diff --git a/.python-version b/.python-version deleted file mode 100644 index 0c7d5f5..0000000 --- a/.python-version +++ /dev/null @@ -1 +0,0 @@ -3.11.4 diff --git a/Jenkinsfile b/Jenkinsfile deleted file mode 100644 index d716510..0000000 --- a/Jenkinsfile +++ /dev/null @@ -1,252 +0,0 @@ -def retryWithDelay(int maxRetries, int delay, Closure body) { - for (int i = 0; i < maxRetries; i++) { - try { - return body() - } catch (Exception e) { - sleep(delay) - } - } - throw Exception("Failed after ${maxRetries} retries") -} - -def device(String ip, String step_label, String cmd) { - withCredentials([file(credentialsId: 'id_rsa', variable: 'key_file')]) { - def ssh_cmd = """ -ssh -tt -o ConnectTimeout=5 -o ServerAliveInterval=5 -o ServerAliveCountMax=2 -o BatchMode=yes -o StrictHostKeyChecking=no -i ${key_file} 'comma@${ip}' /usr/bin/bash <<'END' - -set -e - -shopt -s huponexit # kill all child processes when the shell exits - -export CI=1 -export PYTHONWARNINGS=error -export LOGPRINT=debug -export TEST_DIR=${env.TEST_DIR} -export SOURCE_DIR=${env.SOURCE_DIR} -export GIT_BRANCH=${env.GIT_BRANCH} -export GIT_COMMIT=${env.GIT_COMMIT} -export AZURE_TOKEN='${env.AZURE_TOKEN}' -export MAPBOX_TOKEN='${env.MAPBOX_TOKEN}' -# only use 1 thread for tici tests since most require HIL -export PYTEST_ADDOPTS="-n 0" - - -export GIT_SSH_COMMAND="ssh -i /data/gitkey" - -source ~/.bash_profile -if [ -f /TICI ]; then - source /etc/profile - - rm -rf /tmp/tmp* - rm -rf ~/.commacache - rm -rf /dev/shm/* - - if ! systemctl is-active --quiet systemd-resolved; then - echo "restarting resolved" - sudo systemctl start systemd-resolved - sleep 3 - fi - - # restart aux USB - if [ -e /sys/bus/usb/drivers/hub/3-0:1.0 ]; then - echo "restarting aux usb" - echo "3-0:1.0" | sudo tee /sys/bus/usb/drivers/hub/unbind - sleep 0.5 - echo "3-0:1.0" | sudo tee /sys/bus/usb/drivers/hub/bind - fi -fi -if [ -f /data/openpilot/launch_env.sh ]; then - source /data/openpilot/launch_env.sh -fi - -ln -snf ${env.TEST_DIR} /data/pythonpath - -cd ${env.TEST_DIR} || true -${cmd} -exit 0 - -END""" - - sh script: ssh_cmd, label: step_label - } -} - -def deviceStage(String stageName, String deviceType, List extra_env, def steps) { - stage(stageName) { - if (currentBuild.result != null) { - return - } - - def extra = extra_env.collect { "export ${it}" }.join('\n'); - def branch = env.BRANCH_NAME ?: 'master'; - - lock(resource: "", label: deviceType, inversePrecedence: true, variable: 'device_ip', quantity: 1, resourceSelectStrategy: 'random') { - docker.image('ghcr.io/commaai/alpine-ssh').inside('--user=root') { - timeout(time: 20, unit: 'MINUTES') { - retry (3) { - device(device_ip, "git checkout", extra + "\n" + readFile("selfdrive/test/setup_device_ci.sh")) - } - steps.each { item -> - device(device_ip, item[0], item[1]) - } - } - } - } - } -} - -def pcStage(String stageName, Closure body) { - node { - stage(stageName) { - if (currentBuild.result != null) { - return - } - - checkout scm - - def dockerArgs = "--user=batman -v /tmp/comma_download_cache:/tmp/comma_download_cache -v /tmp/scons_cache:/tmp/scons_cache -e PYTHONPATH=${env.WORKSPACE} --cpus=8 --memory 16g -e PYTEST_ADDOPTS='-n8'"; - - def openpilot_base = retryWithDelay (3, 15) { - return docker.build("openpilot-base:build-${env.GIT_COMMIT}", "-f Dockerfile.openpilot_base .") - } - - lock(resource: "", label: 'pc', inversePrecedence: true, quantity: 1) { - openpilot_base.inside(dockerArgs) { - timeout(time: 20, unit: 'MINUTES') { - try { - retryWithDelay (3, 15) { - sh "git config --global --add safe.directory '*'" - sh "git submodule update --init --recursive" - sh "git lfs pull" - } - body() - } finally { - sh "rm -rf ${env.WORKSPACE}/* || true" - sh "rm -rf .* || true" - } - } - } - } - } - } -} - -def setupCredentials() { - withCredentials([ - string(credentialsId: 'azure_token', variable: 'AZURE_TOKEN'), - string(credentialsId: 'mapbox_token', variable: 'MAPBOX_TOKEN') - ]) { - env.AZURE_TOKEN = "${AZURE_TOKEN}" - env.MAPBOX_TOKEN = "${MAPBOX_TOKEN}" - } -} - - -node { - env.CI = "1" - env.PYTHONWARNINGS = "error" - env.TEST_DIR = "/data/openpilot" - env.SOURCE_DIR = "/data/openpilot_source/" - setupCredentials() - - env.GIT_BRANCH = checkout(scm).GIT_BRANCH - env.GIT_COMMIT = checkout(scm).GIT_COMMIT - - def excludeBranches = ['master-ci', 'devel', 'devel-staging', 'release3', 'release3-staging', - 'testing-closet*', 'hotfix-*'] - def excludeRegex = excludeBranches.join('|').replaceAll('\\*', '.*') - - if (env.BRANCH_NAME != 'master') { - properties([ - disableConcurrentBuilds(abortPrevious: true) - ]) - } - - try { - if (env.BRANCH_NAME == 'devel-staging') { - deviceStage("build release3-staging", "tici-needs-can", [], [ - ["build release3-staging", "RELEASE_BRANCH=release3-staging $SOURCE_DIR/release/build_release.sh"], - ]) - } - - if (env.BRANCH_NAME == 'master-ci') { - deviceStage("build nightly", "tici-needs-can", [], [ - ["build nightly", "RELEASE_BRANCH=nightly $SOURCE_DIR/release/build_release.sh"], - ]) - } - - if (!env.BRANCH_NAME.matches(excludeRegex)) { - parallel ( - // tici tests - 'onroad tests': { - deviceStage("onroad", "tici-needs-can", [], [ - // TODO: ideally, this test runs in master-ci, but it takes 5+m to build it - //["build master-ci", "cd $SOURCE_DIR/release && TARGET_DIR=$TEST_DIR $SOURCE_DIR/scripts/retry.sh ./build_devel.sh"], - ["build openpilot", "cd selfdrive/manager && ./build.py"], - ["check dirty", "release/check-dirty.sh"], - ["onroad tests", "pytest selfdrive/test/test_onroad.py -s"], - ["time to onroad", "pytest selfdrive/test/test_time_to_onroad.py"], - ]) - }, - 'HW + Unit Tests': { - deviceStage("tici-hardware", "tici-common", ["UNSAFE=1"], [ - ["build", "cd selfdrive/manager && ./build.py"], - ["test pandad", "pytest selfdrive/boardd/tests/test_pandad.py"], - ["test power draw", "pytest -s system/hardware/tici/tests/test_power_draw.py"], - ["test encoder", "LD_LIBRARY_PATH=/usr/local/lib pytest system/loggerd/tests/test_encoder.py"], - ["test pigeond", "pytest system/sensord/tests/test_pigeond.py"], - ["test manager", "pytest selfdrive/manager/test/test_manager.py"], - ]) - }, - 'loopback': { - deviceStage("loopback", "tici-loopback", ["UNSAFE=1"], [ - ["build openpilot", "cd selfdrive/manager && ./build.py"], - ["test boardd loopback", "pytest selfdrive/boardd/tests/test_boardd_loopback.py"], - ]) - }, - 'camerad': { - deviceStage("AR0231", "tici-ar0231", ["UNSAFE=1"], [ - ["build", "cd selfdrive/manager && ./build.py"], - ["test camerad", "pytest system/camerad/test/test_camerad.py"], - ["test exposure", "pytest system/camerad/test/test_exposure.py"], - ]) - deviceStage("OX03C10", "tici-ox03c10", ["UNSAFE=1"], [ - ["build", "cd selfdrive/manager && ./build.py"], - ["test camerad", "pytest system/camerad/test/test_camerad.py"], - ["test exposure", "pytest system/camerad/test/test_exposure.py"], - ]) - }, - 'sensord': { - deviceStage("LSM + MMC", "tici-lsmc", ["UNSAFE=1"], [ - ["build", "cd selfdrive/manager && ./build.py"], - ["test sensord", "pytest system/sensord/tests/test_sensord.py"], - ]) - deviceStage("BMX + LSM", "tici-bmx-lsm", ["UNSAFE=1"], [ - ["build", "cd selfdrive/manager && ./build.py"], - ["test sensord", "pytest system/sensord/tests/test_sensord.py"], - ]) - }, - 'replay': { - deviceStage("model-replay", "tici-replay", ["UNSAFE=1"], [ - ["build", "cd selfdrive/manager && ./build.py"], - ["model replay", "selfdrive/test/process_replay/model_replay.py"], - ]) - }, - 'tizi': { - deviceStage("tizi", "tizi", ["UNSAFE=1"], [ - ["build openpilot", "cd selfdrive/manager && ./build.py"], - ["test boardd loopback", "SINGLE_PANDA=1 pytest selfdrive/boardd/tests/test_boardd_loopback.py"], - ["test pandad", "pytest selfdrive/boardd/tests/test_pandad.py"], - ["test amp", "pytest system/hardware/tici/tests/test_amplifier.py"], - ["test hw", "pytest system/hardware/tici/tests/test_hardware.py"], - ["test qcomgpsd", "pytest system/qcomgpsd/tests/test_qcomgpsd.py"], - ]) - }, - - ) - } - } catch (Exception e) { - currentBuild.result = 'FAILED' - throw e - } -} \ No newline at end of file diff --git a/body/board/SConscript b/body/board/SConscript deleted file mode 100644 index 39927c8..0000000 --- a/body/board/SConscript +++ /dev/null @@ -1,197 +0,0 @@ -import os -import subprocess - -PREFIX = "arm-none-eabi-" -BUILDER = "DEV" - -common_flags = [] -build_projects = {} - -build_projects["body"] = { - "MAIN": "main.c", - "STARTUP_FILE": "startup_stm32f413xx.s", - "LINKER_SCRIPT": "stm32fx_flash.ld", - "APP_START_ADDRESS": "0x08004000", - "PROJECT_FLAGS": [ - "-mcpu=cortex-m4", - "-mhard-float", - "-DSTM32F4", - "-DSTM32F413xx", - "-mfpu=fpv4-sp-d16", - "-fsingle-precision-constant", - "-Os", - "-g", - ], -} - -if os.getenv("RELEASE"): - BUILD_TYPE = "RELEASE" - cert_fn = os.getenv("CERT") - assert cert_fn is not None, 'No certificate file specified. Please set CERT env variable' - assert os.path.exists(cert_fn), 'Certificate file not found. Please specify absolute path' -else: - BUILD_TYPE = "DEBUG" - cert_fn = File("../certs/debug").srcnode().relpath - common_flags += ["-DALLOW_DEBUG"] - -if os.getenv("DEBUG"): - common_flags += ["-DDEBUG"] - -includes = [ - "inc/STM32F4xx_HAL_Driver/Inc", - "inc", - "..", - ".", -] - -c_sources = [ - ["hal_flash", "inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash.c"], - ["hal_pwr", "inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr.c"], - ["hal_rcc", "inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc.c"], - ["hal_i2c", "inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2c.c"], - ["hal_i2c_ex", "inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_i2c_ex.c"], - ["hal_tim", "inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim.c"], - ["hal_tim_ex", "inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_tim_ex.c"], - ["hal_adc_ex", "inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc_ex.c"], - ["hal_cortex", "inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cortex.c"], - ["hal_flash_ex", "inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_flash_ex.c"], - ["hal_gpio", "inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_gpio.c"], - ["hal_rcc_ex", "inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc_ex.c"], - ["hal", "inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c"], - ["hal_adc", "inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_adc.c"], - ["hal_dma", "inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_dma.c"], - ["system", "inc/system_stm32f4xx.c"], - ["it", "inc/stm32f4xx_it.c"], - ["bldc", "bldc/bldc.c"], - ["bldc_data", "bldc/BLDC_controller_data.c"], - ["bldc_con", "bldc/BLDC_controller.c"], - ["util", "util.c"], -] - -c_bstub_sources = [ - ["hal_pwr", "inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_pwr.c"], - ["hal_rcc", "inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc.c"], - ["hal_cortex", "inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_cortex.c"], - ["hal_gpio", "inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_gpio.c"], - ["hal_rcc_ex", "inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal_rcc_ex.c"], - ["hal", "inc/STM32F4xx_HAL_Driver/Src/stm32f4xx_hal.c"], - ["system", "inc/system_stm32f4xx.c"], - ["it", "inc/stm32f4xx_it.c"], - ["util", "util.c"], -] - -def get_version(builder, build_type): - try: - git = subprocess.check_output(["git", "rev-parse", "--short=8", "HEAD"], encoding='utf8').strip() - except subprocess.CalledProcessError: - git = "00000000" - return f"{git}" - - -def to_c_uint32(x): - nums = [] - for _ in range(0x20): - nums.append(x % (2**32)) - x //= (2**32) - return "{" + 'U,'.join(map(str, nums)) + "U}" - - -def get_key_header(name): - from Crypto.PublicKey import RSA - - public_fn = f'../certs/{name}.pub' - rsa = RSA.importKey(open(public_fn).read()) - assert(rsa.size_in_bits() == 1024) - - rr = pow(2**1024, 2, rsa.n) - n0inv = 2**32 - pow(rsa.n, -1, 2**32) - - r = [ - f"RSAPublicKey {name}_rsa_key = {{", - f" .len = 0x20,", - f" .n0inv = {n0inv}U,", - f" .n = {to_c_uint32(rsa.n)},", - f" .rr = {to_c_uint32(rr)},", - f" .exponent = {rsa.e},", - f"}};", - ] - return r - -def objcopy(source, target, env, for_signature): - return '$OBJCOPY -O binary %s %s' % (source[0], target[0]) - -# Common autogenerated includes -git_ver = get_version(BUILDER, BUILD_TYPE) -with open("obj/gitversion.h", "w") as f: - f.write(f'const uint8_t gitversion[8] = "{git_ver}";\n') - -certs = [get_key_header(n) for n in ["debug", "release"]] -with open("obj/cert.h", "w") as f: - for cert in certs: - f.write("\n".join(cert) + "\n") - -for project_name in build_projects: - project = build_projects[project_name] - linkerscript_fn = File(project["LINKER_SCRIPT"]).srcnode().relpath - - flags = [ - "-Wall", - "-Wextra", - "-Wstrict-prototypes", - "-Werror", - "-mlittle-endian", - "-mthumb", - "-nostdlib", - "-fno-builtin", - f"-T{linkerscript_fn}", - "-std=gnu11", - "-fdata-sections", - "-ffunction-sections", - "-Wl,--gc-sections", - ] + project["PROJECT_FLAGS"] + common_flags - - project_env = Environment( - ENV=os.environ, - CC=PREFIX + 'gcc', - AS=PREFIX + 'gcc', - OBJCOPY=PREFIX + 'objcopy', - OBJDUMP=PREFIX + 'objdump', - ASCOM="$AS $ASFLAGS -o $TARGET -c $SOURCES", - CFLAGS=flags, - ASFLAGS=flags, - LINKFLAGS=flags, - LIBS = ['gcc',], - CPPPATH=includes, - BUILDERS={ - 'Objcopy': Builder(generator=objcopy, suffix='.bin', src_suffix='.elf') - } - ) - startup = project_env.Object(project["STARTUP_FILE"]) - - c_bstub_obj_list = [] - for c in c_bstub_sources: - c_bstub_obj_list.append(project_env.Object(f"{c[0]}-{project_name}", c[1])) - - # Bootstub - crypto_obj = [ - project_env.Object(f"rsa-{project_name}", "../crypto/rsa.c"), - project_env.Object(f"sha-{project_name}", "../crypto/sha.c") - ] - bootstub_obj = project_env.Object(f"bootstub-{project_name}", "bootstub.c") - bootstub_elf = project_env.Program(f"obj/bootstub.{project_name}.elf", [startup] + crypto_obj + c_bstub_obj_list + [bootstub_obj]) - bootstub_bin = project_env.Objcopy(f"obj/bootstub.{project_name}.bin", bootstub_elf) - - c_obj_list = [] - for c in c_sources: - c_obj_list.append(project_env.Object(f"{c[0]}-{project_name}", c[1])) - - # Build main - main_obj = project_env.Object(f"main-{project_name}", project["MAIN"]) - obj_list = [startup, main_obj] + c_obj_list - main_elf = project_env.Program(f"obj/{project_name}.elf", obj_list, - LINKFLAGS=[f"-Wl,--section-start,.isr_vector={project['APP_START_ADDRESS']}"] + flags) - main_bin = project_env.Objcopy(f"obj/{project_name}.bin", main_elf) - - # Sign main - sign_py = File("../crypto/sign.py").srcnode().relpath - panda_bin_signed = project_env.Command(f"obj/{project_name}.bin.signed", main_bin, f"SETLEN=1 {sign_py} $SOURCE $TARGET {cert_fn}") diff --git a/body/board/bldc/BLDC_controller.h b/body/board/bldc/BLDC_controller.h deleted file mode 100644 index 9d663c2..0000000 --- a/body/board/bldc/BLDC_controller.h +++ /dev/null @@ -1,550 +0,0 @@ -/* - * File: BLDC_controller.h - * - * Code generated for Simulink model 'BLDC_controller'. - * - * Model version : 1.1297 - * Simulink Coder version : 8.13 (R2017b) 24-Jul-2017 - * C/C++ source code generated on : Sun Mar 6 11:02:11 2022 - * - * Target selection: ert.tlc - * Embedded hardware selection: ARM Compatible->ARM Cortex - * Emulation hardware selection: - * Differs from embedded hardware (MATLAB Host) - * Code generation objectives: - * 1. Execution efficiency - * 2. RAM efficiency - * Validation result: Not run - */ - -#ifndef RTW_HEADER_BLDC_controller_h_ -#define RTW_HEADER_BLDC_controller_h_ -#include "rtwtypes.h" -#ifndef BLDC_controller_COMMON_INCLUDES_ -# define BLDC_controller_COMMON_INCLUDES_ -#include "rtwtypes.h" -#endif /* BLDC_controller_COMMON_INCLUDES_ */ - -/* Macros for accessing real-time model data structure */ - -/* Forward declaration for rtModel */ -typedef struct tag_RTM RT_MODEL; - -/* Block signals and states (auto storage) for system '/Counter' */ -typedef struct { - int16_T UnitDelay_DSTATE; /* '/UnitDelay' */ -} DW_Counter; - -/* Block signals and states (auto storage) for system '/Low_Pass_Filter' */ -typedef struct { - int32_T UnitDelay1_DSTATE[2]; /* '/UnitDelay1' */ -} DW_Low_Pass_Filter; - -/* Block signals and states (auto storage) for system '/Counter' */ -typedef struct { - uint16_T UnitDelay_DSTATE; /* '/UnitDelay' */ -} DW_Counter_b; - -/* Block signals and states (auto storage) for system '/either_edge' */ -typedef struct { - boolean_T UnitDelay_DSTATE; /* '/UnitDelay' */ -} DW_either_edge; - -/* Block signals and states (auto storage) for system '/Debounce_Filter' */ -typedef struct { - DW_either_edge either_edge_p; /* '/either_edge' */ - DW_Counter_b Counter_e; /* '/Counter' */ - DW_Counter_b Counter_n1; /* '/Counter' */ - boolean_T UnitDelay_DSTATE; /* '/UnitDelay' */ -} DW_Debounce_Filter; - -/* Block signals and states (auto storage) for system '/I_backCalc_fixdt' */ -typedef struct { - int32_T UnitDelay_DSTATE; /* '/UnitDelay' */ - int32_T UnitDelay_DSTATE_m; /* '/UnitDelay' */ -} DW_I_backCalc_fixdt; - -/* Block signals and states (auto storage) for system '/PI_clamp_fixdt' */ -typedef struct { - int32_T ResettableDelay_DSTATE; /* '/Resettable Delay' */ - uint8_T icLoad; /* '/Resettable Delay' */ - boolean_T UnitDelay1_DSTATE; /* '/UnitDelay1' */ -} DW_PI_clamp_fixdt; - -/* Block signals and states (auto storage) for system '/PI_clamp_fixdt' */ -typedef struct { - int32_T ResettableDelay_DSTATE; /* '/Resettable Delay' */ - uint8_T icLoad; /* '/Resettable Delay' */ - boolean_T UnitDelay1_DSTATE; /* '/UnitDelay1' */ -} DW_PI_clamp_fixdt_m; - -/* Block signals and states (auto storage) for system '/PI_clamp_fixdt' */ -typedef struct { - int16_T ResettableDelay_DSTATE; /* '/Resettable Delay' */ - uint8_T icLoad; /* '/Resettable Delay' */ - boolean_T UnitDelay1_DSTATE; /* '/UnitDelay1' */ -} DW_PI_clamp_fixdt_g; - -/* Block signals and states (auto storage) for system '' */ -typedef struct { - DW_PI_clamp_fixdt_g PI_clamp_fixdt_kh;/* '/PI_clamp_fixdt' */ - DW_PI_clamp_fixdt_m PI_clamp_fixdt_l4;/* '/PI_clamp_fixdt' */ - DW_PI_clamp_fixdt PI_clamp_fixdt_i; /* '/PI_clamp_fixdt' */ - DW_I_backCalc_fixdt I_backCalc_fixdt_j;/* '/I_backCalc_fixdt' */ - DW_I_backCalc_fixdt I_backCalc_fixdt1;/* '/I_backCalc_fixdt1' */ - DW_I_backCalc_fixdt I_backCalc_fixdt_i;/* '/I_backCalc_fixdt' */ - DW_either_edge either_edge_i; /* '/either_edge' */ - DW_Debounce_Filter Debounce_Filter_k;/* '/Debounce_Filter' */ - DW_Low_Pass_Filter Low_Pass_Filter_m;/* '/Low_Pass_Filter' */ - DW_Counter Counter_e; /* '/Counter' */ - int32_T Divide1; /* '/Divide1' */ - int32_T UnitDelay_DSTATE; /* '/UnitDelay' */ - int16_T Gain4_e[3]; /* '/Gain4' */ - int16_T DataTypeConversion[2]; /* '/Data Type Conversion' */ - int16_T z_counterRawPrev; /* '/z_counterRawPrev' */ - int16_T Merge; /* '/Merge' */ - int16_T Switch1; /* '/Switch1' */ - int16_T Vd_max1; /* '/Vd_max1' */ - int16_T Gain3; /* '/Gain3' */ - int16_T Vq_max_M1; /* '/Vq_max_M1' */ - int16_T Gain5; /* '/Gain5' */ - int16_T i_max; /* '/i_max' */ - int16_T Divide1_n; /* '/Divide1' */ - int16_T Gain1; /* '/Gain1' */ - int16_T Gain4; /* '/Gain4' */ - int16_T Switch2_i; /* '/Switch2' */ - int16_T Switch2_o; /* '/Switch2' */ - int16_T Switch2_a; /* '/Switch2' */ - int16_T Divide3; /* '/Divide3' */ - int16_T Merge1; /* '/Merge1' */ - int16_T Abs1; /* '/Abs1' */ - int16_T Abs5_h; /* '/Abs5' */ - int16_T Divide11; /* '/Divide11' */ - int16_T r_sin_M1; /* '/r_sin_M1' */ - int16_T r_cos_M1; /* '/r_cos_M1' */ - int16_T UnitDelay3_DSTATE; /* '/UnitDelay3' */ - int16_T UnitDelay4_DSTATE; /* '/UnitDelay4' */ - int16_T UnitDelay2_DSTATE; /* '/UnitDelay2' */ - int16_T UnitDelay3_DSTATE_o; /* '/UnitDelay3' */ - int16_T UnitDelay5_DSTATE; /* '/UnitDelay5' */ - int16_T UnitDelay4_DSTATE_e; /* '/UnitDelay4' */ - int16_T UnitDelay4_DSTATE_eu; /* '/UnitDelay4' */ - int8_T Switch2_e; /* '/Switch2' */ - int8_T UnitDelay2_DSTATE_b; /* '/UnitDelay2' */ - int8_T If1_ActiveSubsystem; /* '/If1' */ - int8_T If2_ActiveSubsystem; /* '/If2' */ - int8_T If1_ActiveSubsystem_j; /* '/If1' */ - int8_T SwitchCase_ActiveSubsystem; /* '/Switch Case' */ - int8_T If1_ActiveSubsystem_a; /* '/If1' */ - int8_T If1_ActiveSubsystem_o; /* '/If1' */ - int8_T SwitchCase_ActiveSubsystem_d; /* '/Switch Case' */ - int8_T If2_ActiveSubsystem_f; /* '/If2' */ - int8_T If2_ActiveSubsystem_a; /* '/If2' */ - uint8_T z_ctrlMod; /* '/F03_02_Control_Mode_Manager' */ - uint8_T UnitDelay3_DSTATE_fy; /* '/UnitDelay3' */ - uint8_T UnitDelay1_DSTATE; /* '/UnitDelay1' */ - uint8_T UnitDelay2_DSTATE_f; /* '/UnitDelay2' */ - uint8_T UnitDelay_DSTATE_e; /* '/UnitDelay' */ - uint8_T is_active_c1_BLDC_controller;/* '/F03_02_Control_Mode_Manager' */ - uint8_T is_c1_BLDC_controller; /* '/F03_02_Control_Mode_Manager' */ - uint8_T is_ACTIVE; /* '/F03_02_Control_Mode_Manager' */ - boolean_T Merge_p; /* '/Merge' */ - boolean_T dz_cntTrnsDet; /* '/dz_cntTrnsDet' */ - boolean_T UnitDelay2_DSTATE_c; /* '/UnitDelay2' */ - boolean_T UnitDelay5_DSTATE_m; /* '/UnitDelay5' */ - boolean_T UnitDelay6_DSTATE; /* '/UnitDelay6' */ - boolean_T UnitDelay_DSTATE_b; /* '/UnitDelay' */ - boolean_T UnitDelay1_DSTATE_n; /* '/UnitDelay1' */ - boolean_T n_commDeacv_Mode; /* '/n_commDeacv' */ - boolean_T dz_cntTrnsDet_Mode; /* '/dz_cntTrnsDet' */ -} DW; - -/* Constant parameters (auto storage) */ -typedef struct { - /* Computed Parameter: r_sin_M1_Table - * Referenced by: '/r_sin_M1' - */ - int16_T r_sin_M1_Table[181]; - - /* Computed Parameter: r_cos_M1_Table - * Referenced by: '/r_cos_M1' - */ - int16_T r_cos_M1_Table[181]; - - /* Computed Parameter: r_sin3PhaA_M1_Table - * Referenced by: '/r_sin3PhaA_M1' - */ - int16_T r_sin3PhaA_M1_Table[181]; - - /* Computed Parameter: r_sin3PhaB_M1_Table - * Referenced by: '/r_sin3PhaB_M1' - */ - int16_T r_sin3PhaB_M1_Table[181]; - - /* Computed Parameter: r_sin3PhaC_M1_Table - * Referenced by: '/r_sin3PhaC_M1' - */ - int16_T r_sin3PhaC_M1_Table[181]; - - /* Computed Parameter: iq_maxSca_M1_Table - * Referenced by: '/iq_maxSca_M1' - */ - uint16_T iq_maxSca_M1_Table[50]; - - /* Computed Parameter: z_commutMap_M1_table - * Referenced by: '/z_commutMap_M1' - */ - int8_T z_commutMap_M1_table[18]; - - /* Computed Parameter: vec_hallToPos_Value - * Referenced by: '/vec_hallToPos' - */ - int8_T vec_hallToPos_Value[8]; -} ConstP; - -/* External inputs (root inport signals with auto storage) */ -typedef struct { - boolean_T b_motEna; /* '/b_motEna' */ - uint8_T z_ctrlModReq; /* '/z_ctrlModReq' */ - int16_T r_inpTgt; /* '/r_inpTgt' */ - uint8_T b_hallA; /* '/b_hallA ' */ - uint8_T b_hallB; /* '/b_hallB' */ - uint8_T b_hallC; /* '/b_hallC' */ - int16_T i_phaAB; /* '/i_phaAB' */ - int16_T i_phaBC; /* '/i_phaBC' */ - int16_T i_DCLink; /* '/i_DCLink' */ - int16_T a_mechAngle; /* '/a_mechAngle' */ -} ExtU; - -/* External outputs (root outports fed by signals with auto storage) */ -typedef struct { - int16_T DC_phaA; /* '/DC_phaA' */ - int16_T DC_phaB; /* '/DC_phaB' */ - int16_T DC_phaC; /* '/DC_phaC' */ - uint8_T z_errCode; /* '/z_errCode' */ - int16_T n_mot; /* '/n_mot' */ - int16_T a_elecAngle; /* '/a_elecAngle' */ - int16_T iq; /* '/iq' */ - int16_T id; /* '/id' */ -} ExtY; - -/* Parameters (auto storage) */ -struct P_ { - int32_T dV_openRate; /* Variable: dV_openRate - * Referenced by: '/dV_openRate' - */ - int16_T dz_cntTrnsDetHi; /* Variable: dz_cntTrnsDetHi - * Referenced by: '/dz_cntTrnsDet' - */ - int16_T dz_cntTrnsDetLo; /* Variable: dz_cntTrnsDetLo - * Referenced by: '/dz_cntTrnsDet' - */ - int16_T n_cruiseMotTgt; /* Variable: n_cruiseMotTgt - * Referenced by: '/n_cruiseMotTgt' - */ - int16_T z_maxCntRst; /* Variable: z_maxCntRst - * Referenced by: - * '/Counter' - * '/z_maxCntRst' - * '/z_maxCntRst2' - * '/UnitDelay3' - * '/z_counter' - */ - uint16_T cf_speedCoef; /* Variable: cf_speedCoef - * Referenced by: '/cf_speedCoef' - */ - uint16_T t_errDequal; /* Variable: t_errDequal - * Referenced by: '/t_errDequal' - */ - uint16_T t_errQual; /* Variable: t_errQual - * Referenced by: '/t_errQual' - */ - int16_T Vd_max; /* Variable: Vd_max - * Referenced by: - * '/Vd_max' - * '/Vd_max1' - */ - int16_T Vq_max_M1[46]; /* Variable: Vq_max_M1 - * Referenced by: '/Vq_max_M1' - */ - int16_T Vq_max_XA[46]; /* Variable: Vq_max_XA - * Referenced by: '/Vq_max_XA' - */ - int16_T a_phaAdvMax; /* Variable: a_phaAdvMax - * Referenced by: '/a_phaAdvMax' - */ - int16_T i_max; /* Variable: i_max - * Referenced by: - * '/i_max' - * '/i_max' - */ - int16_T id_fieldWeakMax; /* Variable: id_fieldWeakMax - * Referenced by: '/id_fieldWeakMax' - */ - int16_T n_commAcvLo; /* Variable: n_commAcvLo - * Referenced by: '/n_commDeacv' - */ - int16_T n_commDeacvHi; /* Variable: n_commDeacvHi - * Referenced by: '/n_commDeacv' - */ - int16_T n_fieldWeakAuthHi; /* Variable: n_fieldWeakAuthHi - * Referenced by: '/n_fieldWeakAuthHi' - */ - int16_T n_fieldWeakAuthLo; /* Variable: n_fieldWeakAuthLo - * Referenced by: '/n_fieldWeakAuthLo' - */ - int16_T n_max; /* Variable: n_max - * Referenced by: - * '/n_max' - * '/n_max1' - */ - int16_T n_stdStillDet; /* Variable: n_stdStillDet - * Referenced by: '/n_stdStillDet' - */ - int16_T r_errInpTgtThres; /* Variable: r_errInpTgtThres - * Referenced by: '/r_errInpTgtThres' - */ - int16_T r_fieldWeakHi; /* Variable: r_fieldWeakHi - * Referenced by: '/r_fieldWeakHi' - */ - int16_T r_fieldWeakLo; /* Variable: r_fieldWeakLo - * Referenced by: '/r_fieldWeakLo' - */ - uint16_T cf_KbLimProt; /* Variable: cf_KbLimProt - * Referenced by: - * '/cf_KbLimProt' - * '/cf_KbLimProt' - */ - uint16_T cf_idKp; /* Variable: cf_idKp - * Referenced by: '/cf_idKp1' - */ - uint16_T cf_iqKp; /* Variable: cf_iqKp - * Referenced by: '/cf_iqKp' - */ - uint16_T cf_nKp; /* Variable: cf_nKp - * Referenced by: '/cf_nKp' - */ - uint16_T cf_currFilt; /* Variable: cf_currFilt - * Referenced by: '/cf_currFilt' - */ - uint16_T cf_idKi; /* Variable: cf_idKi - * Referenced by: '/cf_idKi1' - */ - uint16_T cf_iqKi; /* Variable: cf_iqKi - * Referenced by: '/cf_iqKi' - */ - uint16_T cf_iqKiLimProt; /* Variable: cf_iqKiLimProt - * Referenced by: - * '/cf_iqKiLimProt' - * '/cf_iqKiLimProt' - */ - uint16_T cf_nKi; /* Variable: cf_nKi - * Referenced by: '/cf_nKi' - */ - uint16_T cf_nKiLimProt; /* Variable: cf_nKiLimProt - * Referenced by: - * '/cf_nKiLimProt' - * '/cf_nKiLimProt' - */ - uint8_T n_polePairs; /* Variable: n_polePairs - * Referenced by: '/n_polePairs' - */ - uint8_T z_ctrlTypSel; /* Variable: z_ctrlTypSel - * Referenced by: '/z_ctrlTypSel' - */ - uint8_T z_selPhaCurMeasABC; /* Variable: z_selPhaCurMeasABC - * Referenced by: '/z_selPhaCurMeasABC' - */ - boolean_T b_angleMeasEna; /* Variable: b_angleMeasEna - * Referenced by: - * '/b_angleMeasEna' - * '/b_angleMeasEna' - */ - boolean_T b_cruiseCtrlEna; /* Variable: b_cruiseCtrlEna - * Referenced by: '/b_cruiseCtrlEna' - */ - boolean_T b_diagEna; /* Variable: b_diagEna - * Referenced by: '/b_diagEna' - */ - boolean_T b_fieldWeakEna; /* Variable: b_fieldWeakEna - * Referenced by: - * '/b_fieldWeakEna' - * '/b_fieldWeakEna' - */ -}; - -/* Parameters (auto storage) */ -typedef struct P_ P; - -/* Real-time Model Data Structure */ -struct tag_RTM { - P *defaultParam; - ExtU *inputs; - ExtY *outputs; - DW *dwork; -}; - -/* Constant parameters (auto storage) */ -extern const ConstP rtConstP; - -/* Model entry point functions */ -extern void BLDC_controller_initialize(RT_MODEL *const rtM); -extern void BLDC_controller_step(RT_MODEL *const rtM); - -/*- - * These blocks were eliminated from the model due to optimizations: - * - * Block '/Scope2' : Unused code path elimination - * Block '/Scope' : Unused code path elimination - * Block '/Data Type Duplicate' : Unused code path elimination - * Block '/Data Type Propagation' : Unused code path elimination - * Block '/Data Type Duplicate' : Unused code path elimination - * Block '/Data Type Propagation' : Unused code path elimination - * Block '/Data Type Duplicate' : Unused code path elimination - * Block '/Data Type Propagation' : Unused code path elimination - * Block '/Data Type Duplicate' : Unused code path elimination - * Block '/Data Type Propagation' : Unused code path elimination - * Block '/Data Type Duplicate' : Unused code path elimination - * Block '/Data Type Propagation' : Unused code path elimination - * Block '/Data Type Duplicate' : Unused code path elimination - * Block '/Data Type Propagation' : Unused code path elimination - * Block '/Data Type Duplicate' : Unused code path elimination - * Block '/Data Type Propagation' : Unused code path elimination - * Block '/Data Type Duplicate' : Unused code path elimination - * Block '/Data Type Propagation' : Unused code path elimination - * Block '/Data Type Duplicate' : Unused code path elimination - * Block '/Data Type Propagation' : Unused code path elimination - * Block '/Data Type Duplicate' : Unused code path elimination - * Block '/Data Type Propagation' : Unused code path elimination - * Block '/Scope12' : Unused code path elimination - * Block '/Scope8' : Unused code path elimination - * Block '/toNegative' : Unused code path elimination - * Block '/Scope' : Unused code path elimination - * Block '/Data Type Conversion' : Eliminate redundant data type conversion - * Block '/Data Type Conversion1' : Eliminate redundant data type conversion - */ - -/*- - * The generated code includes comments that allow you to trace directly - * back to the appropriate location in the model. The basic format - * is /block_name, where system is the system number (uniquely - * assigned by Simulink) and block_name is the name of the block. - * - * Note that this particular code originates from a subsystem build, - * and has its own system numbers different from the parent model. - * Refer to the system hierarchy for this subsystem below, and use the - * MATLAB hilite_system command to trace the generated code back - * to the parent model. For example, - * - * hilite_system('BLDCmotor_FOC_R2017b_fixdt/BLDC_controller') - opens subsystem BLDCmotor_FOC_R2017b_fixdt/BLDC_controller - * hilite_system('BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/Kp') - opens and selects block Kp - * - * Here is the system hierarchy for this model - * - * '' : 'BLDCmotor_FOC_R2017b_fixdt' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/Call_Scheduler' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F01_Estimations' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F02_Diagnostics' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F03_Control_Mode_Manager' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F04_Field_Weakening' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F06_Control_Type_Management' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/Task_Scheduler' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F01_Estimations/F01_01_Edge_Detector' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F01_Estimations/F01_02_Position_Calculation' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F01_Estimations/F01_03_Direction_Detection' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F01_Estimations/F01_04_Speed_Estimation' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F01_Estimations/F01_05_Electrical_Angle_Estimation' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F01_Estimations/F01_06_Electrical_Angle_Measurement' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F01_Estimations/F01_04_Speed_Estimation/Counter' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F01_Estimations/F01_04_Speed_Estimation/Raw_Motor_Speed_Estimation' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F01_Estimations/F01_04_Speed_Estimation/Counter/rst_Delay' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F01_Estimations/F01_06_Electrical_Angle_Measurement/Modulo_fixdt' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F02_Diagnostics/Diagnostics_Enabled' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F02_Diagnostics/Diagnostics_Enabled/Debounce_Filter' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F02_Diagnostics/Diagnostics_Enabled/either_edge' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F02_Diagnostics/Diagnostics_Enabled/Debounce_Filter/Default' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F02_Diagnostics/Diagnostics_Enabled/Debounce_Filter/Dequalification' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F02_Diagnostics/Diagnostics_Enabled/Debounce_Filter/Qualification' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F02_Diagnostics/Diagnostics_Enabled/Debounce_Filter/either_edge' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F02_Diagnostics/Diagnostics_Enabled/Debounce_Filter/Dequalification/Counter' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F02_Diagnostics/Diagnostics_Enabled/Debounce_Filter/Dequalification/Counter/rst_Delay' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F02_Diagnostics/Diagnostics_Enabled/Debounce_Filter/Qualification/Counter' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F02_Diagnostics/Diagnostics_Enabled/Debounce_Filter/Qualification/Counter/rst_Delay' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F03_Control_Mode_Manager/F03_01_Mode_Transition_Calculation' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F03_Control_Mode_Manager/F03_02_Control_Mode_Manager' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F03_Control_Mode_Manager/F03_03_Input_Target_Synthesis' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F03_Control_Mode_Manager/F03_03_Input_Target_Synthesis/Default_Control_Type' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F03_Control_Mode_Manager/F03_03_Input_Target_Synthesis/Default_Mode' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F03_Control_Mode_Manager/F03_03_Input_Target_Synthesis/FOC_Control_Type' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F03_Control_Mode_Manager/F03_03_Input_Target_Synthesis/Open_Mode' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F03_Control_Mode_Manager/F03_03_Input_Target_Synthesis/Open_Mode/Rate_Limiter' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F03_Control_Mode_Manager/F03_03_Input_Target_Synthesis/Open_Mode/rising_edge_init' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F03_Control_Mode_Manager/F03_03_Input_Target_Synthesis/Open_Mode/Rate_Limiter/Delay_Init1' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F03_Control_Mode_Manager/F03_03_Input_Target_Synthesis/Open_Mode/Rate_Limiter/Saturation Dynamic' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F04_Field_Weakening/Field_Weakening_Enabled' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F04_Field_Weakening/Field_Weakening_Enabled/Saturation Dynamic' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F04_Field_Weakening/Field_Weakening_Enabled/Saturation Dynamic1' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Clarke_Park_Transform_Forward' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Clarke_Park_Transform_Inverse' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/FOC' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Motor_Limitations' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Clarke_Park_Transform_Forward/Clarke_Transform' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Clarke_Park_Transform_Forward/Current_Filtering' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Clarke_Park_Transform_Forward/Park_Transform' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Clarke_Park_Transform_Forward/Sine_Cosine_Approximation' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Clarke_Park_Transform_Forward/Clarke_Transform/Clarke_PhasesAB' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Clarke_Park_Transform_Forward/Clarke_Transform/Clarke_PhasesAC' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Clarke_Park_Transform_Forward/Clarke_Transform/Clarke_PhasesBC' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Clarke_Park_Transform_Forward/Current_Filtering/Low_Pass_Filter' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Clarke_Park_Transform_Inverse/Inv_Clarke_Transform' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Clarke_Park_Transform_Inverse/Inv_Park_Transform' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/FOC/FOC_Enabled' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/FOC/FOC_Enabled/Open_Mode' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/FOC/FOC_Enabled/Speed_Mode' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/FOC/FOC_Enabled/Torque_Mode' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/FOC/FOC_Enabled/Vd_Calculation' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/FOC/FOC_Enabled/Voltage_Mode' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/FOC/FOC_Enabled/Speed_Mode/PI_clamp_fixdt' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/FOC/FOC_Enabled/Speed_Mode/PI_clamp_fixdt/Clamping_circuit' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/FOC/FOC_Enabled/Speed_Mode/PI_clamp_fixdt/Integrator' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/FOC/FOC_Enabled/Speed_Mode/PI_clamp_fixdt/Saturation_hit' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/FOC/FOC_Enabled/Torque_Mode/PI_clamp_fixdt' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/FOC/FOC_Enabled/Torque_Mode/Saturation Dynamic1' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/FOC/FOC_Enabled/Torque_Mode/PI_clamp_fixdt/Clamping_circuit' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/FOC/FOC_Enabled/Torque_Mode/PI_clamp_fixdt/Integrator' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/FOC/FOC_Enabled/Torque_Mode/PI_clamp_fixdt/Saturation_hit' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/FOC/FOC_Enabled/Vd_Calculation/PI_clamp_fixdt' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/FOC/FOC_Enabled/Vd_Calculation/Saturation Dynamic' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/FOC/FOC_Enabled/Vd_Calculation/PI_clamp_fixdt/Clamping_circuit' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/FOC/FOC_Enabled/Vd_Calculation/PI_clamp_fixdt/Integrator' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/FOC/FOC_Enabled/Vd_Calculation/PI_clamp_fixdt/Saturation_hit' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/FOC/FOC_Enabled/Voltage_Mode/Saturation Dynamic1' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Motor_Limitations/Motor_Limitations_Enabled' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Motor_Limitations/Motor_Limitations_Enabled/Speed_Mode_Protection' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Motor_Limitations/Motor_Limitations_Enabled/Torque_Mode_Protection' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Motor_Limitations/Motor_Limitations_Enabled/Voltage_Mode_Protection' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Motor_Limitations/Motor_Limitations_Enabled/Speed_Mode_Protection/Saturation Dynamic' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Motor_Limitations/Motor_Limitations_Enabled/Torque_Mode_Protection/I_backCalc_fixdt' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Motor_Limitations/Motor_Limitations_Enabled/Torque_Mode_Protection/I_backCalc_fixdt/Integrator' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Motor_Limitations/Motor_Limitations_Enabled/Torque_Mode_Protection/I_backCalc_fixdt/Saturation Dynamic1' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Motor_Limitations/Motor_Limitations_Enabled/Voltage_Mode_Protection/I_backCalc_fixdt' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Motor_Limitations/Motor_Limitations_Enabled/Voltage_Mode_Protection/I_backCalc_fixdt1' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Motor_Limitations/Motor_Limitations_Enabled/Voltage_Mode_Protection/I_backCalc_fixdt/Integrator' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Motor_Limitations/Motor_Limitations_Enabled/Voltage_Mode_Protection/I_backCalc_fixdt/Saturation Dynamic1' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Motor_Limitations/Motor_Limitations_Enabled/Voltage_Mode_Protection/I_backCalc_fixdt1/Integrator' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F05_Field_Oriented_Control/Motor_Limitations/Motor_Limitations_Enabled/Voltage_Mode_Protection/I_backCalc_fixdt1/Saturation Dynamic1' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F06_Control_Type_Management/COM_Method' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F06_Control_Type_Management/FOC_Method' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F06_Control_Type_Management/SIN_Method' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F06_Control_Type_Management/SIN_Method/Final_Phase_Advance_Calculation' - * '' : 'BLDCmotor_FOC_R2017b_fixdt/BLDC_controller/F06_Control_Type_Management/SIN_Method/Final_Phase_Advance_Calculation/Modulo_fixdt' - */ -#endif /* RTW_HEADER_BLDC_controller_h_ */ - -/* - * File trailer for generated code. - * - * [EOF] - */ diff --git a/body/board/bldc/rtwtypes.h b/body/board/bldc/rtwtypes.h deleted file mode 100644 index 3f68038..0000000 --- a/body/board/bldc/rtwtypes.h +++ /dev/null @@ -1,104 +0,0 @@ -/* - * File: rtwtypes.h - * - * Code generated for Simulink model 'BLDC_controller'. - * - * Model version : 1.1297 - * Simulink Coder version : 8.13 (R2017b) 24-Jul-2017 - * C/C++ source code generated on : Sun Mar 6 11:02:11 2022 - * - * Target selection: ert.tlc - * Embedded hardware selection: ARM Compatible->ARM Cortex - * Emulation hardware selection: - * Differs from embedded hardware (MATLAB Host) - * Code generation objectives: - * 1. Execution efficiency - * 2. RAM efficiency - * Validation result: Not run - */ - -#ifndef RTWTYPES_H -#define RTWTYPES_H - -/* Logical type definitions */ -#if (!defined(__cplusplus)) -# ifndef false -# define false (0U) -# endif - -# ifndef true -# define true (1U) -# endif -#endif - -/*=======================================================================* - * Target hardware information - * Device type: MATLAB Host - * Number of bits: char: 8 short: 16 int: 32 - * long: 32 long long: 64 - * native word size: 64 - * Byte ordering: LittleEndian - * Signed integer division rounds to: Zero - * Shift right on a signed integer as arithmetic shift: on - *=======================================================================*/ - -/*=======================================================================* - * Fixed width word size data types: * - * int8_T, int16_T, int32_T - signed 8, 16, or 32 bit integers * - * uint8_T, uint16_T, uint32_T - unsigned 8, 16, or 32 bit integers * - * real32_T, real64_T - 32 and 64 bit floating point numbers * - *=======================================================================*/ -typedef signed char int8_T; -typedef unsigned char uint8_T; -typedef short int16_T; -typedef unsigned short uint16_T; -typedef int int32_T; -typedef unsigned int uint32_T; -typedef long long int64_T; -typedef unsigned long long uint64_T; -typedef float real32_T; -typedef double real64_T; - -/*===========================================================================* - * Generic type definitions: boolean_T, char_T, byte_T, int_T, uint_T, * - * real_T, time_T, ulong_T, ulonglong_T. * - *===========================================================================*/ -typedef double real_T; -typedef double time_T; -typedef unsigned char boolean_T; -typedef int int_T; -typedef unsigned int uint_T; -typedef unsigned long ulong_T; -typedef unsigned long long ulonglong_T; -typedef char char_T; -typedef unsigned char uchar_T; -typedef char_T byte_T; - -/*=======================================================================* - * Min and Max: * - * int8_T, int16_T, int32_T - signed 8, 16, or 32 bit integers * - * uint8_T, uint16_T, uint32_T - unsigned 8, 16, or 32 bit integers * - *=======================================================================*/ -#define MAX_int8_T ((int8_T)(127)) -#define MIN_int8_T ((int8_T)(-128)) -#define MAX_uint8_T ((uint8_T)(255U)) -#define MAX_int16_T ((int16_T)(32767)) -#define MIN_int16_T ((int16_T)(-32768)) -#define MAX_uint16_T ((uint16_T)(65535U)) -#define MAX_int32_T ((int32_T)(2147483647)) -#define MIN_int32_T ((int32_T)(-2147483647-1)) -#define MAX_uint32_T ((uint32_T)(0xFFFFFFFFU)) -#define MAX_int64_T ((int64_T)(9223372036854775807LL)) -#define MIN_int64_T ((int64_T)(-9223372036854775807LL-1LL)) -#define MAX_uint64_T ((uint64_T)(0xFFFFFFFFFFFFFFFFULL)) - -/* Block D-Work pointer type */ -typedef void * pointer_T; - -#endif /* RTWTYPES_H */ - -/* - * File trailer for generated code. - * - * [EOF] - */ diff --git a/body/board/boards.h b/body/board/boards.h deleted file mode 100644 index 7772325..0000000 --- a/body/board/boards.h +++ /dev/null @@ -1,90 +0,0 @@ -extern uint8_t hw_type; -board_t board; - -void board_detect(void) { - hw_type = board_id(); - // 0 = base, 3 = knee - if (hw_type == HW_TYPE_BASE) { - board.hall_left.hall_portA = GPIOC; - board.hall_left.hall_pinA = GPIO_PIN_13; - board.hall_left.hall_portB = GPIOC; - board.hall_left.hall_pinB = GPIO_PIN_14; - board.hall_left.hall_portC = GPIOC; - board.hall_left.hall_pinC = GPIO_PIN_15; - - board.hall_right.hall_portA = GPIOC; - board.hall_right.hall_pinA = GPIO_PIN_10; - board.hall_right.hall_portB = GPIOC; - board.hall_right.hall_pinB = GPIO_PIN_11; - board.hall_right.hall_portC = GPIOC; - board.hall_right.hall_pinC = GPIO_PIN_12; - - board.CAN = CAN2; - board.can_alt_tx = GPIO_AF9_CAN2; - board.can_alt_rx = GPIO_AF9_CAN2; - board.can_pinRX = GPIO_PIN_5; - board.can_portRX = GPIOB; - board.can_pinTX = GPIO_PIN_6; - board.can_portTX = GPIOB; - board.can_pinEN = GPIO_PIN_7; - board.can_portEN = GPIOB; - - board.ignition_pin = GPIO_PIN_9; - board.ignition_port = GPIOB; - - board.led_pinR = GPIO_PIN_2; - board.led_portR = GPIOD; - board.led_pinG = GPIO_PIN_15; - board.led_portG = GPIOA; - board.led_pinB = GPIO_PIN_1; - board.led_portB = GPIOC; - - board.can_addr_offset = 0x0U; - board.uds_offset = 0x0U; - - } else if (hw_type == HW_TYPE_KNEE) { - board.hall_left.hall_portA = GPIOC; - board.hall_left.hall_pinA = GPIO_PIN_14; - board.hall_left.hall_portB = GPIOC; - board.hall_left.hall_pinB = GPIO_PIN_15; - board.hall_left.hall_portC = GPIOC; - board.hall_left.hall_pinC = GPIO_PIN_13; - - board.hall_right.hall_portA = GPIOD; - board.hall_right.hall_pinA = GPIO_PIN_2; - board.hall_right.hall_portB = GPIOC; - board.hall_right.hall_pinB = GPIO_PIN_0; - board.hall_right.hall_portC = GPIOC; - board.hall_right.hall_pinC = GPIO_PIN_1; - - board.CAN = CAN1; - board.can_alt_tx = GPIO_AF8_CAN1; - board.can_alt_rx = GPIO_AF9_CAN1; - board.can_pinRX = GPIO_PIN_11; - board.can_portRX = GPIOA; - board.can_pinTX = GPIO_PIN_9; - board.can_portTX = GPIOB; - board.can_pinEN = 0; // No pin, pulled down with 10k resistor - board.can_portEN = GPIOB; - - board.ignition_pin = 0; // No pin, always enabled - board.ignition_port = GPIOB; - - board.led_pinR = GPIO_PIN_2; - board.led_portR = GPIOB; - board.led_pinG = GPIO_PIN_15; - board.led_portG = GPIOA; - board.led_pinB = GPIO_PIN_5; - board.led_portB = GPIOB; - - board.can_addr_offset = KNEE_ADDR_OFFSET; - board.uds_offset = 0x10U; - - #ifndef BOOTSTUB - MX_I2C_Init(); - #endif - } else { - // Fail to detect, halt - while(1) {} - } -} diff --git a/body/board/comms.h b/body/board/comms.h deleted file mode 100644 index 342163c..0000000 --- a/body/board/comms.h +++ /dev/null @@ -1,190 +0,0 @@ -// Define to prevent recursive inclusion -#ifndef COMMS_H -#define COMMS_H - -#define OFFSET 0x8U -#define BROADCAST_ADDR 0x7DFU -#define FALLBACK_ADDR 0x7E0U -#define FALLBACK_R_ADDR (FALLBACK_ADDR + OFFSET) -#define ENGINE_ADDR 0x720U -#define ENGINE_R_ADDR (ENGINE_ADDR + OFFSET) -#define DEBUG_ADDR 0x721U -#define DEBUG_R_ADDR (DEBUG_ADDR + OFFSET) - -#include "drivers/llbxcan.h" -#include "uds.h" - -extern P rtP_Left; -extern P rtP_Right; -extern volatile int16_t cmdL; // global variable for Left Command -extern volatile int16_t cmdR; // global variable for Right Command -extern uint8_t hw_type; -extern board_t board; - -extern uint32_t enter_bootloader_mode; -extern volatile uint32_t torque_cmd_timeout; - -extern volatile uint32_t ignition_off_counter; - -const uint8_t crc_poly = 0xD5U; // standard crc8 -uint32_t current_idx = 0; - -typedef struct { - volatile uint32_t w_ptr; - volatile uint32_t r_ptr; - uint32_t fifo_size; - CAN_FIFOMailBox_TypeDef *elems; -} can_ring; - -#define can_buffer(x, size) \ - CAN_FIFOMailBox_TypeDef elems_##x[size]; \ - can_ring can_##x = { .w_ptr = 0, .r_ptr = 0, .fifo_size = (size), .elems = (CAN_FIFOMailBox_TypeDef *)&(elems_##x) }; - -can_buffer(tx_q, 0x1A0) - -bool can_pop(can_ring *q, CAN_FIFOMailBox_TypeDef *elem) { - bool ret = 0; - - if (q->w_ptr != q->r_ptr) { - *elem = q->elems[q->r_ptr]; - if ((q->r_ptr + 1U) == q->fifo_size) { - q->r_ptr = 0; - } else { - q->r_ptr += 1U; - } - ret = 1; - } - return ret; -} - -bool can_push(can_ring *q, CAN_FIFOMailBox_TypeDef *elem) { - bool ret = false; - uint32_t next_w_ptr; - - if ((q->w_ptr + 1U) == q->fifo_size) { - next_w_ptr = 0; - } else { - next_w_ptr = q->w_ptr + 1U; - } - if (next_w_ptr != q->r_ptr) { - q->elems[q->w_ptr] = *elem; - q->w_ptr = next_w_ptr; - ret = true; - } - return ret; -} - -void can_send_msg(uint32_t addr, uint32_t dhr, uint32_t dlr, uint8_t len) { - CAN_FIFOMailBox_TypeDef to_push; - - to_push.RDHR = dhr; - to_push.RDLR = dlr; - to_push.RDTR = len; - to_push.RIR = ((addr >= 0x800U) ? ((addr << 3) | (1U << 2)) : (addr << 21)) | 1; - - can_push(&can_tx_q, &to_push); -} - -void process_can(void) { - __disable_irq(); - CAN_FIFOMailBox_TypeDef to_send; - if ((board.CAN->TSR & CAN_TSR_TME0) == CAN_TSR_TME0) { - if (can_pop(&can_tx_q, &to_send)) { - board.CAN->sTxMailBox[0].TDLR = to_send.RDLR; - board.CAN->sTxMailBox[0].TDHR = to_send.RDHR; - board.CAN->sTxMailBox[0].TDTR = to_send.RDTR; - board.CAN->sTxMailBox[0].TIR = to_send.RIR; - } - } - __enable_irq(); -} - -void can_rx(void) { - while ((board.CAN->RF0R & CAN_RF0R_FMP0) != 0) { - uint32_t address = board.CAN->sFIFOMailBox[0].RIR >> 21; - if (address == (0x250U + board.can_addr_offset)) { - if ((GET_MAILBOX_BYTES_04(&board.CAN->sFIFOMailBox[0]) == 0xdeadface) && (GET_MAILBOX_BYTES_48(&board.CAN->sFIFOMailBox[0]) == 0x0ab00b1e)) { - enter_bootloader_mode = ENTER_SOFTLOADER_MAGIC; - NVIC_SystemReset(); - } - #define MSG_TRQ_LEN 6 - uint8_t dat[MSG_TRQ_LEN]; - for (int i=0; isFIFOMailBox[0], i); - } - uint16_t valueL = ((dat[0] << 8U) | dat[1]); - uint16_t valueR = ((dat[2] << 8U) | dat[3]); - - uint8_t idx = dat[4] & 0xFU; - if (crc_checksum(dat, 5, crc_poly) == dat[5]) { - if (((current_idx + 1U) & 0xFU) == idx) { - cmdL = valueL; - cmdR = valueR; - torque_cmd_timeout = 0; - } - current_idx = idx; - } - out_enable(LED_BLUE, true); - } else if (address == (0x251U + board.can_addr_offset)) { - #define MSG_SPD_LEN 5 - uint8_t dat[MSG_TRQ_LEN]; - for (int i=0; isFIFOMailBox[0], i); - } - uint16_t valueL = ((dat[0] << 8U) | dat[1]); - uint16_t valueR = ((dat[2] << 8U) | dat[3]); - - if (crc_checksum(dat, 4, crc_poly) == dat[4]) { - if ((valueL == 0) || (valueR == 0)) { - rtP_Left.n_max = rtP_Right.n_max = N_MOT_MAX << 4; - } else { - rtP_Left.n_max = valueL << 4; - rtP_Right.n_max = valueR << 4; - } - } - out_enable(LED_BLUE, true); - } else if ((address == BROADCAST_ADDR) || // Process UBS and OBD2 requests - (address == FALLBACK_ADDR) || - (address == (ENGINE_ADDR + board.uds_offset)) || - (address == (DEBUG_ADDR + board.uds_offset))) { - process_uds(address, GET_MAILBOX_BYTES_04(&board.CAN->sFIFOMailBox[0])); - out_enable(LED_BLUE, true); - } else if ((hw_type == HW_TYPE_BASE) && (address == 0x203U + KNEE_ADDR_OFFSET)) { // detect knee by body and set flag for use with UDS message - knee_detected = 1; - } else if ((hw_type == HW_TYPE_KNEE) && (address == 0x202U)) { // CAN based ignition for knee - ignition_off_counter = 0; - } - // next - board.CAN->RF0R |= CAN_RF0R_RFOM0; - } -} - -void CAN1_TX_IRQHandler(void) { - // clear interrupt - board.CAN->TSR |= CAN_TSR_RQCP0; - process_can(); -} - -void CAN1_SCE_IRQHandler(void) { - llcan_clear_send(board.CAN); -} - -void CAN1_RX0_IRQHandler(void) { - can_rx(); -} - -void CAN2_TX_IRQHandler(void) { - // clear interrupt - board.CAN->TSR |= CAN_TSR_RQCP0; - process_can(); -} - -void CAN2_SCE_IRQHandler(void) { - llcan_clear_send(board.CAN); -} - -void CAN2_RX0_IRQHandler(void) { - can_rx(); -} - -#endif diff --git a/body/board/config.h b/body/board/config.h deleted file mode 100644 index a6271ec..0000000 --- a/body/board/config.h +++ /dev/null @@ -1,79 +0,0 @@ -// Define to prevent recursive inclusion -#ifndef CONFIG_H -#define CONFIG_H - -#include "stm32f4xx_hal.h" - -#define CORE_FREQ 96000000U // MCU frequency in hertz -#define I2C_CLOCKSPEED 100 // I2C clock in kHz -#define PWM_FREQ 16000 // PWM frequency in Hz / is also used for buzzer -#define DEAD_TIME 48 // PWM deadtime -#define DELAY_IN_MAIN_LOOP 5 // in ms. default 5. it is independent of all the timing critical stuff. do not touch if you do not know what you are doing. -#define A2BIT_CONV 50 // A to bit for current conversion on ADC. Example: 1 A = 50, 2 A = 100, etc - -#define IGNITION_OFF_DELAY 5 // Stop sending CAN messages after 5 seconds - -#define ADC_CONV_CLOCK_CYCLES (ADC_SAMPLETIME_15CYCLES) -#define ADC_CLOCK_DIV (4) -#define ADC_TOTAL_CONV_TIME (ADC_CLOCK_DIV * ADC_CONV_CLOCK_CYCLES) // = ((SystemCoreClock / ADC_CLOCK_HZ) * ADC_CONV_CLOCK_CYCLES), where ADC_CLOCK_HZ = SystemCoreClock/ADC_CLOCK_DIV - -#define KNEE_ADDR_OFFSET 0x100U -#define ANGLE_TO_DEGREES 0.021972656 // Convert 14 bit angle sensor output to degrees -#define GEARBOX_RATIO_LEFT 19 -#define GEARBOX_RATIO_RIGHT 19 -#define TRQ_LIMIT_LEFT 400 // Torque limit for knee gearbox(left) -#define TRQ_LIMIT_RIGHT 200 // Torque limit for hip gearbox(right) - -#define BAT_FILT_COEF 655 // battery voltage filter coefficient in fixed-point. coef_fixedPoint = coef_floatingPoint * 2^16. In this case 655 = 0.01 * 2^16 -#define BAT_CALIB_REAL_VOLTAGE 3192 // input voltage measured by multimeter (multiplied by 100). In this case 43.00 V * 100 = 4300 -#define BAT_CALIB_ADC 1275 // adc-value measured by mainboard (value nr 5 on UART debug output) -#define BAT_CELLS 7 // battery number of cells. Normal Hoverboard battery: 10s -#define VOLTS_PER_PERCENT 0.00814 // Volts per percent, for conversion of volts to percentage -#define BAT_LVL2 (358 * BAT_CELLS * BAT_CALIB_ADC) / BAT_CALIB_REAL_VOLTAGE // 24% -#define BAT_LVL1 (351 * BAT_CELLS * BAT_CALIB_ADC) / BAT_CALIB_REAL_VOLTAGE // 15% -#define BAT_DEAD (339 * BAT_CELLS * BAT_CALIB_ADC) / BAT_CALIB_REAL_VOLTAGE // 0% - -#define TEMP_FILT_COEF 655 // temperature filter coefficient in fixed-point. coef_fixedPoint = coef_floatingPoint * 2^16. In this case 655 = 0.01 * 2^16 -#define TEMP_CAL_LOW_ADC 945 // temperature 1: ADC value -#define TEMP_CAL_LOW_DEG_C 250 // temperature 1: measured temperature [°C * 10]. Here 35.8 °C -#define TEMP_CAL_HIGH_ADC 949 // temperature 2: ADC value -#define TEMP_CAL_HIGH_DEG_C 251 // temperature 2: measured temperature [°C * 10]. Here 48.9 °C -#define TEMP_WARNING_ENABLE 0 // to beep or not to beep, 1 or 0, DO NOT ACTIVITE WITHOUT CALIBRATION! -#define TEMP_WARNING 600 // annoying fast beeps [°C * 10]. Here 60.0 °C -#define TEMP_POWEROFF_ENABLE 0 // to poweroff or not to poweroff, 1 or 0, DO NOT ACTIVITE WITHOUT CALIBRATION! -#define TEMP_POWEROFF 650 // overheat poweroff. (while not driving) [°C * 10]. Here 65.0 °C - -#define COM_CTRL 0 // [-] Commutation Control Type -#define SIN_CTRL 1 // [-] Sinusoidal Control Type -#define FOC_CTRL 2 // [-] Field Oriented Control (FOC) Type - -#define OPEN_MODE 0 // [-] OPEN mode -#define VLT_MODE 1 // [-] VOLTAGE mode -#define SPD_MODE 2 // [-] SPEED mode -#define TRQ_MODE 3 // [-] TORQUE mode - -// Enable/Disable Motor -#define MOTOR_LEFT_ENA // [-] Enable LEFT motor. Comment-out if this motor is not needed to be operational -#define MOTOR_RIGHT_ENA // [-] Enable RIGHT motor. Comment-out if this motor is not needed to be operational - -// Control selections -#define CTRL_TYP_SEL FOC_CTRL // [-] Control type selection: COM_CTRL, SIN_CTRL, FOC_CTRL (default) -#define CTRL_MOD_REQ TRQ_MODE // [-] Control mode request: OPEN_MODE, VLT_MODE (default), SPD_MODE, TRQ_MODE. Note: SPD_MODE and TRQ_MODE are only available for CTRL_FOC! -#define DIAG_ENA 1 // [-] Motor Diagnostics enable flag: 0 = Disabled, 1 = Enabled (default) - -// Limitation settings -#define I_MOT_MAX 15 // [A] Maximum single motor current limit -#define I_DC_MAX 17 // [A] Maximum stage2 DC Link current limit for Commutation and Sinusoidal types (This is the final current protection. Above this value, current chopping is applied. To avoid this make sure that I_DC_MAX = I_MOT_MAX + 2A) -#define N_MOT_MAX 100 // [rpm] Maximum motor speed limit // 100 ~= 52m/m -#define TORQUE_BASE_MAX 1000 - -// Field Weakening / Phase Advance -#define FIELD_WEAK_ENA 0 // [-] Field Weakening / Phase Advance enable flag: 0 = Disabled (default), 1 = Enabled -#define FIELD_WEAK_MAX 5 // [A] Maximum Field Weakening D axis current (only for FOC). Higher current results in higher maximum speed. Up to 10A has been tested using 10" wheels. -#define PHASE_ADV_MAX 25 // [deg] Maximum Phase Advance angle (only for SIN). Higher angle results in higher maximum speed. -#define FIELD_WEAK_HI 1000 // (1000, 1500] Input target High threshold for reaching maximum Field Weakening / Phase Advance. Do NOT set this higher than 1500. -#define FIELD_WEAK_LO 750 // ( 500, 1000] Input target Low threshold for starting Field Weakening / Phase Advance. Do NOT set this higher than 1000. - -#define SPEED_COEFFICIENT 16384 // Default for SPEED_COEFFICIENT 1.0f [-] higher value == stronger. [0, 65535] = [-2.0 - 2.0]. In this case 16384 = 1.0 * 2^14 - -#endif diff --git a/body/board/defines.h b/body/board/defines.h deleted file mode 100644 index bc7459a..0000000 --- a/body/board/defines.h +++ /dev/null @@ -1,188 +0,0 @@ -// Define to prevent recursive inclusion -#ifndef DEFINES_H -#define DEFINES_H - -#include "stm32f4xx_hal.h" -#include "config.h" - -#define LEFT_TIM TIM8 -#define LEFT_TIM_U CCR1 -#define LEFT_TIM_UH_PIN GPIO_PIN_6 -#define LEFT_TIM_UH_PORT GPIOC -#define LEFT_TIM_UL_PIN GPIO_PIN_7 -#define LEFT_TIM_UL_PORT GPIOA -#define LEFT_TIM_V CCR2 -#define LEFT_TIM_VH_PIN GPIO_PIN_7 -#define LEFT_TIM_VH_PORT GPIOC -#define LEFT_TIM_VL_PIN GPIO_PIN_0 -#define LEFT_TIM_VL_PORT GPIOB -#define LEFT_TIM_W CCR3 -#define LEFT_TIM_WH_PIN GPIO_PIN_8 -#define LEFT_TIM_WH_PORT GPIOC -#define LEFT_TIM_WL_PIN GPIO_PIN_1 -#define LEFT_TIM_WL_PORT GPIOB - -#define RIGHT_TIM TIM1 -#define RIGHT_TIM_U CCR1 -#define RIGHT_TIM_UH_PIN GPIO_PIN_8 -#define RIGHT_TIM_UH_PORT GPIOA -#define RIGHT_TIM_UL_PIN GPIO_PIN_13 -#define RIGHT_TIM_UL_PORT GPIOB -#define RIGHT_TIM_V CCR2 -#define RIGHT_TIM_VH_PIN GPIO_PIN_9 -#define RIGHT_TIM_VH_PORT GPIOA -#define RIGHT_TIM_VL_PIN GPIO_PIN_14 -#define RIGHT_TIM_VL_PORT GPIOB -#define RIGHT_TIM_W CCR3 -#define RIGHT_TIM_WH_PIN GPIO_PIN_10 -#define RIGHT_TIM_WH_PORT GPIOA -#define RIGHT_TIM_WL_PIN GPIO_PIN_15 -#define RIGHT_TIM_WL_PORT GPIOB - -#define LEFT_DC_CUR_PIN GPIO_PIN_3 -#define LEFT_U_CUR_PIN GPIO_PIN_5 -#define LEFT_V_CUR_PIN GPIO_PIN_6 - -#define LEFT_DC_CUR_PORT GPIOA -#define LEFT_U_CUR_PORT GPIOA -#define LEFT_V_CUR_PORT GPIOA - -#define RIGHT_DC_CUR_PIN GPIO_PIN_2 -#define RIGHT_U_CUR_PIN GPIO_PIN_0 -#define RIGHT_V_CUR_PIN GPIO_PIN_1 - -#define RIGHT_DC_CUR_PORT GPIOA -#define RIGHT_U_CUR_PORT GPIOA -#define RIGHT_V_CUR_PORT GPIOA - -#define BATT_PIN GPIO_PIN_4 -#define BATT_PORT GPIOA - -#define BUZZER_PIN GPIO_PIN_2 -#define BUZZER_PORT GPIOC - -#define OFF_PIN GPIO_PIN_4 -#define OFF_PORT GPIOC - -#define BUTTON_PIN GPIO_PIN_8 -#define BUTTON_PORT GPIOB - -#define CHARGER_PIN GPIO_PIN_12 -#define CHARGER_PORT GPIOA - -#define SW_I2C1_SCL_GPIO GPIOB -#define SW_I2C1_SDA_GPIO GPIOB -#define SW_I2C1_SCL_PIN GPIO_PIN_3 -#define SW_I2C1_SDA_PIN GPIO_PIN_4 - -// UID pins -#define KEY1_PIN GPIO_PIN_10 -#define KEY1_PORT GPIOB -#define KEY2_PIN GPIO_PIN_9 -#define KEY2_PORT GPIOC - -#define DELAY_TIM_FREQUENCY_US 1000000 - -#define MILLI_R (R * 1000) -#define MILLI_PSI (PSI * 1000) -#define MILLI_V (V * 1000) - -#define NO 0 -#define YES 1 -#define ABS(a) (((a) < 0) ? -(a) : (a)) -#define LIMIT(x, lowhigh) (((x) > (lowhigh)) ? (lowhigh) : (((x) < (-lowhigh)) ? (-lowhigh) : (x))) -#define SAT(x, lowhigh) (((x) > (lowhigh)) ? (1.0f) : (((x) < (-lowhigh)) ? (-1.0f) : (0.0f))) -#define SAT2(x, low, high) (((x) > (high)) ? (1.0f) : (((x) < (low)) ? (-1.0f) : (0.0f))) -#define STEP(from, to, step) (((from) < (to)) ? (MIN((from) + (step), (to))) : (MAX((from) - (step), (to)))) -#define DEG(a) ((a)*M_PI / 180.0f) -#define RAD(a) ((a)*180.0f / M_PI) -#define SIGN(a) (((a) < 0) ? (-1) : (((a) > 0) ? (1) : (0))) -#define CLAMP(x, low, high) (((x) > (high)) ? (high) : (((x) < (low)) ? (low) : (x))) -#define IN_RANGE(x, low, high) (((x) >= (low)) && ((x) <= (high))) -#define SCALE(value, high, max) MIN(MAX(((max) - (value)) / ((max) - (high)), 0.0f), 1.0f) -#define MIN(a, b) (((a) < (b)) ? (a) : (b)) -#define MAX(a, b) (((a) > (b)) ? (a) : (b)) -#define MIN3(a, b, c) MIN(a, MIN(b, c)) -#define MAX3(a, b, c) MAX(a, MAX(b, c)) -#define ARRAY_LEN(x) (uint32_t)(sizeof(x) / sizeof(*(x))) -#define MAP(x, in_min, in_max, out_min, out_max) (((((x) - (in_min)) * ((out_max) - (out_min))) / ((in_max) - (in_min))) + (out_min)) - -#define GET_MAILBOX_BYTE(msg, b) (((int)(b) > 3) ? (((msg)->RDHR >> (8U * ((unsigned int)(b) % 4U))) & 0xFFU) : (((msg)->RDLR >> (8U * (unsigned int)(b))) & 0xFFU)) -#define GET_MAILBOX_BYTES_04(msg) ((msg)->RDLR) -#define GET_MAILBOX_BYTES_48(msg) ((msg)->RDHR) - -#define BOOT_NORMAL 0xdeadb111U -#define ENTER_SOFTLOADER_MAGIC 0xdeadc0deU - -#define APP_START_ADDRESS 0x8004000U -#define DEVICE_SERIAL_NUMBER_ADDRESS 0x1FFF79C0U - -#define COMPILE_TIME_ASSERT(pred) ((void)sizeof(char[1 - (2 * ((int)(!(pred))))])) - -#define LED_RED 0 -#define LED_GREEN 1 -#define LED_BLUE 2 -#define IGNITION 3 -#define POWERSWITCH 4 -#define TRANSCEIVER 5 - -#define HW_TYPE_BASE 0 -#define HW_TYPE_KNEE 3 - -typedef struct { - uint32_t rrB; - uint32_t rrC; - uint32_t rlA; - uint32_t rlB; - uint32_t dcr; - uint32_t dcl; - uint32_t batt1; - uint32_t temp; -} adc_buf_t; - -typedef struct { - GPIO_TypeDef* hall_portA; - uint16_t hall_pinA; - GPIO_TypeDef* hall_portB; - uint16_t hall_pinB; - GPIO_TypeDef* hall_portC; - uint16_t hall_pinC; -} hall_sensor; - -typedef struct { - hall_sensor hall_left; - hall_sensor hall_right; - - CAN_TypeDef* CAN; - uint8_t can_alt_tx; - uint8_t can_alt_rx; - GPIO_TypeDef* can_portTX; - uint16_t can_pinTX; - GPIO_TypeDef* can_portRX; - uint16_t can_pinRX; - GPIO_TypeDef* can_portEN; - uint16_t can_pinEN; - - GPIO_TypeDef* ignition_port; - uint16_t ignition_pin; - - uint16_t can_addr_offset; - uint8_t uds_offset; - - GPIO_TypeDef* led_portR; - uint16_t led_pinR; - GPIO_TypeDef* led_portG; - uint16_t led_pinG; - GPIO_TypeDef* led_portB; - uint16_t led_pinB; - -} board_t; - -typedef struct { - uint8_t left_i2c : 1; - uint8_t left_angle : 1; - uint8_t right_i2c : 1; - uint8_t right_angle : 1; -} fault_status_t; - -#endif // DEFINES_H diff --git a/body/board/drivers/angle_sensor.h b/body/board/drivers/angle_sensor.h deleted file mode 100644 index 72f0a85..0000000 --- a/body/board/drivers/angle_sensor.h +++ /dev/null @@ -1,69 +0,0 @@ -// Default addresses for AS5048B -#define AS5048_ADDRESS_LEFT 0x40 -#define AS5048_ADDRESS_RIGHT 0x41 -#define UNKNOWN_IMU 0x68 - -#define AS5048B_PROG_REG 0x03 -#define AS5048B_ADDR_REG 0x15 -#define AS5048B_ZEROMSB_REG 0x16 //bits 0..7 -#define AS5048B_ZEROLSB_REG 0x17 //bits 0..5 -#define AS5048B_GAIN_REG 0xFA -#define AS5048B_DIAG_REG 0xFB -#define AS5048B_MAGNMSB_REG 0xFC //bits 0..7 -#define AS5048B_MAGNLSB_REG 0xFD //bits 0..5 -#define AS5048B_ANGLMSB_REG 0xFE //bits 0..7 -#define AS5048B_ANGLLSB_REG 0xFF //bits 0..5 - -extern I2C_HandleTypeDef hi2c1; - -const uint8_t init_imu_regaddr[] = {0x76, 0x4c, 0x4e, 0x4f, 0x50, 0x51, 0x52, 0x53}; -const uint8_t init_imu_data[] = {0x00, 0x12, 0x2f, 0x26, 0x67, 0x04, 0x00, 0x00}; - -fault_status_t fault_status = {0}; - -void angle_sensor_read(uint16_t *sensor_angle) { - - if (fault_status.left_i2c && fault_status.right_i2c) { // Try to reinitialize halted I2C - if (HAL_I2C_Init(&hi2c1) == HAL_OK) { - fault_status.left_i2c = 0; - fault_status.right_i2c = 0; - } - } - - uint8_t buf[2]; - if (HAL_I2C_Mem_Read(&hi2c1, (AS5048_ADDRESS_LEFT<<1), AS5048B_ANGLMSB_REG, I2C_MEMADD_SIZE_8BIT, buf, 2, 10) == HAL_OK) { - sensor_angle[0] = (buf[0] << 6) | (buf[1] & 0x3F); - fault_status.left_i2c = 0; - } else { - fault_status.left_i2c = 1; - } - if (HAL_I2C_Mem_Read(&hi2c1, (AS5048_ADDRESS_RIGHT<<1), AS5048B_ANGLMSB_REG, I2C_MEMADD_SIZE_8BIT, buf, 2, 10) == HAL_OK) { - sensor_angle[1] = (buf[0] << 6) | (buf[1] & 0x3F); - fault_status.right_i2c = 0; - } else { - fault_status.right_i2c = 1; - } -} - -void IMU_soft_init(void) { - i2c_port_init(); - - for (int8_t i = 3; i > 0; i--) { - SW_I2C_WriteControl_8Bit((UNKNOWN_IMU<<1), 0x75, 0x00); - } - for (int8_t i = sizeof(init_imu_regaddr)-1; i >= 0; i--) { - SW_I2C_WriteControl_8Bit((UNKNOWN_IMU<<1), init_imu_regaddr[i], init_imu_data[i]); - } -} - -void IMU_soft_sensor_read(uint16_t *unknown_imu_data) { - static uint8_t buf[12]; - - SW_I2C_WriteControl_8Bit((UNKNOWN_IMU<<1), 0x76, 0x00); - SW_I2C_Multi_ReadnControl_8Bit((UNKNOWN_IMU<<1), 0x1F, 6, buf); - SW_I2C_Multi_ReadnControl_8Bit((UNKNOWN_IMU<<1), 0x25, 6, &buf[6]); - - for (int8_t i = 5; i >= 0; i--) { - unknown_imu_data[i] = (buf[i*2] << 8) | (buf[(i*2)+1]); - } -} diff --git a/body/board/drivers/clock.h b/body/board/drivers/clock.h deleted file mode 100644 index 39a301f..0000000 --- a/body/board/drivers/clock.h +++ /dev/null @@ -1,63 +0,0 @@ -void Error_Handler(void) -{ - /* USER CODE BEGIN Error_Handler_Debug */ - /* User can add his own implementation to report the HAL error return state */ - __disable_irq(); - while (1) - { - } - /* USER CODE END Error_Handler_Debug */ -} -/** System Clock Configuration -*/ -void SystemClock_Config(void) { - RCC_OscInitTypeDef RCC_OscInitStruct; - RCC_ClkInitTypeDef RCC_ClkInitStruct; - - /** Configure the main internal regulator output voltage - */ - __HAL_RCC_SYSCFG_CLK_ENABLE(); - __HAL_RCC_PWR_CLK_ENABLE(); - __HAL_PWR_VOLTAGESCALING_CONFIG(PWR_REGULATOR_VOLTAGE_SCALE1); - - /**Initializes the CPU, AHB and APB busses clocks - */ - RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI; - RCC_OscInitStruct.HSIState = RCC_HSI_ON; - RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT; - RCC_OscInitStruct.PLL.PLLState = RCC_PLL_ON; - RCC_OscInitStruct.PLL.PLLSource = RCC_PLLSOURCE_HSI; - - RCC_OscInitStruct.PLL.PLLM = 8; - RCC_OscInitStruct.PLL.PLLN = 96; // Gives 96 Mhz core clock - RCC_OscInitStruct.PLL.PLLP = RCC_PLLP_DIV2; - RCC_OscInitStruct.PLL.PLLQ = 2; - RCC_OscInitStruct.PLL.PLLR = 2; - if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) { - Error_Handler(); - } - - /**Initializes the CPU, AHB and APB busses clocks - */ - RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK - |RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2; - RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_PLLCLK; - RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1; - RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV2; - RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1; - - if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_2) != HAL_OK) { - Error_Handler(); - } - - /**Configure the Systick interrupt time - */ - HAL_SYSTICK_Config(HAL_RCC_GetHCLKFreq() / 1000); - - /**Configure the Systick - */ - HAL_SYSTICK_CLKSourceConfig(SYSTICK_CLKSOURCE_HCLK); - - /* SysTick_IRQn interrupt configuration */ - HAL_NVIC_SetPriority(SysTick_IRQn, 0, 0); -} diff --git a/body/board/drivers/i2c_soft.h b/body/board/drivers/i2c_soft.h deleted file mode 100644 index aa6280b..0000000 --- a/body/board/drivers/i2c_soft.h +++ /dev/null @@ -1,305 +0,0 @@ -#define SW_I2C_WAIT_TIME 22 - -#define I2C_READ 0x01 -#define READ_CMD 1 -#define WRITE_CMD 0 - - -void SW_I2C_init(void) -{ - GPIO_InitTypeDef GPIO_InitStructure = { 0 }; - - GPIO_InitStructure.Speed = GPIO_SPEED_FREQ_HIGH; - GPIO_InitStructure.Mode = GPIO_MODE_OUTPUT_PP; - - GPIO_InitStructure.Pin = SW_I2C1_SCL_PIN; - HAL_GPIO_Init(SW_I2C1_SCL_GPIO, &GPIO_InitStructure); - GPIO_InitStructure.Pin = SW_I2C1_SDA_PIN; - HAL_GPIO_Init(SW_I2C1_SDA_GPIO, &GPIO_InitStructure); -} - -uint8_t SW_I2C_ReadVal_SDA(void) -{ - uint8_t ret; - ret = (uint16_t)HAL_GPIO_ReadPin(SW_I2C1_SDA_GPIO, SW_I2C1_SDA_PIN); - return ret; -} - -void sda_high(void) -{ - HAL_GPIO_WritePin(SW_I2C1_SDA_GPIO, SW_I2C1_SDA_PIN, GPIO_PIN_SET); -} - - -void sda_low(void) -{ - HAL_GPIO_WritePin(SW_I2C1_SDA_GPIO, SW_I2C1_SDA_PIN, GPIO_PIN_RESET); -} - - -void scl_high(void) -{ - HAL_GPIO_WritePin(SW_I2C1_SCL_GPIO, SW_I2C1_SCL_PIN, GPIO_PIN_SET); -} - - -void scl_low(void) -{ - HAL_GPIO_WritePin(SW_I2C1_SCL_GPIO, SW_I2C1_SCL_PIN, GPIO_PIN_RESET); -} - -void sda_out(uint8_t out) -{ - if (out) { - sda_high(); - } else { - sda_low(); - } -} - -void sda_in_mode(void) -{ - GPIO_InitTypeDef GPIO_InitStructure = { 0 }; - - GPIO_InitStructure.Speed = GPIO_SPEED_FREQ_HIGH; - GPIO_InitStructure.Mode = GPIO_MODE_INPUT; - - GPIO_InitStructure.Pin = SW_I2C1_SDA_PIN; - HAL_GPIO_Init(SW_I2C1_SDA_GPIO, &GPIO_InitStructure); -} - -void sda_out_mode(void) -{ - GPIO_InitTypeDef GPIO_InitStructure = { 0 }; - - GPIO_InitStructure.Speed = GPIO_SPEED_FREQ_HIGH; - GPIO_InitStructure.Mode = GPIO_MODE_OUTPUT_OD; - - GPIO_InitStructure.Pin = SW_I2C1_SDA_PIN; - HAL_GPIO_Init(SW_I2C1_SDA_GPIO, &GPIO_InitStructure); -} - -void i2c_clk_data_out(void) -{ - scl_high(); - delay(SW_I2C_WAIT_TIME); - scl_low(); -} - -void i2c_port_init(void) -{ - sda_high(); - scl_high(); -} - -void i2c_start_condition(void) -{ - sda_high(); - scl_high(); - - delay(SW_I2C_WAIT_TIME); - sda_low(); - delay(SW_I2C_WAIT_TIME); - scl_low(); - - delay(SW_I2C_WAIT_TIME << 1); -} - -void i2c_stop_condition(void) -{ - sda_low(); - scl_high(); - - delay(SW_I2C_WAIT_TIME); - sda_high(); - delay(SW_I2C_WAIT_TIME); -} - -uint8_t i2c_check_ack(void) -{ - uint8_t ack; - int i; - unsigned int temp; - - sda_in_mode(); - - scl_high(); - - ack = 0; - delay(SW_I2C_WAIT_TIME); - - for (i = 10; i > 0; i--) { - temp = !(SW_I2C_ReadVal_SDA()); - if (temp) - { - ack = 1; - break; - } - } - scl_low(); - sda_out_mode(); - - delay(SW_I2C_WAIT_TIME); - return ack; -} - -void i2c_check_not_ack(void) -{ - sda_in_mode(); - i2c_clk_data_out(); - sda_out_mode(); - delay(SW_I2C_WAIT_TIME); -} - -void i2c_slave_address(uint8_t IICID, uint8_t readwrite) -{ - int x; - - if (readwrite) { - IICID |= I2C_READ; - } else { - IICID &= ~I2C_READ; - } - - scl_low(); - - for (x = 7; x >= 0; x--) { - sda_out(IICID & (1 << x)); - delay(SW_I2C_WAIT_TIME); - i2c_clk_data_out(); - } -} - -void i2c_register_address(uint8_t addr) -{ - int x; - - scl_low(); - - for (x = 7; x >= 0; x--) { - sda_out(addr & (1 << x)); - delay(SW_I2C_WAIT_TIME); - i2c_clk_data_out(); - } -} - -void i2c_send_ack(void) -{ - sda_out_mode(); - sda_low(); - - delay(SW_I2C_WAIT_TIME); - scl_high(); - - delay(SW_I2C_WAIT_TIME << 1); - - sda_low(); - delay(SW_I2C_WAIT_TIME << 1); - - scl_low(); - - sda_out_mode(); - - delay(SW_I2C_WAIT_TIME); -} - -void SW_I2C_Write_Data(uint8_t data) -{ - int x; - - scl_low(); - - for (x = 7; x >= 0; x--) { - sda_out(data & (1 << x)); - delay(SW_I2C_WAIT_TIME); - i2c_clk_data_out(); - } -} - -uint8_t SW_I2C_Read_Data(void) -{ - int x; - uint8_t readdata = 0; - - sda_in_mode(); - - for (x = 8; x--;) { - scl_high(); - - readdata <<= 1; - if (SW_I2C_ReadVal_SDA()) { readdata |= 0x01; } - - delay(SW_I2C_WAIT_TIME); - scl_low(); - - delay(SW_I2C_WAIT_TIME); - } - - sda_out_mode(); - return readdata; -} - -uint8_t SW_I2C_WriteControl_8Bit(uint8_t IICID, uint8_t regaddr, uint8_t data) -{ - uint8_t returnack = true; - - i2c_start_condition(); - - i2c_slave_address(IICID, WRITE_CMD); - if (!i2c_check_ack()) { returnack = false; } - - delay(SW_I2C_WAIT_TIME); - - i2c_register_address(regaddr); - if (!i2c_check_ack()) { returnack = false; } - - delay(SW_I2C_WAIT_TIME); - - SW_I2C_Write_Data(data); - if (!i2c_check_ack()) { returnack = false; } - - delay(SW_I2C_WAIT_TIME); - - i2c_stop_condition(); - - return returnack; -} - -uint8_t SW_I2C_Multi_ReadnControl_8Bit(uint8_t IICID, uint8_t regaddr, uint8_t rcnt, uint8_t (*pdata)) -{ - uint8_t returnack = true; - uint8_t index; - - i2c_port_init(); - - i2c_start_condition(); - - i2c_slave_address(IICID, WRITE_CMD); - if (!i2c_check_ack()) { returnack = false; } - - delay(SW_I2C_WAIT_TIME); - - i2c_register_address(regaddr); - if (!i2c_check_ack()) { returnack = false; } - - delay(SW_I2C_WAIT_TIME); - - i2c_start_condition(); - - i2c_slave_address(IICID, READ_CMD); - if (!i2c_check_ack()) { returnack = false; } - - for ( index = 0 ; index < (rcnt-1) ; index++) { - delay(SW_I2C_WAIT_TIME); - pdata[index] = SW_I2C_Read_Data(); - i2c_send_ack(); - } - - pdata[rcnt-1] = SW_I2C_Read_Data(); - - i2c_check_not_ack(); - - i2c_stop_condition(); - - return returnack; -} diff --git a/body/board/drivers/llbxcan.h b/body/board/drivers/llbxcan.h deleted file mode 100644 index 15ebb27..0000000 --- a/body/board/drivers/llbxcan.h +++ /dev/null @@ -1,125 +0,0 @@ -// SAE 2284-3 : minimum 16 tq, SJW 3, sample point at 81.3% -#define CAN_QUANTA 16U -#define CAN_SEQ1 12U -#define CAN_SEQ2 3U -#define CAN_SJW 3U - -#define CAN_PCLK (CORE_FREQ / 2U / 1000U) -#define can_speed_to_prescaler(x) (CAN_PCLK / CAN_QUANTA * 10U / (x)) -#define CAN_INIT_TIMEOUT_MS 500 - -bool llcan_set_speed(CAN_TypeDef *CAN_obj, uint32_t speed, bool loopback, bool silent) { - bool ret = true; - - // initialization mode - CAN1->MCR = CAN_MCR_INRQ; // When we want to use only CAN2 - need to do that - CAN_obj->MCR = CAN_MCR_INRQ; - uint32_t timeout_counter = 0U; - while((CAN_obj->MSR & CAN_MSR_INAK) != CAN_MSR_INAK){ - // Delay for about 1ms - delay(10000); - timeout_counter++; - - if(timeout_counter >= CAN_INIT_TIMEOUT_MS){ - ret = false; - break; - } - } - - if(ret){ - // set time quanta from defines - CAN_obj->BTR = ((CAN_BTR_TS1_0 * (CAN_SEQ1-1)) | - (CAN_BTR_TS2_0 * (CAN_SEQ2-1)) | - (CAN_BTR_SJW_0 * (CAN_SJW-1)) | - (can_speed_to_prescaler(speed) - 1U)); - - // silent loopback mode for debugging - if (loopback) { - CAN_obj->BTR |= CAN_BTR_SILM | CAN_BTR_LBKM; - } - if (silent) { - CAN_obj->BTR |= CAN_BTR_SILM; - } - - CAN_obj->MCR |= CAN_MCR_AWUM; // Automatic wakeup mode - CAN_obj->MCR |= CAN_MCR_ABOM; // Automatic bus-off management - CAN_obj->MCR &= ~CAN_MCR_NART; // Automatic retransmission - CAN_obj->MCR |= CAN_MCR_TXFP; // Priority driven by the request order (chronologically) - CAN_obj->MCR &= ~CAN_MCR_INRQ; - - timeout_counter = 0U; - while(((CAN_obj->MSR & CAN_MSR_INAK) == CAN_MSR_INAK)) { - // Delay for about 1ms - delay(10000); - timeout_counter++; - - if(timeout_counter >= CAN_INIT_TIMEOUT_MS){ - ret = false; - break; - } - } - } - - return ret; -} - -bool llcan_init(CAN_TypeDef *CAN_obj) { - bool ret = true; - - // Enter init mode - CAN_obj->FMR |= CAN_FMR_FINIT; - - // Wait for INAK bit to be set - uint32_t timeout_counter = 0U; - while(((CAN_obj->MSR & CAN_MSR_INAK) == CAN_MSR_INAK)) { - // Delay for about 1ms - delay(10000); - timeout_counter++; - - if(timeout_counter >= CAN_INIT_TIMEOUT_MS){ - ret = false; - break; - } - } - - if(ret){ - // no mask - // For some weird reason some of these registers do not want to set properly on CAN2 and CAN3. Probably something to do with the single/dual mode and their different filters. - // Filters MUST be set always through CAN1(Master) as CAN2/3 are Slave - CAN1->sFilterRegister[0].FR1 = 0U; - CAN1->sFilterRegister[0].FR2 = 0U; - CAN1->sFilterRegister[14].FR1 = 0U; - CAN1->sFilterRegister[14].FR2 = 0U; - CAN1->FA1R |= 1U | (1U << 14); - - // Exit init mode, do not wait - CAN_obj->FMR &= ~CAN_FMR_FINIT; - - // enable certain CAN interrupts - CAN1->IER = 0U; // When we want to use only CAN2 - need to do that - CAN_obj->IER = CAN_IER_FMPIE0 | CAN_IER_TMEIE | CAN_IER_WKUIE; - - if (CAN_obj == CAN1) { - HAL_NVIC_EnableIRQ(CAN1_TX_IRQn); - HAL_NVIC_SetPriority(CAN1_RX0_IRQn, 0, 0); - HAL_NVIC_EnableIRQ(CAN1_RX0_IRQn); - HAL_NVIC_SetPriority(CAN1_SCE_IRQn, 0, 0); - HAL_NVIC_EnableIRQ(CAN1_SCE_IRQn); - } else { - HAL_NVIC_SetPriority(CAN2_TX_IRQn, 0, 0); - HAL_NVIC_EnableIRQ(CAN2_TX_IRQn); - HAL_NVIC_SetPriority(CAN2_RX0_IRQn, 0, 0); - HAL_NVIC_EnableIRQ(CAN2_RX0_IRQn); - HAL_NVIC_SetPriority(CAN2_SCE_IRQn, 0, 0); - HAL_NVIC_EnableIRQ(CAN2_SCE_IRQn); - } - } - return ret; -} - -void llcan_clear_send(CAN_TypeDef *CAN_obj) { - CAN_obj->TSR |= CAN_TSR_ABRQ0; - CAN_obj->MSR &= ~CAN_MSR_ERRI; - // cppcheck-suppress selfAssignment ; needed to clear the register - CAN_obj->MSR = CAN_obj->MSR; -} diff --git a/body/board/drivers/llflash.h b/body/board/drivers/llflash.h deleted file mode 100644 index 7ce5a25..0000000 --- a/body/board/drivers/llflash.h +++ /dev/null @@ -1,26 +0,0 @@ -bool flash_is_locked(void) { - return (FLASH->CR & FLASH_CR_LOCK); -} - -void flash_unlock(void) { - FLASH->KEYR = 0x45670123; - FLASH->KEYR = 0xCDEF89AB; -} - -bool flash_erase_sector(uint8_t sector, bool unlocked) { - // don't erase the bootloader(sector 0) - if (sector != 0 && sector < 12 && unlocked) { - FLASH->CR = (sector << 3) | FLASH_CR_SER; - FLASH->CR |= FLASH_CR_STRT; - while (FLASH->SR & FLASH_SR_BSY); - return true; - } - return false; -} - -void flash_write_word(void *prog_ptr, uint32_t data) { - uint32_t *pp = prog_ptr; - FLASH->CR = FLASH_CR_PSIZE_1 | FLASH_CR_PG; - *pp = data; - while (FLASH->SR & FLASH_SR_BSY); -} diff --git a/body/board/early_init.h b/body/board/early_init.h deleted file mode 100644 index ccfe0a0..0000000 --- a/body/board/early_init.h +++ /dev/null @@ -1,15 +0,0 @@ -// Early bringup -extern void *g_pfnVectors; -extern uint32_t enter_bootloader_mode; - -void early_initialization(void) { - SystemInit(); - // after it's been in the bootloader, things are initted differently, so we reset - if ((enter_bootloader_mode != BOOT_NORMAL) && - (enter_bootloader_mode != ENTER_SOFTLOADER_MAGIC)) { - enter_bootloader_mode = BOOT_NORMAL; - NVIC_SystemReset(); - } - // setup interrupt table - SCB->VTOR = (uint32_t)&g_pfnVectors; // TODO: check if SystemInit is enough! -} diff --git a/body/board/flasher.h b/body/board/flasher.h deleted file mode 100644 index 43cfa47..0000000 --- a/body/board/flasher.h +++ /dev/null @@ -1,288 +0,0 @@ -typedef union { - uint16_t w; - struct BW { - uint8_t msb; - uint8_t lsb; - } - bw; -} -uint16_t_uint8_t; - -typedef union _USB_Setup { - uint32_t d8[2]; - struct _SetupPkt_Struc - { - uint8_t bmRequestType; - uint8_t bRequest; - uint16_t_uint8_t wValue; - uint16_t_uint8_t wIndex; - uint16_t_uint8_t wLength; - } b; -} -USB_Setup_TypeDef; - -uint32_t *prog_ptr = NULL; -bool unlocked = false; -extern uint8_t hw_type; - -#define CAN_BL_INPUT 0x1 -#define CAN_BL_OUTPUT 0x2 - -int can_control_msg(USB_Setup_TypeDef *setup, uint8_t *resp) { - int resp_len = 0; - - // flasher machine - memset(resp, 0, 4); - memcpy(resp+4, "\xde\xad\xd0\x0d", 4); - resp[0] = 0xff; - resp[2] = setup->b.bRequest; - resp[3] = ~setup->b.bRequest; - *((uint32_t **)&resp[8]) = prog_ptr; - resp_len = 0xc; - - int sec; - switch (setup->b.bRequest) { - // **** 0xb0: flasher echo - case 0xb0: - resp[1] = 0xff; - break; - // **** 0xb1: unlock flash - case 0xb1: - if (flash_is_locked()) { - flash_unlock(); - resp[1] = 0xff; - } - out_enable(LED_BLUE, true); - unlocked = true; - prog_ptr = (uint32_t *)APP_START_ADDRESS; - break; - // **** 0xb2: erase sector - case 0xb2: - sec = setup->b.wValue.w; - if (flash_erase_sector(sec, unlocked)) { - resp[1] = 0xff; - } - break; - // **** 0xd0: fetch serial number - case 0xd0: - // addresses are OTP - if (setup->b.wValue.w == 1) { - memcpy(resp, (void *)DEVICE_SERIAL_NUMBER_ADDRESS, 0x10); - resp_len = 0x10; - } else { - get_provision_chunk(resp); - resp_len = PROVISION_CHUNK_LEN; - } - break; - // **** 0xd1: enter bootloader mode - case 0xd1: - switch (setup->b.wValue.w) { - case 1: - enter_bootloader_mode = ENTER_SOFTLOADER_MAGIC; - NVIC_SystemReset(); - break; - } - break; - // **** 0xd6: get version - case 0xd6: - COMPILE_TIME_ASSERT(sizeof(gitversion) <= 0x40U); - memcpy(resp, gitversion, sizeof(gitversion)); - resp_len = sizeof(gitversion); - break; - // **** 0xd8: reset ST - case 0xd8: - NVIC_SystemReset(); - break; - } - return resp_len; -} - -void flash_data(void *data, int len) { - out_enable(LED_RED, false); - for (int i = 0; i < len/4; i++) { - flash_write_word(prog_ptr, *(uint32_t*)(data+(i*4))); - prog_ptr++; - } - out_enable(LED_RED, true); -} - -int prep_data(uint8_t *data, uint8_t *data_out) { - int resp_len = 0; - switch (data[0]) { - case 0: - // control transfer - resp_len = can_control_msg((USB_Setup_TypeDef *)(data+4), data_out); - break; - case 2: - // ep 2, flash! - flash_data(data+4, data[2]); - break; - } - return resp_len; -} - -void CAN2_TX_IRQHandler(void) { - // clear interrupt - board.CAN->TSR |= CAN_TSR_RQCP0; -} - -#define ISOTP_BUF_SIZE 0x110 - -uint8_t isotp_buf[ISOTP_BUF_SIZE]; -uint8_t *isotp_buf_ptr = NULL; -int isotp_buf_remain = 0; - -uint8_t isotp_buf_out[ISOTP_BUF_SIZE]; -uint8_t *isotp_buf_out_ptr = NULL; -int isotp_buf_out_remain = 0; -int isotp_buf_out_idx = 0; - -void bl_can_send(uint8_t *odat) { - // wait for send - while (!(board.CAN->TSR & CAN_TSR_TME0)); - - // send continue - board.CAN->sTxMailBox[0].TDLR = ((uint32_t*)odat)[0]; - board.CAN->sTxMailBox[0].TDHR = ((uint32_t*)odat)[1]; - board.CAN->sTxMailBox[0].TDTR = 8; - board.CAN->sTxMailBox[0].TIR = (CAN_BL_OUTPUT << 21) | 1; -} - -void CAN2_RX0_IRQHandler(void) { - while (board.CAN->RF0R & CAN_RF0R_FMP0) { - if ((board.CAN->sFIFOMailBox[0].RIR>>21) == CAN_BL_INPUT) { - uint8_t dat[8]; - for (int i = 0; i < 8; i++) { - dat[i] = GET_MAILBOX_BYTE(&board.CAN->sFIFOMailBox[0], i); - } - uint8_t odat[8]; - uint8_t type = dat[0] & 0xF0; - if (type == 0x30) { - // continue - while (isotp_buf_out_remain > 0) { - // wait for send - while (!(board.CAN->TSR & CAN_TSR_TME0)); - - odat[0] = 0x20 | isotp_buf_out_idx; - memcpy(odat+1, isotp_buf_out_ptr, 7); - isotp_buf_out_remain -= 7; - isotp_buf_out_ptr += 7; - isotp_buf_out_idx++; - - bl_can_send(odat); - } - } else if (type == 0x20) { - if (isotp_buf_remain > 0) { - memcpy(isotp_buf_ptr, dat+1, 7); - isotp_buf_ptr += 7; - isotp_buf_remain -= 7; - } - if (isotp_buf_remain <= 0) { - // call the function - memset(isotp_buf_out, 0, ISOTP_BUF_SIZE); - isotp_buf_out_remain = prep_data(isotp_buf, isotp_buf_out); - isotp_buf_out_ptr = isotp_buf_out; - isotp_buf_out_idx = 0; - - // send initial - if (isotp_buf_out_remain <= 7) { - odat[0] = isotp_buf_out_remain; - memcpy(odat+1, isotp_buf_out_ptr, isotp_buf_out_remain); - } else { - odat[0] = 0x10 | (isotp_buf_out_remain>>8); - odat[1] = isotp_buf_out_remain & 0xFF; - memcpy(odat+2, isotp_buf_out_ptr, 6); - isotp_buf_out_remain -= 6; - isotp_buf_out_ptr += 6; - isotp_buf_out_idx++; - } - - bl_can_send(odat); - } - } else if (type == 0x10) { - int len = ((dat[0]&0xF)<<8) | dat[1]; - - // setup buffer - isotp_buf_ptr = isotp_buf; - memcpy(isotp_buf_ptr, dat+2, 6); - - if (len < (ISOTP_BUF_SIZE-0x10)) { - isotp_buf_ptr += 6; - isotp_buf_remain = len-6; - } - - memset(odat, 0, 8); - odat[0] = 0x30; - bl_can_send(odat); - } - } - // next - board.CAN->RF0R |= CAN_RF0R_RFOM0; - } -} - -void CAN2_SCE_IRQHandler(void) { - llcan_clear_send(board.CAN); -} - -void CAN1_TX_IRQHandler(void) { - CAN2_TX_IRQHandler(); -} - -void CAN1_RX0_IRQHandler(void) { - CAN2_RX0_IRQHandler(); -} - -void CAN1_SCE_IRQHandler(void) { - CAN2_SCE_IRQHandler(); -} - -void check_powerdown(void) { - if(HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN) && (hw_type == HW_TYPE_BASE)) { - uint16_t cnt_press = 0; - while(HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN)) { - HAL_Delay(10); - cnt_press++; - if (cnt_press == (2 * 100)) { - out_enable(POWERSWITCH, false); - while(1) { - // Temporarily, to see that we went to power off but can't switch the latch - HAL_GPIO_TogglePin(board.led_portR, board.led_pinR); - HAL_Delay(100); - } - } - } - } -} - - -void soft_flasher_start(void) { - enter_bootloader_mode = 0; - - out_enable(TRANSCEIVER, true); - - __HAL_RCC_CAN1_CLK_ENABLE(); // Also needed for CAN2, dumb... - __HAL_RCC_CAN2_CLK_ENABLE(); - - // init can - llcan_set_speed(board.CAN, 5000, false, false); - llcan_init(board.CAN); - - out_enable(LED_BLUE, true); - // Wait for power button release, only for the base - if (hw_type == HW_TYPE_BASE) { - while(HAL_GPIO_ReadPin(BUTTON_PORT, BUTTON_PIN)) {} - } - out_enable(LED_GREEN, false); - - uint64_t cnt = 0; - - for (cnt=0;;cnt++) { - // blink the green LED fast - out_enable(LED_BLUE, false); - delay(500000); - out_enable(LED_BLUE, true); - delay(500000); - check_powerdown(); - } -} diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/Legacy/stm32_hal_legacy.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/Legacy/stm32_hal_legacy.h deleted file mode 100644 index ae83378..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/Legacy/stm32_hal_legacy.h +++ /dev/null @@ -1,3840 +0,0 @@ -/** - ****************************************************************************** - * @file stm32_hal_legacy.h - * @author MCD Application Team - * @brief This file contains aliases definition for the STM32Cube HAL constants - * macros and functions maintained for legacy purpose. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2019 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32_HAL_LEGACY -#define STM32_HAL_LEGACY - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ - -/** @defgroup HAL_AES_Aliased_Defines HAL CRYP Aliased Defines maintained for legacy purpose - * @{ - */ -#define AES_FLAG_RDERR CRYP_FLAG_RDERR -#define AES_FLAG_WRERR CRYP_FLAG_WRERR -#define AES_CLEARFLAG_CCF CRYP_CLEARFLAG_CCF -#define AES_CLEARFLAG_RDERR CRYP_CLEARFLAG_RDERR -#define AES_CLEARFLAG_WRERR CRYP_CLEARFLAG_WRERR -#if defined(STM32U5) -#define CRYP_DATATYPE_32B CRYP_NO_SWAP -#define CRYP_DATATYPE_16B CRYP_HALFWORD_SWAP -#define CRYP_DATATYPE_8B CRYP_BYTE_SWAP -#define CRYP_DATATYPE_1B CRYP_BIT_SWAP -#define CRYP_CCF_CLEAR CRYP_CLEAR_CCF -#define CRYP_ERR_CLEAR CRYP_CLEAR_RWEIF -#endif /* STM32U5 */ -/** - * @} - */ - -/** @defgroup HAL_ADC_Aliased_Defines HAL ADC Aliased Defines maintained for legacy purpose - * @{ - */ -#define ADC_RESOLUTION12b ADC_RESOLUTION_12B -#define ADC_RESOLUTION10b ADC_RESOLUTION_10B -#define ADC_RESOLUTION8b ADC_RESOLUTION_8B -#define ADC_RESOLUTION6b ADC_RESOLUTION_6B -#define OVR_DATA_OVERWRITTEN ADC_OVR_DATA_OVERWRITTEN -#define OVR_DATA_PRESERVED ADC_OVR_DATA_PRESERVED -#define EOC_SINGLE_CONV ADC_EOC_SINGLE_CONV -#define EOC_SEQ_CONV ADC_EOC_SEQ_CONV -#define EOC_SINGLE_SEQ_CONV ADC_EOC_SINGLE_SEQ_CONV -#define REGULAR_GROUP ADC_REGULAR_GROUP -#define INJECTED_GROUP ADC_INJECTED_GROUP -#define REGULAR_INJECTED_GROUP ADC_REGULAR_INJECTED_GROUP -#define AWD_EVENT ADC_AWD_EVENT -#define AWD1_EVENT ADC_AWD1_EVENT -#define AWD2_EVENT ADC_AWD2_EVENT -#define AWD3_EVENT ADC_AWD3_EVENT -#define OVR_EVENT ADC_OVR_EVENT -#define JQOVF_EVENT ADC_JQOVF_EVENT -#define ALL_CHANNELS ADC_ALL_CHANNELS -#define REGULAR_CHANNELS ADC_REGULAR_CHANNELS -#define INJECTED_CHANNELS ADC_INJECTED_CHANNELS -#define SYSCFG_FLAG_SENSOR_ADC ADC_FLAG_SENSOR -#define SYSCFG_FLAG_VREF_ADC ADC_FLAG_VREFINT -#define ADC_CLOCKPRESCALER_PCLK_DIV1 ADC_CLOCK_SYNC_PCLK_DIV1 -#define ADC_CLOCKPRESCALER_PCLK_DIV2 ADC_CLOCK_SYNC_PCLK_DIV2 -#define ADC_CLOCKPRESCALER_PCLK_DIV4 ADC_CLOCK_SYNC_PCLK_DIV4 -#define ADC_CLOCKPRESCALER_PCLK_DIV6 ADC_CLOCK_SYNC_PCLK_DIV6 -#define ADC_CLOCKPRESCALER_PCLK_DIV8 ADC_CLOCK_SYNC_PCLK_DIV8 -#define ADC_EXTERNALTRIG0_T6_TRGO ADC_EXTERNALTRIGCONV_T6_TRGO -#define ADC_EXTERNALTRIG1_T21_CC2 ADC_EXTERNALTRIGCONV_T21_CC2 -#define ADC_EXTERNALTRIG2_T2_TRGO ADC_EXTERNALTRIGCONV_T2_TRGO -#define ADC_EXTERNALTRIG3_T2_CC4 ADC_EXTERNALTRIGCONV_T2_CC4 -#define ADC_EXTERNALTRIG4_T22_TRGO ADC_EXTERNALTRIGCONV_T22_TRGO -#define ADC_EXTERNALTRIG7_EXT_IT11 ADC_EXTERNALTRIGCONV_EXT_IT11 -#define ADC_CLOCK_ASYNC ADC_CLOCK_ASYNC_DIV1 -#define ADC_EXTERNALTRIG_EDGE_NONE ADC_EXTERNALTRIGCONVEDGE_NONE -#define ADC_EXTERNALTRIG_EDGE_RISING ADC_EXTERNALTRIGCONVEDGE_RISING -#define ADC_EXTERNALTRIG_EDGE_FALLING ADC_EXTERNALTRIGCONVEDGE_FALLING -#define ADC_EXTERNALTRIG_EDGE_RISINGFALLING ADC_EXTERNALTRIGCONVEDGE_RISINGFALLING -#define ADC_SAMPLETIME_2CYCLE_5 ADC_SAMPLETIME_2CYCLES_5 - -#define HAL_ADC_STATE_BUSY_REG HAL_ADC_STATE_REG_BUSY -#define HAL_ADC_STATE_BUSY_INJ HAL_ADC_STATE_INJ_BUSY -#define HAL_ADC_STATE_EOC_REG HAL_ADC_STATE_REG_EOC -#define HAL_ADC_STATE_EOC_INJ HAL_ADC_STATE_INJ_EOC -#define HAL_ADC_STATE_ERROR HAL_ADC_STATE_ERROR_INTERNAL -#define HAL_ADC_STATE_BUSY HAL_ADC_STATE_BUSY_INTERNAL -#define HAL_ADC_STATE_AWD HAL_ADC_STATE_AWD1 - -#if defined(STM32H7) -#define ADC_CHANNEL_VBAT_DIV4 ADC_CHANNEL_VBAT -#endif /* STM32H7 */ -/** - * @} - */ - -/** @defgroup HAL_CEC_Aliased_Defines HAL CEC Aliased Defines maintained for legacy purpose - * @{ - */ - -#define __HAL_CEC_GET_IT __HAL_CEC_GET_FLAG - -/** - * @} - */ - -/** @defgroup HAL_COMP_Aliased_Defines HAL COMP Aliased Defines maintained for legacy purpose - * @{ - */ -#define COMP_WINDOWMODE_DISABLED COMP_WINDOWMODE_DISABLE -#define COMP_WINDOWMODE_ENABLED COMP_WINDOWMODE_ENABLE -#define COMP_EXTI_LINE_COMP1_EVENT COMP_EXTI_LINE_COMP1 -#define COMP_EXTI_LINE_COMP2_EVENT COMP_EXTI_LINE_COMP2 -#define COMP_EXTI_LINE_COMP3_EVENT COMP_EXTI_LINE_COMP3 -#define COMP_EXTI_LINE_COMP4_EVENT COMP_EXTI_LINE_COMP4 -#define COMP_EXTI_LINE_COMP5_EVENT COMP_EXTI_LINE_COMP5 -#define COMP_EXTI_LINE_COMP6_EVENT COMP_EXTI_LINE_COMP6 -#define COMP_EXTI_LINE_COMP7_EVENT COMP_EXTI_LINE_COMP7 -#if defined(STM32L0) -#define COMP_LPTIMCONNECTION_ENABLED ((uint32_t)0x00000003U) /*!< COMPX output generic naming: connected to LPTIM input 1 for COMP1, LPTIM input 2 for COMP2 */ -#endif -#define COMP_OUTPUT_COMP6TIM2OCREFCLR COMP_OUTPUT_COMP6_TIM2OCREFCLR -#if defined(STM32F373xC) || defined(STM32F378xx) -#define COMP_OUTPUT_TIM3IC1 COMP_OUTPUT_COMP1_TIM3IC1 -#define COMP_OUTPUT_TIM3OCREFCLR COMP_OUTPUT_COMP1_TIM3OCREFCLR -#endif /* STM32F373xC || STM32F378xx */ - -#if defined(STM32L0) || defined(STM32L4) -#define COMP_WINDOWMODE_ENABLE COMP_WINDOWMODE_COMP1_INPUT_PLUS_COMMON - -#define COMP_NONINVERTINGINPUT_IO1 COMP_INPUT_PLUS_IO1 -#define COMP_NONINVERTINGINPUT_IO2 COMP_INPUT_PLUS_IO2 -#define COMP_NONINVERTINGINPUT_IO3 COMP_INPUT_PLUS_IO3 -#define COMP_NONINVERTINGINPUT_IO4 COMP_INPUT_PLUS_IO4 -#define COMP_NONINVERTINGINPUT_IO5 COMP_INPUT_PLUS_IO5 -#define COMP_NONINVERTINGINPUT_IO6 COMP_INPUT_PLUS_IO6 - -#define COMP_INVERTINGINPUT_1_4VREFINT COMP_INPUT_MINUS_1_4VREFINT -#define COMP_INVERTINGINPUT_1_2VREFINT COMP_INPUT_MINUS_1_2VREFINT -#define COMP_INVERTINGINPUT_3_4VREFINT COMP_INPUT_MINUS_3_4VREFINT -#define COMP_INVERTINGINPUT_VREFINT COMP_INPUT_MINUS_VREFINT -#define COMP_INVERTINGINPUT_DAC1_CH1 COMP_INPUT_MINUS_DAC1_CH1 -#define COMP_INVERTINGINPUT_DAC1_CH2 COMP_INPUT_MINUS_DAC1_CH2 -#define COMP_INVERTINGINPUT_DAC1 COMP_INPUT_MINUS_DAC1_CH1 -#define COMP_INVERTINGINPUT_DAC2 COMP_INPUT_MINUS_DAC1_CH2 -#define COMP_INVERTINGINPUT_IO1 COMP_INPUT_MINUS_IO1 -#if defined(STM32L0) -/* Issue fixed on STM32L0 COMP driver: only 2 dedicated IO (IO1 and IO2), */ -/* IO2 was wrongly assigned to IO shared with DAC and IO3 was corresponding */ -/* to the second dedicated IO (only for COMP2). */ -#define COMP_INVERTINGINPUT_IO2 COMP_INPUT_MINUS_DAC1_CH2 -#define COMP_INVERTINGINPUT_IO3 COMP_INPUT_MINUS_IO2 -#else -#define COMP_INVERTINGINPUT_IO2 COMP_INPUT_MINUS_IO2 -#define COMP_INVERTINGINPUT_IO3 COMP_INPUT_MINUS_IO3 -#endif -#define COMP_INVERTINGINPUT_IO4 COMP_INPUT_MINUS_IO4 -#define COMP_INVERTINGINPUT_IO5 COMP_INPUT_MINUS_IO5 - -#define COMP_OUTPUTLEVEL_LOW COMP_OUTPUT_LEVEL_LOW -#define COMP_OUTPUTLEVEL_HIGH COMP_OUTPUT_LEVEL_HIGH - -/* Note: Literal "COMP_FLAG_LOCK" kept for legacy purpose. */ -/* To check COMP lock state, use macro "__HAL_COMP_IS_LOCKED()". */ -#if defined(COMP_CSR_LOCK) -#define COMP_FLAG_LOCK COMP_CSR_LOCK -#elif defined(COMP_CSR_COMP1LOCK) -#define COMP_FLAG_LOCK COMP_CSR_COMP1LOCK -#elif defined(COMP_CSR_COMPxLOCK) -#define COMP_FLAG_LOCK COMP_CSR_COMPxLOCK -#endif - -#if defined(STM32L4) -#define COMP_BLANKINGSRCE_TIM1OC5 COMP_BLANKINGSRC_TIM1_OC5_COMP1 -#define COMP_BLANKINGSRCE_TIM2OC3 COMP_BLANKINGSRC_TIM2_OC3_COMP1 -#define COMP_BLANKINGSRCE_TIM3OC3 COMP_BLANKINGSRC_TIM3_OC3_COMP1 -#define COMP_BLANKINGSRCE_TIM3OC4 COMP_BLANKINGSRC_TIM3_OC4_COMP2 -#define COMP_BLANKINGSRCE_TIM8OC5 COMP_BLANKINGSRC_TIM8_OC5_COMP2 -#define COMP_BLANKINGSRCE_TIM15OC1 COMP_BLANKINGSRC_TIM15_OC1_COMP2 -#define COMP_BLANKINGSRCE_NONE COMP_BLANKINGSRC_NONE -#endif - -#if defined(STM32L0) -#define COMP_MODE_HIGHSPEED COMP_POWERMODE_MEDIUMSPEED -#define COMP_MODE_LOWSPEED COMP_POWERMODE_ULTRALOWPOWER -#else -#define COMP_MODE_HIGHSPEED COMP_POWERMODE_HIGHSPEED -#define COMP_MODE_MEDIUMSPEED COMP_POWERMODE_MEDIUMSPEED -#define COMP_MODE_LOWPOWER COMP_POWERMODE_LOWPOWER -#define COMP_MODE_ULTRALOWPOWER COMP_POWERMODE_ULTRALOWPOWER -#endif - -#endif -/** - * @} - */ - -/** @defgroup HAL_CORTEX_Aliased_Defines HAL CORTEX Aliased Defines maintained for legacy purpose - * @{ - */ -#define __HAL_CORTEX_SYSTICKCLK_CONFIG HAL_SYSTICK_CLKSourceConfig -/** - * @} - */ - -/** - * @} - */ - -/** @defgroup HAL_CRC_Aliased_Defines HAL CRC Aliased Defines maintained for legacy purpose - * @{ - */ - -#define CRC_OUTPUTDATA_INVERSION_DISABLED CRC_OUTPUTDATA_INVERSION_DISABLE -#define CRC_OUTPUTDATA_INVERSION_ENABLED CRC_OUTPUTDATA_INVERSION_ENABLE - -/** - * @} - */ - -/** @defgroup HAL_DAC_Aliased_Defines HAL DAC Aliased Defines maintained for legacy purpose - * @{ - */ - -#define DAC1_CHANNEL_1 DAC_CHANNEL_1 -#define DAC1_CHANNEL_2 DAC_CHANNEL_2 -#define DAC2_CHANNEL_1 DAC_CHANNEL_1 -#define DAC_WAVE_NONE 0x00000000U -#define DAC_WAVE_NOISE DAC_CR_WAVE1_0 -#define DAC_WAVE_TRIANGLE DAC_CR_WAVE1_1 -#define DAC_WAVEGENERATION_NONE DAC_WAVE_NONE -#define DAC_WAVEGENERATION_NOISE DAC_WAVE_NOISE -#define DAC_WAVEGENERATION_TRIANGLE DAC_WAVE_TRIANGLE - -#if defined(STM32G4) || defined(STM32H7) || defined (STM32U5) -#define DAC_CHIPCONNECT_DISABLE DAC_CHIPCONNECT_EXTERNAL -#define DAC_CHIPCONNECT_ENABLE DAC_CHIPCONNECT_INTERNAL -#endif - -#if defined(STM32L1) || defined(STM32L4) || defined(STM32G0) || defined(STM32L5) || defined(STM32H7) || defined(STM32F4) || defined(STM32G4) -#define HAL_DAC_MSP_INIT_CB_ID HAL_DAC_MSPINIT_CB_ID -#define HAL_DAC_MSP_DEINIT_CB_ID HAL_DAC_MSPDEINIT_CB_ID -#endif - -/** - * @} - */ - -/** @defgroup HAL_DMA_Aliased_Defines HAL DMA Aliased Defines maintained for legacy purpose - * @{ - */ -#define HAL_REMAPDMA_ADC_DMA_CH2 DMA_REMAP_ADC_DMA_CH2 -#define HAL_REMAPDMA_USART1_TX_DMA_CH4 DMA_REMAP_USART1_TX_DMA_CH4 -#define HAL_REMAPDMA_USART1_RX_DMA_CH5 DMA_REMAP_USART1_RX_DMA_CH5 -#define HAL_REMAPDMA_TIM16_DMA_CH4 DMA_REMAP_TIM16_DMA_CH4 -#define HAL_REMAPDMA_TIM17_DMA_CH2 DMA_REMAP_TIM17_DMA_CH2 -#define HAL_REMAPDMA_USART3_DMA_CH32 DMA_REMAP_USART3_DMA_CH32 -#define HAL_REMAPDMA_TIM16_DMA_CH6 DMA_REMAP_TIM16_DMA_CH6 -#define HAL_REMAPDMA_TIM17_DMA_CH7 DMA_REMAP_TIM17_DMA_CH7 -#define HAL_REMAPDMA_SPI2_DMA_CH67 DMA_REMAP_SPI2_DMA_CH67 -#define HAL_REMAPDMA_USART2_DMA_CH67 DMA_REMAP_USART2_DMA_CH67 -#define HAL_REMAPDMA_I2C1_DMA_CH76 DMA_REMAP_I2C1_DMA_CH76 -#define HAL_REMAPDMA_TIM1_DMA_CH6 DMA_REMAP_TIM1_DMA_CH6 -#define HAL_REMAPDMA_TIM2_DMA_CH7 DMA_REMAP_TIM2_DMA_CH7 -#define HAL_REMAPDMA_TIM3_DMA_CH6 DMA_REMAP_TIM3_DMA_CH6 - -#define IS_HAL_REMAPDMA IS_DMA_REMAP -#define __HAL_REMAPDMA_CHANNEL_ENABLE __HAL_DMA_REMAP_CHANNEL_ENABLE -#define __HAL_REMAPDMA_CHANNEL_DISABLE __HAL_DMA_REMAP_CHANNEL_DISABLE - -#if defined(STM32L4) - -#define HAL_DMAMUX1_REQUEST_GEN_EXTI0 HAL_DMAMUX1_REQ_GEN_EXTI0 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI1 HAL_DMAMUX1_REQ_GEN_EXTI1 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI2 HAL_DMAMUX1_REQ_GEN_EXTI2 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI3 HAL_DMAMUX1_REQ_GEN_EXTI3 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI4 HAL_DMAMUX1_REQ_GEN_EXTI4 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI5 HAL_DMAMUX1_REQ_GEN_EXTI5 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI6 HAL_DMAMUX1_REQ_GEN_EXTI6 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI7 HAL_DMAMUX1_REQ_GEN_EXTI7 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI8 HAL_DMAMUX1_REQ_GEN_EXTI8 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI9 HAL_DMAMUX1_REQ_GEN_EXTI9 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI10 HAL_DMAMUX1_REQ_GEN_EXTI10 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI11 HAL_DMAMUX1_REQ_GEN_EXTI11 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI12 HAL_DMAMUX1_REQ_GEN_EXTI12 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI13 HAL_DMAMUX1_REQ_GEN_EXTI13 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI14 HAL_DMAMUX1_REQ_GEN_EXTI14 -#define HAL_DMAMUX1_REQUEST_GEN_EXTI15 HAL_DMAMUX1_REQ_GEN_EXTI15 -#define HAL_DMAMUX1_REQUEST_GEN_DMAMUX1_CH0_EVT HAL_DMAMUX1_REQ_GEN_DMAMUX1_CH0_EVT -#define HAL_DMAMUX1_REQUEST_GEN_DMAMUX1_CH1_EVT HAL_DMAMUX1_REQ_GEN_DMAMUX1_CH1_EVT -#define HAL_DMAMUX1_REQUEST_GEN_DMAMUX1_CH2_EVT HAL_DMAMUX1_REQ_GEN_DMAMUX1_CH2_EVT -#define HAL_DMAMUX1_REQUEST_GEN_DMAMUX1_CH3_EVT HAL_DMAMUX1_REQ_GEN_DMAMUX1_CH3_EVT -#define HAL_DMAMUX1_REQUEST_GEN_LPTIM1_OUT HAL_DMAMUX1_REQ_GEN_LPTIM1_OUT -#define HAL_DMAMUX1_REQUEST_GEN_LPTIM2_OUT HAL_DMAMUX1_REQ_GEN_LPTIM2_OUT -#define HAL_DMAMUX1_REQUEST_GEN_DSI_TE HAL_DMAMUX1_REQ_GEN_DSI_TE -#define HAL_DMAMUX1_REQUEST_GEN_DSI_EOT HAL_DMAMUX1_REQ_GEN_DSI_EOT -#define HAL_DMAMUX1_REQUEST_GEN_DMA2D_EOT HAL_DMAMUX1_REQ_GEN_DMA2D_EOT -#define HAL_DMAMUX1_REQUEST_GEN_LTDC_IT HAL_DMAMUX1_REQ_GEN_LTDC_IT - -#define HAL_DMAMUX_REQUEST_GEN_NO_EVENT HAL_DMAMUX_REQ_GEN_NO_EVENT -#define HAL_DMAMUX_REQUEST_GEN_RISING HAL_DMAMUX_REQ_GEN_RISING -#define HAL_DMAMUX_REQUEST_GEN_FALLING HAL_DMAMUX_REQ_GEN_FALLING -#define HAL_DMAMUX_REQUEST_GEN_RISING_FALLING HAL_DMAMUX_REQ_GEN_RISING_FALLING - -#if defined(STM32L4R5xx) || defined(STM32L4R9xx) || defined(STM32L4R9xx) || defined(STM32L4S5xx) || defined(STM32L4S7xx) || defined(STM32L4S9xx) -#define DMA_REQUEST_DCMI_PSSI DMA_REQUEST_DCMI -#endif - -#endif /* STM32L4 */ - -#if defined(STM32G0) -#define DMA_REQUEST_DAC1_CHANNEL1 DMA_REQUEST_DAC1_CH1 -#define DMA_REQUEST_DAC1_CHANNEL2 DMA_REQUEST_DAC1_CH2 -#define DMA_REQUEST_TIM16_TRIG_COM DMA_REQUEST_TIM16_COM -#define DMA_REQUEST_TIM17_TRIG_COM DMA_REQUEST_TIM17_COM - -#define LL_DMAMUX_REQ_TIM16_TRIG_COM LL_DMAMUX_REQ_TIM16_COM -#define LL_DMAMUX_REQ_TIM17_TRIG_COM LL_DMAMUX_REQ_TIM17_COM -#endif - -#if defined(STM32H7) - -#define DMA_REQUEST_DAC1 DMA_REQUEST_DAC1_CH1 -#define DMA_REQUEST_DAC2 DMA_REQUEST_DAC1_CH2 - -#define BDMA_REQUEST_LP_UART1_RX BDMA_REQUEST_LPUART1_RX -#define BDMA_REQUEST_LP_UART1_TX BDMA_REQUEST_LPUART1_TX - -#define HAL_DMAMUX1_REQUEST_GEN_DMAMUX1_CH0_EVT HAL_DMAMUX1_REQ_GEN_DMAMUX1_CH0_EVT -#define HAL_DMAMUX1_REQUEST_GEN_DMAMUX1_CH1_EVT HAL_DMAMUX1_REQ_GEN_DMAMUX1_CH1_EVT -#define HAL_DMAMUX1_REQUEST_GEN_DMAMUX1_CH2_EVT HAL_DMAMUX1_REQ_GEN_DMAMUX1_CH2_EVT -#define HAL_DMAMUX1_REQUEST_GEN_LPTIM1_OUT HAL_DMAMUX1_REQ_GEN_LPTIM1_OUT -#define HAL_DMAMUX1_REQUEST_GEN_LPTIM2_OUT HAL_DMAMUX1_REQ_GEN_LPTIM2_OUT -#define HAL_DMAMUX1_REQUEST_GEN_LPTIM3_OUT HAL_DMAMUX1_REQ_GEN_LPTIM3_OUT -#define HAL_DMAMUX1_REQUEST_GEN_EXTI0 HAL_DMAMUX1_REQ_GEN_EXTI0 -#define HAL_DMAMUX1_REQUEST_GEN_TIM12_TRGO HAL_DMAMUX1_REQ_GEN_TIM12_TRGO - -#define HAL_DMAMUX2_REQUEST_GEN_DMAMUX2_CH0_EVT HAL_DMAMUX2_REQ_GEN_DMAMUX2_CH0_EVT -#define HAL_DMAMUX2_REQUEST_GEN_DMAMUX2_CH1_EVT HAL_DMAMUX2_REQ_GEN_DMAMUX2_CH1_EVT -#define HAL_DMAMUX2_REQUEST_GEN_DMAMUX2_CH2_EVT HAL_DMAMUX2_REQ_GEN_DMAMUX2_CH2_EVT -#define HAL_DMAMUX2_REQUEST_GEN_DMAMUX2_CH3_EVT HAL_DMAMUX2_REQ_GEN_DMAMUX2_CH3_EVT -#define HAL_DMAMUX2_REQUEST_GEN_DMAMUX2_CH4_EVT HAL_DMAMUX2_REQ_GEN_DMAMUX2_CH4_EVT -#define HAL_DMAMUX2_REQUEST_GEN_DMAMUX2_CH5_EVT HAL_DMAMUX2_REQ_GEN_DMAMUX2_CH5_EVT -#define HAL_DMAMUX2_REQUEST_GEN_DMAMUX2_CH6_EVT HAL_DMAMUX2_REQ_GEN_DMAMUX2_CH6_EVT -#define HAL_DMAMUX2_REQUEST_GEN_LPUART1_RX_WKUP HAL_DMAMUX2_REQ_GEN_LPUART1_RX_WKUP -#define HAL_DMAMUX2_REQUEST_GEN_LPUART1_TX_WKUP HAL_DMAMUX2_REQ_GEN_LPUART1_TX_WKUP -#define HAL_DMAMUX2_REQUEST_GEN_LPTIM2_WKUP HAL_DMAMUX2_REQ_GEN_LPTIM2_WKUP -#define HAL_DMAMUX2_REQUEST_GEN_LPTIM2_OUT HAL_DMAMUX2_REQ_GEN_LPTIM2_OUT -#define HAL_DMAMUX2_REQUEST_GEN_LPTIM3_WKUP HAL_DMAMUX2_REQ_GEN_LPTIM3_WKUP -#define HAL_DMAMUX2_REQUEST_GEN_LPTIM3_OUT HAL_DMAMUX2_REQ_GEN_LPTIM3_OUT -#define HAL_DMAMUX2_REQUEST_GEN_LPTIM4_WKUP HAL_DMAMUX2_REQ_GEN_LPTIM4_WKUP -#define HAL_DMAMUX2_REQUEST_GEN_LPTIM5_WKUP HAL_DMAMUX2_REQ_GEN_LPTIM5_WKUP -#define HAL_DMAMUX2_REQUEST_GEN_I2C4_WKUP HAL_DMAMUX2_REQ_GEN_I2C4_WKUP -#define HAL_DMAMUX2_REQUEST_GEN_SPI6_WKUP HAL_DMAMUX2_REQ_GEN_SPI6_WKUP -#define HAL_DMAMUX2_REQUEST_GEN_COMP1_OUT HAL_DMAMUX2_REQ_GEN_COMP1_OUT -#define HAL_DMAMUX2_REQUEST_GEN_COMP2_OUT HAL_DMAMUX2_REQ_GEN_COMP2_OUT -#define HAL_DMAMUX2_REQUEST_GEN_RTC_WKUP HAL_DMAMUX2_REQ_GEN_RTC_WKUP -#define HAL_DMAMUX2_REQUEST_GEN_EXTI0 HAL_DMAMUX2_REQ_GEN_EXTI0 -#define HAL_DMAMUX2_REQUEST_GEN_EXTI2 HAL_DMAMUX2_REQ_GEN_EXTI2 -#define HAL_DMAMUX2_REQUEST_GEN_I2C4_IT_EVT HAL_DMAMUX2_REQ_GEN_I2C4_IT_EVT -#define HAL_DMAMUX2_REQUEST_GEN_SPI6_IT HAL_DMAMUX2_REQ_GEN_SPI6_IT -#define HAL_DMAMUX2_REQUEST_GEN_LPUART1_TX_IT HAL_DMAMUX2_REQ_GEN_LPUART1_TX_IT -#define HAL_DMAMUX2_REQUEST_GEN_LPUART1_RX_IT HAL_DMAMUX2_REQ_GEN_LPUART1_RX_IT -#define HAL_DMAMUX2_REQUEST_GEN_ADC3_IT HAL_DMAMUX2_REQ_GEN_ADC3_IT -#define HAL_DMAMUX2_REQUEST_GEN_ADC3_AWD1_OUT HAL_DMAMUX2_REQ_GEN_ADC3_AWD1_OUT -#define HAL_DMAMUX2_REQUEST_GEN_BDMA_CH0_IT HAL_DMAMUX2_REQ_GEN_BDMA_CH0_IT -#define HAL_DMAMUX2_REQUEST_GEN_BDMA_CH1_IT HAL_DMAMUX2_REQ_GEN_BDMA_CH1_IT - -#define HAL_DMAMUX_REQUEST_GEN_NO_EVENT HAL_DMAMUX_REQ_GEN_NO_EVENT -#define HAL_DMAMUX_REQUEST_GEN_RISING HAL_DMAMUX_REQ_GEN_RISING -#define HAL_DMAMUX_REQUEST_GEN_FALLING HAL_DMAMUX_REQ_GEN_FALLING -#define HAL_DMAMUX_REQUEST_GEN_RISING_FALLING HAL_DMAMUX_REQ_GEN_RISING_FALLING - -#define DFSDM_FILTER_EXT_TRIG_LPTIM1 DFSDM_FILTER_EXT_TRIG_LPTIM1_OUT -#define DFSDM_FILTER_EXT_TRIG_LPTIM2 DFSDM_FILTER_EXT_TRIG_LPTIM2_OUT -#define DFSDM_FILTER_EXT_TRIG_LPTIM3 DFSDM_FILTER_EXT_TRIG_LPTIM3_OUT - -#define DAC_TRIGGER_LP1_OUT DAC_TRIGGER_LPTIM1_OUT -#define DAC_TRIGGER_LP2_OUT DAC_TRIGGER_LPTIM2_OUT - -#endif /* STM32H7 */ -/** - * @} - */ - -/** @defgroup HAL_FLASH_Aliased_Defines HAL FLASH Aliased Defines maintained for legacy purpose - * @{ - */ - -#define TYPEPROGRAM_BYTE FLASH_TYPEPROGRAM_BYTE -#define TYPEPROGRAM_HALFWORD FLASH_TYPEPROGRAM_HALFWORD -#define TYPEPROGRAM_WORD FLASH_TYPEPROGRAM_WORD -#define TYPEPROGRAM_DOUBLEWORD FLASH_TYPEPROGRAM_DOUBLEWORD -#define TYPEERASE_SECTORS FLASH_TYPEERASE_SECTORS -#define TYPEERASE_PAGES FLASH_TYPEERASE_PAGES -#define TYPEERASE_PAGEERASE FLASH_TYPEERASE_PAGES -#define TYPEERASE_MASSERASE FLASH_TYPEERASE_MASSERASE -#define WRPSTATE_DISABLE OB_WRPSTATE_DISABLE -#define WRPSTATE_ENABLE OB_WRPSTATE_ENABLE -#define HAL_FLASH_TIMEOUT_VALUE FLASH_TIMEOUT_VALUE -#define OBEX_PCROP OPTIONBYTE_PCROP -#define OBEX_BOOTCONFIG OPTIONBYTE_BOOTCONFIG -#define PCROPSTATE_DISABLE OB_PCROP_STATE_DISABLE -#define PCROPSTATE_ENABLE OB_PCROP_STATE_ENABLE -#define TYPEERASEDATA_BYTE FLASH_TYPEERASEDATA_BYTE -#define TYPEERASEDATA_HALFWORD FLASH_TYPEERASEDATA_HALFWORD -#define TYPEERASEDATA_WORD FLASH_TYPEERASEDATA_WORD -#define TYPEPROGRAMDATA_BYTE FLASH_TYPEPROGRAMDATA_BYTE -#define TYPEPROGRAMDATA_HALFWORD FLASH_TYPEPROGRAMDATA_HALFWORD -#define TYPEPROGRAMDATA_WORD FLASH_TYPEPROGRAMDATA_WORD -#define TYPEPROGRAMDATA_FASTBYTE FLASH_TYPEPROGRAMDATA_FASTBYTE -#define TYPEPROGRAMDATA_FASTHALFWORD FLASH_TYPEPROGRAMDATA_FASTHALFWORD -#define TYPEPROGRAMDATA_FASTWORD FLASH_TYPEPROGRAMDATA_FASTWORD -#define PAGESIZE FLASH_PAGE_SIZE -#define TYPEPROGRAM_FASTBYTE FLASH_TYPEPROGRAM_BYTE -#define TYPEPROGRAM_FASTHALFWORD FLASH_TYPEPROGRAM_HALFWORD -#define TYPEPROGRAM_FASTWORD FLASH_TYPEPROGRAM_WORD -#define VOLTAGE_RANGE_1 FLASH_VOLTAGE_RANGE_1 -#define VOLTAGE_RANGE_2 FLASH_VOLTAGE_RANGE_2 -#define VOLTAGE_RANGE_3 FLASH_VOLTAGE_RANGE_3 -#define VOLTAGE_RANGE_4 FLASH_VOLTAGE_RANGE_4 -#define TYPEPROGRAM_FAST FLASH_TYPEPROGRAM_FAST -#define TYPEPROGRAM_FAST_AND_LAST FLASH_TYPEPROGRAM_FAST_AND_LAST -#define WRPAREA_BANK1_AREAA OB_WRPAREA_BANK1_AREAA -#define WRPAREA_BANK1_AREAB OB_WRPAREA_BANK1_AREAB -#define WRPAREA_BANK2_AREAA OB_WRPAREA_BANK2_AREAA -#define WRPAREA_BANK2_AREAB OB_WRPAREA_BANK2_AREAB -#define IWDG_STDBY_FREEZE OB_IWDG_STDBY_FREEZE -#define IWDG_STDBY_ACTIVE OB_IWDG_STDBY_RUN -#define IWDG_STOP_FREEZE OB_IWDG_STOP_FREEZE -#define IWDG_STOP_ACTIVE OB_IWDG_STOP_RUN -#define FLASH_ERROR_NONE HAL_FLASH_ERROR_NONE -#define FLASH_ERROR_RD HAL_FLASH_ERROR_RD -#define FLASH_ERROR_PG HAL_FLASH_ERROR_PROG -#define FLASH_ERROR_PGP HAL_FLASH_ERROR_PGS -#define FLASH_ERROR_WRP HAL_FLASH_ERROR_WRP -#define FLASH_ERROR_OPTV HAL_FLASH_ERROR_OPTV -#define FLASH_ERROR_OPTVUSR HAL_FLASH_ERROR_OPTVUSR -#define FLASH_ERROR_PROG HAL_FLASH_ERROR_PROG -#define FLASH_ERROR_OP HAL_FLASH_ERROR_OPERATION -#define FLASH_ERROR_PGA HAL_FLASH_ERROR_PGA -#define FLASH_ERROR_SIZE HAL_FLASH_ERROR_SIZE -#define FLASH_ERROR_SIZ HAL_FLASH_ERROR_SIZE -#define FLASH_ERROR_PGS HAL_FLASH_ERROR_PGS -#define FLASH_ERROR_MIS HAL_FLASH_ERROR_MIS -#define FLASH_ERROR_FAST HAL_FLASH_ERROR_FAST -#define FLASH_ERROR_FWWERR HAL_FLASH_ERROR_FWWERR -#define FLASH_ERROR_NOTZERO HAL_FLASH_ERROR_NOTZERO -#define FLASH_ERROR_OPERATION HAL_FLASH_ERROR_OPERATION -#define FLASH_ERROR_ERS HAL_FLASH_ERROR_ERS -#define OB_WDG_SW OB_IWDG_SW -#define OB_WDG_HW OB_IWDG_HW -#define OB_SDADC12_VDD_MONITOR_SET OB_SDACD_VDD_MONITOR_SET -#define OB_SDADC12_VDD_MONITOR_RESET OB_SDACD_VDD_MONITOR_RESET -#define OB_RAM_PARITY_CHECK_SET OB_SRAM_PARITY_SET -#define OB_RAM_PARITY_CHECK_RESET OB_SRAM_PARITY_RESET -#define IS_OB_SDADC12_VDD_MONITOR IS_OB_SDACD_VDD_MONITOR -#define OB_RDP_LEVEL0 OB_RDP_LEVEL_0 -#define OB_RDP_LEVEL1 OB_RDP_LEVEL_1 -#define OB_RDP_LEVEL2 OB_RDP_LEVEL_2 -#if defined(STM32G0) -#define OB_BOOT_LOCK_DISABLE OB_BOOT_ENTRY_FORCED_NONE -#define OB_BOOT_LOCK_ENABLE OB_BOOT_ENTRY_FORCED_FLASH -#else -#define OB_BOOT_ENTRY_FORCED_NONE OB_BOOT_LOCK_DISABLE -#define OB_BOOT_ENTRY_FORCED_FLASH OB_BOOT_LOCK_ENABLE -#endif -#if defined(STM32H7) -#define FLASH_FLAG_SNECCE_BANK1RR FLASH_FLAG_SNECCERR_BANK1 -#define FLASH_FLAG_DBECCE_BANK1RR FLASH_FLAG_DBECCERR_BANK1 -#define FLASH_FLAG_STRBER_BANK1R FLASH_FLAG_STRBERR_BANK1 -#define FLASH_FLAG_SNECCE_BANK2RR FLASH_FLAG_SNECCERR_BANK2 -#define FLASH_FLAG_DBECCE_BANK2RR FLASH_FLAG_DBECCERR_BANK2 -#define FLASH_FLAG_STRBER_BANK2R FLASH_FLAG_STRBERR_BANK2 -#define FLASH_FLAG_WDW FLASH_FLAG_WBNE -#define OB_WRP_SECTOR_All OB_WRP_SECTOR_ALL -#endif /* STM32H7 */ -#if defined(STM32U5) -#define OB_USER_nRST_STOP OB_USER_NRST_STOP -#define OB_USER_nRST_STDBY OB_USER_NRST_STDBY -#define OB_USER_nRST_SHDW OB_USER_NRST_SHDW -#define OB_USER_nSWBOOT0 OB_USER_NSWBOOT0 -#define OB_USER_nBOOT0 OB_USER_NBOOT0 -#define OB_nBOOT0_RESET OB_NBOOT0_RESET -#define OB_nBOOT0_SET OB_NBOOT0_SET -#endif /* STM32U5 */ - -/** - * @} - */ - -/** @defgroup HAL_JPEG_Aliased_Macros HAL JPEG Aliased Macros maintained for legacy purpose - * @{ - */ - -#if defined(STM32H7) -#define __HAL_RCC_JPEG_CLK_ENABLE __HAL_RCC_JPGDECEN_CLK_ENABLE -#define __HAL_RCC_JPEG_CLK_DISABLE __HAL_RCC_JPGDECEN_CLK_DISABLE -#define __HAL_RCC_JPEG_FORCE_RESET __HAL_RCC_JPGDECRST_FORCE_RESET -#define __HAL_RCC_JPEG_RELEASE_RESET __HAL_RCC_JPGDECRST_RELEASE_RESET -#define __HAL_RCC_JPEG_CLK_SLEEP_ENABLE __HAL_RCC_JPGDEC_CLK_SLEEP_ENABLE -#define __HAL_RCC_JPEG_CLK_SLEEP_DISABLE __HAL_RCC_JPGDEC_CLK_SLEEP_DISABLE -#endif /* STM32H7 */ - -/** - * @} - */ - -/** @defgroup HAL_SYSCFG_Aliased_Defines HAL SYSCFG Aliased Defines maintained for legacy purpose - * @{ - */ - -#define HAL_SYSCFG_FASTMODEPLUS_I2C_PA9 I2C_FASTMODEPLUS_PA9 -#define HAL_SYSCFG_FASTMODEPLUS_I2C_PA10 I2C_FASTMODEPLUS_PA10 -#define HAL_SYSCFG_FASTMODEPLUS_I2C_PB6 I2C_FASTMODEPLUS_PB6 -#define HAL_SYSCFG_FASTMODEPLUS_I2C_PB7 I2C_FASTMODEPLUS_PB7 -#define HAL_SYSCFG_FASTMODEPLUS_I2C_PB8 I2C_FASTMODEPLUS_PB8 -#define HAL_SYSCFG_FASTMODEPLUS_I2C_PB9 I2C_FASTMODEPLUS_PB9 -#define HAL_SYSCFG_FASTMODEPLUS_I2C1 I2C_FASTMODEPLUS_I2C1 -#define HAL_SYSCFG_FASTMODEPLUS_I2C2 I2C_FASTMODEPLUS_I2C2 -#define HAL_SYSCFG_FASTMODEPLUS_I2C3 I2C_FASTMODEPLUS_I2C3 -#if defined(STM32G4) - -#define HAL_SYSCFG_EnableIOAnalogSwitchBooster HAL_SYSCFG_EnableIOSwitchBooster -#define HAL_SYSCFG_DisableIOAnalogSwitchBooster HAL_SYSCFG_DisableIOSwitchBooster -#define HAL_SYSCFG_EnableIOAnalogSwitchVDD HAL_SYSCFG_EnableIOSwitchVDD -#define HAL_SYSCFG_DisableIOAnalogSwitchVDD HAL_SYSCFG_DisableIOSwitchVDD -#endif /* STM32G4 */ - -/** - * @} - */ - - -/** @defgroup LL_FMC_Aliased_Defines LL FMC Aliased Defines maintained for compatibility purpose - * @{ - */ -#if defined(STM32L4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) -#define FMC_NAND_PCC_WAIT_FEATURE_DISABLE FMC_NAND_WAIT_FEATURE_DISABLE -#define FMC_NAND_PCC_WAIT_FEATURE_ENABLE FMC_NAND_WAIT_FEATURE_ENABLE -#define FMC_NAND_PCC_MEM_BUS_WIDTH_8 FMC_NAND_MEM_BUS_WIDTH_8 -#define FMC_NAND_PCC_MEM_BUS_WIDTH_16 FMC_NAND_MEM_BUS_WIDTH_16 -#elif defined(STM32F1) || defined(STM32F2) || defined(STM32F3) || defined(STM32F4) -#define FMC_NAND_WAIT_FEATURE_DISABLE FMC_NAND_PCC_WAIT_FEATURE_DISABLE -#define FMC_NAND_WAIT_FEATURE_ENABLE FMC_NAND_PCC_WAIT_FEATURE_ENABLE -#define FMC_NAND_MEM_BUS_WIDTH_8 FMC_NAND_PCC_MEM_BUS_WIDTH_8 -#define FMC_NAND_MEM_BUS_WIDTH_16 FMC_NAND_PCC_MEM_BUS_WIDTH_16 -#endif -/** - * @} - */ - -/** @defgroup LL_FSMC_Aliased_Defines LL FSMC Aliased Defines maintained for legacy purpose - * @{ - */ - -#define FSMC_NORSRAM_TYPEDEF FSMC_NORSRAM_TypeDef -#define FSMC_NORSRAM_EXTENDED_TYPEDEF FSMC_NORSRAM_EXTENDED_TypeDef -/** - * @} - */ - -/** @defgroup HAL_GPIO_Aliased_Macros HAL GPIO Aliased Macros maintained for legacy purpose - * @{ - */ -#define GET_GPIO_SOURCE GPIO_GET_INDEX -#define GET_GPIO_INDEX GPIO_GET_INDEX - -#if defined(STM32F4) -#define GPIO_AF12_SDMMC GPIO_AF12_SDIO -#define GPIO_AF12_SDMMC1 GPIO_AF12_SDIO -#endif - -#if defined(STM32F7) -#define GPIO_AF12_SDIO GPIO_AF12_SDMMC1 -#define GPIO_AF12_SDMMC GPIO_AF12_SDMMC1 -#endif - -#if defined(STM32L4) -#define GPIO_AF12_SDIO GPIO_AF12_SDMMC1 -#define GPIO_AF12_SDMMC GPIO_AF12_SDMMC1 -#endif - -#if defined(STM32H7) -#define GPIO_AF7_SDIO1 GPIO_AF7_SDMMC1 -#define GPIO_AF8_SDIO1 GPIO_AF8_SDMMC1 -#define GPIO_AF12_SDIO1 GPIO_AF12_SDMMC1 -#define GPIO_AF9_SDIO2 GPIO_AF9_SDMMC2 -#define GPIO_AF10_SDIO2 GPIO_AF10_SDMMC2 -#define GPIO_AF11_SDIO2 GPIO_AF11_SDMMC2 - -#if defined (STM32H743xx) || defined (STM32H753xx) || defined (STM32H750xx) || defined (STM32H742xx) || \ - defined (STM32H745xx) || defined (STM32H755xx) || defined (STM32H747xx) || defined (STM32H757xx) -#define GPIO_AF10_OTG2_HS GPIO_AF10_OTG2_FS -#define GPIO_AF10_OTG1_FS GPIO_AF10_OTG1_HS -#define GPIO_AF12_OTG2_FS GPIO_AF12_OTG1_FS -#endif /*STM32H743xx || STM32H753xx || STM32H750xx || STM32H742xx || STM32H745xx || STM32H755xx || STM32H747xx || STM32H757xx */ -#endif /* STM32H7 */ - -#define GPIO_AF0_LPTIM GPIO_AF0_LPTIM1 -#define GPIO_AF1_LPTIM GPIO_AF1_LPTIM1 -#define GPIO_AF2_LPTIM GPIO_AF2_LPTIM1 - -#if defined(STM32L0) || defined(STM32L4) || defined(STM32F4) || defined(STM32F2) || defined(STM32F7) || defined(STM32G4) || defined(STM32H7) || defined(STM32WB) || defined(STM32U5) -#define GPIO_SPEED_LOW GPIO_SPEED_FREQ_LOW -#define GPIO_SPEED_MEDIUM GPIO_SPEED_FREQ_MEDIUM -#define GPIO_SPEED_FAST GPIO_SPEED_FREQ_HIGH -#define GPIO_SPEED_HIGH GPIO_SPEED_FREQ_VERY_HIGH -#endif /* STM32L0 || STM32L4 || STM32F4 || STM32F2 || STM32F7 || STM32G4 || STM32H7 || STM32WB || STM32U5*/ - -#if defined(STM32L1) -#define GPIO_SPEED_VERY_LOW GPIO_SPEED_FREQ_LOW -#define GPIO_SPEED_LOW GPIO_SPEED_FREQ_MEDIUM -#define GPIO_SPEED_MEDIUM GPIO_SPEED_FREQ_HIGH -#define GPIO_SPEED_HIGH GPIO_SPEED_FREQ_VERY_HIGH -#endif /* STM32L1 */ - -#if defined(STM32F0) || defined(STM32F3) || defined(STM32F1) -#define GPIO_SPEED_LOW GPIO_SPEED_FREQ_LOW -#define GPIO_SPEED_MEDIUM GPIO_SPEED_FREQ_MEDIUM -#define GPIO_SPEED_HIGH GPIO_SPEED_FREQ_HIGH -#endif /* STM32F0 || STM32F3 || STM32F1 */ - -#define GPIO_AF6_DFSDM GPIO_AF6_DFSDM1 -/** - * @} - */ - -/** @defgroup HAL_HRTIM_Aliased_Macros HAL HRTIM Aliased Macros maintained for legacy purpose - * @{ - */ -#define HRTIM_TIMDELAYEDPROTECTION_DISABLED HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_DISABLED -#define HRTIM_TIMDELAYEDPROTECTION_DELAYEDOUT1_EEV68 HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_DELAYEDOUT1_EEV6 -#define HRTIM_TIMDELAYEDPROTECTION_DELAYEDOUT2_EEV68 HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_DELAYEDOUT2_EEV6 -#define HRTIM_TIMDELAYEDPROTECTION_DELAYEDBOTH_EEV68 HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_DELAYEDBOTH_EEV6 -#define HRTIM_TIMDELAYEDPROTECTION_BALANCED_EEV68 HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_BALANCED_EEV6 -#define HRTIM_TIMDELAYEDPROTECTION_DELAYEDOUT1_DEEV79 HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_DELAYEDOUT1_DEEV7 -#define HRTIM_TIMDELAYEDPROTECTION_DELAYEDOUT2_DEEV79 HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_DELAYEDOUT2_DEEV7 -#define HRTIM_TIMDELAYEDPROTECTION_DELAYEDBOTH_EEV79 HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_DELAYEDBOTH_EEV7 -#define HRTIM_TIMDELAYEDPROTECTION_BALANCED_EEV79 HRTIM_TIMER_A_B_C_DELAYEDPROTECTION_BALANCED_EEV7 - -#define __HAL_HRTIM_SetCounter __HAL_HRTIM_SETCOUNTER -#define __HAL_HRTIM_GetCounter __HAL_HRTIM_GETCOUNTER -#define __HAL_HRTIM_SetPeriod __HAL_HRTIM_SETPERIOD -#define __HAL_HRTIM_GetPeriod __HAL_HRTIM_GETPERIOD -#define __HAL_HRTIM_SetClockPrescaler __HAL_HRTIM_SETCLOCKPRESCALER -#define __HAL_HRTIM_GetClockPrescaler __HAL_HRTIM_GETCLOCKPRESCALER -#define __HAL_HRTIM_SetCompare __HAL_HRTIM_SETCOMPARE -#define __HAL_HRTIM_GetCompare __HAL_HRTIM_GETCOMPARE - -#if defined(STM32G4) -#define HAL_HRTIM_ExternalEventCounterConfig HAL_HRTIM_ExtEventCounterConfig -#define HAL_HRTIM_ExternalEventCounterEnable HAL_HRTIM_ExtEventCounterEnable -#define HAL_HRTIM_ExternalEventCounterDisable HAL_HRTIM_ExtEventCounterDisable -#define HAL_HRTIM_ExternalEventCounterReset HAL_HRTIM_ExtEventCounterReset -#define HRTIM_TIMEEVENT_A HRTIM_EVENTCOUNTER_A -#define HRTIM_TIMEEVENT_B HRTIM_EVENTCOUNTER_B -#define HRTIM_TIMEEVENTRESETMODE_UNCONDITIONAL HRTIM_EVENTCOUNTER_RSTMODE_UNCONDITIONAL -#define HRTIM_TIMEEVENTRESETMODE_CONDITIONAL HRTIM_EVENTCOUNTER_RSTMODE_CONDITIONAL -#endif /* STM32G4 */ - -#if defined(STM32H7) -#define HRTIM_OUTPUTSET_TIMAEV1_TIMBCMP1 HRTIM_OUTPUTSET_TIMEV_1 -#define HRTIM_OUTPUTSET_TIMAEV2_TIMBCMP2 HRTIM_OUTPUTSET_TIMEV_2 -#define HRTIM_OUTPUTSET_TIMAEV3_TIMCCMP2 HRTIM_OUTPUTSET_TIMEV_3 -#define HRTIM_OUTPUTSET_TIMAEV4_TIMCCMP3 HRTIM_OUTPUTSET_TIMEV_4 -#define HRTIM_OUTPUTSET_TIMAEV5_TIMDCMP1 HRTIM_OUTPUTSET_TIMEV_5 -#define HRTIM_OUTPUTSET_TIMAEV6_TIMDCMP2 HRTIM_OUTPUTSET_TIMEV_6 -#define HRTIM_OUTPUTSET_TIMAEV7_TIMECMP3 HRTIM_OUTPUTSET_TIMEV_7 -#define HRTIM_OUTPUTSET_TIMAEV8_TIMECMP4 HRTIM_OUTPUTSET_TIMEV_8 -#define HRTIM_OUTPUTSET_TIMAEV9_TIMFCMP4 HRTIM_OUTPUTSET_TIMEV_9 -#define HRTIM_OUTPUTSET_TIMBEV1_TIMACMP1 HRTIM_OUTPUTSET_TIMEV_1 -#define HRTIM_OUTPUTSET_TIMBEV2_TIMACMP2 HRTIM_OUTPUTSET_TIMEV_2 -#define HRTIM_OUTPUTSET_TIMBEV3_TIMCCMP3 HRTIM_OUTPUTSET_TIMEV_3 -#define HRTIM_OUTPUTSET_TIMBEV4_TIMCCMP4 HRTIM_OUTPUTSET_TIMEV_4 -#define HRTIM_OUTPUTSET_TIMBEV5_TIMDCMP3 HRTIM_OUTPUTSET_TIMEV_5 -#define HRTIM_OUTPUTSET_TIMBEV6_TIMDCMP4 HRTIM_OUTPUTSET_TIMEV_6 -#define HRTIM_OUTPUTSET_TIMBEV7_TIMECMP1 HRTIM_OUTPUTSET_TIMEV_7 -#define HRTIM_OUTPUTSET_TIMBEV8_TIMECMP2 HRTIM_OUTPUTSET_TIMEV_8 -#define HRTIM_OUTPUTSET_TIMBEV9_TIMFCMP3 HRTIM_OUTPUTSET_TIMEV_9 -#define HRTIM_OUTPUTSET_TIMCEV1_TIMACMP1 HRTIM_OUTPUTSET_TIMEV_1 -#define HRTIM_OUTPUTSET_TIMCEV2_TIMACMP2 HRTIM_OUTPUTSET_TIMEV_2 -#define HRTIM_OUTPUTSET_TIMCEV3_TIMBCMP2 HRTIM_OUTPUTSET_TIMEV_3 -#define HRTIM_OUTPUTSET_TIMCEV4_TIMBCMP3 HRTIM_OUTPUTSET_TIMEV_4 -#define HRTIM_OUTPUTSET_TIMCEV5_TIMDCMP2 HRTIM_OUTPUTSET_TIMEV_5 -#define HRTIM_OUTPUTSET_TIMCEV6_TIMDCMP4 HRTIM_OUTPUTSET_TIMEV_6 -#define HRTIM_OUTPUTSET_TIMCEV7_TIMECMP3 HRTIM_OUTPUTSET_TIMEV_7 -#define HRTIM_OUTPUTSET_TIMCEV8_TIMECMP4 HRTIM_OUTPUTSET_TIMEV_8 -#define HRTIM_OUTPUTSET_TIMCEV9_TIMFCMP2 HRTIM_OUTPUTSET_TIMEV_9 -#define HRTIM_OUTPUTSET_TIMDEV1_TIMACMP1 HRTIM_OUTPUTSET_TIMEV_1 -#define HRTIM_OUTPUTSET_TIMDEV2_TIMACMP4 HRTIM_OUTPUTSET_TIMEV_2 -#define HRTIM_OUTPUTSET_TIMDEV3_TIMBCMP2 HRTIM_OUTPUTSET_TIMEV_3 -#define HRTIM_OUTPUTSET_TIMDEV4_TIMBCMP4 HRTIM_OUTPUTSET_TIMEV_4 -#define HRTIM_OUTPUTSET_TIMDEV5_TIMCCMP4 HRTIM_OUTPUTSET_TIMEV_5 -#define HRTIM_OUTPUTSET_TIMDEV6_TIMECMP1 HRTIM_OUTPUTSET_TIMEV_6 -#define HRTIM_OUTPUTSET_TIMDEV7_TIMECMP4 HRTIM_OUTPUTSET_TIMEV_7 -#define HRTIM_OUTPUTSET_TIMDEV8_TIMFCMP1 HRTIM_OUTPUTSET_TIMEV_8 -#define HRTIM_OUTPUTSET_TIMDEV9_TIMFCMP3 HRTIM_OUTPUTSET_TIMEV_9 -#define HRTIM_OUTPUTSET_TIMEEV1_TIMACMP4 HRTIM_OUTPUTSET_TIMEV_1 -#define HRTIM_OUTPUTSET_TIMEEV2_TIMBCMP3 HRTIM_OUTPUTSET_TIMEV_2 -#define HRTIM_OUTPUTSET_TIMEEV3_TIMBCMP4 HRTIM_OUTPUTSET_TIMEV_3 -#define HRTIM_OUTPUTSET_TIMEEV4_TIMCCMP1 HRTIM_OUTPUTSET_TIMEV_4 -#define HRTIM_OUTPUTSET_TIMEEV5_TIMDCMP2 HRTIM_OUTPUTSET_TIMEV_5 -#define HRTIM_OUTPUTSET_TIMEEV6_TIMDCMP1 HRTIM_OUTPUTSET_TIMEV_6 -#define HRTIM_OUTPUTSET_TIMEEV7_TIMDCMP2 HRTIM_OUTPUTSET_TIMEV_7 -#define HRTIM_OUTPUTSET_TIMEEV8_TIMFCMP3 HRTIM_OUTPUTSET_TIMEV_8 -#define HRTIM_OUTPUTSET_TIMEEV9_TIMFCMP4 HRTIM_OUTPUTSET_TIMEV_9 -#define HRTIM_OUTPUTSET_TIMFEV1_TIMACMP3 HRTIM_OUTPUTSET_TIMEV_1 -#define HRTIM_OUTPUTSET_TIMFEV2_TIMBCMP1 HRTIM_OUTPUTSET_TIMEV_2 -#define HRTIM_OUTPUTSET_TIMFEV3_TIMBCMP4 HRTIM_OUTPUTSET_TIMEV_3 -#define HRTIM_OUTPUTSET_TIMFEV4_TIMCCMP1 HRTIM_OUTPUTSET_TIMEV_4 -#define HRTIM_OUTPUTSET_TIMFEV5_TIMCCMP4 HRTIM_OUTPUTSET_TIMEV_5 -#define HRTIM_OUTPUTSET_TIMFEV6_TIMDCMP3 HRTIM_OUTPUTSET_TIMEV_6 -#define HRTIM_OUTPUTSET_TIMFEV7_TIMDCMP4 HRTIM_OUTPUTSET_TIMEV_7 -#define HRTIM_OUTPUTSET_TIMFEV8_TIMECMP2 HRTIM_OUTPUTSET_TIMEV_8 -#define HRTIM_OUTPUTSET_TIMFEV9_TIMECMP3 HRTIM_OUTPUTSET_TIMEV_9 - -#define HRTIM_OUTPUTRESET_TIMAEV1_TIMBCMP1 HRTIM_OUTPUTSET_TIMEV_1 -#define HRTIM_OUTPUTRESET_TIMAEV2_TIMBCMP2 HRTIM_OUTPUTSET_TIMEV_2 -#define HRTIM_OUTPUTRESET_TIMAEV3_TIMCCMP2 HRTIM_OUTPUTSET_TIMEV_3 -#define HRTIM_OUTPUTRESET_TIMAEV4_TIMCCMP3 HRTIM_OUTPUTSET_TIMEV_4 -#define HRTIM_OUTPUTRESET_TIMAEV5_TIMDCMP1 HRTIM_OUTPUTSET_TIMEV_5 -#define HRTIM_OUTPUTRESET_TIMAEV6_TIMDCMP2 HRTIM_OUTPUTSET_TIMEV_6 -#define HRTIM_OUTPUTRESET_TIMAEV7_TIMECMP3 HRTIM_OUTPUTSET_TIMEV_7 -#define HRTIM_OUTPUTRESET_TIMAEV8_TIMECMP4 HRTIM_OUTPUTSET_TIMEV_8 -#define HRTIM_OUTPUTRESET_TIMAEV9_TIMFCMP4 HRTIM_OUTPUTSET_TIMEV_9 -#define HRTIM_OUTPUTRESET_TIMBEV1_TIMACMP1 HRTIM_OUTPUTSET_TIMEV_1 -#define HRTIM_OUTPUTRESET_TIMBEV2_TIMACMP2 HRTIM_OUTPUTSET_TIMEV_2 -#define HRTIM_OUTPUTRESET_TIMBEV3_TIMCCMP3 HRTIM_OUTPUTSET_TIMEV_3 -#define HRTIM_OUTPUTRESET_TIMBEV4_TIMCCMP4 HRTIM_OUTPUTSET_TIMEV_4 -#define HRTIM_OUTPUTRESET_TIMBEV5_TIMDCMP3 HRTIM_OUTPUTSET_TIMEV_5 -#define HRTIM_OUTPUTRESET_TIMBEV6_TIMDCMP4 HRTIM_OUTPUTSET_TIMEV_6 -#define HRTIM_OUTPUTRESET_TIMBEV7_TIMECMP1 HRTIM_OUTPUTSET_TIMEV_7 -#define HRTIM_OUTPUTRESET_TIMBEV8_TIMECMP2 HRTIM_OUTPUTSET_TIMEV_8 -#define HRTIM_OUTPUTRESET_TIMBEV9_TIMFCMP3 HRTIM_OUTPUTSET_TIMEV_9 -#define HRTIM_OUTPUTRESET_TIMCEV1_TIMACMP1 HRTIM_OUTPUTSET_TIMEV_1 -#define HRTIM_OUTPUTRESET_TIMCEV2_TIMACMP2 HRTIM_OUTPUTSET_TIMEV_2 -#define HRTIM_OUTPUTRESET_TIMCEV3_TIMBCMP2 HRTIM_OUTPUTSET_TIMEV_3 -#define HRTIM_OUTPUTRESET_TIMCEV4_TIMBCMP3 HRTIM_OUTPUTSET_TIMEV_4 -#define HRTIM_OUTPUTRESET_TIMCEV5_TIMDCMP2 HRTIM_OUTPUTSET_TIMEV_5 -#define HRTIM_OUTPUTRESET_TIMCEV6_TIMDCMP4 HRTIM_OUTPUTSET_TIMEV_6 -#define HRTIM_OUTPUTRESET_TIMCEV7_TIMECMP3 HRTIM_OUTPUTSET_TIMEV_7 -#define HRTIM_OUTPUTRESET_TIMCEV8_TIMECMP4 HRTIM_OUTPUTSET_TIMEV_8 -#define HRTIM_OUTPUTRESET_TIMCEV9_TIMFCMP2 HRTIM_OUTPUTSET_TIMEV_9 -#define HRTIM_OUTPUTRESET_TIMDEV1_TIMACMP1 HRTIM_OUTPUTSET_TIMEV_1 -#define HRTIM_OUTPUTRESET_TIMDEV2_TIMACMP4 HRTIM_OUTPUTSET_TIMEV_2 -#define HRTIM_OUTPUTRESET_TIMDEV3_TIMBCMP2 HRTIM_OUTPUTSET_TIMEV_3 -#define HRTIM_OUTPUTRESET_TIMDEV4_TIMBCMP4 HRTIM_OUTPUTSET_TIMEV_4 -#define HRTIM_OUTPUTRESET_TIMDEV5_TIMCCMP4 HRTIM_OUTPUTSET_TIMEV_5 -#define HRTIM_OUTPUTRESET_TIMDEV6_TIMECMP1 HRTIM_OUTPUTSET_TIMEV_6 -#define HRTIM_OUTPUTRESET_TIMDEV7_TIMECMP4 HRTIM_OUTPUTSET_TIMEV_7 -#define HRTIM_OUTPUTRESET_TIMDEV8_TIMFCMP1 HRTIM_OUTPUTSET_TIMEV_8 -#define HRTIM_OUTPUTRESET_TIMDEV9_TIMFCMP3 HRTIM_OUTPUTSET_TIMEV_9 -#define HRTIM_OUTPUTRESET_TIMEEV1_TIMACMP4 HRTIM_OUTPUTSET_TIMEV_1 -#define HRTIM_OUTPUTRESET_TIMEEV2_TIMBCMP3 HRTIM_OUTPUTSET_TIMEV_2 -#define HRTIM_OUTPUTRESET_TIMEEV3_TIMBCMP4 HRTIM_OUTPUTSET_TIMEV_3 -#define HRTIM_OUTPUTRESET_TIMEEV4_TIMCCMP1 HRTIM_OUTPUTSET_TIMEV_4 -#define HRTIM_OUTPUTRESET_TIMEEV5_TIMDCMP2 HRTIM_OUTPUTSET_TIMEV_5 -#define HRTIM_OUTPUTRESET_TIMEEV6_TIMDCMP1 HRTIM_OUTPUTSET_TIMEV_6 -#define HRTIM_OUTPUTRESET_TIMEEV7_TIMDCMP2 HRTIM_OUTPUTSET_TIMEV_7 -#define HRTIM_OUTPUTRESET_TIMEEV8_TIMFCMP3 HRTIM_OUTPUTSET_TIMEV_8 -#define HRTIM_OUTPUTRESET_TIMEEV9_TIMFCMP4 HRTIM_OUTPUTSET_TIMEV_9 -#define HRTIM_OUTPUTRESET_TIMFEV1_TIMACMP3 HRTIM_OUTPUTSET_TIMEV_1 -#define HRTIM_OUTPUTRESET_TIMFEV2_TIMBCMP1 HRTIM_OUTPUTSET_TIMEV_2 -#define HRTIM_OUTPUTRESET_TIMFEV3_TIMBCMP4 HRTIM_OUTPUTSET_TIMEV_3 -#define HRTIM_OUTPUTRESET_TIMFEV4_TIMCCMP1 HRTIM_OUTPUTSET_TIMEV_4 -#define HRTIM_OUTPUTRESET_TIMFEV5_TIMCCMP4 HRTIM_OUTPUTSET_TIMEV_5 -#define HRTIM_OUTPUTRESET_TIMFEV6_TIMDCMP3 HRTIM_OUTPUTSET_TIMEV_6 -#define HRTIM_OUTPUTRESET_TIMFEV7_TIMDCMP4 HRTIM_OUTPUTSET_TIMEV_7 -#define HRTIM_OUTPUTRESET_TIMFEV8_TIMECMP2 HRTIM_OUTPUTSET_TIMEV_8 -#define HRTIM_OUTPUTRESET_TIMFEV9_TIMECMP3 HRTIM_OUTPUTSET_TIMEV_9 -#endif /* STM32H7 */ - -#if defined(STM32F3) -/** @brief Constants defining available sources associated to external events. - */ -#define HRTIM_EVENTSRC_1 (0x00000000U) -#define HRTIM_EVENTSRC_2 (HRTIM_EECR1_EE1SRC_0) -#define HRTIM_EVENTSRC_3 (HRTIM_EECR1_EE1SRC_1) -#define HRTIM_EVENTSRC_4 (HRTIM_EECR1_EE1SRC_1 | HRTIM_EECR1_EE1SRC_0) - -/** @brief Constants defining the DLL calibration periods (in micro seconds) - */ -#define HRTIM_CALIBRATIONRATE_7300 0x00000000U -#define HRTIM_CALIBRATIONRATE_910 (HRTIM_DLLCR_CALRTE_0) -#define HRTIM_CALIBRATIONRATE_114 (HRTIM_DLLCR_CALRTE_1) -#define HRTIM_CALIBRATIONRATE_14 (HRTIM_DLLCR_CALRTE_1 | HRTIM_DLLCR_CALRTE_0) - -#endif /* STM32F3 */ -/** - * @} - */ - -/** @defgroup HAL_I2C_Aliased_Defines HAL I2C Aliased Defines maintained for legacy purpose - * @{ - */ -#define I2C_DUALADDRESS_DISABLED I2C_DUALADDRESS_DISABLE -#define I2C_DUALADDRESS_ENABLED I2C_DUALADDRESS_ENABLE -#define I2C_GENERALCALL_DISABLED I2C_GENERALCALL_DISABLE -#define I2C_GENERALCALL_ENABLED I2C_GENERALCALL_ENABLE -#define I2C_NOSTRETCH_DISABLED I2C_NOSTRETCH_DISABLE -#define I2C_NOSTRETCH_ENABLED I2C_NOSTRETCH_ENABLE -#define I2C_ANALOGFILTER_ENABLED I2C_ANALOGFILTER_ENABLE -#define I2C_ANALOGFILTER_DISABLED I2C_ANALOGFILTER_DISABLE -#if defined(STM32F0) || defined(STM32F1) || defined(STM32F3) || defined(STM32G0) || defined(STM32L4) || defined(STM32L1) || defined(STM32F7) -#define HAL_I2C_STATE_MEM_BUSY_TX HAL_I2C_STATE_BUSY_TX -#define HAL_I2C_STATE_MEM_BUSY_RX HAL_I2C_STATE_BUSY_RX -#define HAL_I2C_STATE_MASTER_BUSY_TX HAL_I2C_STATE_BUSY_TX -#define HAL_I2C_STATE_MASTER_BUSY_RX HAL_I2C_STATE_BUSY_RX -#define HAL_I2C_STATE_SLAVE_BUSY_TX HAL_I2C_STATE_BUSY_TX -#define HAL_I2C_STATE_SLAVE_BUSY_RX HAL_I2C_STATE_BUSY_RX -#endif -/** - * @} - */ - -/** @defgroup HAL_IRDA_Aliased_Defines HAL IRDA Aliased Defines maintained for legacy purpose - * @{ - */ -#define IRDA_ONE_BIT_SAMPLE_DISABLED IRDA_ONE_BIT_SAMPLE_DISABLE -#define IRDA_ONE_BIT_SAMPLE_ENABLED IRDA_ONE_BIT_SAMPLE_ENABLE - -/** - * @} - */ - -/** @defgroup HAL_IWDG_Aliased_Defines HAL IWDG Aliased Defines maintained for legacy purpose - * @{ - */ -#define KR_KEY_RELOAD IWDG_KEY_RELOAD -#define KR_KEY_ENABLE IWDG_KEY_ENABLE -#define KR_KEY_EWA IWDG_KEY_WRITE_ACCESS_ENABLE -#define KR_KEY_DWA IWDG_KEY_WRITE_ACCESS_DISABLE -/** - * @} - */ - -/** @defgroup HAL_LPTIM_Aliased_Defines HAL LPTIM Aliased Defines maintained for legacy purpose - * @{ - */ - -#define LPTIM_CLOCKSAMPLETIME_DIRECTTRANSISTION LPTIM_CLOCKSAMPLETIME_DIRECTTRANSITION -#define LPTIM_CLOCKSAMPLETIME_2TRANSISTIONS LPTIM_CLOCKSAMPLETIME_2TRANSITIONS -#define LPTIM_CLOCKSAMPLETIME_4TRANSISTIONS LPTIM_CLOCKSAMPLETIME_4TRANSITIONS -#define LPTIM_CLOCKSAMPLETIME_8TRANSISTIONS LPTIM_CLOCKSAMPLETIME_8TRANSITIONS - -#define LPTIM_CLOCKPOLARITY_RISINGEDGE LPTIM_CLOCKPOLARITY_RISING -#define LPTIM_CLOCKPOLARITY_FALLINGEDGE LPTIM_CLOCKPOLARITY_FALLING -#define LPTIM_CLOCKPOLARITY_BOTHEDGES LPTIM_CLOCKPOLARITY_RISING_FALLING - -#define LPTIM_TRIGSAMPLETIME_DIRECTTRANSISTION LPTIM_TRIGSAMPLETIME_DIRECTTRANSITION -#define LPTIM_TRIGSAMPLETIME_2TRANSISTIONS LPTIM_TRIGSAMPLETIME_2TRANSITIONS -#define LPTIM_TRIGSAMPLETIME_4TRANSISTIONS LPTIM_TRIGSAMPLETIME_4TRANSITIONS -#define LPTIM_TRIGSAMPLETIME_8TRANSISTIONS LPTIM_TRIGSAMPLETIME_8TRANSITIONS - -/* The following 3 definition have also been present in a temporary version of lptim.h */ -/* They need to be renamed also to the right name, just in case */ -#define LPTIM_TRIGSAMPLETIME_2TRANSITION LPTIM_TRIGSAMPLETIME_2TRANSITIONS -#define LPTIM_TRIGSAMPLETIME_4TRANSITION LPTIM_TRIGSAMPLETIME_4TRANSITIONS -#define LPTIM_TRIGSAMPLETIME_8TRANSITION LPTIM_TRIGSAMPLETIME_8TRANSITIONS - -#if defined(STM32U5) -#define LPTIM_ISR_CC1 LPTIM_ISR_CC1IF -#define LPTIM_ISR_CC2 LPTIM_ISR_CC2IF -#endif /* STM32U5 */ -/** - * @} - */ - -/** @defgroup HAL_NAND_Aliased_Defines HAL NAND Aliased Defines maintained for legacy purpose - * @{ - */ -#define HAL_NAND_Read_Page HAL_NAND_Read_Page_8b -#define HAL_NAND_Write_Page HAL_NAND_Write_Page_8b -#define HAL_NAND_Read_SpareArea HAL_NAND_Read_SpareArea_8b -#define HAL_NAND_Write_SpareArea HAL_NAND_Write_SpareArea_8b - -#define NAND_AddressTypedef NAND_AddressTypeDef - -#define __ARRAY_ADDRESS ARRAY_ADDRESS -#define __ADDR_1st_CYCLE ADDR_1ST_CYCLE -#define __ADDR_2nd_CYCLE ADDR_2ND_CYCLE -#define __ADDR_3rd_CYCLE ADDR_3RD_CYCLE -#define __ADDR_4th_CYCLE ADDR_4TH_CYCLE -/** - * @} - */ - -/** @defgroup HAL_NOR_Aliased_Defines HAL NOR Aliased Defines maintained for legacy purpose - * @{ - */ -#define NOR_StatusTypedef HAL_NOR_StatusTypeDef -#define NOR_SUCCESS HAL_NOR_STATUS_SUCCESS -#define NOR_ONGOING HAL_NOR_STATUS_ONGOING -#define NOR_ERROR HAL_NOR_STATUS_ERROR -#define NOR_TIMEOUT HAL_NOR_STATUS_TIMEOUT - -#define __NOR_WRITE NOR_WRITE -#define __NOR_ADDR_SHIFT NOR_ADDR_SHIFT -/** - * @} - */ - -/** @defgroup HAL_OPAMP_Aliased_Defines HAL OPAMP Aliased Defines maintained for legacy purpose - * @{ - */ - -#define OPAMP_NONINVERTINGINPUT_VP0 OPAMP_NONINVERTINGINPUT_IO0 -#define OPAMP_NONINVERTINGINPUT_VP1 OPAMP_NONINVERTINGINPUT_IO1 -#define OPAMP_NONINVERTINGINPUT_VP2 OPAMP_NONINVERTINGINPUT_IO2 -#define OPAMP_NONINVERTINGINPUT_VP3 OPAMP_NONINVERTINGINPUT_IO3 - -#define OPAMP_SEC_NONINVERTINGINPUT_VP0 OPAMP_SEC_NONINVERTINGINPUT_IO0 -#define OPAMP_SEC_NONINVERTINGINPUT_VP1 OPAMP_SEC_NONINVERTINGINPUT_IO1 -#define OPAMP_SEC_NONINVERTINGINPUT_VP2 OPAMP_SEC_NONINVERTINGINPUT_IO2 -#define OPAMP_SEC_NONINVERTINGINPUT_VP3 OPAMP_SEC_NONINVERTINGINPUT_IO3 - -#define OPAMP_INVERTINGINPUT_VM0 OPAMP_INVERTINGINPUT_IO0 -#define OPAMP_INVERTINGINPUT_VM1 OPAMP_INVERTINGINPUT_IO1 - -#define IOPAMP_INVERTINGINPUT_VM0 OPAMP_INVERTINGINPUT_IO0 -#define IOPAMP_INVERTINGINPUT_VM1 OPAMP_INVERTINGINPUT_IO1 - -#define OPAMP_SEC_INVERTINGINPUT_VM0 OPAMP_SEC_INVERTINGINPUT_IO0 -#define OPAMP_SEC_INVERTINGINPUT_VM1 OPAMP_SEC_INVERTINGINPUT_IO1 - -#define OPAMP_INVERTINGINPUT_VINM OPAMP_SEC_INVERTINGINPUT_IO1 - -#define OPAMP_PGACONNECT_NO OPAMP_PGA_CONNECT_INVERTINGINPUT_NO -#define OPAMP_PGACONNECT_VM0 OPAMP_PGA_CONNECT_INVERTINGINPUT_IO0 -#define OPAMP_PGACONNECT_VM1 OPAMP_PGA_CONNECT_INVERTINGINPUT_IO1 - -#if defined(STM32L1) || defined(STM32L4) || defined(STM32L5) || defined(STM32H7) || defined(STM32G4) -#define HAL_OPAMP_MSP_INIT_CB_ID HAL_OPAMP_MSPINIT_CB_ID -#define HAL_OPAMP_MSP_DEINIT_CB_ID HAL_OPAMP_MSPDEINIT_CB_ID -#endif - -#if defined(STM32L4) || defined(STM32L5) -#define OPAMP_POWERMODE_NORMAL OPAMP_POWERMODE_NORMALPOWER -#elif defined(STM32G4) -#define OPAMP_POWERMODE_NORMAL OPAMP_POWERMODE_NORMALSPEED -#endif - -/** - * @} - */ - -/** @defgroup HAL_I2S_Aliased_Defines HAL I2S Aliased Defines maintained for legacy purpose - * @{ - */ -#define I2S_STANDARD_PHILLIPS I2S_STANDARD_PHILIPS - -#if defined(STM32H7) -#define I2S_IT_TXE I2S_IT_TXP -#define I2S_IT_RXNE I2S_IT_RXP - -#define I2S_FLAG_TXE I2S_FLAG_TXP -#define I2S_FLAG_RXNE I2S_FLAG_RXP -#endif - -#if defined(STM32F7) -#define I2S_CLOCK_SYSCLK I2S_CLOCK_PLL -#endif -/** - * @} - */ - -/** @defgroup HAL_PCCARD_Aliased_Defines HAL PCCARD Aliased Defines maintained for legacy purpose - * @{ - */ - -/* Compact Flash-ATA registers description */ -#define CF_DATA ATA_DATA -#define CF_SECTOR_COUNT ATA_SECTOR_COUNT -#define CF_SECTOR_NUMBER ATA_SECTOR_NUMBER -#define CF_CYLINDER_LOW ATA_CYLINDER_LOW -#define CF_CYLINDER_HIGH ATA_CYLINDER_HIGH -#define CF_CARD_HEAD ATA_CARD_HEAD -#define CF_STATUS_CMD ATA_STATUS_CMD -#define CF_STATUS_CMD_ALTERNATE ATA_STATUS_CMD_ALTERNATE -#define CF_COMMON_DATA_AREA ATA_COMMON_DATA_AREA - -/* Compact Flash-ATA commands */ -#define CF_READ_SECTOR_CMD ATA_READ_SECTOR_CMD -#define CF_WRITE_SECTOR_CMD ATA_WRITE_SECTOR_CMD -#define CF_ERASE_SECTOR_CMD ATA_ERASE_SECTOR_CMD -#define CF_IDENTIFY_CMD ATA_IDENTIFY_CMD - -#define PCCARD_StatusTypedef HAL_PCCARD_StatusTypeDef -#define PCCARD_SUCCESS HAL_PCCARD_STATUS_SUCCESS -#define PCCARD_ONGOING HAL_PCCARD_STATUS_ONGOING -#define PCCARD_ERROR HAL_PCCARD_STATUS_ERROR -#define PCCARD_TIMEOUT HAL_PCCARD_STATUS_TIMEOUT -/** - * @} - */ - -/** @defgroup HAL_RTC_Aliased_Defines HAL RTC Aliased Defines maintained for legacy purpose - * @{ - */ - -#define FORMAT_BIN RTC_FORMAT_BIN -#define FORMAT_BCD RTC_FORMAT_BCD - -#define RTC_ALARMSUBSECONDMASK_None RTC_ALARMSUBSECONDMASK_NONE -#define RTC_TAMPERERASEBACKUP_DISABLED RTC_TAMPER_ERASE_BACKUP_DISABLE -#define RTC_TAMPERMASK_FLAG_DISABLED RTC_TAMPERMASK_FLAG_DISABLE -#define RTC_TAMPERMASK_FLAG_ENABLED RTC_TAMPERMASK_FLAG_ENABLE - -#define RTC_MASKTAMPERFLAG_DISABLED RTC_TAMPERMASK_FLAG_DISABLE -#define RTC_MASKTAMPERFLAG_ENABLED RTC_TAMPERMASK_FLAG_ENABLE -#define RTC_TAMPERERASEBACKUP_ENABLED RTC_TAMPER_ERASE_BACKUP_ENABLE -#define RTC_TAMPER1_2_INTERRUPT RTC_ALL_TAMPER_INTERRUPT -#define RTC_TAMPER1_2_3_INTERRUPT RTC_ALL_TAMPER_INTERRUPT - -#define RTC_TIMESTAMPPIN_PC13 RTC_TIMESTAMPPIN_DEFAULT -#define RTC_TIMESTAMPPIN_PA0 RTC_TIMESTAMPPIN_POS1 -#define RTC_TIMESTAMPPIN_PI8 RTC_TIMESTAMPPIN_POS1 -#define RTC_TIMESTAMPPIN_PC1 RTC_TIMESTAMPPIN_POS2 - -#define RTC_OUTPUT_REMAP_PC13 RTC_OUTPUT_REMAP_NONE -#define RTC_OUTPUT_REMAP_PB14 RTC_OUTPUT_REMAP_POS1 -#define RTC_OUTPUT_REMAP_PB2 RTC_OUTPUT_REMAP_POS1 - -#define RTC_TAMPERPIN_PC13 RTC_TAMPERPIN_DEFAULT -#define RTC_TAMPERPIN_PA0 RTC_TAMPERPIN_POS1 -#define RTC_TAMPERPIN_PI8 RTC_TAMPERPIN_POS1 - -#if defined(STM32H7) -#define RTC_TAMPCR_TAMPXE RTC_TAMPER_X -#define RTC_TAMPCR_TAMPXIE RTC_TAMPER_X_INTERRUPT - -#define RTC_TAMPER1_INTERRUPT RTC_IT_TAMP1 -#define RTC_TAMPER2_INTERRUPT RTC_IT_TAMP2 -#define RTC_TAMPER3_INTERRUPT RTC_IT_TAMP3 -#define RTC_ALL_TAMPER_INTERRUPT RTC_IT_TAMPALL -#endif /* STM32H7 */ - -/** - * @} - */ - - -/** @defgroup HAL_SMARTCARD_Aliased_Defines HAL SMARTCARD Aliased Defines maintained for legacy purpose - * @{ - */ -#define SMARTCARD_NACK_ENABLED SMARTCARD_NACK_ENABLE -#define SMARTCARD_NACK_DISABLED SMARTCARD_NACK_DISABLE - -#define SMARTCARD_ONEBIT_SAMPLING_DISABLED SMARTCARD_ONE_BIT_SAMPLE_DISABLE -#define SMARTCARD_ONEBIT_SAMPLING_ENABLED SMARTCARD_ONE_BIT_SAMPLE_ENABLE -#define SMARTCARD_ONEBIT_SAMPLING_DISABLE SMARTCARD_ONE_BIT_SAMPLE_DISABLE -#define SMARTCARD_ONEBIT_SAMPLING_ENABLE SMARTCARD_ONE_BIT_SAMPLE_ENABLE - -#define SMARTCARD_TIMEOUT_DISABLED SMARTCARD_TIMEOUT_DISABLE -#define SMARTCARD_TIMEOUT_ENABLED SMARTCARD_TIMEOUT_ENABLE - -#define SMARTCARD_LASTBIT_DISABLED SMARTCARD_LASTBIT_DISABLE -#define SMARTCARD_LASTBIT_ENABLED SMARTCARD_LASTBIT_ENABLE -/** - * @} - */ - - -/** @defgroup HAL_SMBUS_Aliased_Defines HAL SMBUS Aliased Defines maintained for legacy purpose - * @{ - */ -#define SMBUS_DUALADDRESS_DISABLED SMBUS_DUALADDRESS_DISABLE -#define SMBUS_DUALADDRESS_ENABLED SMBUS_DUALADDRESS_ENABLE -#define SMBUS_GENERALCALL_DISABLED SMBUS_GENERALCALL_DISABLE -#define SMBUS_GENERALCALL_ENABLED SMBUS_GENERALCALL_ENABLE -#define SMBUS_NOSTRETCH_DISABLED SMBUS_NOSTRETCH_DISABLE -#define SMBUS_NOSTRETCH_ENABLED SMBUS_NOSTRETCH_ENABLE -#define SMBUS_ANALOGFILTER_ENABLED SMBUS_ANALOGFILTER_ENABLE -#define SMBUS_ANALOGFILTER_DISABLED SMBUS_ANALOGFILTER_DISABLE -#define SMBUS_PEC_DISABLED SMBUS_PEC_DISABLE -#define SMBUS_PEC_ENABLED SMBUS_PEC_ENABLE -#define HAL_SMBUS_STATE_SLAVE_LISTEN HAL_SMBUS_STATE_LISTEN -/** - * @} - */ - -/** @defgroup HAL_SPI_Aliased_Defines HAL SPI Aliased Defines maintained for legacy purpose - * @{ - */ -#define SPI_TIMODE_DISABLED SPI_TIMODE_DISABLE -#define SPI_TIMODE_ENABLED SPI_TIMODE_ENABLE - -#define SPI_CRCCALCULATION_DISABLED SPI_CRCCALCULATION_DISABLE -#define SPI_CRCCALCULATION_ENABLED SPI_CRCCALCULATION_ENABLE - -#define SPI_NSS_PULSE_DISABLED SPI_NSS_PULSE_DISABLE -#define SPI_NSS_PULSE_ENABLED SPI_NSS_PULSE_ENABLE - -#if defined(STM32H7) - -#define SPI_FLAG_TXE SPI_FLAG_TXP -#define SPI_FLAG_RXNE SPI_FLAG_RXP - -#define SPI_IT_TXE SPI_IT_TXP -#define SPI_IT_RXNE SPI_IT_RXP - -#define SPI_FRLVL_EMPTY SPI_RX_FIFO_0PACKET -#define SPI_FRLVL_QUARTER_FULL SPI_RX_FIFO_1PACKET -#define SPI_FRLVL_HALF_FULL SPI_RX_FIFO_2PACKET -#define SPI_FRLVL_FULL SPI_RX_FIFO_3PACKET - -#endif /* STM32H7 */ - -/** - * @} - */ - -/** @defgroup HAL_TIM_Aliased_Defines HAL TIM Aliased Defines maintained for legacy purpose - * @{ - */ -#define CCER_CCxE_MASK TIM_CCER_CCxE_MASK -#define CCER_CCxNE_MASK TIM_CCER_CCxNE_MASK - -#define TIM_DMABase_CR1 TIM_DMABASE_CR1 -#define TIM_DMABase_CR2 TIM_DMABASE_CR2 -#define TIM_DMABase_SMCR TIM_DMABASE_SMCR -#define TIM_DMABase_DIER TIM_DMABASE_DIER -#define TIM_DMABase_SR TIM_DMABASE_SR -#define TIM_DMABase_EGR TIM_DMABASE_EGR -#define TIM_DMABase_CCMR1 TIM_DMABASE_CCMR1 -#define TIM_DMABase_CCMR2 TIM_DMABASE_CCMR2 -#define TIM_DMABase_CCER TIM_DMABASE_CCER -#define TIM_DMABase_CNT TIM_DMABASE_CNT -#define TIM_DMABase_PSC TIM_DMABASE_PSC -#define TIM_DMABase_ARR TIM_DMABASE_ARR -#define TIM_DMABase_RCR TIM_DMABASE_RCR -#define TIM_DMABase_CCR1 TIM_DMABASE_CCR1 -#define TIM_DMABase_CCR2 TIM_DMABASE_CCR2 -#define TIM_DMABase_CCR3 TIM_DMABASE_CCR3 -#define TIM_DMABase_CCR4 TIM_DMABASE_CCR4 -#define TIM_DMABase_BDTR TIM_DMABASE_BDTR -#define TIM_DMABase_DCR TIM_DMABASE_DCR -#define TIM_DMABase_DMAR TIM_DMABASE_DMAR -#define TIM_DMABase_OR1 TIM_DMABASE_OR1 -#define TIM_DMABase_CCMR3 TIM_DMABASE_CCMR3 -#define TIM_DMABase_CCR5 TIM_DMABASE_CCR5 -#define TIM_DMABase_CCR6 TIM_DMABASE_CCR6 -#define TIM_DMABase_OR2 TIM_DMABASE_OR2 -#define TIM_DMABase_OR3 TIM_DMABASE_OR3 -#define TIM_DMABase_OR TIM_DMABASE_OR - -#define TIM_EventSource_Update TIM_EVENTSOURCE_UPDATE -#define TIM_EventSource_CC1 TIM_EVENTSOURCE_CC1 -#define TIM_EventSource_CC2 TIM_EVENTSOURCE_CC2 -#define TIM_EventSource_CC3 TIM_EVENTSOURCE_CC3 -#define TIM_EventSource_CC4 TIM_EVENTSOURCE_CC4 -#define TIM_EventSource_COM TIM_EVENTSOURCE_COM -#define TIM_EventSource_Trigger TIM_EVENTSOURCE_TRIGGER -#define TIM_EventSource_Break TIM_EVENTSOURCE_BREAK -#define TIM_EventSource_Break2 TIM_EVENTSOURCE_BREAK2 - -#define TIM_DMABurstLength_1Transfer TIM_DMABURSTLENGTH_1TRANSFER -#define TIM_DMABurstLength_2Transfers TIM_DMABURSTLENGTH_2TRANSFERS -#define TIM_DMABurstLength_3Transfers TIM_DMABURSTLENGTH_3TRANSFERS -#define TIM_DMABurstLength_4Transfers TIM_DMABURSTLENGTH_4TRANSFERS -#define TIM_DMABurstLength_5Transfers TIM_DMABURSTLENGTH_5TRANSFERS -#define TIM_DMABurstLength_6Transfers TIM_DMABURSTLENGTH_6TRANSFERS -#define TIM_DMABurstLength_7Transfers TIM_DMABURSTLENGTH_7TRANSFERS -#define TIM_DMABurstLength_8Transfers TIM_DMABURSTLENGTH_8TRANSFERS -#define TIM_DMABurstLength_9Transfers TIM_DMABURSTLENGTH_9TRANSFERS -#define TIM_DMABurstLength_10Transfers TIM_DMABURSTLENGTH_10TRANSFERS -#define TIM_DMABurstLength_11Transfers TIM_DMABURSTLENGTH_11TRANSFERS -#define TIM_DMABurstLength_12Transfers TIM_DMABURSTLENGTH_12TRANSFERS -#define TIM_DMABurstLength_13Transfers TIM_DMABURSTLENGTH_13TRANSFERS -#define TIM_DMABurstLength_14Transfers TIM_DMABURSTLENGTH_14TRANSFERS -#define TIM_DMABurstLength_15Transfers TIM_DMABURSTLENGTH_15TRANSFERS -#define TIM_DMABurstLength_16Transfers TIM_DMABURSTLENGTH_16TRANSFERS -#define TIM_DMABurstLength_17Transfers TIM_DMABURSTLENGTH_17TRANSFERS -#define TIM_DMABurstLength_18Transfers TIM_DMABURSTLENGTH_18TRANSFERS - -#if defined(STM32L0) -#define TIM22_TI1_GPIO1 TIM22_TI1_GPIO -#define TIM22_TI1_GPIO2 TIM22_TI1_GPIO -#endif - -#if defined(STM32F3) -#define IS_TIM_HALL_INTERFACE_INSTANCE IS_TIM_HALL_SENSOR_INTERFACE_INSTANCE -#endif - -#if defined(STM32H7) -#define TIM_TIM1_ETR_COMP1_OUT TIM_TIM1_ETR_COMP1 -#define TIM_TIM1_ETR_COMP2_OUT TIM_TIM1_ETR_COMP2 -#define TIM_TIM8_ETR_COMP1_OUT TIM_TIM8_ETR_COMP1 -#define TIM_TIM8_ETR_COMP2_OUT TIM_TIM8_ETR_COMP2 -#define TIM_TIM2_ETR_COMP1_OUT TIM_TIM2_ETR_COMP1 -#define TIM_TIM2_ETR_COMP2_OUT TIM_TIM2_ETR_COMP2 -#define TIM_TIM3_ETR_COMP1_OUT TIM_TIM3_ETR_COMP1 -#define TIM_TIM1_TI1_COMP1_OUT TIM_TIM1_TI1_COMP1 -#define TIM_TIM8_TI1_COMP2_OUT TIM_TIM8_TI1_COMP2 -#define TIM_TIM2_TI4_COMP1_OUT TIM_TIM2_TI4_COMP1 -#define TIM_TIM2_TI4_COMP2_OUT TIM_TIM2_TI4_COMP2 -#define TIM_TIM2_TI4_COMP1COMP2_OUT TIM_TIM2_TI4_COMP1_COMP2 -#define TIM_TIM3_TI1_COMP1_OUT TIM_TIM3_TI1_COMP1 -#define TIM_TIM3_TI1_COMP2_OUT TIM_TIM3_TI1_COMP2 -#define TIM_TIM3_TI1_COMP1COMP2_OUT TIM_TIM3_TI1_COMP1_COMP2 -#endif - -/** - * @} - */ - -/** @defgroup HAL_TSC_Aliased_Defines HAL TSC Aliased Defines maintained for legacy purpose - * @{ - */ -#define TSC_SYNC_POL_FALL TSC_SYNC_POLARITY_FALLING -#define TSC_SYNC_POL_RISE_HIGH TSC_SYNC_POLARITY_RISING -/** - * @} - */ - -/** @defgroup HAL_UART_Aliased_Defines HAL UART Aliased Defines maintained for legacy purpose - * @{ - */ -#define UART_ONEBIT_SAMPLING_DISABLED UART_ONE_BIT_SAMPLE_DISABLE -#define UART_ONEBIT_SAMPLING_ENABLED UART_ONE_BIT_SAMPLE_ENABLE -#define UART_ONE_BIT_SAMPLE_DISABLED UART_ONE_BIT_SAMPLE_DISABLE -#define UART_ONE_BIT_SAMPLE_ENABLED UART_ONE_BIT_SAMPLE_ENABLE - -#define __HAL_UART_ONEBIT_ENABLE __HAL_UART_ONE_BIT_SAMPLE_ENABLE -#define __HAL_UART_ONEBIT_DISABLE __HAL_UART_ONE_BIT_SAMPLE_DISABLE - -#define __DIV_SAMPLING16 UART_DIV_SAMPLING16 -#define __DIVMANT_SAMPLING16 UART_DIVMANT_SAMPLING16 -#define __DIVFRAQ_SAMPLING16 UART_DIVFRAQ_SAMPLING16 -#define __UART_BRR_SAMPLING16 UART_BRR_SAMPLING16 - -#define __DIV_SAMPLING8 UART_DIV_SAMPLING8 -#define __DIVMANT_SAMPLING8 UART_DIVMANT_SAMPLING8 -#define __DIVFRAQ_SAMPLING8 UART_DIVFRAQ_SAMPLING8 -#define __UART_BRR_SAMPLING8 UART_BRR_SAMPLING8 - -#define __DIV_LPUART UART_DIV_LPUART - -#define UART_WAKEUPMETHODE_IDLELINE UART_WAKEUPMETHOD_IDLELINE -#define UART_WAKEUPMETHODE_ADDRESSMARK UART_WAKEUPMETHOD_ADDRESSMARK - -/** - * @} - */ - - -/** @defgroup HAL_USART_Aliased_Defines HAL USART Aliased Defines maintained for legacy purpose - * @{ - */ - -#define USART_CLOCK_DISABLED USART_CLOCK_DISABLE -#define USART_CLOCK_ENABLED USART_CLOCK_ENABLE - -#define USARTNACK_ENABLED USART_NACK_ENABLE -#define USARTNACK_DISABLED USART_NACK_DISABLE -/** - * @} - */ - -/** @defgroup HAL_WWDG_Aliased_Defines HAL WWDG Aliased Defines maintained for legacy purpose - * @{ - */ -#define CFR_BASE WWDG_CFR_BASE - -/** - * @} - */ - -/** @defgroup HAL_CAN_Aliased_Defines HAL CAN Aliased Defines maintained for legacy purpose - * @{ - */ -#define CAN_FilterFIFO0 CAN_FILTER_FIFO0 -#define CAN_FilterFIFO1 CAN_FILTER_FIFO1 -#define CAN_IT_RQCP0 CAN_IT_TME -#define CAN_IT_RQCP1 CAN_IT_TME -#define CAN_IT_RQCP2 CAN_IT_TME -#define INAK_TIMEOUT CAN_TIMEOUT_VALUE -#define SLAK_TIMEOUT CAN_TIMEOUT_VALUE -#define CAN_TXSTATUS_FAILED ((uint8_t)0x00U) -#define CAN_TXSTATUS_OK ((uint8_t)0x01U) -#define CAN_TXSTATUS_PENDING ((uint8_t)0x02U) - -/** - * @} - */ - -/** @defgroup HAL_ETH_Aliased_Defines HAL ETH Aliased Defines maintained for legacy purpose - * @{ - */ - -#define VLAN_TAG ETH_VLAN_TAG -#define MIN_ETH_PAYLOAD ETH_MIN_ETH_PAYLOAD -#define MAX_ETH_PAYLOAD ETH_MAX_ETH_PAYLOAD -#define JUMBO_FRAME_PAYLOAD ETH_JUMBO_FRAME_PAYLOAD -#define MACMIIAR_CR_MASK ETH_MACMIIAR_CR_MASK -#define MACCR_CLEAR_MASK ETH_MACCR_CLEAR_MASK -#define MACFCR_CLEAR_MASK ETH_MACFCR_CLEAR_MASK -#define DMAOMR_CLEAR_MASK ETH_DMAOMR_CLEAR_MASK - -#define ETH_MMCCR 0x00000100U -#define ETH_MMCRIR 0x00000104U -#define ETH_MMCTIR 0x00000108U -#define ETH_MMCRIMR 0x0000010CU -#define ETH_MMCTIMR 0x00000110U -#define ETH_MMCTGFSCCR 0x0000014CU -#define ETH_MMCTGFMSCCR 0x00000150U -#define ETH_MMCTGFCR 0x00000168U -#define ETH_MMCRFCECR 0x00000194U -#define ETH_MMCRFAECR 0x00000198U -#define ETH_MMCRGUFCR 0x000001C4U - -#define ETH_MAC_TXFIFO_FULL 0x02000000U /* Tx FIFO full */ -#define ETH_MAC_TXFIFONOT_EMPTY 0x01000000U /* Tx FIFO not empty */ -#define ETH_MAC_TXFIFO_WRITE_ACTIVE 0x00400000U /* Tx FIFO write active */ -#define ETH_MAC_TXFIFO_IDLE 0x00000000U /* Tx FIFO read status: Idle */ -#define ETH_MAC_TXFIFO_READ 0x00100000U /* Tx FIFO read status: Read (transferring data to the MAC transmitter) */ -#define ETH_MAC_TXFIFO_WAITING 0x00200000U /* Tx FIFO read status: Waiting for TxStatus from MAC transmitter */ -#define ETH_MAC_TXFIFO_WRITING 0x00300000U /* Tx FIFO read status: Writing the received TxStatus or flushing the TxFIFO */ -#define ETH_MAC_TRANSMISSION_PAUSE 0x00080000U /* MAC transmitter in pause */ -#define ETH_MAC_TRANSMITFRAMECONTROLLER_IDLE 0x00000000U /* MAC transmit frame controller: Idle */ -#define ETH_MAC_TRANSMITFRAMECONTROLLER_WAITING 0x00020000U /* MAC transmit frame controller: Waiting for Status of previous frame or IFG/backoff period to be over */ -#define ETH_MAC_TRANSMITFRAMECONTROLLER_GENRATING_PCF 0x00040000U /* MAC transmit frame controller: Generating and transmitting a Pause control frame (in full duplex mode) */ -#define ETH_MAC_TRANSMITFRAMECONTROLLER_TRANSFERRING 0x00060000U /* MAC transmit frame controller: Transferring input frame for transmission */ -#define ETH_MAC_MII_TRANSMIT_ACTIVE 0x00010000U /* MAC MII transmit engine active */ -#define ETH_MAC_RXFIFO_EMPTY 0x00000000U /* Rx FIFO fill level: empty */ -#define ETH_MAC_RXFIFO_BELOW_THRESHOLD 0x00000100U /* Rx FIFO fill level: fill-level below flow-control de-activate threshold */ -#define ETH_MAC_RXFIFO_ABOVE_THRESHOLD 0x00000200U /* Rx FIFO fill level: fill-level above flow-control activate threshold */ -#define ETH_MAC_RXFIFO_FULL 0x00000300U /* Rx FIFO fill level: full */ -#if defined(STM32F1) -#else -#define ETH_MAC_READCONTROLLER_IDLE 0x00000000U /* Rx FIFO read controller IDLE state */ -#define ETH_MAC_READCONTROLLER_READING_DATA 0x00000020U /* Rx FIFO read controller Reading frame data */ -#define ETH_MAC_READCONTROLLER_READING_STATUS 0x00000040U /* Rx FIFO read controller Reading frame status (or time-stamp) */ -#endif -#define ETH_MAC_READCONTROLLER_FLUSHING 0x00000060U /* Rx FIFO read controller Flushing the frame data and status */ -#define ETH_MAC_RXFIFO_WRITE_ACTIVE 0x00000010U /* Rx FIFO write controller active */ -#define ETH_MAC_SMALL_FIFO_NOTACTIVE 0x00000000U /* MAC small FIFO read / write controllers not active */ -#define ETH_MAC_SMALL_FIFO_READ_ACTIVE 0x00000002U /* MAC small FIFO read controller active */ -#define ETH_MAC_SMALL_FIFO_WRITE_ACTIVE 0x00000004U /* MAC small FIFO write controller active */ -#define ETH_MAC_SMALL_FIFO_RW_ACTIVE 0x00000006U /* MAC small FIFO read / write controllers active */ -#define ETH_MAC_MII_RECEIVE_PROTOCOL_ACTIVE 0x00000001U /* MAC MII receive protocol engine active */ - -/** - * @} - */ - -/** @defgroup HAL_DCMI_Aliased_Defines HAL DCMI Aliased Defines maintained for legacy purpose - * @{ - */ -#define HAL_DCMI_ERROR_OVF HAL_DCMI_ERROR_OVR -#define DCMI_IT_OVF DCMI_IT_OVR -#define DCMI_FLAG_OVFRI DCMI_FLAG_OVRRI -#define DCMI_FLAG_OVFMI DCMI_FLAG_OVRMI - -#define HAL_DCMI_ConfigCROP HAL_DCMI_ConfigCrop -#define HAL_DCMI_EnableCROP HAL_DCMI_EnableCrop -#define HAL_DCMI_DisableCROP HAL_DCMI_DisableCrop - -/** - * @} - */ - -#if defined(STM32L4) || defined(STM32F7) || defined(STM32F427xx) || defined(STM32F437xx) \ - || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) \ - || defined(STM32H7) -/** @defgroup HAL_DMA2D_Aliased_Defines HAL DMA2D Aliased Defines maintained for legacy purpose - * @{ - */ -#define DMA2D_ARGB8888 DMA2D_OUTPUT_ARGB8888 -#define DMA2D_RGB888 DMA2D_OUTPUT_RGB888 -#define DMA2D_RGB565 DMA2D_OUTPUT_RGB565 -#define DMA2D_ARGB1555 DMA2D_OUTPUT_ARGB1555 -#define DMA2D_ARGB4444 DMA2D_OUTPUT_ARGB4444 - -#define CM_ARGB8888 DMA2D_INPUT_ARGB8888 -#define CM_RGB888 DMA2D_INPUT_RGB888 -#define CM_RGB565 DMA2D_INPUT_RGB565 -#define CM_ARGB1555 DMA2D_INPUT_ARGB1555 -#define CM_ARGB4444 DMA2D_INPUT_ARGB4444 -#define CM_L8 DMA2D_INPUT_L8 -#define CM_AL44 DMA2D_INPUT_AL44 -#define CM_AL88 DMA2D_INPUT_AL88 -#define CM_L4 DMA2D_INPUT_L4 -#define CM_A8 DMA2D_INPUT_A8 -#define CM_A4 DMA2D_INPUT_A4 -/** - * @} - */ -#endif /* STM32L4 || STM32F7 || STM32F4 || STM32H7 */ - -#if defined(STM32L4) || defined(STM32F7) || defined(STM32F427xx) || defined(STM32F437xx) \ - || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) \ - || defined(STM32H7) || defined(STM32U5) -/** @defgroup DMA2D_Aliases DMA2D API Aliases - * @{ - */ -#define HAL_DMA2D_DisableCLUT HAL_DMA2D_CLUTLoading_Abort /*!< Aliased to HAL_DMA2D_CLUTLoading_Abort - for compatibility with legacy code */ -/** - * @} - */ - -#endif /* STM32L4 || STM32F7 || STM32F4 || STM32H7 || STM32U5 */ - -/** @defgroup HAL_PPP_Aliased_Defines HAL PPP Aliased Defines maintained for legacy purpose - * @{ - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ - -/** @defgroup HAL_CRYP_Aliased_Functions HAL CRYP Aliased Functions maintained for legacy purpose - * @{ - */ -#define HAL_CRYP_ComputationCpltCallback HAL_CRYPEx_ComputationCpltCallback -/** - * @} - */ - -/** @defgroup HAL_DCACHE_Aliased_Functions HAL DCACHE Aliased Functions maintained for legacy purpose - * @{ - */ - -#if defined(STM32U5) -#define HAL_DCACHE_CleanInvalidateByAddr HAL_DCACHE_CleanInvalidByAddr -#define HAL_DCACHE_CleanInvalidateByAddr_IT HAL_DCACHE_CleanInvalidByAddr_IT -#endif /* STM32U5 */ - -/** - * @} - */ - -#if !defined(STM32F2) -/** @defgroup HASH_alias HASH API alias - * @{ - */ -#define HAL_HASHEx_IRQHandler HAL_HASH_IRQHandler /*!< Redirection for compatibility with legacy code */ -/** - * - * @} - */ -#endif /* STM32F2 */ -/** @defgroup HAL_HASH_Aliased_Functions HAL HASH Aliased Functions maintained for legacy purpose - * @{ - */ -#define HAL_HASH_STATETypeDef HAL_HASH_StateTypeDef -#define HAL_HASHPhaseTypeDef HAL_HASH_PhaseTypeDef -#define HAL_HMAC_MD5_Finish HAL_HASH_MD5_Finish -#define HAL_HMAC_SHA1_Finish HAL_HASH_SHA1_Finish -#define HAL_HMAC_SHA224_Finish HAL_HASH_SHA224_Finish -#define HAL_HMAC_SHA256_Finish HAL_HASH_SHA256_Finish - -/*HASH Algorithm Selection*/ - -#define HASH_AlgoSelection_SHA1 HASH_ALGOSELECTION_SHA1 -#define HASH_AlgoSelection_SHA224 HASH_ALGOSELECTION_SHA224 -#define HASH_AlgoSelection_SHA256 HASH_ALGOSELECTION_SHA256 -#define HASH_AlgoSelection_MD5 HASH_ALGOSELECTION_MD5 - -#define HASH_AlgoMode_HASH HASH_ALGOMODE_HASH -#define HASH_AlgoMode_HMAC HASH_ALGOMODE_HMAC - -#define HASH_HMACKeyType_ShortKey HASH_HMAC_KEYTYPE_SHORTKEY -#define HASH_HMACKeyType_LongKey HASH_HMAC_KEYTYPE_LONGKEY - -#if defined(STM32L4) || defined(STM32L5) || defined(STM32F2) || defined(STM32F4) || defined(STM32F7) || defined(STM32H7) - -#define HAL_HASH_MD5_Accumulate HAL_HASH_MD5_Accmlt -#define HAL_HASH_MD5_Accumulate_End HAL_HASH_MD5_Accmlt_End -#define HAL_HASH_MD5_Accumulate_IT HAL_HASH_MD5_Accmlt_IT -#define HAL_HASH_MD5_Accumulate_End_IT HAL_HASH_MD5_Accmlt_End_IT - -#define HAL_HASH_SHA1_Accumulate HAL_HASH_SHA1_Accmlt -#define HAL_HASH_SHA1_Accumulate_End HAL_HASH_SHA1_Accmlt_End -#define HAL_HASH_SHA1_Accumulate_IT HAL_HASH_SHA1_Accmlt_IT -#define HAL_HASH_SHA1_Accumulate_End_IT HAL_HASH_SHA1_Accmlt_End_IT - -#define HAL_HASHEx_SHA224_Accumulate HAL_HASHEx_SHA224_Accmlt -#define HAL_HASHEx_SHA224_Accumulate_End HAL_HASHEx_SHA224_Accmlt_End -#define HAL_HASHEx_SHA224_Accumulate_IT HAL_HASHEx_SHA224_Accmlt_IT -#define HAL_HASHEx_SHA224_Accumulate_End_IT HAL_HASHEx_SHA224_Accmlt_End_IT - -#define HAL_HASHEx_SHA256_Accumulate HAL_HASHEx_SHA256_Accmlt -#define HAL_HASHEx_SHA256_Accumulate_End HAL_HASHEx_SHA256_Accmlt_End -#define HAL_HASHEx_SHA256_Accumulate_IT HAL_HASHEx_SHA256_Accmlt_IT -#define HAL_HASHEx_SHA256_Accumulate_End_IT HAL_HASHEx_SHA256_Accmlt_End_IT - -#endif /* STM32L4 || STM32L5 || STM32F2 || STM32F4 || STM32F7 || STM32H7 */ -/** - * @} - */ - -/** @defgroup HAL_Aliased_Functions HAL Generic Aliased Functions maintained for legacy purpose - * @{ - */ -#define HAL_EnableDBGSleepMode HAL_DBGMCU_EnableDBGSleepMode -#define HAL_DisableDBGSleepMode HAL_DBGMCU_DisableDBGSleepMode -#define HAL_EnableDBGStopMode HAL_DBGMCU_EnableDBGStopMode -#define HAL_DisableDBGStopMode HAL_DBGMCU_DisableDBGStopMode -#define HAL_EnableDBGStandbyMode HAL_DBGMCU_EnableDBGStandbyMode -#define HAL_DisableDBGStandbyMode HAL_DBGMCU_DisableDBGStandbyMode -#define HAL_DBG_LowPowerConfig(Periph, cmd) (((cmd\ - )==ENABLE)? HAL_DBGMCU_DBG_EnableLowPowerConfig(Periph) : HAL_DBGMCU_DBG_DisableLowPowerConfig(Periph)) -#define HAL_VREFINT_OutputSelect HAL_SYSCFG_VREFINT_OutputSelect -#define HAL_Lock_Cmd(cmd) (((cmd)==ENABLE) ? HAL_SYSCFG_Enable_Lock_VREFINT() : HAL_SYSCFG_Disable_Lock_VREFINT()) -#if defined(STM32L0) -#else -#define HAL_VREFINT_Cmd(cmd) (((cmd)==ENABLE)? HAL_SYSCFG_EnableVREFINT() : HAL_SYSCFG_DisableVREFINT()) -#endif -#define HAL_ADC_EnableBuffer_Cmd(cmd) (((cmd)==ENABLE) ? HAL_ADCEx_EnableVREFINT() : HAL_ADCEx_DisableVREFINT()) -#define HAL_ADC_EnableBufferSensor_Cmd(cmd) (((cmd\ - )==ENABLE) ? HAL_ADCEx_EnableVREFINTTempSensor() : HAL_ADCEx_DisableVREFINTTempSensor()) -#if defined(STM32H7A3xx) || defined(STM32H7B3xx) || defined(STM32H7B0xx) || defined(STM32H7A3xxQ) || defined(STM32H7B3xxQ) || defined(STM32H7B0xxQ) -#define HAL_EnableSRDomainDBGStopMode HAL_EnableDomain3DBGStopMode -#define HAL_DisableSRDomainDBGStopMode HAL_DisableDomain3DBGStopMode -#define HAL_EnableSRDomainDBGStandbyMode HAL_EnableDomain3DBGStandbyMode -#define HAL_DisableSRDomainDBGStandbyMode HAL_DisableDomain3DBGStandbyMode -#endif /* STM32H7A3xx || STM32H7B3xx || STM32H7B0xx || STM32H7A3xxQ || STM32H7B3xxQ || STM32H7B0xxQ */ - -/** - * @} - */ - -/** @defgroup HAL_FLASH_Aliased_Functions HAL FLASH Aliased Functions maintained for legacy purpose - * @{ - */ -#define FLASH_HalfPageProgram HAL_FLASHEx_HalfPageProgram -#define FLASH_EnableRunPowerDown HAL_FLASHEx_EnableRunPowerDown -#define FLASH_DisableRunPowerDown HAL_FLASHEx_DisableRunPowerDown -#define HAL_DATA_EEPROMEx_Unlock HAL_FLASHEx_DATAEEPROM_Unlock -#define HAL_DATA_EEPROMEx_Lock HAL_FLASHEx_DATAEEPROM_Lock -#define HAL_DATA_EEPROMEx_Erase HAL_FLASHEx_DATAEEPROM_Erase -#define HAL_DATA_EEPROMEx_Program HAL_FLASHEx_DATAEEPROM_Program - -/** - * @} - */ - -/** @defgroup HAL_I2C_Aliased_Functions HAL I2C Aliased Functions maintained for legacy purpose - * @{ - */ -#define HAL_I2CEx_AnalogFilter_Config HAL_I2CEx_ConfigAnalogFilter -#define HAL_I2CEx_DigitalFilter_Config HAL_I2CEx_ConfigDigitalFilter -#define HAL_FMPI2CEx_AnalogFilter_Config HAL_FMPI2CEx_ConfigAnalogFilter -#define HAL_FMPI2CEx_DigitalFilter_Config HAL_FMPI2CEx_ConfigDigitalFilter - -#define HAL_I2CFastModePlusConfig(SYSCFG_I2CFastModePlus, cmd) (((cmd\ - )==ENABLE)? HAL_I2CEx_EnableFastModePlus(SYSCFG_I2CFastModePlus): HAL_I2CEx_DisableFastModePlus(SYSCFG_I2CFastModePlus)) - -#if defined(STM32H7) || defined(STM32WB) || defined(STM32G0) || defined(STM32F0) || defined(STM32F1) || defined(STM32F2) || defined(STM32F3) || defined(STM32F4) || defined(STM32F7) || defined(STM32L0) || defined(STM32L4) || defined(STM32L5) || defined(STM32G4) || defined(STM32L1) -#define HAL_I2C_Master_Sequential_Transmit_IT HAL_I2C_Master_Seq_Transmit_IT -#define HAL_I2C_Master_Sequential_Receive_IT HAL_I2C_Master_Seq_Receive_IT -#define HAL_I2C_Slave_Sequential_Transmit_IT HAL_I2C_Slave_Seq_Transmit_IT -#define HAL_I2C_Slave_Sequential_Receive_IT HAL_I2C_Slave_Seq_Receive_IT -#endif /* STM32H7 || STM32WB || STM32G0 || STM32F0 || STM32F1 || STM32F2 || STM32F3 || STM32F4 || STM32F7 || STM32L0 || STM32L4 || STM32L5 || STM32G4 || STM32L1 */ -#if defined(STM32H7) || defined(STM32WB) || defined(STM32G0) || defined(STM32F4) || defined(STM32F7) || defined(STM32L0) || defined(STM32L4) || defined(STM32L5) || defined(STM32G4)|| defined(STM32L1) -#define HAL_I2C_Master_Sequential_Transmit_DMA HAL_I2C_Master_Seq_Transmit_DMA -#define HAL_I2C_Master_Sequential_Receive_DMA HAL_I2C_Master_Seq_Receive_DMA -#define HAL_I2C_Slave_Sequential_Transmit_DMA HAL_I2C_Slave_Seq_Transmit_DMA -#define HAL_I2C_Slave_Sequential_Receive_DMA HAL_I2C_Slave_Seq_Receive_DMA -#endif /* STM32H7 || STM32WB || STM32G0 || STM32F4 || STM32F7 || STM32L0 || STM32L4 || STM32L5 || STM32G4 || STM32L1 */ - -#if defined(STM32F4) -#define HAL_FMPI2C_Master_Sequential_Transmit_IT HAL_FMPI2C_Master_Seq_Transmit_IT -#define HAL_FMPI2C_Master_Sequential_Receive_IT HAL_FMPI2C_Master_Seq_Receive_IT -#define HAL_FMPI2C_Slave_Sequential_Transmit_IT HAL_FMPI2C_Slave_Seq_Transmit_IT -#define HAL_FMPI2C_Slave_Sequential_Receive_IT HAL_FMPI2C_Slave_Seq_Receive_IT -#define HAL_FMPI2C_Master_Sequential_Transmit_DMA HAL_FMPI2C_Master_Seq_Transmit_DMA -#define HAL_FMPI2C_Master_Sequential_Receive_DMA HAL_FMPI2C_Master_Seq_Receive_DMA -#define HAL_FMPI2C_Slave_Sequential_Transmit_DMA HAL_FMPI2C_Slave_Seq_Transmit_DMA -#define HAL_FMPI2C_Slave_Sequential_Receive_DMA HAL_FMPI2C_Slave_Seq_Receive_DMA -#endif /* STM32F4 */ -/** - * @} - */ - -/** @defgroup HAL_PWR_Aliased HAL PWR Aliased maintained for legacy purpose - * @{ - */ - -#if defined(STM32G0) -#define HAL_PWR_ConfigPVD HAL_PWREx_ConfigPVD -#define HAL_PWR_EnablePVD HAL_PWREx_EnablePVD -#define HAL_PWR_DisablePVD HAL_PWREx_DisablePVD -#define HAL_PWR_PVD_IRQHandler HAL_PWREx_PVD_IRQHandler -#endif -#define HAL_PWR_PVDConfig HAL_PWR_ConfigPVD -#define HAL_PWR_DisableBkUpReg HAL_PWREx_DisableBkUpReg -#define HAL_PWR_DisableFlashPowerDown HAL_PWREx_DisableFlashPowerDown -#define HAL_PWR_DisableVddio2Monitor HAL_PWREx_DisableVddio2Monitor -#define HAL_PWR_EnableBkUpReg HAL_PWREx_EnableBkUpReg -#define HAL_PWR_EnableFlashPowerDown HAL_PWREx_EnableFlashPowerDown -#define HAL_PWR_EnableVddio2Monitor HAL_PWREx_EnableVddio2Monitor -#define HAL_PWR_PVD_PVM_IRQHandler HAL_PWREx_PVD_PVM_IRQHandler -#define HAL_PWR_PVDLevelConfig HAL_PWR_ConfigPVD -#define HAL_PWR_Vddio2Monitor_IRQHandler HAL_PWREx_Vddio2Monitor_IRQHandler -#define HAL_PWR_Vddio2MonitorCallback HAL_PWREx_Vddio2MonitorCallback -#define HAL_PWREx_ActivateOverDrive HAL_PWREx_EnableOverDrive -#define HAL_PWREx_DeactivateOverDrive HAL_PWREx_DisableOverDrive -#define HAL_PWREx_DisableSDADCAnalog HAL_PWREx_DisableSDADC -#define HAL_PWREx_EnableSDADCAnalog HAL_PWREx_EnableSDADC -#define HAL_PWREx_PVMConfig HAL_PWREx_ConfigPVM - -#define PWR_MODE_NORMAL PWR_PVD_MODE_NORMAL -#define PWR_MODE_IT_RISING PWR_PVD_MODE_IT_RISING -#define PWR_MODE_IT_FALLING PWR_PVD_MODE_IT_FALLING -#define PWR_MODE_IT_RISING_FALLING PWR_PVD_MODE_IT_RISING_FALLING -#define PWR_MODE_EVENT_RISING PWR_PVD_MODE_EVENT_RISING -#define PWR_MODE_EVENT_FALLING PWR_PVD_MODE_EVENT_FALLING -#define PWR_MODE_EVENT_RISING_FALLING PWR_PVD_MODE_EVENT_RISING_FALLING - -#define CR_OFFSET_BB PWR_CR_OFFSET_BB -#define CSR_OFFSET_BB PWR_CSR_OFFSET_BB -#define PMODE_BIT_NUMBER VOS_BIT_NUMBER -#define CR_PMODE_BB CR_VOS_BB - -#define DBP_BitNumber DBP_BIT_NUMBER -#define PVDE_BitNumber PVDE_BIT_NUMBER -#define PMODE_BitNumber PMODE_BIT_NUMBER -#define EWUP_BitNumber EWUP_BIT_NUMBER -#define FPDS_BitNumber FPDS_BIT_NUMBER -#define ODEN_BitNumber ODEN_BIT_NUMBER -#define ODSWEN_BitNumber ODSWEN_BIT_NUMBER -#define MRLVDS_BitNumber MRLVDS_BIT_NUMBER -#define LPLVDS_BitNumber LPLVDS_BIT_NUMBER -#define BRE_BitNumber BRE_BIT_NUMBER - -#define PWR_MODE_EVT PWR_PVD_MODE_NORMAL - -/** - * @} - */ - -/** @defgroup HAL_SMBUS_Aliased_Functions HAL SMBUS Aliased Functions maintained for legacy purpose - * @{ - */ -#define HAL_SMBUS_Slave_Listen_IT HAL_SMBUS_EnableListen_IT -#define HAL_SMBUS_SlaveAddrCallback HAL_SMBUS_AddrCallback -#define HAL_SMBUS_SlaveListenCpltCallback HAL_SMBUS_ListenCpltCallback -/** - * @} - */ - -/** @defgroup HAL_SPI_Aliased_Functions HAL SPI Aliased Functions maintained for legacy purpose - * @{ - */ -#define HAL_SPI_FlushRxFifo HAL_SPIEx_FlushRxFifo -/** - * @} - */ - -/** @defgroup HAL_TIM_Aliased_Functions HAL TIM Aliased Functions maintained for legacy purpose - * @{ - */ -#define HAL_TIM_DMADelayPulseCplt TIM_DMADelayPulseCplt -#define HAL_TIM_DMAError TIM_DMAError -#define HAL_TIM_DMACaptureCplt TIM_DMACaptureCplt -#define HAL_TIMEx_DMACommutationCplt TIMEx_DMACommutationCplt -#if defined(STM32H7) || defined(STM32G0) || defined(STM32F0) || defined(STM32F1) || defined(STM32F2) || defined(STM32F3) || defined(STM32F4) || defined(STM32F7) || defined(STM32L0) || defined(STM32L4) -#define HAL_TIM_SlaveConfigSynchronization HAL_TIM_SlaveConfigSynchro -#define HAL_TIM_SlaveConfigSynchronization_IT HAL_TIM_SlaveConfigSynchro_IT -#define HAL_TIMEx_CommutationCallback HAL_TIMEx_CommutCallback -#define HAL_TIMEx_ConfigCommutationEvent HAL_TIMEx_ConfigCommutEvent -#define HAL_TIMEx_ConfigCommutationEvent_IT HAL_TIMEx_ConfigCommutEvent_IT -#define HAL_TIMEx_ConfigCommutationEvent_DMA HAL_TIMEx_ConfigCommutEvent_DMA -#endif /* STM32H7 || STM32G0 || STM32F0 || STM32F1 || STM32F2 || STM32F3 || STM32F4 || STM32F7 || STM32L0 */ -/** - * @} - */ - -/** @defgroup HAL_UART_Aliased_Functions HAL UART Aliased Functions maintained for legacy purpose - * @{ - */ -#define HAL_UART_WakeupCallback HAL_UARTEx_WakeupCallback -/** - * @} - */ - -/** @defgroup HAL_LTDC_Aliased_Functions HAL LTDC Aliased Functions maintained for legacy purpose - * @{ - */ -#define HAL_LTDC_LineEvenCallback HAL_LTDC_LineEventCallback -#define HAL_LTDC_Relaod HAL_LTDC_Reload -#define HAL_LTDC_StructInitFromVideoConfig HAL_LTDCEx_StructInitFromVideoConfig -#define HAL_LTDC_StructInitFromAdaptedCommandConfig HAL_LTDCEx_StructInitFromAdaptedCommandConfig -/** - * @} - */ - - -/** @defgroup HAL_PPP_Aliased_Functions HAL PPP Aliased Functions maintained for legacy purpose - * @{ - */ - -/** - * @} - */ - -/* Exported macros ------------------------------------------------------------*/ - -/** @defgroup HAL_AES_Aliased_Macros HAL CRYP Aliased Macros maintained for legacy purpose - * @{ - */ -#define AES_IT_CC CRYP_IT_CC -#define AES_IT_ERR CRYP_IT_ERR -#define AES_FLAG_CCF CRYP_FLAG_CCF -/** - * @} - */ - -/** @defgroup HAL_Aliased_Macros HAL Generic Aliased Macros maintained for legacy purpose - * @{ - */ -#define __HAL_GET_BOOT_MODE __HAL_SYSCFG_GET_BOOT_MODE -#define __HAL_REMAPMEMORY_FLASH __HAL_SYSCFG_REMAPMEMORY_FLASH -#define __HAL_REMAPMEMORY_SYSTEMFLASH __HAL_SYSCFG_REMAPMEMORY_SYSTEMFLASH -#define __HAL_REMAPMEMORY_SRAM __HAL_SYSCFG_REMAPMEMORY_SRAM -#define __HAL_REMAPMEMORY_FMC __HAL_SYSCFG_REMAPMEMORY_FMC -#define __HAL_REMAPMEMORY_FMC_SDRAM __HAL_SYSCFG_REMAPMEMORY_FMC_SDRAM -#define __HAL_REMAPMEMORY_FSMC __HAL_SYSCFG_REMAPMEMORY_FSMC -#define __HAL_REMAPMEMORY_QUADSPI __HAL_SYSCFG_REMAPMEMORY_QUADSPI -#define __HAL_FMC_BANK __HAL_SYSCFG_FMC_BANK -#define __HAL_GET_FLAG __HAL_SYSCFG_GET_FLAG -#define __HAL_CLEAR_FLAG __HAL_SYSCFG_CLEAR_FLAG -#define __HAL_VREFINT_OUT_ENABLE __HAL_SYSCFG_VREFINT_OUT_ENABLE -#define __HAL_VREFINT_OUT_DISABLE __HAL_SYSCFG_VREFINT_OUT_DISABLE -#define __HAL_SYSCFG_SRAM2_WRP_ENABLE __HAL_SYSCFG_SRAM2_WRP_0_31_ENABLE - -#define SYSCFG_FLAG_VREF_READY SYSCFG_FLAG_VREFINT_READY -#define SYSCFG_FLAG_RC48 RCC_FLAG_HSI48 -#define IS_SYSCFG_FASTMODEPLUS_CONFIG IS_I2C_FASTMODEPLUS -#define UFB_MODE_BitNumber UFB_MODE_BIT_NUMBER -#define CMP_PD_BitNumber CMP_PD_BIT_NUMBER - -/** - * @} - */ - - -/** @defgroup HAL_ADC_Aliased_Macros HAL ADC Aliased Macros maintained for legacy purpose - * @{ - */ -#define __ADC_ENABLE __HAL_ADC_ENABLE -#define __ADC_DISABLE __HAL_ADC_DISABLE -#define __HAL_ADC_ENABLING_CONDITIONS ADC_ENABLING_CONDITIONS -#define __HAL_ADC_DISABLING_CONDITIONS ADC_DISABLING_CONDITIONS -#define __HAL_ADC_IS_ENABLED ADC_IS_ENABLE -#define __ADC_IS_ENABLED ADC_IS_ENABLE -#define __HAL_ADC_IS_SOFTWARE_START_REGULAR ADC_IS_SOFTWARE_START_REGULAR -#define __HAL_ADC_IS_SOFTWARE_START_INJECTED ADC_IS_SOFTWARE_START_INJECTED -#define __HAL_ADC_IS_CONVERSION_ONGOING_REGULAR_INJECTED ADC_IS_CONVERSION_ONGOING_REGULAR_INJECTED -#define __HAL_ADC_IS_CONVERSION_ONGOING_REGULAR ADC_IS_CONVERSION_ONGOING_REGULAR -#define __HAL_ADC_IS_CONVERSION_ONGOING_INJECTED ADC_IS_CONVERSION_ONGOING_INJECTED -#define __HAL_ADC_IS_CONVERSION_ONGOING ADC_IS_CONVERSION_ONGOING -#define __HAL_ADC_CLEAR_ERRORCODE ADC_CLEAR_ERRORCODE - -#define __HAL_ADC_GET_RESOLUTION ADC_GET_RESOLUTION -#define __HAL_ADC_JSQR_RK ADC_JSQR_RK -#define __HAL_ADC_CFGR_AWD1CH ADC_CFGR_AWD1CH_SHIFT -#define __HAL_ADC_CFGR_AWD23CR ADC_CFGR_AWD23CR -#define __HAL_ADC_CFGR_INJECT_AUTO_CONVERSION ADC_CFGR_INJECT_AUTO_CONVERSION -#define __HAL_ADC_CFGR_INJECT_CONTEXT_QUEUE ADC_CFGR_INJECT_CONTEXT_QUEUE -#define __HAL_ADC_CFGR_INJECT_DISCCONTINUOUS ADC_CFGR_INJECT_DISCCONTINUOUS -#define __HAL_ADC_CFGR_REG_DISCCONTINUOUS ADC_CFGR_REG_DISCCONTINUOUS -#define __HAL_ADC_CFGR_DISCONTINUOUS_NUM ADC_CFGR_DISCONTINUOUS_NUM -#define __HAL_ADC_CFGR_AUTOWAIT ADC_CFGR_AUTOWAIT -#define __HAL_ADC_CFGR_CONTINUOUS ADC_CFGR_CONTINUOUS -#define __HAL_ADC_CFGR_OVERRUN ADC_CFGR_OVERRUN -#define __HAL_ADC_CFGR_DMACONTREQ ADC_CFGR_DMACONTREQ -#define __HAL_ADC_CFGR_EXTSEL ADC_CFGR_EXTSEL_SET -#define __HAL_ADC_JSQR_JEXTSEL ADC_JSQR_JEXTSEL_SET -#define __HAL_ADC_OFR_CHANNEL ADC_OFR_CHANNEL -#define __HAL_ADC_DIFSEL_CHANNEL ADC_DIFSEL_CHANNEL -#define __HAL_ADC_CALFACT_DIFF_SET ADC_CALFACT_DIFF_SET -#define __HAL_ADC_CALFACT_DIFF_GET ADC_CALFACT_DIFF_GET -#define __HAL_ADC_TRX_HIGHTHRESHOLD ADC_TRX_HIGHTHRESHOLD - -#define __HAL_ADC_OFFSET_SHIFT_RESOLUTION ADC_OFFSET_SHIFT_RESOLUTION -#define __HAL_ADC_AWD1THRESHOLD_SHIFT_RESOLUTION ADC_AWD1THRESHOLD_SHIFT_RESOLUTION -#define __HAL_ADC_AWD23THRESHOLD_SHIFT_RESOLUTION ADC_AWD23THRESHOLD_SHIFT_RESOLUTION -#define __HAL_ADC_COMMON_REGISTER ADC_COMMON_REGISTER -#define __HAL_ADC_COMMON_CCR_MULTI ADC_COMMON_CCR_MULTI -#define __HAL_ADC_MULTIMODE_IS_ENABLED ADC_MULTIMODE_IS_ENABLE -#define __ADC_MULTIMODE_IS_ENABLED ADC_MULTIMODE_IS_ENABLE -#define __HAL_ADC_NONMULTIMODE_OR_MULTIMODEMASTER ADC_NONMULTIMODE_OR_MULTIMODEMASTER -#define __HAL_ADC_COMMON_ADC_OTHER ADC_COMMON_ADC_OTHER -#define __HAL_ADC_MULTI_SLAVE ADC_MULTI_SLAVE - -#define __HAL_ADC_SQR1_L ADC_SQR1_L_SHIFT -#define __HAL_ADC_JSQR_JL ADC_JSQR_JL_SHIFT -#define __HAL_ADC_JSQR_RK_JL ADC_JSQR_RK_JL -#define __HAL_ADC_CR1_DISCONTINUOUS_NUM ADC_CR1_DISCONTINUOUS_NUM -#define __HAL_ADC_CR1_SCAN ADC_CR1_SCAN_SET -#define __HAL_ADC_CONVCYCLES_MAX_RANGE ADC_CONVCYCLES_MAX_RANGE -#define __HAL_ADC_CLOCK_PRESCALER_RANGE ADC_CLOCK_PRESCALER_RANGE -#define __HAL_ADC_GET_CLOCK_PRESCALER ADC_GET_CLOCK_PRESCALER - -#define __HAL_ADC_SQR1 ADC_SQR1 -#define __HAL_ADC_SMPR1 ADC_SMPR1 -#define __HAL_ADC_SMPR2 ADC_SMPR2 -#define __HAL_ADC_SQR3_RK ADC_SQR3_RK -#define __HAL_ADC_SQR2_RK ADC_SQR2_RK -#define __HAL_ADC_SQR1_RK ADC_SQR1_RK -#define __HAL_ADC_CR2_CONTINUOUS ADC_CR2_CONTINUOUS -#define __HAL_ADC_CR1_DISCONTINUOUS ADC_CR1_DISCONTINUOUS -#define __HAL_ADC_CR1_SCANCONV ADC_CR1_SCANCONV -#define __HAL_ADC_CR2_EOCSelection ADC_CR2_EOCSelection -#define __HAL_ADC_CR2_DMAContReq ADC_CR2_DMAContReq -#define __HAL_ADC_JSQR ADC_JSQR - -#define __HAL_ADC_CHSELR_CHANNEL ADC_CHSELR_CHANNEL -#define __HAL_ADC_CFGR1_REG_DISCCONTINUOUS ADC_CFGR1_REG_DISCCONTINUOUS -#define __HAL_ADC_CFGR1_AUTOOFF ADC_CFGR1_AUTOOFF -#define __HAL_ADC_CFGR1_AUTOWAIT ADC_CFGR1_AUTOWAIT -#define __HAL_ADC_CFGR1_CONTINUOUS ADC_CFGR1_CONTINUOUS -#define __HAL_ADC_CFGR1_OVERRUN ADC_CFGR1_OVERRUN -#define __HAL_ADC_CFGR1_SCANDIR ADC_CFGR1_SCANDIR -#define __HAL_ADC_CFGR1_DMACONTREQ ADC_CFGR1_DMACONTREQ - -/** - * @} - */ - -/** @defgroup HAL_DAC_Aliased_Macros HAL DAC Aliased Macros maintained for legacy purpose - * @{ - */ -#define __HAL_DHR12R1_ALIGNEMENT DAC_DHR12R1_ALIGNMENT -#define __HAL_DHR12R2_ALIGNEMENT DAC_DHR12R2_ALIGNMENT -#define __HAL_DHR12RD_ALIGNEMENT DAC_DHR12RD_ALIGNMENT -#define IS_DAC_GENERATE_WAVE IS_DAC_WAVE - -/** - * @} - */ - -/** @defgroup HAL_DBGMCU_Aliased_Macros HAL DBGMCU Aliased Macros maintained for legacy purpose - * @{ - */ -#define __HAL_FREEZE_TIM1_DBGMCU __HAL_DBGMCU_FREEZE_TIM1 -#define __HAL_UNFREEZE_TIM1_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM1 -#define __HAL_FREEZE_TIM2_DBGMCU __HAL_DBGMCU_FREEZE_TIM2 -#define __HAL_UNFREEZE_TIM2_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM2 -#define __HAL_FREEZE_TIM3_DBGMCU __HAL_DBGMCU_FREEZE_TIM3 -#define __HAL_UNFREEZE_TIM3_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM3 -#define __HAL_FREEZE_TIM4_DBGMCU __HAL_DBGMCU_FREEZE_TIM4 -#define __HAL_UNFREEZE_TIM4_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM4 -#define __HAL_FREEZE_TIM5_DBGMCU __HAL_DBGMCU_FREEZE_TIM5 -#define __HAL_UNFREEZE_TIM5_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM5 -#define __HAL_FREEZE_TIM6_DBGMCU __HAL_DBGMCU_FREEZE_TIM6 -#define __HAL_UNFREEZE_TIM6_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM6 -#define __HAL_FREEZE_TIM7_DBGMCU __HAL_DBGMCU_FREEZE_TIM7 -#define __HAL_UNFREEZE_TIM7_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM7 -#define __HAL_FREEZE_TIM8_DBGMCU __HAL_DBGMCU_FREEZE_TIM8 -#define __HAL_UNFREEZE_TIM8_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM8 - -#define __HAL_FREEZE_TIM9_DBGMCU __HAL_DBGMCU_FREEZE_TIM9 -#define __HAL_UNFREEZE_TIM9_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM9 -#define __HAL_FREEZE_TIM10_DBGMCU __HAL_DBGMCU_FREEZE_TIM10 -#define __HAL_UNFREEZE_TIM10_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM10 -#define __HAL_FREEZE_TIM11_DBGMCU __HAL_DBGMCU_FREEZE_TIM11 -#define __HAL_UNFREEZE_TIM11_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM11 -#define __HAL_FREEZE_TIM12_DBGMCU __HAL_DBGMCU_FREEZE_TIM12 -#define __HAL_UNFREEZE_TIM12_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM12 -#define __HAL_FREEZE_TIM13_DBGMCU __HAL_DBGMCU_FREEZE_TIM13 -#define __HAL_UNFREEZE_TIM13_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM13 -#define __HAL_FREEZE_TIM14_DBGMCU __HAL_DBGMCU_FREEZE_TIM14 -#define __HAL_UNFREEZE_TIM14_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM14 -#define __HAL_FREEZE_CAN2_DBGMCU __HAL_DBGMCU_FREEZE_CAN2 -#define __HAL_UNFREEZE_CAN2_DBGMCU __HAL_DBGMCU_UNFREEZE_CAN2 - - -#define __HAL_FREEZE_TIM15_DBGMCU __HAL_DBGMCU_FREEZE_TIM15 -#define __HAL_UNFREEZE_TIM15_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM15 -#define __HAL_FREEZE_TIM16_DBGMCU __HAL_DBGMCU_FREEZE_TIM16 -#define __HAL_UNFREEZE_TIM16_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM16 -#define __HAL_FREEZE_TIM17_DBGMCU __HAL_DBGMCU_FREEZE_TIM17 -#define __HAL_UNFREEZE_TIM17_DBGMCU __HAL_DBGMCU_UNFREEZE_TIM17 -#define __HAL_FREEZE_RTC_DBGMCU __HAL_DBGMCU_FREEZE_RTC -#define __HAL_UNFREEZE_RTC_DBGMCU __HAL_DBGMCU_UNFREEZE_RTC -#if defined(STM32H7) -#define __HAL_FREEZE_WWDG_DBGMCU __HAL_DBGMCU_FREEZE_WWDG1 -#define __HAL_UNFREEZE_WWDG_DBGMCU __HAL_DBGMCU_UnFreeze_WWDG1 -#define __HAL_FREEZE_IWDG_DBGMCU __HAL_DBGMCU_FREEZE_IWDG1 -#define __HAL_UNFREEZE_IWDG_DBGMCU __HAL_DBGMCU_UnFreeze_IWDG1 -#else -#define __HAL_FREEZE_WWDG_DBGMCU __HAL_DBGMCU_FREEZE_WWDG -#define __HAL_UNFREEZE_WWDG_DBGMCU __HAL_DBGMCU_UNFREEZE_WWDG -#define __HAL_FREEZE_IWDG_DBGMCU __HAL_DBGMCU_FREEZE_IWDG -#define __HAL_UNFREEZE_IWDG_DBGMCU __HAL_DBGMCU_UNFREEZE_IWDG -#endif /* STM32H7 */ -#define __HAL_FREEZE_I2C1_TIMEOUT_DBGMCU __HAL_DBGMCU_FREEZE_I2C1_TIMEOUT -#define __HAL_UNFREEZE_I2C1_TIMEOUT_DBGMCU __HAL_DBGMCU_UNFREEZE_I2C1_TIMEOUT -#define __HAL_FREEZE_I2C2_TIMEOUT_DBGMCU __HAL_DBGMCU_FREEZE_I2C2_TIMEOUT -#define __HAL_UNFREEZE_I2C2_TIMEOUT_DBGMCU __HAL_DBGMCU_UNFREEZE_I2C2_TIMEOUT -#define __HAL_FREEZE_I2C3_TIMEOUT_DBGMCU __HAL_DBGMCU_FREEZE_I2C3_TIMEOUT -#define __HAL_UNFREEZE_I2C3_TIMEOUT_DBGMCU __HAL_DBGMCU_UNFREEZE_I2C3_TIMEOUT -#define __HAL_FREEZE_CAN1_DBGMCU __HAL_DBGMCU_FREEZE_CAN1 -#define __HAL_UNFREEZE_CAN1_DBGMCU __HAL_DBGMCU_UNFREEZE_CAN1 -#define __HAL_FREEZE_LPTIM1_DBGMCU __HAL_DBGMCU_FREEZE_LPTIM1 -#define __HAL_UNFREEZE_LPTIM1_DBGMCU __HAL_DBGMCU_UNFREEZE_LPTIM1 -#define __HAL_FREEZE_LPTIM2_DBGMCU __HAL_DBGMCU_FREEZE_LPTIM2 -#define __HAL_UNFREEZE_LPTIM2_DBGMCU __HAL_DBGMCU_UNFREEZE_LPTIM2 - -/** - * @} - */ - -/** @defgroup HAL_COMP_Aliased_Macros HAL COMP Aliased Macros maintained for legacy purpose - * @{ - */ -#if defined(STM32F3) -#define COMP_START __HAL_COMP_ENABLE -#define COMP_STOP __HAL_COMP_DISABLE -#define COMP_LOCK __HAL_COMP_LOCK - -#if defined(STM32F301x8) || defined(STM32F302x8) || defined(STM32F318xx) || defined(STM32F303x8) || defined(STM32F334x8) || defined(STM32F328xx) -#define __HAL_COMP_EXTI_RISING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_RISING_EDGE() : \ - __HAL_COMP_COMP6_EXTI_ENABLE_RISING_EDGE()) -#define __HAL_COMP_EXTI_RISING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_RISING_EDGE() : \ - __HAL_COMP_COMP6_EXTI_DISABLE_RISING_EDGE()) -#define __HAL_COMP_EXTI_FALLING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_FALLING_EDGE() : \ - __HAL_COMP_COMP6_EXTI_ENABLE_FALLING_EDGE()) -#define __HAL_COMP_EXTI_FALLING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_FALLING_EDGE() : \ - __HAL_COMP_COMP6_EXTI_DISABLE_FALLING_EDGE()) -#define __HAL_COMP_EXTI_ENABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_IT() : \ - __HAL_COMP_COMP6_EXTI_ENABLE_IT()) -#define __HAL_COMP_EXTI_DISABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_IT() : \ - __HAL_COMP_COMP6_EXTI_DISABLE_IT()) -#define __HAL_COMP_EXTI_GET_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_GET_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_GET_FLAG() : \ - __HAL_COMP_COMP6_EXTI_GET_FLAG()) -#define __HAL_COMP_EXTI_CLEAR_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_CLEAR_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_CLEAR_FLAG() : \ - __HAL_COMP_COMP6_EXTI_CLEAR_FLAG()) -# endif -# if defined(STM32F302xE) || defined(STM32F302xC) -#define __HAL_COMP_EXTI_RISING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_RISING_EDGE() : \ - __HAL_COMP_COMP6_EXTI_ENABLE_RISING_EDGE()) -#define __HAL_COMP_EXTI_RISING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_RISING_EDGE() : \ - __HAL_COMP_COMP6_EXTI_DISABLE_RISING_EDGE()) -#define __HAL_COMP_EXTI_FALLING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_FALLING_EDGE() : \ - __HAL_COMP_COMP6_EXTI_ENABLE_FALLING_EDGE()) -#define __HAL_COMP_EXTI_FALLING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_FALLING_EDGE() : \ - __HAL_COMP_COMP6_EXTI_DISABLE_FALLING_EDGE()) -#define __HAL_COMP_EXTI_ENABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_IT() : \ - __HAL_COMP_COMP6_EXTI_ENABLE_IT()) -#define __HAL_COMP_EXTI_DISABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_IT() : \ - __HAL_COMP_COMP6_EXTI_DISABLE_IT()) -#define __HAL_COMP_EXTI_GET_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_GET_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_GET_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_GET_FLAG() : \ - __HAL_COMP_COMP6_EXTI_GET_FLAG()) -#define __HAL_COMP_EXTI_CLEAR_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_CLEAR_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_CLEAR_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_CLEAR_FLAG() : \ - __HAL_COMP_COMP6_EXTI_CLEAR_FLAG()) -# endif -# if defined(STM32F303xE) || defined(STM32F398xx) || defined(STM32F303xC) || defined(STM32F358xx) -#define __HAL_COMP_EXTI_RISING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP3) ? __HAL_COMP_COMP3_EXTI_ENABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP5) ? __HAL_COMP_COMP5_EXTI_ENABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP6) ? __HAL_COMP_COMP6_EXTI_ENABLE_RISING_EDGE() : \ - __HAL_COMP_COMP7_EXTI_ENABLE_RISING_EDGE()) -#define __HAL_COMP_EXTI_RISING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP3) ? __HAL_COMP_COMP3_EXTI_DISABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP5) ? __HAL_COMP_COMP5_EXTI_DISABLE_RISING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP6) ? __HAL_COMP_COMP6_EXTI_DISABLE_RISING_EDGE() : \ - __HAL_COMP_COMP7_EXTI_DISABLE_RISING_EDGE()) -#define __HAL_COMP_EXTI_FALLING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP3) ? __HAL_COMP_COMP3_EXTI_ENABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP5) ? __HAL_COMP_COMP5_EXTI_ENABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP6) ? __HAL_COMP_COMP6_EXTI_ENABLE_FALLING_EDGE() : \ - __HAL_COMP_COMP7_EXTI_ENABLE_FALLING_EDGE()) -#define __HAL_COMP_EXTI_FALLING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP3) ? __HAL_COMP_COMP3_EXTI_DISABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP5) ? __HAL_COMP_COMP5_EXTI_DISABLE_FALLING_EDGE() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP6) ? __HAL_COMP_COMP6_EXTI_DISABLE_FALLING_EDGE() : \ - __HAL_COMP_COMP7_EXTI_DISABLE_FALLING_EDGE()) -#define __HAL_COMP_EXTI_ENABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_ENABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP3) ? __HAL_COMP_COMP3_EXTI_ENABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_ENABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP5) ? __HAL_COMP_COMP5_EXTI_ENABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP6) ? __HAL_COMP_COMP6_EXTI_ENABLE_IT() : \ - __HAL_COMP_COMP7_EXTI_ENABLE_IT()) -#define __HAL_COMP_EXTI_DISABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_DISABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP3) ? __HAL_COMP_COMP3_EXTI_DISABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_DISABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP5) ? __HAL_COMP_COMP5_EXTI_DISABLE_IT() : \ - ((__EXTILINE__) == COMP_EXTI_LINE_COMP6) ? __HAL_COMP_COMP6_EXTI_DISABLE_IT() : \ - __HAL_COMP_COMP7_EXTI_DISABLE_IT()) -#define __HAL_COMP_EXTI_GET_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_GET_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_GET_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP3) ? __HAL_COMP_COMP3_EXTI_GET_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_GET_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP5) ? __HAL_COMP_COMP5_EXTI_GET_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP6) ? __HAL_COMP_COMP6_EXTI_GET_FLAG() : \ - __HAL_COMP_COMP7_EXTI_GET_FLAG()) -#define __HAL_COMP_EXTI_CLEAR_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_CLEAR_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP2) ? __HAL_COMP_COMP2_EXTI_CLEAR_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP3) ? __HAL_COMP_COMP3_EXTI_CLEAR_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP4) ? __HAL_COMP_COMP4_EXTI_CLEAR_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP5) ? __HAL_COMP_COMP5_EXTI_CLEAR_FLAG() : \ - ((__FLAG__) == COMP_EXTI_LINE_COMP6) ? __HAL_COMP_COMP6_EXTI_CLEAR_FLAG() : \ - __HAL_COMP_COMP7_EXTI_CLEAR_FLAG()) -# endif -# if defined(STM32F373xC) ||defined(STM32F378xx) -#define __HAL_COMP_EXTI_RISING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_RISING_EDGE() : \ - __HAL_COMP_COMP2_EXTI_ENABLE_RISING_EDGE()) -#define __HAL_COMP_EXTI_RISING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_RISING_EDGE() : \ - __HAL_COMP_COMP2_EXTI_DISABLE_RISING_EDGE()) -#define __HAL_COMP_EXTI_FALLING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_FALLING_EDGE() : \ - __HAL_COMP_COMP2_EXTI_ENABLE_FALLING_EDGE()) -#define __HAL_COMP_EXTI_FALLING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_FALLING_EDGE() : \ - __HAL_COMP_COMP2_EXTI_DISABLE_FALLING_EDGE()) -#define __HAL_COMP_EXTI_ENABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_IT() : \ - __HAL_COMP_COMP2_EXTI_ENABLE_IT()) -#define __HAL_COMP_EXTI_DISABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_IT() : \ - __HAL_COMP_COMP2_EXTI_DISABLE_IT()) -#define __HAL_COMP_EXTI_GET_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_GET_FLAG() : \ - __HAL_COMP_COMP2_EXTI_GET_FLAG()) -#define __HAL_COMP_EXTI_CLEAR_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_CLEAR_FLAG() : \ - __HAL_COMP_COMP2_EXTI_CLEAR_FLAG()) -# endif -#else -#define __HAL_COMP_EXTI_RISING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_RISING_EDGE() : \ - __HAL_COMP_COMP2_EXTI_ENABLE_RISING_EDGE()) -#define __HAL_COMP_EXTI_RISING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_RISING_EDGE() : \ - __HAL_COMP_COMP2_EXTI_DISABLE_RISING_EDGE()) -#define __HAL_COMP_EXTI_FALLING_IT_ENABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_FALLING_EDGE() : \ - __HAL_COMP_COMP2_EXTI_ENABLE_FALLING_EDGE()) -#define __HAL_COMP_EXTI_FALLING_IT_DISABLE(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_FALLING_EDGE() : \ - __HAL_COMP_COMP2_EXTI_DISABLE_FALLING_EDGE()) -#define __HAL_COMP_EXTI_ENABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_ENABLE_IT() : \ - __HAL_COMP_COMP2_EXTI_ENABLE_IT()) -#define __HAL_COMP_EXTI_DISABLE_IT(__EXTILINE__) (((__EXTILINE__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_DISABLE_IT() : \ - __HAL_COMP_COMP2_EXTI_DISABLE_IT()) -#define __HAL_COMP_EXTI_GET_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_GET_FLAG() : \ - __HAL_COMP_COMP2_EXTI_GET_FLAG()) -#define __HAL_COMP_EXTI_CLEAR_FLAG(__FLAG__) (((__FLAG__) == COMP_EXTI_LINE_COMP1) ? __HAL_COMP_COMP1_EXTI_CLEAR_FLAG() : \ - __HAL_COMP_COMP2_EXTI_CLEAR_FLAG()) -#endif - -#define __HAL_COMP_GET_EXTI_LINE COMP_GET_EXTI_LINE - -#if defined(STM32L0) || defined(STM32L4) -/* Note: On these STM32 families, the only argument of this macro */ -/* is COMP_FLAG_LOCK. */ -/* This macro is replaced by __HAL_COMP_IS_LOCKED with only HAL handle */ -/* argument. */ -#define __HAL_COMP_GET_FLAG(__HANDLE__, __FLAG__) (__HAL_COMP_IS_LOCKED(__HANDLE__)) -#endif -/** - * @} - */ - -#if defined(STM32L0) || defined(STM32L4) -/** @defgroup HAL_COMP_Aliased_Functions HAL COMP Aliased Functions maintained for legacy purpose - * @{ - */ -#define HAL_COMP_Start_IT HAL_COMP_Start /* Function considered as legacy as EXTI event or IT configuration is done into HAL_COMP_Init() */ -#define HAL_COMP_Stop_IT HAL_COMP_Stop /* Function considered as legacy as EXTI event or IT configuration is done into HAL_COMP_Init() */ -/** - * @} - */ -#endif - -/** @defgroup HAL_DAC_Aliased_Macros HAL DAC Aliased Macros maintained for legacy purpose - * @{ - */ - -#define IS_DAC_WAVE(WAVE) (((WAVE) == DAC_WAVE_NONE) || \ - ((WAVE) == DAC_WAVE_NOISE)|| \ - ((WAVE) == DAC_WAVE_TRIANGLE)) - -/** - * @} - */ - -/** @defgroup HAL_FLASH_Aliased_Macros HAL FLASH Aliased Macros maintained for legacy purpose - * @{ - */ - -#define IS_WRPAREA IS_OB_WRPAREA -#define IS_TYPEPROGRAM IS_FLASH_TYPEPROGRAM -#define IS_TYPEPROGRAMFLASH IS_FLASH_TYPEPROGRAM -#define IS_TYPEERASE IS_FLASH_TYPEERASE -#define IS_NBSECTORS IS_FLASH_NBSECTORS -#define IS_OB_WDG_SOURCE IS_OB_IWDG_SOURCE - -/** - * @} - */ - -/** @defgroup HAL_I2C_Aliased_Macros HAL I2C Aliased Macros maintained for legacy purpose - * @{ - */ - -#define __HAL_I2C_RESET_CR2 I2C_RESET_CR2 -#define __HAL_I2C_GENERATE_START I2C_GENERATE_START -#if defined(STM32F1) -#define __HAL_I2C_FREQ_RANGE I2C_FREQRANGE -#else -#define __HAL_I2C_FREQ_RANGE I2C_FREQ_RANGE -#endif /* STM32F1 */ -#define __HAL_I2C_RISE_TIME I2C_RISE_TIME -#define __HAL_I2C_SPEED_STANDARD I2C_SPEED_STANDARD -#define __HAL_I2C_SPEED_FAST I2C_SPEED_FAST -#define __HAL_I2C_SPEED I2C_SPEED -#define __HAL_I2C_7BIT_ADD_WRITE I2C_7BIT_ADD_WRITE -#define __HAL_I2C_7BIT_ADD_READ I2C_7BIT_ADD_READ -#define __HAL_I2C_10BIT_ADDRESS I2C_10BIT_ADDRESS -#define __HAL_I2C_10BIT_HEADER_WRITE I2C_10BIT_HEADER_WRITE -#define __HAL_I2C_10BIT_HEADER_READ I2C_10BIT_HEADER_READ -#define __HAL_I2C_MEM_ADD_MSB I2C_MEM_ADD_MSB -#define __HAL_I2C_MEM_ADD_LSB I2C_MEM_ADD_LSB -#define __HAL_I2C_FREQRANGE I2C_FREQRANGE -/** - * @} - */ - -/** @defgroup HAL_I2S_Aliased_Macros HAL I2S Aliased Macros maintained for legacy purpose - * @{ - */ - -#define IS_I2S_INSTANCE IS_I2S_ALL_INSTANCE -#define IS_I2S_INSTANCE_EXT IS_I2S_ALL_INSTANCE_EXT - -#if defined(STM32H7) -#define __HAL_I2S_CLEAR_FREFLAG __HAL_I2S_CLEAR_TIFREFLAG -#endif - -/** - * @} - */ - -/** @defgroup HAL_IRDA_Aliased_Macros HAL IRDA Aliased Macros maintained for legacy purpose - * @{ - */ - -#define __IRDA_DISABLE __HAL_IRDA_DISABLE -#define __IRDA_ENABLE __HAL_IRDA_ENABLE - -#define __HAL_IRDA_GETCLOCKSOURCE IRDA_GETCLOCKSOURCE -#define __HAL_IRDA_MASK_COMPUTATION IRDA_MASK_COMPUTATION -#define __IRDA_GETCLOCKSOURCE IRDA_GETCLOCKSOURCE -#define __IRDA_MASK_COMPUTATION IRDA_MASK_COMPUTATION - -#define IS_IRDA_ONEBIT_SAMPLE IS_IRDA_ONE_BIT_SAMPLE - - -/** - * @} - */ - - -/** @defgroup HAL_IWDG_Aliased_Macros HAL IWDG Aliased Macros maintained for legacy purpose - * @{ - */ -#define __HAL_IWDG_ENABLE_WRITE_ACCESS IWDG_ENABLE_WRITE_ACCESS -#define __HAL_IWDG_DISABLE_WRITE_ACCESS IWDG_DISABLE_WRITE_ACCESS -/** - * @} - */ - - -/** @defgroup HAL_LPTIM_Aliased_Macros HAL LPTIM Aliased Macros maintained for legacy purpose - * @{ - */ - -#define __HAL_LPTIM_ENABLE_INTERRUPT __HAL_LPTIM_ENABLE_IT -#define __HAL_LPTIM_DISABLE_INTERRUPT __HAL_LPTIM_DISABLE_IT -#define __HAL_LPTIM_GET_ITSTATUS __HAL_LPTIM_GET_IT_SOURCE - -/** - * @} - */ - - -/** @defgroup HAL_OPAMP_Aliased_Macros HAL OPAMP Aliased Macros maintained for legacy purpose - * @{ - */ -#define __OPAMP_CSR_OPAXPD OPAMP_CSR_OPAXPD -#define __OPAMP_CSR_S3SELX OPAMP_CSR_S3SELX -#define __OPAMP_CSR_S4SELX OPAMP_CSR_S4SELX -#define __OPAMP_CSR_S5SELX OPAMP_CSR_S5SELX -#define __OPAMP_CSR_S6SELX OPAMP_CSR_S6SELX -#define __OPAMP_CSR_OPAXCAL_L OPAMP_CSR_OPAXCAL_L -#define __OPAMP_CSR_OPAXCAL_H OPAMP_CSR_OPAXCAL_H -#define __OPAMP_CSR_OPAXLPM OPAMP_CSR_OPAXLPM -#define __OPAMP_CSR_ALL_SWITCHES OPAMP_CSR_ALL_SWITCHES -#define __OPAMP_CSR_ANAWSELX OPAMP_CSR_ANAWSELX -#define __OPAMP_CSR_OPAXCALOUT OPAMP_CSR_OPAXCALOUT -#define __OPAMP_OFFSET_TRIM_BITSPOSITION OPAMP_OFFSET_TRIM_BITSPOSITION -#define __OPAMP_OFFSET_TRIM_SET OPAMP_OFFSET_TRIM_SET - -/** - * @} - */ - - -/** @defgroup HAL_PWR_Aliased_Macros HAL PWR Aliased Macros maintained for legacy purpose - * @{ - */ -#define __HAL_PVD_EVENT_DISABLE __HAL_PWR_PVD_EXTI_DISABLE_EVENT -#define __HAL_PVD_EVENT_ENABLE __HAL_PWR_PVD_EXTI_ENABLE_EVENT -#define __HAL_PVD_EXTI_FALLINGTRIGGER_DISABLE __HAL_PWR_PVD_EXTI_DISABLE_FALLING_EDGE -#define __HAL_PVD_EXTI_FALLINGTRIGGER_ENABLE __HAL_PWR_PVD_EXTI_ENABLE_FALLING_EDGE -#define __HAL_PVD_EXTI_RISINGTRIGGER_DISABLE __HAL_PWR_PVD_EXTI_DISABLE_RISING_EDGE -#define __HAL_PVD_EXTI_RISINGTRIGGER_ENABLE __HAL_PWR_PVD_EXTI_ENABLE_RISING_EDGE -#define __HAL_PVM_EVENT_DISABLE __HAL_PWR_PVM_EVENT_DISABLE -#define __HAL_PVM_EVENT_ENABLE __HAL_PWR_PVM_EVENT_ENABLE -#define __HAL_PVM_EXTI_FALLINGTRIGGER_DISABLE __HAL_PWR_PVM_EXTI_FALLINGTRIGGER_DISABLE -#define __HAL_PVM_EXTI_FALLINGTRIGGER_ENABLE __HAL_PWR_PVM_EXTI_FALLINGTRIGGER_ENABLE -#define __HAL_PVM_EXTI_RISINGTRIGGER_DISABLE __HAL_PWR_PVM_EXTI_RISINGTRIGGER_DISABLE -#define __HAL_PVM_EXTI_RISINGTRIGGER_ENABLE __HAL_PWR_PVM_EXTI_RISINGTRIGGER_ENABLE -#define __HAL_PWR_INTERNALWAKEUP_DISABLE HAL_PWREx_DisableInternalWakeUpLine -#define __HAL_PWR_INTERNALWAKEUP_ENABLE HAL_PWREx_EnableInternalWakeUpLine -#define __HAL_PWR_PULL_UP_DOWN_CONFIG_DISABLE HAL_PWREx_DisablePullUpPullDownConfig -#define __HAL_PWR_PULL_UP_DOWN_CONFIG_ENABLE HAL_PWREx_EnablePullUpPullDownConfig -#define __HAL_PWR_PVD_EXTI_CLEAR_EGDE_TRIGGER() do { __HAL_PWR_PVD_EXTI_DISABLE_RISING_EDGE();__HAL_PWR_PVD_EXTI_DISABLE_FALLING_EDGE(); } while(0) -#define __HAL_PWR_PVD_EXTI_EVENT_DISABLE __HAL_PWR_PVD_EXTI_DISABLE_EVENT -#define __HAL_PWR_PVD_EXTI_EVENT_ENABLE __HAL_PWR_PVD_EXTI_ENABLE_EVENT -#define __HAL_PWR_PVD_EXTI_FALLINGTRIGGER_DISABLE __HAL_PWR_PVD_EXTI_DISABLE_FALLING_EDGE -#define __HAL_PWR_PVD_EXTI_FALLINGTRIGGER_ENABLE __HAL_PWR_PVD_EXTI_ENABLE_FALLING_EDGE -#define __HAL_PWR_PVD_EXTI_RISINGTRIGGER_DISABLE __HAL_PWR_PVD_EXTI_DISABLE_RISING_EDGE -#define __HAL_PWR_PVD_EXTI_RISINGTRIGGER_ENABLE __HAL_PWR_PVD_EXTI_ENABLE_RISING_EDGE -#define __HAL_PWR_PVD_EXTI_SET_FALLING_EGDE_TRIGGER __HAL_PWR_PVD_EXTI_ENABLE_FALLING_EDGE -#define __HAL_PWR_PVD_EXTI_SET_RISING_EDGE_TRIGGER __HAL_PWR_PVD_EXTI_ENABLE_RISING_EDGE -#define __HAL_PWR_PVM_DISABLE() do { HAL_PWREx_DisablePVM1();HAL_PWREx_DisablePVM2();HAL_PWREx_DisablePVM3();HAL_PWREx_DisablePVM4(); } while(0) -#define __HAL_PWR_PVM_ENABLE() do { HAL_PWREx_EnablePVM1();HAL_PWREx_EnablePVM2();HAL_PWREx_EnablePVM3();HAL_PWREx_EnablePVM4(); } while(0) -#define __HAL_PWR_SRAM2CONTENT_PRESERVE_DISABLE HAL_PWREx_DisableSRAM2ContentRetention -#define __HAL_PWR_SRAM2CONTENT_PRESERVE_ENABLE HAL_PWREx_EnableSRAM2ContentRetention -#define __HAL_PWR_VDDIO2_DISABLE HAL_PWREx_DisableVddIO2 -#define __HAL_PWR_VDDIO2_ENABLE HAL_PWREx_EnableVddIO2 -#define __HAL_PWR_VDDIO2_EXTI_CLEAR_EGDE_TRIGGER __HAL_PWR_VDDIO2_EXTI_DISABLE_FALLING_EDGE -#define __HAL_PWR_VDDIO2_EXTI_SET_FALLING_EGDE_TRIGGER __HAL_PWR_VDDIO2_EXTI_ENABLE_FALLING_EDGE -#define __HAL_PWR_VDDUSB_DISABLE HAL_PWREx_DisableVddUSB -#define __HAL_PWR_VDDUSB_ENABLE HAL_PWREx_EnableVddUSB - -#if defined (STM32F4) -#define __HAL_PVD_EXTI_ENABLE_IT(PWR_EXTI_LINE_PVD) __HAL_PWR_PVD_EXTI_ENABLE_IT() -#define __HAL_PVD_EXTI_DISABLE_IT(PWR_EXTI_LINE_PVD) __HAL_PWR_PVD_EXTI_DISABLE_IT() -#define __HAL_PVD_EXTI_GET_FLAG(PWR_EXTI_LINE_PVD) __HAL_PWR_PVD_EXTI_GET_FLAG() -#define __HAL_PVD_EXTI_CLEAR_FLAG(PWR_EXTI_LINE_PVD) __HAL_PWR_PVD_EXTI_CLEAR_FLAG() -#define __HAL_PVD_EXTI_GENERATE_SWIT(PWR_EXTI_LINE_PVD) __HAL_PWR_PVD_EXTI_GENERATE_SWIT() -#else -#define __HAL_PVD_EXTI_CLEAR_FLAG __HAL_PWR_PVD_EXTI_CLEAR_FLAG -#define __HAL_PVD_EXTI_DISABLE_IT __HAL_PWR_PVD_EXTI_DISABLE_IT -#define __HAL_PVD_EXTI_ENABLE_IT __HAL_PWR_PVD_EXTI_ENABLE_IT -#define __HAL_PVD_EXTI_GENERATE_SWIT __HAL_PWR_PVD_EXTI_GENERATE_SWIT -#define __HAL_PVD_EXTI_GET_FLAG __HAL_PWR_PVD_EXTI_GET_FLAG -#endif /* STM32F4 */ -/** - * @} - */ - - -/** @defgroup HAL_RCC_Aliased HAL RCC Aliased maintained for legacy purpose - * @{ - */ - -#define RCC_StopWakeUpClock_MSI RCC_STOP_WAKEUPCLOCK_MSI -#define RCC_StopWakeUpClock_HSI RCC_STOP_WAKEUPCLOCK_HSI - -#define HAL_RCC_CCSCallback HAL_RCC_CSSCallback -#define HAL_RC48_EnableBuffer_Cmd(cmd) (((cmd\ - )==ENABLE) ? HAL_RCCEx_EnableHSI48_VREFINT() : HAL_RCCEx_DisableHSI48_VREFINT()) - -#define __ADC_CLK_DISABLE __HAL_RCC_ADC_CLK_DISABLE -#define __ADC_CLK_ENABLE __HAL_RCC_ADC_CLK_ENABLE -#define __ADC_CLK_SLEEP_DISABLE __HAL_RCC_ADC_CLK_SLEEP_DISABLE -#define __ADC_CLK_SLEEP_ENABLE __HAL_RCC_ADC_CLK_SLEEP_ENABLE -#define __ADC_FORCE_RESET __HAL_RCC_ADC_FORCE_RESET -#define __ADC_RELEASE_RESET __HAL_RCC_ADC_RELEASE_RESET -#define __ADC1_CLK_DISABLE __HAL_RCC_ADC1_CLK_DISABLE -#define __ADC1_CLK_ENABLE __HAL_RCC_ADC1_CLK_ENABLE -#define __ADC1_FORCE_RESET __HAL_RCC_ADC1_FORCE_RESET -#define __ADC1_RELEASE_RESET __HAL_RCC_ADC1_RELEASE_RESET -#define __ADC1_CLK_SLEEP_ENABLE __HAL_RCC_ADC1_CLK_SLEEP_ENABLE -#define __ADC1_CLK_SLEEP_DISABLE __HAL_RCC_ADC1_CLK_SLEEP_DISABLE -#define __ADC2_CLK_DISABLE __HAL_RCC_ADC2_CLK_DISABLE -#define __ADC2_CLK_ENABLE __HAL_RCC_ADC2_CLK_ENABLE -#define __ADC2_FORCE_RESET __HAL_RCC_ADC2_FORCE_RESET -#define __ADC2_RELEASE_RESET __HAL_RCC_ADC2_RELEASE_RESET -#define __ADC3_CLK_DISABLE __HAL_RCC_ADC3_CLK_DISABLE -#define __ADC3_CLK_ENABLE __HAL_RCC_ADC3_CLK_ENABLE -#define __ADC3_FORCE_RESET __HAL_RCC_ADC3_FORCE_RESET -#define __ADC3_RELEASE_RESET __HAL_RCC_ADC3_RELEASE_RESET -#define __AES_CLK_DISABLE __HAL_RCC_AES_CLK_DISABLE -#define __AES_CLK_ENABLE __HAL_RCC_AES_CLK_ENABLE -#define __AES_CLK_SLEEP_DISABLE __HAL_RCC_AES_CLK_SLEEP_DISABLE -#define __AES_CLK_SLEEP_ENABLE __HAL_RCC_AES_CLK_SLEEP_ENABLE -#define __AES_FORCE_RESET __HAL_RCC_AES_FORCE_RESET -#define __AES_RELEASE_RESET __HAL_RCC_AES_RELEASE_RESET -#define __CRYP_CLK_SLEEP_ENABLE __HAL_RCC_CRYP_CLK_SLEEP_ENABLE -#define __CRYP_CLK_SLEEP_DISABLE __HAL_RCC_CRYP_CLK_SLEEP_DISABLE -#define __CRYP_CLK_ENABLE __HAL_RCC_CRYP_CLK_ENABLE -#define __CRYP_CLK_DISABLE __HAL_RCC_CRYP_CLK_DISABLE -#define __CRYP_FORCE_RESET __HAL_RCC_CRYP_FORCE_RESET -#define __CRYP_RELEASE_RESET __HAL_RCC_CRYP_RELEASE_RESET -#define __AFIO_CLK_DISABLE __HAL_RCC_AFIO_CLK_DISABLE -#define __AFIO_CLK_ENABLE __HAL_RCC_AFIO_CLK_ENABLE -#define __AFIO_FORCE_RESET __HAL_RCC_AFIO_FORCE_RESET -#define __AFIO_RELEASE_RESET __HAL_RCC_AFIO_RELEASE_RESET -#define __AHB_FORCE_RESET __HAL_RCC_AHB_FORCE_RESET -#define __AHB_RELEASE_RESET __HAL_RCC_AHB_RELEASE_RESET -#define __AHB1_FORCE_RESET __HAL_RCC_AHB1_FORCE_RESET -#define __AHB1_RELEASE_RESET __HAL_RCC_AHB1_RELEASE_RESET -#define __AHB2_FORCE_RESET __HAL_RCC_AHB2_FORCE_RESET -#define __AHB2_RELEASE_RESET __HAL_RCC_AHB2_RELEASE_RESET -#define __AHB3_FORCE_RESET __HAL_RCC_AHB3_FORCE_RESET -#define __AHB3_RELEASE_RESET __HAL_RCC_AHB3_RELEASE_RESET -#define __APB1_FORCE_RESET __HAL_RCC_APB1_FORCE_RESET -#define __APB1_RELEASE_RESET __HAL_RCC_APB1_RELEASE_RESET -#define __APB2_FORCE_RESET __HAL_RCC_APB2_FORCE_RESET -#define __APB2_RELEASE_RESET __HAL_RCC_APB2_RELEASE_RESET -#define __BKP_CLK_DISABLE __HAL_RCC_BKP_CLK_DISABLE -#define __BKP_CLK_ENABLE __HAL_RCC_BKP_CLK_ENABLE -#define __BKP_FORCE_RESET __HAL_RCC_BKP_FORCE_RESET -#define __BKP_RELEASE_RESET __HAL_RCC_BKP_RELEASE_RESET -#define __CAN1_CLK_DISABLE __HAL_RCC_CAN1_CLK_DISABLE -#define __CAN1_CLK_ENABLE __HAL_RCC_CAN1_CLK_ENABLE -#define __CAN1_CLK_SLEEP_DISABLE __HAL_RCC_CAN1_CLK_SLEEP_DISABLE -#define __CAN1_CLK_SLEEP_ENABLE __HAL_RCC_CAN1_CLK_SLEEP_ENABLE -#define __CAN1_FORCE_RESET __HAL_RCC_CAN1_FORCE_RESET -#define __CAN1_RELEASE_RESET __HAL_RCC_CAN1_RELEASE_RESET -#define __CAN_CLK_DISABLE __HAL_RCC_CAN1_CLK_DISABLE -#define __CAN_CLK_ENABLE __HAL_RCC_CAN1_CLK_ENABLE -#define __CAN_FORCE_RESET __HAL_RCC_CAN1_FORCE_RESET -#define __CAN_RELEASE_RESET __HAL_RCC_CAN1_RELEASE_RESET -#define __CAN2_CLK_DISABLE __HAL_RCC_CAN2_CLK_DISABLE -#define __CAN2_CLK_ENABLE __HAL_RCC_CAN2_CLK_ENABLE -#define __CAN2_FORCE_RESET __HAL_RCC_CAN2_FORCE_RESET -#define __CAN2_RELEASE_RESET __HAL_RCC_CAN2_RELEASE_RESET -#define __CEC_CLK_DISABLE __HAL_RCC_CEC_CLK_DISABLE -#define __CEC_CLK_ENABLE __HAL_RCC_CEC_CLK_ENABLE -#define __COMP_CLK_DISABLE __HAL_RCC_COMP_CLK_DISABLE -#define __COMP_CLK_ENABLE __HAL_RCC_COMP_CLK_ENABLE -#define __COMP_FORCE_RESET __HAL_RCC_COMP_FORCE_RESET -#define __COMP_RELEASE_RESET __HAL_RCC_COMP_RELEASE_RESET -#define __COMP_CLK_SLEEP_ENABLE __HAL_RCC_COMP_CLK_SLEEP_ENABLE -#define __COMP_CLK_SLEEP_DISABLE __HAL_RCC_COMP_CLK_SLEEP_DISABLE -#define __CEC_FORCE_RESET __HAL_RCC_CEC_FORCE_RESET -#define __CEC_RELEASE_RESET __HAL_RCC_CEC_RELEASE_RESET -#define __CRC_CLK_DISABLE __HAL_RCC_CRC_CLK_DISABLE -#define __CRC_CLK_ENABLE __HAL_RCC_CRC_CLK_ENABLE -#define __CRC_CLK_SLEEP_DISABLE __HAL_RCC_CRC_CLK_SLEEP_DISABLE -#define __CRC_CLK_SLEEP_ENABLE __HAL_RCC_CRC_CLK_SLEEP_ENABLE -#define __CRC_FORCE_RESET __HAL_RCC_CRC_FORCE_RESET -#define __CRC_RELEASE_RESET __HAL_RCC_CRC_RELEASE_RESET -#define __DAC_CLK_DISABLE __HAL_RCC_DAC_CLK_DISABLE -#define __DAC_CLK_ENABLE __HAL_RCC_DAC_CLK_ENABLE -#define __DAC_FORCE_RESET __HAL_RCC_DAC_FORCE_RESET -#define __DAC_RELEASE_RESET __HAL_RCC_DAC_RELEASE_RESET -#define __DAC1_CLK_DISABLE __HAL_RCC_DAC1_CLK_DISABLE -#define __DAC1_CLK_ENABLE __HAL_RCC_DAC1_CLK_ENABLE -#define __DAC1_CLK_SLEEP_DISABLE __HAL_RCC_DAC1_CLK_SLEEP_DISABLE -#define __DAC1_CLK_SLEEP_ENABLE __HAL_RCC_DAC1_CLK_SLEEP_ENABLE -#define __DAC1_FORCE_RESET __HAL_RCC_DAC1_FORCE_RESET -#define __DAC1_RELEASE_RESET __HAL_RCC_DAC1_RELEASE_RESET -#define __DBGMCU_CLK_ENABLE __HAL_RCC_DBGMCU_CLK_ENABLE -#define __DBGMCU_CLK_DISABLE __HAL_RCC_DBGMCU_CLK_DISABLE -#define __DBGMCU_FORCE_RESET __HAL_RCC_DBGMCU_FORCE_RESET -#define __DBGMCU_RELEASE_RESET __HAL_RCC_DBGMCU_RELEASE_RESET -#define __DFSDM_CLK_DISABLE __HAL_RCC_DFSDM_CLK_DISABLE -#define __DFSDM_CLK_ENABLE __HAL_RCC_DFSDM_CLK_ENABLE -#define __DFSDM_CLK_SLEEP_DISABLE __HAL_RCC_DFSDM_CLK_SLEEP_DISABLE -#define __DFSDM_CLK_SLEEP_ENABLE __HAL_RCC_DFSDM_CLK_SLEEP_ENABLE -#define __DFSDM_FORCE_RESET __HAL_RCC_DFSDM_FORCE_RESET -#define __DFSDM_RELEASE_RESET __HAL_RCC_DFSDM_RELEASE_RESET -#define __DMA1_CLK_DISABLE __HAL_RCC_DMA1_CLK_DISABLE -#define __DMA1_CLK_ENABLE __HAL_RCC_DMA1_CLK_ENABLE -#define __DMA1_CLK_SLEEP_DISABLE __HAL_RCC_DMA1_CLK_SLEEP_DISABLE -#define __DMA1_CLK_SLEEP_ENABLE __HAL_RCC_DMA1_CLK_SLEEP_ENABLE -#define __DMA1_FORCE_RESET __HAL_RCC_DMA1_FORCE_RESET -#define __DMA1_RELEASE_RESET __HAL_RCC_DMA1_RELEASE_RESET -#define __DMA2_CLK_DISABLE __HAL_RCC_DMA2_CLK_DISABLE -#define __DMA2_CLK_ENABLE __HAL_RCC_DMA2_CLK_ENABLE -#define __DMA2_CLK_SLEEP_DISABLE __HAL_RCC_DMA2_CLK_SLEEP_DISABLE -#define __DMA2_CLK_SLEEP_ENABLE __HAL_RCC_DMA2_CLK_SLEEP_ENABLE -#define __DMA2_FORCE_RESET __HAL_RCC_DMA2_FORCE_RESET -#define __DMA2_RELEASE_RESET __HAL_RCC_DMA2_RELEASE_RESET -#define __ETHMAC_CLK_DISABLE __HAL_RCC_ETHMAC_CLK_DISABLE -#define __ETHMAC_CLK_ENABLE __HAL_RCC_ETHMAC_CLK_ENABLE -#define __ETHMAC_FORCE_RESET __HAL_RCC_ETHMAC_FORCE_RESET -#define __ETHMAC_RELEASE_RESET __HAL_RCC_ETHMAC_RELEASE_RESET -#define __ETHMACRX_CLK_DISABLE __HAL_RCC_ETHMACRX_CLK_DISABLE -#define __ETHMACRX_CLK_ENABLE __HAL_RCC_ETHMACRX_CLK_ENABLE -#define __ETHMACTX_CLK_DISABLE __HAL_RCC_ETHMACTX_CLK_DISABLE -#define __ETHMACTX_CLK_ENABLE __HAL_RCC_ETHMACTX_CLK_ENABLE -#define __FIREWALL_CLK_DISABLE __HAL_RCC_FIREWALL_CLK_DISABLE -#define __FIREWALL_CLK_ENABLE __HAL_RCC_FIREWALL_CLK_ENABLE -#define __FLASH_CLK_DISABLE __HAL_RCC_FLASH_CLK_DISABLE -#define __FLASH_CLK_ENABLE __HAL_RCC_FLASH_CLK_ENABLE -#define __FLASH_CLK_SLEEP_DISABLE __HAL_RCC_FLASH_CLK_SLEEP_DISABLE -#define __FLASH_CLK_SLEEP_ENABLE __HAL_RCC_FLASH_CLK_SLEEP_ENABLE -#define __FLASH_FORCE_RESET __HAL_RCC_FLASH_FORCE_RESET -#define __FLASH_RELEASE_RESET __HAL_RCC_FLASH_RELEASE_RESET -#define __FLITF_CLK_DISABLE __HAL_RCC_FLITF_CLK_DISABLE -#define __FLITF_CLK_ENABLE __HAL_RCC_FLITF_CLK_ENABLE -#define __FLITF_FORCE_RESET __HAL_RCC_FLITF_FORCE_RESET -#define __FLITF_RELEASE_RESET __HAL_RCC_FLITF_RELEASE_RESET -#define __FLITF_CLK_SLEEP_ENABLE __HAL_RCC_FLITF_CLK_SLEEP_ENABLE -#define __FLITF_CLK_SLEEP_DISABLE __HAL_RCC_FLITF_CLK_SLEEP_DISABLE -#define __FMC_CLK_DISABLE __HAL_RCC_FMC_CLK_DISABLE -#define __FMC_CLK_ENABLE __HAL_RCC_FMC_CLK_ENABLE -#define __FMC_CLK_SLEEP_DISABLE __HAL_RCC_FMC_CLK_SLEEP_DISABLE -#define __FMC_CLK_SLEEP_ENABLE __HAL_RCC_FMC_CLK_SLEEP_ENABLE -#define __FMC_FORCE_RESET __HAL_RCC_FMC_FORCE_RESET -#define __FMC_RELEASE_RESET __HAL_RCC_FMC_RELEASE_RESET -#define __FSMC_CLK_DISABLE __HAL_RCC_FSMC_CLK_DISABLE -#define __FSMC_CLK_ENABLE __HAL_RCC_FSMC_CLK_ENABLE -#define __GPIOA_CLK_DISABLE __HAL_RCC_GPIOA_CLK_DISABLE -#define __GPIOA_CLK_ENABLE __HAL_RCC_GPIOA_CLK_ENABLE -#define __GPIOA_CLK_SLEEP_DISABLE __HAL_RCC_GPIOA_CLK_SLEEP_DISABLE -#define __GPIOA_CLK_SLEEP_ENABLE __HAL_RCC_GPIOA_CLK_SLEEP_ENABLE -#define __GPIOA_FORCE_RESET __HAL_RCC_GPIOA_FORCE_RESET -#define __GPIOA_RELEASE_RESET __HAL_RCC_GPIOA_RELEASE_RESET -#define __GPIOB_CLK_DISABLE __HAL_RCC_GPIOB_CLK_DISABLE -#define __GPIOB_CLK_ENABLE __HAL_RCC_GPIOB_CLK_ENABLE -#define __GPIOB_CLK_SLEEP_DISABLE __HAL_RCC_GPIOB_CLK_SLEEP_DISABLE -#define __GPIOB_CLK_SLEEP_ENABLE __HAL_RCC_GPIOB_CLK_SLEEP_ENABLE -#define __GPIOB_FORCE_RESET __HAL_RCC_GPIOB_FORCE_RESET -#define __GPIOB_RELEASE_RESET __HAL_RCC_GPIOB_RELEASE_RESET -#define __GPIOC_CLK_DISABLE __HAL_RCC_GPIOC_CLK_DISABLE -#define __GPIOC_CLK_ENABLE __HAL_RCC_GPIOC_CLK_ENABLE -#define __GPIOC_CLK_SLEEP_DISABLE __HAL_RCC_GPIOC_CLK_SLEEP_DISABLE -#define __GPIOC_CLK_SLEEP_ENABLE __HAL_RCC_GPIOC_CLK_SLEEP_ENABLE -#define __GPIOC_FORCE_RESET __HAL_RCC_GPIOC_FORCE_RESET -#define __GPIOC_RELEASE_RESET __HAL_RCC_GPIOC_RELEASE_RESET -#define __GPIOD_CLK_DISABLE __HAL_RCC_GPIOD_CLK_DISABLE -#define __GPIOD_CLK_ENABLE __HAL_RCC_GPIOD_CLK_ENABLE -#define __GPIOD_CLK_SLEEP_DISABLE __HAL_RCC_GPIOD_CLK_SLEEP_DISABLE -#define __GPIOD_CLK_SLEEP_ENABLE __HAL_RCC_GPIOD_CLK_SLEEP_ENABLE -#define __GPIOD_FORCE_RESET __HAL_RCC_GPIOD_FORCE_RESET -#define __GPIOD_RELEASE_RESET __HAL_RCC_GPIOD_RELEASE_RESET -#define __GPIOE_CLK_DISABLE __HAL_RCC_GPIOE_CLK_DISABLE -#define __GPIOE_CLK_ENABLE __HAL_RCC_GPIOE_CLK_ENABLE -#define __GPIOE_CLK_SLEEP_DISABLE __HAL_RCC_GPIOE_CLK_SLEEP_DISABLE -#define __GPIOE_CLK_SLEEP_ENABLE __HAL_RCC_GPIOE_CLK_SLEEP_ENABLE -#define __GPIOE_FORCE_RESET __HAL_RCC_GPIOE_FORCE_RESET -#define __GPIOE_RELEASE_RESET __HAL_RCC_GPIOE_RELEASE_RESET -#define __GPIOF_CLK_DISABLE __HAL_RCC_GPIOF_CLK_DISABLE -#define __GPIOF_CLK_ENABLE __HAL_RCC_GPIOF_CLK_ENABLE -#define __GPIOF_CLK_SLEEP_DISABLE __HAL_RCC_GPIOF_CLK_SLEEP_DISABLE -#define __GPIOF_CLK_SLEEP_ENABLE __HAL_RCC_GPIOF_CLK_SLEEP_ENABLE -#define __GPIOF_FORCE_RESET __HAL_RCC_GPIOF_FORCE_RESET -#define __GPIOF_RELEASE_RESET __HAL_RCC_GPIOF_RELEASE_RESET -#define __GPIOG_CLK_DISABLE __HAL_RCC_GPIOG_CLK_DISABLE -#define __GPIOG_CLK_ENABLE __HAL_RCC_GPIOG_CLK_ENABLE -#define __GPIOG_CLK_SLEEP_DISABLE __HAL_RCC_GPIOG_CLK_SLEEP_DISABLE -#define __GPIOG_CLK_SLEEP_ENABLE __HAL_RCC_GPIOG_CLK_SLEEP_ENABLE -#define __GPIOG_FORCE_RESET __HAL_RCC_GPIOG_FORCE_RESET -#define __GPIOG_RELEASE_RESET __HAL_RCC_GPIOG_RELEASE_RESET -#define __GPIOH_CLK_DISABLE __HAL_RCC_GPIOH_CLK_DISABLE -#define __GPIOH_CLK_ENABLE __HAL_RCC_GPIOH_CLK_ENABLE -#define __GPIOH_CLK_SLEEP_DISABLE __HAL_RCC_GPIOH_CLK_SLEEP_DISABLE -#define __GPIOH_CLK_SLEEP_ENABLE __HAL_RCC_GPIOH_CLK_SLEEP_ENABLE -#define __GPIOH_FORCE_RESET __HAL_RCC_GPIOH_FORCE_RESET -#define __GPIOH_RELEASE_RESET __HAL_RCC_GPIOH_RELEASE_RESET -#define __I2C1_CLK_DISABLE __HAL_RCC_I2C1_CLK_DISABLE -#define __I2C1_CLK_ENABLE __HAL_RCC_I2C1_CLK_ENABLE -#define __I2C1_CLK_SLEEP_DISABLE __HAL_RCC_I2C1_CLK_SLEEP_DISABLE -#define __I2C1_CLK_SLEEP_ENABLE __HAL_RCC_I2C1_CLK_SLEEP_ENABLE -#define __I2C1_FORCE_RESET __HAL_RCC_I2C1_FORCE_RESET -#define __I2C1_RELEASE_RESET __HAL_RCC_I2C1_RELEASE_RESET -#define __I2C2_CLK_DISABLE __HAL_RCC_I2C2_CLK_DISABLE -#define __I2C2_CLK_ENABLE __HAL_RCC_I2C2_CLK_ENABLE -#define __I2C2_CLK_SLEEP_DISABLE __HAL_RCC_I2C2_CLK_SLEEP_DISABLE -#define __I2C2_CLK_SLEEP_ENABLE __HAL_RCC_I2C2_CLK_SLEEP_ENABLE -#define __I2C2_FORCE_RESET __HAL_RCC_I2C2_FORCE_RESET -#define __I2C2_RELEASE_RESET __HAL_RCC_I2C2_RELEASE_RESET -#define __I2C3_CLK_DISABLE __HAL_RCC_I2C3_CLK_DISABLE -#define __I2C3_CLK_ENABLE __HAL_RCC_I2C3_CLK_ENABLE -#define __I2C3_CLK_SLEEP_DISABLE __HAL_RCC_I2C3_CLK_SLEEP_DISABLE -#define __I2C3_CLK_SLEEP_ENABLE __HAL_RCC_I2C3_CLK_SLEEP_ENABLE -#define __I2C3_FORCE_RESET __HAL_RCC_I2C3_FORCE_RESET -#define __I2C3_RELEASE_RESET __HAL_RCC_I2C3_RELEASE_RESET -#define __LCD_CLK_DISABLE __HAL_RCC_LCD_CLK_DISABLE -#define __LCD_CLK_ENABLE __HAL_RCC_LCD_CLK_ENABLE -#define __LCD_CLK_SLEEP_DISABLE __HAL_RCC_LCD_CLK_SLEEP_DISABLE -#define __LCD_CLK_SLEEP_ENABLE __HAL_RCC_LCD_CLK_SLEEP_ENABLE -#define __LCD_FORCE_RESET __HAL_RCC_LCD_FORCE_RESET -#define __LCD_RELEASE_RESET __HAL_RCC_LCD_RELEASE_RESET -#define __LPTIM1_CLK_DISABLE __HAL_RCC_LPTIM1_CLK_DISABLE -#define __LPTIM1_CLK_ENABLE __HAL_RCC_LPTIM1_CLK_ENABLE -#define __LPTIM1_CLK_SLEEP_DISABLE __HAL_RCC_LPTIM1_CLK_SLEEP_DISABLE -#define __LPTIM1_CLK_SLEEP_ENABLE __HAL_RCC_LPTIM1_CLK_SLEEP_ENABLE -#define __LPTIM1_FORCE_RESET __HAL_RCC_LPTIM1_FORCE_RESET -#define __LPTIM1_RELEASE_RESET __HAL_RCC_LPTIM1_RELEASE_RESET -#define __LPTIM2_CLK_DISABLE __HAL_RCC_LPTIM2_CLK_DISABLE -#define __LPTIM2_CLK_ENABLE __HAL_RCC_LPTIM2_CLK_ENABLE -#define __LPTIM2_CLK_SLEEP_DISABLE __HAL_RCC_LPTIM2_CLK_SLEEP_DISABLE -#define __LPTIM2_CLK_SLEEP_ENABLE __HAL_RCC_LPTIM2_CLK_SLEEP_ENABLE -#define __LPTIM2_FORCE_RESET __HAL_RCC_LPTIM2_FORCE_RESET -#define __LPTIM2_RELEASE_RESET __HAL_RCC_LPTIM2_RELEASE_RESET -#define __LPUART1_CLK_DISABLE __HAL_RCC_LPUART1_CLK_DISABLE -#define __LPUART1_CLK_ENABLE __HAL_RCC_LPUART1_CLK_ENABLE -#define __LPUART1_CLK_SLEEP_DISABLE __HAL_RCC_LPUART1_CLK_SLEEP_DISABLE -#define __LPUART1_CLK_SLEEP_ENABLE __HAL_RCC_LPUART1_CLK_SLEEP_ENABLE -#define __LPUART1_FORCE_RESET __HAL_RCC_LPUART1_FORCE_RESET -#define __LPUART1_RELEASE_RESET __HAL_RCC_LPUART1_RELEASE_RESET -#define __OPAMP_CLK_DISABLE __HAL_RCC_OPAMP_CLK_DISABLE -#define __OPAMP_CLK_ENABLE __HAL_RCC_OPAMP_CLK_ENABLE -#define __OPAMP_CLK_SLEEP_DISABLE __HAL_RCC_OPAMP_CLK_SLEEP_DISABLE -#define __OPAMP_CLK_SLEEP_ENABLE __HAL_RCC_OPAMP_CLK_SLEEP_ENABLE -#define __OPAMP_FORCE_RESET __HAL_RCC_OPAMP_FORCE_RESET -#define __OPAMP_RELEASE_RESET __HAL_RCC_OPAMP_RELEASE_RESET -#define __OTGFS_CLK_DISABLE __HAL_RCC_OTGFS_CLK_DISABLE -#define __OTGFS_CLK_ENABLE __HAL_RCC_OTGFS_CLK_ENABLE -#define __OTGFS_CLK_SLEEP_DISABLE __HAL_RCC_OTGFS_CLK_SLEEP_DISABLE -#define __OTGFS_CLK_SLEEP_ENABLE __HAL_RCC_OTGFS_CLK_SLEEP_ENABLE -#define __OTGFS_FORCE_RESET __HAL_RCC_OTGFS_FORCE_RESET -#define __OTGFS_RELEASE_RESET __HAL_RCC_OTGFS_RELEASE_RESET -#define __PWR_CLK_DISABLE __HAL_RCC_PWR_CLK_DISABLE -#define __PWR_CLK_ENABLE __HAL_RCC_PWR_CLK_ENABLE -#define __PWR_CLK_SLEEP_DISABLE __HAL_RCC_PWR_CLK_SLEEP_DISABLE -#define __PWR_CLK_SLEEP_ENABLE __HAL_RCC_PWR_CLK_SLEEP_ENABLE -#define __PWR_FORCE_RESET __HAL_RCC_PWR_FORCE_RESET -#define __PWR_RELEASE_RESET __HAL_RCC_PWR_RELEASE_RESET -#define __QSPI_CLK_DISABLE __HAL_RCC_QSPI_CLK_DISABLE -#define __QSPI_CLK_ENABLE __HAL_RCC_QSPI_CLK_ENABLE -#define __QSPI_CLK_SLEEP_DISABLE __HAL_RCC_QSPI_CLK_SLEEP_DISABLE -#define __QSPI_CLK_SLEEP_ENABLE __HAL_RCC_QSPI_CLK_SLEEP_ENABLE -#define __QSPI_FORCE_RESET __HAL_RCC_QSPI_FORCE_RESET -#define __QSPI_RELEASE_RESET __HAL_RCC_QSPI_RELEASE_RESET - -#if defined(STM32WB) -#define __HAL_RCC_QSPI_CLK_DISABLE __HAL_RCC_QUADSPI_CLK_DISABLE -#define __HAL_RCC_QSPI_CLK_ENABLE __HAL_RCC_QUADSPI_CLK_ENABLE -#define __HAL_RCC_QSPI_CLK_SLEEP_DISABLE __HAL_RCC_QUADSPI_CLK_SLEEP_DISABLE -#define __HAL_RCC_QSPI_CLK_SLEEP_ENABLE __HAL_RCC_QUADSPI_CLK_SLEEP_ENABLE -#define __HAL_RCC_QSPI_FORCE_RESET __HAL_RCC_QUADSPI_FORCE_RESET -#define __HAL_RCC_QSPI_RELEASE_RESET __HAL_RCC_QUADSPI_RELEASE_RESET -#define __HAL_RCC_QSPI_IS_CLK_ENABLED __HAL_RCC_QUADSPI_IS_CLK_ENABLED -#define __HAL_RCC_QSPI_IS_CLK_DISABLED __HAL_RCC_QUADSPI_IS_CLK_DISABLED -#define __HAL_RCC_QSPI_IS_CLK_SLEEP_ENABLED __HAL_RCC_QUADSPI_IS_CLK_SLEEP_ENABLED -#define __HAL_RCC_QSPI_IS_CLK_SLEEP_DISABLED __HAL_RCC_QUADSPI_IS_CLK_SLEEP_DISABLED -#define QSPI_IRQHandler QUADSPI_IRQHandler -#endif /* __HAL_RCC_QUADSPI_CLK_ENABLE */ - -#define __RNG_CLK_DISABLE __HAL_RCC_RNG_CLK_DISABLE -#define __RNG_CLK_ENABLE __HAL_RCC_RNG_CLK_ENABLE -#define __RNG_CLK_SLEEP_DISABLE __HAL_RCC_RNG_CLK_SLEEP_DISABLE -#define __RNG_CLK_SLEEP_ENABLE __HAL_RCC_RNG_CLK_SLEEP_ENABLE -#define __RNG_FORCE_RESET __HAL_RCC_RNG_FORCE_RESET -#define __RNG_RELEASE_RESET __HAL_RCC_RNG_RELEASE_RESET -#define __SAI1_CLK_DISABLE __HAL_RCC_SAI1_CLK_DISABLE -#define __SAI1_CLK_ENABLE __HAL_RCC_SAI1_CLK_ENABLE -#define __SAI1_CLK_SLEEP_DISABLE __HAL_RCC_SAI1_CLK_SLEEP_DISABLE -#define __SAI1_CLK_SLEEP_ENABLE __HAL_RCC_SAI1_CLK_SLEEP_ENABLE -#define __SAI1_FORCE_RESET __HAL_RCC_SAI1_FORCE_RESET -#define __SAI1_RELEASE_RESET __HAL_RCC_SAI1_RELEASE_RESET -#define __SAI2_CLK_DISABLE __HAL_RCC_SAI2_CLK_DISABLE -#define __SAI2_CLK_ENABLE __HAL_RCC_SAI2_CLK_ENABLE -#define __SAI2_CLK_SLEEP_DISABLE __HAL_RCC_SAI2_CLK_SLEEP_DISABLE -#define __SAI2_CLK_SLEEP_ENABLE __HAL_RCC_SAI2_CLK_SLEEP_ENABLE -#define __SAI2_FORCE_RESET __HAL_RCC_SAI2_FORCE_RESET -#define __SAI2_RELEASE_RESET __HAL_RCC_SAI2_RELEASE_RESET -#define __SDIO_CLK_DISABLE __HAL_RCC_SDIO_CLK_DISABLE -#define __SDIO_CLK_ENABLE __HAL_RCC_SDIO_CLK_ENABLE -#define __SDMMC_CLK_DISABLE __HAL_RCC_SDMMC_CLK_DISABLE -#define __SDMMC_CLK_ENABLE __HAL_RCC_SDMMC_CLK_ENABLE -#define __SDMMC_CLK_SLEEP_DISABLE __HAL_RCC_SDMMC_CLK_SLEEP_DISABLE -#define __SDMMC_CLK_SLEEP_ENABLE __HAL_RCC_SDMMC_CLK_SLEEP_ENABLE -#define __SDMMC_FORCE_RESET __HAL_RCC_SDMMC_FORCE_RESET -#define __SDMMC_RELEASE_RESET __HAL_RCC_SDMMC_RELEASE_RESET -#define __SPI1_CLK_DISABLE __HAL_RCC_SPI1_CLK_DISABLE -#define __SPI1_CLK_ENABLE __HAL_RCC_SPI1_CLK_ENABLE -#define __SPI1_CLK_SLEEP_DISABLE __HAL_RCC_SPI1_CLK_SLEEP_DISABLE -#define __SPI1_CLK_SLEEP_ENABLE __HAL_RCC_SPI1_CLK_SLEEP_ENABLE -#define __SPI1_FORCE_RESET __HAL_RCC_SPI1_FORCE_RESET -#define __SPI1_RELEASE_RESET __HAL_RCC_SPI1_RELEASE_RESET -#define __SPI2_CLK_DISABLE __HAL_RCC_SPI2_CLK_DISABLE -#define __SPI2_CLK_ENABLE __HAL_RCC_SPI2_CLK_ENABLE -#define __SPI2_CLK_SLEEP_DISABLE __HAL_RCC_SPI2_CLK_SLEEP_DISABLE -#define __SPI2_CLK_SLEEP_ENABLE __HAL_RCC_SPI2_CLK_SLEEP_ENABLE -#define __SPI2_FORCE_RESET __HAL_RCC_SPI2_FORCE_RESET -#define __SPI2_RELEASE_RESET __HAL_RCC_SPI2_RELEASE_RESET -#define __SPI3_CLK_DISABLE __HAL_RCC_SPI3_CLK_DISABLE -#define __SPI3_CLK_ENABLE __HAL_RCC_SPI3_CLK_ENABLE -#define __SPI3_CLK_SLEEP_DISABLE __HAL_RCC_SPI3_CLK_SLEEP_DISABLE -#define __SPI3_CLK_SLEEP_ENABLE __HAL_RCC_SPI3_CLK_SLEEP_ENABLE -#define __SPI3_FORCE_RESET __HAL_RCC_SPI3_FORCE_RESET -#define __SPI3_RELEASE_RESET __HAL_RCC_SPI3_RELEASE_RESET -#define __SRAM_CLK_DISABLE __HAL_RCC_SRAM_CLK_DISABLE -#define __SRAM_CLK_ENABLE __HAL_RCC_SRAM_CLK_ENABLE -#define __SRAM1_CLK_SLEEP_DISABLE __HAL_RCC_SRAM1_CLK_SLEEP_DISABLE -#define __SRAM1_CLK_SLEEP_ENABLE __HAL_RCC_SRAM1_CLK_SLEEP_ENABLE -#define __SRAM2_CLK_SLEEP_DISABLE __HAL_RCC_SRAM2_CLK_SLEEP_DISABLE -#define __SRAM2_CLK_SLEEP_ENABLE __HAL_RCC_SRAM2_CLK_SLEEP_ENABLE -#define __SWPMI1_CLK_DISABLE __HAL_RCC_SWPMI1_CLK_DISABLE -#define __SWPMI1_CLK_ENABLE __HAL_RCC_SWPMI1_CLK_ENABLE -#define __SWPMI1_CLK_SLEEP_DISABLE __HAL_RCC_SWPMI1_CLK_SLEEP_DISABLE -#define __SWPMI1_CLK_SLEEP_ENABLE __HAL_RCC_SWPMI1_CLK_SLEEP_ENABLE -#define __SWPMI1_FORCE_RESET __HAL_RCC_SWPMI1_FORCE_RESET -#define __SWPMI1_RELEASE_RESET __HAL_RCC_SWPMI1_RELEASE_RESET -#define __SYSCFG_CLK_DISABLE __HAL_RCC_SYSCFG_CLK_DISABLE -#define __SYSCFG_CLK_ENABLE __HAL_RCC_SYSCFG_CLK_ENABLE -#define __SYSCFG_CLK_SLEEP_DISABLE __HAL_RCC_SYSCFG_CLK_SLEEP_DISABLE -#define __SYSCFG_CLK_SLEEP_ENABLE __HAL_RCC_SYSCFG_CLK_SLEEP_ENABLE -#define __SYSCFG_FORCE_RESET __HAL_RCC_SYSCFG_FORCE_RESET -#define __SYSCFG_RELEASE_RESET __HAL_RCC_SYSCFG_RELEASE_RESET -#define __TIM1_CLK_DISABLE __HAL_RCC_TIM1_CLK_DISABLE -#define __TIM1_CLK_ENABLE __HAL_RCC_TIM1_CLK_ENABLE -#define __TIM1_CLK_SLEEP_DISABLE __HAL_RCC_TIM1_CLK_SLEEP_DISABLE -#define __TIM1_CLK_SLEEP_ENABLE __HAL_RCC_TIM1_CLK_SLEEP_ENABLE -#define __TIM1_FORCE_RESET __HAL_RCC_TIM1_FORCE_RESET -#define __TIM1_RELEASE_RESET __HAL_RCC_TIM1_RELEASE_RESET -#define __TIM10_CLK_DISABLE __HAL_RCC_TIM10_CLK_DISABLE -#define __TIM10_CLK_ENABLE __HAL_RCC_TIM10_CLK_ENABLE -#define __TIM10_FORCE_RESET __HAL_RCC_TIM10_FORCE_RESET -#define __TIM10_RELEASE_RESET __HAL_RCC_TIM10_RELEASE_RESET -#define __TIM11_CLK_DISABLE __HAL_RCC_TIM11_CLK_DISABLE -#define __TIM11_CLK_ENABLE __HAL_RCC_TIM11_CLK_ENABLE -#define __TIM11_FORCE_RESET __HAL_RCC_TIM11_FORCE_RESET -#define __TIM11_RELEASE_RESET __HAL_RCC_TIM11_RELEASE_RESET -#define __TIM12_CLK_DISABLE __HAL_RCC_TIM12_CLK_DISABLE -#define __TIM12_CLK_ENABLE __HAL_RCC_TIM12_CLK_ENABLE -#define __TIM12_FORCE_RESET __HAL_RCC_TIM12_FORCE_RESET -#define __TIM12_RELEASE_RESET __HAL_RCC_TIM12_RELEASE_RESET -#define __TIM13_CLK_DISABLE __HAL_RCC_TIM13_CLK_DISABLE -#define __TIM13_CLK_ENABLE __HAL_RCC_TIM13_CLK_ENABLE -#define __TIM13_FORCE_RESET __HAL_RCC_TIM13_FORCE_RESET -#define __TIM13_RELEASE_RESET __HAL_RCC_TIM13_RELEASE_RESET -#define __TIM14_CLK_DISABLE __HAL_RCC_TIM14_CLK_DISABLE -#define __TIM14_CLK_ENABLE __HAL_RCC_TIM14_CLK_ENABLE -#define __TIM14_FORCE_RESET __HAL_RCC_TIM14_FORCE_RESET -#define __TIM14_RELEASE_RESET __HAL_RCC_TIM14_RELEASE_RESET -#define __TIM15_CLK_DISABLE __HAL_RCC_TIM15_CLK_DISABLE -#define __TIM15_CLK_ENABLE __HAL_RCC_TIM15_CLK_ENABLE -#define __TIM15_CLK_SLEEP_DISABLE __HAL_RCC_TIM15_CLK_SLEEP_DISABLE -#define __TIM15_CLK_SLEEP_ENABLE __HAL_RCC_TIM15_CLK_SLEEP_ENABLE -#define __TIM15_FORCE_RESET __HAL_RCC_TIM15_FORCE_RESET -#define __TIM15_RELEASE_RESET __HAL_RCC_TIM15_RELEASE_RESET -#define __TIM16_CLK_DISABLE __HAL_RCC_TIM16_CLK_DISABLE -#define __TIM16_CLK_ENABLE __HAL_RCC_TIM16_CLK_ENABLE -#define __TIM16_CLK_SLEEP_DISABLE __HAL_RCC_TIM16_CLK_SLEEP_DISABLE -#define __TIM16_CLK_SLEEP_ENABLE __HAL_RCC_TIM16_CLK_SLEEP_ENABLE -#define __TIM16_FORCE_RESET __HAL_RCC_TIM16_FORCE_RESET -#define __TIM16_RELEASE_RESET __HAL_RCC_TIM16_RELEASE_RESET -#define __TIM17_CLK_DISABLE __HAL_RCC_TIM17_CLK_DISABLE -#define __TIM17_CLK_ENABLE __HAL_RCC_TIM17_CLK_ENABLE -#define __TIM17_CLK_SLEEP_DISABLE __HAL_RCC_TIM17_CLK_SLEEP_DISABLE -#define __TIM17_CLK_SLEEP_ENABLE __HAL_RCC_TIM17_CLK_SLEEP_ENABLE -#define __TIM17_FORCE_RESET __HAL_RCC_TIM17_FORCE_RESET -#define __TIM17_RELEASE_RESET __HAL_RCC_TIM17_RELEASE_RESET -#define __TIM2_CLK_DISABLE __HAL_RCC_TIM2_CLK_DISABLE -#define __TIM2_CLK_ENABLE __HAL_RCC_TIM2_CLK_ENABLE -#define __TIM2_CLK_SLEEP_DISABLE __HAL_RCC_TIM2_CLK_SLEEP_DISABLE -#define __TIM2_CLK_SLEEP_ENABLE __HAL_RCC_TIM2_CLK_SLEEP_ENABLE -#define __TIM2_FORCE_RESET __HAL_RCC_TIM2_FORCE_RESET -#define __TIM2_RELEASE_RESET __HAL_RCC_TIM2_RELEASE_RESET -#define __TIM3_CLK_DISABLE __HAL_RCC_TIM3_CLK_DISABLE -#define __TIM3_CLK_ENABLE __HAL_RCC_TIM3_CLK_ENABLE -#define __TIM3_CLK_SLEEP_DISABLE __HAL_RCC_TIM3_CLK_SLEEP_DISABLE -#define __TIM3_CLK_SLEEP_ENABLE __HAL_RCC_TIM3_CLK_SLEEP_ENABLE -#define __TIM3_FORCE_RESET __HAL_RCC_TIM3_FORCE_RESET -#define __TIM3_RELEASE_RESET __HAL_RCC_TIM3_RELEASE_RESET -#define __TIM4_CLK_DISABLE __HAL_RCC_TIM4_CLK_DISABLE -#define __TIM4_CLK_ENABLE __HAL_RCC_TIM4_CLK_ENABLE -#define __TIM4_CLK_SLEEP_DISABLE __HAL_RCC_TIM4_CLK_SLEEP_DISABLE -#define __TIM4_CLK_SLEEP_ENABLE __HAL_RCC_TIM4_CLK_SLEEP_ENABLE -#define __TIM4_FORCE_RESET __HAL_RCC_TIM4_FORCE_RESET -#define __TIM4_RELEASE_RESET __HAL_RCC_TIM4_RELEASE_RESET -#define __TIM5_CLK_DISABLE __HAL_RCC_TIM5_CLK_DISABLE -#define __TIM5_CLK_ENABLE __HAL_RCC_TIM5_CLK_ENABLE -#define __TIM5_CLK_SLEEP_DISABLE __HAL_RCC_TIM5_CLK_SLEEP_DISABLE -#define __TIM5_CLK_SLEEP_ENABLE __HAL_RCC_TIM5_CLK_SLEEP_ENABLE -#define __TIM5_FORCE_RESET __HAL_RCC_TIM5_FORCE_RESET -#define __TIM5_RELEASE_RESET __HAL_RCC_TIM5_RELEASE_RESET -#define __TIM6_CLK_DISABLE __HAL_RCC_TIM6_CLK_DISABLE -#define __TIM6_CLK_ENABLE __HAL_RCC_TIM6_CLK_ENABLE -#define __TIM6_CLK_SLEEP_DISABLE __HAL_RCC_TIM6_CLK_SLEEP_DISABLE -#define __TIM6_CLK_SLEEP_ENABLE __HAL_RCC_TIM6_CLK_SLEEP_ENABLE -#define __TIM6_FORCE_RESET __HAL_RCC_TIM6_FORCE_RESET -#define __TIM6_RELEASE_RESET __HAL_RCC_TIM6_RELEASE_RESET -#define __TIM7_CLK_DISABLE __HAL_RCC_TIM7_CLK_DISABLE -#define __TIM7_CLK_ENABLE __HAL_RCC_TIM7_CLK_ENABLE -#define __TIM7_CLK_SLEEP_DISABLE __HAL_RCC_TIM7_CLK_SLEEP_DISABLE -#define __TIM7_CLK_SLEEP_ENABLE __HAL_RCC_TIM7_CLK_SLEEP_ENABLE -#define __TIM7_FORCE_RESET __HAL_RCC_TIM7_FORCE_RESET -#define __TIM7_RELEASE_RESET __HAL_RCC_TIM7_RELEASE_RESET -#define __TIM8_CLK_DISABLE __HAL_RCC_TIM8_CLK_DISABLE -#define __TIM8_CLK_ENABLE __HAL_RCC_TIM8_CLK_ENABLE -#define __TIM8_CLK_SLEEP_DISABLE __HAL_RCC_TIM8_CLK_SLEEP_DISABLE -#define __TIM8_CLK_SLEEP_ENABLE __HAL_RCC_TIM8_CLK_SLEEP_ENABLE -#define __TIM8_FORCE_RESET __HAL_RCC_TIM8_FORCE_RESET -#define __TIM8_RELEASE_RESET __HAL_RCC_TIM8_RELEASE_RESET -#define __TIM9_CLK_DISABLE __HAL_RCC_TIM9_CLK_DISABLE -#define __TIM9_CLK_ENABLE __HAL_RCC_TIM9_CLK_ENABLE -#define __TIM9_FORCE_RESET __HAL_RCC_TIM9_FORCE_RESET -#define __TIM9_RELEASE_RESET __HAL_RCC_TIM9_RELEASE_RESET -#define __TSC_CLK_DISABLE __HAL_RCC_TSC_CLK_DISABLE -#define __TSC_CLK_ENABLE __HAL_RCC_TSC_CLK_ENABLE -#define __TSC_CLK_SLEEP_DISABLE __HAL_RCC_TSC_CLK_SLEEP_DISABLE -#define __TSC_CLK_SLEEP_ENABLE __HAL_RCC_TSC_CLK_SLEEP_ENABLE -#define __TSC_FORCE_RESET __HAL_RCC_TSC_FORCE_RESET -#define __TSC_RELEASE_RESET __HAL_RCC_TSC_RELEASE_RESET -#define __UART4_CLK_DISABLE __HAL_RCC_UART4_CLK_DISABLE -#define __UART4_CLK_ENABLE __HAL_RCC_UART4_CLK_ENABLE -#define __UART4_CLK_SLEEP_DISABLE __HAL_RCC_UART4_CLK_SLEEP_DISABLE -#define __UART4_CLK_SLEEP_ENABLE __HAL_RCC_UART4_CLK_SLEEP_ENABLE -#define __UART4_FORCE_RESET __HAL_RCC_UART4_FORCE_RESET -#define __UART4_RELEASE_RESET __HAL_RCC_UART4_RELEASE_RESET -#define __UART5_CLK_DISABLE __HAL_RCC_UART5_CLK_DISABLE -#define __UART5_CLK_ENABLE __HAL_RCC_UART5_CLK_ENABLE -#define __UART5_CLK_SLEEP_DISABLE __HAL_RCC_UART5_CLK_SLEEP_DISABLE -#define __UART5_CLK_SLEEP_ENABLE __HAL_RCC_UART5_CLK_SLEEP_ENABLE -#define __UART5_FORCE_RESET __HAL_RCC_UART5_FORCE_RESET -#define __UART5_RELEASE_RESET __HAL_RCC_UART5_RELEASE_RESET -#define __USART1_CLK_DISABLE __HAL_RCC_USART1_CLK_DISABLE -#define __USART1_CLK_ENABLE __HAL_RCC_USART1_CLK_ENABLE -#define __USART1_CLK_SLEEP_DISABLE __HAL_RCC_USART1_CLK_SLEEP_DISABLE -#define __USART1_CLK_SLEEP_ENABLE __HAL_RCC_USART1_CLK_SLEEP_ENABLE -#define __USART1_FORCE_RESET __HAL_RCC_USART1_FORCE_RESET -#define __USART1_RELEASE_RESET __HAL_RCC_USART1_RELEASE_RESET -#define __USART2_CLK_DISABLE __HAL_RCC_USART2_CLK_DISABLE -#define __USART2_CLK_ENABLE __HAL_RCC_USART2_CLK_ENABLE -#define __USART2_CLK_SLEEP_DISABLE __HAL_RCC_USART2_CLK_SLEEP_DISABLE -#define __USART2_CLK_SLEEP_ENABLE __HAL_RCC_USART2_CLK_SLEEP_ENABLE -#define __USART2_FORCE_RESET __HAL_RCC_USART2_FORCE_RESET -#define __USART2_RELEASE_RESET __HAL_RCC_USART2_RELEASE_RESET -#define __USART3_CLK_DISABLE __HAL_RCC_USART3_CLK_DISABLE -#define __USART3_CLK_ENABLE __HAL_RCC_USART3_CLK_ENABLE -#define __USART3_CLK_SLEEP_DISABLE __HAL_RCC_USART3_CLK_SLEEP_DISABLE -#define __USART3_CLK_SLEEP_ENABLE __HAL_RCC_USART3_CLK_SLEEP_ENABLE -#define __USART3_FORCE_RESET __HAL_RCC_USART3_FORCE_RESET -#define __USART3_RELEASE_RESET __HAL_RCC_USART3_RELEASE_RESET -#define __USART4_CLK_DISABLE __HAL_RCC_UART4_CLK_DISABLE -#define __USART4_CLK_ENABLE __HAL_RCC_UART4_CLK_ENABLE -#define __USART4_CLK_SLEEP_ENABLE __HAL_RCC_UART4_CLK_SLEEP_ENABLE -#define __USART4_CLK_SLEEP_DISABLE __HAL_RCC_UART4_CLK_SLEEP_DISABLE -#define __USART4_FORCE_RESET __HAL_RCC_UART4_FORCE_RESET -#define __USART4_RELEASE_RESET __HAL_RCC_UART4_RELEASE_RESET -#define __USART5_CLK_DISABLE __HAL_RCC_UART5_CLK_DISABLE -#define __USART5_CLK_ENABLE __HAL_RCC_UART5_CLK_ENABLE -#define __USART5_CLK_SLEEP_ENABLE __HAL_RCC_UART5_CLK_SLEEP_ENABLE -#define __USART5_CLK_SLEEP_DISABLE __HAL_RCC_UART5_CLK_SLEEP_DISABLE -#define __USART5_FORCE_RESET __HAL_RCC_UART5_FORCE_RESET -#define __USART5_RELEASE_RESET __HAL_RCC_UART5_RELEASE_RESET -#define __USART7_CLK_DISABLE __HAL_RCC_UART7_CLK_DISABLE -#define __USART7_CLK_ENABLE __HAL_RCC_UART7_CLK_ENABLE -#define __USART7_FORCE_RESET __HAL_RCC_UART7_FORCE_RESET -#define __USART7_RELEASE_RESET __HAL_RCC_UART7_RELEASE_RESET -#define __USART8_CLK_DISABLE __HAL_RCC_UART8_CLK_DISABLE -#define __USART8_CLK_ENABLE __HAL_RCC_UART8_CLK_ENABLE -#define __USART8_FORCE_RESET __HAL_RCC_UART8_FORCE_RESET -#define __USART8_RELEASE_RESET __HAL_RCC_UART8_RELEASE_RESET -#define __USB_CLK_DISABLE __HAL_RCC_USB_CLK_DISABLE -#define __USB_CLK_ENABLE __HAL_RCC_USB_CLK_ENABLE -#define __USB_FORCE_RESET __HAL_RCC_USB_FORCE_RESET -#define __USB_CLK_SLEEP_ENABLE __HAL_RCC_USB_CLK_SLEEP_ENABLE -#define __USB_CLK_SLEEP_DISABLE __HAL_RCC_USB_CLK_SLEEP_DISABLE -#define __USB_OTG_FS_CLK_DISABLE __HAL_RCC_USB_OTG_FS_CLK_DISABLE -#define __USB_OTG_FS_CLK_ENABLE __HAL_RCC_USB_OTG_FS_CLK_ENABLE -#define __USB_RELEASE_RESET __HAL_RCC_USB_RELEASE_RESET - -#if defined(STM32H7) -#define __HAL_RCC_WWDG_CLK_DISABLE __HAL_RCC_WWDG1_CLK_DISABLE -#define __HAL_RCC_WWDG_CLK_ENABLE __HAL_RCC_WWDG1_CLK_ENABLE -#define __HAL_RCC_WWDG_CLK_SLEEP_DISABLE __HAL_RCC_WWDG1_CLK_SLEEP_DISABLE -#define __HAL_RCC_WWDG_CLK_SLEEP_ENABLE __HAL_RCC_WWDG1_CLK_SLEEP_ENABLE - -#define __HAL_RCC_WWDG_FORCE_RESET ((void)0U) /* Not available on the STM32H7*/ -#define __HAL_RCC_WWDG_RELEASE_RESET ((void)0U) /* Not available on the STM32H7*/ - - -#define __HAL_RCC_WWDG_IS_CLK_ENABLED __HAL_RCC_WWDG1_IS_CLK_ENABLED -#define __HAL_RCC_WWDG_IS_CLK_DISABLED __HAL_RCC_WWDG1_IS_CLK_DISABLED -#endif - -#define __WWDG_CLK_DISABLE __HAL_RCC_WWDG_CLK_DISABLE -#define __WWDG_CLK_ENABLE __HAL_RCC_WWDG_CLK_ENABLE -#define __WWDG_CLK_SLEEP_DISABLE __HAL_RCC_WWDG_CLK_SLEEP_DISABLE -#define __WWDG_CLK_SLEEP_ENABLE __HAL_RCC_WWDG_CLK_SLEEP_ENABLE -#define __WWDG_FORCE_RESET __HAL_RCC_WWDG_FORCE_RESET -#define __WWDG_RELEASE_RESET __HAL_RCC_WWDG_RELEASE_RESET - -#define __TIM21_CLK_ENABLE __HAL_RCC_TIM21_CLK_ENABLE -#define __TIM21_CLK_DISABLE __HAL_RCC_TIM21_CLK_DISABLE -#define __TIM21_FORCE_RESET __HAL_RCC_TIM21_FORCE_RESET -#define __TIM21_RELEASE_RESET __HAL_RCC_TIM21_RELEASE_RESET -#define __TIM21_CLK_SLEEP_ENABLE __HAL_RCC_TIM21_CLK_SLEEP_ENABLE -#define __TIM21_CLK_SLEEP_DISABLE __HAL_RCC_TIM21_CLK_SLEEP_DISABLE -#define __TIM22_CLK_ENABLE __HAL_RCC_TIM22_CLK_ENABLE -#define __TIM22_CLK_DISABLE __HAL_RCC_TIM22_CLK_DISABLE -#define __TIM22_FORCE_RESET __HAL_RCC_TIM22_FORCE_RESET -#define __TIM22_RELEASE_RESET __HAL_RCC_TIM22_RELEASE_RESET -#define __TIM22_CLK_SLEEP_ENABLE __HAL_RCC_TIM22_CLK_SLEEP_ENABLE -#define __TIM22_CLK_SLEEP_DISABLE __HAL_RCC_TIM22_CLK_SLEEP_DISABLE -#define __CRS_CLK_DISABLE __HAL_RCC_CRS_CLK_DISABLE -#define __CRS_CLK_ENABLE __HAL_RCC_CRS_CLK_ENABLE -#define __CRS_CLK_SLEEP_DISABLE __HAL_RCC_CRS_CLK_SLEEP_DISABLE -#define __CRS_CLK_SLEEP_ENABLE __HAL_RCC_CRS_CLK_SLEEP_ENABLE -#define __CRS_FORCE_RESET __HAL_RCC_CRS_FORCE_RESET -#define __CRS_RELEASE_RESET __HAL_RCC_CRS_RELEASE_RESET -#define __RCC_BACKUPRESET_FORCE __HAL_RCC_BACKUPRESET_FORCE -#define __RCC_BACKUPRESET_RELEASE __HAL_RCC_BACKUPRESET_RELEASE - -#define __USB_OTG_FS_FORCE_RESET __HAL_RCC_USB_OTG_FS_FORCE_RESET -#define __USB_OTG_FS_RELEASE_RESET __HAL_RCC_USB_OTG_FS_RELEASE_RESET -#define __USB_OTG_FS_CLK_SLEEP_ENABLE __HAL_RCC_USB_OTG_FS_CLK_SLEEP_ENABLE -#define __USB_OTG_FS_CLK_SLEEP_DISABLE __HAL_RCC_USB_OTG_FS_CLK_SLEEP_DISABLE -#define __USB_OTG_HS_CLK_DISABLE __HAL_RCC_USB_OTG_HS_CLK_DISABLE -#define __USB_OTG_HS_CLK_ENABLE __HAL_RCC_USB_OTG_HS_CLK_ENABLE -#define __USB_OTG_HS_ULPI_CLK_ENABLE __HAL_RCC_USB_OTG_HS_ULPI_CLK_ENABLE -#define __USB_OTG_HS_ULPI_CLK_DISABLE __HAL_RCC_USB_OTG_HS_ULPI_CLK_DISABLE -#define __TIM9_CLK_SLEEP_ENABLE __HAL_RCC_TIM9_CLK_SLEEP_ENABLE -#define __TIM9_CLK_SLEEP_DISABLE __HAL_RCC_TIM9_CLK_SLEEP_DISABLE -#define __TIM10_CLK_SLEEP_ENABLE __HAL_RCC_TIM10_CLK_SLEEP_ENABLE -#define __TIM10_CLK_SLEEP_DISABLE __HAL_RCC_TIM10_CLK_SLEEP_DISABLE -#define __TIM11_CLK_SLEEP_ENABLE __HAL_RCC_TIM11_CLK_SLEEP_ENABLE -#define __TIM11_CLK_SLEEP_DISABLE __HAL_RCC_TIM11_CLK_SLEEP_DISABLE -#define __ETHMACPTP_CLK_SLEEP_ENABLE __HAL_RCC_ETHMACPTP_CLK_SLEEP_ENABLE -#define __ETHMACPTP_CLK_SLEEP_DISABLE __HAL_RCC_ETHMACPTP_CLK_SLEEP_DISABLE -#define __ETHMACPTP_CLK_ENABLE __HAL_RCC_ETHMACPTP_CLK_ENABLE -#define __ETHMACPTP_CLK_DISABLE __HAL_RCC_ETHMACPTP_CLK_DISABLE -#define __HASH_CLK_ENABLE __HAL_RCC_HASH_CLK_ENABLE -#define __HASH_FORCE_RESET __HAL_RCC_HASH_FORCE_RESET -#define __HASH_RELEASE_RESET __HAL_RCC_HASH_RELEASE_RESET -#define __HASH_CLK_SLEEP_ENABLE __HAL_RCC_HASH_CLK_SLEEP_ENABLE -#define __HASH_CLK_SLEEP_DISABLE __HAL_RCC_HASH_CLK_SLEEP_DISABLE -#define __HASH_CLK_DISABLE __HAL_RCC_HASH_CLK_DISABLE -#define __SPI5_CLK_ENABLE __HAL_RCC_SPI5_CLK_ENABLE -#define __SPI5_CLK_DISABLE __HAL_RCC_SPI5_CLK_DISABLE -#define __SPI5_FORCE_RESET __HAL_RCC_SPI5_FORCE_RESET -#define __SPI5_RELEASE_RESET __HAL_RCC_SPI5_RELEASE_RESET -#define __SPI5_CLK_SLEEP_ENABLE __HAL_RCC_SPI5_CLK_SLEEP_ENABLE -#define __SPI5_CLK_SLEEP_DISABLE __HAL_RCC_SPI5_CLK_SLEEP_DISABLE -#define __SPI6_CLK_ENABLE __HAL_RCC_SPI6_CLK_ENABLE -#define __SPI6_CLK_DISABLE __HAL_RCC_SPI6_CLK_DISABLE -#define __SPI6_FORCE_RESET __HAL_RCC_SPI6_FORCE_RESET -#define __SPI6_RELEASE_RESET __HAL_RCC_SPI6_RELEASE_RESET -#define __SPI6_CLK_SLEEP_ENABLE __HAL_RCC_SPI6_CLK_SLEEP_ENABLE -#define __SPI6_CLK_SLEEP_DISABLE __HAL_RCC_SPI6_CLK_SLEEP_DISABLE -#define __LTDC_CLK_ENABLE __HAL_RCC_LTDC_CLK_ENABLE -#define __LTDC_CLK_DISABLE __HAL_RCC_LTDC_CLK_DISABLE -#define __LTDC_FORCE_RESET __HAL_RCC_LTDC_FORCE_RESET -#define __LTDC_RELEASE_RESET __HAL_RCC_LTDC_RELEASE_RESET -#define __LTDC_CLK_SLEEP_ENABLE __HAL_RCC_LTDC_CLK_SLEEP_ENABLE -#define __ETHMAC_CLK_SLEEP_ENABLE __HAL_RCC_ETHMAC_CLK_SLEEP_ENABLE -#define __ETHMAC_CLK_SLEEP_DISABLE __HAL_RCC_ETHMAC_CLK_SLEEP_DISABLE -#define __ETHMACTX_CLK_SLEEP_ENABLE __HAL_RCC_ETHMACTX_CLK_SLEEP_ENABLE -#define __ETHMACTX_CLK_SLEEP_DISABLE __HAL_RCC_ETHMACTX_CLK_SLEEP_DISABLE -#define __ETHMACRX_CLK_SLEEP_ENABLE __HAL_RCC_ETHMACRX_CLK_SLEEP_ENABLE -#define __ETHMACRX_CLK_SLEEP_DISABLE __HAL_RCC_ETHMACRX_CLK_SLEEP_DISABLE -#define __TIM12_CLK_SLEEP_ENABLE __HAL_RCC_TIM12_CLK_SLEEP_ENABLE -#define __TIM12_CLK_SLEEP_DISABLE __HAL_RCC_TIM12_CLK_SLEEP_DISABLE -#define __TIM13_CLK_SLEEP_ENABLE __HAL_RCC_TIM13_CLK_SLEEP_ENABLE -#define __TIM13_CLK_SLEEP_DISABLE __HAL_RCC_TIM13_CLK_SLEEP_DISABLE -#define __TIM14_CLK_SLEEP_ENABLE __HAL_RCC_TIM14_CLK_SLEEP_ENABLE -#define __TIM14_CLK_SLEEP_DISABLE __HAL_RCC_TIM14_CLK_SLEEP_DISABLE -#define __BKPSRAM_CLK_ENABLE __HAL_RCC_BKPSRAM_CLK_ENABLE -#define __BKPSRAM_CLK_DISABLE __HAL_RCC_BKPSRAM_CLK_DISABLE -#define __BKPSRAM_CLK_SLEEP_ENABLE __HAL_RCC_BKPSRAM_CLK_SLEEP_ENABLE -#define __BKPSRAM_CLK_SLEEP_DISABLE __HAL_RCC_BKPSRAM_CLK_SLEEP_DISABLE -#define __CCMDATARAMEN_CLK_ENABLE __HAL_RCC_CCMDATARAMEN_CLK_ENABLE -#define __CCMDATARAMEN_CLK_DISABLE __HAL_RCC_CCMDATARAMEN_CLK_DISABLE -#define __USART6_CLK_ENABLE __HAL_RCC_USART6_CLK_ENABLE -#define __USART6_CLK_DISABLE __HAL_RCC_USART6_CLK_DISABLE -#define __USART6_FORCE_RESET __HAL_RCC_USART6_FORCE_RESET -#define __USART6_RELEASE_RESET __HAL_RCC_USART6_RELEASE_RESET -#define __USART6_CLK_SLEEP_ENABLE __HAL_RCC_USART6_CLK_SLEEP_ENABLE -#define __USART6_CLK_SLEEP_DISABLE __HAL_RCC_USART6_CLK_SLEEP_DISABLE -#define __SPI4_CLK_ENABLE __HAL_RCC_SPI4_CLK_ENABLE -#define __SPI4_CLK_DISABLE __HAL_RCC_SPI4_CLK_DISABLE -#define __SPI4_FORCE_RESET __HAL_RCC_SPI4_FORCE_RESET -#define __SPI4_RELEASE_RESET __HAL_RCC_SPI4_RELEASE_RESET -#define __SPI4_CLK_SLEEP_ENABLE __HAL_RCC_SPI4_CLK_SLEEP_ENABLE -#define __SPI4_CLK_SLEEP_DISABLE __HAL_RCC_SPI4_CLK_SLEEP_DISABLE -#define __GPIOI_CLK_ENABLE __HAL_RCC_GPIOI_CLK_ENABLE -#define __GPIOI_CLK_DISABLE __HAL_RCC_GPIOI_CLK_DISABLE -#define __GPIOI_FORCE_RESET __HAL_RCC_GPIOI_FORCE_RESET -#define __GPIOI_RELEASE_RESET __HAL_RCC_GPIOI_RELEASE_RESET -#define __GPIOI_CLK_SLEEP_ENABLE __HAL_RCC_GPIOI_CLK_SLEEP_ENABLE -#define __GPIOI_CLK_SLEEP_DISABLE __HAL_RCC_GPIOI_CLK_SLEEP_DISABLE -#define __GPIOJ_CLK_ENABLE __HAL_RCC_GPIOJ_CLK_ENABLE -#define __GPIOJ_CLK_DISABLE __HAL_RCC_GPIOJ_CLK_DISABLE -#define __GPIOJ_FORCE_RESET __HAL_RCC_GPIOJ_FORCE_RESET -#define __GPIOJ_RELEASE_RESET __HAL_RCC_GPIOJ_RELEASE_RESET -#define __GPIOJ_CLK_SLEEP_ENABLE __HAL_RCC_GPIOJ_CLK_SLEEP_ENABLE -#define __GPIOJ_CLK_SLEEP_DISABLE __HAL_RCC_GPIOJ_CLK_SLEEP_DISABLE -#define __GPIOK_CLK_ENABLE __HAL_RCC_GPIOK_CLK_ENABLE -#define __GPIOK_CLK_DISABLE __HAL_RCC_GPIOK_CLK_DISABLE -#define __GPIOK_RELEASE_RESET __HAL_RCC_GPIOK_RELEASE_RESET -#define __GPIOK_CLK_SLEEP_ENABLE __HAL_RCC_GPIOK_CLK_SLEEP_ENABLE -#define __GPIOK_CLK_SLEEP_DISABLE __HAL_RCC_GPIOK_CLK_SLEEP_DISABLE -#define __ETH_CLK_ENABLE __HAL_RCC_ETH_CLK_ENABLE -#define __ETH_CLK_DISABLE __HAL_RCC_ETH_CLK_DISABLE -#define __DCMI_CLK_ENABLE __HAL_RCC_DCMI_CLK_ENABLE -#define __DCMI_CLK_DISABLE __HAL_RCC_DCMI_CLK_DISABLE -#define __DCMI_FORCE_RESET __HAL_RCC_DCMI_FORCE_RESET -#define __DCMI_RELEASE_RESET __HAL_RCC_DCMI_RELEASE_RESET -#define __DCMI_CLK_SLEEP_ENABLE __HAL_RCC_DCMI_CLK_SLEEP_ENABLE -#define __DCMI_CLK_SLEEP_DISABLE __HAL_RCC_DCMI_CLK_SLEEP_DISABLE -#define __UART7_CLK_ENABLE __HAL_RCC_UART7_CLK_ENABLE -#define __UART7_CLK_DISABLE __HAL_RCC_UART7_CLK_DISABLE -#define __UART7_RELEASE_RESET __HAL_RCC_UART7_RELEASE_RESET -#define __UART7_FORCE_RESET __HAL_RCC_UART7_FORCE_RESET -#define __UART7_CLK_SLEEP_ENABLE __HAL_RCC_UART7_CLK_SLEEP_ENABLE -#define __UART7_CLK_SLEEP_DISABLE __HAL_RCC_UART7_CLK_SLEEP_DISABLE -#define __UART8_CLK_ENABLE __HAL_RCC_UART8_CLK_ENABLE -#define __UART8_CLK_DISABLE __HAL_RCC_UART8_CLK_DISABLE -#define __UART8_FORCE_RESET __HAL_RCC_UART8_FORCE_RESET -#define __UART8_RELEASE_RESET __HAL_RCC_UART8_RELEASE_RESET -#define __UART8_CLK_SLEEP_ENABLE __HAL_RCC_UART8_CLK_SLEEP_ENABLE -#define __UART8_CLK_SLEEP_DISABLE __HAL_RCC_UART8_CLK_SLEEP_DISABLE -#define __OTGHS_CLK_SLEEP_ENABLE __HAL_RCC_USB_OTG_HS_CLK_SLEEP_ENABLE -#define __OTGHS_CLK_SLEEP_DISABLE __HAL_RCC_USB_OTG_HS_CLK_SLEEP_DISABLE -#define __OTGHS_FORCE_RESET __HAL_RCC_USB_OTG_HS_FORCE_RESET -#define __OTGHS_RELEASE_RESET __HAL_RCC_USB_OTG_HS_RELEASE_RESET -#define __OTGHSULPI_CLK_SLEEP_ENABLE __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_ENABLE -#define __OTGHSULPI_CLK_SLEEP_DISABLE __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_DISABLE -#define __HAL_RCC_OTGHS_CLK_SLEEP_ENABLE __HAL_RCC_USB_OTG_HS_CLK_SLEEP_ENABLE -#define __HAL_RCC_OTGHS_CLK_SLEEP_DISABLE __HAL_RCC_USB_OTG_HS_CLK_SLEEP_DISABLE -#define __HAL_RCC_OTGHS_IS_CLK_SLEEP_ENABLED __HAL_RCC_USB_OTG_HS_IS_CLK_SLEEP_ENABLED -#define __HAL_RCC_OTGHS_IS_CLK_SLEEP_DISABLED __HAL_RCC_USB_OTG_HS_IS_CLK_SLEEP_DISABLED -#define __HAL_RCC_OTGHS_FORCE_RESET __HAL_RCC_USB_OTG_HS_FORCE_RESET -#define __HAL_RCC_OTGHS_RELEASE_RESET __HAL_RCC_USB_OTG_HS_RELEASE_RESET -#define __HAL_RCC_OTGHSULPI_CLK_SLEEP_ENABLE __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_ENABLE -#define __HAL_RCC_OTGHSULPI_CLK_SLEEP_DISABLE __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_DISABLE -#define __HAL_RCC_OTGHSULPI_IS_CLK_SLEEP_ENABLED __HAL_RCC_USB_OTG_HS_ULPI_IS_CLK_SLEEP_ENABLED -#define __HAL_RCC_OTGHSULPI_IS_CLK_SLEEP_DISABLED __HAL_RCC_USB_OTG_HS_ULPI_IS_CLK_SLEEP_DISABLED -#define __SRAM3_CLK_SLEEP_ENABLE __HAL_RCC_SRAM3_CLK_SLEEP_ENABLE -#define __CAN2_CLK_SLEEP_ENABLE __HAL_RCC_CAN2_CLK_SLEEP_ENABLE -#define __CAN2_CLK_SLEEP_DISABLE __HAL_RCC_CAN2_CLK_SLEEP_DISABLE -#define __DAC_CLK_SLEEP_ENABLE __HAL_RCC_DAC_CLK_SLEEP_ENABLE -#define __DAC_CLK_SLEEP_DISABLE __HAL_RCC_DAC_CLK_SLEEP_DISABLE -#define __ADC2_CLK_SLEEP_ENABLE __HAL_RCC_ADC2_CLK_SLEEP_ENABLE -#define __ADC2_CLK_SLEEP_DISABLE __HAL_RCC_ADC2_CLK_SLEEP_DISABLE -#define __ADC3_CLK_SLEEP_ENABLE __HAL_RCC_ADC3_CLK_SLEEP_ENABLE -#define __ADC3_CLK_SLEEP_DISABLE __HAL_RCC_ADC3_CLK_SLEEP_DISABLE -#define __FSMC_FORCE_RESET __HAL_RCC_FSMC_FORCE_RESET -#define __FSMC_RELEASE_RESET __HAL_RCC_FSMC_RELEASE_RESET -#define __FSMC_CLK_SLEEP_ENABLE __HAL_RCC_FSMC_CLK_SLEEP_ENABLE -#define __FSMC_CLK_SLEEP_DISABLE __HAL_RCC_FSMC_CLK_SLEEP_DISABLE -#define __SDIO_FORCE_RESET __HAL_RCC_SDIO_FORCE_RESET -#define __SDIO_RELEASE_RESET __HAL_RCC_SDIO_RELEASE_RESET -#define __SDIO_CLK_SLEEP_DISABLE __HAL_RCC_SDIO_CLK_SLEEP_DISABLE -#define __SDIO_CLK_SLEEP_ENABLE __HAL_RCC_SDIO_CLK_SLEEP_ENABLE -#define __DMA2D_CLK_ENABLE __HAL_RCC_DMA2D_CLK_ENABLE -#define __DMA2D_CLK_DISABLE __HAL_RCC_DMA2D_CLK_DISABLE -#define __DMA2D_FORCE_RESET __HAL_RCC_DMA2D_FORCE_RESET -#define __DMA2D_RELEASE_RESET __HAL_RCC_DMA2D_RELEASE_RESET -#define __DMA2D_CLK_SLEEP_ENABLE __HAL_RCC_DMA2D_CLK_SLEEP_ENABLE -#define __DMA2D_CLK_SLEEP_DISABLE __HAL_RCC_DMA2D_CLK_SLEEP_DISABLE - -/* alias define maintained for legacy */ -#define __HAL_RCC_OTGFS_FORCE_RESET __HAL_RCC_USB_OTG_FS_FORCE_RESET -#define __HAL_RCC_OTGFS_RELEASE_RESET __HAL_RCC_USB_OTG_FS_RELEASE_RESET - -#define __ADC12_CLK_ENABLE __HAL_RCC_ADC12_CLK_ENABLE -#define __ADC12_CLK_DISABLE __HAL_RCC_ADC12_CLK_DISABLE -#define __ADC34_CLK_ENABLE __HAL_RCC_ADC34_CLK_ENABLE -#define __ADC34_CLK_DISABLE __HAL_RCC_ADC34_CLK_DISABLE -#define __DAC2_CLK_ENABLE __HAL_RCC_DAC2_CLK_ENABLE -#define __DAC2_CLK_DISABLE __HAL_RCC_DAC2_CLK_DISABLE -#define __TIM18_CLK_ENABLE __HAL_RCC_TIM18_CLK_ENABLE -#define __TIM18_CLK_DISABLE __HAL_RCC_TIM18_CLK_DISABLE -#define __TIM19_CLK_ENABLE __HAL_RCC_TIM19_CLK_ENABLE -#define __TIM19_CLK_DISABLE __HAL_RCC_TIM19_CLK_DISABLE -#define __TIM20_CLK_ENABLE __HAL_RCC_TIM20_CLK_ENABLE -#define __TIM20_CLK_DISABLE __HAL_RCC_TIM20_CLK_DISABLE -#define __HRTIM1_CLK_ENABLE __HAL_RCC_HRTIM1_CLK_ENABLE -#define __HRTIM1_CLK_DISABLE __HAL_RCC_HRTIM1_CLK_DISABLE -#define __SDADC1_CLK_ENABLE __HAL_RCC_SDADC1_CLK_ENABLE -#define __SDADC2_CLK_ENABLE __HAL_RCC_SDADC2_CLK_ENABLE -#define __SDADC3_CLK_ENABLE __HAL_RCC_SDADC3_CLK_ENABLE -#define __SDADC1_CLK_DISABLE __HAL_RCC_SDADC1_CLK_DISABLE -#define __SDADC2_CLK_DISABLE __HAL_RCC_SDADC2_CLK_DISABLE -#define __SDADC3_CLK_DISABLE __HAL_RCC_SDADC3_CLK_DISABLE - -#define __ADC12_FORCE_RESET __HAL_RCC_ADC12_FORCE_RESET -#define __ADC12_RELEASE_RESET __HAL_RCC_ADC12_RELEASE_RESET -#define __ADC34_FORCE_RESET __HAL_RCC_ADC34_FORCE_RESET -#define __ADC34_RELEASE_RESET __HAL_RCC_ADC34_RELEASE_RESET -#define __DAC2_FORCE_RESET __HAL_RCC_DAC2_FORCE_RESET -#define __DAC2_RELEASE_RESET __HAL_RCC_DAC2_RELEASE_RESET -#define __TIM18_FORCE_RESET __HAL_RCC_TIM18_FORCE_RESET -#define __TIM18_RELEASE_RESET __HAL_RCC_TIM18_RELEASE_RESET -#define __TIM19_FORCE_RESET __HAL_RCC_TIM19_FORCE_RESET -#define __TIM19_RELEASE_RESET __HAL_RCC_TIM19_RELEASE_RESET -#define __TIM20_FORCE_RESET __HAL_RCC_TIM20_FORCE_RESET -#define __TIM20_RELEASE_RESET __HAL_RCC_TIM20_RELEASE_RESET -#define __HRTIM1_FORCE_RESET __HAL_RCC_HRTIM1_FORCE_RESET -#define __HRTIM1_RELEASE_RESET __HAL_RCC_HRTIM1_RELEASE_RESET -#define __SDADC1_FORCE_RESET __HAL_RCC_SDADC1_FORCE_RESET -#define __SDADC2_FORCE_RESET __HAL_RCC_SDADC2_FORCE_RESET -#define __SDADC3_FORCE_RESET __HAL_RCC_SDADC3_FORCE_RESET -#define __SDADC1_RELEASE_RESET __HAL_RCC_SDADC1_RELEASE_RESET -#define __SDADC2_RELEASE_RESET __HAL_RCC_SDADC2_RELEASE_RESET -#define __SDADC3_RELEASE_RESET __HAL_RCC_SDADC3_RELEASE_RESET - -#define __ADC1_IS_CLK_ENABLED __HAL_RCC_ADC1_IS_CLK_ENABLED -#define __ADC1_IS_CLK_DISABLED __HAL_RCC_ADC1_IS_CLK_DISABLED -#define __ADC12_IS_CLK_ENABLED __HAL_RCC_ADC12_IS_CLK_ENABLED -#define __ADC12_IS_CLK_DISABLED __HAL_RCC_ADC12_IS_CLK_DISABLED -#define __ADC34_IS_CLK_ENABLED __HAL_RCC_ADC34_IS_CLK_ENABLED -#define __ADC34_IS_CLK_DISABLED __HAL_RCC_ADC34_IS_CLK_DISABLED -#define __CEC_IS_CLK_ENABLED __HAL_RCC_CEC_IS_CLK_ENABLED -#define __CEC_IS_CLK_DISABLED __HAL_RCC_CEC_IS_CLK_DISABLED -#define __CRC_IS_CLK_ENABLED __HAL_RCC_CRC_IS_CLK_ENABLED -#define __CRC_IS_CLK_DISABLED __HAL_RCC_CRC_IS_CLK_DISABLED -#define __DAC1_IS_CLK_ENABLED __HAL_RCC_DAC1_IS_CLK_ENABLED -#define __DAC1_IS_CLK_DISABLED __HAL_RCC_DAC1_IS_CLK_DISABLED -#define __DAC2_IS_CLK_ENABLED __HAL_RCC_DAC2_IS_CLK_ENABLED -#define __DAC2_IS_CLK_DISABLED __HAL_RCC_DAC2_IS_CLK_DISABLED -#define __DMA1_IS_CLK_ENABLED __HAL_RCC_DMA1_IS_CLK_ENABLED -#define __DMA1_IS_CLK_DISABLED __HAL_RCC_DMA1_IS_CLK_DISABLED -#define __DMA2_IS_CLK_ENABLED __HAL_RCC_DMA2_IS_CLK_ENABLED -#define __DMA2_IS_CLK_DISABLED __HAL_RCC_DMA2_IS_CLK_DISABLED -#define __FLITF_IS_CLK_ENABLED __HAL_RCC_FLITF_IS_CLK_ENABLED -#define __FLITF_IS_CLK_DISABLED __HAL_RCC_FLITF_IS_CLK_DISABLED -#define __FMC_IS_CLK_ENABLED __HAL_RCC_FMC_IS_CLK_ENABLED -#define __FMC_IS_CLK_DISABLED __HAL_RCC_FMC_IS_CLK_DISABLED -#define __GPIOA_IS_CLK_ENABLED __HAL_RCC_GPIOA_IS_CLK_ENABLED -#define __GPIOA_IS_CLK_DISABLED __HAL_RCC_GPIOA_IS_CLK_DISABLED -#define __GPIOB_IS_CLK_ENABLED __HAL_RCC_GPIOB_IS_CLK_ENABLED -#define __GPIOB_IS_CLK_DISABLED __HAL_RCC_GPIOB_IS_CLK_DISABLED -#define __GPIOC_IS_CLK_ENABLED __HAL_RCC_GPIOC_IS_CLK_ENABLED -#define __GPIOC_IS_CLK_DISABLED __HAL_RCC_GPIOC_IS_CLK_DISABLED -#define __GPIOD_IS_CLK_ENABLED __HAL_RCC_GPIOD_IS_CLK_ENABLED -#define __GPIOD_IS_CLK_DISABLED __HAL_RCC_GPIOD_IS_CLK_DISABLED -#define __GPIOE_IS_CLK_ENABLED __HAL_RCC_GPIOE_IS_CLK_ENABLED -#define __GPIOE_IS_CLK_DISABLED __HAL_RCC_GPIOE_IS_CLK_DISABLED -#define __GPIOF_IS_CLK_ENABLED __HAL_RCC_GPIOF_IS_CLK_ENABLED -#define __GPIOF_IS_CLK_DISABLED __HAL_RCC_GPIOF_IS_CLK_DISABLED -#define __GPIOG_IS_CLK_ENABLED __HAL_RCC_GPIOG_IS_CLK_ENABLED -#define __GPIOG_IS_CLK_DISABLED __HAL_RCC_GPIOG_IS_CLK_DISABLED -#define __GPIOH_IS_CLK_ENABLED __HAL_RCC_GPIOH_IS_CLK_ENABLED -#define __GPIOH_IS_CLK_DISABLED __HAL_RCC_GPIOH_IS_CLK_DISABLED -#define __HRTIM1_IS_CLK_ENABLED __HAL_RCC_HRTIM1_IS_CLK_ENABLED -#define __HRTIM1_IS_CLK_DISABLED __HAL_RCC_HRTIM1_IS_CLK_DISABLED -#define __I2C1_IS_CLK_ENABLED __HAL_RCC_I2C1_IS_CLK_ENABLED -#define __I2C1_IS_CLK_DISABLED __HAL_RCC_I2C1_IS_CLK_DISABLED -#define __I2C2_IS_CLK_ENABLED __HAL_RCC_I2C2_IS_CLK_ENABLED -#define __I2C2_IS_CLK_DISABLED __HAL_RCC_I2C2_IS_CLK_DISABLED -#define __I2C3_IS_CLK_ENABLED __HAL_RCC_I2C3_IS_CLK_ENABLED -#define __I2C3_IS_CLK_DISABLED __HAL_RCC_I2C3_IS_CLK_DISABLED -#define __PWR_IS_CLK_ENABLED __HAL_RCC_PWR_IS_CLK_ENABLED -#define __PWR_IS_CLK_DISABLED __HAL_RCC_PWR_IS_CLK_DISABLED -#define __SYSCFG_IS_CLK_ENABLED __HAL_RCC_SYSCFG_IS_CLK_ENABLED -#define __SYSCFG_IS_CLK_DISABLED __HAL_RCC_SYSCFG_IS_CLK_DISABLED -#define __SPI1_IS_CLK_ENABLED __HAL_RCC_SPI1_IS_CLK_ENABLED -#define __SPI1_IS_CLK_DISABLED __HAL_RCC_SPI1_IS_CLK_DISABLED -#define __SPI2_IS_CLK_ENABLED __HAL_RCC_SPI2_IS_CLK_ENABLED -#define __SPI2_IS_CLK_DISABLED __HAL_RCC_SPI2_IS_CLK_DISABLED -#define __SPI3_IS_CLK_ENABLED __HAL_RCC_SPI3_IS_CLK_ENABLED -#define __SPI3_IS_CLK_DISABLED __HAL_RCC_SPI3_IS_CLK_DISABLED -#define __SPI4_IS_CLK_ENABLED __HAL_RCC_SPI4_IS_CLK_ENABLED -#define __SPI4_IS_CLK_DISABLED __HAL_RCC_SPI4_IS_CLK_DISABLED -#define __SDADC1_IS_CLK_ENABLED __HAL_RCC_SDADC1_IS_CLK_ENABLED -#define __SDADC1_IS_CLK_DISABLED __HAL_RCC_SDADC1_IS_CLK_DISABLED -#define __SDADC2_IS_CLK_ENABLED __HAL_RCC_SDADC2_IS_CLK_ENABLED -#define __SDADC2_IS_CLK_DISABLED __HAL_RCC_SDADC2_IS_CLK_DISABLED -#define __SDADC3_IS_CLK_ENABLED __HAL_RCC_SDADC3_IS_CLK_ENABLED -#define __SDADC3_IS_CLK_DISABLED __HAL_RCC_SDADC3_IS_CLK_DISABLED -#define __SRAM_IS_CLK_ENABLED __HAL_RCC_SRAM_IS_CLK_ENABLED -#define __SRAM_IS_CLK_DISABLED __HAL_RCC_SRAM_IS_CLK_DISABLED -#define __TIM1_IS_CLK_ENABLED __HAL_RCC_TIM1_IS_CLK_ENABLED -#define __TIM1_IS_CLK_DISABLED __HAL_RCC_TIM1_IS_CLK_DISABLED -#define __TIM2_IS_CLK_ENABLED __HAL_RCC_TIM2_IS_CLK_ENABLED -#define __TIM2_IS_CLK_DISABLED __HAL_RCC_TIM2_IS_CLK_DISABLED -#define __TIM3_IS_CLK_ENABLED __HAL_RCC_TIM3_IS_CLK_ENABLED -#define __TIM3_IS_CLK_DISABLED __HAL_RCC_TIM3_IS_CLK_DISABLED -#define __TIM4_IS_CLK_ENABLED __HAL_RCC_TIM4_IS_CLK_ENABLED -#define __TIM4_IS_CLK_DISABLED __HAL_RCC_TIM4_IS_CLK_DISABLED -#define __TIM5_IS_CLK_ENABLED __HAL_RCC_TIM5_IS_CLK_ENABLED -#define __TIM5_IS_CLK_DISABLED __HAL_RCC_TIM5_IS_CLK_DISABLED -#define __TIM6_IS_CLK_ENABLED __HAL_RCC_TIM6_IS_CLK_ENABLED -#define __TIM6_IS_CLK_DISABLED __HAL_RCC_TIM6_IS_CLK_DISABLED -#define __TIM7_IS_CLK_ENABLED __HAL_RCC_TIM7_IS_CLK_ENABLED -#define __TIM7_IS_CLK_DISABLED __HAL_RCC_TIM7_IS_CLK_DISABLED -#define __TIM8_IS_CLK_ENABLED __HAL_RCC_TIM8_IS_CLK_ENABLED -#define __TIM8_IS_CLK_DISABLED __HAL_RCC_TIM8_IS_CLK_DISABLED -#define __TIM12_IS_CLK_ENABLED __HAL_RCC_TIM12_IS_CLK_ENABLED -#define __TIM12_IS_CLK_DISABLED __HAL_RCC_TIM12_IS_CLK_DISABLED -#define __TIM13_IS_CLK_ENABLED __HAL_RCC_TIM13_IS_CLK_ENABLED -#define __TIM13_IS_CLK_DISABLED __HAL_RCC_TIM13_IS_CLK_DISABLED -#define __TIM14_IS_CLK_ENABLED __HAL_RCC_TIM14_IS_CLK_ENABLED -#define __TIM14_IS_CLK_DISABLED __HAL_RCC_TIM14_IS_CLK_DISABLED -#define __TIM15_IS_CLK_ENABLED __HAL_RCC_TIM15_IS_CLK_ENABLED -#define __TIM15_IS_CLK_DISABLED __HAL_RCC_TIM15_IS_CLK_DISABLED -#define __TIM16_IS_CLK_ENABLED __HAL_RCC_TIM16_IS_CLK_ENABLED -#define __TIM16_IS_CLK_DISABLED __HAL_RCC_TIM16_IS_CLK_DISABLED -#define __TIM17_IS_CLK_ENABLED __HAL_RCC_TIM17_IS_CLK_ENABLED -#define __TIM17_IS_CLK_DISABLED __HAL_RCC_TIM17_IS_CLK_DISABLED -#define __TIM18_IS_CLK_ENABLED __HAL_RCC_TIM18_IS_CLK_ENABLED -#define __TIM18_IS_CLK_DISABLED __HAL_RCC_TIM18_IS_CLK_DISABLED -#define __TIM19_IS_CLK_ENABLED __HAL_RCC_TIM19_IS_CLK_ENABLED -#define __TIM19_IS_CLK_DISABLED __HAL_RCC_TIM19_IS_CLK_DISABLED -#define __TIM20_IS_CLK_ENABLED __HAL_RCC_TIM20_IS_CLK_ENABLED -#define __TIM20_IS_CLK_DISABLED __HAL_RCC_TIM20_IS_CLK_DISABLED -#define __TSC_IS_CLK_ENABLED __HAL_RCC_TSC_IS_CLK_ENABLED -#define __TSC_IS_CLK_DISABLED __HAL_RCC_TSC_IS_CLK_DISABLED -#define __UART4_IS_CLK_ENABLED __HAL_RCC_UART4_IS_CLK_ENABLED -#define __UART4_IS_CLK_DISABLED __HAL_RCC_UART4_IS_CLK_DISABLED -#define __UART5_IS_CLK_ENABLED __HAL_RCC_UART5_IS_CLK_ENABLED -#define __UART5_IS_CLK_DISABLED __HAL_RCC_UART5_IS_CLK_DISABLED -#define __USART1_IS_CLK_ENABLED __HAL_RCC_USART1_IS_CLK_ENABLED -#define __USART1_IS_CLK_DISABLED __HAL_RCC_USART1_IS_CLK_DISABLED -#define __USART2_IS_CLK_ENABLED __HAL_RCC_USART2_IS_CLK_ENABLED -#define __USART2_IS_CLK_DISABLED __HAL_RCC_USART2_IS_CLK_DISABLED -#define __USART3_IS_CLK_ENABLED __HAL_RCC_USART3_IS_CLK_ENABLED -#define __USART3_IS_CLK_DISABLED __HAL_RCC_USART3_IS_CLK_DISABLED -#define __USB_IS_CLK_ENABLED __HAL_RCC_USB_IS_CLK_ENABLED -#define __USB_IS_CLK_DISABLED __HAL_RCC_USB_IS_CLK_DISABLED -#define __WWDG_IS_CLK_ENABLED __HAL_RCC_WWDG_IS_CLK_ENABLED -#define __WWDG_IS_CLK_DISABLED __HAL_RCC_WWDG_IS_CLK_DISABLED - -#if defined(STM32L1) -#define __HAL_RCC_CRYP_CLK_DISABLE __HAL_RCC_AES_CLK_DISABLE -#define __HAL_RCC_CRYP_CLK_ENABLE __HAL_RCC_AES_CLK_ENABLE -#define __HAL_RCC_CRYP_CLK_SLEEP_DISABLE __HAL_RCC_AES_CLK_SLEEP_DISABLE -#define __HAL_RCC_CRYP_CLK_SLEEP_ENABLE __HAL_RCC_AES_CLK_SLEEP_ENABLE -#define __HAL_RCC_CRYP_FORCE_RESET __HAL_RCC_AES_FORCE_RESET -#define __HAL_RCC_CRYP_RELEASE_RESET __HAL_RCC_AES_RELEASE_RESET -#endif /* STM32L1 */ - -#if defined(STM32F4) -#define __HAL_RCC_SDMMC1_FORCE_RESET __HAL_RCC_SDIO_FORCE_RESET -#define __HAL_RCC_SDMMC1_RELEASE_RESET __HAL_RCC_SDIO_RELEASE_RESET -#define __HAL_RCC_SDMMC1_CLK_SLEEP_ENABLE __HAL_RCC_SDIO_CLK_SLEEP_ENABLE -#define __HAL_RCC_SDMMC1_CLK_SLEEP_DISABLE __HAL_RCC_SDIO_CLK_SLEEP_DISABLE -#define __HAL_RCC_SDMMC1_CLK_ENABLE __HAL_RCC_SDIO_CLK_ENABLE -#define __HAL_RCC_SDMMC1_CLK_DISABLE __HAL_RCC_SDIO_CLK_DISABLE -#define __HAL_RCC_SDMMC1_IS_CLK_ENABLED __HAL_RCC_SDIO_IS_CLK_ENABLED -#define __HAL_RCC_SDMMC1_IS_CLK_DISABLED __HAL_RCC_SDIO_IS_CLK_DISABLED -#define Sdmmc1ClockSelection SdioClockSelection -#define RCC_PERIPHCLK_SDMMC1 RCC_PERIPHCLK_SDIO -#define RCC_SDMMC1CLKSOURCE_CLK48 RCC_SDIOCLKSOURCE_CK48 -#define RCC_SDMMC1CLKSOURCE_SYSCLK RCC_SDIOCLKSOURCE_SYSCLK -#define __HAL_RCC_SDMMC1_CONFIG __HAL_RCC_SDIO_CONFIG -#define __HAL_RCC_GET_SDMMC1_SOURCE __HAL_RCC_GET_SDIO_SOURCE -#endif - -#if defined(STM32F7) || defined(STM32L4) -#define __HAL_RCC_SDIO_FORCE_RESET __HAL_RCC_SDMMC1_FORCE_RESET -#define __HAL_RCC_SDIO_RELEASE_RESET __HAL_RCC_SDMMC1_RELEASE_RESET -#define __HAL_RCC_SDIO_CLK_SLEEP_ENABLE __HAL_RCC_SDMMC1_CLK_SLEEP_ENABLE -#define __HAL_RCC_SDIO_CLK_SLEEP_DISABLE __HAL_RCC_SDMMC1_CLK_SLEEP_DISABLE -#define __HAL_RCC_SDIO_CLK_ENABLE __HAL_RCC_SDMMC1_CLK_ENABLE -#define __HAL_RCC_SDIO_CLK_DISABLE __HAL_RCC_SDMMC1_CLK_DISABLE -#define __HAL_RCC_SDIO_IS_CLK_ENABLED __HAL_RCC_SDMMC1_IS_CLK_ENABLED -#define __HAL_RCC_SDIO_IS_CLK_DISABLED __HAL_RCC_SDMMC1_IS_CLK_DISABLED -#define SdioClockSelection Sdmmc1ClockSelection -#define RCC_PERIPHCLK_SDIO RCC_PERIPHCLK_SDMMC1 -#define __HAL_RCC_SDIO_CONFIG __HAL_RCC_SDMMC1_CONFIG -#define __HAL_RCC_GET_SDIO_SOURCE __HAL_RCC_GET_SDMMC1_SOURCE -#endif - -#if defined(STM32F7) -#define RCC_SDIOCLKSOURCE_CLK48 RCC_SDMMC1CLKSOURCE_CLK48 -#define RCC_SDIOCLKSOURCE_SYSCLK RCC_SDMMC1CLKSOURCE_SYSCLK -#endif - -#if defined(STM32H7) -#define __HAL_RCC_USB_OTG_HS_CLK_ENABLE() __HAL_RCC_USB1_OTG_HS_CLK_ENABLE() -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_ENABLE() __HAL_RCC_USB1_OTG_HS_ULPI_CLK_ENABLE() -#define __HAL_RCC_USB_OTG_HS_CLK_DISABLE() __HAL_RCC_USB1_OTG_HS_CLK_DISABLE() -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_DISABLE() __HAL_RCC_USB1_OTG_HS_ULPI_CLK_DISABLE() -#define __HAL_RCC_USB_OTG_HS_FORCE_RESET() __HAL_RCC_USB1_OTG_HS_FORCE_RESET() -#define __HAL_RCC_USB_OTG_HS_RELEASE_RESET() __HAL_RCC_USB1_OTG_HS_RELEASE_RESET() -#define __HAL_RCC_USB_OTG_HS_CLK_SLEEP_ENABLE() __HAL_RCC_USB1_OTG_HS_CLK_SLEEP_ENABLE() -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_ENABLE() __HAL_RCC_USB1_OTG_HS_ULPI_CLK_SLEEP_ENABLE() -#define __HAL_RCC_USB_OTG_HS_CLK_SLEEP_DISABLE() __HAL_RCC_USB1_OTG_HS_CLK_SLEEP_DISABLE() -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_DISABLE() __HAL_RCC_USB1_OTG_HS_ULPI_CLK_SLEEP_DISABLE() - -#define __HAL_RCC_USB_OTG_FS_CLK_ENABLE() __HAL_RCC_USB2_OTG_FS_CLK_ENABLE() -#define __HAL_RCC_USB_OTG_FS_ULPI_CLK_ENABLE() __HAL_RCC_USB2_OTG_FS_ULPI_CLK_ENABLE() -#define __HAL_RCC_USB_OTG_FS_CLK_DISABLE() __HAL_RCC_USB2_OTG_FS_CLK_DISABLE() -#define __HAL_RCC_USB_OTG_FS_ULPI_CLK_DISABLE() __HAL_RCC_USB2_OTG_FS_ULPI_CLK_DISABLE() -#define __HAL_RCC_USB_OTG_FS_FORCE_RESET() __HAL_RCC_USB2_OTG_FS_FORCE_RESET() -#define __HAL_RCC_USB_OTG_FS_RELEASE_RESET() __HAL_RCC_USB2_OTG_FS_RELEASE_RESET() -#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_ENABLE() __HAL_RCC_USB2_OTG_FS_CLK_SLEEP_ENABLE() -#define __HAL_RCC_USB_OTG_FS_ULPI_CLK_SLEEP_ENABLE() __HAL_RCC_USB2_OTG_FS_ULPI_CLK_SLEEP_ENABLE() -#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_DISABLE() __HAL_RCC_USB2_OTG_FS_CLK_SLEEP_DISABLE() -#define __HAL_RCC_USB_OTG_FS_ULPI_CLK_SLEEP_DISABLE() __HAL_RCC_USB2_OTG_FS_ULPI_CLK_SLEEP_DISABLE() -#endif - -#define __HAL_RCC_I2SCLK __HAL_RCC_I2S_CONFIG -#define __HAL_RCC_I2SCLK_CONFIG __HAL_RCC_I2S_CONFIG - -#define __RCC_PLLSRC RCC_GET_PLL_OSCSOURCE - -#define IS_RCC_MSIRANGE IS_RCC_MSI_CLOCK_RANGE -#define IS_RCC_RTCCLK_SOURCE IS_RCC_RTCCLKSOURCE -#define IS_RCC_SYSCLK_DIV IS_RCC_HCLK -#define IS_RCC_HCLK_DIV IS_RCC_PCLK -#define IS_RCC_PERIPHCLK IS_RCC_PERIPHCLOCK - -#define RCC_IT_HSI14 RCC_IT_HSI14RDY - -#define RCC_IT_CSSLSE RCC_IT_LSECSS -#define RCC_IT_CSSHSE RCC_IT_CSS - -#define RCC_PLLMUL_3 RCC_PLL_MUL3 -#define RCC_PLLMUL_4 RCC_PLL_MUL4 -#define RCC_PLLMUL_6 RCC_PLL_MUL6 -#define RCC_PLLMUL_8 RCC_PLL_MUL8 -#define RCC_PLLMUL_12 RCC_PLL_MUL12 -#define RCC_PLLMUL_16 RCC_PLL_MUL16 -#define RCC_PLLMUL_24 RCC_PLL_MUL24 -#define RCC_PLLMUL_32 RCC_PLL_MUL32 -#define RCC_PLLMUL_48 RCC_PLL_MUL48 - -#define RCC_PLLDIV_2 RCC_PLL_DIV2 -#define RCC_PLLDIV_3 RCC_PLL_DIV3 -#define RCC_PLLDIV_4 RCC_PLL_DIV4 - -#define IS_RCC_MCOSOURCE IS_RCC_MCO1SOURCE -#define __HAL_RCC_MCO_CONFIG __HAL_RCC_MCO1_CONFIG -#define RCC_MCO_NODIV RCC_MCODIV_1 -#define RCC_MCO_DIV1 RCC_MCODIV_1 -#define RCC_MCO_DIV2 RCC_MCODIV_2 -#define RCC_MCO_DIV4 RCC_MCODIV_4 -#define RCC_MCO_DIV8 RCC_MCODIV_8 -#define RCC_MCO_DIV16 RCC_MCODIV_16 -#define RCC_MCO_DIV32 RCC_MCODIV_32 -#define RCC_MCO_DIV64 RCC_MCODIV_64 -#define RCC_MCO_DIV128 RCC_MCODIV_128 -#define RCC_MCOSOURCE_NONE RCC_MCO1SOURCE_NOCLOCK -#define RCC_MCOSOURCE_LSI RCC_MCO1SOURCE_LSI -#define RCC_MCOSOURCE_LSE RCC_MCO1SOURCE_LSE -#define RCC_MCOSOURCE_SYSCLK RCC_MCO1SOURCE_SYSCLK -#define RCC_MCOSOURCE_HSI RCC_MCO1SOURCE_HSI -#define RCC_MCOSOURCE_HSI14 RCC_MCO1SOURCE_HSI14 -#define RCC_MCOSOURCE_HSI48 RCC_MCO1SOURCE_HSI48 -#define RCC_MCOSOURCE_HSE RCC_MCO1SOURCE_HSE -#define RCC_MCOSOURCE_PLLCLK_DIV1 RCC_MCO1SOURCE_PLLCLK -#define RCC_MCOSOURCE_PLLCLK_NODIV RCC_MCO1SOURCE_PLLCLK -#define RCC_MCOSOURCE_PLLCLK_DIV2 RCC_MCO1SOURCE_PLLCLK_DIV2 - -#if defined(STM32L4) || defined(STM32WB) || defined(STM32G0) || defined(STM32G4) || defined(STM32L5) || defined(STM32WL) -#define RCC_RTCCLKSOURCE_NO_CLK RCC_RTCCLKSOURCE_NONE -#else -#define RCC_RTCCLKSOURCE_NONE RCC_RTCCLKSOURCE_NO_CLK -#endif - -#define RCC_USBCLK_PLLSAI1 RCC_USBCLKSOURCE_PLLSAI1 -#define RCC_USBCLK_PLL RCC_USBCLKSOURCE_PLL -#define RCC_USBCLK_MSI RCC_USBCLKSOURCE_MSI -#define RCC_USBCLKSOURCE_PLLCLK RCC_USBCLKSOURCE_PLL -#define RCC_USBPLLCLK_DIV1 RCC_USBCLKSOURCE_PLL -#define RCC_USBPLLCLK_DIV1_5 RCC_USBCLKSOURCE_PLL_DIV1_5 -#define RCC_USBPLLCLK_DIV2 RCC_USBCLKSOURCE_PLL_DIV2 -#define RCC_USBPLLCLK_DIV3 RCC_USBCLKSOURCE_PLL_DIV3 - -#define HSION_BitNumber RCC_HSION_BIT_NUMBER -#define HSION_BITNUMBER RCC_HSION_BIT_NUMBER -#define HSEON_BitNumber RCC_HSEON_BIT_NUMBER -#define HSEON_BITNUMBER RCC_HSEON_BIT_NUMBER -#define MSION_BITNUMBER RCC_MSION_BIT_NUMBER -#define CSSON_BitNumber RCC_CSSON_BIT_NUMBER -#define CSSON_BITNUMBER RCC_CSSON_BIT_NUMBER -#define PLLON_BitNumber RCC_PLLON_BIT_NUMBER -#define PLLON_BITNUMBER RCC_PLLON_BIT_NUMBER -#define PLLI2SON_BitNumber RCC_PLLI2SON_BIT_NUMBER -#define I2SSRC_BitNumber RCC_I2SSRC_BIT_NUMBER -#define RTCEN_BitNumber RCC_RTCEN_BIT_NUMBER -#define RTCEN_BITNUMBER RCC_RTCEN_BIT_NUMBER -#define BDRST_BitNumber RCC_BDRST_BIT_NUMBER -#define BDRST_BITNUMBER RCC_BDRST_BIT_NUMBER -#define RTCRST_BITNUMBER RCC_RTCRST_BIT_NUMBER -#define LSION_BitNumber RCC_LSION_BIT_NUMBER -#define LSION_BITNUMBER RCC_LSION_BIT_NUMBER -#define LSEON_BitNumber RCC_LSEON_BIT_NUMBER -#define LSEON_BITNUMBER RCC_LSEON_BIT_NUMBER -#define LSEBYP_BITNUMBER RCC_LSEBYP_BIT_NUMBER -#define PLLSAION_BitNumber RCC_PLLSAION_BIT_NUMBER -#define TIMPRE_BitNumber RCC_TIMPRE_BIT_NUMBER -#define RMVF_BitNumber RCC_RMVF_BIT_NUMBER -#define RMVF_BITNUMBER RCC_RMVF_BIT_NUMBER -#define RCC_CR2_HSI14TRIM_BitNumber RCC_HSI14TRIM_BIT_NUMBER -#define CR_BYTE2_ADDRESS RCC_CR_BYTE2_ADDRESS -#define CIR_BYTE1_ADDRESS RCC_CIR_BYTE1_ADDRESS -#define CIR_BYTE2_ADDRESS RCC_CIR_BYTE2_ADDRESS -#define BDCR_BYTE0_ADDRESS RCC_BDCR_BYTE0_ADDRESS -#define DBP_TIMEOUT_VALUE RCC_DBP_TIMEOUT_VALUE -#define LSE_TIMEOUT_VALUE RCC_LSE_TIMEOUT_VALUE - -#define CR_HSION_BB RCC_CR_HSION_BB -#define CR_CSSON_BB RCC_CR_CSSON_BB -#define CR_PLLON_BB RCC_CR_PLLON_BB -#define CR_PLLI2SON_BB RCC_CR_PLLI2SON_BB -#define CR_MSION_BB RCC_CR_MSION_BB -#define CSR_LSION_BB RCC_CSR_LSION_BB -#define CSR_LSEON_BB RCC_CSR_LSEON_BB -#define CSR_LSEBYP_BB RCC_CSR_LSEBYP_BB -#define CSR_RTCEN_BB RCC_CSR_RTCEN_BB -#define CSR_RTCRST_BB RCC_CSR_RTCRST_BB -#define CFGR_I2SSRC_BB RCC_CFGR_I2SSRC_BB -#define BDCR_RTCEN_BB RCC_BDCR_RTCEN_BB -#define BDCR_BDRST_BB RCC_BDCR_BDRST_BB -#define CR_HSEON_BB RCC_CR_HSEON_BB -#define CSR_RMVF_BB RCC_CSR_RMVF_BB -#define CR_PLLSAION_BB RCC_CR_PLLSAION_BB -#define DCKCFGR_TIMPRE_BB RCC_DCKCFGR_TIMPRE_BB - -#define __HAL_RCC_CRS_ENABLE_FREQ_ERROR_COUNTER __HAL_RCC_CRS_FREQ_ERROR_COUNTER_ENABLE -#define __HAL_RCC_CRS_DISABLE_FREQ_ERROR_COUNTER __HAL_RCC_CRS_FREQ_ERROR_COUNTER_DISABLE -#define __HAL_RCC_CRS_ENABLE_AUTOMATIC_CALIB __HAL_RCC_CRS_AUTOMATIC_CALIB_ENABLE -#define __HAL_RCC_CRS_DISABLE_AUTOMATIC_CALIB __HAL_RCC_CRS_AUTOMATIC_CALIB_DISABLE -#define __HAL_RCC_CRS_CALCULATE_RELOADVALUE __HAL_RCC_CRS_RELOADVALUE_CALCULATE - -#define __HAL_RCC_GET_IT_SOURCE __HAL_RCC_GET_IT - -#define RCC_CRS_SYNCWARM RCC_CRS_SYNCWARN -#define RCC_CRS_TRIMOV RCC_CRS_TRIMOVF - -#define RCC_PERIPHCLK_CK48 RCC_PERIPHCLK_CLK48 -#define RCC_CK48CLKSOURCE_PLLQ RCC_CLK48CLKSOURCE_PLLQ -#define RCC_CK48CLKSOURCE_PLLSAIP RCC_CLK48CLKSOURCE_PLLSAIP -#define RCC_CK48CLKSOURCE_PLLI2SQ RCC_CLK48CLKSOURCE_PLLI2SQ -#define IS_RCC_CK48CLKSOURCE IS_RCC_CLK48CLKSOURCE -#define RCC_SDIOCLKSOURCE_CK48 RCC_SDIOCLKSOURCE_CLK48 - -#define __HAL_RCC_DFSDM_CLK_ENABLE __HAL_RCC_DFSDM1_CLK_ENABLE -#define __HAL_RCC_DFSDM_CLK_DISABLE __HAL_RCC_DFSDM1_CLK_DISABLE -#define __HAL_RCC_DFSDM_IS_CLK_ENABLED __HAL_RCC_DFSDM1_IS_CLK_ENABLED -#define __HAL_RCC_DFSDM_IS_CLK_DISABLED __HAL_RCC_DFSDM1_IS_CLK_DISABLED -#define __HAL_RCC_DFSDM_FORCE_RESET __HAL_RCC_DFSDM1_FORCE_RESET -#define __HAL_RCC_DFSDM_RELEASE_RESET __HAL_RCC_DFSDM1_RELEASE_RESET -#define __HAL_RCC_DFSDM_CLK_SLEEP_ENABLE __HAL_RCC_DFSDM1_CLK_SLEEP_ENABLE -#define __HAL_RCC_DFSDM_CLK_SLEEP_DISABLE __HAL_RCC_DFSDM1_CLK_SLEEP_DISABLE -#define __HAL_RCC_DFSDM_IS_CLK_SLEEP_ENABLED __HAL_RCC_DFSDM1_IS_CLK_SLEEP_ENABLED -#define __HAL_RCC_DFSDM_IS_CLK_SLEEP_DISABLED __HAL_RCC_DFSDM1_IS_CLK_SLEEP_DISABLED -#define DfsdmClockSelection Dfsdm1ClockSelection -#define RCC_PERIPHCLK_DFSDM RCC_PERIPHCLK_DFSDM1 -#define RCC_DFSDMCLKSOURCE_PCLK RCC_DFSDM1CLKSOURCE_PCLK2 -#define RCC_DFSDMCLKSOURCE_SYSCLK RCC_DFSDM1CLKSOURCE_SYSCLK -#define __HAL_RCC_DFSDM_CONFIG __HAL_RCC_DFSDM1_CONFIG -#define __HAL_RCC_GET_DFSDM_SOURCE __HAL_RCC_GET_DFSDM1_SOURCE -#define RCC_DFSDM1CLKSOURCE_PCLK RCC_DFSDM1CLKSOURCE_PCLK2 -#define RCC_SWPMI1CLKSOURCE_PCLK RCC_SWPMI1CLKSOURCE_PCLK1 -#define RCC_LPTIM1CLKSOURCE_PCLK RCC_LPTIM1CLKSOURCE_PCLK1 -#define RCC_LPTIM2CLKSOURCE_PCLK RCC_LPTIM2CLKSOURCE_PCLK1 - -#define RCC_DFSDM1AUDIOCLKSOURCE_I2SAPB1 RCC_DFSDM1AUDIOCLKSOURCE_I2S1 -#define RCC_DFSDM1AUDIOCLKSOURCE_I2SAPB2 RCC_DFSDM1AUDIOCLKSOURCE_I2S2 -#define RCC_DFSDM2AUDIOCLKSOURCE_I2SAPB1 RCC_DFSDM2AUDIOCLKSOURCE_I2S1 -#define RCC_DFSDM2AUDIOCLKSOURCE_I2SAPB2 RCC_DFSDM2AUDIOCLKSOURCE_I2S2 -#define RCC_DFSDM1CLKSOURCE_APB2 RCC_DFSDM1CLKSOURCE_PCLK2 -#define RCC_DFSDM2CLKSOURCE_APB2 RCC_DFSDM2CLKSOURCE_PCLK2 -#define RCC_FMPI2C1CLKSOURCE_APB RCC_FMPI2C1CLKSOURCE_PCLK1 -#if defined(STM32U5) -#define MSIKPLLModeSEL RCC_MSIKPLL_MODE_SEL -#define MSISPLLModeSEL RCC_MSISPLL_MODE_SEL -#define __HAL_RCC_AHB21_CLK_DISABLE __HAL_RCC_AHB2_1_CLK_DISABLE -#define __HAL_RCC_AHB22_CLK_DISABLE __HAL_RCC_AHB2_2_CLK_DISABLE -#define __HAL_RCC_AHB1_CLK_Disable_Clear __HAL_RCC_AHB1_CLK_ENABLE -#define __HAL_RCC_AHB21_CLK_Disable_Clear __HAL_RCC_AHB2_1_CLK_ENABLE -#define __HAL_RCC_AHB22_CLK_Disable_Clear __HAL_RCC_AHB2_2_CLK_ENABLE -#define __HAL_RCC_AHB3_CLK_Disable_Clear __HAL_RCC_AHB3_CLK_ENABLE -#define __HAL_RCC_APB1_CLK_Disable_Clear __HAL_RCC_APB1_CLK_ENABLE -#define __HAL_RCC_APB2_CLK_Disable_Clear __HAL_RCC_APB2_CLK_ENABLE -#define __HAL_RCC_APB3_CLK_Disable_Clear __HAL_RCC_APB3_CLK_ENABLE -#define IS_RCC_MSIPLLModeSelection IS_RCC_MSIPLLMODE_SELECT -#endif -/** - * @} - */ - -/** @defgroup HAL_RNG_Aliased_Macros HAL RNG Aliased Macros maintained for legacy purpose - * @{ - */ -#define HAL_RNG_ReadyCallback(__HANDLE__) HAL_RNG_ReadyDataCallback((__HANDLE__), uint32_t random32bit) - -/** - * @} - */ - -/** @defgroup HAL_RTC_Aliased_Macros HAL RTC Aliased Macros maintained for legacy purpose - * @{ - */ -#if defined (STM32G0) || defined (STM32L5) || defined (STM32L412xx) || defined (STM32L422xx) || defined (STM32L4P5xx) || defined (STM32L4Q5xx) || defined (STM32G4) || defined (STM32WL) || defined (STM32U5) -#else -#define __HAL_RTC_CLEAR_FLAG __HAL_RTC_EXTI_CLEAR_FLAG -#endif -#define __HAL_RTC_DISABLE_IT __HAL_RTC_EXTI_DISABLE_IT -#define __HAL_RTC_ENABLE_IT __HAL_RTC_EXTI_ENABLE_IT - -#if defined (STM32F1) -#define __HAL_RTC_EXTI_CLEAR_FLAG(RTC_EXTI_LINE_ALARM_EVENT) __HAL_RTC_ALARM_EXTI_CLEAR_FLAG() - -#define __HAL_RTC_EXTI_ENABLE_IT(RTC_EXTI_LINE_ALARM_EVENT) __HAL_RTC_ALARM_EXTI_ENABLE_IT() - -#define __HAL_RTC_EXTI_DISABLE_IT(RTC_EXTI_LINE_ALARM_EVENT) __HAL_RTC_ALARM_EXTI_DISABLE_IT() - -#define __HAL_RTC_EXTI_GET_FLAG(RTC_EXTI_LINE_ALARM_EVENT) __HAL_RTC_ALARM_EXTI_GET_FLAG() - -#define __HAL_RTC_EXTI_GENERATE_SWIT(RTC_EXTI_LINE_ALARM_EVENT) __HAL_RTC_ALARM_EXTI_GENERATE_SWIT() -#else -#define __HAL_RTC_EXTI_CLEAR_FLAG(__EXTI_LINE__) (((__EXTI_LINE__) == RTC_EXTI_LINE_ALARM_EVENT) ? __HAL_RTC_ALARM_EXTI_CLEAR_FLAG() : \ - (((__EXTI_LINE__) == RTC_EXTI_LINE_WAKEUPTIMER_EVENT) ? __HAL_RTC_WAKEUPTIMER_EXTI_CLEAR_FLAG() : \ - __HAL_RTC_TAMPER_TIMESTAMP_EXTI_CLEAR_FLAG())) -#define __HAL_RTC_EXTI_ENABLE_IT(__EXTI_LINE__) (((__EXTI_LINE__) == RTC_EXTI_LINE_ALARM_EVENT) ? __HAL_RTC_ALARM_EXTI_ENABLE_IT() : \ - (((__EXTI_LINE__) == RTC_EXTI_LINE_WAKEUPTIMER_EVENT) ? __HAL_RTC_WAKEUPTIMER_EXTI_ENABLE_IT() : \ - __HAL_RTC_TAMPER_TIMESTAMP_EXTI_ENABLE_IT())) -#define __HAL_RTC_EXTI_DISABLE_IT(__EXTI_LINE__) (((__EXTI_LINE__) == RTC_EXTI_LINE_ALARM_EVENT) ? __HAL_RTC_ALARM_EXTI_DISABLE_IT() : \ - (((__EXTI_LINE__) == RTC_EXTI_LINE_WAKEUPTIMER_EVENT) ? __HAL_RTC_WAKEUPTIMER_EXTI_DISABLE_IT() : \ - __HAL_RTC_TAMPER_TIMESTAMP_EXTI_DISABLE_IT())) -#define __HAL_RTC_EXTI_GET_FLAG(__EXTI_LINE__) (((__EXTI_LINE__) == RTC_EXTI_LINE_ALARM_EVENT) ? __HAL_RTC_ALARM_EXTI_GET_FLAG() : \ - (((__EXTI_LINE__) == RTC_EXTI_LINE_WAKEUPTIMER_EVENT) ? __HAL_RTC_WAKEUPTIMER_EXTI_GET_FLAG() : \ - __HAL_RTC_TAMPER_TIMESTAMP_EXTI_GET_FLAG())) -#define __HAL_RTC_EXTI_GENERATE_SWIT(__EXTI_LINE__) (((__EXTI_LINE__) == RTC_EXTI_LINE_ALARM_EVENT) ? __HAL_RTC_ALARM_EXTI_GENERATE_SWIT() : \ - (((__EXTI_LINE__) == RTC_EXTI_LINE_WAKEUPTIMER_EVENT) ? __HAL_RTC_WAKEUPTIMER_EXTI_GENERATE_SWIT() : \ - __HAL_RTC_TAMPER_TIMESTAMP_EXTI_GENERATE_SWIT())) -#endif /* STM32F1 */ - -#define IS_ALARM IS_RTC_ALARM -#define IS_ALARM_MASK IS_RTC_ALARM_MASK -#define IS_TAMPER IS_RTC_TAMPER -#define IS_TAMPER_ERASE_MODE IS_RTC_TAMPER_ERASE_MODE -#define IS_TAMPER_FILTER IS_RTC_TAMPER_FILTER -#define IS_TAMPER_INTERRUPT IS_RTC_TAMPER_INTERRUPT -#define IS_TAMPER_MASKFLAG_STATE IS_RTC_TAMPER_MASKFLAG_STATE -#define IS_TAMPER_PRECHARGE_DURATION IS_RTC_TAMPER_PRECHARGE_DURATION -#define IS_TAMPER_PULLUP_STATE IS_RTC_TAMPER_PULLUP_STATE -#define IS_TAMPER_SAMPLING_FREQ IS_RTC_TAMPER_SAMPLING_FREQ -#define IS_TAMPER_TIMESTAMPONTAMPER_DETECTION IS_RTC_TAMPER_TIMESTAMPONTAMPER_DETECTION -#define IS_TAMPER_TRIGGER IS_RTC_TAMPER_TRIGGER -#define IS_WAKEUP_CLOCK IS_RTC_WAKEUP_CLOCK -#define IS_WAKEUP_COUNTER IS_RTC_WAKEUP_COUNTER - -#define __RTC_WRITEPROTECTION_ENABLE __HAL_RTC_WRITEPROTECTION_ENABLE -#define __RTC_WRITEPROTECTION_DISABLE __HAL_RTC_WRITEPROTECTION_DISABLE - -/** - * @} - */ - -/** @defgroup HAL_SD_Aliased_Macros HAL SD/MMC Aliased Macros maintained for legacy purpose - * @{ - */ - -#define SD_OCR_CID_CSD_OVERWRIETE SD_OCR_CID_CSD_OVERWRITE -#define SD_CMD_SD_APP_STAUS SD_CMD_SD_APP_STATUS - -#if !defined(STM32F1) && !defined(STM32F2) && !defined(STM32F4) && !defined(STM32F7) && !defined(STM32L1) -#define eMMC_HIGH_VOLTAGE_RANGE EMMC_HIGH_VOLTAGE_RANGE -#define eMMC_DUAL_VOLTAGE_RANGE EMMC_DUAL_VOLTAGE_RANGE -#define eMMC_LOW_VOLTAGE_RANGE EMMC_LOW_VOLTAGE_RANGE - -#define SDMMC_NSpeed_CLK_DIV SDMMC_NSPEED_CLK_DIV -#define SDMMC_HSpeed_CLK_DIV SDMMC_HSPEED_CLK_DIV -#endif - -#if defined(STM32F4) || defined(STM32F2) -#define SD_SDMMC_DISABLED SD_SDIO_DISABLED -#define SD_SDMMC_FUNCTION_BUSY SD_SDIO_FUNCTION_BUSY -#define SD_SDMMC_FUNCTION_FAILED SD_SDIO_FUNCTION_FAILED -#define SD_SDMMC_UNKNOWN_FUNCTION SD_SDIO_UNKNOWN_FUNCTION -#define SD_CMD_SDMMC_SEN_OP_COND SD_CMD_SDIO_SEN_OP_COND -#define SD_CMD_SDMMC_RW_DIRECT SD_CMD_SDIO_RW_DIRECT -#define SD_CMD_SDMMC_RW_EXTENDED SD_CMD_SDIO_RW_EXTENDED -#define __HAL_SD_SDMMC_ENABLE __HAL_SD_SDIO_ENABLE -#define __HAL_SD_SDMMC_DISABLE __HAL_SD_SDIO_DISABLE -#define __HAL_SD_SDMMC_DMA_ENABLE __HAL_SD_SDIO_DMA_ENABLE -#define __HAL_SD_SDMMC_DMA_DISABLE __HAL_SD_SDIO_DMA_DISABL -#define __HAL_SD_SDMMC_ENABLE_IT __HAL_SD_SDIO_ENABLE_IT -#define __HAL_SD_SDMMC_DISABLE_IT __HAL_SD_SDIO_DISABLE_IT -#define __HAL_SD_SDMMC_GET_FLAG __HAL_SD_SDIO_GET_FLAG -#define __HAL_SD_SDMMC_CLEAR_FLAG __HAL_SD_SDIO_CLEAR_FLAG -#define __HAL_SD_SDMMC_GET_IT __HAL_SD_SDIO_GET_IT -#define __HAL_SD_SDMMC_CLEAR_IT __HAL_SD_SDIO_CLEAR_IT -#define SDMMC_STATIC_FLAGS SDIO_STATIC_FLAGS -#define SDMMC_CMD0TIMEOUT SDIO_CMD0TIMEOUT -#define SD_SDMMC_SEND_IF_COND SD_SDIO_SEND_IF_COND -/* alias CMSIS */ -#define SDMMC1_IRQn SDIO_IRQn -#define SDMMC1_IRQHandler SDIO_IRQHandler -#endif - -#if defined(STM32F7) || defined(STM32L4) -#define SD_SDIO_DISABLED SD_SDMMC_DISABLED -#define SD_SDIO_FUNCTION_BUSY SD_SDMMC_FUNCTION_BUSY -#define SD_SDIO_FUNCTION_FAILED SD_SDMMC_FUNCTION_FAILED -#define SD_SDIO_UNKNOWN_FUNCTION SD_SDMMC_UNKNOWN_FUNCTION -#define SD_CMD_SDIO_SEN_OP_COND SD_CMD_SDMMC_SEN_OP_COND -#define SD_CMD_SDIO_RW_DIRECT SD_CMD_SDMMC_RW_DIRECT -#define SD_CMD_SDIO_RW_EXTENDED SD_CMD_SDMMC_RW_EXTENDED -#define __HAL_SD_SDIO_ENABLE __HAL_SD_SDMMC_ENABLE -#define __HAL_SD_SDIO_DISABLE __HAL_SD_SDMMC_DISABLE -#define __HAL_SD_SDIO_DMA_ENABLE __HAL_SD_SDMMC_DMA_ENABLE -#define __HAL_SD_SDIO_DMA_DISABL __HAL_SD_SDMMC_DMA_DISABLE -#define __HAL_SD_SDIO_ENABLE_IT __HAL_SD_SDMMC_ENABLE_IT -#define __HAL_SD_SDIO_DISABLE_IT __HAL_SD_SDMMC_DISABLE_IT -#define __HAL_SD_SDIO_GET_FLAG __HAL_SD_SDMMC_GET_FLAG -#define __HAL_SD_SDIO_CLEAR_FLAG __HAL_SD_SDMMC_CLEAR_FLAG -#define __HAL_SD_SDIO_GET_IT __HAL_SD_SDMMC_GET_IT -#define __HAL_SD_SDIO_CLEAR_IT __HAL_SD_SDMMC_CLEAR_IT -#define SDIO_STATIC_FLAGS SDMMC_STATIC_FLAGS -#define SDIO_CMD0TIMEOUT SDMMC_CMD0TIMEOUT -#define SD_SDIO_SEND_IF_COND SD_SDMMC_SEND_IF_COND -/* alias CMSIS for compatibilities */ -#define SDIO_IRQn SDMMC1_IRQn -#define SDIO_IRQHandler SDMMC1_IRQHandler -#endif - -#if defined(STM32F7) || defined(STM32F4) || defined(STM32F2) || defined(STM32L4) || defined(STM32H7) -#define HAL_SD_CardCIDTypedef HAL_SD_CardCIDTypeDef -#define HAL_SD_CardCSDTypedef HAL_SD_CardCSDTypeDef -#define HAL_SD_CardStatusTypedef HAL_SD_CardStatusTypeDef -#define HAL_SD_CardStateTypedef HAL_SD_CardStateTypeDef -#endif - -#if defined(STM32H7) || defined(STM32L5) -#define HAL_MMCEx_Read_DMADoubleBuffer0CpltCallback HAL_MMCEx_Read_DMADoubleBuf0CpltCallback -#define HAL_MMCEx_Read_DMADoubleBuffer1CpltCallback HAL_MMCEx_Read_DMADoubleBuf1CpltCallback -#define HAL_MMCEx_Write_DMADoubleBuffer0CpltCallback HAL_MMCEx_Write_DMADoubleBuf0CpltCallback -#define HAL_MMCEx_Write_DMADoubleBuffer1CpltCallback HAL_MMCEx_Write_DMADoubleBuf1CpltCallback -#define HAL_SDEx_Read_DMADoubleBuffer0CpltCallback HAL_SDEx_Read_DMADoubleBuf0CpltCallback -#define HAL_SDEx_Read_DMADoubleBuffer1CpltCallback HAL_SDEx_Read_DMADoubleBuf1CpltCallback -#define HAL_SDEx_Write_DMADoubleBuffer0CpltCallback HAL_SDEx_Write_DMADoubleBuf0CpltCallback -#define HAL_SDEx_Write_DMADoubleBuffer1CpltCallback HAL_SDEx_Write_DMADoubleBuf1CpltCallback -#define HAL_SD_DriveTransciver_1_8V_Callback HAL_SD_DriveTransceiver_1_8V_Callback -#endif -/** - * @} - */ - -/** @defgroup HAL_SMARTCARD_Aliased_Macros HAL SMARTCARD Aliased Macros maintained for legacy purpose - * @{ - */ - -#define __SMARTCARD_ENABLE_IT __HAL_SMARTCARD_ENABLE_IT -#define __SMARTCARD_DISABLE_IT __HAL_SMARTCARD_DISABLE_IT -#define __SMARTCARD_ENABLE __HAL_SMARTCARD_ENABLE -#define __SMARTCARD_DISABLE __HAL_SMARTCARD_DISABLE -#define __SMARTCARD_DMA_REQUEST_ENABLE __HAL_SMARTCARD_DMA_REQUEST_ENABLE -#define __SMARTCARD_DMA_REQUEST_DISABLE __HAL_SMARTCARD_DMA_REQUEST_DISABLE - -#define __HAL_SMARTCARD_GETCLOCKSOURCE SMARTCARD_GETCLOCKSOURCE -#define __SMARTCARD_GETCLOCKSOURCE SMARTCARD_GETCLOCKSOURCE - -#define IS_SMARTCARD_ONEBIT_SAMPLING IS_SMARTCARD_ONE_BIT_SAMPLE - -/** - * @} - */ - -/** @defgroup HAL_SMBUS_Aliased_Macros HAL SMBUS Aliased Macros maintained for legacy purpose - * @{ - */ -#define __HAL_SMBUS_RESET_CR1 SMBUS_RESET_CR1 -#define __HAL_SMBUS_RESET_CR2 SMBUS_RESET_CR2 -#define __HAL_SMBUS_GENERATE_START SMBUS_GENERATE_START -#define __HAL_SMBUS_GET_ADDR_MATCH SMBUS_GET_ADDR_MATCH -#define __HAL_SMBUS_GET_DIR SMBUS_GET_DIR -#define __HAL_SMBUS_GET_STOP_MODE SMBUS_GET_STOP_MODE -#define __HAL_SMBUS_GET_PEC_MODE SMBUS_GET_PEC_MODE -#define __HAL_SMBUS_GET_ALERT_ENABLED SMBUS_GET_ALERT_ENABLED -/** - * @} - */ - -/** @defgroup HAL_SPI_Aliased_Macros HAL SPI Aliased Macros maintained for legacy purpose - * @{ - */ - -#define __HAL_SPI_1LINE_TX SPI_1LINE_TX -#define __HAL_SPI_1LINE_RX SPI_1LINE_RX -#define __HAL_SPI_RESET_CRC SPI_RESET_CRC - -/** - * @} - */ - -/** @defgroup HAL_UART_Aliased_Macros HAL UART Aliased Macros maintained for legacy purpose - * @{ - */ - -#define __HAL_UART_GETCLOCKSOURCE UART_GETCLOCKSOURCE -#define __HAL_UART_MASK_COMPUTATION UART_MASK_COMPUTATION -#define __UART_GETCLOCKSOURCE UART_GETCLOCKSOURCE -#define __UART_MASK_COMPUTATION UART_MASK_COMPUTATION - -#define IS_UART_WAKEUPMETHODE IS_UART_WAKEUPMETHOD - -#define IS_UART_ONEBIT_SAMPLE IS_UART_ONE_BIT_SAMPLE -#define IS_UART_ONEBIT_SAMPLING IS_UART_ONE_BIT_SAMPLE - -/** - * @} - */ - - -/** @defgroup HAL_USART_Aliased_Macros HAL USART Aliased Macros maintained for legacy purpose - * @{ - */ - -#define __USART_ENABLE_IT __HAL_USART_ENABLE_IT -#define __USART_DISABLE_IT __HAL_USART_DISABLE_IT -#define __USART_ENABLE __HAL_USART_ENABLE -#define __USART_DISABLE __HAL_USART_DISABLE - -#define __HAL_USART_GETCLOCKSOURCE USART_GETCLOCKSOURCE -#define __USART_GETCLOCKSOURCE USART_GETCLOCKSOURCE - -#if defined(STM32F0) || defined(STM32F3) || defined(STM32F7) -#define USART_OVERSAMPLING_16 0x00000000U -#define USART_OVERSAMPLING_8 USART_CR1_OVER8 - -#define IS_USART_OVERSAMPLING(__SAMPLING__) (((__SAMPLING__) == USART_OVERSAMPLING_16) || \ - ((__SAMPLING__) == USART_OVERSAMPLING_8)) -#endif /* STM32F0 || STM32F3 || STM32F7 */ -/** - * @} - */ - -/** @defgroup HAL_USB_Aliased_Macros HAL USB Aliased Macros maintained for legacy purpose - * @{ - */ -#define USB_EXTI_LINE_WAKEUP USB_WAKEUP_EXTI_LINE - -#define USB_FS_EXTI_TRIGGER_RISING_EDGE USB_OTG_FS_WAKEUP_EXTI_RISING_EDGE -#define USB_FS_EXTI_TRIGGER_FALLING_EDGE USB_OTG_FS_WAKEUP_EXTI_FALLING_EDGE -#define USB_FS_EXTI_TRIGGER_BOTH_EDGE USB_OTG_FS_WAKEUP_EXTI_RISING_FALLING_EDGE -#define USB_FS_EXTI_LINE_WAKEUP USB_OTG_FS_WAKEUP_EXTI_LINE - -#define USB_HS_EXTI_TRIGGER_RISING_EDGE USB_OTG_HS_WAKEUP_EXTI_RISING_EDGE -#define USB_HS_EXTI_TRIGGER_FALLING_EDGE USB_OTG_HS_WAKEUP_EXTI_FALLING_EDGE -#define USB_HS_EXTI_TRIGGER_BOTH_EDGE USB_OTG_HS_WAKEUP_EXTI_RISING_FALLING_EDGE -#define USB_HS_EXTI_LINE_WAKEUP USB_OTG_HS_WAKEUP_EXTI_LINE - -#define __HAL_USB_EXTI_ENABLE_IT __HAL_USB_WAKEUP_EXTI_ENABLE_IT -#define __HAL_USB_EXTI_DISABLE_IT __HAL_USB_WAKEUP_EXTI_DISABLE_IT -#define __HAL_USB_EXTI_GET_FLAG __HAL_USB_WAKEUP_EXTI_GET_FLAG -#define __HAL_USB_EXTI_CLEAR_FLAG __HAL_USB_WAKEUP_EXTI_CLEAR_FLAG -#define __HAL_USB_EXTI_SET_RISING_EDGE_TRIGGER __HAL_USB_WAKEUP_EXTI_ENABLE_RISING_EDGE -#define __HAL_USB_EXTI_SET_FALLING_EDGE_TRIGGER __HAL_USB_WAKEUP_EXTI_ENABLE_FALLING_EDGE -#define __HAL_USB_EXTI_SET_FALLINGRISING_TRIGGER __HAL_USB_WAKEUP_EXTI_ENABLE_RISING_FALLING_EDGE - -#define __HAL_USB_FS_EXTI_ENABLE_IT __HAL_USB_OTG_FS_WAKEUP_EXTI_ENABLE_IT -#define __HAL_USB_FS_EXTI_DISABLE_IT __HAL_USB_OTG_FS_WAKEUP_EXTI_DISABLE_IT -#define __HAL_USB_FS_EXTI_GET_FLAG __HAL_USB_OTG_FS_WAKEUP_EXTI_GET_FLAG -#define __HAL_USB_FS_EXTI_CLEAR_FLAG __HAL_USB_OTG_FS_WAKEUP_EXTI_CLEAR_FLAG -#define __HAL_USB_FS_EXTI_SET_RISING_EGDE_TRIGGER __HAL_USB_OTG_FS_WAKEUP_EXTI_ENABLE_RISING_EDGE -#define __HAL_USB_FS_EXTI_SET_FALLING_EGDE_TRIGGER __HAL_USB_OTG_FS_WAKEUP_EXTI_ENABLE_FALLING_EDGE -#define __HAL_USB_FS_EXTI_SET_FALLINGRISING_TRIGGER __HAL_USB_OTG_FS_WAKEUP_EXTI_ENABLE_RISING_FALLING_EDGE -#define __HAL_USB_FS_EXTI_GENERATE_SWIT __HAL_USB_OTG_FS_WAKEUP_EXTI_GENERATE_SWIT - -#define __HAL_USB_HS_EXTI_ENABLE_IT __HAL_USB_OTG_HS_WAKEUP_EXTI_ENABLE_IT -#define __HAL_USB_HS_EXTI_DISABLE_IT __HAL_USB_OTG_HS_WAKEUP_EXTI_DISABLE_IT -#define __HAL_USB_HS_EXTI_GET_FLAG __HAL_USB_OTG_HS_WAKEUP_EXTI_GET_FLAG -#define __HAL_USB_HS_EXTI_CLEAR_FLAG __HAL_USB_OTG_HS_WAKEUP_EXTI_CLEAR_FLAG -#define __HAL_USB_HS_EXTI_SET_RISING_EGDE_TRIGGER __HAL_USB_OTG_HS_WAKEUP_EXTI_ENABLE_RISING_EDGE -#define __HAL_USB_HS_EXTI_SET_FALLING_EGDE_TRIGGER __HAL_USB_OTG_HS_WAKEUP_EXTI_ENABLE_FALLING_EDGE -#define __HAL_USB_HS_EXTI_SET_FALLINGRISING_TRIGGER __HAL_USB_OTG_HS_WAKEUP_EXTI_ENABLE_RISING_FALLING_EDGE -#define __HAL_USB_HS_EXTI_GENERATE_SWIT __HAL_USB_OTG_HS_WAKEUP_EXTI_GENERATE_SWIT - -#define HAL_PCD_ActiveRemoteWakeup HAL_PCD_ActivateRemoteWakeup -#define HAL_PCD_DeActiveRemoteWakeup HAL_PCD_DeActivateRemoteWakeup - -#define HAL_PCD_SetTxFiFo HAL_PCDEx_SetTxFiFo -#define HAL_PCD_SetRxFiFo HAL_PCDEx_SetRxFiFo -/** - * @} - */ - -/** @defgroup HAL_TIM_Aliased_Macros HAL TIM Aliased Macros maintained for legacy purpose - * @{ - */ -#define __HAL_TIM_SetICPrescalerValue TIM_SET_ICPRESCALERVALUE -#define __HAL_TIM_ResetICPrescalerValue TIM_RESET_ICPRESCALERVALUE - -#define TIM_GET_ITSTATUS __HAL_TIM_GET_IT_SOURCE -#define TIM_GET_CLEAR_IT __HAL_TIM_CLEAR_IT - -#define __HAL_TIM_GET_ITSTATUS __HAL_TIM_GET_IT_SOURCE - -#define __HAL_TIM_DIRECTION_STATUS __HAL_TIM_IS_TIM_COUNTING_DOWN -#define __HAL_TIM_PRESCALER __HAL_TIM_SET_PRESCALER -#define __HAL_TIM_SetCounter __HAL_TIM_SET_COUNTER -#define __HAL_TIM_GetCounter __HAL_TIM_GET_COUNTER -#define __HAL_TIM_SetAutoreload __HAL_TIM_SET_AUTORELOAD -#define __HAL_TIM_GetAutoreload __HAL_TIM_GET_AUTORELOAD -#define __HAL_TIM_SetClockDivision __HAL_TIM_SET_CLOCKDIVISION -#define __HAL_TIM_GetClockDivision __HAL_TIM_GET_CLOCKDIVISION -#define __HAL_TIM_SetICPrescaler __HAL_TIM_SET_ICPRESCALER -#define __HAL_TIM_GetICPrescaler __HAL_TIM_GET_ICPRESCALER -#define __HAL_TIM_SetCompare __HAL_TIM_SET_COMPARE -#define __HAL_TIM_GetCompare __HAL_TIM_GET_COMPARE - -#define TIM_BREAKINPUTSOURCE_DFSDM TIM_BREAKINPUTSOURCE_DFSDM1 -/** - * @} - */ - -/** @defgroup HAL_ETH_Aliased_Macros HAL ETH Aliased Macros maintained for legacy purpose - * @{ - */ - -#define __HAL_ETH_EXTI_ENABLE_IT __HAL_ETH_WAKEUP_EXTI_ENABLE_IT -#define __HAL_ETH_EXTI_DISABLE_IT __HAL_ETH_WAKEUP_EXTI_DISABLE_IT -#define __HAL_ETH_EXTI_GET_FLAG __HAL_ETH_WAKEUP_EXTI_GET_FLAG -#define __HAL_ETH_EXTI_CLEAR_FLAG __HAL_ETH_WAKEUP_EXTI_CLEAR_FLAG -#define __HAL_ETH_EXTI_SET_RISING_EGDE_TRIGGER __HAL_ETH_WAKEUP_EXTI_ENABLE_RISING_EDGE_TRIGGER -#define __HAL_ETH_EXTI_SET_FALLING_EGDE_TRIGGER __HAL_ETH_WAKEUP_EXTI_ENABLE_FALLING_EDGE_TRIGGER -#define __HAL_ETH_EXTI_SET_FALLINGRISING_TRIGGER __HAL_ETH_WAKEUP_EXTI_ENABLE_FALLINGRISING_TRIGGER - -#define ETH_PROMISCIOUSMODE_ENABLE ETH_PROMISCUOUS_MODE_ENABLE -#define ETH_PROMISCIOUSMODE_DISABLE ETH_PROMISCUOUS_MODE_DISABLE -#define IS_ETH_PROMISCIOUS_MODE IS_ETH_PROMISCUOUS_MODE -/** - * @} - */ - -/** @defgroup HAL_LTDC_Aliased_Macros HAL LTDC Aliased Macros maintained for legacy purpose - * @{ - */ -#define __HAL_LTDC_LAYER LTDC_LAYER -#define __HAL_LTDC_RELOAD_CONFIG __HAL_LTDC_RELOAD_IMMEDIATE_CONFIG -/** - * @} - */ - -/** @defgroup HAL_SAI_Aliased_Macros HAL SAI Aliased Macros maintained for legacy purpose - * @{ - */ -#define SAI_OUTPUTDRIVE_DISABLED SAI_OUTPUTDRIVE_DISABLE -#define SAI_OUTPUTDRIVE_ENABLED SAI_OUTPUTDRIVE_ENABLE -#define SAI_MASTERDIVIDER_ENABLED SAI_MASTERDIVIDER_ENABLE -#define SAI_MASTERDIVIDER_DISABLED SAI_MASTERDIVIDER_DISABLE -#define SAI_STREOMODE SAI_STEREOMODE -#define SAI_FIFOStatus_Empty SAI_FIFOSTATUS_EMPTY -#define SAI_FIFOStatus_Less1QuarterFull SAI_FIFOSTATUS_LESS1QUARTERFULL -#define SAI_FIFOStatus_1QuarterFull SAI_FIFOSTATUS_1QUARTERFULL -#define SAI_FIFOStatus_HalfFull SAI_FIFOSTATUS_HALFFULL -#define SAI_FIFOStatus_3QuartersFull SAI_FIFOSTATUS_3QUARTERFULL -#define SAI_FIFOStatus_Full SAI_FIFOSTATUS_FULL -#define IS_SAI_BLOCK_MONO_STREO_MODE IS_SAI_BLOCK_MONO_STEREO_MODE -#define SAI_SYNCHRONOUS_EXT SAI_SYNCHRONOUS_EXT_SAI1 -#define SAI_SYNCEXT_IN_ENABLE SAI_SYNCEXT_OUTBLOCKA_ENABLE -/** - * @} - */ - -/** @defgroup HAL_SPDIFRX_Aliased_Macros HAL SPDIFRX Aliased Macros maintained for legacy purpose - * @{ - */ -#if defined(STM32H7) -#define HAL_SPDIFRX_ReceiveControlFlow HAL_SPDIFRX_ReceiveCtrlFlow -#define HAL_SPDIFRX_ReceiveControlFlow_IT HAL_SPDIFRX_ReceiveCtrlFlow_IT -#define HAL_SPDIFRX_ReceiveControlFlow_DMA HAL_SPDIFRX_ReceiveCtrlFlow_DMA -#endif -/** - * @} - */ - -/** @defgroup HAL_HRTIM_Aliased_Functions HAL HRTIM Aliased Functions maintained for legacy purpose - * @{ - */ -#if defined (STM32H7) || defined (STM32G4) || defined (STM32F3) -#define HAL_HRTIM_WaveformCounterStart_IT HAL_HRTIM_WaveformCountStart_IT -#define HAL_HRTIM_WaveformCounterStart_DMA HAL_HRTIM_WaveformCountStart_DMA -#define HAL_HRTIM_WaveformCounterStart HAL_HRTIM_WaveformCountStart -#define HAL_HRTIM_WaveformCounterStop_IT HAL_HRTIM_WaveformCountStop_IT -#define HAL_HRTIM_WaveformCounterStop_DMA HAL_HRTIM_WaveformCountStop_DMA -#define HAL_HRTIM_WaveformCounterStop HAL_HRTIM_WaveformCountStop -#endif -/** - * @} - */ - -/** @defgroup HAL_QSPI_Aliased_Macros HAL QSPI Aliased Macros maintained for legacy purpose - * @{ - */ -#if defined (STM32L4) || defined (STM32F4) || defined (STM32F7) || defined(STM32H7) -#define HAL_QPSI_TIMEOUT_DEFAULT_VALUE HAL_QSPI_TIMEOUT_DEFAULT_VALUE -#endif /* STM32L4 || STM32F4 || STM32F7 */ -/** - * @} - */ - -/** @defgroup HAL_PPP_Aliased_Macros HAL PPP Aliased Macros maintained for legacy purpose - * @{ - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32_HAL_LEGACY */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ - diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/Legacy/stm32f4xx_hal_can_legacy.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/Legacy/stm32f4xx_hal_can_legacy.h deleted file mode 100644 index aacf0f0..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/Legacy/stm32f4xx_hal_can_legacy.h +++ /dev/null @@ -1,785 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_can_legacy.h - * @author MCD Application Team - * @brief Header file of CAN HAL module. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT(c) 2017 STMicroelectronics

- * - * Redistribution and use in source and binary forms, with or without modification, - * are permitted provided that the following conditions are met: - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE - * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL - * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR - * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, - * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE - * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_CAN_LEGACY_H -#define __STM32F4xx_HAL_CAN_LEGACY_H - -#ifdef __cplusplus - extern "C" { -#endif - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) ||\ - defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) ||\ - defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) ||\ - defined(STM32F423xx) -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup CAN - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup CAN_Exported_Types CAN Exported Types - * @{ - */ - -/** - * @brief HAL State structures definition - */ -typedef enum -{ - HAL_CAN_STATE_RESET = 0x00U, /*!< CAN not yet initialized or disabled */ - HAL_CAN_STATE_READY = 0x01U, /*!< CAN initialized and ready for use */ - HAL_CAN_STATE_BUSY = 0x02U, /*!< CAN process is ongoing */ - HAL_CAN_STATE_BUSY_TX = 0x12U, /*!< CAN process is ongoing */ - HAL_CAN_STATE_BUSY_RX0 = 0x22U, /*!< CAN process is ongoing */ - HAL_CAN_STATE_BUSY_RX1 = 0x32U, /*!< CAN process is ongoing */ - HAL_CAN_STATE_BUSY_TX_RX0 = 0x42U, /*!< CAN process is ongoing */ - HAL_CAN_STATE_BUSY_TX_RX1 = 0x52U, /*!< CAN process is ongoing */ - HAL_CAN_STATE_BUSY_RX0_RX1 = 0x62U, /*!< CAN process is ongoing */ - HAL_CAN_STATE_BUSY_TX_RX0_RX1 = 0x72U, /*!< CAN process is ongoing */ - HAL_CAN_STATE_TIMEOUT = 0x03U, /*!< CAN in Timeout state */ - HAL_CAN_STATE_ERROR = 0x04U /*!< CAN error state */ - -}HAL_CAN_StateTypeDef; - -/** - * @brief CAN init structure definition - */ -typedef struct -{ - uint32_t Prescaler; /*!< Specifies the length of a time quantum. - This parameter must be a number between Min_Data = 1 and Max_Data = 1024 */ - - uint32_t Mode; /*!< Specifies the CAN operating mode. - This parameter can be a value of @ref CAN_operating_mode */ - - uint32_t SJW; /*!< Specifies the maximum number of time quanta - the CAN hardware is allowed to lengthen or - shorten a bit to perform resynchronization. - This parameter can be a value of @ref CAN_synchronisation_jump_width */ - - uint32_t BS1; /*!< Specifies the number of time quanta in Bit Segment 1. - This parameter can be a value of @ref CAN_time_quantum_in_bit_segment_1 */ - - uint32_t BS2; /*!< Specifies the number of time quanta in Bit Segment 2. - This parameter can be a value of @ref CAN_time_quantum_in_bit_segment_2 */ - - uint32_t TTCM; /*!< Enable or disable the time triggered communication mode. - This parameter can be set to ENABLE or DISABLE. */ - - uint32_t ABOM; /*!< Enable or disable the automatic bus-off management. - This parameter can be set to ENABLE or DISABLE */ - - uint32_t AWUM; /*!< Enable or disable the automatic wake-up mode. - This parameter can be set to ENABLE or DISABLE */ - - uint32_t NART; /*!< Enable or disable the non-automatic retransmission mode. - This parameter can be set to ENABLE or DISABLE */ - - uint32_t RFLM; /*!< Enable or disable the receive FIFO Locked mode. - This parameter can be set to ENABLE or DISABLE */ - - uint32_t TXFP; /*!< Enable or disable the transmit FIFO priority. - This parameter can be set to ENABLE or DISABLE */ -}CAN_InitTypeDef; - -/** - * @brief CAN filter configuration structure definition - */ -typedef struct -{ - uint32_t FilterIdHigh; /*!< Specifies the filter identification number (MSBs for a 32-bit - configuration, first one for a 16-bit configuration). - This parameter must be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF */ - - uint32_t FilterIdLow; /*!< Specifies the filter identification number (LSBs for a 32-bit - configuration, second one for a 16-bit configuration). - This parameter must be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF */ - - uint32_t FilterMaskIdHigh; /*!< Specifies the filter mask number or identification number, - according to the mode (MSBs for a 32-bit configuration, - first one for a 16-bit configuration). - This parameter must be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF */ - - uint32_t FilterMaskIdLow; /*!< Specifies the filter mask number or identification number, - according to the mode (LSBs for a 32-bit configuration, - second one for a 16-bit configuration). - This parameter must be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF */ - - uint32_t FilterFIFOAssignment; /*!< Specifies the FIFO (0 or 1) which will be assigned to the filter. - This parameter can be a value of @ref CAN_filter_FIFO */ - - uint32_t FilterNumber; /*!< Specifies the filter which will be initialized. - This parameter must be a number between Min_Data = 0 and Max_Data = 27 */ - - uint32_t FilterMode; /*!< Specifies the filter mode to be initialized. - This parameter can be a value of @ref CAN_filter_mode */ - - uint32_t FilterScale; /*!< Specifies the filter scale. - This parameter can be a value of @ref CAN_filter_scale */ - - uint32_t FilterActivation; /*!< Enable or disable the filter. - This parameter can be set to ENABLE or DISABLE. */ - - uint32_t BankNumber; /*!< Select the start slave bank filter. - This parameter must be a number between Min_Data = 0 and Max_Data = 28 */ - -}CAN_FilterConfTypeDef; - -/** - * @brief CAN Tx message structure definition - */ -typedef struct -{ - uint32_t StdId; /*!< Specifies the standard identifier. - This parameter must be a number between Min_Data = 0 and Max_Data = 0x7FF */ - - uint32_t ExtId; /*!< Specifies the extended identifier. - This parameter must be a number between Min_Data = 0 and Max_Data = 0x1FFFFFFF */ - - uint32_t IDE; /*!< Specifies the type of identifier for the message that will be transmitted. - This parameter can be a value of @ref CAN_Identifier_Type */ - - uint32_t RTR; /*!< Specifies the type of frame for the message that will be transmitted. - This parameter can be a value of @ref CAN_remote_transmission_request */ - - uint32_t DLC; /*!< Specifies the length of the frame that will be transmitted. - This parameter must be a number between Min_Data = 0 and Max_Data = 8 */ - - uint8_t Data[8]; /*!< Contains the data to be transmitted. - This parameter must be a number between Min_Data = 0 and Max_Data = 0xFF */ - -}CanTxMsgTypeDef; - -/** - * @brief CAN Rx message structure definition - */ -typedef struct -{ - uint32_t StdId; /*!< Specifies the standard identifier. - This parameter must be a number between Min_Data = 0 and Max_Data = 0x7FF */ - - uint32_t ExtId; /*!< Specifies the extended identifier. - This parameter must be a number between Min_Data = 0 and Max_Data = 0x1FFFFFFF */ - - uint32_t IDE; /*!< Specifies the type of identifier for the message that will be received. - This parameter can be a value of @ref CAN_Identifier_Type */ - - uint32_t RTR; /*!< Specifies the type of frame for the received message. - This parameter can be a value of @ref CAN_remote_transmission_request */ - - uint32_t DLC; /*!< Specifies the length of the frame that will be received. - This parameter must be a number between Min_Data = 0 and Max_Data = 8 */ - - uint8_t Data[8]; /*!< Contains the data to be received. - This parameter must be a number between Min_Data = 0 and Max_Data = 0xFF */ - - uint32_t FMI; /*!< Specifies the index of the filter the message stored in the mailbox passes through. - This parameter must be a number between Min_Data = 0 and Max_Data = 0xFF */ - - uint32_t FIFONumber; /*!< Specifies the receive FIFO number. - This parameter can be CAN_FIFO0 or CAN_FIFO1 */ - -}CanRxMsgTypeDef; - -/** - * @brief CAN handle Structure definition - */ -typedef struct -{ - CAN_TypeDef *Instance; /*!< Register base address */ - - CAN_InitTypeDef Init; /*!< CAN required parameters */ - - CanTxMsgTypeDef* pTxMsg; /*!< Pointer to transmit structure */ - - CanRxMsgTypeDef* pRxMsg; /*!< Pointer to reception structure for RX FIFO0 msg */ - - CanRxMsgTypeDef* pRx1Msg; /*!< Pointer to reception structure for RX FIFO1 msg */ - - __IO HAL_CAN_StateTypeDef State; /*!< CAN communication state */ - - HAL_LockTypeDef Lock; /*!< CAN locking object */ - - __IO uint32_t ErrorCode; /*!< CAN Error code */ - -}CAN_HandleTypeDef; - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup CAN_Exported_Constants CAN Exported Constants - * @{ - */ - -/** @defgroup CAN_Error_Code CAN Error Code - * @{ - */ -#define HAL_CAN_ERROR_NONE 0x00000000U /*!< No error */ -#define HAL_CAN_ERROR_EWG 0x00000001U /*!< EWG error */ -#define HAL_CAN_ERROR_EPV 0x00000002U /*!< EPV error */ -#define HAL_CAN_ERROR_BOF 0x00000004U /*!< BOF error */ -#define HAL_CAN_ERROR_STF 0x00000008U /*!< Stuff error */ -#define HAL_CAN_ERROR_FOR 0x00000010U /*!< Form error */ -#define HAL_CAN_ERROR_ACK 0x00000020U /*!< Acknowledgment error */ -#define HAL_CAN_ERROR_BR 0x00000040U /*!< Bit recessive */ -#define HAL_CAN_ERROR_BD 0x00000080U /*!< LEC dominant */ -#define HAL_CAN_ERROR_CRC 0x00000100U /*!< LEC transfer error */ -#define HAL_CAN_ERROR_FOV0 0x00000200U /*!< FIFO0 overrun error */ -#define HAL_CAN_ERROR_FOV1 0x00000400U /*!< FIFO1 overrun error */ -#define HAL_CAN_ERROR_TXFAIL 0x00000800U /*!< Transmit failure */ -/** - * @} - */ - -/** @defgroup CAN_InitStatus CAN InitStatus - * @{ - */ -#define CAN_INITSTATUS_FAILED ((uint8_t)0x00) /*!< CAN initialization failed */ -#define CAN_INITSTATUS_SUCCESS ((uint8_t)0x01) /*!< CAN initialization OK */ -/** - * @} - */ - -/** @defgroup CAN_operating_mode CAN Operating Mode - * @{ - */ -#define CAN_MODE_NORMAL 0x00000000U /*!< Normal mode */ -#define CAN_MODE_LOOPBACK ((uint32_t)CAN_BTR_LBKM) /*!< Loopback mode */ -#define CAN_MODE_SILENT ((uint32_t)CAN_BTR_SILM) /*!< Silent mode */ -#define CAN_MODE_SILENT_LOOPBACK ((uint32_t)(CAN_BTR_LBKM | CAN_BTR_SILM)) /*!< Loopback combined with silent mode */ -/** - * @} - */ - -/** @defgroup CAN_synchronisation_jump_width CAN Synchronisation Jump Width - * @{ - */ -#define CAN_SJW_1TQ 0x00000000U /*!< 1 time quantum */ -#define CAN_SJW_2TQ ((uint32_t)CAN_BTR_SJW_0) /*!< 2 time quantum */ -#define CAN_SJW_3TQ ((uint32_t)CAN_BTR_SJW_1) /*!< 3 time quantum */ -#define CAN_SJW_4TQ ((uint32_t)CAN_BTR_SJW) /*!< 4 time quantum */ -/** - * @} - */ - -/** @defgroup CAN_time_quantum_in_bit_segment_1 CAN Time Quantum in bit segment 1 - * @{ - */ -#define CAN_BS1_1TQ 0x00000000U /*!< 1 time quantum */ -#define CAN_BS1_2TQ ((uint32_t)CAN_BTR_TS1_0) /*!< 2 time quantum */ -#define CAN_BS1_3TQ ((uint32_t)CAN_BTR_TS1_1) /*!< 3 time quantum */ -#define CAN_BS1_4TQ ((uint32_t)(CAN_BTR_TS1_1 | CAN_BTR_TS1_0)) /*!< 4 time quantum */ -#define CAN_BS1_5TQ ((uint32_t)CAN_BTR_TS1_2) /*!< 5 time quantum */ -#define CAN_BS1_6TQ ((uint32_t)(CAN_BTR_TS1_2 | CAN_BTR_TS1_0)) /*!< 6 time quantum */ -#define CAN_BS1_7TQ ((uint32_t)(CAN_BTR_TS1_2 | CAN_BTR_TS1_1)) /*!< 7 time quantum */ -#define CAN_BS1_8TQ ((uint32_t)(CAN_BTR_TS1_2 | CAN_BTR_TS1_1 | CAN_BTR_TS1_0)) /*!< 8 time quantum */ -#define CAN_BS1_9TQ ((uint32_t)CAN_BTR_TS1_3) /*!< 9 time quantum */ -#define CAN_BS1_10TQ ((uint32_t)(CAN_BTR_TS1_3 | CAN_BTR_TS1_0)) /*!< 10 time quantum */ -#define CAN_BS1_11TQ ((uint32_t)(CAN_BTR_TS1_3 | CAN_BTR_TS1_1)) /*!< 11 time quantum */ -#define CAN_BS1_12TQ ((uint32_t)(CAN_BTR_TS1_3 | CAN_BTR_TS1_1 | CAN_BTR_TS1_0)) /*!< 12 time quantum */ -#define CAN_BS1_13TQ ((uint32_t)(CAN_BTR_TS1_3 | CAN_BTR_TS1_2)) /*!< 13 time quantum */ -#define CAN_BS1_14TQ ((uint32_t)(CAN_BTR_TS1_3 | CAN_BTR_TS1_2 | CAN_BTR_TS1_0)) /*!< 14 time quantum */ -#define CAN_BS1_15TQ ((uint32_t)(CAN_BTR_TS1_3 | CAN_BTR_TS1_2 | CAN_BTR_TS1_1)) /*!< 15 time quantum */ -#define CAN_BS1_16TQ ((uint32_t)CAN_BTR_TS1) /*!< 16 time quantum */ -/** - * @} - */ - -/** @defgroup CAN_time_quantum_in_bit_segment_2 CAN Time Quantum in bit segment 2 - * @{ - */ -#define CAN_BS2_1TQ 0x00000000U /*!< 1 time quantum */ -#define CAN_BS2_2TQ ((uint32_t)CAN_BTR_TS2_0) /*!< 2 time quantum */ -#define CAN_BS2_3TQ ((uint32_t)CAN_BTR_TS2_1) /*!< 3 time quantum */ -#define CAN_BS2_4TQ ((uint32_t)(CAN_BTR_TS2_1 | CAN_BTR_TS2_0)) /*!< 4 time quantum */ -#define CAN_BS2_5TQ ((uint32_t)CAN_BTR_TS2_2) /*!< 5 time quantum */ -#define CAN_BS2_6TQ ((uint32_t)(CAN_BTR_TS2_2 | CAN_BTR_TS2_0)) /*!< 6 time quantum */ -#define CAN_BS2_7TQ ((uint32_t)(CAN_BTR_TS2_2 | CAN_BTR_TS2_1)) /*!< 7 time quantum */ -#define CAN_BS2_8TQ ((uint32_t)CAN_BTR_TS2) /*!< 8 time quantum */ -/** - * @} - */ - -/** @defgroup CAN_filter_mode CAN Filter Mode - * @{ - */ -#define CAN_FILTERMODE_IDMASK ((uint8_t)0x00) /*!< Identifier mask mode */ -#define CAN_FILTERMODE_IDLIST ((uint8_t)0x01) /*!< Identifier list mode */ -/** - * @} - */ - -/** @defgroup CAN_filter_scale CAN Filter Scale - * @{ - */ -#define CAN_FILTERSCALE_16BIT ((uint8_t)0x00) /*!< Two 16-bit filters */ -#define CAN_FILTERSCALE_32BIT ((uint8_t)0x01) /*!< One 32-bit filter */ -/** - * @} - */ - -/** @defgroup CAN_filter_FIFO CAN Filter FIFO - * @{ - */ -#define CAN_FILTER_FIFO0 ((uint8_t)0x00) /*!< Filter FIFO 0 assignment for filter x */ -#define CAN_FILTER_FIFO1 ((uint8_t)0x01) /*!< Filter FIFO 1 assignment for filter x */ -/** - * @} - */ - -/** @defgroup CAN_Identifier_Type CAN Identifier Type - * @{ - */ -#define CAN_ID_STD 0x00000000U /*!< Standard Id */ -#define CAN_ID_EXT 0x00000004U /*!< Extended Id */ -/** - * @} - */ - -/** @defgroup CAN_remote_transmission_request CAN Remote Transmission Request - * @{ - */ -#define CAN_RTR_DATA 0x00000000U /*!< Data frame */ -#define CAN_RTR_REMOTE 0x00000002U /*!< Remote frame */ -/** - * @} - */ - -/** @defgroup CAN_receive_FIFO_number_constants CAN Receive FIFO Number Constants - * @{ - */ -#define CAN_FIFO0 ((uint8_t)0x00) /*!< CAN FIFO 0 used to receive */ -#define CAN_FIFO1 ((uint8_t)0x01) /*!< CAN FIFO 1 used to receive */ -/** - * @} - */ - -/** @defgroup CAN_flags CAN Flags - * @{ - */ -/* If the flag is 0x3XXXXXXX, it means that it can be used with CAN_GetFlagStatus() - and CAN_ClearFlag() functions. */ -/* If the flag is 0x1XXXXXXX, it means that it can only be used with - CAN_GetFlagStatus() function. */ - -/* Transmit Flags */ -#define CAN_FLAG_RQCP0 0x00000500U /*!< Request MailBox0 flag */ -#define CAN_FLAG_RQCP1 0x00000508U /*!< Request MailBox1 flag */ -#define CAN_FLAG_RQCP2 0x00000510U /*!< Request MailBox2 flag */ -#define CAN_FLAG_TXOK0 0x00000501U /*!< Transmission OK MailBox0 flag */ -#define CAN_FLAG_TXOK1 0x00000509U /*!< Transmission OK MailBox1 flag */ -#define CAN_FLAG_TXOK2 0x00000511U /*!< Transmission OK MailBox2 flag */ -#define CAN_FLAG_TME0 0x0000051AU /*!< Transmit mailbox 0 empty flag */ -#define CAN_FLAG_TME1 0x0000051BU /*!< Transmit mailbox 0 empty flag */ -#define CAN_FLAG_TME2 0x0000051CU /*!< Transmit mailbox 0 empty flag */ - -/* Receive Flags */ -#define CAN_FLAG_FF0 0x00000203U /*!< FIFO 0 Full flag */ -#define CAN_FLAG_FOV0 0x00000204U /*!< FIFO 0 Overrun flag */ - -#define CAN_FLAG_FF1 0x00000403U /*!< FIFO 1 Full flag */ -#define CAN_FLAG_FOV1 0x00000404U /*!< FIFO 1 Overrun flag */ - -/* Operating Mode Flags */ -#define CAN_FLAG_INAK 0x00000100U /*!< Initialization acknowledge flag */ -#define CAN_FLAG_SLAK 0x00000101U /*!< Sleep acknowledge flag */ -#define CAN_FLAG_ERRI 0x00000102U /*!< Error flag */ -#define CAN_FLAG_WKU 0x00000103U /*!< Wake up flag */ -#define CAN_FLAG_SLAKI 0x00000104U /*!< Sleep acknowledge flag */ - -/* @note When SLAK interrupt is disabled (SLKIE=0), no polling on SLAKI is possible. - In this case the SLAK bit can be polled.*/ - -/* Error Flags */ -#define CAN_FLAG_EWG 0x00000300U /*!< Error warning flag */ -#define CAN_FLAG_EPV 0x00000301U /*!< Error passive flag */ -#define CAN_FLAG_BOF 0x00000302U /*!< Bus-Off flag */ -/** - * @} - */ - -/** @defgroup CAN_Interrupts CAN Interrupts - * @{ - */ -#define CAN_IT_TME ((uint32_t)CAN_IER_TMEIE) /*!< Transmit mailbox empty interrupt */ - -/* Receive Interrupts */ -#define CAN_IT_FMP0 ((uint32_t)CAN_IER_FMPIE0) /*!< FIFO 0 message pending interrupt */ -#define CAN_IT_FF0 ((uint32_t)CAN_IER_FFIE0) /*!< FIFO 0 full interrupt */ -#define CAN_IT_FOV0 ((uint32_t)CAN_IER_FOVIE0) /*!< FIFO 0 overrun interrupt */ -#define CAN_IT_FMP1 ((uint32_t)CAN_IER_FMPIE1) /*!< FIFO 1 message pending interrupt */ -#define CAN_IT_FF1 ((uint32_t)CAN_IER_FFIE1) /*!< FIFO 1 full interrupt */ -#define CAN_IT_FOV1 ((uint32_t)CAN_IER_FOVIE1) /*!< FIFO 1 overrun interrupt */ - -/* Operating Mode Interrupts */ -#define CAN_IT_WKU ((uint32_t)CAN_IER_WKUIE) /*!< Wake-up interrupt */ -#define CAN_IT_SLK ((uint32_t)CAN_IER_SLKIE) /*!< Sleep acknowledge interrupt */ - -/* Error Interrupts */ -#define CAN_IT_EWG ((uint32_t)CAN_IER_EWGIE) /*!< Error warning interrupt */ -#define CAN_IT_EPV ((uint32_t)CAN_IER_EPVIE) /*!< Error passive interrupt */ -#define CAN_IT_BOF ((uint32_t)CAN_IER_BOFIE) /*!< Bus-off interrupt */ -#define CAN_IT_LEC ((uint32_t)CAN_IER_LECIE) /*!< Last error code interrupt */ -#define CAN_IT_ERR ((uint32_t)CAN_IER_ERRIE) /*!< Error Interrupt */ -/** - * @} - */ - -/** @defgroup CAN_Mailboxes_Definition CAN Mailboxes Definition - * @{ - */ -#define CAN_TXMAILBOX_0 ((uint8_t)0x00) -#define CAN_TXMAILBOX_1 ((uint8_t)0x01) -#define CAN_TXMAILBOX_2 ((uint8_t)0x02) -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup CAN_Exported_Macros CAN Exported Macros - * @{ - */ - -/** @brief Reset CAN handle state - * @param __HANDLE__ specifies the CAN Handle. - * @retval None - */ -#define __HAL_CAN_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_CAN_STATE_RESET) - -/** - * @brief Enable the specified CAN interrupts. - * @param __HANDLE__ CAN handle - * @param __INTERRUPT__ CAN Interrupt - * @retval None - */ -#define __HAL_CAN_ENABLE_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->IER) |= (__INTERRUPT__)) - -/** - * @brief Disable the specified CAN interrupts. - * @param __HANDLE__ CAN handle - * @param __INTERRUPT__ CAN Interrupt - * @retval None - */ -#define __HAL_CAN_DISABLE_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->IER) &= ~(__INTERRUPT__)) - -/** - * @brief Return the number of pending received messages. - * @param __HANDLE__ CAN handle - * @param __FIFONUMBER__ Receive FIFO number, CAN_FIFO0 or CAN_FIFO1. - * @retval The number of pending message. - */ -#define __HAL_CAN_MSG_PENDING(__HANDLE__, __FIFONUMBER__) (((__FIFONUMBER__) == CAN_FIFO0)? \ -((uint8_t)((__HANDLE__)->Instance->RF0R&0x03U)) : ((uint8_t)((__HANDLE__)->Instance->RF1R & 0x03U))) - -/** @brief Check whether the specified CAN flag is set or not. - * @param __HANDLE__ CAN Handle - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg CAN_TSR_RQCP0: Request MailBox0 Flag - * @arg CAN_TSR_RQCP1: Request MailBox1 Flag - * @arg CAN_TSR_RQCP2: Request MailBox2 Flag - * @arg CAN_FLAG_TXOK0: Transmission OK MailBox0 Flag - * @arg CAN_FLAG_TXOK1: Transmission OK MailBox1 Flag - * @arg CAN_FLAG_TXOK2: Transmission OK MailBox2 Flag - * @arg CAN_FLAG_TME0: Transmit mailbox 0 empty Flag - * @arg CAN_FLAG_TME1: Transmit mailbox 1 empty Flag - * @arg CAN_FLAG_TME2: Transmit mailbox 2 empty Flag - * @arg CAN_FLAG_FMP0: FIFO 0 Message Pending Flag - * @arg CAN_FLAG_FF0: FIFO 0 Full Flag - * @arg CAN_FLAG_FOV0: FIFO 0 Overrun Flag - * @arg CAN_FLAG_FMP1: FIFO 1 Message Pending Flag - * @arg CAN_FLAG_FF1: FIFO 1 Full Flag - * @arg CAN_FLAG_FOV1: FIFO 1 Overrun Flag - * @arg CAN_FLAG_WKU: Wake up Flag - * @arg CAN_FLAG_SLAK: Sleep acknowledge Flag - * @arg CAN_FLAG_SLAKI: Sleep acknowledge Flag - * @arg CAN_FLAG_EWG: Error Warning Flag - * @arg CAN_FLAG_EPV: Error Passive Flag - * @arg CAN_FLAG_BOF: Bus-Off Flag - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_CAN_GET_FLAG(__HANDLE__, __FLAG__) \ -((((__FLAG__) >> 8U) == 5U)? ((((__HANDLE__)->Instance->TSR) & (1U << ((__FLAG__) & CAN_FLAG_MASK))) == (1U << ((__FLAG__) & CAN_FLAG_MASK))): \ - (((__FLAG__) >> 8U) == 2U)? ((((__HANDLE__)->Instance->RF0R) & (1U << ((__FLAG__) & CAN_FLAG_MASK))) == (1U << ((__FLAG__) & CAN_FLAG_MASK))): \ - (((__FLAG__) >> 8U) == 4U)? ((((__HANDLE__)->Instance->RF1R) & (1U << ((__FLAG__) & CAN_FLAG_MASK))) == (1U << ((__FLAG__) & CAN_FLAG_MASK))): \ - (((__FLAG__) >> 8U) == 1U)? ((((__HANDLE__)->Instance->MSR) & (1U << ((__FLAG__) & CAN_FLAG_MASK))) == (1U << ((__FLAG__) & CAN_FLAG_MASK))): \ - ((((__HANDLE__)->Instance->ESR) & (1U << ((__FLAG__) & CAN_FLAG_MASK))) == (1U << ((__FLAG__) & CAN_FLAG_MASK)))) - -/** @brief Clear the specified CAN pending flag. - * @param __HANDLE__ CAN Handle. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg CAN_TSR_RQCP0: Request MailBox0 Flag - * @arg CAN_TSR_RQCP1: Request MailBox1 Flag - * @arg CAN_TSR_RQCP2: Request MailBox2 Flag - * @arg CAN_FLAG_TXOK0: Transmission OK MailBox0 Flag - * @arg CAN_FLAG_TXOK1: Transmission OK MailBox1 Flag - * @arg CAN_FLAG_TXOK2: Transmission OK MailBox2 Flag - * @arg CAN_FLAG_TME0: Transmit mailbox 0 empty Flag - * @arg CAN_FLAG_TME1: Transmit mailbox 1 empty Flag - * @arg CAN_FLAG_TME2: Transmit mailbox 2 empty Flag - * @arg CAN_FLAG_FMP0: FIFO 0 Message Pending Flag - * @arg CAN_FLAG_FF0: FIFO 0 Full Flag - * @arg CAN_FLAG_FOV0: FIFO 0 Overrun Flag - * @arg CAN_FLAG_FMP1: FIFO 1 Message Pending Flag - * @arg CAN_FLAG_FF1: FIFO 1 Full Flag - * @arg CAN_FLAG_FOV1: FIFO 1 Overrun Flag - * @arg CAN_FLAG_WKU: Wake up Flag - * @arg CAN_FLAG_SLAK: Sleep acknowledge Flag - * @arg CAN_FLAG_SLAKI: Sleep acknowledge Flag - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_CAN_CLEAR_FLAG(__HANDLE__, __FLAG__) \ -((((__FLAG__) >> 8U) == 5U)? (((__HANDLE__)->Instance->TSR) = (1U << ((__FLAG__) & CAN_FLAG_MASK))): \ - (((__FLAG__) >> 8U) == 2U)? (((__HANDLE__)->Instance->RF0R) = (1U << ((__FLAG__) & CAN_FLAG_MASK))): \ - (((__FLAG__) >> 8U) == 4U)? (((__HANDLE__)->Instance->RF1R) = (1U << ((__FLAG__) & CAN_FLAG_MASK))): \ - (((__HANDLE__)->Instance->MSR) = ((uint32_t)1U << ((__FLAG__) & CAN_FLAG_MASK)))) - -/** @brief Check if the specified CAN interrupt source is enabled or disabled. - * @param __HANDLE__ CAN Handle - * @param __INTERRUPT__ specifies the CAN interrupt source to check. - * This parameter can be one of the following values: - * @arg CAN_IT_TME: Transmit mailbox empty interrupt enable - * @arg CAN_IT_FMP0: FIFO0 message pending interrupt enable - * @arg CAN_IT_FMP1: FIFO1 message pending interrupt enable - * @retval The new state of __IT__ (TRUE or FALSE). - */ -#define __HAL_CAN_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((((__HANDLE__)->Instance->IER & (__INTERRUPT__)) == (__INTERRUPT__)) ? SET : RESET) - -/** - * @brief Check the transmission status of a CAN Frame. - * @param __HANDLE__ CAN Handle - * @param __TRANSMITMAILBOX__ the number of the mailbox that is used for transmission. - * @retval The new status of transmission (TRUE or FALSE). - */ -#define __HAL_CAN_TRANSMIT_STATUS(__HANDLE__, __TRANSMITMAILBOX__)\ -(((__TRANSMITMAILBOX__) == CAN_TXMAILBOX_0)? ((((__HANDLE__)->Instance->TSR) & (CAN_TSR_RQCP0 | CAN_TSR_TXOK0 | CAN_TSR_TME0)) == (CAN_TSR_RQCP0 | CAN_TSR_TXOK0 | CAN_TSR_TME0)) :\ - ((__TRANSMITMAILBOX__) == CAN_TXMAILBOX_1)? ((((__HANDLE__)->Instance->TSR) & (CAN_TSR_RQCP1 | CAN_TSR_TXOK1 | CAN_TSR_TME1)) == (CAN_TSR_RQCP1 | CAN_TSR_TXOK1 | CAN_TSR_TME1)) :\ - ((((__HANDLE__)->Instance->TSR) & (CAN_TSR_RQCP2 | CAN_TSR_TXOK2 | CAN_TSR_TME2)) == (CAN_TSR_RQCP2 | CAN_TSR_TXOK2 | CAN_TSR_TME2))) - -/** - * @brief Release the specified receive FIFO. - * @param __HANDLE__ CAN handle - * @param __FIFONUMBER__ Receive FIFO number, CAN_FIFO0 or CAN_FIFO1. - * @retval None - */ -#define __HAL_CAN_FIFO_RELEASE(__HANDLE__, __FIFONUMBER__) (((__FIFONUMBER__) == CAN_FIFO0)? \ -((__HANDLE__)->Instance->RF0R = CAN_RF0R_RFOM0) : ((__HANDLE__)->Instance->RF1R = CAN_RF1R_RFOM1)) - -/** - * @brief Cancel a transmit request. - * @param __HANDLE__ CAN Handle - * @param __TRANSMITMAILBOX__ the number of the mailbox that is used for transmission. - * @retval None - */ -#define __HAL_CAN_CANCEL_TRANSMIT(__HANDLE__, __TRANSMITMAILBOX__)\ -(((__TRANSMITMAILBOX__) == CAN_TXMAILBOX_0)? ((__HANDLE__)->Instance->TSR = CAN_TSR_ABRQ0) :\ - ((__TRANSMITMAILBOX__) == CAN_TXMAILBOX_1)? ((__HANDLE__)->Instance->TSR = CAN_TSR_ABRQ1) :\ - ((__HANDLE__)->Instance->TSR = CAN_TSR_ABRQ2)) - -/** - * @brief Enable or disable the DBG Freeze for CAN. - * @param __HANDLE__ CAN Handle - * @param __NEWSTATE__ new state of the CAN peripheral. - * This parameter can be: ENABLE (CAN reception/transmission is frozen - * during debug. Reception FIFOs can still be accessed/controlled normally) - * or DISABLE (CAN is working during debug). - * @retval None - */ -#define __HAL_CAN_DBG_FREEZE(__HANDLE__, __NEWSTATE__) (((__NEWSTATE__) == ENABLE)? \ -((__HANDLE__)->Instance->MCR |= CAN_MCR_DBF) : ((__HANDLE__)->Instance->MCR &= ~CAN_MCR_DBF)) - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup CAN_Exported_Functions - * @{ - */ - -/** @addtogroup CAN_Exported_Functions_Group1 - * @{ - */ -/* Initialization/de-initialization functions ***********************************/ -HAL_StatusTypeDef HAL_CAN_Init(CAN_HandleTypeDef* hcan); -HAL_StatusTypeDef HAL_CAN_ConfigFilter(CAN_HandleTypeDef* hcan, CAN_FilterConfTypeDef* sFilterConfig); -HAL_StatusTypeDef HAL_CAN_DeInit(CAN_HandleTypeDef* hcan); -void HAL_CAN_MspInit(CAN_HandleTypeDef* hcan); -void HAL_CAN_MspDeInit(CAN_HandleTypeDef* hcan); -/** - * @} - */ - -/** @addtogroup CAN_Exported_Functions_Group2 - * @{ - */ -/* I/O operation functions ******************************************************/ -HAL_StatusTypeDef HAL_CAN_Transmit(CAN_HandleTypeDef *hcan, uint32_t Timeout); -HAL_StatusTypeDef HAL_CAN_Transmit_IT(CAN_HandleTypeDef *hcan); -HAL_StatusTypeDef HAL_CAN_Receive(CAN_HandleTypeDef *hcan, uint8_t FIFONumber, uint32_t Timeout); -HAL_StatusTypeDef HAL_CAN_Receive_IT(CAN_HandleTypeDef *hcan, uint8_t FIFONumber); -HAL_StatusTypeDef HAL_CAN_Sleep(CAN_HandleTypeDef *hcan); -HAL_StatusTypeDef HAL_CAN_WakeUp(CAN_HandleTypeDef *hcan); -void HAL_CAN_IRQHandler(CAN_HandleTypeDef* hcan); -void HAL_CAN_TxCpltCallback(CAN_HandleTypeDef* hcan); -void HAL_CAN_RxCpltCallback(CAN_HandleTypeDef* hcan); -void HAL_CAN_ErrorCallback(CAN_HandleTypeDef *hcan); -/** - * @} - */ - -/** @addtogroup CAN_Exported_Functions_Group3 - * @{ - */ -/* Peripheral State functions ***************************************************/ -uint32_t HAL_CAN_GetError(CAN_HandleTypeDef *hcan); -HAL_CAN_StateTypeDef HAL_CAN_GetState(CAN_HandleTypeDef* hcan); -/** - * @} - */ - -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/** @defgroup CAN_Private_Types CAN Private Types - * @{ - */ - -/** - * @} - */ - -/* Private variables ---------------------------------------------------------*/ -/** @defgroup CAN_Private_Variables CAN Private Variables - * @{ - */ - -/** - * @} - */ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup CAN_Private_Constants CAN Private Constants - * @{ - */ -#define CAN_TXSTATUS_NOMAILBOX ((uint8_t)0x04) /*!< CAN cell did not provide CAN_TxStatus_NoMailBox */ -#define CAN_FLAG_MASK 0x000000FFU -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup CAN_Private_Macros CAN Private Macros - * @{ - */ -#define IS_CAN_MODE(MODE) (((MODE) == CAN_MODE_NORMAL) || \ - ((MODE) == CAN_MODE_LOOPBACK)|| \ - ((MODE) == CAN_MODE_SILENT) || \ - ((MODE) == CAN_MODE_SILENT_LOOPBACK)) -#define IS_CAN_SJW(SJW) (((SJW) == CAN_SJW_1TQ) || ((SJW) == CAN_SJW_2TQ)|| \ - ((SJW) == CAN_SJW_3TQ) || ((SJW) == CAN_SJW_4TQ)) -#define IS_CAN_BS1(BS1) ((BS1) <= CAN_BS1_16TQ) -#define IS_CAN_BS2(BS2) ((BS2) <= CAN_BS2_8TQ) -#define IS_CAN_PRESCALER(PRESCALER) (((PRESCALER) >= 1U) && ((PRESCALER) <= 1024U)) -#define IS_CAN_FILTER_NUMBER(NUMBER) ((NUMBER) <= 27U) -#define IS_CAN_FILTER_MODE(MODE) (((MODE) == CAN_FILTERMODE_IDMASK) || \ - ((MODE) == CAN_FILTERMODE_IDLIST)) -#define IS_CAN_FILTER_SCALE(SCALE) (((SCALE) == CAN_FILTERSCALE_16BIT) || \ - ((SCALE) == CAN_FILTERSCALE_32BIT)) -#define IS_CAN_FILTER_FIFO(FIFO) (((FIFO) == CAN_FILTER_FIFO0) || \ - ((FIFO) == CAN_FILTER_FIFO1)) -#define IS_CAN_BANKNUMBER(BANKNUMBER) ((BANKNUMBER) <= 28U) - -#define IS_CAN_TRANSMITMAILBOX(TRANSMITMAILBOX) ((TRANSMITMAILBOX) <= ((uint8_t)0x02)) -#define IS_CAN_STDID(STDID) ((STDID) <= ((uint32_t)0x7FFU)) -#define IS_CAN_EXTID(EXTID) ((EXTID) <= 0x1FFFFFFFU) -#define IS_CAN_DLC(DLC) ((DLC) <= ((uint8_t)0x08)) - -#define IS_CAN_IDTYPE(IDTYPE) (((IDTYPE) == CAN_ID_STD) || \ - ((IDTYPE) == CAN_ID_EXT)) -#define IS_CAN_RTR(RTR) (((RTR) == CAN_RTR_DATA) || ((RTR) == CAN_RTR_REMOTE)) -#define IS_CAN_FIFO(FIFO) (((FIFO) == CAN_FIFO0) || ((FIFO) == CAN_FIFO1)) - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup CAN_Private_Functions CAN Private Functions - * @{ - */ - -/** - * @} - */ - -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx ||\ - STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx ||\ - STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_CAN_LEGACY_H */ - - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32_assert_template.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32_assert_template.h deleted file mode 100644 index 4711b65..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32_assert_template.h +++ /dev/null @@ -1,57 +0,0 @@ -/** - ****************************************************************************** - * @file stm32_assert.h - * @author MCD Application Team - * @brief STM32 assert template file. - * This file should be copied to the application folder and renamed - * to stm32_assert.h. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32_ASSERT_H -#define __STM32_ASSERT_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/* Includes ------------------------------------------------------------------*/ -/* Exported macro ------------------------------------------------------------*/ -#ifdef USE_FULL_ASSERT -/** - * @brief The assert_param macro is used for function's parameters check. - * @param expr If expr is false, it calls assert_failed function - * which reports the name of the source file and the source - * line number of the call that failed. - * If expr is true, it returns no value. - * @retval None - */ - #define assert_param(expr) ((expr) ? (void)0U : assert_failed((uint8_t *)__FILE__, __LINE__)) -/* Exported functions ------------------------------------------------------- */ - void assert_failed(uint8_t* file, uint32_t line); -#else - #define assert_param(expr) ((void)0U) -#endif /* USE_FULL_ASSERT */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32_ASSERT_H */ - - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal.h deleted file mode 100644 index 209864d..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal.h +++ /dev/null @@ -1,298 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal.h - * @author MCD Application Team - * @brief This file contains all the functions prototypes for the HAL - * module driver. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_H -#define __STM32F4xx_HAL_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_conf.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup HAL - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ - -/** @defgroup HAL_Exported_Constants HAL Exported Constants - * @{ - */ - -/** @defgroup HAL_TICK_FREQ Tick Frequency - * @{ - */ -typedef enum -{ - HAL_TICK_FREQ_10HZ = 100U, - HAL_TICK_FREQ_100HZ = 10U, - HAL_TICK_FREQ_1KHZ = 1U, - HAL_TICK_FREQ_DEFAULT = HAL_TICK_FREQ_1KHZ -} HAL_TickFreqTypeDef; -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup HAL_Exported_Macros HAL Exported Macros - * @{ - */ - -/** @brief Freeze/Unfreeze Peripherals in Debug mode - */ -#define __HAL_DBGMCU_FREEZE_TIM2() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM2_STOP)) -#define __HAL_DBGMCU_FREEZE_TIM3() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM3_STOP)) -#define __HAL_DBGMCU_FREEZE_TIM4() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM4_STOP)) -#define __HAL_DBGMCU_FREEZE_TIM5() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM5_STOP)) -#define __HAL_DBGMCU_FREEZE_TIM6() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM6_STOP)) -#define __HAL_DBGMCU_FREEZE_TIM7() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM7_STOP)) -#define __HAL_DBGMCU_FREEZE_TIM12() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM12_STOP)) -#define __HAL_DBGMCU_FREEZE_TIM13() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM13_STOP)) -#define __HAL_DBGMCU_FREEZE_TIM14() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_TIM14_STOP)) -#define __HAL_DBGMCU_FREEZE_RTC() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_RTC_STOP)) -#define __HAL_DBGMCU_FREEZE_WWDG() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_WWDG_STOP)) -#define __HAL_DBGMCU_FREEZE_IWDG() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_IWDG_STOP)) -#define __HAL_DBGMCU_FREEZE_I2C1_TIMEOUT() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_I2C1_SMBUS_TIMEOUT)) -#define __HAL_DBGMCU_FREEZE_I2C2_TIMEOUT() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_I2C2_SMBUS_TIMEOUT)) -#define __HAL_DBGMCU_FREEZE_I2C3_TIMEOUT() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_I2C3_SMBUS_TIMEOUT)) -#define __HAL_DBGMCU_FREEZE_CAN1() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_CAN1_STOP)) -#define __HAL_DBGMCU_FREEZE_CAN2() (DBGMCU->APB1FZ |= (DBGMCU_APB1_FZ_DBG_CAN2_STOP)) -#define __HAL_DBGMCU_FREEZE_TIM1() (DBGMCU->APB2FZ |= (DBGMCU_APB2_FZ_DBG_TIM1_STOP)) -#define __HAL_DBGMCU_FREEZE_TIM8() (DBGMCU->APB2FZ |= (DBGMCU_APB2_FZ_DBG_TIM8_STOP)) -#define __HAL_DBGMCU_FREEZE_TIM9() (DBGMCU->APB2FZ |= (DBGMCU_APB2_FZ_DBG_TIM9_STOP)) -#define __HAL_DBGMCU_FREEZE_TIM10() (DBGMCU->APB2FZ |= (DBGMCU_APB2_FZ_DBG_TIM10_STOP)) -#define __HAL_DBGMCU_FREEZE_TIM11() (DBGMCU->APB2FZ |= (DBGMCU_APB2_FZ_DBG_TIM11_STOP)) - -#define __HAL_DBGMCU_UNFREEZE_TIM2() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM2_STOP)) -#define __HAL_DBGMCU_UNFREEZE_TIM3() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM3_STOP)) -#define __HAL_DBGMCU_UNFREEZE_TIM4() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM4_STOP)) -#define __HAL_DBGMCU_UNFREEZE_TIM5() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM5_STOP)) -#define __HAL_DBGMCU_UNFREEZE_TIM6() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM6_STOP)) -#define __HAL_DBGMCU_UNFREEZE_TIM7() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM7_STOP)) -#define __HAL_DBGMCU_UNFREEZE_TIM12() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM12_STOP)) -#define __HAL_DBGMCU_UNFREEZE_TIM13() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM13_STOP)) -#define __HAL_DBGMCU_UNFREEZE_TIM14() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_TIM14_STOP)) -#define __HAL_DBGMCU_UNFREEZE_RTC() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_RTC_STOP)) -#define __HAL_DBGMCU_UNFREEZE_WWDG() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_WWDG_STOP)) -#define __HAL_DBGMCU_UNFREEZE_IWDG() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_IWDG_STOP)) -#define __HAL_DBGMCU_UNFREEZE_I2C1_TIMEOUT() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_I2C1_SMBUS_TIMEOUT)) -#define __HAL_DBGMCU_UNFREEZE_I2C2_TIMEOUT() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_I2C2_SMBUS_TIMEOUT)) -#define __HAL_DBGMCU_UNFREEZE_I2C3_TIMEOUT() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_I2C3_SMBUS_TIMEOUT)) -#define __HAL_DBGMCU_UNFREEZE_CAN1() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_CAN1_STOP)) -#define __HAL_DBGMCU_UNFREEZE_CAN2() (DBGMCU->APB1FZ &= ~(DBGMCU_APB1_FZ_DBG_CAN2_STOP)) -#define __HAL_DBGMCU_UNFREEZE_TIM1() (DBGMCU->APB2FZ &= ~(DBGMCU_APB2_FZ_DBG_TIM1_STOP)) -#define __HAL_DBGMCU_UNFREEZE_TIM8() (DBGMCU->APB2FZ &= ~(DBGMCU_APB2_FZ_DBG_TIM8_STOP)) -#define __HAL_DBGMCU_UNFREEZE_TIM9() (DBGMCU->APB2FZ &= ~(DBGMCU_APB2_FZ_DBG_TIM9_STOP)) -#define __HAL_DBGMCU_UNFREEZE_TIM10() (DBGMCU->APB2FZ &= ~(DBGMCU_APB2_FZ_DBG_TIM10_STOP)) -#define __HAL_DBGMCU_UNFREEZE_TIM11() (DBGMCU->APB2FZ &= ~(DBGMCU_APB2_FZ_DBG_TIM11_STOP)) - -/** @brief Main Flash memory mapped at 0x00000000 - */ -#define __HAL_SYSCFG_REMAPMEMORY_FLASH() (SYSCFG->MEMRMP &= ~(SYSCFG_MEMRMP_MEM_MODE)) - -/** @brief System Flash memory mapped at 0x00000000 - */ -#define __HAL_SYSCFG_REMAPMEMORY_SYSTEMFLASH() do {SYSCFG->MEMRMP &= ~(SYSCFG_MEMRMP_MEM_MODE);\ - SYSCFG->MEMRMP |= SYSCFG_MEMRMP_MEM_MODE_0;\ - }while(0); - -/** @brief Embedded SRAM mapped at 0x00000000 - */ -#define __HAL_SYSCFG_REMAPMEMORY_SRAM() do {SYSCFG->MEMRMP &= ~(SYSCFG_MEMRMP_MEM_MODE);\ - SYSCFG->MEMRMP |= (SYSCFG_MEMRMP_MEM_MODE_0 | SYSCFG_MEMRMP_MEM_MODE_1);\ - }while(0); - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx)|| defined(STM32F417xx) -/** @brief FSMC Bank1 (NOR/PSRAM 1 and 2) mapped at 0x00000000 - */ -#define __HAL_SYSCFG_REMAPMEMORY_FSMC() do {SYSCFG->MEMRMP &= ~(SYSCFG_MEMRMP_MEM_MODE);\ - SYSCFG->MEMRMP |= (SYSCFG_MEMRMP_MEM_MODE_1);\ - }while(0); -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx)|| defined(STM32F439xx) ||\ - defined(STM32F469xx) || defined(STM32F479xx) -/** @brief FMC Bank1 (NOR/PSRAM 1 and 2) mapped at 0x00000000 - */ -#define __HAL_SYSCFG_REMAPMEMORY_FMC() do {SYSCFG->MEMRMP &= ~(SYSCFG_MEMRMP_MEM_MODE);\ - SYSCFG->MEMRMP |= (SYSCFG_MEMRMP_MEM_MODE_1);\ - }while(0); - -/** @brief FMC/SDRAM Bank 1 and 2 mapped at 0x00000000 - */ -#define __HAL_SYSCFG_REMAPMEMORY_FMC_SDRAM() do {SYSCFG->MEMRMP &= ~(SYSCFG_MEMRMP_MEM_MODE);\ - SYSCFG->MEMRMP |= (SYSCFG_MEMRMP_MEM_MODE_2);\ - }while(0); -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F413xx) || defined(STM32F423xx) -/** @defgroup Cortex_Lockup_Enable Cortex Lockup Enable - * @{ - */ -/** @brief SYSCFG Break Lockup lock - * Enables and locks the connection of Cortex-M4 LOCKUP (Hardfault) output to TIM1/8 input - * @note The selected configuration is locked and can be unlocked by system reset - */ -#define __HAL_SYSCFG_BREAK_PVD_LOCK() do {SYSCFG->CFGR2 &= ~(SYSCFG_CFGR2_PVD_LOCK); \ - SYSCFG->CFGR2 |= SYSCFG_CFGR2_PVD_LOCK; \ - }while(0) -/** - * @} - */ - -/** @defgroup PVD_Lock_Enable PVD Lock - * @{ - */ -/** @brief SYSCFG Break PVD lock - * Enables and locks the PVD connection with Timer1/8 Break Input, , as well as the PVDE and PLS[2:0] in the PWR_CR register - * @note The selected configuration is locked and can be unlocked by system reset - */ -#define __HAL_SYSCFG_BREAK_LOCKUP_LOCK() do {SYSCFG->CFGR2 &= ~(SYSCFG_CFGR2_LOCKUP_LOCK); \ - SYSCFG->CFGR2 |= SYSCFG_CFGR2_LOCKUP_LOCK; \ - }while(0) -/** - * @} - */ -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx || STM32F413xx || STM32F423xx */ -/** - * @} - */ - -/** @defgroup HAL_Private_Macros HAL Private Macros - * @{ - */ -#define IS_TICKFREQ(FREQ) (((FREQ) == HAL_TICK_FREQ_10HZ) || \ - ((FREQ) == HAL_TICK_FREQ_100HZ) || \ - ((FREQ) == HAL_TICK_FREQ_1KHZ)) -/** - * @} - */ - -/* Exported variables --------------------------------------------------------*/ - -/** @addtogroup HAL_Exported_Variables - * @{ - */ -extern __IO uint32_t uwTick; -extern uint32_t uwTickPrio; -extern HAL_TickFreqTypeDef uwTickFreq; -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup HAL_Exported_Functions - * @{ - */ -/** @addtogroup HAL_Exported_Functions_Group1 - * @{ - */ -/* Initialization and Configuration functions ******************************/ -HAL_StatusTypeDef HAL_Init(void); -HAL_StatusTypeDef HAL_DeInit(void); -void HAL_MspInit(void); -void HAL_MspDeInit(void); -HAL_StatusTypeDef HAL_InitTick (uint32_t TickPriority); -/** - * @} - */ - -/** @addtogroup HAL_Exported_Functions_Group2 - * @{ - */ -/* Peripheral Control functions ************************************************/ -void HAL_IncTick(void); -void HAL_Delay(uint32_t Delay); -uint32_t HAL_GetTick(void); -uint32_t HAL_GetTickPrio(void); -HAL_StatusTypeDef HAL_SetTickFreq(HAL_TickFreqTypeDef Freq); -HAL_TickFreqTypeDef HAL_GetTickFreq(void); -void HAL_SuspendTick(void); -void HAL_ResumeTick(void); -uint32_t HAL_GetHalVersion(void); -uint32_t HAL_GetREVID(void); -uint32_t HAL_GetDEVID(void); -void HAL_DBGMCU_EnableDBGSleepMode(void); -void HAL_DBGMCU_DisableDBGSleepMode(void); -void HAL_DBGMCU_EnableDBGStopMode(void); -void HAL_DBGMCU_DisableDBGStopMode(void); -void HAL_DBGMCU_EnableDBGStandbyMode(void); -void HAL_DBGMCU_DisableDBGStandbyMode(void); -void HAL_EnableCompensationCell(void); -void HAL_DisableCompensationCell(void); -uint32_t HAL_GetUIDw0(void); -uint32_t HAL_GetUIDw1(void); -uint32_t HAL_GetUIDw2(void); -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx)|| defined(STM32F439xx) ||\ - defined(STM32F469xx) || defined(STM32F479xx) -void HAL_EnableMemorySwappingBank(void); -void HAL_DisableMemorySwappingBank(void); -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ -/** - * @} - */ - -/** - * @} - */ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/** @defgroup HAL_Private_Variables HAL Private Variables - * @{ - */ -/** - * @} - */ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup HAL_Private_Constants HAL Private Constants - * @{ - */ -/** - * @} - */ -/* Private macros ------------------------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc.h deleted file mode 100644 index a041e76..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc.h +++ /dev/null @@ -1,900 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_adc.h - * @author MCD Application Team - * @brief Header file containing functions prototypes of ADC HAL library. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_ADC_H -#define __STM32F4xx_ADC_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/* Include low level driver */ -#include "stm32f4xx_ll_adc.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup ADC - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup ADC_Exported_Types ADC Exported Types - * @{ - */ - -/** - * @brief Structure definition of ADC and regular group initialization - * @note Parameters of this structure are shared within 2 scopes: - * - Scope entire ADC (affects regular and injected groups): ClockPrescaler, Resolution, ScanConvMode, DataAlign, ScanConvMode, EOCSelection, LowPowerAutoWait, LowPowerAutoPowerOff, ChannelsBank. - * - Scope regular group: ContinuousConvMode, NbrOfConversion, DiscontinuousConvMode, NbrOfDiscConversion, ExternalTrigConvEdge, ExternalTrigConv. - * @note The setting of these parameters with function HAL_ADC_Init() is conditioned to ADC state. - * ADC state can be either: - * - For all parameters: ADC disabled - * - For all parameters except 'Resolution', 'ScanConvMode', 'DiscontinuousConvMode', 'NbrOfDiscConversion' : ADC enabled without conversion on going on regular group. - * - For parameters 'ExternalTrigConv' and 'ExternalTrigConvEdge': ADC enabled, even with conversion on going. - * If ADC is not in the appropriate state to modify some parameters, these parameters setting is bypassed - * without error reporting (as it can be the expected behaviour in case of intended action to update another parameter (which fulfills the ADC state condition) on the fly). - */ -typedef struct -{ - uint32_t ClockPrescaler; /*!< Select ADC clock prescaler. The clock is common for - all the ADCs. - This parameter can be a value of @ref ADC_ClockPrescaler */ - uint32_t Resolution; /*!< Configures the ADC resolution. - This parameter can be a value of @ref ADC_Resolution */ - uint32_t DataAlign; /*!< Specifies ADC data alignment to right (MSB on register bit 11 and LSB on register bit 0) (default setting) - or to left (if regular group: MSB on register bit 15 and LSB on register bit 4, if injected group (MSB kept as signed value due to potential negative value after offset application): MSB on register bit 14 and LSB on register bit 3). - This parameter can be a value of @ref ADC_Data_align */ - uint32_t ScanConvMode; /*!< Configures the sequencer of regular and injected groups. - This parameter can be associated to parameter 'DiscontinuousConvMode' to have main sequence subdivided in successive parts. - If disabled: Conversion is performed in single mode (one channel converted, the one defined in rank 1). - Parameters 'NbrOfConversion' and 'InjectedNbrOfConversion' are discarded (equivalent to set to 1). - If enabled: Conversions are performed in sequence mode (multiple ranks defined by 'NbrOfConversion'/'InjectedNbrOfConversion' and each channel rank). - Scan direction is upward: from rank1 to rank 'n'. - This parameter can be set to ENABLE or DISABLE */ - uint32_t EOCSelection; /*!< Specifies what EOC (End Of Conversion) flag is used for conversion by polling and interruption: end of conversion of each rank or complete sequence. - This parameter can be a value of @ref ADC_EOCSelection. - Note: For injected group, end of conversion (flag&IT) is raised only at the end of the sequence. - Therefore, if end of conversion is set to end of each conversion, injected group should not be used with interruption (HAL_ADCEx_InjectedStart_IT) - or polling (HAL_ADCEx_InjectedStart and HAL_ADCEx_InjectedPollForConversion). By the way, polling is still possible since driver will use an estimated timing for end of injected conversion. - Note: If overrun feature is intended to be used, use ADC in mode 'interruption' (function HAL_ADC_Start_IT() ) with parameter EOCSelection set to end of each conversion or in mode 'transfer by DMA' (function HAL_ADC_Start_DMA()). - If overrun feature is intended to be bypassed, use ADC in mode 'polling' or 'interruption' with parameter EOCSelection must be set to end of sequence */ - FunctionalState ContinuousConvMode; /*!< Specifies whether the conversion is performed in single mode (one conversion) or continuous mode for regular group, - after the selected trigger occurred (software start or external trigger). - This parameter can be set to ENABLE or DISABLE. */ - uint32_t NbrOfConversion; /*!< Specifies the number of ranks that will be converted within the regular group sequencer. - To use regular group sequencer and convert several ranks, parameter 'ScanConvMode' must be enabled. - This parameter must be a number between Min_Data = 1 and Max_Data = 16. */ - FunctionalState DiscontinuousConvMode; /*!< Specifies whether the conversions sequence of regular group is performed in Complete-sequence/Discontinuous-sequence (main sequence subdivided in successive parts). - Discontinuous mode is used only if sequencer is enabled (parameter 'ScanConvMode'). If sequencer is disabled, this parameter is discarded. - Discontinuous mode can be enabled only if continuous mode is disabled. If continuous mode is enabled, this parameter setting is discarded. - This parameter can be set to ENABLE or DISABLE. */ - uint32_t NbrOfDiscConversion; /*!< Specifies the number of discontinuous conversions in which the main sequence of regular group (parameter NbrOfConversion) will be subdivided. - If parameter 'DiscontinuousConvMode' is disabled, this parameter is discarded. - This parameter must be a number between Min_Data = 1 and Max_Data = 8. */ - uint32_t ExternalTrigConv; /*!< Selects the external event used to trigger the conversion start of regular group. - If set to ADC_SOFTWARE_START, external triggers are disabled. - If set to external trigger source, triggering is on event rising edge by default. - This parameter can be a value of @ref ADC_External_trigger_Source_Regular */ - uint32_t ExternalTrigConvEdge; /*!< Selects the external trigger edge of regular group. - If trigger is set to ADC_SOFTWARE_START, this parameter is discarded. - This parameter can be a value of @ref ADC_External_trigger_edge_Regular */ - FunctionalState DMAContinuousRequests; /*!< Specifies whether the DMA requests are performed in one shot mode (DMA transfer stop when number of conversions is reached) - or in Continuous mode (DMA transfer unlimited, whatever number of conversions). - Note: In continuous mode, DMA must be configured in circular mode. Otherwise an overrun will be triggered when DMA buffer maximum pointer is reached. - Note: This parameter must be modified when no conversion is on going on both regular and injected groups (ADC disabled, or ADC enabled without continuous mode or external trigger that could launch a conversion). - This parameter can be set to ENABLE or DISABLE. */ -}ADC_InitTypeDef; - - - -/** - * @brief Structure definition of ADC channel for regular group - * @note The setting of these parameters with function HAL_ADC_ConfigChannel() is conditioned to ADC state. - * ADC can be either disabled or enabled without conversion on going on regular group. - */ -typedef struct -{ - uint32_t Channel; /*!< Specifies the channel to configure into ADC regular group. - This parameter can be a value of @ref ADC_channels */ - uint32_t Rank; /*!< Specifies the rank in the regular group sequencer. - This parameter must be a number between Min_Data = 1 and Max_Data = 16 */ - uint32_t SamplingTime; /*!< Sampling time value to be set for the selected channel. - Unit: ADC clock cycles - Conversion time is the addition of sampling time and processing time (12 ADC clock cycles at ADC resolution 12 bits, 11 cycles at 10 bits, 9 cycles at 8 bits, 7 cycles at 6 bits). - This parameter can be a value of @ref ADC_sampling_times - Caution: This parameter updates the parameter property of the channel, that can be used into regular and/or injected groups. - If this same channel has been previously configured in the other group (regular/injected), it will be updated to last setting. - Note: In case of usage of internal measurement channels (VrefInt/Vbat/TempSensor), - sampling time constraints must be respected (sampling time can be adjusted in function of ADC clock frequency and sampling time setting) - Refer to device datasheet for timings values, parameters TS_vrefint, TS_temp (values rough order: 4us min). */ - uint32_t Offset; /*!< Reserved for future use, can be set to 0 */ -}ADC_ChannelConfTypeDef; - -/** - * @brief ADC Configuration multi-mode structure definition - */ -typedef struct -{ - uint32_t WatchdogMode; /*!< Configures the ADC analog watchdog mode. - This parameter can be a value of @ref ADC_analog_watchdog_selection */ - uint32_t HighThreshold; /*!< Configures the ADC analog watchdog High threshold value. - This parameter must be a 12-bit value. */ - uint32_t LowThreshold; /*!< Configures the ADC analog watchdog High threshold value. - This parameter must be a 12-bit value. */ - uint32_t Channel; /*!< Configures ADC channel for the analog watchdog. - This parameter has an effect only if watchdog mode is configured on single channel - This parameter can be a value of @ref ADC_channels */ - FunctionalState ITMode; /*!< Specifies whether the analog watchdog is configured - is interrupt mode or in polling mode. - This parameter can be set to ENABLE or DISABLE */ - uint32_t WatchdogNumber; /*!< Reserved for future use, can be set to 0 */ -}ADC_AnalogWDGConfTypeDef; - -/** - * @brief HAL ADC state machine: ADC states definition (bitfields) - */ -/* States of ADC global scope */ -#define HAL_ADC_STATE_RESET 0x00000000U /*!< ADC not yet initialized or disabled */ -#define HAL_ADC_STATE_READY 0x00000001U /*!< ADC peripheral ready for use */ -#define HAL_ADC_STATE_BUSY_INTERNAL 0x00000002U /*!< ADC is busy to internal process (initialization, calibration) */ -#define HAL_ADC_STATE_TIMEOUT 0x00000004U /*!< TimeOut occurrence */ - -/* States of ADC errors */ -#define HAL_ADC_STATE_ERROR_INTERNAL 0x00000010U /*!< Internal error occurrence */ -#define HAL_ADC_STATE_ERROR_CONFIG 0x00000020U /*!< Configuration error occurrence */ -#define HAL_ADC_STATE_ERROR_DMA 0x00000040U /*!< DMA error occurrence */ - -/* States of ADC group regular */ -#define HAL_ADC_STATE_REG_BUSY 0x00000100U /*!< A conversion on group regular is ongoing or can occur (either by continuous mode, - external trigger, low power auto power-on (if feature available), multimode ADC master control (if feature available)) */ -#define HAL_ADC_STATE_REG_EOC 0x00000200U /*!< Conversion data available on group regular */ -#define HAL_ADC_STATE_REG_OVR 0x00000400U /*!< Overrun occurrence */ - -/* States of ADC group injected */ -#define HAL_ADC_STATE_INJ_BUSY 0x00001000U /*!< A conversion on group injected is ongoing or can occur (either by auto-injection mode, - external trigger, low power auto power-on (if feature available), multimode ADC master control (if feature available)) */ -#define HAL_ADC_STATE_INJ_EOC 0x00002000U /*!< Conversion data available on group injected */ - -/* States of ADC analog watchdogs */ -#define HAL_ADC_STATE_AWD1 0x00010000U /*!< Out-of-window occurrence of analog watchdog 1 */ -#define HAL_ADC_STATE_AWD2 0x00020000U /*!< Not available on STM32F4 device: Out-of-window occurrence of analog watchdog 2 */ -#define HAL_ADC_STATE_AWD3 0x00040000U /*!< Not available on STM32F4 device: Out-of-window occurrence of analog watchdog 3 */ - -/* States of ADC multi-mode */ -#define HAL_ADC_STATE_MULTIMODE_SLAVE 0x00100000U /*!< Not available on STM32F4 device: ADC in multimode slave state, controlled by another ADC master ( */ - - -/** - * @brief ADC handle Structure definition - */ -#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) -typedef struct __ADC_HandleTypeDef -#else -typedef struct -#endif -{ - ADC_TypeDef *Instance; /*!< Register base address */ - - ADC_InitTypeDef Init; /*!< ADC required parameters */ - - __IO uint32_t NbrOfCurrentConversionRank; /*!< ADC number of current conversion rank */ - - DMA_HandleTypeDef *DMA_Handle; /*!< Pointer DMA Handler */ - - HAL_LockTypeDef Lock; /*!< ADC locking object */ - - __IO uint32_t State; /*!< ADC communication state */ - - __IO uint32_t ErrorCode; /*!< ADC Error code */ -#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) - void (* ConvCpltCallback)(struct __ADC_HandleTypeDef *hadc); /*!< ADC conversion complete callback */ - void (* ConvHalfCpltCallback)(struct __ADC_HandleTypeDef *hadc); /*!< ADC conversion DMA half-transfer callback */ - void (* LevelOutOfWindowCallback)(struct __ADC_HandleTypeDef *hadc); /*!< ADC analog watchdog 1 callback */ - void (* ErrorCallback)(struct __ADC_HandleTypeDef *hadc); /*!< ADC error callback */ - void (* InjectedConvCpltCallback)(struct __ADC_HandleTypeDef *hadc); /*!< ADC group injected conversion complete callback */ - void (* MspInitCallback)(struct __ADC_HandleTypeDef *hadc); /*!< ADC Msp Init callback */ - void (* MspDeInitCallback)(struct __ADC_HandleTypeDef *hadc); /*!< ADC Msp DeInit callback */ -#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ -}ADC_HandleTypeDef; - -#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) -/** - * @brief HAL ADC Callback ID enumeration definition - */ -typedef enum -{ - HAL_ADC_CONVERSION_COMPLETE_CB_ID = 0x00U, /*!< ADC conversion complete callback ID */ - HAL_ADC_CONVERSION_HALF_CB_ID = 0x01U, /*!< ADC conversion DMA half-transfer callback ID */ - HAL_ADC_LEVEL_OUT_OF_WINDOW_1_CB_ID = 0x02U, /*!< ADC analog watchdog 1 callback ID */ - HAL_ADC_ERROR_CB_ID = 0x03U, /*!< ADC error callback ID */ - HAL_ADC_INJ_CONVERSION_COMPLETE_CB_ID = 0x04U, /*!< ADC group injected conversion complete callback ID */ - HAL_ADC_MSPINIT_CB_ID = 0x05U, /*!< ADC Msp Init callback ID */ - HAL_ADC_MSPDEINIT_CB_ID = 0x06U /*!< ADC Msp DeInit callback ID */ -} HAL_ADC_CallbackIDTypeDef; - -/** - * @brief HAL ADC Callback pointer definition - */ -typedef void (*pADC_CallbackTypeDef)(ADC_HandleTypeDef *hadc); /*!< pointer to a ADC callback function */ - -#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup ADC_Exported_Constants ADC Exported Constants - * @{ - */ - -/** @defgroup ADC_Error_Code ADC Error Code - * @{ - */ -#define HAL_ADC_ERROR_NONE 0x00U /*!< No error */ -#define HAL_ADC_ERROR_INTERNAL 0x01U /*!< ADC IP internal error: if problem of clocking, - enable/disable, erroneous state */ -#define HAL_ADC_ERROR_OVR 0x02U /*!< Overrun error */ -#define HAL_ADC_ERROR_DMA 0x04U /*!< DMA transfer error */ -#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) -#define HAL_ADC_ERROR_INVALID_CALLBACK (0x10U) /*!< Invalid Callback error */ -#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ -/** - * @} - */ - - -/** @defgroup ADC_ClockPrescaler ADC Clock Prescaler - * @{ - */ -#define ADC_CLOCK_SYNC_PCLK_DIV2 0x00000000U -#define ADC_CLOCK_SYNC_PCLK_DIV4 ((uint32_t)ADC_CCR_ADCPRE_0) -#define ADC_CLOCK_SYNC_PCLK_DIV6 ((uint32_t)ADC_CCR_ADCPRE_1) -#define ADC_CLOCK_SYNC_PCLK_DIV8 ((uint32_t)ADC_CCR_ADCPRE) -/** - * @} - */ - -/** @defgroup ADC_delay_between_2_sampling_phases ADC Delay Between 2 Sampling Phases - * @{ - */ -#define ADC_TWOSAMPLINGDELAY_5CYCLES 0x00000000U -#define ADC_TWOSAMPLINGDELAY_6CYCLES ((uint32_t)ADC_CCR_DELAY_0) -#define ADC_TWOSAMPLINGDELAY_7CYCLES ((uint32_t)ADC_CCR_DELAY_1) -#define ADC_TWOSAMPLINGDELAY_8CYCLES ((uint32_t)(ADC_CCR_DELAY_1 | ADC_CCR_DELAY_0)) -#define ADC_TWOSAMPLINGDELAY_9CYCLES ((uint32_t)ADC_CCR_DELAY_2) -#define ADC_TWOSAMPLINGDELAY_10CYCLES ((uint32_t)(ADC_CCR_DELAY_2 | ADC_CCR_DELAY_0)) -#define ADC_TWOSAMPLINGDELAY_11CYCLES ((uint32_t)(ADC_CCR_DELAY_2 | ADC_CCR_DELAY_1)) -#define ADC_TWOSAMPLINGDELAY_12CYCLES ((uint32_t)(ADC_CCR_DELAY_2 | ADC_CCR_DELAY_1 | ADC_CCR_DELAY_0)) -#define ADC_TWOSAMPLINGDELAY_13CYCLES ((uint32_t)ADC_CCR_DELAY_3) -#define ADC_TWOSAMPLINGDELAY_14CYCLES ((uint32_t)(ADC_CCR_DELAY_3 | ADC_CCR_DELAY_0)) -#define ADC_TWOSAMPLINGDELAY_15CYCLES ((uint32_t)(ADC_CCR_DELAY_3 | ADC_CCR_DELAY_1)) -#define ADC_TWOSAMPLINGDELAY_16CYCLES ((uint32_t)(ADC_CCR_DELAY_3 | ADC_CCR_DELAY_1 | ADC_CCR_DELAY_0)) -#define ADC_TWOSAMPLINGDELAY_17CYCLES ((uint32_t)(ADC_CCR_DELAY_3 | ADC_CCR_DELAY_2)) -#define ADC_TWOSAMPLINGDELAY_18CYCLES ((uint32_t)(ADC_CCR_DELAY_3 | ADC_CCR_DELAY_2 | ADC_CCR_DELAY_0)) -#define ADC_TWOSAMPLINGDELAY_19CYCLES ((uint32_t)(ADC_CCR_DELAY_3 | ADC_CCR_DELAY_2 | ADC_CCR_DELAY_1)) -#define ADC_TWOSAMPLINGDELAY_20CYCLES ((uint32_t)ADC_CCR_DELAY) -/** - * @} - */ - -/** @defgroup ADC_Resolution ADC Resolution - * @{ - */ -#define ADC_RESOLUTION_12B 0x00000000U -#define ADC_RESOLUTION_10B ((uint32_t)ADC_CR1_RES_0) -#define ADC_RESOLUTION_8B ((uint32_t)ADC_CR1_RES_1) -#define ADC_RESOLUTION_6B ((uint32_t)ADC_CR1_RES) -/** - * @} - */ - -/** @defgroup ADC_External_trigger_edge_Regular ADC External Trigger Edge Regular - * @{ - */ -#define ADC_EXTERNALTRIGCONVEDGE_NONE 0x00000000U -#define ADC_EXTERNALTRIGCONVEDGE_RISING ((uint32_t)ADC_CR2_EXTEN_0) -#define ADC_EXTERNALTRIGCONVEDGE_FALLING ((uint32_t)ADC_CR2_EXTEN_1) -#define ADC_EXTERNALTRIGCONVEDGE_RISINGFALLING ((uint32_t)ADC_CR2_EXTEN) -/** - * @} - */ - -/** @defgroup ADC_External_trigger_Source_Regular ADC External Trigger Source Regular - * @{ - */ -/* Note: Parameter ADC_SOFTWARE_START is a software parameter used for */ -/* compatibility with other STM32 devices. */ -#define ADC_EXTERNALTRIGCONV_T1_CC1 0x00000000U -#define ADC_EXTERNALTRIGCONV_T1_CC2 ((uint32_t)ADC_CR2_EXTSEL_0) -#define ADC_EXTERNALTRIGCONV_T1_CC3 ((uint32_t)ADC_CR2_EXTSEL_1) -#define ADC_EXTERNALTRIGCONV_T2_CC2 ((uint32_t)(ADC_CR2_EXTSEL_1 | ADC_CR2_EXTSEL_0)) -#define ADC_EXTERNALTRIGCONV_T2_CC3 ((uint32_t)ADC_CR2_EXTSEL_2) -#define ADC_EXTERNALTRIGCONV_T2_CC4 ((uint32_t)(ADC_CR2_EXTSEL_2 | ADC_CR2_EXTSEL_0)) -#define ADC_EXTERNALTRIGCONV_T2_TRGO ((uint32_t)(ADC_CR2_EXTSEL_2 | ADC_CR2_EXTSEL_1)) -#define ADC_EXTERNALTRIGCONV_T3_CC1 ((uint32_t)(ADC_CR2_EXTSEL_2 | ADC_CR2_EXTSEL_1 | ADC_CR2_EXTSEL_0)) -#define ADC_EXTERNALTRIGCONV_T3_TRGO ((uint32_t)ADC_CR2_EXTSEL_3) -#define ADC_EXTERNALTRIGCONV_T4_CC4 ((uint32_t)(ADC_CR2_EXTSEL_3 | ADC_CR2_EXTSEL_0)) -#define ADC_EXTERNALTRIGCONV_T5_CC1 ((uint32_t)(ADC_CR2_EXTSEL_3 | ADC_CR2_EXTSEL_1)) -#define ADC_EXTERNALTRIGCONV_T5_CC2 ((uint32_t)(ADC_CR2_EXTSEL_3 | ADC_CR2_EXTSEL_1 | ADC_CR2_EXTSEL_0)) -#define ADC_EXTERNALTRIGCONV_T5_CC3 ((uint32_t)(ADC_CR2_EXTSEL_3 | ADC_CR2_EXTSEL_2)) -#define ADC_EXTERNALTRIGCONV_T8_CC1 ((uint32_t)(ADC_CR2_EXTSEL_3 | ADC_CR2_EXTSEL_2 | ADC_CR2_EXTSEL_0)) -#define ADC_EXTERNALTRIGCONV_T8_TRGO ((uint32_t)(ADC_CR2_EXTSEL_3 | ADC_CR2_EXTSEL_2 | ADC_CR2_EXTSEL_1)) -#define ADC_EXTERNALTRIGCONV_Ext_IT11 ((uint32_t)ADC_CR2_EXTSEL) -#define ADC_SOFTWARE_START ((uint32_t)ADC_CR2_EXTSEL + 1U) -/** - * @} - */ - -/** @defgroup ADC_Data_align ADC Data Align - * @{ - */ -#define ADC_DATAALIGN_RIGHT 0x00000000U -#define ADC_DATAALIGN_LEFT ((uint32_t)ADC_CR2_ALIGN) -/** - * @} - */ - -/** @defgroup ADC_channels ADC Common Channels - * @{ - */ -#define ADC_CHANNEL_0 0x00000000U -#define ADC_CHANNEL_1 ((uint32_t)ADC_CR1_AWDCH_0) -#define ADC_CHANNEL_2 ((uint32_t)ADC_CR1_AWDCH_1) -#define ADC_CHANNEL_3 ((uint32_t)(ADC_CR1_AWDCH_1 | ADC_CR1_AWDCH_0)) -#define ADC_CHANNEL_4 ((uint32_t)ADC_CR1_AWDCH_2) -#define ADC_CHANNEL_5 ((uint32_t)(ADC_CR1_AWDCH_2 | ADC_CR1_AWDCH_0)) -#define ADC_CHANNEL_6 ((uint32_t)(ADC_CR1_AWDCH_2 | ADC_CR1_AWDCH_1)) -#define ADC_CHANNEL_7 ((uint32_t)(ADC_CR1_AWDCH_2 | ADC_CR1_AWDCH_1 | ADC_CR1_AWDCH_0)) -#define ADC_CHANNEL_8 ((uint32_t)ADC_CR1_AWDCH_3) -#define ADC_CHANNEL_9 ((uint32_t)(ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_0)) -#define ADC_CHANNEL_10 ((uint32_t)(ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_1)) -#define ADC_CHANNEL_11 ((uint32_t)(ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_1 | ADC_CR1_AWDCH_0)) -#define ADC_CHANNEL_12 ((uint32_t)(ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_2)) -#define ADC_CHANNEL_13 ((uint32_t)(ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_2 | ADC_CR1_AWDCH_0)) -#define ADC_CHANNEL_14 ((uint32_t)(ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_2 | ADC_CR1_AWDCH_1)) -#define ADC_CHANNEL_15 ((uint32_t)(ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_2 | ADC_CR1_AWDCH_1 | ADC_CR1_AWDCH_0)) -#define ADC_CHANNEL_16 ((uint32_t)ADC_CR1_AWDCH_4) -#define ADC_CHANNEL_17 ((uint32_t)(ADC_CR1_AWDCH_4 | ADC_CR1_AWDCH_0)) -#define ADC_CHANNEL_18 ((uint32_t)(ADC_CR1_AWDCH_4 | ADC_CR1_AWDCH_1)) - -#define ADC_CHANNEL_VREFINT ((uint32_t)ADC_CHANNEL_17) -#define ADC_CHANNEL_VBAT ((uint32_t)ADC_CHANNEL_18) -/** - * @} - */ - -/** @defgroup ADC_sampling_times ADC Sampling Times - * @{ - */ -#define ADC_SAMPLETIME_3CYCLES 0x00000000U -#define ADC_SAMPLETIME_15CYCLES ((uint32_t)ADC_SMPR1_SMP10_0) -#define ADC_SAMPLETIME_28CYCLES ((uint32_t)ADC_SMPR1_SMP10_1) -#define ADC_SAMPLETIME_56CYCLES ((uint32_t)(ADC_SMPR1_SMP10_1 | ADC_SMPR1_SMP10_0)) -#define ADC_SAMPLETIME_84CYCLES ((uint32_t)ADC_SMPR1_SMP10_2) -#define ADC_SAMPLETIME_112CYCLES ((uint32_t)(ADC_SMPR1_SMP10_2 | ADC_SMPR1_SMP10_0)) -#define ADC_SAMPLETIME_144CYCLES ((uint32_t)(ADC_SMPR1_SMP10_2 | ADC_SMPR1_SMP10_1)) -#define ADC_SAMPLETIME_480CYCLES ((uint32_t)ADC_SMPR1_SMP10) -/** - * @} - */ - - /** @defgroup ADC_EOCSelection ADC EOC Selection - * @{ - */ -#define ADC_EOC_SEQ_CONV 0x00000000U -#define ADC_EOC_SINGLE_CONV 0x00000001U -#define ADC_EOC_SINGLE_SEQ_CONV 0x00000002U /*!< reserved for future use */ -/** - * @} - */ - -/** @defgroup ADC_Event_type ADC Event Type - * @{ - */ -#define ADC_AWD_EVENT ((uint32_t)ADC_FLAG_AWD) -#define ADC_OVR_EVENT ((uint32_t)ADC_FLAG_OVR) -/** - * @} - */ - -/** @defgroup ADC_analog_watchdog_selection ADC Analog Watchdog Selection - * @{ - */ -#define ADC_ANALOGWATCHDOG_SINGLE_REG ((uint32_t)(ADC_CR1_AWDSGL | ADC_CR1_AWDEN)) -#define ADC_ANALOGWATCHDOG_SINGLE_INJEC ((uint32_t)(ADC_CR1_AWDSGL | ADC_CR1_JAWDEN)) -#define ADC_ANALOGWATCHDOG_SINGLE_REGINJEC ((uint32_t)(ADC_CR1_AWDSGL | ADC_CR1_AWDEN | ADC_CR1_JAWDEN)) -#define ADC_ANALOGWATCHDOG_ALL_REG ((uint32_t)ADC_CR1_AWDEN) -#define ADC_ANALOGWATCHDOG_ALL_INJEC ((uint32_t)ADC_CR1_JAWDEN) -#define ADC_ANALOGWATCHDOG_ALL_REGINJEC ((uint32_t)(ADC_CR1_AWDEN | ADC_CR1_JAWDEN)) -#define ADC_ANALOGWATCHDOG_NONE 0x00000000U -/** - * @} - */ - -/** @defgroup ADC_interrupts_definition ADC Interrupts Definition - * @{ - */ -#define ADC_IT_EOC ((uint32_t)ADC_CR1_EOCIE) -#define ADC_IT_AWD ((uint32_t)ADC_CR1_AWDIE) -#define ADC_IT_JEOC ((uint32_t)ADC_CR1_JEOCIE) -#define ADC_IT_OVR ((uint32_t)ADC_CR1_OVRIE) -/** - * @} - */ - -/** @defgroup ADC_flags_definition ADC Flags Definition - * @{ - */ -#define ADC_FLAG_AWD ((uint32_t)ADC_SR_AWD) -#define ADC_FLAG_EOC ((uint32_t)ADC_SR_EOC) -#define ADC_FLAG_JEOC ((uint32_t)ADC_SR_JEOC) -#define ADC_FLAG_JSTRT ((uint32_t)ADC_SR_JSTRT) -#define ADC_FLAG_STRT ((uint32_t)ADC_SR_STRT) -#define ADC_FLAG_OVR ((uint32_t)ADC_SR_OVR) -/** - * @} - */ - -/** @defgroup ADC_channels_type ADC Channels Type - * @{ - */ -#define ADC_ALL_CHANNELS 0x00000001U -#define ADC_REGULAR_CHANNELS 0x00000002U /*!< reserved for future use */ -#define ADC_INJECTED_CHANNELS 0x00000003U /*!< reserved for future use */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup ADC_Exported_Macros ADC Exported Macros - * @{ - */ - -/** @brief Reset ADC handle state - * @param __HANDLE__ ADC handle - * @retval None - */ -#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) -#define __HAL_ADC_RESET_HANDLE_STATE(__HANDLE__) \ - do{ \ - (__HANDLE__)->State = HAL_ADC_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_ADC_RESET_HANDLE_STATE(__HANDLE__) \ - ((__HANDLE__)->State = HAL_ADC_STATE_RESET) -#endif - -/** - * @brief Enable the ADC peripheral. - * @param __HANDLE__ ADC handle - * @retval None - */ -#define __HAL_ADC_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR2 |= ADC_CR2_ADON) - -/** - * @brief Disable the ADC peripheral. - * @param __HANDLE__ ADC handle - * @retval None - */ -#define __HAL_ADC_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR2 &= ~ADC_CR2_ADON) - -/** - * @brief Enable the ADC end of conversion interrupt. - * @param __HANDLE__ specifies the ADC Handle. - * @param __INTERRUPT__ ADC Interrupt. - * @retval None - */ -#define __HAL_ADC_ENABLE_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->CR1) |= (__INTERRUPT__)) - -/** - * @brief Disable the ADC end of conversion interrupt. - * @param __HANDLE__ specifies the ADC Handle. - * @param __INTERRUPT__ ADC interrupt. - * @retval None - */ -#define __HAL_ADC_DISABLE_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->CR1) &= ~(__INTERRUPT__)) - -/** @brief Check if the specified ADC interrupt source is enabled or disabled. - * @param __HANDLE__ specifies the ADC Handle. - * @param __INTERRUPT__ specifies the ADC interrupt source to check. - * @retval The new state of __IT__ (TRUE or FALSE). - */ -#define __HAL_ADC_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->CR1 & (__INTERRUPT__)) == (__INTERRUPT__)) - -/** - * @brief Clear the ADC's pending flags. - * @param __HANDLE__ specifies the ADC Handle. - * @param __FLAG__ ADC flag. - * @retval None - */ -#define __HAL_ADC_CLEAR_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->SR) = ~(__FLAG__)) - -/** - * @brief Get the selected ADC's flag status. - * @param __HANDLE__ specifies the ADC Handle. - * @param __FLAG__ ADC flag. - * @retval None - */ -#define __HAL_ADC_GET_FLAG(__HANDLE__, __FLAG__) ((((__HANDLE__)->Instance->SR) & (__FLAG__)) == (__FLAG__)) - -/** - * @} - */ - -/* Include ADC HAL Extension module */ -#include "stm32f4xx_hal_adc_ex.h" - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup ADC_Exported_Functions - * @{ - */ - -/** @addtogroup ADC_Exported_Functions_Group1 - * @{ - */ -/* Initialization/de-initialization functions ***********************************/ -HAL_StatusTypeDef HAL_ADC_Init(ADC_HandleTypeDef* hadc); -HAL_StatusTypeDef HAL_ADC_DeInit(ADC_HandleTypeDef *hadc); -void HAL_ADC_MspInit(ADC_HandleTypeDef* hadc); -void HAL_ADC_MspDeInit(ADC_HandleTypeDef* hadc); - -#if (USE_HAL_ADC_REGISTER_CALLBACKS == 1) -/* Callbacks Register/UnRegister functions ***********************************/ -HAL_StatusTypeDef HAL_ADC_RegisterCallback(ADC_HandleTypeDef *hadc, HAL_ADC_CallbackIDTypeDef CallbackID, pADC_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_ADC_UnRegisterCallback(ADC_HandleTypeDef *hadc, HAL_ADC_CallbackIDTypeDef CallbackID); -#endif /* USE_HAL_ADC_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @addtogroup ADC_Exported_Functions_Group2 - * @{ - */ -/* I/O operation functions ******************************************************/ -HAL_StatusTypeDef HAL_ADC_Start(ADC_HandleTypeDef* hadc); -HAL_StatusTypeDef HAL_ADC_Stop(ADC_HandleTypeDef* hadc); -HAL_StatusTypeDef HAL_ADC_PollForConversion(ADC_HandleTypeDef* hadc, uint32_t Timeout); - -HAL_StatusTypeDef HAL_ADC_PollForEvent(ADC_HandleTypeDef* hadc, uint32_t EventType, uint32_t Timeout); - -HAL_StatusTypeDef HAL_ADC_Start_IT(ADC_HandleTypeDef* hadc); -HAL_StatusTypeDef HAL_ADC_Stop_IT(ADC_HandleTypeDef* hadc); - -void HAL_ADC_IRQHandler(ADC_HandleTypeDef* hadc); - -HAL_StatusTypeDef HAL_ADC_Start_DMA(ADC_HandleTypeDef* hadc, uint32_t* pData, uint32_t Length); -HAL_StatusTypeDef HAL_ADC_Stop_DMA(ADC_HandleTypeDef* hadc); - -uint32_t HAL_ADC_GetValue(ADC_HandleTypeDef* hadc); - -void HAL_ADC_ConvCpltCallback(ADC_HandleTypeDef* hadc); -void HAL_ADC_ConvHalfCpltCallback(ADC_HandleTypeDef* hadc); -void HAL_ADC_LevelOutOfWindowCallback(ADC_HandleTypeDef* hadc); -void HAL_ADC_ErrorCallback(ADC_HandleTypeDef *hadc); -/** - * @} - */ - -/** @addtogroup ADC_Exported_Functions_Group3 - * @{ - */ -/* Peripheral Control functions *************************************************/ -HAL_StatusTypeDef HAL_ADC_ConfigChannel(ADC_HandleTypeDef* hadc, ADC_ChannelConfTypeDef* sConfig); -HAL_StatusTypeDef HAL_ADC_AnalogWDGConfig(ADC_HandleTypeDef* hadc, ADC_AnalogWDGConfTypeDef* AnalogWDGConfig); -/** - * @} - */ - -/** @addtogroup ADC_Exported_Functions_Group4 - * @{ - */ -/* Peripheral State functions ***************************************************/ -uint32_t HAL_ADC_GetState(ADC_HandleTypeDef* hadc); -uint32_t HAL_ADC_GetError(ADC_HandleTypeDef *hadc); -/** - * @} - */ - -/** - * @} - */ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup ADC_Private_Constants ADC Private Constants - * @{ - */ -/* Delay for ADC stabilization time. */ -/* Maximum delay is 1us (refer to device datasheet, parameter tSTAB). */ -/* Unit: us */ -#define ADC_STAB_DELAY_US 3U -/* Delay for temperature sensor stabilization time. */ -/* Maximum delay is 10us (refer to device datasheet, parameter tSTART). */ -/* Unit: us */ -#define ADC_TEMPSENSOR_DELAY_US 10U -/** - * @} - */ - -/* Private macro ------------------------------------------------------------*/ - -/** @defgroup ADC_Private_Macros ADC Private Macros - * @{ - */ -/* Macro reserved for internal HAL driver usage, not intended to be used in - code of final user */ - -/** - * @brief Verification of ADC state: enabled or disabled - * @param __HANDLE__ ADC handle - * @retval SET (ADC enabled) or RESET (ADC disabled) - */ -#define ADC_IS_ENABLE(__HANDLE__) \ - ((( ((__HANDLE__)->Instance->SR & ADC_SR_ADONS) == ADC_SR_ADONS ) \ - ) ? SET : RESET) - -/** - * @brief Test if conversion trigger of regular group is software start - * or external trigger. - * @param __HANDLE__ ADC handle - * @retval SET (software start) or RESET (external trigger) - */ -#define ADC_IS_SOFTWARE_START_REGULAR(__HANDLE__) \ - (((__HANDLE__)->Instance->CR2 & ADC_CR2_EXTEN) == RESET) - -/** - * @brief Test if conversion trigger of injected group is software start - * or external trigger. - * @param __HANDLE__ ADC handle - * @retval SET (software start) or RESET (external trigger) - */ -#define ADC_IS_SOFTWARE_START_INJECTED(__HANDLE__) \ - (((__HANDLE__)->Instance->CR2 & ADC_CR2_JEXTEN) == RESET) - -/** - * @brief Simultaneously clears and sets specific bits of the handle State - * @note: ADC_STATE_CLR_SET() macro is merely aliased to generic macro MODIFY_REG(), - * the first parameter is the ADC handle State, the second parameter is the - * bit field to clear, the third and last parameter is the bit field to set. - * @retval None - */ -#define ADC_STATE_CLR_SET MODIFY_REG - -/** - * @brief Clear ADC error code (set it to error code: "no error") - * @param __HANDLE__ ADC handle - * @retval None - */ -#define ADC_CLEAR_ERRORCODE(__HANDLE__) \ - ((__HANDLE__)->ErrorCode = HAL_ADC_ERROR_NONE) - - -#define IS_ADC_CLOCKPRESCALER(ADC_CLOCK) (((ADC_CLOCK) == ADC_CLOCK_SYNC_PCLK_DIV2) || \ - ((ADC_CLOCK) == ADC_CLOCK_SYNC_PCLK_DIV4) || \ - ((ADC_CLOCK) == ADC_CLOCK_SYNC_PCLK_DIV6) || \ - ((ADC_CLOCK) == ADC_CLOCK_SYNC_PCLK_DIV8)) -#define IS_ADC_SAMPLING_DELAY(DELAY) (((DELAY) == ADC_TWOSAMPLINGDELAY_5CYCLES) || \ - ((DELAY) == ADC_TWOSAMPLINGDELAY_6CYCLES) || \ - ((DELAY) == ADC_TWOSAMPLINGDELAY_7CYCLES) || \ - ((DELAY) == ADC_TWOSAMPLINGDELAY_8CYCLES) || \ - ((DELAY) == ADC_TWOSAMPLINGDELAY_9CYCLES) || \ - ((DELAY) == ADC_TWOSAMPLINGDELAY_10CYCLES) || \ - ((DELAY) == ADC_TWOSAMPLINGDELAY_11CYCLES) || \ - ((DELAY) == ADC_TWOSAMPLINGDELAY_12CYCLES) || \ - ((DELAY) == ADC_TWOSAMPLINGDELAY_13CYCLES) || \ - ((DELAY) == ADC_TWOSAMPLINGDELAY_14CYCLES) || \ - ((DELAY) == ADC_TWOSAMPLINGDELAY_15CYCLES) || \ - ((DELAY) == ADC_TWOSAMPLINGDELAY_16CYCLES) || \ - ((DELAY) == ADC_TWOSAMPLINGDELAY_17CYCLES) || \ - ((DELAY) == ADC_TWOSAMPLINGDELAY_18CYCLES) || \ - ((DELAY) == ADC_TWOSAMPLINGDELAY_19CYCLES) || \ - ((DELAY) == ADC_TWOSAMPLINGDELAY_20CYCLES)) -#define IS_ADC_RESOLUTION(RESOLUTION) (((RESOLUTION) == ADC_RESOLUTION_12B) || \ - ((RESOLUTION) == ADC_RESOLUTION_10B) || \ - ((RESOLUTION) == ADC_RESOLUTION_8B) || \ - ((RESOLUTION) == ADC_RESOLUTION_6B)) -#define IS_ADC_EXT_TRIG_EDGE(EDGE) (((EDGE) == ADC_EXTERNALTRIGCONVEDGE_NONE) || \ - ((EDGE) == ADC_EXTERNALTRIGCONVEDGE_RISING) || \ - ((EDGE) == ADC_EXTERNALTRIGCONVEDGE_FALLING) || \ - ((EDGE) == ADC_EXTERNALTRIGCONVEDGE_RISINGFALLING)) -#define IS_ADC_EXT_TRIG(REGTRIG) (((REGTRIG) == ADC_EXTERNALTRIGCONV_T1_CC1) || \ - ((REGTRIG) == ADC_EXTERNALTRIGCONV_T1_CC2) || \ - ((REGTRIG) == ADC_EXTERNALTRIGCONV_T1_CC3) || \ - ((REGTRIG) == ADC_EXTERNALTRIGCONV_T2_CC2) || \ - ((REGTRIG) == ADC_EXTERNALTRIGCONV_T2_CC3) || \ - ((REGTRIG) == ADC_EXTERNALTRIGCONV_T2_CC4) || \ - ((REGTRIG) == ADC_EXTERNALTRIGCONV_T2_TRGO) || \ - ((REGTRIG) == ADC_EXTERNALTRIGCONV_T3_CC1) || \ - ((REGTRIG) == ADC_EXTERNALTRIGCONV_T3_TRGO) || \ - ((REGTRIG) == ADC_EXTERNALTRIGCONV_T4_CC4) || \ - ((REGTRIG) == ADC_EXTERNALTRIGCONV_T5_CC1) || \ - ((REGTRIG) == ADC_EXTERNALTRIGCONV_T5_CC2) || \ - ((REGTRIG) == ADC_EXTERNALTRIGCONV_T5_CC3) || \ - ((REGTRIG) == ADC_EXTERNALTRIGCONV_T8_CC1) || \ - ((REGTRIG) == ADC_EXTERNALTRIGCONV_T8_TRGO) || \ - ((REGTRIG) == ADC_EXTERNALTRIGCONV_Ext_IT11)|| \ - ((REGTRIG) == ADC_SOFTWARE_START)) -#define IS_ADC_DATA_ALIGN(ALIGN) (((ALIGN) == ADC_DATAALIGN_RIGHT) || \ - ((ALIGN) == ADC_DATAALIGN_LEFT)) -#define IS_ADC_SAMPLE_TIME(TIME) (((TIME) == ADC_SAMPLETIME_3CYCLES) || \ - ((TIME) == ADC_SAMPLETIME_15CYCLES) || \ - ((TIME) == ADC_SAMPLETIME_28CYCLES) || \ - ((TIME) == ADC_SAMPLETIME_56CYCLES) || \ - ((TIME) == ADC_SAMPLETIME_84CYCLES) || \ - ((TIME) == ADC_SAMPLETIME_112CYCLES) || \ - ((TIME) == ADC_SAMPLETIME_144CYCLES) || \ - ((TIME) == ADC_SAMPLETIME_480CYCLES)) -#define IS_ADC_EOCSelection(EOCSelection) (((EOCSelection) == ADC_EOC_SINGLE_CONV) || \ - ((EOCSelection) == ADC_EOC_SEQ_CONV) || \ - ((EOCSelection) == ADC_EOC_SINGLE_SEQ_CONV)) -#define IS_ADC_EVENT_TYPE(EVENT) (((EVENT) == ADC_AWD_EVENT) || \ - ((EVENT) == ADC_OVR_EVENT)) -#define IS_ADC_ANALOG_WATCHDOG(WATCHDOG) (((WATCHDOG) == ADC_ANALOGWATCHDOG_SINGLE_REG) || \ - ((WATCHDOG) == ADC_ANALOGWATCHDOG_SINGLE_INJEC) || \ - ((WATCHDOG) == ADC_ANALOGWATCHDOG_SINGLE_REGINJEC) || \ - ((WATCHDOG) == ADC_ANALOGWATCHDOG_ALL_REG) || \ - ((WATCHDOG) == ADC_ANALOGWATCHDOG_ALL_INJEC) || \ - ((WATCHDOG) == ADC_ANALOGWATCHDOG_ALL_REGINJEC) || \ - ((WATCHDOG) == ADC_ANALOGWATCHDOG_NONE)) -#define IS_ADC_CHANNELS_TYPE(CHANNEL_TYPE) (((CHANNEL_TYPE) == ADC_ALL_CHANNELS) || \ - ((CHANNEL_TYPE) == ADC_REGULAR_CHANNELS) || \ - ((CHANNEL_TYPE) == ADC_INJECTED_CHANNELS)) -#define IS_ADC_THRESHOLD(THRESHOLD) ((THRESHOLD) <= 0xFFFU) - -#define IS_ADC_REGULAR_LENGTH(LENGTH) (((LENGTH) >= 1U) && ((LENGTH) <= 16U)) -#define IS_ADC_REGULAR_RANK(RANK) (((RANK) >= 1U) && ((RANK) <= (16U))) -#define IS_ADC_REGULAR_DISC_NUMBER(NUMBER) (((NUMBER) >= 1U) && ((NUMBER) <= 8U)) -#define IS_ADC_RANGE(RESOLUTION, ADC_VALUE) \ - ((((RESOLUTION) == ADC_RESOLUTION_12B) && ((ADC_VALUE) <= 0x0FFFU)) || \ - (((RESOLUTION) == ADC_RESOLUTION_10B) && ((ADC_VALUE) <= 0x03FFU)) || \ - (((RESOLUTION) == ADC_RESOLUTION_8B) && ((ADC_VALUE) <= 0x00FFU)) || \ - (((RESOLUTION) == ADC_RESOLUTION_6B) && ((ADC_VALUE) <= 0x003FU))) - -/** - * @brief Set ADC Regular channel sequence length. - * @param _NbrOfConversion_ Regular channel sequence length. - * @retval None - */ -#define ADC_SQR1(_NbrOfConversion_) (((_NbrOfConversion_) - (uint8_t)1U) << 20U) - -/** - * @brief Set the ADC's sample time for channel numbers between 10 and 18. - * @param _SAMPLETIME_ Sample time parameter. - * @param _CHANNELNB_ Channel number. - * @retval None - */ -#define ADC_SMPR1(_SAMPLETIME_, _CHANNELNB_) ((_SAMPLETIME_) << (3U * (((uint32_t)((uint16_t)(_CHANNELNB_))) - 10U))) - -/** - * @brief Set the ADC's sample time for channel numbers between 0 and 9. - * @param _SAMPLETIME_ Sample time parameter. - * @param _CHANNELNB_ Channel number. - * @retval None - */ -#define ADC_SMPR2(_SAMPLETIME_, _CHANNELNB_) ((_SAMPLETIME_) << (3U * ((uint32_t)((uint16_t)(_CHANNELNB_))))) - -/** - * @brief Set the selected regular channel rank for rank between 1 and 6. - * @param _CHANNELNB_ Channel number. - * @param _RANKNB_ Rank number. - * @retval None - */ -#define ADC_SQR3_RK(_CHANNELNB_, _RANKNB_) (((uint32_t)((uint16_t)(_CHANNELNB_))) << (5U * ((_RANKNB_) - 1U))) - -/** - * @brief Set the selected regular channel rank for rank between 7 and 12. - * @param _CHANNELNB_ Channel number. - * @param _RANKNB_ Rank number. - * @retval None - */ -#define ADC_SQR2_RK(_CHANNELNB_, _RANKNB_) (((uint32_t)((uint16_t)(_CHANNELNB_))) << (5U * ((_RANKNB_) - 7U))) - -/** - * @brief Set the selected regular channel rank for rank between 13 and 16. - * @param _CHANNELNB_ Channel number. - * @param _RANKNB_ Rank number. - * @retval None - */ -#define ADC_SQR1_RK(_CHANNELNB_, _RANKNB_) (((uint32_t)((uint16_t)(_CHANNELNB_))) << (5U * ((_RANKNB_) - 13U))) - -/** - * @brief Enable ADC continuous conversion mode. - * @param _CONTINUOUS_MODE_ Continuous mode. - * @retval None - */ -#define ADC_CR2_CONTINUOUS(_CONTINUOUS_MODE_) ((_CONTINUOUS_MODE_) << 1U) - -/** - * @brief Configures the number of discontinuous conversions for the regular group channels. - * @param _NBR_DISCONTINUOUSCONV_ Number of discontinuous conversions. - * @retval None - */ -#define ADC_CR1_DISCONTINUOUS(_NBR_DISCONTINUOUSCONV_) (((_NBR_DISCONTINUOUSCONV_) - 1U) << ADC_CR1_DISCNUM_Pos) - -/** - * @brief Enable ADC scan mode. - * @param _SCANCONV_MODE_ Scan conversion mode. - * @retval None - */ -#define ADC_CR1_SCANCONV(_SCANCONV_MODE_) ((_SCANCONV_MODE_) << 8U) - -/** - * @brief Enable the ADC end of conversion selection. - * @param _EOCSelection_MODE_ End of conversion selection mode. - * @retval None - */ -#define ADC_CR2_EOCSelection(_EOCSelection_MODE_) ((_EOCSelection_MODE_) << 10U) - -/** - * @brief Enable the ADC DMA continuous request. - * @param _DMAContReq_MODE_ DMA continuous request mode. - * @retval None - */ -#define ADC_CR2_DMAContReq(_DMAContReq_MODE_) ((_DMAContReq_MODE_) << 9U) - -/** - * @brief Return resolution bits in CR1 register. - * @param __HANDLE__ ADC handle - * @retval None - */ -#define ADC_GET_RESOLUTION(__HANDLE__) (((__HANDLE__)->Instance->CR1) & ADC_CR1_RES) - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup ADC_Private_Functions ADC Private Functions - * @{ - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /*__STM32F4xx_ADC_H */ - - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc_ex.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc_ex.h deleted file mode 100644 index b0cdd2a..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_adc_ex.h +++ /dev/null @@ -1,409 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_adc_ex.h - * @author MCD Application Team - * @brief Header file of ADC HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_ADC_EX_H -#define __STM32F4xx_ADC_EX_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup ADCEx - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup ADCEx_Exported_Types ADC Exported Types - * @{ - */ - -/** - * @brief ADC Configuration injected Channel structure definition - * @note Parameters of this structure are shared within 2 scopes: - * - Scope channel: InjectedChannel, InjectedRank, InjectedSamplingTime, InjectedOffset - * - Scope injected group (affects all channels of injected group): InjectedNbrOfConversion, InjectedDiscontinuousConvMode, - * AutoInjectedConv, ExternalTrigInjecConvEdge, ExternalTrigInjecConv. - * @note The setting of these parameters with function HAL_ADCEx_InjectedConfigChannel() is conditioned to ADC state. - * ADC state can be either: - * - For all parameters: ADC disabled - * - For all except parameters 'InjectedDiscontinuousConvMode' and 'AutoInjectedConv': ADC enabled without conversion on going on injected group. - * - For parameters 'ExternalTrigInjecConv' and 'ExternalTrigInjecConvEdge': ADC enabled, even with conversion on going on injected group. - */ -typedef struct -{ - uint32_t InjectedChannel; /*!< Selection of ADC channel to configure - This parameter can be a value of @ref ADC_channels - Note: Depending on devices, some channels may not be available on package pins. Refer to device datasheet for channels availability. */ - uint32_t InjectedRank; /*!< Rank in the injected group sequencer - This parameter must be a value of @ref ADCEx_injected_rank - Note: In case of need to disable a channel or change order of conversion sequencer, rank containing a previous channel setting can be overwritten by the new channel setting (or parameter number of conversions can be adjusted) */ - uint32_t InjectedSamplingTime; /*!< Sampling time value to be set for the selected channel. - Unit: ADC clock cycles - Conversion time is the addition of sampling time and processing time (12 ADC clock cycles at ADC resolution 12 bits, 11 cycles at 10 bits, 9 cycles at 8 bits, 7 cycles at 6 bits). - This parameter can be a value of @ref ADC_sampling_times - Caution: This parameter updates the parameter property of the channel, that can be used into regular and/or injected groups. - If this same channel has been previously configured in the other group (regular/injected), it will be updated to last setting. - Note: In case of usage of internal measurement channels (VrefInt/Vbat/TempSensor), - sampling time constraints must be respected (sampling time can be adjusted in function of ADC clock frequency and sampling time setting) - Refer to device datasheet for timings values, parameters TS_vrefint, TS_temp (values rough order: 4us min). */ - uint32_t InjectedOffset; /*!< Defines the offset to be subtracted from the raw converted data (for channels set on injected group only). - Offset value must be a positive number. - Depending of ADC resolution selected (12, 10, 8 or 6 bits), - this parameter must be a number between Min_Data = 0x000 and Max_Data = 0xFFF, 0x3FF, 0xFF or 0x3F respectively. */ - uint32_t InjectedNbrOfConversion; /*!< Specifies the number of ranks that will be converted within the injected group sequencer. - To use the injected group sequencer and convert several ranks, parameter 'ScanConvMode' must be enabled. - This parameter must be a number between Min_Data = 1 and Max_Data = 4. - Caution: this setting impacts the entire injected group. Therefore, call of HAL_ADCEx_InjectedConfigChannel() to - configure a channel on injected group can impact the configuration of other channels previously set. */ - FunctionalState InjectedDiscontinuousConvMode; /*!< Specifies whether the conversions sequence of injected group is performed in Complete-sequence/Discontinuous-sequence (main sequence subdivided in successive parts). - Discontinuous mode is used only if sequencer is enabled (parameter 'ScanConvMode'). If sequencer is disabled, this parameter is discarded. - Discontinuous mode can be enabled only if continuous mode is disabled. If continuous mode is enabled, this parameter setting is discarded. - This parameter can be set to ENABLE or DISABLE. - Note: For injected group, number of discontinuous ranks increment is fixed to one-by-one. - Caution: this setting impacts the entire injected group. Therefore, call of HAL_ADCEx_InjectedConfigChannel() to - configure a channel on injected group can impact the configuration of other channels previously set. */ - FunctionalState AutoInjectedConv; /*!< Enables or disables the selected ADC automatic injected group conversion after regular one - This parameter can be set to ENABLE or DISABLE. - Note: To use Automatic injected conversion, discontinuous mode must be disabled ('DiscontinuousConvMode' and 'InjectedDiscontinuousConvMode' set to DISABLE) - Note: To use Automatic injected conversion, injected group external triggers must be disabled ('ExternalTrigInjecConv' set to ADC_SOFTWARE_START) - Note: In case of DMA used with regular group: if DMA configured in normal mode (single shot) JAUTO will be stopped upon DMA transfer complete. - To maintain JAUTO always enabled, DMA must be configured in circular mode. - Caution: this setting impacts the entire injected group. Therefore, call of HAL_ADCEx_InjectedConfigChannel() to - configure a channel on injected group can impact the configuration of other channels previously set. */ - uint32_t ExternalTrigInjecConv; /*!< Selects the external event used to trigger the conversion start of injected group. - If set to ADC_INJECTED_SOFTWARE_START, external triggers are disabled. - If set to external trigger source, triggering is on event rising edge. - This parameter can be a value of @ref ADCEx_External_trigger_Source_Injected - Note: This parameter must be modified when ADC is disabled (before ADC start conversion or after ADC stop conversion). - If ADC is enabled, this parameter setting is bypassed without error reporting (as it can be the expected behaviour in case of another parameter update on the fly) - Caution: this setting impacts the entire injected group. Therefore, call of HAL_ADCEx_InjectedConfigChannel() to - configure a channel on injected group can impact the configuration of other channels previously set. */ - uint32_t ExternalTrigInjecConvEdge; /*!< Selects the external trigger edge of injected group. - This parameter can be a value of @ref ADCEx_External_trigger_edge_Injected. - If trigger is set to ADC_INJECTED_SOFTWARE_START, this parameter is discarded. - Caution: this setting impacts the entire injected group. Therefore, call of HAL_ADCEx_InjectedConfigChannel() to - configure a channel on injected group can impact the configuration of other channels previously set. */ -}ADC_InjectionConfTypeDef; - -/** - * @brief ADC Configuration multi-mode structure definition - */ -typedef struct -{ - uint32_t Mode; /*!< Configures the ADC to operate in independent or multi mode. - This parameter can be a value of @ref ADCEx_Common_mode */ - uint32_t DMAAccessMode; /*!< Configures the Direct memory access mode for multi ADC mode. - This parameter can be a value of @ref ADCEx_Direct_memory_access_mode_for_multi_mode */ - uint32_t TwoSamplingDelay; /*!< Configures the Delay between 2 sampling phases. - This parameter can be a value of @ref ADC_delay_between_2_sampling_phases */ -}ADC_MultiModeTypeDef; - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup ADCEx_Exported_Constants ADC Exported Constants - * @{ - */ - -/** @defgroup ADCEx_Common_mode ADC Common Mode - * @{ - */ -#define ADC_MODE_INDEPENDENT 0x00000000U -#define ADC_DUALMODE_REGSIMULT_INJECSIMULT ((uint32_t)ADC_CCR_MULTI_0) -#define ADC_DUALMODE_REGSIMULT_ALTERTRIG ((uint32_t)ADC_CCR_MULTI_1) -#define ADC_DUALMODE_INJECSIMULT ((uint32_t)(ADC_CCR_MULTI_2 | ADC_CCR_MULTI_0)) -#define ADC_DUALMODE_REGSIMULT ((uint32_t)(ADC_CCR_MULTI_2 | ADC_CCR_MULTI_1)) -#define ADC_DUALMODE_INTERL ((uint32_t)(ADC_CCR_MULTI_2 | ADC_CCR_MULTI_1 | ADC_CCR_MULTI_0)) -#define ADC_DUALMODE_ALTERTRIG ((uint32_t)(ADC_CCR_MULTI_3 | ADC_CCR_MULTI_0)) -#define ADC_TRIPLEMODE_REGSIMULT_INJECSIMULT ((uint32_t)(ADC_CCR_MULTI_4 | ADC_CCR_MULTI_0)) -#define ADC_TRIPLEMODE_REGSIMULT_AlterTrig ((uint32_t)(ADC_CCR_MULTI_4 | ADC_CCR_MULTI_1)) -#define ADC_TRIPLEMODE_INJECSIMULT ((uint32_t)(ADC_CCR_MULTI_4 | ADC_CCR_MULTI_2 | ADC_CCR_MULTI_0)) -#define ADC_TRIPLEMODE_REGSIMULT ((uint32_t)(ADC_CCR_MULTI_4 | ADC_CCR_MULTI_2 | ADC_CCR_MULTI_1)) -#define ADC_TRIPLEMODE_INTERL ((uint32_t)(ADC_CCR_MULTI_4 | ADC_CCR_MULTI_2 | ADC_CCR_MULTI_1 | ADC_CCR_MULTI_0)) -#define ADC_TRIPLEMODE_ALTERTRIG ((uint32_t)(ADC_CCR_MULTI_4 | ADC_CCR_MULTI_3 | ADC_CCR_MULTI_0)) -/** - * @} - */ - -/** @defgroup ADCEx_Direct_memory_access_mode_for_multi_mode ADC Direct Memory Access Mode For Multi Mode - * @{ - */ -#define ADC_DMAACCESSMODE_DISABLED 0x00000000U /*!< DMA mode disabled */ -#define ADC_DMAACCESSMODE_1 ((uint32_t)ADC_CCR_DMA_0) /*!< DMA mode 1 enabled (2 / 3 half-words one by one - 1 then 2 then 3)*/ -#define ADC_DMAACCESSMODE_2 ((uint32_t)ADC_CCR_DMA_1) /*!< DMA mode 2 enabled (2 / 3 half-words by pairs - 2&1 then 1&3 then 3&2)*/ -#define ADC_DMAACCESSMODE_3 ((uint32_t)ADC_CCR_DMA) /*!< DMA mode 3 enabled (2 / 3 bytes by pairs - 2&1 then 1&3 then 3&2) */ -/** - * @} - */ - -/** @defgroup ADCEx_External_trigger_edge_Injected ADC External Trigger Edge Injected - * @{ - */ -#define ADC_EXTERNALTRIGINJECCONVEDGE_NONE 0x00000000U -#define ADC_EXTERNALTRIGINJECCONVEDGE_RISING ((uint32_t)ADC_CR2_JEXTEN_0) -#define ADC_EXTERNALTRIGINJECCONVEDGE_FALLING ((uint32_t)ADC_CR2_JEXTEN_1) -#define ADC_EXTERNALTRIGINJECCONVEDGE_RISINGFALLING ((uint32_t)ADC_CR2_JEXTEN) -/** - * @} - */ - -/** @defgroup ADCEx_External_trigger_Source_Injected ADC External Trigger Source Injected - * @{ - */ -#define ADC_EXTERNALTRIGINJECCONV_T1_CC4 0x00000000U -#define ADC_EXTERNALTRIGINJECCONV_T1_TRGO ((uint32_t)ADC_CR2_JEXTSEL_0) -#define ADC_EXTERNALTRIGINJECCONV_T2_CC1 ((uint32_t)ADC_CR2_JEXTSEL_1) -#define ADC_EXTERNALTRIGINJECCONV_T2_TRGO ((uint32_t)(ADC_CR2_JEXTSEL_1 | ADC_CR2_JEXTSEL_0)) -#define ADC_EXTERNALTRIGINJECCONV_T3_CC2 ((uint32_t)ADC_CR2_JEXTSEL_2) -#define ADC_EXTERNALTRIGINJECCONV_T3_CC4 ((uint32_t)(ADC_CR2_JEXTSEL_2 | ADC_CR2_JEXTSEL_0)) -#define ADC_EXTERNALTRIGINJECCONV_T4_CC1 ((uint32_t)(ADC_CR2_JEXTSEL_2 | ADC_CR2_JEXTSEL_1)) -#define ADC_EXTERNALTRIGINJECCONV_T4_CC2 ((uint32_t)(ADC_CR2_JEXTSEL_2 | ADC_CR2_JEXTSEL_1 | ADC_CR2_JEXTSEL_0)) -#define ADC_EXTERNALTRIGINJECCONV_T4_CC3 ((uint32_t)ADC_CR2_JEXTSEL_3) -#define ADC_EXTERNALTRIGINJECCONV_T4_TRGO ((uint32_t)(ADC_CR2_JEXTSEL_3 | ADC_CR2_JEXTSEL_0)) -#define ADC_EXTERNALTRIGINJECCONV_T5_CC4 ((uint32_t)(ADC_CR2_JEXTSEL_3 | ADC_CR2_JEXTSEL_1)) -#define ADC_EXTERNALTRIGINJECCONV_T5_TRGO ((uint32_t)(ADC_CR2_JEXTSEL_3 | ADC_CR2_JEXTSEL_1 | ADC_CR2_JEXTSEL_0)) -#define ADC_EXTERNALTRIGINJECCONV_T8_CC2 ((uint32_t)(ADC_CR2_JEXTSEL_3 | ADC_CR2_JEXTSEL_2)) -#define ADC_EXTERNALTRIGINJECCONV_T8_CC3 ((uint32_t)(ADC_CR2_JEXTSEL_3 | ADC_CR2_JEXTSEL_2 | ADC_CR2_JEXTSEL_0)) -#define ADC_EXTERNALTRIGINJECCONV_T8_CC4 ((uint32_t)(ADC_CR2_JEXTSEL_3 | ADC_CR2_JEXTSEL_2 | ADC_CR2_JEXTSEL_1)) -#define ADC_EXTERNALTRIGINJECCONV_EXT_IT15 ((uint32_t)ADC_CR2_JEXTSEL) -#define ADC_INJECTED_SOFTWARE_START ((uint32_t)ADC_CR2_JEXTSEL + 1U) -/** - * @} - */ - -/** @defgroup ADCEx_injected_rank ADC Injected Rank - * @{ - */ -#define ADC_INJECTED_RANK_1 0x00000001U -#define ADC_INJECTED_RANK_2 0x00000002U -#define ADC_INJECTED_RANK_3 0x00000003U -#define ADC_INJECTED_RANK_4 0x00000004U -/** - * @} - */ - -/** @defgroup ADCEx_channels ADC Specific Channels - * @{ - */ -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || \ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) || \ - defined(STM32F410Rx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || \ - defined(STM32F412Cx) -#define ADC_CHANNEL_TEMPSENSOR ((uint32_t)ADC_CHANNEL_16) -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F401xC || STM32F401xE || STM32F410xx || STM32F412Zx || - STM32F412Vx || STM32F412Rx || STM32F412Cx */ - -#if defined(STM32F411xE) || defined(STM32F413xx) || defined(STM32F423xx) || defined(STM32F427xx) || defined(STM32F437xx) ||\ - defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -#define ADC_CHANNEL_DIFFERENCIATION_TEMPSENSOR_VBAT 0x10000000U /* Dummy bit for driver internal usage, not used in ADC channel setting registers CR1 or SQRx */ -#define ADC_CHANNEL_TEMPSENSOR ((uint32_t)ADC_CHANNEL_18 | ADC_CHANNEL_DIFFERENCIATION_TEMPSENSOR_VBAT) -#endif /* STM32F411xE || STM32F413xx || STM32F423xx || STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ -/** - * @} - */ - - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup ADC_Exported_Macros ADC Exported Macros - * @{ - */ -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx)|| defined(STM32F439xx) -/** - * @brief Disable internal path of ADC channel Vbat - * @note Use case of this macro: - * On devices STM32F42x and STM32F43x, ADC internal channels - * Vbat and VrefInt share the same internal path, only - * one of them can be enabled.This macro is to be used when ADC - * channels Vbat and VrefInt are selected, and must be called - * before starting conversion of ADC channel VrefInt in order - * to disable ADC channel Vbat. - * @retval None - */ -#define __HAL_ADC_PATH_INTERNAL_VBAT_DISABLE() (ADC->CCR &= ~(ADC_CCR_VBATE)) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx */ -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup ADCEx_Exported_Functions - * @{ - */ - -/** @addtogroup ADCEx_Exported_Functions_Group1 - * @{ - */ - -/* I/O operation functions ******************************************************/ -HAL_StatusTypeDef HAL_ADCEx_InjectedStart(ADC_HandleTypeDef* hadc); -HAL_StatusTypeDef HAL_ADCEx_InjectedStop(ADC_HandleTypeDef* hadc); -HAL_StatusTypeDef HAL_ADCEx_InjectedPollForConversion(ADC_HandleTypeDef* hadc, uint32_t Timeout); -HAL_StatusTypeDef HAL_ADCEx_InjectedStart_IT(ADC_HandleTypeDef* hadc); -HAL_StatusTypeDef HAL_ADCEx_InjectedStop_IT(ADC_HandleTypeDef* hadc); -uint32_t HAL_ADCEx_InjectedGetValue(ADC_HandleTypeDef* hadc, uint32_t InjectedRank); -HAL_StatusTypeDef HAL_ADCEx_MultiModeStart_DMA(ADC_HandleTypeDef* hadc, uint32_t* pData, uint32_t Length); -HAL_StatusTypeDef HAL_ADCEx_MultiModeStop_DMA(ADC_HandleTypeDef* hadc); -uint32_t HAL_ADCEx_MultiModeGetValue(ADC_HandleTypeDef* hadc); -void HAL_ADCEx_InjectedConvCpltCallback(ADC_HandleTypeDef* hadc); - -/* Peripheral Control functions *************************************************/ -HAL_StatusTypeDef HAL_ADCEx_InjectedConfigChannel(ADC_HandleTypeDef* hadc,ADC_InjectionConfTypeDef* sConfigInjected); -HAL_StatusTypeDef HAL_ADCEx_MultiModeConfigChannel(ADC_HandleTypeDef* hadc, ADC_MultiModeTypeDef* multimode); - -/** - * @} - */ - -/** - * @} - */ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup ADCEx_Private_Constants ADC Private Constants - * @{ - */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup ADCEx_Private_Macros ADC Private Macros - * @{ - */ -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || \ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) || \ - defined(STM32F410Rx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || \ - defined(STM32F412Cx) -#define IS_ADC_CHANNEL(CHANNEL) ((CHANNEL) <= ADC_CHANNEL_18) -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F401xC || STM32F401xE || - STM32F410xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ - -#if defined(STM32F411xE) || defined(STM32F413xx) || defined(STM32F423xx) || defined(STM32F427xx) || \ - defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F446xx) || \ - defined(STM32F469xx) || defined(STM32F479xx) -#define IS_ADC_CHANNEL(CHANNEL) (((CHANNEL) <= ADC_CHANNEL_18) || \ - ((CHANNEL) == ADC_CHANNEL_TEMPSENSOR)) -#endif /* STM32F411xE || STM32F413xx || STM32F423xx || STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ - -#define IS_ADC_MODE(MODE) (((MODE) == ADC_MODE_INDEPENDENT) || \ - ((MODE) == ADC_DUALMODE_REGSIMULT_INJECSIMULT) || \ - ((MODE) == ADC_DUALMODE_REGSIMULT_ALTERTRIG) || \ - ((MODE) == ADC_DUALMODE_INJECSIMULT) || \ - ((MODE) == ADC_DUALMODE_REGSIMULT) || \ - ((MODE) == ADC_DUALMODE_INTERL) || \ - ((MODE) == ADC_DUALMODE_ALTERTRIG) || \ - ((MODE) == ADC_TRIPLEMODE_REGSIMULT_INJECSIMULT) || \ - ((MODE) == ADC_TRIPLEMODE_REGSIMULT_AlterTrig) || \ - ((MODE) == ADC_TRIPLEMODE_INJECSIMULT) || \ - ((MODE) == ADC_TRIPLEMODE_REGSIMULT) || \ - ((MODE) == ADC_TRIPLEMODE_INTERL) || \ - ((MODE) == ADC_TRIPLEMODE_ALTERTRIG)) -#define IS_ADC_DMA_ACCESS_MODE(MODE) (((MODE) == ADC_DMAACCESSMODE_DISABLED) || \ - ((MODE) == ADC_DMAACCESSMODE_1) || \ - ((MODE) == ADC_DMAACCESSMODE_2) || \ - ((MODE) == ADC_DMAACCESSMODE_3)) -#define IS_ADC_EXT_INJEC_TRIG_EDGE(EDGE) (((EDGE) == ADC_EXTERNALTRIGINJECCONVEDGE_NONE) || \ - ((EDGE) == ADC_EXTERNALTRIGINJECCONVEDGE_RISING) || \ - ((EDGE) == ADC_EXTERNALTRIGINJECCONVEDGE_FALLING) || \ - ((EDGE) == ADC_EXTERNALTRIGINJECCONVEDGE_RISINGFALLING)) -#define IS_ADC_EXT_INJEC_TRIG(INJTRIG) (((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T1_CC4) || \ - ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T1_TRGO) || \ - ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T2_CC1) || \ - ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T2_TRGO) || \ - ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T3_CC2) || \ - ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T3_CC4) || \ - ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T4_CC1) || \ - ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T4_CC2) || \ - ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T4_CC3) || \ - ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T4_TRGO) || \ - ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T5_CC4) || \ - ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T5_TRGO) || \ - ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T8_CC2) || \ - ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T8_CC3) || \ - ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_T8_CC4) || \ - ((INJTRIG) == ADC_EXTERNALTRIGINJECCONV_EXT_IT15)|| \ - ((INJTRIG) == ADC_INJECTED_SOFTWARE_START)) -#define IS_ADC_INJECTED_LENGTH(LENGTH) (((LENGTH) >= 1U) && ((LENGTH) <= 4U)) -#define IS_ADC_INJECTED_RANK(RANK) (((RANK) >= 1U) && ((RANK) <= 4U)) - -/** - * @brief Set the selected injected Channel rank. - * @param _CHANNELNB_ Channel number. - * @param _RANKNB_ Rank number. - * @param _JSQR_JL_ Sequence length. - * @retval None - */ -#define ADC_JSQR(_CHANNELNB_, _RANKNB_, _JSQR_JL_) (((uint32_t)((uint16_t)(_CHANNELNB_))) << (5U * (uint8_t)(((_RANKNB_) + 3U) - (_JSQR_JL_)))) - -/** - * @brief Defines if the selected ADC is within ADC common register ADC123 or ADC1 - * if available (ADC2, ADC3 availability depends on STM32 product) - * @param __HANDLE__ ADC handle - * @retval Common control register ADC123 or ADC1 - */ -#if defined(STM32F405xx) || defined(STM32F407xx) || defined(STM32F415xx) || defined(STM32F417xx) || defined(STM32F427xx) || defined(STM32F429xx) || defined(STM32F437xx) || defined(STM32F439xx) || defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -#define ADC_COMMON_REGISTER(__HANDLE__) ADC123_COMMON -#else -#define ADC_COMMON_REGISTER(__HANDLE__) ADC1_COMMON -#endif /* STM32F405xx || STM32F407xx || STM32F415xx || STM32F417xx || STM32F427xx || STM32F429xx || STM32F437xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup ADCEx_Private_Functions ADC Private Functions - * @{ - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /*__STM32F4xx_ADC_EX_H */ - - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_can.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_can.h deleted file mode 100644 index 062abd6..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_can.h +++ /dev/null @@ -1,848 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_can.h - * @author MCD Application Team - * @brief Header file of CAN HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_CAN_H -#define STM32F4xx_HAL_CAN_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -#if defined (CAN1) -/** @addtogroup CAN - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup CAN_Exported_Types CAN Exported Types - * @{ - */ -/** - * @brief HAL State structures definition - */ -typedef enum -{ - HAL_CAN_STATE_RESET = 0x00U, /*!< CAN not yet initialized or disabled */ - HAL_CAN_STATE_READY = 0x01U, /*!< CAN initialized and ready for use */ - HAL_CAN_STATE_LISTENING = 0x02U, /*!< CAN receive process is ongoing */ - HAL_CAN_STATE_SLEEP_PENDING = 0x03U, /*!< CAN sleep request is pending */ - HAL_CAN_STATE_SLEEP_ACTIVE = 0x04U, /*!< CAN sleep mode is active */ - HAL_CAN_STATE_ERROR = 0x05U /*!< CAN error state */ - -} HAL_CAN_StateTypeDef; - -/** - * @brief CAN init structure definition - */ -typedef struct -{ - uint32_t Prescaler; /*!< Specifies the length of a time quantum. - This parameter must be a number between Min_Data = 1 and Max_Data = 1024. */ - - uint32_t Mode; /*!< Specifies the CAN operating mode. - This parameter can be a value of @ref CAN_operating_mode */ - - uint32_t SyncJumpWidth; /*!< Specifies the maximum number of time quanta the CAN hardware - is allowed to lengthen or shorten a bit to perform resynchronization. - This parameter can be a value of @ref CAN_synchronisation_jump_width */ - - uint32_t TimeSeg1; /*!< Specifies the number of time quanta in Bit Segment 1. - This parameter can be a value of @ref CAN_time_quantum_in_bit_segment_1 */ - - uint32_t TimeSeg2; /*!< Specifies the number of time quanta in Bit Segment 2. - This parameter can be a value of @ref CAN_time_quantum_in_bit_segment_2 */ - - FunctionalState TimeTriggeredMode; /*!< Enable or disable the time triggered communication mode. - This parameter can be set to ENABLE or DISABLE. */ - - FunctionalState AutoBusOff; /*!< Enable or disable the automatic bus-off management. - This parameter can be set to ENABLE or DISABLE. */ - - FunctionalState AutoWakeUp; /*!< Enable or disable the automatic wake-up mode. - This parameter can be set to ENABLE or DISABLE. */ - - FunctionalState AutoRetransmission; /*!< Enable or disable the non-automatic retransmission mode. - This parameter can be set to ENABLE or DISABLE. */ - - FunctionalState ReceiveFifoLocked; /*!< Enable or disable the Receive FIFO Locked mode. - This parameter can be set to ENABLE or DISABLE. */ - - FunctionalState TransmitFifoPriority;/*!< Enable or disable the transmit FIFO priority. - This parameter can be set to ENABLE or DISABLE. */ - -} CAN_InitTypeDef; - -/** - * @brief CAN filter configuration structure definition - */ -typedef struct -{ - uint32_t FilterIdHigh; /*!< Specifies the filter identification number (MSBs for a 32-bit - configuration, first one for a 16-bit configuration). - This parameter must be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF. */ - - uint32_t FilterIdLow; /*!< Specifies the filter identification number (LSBs for a 32-bit - configuration, second one for a 16-bit configuration). - This parameter must be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF. */ - - uint32_t FilterMaskIdHigh; /*!< Specifies the filter mask number or identification number, - according to the mode (MSBs for a 32-bit configuration, - first one for a 16-bit configuration). - This parameter must be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF. */ - - uint32_t FilterMaskIdLow; /*!< Specifies the filter mask number or identification number, - according to the mode (LSBs for a 32-bit configuration, - second one for a 16-bit configuration). - This parameter must be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF. */ - - uint32_t FilterFIFOAssignment; /*!< Specifies the FIFO (0 or 1U) which will be assigned to the filter. - This parameter can be a value of @ref CAN_filter_FIFO */ - - uint32_t FilterBank; /*!< Specifies the filter bank which will be initialized. - For single CAN instance(14 dedicated filter banks), - this parameter must be a number between Min_Data = 0 and Max_Data = 13. - For dual CAN instances(28 filter banks shared), - this parameter must be a number between Min_Data = 0 and Max_Data = 27. */ - - uint32_t FilterMode; /*!< Specifies the filter mode to be initialized. - This parameter can be a value of @ref CAN_filter_mode */ - - uint32_t FilterScale; /*!< Specifies the filter scale. - This parameter can be a value of @ref CAN_filter_scale */ - - uint32_t FilterActivation; /*!< Enable or disable the filter. - This parameter can be a value of @ref CAN_filter_activation */ - - uint32_t SlaveStartFilterBank; /*!< Select the start filter bank for the slave CAN instance. - For single CAN instances, this parameter is meaningless. - For dual CAN instances, all filter banks with lower index are assigned to master - CAN instance, whereas all filter banks with greater index are assigned to slave - CAN instance. - This parameter must be a number between Min_Data = 0 and Max_Data = 27. */ - -} CAN_FilterTypeDef; - -/** - * @brief CAN Tx message header structure definition - */ -typedef struct -{ - uint32_t StdId; /*!< Specifies the standard identifier. - This parameter must be a number between Min_Data = 0 and Max_Data = 0x7FF. */ - - uint32_t ExtId; /*!< Specifies the extended identifier. - This parameter must be a number between Min_Data = 0 and Max_Data = 0x1FFFFFFF. */ - - uint32_t IDE; /*!< Specifies the type of identifier for the message that will be transmitted. - This parameter can be a value of @ref CAN_identifier_type */ - - uint32_t RTR; /*!< Specifies the type of frame for the message that will be transmitted. - This parameter can be a value of @ref CAN_remote_transmission_request */ - - uint32_t DLC; /*!< Specifies the length of the frame that will be transmitted. - This parameter must be a number between Min_Data = 0 and Max_Data = 8. */ - - FunctionalState TransmitGlobalTime; /*!< Specifies whether the timestamp counter value captured on start - of frame transmission, is sent in DATA6 and DATA7 replacing pData[6] and pData[7]. - @note: Time Triggered Communication Mode must be enabled. - @note: DLC must be programmed as 8 bytes, in order these 2 bytes are sent. - This parameter can be set to ENABLE or DISABLE. */ - -} CAN_TxHeaderTypeDef; - -/** - * @brief CAN Rx message header structure definition - */ -typedef struct -{ - uint32_t StdId; /*!< Specifies the standard identifier. - This parameter must be a number between Min_Data = 0 and Max_Data = 0x7FF. */ - - uint32_t ExtId; /*!< Specifies the extended identifier. - This parameter must be a number between Min_Data = 0 and Max_Data = 0x1FFFFFFF. */ - - uint32_t IDE; /*!< Specifies the type of identifier for the message that will be transmitted. - This parameter can be a value of @ref CAN_identifier_type */ - - uint32_t RTR; /*!< Specifies the type of frame for the message that will be transmitted. - This parameter can be a value of @ref CAN_remote_transmission_request */ - - uint32_t DLC; /*!< Specifies the length of the frame that will be transmitted. - This parameter must be a number between Min_Data = 0 and Max_Data = 8. */ - - uint32_t Timestamp; /*!< Specifies the timestamp counter value captured on start of frame reception. - @note: Time Triggered Communication Mode must be enabled. - This parameter must be a number between Min_Data = 0 and Max_Data = 0xFFFF. */ - - uint32_t FilterMatchIndex; /*!< Specifies the index of matching acceptance filter element. - This parameter must be a number between Min_Data = 0 and Max_Data = 0xFF. */ - -} CAN_RxHeaderTypeDef; - -/** - * @brief CAN handle Structure definition - */ -typedef struct __CAN_HandleTypeDef -{ - CAN_TypeDef *Instance; /*!< Register base address */ - - CAN_InitTypeDef Init; /*!< CAN required parameters */ - - __IO HAL_CAN_StateTypeDef State; /*!< CAN communication state */ - - __IO uint32_t ErrorCode; /*!< CAN Error code. - This parameter can be a value of @ref CAN_Error_Code */ - -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 - void (* TxMailbox0CompleteCallback)(struct __CAN_HandleTypeDef *hcan);/*!< CAN Tx Mailbox 0 complete callback */ - void (* TxMailbox1CompleteCallback)(struct __CAN_HandleTypeDef *hcan);/*!< CAN Tx Mailbox 1 complete callback */ - void (* TxMailbox2CompleteCallback)(struct __CAN_HandleTypeDef *hcan);/*!< CAN Tx Mailbox 2 complete callback */ - void (* TxMailbox0AbortCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Tx Mailbox 0 abort callback */ - void (* TxMailbox1AbortCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Tx Mailbox 1 abort callback */ - void (* TxMailbox2AbortCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Tx Mailbox 2 abort callback */ - void (* RxFifo0MsgPendingCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Rx FIFO 0 msg pending callback */ - void (* RxFifo0FullCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Rx FIFO 0 full callback */ - void (* RxFifo1MsgPendingCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Rx FIFO 1 msg pending callback */ - void (* RxFifo1FullCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Rx FIFO 1 full callback */ - void (* SleepCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Sleep callback */ - void (* WakeUpFromRxMsgCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Wake Up from Rx msg callback */ - void (* ErrorCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Error callback */ - - void (* MspInitCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Msp Init callback */ - void (* MspDeInitCallback)(struct __CAN_HandleTypeDef *hcan); /*!< CAN Msp DeInit callback */ - -#endif /* (USE_HAL_CAN_REGISTER_CALLBACKS) */ -} CAN_HandleTypeDef; - -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 -/** - * @brief HAL CAN common Callback ID enumeration definition - */ -typedef enum -{ - HAL_CAN_TX_MAILBOX0_COMPLETE_CB_ID = 0x00U, /*!< CAN Tx Mailbox 0 complete callback ID */ - HAL_CAN_TX_MAILBOX1_COMPLETE_CB_ID = 0x01U, /*!< CAN Tx Mailbox 1 complete callback ID */ - HAL_CAN_TX_MAILBOX2_COMPLETE_CB_ID = 0x02U, /*!< CAN Tx Mailbox 2 complete callback ID */ - HAL_CAN_TX_MAILBOX0_ABORT_CB_ID = 0x03U, /*!< CAN Tx Mailbox 0 abort callback ID */ - HAL_CAN_TX_MAILBOX1_ABORT_CB_ID = 0x04U, /*!< CAN Tx Mailbox 1 abort callback ID */ - HAL_CAN_TX_MAILBOX2_ABORT_CB_ID = 0x05U, /*!< CAN Tx Mailbox 2 abort callback ID */ - HAL_CAN_RX_FIFO0_MSG_PENDING_CB_ID = 0x06U, /*!< CAN Rx FIFO 0 message pending callback ID */ - HAL_CAN_RX_FIFO0_FULL_CB_ID = 0x07U, /*!< CAN Rx FIFO 0 full callback ID */ - HAL_CAN_RX_FIFO1_MSG_PENDING_CB_ID = 0x08U, /*!< CAN Rx FIFO 1 message pending callback ID */ - HAL_CAN_RX_FIFO1_FULL_CB_ID = 0x09U, /*!< CAN Rx FIFO 1 full callback ID */ - HAL_CAN_SLEEP_CB_ID = 0x0AU, /*!< CAN Sleep callback ID */ - HAL_CAN_WAKEUP_FROM_RX_MSG_CB_ID = 0x0BU, /*!< CAN Wake Up from Rx msg callback ID */ - HAL_CAN_ERROR_CB_ID = 0x0CU, /*!< CAN Error callback ID */ - - HAL_CAN_MSPINIT_CB_ID = 0x0DU, /*!< CAN MspInit callback ID */ - HAL_CAN_MSPDEINIT_CB_ID = 0x0EU, /*!< CAN MspDeInit callback ID */ - -} HAL_CAN_CallbackIDTypeDef; - -/** - * @brief HAL CAN Callback pointer definition - */ -typedef void (*pCAN_CallbackTypeDef)(CAN_HandleTypeDef *hcan); /*!< pointer to a CAN callback function */ - -#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ - -/** @defgroup CAN_Exported_Constants CAN Exported Constants - * @{ - */ - -/** @defgroup CAN_Error_Code CAN Error Code - * @{ - */ -#define HAL_CAN_ERROR_NONE (0x00000000U) /*!< No error */ -#define HAL_CAN_ERROR_EWG (0x00000001U) /*!< Protocol Error Warning */ -#define HAL_CAN_ERROR_EPV (0x00000002U) /*!< Error Passive */ -#define HAL_CAN_ERROR_BOF (0x00000004U) /*!< Bus-off error */ -#define HAL_CAN_ERROR_STF (0x00000008U) /*!< Stuff error */ -#define HAL_CAN_ERROR_FOR (0x00000010U) /*!< Form error */ -#define HAL_CAN_ERROR_ACK (0x00000020U) /*!< Acknowledgment error */ -#define HAL_CAN_ERROR_BR (0x00000040U) /*!< Bit recessive error */ -#define HAL_CAN_ERROR_BD (0x00000080U) /*!< Bit dominant error */ -#define HAL_CAN_ERROR_CRC (0x00000100U) /*!< CRC error */ -#define HAL_CAN_ERROR_RX_FOV0 (0x00000200U) /*!< Rx FIFO0 overrun error */ -#define HAL_CAN_ERROR_RX_FOV1 (0x00000400U) /*!< Rx FIFO1 overrun error */ -#define HAL_CAN_ERROR_TX_ALST0 (0x00000800U) /*!< TxMailbox 0 transmit failure due to arbitration lost */ -#define HAL_CAN_ERROR_TX_TERR0 (0x00001000U) /*!< TxMailbox 0 transmit failure due to transmit error */ -#define HAL_CAN_ERROR_TX_ALST1 (0x00002000U) /*!< TxMailbox 1 transmit failure due to arbitration lost */ -#define HAL_CAN_ERROR_TX_TERR1 (0x00004000U) /*!< TxMailbox 1 transmit failure due to transmit error */ -#define HAL_CAN_ERROR_TX_ALST2 (0x00008000U) /*!< TxMailbox 2 transmit failure due to arbitration lost */ -#define HAL_CAN_ERROR_TX_TERR2 (0x00010000U) /*!< TxMailbox 2 transmit failure due to transmit error */ -#define HAL_CAN_ERROR_TIMEOUT (0x00020000U) /*!< Timeout error */ -#define HAL_CAN_ERROR_NOT_INITIALIZED (0x00040000U) /*!< Peripheral not initialized */ -#define HAL_CAN_ERROR_NOT_READY (0x00080000U) /*!< Peripheral not ready */ -#define HAL_CAN_ERROR_NOT_STARTED (0x00100000U) /*!< Peripheral not started */ -#define HAL_CAN_ERROR_PARAM (0x00200000U) /*!< Parameter error */ - -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 -#define HAL_CAN_ERROR_INVALID_CALLBACK (0x00400000U) /*!< Invalid Callback error */ -#endif /* USE_HAL_CAN_REGISTER_CALLBACKS */ -#define HAL_CAN_ERROR_INTERNAL (0x00800000U) /*!< Internal error */ - -/** - * @} - */ - -/** @defgroup CAN_InitStatus CAN InitStatus - * @{ - */ -#define CAN_INITSTATUS_FAILED (0x00000000U) /*!< CAN initialization failed */ -#define CAN_INITSTATUS_SUCCESS (0x00000001U) /*!< CAN initialization OK */ -/** - * @} - */ - -/** @defgroup CAN_operating_mode CAN Operating Mode - * @{ - */ -#define CAN_MODE_NORMAL (0x00000000U) /*!< Normal mode */ -#define CAN_MODE_LOOPBACK ((uint32_t)CAN_BTR_LBKM) /*!< Loopback mode */ -#define CAN_MODE_SILENT ((uint32_t)CAN_BTR_SILM) /*!< Silent mode */ -#define CAN_MODE_SILENT_LOOPBACK ((uint32_t)(CAN_BTR_LBKM | CAN_BTR_SILM)) /*!< Loopback combined with silent mode */ -/** - * @} - */ - - -/** @defgroup CAN_synchronisation_jump_width CAN Synchronization Jump Width - * @{ - */ -#define CAN_SJW_1TQ (0x00000000U) /*!< 1 time quantum */ -#define CAN_SJW_2TQ ((uint32_t)CAN_BTR_SJW_0) /*!< 2 time quantum */ -#define CAN_SJW_3TQ ((uint32_t)CAN_BTR_SJW_1) /*!< 3 time quantum */ -#define CAN_SJW_4TQ ((uint32_t)CAN_BTR_SJW) /*!< 4 time quantum */ -/** - * @} - */ - -/** @defgroup CAN_time_quantum_in_bit_segment_1 CAN Time Quantum in Bit Segment 1 - * @{ - */ -#define CAN_BS1_1TQ (0x00000000U) /*!< 1 time quantum */ -#define CAN_BS1_2TQ ((uint32_t)CAN_BTR_TS1_0) /*!< 2 time quantum */ -#define CAN_BS1_3TQ ((uint32_t)CAN_BTR_TS1_1) /*!< 3 time quantum */ -#define CAN_BS1_4TQ ((uint32_t)(CAN_BTR_TS1_1 | CAN_BTR_TS1_0)) /*!< 4 time quantum */ -#define CAN_BS1_5TQ ((uint32_t)CAN_BTR_TS1_2) /*!< 5 time quantum */ -#define CAN_BS1_6TQ ((uint32_t)(CAN_BTR_TS1_2 | CAN_BTR_TS1_0)) /*!< 6 time quantum */ -#define CAN_BS1_7TQ ((uint32_t)(CAN_BTR_TS1_2 | CAN_BTR_TS1_1)) /*!< 7 time quantum */ -#define CAN_BS1_8TQ ((uint32_t)(CAN_BTR_TS1_2 | CAN_BTR_TS1_1 | CAN_BTR_TS1_0)) /*!< 8 time quantum */ -#define CAN_BS1_9TQ ((uint32_t)CAN_BTR_TS1_3) /*!< 9 time quantum */ -#define CAN_BS1_10TQ ((uint32_t)(CAN_BTR_TS1_3 | CAN_BTR_TS1_0)) /*!< 10 time quantum */ -#define CAN_BS1_11TQ ((uint32_t)(CAN_BTR_TS1_3 | CAN_BTR_TS1_1)) /*!< 11 time quantum */ -#define CAN_BS1_12TQ ((uint32_t)(CAN_BTR_TS1_3 | CAN_BTR_TS1_1 | CAN_BTR_TS1_0)) /*!< 12 time quantum */ -#define CAN_BS1_13TQ ((uint32_t)(CAN_BTR_TS1_3 | CAN_BTR_TS1_2)) /*!< 13 time quantum */ -#define CAN_BS1_14TQ ((uint32_t)(CAN_BTR_TS1_3 | CAN_BTR_TS1_2 | CAN_BTR_TS1_0)) /*!< 14 time quantum */ -#define CAN_BS1_15TQ ((uint32_t)(CAN_BTR_TS1_3 | CAN_BTR_TS1_2 | CAN_BTR_TS1_1)) /*!< 15 time quantum */ -#define CAN_BS1_16TQ ((uint32_t)CAN_BTR_TS1) /*!< 16 time quantum */ -/** - * @} - */ - -/** @defgroup CAN_time_quantum_in_bit_segment_2 CAN Time Quantum in Bit Segment 2 - * @{ - */ -#define CAN_BS2_1TQ (0x00000000U) /*!< 1 time quantum */ -#define CAN_BS2_2TQ ((uint32_t)CAN_BTR_TS2_0) /*!< 2 time quantum */ -#define CAN_BS2_3TQ ((uint32_t)CAN_BTR_TS2_1) /*!< 3 time quantum */ -#define CAN_BS2_4TQ ((uint32_t)(CAN_BTR_TS2_1 | CAN_BTR_TS2_0)) /*!< 4 time quantum */ -#define CAN_BS2_5TQ ((uint32_t)CAN_BTR_TS2_2) /*!< 5 time quantum */ -#define CAN_BS2_6TQ ((uint32_t)(CAN_BTR_TS2_2 | CAN_BTR_TS2_0)) /*!< 6 time quantum */ -#define CAN_BS2_7TQ ((uint32_t)(CAN_BTR_TS2_2 | CAN_BTR_TS2_1)) /*!< 7 time quantum */ -#define CAN_BS2_8TQ ((uint32_t)CAN_BTR_TS2) /*!< 8 time quantum */ -/** - * @} - */ - -/** @defgroup CAN_filter_mode CAN Filter Mode - * @{ - */ -#define CAN_FILTERMODE_IDMASK (0x00000000U) /*!< Identifier mask mode */ -#define CAN_FILTERMODE_IDLIST (0x00000001U) /*!< Identifier list mode */ -/** - * @} - */ - -/** @defgroup CAN_filter_scale CAN Filter Scale - * @{ - */ -#define CAN_FILTERSCALE_16BIT (0x00000000U) /*!< Two 16-bit filters */ -#define CAN_FILTERSCALE_32BIT (0x00000001U) /*!< One 32-bit filter */ -/** - * @} - */ - -/** @defgroup CAN_filter_activation CAN Filter Activation - * @{ - */ -#define CAN_FILTER_DISABLE (0x00000000U) /*!< Disable filter */ -#define CAN_FILTER_ENABLE (0x00000001U) /*!< Enable filter */ -/** - * @} - */ - -/** @defgroup CAN_filter_FIFO CAN Filter FIFO - * @{ - */ -#define CAN_FILTER_FIFO0 (0x00000000U) /*!< Filter FIFO 0 assignment for filter x */ -#define CAN_FILTER_FIFO1 (0x00000001U) /*!< Filter FIFO 1 assignment for filter x */ -/** - * @} - */ - -/** @defgroup CAN_identifier_type CAN Identifier Type - * @{ - */ -#define CAN_ID_STD (0x00000000U) /*!< Standard Id */ -#define CAN_ID_EXT (0x00000004U) /*!< Extended Id */ -/** - * @} - */ - -/** @defgroup CAN_remote_transmission_request CAN Remote Transmission Request - * @{ - */ -#define CAN_RTR_DATA (0x00000000U) /*!< Data frame */ -#define CAN_RTR_REMOTE (0x00000002U) /*!< Remote frame */ -/** - * @} - */ - -/** @defgroup CAN_receive_FIFO_number CAN Receive FIFO Number - * @{ - */ -#define CAN_RX_FIFO0 (0x00000000U) /*!< CAN receive FIFO 0 */ -#define CAN_RX_FIFO1 (0x00000001U) /*!< CAN receive FIFO 1 */ -/** - * @} - */ - -/** @defgroup CAN_Tx_Mailboxes CAN Tx Mailboxes - * @{ - */ -#define CAN_TX_MAILBOX0 (0x00000001U) /*!< Tx Mailbox 0 */ -#define CAN_TX_MAILBOX1 (0x00000002U) /*!< Tx Mailbox 1 */ -#define CAN_TX_MAILBOX2 (0x00000004U) /*!< Tx Mailbox 2 */ -/** - * @} - */ - -/** @defgroup CAN_flags CAN Flags - * @{ - */ -/* Transmit Flags */ -#define CAN_FLAG_RQCP0 (0x00000500U) /*!< Request complete MailBox 0 flag */ -#define CAN_FLAG_TXOK0 (0x00000501U) /*!< Transmission OK MailBox 0 flag */ -#define CAN_FLAG_ALST0 (0x00000502U) /*!< Arbitration Lost MailBox 0 flag */ -#define CAN_FLAG_TERR0 (0x00000503U) /*!< Transmission error MailBox 0 flag */ -#define CAN_FLAG_RQCP1 (0x00000508U) /*!< Request complete MailBox1 flag */ -#define CAN_FLAG_TXOK1 (0x00000509U) /*!< Transmission OK MailBox 1 flag */ -#define CAN_FLAG_ALST1 (0x0000050AU) /*!< Arbitration Lost MailBox 1 flag */ -#define CAN_FLAG_TERR1 (0x0000050BU) /*!< Transmission error MailBox 1 flag */ -#define CAN_FLAG_RQCP2 (0x00000510U) /*!< Request complete MailBox2 flag */ -#define CAN_FLAG_TXOK2 (0x00000511U) /*!< Transmission OK MailBox 2 flag */ -#define CAN_FLAG_ALST2 (0x00000512U) /*!< Arbitration Lost MailBox 2 flag */ -#define CAN_FLAG_TERR2 (0x00000513U) /*!< Transmission error MailBox 2 flag */ -#define CAN_FLAG_TME0 (0x0000051AU) /*!< Transmit mailbox 0 empty flag */ -#define CAN_FLAG_TME1 (0x0000051BU) /*!< Transmit mailbox 1 empty flag */ -#define CAN_FLAG_TME2 (0x0000051CU) /*!< Transmit mailbox 2 empty flag */ -#define CAN_FLAG_LOW0 (0x0000051DU) /*!< Lowest priority mailbox 0 flag */ -#define CAN_FLAG_LOW1 (0x0000051EU) /*!< Lowest priority mailbox 1 flag */ -#define CAN_FLAG_LOW2 (0x0000051FU) /*!< Lowest priority mailbox 2 flag */ - -/* Receive Flags */ -#define CAN_FLAG_FF0 (0x00000203U) /*!< RX FIFO 0 Full flag */ -#define CAN_FLAG_FOV0 (0x00000204U) /*!< RX FIFO 0 Overrun flag */ -#define CAN_FLAG_FF1 (0x00000403U) /*!< RX FIFO 1 Full flag */ -#define CAN_FLAG_FOV1 (0x00000404U) /*!< RX FIFO 1 Overrun flag */ - -/* Operating Mode Flags */ -#define CAN_FLAG_INAK (0x00000100U) /*!< Initialization acknowledge flag */ -#define CAN_FLAG_SLAK (0x00000101U) /*!< Sleep acknowledge flag */ -#define CAN_FLAG_ERRI (0x00000102U) /*!< Error flag */ -#define CAN_FLAG_WKU (0x00000103U) /*!< Wake up interrupt flag */ -#define CAN_FLAG_SLAKI (0x00000104U) /*!< Sleep acknowledge interrupt flag */ - -/* Error Flags */ -#define CAN_FLAG_EWG (0x00000300U) /*!< Error warning flag */ -#define CAN_FLAG_EPV (0x00000301U) /*!< Error passive flag */ -#define CAN_FLAG_BOF (0x00000302U) /*!< Bus-Off flag */ -/** - * @} - */ - - -/** @defgroup CAN_Interrupts CAN Interrupts - * @{ - */ -/* Transmit Interrupt */ -#define CAN_IT_TX_MAILBOX_EMPTY ((uint32_t)CAN_IER_TMEIE) /*!< Transmit mailbox empty interrupt */ - -/* Receive Interrupts */ -#define CAN_IT_RX_FIFO0_MSG_PENDING ((uint32_t)CAN_IER_FMPIE0) /*!< FIFO 0 message pending interrupt */ -#define CAN_IT_RX_FIFO0_FULL ((uint32_t)CAN_IER_FFIE0) /*!< FIFO 0 full interrupt */ -#define CAN_IT_RX_FIFO0_OVERRUN ((uint32_t)CAN_IER_FOVIE0) /*!< FIFO 0 overrun interrupt */ -#define CAN_IT_RX_FIFO1_MSG_PENDING ((uint32_t)CAN_IER_FMPIE1) /*!< FIFO 1 message pending interrupt */ -#define CAN_IT_RX_FIFO1_FULL ((uint32_t)CAN_IER_FFIE1) /*!< FIFO 1 full interrupt */ -#define CAN_IT_RX_FIFO1_OVERRUN ((uint32_t)CAN_IER_FOVIE1) /*!< FIFO 1 overrun interrupt */ - -/* Operating Mode Interrupts */ -#define CAN_IT_WAKEUP ((uint32_t)CAN_IER_WKUIE) /*!< Wake-up interrupt */ -#define CAN_IT_SLEEP_ACK ((uint32_t)CAN_IER_SLKIE) /*!< Sleep acknowledge interrupt */ - -/* Error Interrupts */ -#define CAN_IT_ERROR_WARNING ((uint32_t)CAN_IER_EWGIE) /*!< Error warning interrupt */ -#define CAN_IT_ERROR_PASSIVE ((uint32_t)CAN_IER_EPVIE) /*!< Error passive interrupt */ -#define CAN_IT_BUSOFF ((uint32_t)CAN_IER_BOFIE) /*!< Bus-off interrupt */ -#define CAN_IT_LAST_ERROR_CODE ((uint32_t)CAN_IER_LECIE) /*!< Last error code interrupt */ -#define CAN_IT_ERROR ((uint32_t)CAN_IER_ERRIE) /*!< Error Interrupt */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macros -----------------------------------------------------------*/ -/** @defgroup CAN_Exported_Macros CAN Exported Macros - * @{ - */ - -/** @brief Reset CAN handle state - * @param __HANDLE__ CAN handle. - * @retval None - */ -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 -#define __HAL_CAN_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->State = HAL_CAN_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_CAN_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_CAN_STATE_RESET) -#endif /*USE_HAL_CAN_REGISTER_CALLBACKS */ - -/** - * @brief Enable the specified CAN interrupts. - * @param __HANDLE__ CAN handle. - * @param __INTERRUPT__ CAN Interrupt sources to enable. - * This parameter can be any combination of @arg CAN_Interrupts - * @retval None - */ -#define __HAL_CAN_ENABLE_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->IER) |= (__INTERRUPT__)) - -/** - * @brief Disable the specified CAN interrupts. - * @param __HANDLE__ CAN handle. - * @param __INTERRUPT__ CAN Interrupt sources to disable. - * This parameter can be any combination of @arg CAN_Interrupts - * @retval None - */ -#define __HAL_CAN_DISABLE_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->IER) &= ~(__INTERRUPT__)) - -/** @brief Check if the specified CAN interrupt source is enabled or disabled. - * @param __HANDLE__ specifies the CAN Handle. - * @param __INTERRUPT__ specifies the CAN interrupt source to check. - * This parameter can be a value of @arg CAN_Interrupts - * @retval The state of __IT__ (TRUE or FALSE). - */ -#define __HAL_CAN_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->IER) & (__INTERRUPT__)) - -/** @brief Check whether the specified CAN flag is set or not. - * @param __HANDLE__ specifies the CAN Handle. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of @arg CAN_flags - * @retval The state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_CAN_GET_FLAG(__HANDLE__, __FLAG__) \ - ((((__FLAG__) >> 8U) == 5U)? ((((__HANDLE__)->Instance->TSR) & (1U << ((__FLAG__) & CAN_FLAG_MASK))) == (1U << ((__FLAG__) & CAN_FLAG_MASK))): \ - (((__FLAG__) >> 8U) == 2U)? ((((__HANDLE__)->Instance->RF0R) & (1U << ((__FLAG__) & CAN_FLAG_MASK))) == (1U << ((__FLAG__) & CAN_FLAG_MASK))): \ - (((__FLAG__) >> 8U) == 4U)? ((((__HANDLE__)->Instance->RF1R) & (1U << ((__FLAG__) & CAN_FLAG_MASK))) == (1U << ((__FLAG__) & CAN_FLAG_MASK))): \ - (((__FLAG__) >> 8U) == 1U)? ((((__HANDLE__)->Instance->MSR) & (1U << ((__FLAG__) & CAN_FLAG_MASK))) == (1U << ((__FLAG__) & CAN_FLAG_MASK))): \ - (((__FLAG__) >> 8U) == 3U)? ((((__HANDLE__)->Instance->ESR) & (1U << ((__FLAG__) & CAN_FLAG_MASK))) == (1U << ((__FLAG__) & CAN_FLAG_MASK))): 0U) - -/** @brief Clear the specified CAN pending flag. - * @param __HANDLE__ specifies the CAN Handle. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg CAN_FLAG_RQCP0: Request complete MailBox 0 Flag - * @arg CAN_FLAG_TXOK0: Transmission OK MailBox 0 Flag - * @arg CAN_FLAG_ALST0: Arbitration Lost MailBox 0 Flag - * @arg CAN_FLAG_TERR0: Transmission error MailBox 0 Flag - * @arg CAN_FLAG_RQCP1: Request complete MailBox 1 Flag - * @arg CAN_FLAG_TXOK1: Transmission OK MailBox 1 Flag - * @arg CAN_FLAG_ALST1: Arbitration Lost MailBox 1 Flag - * @arg CAN_FLAG_TERR1: Transmission error MailBox 1 Flag - * @arg CAN_FLAG_RQCP2: Request complete MailBox 2 Flag - * @arg CAN_FLAG_TXOK2: Transmission OK MailBox 2 Flag - * @arg CAN_FLAG_ALST2: Arbitration Lost MailBox 2 Flag - * @arg CAN_FLAG_TERR2: Transmission error MailBox 2 Flag - * @arg CAN_FLAG_FF0: RX FIFO 0 Full Flag - * @arg CAN_FLAG_FOV0: RX FIFO 0 Overrun Flag - * @arg CAN_FLAG_FF1: RX FIFO 1 Full Flag - * @arg CAN_FLAG_FOV1: RX FIFO 1 Overrun Flag - * @arg CAN_FLAG_WKUI: Wake up Interrupt Flag - * @arg CAN_FLAG_SLAKI: Sleep acknowledge Interrupt Flag - * @retval None - */ -#define __HAL_CAN_CLEAR_FLAG(__HANDLE__, __FLAG__) \ - ((((__FLAG__) >> 8U) == 5U)? (((__HANDLE__)->Instance->TSR) = (1U << ((__FLAG__) & CAN_FLAG_MASK))): \ - (((__FLAG__) >> 8U) == 2U)? (((__HANDLE__)->Instance->RF0R) = (1U << ((__FLAG__) & CAN_FLAG_MASK))): \ - (((__FLAG__) >> 8U) == 4U)? (((__HANDLE__)->Instance->RF1R) = (1U << ((__FLAG__) & CAN_FLAG_MASK))): \ - (((__FLAG__) >> 8U) == 1U)? (((__HANDLE__)->Instance->MSR) = (1U << ((__FLAG__) & CAN_FLAG_MASK))): 0U) - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup CAN_Exported_Functions CAN Exported Functions - * @{ - */ - -/** @addtogroup CAN_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and Configuration functions - * @{ - */ - -/* Initialization and de-initialization functions *****************************/ -HAL_StatusTypeDef HAL_CAN_Init(CAN_HandleTypeDef *hcan); -HAL_StatusTypeDef HAL_CAN_DeInit(CAN_HandleTypeDef *hcan); -void HAL_CAN_MspInit(CAN_HandleTypeDef *hcan); -void HAL_CAN_MspDeInit(CAN_HandleTypeDef *hcan); - -#if USE_HAL_CAN_REGISTER_CALLBACKS == 1 -/* Callbacks Register/UnRegister functions ***********************************/ -HAL_StatusTypeDef HAL_CAN_RegisterCallback(CAN_HandleTypeDef *hcan, HAL_CAN_CallbackIDTypeDef CallbackID, void (* pCallback)(CAN_HandleTypeDef *_hcan)); -HAL_StatusTypeDef HAL_CAN_UnRegisterCallback(CAN_HandleTypeDef *hcan, HAL_CAN_CallbackIDTypeDef CallbackID); - -#endif /* (USE_HAL_CAN_REGISTER_CALLBACKS) */ -/** - * @} - */ - -/** @addtogroup CAN_Exported_Functions_Group2 Configuration functions - * @brief Configuration functions - * @{ - */ - -/* Configuration functions ****************************************************/ -HAL_StatusTypeDef HAL_CAN_ConfigFilter(CAN_HandleTypeDef *hcan, CAN_FilterTypeDef *sFilterConfig); - -/** - * @} - */ - -/** @addtogroup CAN_Exported_Functions_Group3 Control functions - * @brief Control functions - * @{ - */ - -/* Control functions **********************************************************/ -HAL_StatusTypeDef HAL_CAN_Start(CAN_HandleTypeDef *hcan); -HAL_StatusTypeDef HAL_CAN_Stop(CAN_HandleTypeDef *hcan); -HAL_StatusTypeDef HAL_CAN_RequestSleep(CAN_HandleTypeDef *hcan); -HAL_StatusTypeDef HAL_CAN_WakeUp(CAN_HandleTypeDef *hcan); -uint32_t HAL_CAN_IsSleepActive(CAN_HandleTypeDef *hcan); -HAL_StatusTypeDef HAL_CAN_AddTxMessage(CAN_HandleTypeDef *hcan, CAN_TxHeaderTypeDef *pHeader, uint8_t aData[], uint32_t *pTxMailbox); -HAL_StatusTypeDef HAL_CAN_AbortTxRequest(CAN_HandleTypeDef *hcan, uint32_t TxMailboxes); -uint32_t HAL_CAN_GetTxMailboxesFreeLevel(CAN_HandleTypeDef *hcan); -uint32_t HAL_CAN_IsTxMessagePending(CAN_HandleTypeDef *hcan, uint32_t TxMailboxes); -uint32_t HAL_CAN_GetTxTimestamp(CAN_HandleTypeDef *hcan, uint32_t TxMailbox); -HAL_StatusTypeDef HAL_CAN_GetRxMessage(CAN_HandleTypeDef *hcan, uint32_t RxFifo, CAN_RxHeaderTypeDef *pHeader, uint8_t aData[]); -uint32_t HAL_CAN_GetRxFifoFillLevel(CAN_HandleTypeDef *hcan, uint32_t RxFifo); - -/** - * @} - */ - -/** @addtogroup CAN_Exported_Functions_Group4 Interrupts management - * @brief Interrupts management - * @{ - */ -/* Interrupts management ******************************************************/ -HAL_StatusTypeDef HAL_CAN_ActivateNotification(CAN_HandleTypeDef *hcan, uint32_t ActiveITs); -HAL_StatusTypeDef HAL_CAN_DeactivateNotification(CAN_HandleTypeDef *hcan, uint32_t InactiveITs); -void HAL_CAN_IRQHandler(CAN_HandleTypeDef *hcan); - -/** - * @} - */ - -/** @addtogroup CAN_Exported_Functions_Group5 Callback functions - * @brief Callback functions - * @{ - */ -/* Callbacks functions ********************************************************/ - -void HAL_CAN_TxMailbox0CompleteCallback(CAN_HandleTypeDef *hcan); -void HAL_CAN_TxMailbox1CompleteCallback(CAN_HandleTypeDef *hcan); -void HAL_CAN_TxMailbox2CompleteCallback(CAN_HandleTypeDef *hcan); -void HAL_CAN_TxMailbox0AbortCallback(CAN_HandleTypeDef *hcan); -void HAL_CAN_TxMailbox1AbortCallback(CAN_HandleTypeDef *hcan); -void HAL_CAN_TxMailbox2AbortCallback(CAN_HandleTypeDef *hcan); -void HAL_CAN_RxFifo0MsgPendingCallback(CAN_HandleTypeDef *hcan); -void HAL_CAN_RxFifo0FullCallback(CAN_HandleTypeDef *hcan); -void HAL_CAN_RxFifo1MsgPendingCallback(CAN_HandleTypeDef *hcan); -void HAL_CAN_RxFifo1FullCallback(CAN_HandleTypeDef *hcan); -void HAL_CAN_SleepCallback(CAN_HandleTypeDef *hcan); -void HAL_CAN_WakeUpFromRxMsgCallback(CAN_HandleTypeDef *hcan); -void HAL_CAN_ErrorCallback(CAN_HandleTypeDef *hcan); - -/** - * @} - */ - -/** @addtogroup CAN_Exported_Functions_Group6 Peripheral State and Error functions - * @brief CAN Peripheral State functions - * @{ - */ -/* Peripheral State and Error functions ***************************************/ -HAL_CAN_StateTypeDef HAL_CAN_GetState(CAN_HandleTypeDef *hcan); -uint32_t HAL_CAN_GetError(CAN_HandleTypeDef *hcan); -HAL_StatusTypeDef HAL_CAN_ResetError(CAN_HandleTypeDef *hcan); - -/** - * @} - */ - -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/** @defgroup CAN_Private_Types CAN Private Types - * @{ - */ - -/** - * @} - */ - -/* Private variables ---------------------------------------------------------*/ -/** @defgroup CAN_Private_Variables CAN Private Variables - * @{ - */ - -/** - * @} - */ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup CAN_Private_Constants CAN Private Constants - * @{ - */ -#define CAN_FLAG_MASK (0x000000FFU) -/** - * @} - */ - -/* Private Macros -----------------------------------------------------------*/ -/** @defgroup CAN_Private_Macros CAN Private Macros - * @{ - */ - -#define IS_CAN_MODE(MODE) (((MODE) == CAN_MODE_NORMAL) || \ - ((MODE) == CAN_MODE_LOOPBACK)|| \ - ((MODE) == CAN_MODE_SILENT) || \ - ((MODE) == CAN_MODE_SILENT_LOOPBACK)) -#define IS_CAN_SJW(SJW) (((SJW) == CAN_SJW_1TQ) || ((SJW) == CAN_SJW_2TQ) || \ - ((SJW) == CAN_SJW_3TQ) || ((SJW) == CAN_SJW_4TQ)) -#define IS_CAN_BS1(BS1) (((BS1) == CAN_BS1_1TQ) || ((BS1) == CAN_BS1_2TQ) || \ - ((BS1) == CAN_BS1_3TQ) || ((BS1) == CAN_BS1_4TQ) || \ - ((BS1) == CAN_BS1_5TQ) || ((BS1) == CAN_BS1_6TQ) || \ - ((BS1) == CAN_BS1_7TQ) || ((BS1) == CAN_BS1_8TQ) || \ - ((BS1) == CAN_BS1_9TQ) || ((BS1) == CAN_BS1_10TQ)|| \ - ((BS1) == CAN_BS1_11TQ)|| ((BS1) == CAN_BS1_12TQ)|| \ - ((BS1) == CAN_BS1_13TQ)|| ((BS1) == CAN_BS1_14TQ)|| \ - ((BS1) == CAN_BS1_15TQ)|| ((BS1) == CAN_BS1_16TQ)) -#define IS_CAN_BS2(BS2) (((BS2) == CAN_BS2_1TQ) || ((BS2) == CAN_BS2_2TQ) || \ - ((BS2) == CAN_BS2_3TQ) || ((BS2) == CAN_BS2_4TQ) || \ - ((BS2) == CAN_BS2_5TQ) || ((BS2) == CAN_BS2_6TQ) || \ - ((BS2) == CAN_BS2_7TQ) || ((BS2) == CAN_BS2_8TQ)) -#define IS_CAN_PRESCALER(PRESCALER) (((PRESCALER) >= 1U) && ((PRESCALER) <= 1024U)) -#define IS_CAN_FILTER_ID_HALFWORD(HALFWORD) ((HALFWORD) <= 0xFFFFU) -#define IS_CAN_FILTER_BANK_DUAL(BANK) ((BANK) <= 27U) -#define IS_CAN_FILTER_BANK_SINGLE(BANK) ((BANK) <= 13U) -#define IS_CAN_FILTER_MODE(MODE) (((MODE) == CAN_FILTERMODE_IDMASK) || \ - ((MODE) == CAN_FILTERMODE_IDLIST)) -#define IS_CAN_FILTER_SCALE(SCALE) (((SCALE) == CAN_FILTERSCALE_16BIT) || \ - ((SCALE) == CAN_FILTERSCALE_32BIT)) -#define IS_CAN_FILTER_ACTIVATION(ACTIVATION) (((ACTIVATION) == CAN_FILTER_DISABLE) || \ - ((ACTIVATION) == CAN_FILTER_ENABLE)) -#define IS_CAN_FILTER_FIFO(FIFO) (((FIFO) == CAN_FILTER_FIFO0) || \ - ((FIFO) == CAN_FILTER_FIFO1)) -#define IS_CAN_TX_MAILBOX(TRANSMITMAILBOX) (((TRANSMITMAILBOX) == CAN_TX_MAILBOX0 ) || \ - ((TRANSMITMAILBOX) == CAN_TX_MAILBOX1 ) || \ - ((TRANSMITMAILBOX) == CAN_TX_MAILBOX2 )) -#define IS_CAN_TX_MAILBOX_LIST(TRANSMITMAILBOX) ((TRANSMITMAILBOX) <= (CAN_TX_MAILBOX0 | CAN_TX_MAILBOX1 | CAN_TX_MAILBOX2)) -#define IS_CAN_STDID(STDID) ((STDID) <= 0x7FFU) -#define IS_CAN_EXTID(EXTID) ((EXTID) <= 0x1FFFFFFFU) -#define IS_CAN_DLC(DLC) ((DLC) <= 8U) -#define IS_CAN_IDTYPE(IDTYPE) (((IDTYPE) == CAN_ID_STD) || \ - ((IDTYPE) == CAN_ID_EXT)) -#define IS_CAN_RTR(RTR) (((RTR) == CAN_RTR_DATA) || ((RTR) == CAN_RTR_REMOTE)) -#define IS_CAN_RX_FIFO(FIFO) (((FIFO) == CAN_RX_FIFO0) || ((FIFO) == CAN_RX_FIFO1)) -#define IS_CAN_IT(IT) ((IT) <= (CAN_IT_TX_MAILBOX_EMPTY | CAN_IT_RX_FIFO0_MSG_PENDING | \ - CAN_IT_RX_FIFO0_FULL | CAN_IT_RX_FIFO0_OVERRUN | \ - CAN_IT_RX_FIFO1_MSG_PENDING | CAN_IT_RX_FIFO1_FULL | \ - CAN_IT_RX_FIFO1_OVERRUN | CAN_IT_WAKEUP | \ - CAN_IT_SLEEP_ACK | CAN_IT_ERROR_WARNING | \ - CAN_IT_ERROR_PASSIVE | CAN_IT_BUSOFF | \ - CAN_IT_LAST_ERROR_CODE | CAN_IT_ERROR)) - -/** - * @} - */ -/* End of private macros -----------------------------------------------------*/ - -/** - * @} - */ - - -#endif /* CAN1 */ -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_HAL_CAN_H */ - - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_cec.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_cec.h deleted file mode 100644 index 9041577..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_cec.h +++ /dev/null @@ -1,794 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_cec.h - * @author MCD Application Team - * @brief Header file of CEC HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_CEC_H -#define STM32F4xx_HAL_CEC_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -#if defined (CEC) - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup CEC - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup CEC_Exported_Types CEC Exported Types - * @{ - */ - -/** - * @brief CEC Init Structure definition - */ -typedef struct -{ - uint32_t SignalFreeTime; /*!< Set SFT field, specifies the Signal Free Time. - It can be one of @ref CEC_Signal_Free_Time - and belongs to the set {0,...,7} where - 0x0 is the default configuration - else means 0.5 + (SignalFreeTime - 1) nominal data bit periods */ - - uint32_t Tolerance; /*!< Set RXTOL bit, specifies the tolerance accepted on the received waveforms, - it can be a value of @ref CEC_Tolerance : it is either CEC_STANDARD_TOLERANCE - or CEC_EXTENDED_TOLERANCE */ - - uint32_t BRERxStop; /*!< Set BRESTP bit @ref CEC_BRERxStop : specifies whether or not a Bit Rising Error stops the reception. - CEC_NO_RX_STOP_ON_BRE: reception is not stopped. - CEC_RX_STOP_ON_BRE: reception is stopped. */ - - uint32_t BREErrorBitGen; /*!< Set BREGEN bit @ref CEC_BREErrorBitGen : specifies whether or not an Error-Bit is generated on the - CEC line upon Bit Rising Error detection. - CEC_BRE_ERRORBIT_NO_GENERATION: no error-bit generation. - CEC_BRE_ERRORBIT_GENERATION: error-bit generation if BRESTP is set. */ - - uint32_t LBPEErrorBitGen; /*!< Set LBPEGEN bit @ref CEC_LBPEErrorBitGen : specifies whether or not an Error-Bit is generated on the - CEC line upon Long Bit Period Error detection. - CEC_LBPE_ERRORBIT_NO_GENERATION: no error-bit generation. - CEC_LBPE_ERRORBIT_GENERATION: error-bit generation. */ - - uint32_t BroadcastMsgNoErrorBitGen; /*!< Set BRDNOGEN bit @ref CEC_BroadCastMsgErrorBitGen : allows to avoid an Error-Bit generation on the CEC line - upon an error detected on a broadcast message. - - It supersedes BREGEN and LBPEGEN bits for a broadcast message error handling. It can take two values: - - 1) CEC_BROADCASTERROR_ERRORBIT_GENERATION. - a) BRE detection: error-bit generation on the CEC line if BRESTP=CEC_RX_STOP_ON_BRE - and BREGEN=CEC_BRE_ERRORBIT_NO_GENERATION. - b) LBPE detection: error-bit generation on the CEC line - if LBPGEN=CEC_LBPE_ERRORBIT_NO_GENERATION. - - 2) CEC_BROADCASTERROR_NO_ERRORBIT_GENERATION. - no error-bit generation in case neither a) nor b) are satisfied. Additionally, - there is no error-bit generation in case of Short Bit Period Error detection in - a broadcast message while LSTN bit is set. */ - - uint32_t SignalFreeTimeOption; /*!< Set SFTOP bit @ref CEC_SFT_Option : specifies when SFT timer starts. - CEC_SFT_START_ON_TXSOM SFT: timer starts when TXSOM is set by software. - CEC_SFT_START_ON_TX_RX_END: SFT timer starts automatically at the end of message transmission/reception. */ - - uint32_t ListenMode; /*!< Set LSTN bit @ref CEC_Listening_Mode : specifies device listening mode. It can take two values: - - CEC_REDUCED_LISTENING_MODE: CEC peripheral receives only message addressed to its - own address (OAR). Messages addressed to different destination are ignored. - Broadcast messages are always received. - - CEC_FULL_LISTENING_MODE: CEC peripheral receives messages addressed to its own - address (OAR) with positive acknowledge. Messages addressed to different destination - are received, but without interfering with the CEC bus: no acknowledge sent. */ - - uint16_t OwnAddress; /*!< Own addresses configuration - This parameter can be a value of @ref CEC_OWN_ADDRESS */ - - uint8_t *RxBuffer; /*!< CEC Rx buffer pointeur */ - - -} CEC_InitTypeDef; - -/** - * @brief HAL CEC State definition - * @note HAL CEC State value is a combination of 2 different substates: gState and RxState (see @ref CEC_State_Definition). - * - gState contains CEC state information related to global Handle management - * and also information related to Tx operations. - * gState value coding follow below described bitmap : - * b7 (not used) - * x : Should be set to 0 - * b6 Error information - * 0 : No Error - * 1 : Error - * b5 CEC peripheral initialization status - * 0 : Reset (peripheral not initialized) - * 1 : Init done (peripheral initialized. HAL CEC Init function already called) - * b4-b3 (not used) - * xx : Should be set to 00 - * b2 Intrinsic process state - * 0 : Ready - * 1 : Busy (peripheral busy with some configuration or internal operations) - * b1 (not used) - * x : Should be set to 0 - * b0 Tx state - * 0 : Ready (no Tx operation ongoing) - * 1 : Busy (Tx operation ongoing) - * - RxState contains information related to Rx operations. - * RxState value coding follow below described bitmap : - * b7-b6 (not used) - * xx : Should be set to 00 - * b5 CEC peripheral initialization status - * 0 : Reset (peripheral not initialized) - * 1 : Init done (peripheral initialized) - * b4-b2 (not used) - * xxx : Should be set to 000 - * b1 Rx state - * 0 : Ready (no Rx operation ongoing) - * 1 : Busy (Rx operation ongoing) - * b0 (not used) - * x : Should be set to 0. - */ -typedef uint32_t HAL_CEC_StateTypeDef; - -/** - * @brief CEC handle Structure definition - */ -#if (USE_HAL_CEC_REGISTER_CALLBACKS == 1) -typedef struct __CEC_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_CEC_REGISTER_CALLBACKS */ -{ - CEC_TypeDef *Instance; /*!< CEC registers base address */ - - CEC_InitTypeDef Init; /*!< CEC communication parameters */ - - uint8_t *pTxBuffPtr; /*!< Pointer to CEC Tx transfer Buffer */ - - uint16_t TxXferCount; /*!< CEC Tx Transfer Counter */ - - uint16_t RxXferSize; /*!< CEC Rx Transfer size, 0: header received only */ - - HAL_LockTypeDef Lock; /*!< Locking object */ - - HAL_CEC_StateTypeDef gState; /*!< CEC state information related to global Handle management - and also related to Tx operations. - This parameter can be a value of @ref HAL_CEC_StateTypeDef */ - - HAL_CEC_StateTypeDef RxState; /*!< CEC state information related to Rx operations. - This parameter can be a value of @ref HAL_CEC_StateTypeDef */ - - uint32_t ErrorCode; /*!< For errors handling purposes, copy of ISR register - in case error is reported */ - -#if (USE_HAL_CEC_REGISTER_CALLBACKS == 1) - void (* TxCpltCallback)(struct __CEC_HandleTypeDef - *hcec); /*!< CEC Tx Transfer completed callback */ - void (* RxCpltCallback)(struct __CEC_HandleTypeDef *hcec, - uint32_t RxFrameSize); /*!< CEC Rx Transfer completed callback */ - void (* ErrorCallback)(struct __CEC_HandleTypeDef *hcec); /*!< CEC error callback */ - - void (* MspInitCallback)(struct __CEC_HandleTypeDef *hcec); /*!< CEC Msp Init callback */ - void (* MspDeInitCallback)(struct __CEC_HandleTypeDef *hcec); /*!< CEC Msp DeInit callback */ - -#endif /* (USE_HAL_CEC_REGISTER_CALLBACKS) */ -} CEC_HandleTypeDef; - -#if (USE_HAL_CEC_REGISTER_CALLBACKS == 1) -/** - * @brief HAL CEC Callback ID enumeration definition - */ -typedef enum -{ - HAL_CEC_TX_CPLT_CB_ID = 0x00U, /*!< CEC Tx Transfer completed callback ID */ - HAL_CEC_RX_CPLT_CB_ID = 0x01U, /*!< CEC Rx Transfer completed callback ID */ - HAL_CEC_ERROR_CB_ID = 0x02U, /*!< CEC error callback ID */ - HAL_CEC_MSPINIT_CB_ID = 0x03U, /*!< CEC Msp Init callback ID */ - HAL_CEC_MSPDEINIT_CB_ID = 0x04U /*!< CEC Msp DeInit callback ID */ -} HAL_CEC_CallbackIDTypeDef; - -/** - * @brief HAL CEC Callback pointer definition - */ -typedef void (*pCEC_CallbackTypeDef)(CEC_HandleTypeDef *hcec); /*!< pointer to an CEC callback function */ -typedef void (*pCEC_RxCallbackTypeDef)(CEC_HandleTypeDef *hcec, - uint32_t RxFrameSize); /*!< pointer to an Rx Transfer completed callback function */ -#endif /* USE_HAL_CEC_REGISTER_CALLBACKS */ -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup CEC_Exported_Constants CEC Exported Constants - * @{ - */ -/** @defgroup CEC_State_Definition CEC State Code Definition - * @{ - */ -#define HAL_CEC_STATE_RESET ((uint32_t)0x00000000) /*!< Peripheral is not yet Initialized - Value is allowed for gState and RxState */ -#define HAL_CEC_STATE_READY ((uint32_t)0x00000020) /*!< Peripheral Initialized and ready for use - Value is allowed for gState and RxState */ -#define HAL_CEC_STATE_BUSY ((uint32_t)0x00000024) /*!< an internal process is ongoing - Value is allowed for gState only */ -#define HAL_CEC_STATE_BUSY_RX ((uint32_t)0x00000022) /*!< Data Reception process is ongoing - Value is allowed for RxState only */ -#define HAL_CEC_STATE_BUSY_TX ((uint32_t)0x00000021) /*!< Data Transmission process is ongoing - Value is allowed for gState only */ -#define HAL_CEC_STATE_BUSY_RX_TX ((uint32_t)0x00000023) /*!< an internal process is ongoing - Value is allowed for gState only */ -#define HAL_CEC_STATE_ERROR ((uint32_t)0x00000050) /*!< Error Value is allowed for gState only */ -/** - * @} - */ -/** @defgroup CEC_Error_Code CEC Error Code - * @{ - */ -#define HAL_CEC_ERROR_NONE (uint32_t) 0x0000U /*!< no error */ -#define HAL_CEC_ERROR_RXOVR CEC_ISR_RXOVR /*!< CEC Rx-Overrun */ -#define HAL_CEC_ERROR_BRE CEC_ISR_BRE /*!< CEC Rx Bit Rising Error */ -#define HAL_CEC_ERROR_SBPE CEC_ISR_SBPE /*!< CEC Rx Short Bit period Error */ -#define HAL_CEC_ERROR_LBPE CEC_ISR_LBPE /*!< CEC Rx Long Bit period Error */ -#define HAL_CEC_ERROR_RXACKE CEC_ISR_RXACKE /*!< CEC Rx Missing Acknowledge */ -#define HAL_CEC_ERROR_ARBLST CEC_ISR_ARBLST /*!< CEC Arbitration Lost */ -#define HAL_CEC_ERROR_TXUDR CEC_ISR_TXUDR /*!< CEC Tx-Buffer Underrun */ -#define HAL_CEC_ERROR_TXERR CEC_ISR_TXERR /*!< CEC Tx-Error */ -#define HAL_CEC_ERROR_TXACKE CEC_ISR_TXACKE /*!< CEC Tx Missing Acknowledge */ -#if (USE_HAL_CEC_REGISTER_CALLBACKS == 1) -#define HAL_CEC_ERROR_INVALID_CALLBACK ((uint32_t)0x00002000U) /*!< Invalid Callback Error */ -#endif /* USE_HAL_CEC_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @defgroup CEC_Signal_Free_Time CEC Signal Free Time setting parameter - * @{ - */ -#define CEC_DEFAULT_SFT ((uint32_t)0x00000000U) -#define CEC_0_5_BITPERIOD_SFT ((uint32_t)0x00000001U) -#define CEC_1_5_BITPERIOD_SFT ((uint32_t)0x00000002U) -#define CEC_2_5_BITPERIOD_SFT ((uint32_t)0x00000003U) -#define CEC_3_5_BITPERIOD_SFT ((uint32_t)0x00000004U) -#define CEC_4_5_BITPERIOD_SFT ((uint32_t)0x00000005U) -#define CEC_5_5_BITPERIOD_SFT ((uint32_t)0x00000006U) -#define CEC_6_5_BITPERIOD_SFT ((uint32_t)0x00000007U) -/** - * @} - */ - -/** @defgroup CEC_Tolerance CEC Receiver Tolerance - * @{ - */ -#define CEC_STANDARD_TOLERANCE ((uint32_t)0x00000000U) -#define CEC_EXTENDED_TOLERANCE ((uint32_t)CEC_CFGR_RXTOL) -/** - * @} - */ - -/** @defgroup CEC_BRERxStop CEC Reception Stop on Error - * @{ - */ -#define CEC_NO_RX_STOP_ON_BRE ((uint32_t)0x00000000U) -#define CEC_RX_STOP_ON_BRE ((uint32_t)CEC_CFGR_BRESTP) -/** - * @} - */ - -/** @defgroup CEC_BREErrorBitGen CEC Error Bit Generation if Bit Rise Error reported - * @{ - */ -#define CEC_BRE_ERRORBIT_NO_GENERATION ((uint32_t)0x00000000U) -#define CEC_BRE_ERRORBIT_GENERATION ((uint32_t)CEC_CFGR_BREGEN) -/** - * @} - */ - -/** @defgroup CEC_LBPEErrorBitGen CEC Error Bit Generation if Long Bit Period Error reported - * @{ - */ -#define CEC_LBPE_ERRORBIT_NO_GENERATION ((uint32_t)0x00000000U) -#define CEC_LBPE_ERRORBIT_GENERATION ((uint32_t)CEC_CFGR_LBPEGEN) -/** - * @} - */ - -/** @defgroup CEC_BroadCastMsgErrorBitGen CEC Error Bit Generation on Broadcast message - * @{ - */ -#define CEC_BROADCASTERROR_ERRORBIT_GENERATION ((uint32_t)0x00000000U) -#define CEC_BROADCASTERROR_NO_ERRORBIT_GENERATION ((uint32_t)CEC_CFGR_BRDNOGEN) -/** - * @} - */ - -/** @defgroup CEC_SFT_Option CEC Signal Free Time start option - * @{ - */ -#define CEC_SFT_START_ON_TXSOM ((uint32_t)0x00000000U) -#define CEC_SFT_START_ON_TX_RX_END ((uint32_t)CEC_CFGR_SFTOPT) -/** - * @} - */ - -/** @defgroup CEC_Listening_Mode CEC Listening mode option - * @{ - */ -#define CEC_REDUCED_LISTENING_MODE ((uint32_t)0x00000000U) -#define CEC_FULL_LISTENING_MODE ((uint32_t)CEC_CFGR_LSTN) -/** - * @} - */ - -/** @defgroup CEC_OAR_Position CEC Device Own Address position in CEC CFGR register - * @{ - */ -#define CEC_CFGR_OAR_LSB_POS ((uint32_t) 16U) -/** - * @} - */ - -/** @defgroup CEC_Initiator_Position CEC Initiator logical address position in message header - * @{ - */ -#define CEC_INITIATOR_LSB_POS ((uint32_t) 4U) -/** - * @} - */ - -/** @defgroup CEC_OWN_ADDRESS CEC Own Address - * @{ - */ -#define CEC_OWN_ADDRESS_NONE ((uint16_t) 0x0000U) /* Reset value */ -#define CEC_OWN_ADDRESS_0 ((uint16_t) 0x0001U) /* Logical Address 0 */ -#define CEC_OWN_ADDRESS_1 ((uint16_t) 0x0002U) /* Logical Address 1 */ -#define CEC_OWN_ADDRESS_2 ((uint16_t) 0x0004U) /* Logical Address 2 */ -#define CEC_OWN_ADDRESS_3 ((uint16_t) 0x0008U) /* Logical Address 3 */ -#define CEC_OWN_ADDRESS_4 ((uint16_t) 0x0010U) /* Logical Address 4 */ -#define CEC_OWN_ADDRESS_5 ((uint16_t) 0x0020U) /* Logical Address 5 */ -#define CEC_OWN_ADDRESS_6 ((uint16_t) 0x0040U) /* Logical Address 6 */ -#define CEC_OWN_ADDRESS_7 ((uint16_t) 0x0080U) /* Logical Address 7 */ -#define CEC_OWN_ADDRESS_8 ((uint16_t) 0x0100U) /* Logical Address 9 */ -#define CEC_OWN_ADDRESS_9 ((uint16_t) 0x0200U) /* Logical Address 10 */ -#define CEC_OWN_ADDRESS_10 ((uint16_t) 0x0400U) /* Logical Address 11 */ -#define CEC_OWN_ADDRESS_11 ((uint16_t) 0x0800U) /* Logical Address 12 */ -#define CEC_OWN_ADDRESS_12 ((uint16_t) 0x1000U) /* Logical Address 13 */ -#define CEC_OWN_ADDRESS_13 ((uint16_t) 0x2000U) /* Logical Address 14 */ -#define CEC_OWN_ADDRESS_14 ((uint16_t) 0x4000U) /* Logical Address 15 */ -/** - * @} - */ - -/** @defgroup CEC_Interrupts_Definitions CEC Interrupts definition - * @{ - */ -#define CEC_IT_TXACKE CEC_IER_TXACKEIE -#define CEC_IT_TXERR CEC_IER_TXERRIE -#define CEC_IT_TXUDR CEC_IER_TXUDRIE -#define CEC_IT_TXEND CEC_IER_TXENDIE -#define CEC_IT_TXBR CEC_IER_TXBRIE -#define CEC_IT_ARBLST CEC_IER_ARBLSTIE -#define CEC_IT_RXACKE CEC_IER_RXACKEIE -#define CEC_IT_LBPE CEC_IER_LBPEIE -#define CEC_IT_SBPE CEC_IER_SBPEIE -#define CEC_IT_BRE CEC_IER_BREIE -#define CEC_IT_RXOVR CEC_IER_RXOVRIE -#define CEC_IT_RXEND CEC_IER_RXENDIE -#define CEC_IT_RXBR CEC_IER_RXBRIE -/** - * @} - */ - -/** @defgroup CEC_Flags_Definitions CEC Flags definition - * @{ - */ -#define CEC_FLAG_TXACKE CEC_ISR_TXACKE -#define CEC_FLAG_TXERR CEC_ISR_TXERR -#define CEC_FLAG_TXUDR CEC_ISR_TXUDR -#define CEC_FLAG_TXEND CEC_ISR_TXEND -#define CEC_FLAG_TXBR CEC_ISR_TXBR -#define CEC_FLAG_ARBLST CEC_ISR_ARBLST -#define CEC_FLAG_RXACKE CEC_ISR_RXACKE -#define CEC_FLAG_LBPE CEC_ISR_LBPE -#define CEC_FLAG_SBPE CEC_ISR_SBPE -#define CEC_FLAG_BRE CEC_ISR_BRE -#define CEC_FLAG_RXOVR CEC_ISR_RXOVR -#define CEC_FLAG_RXEND CEC_ISR_RXEND -#define CEC_FLAG_RXBR CEC_ISR_RXBR -/** - * @} - */ - -/** @defgroup CEC_ALL_ERROR CEC all RX or TX errors flags - * @{ - */ -#define CEC_ISR_ALL_ERROR ((uint32_t)CEC_ISR_RXOVR|CEC_ISR_BRE|CEC_ISR_SBPE|CEC_ISR_LBPE|CEC_ISR_RXACKE|\ - CEC_ISR_ARBLST|CEC_ISR_TXUDR|CEC_ISR_TXERR|CEC_ISR_TXACKE) -/** - * @} - */ - -/** @defgroup CEC_IER_ALL_RX CEC all RX errors interrupts enabling flag - * @{ - */ -#define CEC_IER_RX_ALL_ERR ((uint32_t)CEC_IER_RXACKEIE|CEC_IER_LBPEIE|CEC_IER_SBPEIE|CEC_IER_BREIE|CEC_IER_RXOVRIE) -/** - * @} - */ - -/** @defgroup CEC_IER_ALL_TX CEC all TX errors interrupts enabling flag - * @{ - */ -#define CEC_IER_TX_ALL_ERR ((uint32_t)CEC_IER_TXACKEIE|CEC_IER_TXERRIE|CEC_IER_TXUDRIE|CEC_IER_ARBLSTIE) -/** - * @} - */ - -/** - * @} - */ - -/* Exported macros -----------------------------------------------------------*/ -/** @defgroup CEC_Exported_Macros CEC Exported Macros - * @{ - */ - -/** @brief Reset CEC handle gstate & RxState - * @param __HANDLE__ CEC handle. - * @retval None - */ -#if (USE_HAL_CEC_REGISTER_CALLBACKS == 1) -#define __HAL_CEC_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->gState = HAL_CEC_STATE_RESET; \ - (__HANDLE__)->RxState = HAL_CEC_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_CEC_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->gState = HAL_CEC_STATE_RESET; \ - (__HANDLE__)->RxState = HAL_CEC_STATE_RESET; \ - } while(0) -#endif /* USE_HAL_CEC_REGISTER_CALLBACKS */ -/** @brief Checks whether or not the specified CEC interrupt flag is set. - * @param __HANDLE__ specifies the CEC Handle. - * @param __FLAG__ specifies the flag to check. - * @arg CEC_FLAG_TXACKE: Tx Missing acknowledge Error - * @arg CEC_FLAG_TXERR: Tx Error. - * @arg CEC_FLAG_TXUDR: Tx-Buffer Underrun. - * @arg CEC_FLAG_TXEND: End of transmission (successful transmission of the last byte). - * @arg CEC_FLAG_TXBR: Tx-Byte Request. - * @arg CEC_FLAG_ARBLST: Arbitration Lost - * @arg CEC_FLAG_RXACKE: Rx-Missing Acknowledge - * @arg CEC_FLAG_LBPE: Rx Long period Error - * @arg CEC_FLAG_SBPE: Rx Short period Error - * @arg CEC_FLAG_BRE: Rx Bit Rising Error - * @arg CEC_FLAG_RXOVR: Rx Overrun. - * @arg CEC_FLAG_RXEND: End Of Reception. - * @arg CEC_FLAG_RXBR: Rx-Byte Received. - * @retval ITStatus - */ -#define __HAL_CEC_GET_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->ISR & (__FLAG__)) - -/** @brief Clears the interrupt or status flag when raised (write at 1) - * @param __HANDLE__ specifies the CEC Handle. - * @param __FLAG__ specifies the interrupt/status flag to clear. - * This parameter can be one of the following values: - * @arg CEC_FLAG_TXACKE: Tx Missing acknowledge Error - * @arg CEC_FLAG_TXERR: Tx Error. - * @arg CEC_FLAG_TXUDR: Tx-Buffer Underrun. - * @arg CEC_FLAG_TXEND: End of transmission (successful transmission of the last byte). - * @arg CEC_FLAG_TXBR: Tx-Byte Request. - * @arg CEC_FLAG_ARBLST: Arbitration Lost - * @arg CEC_FLAG_RXACKE: Rx-Missing Acknowledge - * @arg CEC_FLAG_LBPE: Rx Long period Error - * @arg CEC_FLAG_SBPE: Rx Short period Error - * @arg CEC_FLAG_BRE: Rx Bit Rising Error - * @arg CEC_FLAG_RXOVR: Rx Overrun. - * @arg CEC_FLAG_RXEND: End Of Reception. - * @arg CEC_FLAG_RXBR: Rx-Byte Received. - * @retval none - */ -#define __HAL_CEC_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->ISR |= (__FLAG__)) - -/** @brief Enables the specified CEC interrupt. - * @param __HANDLE__ specifies the CEC Handle. - * @param __INTERRUPT__ specifies the CEC interrupt to enable. - * This parameter can be one of the following values: - * @arg CEC_IT_TXACKE: Tx Missing acknowledge Error IT Enable - * @arg CEC_IT_TXERR: Tx Error IT Enable - * @arg CEC_IT_TXUDR: Tx-Buffer Underrun IT Enable - * @arg CEC_IT_TXEND: End of transmission IT Enable - * @arg CEC_IT_TXBR: Tx-Byte Request IT Enable - * @arg CEC_IT_ARBLST: Arbitration Lost IT Enable - * @arg CEC_IT_RXACKE: Rx-Missing Acknowledge IT Enable - * @arg CEC_IT_LBPE: Rx Long period Error IT Enable - * @arg CEC_IT_SBPE: Rx Short period Error IT Enable - * @arg CEC_IT_BRE: Rx Bit Rising Error IT Enable - * @arg CEC_IT_RXOVR: Rx Overrun IT Enable - * @arg CEC_IT_RXEND: End Of Reception IT Enable - * @arg CEC_IT_RXBR: Rx-Byte Received IT Enable - * @retval none - */ -#define __HAL_CEC_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->IER |= (__INTERRUPT__)) - -/** @brief Disables the specified CEC interrupt. - * @param __HANDLE__ specifies the CEC Handle. - * @param __INTERRUPT__ specifies the CEC interrupt to disable. - * This parameter can be one of the following values: - * @arg CEC_IT_TXACKE: Tx Missing acknowledge Error IT Enable - * @arg CEC_IT_TXERR: Tx Error IT Enable - * @arg CEC_IT_TXUDR: Tx-Buffer Underrun IT Enable - * @arg CEC_IT_TXEND: End of transmission IT Enable - * @arg CEC_IT_TXBR: Tx-Byte Request IT Enable - * @arg CEC_IT_ARBLST: Arbitration Lost IT Enable - * @arg CEC_IT_RXACKE: Rx-Missing Acknowledge IT Enable - * @arg CEC_IT_LBPE: Rx Long period Error IT Enable - * @arg CEC_IT_SBPE: Rx Short period Error IT Enable - * @arg CEC_IT_BRE: Rx Bit Rising Error IT Enable - * @arg CEC_IT_RXOVR: Rx Overrun IT Enable - * @arg CEC_IT_RXEND: End Of Reception IT Enable - * @arg CEC_IT_RXBR: Rx-Byte Received IT Enable - * @retval none - */ -#define __HAL_CEC_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->IER &= (~(__INTERRUPT__))) - -/** @brief Checks whether or not the specified CEC interrupt is enabled. - * @param __HANDLE__ specifies the CEC Handle. - * @param __INTERRUPT__ specifies the CEC interrupt to check. - * This parameter can be one of the following values: - * @arg CEC_IT_TXACKE: Tx Missing acknowledge Error IT Enable - * @arg CEC_IT_TXERR: Tx Error IT Enable - * @arg CEC_IT_TXUDR: Tx-Buffer Underrun IT Enable - * @arg CEC_IT_TXEND: End of transmission IT Enable - * @arg CEC_IT_TXBR: Tx-Byte Request IT Enable - * @arg CEC_IT_ARBLST: Arbitration Lost IT Enable - * @arg CEC_IT_RXACKE: Rx-Missing Acknowledge IT Enable - * @arg CEC_IT_LBPE: Rx Long period Error IT Enable - * @arg CEC_IT_SBPE: Rx Short period Error IT Enable - * @arg CEC_IT_BRE: Rx Bit Rising Error IT Enable - * @arg CEC_IT_RXOVR: Rx Overrun IT Enable - * @arg CEC_IT_RXEND: End Of Reception IT Enable - * @arg CEC_IT_RXBR: Rx-Byte Received IT Enable - * @retval FlagStatus - */ -#define __HAL_CEC_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->IER & (__INTERRUPT__)) - -/** @brief Enables the CEC device - * @param __HANDLE__ specifies the CEC Handle. - * @retval none - */ -#define __HAL_CEC_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= CEC_CR_CECEN) - -/** @brief Disables the CEC device - * @param __HANDLE__ specifies the CEC Handle. - * @retval none - */ -#define __HAL_CEC_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR &= ~CEC_CR_CECEN) - -/** @brief Set Transmission Start flag - * @param __HANDLE__ specifies the CEC Handle. - * @retval none - */ -#define __HAL_CEC_FIRST_BYTE_TX_SET(__HANDLE__) ((__HANDLE__)->Instance->CR |= CEC_CR_TXSOM) - -/** @brief Set Transmission End flag - * @param __HANDLE__ specifies the CEC Handle. - * @retval none - * If the CEC message consists of only one byte, TXEOM must be set before of TXSOM. - */ -#define __HAL_CEC_LAST_BYTE_TX_SET(__HANDLE__) ((__HANDLE__)->Instance->CR |= CEC_CR_TXEOM) - -/** @brief Get Transmission Start flag - * @param __HANDLE__ specifies the CEC Handle. - * @retval FlagStatus - */ -#define __HAL_CEC_GET_TRANSMISSION_START_FLAG(__HANDLE__) ((__HANDLE__)->Instance->CR & CEC_CR_TXSOM) - -/** @brief Get Transmission End flag - * @param __HANDLE__ specifies the CEC Handle. - * @retval FlagStatus - */ -#define __HAL_CEC_GET_TRANSMISSION_END_FLAG(__HANDLE__) ((__HANDLE__)->Instance->CR & CEC_CR_TXEOM) - -/** @brief Clear OAR register - * @param __HANDLE__ specifies the CEC Handle. - * @retval none - */ -#define __HAL_CEC_CLEAR_OAR(__HANDLE__) CLEAR_BIT((__HANDLE__)->Instance->CFGR, CEC_CFGR_OAR) - -/** @brief Set OAR register (without resetting previously set address in case of multi-address mode) - * To reset OAR, __HAL_CEC_CLEAR_OAR() needs to be called beforehand - * @param __HANDLE__ specifies the CEC Handle. - * @param __ADDRESS__ Own Address value (CEC logical address is identified by bit position) - * @retval none - */ -#define __HAL_CEC_SET_OAR(__HANDLE__,__ADDRESS__) SET_BIT((__HANDLE__)->Instance->CFGR, (__ADDRESS__)<< CEC_CFGR_OAR_LSB_POS) - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup CEC_Exported_Functions - * @{ - */ - -/** @addtogroup CEC_Exported_Functions_Group1 - * @{ - */ -/* Initialization and de-initialization functions ****************************/ -HAL_StatusTypeDef HAL_CEC_Init(CEC_HandleTypeDef *hcec); -HAL_StatusTypeDef HAL_CEC_DeInit(CEC_HandleTypeDef *hcec); -HAL_StatusTypeDef HAL_CEC_SetDeviceAddress(CEC_HandleTypeDef *hcec, uint16_t CEC_OwnAddress); -void HAL_CEC_MspInit(CEC_HandleTypeDef *hcec); -void HAL_CEC_MspDeInit(CEC_HandleTypeDef *hcec); - -#if (USE_HAL_CEC_REGISTER_CALLBACKS == 1) -HAL_StatusTypeDef HAL_CEC_RegisterCallback(CEC_HandleTypeDef *hcec, HAL_CEC_CallbackIDTypeDef CallbackID, - pCEC_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_CEC_UnRegisterCallback(CEC_HandleTypeDef *hcec, HAL_CEC_CallbackIDTypeDef CallbackID); - -HAL_StatusTypeDef HAL_CEC_RegisterRxCpltCallback(CEC_HandleTypeDef *hcec, pCEC_RxCallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_CEC_UnRegisterRxCpltCallback(CEC_HandleTypeDef *hcec); -#endif /* USE_HAL_CEC_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @addtogroup CEC_Exported_Functions_Group2 - * @{ - */ -/* I/O operation functions ***************************************************/ -HAL_StatusTypeDef HAL_CEC_Transmit_IT(CEC_HandleTypeDef *hcec, uint8_t InitiatorAddress, uint8_t DestinationAddress, - uint8_t *pData, uint32_t Size); -uint32_t HAL_CEC_GetLastReceivedFrameSize(CEC_HandleTypeDef *hcec); -void HAL_CEC_ChangeRxBuffer(CEC_HandleTypeDef *hcec, uint8_t *Rxbuffer); -void HAL_CEC_IRQHandler(CEC_HandleTypeDef *hcec); -void HAL_CEC_TxCpltCallback(CEC_HandleTypeDef *hcec); -void HAL_CEC_RxCpltCallback(CEC_HandleTypeDef *hcec, uint32_t RxFrameSize); -void HAL_CEC_ErrorCallback(CEC_HandleTypeDef *hcec); -/** - * @} - */ - -/** @addtogroup CEC_Exported_Functions_Group3 - * @{ - */ -/* Peripheral State functions ************************************************/ -HAL_CEC_StateTypeDef HAL_CEC_GetState(CEC_HandleTypeDef *hcec); -uint32_t HAL_CEC_GetError(CEC_HandleTypeDef *hcec); -/** - * @} - */ - -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/** @defgroup CEC_Private_Types CEC Private Types - * @{ - */ - -/** - * @} - */ - -/* Private variables ---------------------------------------------------------*/ -/** @defgroup CEC_Private_Variables CEC Private Variables - * @{ - */ - -/** - * @} - */ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup CEC_Private_Constants CEC Private Constants - * @{ - */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup CEC_Private_Macros CEC Private Macros - * @{ - */ - -#define IS_CEC_SIGNALFREETIME(__SFT__) ((__SFT__) <= CEC_CFGR_SFT) - -#define IS_CEC_TOLERANCE(__RXTOL__) (((__RXTOL__) == CEC_STANDARD_TOLERANCE) || \ - ((__RXTOL__) == CEC_EXTENDED_TOLERANCE)) - -#define IS_CEC_BRERXSTOP(__BRERXSTOP__) (((__BRERXSTOP__) == CEC_NO_RX_STOP_ON_BRE) || \ - ((__BRERXSTOP__) == CEC_RX_STOP_ON_BRE)) - -#define IS_CEC_BREERRORBITGEN(__ERRORBITGEN__) (((__ERRORBITGEN__) == CEC_BRE_ERRORBIT_NO_GENERATION) || \ - ((__ERRORBITGEN__) == CEC_BRE_ERRORBIT_GENERATION)) - -#define IS_CEC_LBPEERRORBITGEN(__ERRORBITGEN__) (((__ERRORBITGEN__) == CEC_LBPE_ERRORBIT_NO_GENERATION) || \ - ((__ERRORBITGEN__) == CEC_LBPE_ERRORBIT_GENERATION)) - -#define IS_CEC_BROADCASTERROR_NO_ERRORBIT_GENERATION(__ERRORBITGEN__) (((__ERRORBITGEN__) == CEC_BROADCASTERROR_ERRORBIT_GENERATION) || \ - ((__ERRORBITGEN__) == CEC_BROADCASTERROR_NO_ERRORBIT_GENERATION)) - -#define IS_CEC_SFTOP(__SFTOP__) (((__SFTOP__) == CEC_SFT_START_ON_TXSOM) || \ - ((__SFTOP__) == CEC_SFT_START_ON_TX_RX_END)) - -#define IS_CEC_LISTENING_MODE(__MODE__) (((__MODE__) == CEC_REDUCED_LISTENING_MODE) || \ - ((__MODE__) == CEC_FULL_LISTENING_MODE)) - -/** @brief Check CEC message size. - * The message size is the payload size: without counting the header, - * it varies from 0 byte (ping operation, one header only, no payload) to - * 15 bytes (1 opcode and up to 14 operands following the header). - * @param __SIZE__ CEC message size. - * @retval Test result (TRUE or FALSE). - */ -#define IS_CEC_MSGSIZE(__SIZE__) ((__SIZE__) <= 0x10U) - -/** @brief Check CEC device Own Address Register (OAR) setting. - * OAR address is written in a 15-bit field within CEC_CFGR register. - * @param __ADDRESS__ CEC own address. - * @retval Test result (TRUE or FALSE). - */ -#define IS_CEC_OWN_ADDRESS(__ADDRESS__) ((__ADDRESS__) <= 0x7FFFU) - -/** @brief Check CEC initiator or destination logical address setting. - * Initiator and destination addresses are coded over 4 bits. - * @param __ADDRESS__ CEC initiator or logical address. - * @retval Test result (TRUE or FALSE). - */ -#define IS_CEC_ADDRESS(__ADDRESS__) ((__ADDRESS__) <= 0xFU) -/** - * @} - */ -/* Private functions ---------------------------------------------------------*/ -/** @defgroup CEC_Private_Functions CEC Private Functions - * @{ - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* CEC */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xxHAL_CEC_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_conf_template.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_conf_template.h deleted file mode 100644 index afa2f56..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_conf_template.h +++ /dev/null @@ -1,501 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_conf_template.h - * @author MCD Application Team - * @brief HAL configuration template file. - * This file should be copied to the application folder and renamed - * to stm32f4xx_hal_conf.h. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_CONF_H -#define __STM32F4xx_HAL_CONF_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ - -/* ########################## Module Selection ############################## */ -/** - * @brief This is the list of modules to be used in the HAL driver - */ -#define HAL_MODULE_ENABLED -#define HAL_ADC_MODULE_ENABLED -#define HAL_CAN_MODULE_ENABLED -/* #define HAL_CAN_LEGACY_MODULE_ENABLED */ -#define HAL_CRC_MODULE_ENABLED -#define HAL_CEC_MODULE_ENABLED -#define HAL_CRYP_MODULE_ENABLED -#define HAL_DAC_MODULE_ENABLED -#define HAL_DCMI_MODULE_ENABLED -#define HAL_DMA_MODULE_ENABLED -#define HAL_DMA2D_MODULE_ENABLED -#define HAL_ETH_MODULE_ENABLED -#define HAL_FLASH_MODULE_ENABLED -#define HAL_NAND_MODULE_ENABLED -#define HAL_NOR_MODULE_ENABLED -#define HAL_PCCARD_MODULE_ENABLED -#define HAL_SRAM_MODULE_ENABLED -#define HAL_SDRAM_MODULE_ENABLED -#define HAL_HASH_MODULE_ENABLED -#define HAL_GPIO_MODULE_ENABLED -#define HAL_EXTI_MODULE_ENABLED -#define HAL_I2C_MODULE_ENABLED -#define HAL_SMBUS_MODULE_ENABLED -#define HAL_I2S_MODULE_ENABLED -#define HAL_IWDG_MODULE_ENABLED -#define HAL_LTDC_MODULE_ENABLED -#define HAL_DSI_MODULE_ENABLED -#define HAL_PWR_MODULE_ENABLED -#define HAL_QSPI_MODULE_ENABLED -#define HAL_RCC_MODULE_ENABLED -#define HAL_RNG_MODULE_ENABLED -#define HAL_RTC_MODULE_ENABLED -#define HAL_SAI_MODULE_ENABLED -#define HAL_SD_MODULE_ENABLED -#define HAL_SPI_MODULE_ENABLED -#define HAL_TIM_MODULE_ENABLED -#define HAL_UART_MODULE_ENABLED -#define HAL_USART_MODULE_ENABLED -#define HAL_IRDA_MODULE_ENABLED -#define HAL_SMARTCARD_MODULE_ENABLED -#define HAL_WWDG_MODULE_ENABLED -#define HAL_CORTEX_MODULE_ENABLED -#define HAL_PCD_MODULE_ENABLED -#define HAL_HCD_MODULE_ENABLED -#define HAL_FMPI2C_MODULE_ENABLED -#define HAL_FMPSMBUS_MODULE_ENABLED -#define HAL_SPDIFRX_MODULE_ENABLED -#define HAL_DFSDM_MODULE_ENABLED -#define HAL_LPTIM_MODULE_ENABLED -#define HAL_MMC_MODULE_ENABLED - -/* ########################## HSE/HSI Values adaptation ##################### */ -/** - * @brief Adjust the value of External High Speed oscillator (HSE) used in your application. - * This value is used by the RCC HAL module to compute the system frequency - * (when HSE is used as system clock source, directly or through the PLL). - */ -#if !defined (HSE_VALUE) - #define HSE_VALUE 25000000U /*!< Value of the External oscillator in Hz */ -#endif /* HSE_VALUE */ - -#if !defined (HSE_STARTUP_TIMEOUT) - #define HSE_STARTUP_TIMEOUT 100U /*!< Time out for HSE start up, in ms */ -#endif /* HSE_STARTUP_TIMEOUT */ - -/** - * @brief Internal High Speed oscillator (HSI) value. - * This value is used by the RCC HAL module to compute the system frequency - * (when HSI is used as system clock source, directly or through the PLL). - */ -#if !defined (HSI_VALUE) - #define HSI_VALUE 16000000U /*!< Value of the Internal oscillator in Hz */ -#endif /* HSI_VALUE */ - -/** - * @brief Internal Low Speed oscillator (LSI) value. - */ -#if !defined (LSI_VALUE) - #define LSI_VALUE 32000U /*!< LSI Typical Value in Hz */ -#endif /* LSI_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz - The real value may vary depending on the variations - in voltage and temperature. */ -/** - * @brief External Low Speed oscillator (LSE) value. - */ -#if !defined (LSE_VALUE) - #define LSE_VALUE 32768U /*!< Value of the External Low Speed oscillator in Hz */ -#endif /* LSE_VALUE */ - -#if !defined (LSE_STARTUP_TIMEOUT) - #define LSE_STARTUP_TIMEOUT 5000U /*!< Time out for LSE start up, in ms */ -#endif /* LSE_STARTUP_TIMEOUT */ - -/** - * @brief External clock source for I2S peripheral - * This value is used by the I2S HAL module to compute the I2S clock source - * frequency, this source is inserted directly through I2S_CKIN pad. - */ -#if !defined (EXTERNAL_CLOCK_VALUE) - #define EXTERNAL_CLOCK_VALUE 12288000U /*!< Value of the External oscillator in Hz*/ -#endif /* EXTERNAL_CLOCK_VALUE */ - -/* Tip: To avoid modifying this file each time you need to use different HSE, - === you can define the HSE value in your toolchain compiler preprocessor. */ - -/* ########################### System Configuration ######################### */ -/** - * @brief This is the HAL system configuration section - */ -#define VDD_VALUE 3300U /*!< Value of VDD in mv */ -#define TICK_INT_PRIORITY 0x0FU /*!< tick interrupt priority */ -#define USE_RTOS 0U -#define PREFETCH_ENABLE 1U -#define INSTRUCTION_CACHE_ENABLE 1U -#define DATA_CACHE_ENABLE 1U - -#define USE_HAL_ADC_REGISTER_CALLBACKS 0U /* ADC register callback disabled */ -#define USE_HAL_CAN_REGISTER_CALLBACKS 0U /* CAN register callback disabled */ -#define USE_HAL_CEC_REGISTER_CALLBACKS 0U /* CEC register callback disabled */ -#define USE_HAL_CRYP_REGISTER_CALLBACKS 0U /* CRYP register callback disabled */ -#define USE_HAL_DAC_REGISTER_CALLBACKS 0U /* DAC register callback disabled */ -#define USE_HAL_DCMI_REGISTER_CALLBACKS 0U /* DCMI register callback disabled */ -#define USE_HAL_DFSDM_REGISTER_CALLBACKS 0U /* DFSDM register callback disabled */ -#define USE_HAL_DMA2D_REGISTER_CALLBACKS 0U /* DMA2D register callback disabled */ -#define USE_HAL_DSI_REGISTER_CALLBACKS 0U /* DSI register callback disabled */ -#define USE_HAL_ETH_REGISTER_CALLBACKS 0U /* ETH register callback disabled */ -#define USE_HAL_HASH_REGISTER_CALLBACKS 0U /* HASH register callback disabled */ -#define USE_HAL_HCD_REGISTER_CALLBACKS 0U /* HCD register callback disabled */ -#define USE_HAL_I2C_REGISTER_CALLBACKS 0U /* I2C register callback disabled */ -#define USE_HAL_FMPI2C_REGISTER_CALLBACKS 0U /* FMPI2C register callback disabled */ -#define USE_HAL_FMPSMBUS_REGISTER_CALLBACKS 0U /* FMPSMBUS register callback disabled */ -#define USE_HAL_I2S_REGISTER_CALLBACKS 0U /* I2S register callback disabled */ -#define USE_HAL_IRDA_REGISTER_CALLBACKS 0U /* IRDA register callback disabled */ -#define USE_HAL_LPTIM_REGISTER_CALLBACKS 0U /* LPTIM register callback disabled */ -#define USE_HAL_LTDC_REGISTER_CALLBACKS 0U /* LTDC register callback disabled */ -#define USE_HAL_MMC_REGISTER_CALLBACKS 0U /* MMC register callback disabled */ -#define USE_HAL_NAND_REGISTER_CALLBACKS 0U /* NAND register callback disabled */ -#define USE_HAL_NOR_REGISTER_CALLBACKS 0U /* NOR register callback disabled */ -#define USE_HAL_PCCARD_REGISTER_CALLBACKS 0U /* PCCARD register callback disabled */ -#define USE_HAL_PCD_REGISTER_CALLBACKS 0U /* PCD register callback disabled */ -#define USE_HAL_QSPI_REGISTER_CALLBACKS 0U /* QSPI register callback disabled */ -#define USE_HAL_RNG_REGISTER_CALLBACKS 0U /* RNG register callback disabled */ -#define USE_HAL_RTC_REGISTER_CALLBACKS 0U /* RTC register callback disabled */ -#define USE_HAL_SAI_REGISTER_CALLBACKS 0U /* SAI register callback disabled */ -#define USE_HAL_SD_REGISTER_CALLBACKS 0U /* SD register callback disabled */ -#define USE_HAL_SMARTCARD_REGISTER_CALLBACKS 0U /* SMARTCARD register callback disabled */ -#define USE_HAL_SDRAM_REGISTER_CALLBACKS 0U /* SDRAM register callback disabled */ -#define USE_HAL_SRAM_REGISTER_CALLBACKS 0U /* SRAM register callback disabled */ -#define USE_HAL_SPDIFRX_REGISTER_CALLBACKS 0U /* SPDIFRX register callback disabled */ -#define USE_HAL_SMBUS_REGISTER_CALLBACKS 0U /* SMBUS register callback disabled */ -#define USE_HAL_SPI_REGISTER_CALLBACKS 0U /* SPI register callback disabled */ -#define USE_HAL_TIM_REGISTER_CALLBACKS 0U /* TIM register callback disabled */ -#define USE_HAL_UART_REGISTER_CALLBACKS 0U /* UART register callback disabled */ -#define USE_HAL_USART_REGISTER_CALLBACKS 0U /* USART register callback disabled */ -#define USE_HAL_WWDG_REGISTER_CALLBACKS 0U /* WWDG register callback disabled */ - -/* ########################## Assert Selection ############################## */ -/** - * @brief Uncomment the line below to expanse the "assert_param" macro in the - * HAL drivers code - */ -/* #define USE_FULL_ASSERT 1U */ - -/* ################## Ethernet peripheral configuration ##################### */ - -/* Section 1 : Ethernet peripheral configuration */ - -/* MAC ADDRESS: MAC_ADDR0:MAC_ADDR1:MAC_ADDR2:MAC_ADDR3:MAC_ADDR4:MAC_ADDR5 */ -#define MAC_ADDR0 2U -#define MAC_ADDR1 0U -#define MAC_ADDR2 0U -#define MAC_ADDR3 0U -#define MAC_ADDR4 0U -#define MAC_ADDR5 0U - -/* Definition of the Ethernet driver buffers size and count */ -#define ETH_RX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for receive */ -#define ETH_TX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for transmit */ -#define ETH_RXBUFNB 4U /* 4 Rx buffers of size ETH_RX_BUF_SIZE */ -#define ETH_TXBUFNB 4U /* 4 Tx buffers of size ETH_TX_BUF_SIZE */ - -/* Section 2: PHY configuration section */ - -/* DP83848 PHY Address*/ -#define DP83848_PHY_ADDRESS 0x01U -/* PHY Reset delay these values are based on a 1 ms Systick interrupt*/ -#define PHY_RESET_DELAY 0x000000FFU -/* PHY Configuration delay */ -#define PHY_CONFIG_DELAY 0x00000FFFU - -#define PHY_READ_TO 0x0000FFFFU -#define PHY_WRITE_TO 0x0000FFFFU - -/* Section 3: Common PHY Registers */ - -#define PHY_BCR ((uint16_t)0x0000) /*!< Transceiver Basic Control Register */ -#define PHY_BSR ((uint16_t)0x0001) /*!< Transceiver Basic Status Register */ - -#define PHY_RESET ((uint16_t)0x8000) /*!< PHY Reset */ -#define PHY_LOOPBACK ((uint16_t)0x4000) /*!< Select loop-back mode */ -#define PHY_FULLDUPLEX_100M ((uint16_t)0x2100) /*!< Set the full-duplex mode at 100 Mb/s */ -#define PHY_HALFDUPLEX_100M ((uint16_t)0x2000) /*!< Set the half-duplex mode at 100 Mb/s */ -#define PHY_FULLDUPLEX_10M ((uint16_t)0x0100) /*!< Set the full-duplex mode at 10 Mb/s */ -#define PHY_HALFDUPLEX_10M ((uint16_t)0x0000) /*!< Set the half-duplex mode at 10 Mb/s */ -#define PHY_AUTONEGOTIATION ((uint16_t)0x1000) /*!< Enable auto-negotiation function */ -#define PHY_RESTART_AUTONEGOTIATION ((uint16_t)0x0200) /*!< Restart auto-negotiation function */ -#define PHY_POWERDOWN ((uint16_t)0x0800) /*!< Select the power down mode */ -#define PHY_ISOLATE ((uint16_t)0x0400) /*!< Isolate PHY from MII */ - -#define PHY_AUTONEGO_COMPLETE ((uint16_t)0x0020) /*!< Auto-Negotiation process completed */ -#define PHY_LINKED_STATUS ((uint16_t)0x0004) /*!< Valid link established */ -#define PHY_JABBER_DETECTION ((uint16_t)0x0002) /*!< Jabber condition detected */ - -/* Section 4: Extended PHY Registers */ - -#define PHY_SR ((uint16_t)0x0010) /*!< PHY status register Offset */ -#define PHY_MICR ((uint16_t)0x0011) /*!< MII Interrupt Control Register */ -#define PHY_MISR ((uint16_t)0x0012) /*!< MII Interrupt Status and Misc. Control Register */ - -#define PHY_LINK_STATUS ((uint16_t)0x0001) /*!< PHY Link mask */ -#define PHY_SPEED_STATUS ((uint16_t)0x0002) /*!< PHY Speed mask */ -#define PHY_DUPLEX_STATUS ((uint16_t)0x0004) /*!< PHY Duplex mask */ - -#define PHY_MICR_INT_EN ((uint16_t)0x0002) /*!< PHY Enable interrupts */ -#define PHY_MICR_INT_OE ((uint16_t)0x0001) /*!< PHY Enable output interrupt events */ - -#define PHY_MISR_LINK_INT_EN ((uint16_t)0x0020) /*!< Enable Interrupt on change of link status */ -#define PHY_LINK_INTERRUPT ((uint16_t)0x2000) /*!< PHY link status interrupt mask */ - -/* ################## SPI peripheral configuration ########################## */ - -/* CRC FEATURE: Use to activate CRC feature inside HAL SPI Driver -* Activated: CRC code is present inside driver -* Deactivated: CRC code cleaned from driver -*/ - -#define USE_SPI_CRC 1U - -/* Includes ------------------------------------------------------------------*/ -/** - * @brief Include module's header file - */ - -#ifdef HAL_RCC_MODULE_ENABLED - #include "stm32f4xx_hal_rcc.h" -#endif /* HAL_RCC_MODULE_ENABLED */ - -#ifdef HAL_GPIO_MODULE_ENABLED - #include "stm32f4xx_hal_gpio.h" -#endif /* HAL_GPIO_MODULE_ENABLED */ - -#ifdef HAL_EXTI_MODULE_ENABLED - #include "stm32f4xx_hal_exti.h" -#endif /* HAL_EXTI_MODULE_ENABLED */ - -#ifdef HAL_DMA_MODULE_ENABLED - #include "stm32f4xx_hal_dma.h" -#endif /* HAL_DMA_MODULE_ENABLED */ - -#ifdef HAL_CORTEX_MODULE_ENABLED - #include "stm32f4xx_hal_cortex.h" -#endif /* HAL_CORTEX_MODULE_ENABLED */ - -#ifdef HAL_ADC_MODULE_ENABLED - #include "stm32f4xx_hal_adc.h" -#endif /* HAL_ADC_MODULE_ENABLED */ - -#ifdef HAL_CAN_MODULE_ENABLED - #include "stm32f4xx_hal_can.h" -#endif /* HAL_CAN_MODULE_ENABLED */ - -#ifdef HAL_CAN_LEGACY_MODULE_ENABLED - #include "stm32f4xx_hal_can_legacy.h" -#endif /* HAL_CAN_LEGACY_MODULE_ENABLED */ - -#ifdef HAL_CRC_MODULE_ENABLED - #include "stm32f4xx_hal_crc.h" -#endif /* HAL_CRC_MODULE_ENABLED */ - -#ifdef HAL_CRYP_MODULE_ENABLED - #include "stm32f4xx_hal_cryp.h" -#endif /* HAL_CRYP_MODULE_ENABLED */ - -#ifdef HAL_DMA2D_MODULE_ENABLED - #include "stm32f4xx_hal_dma2d.h" -#endif /* HAL_DMA2D_MODULE_ENABLED */ - -#ifdef HAL_DAC_MODULE_ENABLED - #include "stm32f4xx_hal_dac.h" -#endif /* HAL_DAC_MODULE_ENABLED */ - -#ifdef HAL_DCMI_MODULE_ENABLED - #include "stm32f4xx_hal_dcmi.h" -#endif /* HAL_DCMI_MODULE_ENABLED */ - -#ifdef HAL_ETH_MODULE_ENABLED - #include "stm32f4xx_hal_eth.h" -#endif /* HAL_ETH_MODULE_ENABLED */ - -#ifdef HAL_FLASH_MODULE_ENABLED - #include "stm32f4xx_hal_flash.h" -#endif /* HAL_FLASH_MODULE_ENABLED */ - -#ifdef HAL_SRAM_MODULE_ENABLED - #include "stm32f4xx_hal_sram.h" -#endif /* HAL_SRAM_MODULE_ENABLED */ - -#ifdef HAL_NOR_MODULE_ENABLED - #include "stm32f4xx_hal_nor.h" -#endif /* HAL_NOR_MODULE_ENABLED */ - -#ifdef HAL_NAND_MODULE_ENABLED - #include "stm32f4xx_hal_nand.h" -#endif /* HAL_NAND_MODULE_ENABLED */ - -#ifdef HAL_PCCARD_MODULE_ENABLED - #include "stm32f4xx_hal_pccard.h" -#endif /* HAL_PCCARD_MODULE_ENABLED */ - -#ifdef HAL_SDRAM_MODULE_ENABLED - #include "stm32f4xx_hal_sdram.h" -#endif /* HAL_SDRAM_MODULE_ENABLED */ - -#ifdef HAL_HASH_MODULE_ENABLED - #include "stm32f4xx_hal_hash.h" -#endif /* HAL_HASH_MODULE_ENABLED */ - -#ifdef HAL_I2C_MODULE_ENABLED - #include "stm32f4xx_hal_i2c.h" -#endif /* HAL_I2C_MODULE_ENABLED */ - -#ifdef HAL_SMBUS_MODULE_ENABLED - #include "stm32f4xx_hal_smbus.h" -#endif /* HAL_SMBUS_MODULE_ENABLED */ - -#ifdef HAL_I2S_MODULE_ENABLED - #include "stm32f4xx_hal_i2s.h" -#endif /* HAL_I2S_MODULE_ENABLED */ - -#ifdef HAL_IWDG_MODULE_ENABLED - #include "stm32f4xx_hal_iwdg.h" -#endif /* HAL_IWDG_MODULE_ENABLED */ - -#ifdef HAL_LTDC_MODULE_ENABLED - #include "stm32f4xx_hal_ltdc.h" -#endif /* HAL_LTDC_MODULE_ENABLED */ - -#ifdef HAL_PWR_MODULE_ENABLED - #include "stm32f4xx_hal_pwr.h" -#endif /* HAL_PWR_MODULE_ENABLED */ - -#ifdef HAL_RNG_MODULE_ENABLED - #include "stm32f4xx_hal_rng.h" -#endif /* HAL_RNG_MODULE_ENABLED */ - -#ifdef HAL_RTC_MODULE_ENABLED - #include "stm32f4xx_hal_rtc.h" -#endif /* HAL_RTC_MODULE_ENABLED */ - -#ifdef HAL_SAI_MODULE_ENABLED - #include "stm32f4xx_hal_sai.h" -#endif /* HAL_SAI_MODULE_ENABLED */ - -#ifdef HAL_SD_MODULE_ENABLED - #include "stm32f4xx_hal_sd.h" -#endif /* HAL_SD_MODULE_ENABLED */ - -#ifdef HAL_SPI_MODULE_ENABLED - #include "stm32f4xx_hal_spi.h" -#endif /* HAL_SPI_MODULE_ENABLED */ - -#ifdef HAL_TIM_MODULE_ENABLED - #include "stm32f4xx_hal_tim.h" -#endif /* HAL_TIM_MODULE_ENABLED */ - -#ifdef HAL_UART_MODULE_ENABLED - #include "stm32f4xx_hal_uart.h" -#endif /* HAL_UART_MODULE_ENABLED */ - -#ifdef HAL_USART_MODULE_ENABLED - #include "stm32f4xx_hal_usart.h" -#endif /* HAL_USART_MODULE_ENABLED */ - -#ifdef HAL_IRDA_MODULE_ENABLED - #include "stm32f4xx_hal_irda.h" -#endif /* HAL_IRDA_MODULE_ENABLED */ - -#ifdef HAL_SMARTCARD_MODULE_ENABLED - #include "stm32f4xx_hal_smartcard.h" -#endif /* HAL_SMARTCARD_MODULE_ENABLED */ - -#ifdef HAL_WWDG_MODULE_ENABLED - #include "stm32f4xx_hal_wwdg.h" -#endif /* HAL_WWDG_MODULE_ENABLED */ - -#ifdef HAL_PCD_MODULE_ENABLED - #include "stm32f4xx_hal_pcd.h" -#endif /* HAL_PCD_MODULE_ENABLED */ - -#ifdef HAL_HCD_MODULE_ENABLED - #include "stm32f4xx_hal_hcd.h" -#endif /* HAL_HCD_MODULE_ENABLED */ - -#ifdef HAL_DSI_MODULE_ENABLED - #include "stm32f4xx_hal_dsi.h" -#endif /* HAL_DSI_MODULE_ENABLED */ - -#ifdef HAL_QSPI_MODULE_ENABLED - #include "stm32f4xx_hal_qspi.h" -#endif /* HAL_QSPI_MODULE_ENABLED */ - -#ifdef HAL_CEC_MODULE_ENABLED - #include "stm32f4xx_hal_cec.h" -#endif /* HAL_CEC_MODULE_ENABLED */ - -#ifdef HAL_FMPI2C_MODULE_ENABLED - #include "stm32f4xx_hal_fmpi2c.h" -#endif /* HAL_FMPI2C_MODULE_ENABLED */ - -#ifdef HAL_FMPSMBUS_MODULE_ENABLED - #include "stm32f4xx_hal_fmpsmbus.h" -#endif /* HAL_FMPSMBUS_MODULE_ENABLED */ - -#ifdef HAL_SPDIFRX_MODULE_ENABLED - #include "stm32f4xx_hal_spdifrx.h" -#endif /* HAL_SPDIFRX_MODULE_ENABLED */ - -#ifdef HAL_DFSDM_MODULE_ENABLED - #include "stm32f4xx_hal_dfsdm.h" -#endif /* HAL_DFSDM_MODULE_ENABLED */ - -#ifdef HAL_LPTIM_MODULE_ENABLED - #include "stm32f4xx_hal_lptim.h" -#endif /* HAL_LPTIM_MODULE_ENABLED */ - -#ifdef HAL_MMC_MODULE_ENABLED - #include "stm32f4xx_hal_mmc.h" -#endif /* HAL_MMC_MODULE_ENABLED */ - -/* Exported macro ------------------------------------------------------------*/ -#ifdef USE_FULL_ASSERT -/** - * @brief The assert_param macro is used for function's parameters check. - * @param expr If expr is false, it calls assert_failed function - * which reports the name of the source file and the source - * line number of the call that failed. - * If expr is true, it returns no value. - * @retval None - */ - #define assert_param(expr) ((expr) ? (void)0U : assert_failed((uint8_t *)__FILE__, __LINE__)) -/* Exported functions ------------------------------------------------------- */ - void assert_failed(uint8_t* file, uint32_t line); -#else - #define assert_param(expr) ((void)0U) -#endif /* USE_FULL_ASSERT */ - - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_CONF_H */ - - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_cortex.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_cortex.h deleted file mode 100644 index 95218cf..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_cortex.h +++ /dev/null @@ -1,410 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_cortex.h - * @author MCD Application Team - * @brief Header file of CORTEX HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_CORTEX_H -#define __STM32F4xx_HAL_CORTEX_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup CORTEX - * @{ - */ -/* Exported types ------------------------------------------------------------*/ -/** @defgroup CORTEX_Exported_Types Cortex Exported Types - * @{ - */ - -#if (__MPU_PRESENT == 1U) -/** @defgroup CORTEX_MPU_Region_Initialization_Structure_definition MPU Region Initialization Structure Definition - * @brief MPU Region initialization structure - * @{ - */ -typedef struct -{ - uint8_t Enable; /*!< Specifies the status of the region. - This parameter can be a value of @ref CORTEX_MPU_Region_Enable */ - uint8_t Number; /*!< Specifies the number of the region to protect. - This parameter can be a value of @ref CORTEX_MPU_Region_Number */ - uint32_t BaseAddress; /*!< Specifies the base address of the region to protect. */ - uint8_t Size; /*!< Specifies the size of the region to protect. - This parameter can be a value of @ref CORTEX_MPU_Region_Size */ - uint8_t SubRegionDisable; /*!< Specifies the number of the subregion protection to disable. - This parameter must be a number between Min_Data = 0x00 and Max_Data = 0xFF */ - uint8_t TypeExtField; /*!< Specifies the TEX field level. - This parameter can be a value of @ref CORTEX_MPU_TEX_Levels */ - uint8_t AccessPermission; /*!< Specifies the region access permission type. - This parameter can be a value of @ref CORTEX_MPU_Region_Permission_Attributes */ - uint8_t DisableExec; /*!< Specifies the instruction access status. - This parameter can be a value of @ref CORTEX_MPU_Instruction_Access */ - uint8_t IsShareable; /*!< Specifies the shareability status of the protected region. - This parameter can be a value of @ref CORTEX_MPU_Access_Shareable */ - uint8_t IsCacheable; /*!< Specifies the cacheable status of the region protected. - This parameter can be a value of @ref CORTEX_MPU_Access_Cacheable */ - uint8_t IsBufferable; /*!< Specifies the bufferable status of the protected region. - This parameter can be a value of @ref CORTEX_MPU_Access_Bufferable */ -}MPU_Region_InitTypeDef; -/** - * @} - */ -#endif /* __MPU_PRESENT */ - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ - -/** @defgroup CORTEX_Exported_Constants CORTEX Exported Constants - * @{ - */ - -/** @defgroup CORTEX_Preemption_Priority_Group CORTEX Preemption Priority Group - * @{ - */ -#define NVIC_PRIORITYGROUP_0 0x00000007U /*!< 0 bits for pre-emption priority - 4 bits for subpriority */ -#define NVIC_PRIORITYGROUP_1 0x00000006U /*!< 1 bits for pre-emption priority - 3 bits for subpriority */ -#define NVIC_PRIORITYGROUP_2 0x00000005U /*!< 2 bits for pre-emption priority - 2 bits for subpriority */ -#define NVIC_PRIORITYGROUP_3 0x00000004U /*!< 3 bits for pre-emption priority - 1 bits for subpriority */ -#define NVIC_PRIORITYGROUP_4 0x00000003U /*!< 4 bits for pre-emption priority - 0 bits for subpriority */ -/** - * @} - */ - -/** @defgroup CORTEX_SysTick_clock_source CORTEX _SysTick clock source - * @{ - */ -#define SYSTICK_CLKSOURCE_HCLK_DIV8 0x00000000U -#define SYSTICK_CLKSOURCE_HCLK 0x00000004U - -/** - * @} - */ - -#if (__MPU_PRESENT == 1) -/** @defgroup CORTEX_MPU_HFNMI_PRIVDEF_Control MPU HFNMI and PRIVILEGED Access control - * @{ - */ -#define MPU_HFNMI_PRIVDEF_NONE 0x00000000U -#define MPU_HARDFAULT_NMI MPU_CTRL_HFNMIENA_Msk -#define MPU_PRIVILEGED_DEFAULT MPU_CTRL_PRIVDEFENA_Msk -#define MPU_HFNMI_PRIVDEF (MPU_CTRL_HFNMIENA_Msk | MPU_CTRL_PRIVDEFENA_Msk) - -/** - * @} - */ - -/** @defgroup CORTEX_MPU_Region_Enable CORTEX MPU Region Enable - * @{ - */ -#define MPU_REGION_ENABLE ((uint8_t)0x01) -#define MPU_REGION_DISABLE ((uint8_t)0x00) -/** - * @} - */ - -/** @defgroup CORTEX_MPU_Instruction_Access CORTEX MPU Instruction Access - * @{ - */ -#define MPU_INSTRUCTION_ACCESS_ENABLE ((uint8_t)0x00) -#define MPU_INSTRUCTION_ACCESS_DISABLE ((uint8_t)0x01) -/** - * @} - */ - -/** @defgroup CORTEX_MPU_Access_Shareable CORTEX MPU Instruction Access Shareable - * @{ - */ -#define MPU_ACCESS_SHAREABLE ((uint8_t)0x01) -#define MPU_ACCESS_NOT_SHAREABLE ((uint8_t)0x00) -/** - * @} - */ - -/** @defgroup CORTEX_MPU_Access_Cacheable CORTEX MPU Instruction Access Cacheable - * @{ - */ -#define MPU_ACCESS_CACHEABLE ((uint8_t)0x01) -#define MPU_ACCESS_NOT_CACHEABLE ((uint8_t)0x00) -/** - * @} - */ - -/** @defgroup CORTEX_MPU_Access_Bufferable CORTEX MPU Instruction Access Bufferable - * @{ - */ -#define MPU_ACCESS_BUFFERABLE ((uint8_t)0x01) -#define MPU_ACCESS_NOT_BUFFERABLE ((uint8_t)0x00) -/** - * @} - */ - -/** @defgroup CORTEX_MPU_TEX_Levels MPU TEX Levels - * @{ - */ -#define MPU_TEX_LEVEL0 ((uint8_t)0x00) -#define MPU_TEX_LEVEL1 ((uint8_t)0x01) -#define MPU_TEX_LEVEL2 ((uint8_t)0x02) -/** - * @} - */ - -/** @defgroup CORTEX_MPU_Region_Size CORTEX MPU Region Size - * @{ - */ -#define MPU_REGION_SIZE_32B ((uint8_t)0x04) -#define MPU_REGION_SIZE_64B ((uint8_t)0x05) -#define MPU_REGION_SIZE_128B ((uint8_t)0x06) -#define MPU_REGION_SIZE_256B ((uint8_t)0x07) -#define MPU_REGION_SIZE_512B ((uint8_t)0x08) -#define MPU_REGION_SIZE_1KB ((uint8_t)0x09) -#define MPU_REGION_SIZE_2KB ((uint8_t)0x0A) -#define MPU_REGION_SIZE_4KB ((uint8_t)0x0B) -#define MPU_REGION_SIZE_8KB ((uint8_t)0x0C) -#define MPU_REGION_SIZE_16KB ((uint8_t)0x0D) -#define MPU_REGION_SIZE_32KB ((uint8_t)0x0E) -#define MPU_REGION_SIZE_64KB ((uint8_t)0x0F) -#define MPU_REGION_SIZE_128KB ((uint8_t)0x10) -#define MPU_REGION_SIZE_256KB ((uint8_t)0x11) -#define MPU_REGION_SIZE_512KB ((uint8_t)0x12) -#define MPU_REGION_SIZE_1MB ((uint8_t)0x13) -#define MPU_REGION_SIZE_2MB ((uint8_t)0x14) -#define MPU_REGION_SIZE_4MB ((uint8_t)0x15) -#define MPU_REGION_SIZE_8MB ((uint8_t)0x16) -#define MPU_REGION_SIZE_16MB ((uint8_t)0x17) -#define MPU_REGION_SIZE_32MB ((uint8_t)0x18) -#define MPU_REGION_SIZE_64MB ((uint8_t)0x19) -#define MPU_REGION_SIZE_128MB ((uint8_t)0x1A) -#define MPU_REGION_SIZE_256MB ((uint8_t)0x1B) -#define MPU_REGION_SIZE_512MB ((uint8_t)0x1C) -#define MPU_REGION_SIZE_1GB ((uint8_t)0x1D) -#define MPU_REGION_SIZE_2GB ((uint8_t)0x1E) -#define MPU_REGION_SIZE_4GB ((uint8_t)0x1F) -/** - * @} - */ - -/** @defgroup CORTEX_MPU_Region_Permission_Attributes CORTEX MPU Region Permission Attributes - * @{ - */ -#define MPU_REGION_NO_ACCESS ((uint8_t)0x00) -#define MPU_REGION_PRIV_RW ((uint8_t)0x01) -#define MPU_REGION_PRIV_RW_URO ((uint8_t)0x02) -#define MPU_REGION_FULL_ACCESS ((uint8_t)0x03) -#define MPU_REGION_PRIV_RO ((uint8_t)0x05) -#define MPU_REGION_PRIV_RO_URO ((uint8_t)0x06) -/** - * @} - */ - -/** @defgroup CORTEX_MPU_Region_Number CORTEX MPU Region Number - * @{ - */ -#define MPU_REGION_NUMBER0 ((uint8_t)0x00) -#define MPU_REGION_NUMBER1 ((uint8_t)0x01) -#define MPU_REGION_NUMBER2 ((uint8_t)0x02) -#define MPU_REGION_NUMBER3 ((uint8_t)0x03) -#define MPU_REGION_NUMBER4 ((uint8_t)0x04) -#define MPU_REGION_NUMBER5 ((uint8_t)0x05) -#define MPU_REGION_NUMBER6 ((uint8_t)0x06) -#define MPU_REGION_NUMBER7 ((uint8_t)0x07) -/** - * @} - */ -#endif /* __MPU_PRESENT */ - -/** - * @} - */ - - -/* Exported Macros -----------------------------------------------------------*/ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup CORTEX_Exported_Functions - * @{ - */ - -/** @addtogroup CORTEX_Exported_Functions_Group1 - * @{ - */ -/* Initialization and de-initialization functions *****************************/ -void HAL_NVIC_SetPriorityGrouping(uint32_t PriorityGroup); -void HAL_NVIC_SetPriority(IRQn_Type IRQn, uint32_t PreemptPriority, uint32_t SubPriority); -void HAL_NVIC_EnableIRQ(IRQn_Type IRQn); -void HAL_NVIC_DisableIRQ(IRQn_Type IRQn); -void HAL_NVIC_SystemReset(void); -uint32_t HAL_SYSTICK_Config(uint32_t TicksNumb); -/** - * @} - */ - -/** @addtogroup CORTEX_Exported_Functions_Group2 - * @{ - */ -/* Peripheral Control functions ***********************************************/ -uint32_t HAL_NVIC_GetPriorityGrouping(void); -void HAL_NVIC_GetPriority(IRQn_Type IRQn, uint32_t PriorityGroup, uint32_t* pPreemptPriority, uint32_t* pSubPriority); -uint32_t HAL_NVIC_GetPendingIRQ(IRQn_Type IRQn); -void HAL_NVIC_SetPendingIRQ(IRQn_Type IRQn); -void HAL_NVIC_ClearPendingIRQ(IRQn_Type IRQn); -uint32_t HAL_NVIC_GetActive(IRQn_Type IRQn); -void HAL_SYSTICK_CLKSourceConfig(uint32_t CLKSource); -void HAL_SYSTICK_IRQHandler(void); -void HAL_SYSTICK_Callback(void); - -#if (__MPU_PRESENT == 1U) -void HAL_MPU_Enable(uint32_t MPU_Control); -void HAL_MPU_Disable(void); -void HAL_MPU_ConfigRegion(MPU_Region_InitTypeDef *MPU_Init); -#endif /* __MPU_PRESENT */ -/** - * @} - */ - -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/** @defgroup CORTEX_Private_Macros CORTEX Private Macros - * @{ - */ -#define IS_NVIC_PRIORITY_GROUP(GROUP) (((GROUP) == NVIC_PRIORITYGROUP_0) || \ - ((GROUP) == NVIC_PRIORITYGROUP_1) || \ - ((GROUP) == NVIC_PRIORITYGROUP_2) || \ - ((GROUP) == NVIC_PRIORITYGROUP_3) || \ - ((GROUP) == NVIC_PRIORITYGROUP_4)) - -#define IS_NVIC_PREEMPTION_PRIORITY(PRIORITY) ((PRIORITY) < 0x10U) - -#define IS_NVIC_SUB_PRIORITY(PRIORITY) ((PRIORITY) < 0x10U) - -#define IS_NVIC_DEVICE_IRQ(IRQ) ((IRQ) >= (IRQn_Type)0x00U) - -#define IS_SYSTICK_CLK_SOURCE(SOURCE) (((SOURCE) == SYSTICK_CLKSOURCE_HCLK) || \ - ((SOURCE) == SYSTICK_CLKSOURCE_HCLK_DIV8)) - -#if (__MPU_PRESENT == 1U) -#define IS_MPU_REGION_ENABLE(STATE) (((STATE) == MPU_REGION_ENABLE) || \ - ((STATE) == MPU_REGION_DISABLE)) - -#define IS_MPU_INSTRUCTION_ACCESS(STATE) (((STATE) == MPU_INSTRUCTION_ACCESS_ENABLE) || \ - ((STATE) == MPU_INSTRUCTION_ACCESS_DISABLE)) - -#define IS_MPU_ACCESS_SHAREABLE(STATE) (((STATE) == MPU_ACCESS_SHAREABLE) || \ - ((STATE) == MPU_ACCESS_NOT_SHAREABLE)) - -#define IS_MPU_ACCESS_CACHEABLE(STATE) (((STATE) == MPU_ACCESS_CACHEABLE) || \ - ((STATE) == MPU_ACCESS_NOT_CACHEABLE)) - -#define IS_MPU_ACCESS_BUFFERABLE(STATE) (((STATE) == MPU_ACCESS_BUFFERABLE) || \ - ((STATE) == MPU_ACCESS_NOT_BUFFERABLE)) - -#define IS_MPU_TEX_LEVEL(TYPE) (((TYPE) == MPU_TEX_LEVEL0) || \ - ((TYPE) == MPU_TEX_LEVEL1) || \ - ((TYPE) == MPU_TEX_LEVEL2)) - -#define IS_MPU_REGION_PERMISSION_ATTRIBUTE(TYPE) (((TYPE) == MPU_REGION_NO_ACCESS) || \ - ((TYPE) == MPU_REGION_PRIV_RW) || \ - ((TYPE) == MPU_REGION_PRIV_RW_URO) || \ - ((TYPE) == MPU_REGION_FULL_ACCESS) || \ - ((TYPE) == MPU_REGION_PRIV_RO) || \ - ((TYPE) == MPU_REGION_PRIV_RO_URO)) - -#define IS_MPU_REGION_NUMBER(NUMBER) (((NUMBER) == MPU_REGION_NUMBER0) || \ - ((NUMBER) == MPU_REGION_NUMBER1) || \ - ((NUMBER) == MPU_REGION_NUMBER2) || \ - ((NUMBER) == MPU_REGION_NUMBER3) || \ - ((NUMBER) == MPU_REGION_NUMBER4) || \ - ((NUMBER) == MPU_REGION_NUMBER5) || \ - ((NUMBER) == MPU_REGION_NUMBER6) || \ - ((NUMBER) == MPU_REGION_NUMBER7)) - -#define IS_MPU_REGION_SIZE(SIZE) (((SIZE) == MPU_REGION_SIZE_32B) || \ - ((SIZE) == MPU_REGION_SIZE_64B) || \ - ((SIZE) == MPU_REGION_SIZE_128B) || \ - ((SIZE) == MPU_REGION_SIZE_256B) || \ - ((SIZE) == MPU_REGION_SIZE_512B) || \ - ((SIZE) == MPU_REGION_SIZE_1KB) || \ - ((SIZE) == MPU_REGION_SIZE_2KB) || \ - ((SIZE) == MPU_REGION_SIZE_4KB) || \ - ((SIZE) == MPU_REGION_SIZE_8KB) || \ - ((SIZE) == MPU_REGION_SIZE_16KB) || \ - ((SIZE) == MPU_REGION_SIZE_32KB) || \ - ((SIZE) == MPU_REGION_SIZE_64KB) || \ - ((SIZE) == MPU_REGION_SIZE_128KB) || \ - ((SIZE) == MPU_REGION_SIZE_256KB) || \ - ((SIZE) == MPU_REGION_SIZE_512KB) || \ - ((SIZE) == MPU_REGION_SIZE_1MB) || \ - ((SIZE) == MPU_REGION_SIZE_2MB) || \ - ((SIZE) == MPU_REGION_SIZE_4MB) || \ - ((SIZE) == MPU_REGION_SIZE_8MB) || \ - ((SIZE) == MPU_REGION_SIZE_16MB) || \ - ((SIZE) == MPU_REGION_SIZE_32MB) || \ - ((SIZE) == MPU_REGION_SIZE_64MB) || \ - ((SIZE) == MPU_REGION_SIZE_128MB) || \ - ((SIZE) == MPU_REGION_SIZE_256MB) || \ - ((SIZE) == MPU_REGION_SIZE_512MB) || \ - ((SIZE) == MPU_REGION_SIZE_1GB) || \ - ((SIZE) == MPU_REGION_SIZE_2GB) || \ - ((SIZE) == MPU_REGION_SIZE_4GB)) - -#define IS_MPU_SUB_REGION_DISABLE(SUBREGION) ((SUBREGION) < (uint16_t)0x00FF) -#endif /* __MPU_PRESENT */ - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_CORTEX_H */ - - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_crc.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_crc.h deleted file mode 100644 index bbd58a5..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_crc.h +++ /dev/null @@ -1,184 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_crc.h - * @author MCD Application Team - * @brief Header file of CRC HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_CRC_H -#define STM32F4xx_HAL_CRC_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup CRC - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup CRC_Exported_Types CRC Exported Types - * @{ - */ - -/** - * @brief CRC HAL State Structure definition - */ -typedef enum -{ - HAL_CRC_STATE_RESET = 0x00U, /*!< CRC not yet initialized or disabled */ - HAL_CRC_STATE_READY = 0x01U, /*!< CRC initialized and ready for use */ - HAL_CRC_STATE_BUSY = 0x02U, /*!< CRC internal process is ongoing */ - HAL_CRC_STATE_TIMEOUT = 0x03U, /*!< CRC timeout state */ - HAL_CRC_STATE_ERROR = 0x04U /*!< CRC error state */ -} HAL_CRC_StateTypeDef; - - -/** - * @brief CRC Handle Structure definition - */ -typedef struct -{ - CRC_TypeDef *Instance; /*!< Register base address */ - - HAL_LockTypeDef Lock; /*!< CRC Locking object */ - - __IO HAL_CRC_StateTypeDef State; /*!< CRC communication state */ - -} CRC_HandleTypeDef; -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup CRC_Exported_Constants CRC Exported Constants - * @{ - */ - -/** - * @} - */ - -/* Exported macros -----------------------------------------------------------*/ -/** @defgroup CRC_Exported_Macros CRC Exported Macros - * @{ - */ - -/** @brief Reset CRC handle state. - * @param __HANDLE__ CRC handle. - * @retval None - */ -#define __HAL_CRC_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_CRC_STATE_RESET) - -/** - * @brief Reset CRC Data Register. - * @param __HANDLE__ CRC handle - * @retval None - */ -#define __HAL_CRC_DR_RESET(__HANDLE__) ((__HANDLE__)->Instance->CR |= CRC_CR_RESET) - -/** - * @brief Store data in the Independent Data (ID) register. - * @param __HANDLE__ CRC handle - * @param __VALUE__ Value to be stored in the ID register - * @note Refer to the Reference Manual to get the authorized __VALUE__ length in bits - * @retval None - */ -#define __HAL_CRC_SET_IDR(__HANDLE__, __VALUE__) (WRITE_REG((__HANDLE__)->Instance->IDR, (__VALUE__))) - -/** - * @brief Return the data stored in the Independent Data (ID) register. - * @param __HANDLE__ CRC handle - * @note Refer to the Reference Manual to get the authorized __VALUE__ length in bits - * @retval Value of the ID register - */ -#define __HAL_CRC_GET_IDR(__HANDLE__) (((__HANDLE__)->Instance->IDR) & CRC_IDR_IDR) -/** - * @} - */ - - -/* Private macros --------------------------------------------------------*/ -/** @defgroup CRC_Private_Macros CRC Private Macros - * @{ - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup CRC_Exported_Functions CRC Exported Functions - * @{ - */ - -/* Initialization and de-initialization functions ****************************/ -/** @defgroup CRC_Exported_Functions_Group1 Initialization and de-initialization functions - * @{ - */ -HAL_StatusTypeDef HAL_CRC_Init(CRC_HandleTypeDef *hcrc); -HAL_StatusTypeDef HAL_CRC_DeInit(CRC_HandleTypeDef *hcrc); -void HAL_CRC_MspInit(CRC_HandleTypeDef *hcrc); -void HAL_CRC_MspDeInit(CRC_HandleTypeDef *hcrc); -/** - * @} - */ - -/* Peripheral Control functions ***********************************************/ -/** @defgroup CRC_Exported_Functions_Group2 Peripheral Control functions - * @{ - */ -uint32_t HAL_CRC_Accumulate(CRC_HandleTypeDef *hcrc, uint32_t pBuffer[], uint32_t BufferLength); -uint32_t HAL_CRC_Calculate(CRC_HandleTypeDef *hcrc, uint32_t pBuffer[], uint32_t BufferLength); -/** - * @} - */ - -/* Peripheral State and Error functions ***************************************/ -/** @defgroup CRC_Exported_Functions_Group3 Peripheral State functions - * @{ - */ -HAL_CRC_StateTypeDef HAL_CRC_GetState(CRC_HandleTypeDef *hcrc); -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_HAL_CRC_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_cryp.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_cryp.h deleted file mode 100644 index 8596fe7..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_cryp.h +++ /dev/null @@ -1,685 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_cryp.h - * @author MCD Application Team - * @brief Header file of CRYP HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_CRYP_H -#define __STM32F4xx_HAL_CRYP_H - -#ifdef __cplusplus -extern "C" { -#endif - - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ -#if defined (AES) || defined (CRYP) -/** @addtogroup CRYP - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ - -/** @defgroup CRYP_Exported_Types CRYP Exported Types - * @{ - */ - -/** - * @brief CRYP Init Structure definition - */ - -typedef struct -{ - uint32_t DataType; /*!< 32-bit data, 16-bit data, 8-bit data or 1-bit string. - This parameter can be a value of @ref CRYP_Data_Type */ - uint32_t KeySize; /*!< Used only in AES mode : 128, 192 or 256 bit key length in CRYP1. - 128 or 256 bit key length in TinyAES This parameter can be a value of @ref CRYP_Key_Size */ - uint32_t *pKey; /*!< The key used for encryption/decryption */ - uint32_t *pInitVect; /*!< The initialization vector used also as initialization - counter in CTR mode */ - uint32_t Algorithm; /*!< DES/ TDES Algorithm ECB/CBC - AES Algorithm ECB/CBC/CTR/GCM or CCM - This parameter can be a value of @ref CRYP_Algorithm_Mode */ - uint32_t *Header; /*!< used only in AES GCM and CCM Algorithm for authentication, - GCM : also known as Additional Authentication Data - CCM : named B1 composed of the associated data length and Associated Data. */ - uint32_t HeaderSize; /*!< The size of header buffer in word */ - uint32_t *B0; /*!< B0 is first authentication block used only in AES CCM mode */ - uint32_t DataWidthUnit; /*!< Data With Unit, this parameter can be value of @ref CRYP_Data_Width_Unit*/ - uint32_t HeaderWidthUnit; /*!< Header Width Unit, this parameter can be value of @ref CRYP_Header_Width_Unit*/ - uint32_t KeyIVConfigSkip; /*!< CRYP peripheral Key and IV configuration skip, to config Key and Initialization - Vector only once and to skip configuration for consecutive processings. - This parameter can be a value of @ref CRYP_Configuration_Skip */ - -} CRYP_ConfigTypeDef; - - -/** - * @brief CRYP State Structure definition - */ - -typedef enum -{ - HAL_CRYP_STATE_RESET = 0x00U, /*!< CRYP not yet initialized or disabled */ - HAL_CRYP_STATE_READY = 0x01U, /*!< CRYP initialized and ready for use */ - HAL_CRYP_STATE_BUSY = 0x02U /*!< CRYP BUSY, internal processing is ongoing */ -} HAL_CRYP_STATETypeDef; - - -/** - * @brief CRYP handle Structure definition - */ - -typedef struct __CRYP_HandleTypeDef -{ -#if defined (CRYP) - CRYP_TypeDef *Instance; /*!< CRYP registers base address */ -#else /* AES*/ - AES_TypeDef *Instance; /*!< AES Register base address */ -#endif /* End AES or CRYP */ - - CRYP_ConfigTypeDef Init; /*!< CRYP required parameters */ - - FunctionalState AutoKeyDerivation; /*!< Used only in TinyAES to allows to bypass or not key write-up before decryption. - This parameter can be a value of ENABLE/DISABLE */ - - uint32_t *pCrypInBuffPtr; /*!< Pointer to CRYP processing (encryption, decryption,...) buffer */ - - uint32_t *pCrypOutBuffPtr; /*!< Pointer to CRYP processing (encryption, decryption,...) buffer */ - - __IO uint16_t CrypHeaderCount; /*!< Counter of header data */ - - __IO uint16_t CrypInCount; /*!< Counter of input data */ - - __IO uint16_t CrypOutCount; /*!< Counter of output data */ - - uint16_t Size; /*!< length of input data in word */ - - uint32_t Phase; /*!< CRYP peripheral phase */ - - DMA_HandleTypeDef *hdmain; /*!< CRYP In DMA handle parameters */ - - DMA_HandleTypeDef *hdmaout; /*!< CRYP Out DMA handle parameters */ - - HAL_LockTypeDef Lock; /*!< CRYP locking object */ - - __IO HAL_CRYP_STATETypeDef State; /*!< CRYP peripheral state */ - - __IO uint32_t ErrorCode; /*!< CRYP peripheral error code */ - - uint32_t KeyIVConfig; /*!< CRYP peripheral Key and IV configuration flag, used when - configuration can be skipped */ - - uint32_t SizesSum; /*!< Sum of successive payloads lengths (in bytes), stored - for a single signature computation after several - messages processing */ - -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) - void (*InCpltCallback)(struct __CRYP_HandleTypeDef *hcryp); /*!< CRYP Input FIFO transfer completed callback */ - void (*OutCpltCallback)(struct __CRYP_HandleTypeDef *hcryp); /*!< CRYP Output FIFO transfer completed callback */ - void (*ErrorCallback)(struct __CRYP_HandleTypeDef *hcryp); /*!< CRYP Error callback */ - - void (* MspInitCallback)(struct __CRYP_HandleTypeDef *hcryp); /*!< CRYP Msp Init callback */ - void (* MspDeInitCallback)(struct __CRYP_HandleTypeDef *hcryp); /*!< CRYP Msp DeInit callback */ - -#endif /* (USE_HAL_CRYP_REGISTER_CALLBACKS) */ -} CRYP_HandleTypeDef; - - -/** - * @} - */ - -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) -/** @defgroup HAL_CRYP_Callback_ID_enumeration_definition HAL CRYP Callback ID enumeration definition - * @brief HAL CRYP Callback ID enumeration definition - * @{ - */ -typedef enum -{ - HAL_CRYP_INPUT_COMPLETE_CB_ID = 0x01U, /*!< CRYP Input FIFO transfer completed callback ID */ - HAL_CRYP_OUTPUT_COMPLETE_CB_ID = 0x02U, /*!< CRYP Output FIFO transfer completed callback ID */ - HAL_CRYP_ERROR_CB_ID = 0x03U, /*!< CRYP Error callback ID */ - - HAL_CRYP_MSPINIT_CB_ID = 0x04U, /*!< CRYP MspInit callback ID */ - HAL_CRYP_MSPDEINIT_CB_ID = 0x05U /*!< CRYP MspDeInit callback ID */ - -} HAL_CRYP_CallbackIDTypeDef; -/** - * @} - */ - -/** @defgroup HAL_CRYP_Callback_pointer_definition HAL CRYP Callback pointer definition - * @brief HAL CRYP Callback pointer definition - * @{ - */ - -typedef void (*pCRYP_CallbackTypeDef)(CRYP_HandleTypeDef *hcryp); /*!< pointer to a common CRYP callback function */ - -/** - * @} - */ - -#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup CRYP_Exported_Constants CRYP Exported Constants - * @{ - */ - -/** @defgroup CRYP_Error_Definition CRYP Error Definition - * @{ - */ -#define HAL_CRYP_ERROR_NONE 0x00000000U /*!< No error */ -#define HAL_CRYP_ERROR_WRITE 0x00000001U /*!< Write error */ -#define HAL_CRYP_ERROR_READ 0x00000002U /*!< Read error */ -#define HAL_CRYP_ERROR_DMA 0x00000004U /*!< DMA error */ -#define HAL_CRYP_ERROR_BUSY 0x00000008U /*!< Busy flag error */ -#define HAL_CRYP_ERROR_TIMEOUT 0x00000010U /*!< Timeout error */ -#define HAL_CRYP_ERROR_NOT_SUPPORTED 0x00000020U /*!< Not supported mode */ -#define HAL_CRYP_ERROR_AUTH_TAG_SEQUENCE 0x00000040U /*!< Sequence are not respected only for GCM or CCM */ -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) -#define HAL_CRYP_ERROR_INVALID_CALLBACK ((uint32_t)0x00000080U) /*!< Invalid Callback error */ -#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @defgroup CRYP_Data_Width_Unit CRYP Data Width Unit - * @{ - */ - -#define CRYP_DATAWIDTHUNIT_WORD 0x00000000U /*!< By default, size unit is word */ -#define CRYP_DATAWIDTHUNIT_BYTE 0x00000001U /*!< By default, size unit is word */ - -/** - * @} - */ - -/** @defgroup CRYP_Header_Width_Unit CRYP Header Width Unit - * @{ - */ - -#define CRYP_HEADERWIDTHUNIT_WORD 0x00000000U /*!< By default, header size unit is word */ -#define CRYP_HEADERWIDTHUNIT_BYTE 0x00000001U /*!< By default, header size unit is byte */ - -/** - * @} - */ - -/** @defgroup CRYP_Algorithm_Mode CRYP Algorithm Mode - * @{ - */ -#if defined(CRYP) - -#define CRYP_DES_ECB CRYP_CR_ALGOMODE_DES_ECB -#define CRYP_DES_CBC CRYP_CR_ALGOMODE_DES_CBC -#define CRYP_TDES_ECB CRYP_CR_ALGOMODE_TDES_ECB -#define CRYP_TDES_CBC CRYP_CR_ALGOMODE_TDES_CBC -#define CRYP_AES_ECB CRYP_CR_ALGOMODE_AES_ECB -#define CRYP_AES_CBC CRYP_CR_ALGOMODE_AES_CBC -#define CRYP_AES_CTR CRYP_CR_ALGOMODE_AES_CTR -#if defined (CRYP_CR_ALGOMODE_AES_GCM) -#define CRYP_AES_GCM CRYP_CR_ALGOMODE_AES_GCM -#define CRYP_AES_CCM CRYP_CR_ALGOMODE_AES_CCM -#endif /* GCM CCM defined*/ -#else /* AES*/ -#define CRYP_AES_ECB 0x00000000U /*!< Electronic codebook chaining algorithm */ -#define CRYP_AES_CBC AES_CR_CHMOD_0 /*!< Cipher block chaining algorithm */ -#define CRYP_AES_CTR AES_CR_CHMOD_1 /*!< Counter mode chaining algorithm */ -#define CRYP_AES_GCM_GMAC (AES_CR_CHMOD_0 | AES_CR_CHMOD_1) /*!< Galois counter mode - Galois message authentication code */ -#define CRYP_AES_CCM AES_CR_CHMOD_2 /*!< Counter with Cipher Mode */ -#endif /* End AES or CRYP */ - -/** - * @} - */ - -/** @defgroup CRYP_Key_Size CRYP Key Size - * @{ - */ -#if defined(CRYP) -#define CRYP_KEYSIZE_128B 0x00000000U -#define CRYP_KEYSIZE_192B CRYP_CR_KEYSIZE_0 -#define CRYP_KEYSIZE_256B CRYP_CR_KEYSIZE_1 -#else /* AES*/ -#define CRYP_KEYSIZE_128B 0x00000000U /*!< 128-bit long key */ -#define CRYP_KEYSIZE_256B AES_CR_KEYSIZE /*!< 256-bit long key */ -#endif /* End AES or CRYP */ -/** - * @} - */ - -/** @defgroup CRYP_Data_Type CRYP Data Type - * @{ - */ -#if defined(CRYP) -#define CRYP_DATATYPE_32B 0x00000000U -#define CRYP_DATATYPE_16B CRYP_CR_DATATYPE_0 -#define CRYP_DATATYPE_8B CRYP_CR_DATATYPE_1 -#define CRYP_DATATYPE_1B CRYP_CR_DATATYPE -#else /* AES*/ -#define CRYP_DATATYPE_32B 0x00000000U /*!< 32-bit data type (no swapping) */ -#define CRYP_DATATYPE_16B AES_CR_DATATYPE_0 /*!< 16-bit data type (half-word swapping) */ -#define CRYP_DATATYPE_8B AES_CR_DATATYPE_1 /*!< 8-bit data type (byte swapping) */ -#define CRYP_DATATYPE_1B AES_CR_DATATYPE /*!< 1-bit data type (bit swapping) */ -#endif /* End AES or CRYP */ - -/** - * @} - */ - -/** @defgroup CRYP_Interrupt CRYP Interrupt - * @{ - */ -#if defined (CRYP) -#define CRYP_IT_INI CRYP_IMSCR_INIM /*!< Input FIFO Interrupt */ -#define CRYP_IT_OUTI CRYP_IMSCR_OUTIM /*!< Output FIFO Interrupt */ -#else /* AES*/ -#define CRYP_IT_CCFIE AES_CR_CCFIE /*!< Computation Complete interrupt enable */ -#define CRYP_IT_ERRIE AES_CR_ERRIE /*!< Error interrupt enable */ -#define CRYP_IT_WRERR AES_SR_WRERR /*!< Write Error */ -#define CRYP_IT_RDERR AES_SR_RDERR /*!< Read Error */ -#define CRYP_IT_CCF AES_SR_CCF /*!< Computation completed */ -#endif /* End AES or CRYP */ - -/** - * @} - */ - -/** @defgroup CRYP_Flags CRYP Flags - * @{ - */ -#if defined (CRYP) -/* Flags in the SR register */ -#define CRYP_FLAG_IFEM CRYP_SR_IFEM /*!< Input FIFO is empty */ -#define CRYP_FLAG_IFNF CRYP_SR_IFNF /*!< Input FIFO is not Full */ -#define CRYP_FLAG_OFNE CRYP_SR_OFNE /*!< Output FIFO is not empty */ -#define CRYP_FLAG_OFFU CRYP_SR_OFFU /*!< Output FIFO is Full */ -#define CRYP_FLAG_BUSY CRYP_SR_BUSY /*!< The CRYP core is currently processing a block of data - or a key preparation (for AES decryption). */ -/* Flags in the RISR register */ -#define CRYP_FLAG_OUTRIS 0x01000002U /*!< Output FIFO service raw interrupt status */ -#define CRYP_FLAG_INRIS 0x01000001U /*!< Input FIFO service raw interrupt status*/ -#else /* AES*/ -/* status flags */ -#define CRYP_FLAG_BUSY AES_SR_BUSY /*!< GCM process suspension forbidden */ -#define CRYP_FLAG_WRERR AES_SR_WRERR /*!< Write Error */ -#define CRYP_FLAG_RDERR AES_SR_RDERR /*!< Read error */ -#define CRYP_FLAG_CCF AES_SR_CCF /*!< Computation completed */ -/* clearing flags */ -#define CRYP_CCF_CLEAR AES_CR_CCFC /*!< Computation Complete Flag Clear */ -#define CRYP_ERR_CLEAR AES_CR_ERRC /*!< Error Flag Clear */ -#endif /* End AES or CRYP */ - -/** - * @} - */ - -/** @defgroup CRYP_Configuration_Skip CRYP Key and IV Configuration Skip Mode - * @{ - */ - -#define CRYP_KEYIVCONFIG_ALWAYS 0x00000000U /*!< Peripheral Key and IV configuration to do systematically */ -#define CRYP_KEYIVCONFIG_ONCE 0x00000001U /*!< Peripheral Key and IV configuration to do only once */ - -/** - * @} - */ - - -/** - * @} - */ - -/* Exported macros -----------------------------------------------------------*/ -/** @defgroup CRYP_Exported_Macros CRYP Exported Macros - * @{ - */ - -/** @brief Reset CRYP handle state - * @param __HANDLE__ specifies the CRYP handle. - * @retval None - */ -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) -#define __HAL_CRYP_RESET_HANDLE_STATE(__HANDLE__) do{\ - (__HANDLE__)->State = HAL_CRYP_STATE_RESET;\ - (__HANDLE__)->MspInitCallback = NULL;\ - (__HANDLE__)->MspDeInitCallback = NULL;\ - }while(0) -#else -#define __HAL_CRYP_RESET_HANDLE_STATE(__HANDLE__) ( (__HANDLE__)->State = HAL_CRYP_STATE_RESET) -#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ - -/** - * @brief Enable/Disable the CRYP peripheral. - * @param __HANDLE__: specifies the CRYP handle. - * @retval None - */ -#if defined(CRYP) -#define __HAL_CRYP_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= CRYP_CR_CRYPEN) -#define __HAL_CRYP_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR &= ~CRYP_CR_CRYPEN) -#else /* AES*/ -#define __HAL_CRYP_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= AES_CR_EN) -#define __HAL_CRYP_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR &= ~AES_CR_EN) -#endif /* End AES or CRYP */ - -/** @brief Check whether the specified CRYP status flag is set or not. - * @param __FLAG__: specifies the flag to check. - * This parameter can be one of the following values for TinyAES: - * @arg @ref CRYP_FLAG_BUSY GCM process suspension forbidden - * @arg @ref CRYP_IT_WRERR Write Error - * @arg @ref CRYP_IT_RDERR Read Error - * @arg @ref CRYP_IT_CCF Computation Complete - * This parameter can be one of the following values for CRYP: - * @arg CRYP_FLAG_BUSY: The CRYP core is currently processing a block of data - * or a key preparation (for AES decryption). - * @arg CRYP_FLAG_IFEM: Input FIFO is empty - * @arg CRYP_FLAG_IFNF: Input FIFO is not full - * @arg CRYP_FLAG_INRIS: Input FIFO service raw interrupt is pending - * @arg CRYP_FLAG_OFNE: Output FIFO is not empty - * @arg CRYP_FLAG_OFFU: Output FIFO is full - * @arg CRYP_FLAG_OUTRIS: Input FIFO service raw interrupt is pending - * @retval The state of __FLAG__ (TRUE or FALSE). - */ -#define CRYP_FLAG_MASK 0x0000001FU -#if defined(CRYP) -#define __HAL_CRYP_GET_FLAG(__HANDLE__, __FLAG__) ((((uint8_t)((__FLAG__) >> 24)) == 0x01U)?((((__HANDLE__)->Instance->RISR) & ((__FLAG__) & CRYP_FLAG_MASK)) == ((__FLAG__) & CRYP_FLAG_MASK)): \ - ((((__HANDLE__)->Instance->RISR) & ((__FLAG__) & CRYP_FLAG_MASK)) == ((__FLAG__) & CRYP_FLAG_MASK))) -#else /* AES*/ -#define __HAL_CRYP_GET_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->SR & (__FLAG__)) == (__FLAG__)) -#endif /* End AES or CRYP */ - -/** @brief Clear the CRYP pending status flag. - * @param __FLAG__: specifies the flag to clear. - * This parameter can be one of the following values: - * @arg @ref CRYP_ERR_CLEAR Read (RDERR) or Write Error (WRERR) Flag Clear - * @arg @ref CRYP_CCF_CLEAR Computation Complete Flag (CCF) Clear - * @param __HANDLE__: specifies the CRYP handle. - * @retval None - */ - -#if defined(AES) -#define __HAL_CRYP_CLEAR_FLAG(__HANDLE__, __FLAG__) SET_BIT((__HANDLE__)->Instance->CR, (__FLAG__)) - - -/** @brief Check whether the specified CRYP interrupt source is enabled or not. - * @param __INTERRUPT__: CRYP interrupt source to check - * This parameter can be one of the following values for TinyAES: - * @arg @ref CRYP_IT_ERRIE Error interrupt (used for RDERR and WRERR) - * @arg @ref CRYP_IT_CCFIE Computation Complete interrupt - * @param __HANDLE__: specifies the CRYP handle. - * @retval State of interruption (TRUE or FALSE). - */ - -#define __HAL_CRYP_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->CR\ - & (__INTERRUPT__)) == (__INTERRUPT__)) - -#endif /* AES */ - -/** @brief Check whether the specified CRYP interrupt is set or not. - * @param __INTERRUPT__: specifies the interrupt to check. - * This parameter can be one of the following values for TinyAES: - * @arg @ref CRYP_IT_WRERR Write Error - * @arg @ref CRYP_IT_RDERR Read Error - * @arg @ref CRYP_IT_CCF Computation Complete - * This parameter can be one of the following values for CRYP: - * @arg CRYP_IT_INI: Input FIFO service masked interrupt status - * @arg CRYP_IT_OUTI: Output FIFO service masked interrupt status - * @param __HANDLE__: specifies the CRYP handle. - * @retval The state of __INTERRUPT__ (TRUE or FALSE). - */ -#if defined(CRYP) -#define __HAL_CRYP_GET_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->MISR\ - & (__INTERRUPT__)) == (__INTERRUPT__)) -#else /* AES*/ -#define __HAL_CRYP_GET_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->SR & (__INTERRUPT__)) == (__INTERRUPT__)) -#endif /* End AES or CRYP */ - -/** - * @brief Enable the CRYP interrupt. - * @param __INTERRUPT__: CRYP Interrupt. - * This parameter can be one of the following values for TinyAES: - * @arg @ref CRYP_IT_ERRIE Error interrupt (used for RDERR and WRERR) - * @arg @ref CRYP_IT_CCFIE Computation Complete interrupt - * This parameter can be one of the following values for CRYP: - * @ CRYP_IT_INI : Input FIFO service interrupt mask. - * @ CRYP_IT_OUTI : Output FIFO service interrupt mask.CRYP interrupt. - * @param __HANDLE__: specifies the CRYP handle. - * @retval None - */ -#if defined(CRYP) -#define __HAL_CRYP_ENABLE_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->IMSCR) |= (__INTERRUPT__)) -#else /* AES*/ -#define __HAL_CRYP_ENABLE_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->CR) |= (__INTERRUPT__)) -#endif /* End AES or CRYP */ - -/** - * @brief Disable the CRYP interrupt. - * @param __INTERRUPT__: CRYP Interrupt. - * This parameter can be one of the following values for TinyAES: - * @arg @ref CRYP_IT_ERRIE Error interrupt (used for RDERR and WRERR) - * @arg @ref CRYP_IT_CCFIE Computation Complete interrupt - * This parameter can be one of the following values for CRYP: - * @ CRYP_IT_INI : Input FIFO service interrupt mask. - * @ CRYP_IT_OUTI : Output FIFO service interrupt mask.CRYP interrupt. - * @param __HANDLE__: specifies the CRYP handle. - * @retval None - */ -#if defined(CRYP) -#define __HAL_CRYP_DISABLE_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->IMSCR) &= ~(__INTERRUPT__)) -#else /* AES*/ -#define __HAL_CRYP_DISABLE_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->CR) &= ~(__INTERRUPT__)) -#endif /* End AES or CRYP */ - -/** - * @} - */ -#if defined (CRYP_CR_ALGOMODE_AES_GCM)|| defined (AES) -/* Include CRYP HAL Extended module */ -#include "stm32f4xx_hal_cryp_ex.h" -#endif /* AES or GCM CCM defined*/ -/* Exported functions --------------------------------------------------------*/ -/** @defgroup CRYP_Exported_Functions CRYP Exported Functions - * @{ - */ - -/** @addtogroup CRYP_Exported_Functions_Group1 - * @{ - */ -HAL_StatusTypeDef HAL_CRYP_Init(CRYP_HandleTypeDef *hcryp); -HAL_StatusTypeDef HAL_CRYP_DeInit(CRYP_HandleTypeDef *hcryp); -void HAL_CRYP_MspInit(CRYP_HandleTypeDef *hcryp); -void HAL_CRYP_MspDeInit(CRYP_HandleTypeDef *hcryp); -HAL_StatusTypeDef HAL_CRYP_SetConfig(CRYP_HandleTypeDef *hcryp, CRYP_ConfigTypeDef *pConf); -HAL_StatusTypeDef HAL_CRYP_GetConfig(CRYP_HandleTypeDef *hcryp, CRYP_ConfigTypeDef *pConf); -#if (USE_HAL_CRYP_REGISTER_CALLBACKS == 1) -HAL_StatusTypeDef HAL_CRYP_RegisterCallback(CRYP_HandleTypeDef *hcryp, HAL_CRYP_CallbackIDTypeDef CallbackID, - pCRYP_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_CRYP_UnRegisterCallback(CRYP_HandleTypeDef *hcryp, HAL_CRYP_CallbackIDTypeDef CallbackID); -#endif /* USE_HAL_CRYP_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @addtogroup CRYP_Exported_Functions_Group2 - * @{ - */ - -/* encryption/decryption ***********************************/ -HAL_StatusTypeDef HAL_CRYP_Encrypt(CRYP_HandleTypeDef *hcryp, uint32_t *Input, uint16_t Size, uint32_t *Output, - uint32_t Timeout); -HAL_StatusTypeDef HAL_CRYP_Decrypt(CRYP_HandleTypeDef *hcryp, uint32_t *Input, uint16_t Size, uint32_t *Output, - uint32_t Timeout); -HAL_StatusTypeDef HAL_CRYP_Encrypt_IT(CRYP_HandleTypeDef *hcryp, uint32_t *Input, uint16_t Size, uint32_t *Output); -HAL_StatusTypeDef HAL_CRYP_Decrypt_IT(CRYP_HandleTypeDef *hcryp, uint32_t *Input, uint16_t Size, uint32_t *Output); -HAL_StatusTypeDef HAL_CRYP_Encrypt_DMA(CRYP_HandleTypeDef *hcryp, uint32_t *Input, uint16_t Size, uint32_t *Output); -HAL_StatusTypeDef HAL_CRYP_Decrypt_DMA(CRYP_HandleTypeDef *hcryp, uint32_t *Input, uint16_t Size, uint32_t *Output); - -/** - * @} - */ - - -/** @addtogroup CRYP_Exported_Functions_Group3 - * @{ - */ -/* Interrupt Handler functions **********************************************/ -void HAL_CRYP_IRQHandler(CRYP_HandleTypeDef *hcryp); -HAL_CRYP_STATETypeDef HAL_CRYP_GetState(CRYP_HandleTypeDef *hcryp); -void HAL_CRYP_InCpltCallback(CRYP_HandleTypeDef *hcryp); -void HAL_CRYP_OutCpltCallback(CRYP_HandleTypeDef *hcryp); -void HAL_CRYP_ErrorCallback(CRYP_HandleTypeDef *hcryp); -uint32_t HAL_CRYP_GetError(CRYP_HandleTypeDef *hcryp); - -/** - * @} - */ - -/** - * @} - */ - -/* Private macros --------------------------------------------------------*/ -/** @defgroup CRYP_Private_Macros CRYP Private Macros - * @{ - */ - -/** @defgroup CRYP_IS_CRYP_Definitions CRYP Private macros to check input parameters - * @{ - */ -#if defined(CRYP) -#if defined (CRYP_CR_ALGOMODE_AES_GCM) -#define IS_CRYP_ALGORITHM(ALGORITHM) (((ALGORITHM) == CRYP_DES_ECB) || \ - ((ALGORITHM) == CRYP_DES_CBC) || \ - ((ALGORITHM) == CRYP_TDES_ECB) || \ - ((ALGORITHM) == CRYP_TDES_CBC) || \ - ((ALGORITHM) == CRYP_AES_ECB) || \ - ((ALGORITHM) == CRYP_AES_CBC) || \ - ((ALGORITHM) == CRYP_AES_CTR) || \ - ((ALGORITHM) == CRYP_AES_GCM) || \ - ((ALGORITHM) == CRYP_AES_CCM)) -#else /*NO GCM CCM */ -#define IS_CRYP_ALGORITHM(ALGORITHM) (((ALGORITHM) == CRYP_DES_ECB) || \ - ((ALGORITHM) == CRYP_DES_CBC) || \ - ((ALGORITHM) == CRYP_TDES_ECB) || \ - ((ALGORITHM) == CRYP_TDES_CBC) || \ - ((ALGORITHM) == CRYP_AES_ECB) || \ - ((ALGORITHM) == CRYP_AES_CBC) || \ - ((ALGORITHM) == CRYP_AES_CTR)) -#endif /* GCM CCM defined*/ -#define IS_CRYP_KEYSIZE(KEYSIZE)(((KEYSIZE) == CRYP_KEYSIZE_128B) || \ - ((KEYSIZE) == CRYP_KEYSIZE_192B) || \ - ((KEYSIZE) == CRYP_KEYSIZE_256B)) -#else /* AES*/ -#define IS_CRYP_ALGORITHM(ALGORITHM) (((ALGORITHM) == CRYP_AES_ECB) || \ - ((ALGORITHM) == CRYP_AES_CBC) || \ - ((ALGORITHM) == CRYP_AES_CTR) || \ - ((ALGORITHM) == CRYP_AES_GCM_GMAC)|| \ - ((ALGORITHM) == CRYP_AES_CCM)) - - -#define IS_CRYP_KEYSIZE(KEYSIZE)(((KEYSIZE) == CRYP_KEYSIZE_128B) || \ - ((KEYSIZE) == CRYP_KEYSIZE_256B)) -#endif /* End AES or CRYP */ - -#define IS_CRYP_DATATYPE(DATATYPE)(((DATATYPE) == CRYP_DATATYPE_32B) || \ - ((DATATYPE) == CRYP_DATATYPE_16B) || \ - ((DATATYPE) == CRYP_DATATYPE_8B) || \ - ((DATATYPE) == CRYP_DATATYPE_1B)) - -#define IS_CRYP_INIT(CONFIG)(((CONFIG) == CRYP_KEYIVCONFIG_ALWAYS) || \ - ((CONFIG) == CRYP_KEYIVCONFIG_ONCE)) -/** - * @} - */ - -/** - * @} - */ - - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup CRYP_Private_Constants CRYP Private Constants - * @{ - */ - -/** - * @} - */ -/* Private defines -----------------------------------------------------------*/ -/** @defgroup CRYP_Private_Defines CRYP Private Defines - * @{ - */ - -/** - * @} - */ - -/* Private variables ---------------------------------------------------------*/ -/** @defgroup CRYP_Private_Variables CRYP Private Variables - * @{ - */ - -/** - * @} - */ -/* Private functions prototypes ----------------------------------------------*/ -/** @defgroup CRYP_Private_Functions_Prototypes CRYP Private Functions Prototypes - * @{ - */ - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup CRYP_Private_Functions CRYP Private Functions - * @{ - */ - -/** - * @} - */ - - -/** - * @} - */ - - -/** - * @} - */ -#endif /* TinyAES or CRYP*/ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_CRYP_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_cryp_ex.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_cryp_ex.h deleted file mode 100644 index 251e94b..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_cryp_ex.h +++ /dev/null @@ -1,144 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_cryp_ex.h - * @author MCD Application Team - * @brief Header file of CRYP HAL Extension module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_CRYP_EX_H -#define __STM32F4xx_HAL_CRYP_EX_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup CRYPEx - * @{ - */ -/* Exported types ------------------------------------------------------------*/ -/** @defgroup CRYPEx_Exported_Types CRYPEx Exported types - * @{ - */ - -/** - * @} - */ -/* Exported constants --------------------------------------------------------*/ -/** @defgroup CRYPEx_Exported_Constants CRYPEx Exported constants - * @{ - */ - -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/** @defgroup CRYPEx_Private_Types CRYPEx Private Types - * @{ - */ - -/** - * @} - */ - -/* Private variables ---------------------------------------------------------*/ -/** @defgroup CRYPEx_Private_Variables CRYPEx Private Variables - * @{ - */ - -/** - * @} - */ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup CRYPEx_Private_Constants CRYPEx Private Constants - * @{ - */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup CRYPEx_Private_Macros CRYPEx Private Macros - * @{ - */ - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup CRYPEx_Private_Functions CRYPEx Private Functions - * @{ - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup CRYPEx_Exported_Functions CRYPEx Exported Functions - * @{ - */ -#if defined (CRYP) || defined (AES) -/** @addtogroup CRYPEx_Exported_Functions_Group1 - * @{ - */ -HAL_StatusTypeDef HAL_CRYPEx_AESGCM_GenerateAuthTAG(CRYP_HandleTypeDef *hcryp, uint32_t *AuthTag, uint32_t Timeout); -HAL_StatusTypeDef HAL_CRYPEx_AESCCM_GenerateAuthTAG(CRYP_HandleTypeDef *hcryp, uint32_t *AuthTag, uint32_t Timeout); -/** - * @} - */ -#endif /* CRYP||AES */ - -#if defined (AES) -/** @addtogroup CRYPEx_Exported_Functions_Group2 - * @{ - */ -void HAL_CRYPEx_EnableAutoKeyDerivation(CRYP_HandleTypeDef *hcryp); -void HAL_CRYPEx_DisableAutoKeyDerivation(CRYP_HandleTypeDef *hcryp); -/** - * @} - */ -#endif /* AES */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_CRYP_EX_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dac.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dac.h deleted file mode 100644 index abd8544..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dac.h +++ /dev/null @@ -1,482 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_dac.h - * @author MCD Application Team - * @brief Header file of DAC HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_DAC_H -#define STM32F4xx_HAL_DAC_H - -#ifdef __cplusplus -extern "C" { -#endif - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -#if defined(DAC) - -/** @addtogroup DAC - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ - -/** @defgroup DAC_Exported_Types DAC Exported Types - * @{ - */ - -/** - * @brief HAL State structures definition - */ -typedef enum -{ - HAL_DAC_STATE_RESET = 0x00U, /*!< DAC not yet initialized or disabled */ - HAL_DAC_STATE_READY = 0x01U, /*!< DAC initialized and ready for use */ - HAL_DAC_STATE_BUSY = 0x02U, /*!< DAC internal processing is ongoing */ - HAL_DAC_STATE_TIMEOUT = 0x03U, /*!< DAC timeout state */ - HAL_DAC_STATE_ERROR = 0x04U /*!< DAC error state */ - -} HAL_DAC_StateTypeDef; - -/** - * @brief DAC handle Structure definition - */ -#if (USE_HAL_DAC_REGISTER_CALLBACKS == 1) -typedef struct __DAC_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_DAC_REGISTER_CALLBACKS */ -{ - DAC_TypeDef *Instance; /*!< Register base address */ - - __IO HAL_DAC_StateTypeDef State; /*!< DAC communication state */ - - HAL_LockTypeDef Lock; /*!< DAC locking object */ - - DMA_HandleTypeDef *DMA_Handle1; /*!< Pointer DMA handler for channel 1 */ - - DMA_HandleTypeDef *DMA_Handle2; /*!< Pointer DMA handler for channel 2 */ - - __IO uint32_t ErrorCode; /*!< DAC Error code */ - -#if (USE_HAL_DAC_REGISTER_CALLBACKS == 1) - void (* ConvCpltCallbackCh1) (struct __DAC_HandleTypeDef *hdac); - void (* ConvHalfCpltCallbackCh1) (struct __DAC_HandleTypeDef *hdac); - void (* ErrorCallbackCh1) (struct __DAC_HandleTypeDef *hdac); - void (* DMAUnderrunCallbackCh1) (struct __DAC_HandleTypeDef *hdac); -#if defined(DAC_CHANNEL2_SUPPORT) - void (* ConvCpltCallbackCh2) (struct __DAC_HandleTypeDef *hdac); - void (* ConvHalfCpltCallbackCh2) (struct __DAC_HandleTypeDef *hdac); - void (* ErrorCallbackCh2) (struct __DAC_HandleTypeDef *hdac); - void (* DMAUnderrunCallbackCh2) (struct __DAC_HandleTypeDef *hdac); -#endif /* DAC_CHANNEL2_SUPPORT */ - - void (* MspInitCallback) (struct __DAC_HandleTypeDef *hdac); - void (* MspDeInitCallback) (struct __DAC_HandleTypeDef *hdac); -#endif /* USE_HAL_DAC_REGISTER_CALLBACKS */ - -} DAC_HandleTypeDef; - -/** - * @brief DAC Configuration regular Channel structure definition - */ -typedef struct -{ - uint32_t DAC_Trigger; /*!< Specifies the external trigger for the selected DAC channel. - This parameter can be a value of @ref DAC_trigger_selection */ - - uint32_t DAC_OutputBuffer; /*!< Specifies whether the DAC channel output buffer is enabled or disabled. - This parameter can be a value of @ref DAC_output_buffer */ - -} DAC_ChannelConfTypeDef; - -#if (USE_HAL_DAC_REGISTER_CALLBACKS == 1) -/** - * @brief HAL DAC Callback ID enumeration definition - */ -typedef enum -{ - HAL_DAC_CH1_COMPLETE_CB_ID = 0x00U, /*!< DAC CH1 Complete Callback ID */ - HAL_DAC_CH1_HALF_COMPLETE_CB_ID = 0x01U, /*!< DAC CH1 half Complete Callback ID */ - HAL_DAC_CH1_ERROR_ID = 0x02U, /*!< DAC CH1 error Callback ID */ - HAL_DAC_CH1_UNDERRUN_CB_ID = 0x03U, /*!< DAC CH1 underrun Callback ID */ -#if defined(DAC_CHANNEL2_SUPPORT) - HAL_DAC_CH2_COMPLETE_CB_ID = 0x04U, /*!< DAC CH2 Complete Callback ID */ - HAL_DAC_CH2_HALF_COMPLETE_CB_ID = 0x05U, /*!< DAC CH2 half Complete Callback ID */ - HAL_DAC_CH2_ERROR_ID = 0x06U, /*!< DAC CH2 error Callback ID */ - HAL_DAC_CH2_UNDERRUN_CB_ID = 0x07U, /*!< DAC CH2 underrun Callback ID */ -#endif /* DAC_CHANNEL2_SUPPORT */ - HAL_DAC_MSPINIT_CB_ID = 0x08U, /*!< DAC MspInit Callback ID */ - HAL_DAC_MSPDEINIT_CB_ID = 0x09U, /*!< DAC MspDeInit Callback ID */ - HAL_DAC_ALL_CB_ID = 0x0AU /*!< DAC All ID */ -} HAL_DAC_CallbackIDTypeDef; - -/** - * @brief HAL DAC Callback pointer definition - */ -typedef void (*pDAC_CallbackTypeDef)(DAC_HandleTypeDef *hdac); -#endif /* USE_HAL_DAC_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ - -/** @defgroup DAC_Exported_Constants DAC Exported Constants - * @{ - */ - -/** @defgroup DAC_Error_Code DAC Error Code - * @{ - */ -#define HAL_DAC_ERROR_NONE 0x00U /*!< No error */ -#define HAL_DAC_ERROR_DMAUNDERRUNCH1 0x01U /*!< DAC channel1 DMA underrun error */ -#if defined(DAC_CHANNEL2_SUPPORT) -#define HAL_DAC_ERROR_DMAUNDERRUNCH2 0x02U /*!< DAC channel2 DMA underrun error */ -#endif /* DAC_CHANNEL2_SUPPORT */ -#define HAL_DAC_ERROR_DMA 0x04U /*!< DMA error */ -#define HAL_DAC_ERROR_TIMEOUT 0x08U /*!< Timeout error */ -#if (USE_HAL_DAC_REGISTER_CALLBACKS == 1) -#define HAL_DAC_ERROR_INVALID_CALLBACK 0x10U /*!< Invalid callback error */ -#endif /* USE_HAL_DAC_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @defgroup DAC_trigger_selection DAC trigger selection - * @{ - */ -#define DAC_TRIGGER_NONE 0x00000000UL /*!< Conversion is automatic once the DAC1_DHRxxxx register has been loaded, and not by external trigger */ -#define DAC_TRIGGER_T2_TRGO (DAC_CR_TSEL1_2 | DAC_CR_TEN1) /*!< TIM2 TRGO selected as external conversion trigger for DAC channel */ -#define DAC_TRIGGER_T4_TRGO (DAC_CR_TSEL1_2 | DAC_CR_TSEL1_0 | DAC_CR_TEN1) /*!< TIM4 TRGO selected as external conversion trigger for DAC channel */ -#define DAC_TRIGGER_T5_TRGO ( DAC_CR_TSEL1_1 | DAC_CR_TSEL1_0 | DAC_CR_TEN1) /*!< TIM3 TRGO selected as external conversion trigger for DAC channel */ -#define DAC_TRIGGER_T6_TRGO ( DAC_CR_TEN1) /*!< Conversion started by software trigger for DAC channel */ -#define DAC_TRIGGER_T7_TRGO ( DAC_CR_TSEL1_1 | DAC_CR_TEN1) /*!< TIM7 TRGO selected as external conversion trigger for DAC channel */ -#define DAC_TRIGGER_T8_TRGO ( DAC_CR_TSEL1_0 | DAC_CR_TEN1) /*!< TIM8 TRGO selected as external conversion trigger for DAC channel */ -#define DAC_TRIGGER_EXT_IT9 (DAC_CR_TSEL1_2 | DAC_CR_TSEL1_1 | DAC_CR_TEN1) /*!< EXTI Line9 event selected as external conversion trigger for DAC channel */ -#define DAC_TRIGGER_SOFTWARE (DAC_CR_TSEL1 | DAC_CR_TEN1) /*!< Conversion started by software trigger for DAC channel */ - -/** - * @} - */ - -/** @defgroup DAC_output_buffer DAC output buffer - * @{ - */ -#define DAC_OUTPUTBUFFER_ENABLE 0x00000000U -#define DAC_OUTPUTBUFFER_DISABLE (DAC_CR_BOFF1) - -/** - * @} - */ - -/** @defgroup DAC_Channel_selection DAC Channel selection - * @{ - */ -#define DAC_CHANNEL_1 0x00000000U -#if defined(DAC_CHANNEL2_SUPPORT) -#define DAC_CHANNEL_2 0x00000010U -#endif /* DAC_CHANNEL2_SUPPORT */ -/** - * @} - */ - -/** @defgroup DAC_data_alignment DAC data alignment - * @{ - */ -#define DAC_ALIGN_12B_R 0x00000000U -#define DAC_ALIGN_12B_L 0x00000004U -#define DAC_ALIGN_8B_R 0x00000008U - -/** - * @} - */ - -/** @defgroup DAC_flags_definition DAC flags definition - * @{ - */ -#define DAC_FLAG_DMAUDR1 (DAC_SR_DMAUDR1) -#if defined(DAC_CHANNEL2_SUPPORT) -#define DAC_FLAG_DMAUDR2 (DAC_SR_DMAUDR2) -#endif /* DAC_CHANNEL2_SUPPORT */ - -/** - * @} - */ - -/** @defgroup DAC_IT_definition DAC IT definition - * @{ - */ -#define DAC_IT_DMAUDR1 (DAC_SR_DMAUDR1) -#if defined(DAC_CHANNEL2_SUPPORT) -#define DAC_IT_DMAUDR2 (DAC_SR_DMAUDR2) -#endif /* DAC_CHANNEL2_SUPPORT */ - -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ - -/** @defgroup DAC_Exported_Macros DAC Exported Macros - * @{ - */ - -/** @brief Reset DAC handle state. - * @param __HANDLE__ specifies the DAC handle. - * @retval None - */ -#if (USE_HAL_DAC_REGISTER_CALLBACKS == 1) -#define __HAL_DAC_RESET_HANDLE_STATE(__HANDLE__) do { \ - (__HANDLE__)->State = HAL_DAC_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_DAC_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_DAC_STATE_RESET) -#endif /* USE_HAL_DAC_REGISTER_CALLBACKS */ - -/** @brief Enable the DAC channel. - * @param __HANDLE__ specifies the DAC handle. - * @param __DAC_Channel__ specifies the DAC channel - * @retval None - */ -#define __HAL_DAC_ENABLE(__HANDLE__, __DAC_Channel__) \ - ((__HANDLE__)->Instance->CR |= (DAC_CR_EN1 << ((__DAC_Channel__) & 0x10UL))) - -/** @brief Disable the DAC channel. - * @param __HANDLE__ specifies the DAC handle - * @param __DAC_Channel__ specifies the DAC channel. - * @retval None - */ -#define __HAL_DAC_DISABLE(__HANDLE__, __DAC_Channel__) \ - ((__HANDLE__)->Instance->CR &= ~(DAC_CR_EN1 << ((__DAC_Channel__) & 0x10UL))) - -/** @brief Set DHR12R1 alignment. - * @param __ALIGNMENT__ specifies the DAC alignment - * @retval None - */ -#define DAC_DHR12R1_ALIGNMENT(__ALIGNMENT__) (0x00000008UL + (__ALIGNMENT__)) - -#if defined(DAC_CHANNEL2_SUPPORT) -/** @brief Set DHR12R2 alignment. - * @param __ALIGNMENT__ specifies the DAC alignment - * @retval None - */ -#define DAC_DHR12R2_ALIGNMENT(__ALIGNMENT__) (0x00000014UL + (__ALIGNMENT__)) -#endif /* DAC_CHANNEL2_SUPPORT */ - -/** @brief Set DHR12RD alignment. - * @param __ALIGNMENT__ specifies the DAC alignment - * @retval None - */ -#define DAC_DHR12RD_ALIGNMENT(__ALIGNMENT__) (0x00000020UL + (__ALIGNMENT__)) - -/** @brief Enable the DAC interrupt. - * @param __HANDLE__ specifies the DAC handle - * @param __INTERRUPT__ specifies the DAC interrupt. - * This parameter can be any combination of the following values: - * @arg DAC_IT_DMAUDR1 DAC channel 1 DMA underrun interrupt - * @arg DAC_IT_DMAUDR2 DAC channel 2 DMA underrun interrupt - * @retval None - */ -#define __HAL_DAC_ENABLE_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->CR) |= (__INTERRUPT__)) - -/** @brief Disable the DAC interrupt. - * @param __HANDLE__ specifies the DAC handle - * @param __INTERRUPT__ specifies the DAC interrupt. - * This parameter can be any combination of the following values: - * @arg DAC_IT_DMAUDR1 DAC channel 1 DMA underrun interrupt - * @arg DAC_IT_DMAUDR2 DAC channel 2 DMA underrun interrupt - * @retval None - */ -#define __HAL_DAC_DISABLE_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->CR) &= ~(__INTERRUPT__)) - -/** @brief Check whether the specified DAC interrupt source is enabled or not. - * @param __HANDLE__ DAC handle - * @param __INTERRUPT__ DAC interrupt source to check - * This parameter can be any combination of the following values: - * @arg DAC_IT_DMAUDR1 DAC channel 1 DMA underrun interrupt - * @arg DAC_IT_DMAUDR2 DAC channel 2 DMA underrun interrupt - * @retval State of interruption (SET or RESET) - */ -#define __HAL_DAC_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->CR\ - & (__INTERRUPT__)) == (__INTERRUPT__)) - -/** @brief Get the selected DAC's flag status. - * @param __HANDLE__ specifies the DAC handle. - * @param __FLAG__ specifies the DAC flag to get. - * This parameter can be any combination of the following values: - * @arg DAC_FLAG_DMAUDR1 DAC channel 1 DMA underrun flag - * @arg DAC_FLAG_DMAUDR2 DAC channel 2 DMA underrun flag - * @retval None - */ -#define __HAL_DAC_GET_FLAG(__HANDLE__, __FLAG__) ((((__HANDLE__)->Instance->SR) & (__FLAG__)) == (__FLAG__)) - -/** @brief Clear the DAC's flag. - * @param __HANDLE__ specifies the DAC handle. - * @param __FLAG__ specifies the DAC flag to clear. - * This parameter can be any combination of the following values: - * @arg DAC_FLAG_DMAUDR1 DAC channel 1 DMA underrun flag - * @arg DAC_FLAG_DMAUDR2 DAC channel 2 DMA underrun flag - * @retval None - */ -#define __HAL_DAC_CLEAR_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->SR) = (__FLAG__)) - -/** - * @} - */ - -/* Private macro -------------------------------------------------------------*/ - -/** @defgroup DAC_Private_Macros DAC Private Macros - * @{ - */ -#define IS_DAC_OUTPUT_BUFFER_STATE(STATE) (((STATE) == DAC_OUTPUTBUFFER_ENABLE) || \ - ((STATE) == DAC_OUTPUTBUFFER_DISABLE)) - -#if defined(DAC_CHANNEL2_SUPPORT) -#define IS_DAC_CHANNEL(CHANNEL) (((CHANNEL) == DAC_CHANNEL_1) || \ - ((CHANNEL) == DAC_CHANNEL_2)) -#else -#define IS_DAC_CHANNEL(CHANNEL) ((CHANNEL) == DAC_CHANNEL_1) -#endif /* DAC_CHANNEL2_SUPPORT */ - -#define IS_DAC_ALIGN(ALIGN) (((ALIGN) == DAC_ALIGN_12B_R) || \ - ((ALIGN) == DAC_ALIGN_12B_L) || \ - ((ALIGN) == DAC_ALIGN_8B_R)) - -#define IS_DAC_DATA(DATA) ((DATA) <= 0xFFF0UL) - -/** - * @} - */ - -/* Include DAC HAL Extended module */ -#include "stm32f4xx_hal_dac_ex.h" - -/* Exported functions --------------------------------------------------------*/ - -/** @addtogroup DAC_Exported_Functions - * @{ - */ - -/** @addtogroup DAC_Exported_Functions_Group1 - * @{ - */ -/* Initialization and de-initialization functions *****************************/ -HAL_StatusTypeDef HAL_DAC_Init(DAC_HandleTypeDef *hdac); -HAL_StatusTypeDef HAL_DAC_DeInit(DAC_HandleTypeDef *hdac); -void HAL_DAC_MspInit(DAC_HandleTypeDef *hdac); -void HAL_DAC_MspDeInit(DAC_HandleTypeDef *hdac); - -/** - * @} - */ - -/** @addtogroup DAC_Exported_Functions_Group2 - * @{ - */ -/* IO operation functions *****************************************************/ -HAL_StatusTypeDef HAL_DAC_Start(DAC_HandleTypeDef *hdac, uint32_t Channel); -HAL_StatusTypeDef HAL_DAC_Stop(DAC_HandleTypeDef *hdac, uint32_t Channel); -HAL_StatusTypeDef HAL_DAC_Start_DMA(DAC_HandleTypeDef *hdac, uint32_t Channel, uint32_t *pData, uint32_t Length, - uint32_t Alignment); -HAL_StatusTypeDef HAL_DAC_Stop_DMA(DAC_HandleTypeDef *hdac, uint32_t Channel); -void HAL_DAC_IRQHandler(DAC_HandleTypeDef *hdac); -HAL_StatusTypeDef HAL_DAC_SetValue(DAC_HandleTypeDef *hdac, uint32_t Channel, uint32_t Alignment, uint32_t Data); - -void HAL_DAC_ConvCpltCallbackCh1(DAC_HandleTypeDef *hdac); -void HAL_DAC_ConvHalfCpltCallbackCh1(DAC_HandleTypeDef *hdac); -void HAL_DAC_ErrorCallbackCh1(DAC_HandleTypeDef *hdac); -void HAL_DAC_DMAUnderrunCallbackCh1(DAC_HandleTypeDef *hdac); - -#if (USE_HAL_DAC_REGISTER_CALLBACKS == 1) -/* DAC callback registering/unregistering */ -HAL_StatusTypeDef HAL_DAC_RegisterCallback(DAC_HandleTypeDef *hdac, HAL_DAC_CallbackIDTypeDef CallbackID, - pDAC_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_DAC_UnRegisterCallback(DAC_HandleTypeDef *hdac, HAL_DAC_CallbackIDTypeDef CallbackID); -#endif /* USE_HAL_DAC_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @addtogroup DAC_Exported_Functions_Group3 - * @{ - */ -/* Peripheral Control functions ***********************************************/ -uint32_t HAL_DAC_GetValue(DAC_HandleTypeDef *hdac, uint32_t Channel); -HAL_StatusTypeDef HAL_DAC_ConfigChannel(DAC_HandleTypeDef *hdac, DAC_ChannelConfTypeDef *sConfig, uint32_t Channel); -/** - * @} - */ - -/** @addtogroup DAC_Exported_Functions_Group4 - * @{ - */ -/* Peripheral State and Error functions ***************************************/ -HAL_DAC_StateTypeDef HAL_DAC_GetState(DAC_HandleTypeDef *hdac); -uint32_t HAL_DAC_GetError(DAC_HandleTypeDef *hdac); - -/** - * @} - */ - -/** - * @} - */ - -/** @defgroup DAC_Private_Functions DAC Private Functions - * @{ - */ -void DAC_DMAConvCpltCh1(DMA_HandleTypeDef *hdma); -void DAC_DMAErrorCh1(DMA_HandleTypeDef *hdma); -void DAC_DMAHalfConvCpltCh1(DMA_HandleTypeDef *hdma); -/** - * @} - */ - -/** - * @} - */ - -#endif /* DAC */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - - -#endif /* STM32F4xx_HAL_DAC_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dac_ex.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dac_ex.h deleted file mode 100644 index 03159d4..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dac_ex.h +++ /dev/null @@ -1,207 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_dac_ex.h - * @author MCD Application Team - * @brief Header file of DAC HAL Extended module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_DAC_EX_H -#define STM32F4xx_HAL_DAC_EX_H - -#ifdef __cplusplus -extern "C" { -#endif - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -#if defined(DAC) - -/** @addtogroup DACEx - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ - -/** - * @brief HAL State structures definition - */ - -/* Exported constants --------------------------------------------------------*/ - -/** @defgroup DACEx_Exported_Constants DACEx Exported Constants - * @{ - */ - -/** @defgroup DACEx_lfsrunmask_triangleamplitude DACEx lfsrunmask triangle amplitude - * @{ - */ -#define DAC_LFSRUNMASK_BIT0 0x00000000UL /*!< Unmask DAC channel LFSR bit0 for noise wave generation */ -#define DAC_LFSRUNMASK_BITS1_0 ( DAC_CR_MAMP1_0) /*!< Unmask DAC channel LFSR bit[1:0] for noise wave generation */ -#define DAC_LFSRUNMASK_BITS2_0 ( DAC_CR_MAMP1_1 ) /*!< Unmask DAC channel LFSR bit[2:0] for noise wave generation */ -#define DAC_LFSRUNMASK_BITS3_0 ( DAC_CR_MAMP1_1 | DAC_CR_MAMP1_0) /*!< Unmask DAC channel LFSR bit[3:0] for noise wave generation */ -#define DAC_LFSRUNMASK_BITS4_0 ( DAC_CR_MAMP1_2 ) /*!< Unmask DAC channel LFSR bit[4:0] for noise wave generation */ -#define DAC_LFSRUNMASK_BITS5_0 ( DAC_CR_MAMP1_2 | DAC_CR_MAMP1_0) /*!< Unmask DAC channel LFSR bit[5:0] for noise wave generation */ -#define DAC_LFSRUNMASK_BITS6_0 ( DAC_CR_MAMP1_2 | DAC_CR_MAMP1_1 ) /*!< Unmask DAC channel LFSR bit[6:0] for noise wave generation */ -#define DAC_LFSRUNMASK_BITS7_0 ( DAC_CR_MAMP1_2 | DAC_CR_MAMP1_1 | DAC_CR_MAMP1_0) /*!< Unmask DAC channel LFSR bit[7:0] for noise wave generation */ -#define DAC_LFSRUNMASK_BITS8_0 (DAC_CR_MAMP1_3 ) /*!< Unmask DAC channel LFSR bit[8:0] for noise wave generation */ -#define DAC_LFSRUNMASK_BITS9_0 (DAC_CR_MAMP1_3 | DAC_CR_MAMP1_0) /*!< Unmask DAC channel LFSR bit[9:0] for noise wave generation */ -#define DAC_LFSRUNMASK_BITS10_0 (DAC_CR_MAMP1_3 | DAC_CR_MAMP1_1 ) /*!< Unmask DAC channel LFSR bit[10:0] for noise wave generation */ -#define DAC_LFSRUNMASK_BITS11_0 (DAC_CR_MAMP1_3 | DAC_CR_MAMP1_1 | DAC_CR_MAMP1_0) /*!< Unmask DAC channel LFSR bit[11:0] for noise wave generation */ -#define DAC_TRIANGLEAMPLITUDE_1 0x00000000UL /*!< Select max triangle amplitude of 1 */ -#define DAC_TRIANGLEAMPLITUDE_3 ( DAC_CR_MAMP1_0) /*!< Select max triangle amplitude of 3 */ -#define DAC_TRIANGLEAMPLITUDE_7 ( DAC_CR_MAMP1_1 ) /*!< Select max triangle amplitude of 7 */ -#define DAC_TRIANGLEAMPLITUDE_15 ( DAC_CR_MAMP1_1 | DAC_CR_MAMP1_0) /*!< Select max triangle amplitude of 15 */ -#define DAC_TRIANGLEAMPLITUDE_31 ( DAC_CR_MAMP1_2 ) /*!< Select max triangle amplitude of 31 */ -#define DAC_TRIANGLEAMPLITUDE_63 ( DAC_CR_MAMP1_2 | DAC_CR_MAMP1_0) /*!< Select max triangle amplitude of 63 */ -#define DAC_TRIANGLEAMPLITUDE_127 ( DAC_CR_MAMP1_2 | DAC_CR_MAMP1_1 ) /*!< Select max triangle amplitude of 127 */ -#define DAC_TRIANGLEAMPLITUDE_255 ( DAC_CR_MAMP1_2 | DAC_CR_MAMP1_1 | DAC_CR_MAMP1_0) /*!< Select max triangle amplitude of 255 */ -#define DAC_TRIANGLEAMPLITUDE_511 (DAC_CR_MAMP1_3 ) /*!< Select max triangle amplitude of 511 */ -#define DAC_TRIANGLEAMPLITUDE_1023 (DAC_CR_MAMP1_3 | DAC_CR_MAMP1_0) /*!< Select max triangle amplitude of 1023 */ -#define DAC_TRIANGLEAMPLITUDE_2047 (DAC_CR_MAMP1_3 | DAC_CR_MAMP1_1 ) /*!< Select max triangle amplitude of 2047 */ -#define DAC_TRIANGLEAMPLITUDE_4095 (DAC_CR_MAMP1_3 | DAC_CR_MAMP1_1 | DAC_CR_MAMP1_0) /*!< Select max triangle amplitude of 4095 */ - -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ - - -/* Private macro -------------------------------------------------------------*/ - -/** @defgroup DACEx_Private_Macros DACEx Private Macros - * @{ - */ -#define IS_DAC_TRIGGER(TRIGGER) (((TRIGGER) == DAC_TRIGGER_NONE) || \ - ((TRIGGER) == DAC_TRIGGER_T2_TRGO) || \ - ((TRIGGER) == DAC_TRIGGER_T8_TRGO) || \ - ((TRIGGER) == DAC_TRIGGER_T7_TRGO) || \ - ((TRIGGER) == DAC_TRIGGER_T5_TRGO) || \ - ((TRIGGER) == DAC_TRIGGER_T6_TRGO) || \ - ((TRIGGER) == DAC_TRIGGER_T4_TRGO) || \ - ((TRIGGER) == DAC_TRIGGER_EXT_IT9) || \ - ((TRIGGER) == DAC_TRIGGER_SOFTWARE)) - -#define IS_DAC_LFSR_UNMASK_TRIANGLE_AMPLITUDE(VALUE) (((VALUE) == DAC_LFSRUNMASK_BIT0) || \ - ((VALUE) == DAC_LFSRUNMASK_BITS1_0) || \ - ((VALUE) == DAC_LFSRUNMASK_BITS2_0) || \ - ((VALUE) == DAC_LFSRUNMASK_BITS3_0) || \ - ((VALUE) == DAC_LFSRUNMASK_BITS4_0) || \ - ((VALUE) == DAC_LFSRUNMASK_BITS5_0) || \ - ((VALUE) == DAC_LFSRUNMASK_BITS6_0) || \ - ((VALUE) == DAC_LFSRUNMASK_BITS7_0) || \ - ((VALUE) == DAC_LFSRUNMASK_BITS8_0) || \ - ((VALUE) == DAC_LFSRUNMASK_BITS9_0) || \ - ((VALUE) == DAC_LFSRUNMASK_BITS10_0) || \ - ((VALUE) == DAC_LFSRUNMASK_BITS11_0) || \ - ((VALUE) == DAC_TRIANGLEAMPLITUDE_1) || \ - ((VALUE) == DAC_TRIANGLEAMPLITUDE_3) || \ - ((VALUE) == DAC_TRIANGLEAMPLITUDE_7) || \ - ((VALUE) == DAC_TRIANGLEAMPLITUDE_15) || \ - ((VALUE) == DAC_TRIANGLEAMPLITUDE_31) || \ - ((VALUE) == DAC_TRIANGLEAMPLITUDE_63) || \ - ((VALUE) == DAC_TRIANGLEAMPLITUDE_127) || \ - ((VALUE) == DAC_TRIANGLEAMPLITUDE_255) || \ - ((VALUE) == DAC_TRIANGLEAMPLITUDE_511) || \ - ((VALUE) == DAC_TRIANGLEAMPLITUDE_1023) || \ - ((VALUE) == DAC_TRIANGLEAMPLITUDE_2047) || \ - ((VALUE) == DAC_TRIANGLEAMPLITUDE_4095)) -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/* Extended features functions ***********************************************/ - -/** @addtogroup DACEx_Exported_Functions - * @{ - */ - -/** @addtogroup DACEx_Exported_Functions_Group2 - * @{ - */ -/* IO operation functions *****************************************************/ - -HAL_StatusTypeDef HAL_DACEx_TriangleWaveGenerate(DAC_HandleTypeDef *hdac, uint32_t Channel, uint32_t Amplitude); -HAL_StatusTypeDef HAL_DACEx_NoiseWaveGenerate(DAC_HandleTypeDef *hdac, uint32_t Channel, uint32_t Amplitude); - -#if defined(DAC_CHANNEL2_SUPPORT) -#endif -HAL_StatusTypeDef HAL_DACEx_DualStart(DAC_HandleTypeDef *hdac); -HAL_StatusTypeDef HAL_DACEx_DualStop(DAC_HandleTypeDef *hdac); -HAL_StatusTypeDef HAL_DACEx_DualSetValue(DAC_HandleTypeDef *hdac, uint32_t Alignment, uint32_t Data1, uint32_t Data2); -uint32_t HAL_DACEx_DualGetValue(DAC_HandleTypeDef *hdac); - -#if defined(DAC_CHANNEL2_SUPPORT) -#endif -void HAL_DACEx_ConvCpltCallbackCh2(DAC_HandleTypeDef *hdac); -void HAL_DACEx_ConvHalfCpltCallbackCh2(DAC_HandleTypeDef *hdac); -void HAL_DACEx_ErrorCallbackCh2(DAC_HandleTypeDef *hdac); -void HAL_DACEx_DMAUnderrunCallbackCh2(DAC_HandleTypeDef *hdac); - - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** @addtogroup DACEx_Private_Functions - * @{ - */ -#if defined(DAC_CHANNEL2_SUPPORT) -/* DAC_DMAConvCpltCh2 / DAC_DMAErrorCh2 / DAC_DMAHalfConvCpltCh2 */ -/* are called by HAL_DAC_Start_DMA */ -void DAC_DMAConvCpltCh2(DMA_HandleTypeDef *hdma); -void DAC_DMAErrorCh2(DMA_HandleTypeDef *hdma); -void DAC_DMAHalfConvCpltCh2(DMA_HandleTypeDef *hdma); -#endif /* DAC_CHANNEL2_SUPPORT */ -/** - * @} - */ - -/** - * @} - */ - -#endif /* DAC */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_HAL_DAC_EX_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dcmi.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dcmi.h deleted file mode 100644 index 2a9edb6..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dcmi.h +++ /dev/null @@ -1,567 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_dcmi.h - * @author MCD Application Team - * @brief Header file of DCMI HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_DCMI_H -#define __STM32F4xx_HAL_DCMI_H - -#ifdef __cplusplus - extern "C" { -#endif - -#if defined(STM32F407xx) || defined(STM32F417xx) || defined(STM32F427xx) || defined(STM32F437xx) ||\ - defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F446xx) || defined(STM32F469xx) ||\ - defined(STM32F479xx) -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/* Include DCMI HAL Extended module */ -/* (include on top of file since DCMI structures are defined in extended file) */ -#include "stm32f4xx_hal_dcmi_ex.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup DCMI DCMI - * @brief DCMI HAL module driver - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup DCMI_Exported_Types DCMI Exported Types - * @{ - */ -/** - * @brief DCMI Embedded Synchronisation CODE Init structure definition - */ -typedef struct -{ - uint8_t FrameStartUnmask; /*!< Specifies the frame start delimiter unmask. */ - uint8_t LineStartUnmask; /*!< Specifies the line start delimiter unmask. */ - uint8_t LineEndUnmask; /*!< Specifies the line end delimiter unmask. */ - uint8_t FrameEndUnmask; /*!< Specifies the frame end delimiter unmask. */ -}DCMI_SyncUnmaskTypeDef; -/** - * @brief HAL DCMI State structures definition - */ -typedef enum -{ - HAL_DCMI_STATE_RESET = 0x00U, /*!< DCMI not yet initialized or disabled */ - HAL_DCMI_STATE_READY = 0x01U, /*!< DCMI initialized and ready for use */ - HAL_DCMI_STATE_BUSY = 0x02U, /*!< DCMI internal processing is ongoing */ - HAL_DCMI_STATE_TIMEOUT = 0x03U, /*!< DCMI timeout state */ - HAL_DCMI_STATE_ERROR = 0x04U, /*!< DCMI error state */ - HAL_DCMI_STATE_SUSPENDED = 0x05U /*!< DCMI suspend state */ -}HAL_DCMI_StateTypeDef; - -/** - * @brief DCMI handle Structure definition - */ -typedef struct __DCMI_HandleTypeDef -{ - DCMI_TypeDef *Instance; /*!< DCMI Register base address */ - - DCMI_InitTypeDef Init; /*!< DCMI parameters */ - - HAL_LockTypeDef Lock; /*!< DCMI locking object */ - - __IO HAL_DCMI_StateTypeDef State; /*!< DCMI state */ - - __IO uint32_t XferCount; /*!< DMA transfer counter */ - - __IO uint32_t XferSize; /*!< DMA transfer size */ - - uint32_t XferTransferNumber; /*!< DMA transfer number */ - - uint32_t pBuffPtr; /*!< Pointer to DMA output buffer */ - - DMA_HandleTypeDef *DMA_Handle; /*!< Pointer to the DMA handler */ - - __IO uint32_t ErrorCode; /*!< DCMI Error code */ -#if (USE_HAL_DCMI_REGISTER_CALLBACKS == 1) - void (* FrameEventCallback) ( struct __DCMI_HandleTypeDef *hdcmi); /*!< DCMI Frame Event Callback */ - void (* VsyncEventCallback) ( struct __DCMI_HandleTypeDef *hdcmi); /*!< DCMI Vsync Event Callback */ - void (* LineEventCallback ) ( struct __DCMI_HandleTypeDef *hdcmi); /*!< DCMI Line Event Callback */ - void (* ErrorCallback) ( struct __DCMI_HandleTypeDef *hdcmi); /*!< DCMI Error Callback */ - void (* MspInitCallback) ( struct __DCMI_HandleTypeDef *hdcmi); /*!< DCMI Msp Init callback */ - void (* MspDeInitCallback) ( struct __DCMI_HandleTypeDef *hdcmi); /*!< DCMI Msp DeInit callback */ -#endif /* USE_HAL_DCMI_REGISTER_CALLBACKS */ -}DCMI_HandleTypeDef; - -#if (USE_HAL_DCMI_REGISTER_CALLBACKS == 1) -typedef enum -{ - HAL_DCMI_FRAME_EVENT_CB_ID = 0x00U, /*!< DCMI Frame Event Callback ID */ - HAL_DCMI_VSYNC_EVENT_CB_ID = 0x01U, /*!< DCMI Vsync Event Callback ID */ - HAL_DCMI_LINE_EVENT_CB_ID = 0x02U, /*!< DCMI Line Event Callback ID */ - HAL_DCMI_ERROR_CB_ID = 0x03U, /*!< DCMI Error Callback ID */ - HAL_DCMI_MSPINIT_CB_ID = 0x04U, /*!< DCMI MspInit callback ID */ - HAL_DCMI_MSPDEINIT_CB_ID = 0x05U /*!< DCMI MspDeInit callback ID */ - -}HAL_DCMI_CallbackIDTypeDef; - -typedef void (*pDCMI_CallbackTypeDef)(DCMI_HandleTypeDef *hdcmi); -#endif /* USE_HAL_DCMI_REGISTER_CALLBACKS */ - - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup DCMI_Exported_Constants DCMI Exported Constants - * @{ - */ - -/** @defgroup DCMI_Error_Code DCMI Error Code - * @{ - */ -#define HAL_DCMI_ERROR_NONE 0x00000000U /*!< No error */ -#define HAL_DCMI_ERROR_OVR 0x00000001U /*!< Overrun error */ -#define HAL_DCMI_ERROR_SYNC 0x00000002U /*!< Synchronization error */ -#define HAL_DCMI_ERROR_TIMEOUT 0x00000020U /*!< Timeout error */ -#define HAL_DCMI_ERROR_DMA 0x00000040U /*!< DMA error */ -#if (USE_HAL_DCMI_REGISTER_CALLBACKS == 1) -#define HAL_DCMI_ERROR_INVALID_CALLBACK ((uint32_t)0x00000080U) /*!< Invalid callback error */ -#endif -/** - * @} - */ - -/** @defgroup DCMI_Capture_Mode DCMI Capture Mode - * @{ - */ -#define DCMI_MODE_CONTINUOUS 0x00000000U /*!< The received data are transferred continuously - into the destination memory through the DMA */ -#define DCMI_MODE_SNAPSHOT ((uint32_t)DCMI_CR_CM) /*!< Once activated, the interface waits for the start of - frame and then transfers a single frame through the DMA */ -/** - * @} - */ - -/** @defgroup DCMI_Synchronization_Mode DCMI Synchronization Mode - * @{ - */ -#define DCMI_SYNCHRO_HARDWARE 0x00000000U /*!< Hardware synchronization data capture (frame/line start/stop) - is synchronized with the HSYNC/VSYNC signals */ -#define DCMI_SYNCHRO_EMBEDDED ((uint32_t)DCMI_CR_ESS) /*!< Embedded synchronization data capture is synchronized with - synchronization codes embedded in the data flow */ - -/** - * @} - */ - -/** @defgroup DCMI_PIXCK_Polarity DCMI PIXCK Polarity - * @{ - */ -#define DCMI_PCKPOLARITY_FALLING 0x00000000U /*!< Pixel clock active on Falling edge */ -#define DCMI_PCKPOLARITY_RISING ((uint32_t)DCMI_CR_PCKPOL) /*!< Pixel clock active on Rising edge */ - -/** - * @} - */ - -/** @defgroup DCMI_VSYNC_Polarity DCMI VSYNC Polarity - * @{ - */ -#define DCMI_VSPOLARITY_LOW 0x00000000U /*!< Vertical synchronization active Low */ -#define DCMI_VSPOLARITY_HIGH ((uint32_t)DCMI_CR_VSPOL) /*!< Vertical synchronization active High */ - -/** - * @} - */ - -/** @defgroup DCMI_HSYNC_Polarity DCMI HSYNC Polarity - * @{ - */ -#define DCMI_HSPOLARITY_LOW 0x00000000U /*!< Horizontal synchronization active Low */ -#define DCMI_HSPOLARITY_HIGH ((uint32_t)DCMI_CR_HSPOL) /*!< Horizontal synchronization active High */ - -/** - * @} - */ - -/** @defgroup DCMI_MODE_JPEG DCMI MODE JPEG - * @{ - */ -#define DCMI_JPEG_DISABLE 0x00000000U /*!< Mode JPEG Disabled */ -#define DCMI_JPEG_ENABLE ((uint32_t)DCMI_CR_JPEG) /*!< Mode JPEG Enabled */ - -/** - * @} - */ - -/** @defgroup DCMI_Capture_Rate DCMI Capture Rate - * @{ - */ -#define DCMI_CR_ALL_FRAME 0x00000000U /*!< All frames are captured */ -#define DCMI_CR_ALTERNATE_2_FRAME ((uint32_t)DCMI_CR_FCRC_0) /*!< Every alternate frame captured */ -#define DCMI_CR_ALTERNATE_4_FRAME ((uint32_t)DCMI_CR_FCRC_1) /*!< One frame in 4 frames captured */ - -/** - * @} - */ - -/** @defgroup DCMI_Extended_Data_Mode DCMI Extended Data Mode - * @{ - */ -#define DCMI_EXTEND_DATA_8B 0x00000000U /*!< Interface captures 8-bit data on every pixel clock */ -#define DCMI_EXTEND_DATA_10B ((uint32_t)DCMI_CR_EDM_0) /*!< Interface captures 10-bit data on every pixel clock */ -#define DCMI_EXTEND_DATA_12B ((uint32_t)DCMI_CR_EDM_1) /*!< Interface captures 12-bit data on every pixel clock */ -#define DCMI_EXTEND_DATA_14B ((uint32_t)(DCMI_CR_EDM_0 | DCMI_CR_EDM_1)) /*!< Interface captures 14-bit data on every pixel clock */ - -/** - * @} - */ - -/** @defgroup DCMI_Window_Coordinate DCMI Window Coordinate - * @{ - */ -#define DCMI_WINDOW_COORDINATE 0x3FFFU /*!< Window coordinate */ - -/** - * @} - */ - -/** @defgroup DCMI_Window_Height DCMI Window Height - * @{ - */ -#define DCMI_WINDOW_HEIGHT 0x1FFFU /*!< Window Height */ - -/** - * @} - */ - -/** @defgroup DCMI_Window_Vertical_Line DCMI Window Vertical Line - * @{ - */ -#define DCMI_POSITION_CWSIZE_VLINE (uint32_t)DCMI_CWSIZE_VLINE_Pos /*!< Required left shift to set crop window vertical line count */ -#define DCMI_POSITION_CWSTRT_VST (uint32_t)DCMI_CWSTRT_VST_Pos /*!< Required left shift to set crop window vertical start line count */ - -/** - * @} - */ - -/** @defgroup DCMI_interrupt_sources DCMI interrupt sources - * @{ - */ -#define DCMI_IT_FRAME ((uint32_t)DCMI_IER_FRAME_IE) /*!< Capture complete interrupt */ -#define DCMI_IT_OVR ((uint32_t)DCMI_IER_OVR_IE) /*!< Overrun interrupt */ -#define DCMI_IT_ERR ((uint32_t)DCMI_IER_ERR_IE) /*!< Synchronization error interrupt */ -#define DCMI_IT_VSYNC ((uint32_t)DCMI_IER_VSYNC_IE) /*!< VSYNC interrupt */ -#define DCMI_IT_LINE ((uint32_t)DCMI_IER_LINE_IE) /*!< Line interrupt */ -/** - * @} - */ - -/** @defgroup DCMI_Flags DCMI Flags - * @{ - */ - -/** - * @brief DCMI SR register - */ -#define DCMI_FLAG_HSYNC ((uint32_t)DCMI_SR_INDEX|DCMI_SR_HSYNC) /*!< HSYNC pin state (active line / synchronization between lines) */ -#define DCMI_FLAG_VSYNC ((uint32_t)DCMI_SR_INDEX|DCMI_SR_VSYNC) /*!< VSYNC pin state (active frame / synchronization between frames) */ -#define DCMI_FLAG_FNE ((uint32_t)DCMI_SR_INDEX|DCMI_SR_FNE) /*!< FIFO not empty flag */ -/** - * @brief DCMI RIS register - */ -#define DCMI_FLAG_FRAMERI ((uint32_t)DCMI_RISR_FRAME_RIS) /*!< Frame capture complete interrupt flag */ -#define DCMI_FLAG_OVRRI ((uint32_t)DCMI_RISR_OVR_RIS) /*!< Overrun interrupt flag */ -#define DCMI_FLAG_ERRRI ((uint32_t)DCMI_RISR_ERR_RIS) /*!< Synchronization error interrupt flag */ -#define DCMI_FLAG_VSYNCRI ((uint32_t)DCMI_RISR_VSYNC_RIS) /*!< VSYNC interrupt flag */ -#define DCMI_FLAG_LINERI ((uint32_t)DCMI_RISR_LINE_RIS) /*!< Line interrupt flag */ -/** - * @brief DCMI MIS register - */ -#define DCMI_FLAG_FRAMEMI ((uint32_t)DCMI_MIS_INDEX|DCMI_MIS_FRAME_MIS) /*!< DCMI Frame capture complete masked interrupt status */ -#define DCMI_FLAG_OVRMI ((uint32_t)DCMI_MIS_INDEX|DCMI_MIS_OVR_MIS ) /*!< DCMI Overrun masked interrupt status */ -#define DCMI_FLAG_ERRMI ((uint32_t)DCMI_MIS_INDEX|DCMI_MIS_ERR_MIS ) /*!< DCMI Synchronization error masked interrupt status */ -#define DCMI_FLAG_VSYNCMI ((uint32_t)DCMI_MIS_INDEX|DCMI_MIS_VSYNC_MIS) /*!< DCMI VSYNC masked interrupt status */ -#define DCMI_FLAG_LINEMI ((uint32_t)DCMI_MIS_INDEX|DCMI_MIS_LINE_MIS ) /*!< DCMI Line masked interrupt status */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup DCMI_Exported_Macros DCMI Exported Macros - * @{ - */ - -/** @brief Reset DCMI handle state - * @param __HANDLE__ specifies the DCMI handle. - * @retval None - */ -#define __HAL_DCMI_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->State = HAL_DCMI_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) - -/** - * @brief Enable the DCMI. - * @param __HANDLE__ DCMI handle - * @retval None - */ -#define __HAL_DCMI_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= DCMI_CR_ENABLE) - -/** - * @brief Disable the DCMI. - * @param __HANDLE__ DCMI handle - * @retval None - */ -#define __HAL_DCMI_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR &= ~(DCMI_CR_ENABLE)) - -/* Interrupt & Flag management */ -/** - * @brief Get the DCMI pending flag. - * @param __HANDLE__ DCMI handle - * @param __FLAG__ Get the specified flag. - * This parameter can be one of the following values (no combination allowed) - * @arg DCMI_FLAG_HSYNC: HSYNC pin state (active line / synchronization between lines) - * @arg DCMI_FLAG_VSYNC: VSYNC pin state (active frame / synchronization between frames) - * @arg DCMI_FLAG_FNE: FIFO empty flag - * @arg DCMI_FLAG_FRAMERI: Frame capture complete flag mask - * @arg DCMI_FLAG_OVRRI: Overrun flag mask - * @arg DCMI_FLAG_ERRRI: Synchronization error flag mask - * @arg DCMI_FLAG_VSYNCRI: VSYNC flag mask - * @arg DCMI_FLAG_LINERI: Line flag mask - * @arg DCMI_FLAG_FRAMEMI: DCMI Capture complete masked interrupt status - * @arg DCMI_FLAG_OVRMI: DCMI Overrun masked interrupt status - * @arg DCMI_FLAG_ERRMI: DCMI Synchronization error masked interrupt status - * @arg DCMI_FLAG_VSYNCMI: DCMI VSYNC masked interrupt status - * @arg DCMI_FLAG_LINEMI: DCMI Line masked interrupt status - * @retval The state of FLAG. - */ -#define __HAL_DCMI_GET_FLAG(__HANDLE__, __FLAG__)\ -((((__FLAG__) & (DCMI_SR_INDEX|DCMI_MIS_INDEX)) == 0x0U)? ((__HANDLE__)->Instance->RISR & (__FLAG__)) :\ - (((__FLAG__) & DCMI_SR_INDEX) == 0x0U)? ((__HANDLE__)->Instance->MISR & (__FLAG__)) : ((__HANDLE__)->Instance->SR & (__FLAG__))) - -/** - * @brief Clear the DCMI pending flags. - * @param __HANDLE__ DCMI handle - * @param __FLAG__ specifies the flag to clear. - * This parameter can be any combination of the following values: - * @arg DCMI_FLAG_FRAMERI: Frame capture complete flag mask - * @arg DCMI_FLAG_OVRRI: Overrun flag mask - * @arg DCMI_FLAG_ERRRI: Synchronization error flag mask - * @arg DCMI_FLAG_VSYNCRI: VSYNC flag mask - * @arg DCMI_FLAG_LINERI: Line flag mask - * @retval None - */ -#define __HAL_DCMI_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->ICR = (__FLAG__)) - -/** - * @brief Enable the specified DCMI interrupts. - * @param __HANDLE__ DCMI handle - * @param __INTERRUPT__ specifies the DCMI interrupt sources to be enabled. - * This parameter can be any combination of the following values: - * @arg DCMI_IT_FRAME: Frame capture complete interrupt mask - * @arg DCMI_IT_OVR: Overrun interrupt mask - * @arg DCMI_IT_ERR: Synchronization error interrupt mask - * @arg DCMI_IT_VSYNC: VSYNC interrupt mask - * @arg DCMI_IT_LINE: Line interrupt mask - * @retval None - */ -#define __HAL_DCMI_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->IER |= (__INTERRUPT__)) - -/** - * @brief Disable the specified DCMI interrupts. - * @param __HANDLE__ DCMI handle - * @param __INTERRUPT__ specifies the DCMI interrupt sources to be enabled. - * This parameter can be any combination of the following values: - * @arg DCMI_IT_FRAME: Frame capture complete interrupt mask - * @arg DCMI_IT_OVR: Overrun interrupt mask - * @arg DCMI_IT_ERR: Synchronization error interrupt mask - * @arg DCMI_IT_VSYNC: VSYNC interrupt mask - * @arg DCMI_IT_LINE: Line interrupt mask - * @retval None - */ -#define __HAL_DCMI_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->IER &= ~(__INTERRUPT__)) - -/** - * @brief Check whether the specified DCMI interrupt has occurred or not. - * @param __HANDLE__ DCMI handle - * @param __INTERRUPT__ specifies the DCMI interrupt source to check. - * This parameter can be one of the following values: - * @arg DCMI_IT_FRAME: Frame capture complete interrupt mask - * @arg DCMI_IT_OVR: Overrun interrupt mask - * @arg DCMI_IT_ERR: Synchronization error interrupt mask - * @arg DCMI_IT_VSYNC: VSYNC interrupt mask - * @arg DCMI_IT_LINE: Line interrupt mask - * @retval The state of INTERRUPT. - */ -#define __HAL_DCMI_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->MISR & (__INTERRUPT__)) - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup DCMI_Exported_Functions DCMI Exported Functions - * @{ - */ - -/** @addtogroup DCMI_Exported_Functions_Group1 Initialization and Configuration functions - * @{ - */ -/* Initialization and de-initialization functions *****************************/ -HAL_StatusTypeDef HAL_DCMI_Init(DCMI_HandleTypeDef *hdcmi); -HAL_StatusTypeDef HAL_DCMI_DeInit(DCMI_HandleTypeDef *hdcmi); -void HAL_DCMI_MspInit(DCMI_HandleTypeDef* hdcmi); -void HAL_DCMI_MspDeInit(DCMI_HandleTypeDef* hdcmi); - -/* Callbacks Register/UnRegister functions ***********************************/ -#if (USE_HAL_DCMI_REGISTER_CALLBACKS == 1) -HAL_StatusTypeDef HAL_DCMI_RegisterCallback(DCMI_HandleTypeDef *hdcmi, HAL_DCMI_CallbackIDTypeDef CallbackID, pDCMI_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_DCMI_UnRegisterCallback(DCMI_HandleTypeDef *hdcmi, HAL_DCMI_CallbackIDTypeDef CallbackID); -#endif /* USE_HAL_DCMI_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @addtogroup DCMI_Exported_Functions_Group2 IO operation functions - * @{ - */ -/* IO operation functions *****************************************************/ -HAL_StatusTypeDef HAL_DCMI_Start_DMA(DCMI_HandleTypeDef* hdcmi, uint32_t DCMI_Mode, uint32_t pData, uint32_t Length); -HAL_StatusTypeDef HAL_DCMI_Stop(DCMI_HandleTypeDef* hdcmi); -HAL_StatusTypeDef HAL_DCMI_Suspend(DCMI_HandleTypeDef* hdcmi); -HAL_StatusTypeDef HAL_DCMI_Resume(DCMI_HandleTypeDef* hdcmi); -void HAL_DCMI_ErrorCallback(DCMI_HandleTypeDef *hdcmi); -void HAL_DCMI_LineEventCallback(DCMI_HandleTypeDef *hdcmi); -void HAL_DCMI_FrameEventCallback(DCMI_HandleTypeDef *hdcmi); -void HAL_DCMI_VsyncEventCallback(DCMI_HandleTypeDef *hdcmi); -void HAL_DCMI_VsyncCallback(DCMI_HandleTypeDef *hdcmi); -void HAL_DCMI_HsyncCallback(DCMI_HandleTypeDef *hdcmi); -void HAL_DCMI_IRQHandler(DCMI_HandleTypeDef *hdcmi); -/** - * @} - */ - -/** @addtogroup DCMI_Exported_Functions_Group3 Peripheral Control functions - * @{ - */ -/* Peripheral Control functions ***********************************************/ -HAL_StatusTypeDef HAL_DCMI_ConfigCrop(DCMI_HandleTypeDef *hdcmi, uint32_t X0, uint32_t Y0, uint32_t XSize, uint32_t YSize); -HAL_StatusTypeDef HAL_DCMI_EnableCrop(DCMI_HandleTypeDef *hdcmi); -HAL_StatusTypeDef HAL_DCMI_DisableCrop(DCMI_HandleTypeDef *hdcmi); -HAL_StatusTypeDef HAL_DCMI_ConfigSyncUnmask(DCMI_HandleTypeDef *hdcmi, DCMI_SyncUnmaskTypeDef *SyncUnmask); -/** - * @} - */ - -/** @addtogroup DCMI_Exported_Functions_Group4 Peripheral State functions - * @{ - */ -/* Peripheral State functions *************************************************/ -HAL_DCMI_StateTypeDef HAL_DCMI_GetState(DCMI_HandleTypeDef *hdcmi); -uint32_t HAL_DCMI_GetError(DCMI_HandleTypeDef *hdcmi); -/** - * @} - */ - -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup DCMI_Private_Constants DCMI Private Constants - * @{ - */ -#define DCMI_MIS_INDEX 0x1000U /*!< DCMI MIS register index */ -#define DCMI_SR_INDEX 0x2000U /*!< DCMI SR register index */ -/** - * @} - */ -/* Private macro -------------------------------------------------------------*/ -/** @defgroup DCMI_Private_Macros DCMI Private Macros - * @{ - */ -#define IS_DCMI_CAPTURE_MODE(MODE)(((MODE) == DCMI_MODE_CONTINUOUS) || \ - ((MODE) == DCMI_MODE_SNAPSHOT)) - -#define IS_DCMI_SYNCHRO(MODE)(((MODE) == DCMI_SYNCHRO_HARDWARE) || \ - ((MODE) == DCMI_SYNCHRO_EMBEDDED)) - -#define IS_DCMI_PCKPOLARITY(POLARITY)(((POLARITY) == DCMI_PCKPOLARITY_FALLING) || \ - ((POLARITY) == DCMI_PCKPOLARITY_RISING)) - -#define IS_DCMI_VSPOLARITY(POLARITY)(((POLARITY) == DCMI_VSPOLARITY_LOW) || \ - ((POLARITY) == DCMI_VSPOLARITY_HIGH)) - -#define IS_DCMI_HSPOLARITY(POLARITY)(((POLARITY) == DCMI_HSPOLARITY_LOW) || \ - ((POLARITY) == DCMI_HSPOLARITY_HIGH)) - -#define IS_DCMI_MODE_JPEG(JPEG_MODE)(((JPEG_MODE) == DCMI_JPEG_DISABLE) || \ - ((JPEG_MODE) == DCMI_JPEG_ENABLE)) - -#define IS_DCMI_CAPTURE_RATE(RATE) (((RATE) == DCMI_CR_ALL_FRAME) || \ - ((RATE) == DCMI_CR_ALTERNATE_2_FRAME) || \ - ((RATE) == DCMI_CR_ALTERNATE_4_FRAME)) - -#define IS_DCMI_EXTENDED_DATA(DATA)(((DATA) == DCMI_EXTEND_DATA_8B) || \ - ((DATA) == DCMI_EXTEND_DATA_10B) || \ - ((DATA) == DCMI_EXTEND_DATA_12B) || \ - ((DATA) == DCMI_EXTEND_DATA_14B)) - -#define IS_DCMI_WINDOW_COORDINATE(COORDINATE) ((COORDINATE) <= DCMI_WINDOW_COORDINATE) - -#define IS_DCMI_WINDOW_HEIGHT(HEIGHT) ((HEIGHT) <= DCMI_WINDOW_HEIGHT) - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @addtogroup DCMI_Private_Functions DCMI Private Functions - * @{ - */ - -/** - * @} - */ - -#endif /* STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx ||\ - STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx ||\ - STM32F479xx */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_DCMI_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dcmi_ex.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dcmi_ex.h deleted file mode 100644 index 9bc942d..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dcmi_ex.h +++ /dev/null @@ -1,212 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_dcmi_ex.h - * @author MCD Application Team - * @brief Header file of DCMI Extension HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_DCMI_EX_H -#define __STM32F4xx_HAL_DCMI_EX_H - -#ifdef __cplusplus - extern "C" { -#endif - -#if defined(STM32F407xx) || defined(STM32F417xx) || defined(STM32F427xx) || defined(STM32F437xx) ||\ - defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F446xx) || defined(STM32F469xx) ||\ - defined(STM32F479xx) - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup DCMIEx - * @brief DCMI HAL module driver - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup DCMIEx_Exported_Types DCMI Extended Exported Types - * @{ - */ -/** - * @brief DCMIEx Embedded Synchronisation CODE Init structure definition - */ -typedef struct -{ - uint8_t FrameStartCode; /*!< Specifies the code of the frame start delimiter. */ - uint8_t LineStartCode; /*!< Specifies the code of the line start delimiter. */ - uint8_t LineEndCode; /*!< Specifies the code of the line end delimiter. */ - uint8_t FrameEndCode; /*!< Specifies the code of the frame end delimiter. */ -}DCMI_CodesInitTypeDef; - -/** - * @brief DCMI Init structure definition - */ -typedef struct -{ - uint32_t SynchroMode; /*!< Specifies the Synchronization Mode: Hardware or Embedded. - This parameter can be a value of @ref DCMI_Synchronization_Mode */ - - uint32_t PCKPolarity; /*!< Specifies the Pixel clock polarity: Falling or Rising. - This parameter can be a value of @ref DCMI_PIXCK_Polarity */ - - uint32_t VSPolarity; /*!< Specifies the Vertical synchronization polarity: High or Low. - This parameter can be a value of @ref DCMI_VSYNC_Polarity */ - - uint32_t HSPolarity; /*!< Specifies the Horizontal synchronization polarity: High or Low. - This parameter can be a value of @ref DCMI_HSYNC_Polarity */ - - uint32_t CaptureRate; /*!< Specifies the frequency of frame capture: All, 1/2 or 1/4. - This parameter can be a value of @ref DCMI_Capture_Rate */ - - uint32_t ExtendedDataMode; /*!< Specifies the data width: 8-bit, 10-bit, 12-bit or 14-bit. - This parameter can be a value of @ref DCMI_Extended_Data_Mode */ - - DCMI_CodesInitTypeDef SyncroCode; /*!< Specifies the code of the frame start delimiter. */ - - uint32_t JPEGMode; /*!< Enable or Disable the JPEG mode - This parameter can be a value of @ref DCMI_MODE_JPEG */ -#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) - uint32_t ByteSelectMode; /*!< Specifies the data to be captured by the interface - This parameter can be a value of @ref DCMIEx_Byte_Select_Mode */ - - uint32_t ByteSelectStart; /*!< Specifies if the data to be captured by the interface is even or odd - This parameter can be a value of @ref DCMIEx_Byte_Select_Start */ - - uint32_t LineSelectMode; /*!< Specifies the line of data to be captured by the interface - This parameter can be a value of @ref DCMIEx_Line_Select_Mode */ - - uint32_t LineSelectStart; /*!< Specifies if the line of data to be captured by the interface is even or odd - This parameter can be a value of @ref DCMIEx_Line_Select_Start */ - -#endif /* STM32F446xx || STM32F469xx || STM32F479xx */ -}DCMI_InitTypeDef; - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -/** @defgroup DCMIEx_Exported_Constants DCMI Exported Constants - * @{ - */ - -/** @defgroup DCMIEx_Byte_Select_Mode DCMI Byte Select Mode - * @{ - */ -#define DCMI_BSM_ALL 0x00000000U /*!< Interface captures all received data */ -#define DCMI_BSM_OTHER ((uint32_t)DCMI_CR_BSM_0) /*!< Interface captures every other byte from the received data */ -#define DCMI_BSM_ALTERNATE_4 ((uint32_t)DCMI_CR_BSM_1) /*!< Interface captures one byte out of four */ -#define DCMI_BSM_ALTERNATE_2 ((uint32_t)(DCMI_CR_BSM_0 | DCMI_CR_BSM_1)) /*!< Interface captures two bytes out of four */ - -/** - * @} - */ - -/** @defgroup DCMIEx_Byte_Select_Start DCMI Byte Select Start - * @{ - */ -#define DCMI_OEBS_ODD 0x00000000U /*!< Interface captures first data from the frame/line start, second one being dropped */ -#define DCMI_OEBS_EVEN ((uint32_t)DCMI_CR_OEBS) /*!< Interface captures second data from the frame/line start, first one being dropped */ - -/** - * @} - */ - -/** @defgroup DCMIEx_Line_Select_Mode DCMI Line Select Mode - * @{ - */ -#define DCMI_LSM_ALL 0x00000000U /*!< Interface captures all received lines */ -#define DCMI_LSM_ALTERNATE_2 ((uint32_t)DCMI_CR_LSM) /*!< Interface captures one line out of two */ - -/** - * @} - */ - -/** @defgroup DCMIEx_Line_Select_Start DCMI Line Select Start - * @{ - */ -#define DCMI_OELS_ODD 0x00000000U /*!< Interface captures first line from the frame start, second one being dropped */ -#define DCMI_OELS_EVEN ((uint32_t)DCMI_CR_OELS) /*!< Interface captures second line from the frame start, first one being dropped */ - -/** - * @} - */ - -/** - * @} - */ -#endif /* STM32F446xx || STM32F469xx || STM32F479xx */ - -/* Exported macro ------------------------------------------------------------*/ -/* Exported functions --------------------------------------------------------*/ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -#define DCMI_POSITION_ESCR_LSC (uint32_t)DCMI_ESCR_LSC_Pos /*!< Required left shift to set line start delimiter */ -#define DCMI_POSITION_ESCR_LEC (uint32_t)DCMI_ESCR_LEC_Pos /*!< Required left shift to set line end delimiter */ -#define DCMI_POSITION_ESCR_FEC (uint32_t)DCMI_ESCR_FEC_Pos /*!< Required left shift to set frame end delimiter */ - -/* Private macro -------------------------------------------------------------*/ -#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -/** @defgroup DCMIEx_Private_Macros DCMI Extended Private Macros - * @{ - */ -#define IS_DCMI_BYTE_SELECT_MODE(MODE)(((MODE) == DCMI_BSM_ALL) || \ - ((MODE) == DCMI_BSM_OTHER) || \ - ((MODE) == DCMI_BSM_ALTERNATE_4) || \ - ((MODE) == DCMI_BSM_ALTERNATE_2)) - -#define IS_DCMI_BYTE_SELECT_START(POLARITY)(((POLARITY) == DCMI_OEBS_ODD) || \ - ((POLARITY) == DCMI_OEBS_EVEN)) - -#define IS_DCMI_LINE_SELECT_MODE(MODE)(((MODE) == DCMI_LSM_ALL) || \ - ((MODE) == DCMI_LSM_ALTERNATE_2)) - -#define IS_DCMI_LINE_SELECT_START(POLARITY)(((POLARITY) == DCMI_OELS_ODD) || \ - ((POLARITY) == DCMI_OELS_EVEN)) -#endif /* STM32F446xx || STM32F469xx || STM32F479xx */ -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -#endif /* STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx ||\ - STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx ||\ - STM32F479xx */ - - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_DCMI_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_def.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_def.h deleted file mode 100644 index 975f70b..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_def.h +++ /dev/null @@ -1,211 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_def.h - * @author MCD Application Team - * @brief This file contains HAL common defines, enumeration, macros and - * structures definitions. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_DEF -#define __STM32F4xx_HAL_DEF - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" -#include "Legacy/stm32_hal_legacy.h" -#include - -/* Exported types ------------------------------------------------------------*/ - -/** - * @brief HAL Status structures definition - */ -typedef enum -{ - HAL_OK = 0x00U, - HAL_ERROR = 0x01U, - HAL_BUSY = 0x02U, - HAL_TIMEOUT = 0x03U -} HAL_StatusTypeDef; - -/** - * @brief HAL Lock structures definition - */ -typedef enum -{ - HAL_UNLOCKED = 0x00U, - HAL_LOCKED = 0x01U -} HAL_LockTypeDef; - -/* Exported macro ------------------------------------------------------------*/ - -#define UNUSED(X) (void)X /* To avoid gcc/g++ warnings */ - -#define HAL_MAX_DELAY 0xFFFFFFFFU - -#define HAL_IS_BIT_SET(REG, BIT) (((REG) & (BIT)) == (BIT)) -#define HAL_IS_BIT_CLR(REG, BIT) (((REG) & (BIT)) == 0U) - -#define __HAL_LINKDMA(__HANDLE__, __PPP_DMA_FIELD__, __DMA_HANDLE__) \ - do{ \ - (__HANDLE__)->__PPP_DMA_FIELD__ = &(__DMA_HANDLE__); \ - (__DMA_HANDLE__).Parent = (__HANDLE__); \ - } while(0U) - -/** @brief Reset the Handle's State field. - * @param __HANDLE__ specifies the Peripheral Handle. - * @note This macro can be used for the following purpose: - * - When the Handle is declared as local variable; before passing it as parameter - * to HAL_PPP_Init() for the first time, it is mandatory to use this macro - * to set to 0 the Handle's "State" field. - * Otherwise, "State" field may have any random value and the first time the function - * HAL_PPP_Init() is called, the low level hardware initialization will be missed - * (i.e. HAL_PPP_MspInit() will not be executed). - * - When there is a need to reconfigure the low level hardware: instead of calling - * HAL_PPP_DeInit() then HAL_PPP_Init(), user can make a call to this macro then HAL_PPP_Init(). - * In this later function, when the Handle's "State" field is set to 0, it will execute the function - * HAL_PPP_MspInit() which will reconfigure the low level hardware. - * @retval None - */ -#define __HAL_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = 0U) - -#if (USE_RTOS == 1U) - /* Reserved for future use */ - #error "USE_RTOS should be 0 in the current HAL release" -#else - #define __HAL_LOCK(__HANDLE__) \ - do{ \ - if((__HANDLE__)->Lock == HAL_LOCKED) \ - { \ - return HAL_BUSY; \ - } \ - else \ - { \ - (__HANDLE__)->Lock = HAL_LOCKED; \ - } \ - }while (0U) - - #define __HAL_UNLOCK(__HANDLE__) \ - do{ \ - (__HANDLE__)->Lock = HAL_UNLOCKED; \ - }while (0U) -#endif /* USE_RTOS */ - -#if defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) /* ARM Compiler V6 */ - #ifndef __weak - #define __weak __attribute__((weak)) - #endif - #ifndef __packed - #define __packed __attribute__((packed)) - #endif -#elif defined ( __GNUC__ ) && !defined (__CC_ARM) /* GNU Compiler */ - #ifndef __weak - #define __weak __attribute__((weak)) - #endif /* __weak */ - #ifndef __packed - #define __packed __attribute__((__packed__)) - #endif /* __packed */ -#endif /* __GNUC__ */ - - -/* Macro to get variable aligned on 4-bytes, for __ICCARM__ the directive "#pragma data_alignment=4" must be used instead */ -#if defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) /* ARM Compiler V6 */ - #ifndef __ALIGN_BEGIN - #define __ALIGN_BEGIN - #endif - #ifndef __ALIGN_END - #define __ALIGN_END __attribute__ ((aligned (4))) - #endif -#elif defined ( __GNUC__ ) && !defined (__CC_ARM) /* GNU Compiler */ - #ifndef __ALIGN_END -#define __ALIGN_END __attribute__ ((aligned (4))) - #endif /* __ALIGN_END */ - #ifndef __ALIGN_BEGIN - #define __ALIGN_BEGIN - #endif /* __ALIGN_BEGIN */ -#else - #ifndef __ALIGN_END - #define __ALIGN_END - #endif /* __ALIGN_END */ - #ifndef __ALIGN_BEGIN - #if defined (__CC_ARM) /* ARM Compiler V5*/ -#define __ALIGN_BEGIN __align(4) - #elif defined (__ICCARM__) /* IAR Compiler */ - #define __ALIGN_BEGIN - #endif /* __CC_ARM */ - #endif /* __ALIGN_BEGIN */ -#endif /* __GNUC__ */ - - -/** - * @brief __RAM_FUNC definition - */ -#if defined ( __CC_ARM ) || (defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)) -/* ARM Compiler V4/V5 and V6 - -------------------------- - RAM functions are defined using the toolchain options. - Functions that are executed in RAM should reside in a separate source module. - Using the 'Options for File' dialog you can simply change the 'Code / Const' - area of a module to a memory space in physical RAM. - Available memory areas are declared in the 'Target' tab of the 'Options for Target' - dialog. -*/ -#define __RAM_FUNC - -#elif defined ( __ICCARM__ ) -/* ICCARM Compiler - --------------- - RAM functions are defined using a specific toolchain keyword "__ramfunc". -*/ -#define __RAM_FUNC __ramfunc - -#elif defined ( __GNUC__ ) -/* GNU Compiler - ------------ - RAM functions are defined using a specific toolchain attribute - "__attribute__((section(".RamFunc")))". -*/ -#define __RAM_FUNC __attribute__((section(".RamFunc"))) - -#endif - -/** - * @brief __NOINLINE definition - */ -#if defined ( __CC_ARM ) || (defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)) || defined ( __GNUC__ ) -/* ARM V4/V5 and V6 & GNU Compiler - ------------------------------- -*/ -#define __NOINLINE __attribute__ ( (noinline) ) - -#elif defined ( __ICCARM__ ) -/* ICCARM Compiler - --------------- -*/ -#define __NOINLINE _Pragma("optimize = no_inline") - -#endif - -#ifdef __cplusplus -} -#endif - -#endif /* ___STM32F4xx_HAL_DEF */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dfsdm.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dfsdm.h deleted file mode 100644 index 09c6551..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dfsdm.h +++ /dev/null @@ -1,1144 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_dfsdm.h - * @author MCD Application Team - * @brief Header file of DFSDM HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_DFSDM_H -#define __STM32F4xx_HAL_DFSDM_H - -#ifdef __cplusplus - extern "C" { -#endif - -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup DFSDM - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup DFSDM_Exported_Types DFSDM Exported Types - * @{ - */ - -/** - * @brief HAL DFSDM Channel states definition - */ -typedef enum -{ - HAL_DFSDM_CHANNEL_STATE_RESET = 0x00U, /*!< DFSDM channel not initialized */ - HAL_DFSDM_CHANNEL_STATE_READY = 0x01U, /*!< DFSDM channel initialized and ready for use */ - HAL_DFSDM_CHANNEL_STATE_ERROR = 0xFFU /*!< DFSDM channel state error */ -}HAL_DFSDM_Channel_StateTypeDef; - -/** - * @brief DFSDM channel output clock structure definition - */ -typedef struct -{ - FunctionalState Activation; /*!< Output clock enable/disable */ - uint32_t Selection; /*!< Output clock is system clock or audio clock. - This parameter can be a value of @ref DFSDM_Channel_OuputClock */ - uint32_t Divider; /*!< Output clock divider. - This parameter must be a number between Min_Data = 2 and Max_Data = 256 */ -}DFSDM_Channel_OutputClockTypeDef; - -/** - * @brief DFSDM channel input structure definition - */ -typedef struct -{ - uint32_t Multiplexer; /*!< Input is external serial inputs or internal register. - This parameter can be a value of @ref DFSDM_Channel_InputMultiplexer */ - uint32_t DataPacking; /*!< Standard, interleaved or dual mode for internal register. - This parameter can be a value of @ref DFSDM_Channel_DataPacking */ - uint32_t Pins; /*!< Input pins are taken from same or following channel. - This parameter can be a value of @ref DFSDM_Channel_InputPins */ -}DFSDM_Channel_InputTypeDef; - -/** - * @brief DFSDM channel serial interface structure definition - */ -typedef struct -{ - uint32_t Type; /*!< SPI or Manchester modes. - This parameter can be a value of @ref DFSDM_Channel_SerialInterfaceType */ - uint32_t SpiClock; /*!< SPI clock select (external or internal with different sampling point). - This parameter can be a value of @ref DFSDM_Channel_SpiClock */ -}DFSDM_Channel_SerialInterfaceTypeDef; - -/** - * @brief DFSDM channel analog watchdog structure definition - */ -typedef struct -{ - uint32_t FilterOrder; /*!< Analog watchdog Sinc filter order. - This parameter can be a value of @ref DFSDM_Channel_AwdFilterOrder */ - uint32_t Oversampling; /*!< Analog watchdog filter oversampling ratio. - This parameter must be a number between Min_Data = 1 and Max_Data = 32 */ -}DFSDM_Channel_AwdTypeDef; - -/** - * @brief DFSDM channel init structure definition - */ -typedef struct -{ - DFSDM_Channel_OutputClockTypeDef OutputClock; /*!< DFSDM channel output clock parameters */ - DFSDM_Channel_InputTypeDef Input; /*!< DFSDM channel input parameters */ - DFSDM_Channel_SerialInterfaceTypeDef SerialInterface; /*!< DFSDM channel serial interface parameters */ - DFSDM_Channel_AwdTypeDef Awd; /*!< DFSDM channel analog watchdog parameters */ - int32_t Offset; /*!< DFSDM channel offset. - This parameter must be a number between Min_Data = -8388608 and Max_Data = 8388607 */ - uint32_t RightBitShift; /*!< DFSDM channel right bit shift. - This parameter must be a number between Min_Data = 0x00 and Max_Data = 0x1F */ -}DFSDM_Channel_InitTypeDef; - -/** - * @brief DFSDM channel handle structure definition - */ -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) -typedef struct __DFSDM_Channel_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_DFSDM_REGISTER_CALLBACKS */ -{ - DFSDM_Channel_TypeDef *Instance; /*!< DFSDM channel instance */ - DFSDM_Channel_InitTypeDef Init; /*!< DFSDM channel init parameters */ - HAL_DFSDM_Channel_StateTypeDef State; /*!< DFSDM channel state */ -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) - void (*CkabCallback) (struct __DFSDM_Channel_HandleTypeDef *hdfsdm_channel); /*!< DFSDM channel clock absence detection callback */ - void (*ScdCallback) (struct __DFSDM_Channel_HandleTypeDef *hdfsdm_channel); /*!< DFSDM channel short circuit detection callback */ - void (*MspInitCallback) (struct __DFSDM_Channel_HandleTypeDef *hdfsdm_channel); /*!< DFSDM channel MSP init callback */ - void (*MspDeInitCallback) (struct __DFSDM_Channel_HandleTypeDef *hdfsdm_channel); /*!< DFSDM channel MSP de-init callback */ -#endif -}DFSDM_Channel_HandleTypeDef; - -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) -/** - * @brief DFSDM channel callback ID enumeration definition - */ -typedef enum -{ - HAL_DFSDM_CHANNEL_CKAB_CB_ID = 0x00U, /*!< DFSDM channel clock absence detection callback ID */ - HAL_DFSDM_CHANNEL_SCD_CB_ID = 0x01U, /*!< DFSDM channel short circuit detection callback ID */ - HAL_DFSDM_CHANNEL_MSPINIT_CB_ID = 0x02U, /*!< DFSDM channel MSP init callback ID */ - HAL_DFSDM_CHANNEL_MSPDEINIT_CB_ID = 0x03U /*!< DFSDM channel MSP de-init callback ID */ -}HAL_DFSDM_Channel_CallbackIDTypeDef; - -/** - * @brief DFSDM channel callback pointer definition - */ -typedef void (*pDFSDM_Channel_CallbackTypeDef)(DFSDM_Channel_HandleTypeDef *hdfsdm_channel); -#endif -/** - * @brief HAL DFSDM Filter states definition - */ -typedef enum -{ - HAL_DFSDM_FILTER_STATE_RESET = 0x00U, /*!< DFSDM filter not initialized */ - HAL_DFSDM_FILTER_STATE_READY = 0x01U, /*!< DFSDM filter initialized and ready for use */ - HAL_DFSDM_FILTER_STATE_REG = 0x02U, /*!< DFSDM filter regular conversion in progress */ - HAL_DFSDM_FILTER_STATE_INJ = 0x03U, /*!< DFSDM filter injected conversion in progress */ - HAL_DFSDM_FILTER_STATE_REG_INJ = 0x04U, /*!< DFSDM filter regular and injected conversions in progress */ - HAL_DFSDM_FILTER_STATE_ERROR = 0xFFU /*!< DFSDM filter state error */ -}HAL_DFSDM_Filter_StateTypeDef; - -/** - * @brief DFSDM filter regular conversion parameters structure definition - */ -typedef struct -{ - uint32_t Trigger; /*!< Trigger used to start regular conversion: software or synchronous. - This parameter can be a value of @ref DFSDM_Filter_Trigger */ - FunctionalState FastMode; /*!< Enable/disable fast mode for regular conversion */ - FunctionalState DmaMode; /*!< Enable/disable DMA for regular conversion */ -}DFSDM_Filter_RegularParamTypeDef; - -/** - * @brief DFSDM filter injected conversion parameters structure definition - */ -typedef struct -{ - uint32_t Trigger; /*!< Trigger used to start injected conversion: software, external or synchronous. - This parameter can be a value of @ref DFSDM_Filter_Trigger */ - FunctionalState ScanMode; /*!< Enable/disable scanning mode for injected conversion */ - FunctionalState DmaMode; /*!< Enable/disable DMA for injected conversion */ - uint32_t ExtTrigger; /*!< External trigger. - This parameter can be a value of @ref DFSDM_Filter_ExtTrigger */ - uint32_t ExtTriggerEdge; /*!< External trigger edge: rising, falling or both. - This parameter can be a value of @ref DFSDM_Filter_ExtTriggerEdge */ -}DFSDM_Filter_InjectedParamTypeDef; - -/** - * @brief DFSDM filter parameters structure definition - */ -typedef struct -{ - uint32_t SincOrder; /*!< Sinc filter order. - This parameter can be a value of @ref DFSDM_Filter_SincOrder */ - uint32_t Oversampling; /*!< Filter oversampling ratio. - This parameter must be a number between Min_Data = 1 and Max_Data = 1024 */ - uint32_t IntOversampling; /*!< Integrator oversampling ratio. - This parameter must be a number between Min_Data = 1 and Max_Data = 256 */ -}DFSDM_Filter_FilterParamTypeDef; - -/** - * @brief DFSDM filter init structure definition - */ -typedef struct -{ - DFSDM_Filter_RegularParamTypeDef RegularParam; /*!< DFSDM regular conversion parameters */ - DFSDM_Filter_InjectedParamTypeDef InjectedParam; /*!< DFSDM injected conversion parameters */ - DFSDM_Filter_FilterParamTypeDef FilterParam; /*!< DFSDM filter parameters */ -}DFSDM_Filter_InitTypeDef; - -/** - * @brief DFSDM filter handle structure definition - */ -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) -typedef struct __DFSDM_Filter_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_DFSDM_REGISTER_CALLBACKS */ -{ - DFSDM_Filter_TypeDef *Instance; /*!< DFSDM filter instance */ - DFSDM_Filter_InitTypeDef Init; /*!< DFSDM filter init parameters */ - DMA_HandleTypeDef *hdmaReg; /*!< Pointer on DMA handler for regular conversions */ - DMA_HandleTypeDef *hdmaInj; /*!< Pointer on DMA handler for injected conversions */ - uint32_t RegularContMode; /*!< Regular conversion continuous mode */ - uint32_t RegularTrigger; /*!< Trigger used for regular conversion */ - uint32_t InjectedTrigger; /*!< Trigger used for injected conversion */ - uint32_t ExtTriggerEdge; /*!< Rising, falling or both edges selected */ - FunctionalState InjectedScanMode; /*!< Injected scanning mode */ - uint32_t InjectedChannelsNbr; /*!< Number of channels in injected sequence */ - uint32_t InjConvRemaining; /*!< Injected conversions remaining */ - HAL_DFSDM_Filter_StateTypeDef State; /*!< DFSDM filter state */ - uint32_t ErrorCode; /*!< DFSDM filter error code */ -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) - void (*AwdCallback) (struct __DFSDM_Filter_HandleTypeDef *hdfsdm_filter, - uint32_t Channel, uint32_t Threshold); /*!< DFSDM filter analog watchdog callback */ - void (*RegConvCpltCallback) (struct __DFSDM_Filter_HandleTypeDef *hdfsdm_filter); /*!< DFSDM filter regular conversion complete callback */ - void (*RegConvHalfCpltCallback) (struct __DFSDM_Filter_HandleTypeDef *hdfsdm_filter); /*!< DFSDM filter half regular conversion complete callback */ - void (*InjConvCpltCallback) (struct __DFSDM_Filter_HandleTypeDef *hdfsdm_filter); /*!< DFSDM filter injected conversion complete callback */ - void (*InjConvHalfCpltCallback) (struct __DFSDM_Filter_HandleTypeDef *hdfsdm_filter); /*!< DFSDM filter half injected conversion complete callback */ - void (*ErrorCallback) (struct __DFSDM_Filter_HandleTypeDef *hdfsdm_filter); /*!< DFSDM filter error callback */ - void (*MspInitCallback) (struct __DFSDM_Filter_HandleTypeDef *hdfsdm_filter); /*!< DFSDM filter MSP init callback */ - void (*MspDeInitCallback) (struct __DFSDM_Filter_HandleTypeDef *hdfsdm_filter); /*!< DFSDM filter MSP de-init callback */ -#endif -}DFSDM_Filter_HandleTypeDef; - -/** - * @brief DFSDM filter analog watchdog parameters structure definition - */ -typedef struct -{ - uint32_t DataSource; /*!< Values from digital filter or from channel watchdog filter. - This parameter can be a value of @ref DFSDM_Filter_AwdDataSource */ - uint32_t Channel; /*!< Analog watchdog channel selection. - This parameter can be a values combination of @ref DFSDM_Channel_Selection */ - int32_t HighThreshold; /*!< High threshold for the analog watchdog. - This parameter must be a number between Min_Data = -8388608 and Max_Data = 8388607 */ - int32_t LowThreshold; /*!< Low threshold for the analog watchdog. - This parameter must be a number between Min_Data = -8388608 and Max_Data = 8388607 */ - uint32_t HighBreakSignal; /*!< Break signal assigned to analog watchdog high threshold event. - This parameter can be a values combination of @ref DFSDM_BreakSignals */ - uint32_t LowBreakSignal; /*!< Break signal assigned to analog watchdog low threshold event. - This parameter can be a values combination of @ref DFSDM_BreakSignals */ -}DFSDM_Filter_AwdParamTypeDef; - -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) -/** - * @brief DFSDM filter callback ID enumeration definition - */ -typedef enum -{ - HAL_DFSDM_FILTER_REGCONV_COMPLETE_CB_ID = 0x00U, /*!< DFSDM filter regular conversion complete callback ID */ - HAL_DFSDM_FILTER_REGCONV_HALFCOMPLETE_CB_ID = 0x01U, /*!< DFSDM filter half regular conversion complete callback ID */ - HAL_DFSDM_FILTER_INJCONV_COMPLETE_CB_ID = 0x02U, /*!< DFSDM filter injected conversion complete callback ID */ - HAL_DFSDM_FILTER_INJCONV_HALFCOMPLETE_CB_ID = 0x03U, /*!< DFSDM filter half injected conversion complete callback ID */ - HAL_DFSDM_FILTER_ERROR_CB_ID = 0x04U, /*!< DFSDM filter error callback ID */ - HAL_DFSDM_FILTER_MSPINIT_CB_ID = 0x05U, /*!< DFSDM filter MSP init callback ID */ - HAL_DFSDM_FILTER_MSPDEINIT_CB_ID = 0x06U /*!< DFSDM filter MSP de-init callback ID */ -}HAL_DFSDM_Filter_CallbackIDTypeDef; - -/** - * @brief DFSDM filter callback pointer definition - */ -typedef void (*pDFSDM_Filter_CallbackTypeDef)(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -typedef void (*pDFSDM_Filter_AwdCallbackTypeDef)(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, uint32_t Channel, uint32_t Threshold); -#endif - -/** - * @} - */ -#if defined(SYSCFG_MCHDLYCR_BSCKSEL) -/** - * @brief Synchronization parameters structure definition for STM32F413xx/STM32F423xx devices - */ -typedef struct -{ - uint32_t DFSDM1ClockIn; /*!< Source selection for DFSDM1_Ckin. - This parameter can be a value of @ref DFSDM_1_CLOCKIN_SELECTION*/ - uint32_t DFSDM2ClockIn; /*!< Source selection for DFSDM2_Ckin. - This parameter can be a value of @ref DFSDM_2_CLOCKIN_SELECTION*/ - uint32_t DFSDM1ClockOut; /*!< Source selection for DFSDM1_Ckout. - This parameter can be a value of @ref DFSDM_1_CLOCKOUT_SELECTION*/ - uint32_t DFSDM2ClockOut; /*!< Source selection for DFSDM2_Ckout. - This parameter can be a value of @ref DFSDM_2_CLOCKOUT_SELECTION*/ - uint32_t DFSDM1BitClkDistribution; /*!< Distribution of the DFSDM1 bitstream clock gated by TIM4 OC1 or TIM4 OC2. - This parameter can be a value of @ref DFSDM_1_BIT_STREAM_DISTRIBUTION - @note The DFSDM2 audio gated by TIM4 OC2 can be injected on CKIN0 or CKIN2 - @note The DFSDM2 audio gated by TIM4 OC1 can be injected on CKIN1 or CKIN3 */ - uint32_t DFSDM2BitClkDistribution; /*!< Distribution of the DFSDM2 bitstream clock gated by TIM3 OC1 or TIM3 OC2 or TIM3 OC3 or TIM3 OC4. - This parameter can be a value of @ref DFSDM_2_BIT_STREAM_DISTRIBUTION - @note The DFSDM2 audio gated by TIM3 OC4 can be injected on CKIN0 or CKIN4 - @note The DFSDM2 audio gated by TIM3 OC3 can be injected on CKIN1 or CKIN5 - @note The DFSDM2 audio gated by TIM3 OC2 can be injected on CKIN2 or CKIN6 - @note The DFSDM2 audio gated by TIM3 OC1 can be injected on CKIN3 or CKIN7 */ - uint32_t DFSDM1DataDistribution; /*!< Source selection for DatIn0 and DatIn2 of DFSDM1. - This parameter can be a value of @ref DFSDM_1_DATA_DISTRIBUTION */ - uint32_t DFSDM2DataDistribution; /*!< Source selection for DatIn0, DatIn2, DatIn4 and DatIn6 of DFSDM2. - This parameter can be a value of @ref DFSDM_2_DATA_DISTRIBUTION */ -}DFSDM_MultiChannelConfigTypeDef; -#endif /* SYSCFG_MCHDLYCR_BSCKSEL */ -/** - * @} - */ - -/* End of exported types -----------------------------------------------------*/ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup DFSDM_Exported_Constants DFSDM Exported Constants - * @{ - */ - -/** @defgroup DFSDM_Channel_OuputClock DFSDM channel output clock selection - * @{ - */ -#define DFSDM_CHANNEL_OUTPUT_CLOCK_SYSTEM 0x00000000U /*!< Source for ouput clock is system clock */ -#define DFSDM_CHANNEL_OUTPUT_CLOCK_AUDIO DFSDM_CHCFGR1_CKOUTSRC /*!< Source for ouput clock is audio clock */ -/** - * @} - */ - -/** @defgroup DFSDM_Channel_InputMultiplexer DFSDM channel input multiplexer - * @{ - */ -#define DFSDM_CHANNEL_EXTERNAL_INPUTS 0x00000000U /*!< Data are taken from external inputs */ -#define DFSDM_CHANNEL_INTERNAL_REGISTER DFSDM_CHCFGR1_DATMPX_1 /*!< Data are taken from internal register */ -/** - * @} - */ - -/** @defgroup DFSDM_Channel_DataPacking DFSDM channel input data packing - * @{ - */ -#define DFSDM_CHANNEL_STANDARD_MODE 0x00000000U /*!< Standard data packing mode */ -#define DFSDM_CHANNEL_INTERLEAVED_MODE DFSDM_CHCFGR1_DATPACK_0 /*!< Interleaved data packing mode */ -#define DFSDM_CHANNEL_DUAL_MODE DFSDM_CHCFGR1_DATPACK_1 /*!< Dual data packing mode */ -/** - * @} - */ - -/** @defgroup DFSDM_Channel_InputPins DFSDM channel input pins - * @{ - */ -#define DFSDM_CHANNEL_SAME_CHANNEL_PINS 0x00000000U /*!< Input from pins on same channel */ -#define DFSDM_CHANNEL_FOLLOWING_CHANNEL_PINS DFSDM_CHCFGR1_CHINSEL /*!< Input from pins on following channel */ -/** - * @} - */ - -/** @defgroup DFSDM_Channel_SerialInterfaceType DFSDM channel serial interface type - * @{ - */ -#define DFSDM_CHANNEL_SPI_RISING 0x00000000U /*!< SPI with rising edge */ -#define DFSDM_CHANNEL_SPI_FALLING DFSDM_CHCFGR1_SITP_0 /*!< SPI with falling edge */ -#define DFSDM_CHANNEL_MANCHESTER_RISING DFSDM_CHCFGR1_SITP_1 /*!< Manchester with rising edge */ -#define DFSDM_CHANNEL_MANCHESTER_FALLING DFSDM_CHCFGR1_SITP /*!< Manchester with falling edge */ -/** - * @} - */ - -/** @defgroup DFSDM_Channel_SpiClock DFSDM channel SPI clock selection - * @{ - */ -#define DFSDM_CHANNEL_SPI_CLOCK_EXTERNAL 0x00000000U /*!< External SPI clock */ -#define DFSDM_CHANNEL_SPI_CLOCK_INTERNAL DFSDM_CHCFGR1_SPICKSEL_0 /*!< Internal SPI clock */ -#define DFSDM_CHANNEL_SPI_CLOCK_INTERNAL_DIV2_FALLING DFSDM_CHCFGR1_SPICKSEL_1 /*!< Internal SPI clock divided by 2, falling edge */ -#define DFSDM_CHANNEL_SPI_CLOCK_INTERNAL_DIV2_RISING DFSDM_CHCFGR1_SPICKSEL /*!< Internal SPI clock divided by 2, rising edge */ -/** - * @} - */ - -/** @defgroup DFSDM_Channel_AwdFilterOrder DFSDM channel analog watchdog filter order - * @{ - */ -#define DFSDM_CHANNEL_FASTSINC_ORDER 0x00000000U /*!< FastSinc filter type */ -#define DFSDM_CHANNEL_SINC1_ORDER DFSDM_CHAWSCDR_AWFORD_0 /*!< Sinc 1 filter type */ -#define DFSDM_CHANNEL_SINC2_ORDER DFSDM_CHAWSCDR_AWFORD_1 /*!< Sinc 2 filter type */ -#define DFSDM_CHANNEL_SINC3_ORDER DFSDM_CHAWSCDR_AWFORD /*!< Sinc 3 filter type */ -/** - * @} - */ - -/** @defgroup DFSDM_Filter_Trigger DFSDM filter conversion trigger - * @{ - */ -#define DFSDM_FILTER_SW_TRIGGER 0x00000000U /*!< Software trigger */ -#define DFSDM_FILTER_SYNC_TRIGGER 0x00000001U /*!< Synchronous with DFSDM_FLT0 */ -#define DFSDM_FILTER_EXT_TRIGGER 0x00000002U /*!< External trigger (only for injected conversion) */ -/** - * @} - */ - -/** @defgroup DFSDM_Filter_ExtTrigger DFSDM filter external trigger - * @{ - */ -#if defined(STM32F413xx) || defined(STM32F423xx) -/* Trigger for stm32f413xx and STM32f423xx devices */ -#define DFSDM_FILTER_EXT_TRIG_TIM1_TRGO 0x00000000U /*!< For All DFSDM1/2 filters */ -#define DFSDM_FILTER_EXT_TRIG_TIM3_TRGO DFSDM_FLTCR1_JEXTSEL_0 /*!< For All DFSDM1/2 filters */ -#define DFSDM_FILTER_EXT_TRIG_TIM8_TRGO DFSDM_FLTCR1_JEXTSEL_1 /*!< For All DFSDM1/2 filters */ -#define DFSDM_FILTER_EXT_TRIG_TIM10_OC1 (DFSDM_FLTCR1_JEXTSEL_0 | DFSDM_FLTCR1_JEXTSEL_1) /*!< For DFSDM1 filter 0 and 1 and DFSDM2 filter 0, 1 and 2 */ -#define DFSDM_FILTER_EXT_TRIG_TIM2_TRGO (DFSDM_FLTCR1_JEXTSEL_0 | DFSDM_FLTCR1_JEXTSEL_1) /*!< For DFSDM2 filter 3 */ -#define DFSDM_FILTER_EXT_TRIG_TIM4_TRGO DFSDM_FLTCR1_JEXTSEL_2 /*!< For DFSDM1 filter 0 and 1 and DFSDM2 filter 0, 1 and 2 */ -#define DFSDM_FILTER_EXT_TRIG_TIM11_OC1 DFSDM_FLTCR1_JEXTSEL_2 /*!< For DFSDM2 filter 3 */ -#define DFSDM_FILTER_EXT_TRIG_TIM6_TRGO (DFSDM_FLTCR1_JEXTSEL_0 | DFSDM_FLTCR1_JEXTSEL_2) /*!< For DFSDM1 filter 0 and 1 and DFSDM2 filter 0 and 1 */ -#define DFSDM_FILTER_EXT_TRIG_TIM7_TRGO (DFSDM_FLTCR1_JEXTSEL_0 | DFSDM_FLTCR1_JEXTSEL_2) /*!< For DFSDM2 filter 2 and 3*/ -#define DFSDM_FILTER_EXT_TRIG_EXTI11 (DFSDM_FLTCR1_JEXTSEL_1 | DFSDM_FLTCR1_JEXTSEL_2) /*!< For All DFSDM1/2 filters */ -#define DFSDM_FILTER_EXT_TRIG_EXTI15 DFSDM_FLTCR1_JEXTSEL /*!< For All DFSDM1/2 filters */ -#else -/* Trigger for stm32f412xx devices */ -#define DFSDM_FILTER_EXT_TRIG_TIM1_TRGO 0x00000000U /*!< For DFSDM1 filter 0 and 1*/ -#define DFSDM_FILTER_EXT_TRIG_TIM3_TRGO DFSDM_FLTCR1_JEXTSEL_0 /*!< For DFSDM1 filter 0 and 1*/ -#define DFSDM_FILTER_EXT_TRIG_TIM8_TRGO DFSDM_FLTCR1_JEXTSEL_1 /*!< For DFSDM1 filter 0 and 1*/ -#define DFSDM_FILTER_EXT_TRIG_TIM10_OC1 (DFSDM_FLTCR1_JEXTSEL_0 | DFSDM_FLTCR1_JEXTSEL_1) /*!< For DFSDM1 filter 0 and 1*/ -#define DFSDM_FILTER_EXT_TRIG_TIM4_TRGO DFSDM_FLTCR1_JEXTSEL_2 /*!< For DFSDM1 filter 0 and 1*/ -#define DFSDM_FILTER_EXT_TRIG_TIM6_TRGO (DFSDM_FLTCR1_JEXTSEL_0 | DFSDM_FLTCR1_JEXTSEL_2) /*!< For DFSDM1 filter 0 and 1*/ -#define DFSDM_FILTER_EXT_TRIG_EXTI11 (DFSDM_FLTCR1_JEXTSEL_1 | DFSDM_FLTCR1_JEXTSEL_2) /*!< For DFSDM1 filter 0 and 1*/ -#define DFSDM_FILTER_EXT_TRIG_EXTI15 DFSDM_FLTCR1_JEXTSEL /*!< For DFSDM1 filter 0 and 1*/ -#endif -/** - * @} - */ - -/** @defgroup DFSDM_Filter_ExtTriggerEdge DFSDM filter external trigger edge - * @{ - */ -#define DFSDM_FILTER_EXT_TRIG_RISING_EDGE DFSDM_FLTCR1_JEXTEN_0 /*!< External rising edge */ -#define DFSDM_FILTER_EXT_TRIG_FALLING_EDGE DFSDM_FLTCR1_JEXTEN_1 /*!< External falling edge */ -#define DFSDM_FILTER_EXT_TRIG_BOTH_EDGES DFSDM_FLTCR1_JEXTEN /*!< External rising and falling edges */ -/** - * @} - */ - -/** @defgroup DFSDM_Filter_SincOrder DFSDM filter sinc order - * @{ - */ -#define DFSDM_FILTER_FASTSINC_ORDER 0x00000000U /*!< FastSinc filter type */ -#define DFSDM_FILTER_SINC1_ORDER DFSDM_FLTFCR_FORD_0 /*!< Sinc 1 filter type */ -#define DFSDM_FILTER_SINC2_ORDER DFSDM_FLTFCR_FORD_1 /*!< Sinc 2 filter type */ -#define DFSDM_FILTER_SINC3_ORDER (DFSDM_FLTFCR_FORD_0 | DFSDM_FLTFCR_FORD_1) /*!< Sinc 3 filter type */ -#define DFSDM_FILTER_SINC4_ORDER DFSDM_FLTFCR_FORD_2 /*!< Sinc 4 filter type */ -#define DFSDM_FILTER_SINC5_ORDER (DFSDM_FLTFCR_FORD_0 | DFSDM_FLTFCR_FORD_2) /*!< Sinc 5 filter type */ -/** - * @} - */ - -/** @defgroup DFSDM_Filter_AwdDataSource DFSDM filter analog watchdog data source - * @{ - */ -#define DFSDM_FILTER_AWD_FILTER_DATA 0x00000000U /*!< From digital filter */ -#define DFSDM_FILTER_AWD_CHANNEL_DATA DFSDM_FLTCR1_AWFSEL /*!< From analog watchdog channel */ -/** - * @} - */ - -/** @defgroup DFSDM_Filter_ErrorCode DFSDM filter error code - * @{ - */ -#define DFSDM_FILTER_ERROR_NONE 0x00000000U /*!< No error */ -#define DFSDM_FILTER_ERROR_REGULAR_OVERRUN 0x00000001U /*!< Overrun occurs during regular conversion */ -#define DFSDM_FILTER_ERROR_INJECTED_OVERRUN 0x00000002U /*!< Overrun occurs during injected conversion */ -#define DFSDM_FILTER_ERROR_DMA 0x00000003U /*!< DMA error occurs */ -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) -#define DFSDM_FILTER_ERROR_INVALID_CALLBACK 0x00000004U /*!< Invalid callback error occurs */ -#endif -/** - * @} - */ - -/** @defgroup DFSDM_BreakSignals DFSDM break signals - * @{ - */ -#define DFSDM_NO_BREAK_SIGNAL 0x00000000U /*!< No break signal */ -#define DFSDM_BREAK_SIGNAL_0 0x00000001U /*!< Break signal 0 */ -#define DFSDM_BREAK_SIGNAL_1 0x00000002U /*!< Break signal 1 */ -#define DFSDM_BREAK_SIGNAL_2 0x00000004U /*!< Break signal 2 */ -#define DFSDM_BREAK_SIGNAL_3 0x00000008U /*!< Break signal 3 */ -/** - * @} - */ - -/** @defgroup DFSDM_Channel_Selection DFSDM Channel Selection - * @{ - */ -/* DFSDM Channels ------------------------------------------------------------*/ -/* The DFSDM channels are defined as follows: - - in 16-bit LSB the channel mask is set - - in 16-bit MSB the channel number is set - e.g. for channel 3 definition: - - the channel mask is 0x00000008 (bit 3 is set) - - the channel number 3 is 0x00030000 - --> Consequently, channel 3 definition is 0x00000008 | 0x00030000 = 0x00030008 */ -#define DFSDM_CHANNEL_0 0x00000001U -#define DFSDM_CHANNEL_1 0x00010002U -#define DFSDM_CHANNEL_2 0x00020004U -#define DFSDM_CHANNEL_3 0x00030008U -#define DFSDM_CHANNEL_4 0x00040010U /* only for stmm32f413xx and stm32f423xx devices */ -#define DFSDM_CHANNEL_5 0x00050020U /* only for stmm32f413xx and stm32f423xx devices */ -#define DFSDM_CHANNEL_6 0x00060040U /* only for stmm32f413xx and stm32f423xx devices */ -#define DFSDM_CHANNEL_7 0x00070080U /* only for stmm32f413xx and stm32f423xx devices */ -/** - * @} - */ - -/** @defgroup DFSDM_ContinuousMode DFSDM Continuous Mode - * @{ - */ -#define DFSDM_CONTINUOUS_CONV_OFF 0x00000000U /*!< Conversion are not continuous */ -#define DFSDM_CONTINUOUS_CONV_ON 0x00000001U /*!< Conversion are continuous */ -/** - * @} - */ - -/** @defgroup DFSDM_AwdThreshold DFSDM analog watchdog threshold - * @{ - */ -#define DFSDM_AWD_HIGH_THRESHOLD 0x00000000U /*!< Analog watchdog high threshold */ -#define DFSDM_AWD_LOW_THRESHOLD 0x00000001U /*!< Analog watchdog low threshold */ -/** - * @} - */ - -#if defined(SYSCFG_MCHDLYCR_BSCKSEL) -/** @defgroup DFSDM_1_CLOCKOUT_SELECTION DFSDM1 ClockOut Selection - * @{ - */ -#define DFSDM1_CKOUT_DFSDM2_CKOUT 0x00000080U -#define DFSDM1_CKOUT_DFSDM1 0x00000000U -/** - * @} - */ - -/** @defgroup DFSDM_2_CLOCKOUT_SELECTION DFSDM2 ClockOut Selection - * @{ - */ -#define DFSDM2_CKOUT_DFSDM2_CKOUT 0x00040000U -#define DFSDM2_CKOUT_DFSDM2 0x00000000U -/** - * @} - */ - -/** @defgroup DFSDM_1_CLOCKIN_SELECTION DFSDM1 ClockIn Selection - * @{ - */ -#define DFSDM1_CKIN_DFSDM2_CKOUT 0x00000040U -#define DFSDM1_CKIN_PAD 0x00000000U -/** - * @} - */ - -/** @defgroup DFSDM_2_CLOCKIN_SELECTION DFSDM2 ClockIn Selection - * @{ - */ -#define DFSDM2_CKIN_DFSDM2_CKOUT 0x00020000U -#define DFSDM2_CKIN_PAD 0x00000000U -/** - * @} - */ - -/** @defgroup DFSDM_1_BIT_STREAM_DISTRIBUTION DFSDM1 Bit Stream Distribution - * @{ - */ -#define DFSDM1_T4_OC2_BITSTREAM_CKIN0 0x00000000U /* TIM4_OC2 to CLKIN0 */ -#define DFSDM1_T4_OC2_BITSTREAM_CKIN2 SYSCFG_MCHDLYCR_DFSDM1CK02SEL /* TIM4_OC2 to CLKIN2 */ -#define DFSDM1_T4_OC1_BITSTREAM_CKIN3 SYSCFG_MCHDLYCR_DFSDM1CK13SEL /* TIM4_OC1 to CLKIN3 */ -#define DFSDM1_T4_OC1_BITSTREAM_CKIN1 0x00000000U /* TIM4_OC1 to CLKIN1 */ -/** - * @} - */ - -/** @defgroup DFSDM_2_BIT_STREAM_DISTRIBUTION DFSDM12 Bit Stream Distribution - * @{ - */ -#define DFSDM2_T3_OC4_BITSTREAM_CKIN0 0x00000000U /* TIM3_OC4 to CKIN0 */ -#define DFSDM2_T3_OC4_BITSTREAM_CKIN4 SYSCFG_MCHDLYCR_DFSDM2CK04SEL /* TIM3_OC4 to CKIN4 */ -#define DFSDM2_T3_OC3_BITSTREAM_CKIN5 SYSCFG_MCHDLYCR_DFSDM2CK15SEL /* TIM3_OC3 to CKIN5 */ -#define DFSDM2_T3_OC3_BITSTREAM_CKIN1 0x00000000U /* TIM3_OC3 to CKIN1 */ -#define DFSDM2_T3_OC2_BITSTREAM_CKIN6 SYSCFG_MCHDLYCR_DFSDM2CK26SEL /* TIM3_OC2to CKIN6 */ -#define DFSDM2_T3_OC2_BITSTREAM_CKIN2 0x00000000U /* TIM3_OC2 to CKIN2 */ -#define DFSDM2_T3_OC1_BITSTREAM_CKIN3 0x00000000U /* TIM3_OC1 to CKIN3 */ -#define DFSDM2_T3_OC1_BITSTREAM_CKIN7 SYSCFG_MCHDLYCR_DFSDM2CK37SEL /* TIM3_OC1 to CKIN7 */ -/** - * @} - */ - -/** @defgroup DFSDM_1_DATA_DISTRIBUTION DFSDM1 Data Distribution - * @{ - */ -#define DFSDM1_DATIN0_TO_DATIN0_PAD 0x00000000U -#define DFSDM1_DATIN0_TO_DATIN1_PAD SYSCFG_MCHDLYCR_DFSDM1D0SEL -#define DFSDM1_DATIN2_TO_DATIN2_PAD 0x00000000U -#define DFSDM1_DATIN2_TO_DATIN3_PAD SYSCFG_MCHDLYCR_DFSDM1D2SEL -/** - * @} - */ - -/** @defgroup DFSDM_2_DATA_DISTRIBUTION DFSDM2 Data Distribution - * @{ - */ -#define DFSDM2_DATIN0_TO_DATIN0_PAD 0x00000000U -#define DFSDM2_DATIN0_TO_DATIN1_PAD SYSCFG_MCHDLYCR_DFSDM2D0SEL -#define DFSDM2_DATIN2_TO_DATIN2_PAD 0x00000000U -#define DFSDM2_DATIN2_TO_DATIN3_PAD SYSCFG_MCHDLYCR_DFSDM2D2SEL -#define DFSDM2_DATIN4_TO_DATIN4_PAD 0x00000000U -#define DFSDM2_DATIN4_TO_DATIN5_PAD SYSCFG_MCHDLYCR_DFSDM2D4SEL -#define DFSDM2_DATIN6_TO_DATIN6_PAD 0x00000000U -#define DFSDM2_DATIN6_TO_DATIN7_PAD SYSCFG_MCHDLYCR_DFSDM2D6SEL -/** - * @} - */ - -/** @defgroup HAL_MCHDLY_CLOCK HAL MCHDLY Clock enable - * @{ - */ -#define HAL_MCHDLY_CLOCK_DFSDM2 SYSCFG_MCHDLYCR_MCHDLY2EN -#define HAL_MCHDLY_CLOCK_DFSDM1 SYSCFG_MCHDLYCR_MCHDLY1EN -/** - * @} - */ - -/** @defgroup DFSDM_CLOCKIN_SOURCE DFSDM Clock In Source Selection - * @{ - */ -#define HAL_DFSDM2_CKIN_PAD 0x00040000U -#define HAL_DFSDM2_CKIN_DM SYSCFG_MCHDLYCR_DFSDM2CFG -#define HAL_DFSDM1_CKIN_PAD 0x00000000U -#define HAL_DFSDM1_CKIN_DM SYSCFG_MCHDLYCR_DFSDM1CFG -/** - * @} - */ - -/** @defgroup DFSDM_CLOCKOUT_SOURCE DFSDM Clock Source Selection - * @{ - */ -#define HAL_DFSDM2_CKOUT_DFSDM2 0x10000000U -#define HAL_DFSDM2_CKOUT_M27 SYSCFG_MCHDLYCR_DFSDM2CKOSEL -#define HAL_DFSDM1_CKOUT_DFSDM1 0x00000000U -#define HAL_DFSDM1_CKOUT_M27 SYSCFG_MCHDLYCR_DFSDM1CKOSEL -/** - * @} - */ - -/** @defgroup DFSDM_DATAIN0_SOURCE DFSDM Source Selection For DATAIN0 - * @{ - */ -#define HAL_DATAIN0_DFSDM2_PAD 0x10000000U -#define HAL_DATAIN0_DFSDM2_DATAIN1 SYSCFG_MCHDLYCR_DFSDM2D0SEL -#define HAL_DATAIN0_DFSDM1_PAD 0x00000000U -#define HAL_DATAIN0_DFSDM1_DATAIN1 SYSCFG_MCHDLYCR_DFSDM1D0SEL -/** - * @} - */ - -/** @defgroup DFSDM_DATAIN2_SOURCE DFSDM Source Selection For DATAIN2 - * @{ - */ -#define HAL_DATAIN2_DFSDM2_PAD 0x10000000U -#define HAL_DATAIN2_DFSDM2_DATAIN3 SYSCFG_MCHDLYCR_DFSDM2D2SEL -#define HAL_DATAIN2_DFSDM1_PAD 0x00000000U -#define HAL_DATAIN2_DFSDM1_DATAIN3 SYSCFG_MCHDLYCR_DFSDM1D2SEL -/** - * @} - */ - -/** @defgroup DFSDM_DATAIN4_SOURCE DFSDM Source Selection For DATAIN4 - * @{ - */ -#define HAL_DATAIN4_DFSDM2_PAD 0x00000000U -#define HAL_DATAIN4_DFSDM2_DATAIN5 SYSCFG_MCHDLYCR_DFSDM2D4SEL -/** - * @} - */ - -/** @defgroup DFSDM_DATAIN6_SOURCE DFSDM Source Selection For DATAIN6 - * @{ - */ -#define HAL_DATAIN6_DFSDM2_PAD 0x00000000U -#define HAL_DATAIN6_DFSDM2_DATAIN7 SYSCFG_MCHDLYCR_DFSDM2D6SEL -/** - * @} - */ - -/** @defgroup DFSDM1_CLKIN_SOURCE DFSDM1 Source Selection For CLKIN - * @{ - */ -#define HAL_DFSDM1_CLKIN0_TIM4OC2 0x01000000U -#define HAL_DFSDM1_CLKIN2_TIM4OC2 SYSCFG_MCHDLYCR_DFSDM1CK02SEL -#define HAL_DFSDM1_CLKIN1_TIM4OC1 0x02000000U -#define HAL_DFSDM1_CLKIN3_TIM4OC1 SYSCFG_MCHDLYCR_DFSDM1CK13SEL -/** - * @} - */ - -/** @defgroup DFSDM2_CLKIN_SOURCE DFSDM2 Source Selection For CLKIN - * @{ - */ -#define HAL_DFSDM2_CLKIN0_TIM3OC4 0x04000000U -#define HAL_DFSDM2_CLKIN4_TIM3OC4 SYSCFG_MCHDLYCR_DFSDM2CK04SEL -#define HAL_DFSDM2_CLKIN1_TIM3OC3 0x08000000U -#define HAL_DFSDM2_CLKIN5_TIM3OC3 SYSCFG_MCHDLYCR_DFSDM2CK15SEL -#define HAL_DFSDM2_CLKIN2_TIM3OC2 0x10000000U -#define HAL_DFSDM2_CLKIN6_TIM3OC2 SYSCFG_MCHDLYCR_DFSDM2CK26SEL -#define HAL_DFSDM2_CLKIN3_TIM3OC1 0x00000000U -#define HAL_DFSDM2_CLKIN7_TIM3OC1 SYSCFG_MCHDLYCR_DFSDM2CK37SEL -/** - * @} - */ - -#endif /* SYSCFG_MCHDLYCR_BSCKSEL*/ -/** - * @} - */ -/* End of exported constants -------------------------------------------------*/ - -/* Exported macros -----------------------------------------------------------*/ -/** @defgroup DFSDM_Exported_Macros DFSDM Exported Macros - * @{ - */ - -/** @brief Reset DFSDM channel handle state. - * @param __HANDLE__ DFSDM channel handle. - * @retval None - */ -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) -#define __HAL_DFSDM_CHANNEL_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->State = HAL_DFSDM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_DFSDM_CHANNEL_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_DFSDM_CHANNEL_STATE_RESET) -#endif - -/** @brief Reset DFSDM filter handle state. - * @param __HANDLE__ DFSDM filter handle. - * @retval None - */ -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) -#define __HAL_DFSDM_FILTER_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->State = HAL_DFSDM_FILTER_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_DFSDM_FILTER_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_DFSDM_FILTER_STATE_RESET) -#endif - -/** - * @} - */ -/* End of exported macros ----------------------------------------------------*/ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup DFSDM_Exported_Functions DFSDM Exported Functions - * @{ - */ - -/** @addtogroup DFSDM_Exported_Functions_Group1_Channel Channel initialization and de-initialization functions - * @{ - */ -/* Channel initialization and de-initialization functions *********************/ -HAL_StatusTypeDef HAL_DFSDM_ChannelInit(DFSDM_Channel_HandleTypeDef *hdfsdm_channel); -HAL_StatusTypeDef HAL_DFSDM_ChannelDeInit(DFSDM_Channel_HandleTypeDef *hdfsdm_channel); -void HAL_DFSDM_ChannelMspInit(DFSDM_Channel_HandleTypeDef *hdfsdm_channel); -void HAL_DFSDM_ChannelMspDeInit(DFSDM_Channel_HandleTypeDef *hdfsdm_channel); -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) -/* Channel callbacks register/unregister functions ****************************/ -HAL_StatusTypeDef HAL_DFSDM_Channel_RegisterCallback(DFSDM_Channel_HandleTypeDef *hdfsdm_channel, - HAL_DFSDM_Channel_CallbackIDTypeDef CallbackID, - pDFSDM_Channel_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_DFSDM_Channel_UnRegisterCallback(DFSDM_Channel_HandleTypeDef *hdfsdm_channel, - HAL_DFSDM_Channel_CallbackIDTypeDef CallbackID); -#endif -/** - * @} - */ - -/** @addtogroup DFSDM_Exported_Functions_Group2_Channel Channel operation functions - * @{ - */ -/* Channel operation functions ************************************************/ -HAL_StatusTypeDef HAL_DFSDM_ChannelCkabStart(DFSDM_Channel_HandleTypeDef *hdfsdm_channel); -HAL_StatusTypeDef HAL_DFSDM_ChannelCkabStart_IT(DFSDM_Channel_HandleTypeDef *hdfsdm_channel); -HAL_StatusTypeDef HAL_DFSDM_ChannelCkabStop(DFSDM_Channel_HandleTypeDef *hdfsdm_channel); -HAL_StatusTypeDef HAL_DFSDM_ChannelCkabStop_IT(DFSDM_Channel_HandleTypeDef *hdfsdm_channel); - -HAL_StatusTypeDef HAL_DFSDM_ChannelScdStart(DFSDM_Channel_HandleTypeDef *hdfsdm_channel, uint32_t Threshold, uint32_t BreakSignal); -HAL_StatusTypeDef HAL_DFSDM_ChannelScdStart_IT(DFSDM_Channel_HandleTypeDef *hdfsdm_channel, uint32_t Threshold, uint32_t BreakSignal); -HAL_StatusTypeDef HAL_DFSDM_ChannelScdStop(DFSDM_Channel_HandleTypeDef *hdfsdm_channel); -HAL_StatusTypeDef HAL_DFSDM_ChannelScdStop_IT(DFSDM_Channel_HandleTypeDef *hdfsdm_channel); - -int16_t HAL_DFSDM_ChannelGetAwdValue(DFSDM_Channel_HandleTypeDef *hdfsdm_channel); -HAL_StatusTypeDef HAL_DFSDM_ChannelModifyOffset(DFSDM_Channel_HandleTypeDef *hdfsdm_channel, int32_t Offset); - -HAL_StatusTypeDef HAL_DFSDM_ChannelPollForCkab(DFSDM_Channel_HandleTypeDef *hdfsdm_channel, uint32_t Timeout); -HAL_StatusTypeDef HAL_DFSDM_ChannelPollForScd(DFSDM_Channel_HandleTypeDef *hdfsdm_channel, uint32_t Timeout); - -void HAL_DFSDM_ChannelCkabCallback(DFSDM_Channel_HandleTypeDef *hdfsdm_channel); -void HAL_DFSDM_ChannelScdCallback(DFSDM_Channel_HandleTypeDef *hdfsdm_channel); -/** - * @} - */ - -/** @defgroup DFSDM_Exported_Functions_Group3_Channel Channel state function - * @{ - */ -/* Channel state function *****************************************************/ -HAL_DFSDM_Channel_StateTypeDef HAL_DFSDM_ChannelGetState(DFSDM_Channel_HandleTypeDef *hdfsdm_channel); -/** - * @} - */ - -/** @addtogroup DFSDM_Exported_Functions_Group1_Filter Filter initialization and de-initialization functions - * @{ - */ -/* Filter initialization and de-initialization functions *********************/ -HAL_StatusTypeDef HAL_DFSDM_FilterInit(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -HAL_StatusTypeDef HAL_DFSDM_FilterDeInit(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -void HAL_DFSDM_FilterMspInit(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -void HAL_DFSDM_FilterMspDeInit(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -#if (USE_HAL_DFSDM_REGISTER_CALLBACKS == 1) -/* Filter callbacks register/unregister functions ****************************/ -HAL_StatusTypeDef HAL_DFSDM_Filter_RegisterCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, - HAL_DFSDM_Filter_CallbackIDTypeDef CallbackID, - pDFSDM_Filter_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_DFSDM_Filter_UnRegisterCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, - HAL_DFSDM_Filter_CallbackIDTypeDef CallbackID); -HAL_StatusTypeDef HAL_DFSDM_Filter_RegisterAwdCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, - pDFSDM_Filter_AwdCallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_DFSDM_Filter_UnRegisterAwdCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -#endif -/** - * @} - */ - -/** @addtogroup DFSDM_Exported_Functions_Group2_Filter Filter control functions - * @{ - */ -/* Filter control functions *********************/ -HAL_StatusTypeDef HAL_DFSDM_FilterConfigRegChannel(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, - uint32_t Channel, - uint32_t ContinuousMode); -HAL_StatusTypeDef HAL_DFSDM_FilterConfigInjChannel(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, - uint32_t Channel); -/** - * @} - */ - -/** @addtogroup DFSDM_Exported_Functions_Group3_Filter Filter operation functions - * @{ - */ -/* Filter operation functions *********************/ -HAL_StatusTypeDef HAL_DFSDM_FilterRegularStart(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -HAL_StatusTypeDef HAL_DFSDM_FilterRegularStart_IT(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -HAL_StatusTypeDef HAL_DFSDM_FilterRegularStart_DMA(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, int32_t *pData, uint32_t Length); -HAL_StatusTypeDef HAL_DFSDM_FilterRegularMsbStart_DMA(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, int16_t *pData, uint32_t Length); -HAL_StatusTypeDef HAL_DFSDM_FilterRegularStop(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -HAL_StatusTypeDef HAL_DFSDM_FilterRegularStop_IT(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -HAL_StatusTypeDef HAL_DFSDM_FilterRegularStop_DMA(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -HAL_StatusTypeDef HAL_DFSDM_FilterInjectedStart(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -HAL_StatusTypeDef HAL_DFSDM_FilterInjectedStart_IT(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -HAL_StatusTypeDef HAL_DFSDM_FilterInjectedStart_DMA(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, int32_t *pData, uint32_t Length); -HAL_StatusTypeDef HAL_DFSDM_FilterInjectedMsbStart_DMA(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, int16_t *pData, uint32_t Length); -HAL_StatusTypeDef HAL_DFSDM_FilterInjectedStop(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -HAL_StatusTypeDef HAL_DFSDM_FilterInjectedStop_IT(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -HAL_StatusTypeDef HAL_DFSDM_FilterInjectedStop_DMA(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -HAL_StatusTypeDef HAL_DFSDM_FilterAwdStart_IT(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, - DFSDM_Filter_AwdParamTypeDef* awdParam); -HAL_StatusTypeDef HAL_DFSDM_FilterAwdStop_IT(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -HAL_StatusTypeDef HAL_DFSDM_FilterExdStart(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, uint32_t Channel); -HAL_StatusTypeDef HAL_DFSDM_FilterExdStop(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); - -int32_t HAL_DFSDM_FilterGetRegularValue(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, uint32_t* Channel); -int32_t HAL_DFSDM_FilterGetInjectedValue(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, uint32_t* Channel); -int32_t HAL_DFSDM_FilterGetExdMaxValue(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, uint32_t* Channel); -int32_t HAL_DFSDM_FilterGetExdMinValue(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, uint32_t* Channel); -uint32_t HAL_DFSDM_FilterGetConvTimeValue(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); - -void HAL_DFSDM_IRQHandler(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); - -HAL_StatusTypeDef HAL_DFSDM_FilterPollForRegConversion(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, uint32_t Timeout); -HAL_StatusTypeDef HAL_DFSDM_FilterPollForInjConversion(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, uint32_t Timeout); - -void HAL_DFSDM_FilterRegConvCpltCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -void HAL_DFSDM_FilterRegConvHalfCpltCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -void HAL_DFSDM_FilterInjConvCpltCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -void HAL_DFSDM_FilterInjConvHalfCpltCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -void HAL_DFSDM_FilterAwdCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter, uint32_t Channel, uint32_t Threshold); -void HAL_DFSDM_FilterErrorCallback(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -/** - * @} - */ - -/** @addtogroup DFSDM_Exported_Functions_Group4_Filter Filter state functions - * @{ - */ -/* Filter state functions *****************************************************/ -HAL_DFSDM_Filter_StateTypeDef HAL_DFSDM_FilterGetState(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -uint32_t HAL_DFSDM_FilterGetError(DFSDM_Filter_HandleTypeDef *hdfsdm_filter); -/** - * @} - */ -/** @addtogroup DFSDM_Exported_Functions_Group5_Filter MultiChannel operation functions - * @{ - */ -#if defined(SYSCFG_MCHDLYCR_BSCKSEL) -void HAL_DFSDM_ConfigMultiChannelDelay(DFSDM_MultiChannelConfigTypeDef* mchdlystruct); -void HAL_DFSDM_BitstreamClock_Start(void); -void HAL_DFSDM_BitstreamClock_Stop(void); -void HAL_DFSDM_DisableDelayClock(uint32_t MCHDLY); -void HAL_DFSDM_EnableDelayClock(uint32_t MCHDLY); -void HAL_DFSDM_ClockIn_SourceSelection(uint32_t source); -void HAL_DFSDM_ClockOut_SourceSelection(uint32_t source); -void HAL_DFSDM_DataIn0_SourceSelection(uint32_t source); -void HAL_DFSDM_DataIn2_SourceSelection(uint32_t source); -void HAL_DFSDM_DataIn4_SourceSelection(uint32_t source); -void HAL_DFSDM_DataIn6_SourceSelection(uint32_t source); -void HAL_DFSDM_BitStreamClkDistribution_Config(uint32_t source); -#endif /* SYSCFG_MCHDLYCR_BSCKSEL */ -/** - * @} - */ -/** - * @} - */ -/* End of exported functions -------------------------------------------------*/ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup DFSDM_Private_Macros DFSDM Private Macros -* @{ -*/ -#define IS_DFSDM_CHANNEL_OUTPUT_CLOCK(CLOCK) (((CLOCK) == DFSDM_CHANNEL_OUTPUT_CLOCK_SYSTEM) || \ - ((CLOCK) == DFSDM_CHANNEL_OUTPUT_CLOCK_AUDIO)) -#define IS_DFSDM_CHANNEL_OUTPUT_CLOCK_DIVIDER(DIVIDER) ((2U <= (DIVIDER)) && ((DIVIDER) <= 256U)) -#define IS_DFSDM_CHANNEL_INPUT(INPUT) (((INPUT) == DFSDM_CHANNEL_EXTERNAL_INPUTS) || \ - ((INPUT) == DFSDM_CHANNEL_INTERNAL_REGISTER)) -#define IS_DFSDM_CHANNEL_DATA_PACKING(MODE) (((MODE) == DFSDM_CHANNEL_STANDARD_MODE) || \ - ((MODE) == DFSDM_CHANNEL_INTERLEAVED_MODE) || \ - ((MODE) == DFSDM_CHANNEL_DUAL_MODE)) -#define IS_DFSDM_CHANNEL_INPUT_PINS(PINS) (((PINS) == DFSDM_CHANNEL_SAME_CHANNEL_PINS) || \ - ((PINS) == DFSDM_CHANNEL_FOLLOWING_CHANNEL_PINS)) -#define IS_DFSDM_CHANNEL_SERIAL_INTERFACE_TYPE(MODE) (((MODE) == DFSDM_CHANNEL_SPI_RISING) || \ - ((MODE) == DFSDM_CHANNEL_SPI_FALLING) || \ - ((MODE) == DFSDM_CHANNEL_MANCHESTER_RISING) || \ - ((MODE) == DFSDM_CHANNEL_MANCHESTER_FALLING)) -#define IS_DFSDM_CHANNEL_SPI_CLOCK(TYPE) (((TYPE) == DFSDM_CHANNEL_SPI_CLOCK_EXTERNAL) || \ - ((TYPE) == DFSDM_CHANNEL_SPI_CLOCK_INTERNAL) || \ - ((TYPE) == DFSDM_CHANNEL_SPI_CLOCK_INTERNAL_DIV2_FALLING) || \ - ((TYPE) == DFSDM_CHANNEL_SPI_CLOCK_INTERNAL_DIV2_RISING)) -#define IS_DFSDM_CHANNEL_FILTER_ORDER(ORDER) (((ORDER) == DFSDM_CHANNEL_FASTSINC_ORDER) || \ - ((ORDER) == DFSDM_CHANNEL_SINC1_ORDER) || \ - ((ORDER) == DFSDM_CHANNEL_SINC2_ORDER) || \ - ((ORDER) == DFSDM_CHANNEL_SINC3_ORDER)) -#define IS_DFSDM_CHANNEL_FILTER_OVS_RATIO(RATIO) ((1U <= (RATIO)) && ((RATIO) <= 32U)) -#define IS_DFSDM_CHANNEL_OFFSET(VALUE) ((-8388608 <= (VALUE)) && ((VALUE) <= 8388607)) -#define IS_DFSDM_CHANNEL_RIGHT_BIT_SHIFT(VALUE) ((VALUE) <= 0x1FU) -#define IS_DFSDM_CHANNEL_SCD_THRESHOLD(VALUE) ((VALUE) <= 0xFFU) -#define IS_DFSDM_FILTER_REG_TRIGGER(TRIG) (((TRIG) == DFSDM_FILTER_SW_TRIGGER) || \ - ((TRIG) == DFSDM_FILTER_SYNC_TRIGGER)) -#define IS_DFSDM_FILTER_INJ_TRIGGER(TRIG) (((TRIG) == DFSDM_FILTER_SW_TRIGGER) || \ - ((TRIG) == DFSDM_FILTER_SYNC_TRIGGER) || \ - ((TRIG) == DFSDM_FILTER_EXT_TRIGGER)) -#if defined (STM32F413xx) || defined (STM32F423xx) -#define IS_DFSDM_FILTER_EXT_TRIG(TRIG) (((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM1_TRGO) || \ - ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM3_TRGO) || \ - ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM8_TRGO) || \ - ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM10_OC1) || \ - ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM2_TRGO) || \ - ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM4_TRGO) || \ - ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM11_OC1) || \ - ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM6_TRGO) || \ - ((TRIG) == DFSDM_FILTER_EXT_TRIG_EXTI11) || \ - ((TRIG) == DFSDM_FILTER_EXT_TRIG_EXTI15)) -#define IS_DFSDM_DELAY_CLOCK(CLOCK) (((CLOCK) == HAL_MCHDLY_CLOCK_DFSDM2) || \ - ((CLOCK) == HAL_MCHDLY_CLOCK_DFSDM1)) -#else -#define IS_DFSDM_FILTER_EXT_TRIG(TRIG) (((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM1_TRGO) || \ - ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM3_TRGO) || \ - ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM8_TRGO) || \ - ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM10_OC1) || \ - ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM4_TRGO) || \ - ((TRIG) == DFSDM_FILTER_EXT_TRIG_TIM6_TRGO) || \ - ((TRIG) == DFSDM_FILTER_EXT_TRIG_EXTI11) || \ - ((TRIG) == DFSDM_FILTER_EXT_TRIG_EXTI15)) -#endif -#define IS_DFSDM_FILTER_EXT_TRIG_EDGE(EDGE) (((EDGE) == DFSDM_FILTER_EXT_TRIG_RISING_EDGE) || \ - ((EDGE) == DFSDM_FILTER_EXT_TRIG_FALLING_EDGE) || \ - ((EDGE) == DFSDM_FILTER_EXT_TRIG_BOTH_EDGES)) -#define IS_DFSDM_FILTER_SINC_ORDER(ORDER) (((ORDER) == DFSDM_FILTER_FASTSINC_ORDER) || \ - ((ORDER) == DFSDM_FILTER_SINC1_ORDER) || \ - ((ORDER) == DFSDM_FILTER_SINC2_ORDER) || \ - ((ORDER) == DFSDM_FILTER_SINC3_ORDER) || \ - ((ORDER) == DFSDM_FILTER_SINC4_ORDER) || \ - ((ORDER) == DFSDM_FILTER_SINC5_ORDER)) -#define IS_DFSDM_FILTER_OVS_RATIO(RATIO) ((1U <= (RATIO)) && ((RATIO) <= 1024U)) -#define IS_DFSDM_FILTER_INTEGRATOR_OVS_RATIO(RATIO) ((1U <= (RATIO)) && ((RATIO) <= 256U)) -#define IS_DFSDM_FILTER_AWD_DATA_SOURCE(DATA) (((DATA) == DFSDM_FILTER_AWD_FILTER_DATA) || \ - ((DATA) == DFSDM_FILTER_AWD_CHANNEL_DATA)) -#define IS_DFSDM_FILTER_AWD_THRESHOLD(VALUE) ((-8388608 <= (VALUE)) && ((VALUE) <= 8388607)) -#define IS_DFSDM_BREAK_SIGNALS(VALUE) ((VALUE) <= 0x0FU) -#if defined(DFSDM2_Channel0) -#define IS_DFSDM_REGULAR_CHANNEL(CHANNEL) (((CHANNEL) == DFSDM_CHANNEL_0) || \ - ((CHANNEL) == DFSDM_CHANNEL_1) || \ - ((CHANNEL) == DFSDM_CHANNEL_2) || \ - ((CHANNEL) == DFSDM_CHANNEL_3) || \ - ((CHANNEL) == DFSDM_CHANNEL_4) || \ - ((CHANNEL) == DFSDM_CHANNEL_5) || \ - ((CHANNEL) == DFSDM_CHANNEL_6) || \ - ((CHANNEL) == DFSDM_CHANNEL_7)) -#define IS_DFSDM_INJECTED_CHANNEL(CHANNEL) (((CHANNEL) != 0U) && ((CHANNEL) <= 0x000F00FFU)) -#else -#define IS_DFSDM_REGULAR_CHANNEL(CHANNEL) (((CHANNEL) == DFSDM_CHANNEL_0) || \ - ((CHANNEL) == DFSDM_CHANNEL_1) || \ - ((CHANNEL) == DFSDM_CHANNEL_2) || \ - ((CHANNEL) == DFSDM_CHANNEL_3)) -#define IS_DFSDM_INJECTED_CHANNEL(CHANNEL) (((CHANNEL) != 0U) && ((CHANNEL) <= 0x0003000FU)) -#endif -#define IS_DFSDM_CONTINUOUS_MODE(MODE) (((MODE) == DFSDM_CONTINUOUS_CONV_OFF) || \ - ((MODE) == DFSDM_CONTINUOUS_CONV_ON)) -#if defined(DFSDM2_Channel0) -#define IS_DFSDM1_CHANNEL_INSTANCE(INSTANCE) (((INSTANCE) == DFSDM1_Channel0) || \ - ((INSTANCE) == DFSDM1_Channel1) || \ - ((INSTANCE) == DFSDM1_Channel2) || \ - ((INSTANCE) == DFSDM1_Channel3)) -#define IS_DFSDM1_FILTER_INSTANCE(INSTANCE) (((INSTANCE) == DFSDM1_Filter0) || \ - ((INSTANCE) == DFSDM1_Filter1)) -#endif /* DFSDM2_Channel0 */ - -#if defined(SYSCFG_MCHDLYCR_BSCKSEL) -#define IS_DFSDM_CLOCKIN_SELECTION(SELECTION) (((SELECTION) == HAL_DFSDM2_CKIN_PAD) || \ - ((SELECTION) == HAL_DFSDM2_CKIN_DM) || \ - ((SELECTION) == HAL_DFSDM1_CKIN_PAD) || \ - ((SELECTION) == HAL_DFSDM1_CKIN_DM)) -#define IS_DFSDM_CLOCKOUT_SELECTION(SELECTION) (((SELECTION) == HAL_DFSDM2_CKOUT_DFSDM2) || \ - ((SELECTION) == HAL_DFSDM2_CKOUT_M27) || \ - ((SELECTION) == HAL_DFSDM1_CKOUT_DFSDM1) || \ - ((SELECTION) == HAL_DFSDM1_CKOUT_M27)) -#define IS_DFSDM_DATAIN0_SRC_SELECTION(SELECTION) (((SELECTION) == HAL_DATAIN0_DFSDM2_PAD) || \ - ((SELECTION) == HAL_DATAIN0_DFSDM2_DATAIN1) || \ - ((SELECTION) == HAL_DATAIN0_DFSDM1_PAD) || \ - ((SELECTION) == HAL_DATAIN0_DFSDM1_DATAIN1)) -#define IS_DFSDM_DATAIN2_SRC_SELECTION(SELECTION) (((SELECTION) == HAL_DATAIN2_DFSDM2_PAD) || \ - ((SELECTION) == HAL_DATAIN2_DFSDM2_DATAIN3) || \ - ((SELECTION) == HAL_DATAIN2_DFSDM1_PAD) || \ - ((SELECTION) == HAL_DATAIN2_DFSDM1_DATAIN3)) -#define IS_DFSDM_DATAIN4_SRC_SELECTION(SELECTION) (((SELECTION) == HAL_DATAIN4_DFSDM2_PAD) || \ - ((SELECTION) == HAL_DATAIN4_DFSDM2_DATAIN5)) -#define IS_DFSDM_DATAIN6_SRC_SELECTION(SELECTION) (((SELECTION) == HAL_DATAIN6_DFSDM2_PAD) || \ - ((SELECTION) == HAL_DATAIN6_DFSDM2_DATAIN7)) -#define IS_DFSDM_BITSTREM_CLK_DISTRIBUTION(DISTRIBUTION) (((DISTRIBUTION) == HAL_DFSDM1_CLKIN0_TIM4OC2) || \ - ((DISTRIBUTION) == HAL_DFSDM1_CLKIN2_TIM4OC2) || \ - ((DISTRIBUTION) == HAL_DFSDM1_CLKIN1_TIM4OC1) || \ - ((DISTRIBUTION) == HAL_DFSDM1_CLKIN3_TIM4OC1) || \ - ((DISTRIBUTION) == HAL_DFSDM2_CLKIN0_TIM3OC4) || \ - ((DISTRIBUTION) == HAL_DFSDM2_CLKIN4_TIM3OC4) || \ - ((DISTRIBUTION) == HAL_DFSDM2_CLKIN1_TIM3OC3)|| \ - ((DISTRIBUTION) == HAL_DFSDM2_CLKIN5_TIM3OC3) || \ - ((DISTRIBUTION) == HAL_DFSDM2_CLKIN2_TIM3OC2) || \ - ((DISTRIBUTION) == HAL_DFSDM2_CLKIN6_TIM3OC2) || \ - ((DISTRIBUTION) == HAL_DFSDM2_CLKIN3_TIM3OC1)|| \ - ((DISTRIBUTION) == HAL_DFSDM2_CLKIN7_TIM3OC1)) -#define IS_DFSDM_DFSDM1_CLKOUT(CLKOUT) (((CLKOUT) == DFSDM1_CKOUT_DFSDM2_CKOUT) || \ - ((CLKOUT) == DFSDM1_CKOUT_DFSDM1)) -#define IS_DFSDM_DFSDM2_CLKOUT(CLKOUT) (((CLKOUT) == DFSDM2_CKOUT_DFSDM2_CKOUT) || \ - ((CLKOUT) == DFSDM2_CKOUT_DFSDM2)) -#define IS_DFSDM_DFSDM1_CLKIN(CLKIN) (((CLKIN) == DFSDM1_CKIN_DFSDM2_CKOUT) || \ - ((CLKIN) == DFSDM1_CKIN_PAD)) -#define IS_DFSDM_DFSDM2_CLKIN(CLKIN) (((CLKIN) == DFSDM2_CKIN_DFSDM2_CKOUT) || \ - ((CLKIN) == DFSDM2_CKIN_PAD)) -#define IS_DFSDM_DFSDM1_BIT_CLK(CLK) (((CLK) == DFSDM1_T4_OC2_BITSTREAM_CKIN0) || \ - ((CLK) == DFSDM1_T4_OC2_BITSTREAM_CKIN2) || \ - ((CLK) == DFSDM1_T4_OC1_BITSTREAM_CKIN3) || \ - ((CLK) == DFSDM1_T4_OC1_BITSTREAM_CKIN1) || \ - ((CLK) <= 0x30U)) - -#define IS_DFSDM_DFSDM2_BIT_CLK(CLK) (((CLK) == DFSDM2_T3_OC4_BITSTREAM_CKIN0) || \ - ((CLK) == DFSDM2_T3_OC4_BITSTREAM_CKIN4) || \ - ((CLK) == DFSDM2_T3_OC3_BITSTREAM_CKIN5) || \ - ((CLK) == DFSDM2_T3_OC3_BITSTREAM_CKIN1) || \ - ((CLK) == DFSDM2_T3_OC2_BITSTREAM_CKIN6) || \ - ((CLK) == DFSDM2_T3_OC2_BITSTREAM_CKIN2) || \ - ((CLK) == DFSDM2_T3_OC1_BITSTREAM_CKIN3) || \ - ((CLK) == DFSDM2_T3_OC1_BITSTREAM_CKIN7)|| \ - ((CLK) <= 0x1E000U)) - -#define IS_DFSDM_DFSDM1_DATA_DISTRIBUTION(DISTRIBUTION)(((DISTRIBUTION) == DFSDM1_DATIN0_TO_DATIN0_PAD )|| \ - ((DISTRIBUTION) == DFSDM1_DATIN0_TO_DATIN1_PAD) || \ - ((DISTRIBUTION) == DFSDM1_DATIN2_TO_DATIN2_PAD) || \ - ((DISTRIBUTION) == DFSDM1_DATIN2_TO_DATIN3_PAD)|| \ - ((DISTRIBUTION) <= 0xCU)) - -#define IS_DFSDM_DFSDM2_DATA_DISTRIBUTION(DISTRIBUTION)(((DISTRIBUTION) == DFSDM2_DATIN0_TO_DATIN0_PAD)|| \ - ((DISTRIBUTION) == DFSDM2_DATIN0_TO_DATIN1_PAD)|| \ - ((DISTRIBUTION) == DFSDM2_DATIN2_TO_DATIN2_PAD)|| \ - ((DISTRIBUTION) == DFSDM2_DATIN2_TO_DATIN3_PAD)|| \ - ((DISTRIBUTION) == DFSDM2_DATIN4_TO_DATIN4_PAD)|| \ - ((DISTRIBUTION) == DFSDM2_DATIN4_TO_DATIN5_PAD)|| \ - ((DISTRIBUTION) == DFSDM2_DATIN6_TO_DATIN6_PAD)|| \ - ((DISTRIBUTION) == DFSDM2_DATIN6_TO_DATIN7_PAD)|| \ - ((DISTRIBUTION) <= 0x1D00U)) -#endif /* (SYSCFG_MCHDLYCR_BSCKSEL) */ -/** - * @} - */ -/* End of private macros -----------------------------------------------------*/ - -/** - * @} - */ - -/** - * @} - */ -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_DFSDM_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h deleted file mode 100644 index 90dd292..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma.h +++ /dev/null @@ -1,804 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_dma.h - * @author MCD Application Team - * @brief Header file of DMA HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_DMA_H -#define __STM32F4xx_HAL_DMA_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup DMA - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ - -/** @defgroup DMA_Exported_Types DMA Exported Types - * @brief DMA Exported Types - * @{ - */ - -/** - * @brief DMA Configuration Structure definition - */ -typedef struct -{ - uint32_t Channel; /*!< Specifies the channel used for the specified stream. - This parameter can be a value of @ref DMA_Channel_selection */ - - uint32_t Direction; /*!< Specifies if the data will be transferred from memory to peripheral, - from memory to memory or from peripheral to memory. - This parameter can be a value of @ref DMA_Data_transfer_direction */ - - uint32_t PeriphInc; /*!< Specifies whether the Peripheral address register should be incremented or not. - This parameter can be a value of @ref DMA_Peripheral_incremented_mode */ - - uint32_t MemInc; /*!< Specifies whether the memory address register should be incremented or not. - This parameter can be a value of @ref DMA_Memory_incremented_mode */ - - uint32_t PeriphDataAlignment; /*!< Specifies the Peripheral data width. - This parameter can be a value of @ref DMA_Peripheral_data_size */ - - uint32_t MemDataAlignment; /*!< Specifies the Memory data width. - This parameter can be a value of @ref DMA_Memory_data_size */ - - uint32_t Mode; /*!< Specifies the operation mode of the DMAy Streamx. - This parameter can be a value of @ref DMA_mode - @note The circular buffer mode cannot be used if the memory-to-memory - data transfer is configured on the selected Stream */ - - uint32_t Priority; /*!< Specifies the software priority for the DMAy Streamx. - This parameter can be a value of @ref DMA_Priority_level */ - - uint32_t FIFOMode; /*!< Specifies if the FIFO mode or Direct mode will be used for the specified stream. - This parameter can be a value of @ref DMA_FIFO_direct_mode - @note The Direct mode (FIFO mode disabled) cannot be used if the - memory-to-memory data transfer is configured on the selected stream */ - - uint32_t FIFOThreshold; /*!< Specifies the FIFO threshold level. - This parameter can be a value of @ref DMA_FIFO_threshold_level */ - - uint32_t MemBurst; /*!< Specifies the Burst transfer configuration for the memory transfers. - It specifies the amount of data to be transferred in a single non interruptible - transaction. - This parameter can be a value of @ref DMA_Memory_burst - @note The burst mode is possible only if the address Increment mode is enabled. */ - - uint32_t PeriphBurst; /*!< Specifies the Burst transfer configuration for the peripheral transfers. - It specifies the amount of data to be transferred in a single non interruptible - transaction. - This parameter can be a value of @ref DMA_Peripheral_burst - @note The burst mode is possible only if the address Increment mode is enabled. */ -}DMA_InitTypeDef; - - -/** - * @brief HAL DMA State structures definition - */ -typedef enum -{ - HAL_DMA_STATE_RESET = 0x00U, /*!< DMA not yet initialized or disabled */ - HAL_DMA_STATE_READY = 0x01U, /*!< DMA initialized and ready for use */ - HAL_DMA_STATE_BUSY = 0x02U, /*!< DMA process is ongoing */ - HAL_DMA_STATE_TIMEOUT = 0x03U, /*!< DMA timeout state */ - HAL_DMA_STATE_ERROR = 0x04U, /*!< DMA error state */ - HAL_DMA_STATE_ABORT = 0x05U, /*!< DMA Abort state */ -}HAL_DMA_StateTypeDef; - -/** - * @brief HAL DMA Error Code structure definition - */ -typedef enum -{ - HAL_DMA_FULL_TRANSFER = 0x00U, /*!< Full transfer */ - HAL_DMA_HALF_TRANSFER = 0x01U /*!< Half Transfer */ -}HAL_DMA_LevelCompleteTypeDef; - -/** - * @brief HAL DMA Error Code structure definition - */ -typedef enum -{ - HAL_DMA_XFER_CPLT_CB_ID = 0x00U, /*!< Full transfer */ - HAL_DMA_XFER_HALFCPLT_CB_ID = 0x01U, /*!< Half Transfer */ - HAL_DMA_XFER_M1CPLT_CB_ID = 0x02U, /*!< M1 Full Transfer */ - HAL_DMA_XFER_M1HALFCPLT_CB_ID = 0x03U, /*!< M1 Half Transfer */ - HAL_DMA_XFER_ERROR_CB_ID = 0x04U, /*!< Error */ - HAL_DMA_XFER_ABORT_CB_ID = 0x05U, /*!< Abort */ - HAL_DMA_XFER_ALL_CB_ID = 0x06U /*!< All */ -}HAL_DMA_CallbackIDTypeDef; - -/** - * @brief DMA handle Structure definition - */ -typedef struct __DMA_HandleTypeDef -{ - DMA_Stream_TypeDef *Instance; /*!< Register base address */ - - DMA_InitTypeDef Init; /*!< DMA communication parameters */ - - HAL_LockTypeDef Lock; /*!< DMA locking object */ - - __IO HAL_DMA_StateTypeDef State; /*!< DMA transfer state */ - - void *Parent; /*!< Parent object state */ - - void (* XferCpltCallback)( struct __DMA_HandleTypeDef * hdma); /*!< DMA transfer complete callback */ - - void (* XferHalfCpltCallback)( struct __DMA_HandleTypeDef * hdma); /*!< DMA Half transfer complete callback */ - - void (* XferM1CpltCallback)( struct __DMA_HandleTypeDef * hdma); /*!< DMA transfer complete Memory1 callback */ - - void (* XferM1HalfCpltCallback)( struct __DMA_HandleTypeDef * hdma); /*!< DMA transfer Half complete Memory1 callback */ - - void (* XferErrorCallback)( struct __DMA_HandleTypeDef * hdma); /*!< DMA transfer error callback */ - - void (* XferAbortCallback)( struct __DMA_HandleTypeDef * hdma); /*!< DMA transfer Abort callback */ - - __IO uint32_t ErrorCode; /*!< DMA Error code */ - - uint32_t StreamBaseAddress; /*!< DMA Stream Base Address */ - - uint32_t StreamIndex; /*!< DMA Stream Index */ - -}DMA_HandleTypeDef; - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ - -/** @defgroup DMA_Exported_Constants DMA Exported Constants - * @brief DMA Exported constants - * @{ - */ - -/** @defgroup DMA_Error_Code DMA Error Code - * @brief DMA Error Code - * @{ - */ -#define HAL_DMA_ERROR_NONE 0x00000000U /*!< No error */ -#define HAL_DMA_ERROR_TE 0x00000001U /*!< Transfer error */ -#define HAL_DMA_ERROR_FE 0x00000002U /*!< FIFO error */ -#define HAL_DMA_ERROR_DME 0x00000004U /*!< Direct Mode error */ -#define HAL_DMA_ERROR_TIMEOUT 0x00000020U /*!< Timeout error */ -#define HAL_DMA_ERROR_PARAM 0x00000040U /*!< Parameter error */ -#define HAL_DMA_ERROR_NO_XFER 0x00000080U /*!< Abort requested with no Xfer ongoing */ -#define HAL_DMA_ERROR_NOT_SUPPORTED 0x00000100U /*!< Not supported mode */ -/** - * @} - */ - -/** @defgroup DMA_Channel_selection DMA Channel selection - * @brief DMA channel selection - * @{ - */ -#define DMA_CHANNEL_0 0x00000000U /*!< DMA Channel 0 */ -#define DMA_CHANNEL_1 0x02000000U /*!< DMA Channel 1 */ -#define DMA_CHANNEL_2 0x04000000U /*!< DMA Channel 2 */ -#define DMA_CHANNEL_3 0x06000000U /*!< DMA Channel 3 */ -#define DMA_CHANNEL_4 0x08000000U /*!< DMA Channel 4 */ -#define DMA_CHANNEL_5 0x0A000000U /*!< DMA Channel 5 */ -#define DMA_CHANNEL_6 0x0C000000U /*!< DMA Channel 6 */ -#define DMA_CHANNEL_7 0x0E000000U /*!< DMA Channel 7 */ -#if defined (DMA_SxCR_CHSEL_3) -#define DMA_CHANNEL_8 0x10000000U /*!< DMA Channel 8 */ -#define DMA_CHANNEL_9 0x12000000U /*!< DMA Channel 9 */ -#define DMA_CHANNEL_10 0x14000000U /*!< DMA Channel 10 */ -#define DMA_CHANNEL_11 0x16000000U /*!< DMA Channel 11 */ -#define DMA_CHANNEL_12 0x18000000U /*!< DMA Channel 12 */ -#define DMA_CHANNEL_13 0x1A000000U /*!< DMA Channel 13 */ -#define DMA_CHANNEL_14 0x1C000000U /*!< DMA Channel 14 */ -#define DMA_CHANNEL_15 0x1E000000U /*!< DMA Channel 15 */ -#endif /* DMA_SxCR_CHSEL_3 */ -/** - * @} - */ - -/** @defgroup DMA_Data_transfer_direction DMA Data transfer direction - * @brief DMA data transfer direction - * @{ - */ -#define DMA_PERIPH_TO_MEMORY 0x00000000U /*!< Peripheral to memory direction */ -#define DMA_MEMORY_TO_PERIPH ((uint32_t)DMA_SxCR_DIR_0) /*!< Memory to peripheral direction */ -#define DMA_MEMORY_TO_MEMORY ((uint32_t)DMA_SxCR_DIR_1) /*!< Memory to memory direction */ -/** - * @} - */ - -/** @defgroup DMA_Peripheral_incremented_mode DMA Peripheral incremented mode - * @brief DMA peripheral incremented mode - * @{ - */ -#define DMA_PINC_ENABLE ((uint32_t)DMA_SxCR_PINC) /*!< Peripheral increment mode enable */ -#define DMA_PINC_DISABLE 0x00000000U /*!< Peripheral increment mode disable */ -/** - * @} - */ - -/** @defgroup DMA_Memory_incremented_mode DMA Memory incremented mode - * @brief DMA memory incremented mode - * @{ - */ -#define DMA_MINC_ENABLE ((uint32_t)DMA_SxCR_MINC) /*!< Memory increment mode enable */ -#define DMA_MINC_DISABLE 0x00000000U /*!< Memory increment mode disable */ -/** - * @} - */ - -/** @defgroup DMA_Peripheral_data_size DMA Peripheral data size - * @brief DMA peripheral data size - * @{ - */ -#define DMA_PDATAALIGN_BYTE 0x00000000U /*!< Peripheral data alignment: Byte */ -#define DMA_PDATAALIGN_HALFWORD ((uint32_t)DMA_SxCR_PSIZE_0) /*!< Peripheral data alignment: HalfWord */ -#define DMA_PDATAALIGN_WORD ((uint32_t)DMA_SxCR_PSIZE_1) /*!< Peripheral data alignment: Word */ -/** - * @} - */ - -/** @defgroup DMA_Memory_data_size DMA Memory data size - * @brief DMA memory data size - * @{ - */ -#define DMA_MDATAALIGN_BYTE 0x00000000U /*!< Memory data alignment: Byte */ -#define DMA_MDATAALIGN_HALFWORD ((uint32_t)DMA_SxCR_MSIZE_0) /*!< Memory data alignment: HalfWord */ -#define DMA_MDATAALIGN_WORD ((uint32_t)DMA_SxCR_MSIZE_1) /*!< Memory data alignment: Word */ -/** - * @} - */ - -/** @defgroup DMA_mode DMA mode - * @brief DMA mode - * @{ - */ -#define DMA_NORMAL 0x00000000U /*!< Normal mode */ -#define DMA_CIRCULAR ((uint32_t)DMA_SxCR_CIRC) /*!< Circular mode */ -#define DMA_PFCTRL ((uint32_t)DMA_SxCR_PFCTRL) /*!< Peripheral flow control mode */ -/** - * @} - */ - -/** @defgroup DMA_Priority_level DMA Priority level - * @brief DMA priority levels - * @{ - */ -#define DMA_PRIORITY_LOW 0x00000000U /*!< Priority level: Low */ -#define DMA_PRIORITY_MEDIUM ((uint32_t)DMA_SxCR_PL_0) /*!< Priority level: Medium */ -#define DMA_PRIORITY_HIGH ((uint32_t)DMA_SxCR_PL_1) /*!< Priority level: High */ -#define DMA_PRIORITY_VERY_HIGH ((uint32_t)DMA_SxCR_PL) /*!< Priority level: Very High */ -/** - * @} - */ - -/** @defgroup DMA_FIFO_direct_mode DMA FIFO direct mode - * @brief DMA FIFO direct mode - * @{ - */ -#define DMA_FIFOMODE_DISABLE 0x00000000U /*!< FIFO mode disable */ -#define DMA_FIFOMODE_ENABLE ((uint32_t)DMA_SxFCR_DMDIS) /*!< FIFO mode enable */ -/** - * @} - */ - -/** @defgroup DMA_FIFO_threshold_level DMA FIFO threshold level - * @brief DMA FIFO level - * @{ - */ -#define DMA_FIFO_THRESHOLD_1QUARTERFULL 0x00000000U /*!< FIFO threshold 1 quart full configuration */ -#define DMA_FIFO_THRESHOLD_HALFFULL ((uint32_t)DMA_SxFCR_FTH_0) /*!< FIFO threshold half full configuration */ -#define DMA_FIFO_THRESHOLD_3QUARTERSFULL ((uint32_t)DMA_SxFCR_FTH_1) /*!< FIFO threshold 3 quarts full configuration */ -#define DMA_FIFO_THRESHOLD_FULL ((uint32_t)DMA_SxFCR_FTH) /*!< FIFO threshold full configuration */ -/** - * @} - */ - -/** @defgroup DMA_Memory_burst DMA Memory burst - * @brief DMA memory burst - * @{ - */ -#define DMA_MBURST_SINGLE 0x00000000U -#define DMA_MBURST_INC4 ((uint32_t)DMA_SxCR_MBURST_0) -#define DMA_MBURST_INC8 ((uint32_t)DMA_SxCR_MBURST_1) -#define DMA_MBURST_INC16 ((uint32_t)DMA_SxCR_MBURST) -/** - * @} - */ - -/** @defgroup DMA_Peripheral_burst DMA Peripheral burst - * @brief DMA peripheral burst - * @{ - */ -#define DMA_PBURST_SINGLE 0x00000000U -#define DMA_PBURST_INC4 ((uint32_t)DMA_SxCR_PBURST_0) -#define DMA_PBURST_INC8 ((uint32_t)DMA_SxCR_PBURST_1) -#define DMA_PBURST_INC16 ((uint32_t)DMA_SxCR_PBURST) -/** - * @} - */ - -/** @defgroup DMA_interrupt_enable_definitions DMA interrupt enable definitions - * @brief DMA interrupts definition - * @{ - */ -#define DMA_IT_TC ((uint32_t)DMA_SxCR_TCIE) -#define DMA_IT_HT ((uint32_t)DMA_SxCR_HTIE) -#define DMA_IT_TE ((uint32_t)DMA_SxCR_TEIE) -#define DMA_IT_DME ((uint32_t)DMA_SxCR_DMEIE) -#define DMA_IT_FE 0x00000080U -/** - * @} - */ - -/** @defgroup DMA_flag_definitions DMA flag definitions - * @brief DMA flag definitions - * @{ - */ -#define DMA_FLAG_FEIF0_4 0x00000001U -#define DMA_FLAG_DMEIF0_4 0x00000004U -#define DMA_FLAG_TEIF0_4 0x00000008U -#define DMA_FLAG_HTIF0_4 0x00000010U -#define DMA_FLAG_TCIF0_4 0x00000020U -#define DMA_FLAG_FEIF1_5 0x00000040U -#define DMA_FLAG_DMEIF1_5 0x00000100U -#define DMA_FLAG_TEIF1_5 0x00000200U -#define DMA_FLAG_HTIF1_5 0x00000400U -#define DMA_FLAG_TCIF1_5 0x00000800U -#define DMA_FLAG_FEIF2_6 0x00010000U -#define DMA_FLAG_DMEIF2_6 0x00040000U -#define DMA_FLAG_TEIF2_6 0x00080000U -#define DMA_FLAG_HTIF2_6 0x00100000U -#define DMA_FLAG_TCIF2_6 0x00200000U -#define DMA_FLAG_FEIF3_7 0x00400000U -#define DMA_FLAG_DMEIF3_7 0x01000000U -#define DMA_FLAG_TEIF3_7 0x02000000U -#define DMA_FLAG_HTIF3_7 0x04000000U -#define DMA_FLAG_TCIF3_7 0x08000000U -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ - -/** @brief Reset DMA handle state - * @param __HANDLE__ specifies the DMA handle. - * @retval None - */ -#define __HAL_DMA_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_DMA_STATE_RESET) - -/** - * @brief Return the current DMA Stream FIFO filled level. - * @param __HANDLE__ DMA handle - * @retval The FIFO filling state. - * - DMA_FIFOStatus_Less1QuarterFull: when FIFO is less than 1 quarter-full - * and not empty. - * - DMA_FIFOStatus_1QuarterFull: if more than 1 quarter-full. - * - DMA_FIFOStatus_HalfFull: if more than 1 half-full. - * - DMA_FIFOStatus_3QuartersFull: if more than 3 quarters-full. - * - DMA_FIFOStatus_Empty: when FIFO is empty - * - DMA_FIFOStatus_Full: when FIFO is full - */ -#define __HAL_DMA_GET_FS(__HANDLE__) (((__HANDLE__)->Instance->FCR & (DMA_SxFCR_FS))) - -/** - * @brief Enable the specified DMA Stream. - * @param __HANDLE__ DMA handle - * @retval None - */ -#define __HAL_DMA_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= DMA_SxCR_EN) - -/** - * @brief Disable the specified DMA Stream. - * @param __HANDLE__ DMA handle - * @retval None - */ -#define __HAL_DMA_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR &= ~DMA_SxCR_EN) - -/* Interrupt & Flag management */ - -/** - * @brief Return the current DMA Stream transfer complete flag. - * @param __HANDLE__ DMA handle - * @retval The specified transfer complete flag index. - */ -#define __HAL_DMA_GET_TC_FLAG_INDEX(__HANDLE__) \ -(((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream0))? DMA_FLAG_TCIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream0))? DMA_FLAG_TCIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream4))? DMA_FLAG_TCIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream4))? DMA_FLAG_TCIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream1))? DMA_FLAG_TCIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream1))? DMA_FLAG_TCIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream5))? DMA_FLAG_TCIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream5))? DMA_FLAG_TCIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream2))? DMA_FLAG_TCIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream2))? DMA_FLAG_TCIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream6))? DMA_FLAG_TCIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream6))? DMA_FLAG_TCIF2_6 :\ - DMA_FLAG_TCIF3_7) - -/** - * @brief Return the current DMA Stream half transfer complete flag. - * @param __HANDLE__ DMA handle - * @retval The specified half transfer complete flag index. - */ -#define __HAL_DMA_GET_HT_FLAG_INDEX(__HANDLE__)\ -(((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream0))? DMA_FLAG_HTIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream0))? DMA_FLAG_HTIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream4))? DMA_FLAG_HTIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream4))? DMA_FLAG_HTIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream1))? DMA_FLAG_HTIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream1))? DMA_FLAG_HTIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream5))? DMA_FLAG_HTIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream5))? DMA_FLAG_HTIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream2))? DMA_FLAG_HTIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream2))? DMA_FLAG_HTIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream6))? DMA_FLAG_HTIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream6))? DMA_FLAG_HTIF2_6 :\ - DMA_FLAG_HTIF3_7) - -/** - * @brief Return the current DMA Stream transfer error flag. - * @param __HANDLE__ DMA handle - * @retval The specified transfer error flag index. - */ -#define __HAL_DMA_GET_TE_FLAG_INDEX(__HANDLE__)\ -(((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream0))? DMA_FLAG_TEIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream0))? DMA_FLAG_TEIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream4))? DMA_FLAG_TEIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream4))? DMA_FLAG_TEIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream1))? DMA_FLAG_TEIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream1))? DMA_FLAG_TEIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream5))? DMA_FLAG_TEIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream5))? DMA_FLAG_TEIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream2))? DMA_FLAG_TEIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream2))? DMA_FLAG_TEIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream6))? DMA_FLAG_TEIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream6))? DMA_FLAG_TEIF2_6 :\ - DMA_FLAG_TEIF3_7) - -/** - * @brief Return the current DMA Stream FIFO error flag. - * @param __HANDLE__ DMA handle - * @retval The specified FIFO error flag index. - */ -#define __HAL_DMA_GET_FE_FLAG_INDEX(__HANDLE__)\ -(((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream0))? DMA_FLAG_FEIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream0))? DMA_FLAG_FEIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream4))? DMA_FLAG_FEIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream4))? DMA_FLAG_FEIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream1))? DMA_FLAG_FEIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream1))? DMA_FLAG_FEIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream5))? DMA_FLAG_FEIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream5))? DMA_FLAG_FEIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream2))? DMA_FLAG_FEIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream2))? DMA_FLAG_FEIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream6))? DMA_FLAG_FEIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream6))? DMA_FLAG_FEIF2_6 :\ - DMA_FLAG_FEIF3_7) - -/** - * @brief Return the current DMA Stream direct mode error flag. - * @param __HANDLE__ DMA handle - * @retval The specified direct mode error flag index. - */ -#define __HAL_DMA_GET_DME_FLAG_INDEX(__HANDLE__)\ -(((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream0))? DMA_FLAG_DMEIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream0))? DMA_FLAG_DMEIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream4))? DMA_FLAG_DMEIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream4))? DMA_FLAG_DMEIF0_4 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream1))? DMA_FLAG_DMEIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream1))? DMA_FLAG_DMEIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream5))? DMA_FLAG_DMEIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream5))? DMA_FLAG_DMEIF1_5 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream2))? DMA_FLAG_DMEIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream2))? DMA_FLAG_DMEIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA1_Stream6))? DMA_FLAG_DMEIF2_6 :\ - ((uint32_t)((__HANDLE__)->Instance) == ((uint32_t)DMA2_Stream6))? DMA_FLAG_DMEIF2_6 :\ - DMA_FLAG_DMEIF3_7) - -/** - * @brief Get the DMA Stream pending flags. - * @param __HANDLE__ DMA handle - * @param __FLAG__ Get the specified flag. - * This parameter can be any combination of the following values: - * @arg DMA_FLAG_TCIFx: Transfer complete flag. - * @arg DMA_FLAG_HTIFx: Half transfer complete flag. - * @arg DMA_FLAG_TEIFx: Transfer error flag. - * @arg DMA_FLAG_DMEIFx: Direct mode error flag. - * @arg DMA_FLAG_FEIFx: FIFO error flag. - * Where x can be 0_4, 1_5, 2_6 or 3_7 to select the DMA Stream flag. - * @retval The state of FLAG (SET or RESET). - */ -#define __HAL_DMA_GET_FLAG(__HANDLE__, __FLAG__)\ -(((uint32_t)((__HANDLE__)->Instance) > (uint32_t)DMA2_Stream3)? (DMA2->HISR & (__FLAG__)) :\ - ((uint32_t)((__HANDLE__)->Instance) > (uint32_t)DMA1_Stream7)? (DMA2->LISR & (__FLAG__)) :\ - ((uint32_t)((__HANDLE__)->Instance) > (uint32_t)DMA1_Stream3)? (DMA1->HISR & (__FLAG__)) : (DMA1->LISR & (__FLAG__))) - -/** - * @brief Clear the DMA Stream pending flags. - * @param __HANDLE__ DMA handle - * @param __FLAG__ specifies the flag to clear. - * This parameter can be any combination of the following values: - * @arg DMA_FLAG_TCIFx: Transfer complete flag. - * @arg DMA_FLAG_HTIFx: Half transfer complete flag. - * @arg DMA_FLAG_TEIFx: Transfer error flag. - * @arg DMA_FLAG_DMEIFx: Direct mode error flag. - * @arg DMA_FLAG_FEIFx: FIFO error flag. - * Where x can be 0_4, 1_5, 2_6 or 3_7 to select the DMA Stream flag. - * @retval None - */ -#define __HAL_DMA_CLEAR_FLAG(__HANDLE__, __FLAG__) \ -(((uint32_t)((__HANDLE__)->Instance) > (uint32_t)DMA2_Stream3)? (DMA2->HIFCR = (__FLAG__)) :\ - ((uint32_t)((__HANDLE__)->Instance) > (uint32_t)DMA1_Stream7)? (DMA2->LIFCR = (__FLAG__)) :\ - ((uint32_t)((__HANDLE__)->Instance) > (uint32_t)DMA1_Stream3)? (DMA1->HIFCR = (__FLAG__)) : (DMA1->LIFCR = (__FLAG__))) - -/** - * @brief Enable the specified DMA Stream interrupts. - * @param __HANDLE__ DMA handle - * @param __INTERRUPT__ specifies the DMA interrupt sources to be enabled or disabled. - * This parameter can be any combination of the following values: - * @arg DMA_IT_TC: Transfer complete interrupt mask. - * @arg DMA_IT_HT: Half transfer complete interrupt mask. - * @arg DMA_IT_TE: Transfer error interrupt mask. - * @arg DMA_IT_FE: FIFO error interrupt mask. - * @arg DMA_IT_DME: Direct mode error interrupt. - * @retval None - */ -#define __HAL_DMA_ENABLE_IT(__HANDLE__, __INTERRUPT__) (((__INTERRUPT__) != DMA_IT_FE)? \ -((__HANDLE__)->Instance->CR |= (__INTERRUPT__)) : ((__HANDLE__)->Instance->FCR |= (__INTERRUPT__))) - -/** - * @brief Disable the specified DMA Stream interrupts. - * @param __HANDLE__ DMA handle - * @param __INTERRUPT__ specifies the DMA interrupt sources to be enabled or disabled. - * This parameter can be any combination of the following values: - * @arg DMA_IT_TC: Transfer complete interrupt mask. - * @arg DMA_IT_HT: Half transfer complete interrupt mask. - * @arg DMA_IT_TE: Transfer error interrupt mask. - * @arg DMA_IT_FE: FIFO error interrupt mask. - * @arg DMA_IT_DME: Direct mode error interrupt. - * @retval None - */ -#define __HAL_DMA_DISABLE_IT(__HANDLE__, __INTERRUPT__) (((__INTERRUPT__) != DMA_IT_FE)? \ -((__HANDLE__)->Instance->CR &= ~(__INTERRUPT__)) : ((__HANDLE__)->Instance->FCR &= ~(__INTERRUPT__))) - -/** - * @brief Check whether the specified DMA Stream interrupt is enabled or disabled. - * @param __HANDLE__ DMA handle - * @param __INTERRUPT__ specifies the DMA interrupt source to check. - * This parameter can be one of the following values: - * @arg DMA_IT_TC: Transfer complete interrupt mask. - * @arg DMA_IT_HT: Half transfer complete interrupt mask. - * @arg DMA_IT_TE: Transfer error interrupt mask. - * @arg DMA_IT_FE: FIFO error interrupt mask. - * @arg DMA_IT_DME: Direct mode error interrupt. - * @retval The state of DMA_IT. - */ -#define __HAL_DMA_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) (((__INTERRUPT__) != DMA_IT_FE)? \ - ((__HANDLE__)->Instance->CR & (__INTERRUPT__)) : \ - ((__HANDLE__)->Instance->FCR & (__INTERRUPT__))) - -/** - * @brief Writes the number of data units to be transferred on the DMA Stream. - * @param __HANDLE__ DMA handle - * @param __COUNTER__ Number of data units to be transferred (from 0 to 65535) - * Number of data items depends only on the Peripheral data format. - * - * @note If Peripheral data format is Bytes: number of data units is equal - * to total number of bytes to be transferred. - * - * @note If Peripheral data format is Half-Word: number of data units is - * equal to total number of bytes to be transferred / 2. - * - * @note If Peripheral data format is Word: number of data units is equal - * to total number of bytes to be transferred / 4. - * - * @retval The number of remaining data units in the current DMAy Streamx transfer. - */ -#define __HAL_DMA_SET_COUNTER(__HANDLE__, __COUNTER__) ((__HANDLE__)->Instance->NDTR = (uint16_t)(__COUNTER__)) - -/** - * @brief Returns the number of remaining data units in the current DMAy Streamx transfer. - * @param __HANDLE__ DMA handle - * - * @retval The number of remaining data units in the current DMA Stream transfer. - */ -#define __HAL_DMA_GET_COUNTER(__HANDLE__) ((__HANDLE__)->Instance->NDTR) - - -/* Include DMA HAL Extension module */ -#include "stm32f4xx_hal_dma_ex.h" - -/* Exported functions --------------------------------------------------------*/ - -/** @defgroup DMA_Exported_Functions DMA Exported Functions - * @brief DMA Exported functions - * @{ - */ - -/** @defgroup DMA_Exported_Functions_Group1 Initialization and de-initialization functions - * @brief Initialization and de-initialization functions - * @{ - */ -HAL_StatusTypeDef HAL_DMA_Init(DMA_HandleTypeDef *hdma); -HAL_StatusTypeDef HAL_DMA_DeInit(DMA_HandleTypeDef *hdma); -/** - * @} - */ - -/** @defgroup DMA_Exported_Functions_Group2 I/O operation functions - * @brief I/O operation functions - * @{ - */ -HAL_StatusTypeDef HAL_DMA_Start (DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength); -HAL_StatusTypeDef HAL_DMA_Start_IT(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t DataLength); -HAL_StatusTypeDef HAL_DMA_Abort(DMA_HandleTypeDef *hdma); -HAL_StatusTypeDef HAL_DMA_Abort_IT(DMA_HandleTypeDef *hdma); -HAL_StatusTypeDef HAL_DMA_PollForTransfer(DMA_HandleTypeDef *hdma, HAL_DMA_LevelCompleteTypeDef CompleteLevel, uint32_t Timeout); -void HAL_DMA_IRQHandler(DMA_HandleTypeDef *hdma); -HAL_StatusTypeDef HAL_DMA_CleanCallbacks(DMA_HandleTypeDef *hdma); -HAL_StatusTypeDef HAL_DMA_RegisterCallback(DMA_HandleTypeDef *hdma, HAL_DMA_CallbackIDTypeDef CallbackID, void (* pCallback)(DMA_HandleTypeDef *_hdma)); -HAL_StatusTypeDef HAL_DMA_UnRegisterCallback(DMA_HandleTypeDef *hdma, HAL_DMA_CallbackIDTypeDef CallbackID); - -/** - * @} - */ - -/** @defgroup DMA_Exported_Functions_Group3 Peripheral State functions - * @brief Peripheral State functions - * @{ - */ -HAL_DMA_StateTypeDef HAL_DMA_GetState(DMA_HandleTypeDef *hdma); -uint32_t HAL_DMA_GetError(DMA_HandleTypeDef *hdma); -/** - * @} - */ -/** - * @} - */ -/* Private Constants -------------------------------------------------------------*/ -/** @defgroup DMA_Private_Constants DMA Private Constants - * @brief DMA private defines and constants - * @{ - */ -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup DMA_Private_Macros DMA Private Macros - * @brief DMA private macros - * @{ - */ -#if defined (DMA_SxCR_CHSEL_3) -#define IS_DMA_CHANNEL(CHANNEL) (((CHANNEL) == DMA_CHANNEL_0) || \ - ((CHANNEL) == DMA_CHANNEL_1) || \ - ((CHANNEL) == DMA_CHANNEL_2) || \ - ((CHANNEL) == DMA_CHANNEL_3) || \ - ((CHANNEL) == DMA_CHANNEL_4) || \ - ((CHANNEL) == DMA_CHANNEL_5) || \ - ((CHANNEL) == DMA_CHANNEL_6) || \ - ((CHANNEL) == DMA_CHANNEL_7) || \ - ((CHANNEL) == DMA_CHANNEL_8) || \ - ((CHANNEL) == DMA_CHANNEL_9) || \ - ((CHANNEL) == DMA_CHANNEL_10)|| \ - ((CHANNEL) == DMA_CHANNEL_11)|| \ - ((CHANNEL) == DMA_CHANNEL_12)|| \ - ((CHANNEL) == DMA_CHANNEL_13)|| \ - ((CHANNEL) == DMA_CHANNEL_14)|| \ - ((CHANNEL) == DMA_CHANNEL_15)) -#else -#define IS_DMA_CHANNEL(CHANNEL) (((CHANNEL) == DMA_CHANNEL_0) || \ - ((CHANNEL) == DMA_CHANNEL_1) || \ - ((CHANNEL) == DMA_CHANNEL_2) || \ - ((CHANNEL) == DMA_CHANNEL_3) || \ - ((CHANNEL) == DMA_CHANNEL_4) || \ - ((CHANNEL) == DMA_CHANNEL_5) || \ - ((CHANNEL) == DMA_CHANNEL_6) || \ - ((CHANNEL) == DMA_CHANNEL_7)) -#endif /* DMA_SxCR_CHSEL_3 */ - -#define IS_DMA_DIRECTION(DIRECTION) (((DIRECTION) == DMA_PERIPH_TO_MEMORY ) || \ - ((DIRECTION) == DMA_MEMORY_TO_PERIPH) || \ - ((DIRECTION) == DMA_MEMORY_TO_MEMORY)) - -#define IS_DMA_BUFFER_SIZE(SIZE) (((SIZE) >= 0x01U) && ((SIZE) < 0x10000U)) - -#define IS_DMA_PERIPHERAL_INC_STATE(STATE) (((STATE) == DMA_PINC_ENABLE) || \ - ((STATE) == DMA_PINC_DISABLE)) - -#define IS_DMA_MEMORY_INC_STATE(STATE) (((STATE) == DMA_MINC_ENABLE) || \ - ((STATE) == DMA_MINC_DISABLE)) - -#define IS_DMA_PERIPHERAL_DATA_SIZE(SIZE) (((SIZE) == DMA_PDATAALIGN_BYTE) || \ - ((SIZE) == DMA_PDATAALIGN_HALFWORD) || \ - ((SIZE) == DMA_PDATAALIGN_WORD)) - -#define IS_DMA_MEMORY_DATA_SIZE(SIZE) (((SIZE) == DMA_MDATAALIGN_BYTE) || \ - ((SIZE) == DMA_MDATAALIGN_HALFWORD) || \ - ((SIZE) == DMA_MDATAALIGN_WORD )) - -#define IS_DMA_MODE(MODE) (((MODE) == DMA_NORMAL ) || \ - ((MODE) == DMA_CIRCULAR) || \ - ((MODE) == DMA_PFCTRL)) - -#define IS_DMA_PRIORITY(PRIORITY) (((PRIORITY) == DMA_PRIORITY_LOW ) || \ - ((PRIORITY) == DMA_PRIORITY_MEDIUM) || \ - ((PRIORITY) == DMA_PRIORITY_HIGH) || \ - ((PRIORITY) == DMA_PRIORITY_VERY_HIGH)) - -#define IS_DMA_FIFO_MODE_STATE(STATE) (((STATE) == DMA_FIFOMODE_DISABLE ) || \ - ((STATE) == DMA_FIFOMODE_ENABLE)) - -#define IS_DMA_FIFO_THRESHOLD(THRESHOLD) (((THRESHOLD) == DMA_FIFO_THRESHOLD_1QUARTERFULL ) || \ - ((THRESHOLD) == DMA_FIFO_THRESHOLD_HALFFULL) || \ - ((THRESHOLD) == DMA_FIFO_THRESHOLD_3QUARTERSFULL) || \ - ((THRESHOLD) == DMA_FIFO_THRESHOLD_FULL)) - -#define IS_DMA_MEMORY_BURST(BURST) (((BURST) == DMA_MBURST_SINGLE) || \ - ((BURST) == DMA_MBURST_INC4) || \ - ((BURST) == DMA_MBURST_INC8) || \ - ((BURST) == DMA_MBURST_INC16)) - -#define IS_DMA_PERIPHERAL_BURST(BURST) (((BURST) == DMA_PBURST_SINGLE) || \ - ((BURST) == DMA_PBURST_INC4) || \ - ((BURST) == DMA_PBURST_INC8) || \ - ((BURST) == DMA_PBURST_INC16)) -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup DMA_Private_Functions DMA Private Functions - * @brief DMA private functions - * @{ - */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_DMA_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma2d.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma2d.h deleted file mode 100644 index 158ed67..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma2d.h +++ /dev/null @@ -1,651 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_dma2d.h - * @author MCD Application Team - * @brief Header file of DMA2D HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_DMA2D_H -#define STM32F4xx_HAL_DMA2D_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -#if defined (DMA2D) - -/** @addtogroup DMA2D DMA2D - * @brief DMA2D HAL module driver - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup DMA2D_Exported_Types DMA2D Exported Types - * @{ - */ -#define MAX_DMA2D_LAYER 2U /*!< DMA2D maximum number of layers */ - -/** - * @brief DMA2D CLUT Structure definition - */ -typedef struct -{ - uint32_t *pCLUT; /*!< Configures the DMA2D CLUT memory address.*/ - - uint32_t CLUTColorMode; /*!< Configures the DMA2D CLUT color mode. - This parameter can be one value of @ref DMA2D_CLUT_CM. */ - - uint32_t Size; /*!< Configures the DMA2D CLUT size. - This parameter must be a number between Min_Data = 0x00 and Max_Data = 0xFF.*/ -} DMA2D_CLUTCfgTypeDef; - -/** - * @brief DMA2D Init structure definition - */ -typedef struct -{ - uint32_t Mode; /*!< Configures the DMA2D transfer mode. - This parameter can be one value of @ref DMA2D_Mode. */ - - uint32_t ColorMode; /*!< Configures the color format of the output image. - This parameter can be one value of @ref DMA2D_Output_Color_Mode. */ - - uint32_t OutputOffset; /*!< Specifies the Offset value. - This parameter must be a number between - Min_Data = 0x0000 and Max_Data = 0x3FFF. */ - - - - -} DMA2D_InitTypeDef; - - -/** - * @brief DMA2D Layer structure definition - */ -typedef struct -{ - uint32_t InputOffset; /*!< Configures the DMA2D foreground or background offset. - This parameter must be a number between - Min_Data = 0x0000 and Max_Data = 0x3FFF. */ - - uint32_t InputColorMode; /*!< Configures the DMA2D foreground or background color mode. - This parameter can be one value of @ref DMA2D_Input_Color_Mode. */ - - uint32_t AlphaMode; /*!< Configures the DMA2D foreground or background alpha mode. - This parameter can be one value of @ref DMA2D_Alpha_Mode. */ - - uint32_t InputAlpha; /*!< Specifies the DMA2D foreground or background alpha value and color value - in case of A8 or A4 color mode. - This parameter must be a number between Min_Data = 0x00 - and Max_Data = 0xFF except for the color modes detailed below. - @note In case of A8 or A4 color mode (ARGB), - this parameter must be a number between - Min_Data = 0x00000000 and Max_Data = 0xFFFFFFFF where - - InputAlpha[24:31] is the alpha value ALPHA[0:7] - - InputAlpha[16:23] is the red value RED[0:7] - - InputAlpha[8:15] is the green value GREEN[0:7] - - InputAlpha[0:7] is the blue value BLUE[0:7]. */ - - -} DMA2D_LayerCfgTypeDef; - -/** - * @brief HAL DMA2D State structures definition - */ -typedef enum -{ - HAL_DMA2D_STATE_RESET = 0x00U, /*!< DMA2D not yet initialized or disabled */ - HAL_DMA2D_STATE_READY = 0x01U, /*!< Peripheral Initialized and ready for use */ - HAL_DMA2D_STATE_BUSY = 0x02U, /*!< An internal process is ongoing */ - HAL_DMA2D_STATE_TIMEOUT = 0x03U, /*!< Timeout state */ - HAL_DMA2D_STATE_ERROR = 0x04U, /*!< DMA2D state error */ - HAL_DMA2D_STATE_SUSPEND = 0x05U /*!< DMA2D process is suspended */ -} HAL_DMA2D_StateTypeDef; - -/** - * @brief DMA2D handle Structure definition - */ -typedef struct __DMA2D_HandleTypeDef -{ - DMA2D_TypeDef *Instance; /*!< DMA2D register base address. */ - - DMA2D_InitTypeDef Init; /*!< DMA2D communication parameters. */ - - void (* XferCpltCallback)(struct __DMA2D_HandleTypeDef *hdma2d); /*!< DMA2D transfer complete callback. */ - - void (* XferErrorCallback)(struct __DMA2D_HandleTypeDef *hdma2d); /*!< DMA2D transfer error callback. */ - -#if (USE_HAL_DMA2D_REGISTER_CALLBACKS == 1) - void (* LineEventCallback)(struct __DMA2D_HandleTypeDef *hdma2d); /*!< DMA2D line event callback. */ - - void (* CLUTLoadingCpltCallback)(struct __DMA2D_HandleTypeDef *hdma2d); /*!< DMA2D CLUT loading completion callback */ - - void (* MspInitCallback)(struct __DMA2D_HandleTypeDef *hdma2d); /*!< DMA2D Msp Init callback. */ - - void (* MspDeInitCallback)(struct __DMA2D_HandleTypeDef *hdma2d); /*!< DMA2D Msp DeInit callback. */ - -#endif /* (USE_HAL_DMA2D_REGISTER_CALLBACKS) */ - - DMA2D_LayerCfgTypeDef LayerCfg[MAX_DMA2D_LAYER]; /*!< DMA2D Layers parameters */ - - HAL_LockTypeDef Lock; /*!< DMA2D lock. */ - - __IO HAL_DMA2D_StateTypeDef State; /*!< DMA2D transfer state. */ - - __IO uint32_t ErrorCode; /*!< DMA2D error code. */ -} DMA2D_HandleTypeDef; - -#if (USE_HAL_DMA2D_REGISTER_CALLBACKS == 1) -/** - * @brief HAL DMA2D Callback pointer definition - */ -typedef void (*pDMA2D_CallbackTypeDef)(DMA2D_HandleTypeDef *hdma2d); /*!< Pointer to a DMA2D common callback function */ -#endif /* USE_HAL_DMA2D_REGISTER_CALLBACKS */ -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup DMA2D_Exported_Constants DMA2D Exported Constants - * @{ - */ - -/** @defgroup DMA2D_Error_Code DMA2D Error Code - * @{ - */ -#define HAL_DMA2D_ERROR_NONE 0x00000000U /*!< No error */ -#define HAL_DMA2D_ERROR_TE 0x00000001U /*!< Transfer error */ -#define HAL_DMA2D_ERROR_CE 0x00000002U /*!< Configuration error */ -#define HAL_DMA2D_ERROR_CAE 0x00000004U /*!< CLUT access error */ -#define HAL_DMA2D_ERROR_TIMEOUT 0x00000020U /*!< Timeout error */ -#if (USE_HAL_DMA2D_REGISTER_CALLBACKS == 1) -#define HAL_DMA2D_ERROR_INVALID_CALLBACK 0x00000040U /*!< Invalid callback error */ -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @defgroup DMA2D_Mode DMA2D Mode - * @{ - */ -#define DMA2D_M2M 0x00000000U /*!< DMA2D memory to memory transfer mode */ -#define DMA2D_M2M_PFC DMA2D_CR_MODE_0 /*!< DMA2D memory to memory with pixel format conversion transfer mode */ -#define DMA2D_M2M_BLEND DMA2D_CR_MODE_1 /*!< DMA2D memory to memory with blending transfer mode */ -#define DMA2D_R2M DMA2D_CR_MODE /*!< DMA2D register to memory transfer mode */ -/** - * @} - */ - -/** @defgroup DMA2D_Output_Color_Mode DMA2D Output Color Mode - * @{ - */ -#define DMA2D_OUTPUT_ARGB8888 0x00000000U /*!< ARGB8888 DMA2D color mode */ -#define DMA2D_OUTPUT_RGB888 DMA2D_OPFCCR_CM_0 /*!< RGB888 DMA2D color mode */ -#define DMA2D_OUTPUT_RGB565 DMA2D_OPFCCR_CM_1 /*!< RGB565 DMA2D color mode */ -#define DMA2D_OUTPUT_ARGB1555 (DMA2D_OPFCCR_CM_0|DMA2D_OPFCCR_CM_1) /*!< ARGB1555 DMA2D color mode */ -#define DMA2D_OUTPUT_ARGB4444 DMA2D_OPFCCR_CM_2 /*!< ARGB4444 DMA2D color mode */ -/** - * @} - */ - -/** @defgroup DMA2D_Input_Color_Mode DMA2D Input Color Mode - * @{ - */ -#define DMA2D_INPUT_ARGB8888 0x00000000U /*!< ARGB8888 color mode */ -#define DMA2D_INPUT_RGB888 0x00000001U /*!< RGB888 color mode */ -#define DMA2D_INPUT_RGB565 0x00000002U /*!< RGB565 color mode */ -#define DMA2D_INPUT_ARGB1555 0x00000003U /*!< ARGB1555 color mode */ -#define DMA2D_INPUT_ARGB4444 0x00000004U /*!< ARGB4444 color mode */ -#define DMA2D_INPUT_L8 0x00000005U /*!< L8 color mode */ -#define DMA2D_INPUT_AL44 0x00000006U /*!< AL44 color mode */ -#define DMA2D_INPUT_AL88 0x00000007U /*!< AL88 color mode */ -#define DMA2D_INPUT_L4 0x00000008U /*!< L4 color mode */ -#define DMA2D_INPUT_A8 0x00000009U /*!< A8 color mode */ -#define DMA2D_INPUT_A4 0x0000000AU /*!< A4 color mode */ -/** - * @} - */ - -/** @defgroup DMA2D_Alpha_Mode DMA2D Alpha Mode - * @{ - */ -#define DMA2D_NO_MODIF_ALPHA 0x00000000U /*!< No modification of the alpha channel value */ -#define DMA2D_REPLACE_ALPHA 0x00000001U /*!< Replace original alpha channel value by programmed alpha value */ -#define DMA2D_COMBINE_ALPHA 0x00000002U /*!< Replace original alpha channel value by programmed alpha value - with original alpha channel value */ -/** - * @} - */ - - - - - - -/** @defgroup DMA2D_CLUT_CM DMA2D CLUT Color Mode - * @{ - */ -#define DMA2D_CCM_ARGB8888 0x00000000U /*!< ARGB8888 DMA2D CLUT color mode */ -#define DMA2D_CCM_RGB888 0x00000001U /*!< RGB888 DMA2D CLUT color mode */ -/** - * @} - */ - -/** @defgroup DMA2D_Interrupts DMA2D Interrupts - * @{ - */ -#define DMA2D_IT_CE DMA2D_CR_CEIE /*!< Configuration Error Interrupt */ -#define DMA2D_IT_CTC DMA2D_CR_CTCIE /*!< CLUT Transfer Complete Interrupt */ -#define DMA2D_IT_CAE DMA2D_CR_CAEIE /*!< CLUT Access Error Interrupt */ -#define DMA2D_IT_TW DMA2D_CR_TWIE /*!< Transfer Watermark Interrupt */ -#define DMA2D_IT_TC DMA2D_CR_TCIE /*!< Transfer Complete Interrupt */ -#define DMA2D_IT_TE DMA2D_CR_TEIE /*!< Transfer Error Interrupt */ -/** - * @} - */ - -/** @defgroup DMA2D_Flags DMA2D Flags - * @{ - */ -#define DMA2D_FLAG_CE DMA2D_ISR_CEIF /*!< Configuration Error Interrupt Flag */ -#define DMA2D_FLAG_CTC DMA2D_ISR_CTCIF /*!< CLUT Transfer Complete Interrupt Flag */ -#define DMA2D_FLAG_CAE DMA2D_ISR_CAEIF /*!< CLUT Access Error Interrupt Flag */ -#define DMA2D_FLAG_TW DMA2D_ISR_TWIF /*!< Transfer Watermark Interrupt Flag */ -#define DMA2D_FLAG_TC DMA2D_ISR_TCIF /*!< Transfer Complete Interrupt Flag */ -#define DMA2D_FLAG_TE DMA2D_ISR_TEIF /*!< Transfer Error Interrupt Flag */ -/** - * @} - */ - -/** @defgroup DMA2D_Aliases DMA2D API Aliases - * @{ - */ -#define HAL_DMA2D_DisableCLUT HAL_DMA2D_CLUTLoading_Abort /*!< Aliased to HAL_DMA2D_CLUTLoading_Abort - for compatibility with legacy code */ -/** - * @} - */ - -#if (USE_HAL_DMA2D_REGISTER_CALLBACKS == 1) -/** - * @brief HAL DMA2D common Callback ID enumeration definition - */ -typedef enum -{ - HAL_DMA2D_MSPINIT_CB_ID = 0x00U, /*!< DMA2D MspInit callback ID */ - HAL_DMA2D_MSPDEINIT_CB_ID = 0x01U, /*!< DMA2D MspDeInit callback ID */ - HAL_DMA2D_TRANSFERCOMPLETE_CB_ID = 0x02U, /*!< DMA2D transfer complete callback ID */ - HAL_DMA2D_TRANSFERERROR_CB_ID = 0x03U, /*!< DMA2D transfer error callback ID */ - HAL_DMA2D_LINEEVENT_CB_ID = 0x04U, /*!< DMA2D line event callback ID */ - HAL_DMA2D_CLUTLOADINGCPLT_CB_ID = 0x05U, /*!< DMA2D CLUT loading completion callback ID */ -} HAL_DMA2D_CallbackIDTypeDef; -#endif /* USE_HAL_DMA2D_REGISTER_CALLBACKS */ - - -/** - * @} - */ -/* Exported macros ------------------------------------------------------------*/ -/** @defgroup DMA2D_Exported_Macros DMA2D Exported Macros - * @{ - */ - -/** @brief Reset DMA2D handle state - * @param __HANDLE__ specifies the DMA2D handle. - * @retval None - */ -#if (USE_HAL_DMA2D_REGISTER_CALLBACKS == 1) -#define __HAL_DMA2D_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->State = HAL_DMA2D_STATE_RESET;\ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - }while(0) -#else -#define __HAL_DMA2D_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_DMA2D_STATE_RESET) -#endif /* USE_HAL_DMA2D_REGISTER_CALLBACKS */ - - -/** - * @brief Enable the DMA2D. - * @param __HANDLE__ DMA2D handle - * @retval None. - */ -#define __HAL_DMA2D_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= DMA2D_CR_START) - - -/* Interrupt & Flag management */ -/** - * @brief Get the DMA2D pending flags. - * @param __HANDLE__ DMA2D handle - * @param __FLAG__ flag to check. - * This parameter can be any combination of the following values: - * @arg DMA2D_FLAG_CE: Configuration error flag - * @arg DMA2D_FLAG_CTC: CLUT transfer complete flag - * @arg DMA2D_FLAG_CAE: CLUT access error flag - * @arg DMA2D_FLAG_TW: Transfer Watermark flag - * @arg DMA2D_FLAG_TC: Transfer complete flag - * @arg DMA2D_FLAG_TE: Transfer error flag - * @retval The state of FLAG. - */ -#define __HAL_DMA2D_GET_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->ISR & (__FLAG__)) - -/** - * @brief Clear the DMA2D pending flags. - * @param __HANDLE__ DMA2D handle - * @param __FLAG__ specifies the flag to clear. - * This parameter can be any combination of the following values: - * @arg DMA2D_FLAG_CE: Configuration error flag - * @arg DMA2D_FLAG_CTC: CLUT transfer complete flag - * @arg DMA2D_FLAG_CAE: CLUT access error flag - * @arg DMA2D_FLAG_TW: Transfer Watermark flag - * @arg DMA2D_FLAG_TC: Transfer complete flag - * @arg DMA2D_FLAG_TE: Transfer error flag - * @retval None - */ -#define __HAL_DMA2D_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->IFCR = (__FLAG__)) - -/** - * @brief Enable the specified DMA2D interrupts. - * @param __HANDLE__ DMA2D handle - * @param __INTERRUPT__ specifies the DMA2D interrupt sources to be enabled. - * This parameter can be any combination of the following values: - * @arg DMA2D_IT_CE: Configuration error interrupt mask - * @arg DMA2D_IT_CTC: CLUT transfer complete interrupt mask - * @arg DMA2D_IT_CAE: CLUT access error interrupt mask - * @arg DMA2D_IT_TW: Transfer Watermark interrupt mask - * @arg DMA2D_IT_TC: Transfer complete interrupt mask - * @arg DMA2D_IT_TE: Transfer error interrupt mask - * @retval None - */ -#define __HAL_DMA2D_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR |= (__INTERRUPT__)) - -/** - * @brief Disable the specified DMA2D interrupts. - * @param __HANDLE__ DMA2D handle - * @param __INTERRUPT__ specifies the DMA2D interrupt sources to be disabled. - * This parameter can be any combination of the following values: - * @arg DMA2D_IT_CE: Configuration error interrupt mask - * @arg DMA2D_IT_CTC: CLUT transfer complete interrupt mask - * @arg DMA2D_IT_CAE: CLUT access error interrupt mask - * @arg DMA2D_IT_TW: Transfer Watermark interrupt mask - * @arg DMA2D_IT_TC: Transfer complete interrupt mask - * @arg DMA2D_IT_TE: Transfer error interrupt mask - * @retval None - */ -#define __HAL_DMA2D_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR &= ~(__INTERRUPT__)) - -/** - * @brief Check whether the specified DMA2D interrupt source is enabled or not. - * @param __HANDLE__ DMA2D handle - * @param __INTERRUPT__ specifies the DMA2D interrupt source to check. - * This parameter can be one of the following values: - * @arg DMA2D_IT_CE: Configuration error interrupt mask - * @arg DMA2D_IT_CTC: CLUT transfer complete interrupt mask - * @arg DMA2D_IT_CAE: CLUT access error interrupt mask - * @arg DMA2D_IT_TW: Transfer Watermark interrupt mask - * @arg DMA2D_IT_TC: Transfer complete interrupt mask - * @arg DMA2D_IT_TE: Transfer error interrupt mask - * @retval The state of INTERRUPT source. - */ -#define __HAL_DMA2D_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR & (__INTERRUPT__)) - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup DMA2D_Exported_Functions DMA2D Exported Functions - * @{ - */ - -/** @addtogroup DMA2D_Exported_Functions_Group1 Initialization and de-initialization functions - * @{ - */ - -/* Initialization and de-initialization functions *******************************/ -HAL_StatusTypeDef HAL_DMA2D_Init(DMA2D_HandleTypeDef *hdma2d); -HAL_StatusTypeDef HAL_DMA2D_DeInit(DMA2D_HandleTypeDef *hdma2d); -void HAL_DMA2D_MspInit(DMA2D_HandleTypeDef *hdma2d); -void HAL_DMA2D_MspDeInit(DMA2D_HandleTypeDef *hdma2d); -/* Callbacks Register/UnRegister functions ***********************************/ -#if (USE_HAL_DMA2D_REGISTER_CALLBACKS == 1) -HAL_StatusTypeDef HAL_DMA2D_RegisterCallback(DMA2D_HandleTypeDef *hdma2d, HAL_DMA2D_CallbackIDTypeDef CallbackID, - pDMA2D_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_DMA2D_UnRegisterCallback(DMA2D_HandleTypeDef *hdma2d, HAL_DMA2D_CallbackIDTypeDef CallbackID); -#endif /* USE_HAL_DMA2D_REGISTER_CALLBACKS */ - -/** - * @} - */ - - -/** @addtogroup DMA2D_Exported_Functions_Group2 IO operation functions - * @{ - */ - -/* IO operation functions *******************************************************/ -HAL_StatusTypeDef HAL_DMA2D_Start(DMA2D_HandleTypeDef *hdma2d, uint32_t pdata, uint32_t DstAddress, uint32_t Width, - uint32_t Height); -HAL_StatusTypeDef HAL_DMA2D_BlendingStart(DMA2D_HandleTypeDef *hdma2d, uint32_t SrcAddress1, uint32_t SrcAddress2, - uint32_t DstAddress, uint32_t Width, uint32_t Height); -HAL_StatusTypeDef HAL_DMA2D_Start_IT(DMA2D_HandleTypeDef *hdma2d, uint32_t pdata, uint32_t DstAddress, uint32_t Width, - uint32_t Height); -HAL_StatusTypeDef HAL_DMA2D_BlendingStart_IT(DMA2D_HandleTypeDef *hdma2d, uint32_t SrcAddress1, uint32_t SrcAddress2, - uint32_t DstAddress, uint32_t Width, uint32_t Height); -HAL_StatusTypeDef HAL_DMA2D_Suspend(DMA2D_HandleTypeDef *hdma2d); -HAL_StatusTypeDef HAL_DMA2D_Resume(DMA2D_HandleTypeDef *hdma2d); -HAL_StatusTypeDef HAL_DMA2D_Abort(DMA2D_HandleTypeDef *hdma2d); -HAL_StatusTypeDef HAL_DMA2D_EnableCLUT(DMA2D_HandleTypeDef *hdma2d, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_DMA2D_CLUTStartLoad(DMA2D_HandleTypeDef *hdma2d, DMA2D_CLUTCfgTypeDef *CLUTCfg, - uint32_t LayerIdx); -HAL_StatusTypeDef HAL_DMA2D_CLUTStartLoad_IT(DMA2D_HandleTypeDef *hdma2d, DMA2D_CLUTCfgTypeDef *CLUTCfg, - uint32_t LayerIdx); -HAL_StatusTypeDef HAL_DMA2D_CLUTLoad(DMA2D_HandleTypeDef *hdma2d, DMA2D_CLUTCfgTypeDef CLUTCfg, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_DMA2D_CLUTLoad_IT(DMA2D_HandleTypeDef *hdma2d, DMA2D_CLUTCfgTypeDef CLUTCfg, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_DMA2D_CLUTLoading_Abort(DMA2D_HandleTypeDef *hdma2d, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_DMA2D_CLUTLoading_Suspend(DMA2D_HandleTypeDef *hdma2d, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_DMA2D_CLUTLoading_Resume(DMA2D_HandleTypeDef *hdma2d, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_DMA2D_PollForTransfer(DMA2D_HandleTypeDef *hdma2d, uint32_t Timeout); -void HAL_DMA2D_IRQHandler(DMA2D_HandleTypeDef *hdma2d); -void HAL_DMA2D_LineEventCallback(DMA2D_HandleTypeDef *hdma2d); -void HAL_DMA2D_CLUTLoadingCpltCallback(DMA2D_HandleTypeDef *hdma2d); - -/** - * @} - */ - -/** @addtogroup DMA2D_Exported_Functions_Group3 Peripheral Control functions - * @{ - */ - -/* Peripheral Control functions *************************************************/ -HAL_StatusTypeDef HAL_DMA2D_ConfigLayer(DMA2D_HandleTypeDef *hdma2d, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_DMA2D_ConfigCLUT(DMA2D_HandleTypeDef *hdma2d, DMA2D_CLUTCfgTypeDef CLUTCfg, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_DMA2D_ProgramLineEvent(DMA2D_HandleTypeDef *hdma2d, uint32_t Line); -HAL_StatusTypeDef HAL_DMA2D_EnableDeadTime(DMA2D_HandleTypeDef *hdma2d); -HAL_StatusTypeDef HAL_DMA2D_DisableDeadTime(DMA2D_HandleTypeDef *hdma2d); -HAL_StatusTypeDef HAL_DMA2D_ConfigDeadTime(DMA2D_HandleTypeDef *hdma2d, uint8_t DeadTime); - -/** - * @} - */ - -/** @addtogroup DMA2D_Exported_Functions_Group4 Peripheral State and Error functions - * @{ - */ - -/* Peripheral State functions ***************************************************/ -HAL_DMA2D_StateTypeDef HAL_DMA2D_GetState(DMA2D_HandleTypeDef *hdma2d); -uint32_t HAL_DMA2D_GetError(DMA2D_HandleTypeDef *hdma2d); - -/** - * @} - */ - -/** - * @} - */ - -/* Private constants ---------------------------------------------------------*/ - -/** @addtogroup DMA2D_Private_Constants DMA2D Private Constants - * @{ - */ - -/** @defgroup DMA2D_Maximum_Line_WaterMark DMA2D Maximum Line Watermark - * @{ - */ -#define DMA2D_LINE_WATERMARK_MAX DMA2D_LWR_LW /*!< DMA2D maximum line watermark */ -/** - * @} - */ - -/** @defgroup DMA2D_Color_Value DMA2D Color Value - * @{ - */ -#define DMA2D_COLOR_VALUE 0x000000FFU /*!< Color value mask */ -/** - * @} - */ - -/** @defgroup DMA2D_Max_Layer DMA2D Maximum Number of Layers - * @{ - */ -#define DMA2D_MAX_LAYER 2U /*!< DMA2D maximum number of layers */ -/** - * @} - */ - -/** @defgroup DMA2D_Layers DMA2D Layers - * @{ - */ -#define DMA2D_BACKGROUND_LAYER 0x00000000U /*!< DMA2D Background Layer (layer 0) */ -#define DMA2D_FOREGROUND_LAYER 0x00000001U /*!< DMA2D Foreground Layer (layer 1) */ -/** - * @} - */ - -/** @defgroup DMA2D_Offset DMA2D Offset - * @{ - */ -#define DMA2D_OFFSET DMA2D_FGOR_LO /*!< maximum Line Offset */ -/** - * @} - */ - -/** @defgroup DMA2D_Size DMA2D Size - * @{ - */ -#define DMA2D_PIXEL (DMA2D_NLR_PL >> 16U) /*!< DMA2D maximum number of pixels per line */ -#define DMA2D_LINE DMA2D_NLR_NL /*!< DMA2D maximum number of lines */ -/** - * @} - */ - -/** @defgroup DMA2D_CLUT_Size DMA2D CLUT Size - * @{ - */ -#define DMA2D_CLUT_SIZE (DMA2D_FGPFCCR_CS >> 8U) /*!< DMA2D maximum CLUT size */ -/** - * @} - */ - -/** - * @} - */ - - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup DMA2D_Private_Macros DMA2D Private Macros - * @{ - */ -#define IS_DMA2D_LAYER(LAYER) (((LAYER) == DMA2D_BACKGROUND_LAYER)\ - || ((LAYER) == DMA2D_FOREGROUND_LAYER)) - -#define IS_DMA2D_MODE(MODE) (((MODE) == DMA2D_M2M) || ((MODE) == DMA2D_M2M_PFC) || \ - ((MODE) == DMA2D_M2M_BLEND) || ((MODE) == DMA2D_R2M)) - -#define IS_DMA2D_CMODE(MODE_ARGB) (((MODE_ARGB) == DMA2D_OUTPUT_ARGB8888) || \ - ((MODE_ARGB) == DMA2D_OUTPUT_RGB888) || \ - ((MODE_ARGB) == DMA2D_OUTPUT_RGB565) || \ - ((MODE_ARGB) == DMA2D_OUTPUT_ARGB1555) || \ - ((MODE_ARGB) == DMA2D_OUTPUT_ARGB4444)) - -#define IS_DMA2D_COLOR(COLOR) ((COLOR) <= DMA2D_COLOR_VALUE) -#define IS_DMA2D_LINE(LINE) ((LINE) <= DMA2D_LINE) -#define IS_DMA2D_PIXEL(PIXEL) ((PIXEL) <= DMA2D_PIXEL) -#define IS_DMA2D_OFFSET(OOFFSET) ((OOFFSET) <= DMA2D_OFFSET) - -#define IS_DMA2D_INPUT_COLOR_MODE(INPUT_CM) (((INPUT_CM) == DMA2D_INPUT_ARGB8888) || \ - ((INPUT_CM) == DMA2D_INPUT_RGB888) || \ - ((INPUT_CM) == DMA2D_INPUT_RGB565) || \ - ((INPUT_CM) == DMA2D_INPUT_ARGB1555) || \ - ((INPUT_CM) == DMA2D_INPUT_ARGB4444) || \ - ((INPUT_CM) == DMA2D_INPUT_L8) || \ - ((INPUT_CM) == DMA2D_INPUT_AL44) || \ - ((INPUT_CM) == DMA2D_INPUT_AL88) || \ - ((INPUT_CM) == DMA2D_INPUT_L4) || \ - ((INPUT_CM) == DMA2D_INPUT_A8) || \ - ((INPUT_CM) == DMA2D_INPUT_A4)) - -#define IS_DMA2D_ALPHA_MODE(AlphaMode) (((AlphaMode) == DMA2D_NO_MODIF_ALPHA) || \ - ((AlphaMode) == DMA2D_REPLACE_ALPHA) || \ - ((AlphaMode) == DMA2D_COMBINE_ALPHA)) - - - - - -#define IS_DMA2D_CLUT_CM(CLUT_CM) (((CLUT_CM) == DMA2D_CCM_ARGB8888) || ((CLUT_CM) == DMA2D_CCM_RGB888)) -#define IS_DMA2D_CLUT_SIZE(CLUT_SIZE) ((CLUT_SIZE) <= DMA2D_CLUT_SIZE) -#define IS_DMA2D_LINEWATERMARK(LineWatermark) ((LineWatermark) <= DMA2D_LINE_WATERMARK_MAX) -#define IS_DMA2D_IT(IT) (((IT) == DMA2D_IT_CTC) || ((IT) == DMA2D_IT_CAE) || \ - ((IT) == DMA2D_IT_TW) || ((IT) == DMA2D_IT_TC) || \ - ((IT) == DMA2D_IT_TE) || ((IT) == DMA2D_IT_CE)) -#define IS_DMA2D_GET_FLAG(FLAG) (((FLAG) == DMA2D_FLAG_CTC) || ((FLAG) == DMA2D_FLAG_CAE) || \ - ((FLAG) == DMA2D_FLAG_TW) || ((FLAG) == DMA2D_FLAG_TC) || \ - ((FLAG) == DMA2D_FLAG_TE) || ((FLAG) == DMA2D_FLAG_CE)) -/** - * @} - */ - -/** - * @} - */ - -#endif /* defined (DMA2D) */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_HAL_DMA2D_H */ - - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma_ex.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma_ex.h deleted file mode 100644 index 2e60aff..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dma_ex.h +++ /dev/null @@ -1,104 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_dma_ex.h - * @author MCD Application Team - * @brief Header file of DMA HAL extension module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_DMA_EX_H -#define __STM32F4xx_HAL_DMA_EX_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup DMAEx - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup DMAEx_Exported_Types DMAEx Exported Types - * @brief DMAEx Exported types - * @{ - */ - -/** - * @brief HAL DMA Memory definition - */ -typedef enum -{ - MEMORY0 = 0x00U, /*!< Memory 0 */ - MEMORY1 = 0x01U /*!< Memory 1 */ -}HAL_DMA_MemoryTypeDef; - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup DMAEx_Exported_Functions DMAEx Exported Functions - * @brief DMAEx Exported functions - * @{ - */ - -/** @defgroup DMAEx_Exported_Functions_Group1 Extended features functions - * @brief Extended features functions - * @{ - */ - -/* IO operation functions *******************************************************/ -HAL_StatusTypeDef HAL_DMAEx_MultiBufferStart(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t SecondMemAddress, uint32_t DataLength); -HAL_StatusTypeDef HAL_DMAEx_MultiBufferStart_IT(DMA_HandleTypeDef *hdma, uint32_t SrcAddress, uint32_t DstAddress, uint32_t SecondMemAddress, uint32_t DataLength); -HAL_StatusTypeDef HAL_DMAEx_ChangeMemory(DMA_HandleTypeDef *hdma, uint32_t Address, HAL_DMA_MemoryTypeDef memory); - -/** - * @} - */ -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup DMAEx_Private_Functions DMAEx Private Functions - * @brief DMAEx Private functions - * @{ - */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /*__STM32F4xx_HAL_DMA_EX_H*/ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dsi.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dsi.h deleted file mode 100644 index 716dea1..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_dsi.h +++ /dev/null @@ -1,1353 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_dsi.h - * @author MCD Application Team - * @brief Header file of DSI HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_DSI_H -#define STM32F4xx_HAL_DSI_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -#if defined(DSI) - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup DSI DSI - * @brief DSI HAL module driver - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** - * @brief DSI Init Structure definition - */ -typedef struct -{ - uint32_t AutomaticClockLaneControl; /*!< Automatic clock lane control - This parameter can be any value of @ref DSI_Automatic_Clk_Lane_Control */ - - uint32_t TXEscapeCkdiv; /*!< TX Escape clock division - The values 0 and 1 stop the TX_ESC clock generation */ - - uint32_t NumberOfLanes; /*!< Number of lanes - This parameter can be any value of @ref DSI_Number_Of_Lanes */ - -} DSI_InitTypeDef; - -/** - * @brief DSI PLL Clock structure definition - */ -typedef struct -{ - uint32_t PLLNDIV; /*!< PLL Loop Division Factor - This parameter must be a value between 10 and 125 */ - - uint32_t PLLIDF; /*!< PLL Input Division Factor - This parameter can be any value of @ref DSI_PLL_IDF */ - - uint32_t PLLODF; /*!< PLL Output Division Factor - This parameter can be any value of @ref DSI_PLL_ODF */ - -} DSI_PLLInitTypeDef; - -/** - * @brief DSI Video mode configuration - */ -typedef struct -{ - uint32_t VirtualChannelID; /*!< Virtual channel ID */ - - uint32_t ColorCoding; /*!< Color coding for LTDC interface - This parameter can be any value of @ref DSI_Color_Coding */ - - uint32_t LooselyPacked; /*!< Enable or disable loosely packed stream (needed only when using - 18-bit configuration). - This parameter can be any value of @ref DSI_LooselyPacked */ - - uint32_t Mode; /*!< Video mode type - This parameter can be any value of @ref DSI_Video_Mode_Type */ - - uint32_t PacketSize; /*!< Video packet size */ - - uint32_t NumberOfChunks; /*!< Number of chunks */ - - uint32_t NullPacketSize; /*!< Null packet size */ - - uint32_t HSPolarity; /*!< HSYNC pin polarity - This parameter can be any value of @ref DSI_HSYNC_Polarity */ - - uint32_t VSPolarity; /*!< VSYNC pin polarity - This parameter can be any value of @ref DSI_VSYNC_Active_Polarity */ - - uint32_t DEPolarity; /*!< Data Enable pin polarity - This parameter can be any value of @ref DSI_DATA_ENABLE_Polarity */ - - uint32_t HorizontalSyncActive; /*!< Horizontal synchronism active duration (in lane byte clock cycles) */ - - uint32_t HorizontalBackPorch; /*!< Horizontal back-porch duration (in lane byte clock cycles) */ - - uint32_t HorizontalLine; /*!< Horizontal line duration (in lane byte clock cycles) */ - - uint32_t VerticalSyncActive; /*!< Vertical synchronism active duration */ - - uint32_t VerticalBackPorch; /*!< Vertical back-porch duration */ - - uint32_t VerticalFrontPorch; /*!< Vertical front-porch duration */ - - uint32_t VerticalActive; /*!< Vertical active duration */ - - uint32_t LPCommandEnable; /*!< Low-power command enable - This parameter can be any value of @ref DSI_LP_Command */ - - uint32_t LPLargestPacketSize; /*!< The size, in bytes, of the low power largest packet that - can fit in a line during VSA, VBP and VFP regions */ - - uint32_t LPVACTLargestPacketSize; /*!< The size, in bytes, of the low power largest packet that - can fit in a line during VACT region */ - - uint32_t LPHorizontalFrontPorchEnable; /*!< Low-power horizontal front-porch enable - This parameter can be any value of @ref DSI_LP_HFP */ - - uint32_t LPHorizontalBackPorchEnable; /*!< Low-power horizontal back-porch enable - This parameter can be any value of @ref DSI_LP_HBP */ - - uint32_t LPVerticalActiveEnable; /*!< Low-power vertical active enable - This parameter can be any value of @ref DSI_LP_VACT */ - - uint32_t LPVerticalFrontPorchEnable; /*!< Low-power vertical front-porch enable - This parameter can be any value of @ref DSI_LP_VFP */ - - uint32_t LPVerticalBackPorchEnable; /*!< Low-power vertical back-porch enable - This parameter can be any value of @ref DSI_LP_VBP */ - - uint32_t LPVerticalSyncActiveEnable; /*!< Low-power vertical sync active enable - This parameter can be any value of @ref DSI_LP_VSYNC */ - - uint32_t FrameBTAAcknowledgeEnable; /*!< Frame bus-turn-around acknowledge enable - This parameter can be any value of @ref DSI_FBTA_acknowledge */ - -} DSI_VidCfgTypeDef; - -/** - * @brief DSI Adapted command mode configuration - */ -typedef struct -{ - uint32_t VirtualChannelID; /*!< Virtual channel ID */ - - uint32_t ColorCoding; /*!< Color coding for LTDC interface - This parameter can be any value of @ref DSI_Color_Coding */ - - uint32_t CommandSize; /*!< Maximum allowed size for an LTDC write memory command, measured in - pixels. This parameter can be any value between 0x00 and 0xFFFFU */ - - uint32_t TearingEffectSource; /*!< Tearing effect source - This parameter can be any value of @ref DSI_TearingEffectSource */ - - uint32_t TearingEffectPolarity; /*!< Tearing effect pin polarity - This parameter can be any value of @ref DSI_TearingEffectPolarity */ - - uint32_t HSPolarity; /*!< HSYNC pin polarity - This parameter can be any value of @ref DSI_HSYNC_Polarity */ - - uint32_t VSPolarity; /*!< VSYNC pin polarity - This parameter can be any value of @ref DSI_VSYNC_Active_Polarity */ - - uint32_t DEPolarity; /*!< Data Enable pin polarity - This parameter can be any value of @ref DSI_DATA_ENABLE_Polarity */ - - uint32_t VSyncPol; /*!< VSync edge on which the LTDC is halted - This parameter can be any value of @ref DSI_Vsync_Polarity */ - - uint32_t AutomaticRefresh; /*!< Automatic refresh mode - This parameter can be any value of @ref DSI_AutomaticRefresh */ - - uint32_t TEAcknowledgeRequest; /*!< Tearing Effect Acknowledge Request Enable - This parameter can be any value of @ref DSI_TE_AcknowledgeRequest */ - -} DSI_CmdCfgTypeDef; - -/** - * @brief DSI command transmission mode configuration - */ -typedef struct -{ - uint32_t LPGenShortWriteNoP; /*!< Generic Short Write Zero parameters Transmission - This parameter can be any value of @ref DSI_LP_LPGenShortWriteNoP */ - - uint32_t LPGenShortWriteOneP; /*!< Generic Short Write One parameter Transmission - This parameter can be any value of @ref DSI_LP_LPGenShortWriteOneP */ - - uint32_t LPGenShortWriteTwoP; /*!< Generic Short Write Two parameters Transmission - This parameter can be any value of @ref DSI_LP_LPGenShortWriteTwoP */ - - uint32_t LPGenShortReadNoP; /*!< Generic Short Read Zero parameters Transmission - This parameter can be any value of @ref DSI_LP_LPGenShortReadNoP */ - - uint32_t LPGenShortReadOneP; /*!< Generic Short Read One parameter Transmission - This parameter can be any value of @ref DSI_LP_LPGenShortReadOneP */ - - uint32_t LPGenShortReadTwoP; /*!< Generic Short Read Two parameters Transmission - This parameter can be any value of @ref DSI_LP_LPGenShortReadTwoP */ - - uint32_t LPGenLongWrite; /*!< Generic Long Write Transmission - This parameter can be any value of @ref DSI_LP_LPGenLongWrite */ - - uint32_t LPDcsShortWriteNoP; /*!< DCS Short Write Zero parameters Transmission - This parameter can be any value of @ref DSI_LP_LPDcsShortWriteNoP */ - - uint32_t LPDcsShortWriteOneP; /*!< DCS Short Write One parameter Transmission - This parameter can be any value of @ref DSI_LP_LPDcsShortWriteOneP */ - - uint32_t LPDcsShortReadNoP; /*!< DCS Short Read Zero parameters Transmission - This parameter can be any value of @ref DSI_LP_LPDcsShortReadNoP */ - - uint32_t LPDcsLongWrite; /*!< DCS Long Write Transmission - This parameter can be any value of @ref DSI_LP_LPDcsLongWrite */ - - uint32_t LPMaxReadPacket; /*!< Maximum Read Packet Size Transmission - This parameter can be any value of @ref DSI_LP_LPMaxReadPacket */ - - uint32_t AcknowledgeRequest; /*!< Acknowledge Request Enable - This parameter can be any value of @ref DSI_AcknowledgeRequest */ - -} DSI_LPCmdTypeDef; - -/** - * @brief DSI PHY Timings definition - */ -typedef struct -{ - uint32_t ClockLaneHS2LPTime; /*!< The maximum time that the D-PHY clock lane takes to go from high-speed - to low-power transmission */ - - uint32_t ClockLaneLP2HSTime; /*!< The maximum time that the D-PHY clock lane takes to go from low-power - to high-speed transmission */ - - uint32_t DataLaneHS2LPTime; /*!< The maximum time that the D-PHY data lanes takes to go from high-speed - to low-power transmission */ - - uint32_t DataLaneLP2HSTime; /*!< The maximum time that the D-PHY data lanes takes to go from low-power - to high-speed transmission */ - - uint32_t DataLaneMaxReadTime; /*!< The maximum time required to perform a read command */ - - uint32_t StopWaitTime; /*!< The minimum wait period to request a High-Speed transmission after the - Stop state */ - -} DSI_PHY_TimerTypeDef; - -/** - * @brief DSI HOST Timeouts definition - */ -typedef struct -{ - uint32_t TimeoutCkdiv; /*!< Time-out clock division */ - - uint32_t HighSpeedTransmissionTimeout; /*!< High-speed transmission time-out */ - - uint32_t LowPowerReceptionTimeout; /*!< Low-power reception time-out */ - - uint32_t HighSpeedReadTimeout; /*!< High-speed read time-out */ - - uint32_t LowPowerReadTimeout; /*!< Low-power read time-out */ - - uint32_t HighSpeedWriteTimeout; /*!< High-speed write time-out */ - - uint32_t HighSpeedWritePrespMode; /*!< High-speed write presp mode - This parameter can be any value of @ref DSI_HS_PrespMode */ - - uint32_t LowPowerWriteTimeout; /*!< Low-speed write time-out */ - - uint32_t BTATimeout; /*!< BTA time-out */ - -} DSI_HOST_TimeoutTypeDef; - -/** - * @brief DSI States Structure definition - */ -typedef enum -{ - HAL_DSI_STATE_RESET = 0x00U, - HAL_DSI_STATE_READY = 0x01U, - HAL_DSI_STATE_ERROR = 0x02U, - HAL_DSI_STATE_BUSY = 0x03U, - HAL_DSI_STATE_TIMEOUT = 0x04U -} HAL_DSI_StateTypeDef; - -/** - * @brief DSI Handle Structure definition - */ -#if (USE_HAL_DSI_REGISTER_CALLBACKS == 1) -typedef struct __DSI_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_DSI_REGISTER_CALLBACKS */ -{ - DSI_TypeDef *Instance; /*!< Register base address */ - DSI_InitTypeDef Init; /*!< DSI required parameters */ - HAL_LockTypeDef Lock; /*!< DSI peripheral status */ - __IO HAL_DSI_StateTypeDef State; /*!< DSI communication state */ - __IO uint32_t ErrorCode; /*!< DSI Error code */ - uint32_t ErrorMsk; /*!< DSI Error monitoring mask */ - -#if (USE_HAL_DSI_REGISTER_CALLBACKS == 1) - void (* TearingEffectCallback)(struct __DSI_HandleTypeDef *hdsi); /*!< DSI Tearing Effect Callback */ - void (* EndOfRefreshCallback)(struct __DSI_HandleTypeDef *hdsi); /*!< DSI End Of Refresh Callback */ - void (* ErrorCallback)(struct __DSI_HandleTypeDef *hdsi); /*!< DSI Error Callback */ - - void (* MspInitCallback)(struct __DSI_HandleTypeDef *hdsi); /*!< DSI Msp Init callback */ - void (* MspDeInitCallback)(struct __DSI_HandleTypeDef *hdsi); /*!< DSI Msp DeInit callback */ - -#endif /* USE_HAL_DSI_REGISTER_CALLBACKS */ - -} DSI_HandleTypeDef; - -#if (USE_HAL_DSI_REGISTER_CALLBACKS == 1) -/** - * @brief HAL DSI Callback ID enumeration definition - */ -typedef enum -{ - HAL_DSI_MSPINIT_CB_ID = 0x00U, /*!< DSI MspInit callback ID */ - HAL_DSI_MSPDEINIT_CB_ID = 0x01U, /*!< DSI MspDeInit callback ID */ - - HAL_DSI_TEARING_EFFECT_CB_ID = 0x02U, /*!< DSI Tearing Effect Callback ID */ - HAL_DSI_ENDOF_REFRESH_CB_ID = 0x03U, /*!< DSI End Of Refresh Callback ID */ - HAL_DSI_ERROR_CB_ID = 0x04U /*!< DSI Error Callback ID */ - -} HAL_DSI_CallbackIDTypeDef; - -/** - * @brief HAL DSI Callback pointer definition - */ -typedef void (*pDSI_CallbackTypeDef)(DSI_HandleTypeDef *hdsi); /*!< pointer to an DSI callback function */ - -#endif /* USE_HAL_DSI_REGISTER_CALLBACKS */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup DSI_Exported_Constants DSI Exported Constants - * @{ - */ -/** @defgroup DSI_DCS_Command DSI DCS Command - * @{ - */ -#define DSI_ENTER_IDLE_MODE 0x39U -#define DSI_ENTER_INVERT_MODE 0x21U -#define DSI_ENTER_NORMAL_MODE 0x13U -#define DSI_ENTER_PARTIAL_MODE 0x12U -#define DSI_ENTER_SLEEP_MODE 0x10U -#define DSI_EXIT_IDLE_MODE 0x38U -#define DSI_EXIT_INVERT_MODE 0x20U -#define DSI_EXIT_SLEEP_MODE 0x11U -#define DSI_GET_3D_CONTROL 0x3FU -#define DSI_GET_ADDRESS_MODE 0x0BU -#define DSI_GET_BLUE_CHANNEL 0x08U -#define DSI_GET_DIAGNOSTIC_RESULT 0x0FU -#define DSI_GET_DISPLAY_MODE 0x0DU -#define DSI_GET_GREEN_CHANNEL 0x07U -#define DSI_GET_PIXEL_FORMAT 0x0CU -#define DSI_GET_POWER_MODE 0x0AU -#define DSI_GET_RED_CHANNEL 0x06U -#define DSI_GET_SCANLINE 0x45U -#define DSI_GET_SIGNAL_MODE 0x0EU -#define DSI_NOP 0x00U -#define DSI_READ_DDB_CONTINUE 0xA8U -#define DSI_READ_DDB_START 0xA1U -#define DSI_READ_MEMORY_CONTINUE 0x3EU -#define DSI_READ_MEMORY_START 0x2EU -#define DSI_SET_3D_CONTROL 0x3DU -#define DSI_SET_ADDRESS_MODE 0x36U -#define DSI_SET_COLUMN_ADDRESS 0x2AU -#define DSI_SET_DISPLAY_OFF 0x28U -#define DSI_SET_DISPLAY_ON 0x29U -#define DSI_SET_GAMMA_CURVE 0x26U -#define DSI_SET_PAGE_ADDRESS 0x2BU -#define DSI_SET_PARTIAL_COLUMNS 0x31U -#define DSI_SET_PARTIAL_ROWS 0x30U -#define DSI_SET_PIXEL_FORMAT 0x3AU -#define DSI_SET_SCROLL_AREA 0x33U -#define DSI_SET_SCROLL_START 0x37U -#define DSI_SET_TEAR_OFF 0x34U -#define DSI_SET_TEAR_ON 0x35U -#define DSI_SET_TEAR_SCANLINE 0x44U -#define DSI_SET_VSYNC_TIMING 0x40U -#define DSI_SOFT_RESET 0x01U -#define DSI_WRITE_LUT 0x2DU -#define DSI_WRITE_MEMORY_CONTINUE 0x3CU -#define DSI_WRITE_MEMORY_START 0x2CU -/** - * @} - */ - -/** @defgroup DSI_Video_Mode_Type DSI Video Mode Type - * @{ - */ -#define DSI_VID_MODE_NB_PULSES 0U -#define DSI_VID_MODE_NB_EVENTS 1U -#define DSI_VID_MODE_BURST 2U -/** - * @} - */ - -/** @defgroup DSI_Color_Mode DSI Color Mode - * @{ - */ -#define DSI_COLOR_MODE_FULL 0x00000000U -#define DSI_COLOR_MODE_EIGHT DSI_WCR_COLM -/** - * @} - */ - -/** @defgroup DSI_ShutDown DSI ShutDown - * @{ - */ -#define DSI_DISPLAY_ON 0x00000000U -#define DSI_DISPLAY_OFF DSI_WCR_SHTDN -/** - * @} - */ - -/** @defgroup DSI_LP_Command DSI LP Command - * @{ - */ -#define DSI_LP_COMMAND_DISABLE 0x00000000U -#define DSI_LP_COMMAND_ENABLE DSI_VMCR_LPCE -/** - * @} - */ - -/** @defgroup DSI_LP_HFP DSI LP HFP - * @{ - */ -#define DSI_LP_HFP_DISABLE 0x00000000U -#define DSI_LP_HFP_ENABLE DSI_VMCR_LPHFPE -/** - * @} - */ - -/** @defgroup DSI_LP_HBP DSI LP HBP - * @{ - */ -#define DSI_LP_HBP_DISABLE 0x00000000U -#define DSI_LP_HBP_ENABLE DSI_VMCR_LPHBPE -/** - * @} - */ - -/** @defgroup DSI_LP_VACT DSI LP VACT - * @{ - */ -#define DSI_LP_VACT_DISABLE 0x00000000U -#define DSI_LP_VACT_ENABLE DSI_VMCR_LPVAE -/** - * @} - */ - -/** @defgroup DSI_LP_VFP DSI LP VFP - * @{ - */ -#define DSI_LP_VFP_DISABLE 0x00000000U -#define DSI_LP_VFP_ENABLE DSI_VMCR_LPVFPE -/** - * @} - */ - -/** @defgroup DSI_LP_VBP DSI LP VBP - * @{ - */ -#define DSI_LP_VBP_DISABLE 0x00000000U -#define DSI_LP_VBP_ENABLE DSI_VMCR_LPVBPE -/** - * @} - */ - -/** @defgroup DSI_LP_VSYNC DSI LP VSYNC - * @{ - */ -#define DSI_LP_VSYNC_DISABLE 0x00000000U -#define DSI_LP_VSYNC_ENABLE DSI_VMCR_LPVSAE -/** - * @} - */ - -/** @defgroup DSI_FBTA_acknowledge DSI FBTA Acknowledge - * @{ - */ -#define DSI_FBTAA_DISABLE 0x00000000U -#define DSI_FBTAA_ENABLE DSI_VMCR_FBTAAE -/** - * @} - */ - -/** @defgroup DSI_TearingEffectSource DSI Tearing Effect Source - * @{ - */ -#define DSI_TE_DSILINK 0x00000000U -#define DSI_TE_EXTERNAL DSI_WCFGR_TESRC -/** - * @} - */ - -/** @defgroup DSI_TearingEffectPolarity DSI Tearing Effect Polarity - * @{ - */ -#define DSI_TE_RISING_EDGE 0x00000000U -#define DSI_TE_FALLING_EDGE DSI_WCFGR_TEPOL -/** - * @} - */ - -/** @defgroup DSI_Vsync_Polarity DSI Vsync Polarity - * @{ - */ -#define DSI_VSYNC_FALLING 0x00000000U -#define DSI_VSYNC_RISING DSI_WCFGR_VSPOL -/** - * @} - */ - -/** @defgroup DSI_AutomaticRefresh DSI Automatic Refresh - * @{ - */ -#define DSI_AR_DISABLE 0x00000000U -#define DSI_AR_ENABLE DSI_WCFGR_AR -/** - * @} - */ - -/** @defgroup DSI_TE_AcknowledgeRequest DSI TE Acknowledge Request - * @{ - */ -#define DSI_TE_ACKNOWLEDGE_DISABLE 0x00000000U -#define DSI_TE_ACKNOWLEDGE_ENABLE DSI_CMCR_TEARE -/** - * @} - */ - -/** @defgroup DSI_AcknowledgeRequest DSI Acknowledge Request - * @{ - */ -#define DSI_ACKNOWLEDGE_DISABLE 0x00000000U -#define DSI_ACKNOWLEDGE_ENABLE DSI_CMCR_ARE -/** - * @} - */ - -/** @defgroup DSI_LP_LPGenShortWriteNoP DSI LP LPGen Short Write NoP - * @{ - */ -#define DSI_LP_GSW0P_DISABLE 0x00000000U -#define DSI_LP_GSW0P_ENABLE DSI_CMCR_GSW0TX -/** - * @} - */ - -/** @defgroup DSI_LP_LPGenShortWriteOneP DSI LP LPGen Short Write OneP - * @{ - */ -#define DSI_LP_GSW1P_DISABLE 0x00000000U -#define DSI_LP_GSW1P_ENABLE DSI_CMCR_GSW1TX -/** - * @} - */ - -/** @defgroup DSI_LP_LPGenShortWriteTwoP DSI LP LPGen Short Write TwoP - * @{ - */ -#define DSI_LP_GSW2P_DISABLE 0x00000000U -#define DSI_LP_GSW2P_ENABLE DSI_CMCR_GSW2TX -/** - * @} - */ - -/** @defgroup DSI_LP_LPGenShortReadNoP DSI LP LPGen Short Read NoP - * @{ - */ -#define DSI_LP_GSR0P_DISABLE 0x00000000U -#define DSI_LP_GSR0P_ENABLE DSI_CMCR_GSR0TX -/** - * @} - */ - -/** @defgroup DSI_LP_LPGenShortReadOneP DSI LP LPGen Short Read OneP - * @{ - */ -#define DSI_LP_GSR1P_DISABLE 0x00000000U -#define DSI_LP_GSR1P_ENABLE DSI_CMCR_GSR1TX -/** - * @} - */ - -/** @defgroup DSI_LP_LPGenShortReadTwoP DSI LP LPGen Short Read TwoP - * @{ - */ -#define DSI_LP_GSR2P_DISABLE 0x00000000U -#define DSI_LP_GSR2P_ENABLE DSI_CMCR_GSR2TX -/** - * @} - */ - -/** @defgroup DSI_LP_LPGenLongWrite DSI LP LPGen LongWrite - * @{ - */ -#define DSI_LP_GLW_DISABLE 0x00000000U -#define DSI_LP_GLW_ENABLE DSI_CMCR_GLWTX -/** - * @} - */ - -/** @defgroup DSI_LP_LPDcsShortWriteNoP DSI LP LPDcs Short Write NoP - * @{ - */ -#define DSI_LP_DSW0P_DISABLE 0x00000000U -#define DSI_LP_DSW0P_ENABLE DSI_CMCR_DSW0TX -/** - * @} - */ - -/** @defgroup DSI_LP_LPDcsShortWriteOneP DSI LP LPDcs Short Write OneP - * @{ - */ -#define DSI_LP_DSW1P_DISABLE 0x00000000U -#define DSI_LP_DSW1P_ENABLE DSI_CMCR_DSW1TX -/** - * @} - */ - -/** @defgroup DSI_LP_LPDcsShortReadNoP DSI LP LPDcs Short Read NoP - * @{ - */ -#define DSI_LP_DSR0P_DISABLE 0x00000000U -#define DSI_LP_DSR0P_ENABLE DSI_CMCR_DSR0TX -/** - * @} - */ - -/** @defgroup DSI_LP_LPDcsLongWrite DSI LP LPDcs Long Write - * @{ - */ -#define DSI_LP_DLW_DISABLE 0x00000000U -#define DSI_LP_DLW_ENABLE DSI_CMCR_DLWTX -/** - * @} - */ - -/** @defgroup DSI_LP_LPMaxReadPacket DSI LP LPMax Read Packet - * @{ - */ -#define DSI_LP_MRDP_DISABLE 0x00000000U -#define DSI_LP_MRDP_ENABLE DSI_CMCR_MRDPS -/** - * @} - */ - -/** @defgroup DSI_HS_PrespMode DSI HS Presp Mode - * @{ - */ -#define DSI_HS_PM_DISABLE 0x00000000U -#define DSI_HS_PM_ENABLE DSI_TCCR3_PM -/** - * @} - */ - - -/** @defgroup DSI_Automatic_Clk_Lane_Control DSI Automatic Clk Lane Control - * @{ - */ -#define DSI_AUTO_CLK_LANE_CTRL_DISABLE 0x00000000U -#define DSI_AUTO_CLK_LANE_CTRL_ENABLE DSI_CLCR_ACR -/** - * @} - */ - -/** @defgroup DSI_Number_Of_Lanes DSI Number Of Lanes - * @{ - */ -#define DSI_ONE_DATA_LANE 0U -#define DSI_TWO_DATA_LANES 1U -/** - * @} - */ - -/** @defgroup DSI_FlowControl DSI Flow Control - * @{ - */ -#define DSI_FLOW_CONTROL_CRC_RX DSI_PCR_CRCRXE -#define DSI_FLOW_CONTROL_ECC_RX DSI_PCR_ECCRXE -#define DSI_FLOW_CONTROL_BTA DSI_PCR_BTAE -#define DSI_FLOW_CONTROL_EOTP_RX DSI_PCR_ETRXE -#define DSI_FLOW_CONTROL_EOTP_TX DSI_PCR_ETTXE -#define DSI_FLOW_CONTROL_ALL (DSI_FLOW_CONTROL_CRC_RX | DSI_FLOW_CONTROL_ECC_RX | \ - DSI_FLOW_CONTROL_BTA | DSI_FLOW_CONTROL_EOTP_RX | \ - DSI_FLOW_CONTROL_EOTP_TX) -/** - * @} - */ - -/** @defgroup DSI_Color_Coding DSI Color Coding - * @{ - */ -#define DSI_RGB565 0x00000000U /*!< The values 0x00000001 and 0x00000002 can also be used for the RGB565 color mode configuration */ -#define DSI_RGB666 0x00000003U /*!< The value 0x00000004 can also be used for the RGB666 color mode configuration */ -#define DSI_RGB888 0x00000005U -/** - * @} - */ - -/** @defgroup DSI_LooselyPacked DSI Loosely Packed - * @{ - */ -#define DSI_LOOSELY_PACKED_ENABLE DSI_LCOLCR_LPE -#define DSI_LOOSELY_PACKED_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup DSI_HSYNC_Polarity DSI HSYNC Polarity - * @{ - */ -#define DSI_HSYNC_ACTIVE_HIGH 0x00000000U -#define DSI_HSYNC_ACTIVE_LOW DSI_LPCR_HSP -/** - * @} - */ - -/** @defgroup DSI_VSYNC_Active_Polarity DSI VSYNC Active Polarity - * @{ - */ -#define DSI_VSYNC_ACTIVE_HIGH 0x00000000U -#define DSI_VSYNC_ACTIVE_LOW DSI_LPCR_VSP -/** - * @} - */ - -/** @defgroup DSI_DATA_ENABLE_Polarity DSI DATA ENABLE Polarity - * @{ - */ -#define DSI_DATA_ENABLE_ACTIVE_HIGH 0x00000000U -#define DSI_DATA_ENABLE_ACTIVE_LOW DSI_LPCR_DEP -/** - * @} - */ - -/** @defgroup DSI_PLL_IDF DSI PLL IDF - * @{ - */ -#define DSI_PLL_IN_DIV1 0x00000001U -#define DSI_PLL_IN_DIV2 0x00000002U -#define DSI_PLL_IN_DIV3 0x00000003U -#define DSI_PLL_IN_DIV4 0x00000004U -#define DSI_PLL_IN_DIV5 0x00000005U -#define DSI_PLL_IN_DIV6 0x00000006U -#define DSI_PLL_IN_DIV7 0x00000007U -/** - * @} - */ - -/** @defgroup DSI_PLL_ODF DSI PLL ODF - * @{ - */ -#define DSI_PLL_OUT_DIV1 0x00000000U -#define DSI_PLL_OUT_DIV2 0x00000001U -#define DSI_PLL_OUT_DIV4 0x00000002U -#define DSI_PLL_OUT_DIV8 0x00000003U -/** - * @} - */ - -/** @defgroup DSI_Flags DSI Flags - * @{ - */ -#define DSI_FLAG_TE DSI_WISR_TEIF -#define DSI_FLAG_ER DSI_WISR_ERIF -#define DSI_FLAG_BUSY DSI_WISR_BUSY -#define DSI_FLAG_PLLLS DSI_WISR_PLLLS -#define DSI_FLAG_PLLL DSI_WISR_PLLLIF -#define DSI_FLAG_PLLU DSI_WISR_PLLUIF -#define DSI_FLAG_RRS DSI_WISR_RRS -#define DSI_FLAG_RR DSI_WISR_RRIF -/** - * @} - */ - -/** @defgroup DSI_Interrupts DSI Interrupts - * @{ - */ -#define DSI_IT_TE DSI_WIER_TEIE -#define DSI_IT_ER DSI_WIER_ERIE -#define DSI_IT_PLLL DSI_WIER_PLLLIE -#define DSI_IT_PLLU DSI_WIER_PLLUIE -#define DSI_IT_RR DSI_WIER_RRIE -/** - * @} - */ - -/** @defgroup DSI_SHORT_WRITE_PKT_Data_Type DSI SHORT WRITE PKT Data Type - * @{ - */ -#define DSI_DCS_SHORT_PKT_WRITE_P0 0x00000005U /*!< DCS short write, no parameters */ -#define DSI_DCS_SHORT_PKT_WRITE_P1 0x00000015U /*!< DCS short write, one parameter */ -#define DSI_GEN_SHORT_PKT_WRITE_P0 0x00000003U /*!< Generic short write, no parameters */ -#define DSI_GEN_SHORT_PKT_WRITE_P1 0x00000013U /*!< Generic short write, one parameter */ -#define DSI_GEN_SHORT_PKT_WRITE_P2 0x00000023U /*!< Generic short write, two parameters */ -/** - * @} - */ - -/** @defgroup DSI_LONG_WRITE_PKT_Data_Type DSI LONG WRITE PKT Data Type - * @{ - */ -#define DSI_DCS_LONG_PKT_WRITE 0x00000039U /*!< DCS long write */ -#define DSI_GEN_LONG_PKT_WRITE 0x00000029U /*!< Generic long write */ -/** - * @} - */ - -/** @defgroup DSI_SHORT_READ_PKT_Data_Type DSI SHORT READ PKT Data Type - * @{ - */ -#define DSI_DCS_SHORT_PKT_READ 0x00000006U /*!< DCS short read */ -#define DSI_GEN_SHORT_PKT_READ_P0 0x00000004U /*!< Generic short read, no parameters */ -#define DSI_GEN_SHORT_PKT_READ_P1 0x00000014U /*!< Generic short read, one parameter */ -#define DSI_GEN_SHORT_PKT_READ_P2 0x00000024U /*!< Generic short read, two parameters */ -/** - * @} - */ - -/** @defgroup DSI_Error_Data_Type DSI Error Data Type - * @{ - */ -#define HAL_DSI_ERROR_NONE 0U -#define HAL_DSI_ERROR_ACK 0x00000001U /*!< acknowledge errors */ -#define HAL_DSI_ERROR_PHY 0x00000002U /*!< PHY related errors */ -#define HAL_DSI_ERROR_TX 0x00000004U /*!< transmission error */ -#define HAL_DSI_ERROR_RX 0x00000008U /*!< reception error */ -#define HAL_DSI_ERROR_ECC 0x00000010U /*!< ECC errors */ -#define HAL_DSI_ERROR_CRC 0x00000020U /*!< CRC error */ -#define HAL_DSI_ERROR_PSE 0x00000040U /*!< Packet Size error */ -#define HAL_DSI_ERROR_EOT 0x00000080U /*!< End Of Transmission error */ -#define HAL_DSI_ERROR_OVF 0x00000100U /*!< FIFO overflow error */ -#define HAL_DSI_ERROR_GEN 0x00000200U /*!< Generic FIFO related errors */ -#if (USE_HAL_DSI_REGISTER_CALLBACKS == 1) -#define HAL_DSI_ERROR_INVALID_CALLBACK 0x00000400U /*!< DSI Invalid Callback error */ -#endif /* USE_HAL_DSI_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @defgroup DSI_Lane_Group DSI Lane Group - * @{ - */ -#define DSI_CLOCK_LANE 0x00000000U -#define DSI_DATA_LANES 0x00000001U -/** - * @} - */ - -/** @defgroup DSI_Communication_Delay DSI Communication Delay - * @{ - */ -#define DSI_SLEW_RATE_HSTX 0x00000000U -#define DSI_SLEW_RATE_LPTX 0x00000001U -#define DSI_HS_DELAY 0x00000002U -/** - * @} - */ - -/** @defgroup DSI_CustomLane DSI CustomLane - * @{ - */ -#define DSI_SWAP_LANE_PINS 0x00000000U -#define DSI_INVERT_HS_SIGNAL 0x00000001U -/** - * @} - */ - -/** @defgroup DSI_Lane_Select DSI Lane Select - * @{ - */ -#define DSI_CLK_LANE 0x00000000U -#define DSI_DATA_LANE0 0x00000001U -#define DSI_DATA_LANE1 0x00000002U -/** - * @} - */ - -/** @defgroup DSI_PHY_Timing DSI PHY Timing - * @{ - */ -#define DSI_TCLK_POST 0x00000000U -#define DSI_TLPX_CLK 0x00000001U -#define DSI_THS_EXIT 0x00000002U -#define DSI_TLPX_DATA 0x00000003U -#define DSI_THS_ZERO 0x00000004U -#define DSI_THS_TRAIL 0x00000005U -#define DSI_THS_PREPARE 0x00000006U -#define DSI_TCLK_ZERO 0x00000007U -#define DSI_TCLK_PREPARE 0x00000008U -/** - * @} - */ - -/** - * @} - */ - -/* Exported macros -----------------------------------------------------------*/ -/** @defgroup DSI_Exported_Macros DSI Exported Macros - * @{ - */ - -/** - * @brief Reset DSI handle state. - * @param __HANDLE__ DSI handle - * @retval None - */ -#if (USE_HAL_DSI_REGISTER_CALLBACKS == 1) -#define __HAL_DSI_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->State = HAL_DSI_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_DSI_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_DSI_STATE_RESET) -#endif /*USE_HAL_DSI_REGISTER_CALLBACKS */ - -/** - * @brief Enables the DSI host. - * @param __HANDLE__ DSI handle - * @retval None. - */ -#define __HAL_DSI_ENABLE(__HANDLE__) do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT((__HANDLE__)->Instance->CR, DSI_CR_EN);\ - /* Delay after an DSI Host enabling */ \ - tmpreg = READ_BIT((__HANDLE__)->Instance->CR, DSI_CR_EN);\ - UNUSED(tmpreg); \ - } while(0U) - -/** - * @brief Disables the DSI host. - * @param __HANDLE__ DSI handle - * @retval None. - */ -#define __HAL_DSI_DISABLE(__HANDLE__) do { \ - __IO uint32_t tmpreg = 0x00U; \ - CLEAR_BIT((__HANDLE__)->Instance->CR, DSI_CR_EN);\ - /* Delay after an DSI Host disabling */ \ - tmpreg = READ_BIT((__HANDLE__)->Instance->CR, DSI_CR_EN);\ - UNUSED(tmpreg); \ - } while(0U) - -/** - * @brief Enables the DSI wrapper. - * @param __HANDLE__ DSI handle - * @retval None. - */ -#define __HAL_DSI_WRAPPER_ENABLE(__HANDLE__) do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT((__HANDLE__)->Instance->WCR, DSI_WCR_DSIEN);\ - /* Delay after an DSI warpper enabling */ \ - tmpreg = READ_BIT((__HANDLE__)->Instance->WCR, DSI_WCR_DSIEN);\ - UNUSED(tmpreg); \ - } while(0U) - -/** - * @brief Disable the DSI wrapper. - * @param __HANDLE__ DSI handle - * @retval None. - */ -#define __HAL_DSI_WRAPPER_DISABLE(__HANDLE__) do { \ - __IO uint32_t tmpreg = 0x00U; \ - CLEAR_BIT((__HANDLE__)->Instance->WCR, DSI_WCR_DSIEN);\ - /* Delay after an DSI warpper disabling*/ \ - tmpreg = READ_BIT((__HANDLE__)->Instance->WCR, DSI_WCR_DSIEN);\ - UNUSED(tmpreg); \ - } while(0U) - -/** - * @brief Enables the DSI PLL. - * @param __HANDLE__ DSI handle - * @retval None. - */ -#define __HAL_DSI_PLL_ENABLE(__HANDLE__) do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT((__HANDLE__)->Instance->WRPCR, DSI_WRPCR_PLLEN);\ - /* Delay after an DSI PLL enabling */ \ - tmpreg = READ_BIT((__HANDLE__)->Instance->WRPCR, DSI_WRPCR_PLLEN);\ - UNUSED(tmpreg); \ - } while(0U) - -/** - * @brief Disables the DSI PLL. - * @param __HANDLE__ DSI handle - * @retval None. - */ -#define __HAL_DSI_PLL_DISABLE(__HANDLE__) do { \ - __IO uint32_t tmpreg = 0x00U; \ - CLEAR_BIT((__HANDLE__)->Instance->WRPCR, DSI_WRPCR_PLLEN);\ - /* Delay after an DSI PLL disabling */ \ - tmpreg = READ_BIT((__HANDLE__)->Instance->WRPCR, DSI_WRPCR_PLLEN);\ - UNUSED(tmpreg); \ - } while(0U) - -/** - * @brief Enables the DSI regulator. - * @param __HANDLE__ DSI handle - * @retval None. - */ -#define __HAL_DSI_REG_ENABLE(__HANDLE__) do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT((__HANDLE__)->Instance->WRPCR, DSI_WRPCR_REGEN);\ - /* Delay after an DSI regulator enabling */ \ - tmpreg = READ_BIT((__HANDLE__)->Instance->WRPCR, DSI_WRPCR_REGEN);\ - UNUSED(tmpreg); \ - } while(0U) - -/** - * @brief Disables the DSI regulator. - * @param __HANDLE__ DSI handle - * @retval None. - */ -#define __HAL_DSI_REG_DISABLE(__HANDLE__) do { \ - __IO uint32_t tmpreg = 0x00U; \ - CLEAR_BIT((__HANDLE__)->Instance->WRPCR, DSI_WRPCR_REGEN);\ - /* Delay after an DSI regulator disabling */ \ - tmpreg = READ_BIT((__HANDLE__)->Instance->WRPCR, DSI_WRPCR_REGEN);\ - UNUSED(tmpreg); \ - } while(0U) - -/** - * @brief Get the DSI pending flags. - * @param __HANDLE__ DSI handle. - * @param __FLAG__ Get the specified flag. - * This parameter can be any combination of the following values: - * @arg DSI_FLAG_TE : Tearing Effect Interrupt Flag - * @arg DSI_FLAG_ER : End of Refresh Interrupt Flag - * @arg DSI_FLAG_BUSY : Busy Flag - * @arg DSI_FLAG_PLLLS: PLL Lock Status - * @arg DSI_FLAG_PLLL : PLL Lock Interrupt Flag - * @arg DSI_FLAG_PLLU : PLL Unlock Interrupt Flag - * @arg DSI_FLAG_RRS : Regulator Ready Flag - * @arg DSI_FLAG_RR : Regulator Ready Interrupt Flag - * @retval The state of FLAG (SET or RESET). - */ -#define __HAL_DSI_GET_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->WISR & (__FLAG__)) - -/** - * @brief Clears the DSI pending flags. - * @param __HANDLE__ DSI handle. - * @param __FLAG__ specifies the flag to clear. - * This parameter can be any combination of the following values: - * @arg DSI_FLAG_TE : Tearing Effect Interrupt Flag - * @arg DSI_FLAG_ER : End of Refresh Interrupt Flag - * @arg DSI_FLAG_PLLL : PLL Lock Interrupt Flag - * @arg DSI_FLAG_PLLU : PLL Unlock Interrupt Flag - * @arg DSI_FLAG_RR : Regulator Ready Interrupt Flag - * @retval None - */ -#define __HAL_DSI_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->WIFCR = (__FLAG__)) - -/** - * @brief Enables the specified DSI interrupts. - * @param __HANDLE__ DSI handle. - * @param __INTERRUPT__ specifies the DSI interrupt sources to be enabled. - * This parameter can be any combination of the following values: - * @arg DSI_IT_TE : Tearing Effect Interrupt - * @arg DSI_IT_ER : End of Refresh Interrupt - * @arg DSI_IT_PLLL: PLL Lock Interrupt - * @arg DSI_IT_PLLU: PLL Unlock Interrupt - * @arg DSI_IT_RR : Regulator Ready Interrupt - * @retval None - */ -#define __HAL_DSI_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->WIER |= (__INTERRUPT__)) - -/** - * @brief Disables the specified DSI interrupts. - * @param __HANDLE__ DSI handle - * @param __INTERRUPT__ specifies the DSI interrupt sources to be disabled. - * This parameter can be any combination of the following values: - * @arg DSI_IT_TE : Tearing Effect Interrupt - * @arg DSI_IT_ER : End of Refresh Interrupt - * @arg DSI_IT_PLLL: PLL Lock Interrupt - * @arg DSI_IT_PLLU: PLL Unlock Interrupt - * @arg DSI_IT_RR : Regulator Ready Interrupt - * @retval None - */ -#define __HAL_DSI_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->WIER &= ~(__INTERRUPT__)) - -/** - * @brief Checks whether the specified DSI interrupt source is enabled or not. - * @param __HANDLE__ DSI handle - * @param __INTERRUPT__ specifies the DSI interrupt source to check. - * This parameter can be one of the following values: - * @arg DSI_IT_TE : Tearing Effect Interrupt - * @arg DSI_IT_ER : End of Refresh Interrupt - * @arg DSI_IT_PLLL: PLL Lock Interrupt - * @arg DSI_IT_PLLU: PLL Unlock Interrupt - * @arg DSI_IT_RR : Regulator Ready Interrupt - * @retval The state of INTERRUPT (SET or RESET). - */ -#define __HAL_DSI_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->WIER & (__INTERRUPT__)) - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup DSI_Exported_Functions DSI Exported Functions - * @{ - */ -HAL_StatusTypeDef HAL_DSI_Init(DSI_HandleTypeDef *hdsi, DSI_PLLInitTypeDef *PLLInit); -HAL_StatusTypeDef HAL_DSI_DeInit(DSI_HandleTypeDef *hdsi); -void HAL_DSI_MspInit(DSI_HandleTypeDef *hdsi); -void HAL_DSI_MspDeInit(DSI_HandleTypeDef *hdsi); - -void HAL_DSI_IRQHandler(DSI_HandleTypeDef *hdsi); -void HAL_DSI_TearingEffectCallback(DSI_HandleTypeDef *hdsi); -void HAL_DSI_EndOfRefreshCallback(DSI_HandleTypeDef *hdsi); -void HAL_DSI_ErrorCallback(DSI_HandleTypeDef *hdsi); - -/* Callbacks Register/UnRegister functions ***********************************/ -#if (USE_HAL_DSI_REGISTER_CALLBACKS == 1) -HAL_StatusTypeDef HAL_DSI_RegisterCallback(DSI_HandleTypeDef *hdsi, HAL_DSI_CallbackIDTypeDef CallbackID, - pDSI_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_DSI_UnRegisterCallback(DSI_HandleTypeDef *hdsi, HAL_DSI_CallbackIDTypeDef CallbackID); -#endif /* USE_HAL_DSI_REGISTER_CALLBACKS */ - -HAL_StatusTypeDef HAL_DSI_SetGenericVCID(DSI_HandleTypeDef *hdsi, uint32_t VirtualChannelID); -HAL_StatusTypeDef HAL_DSI_ConfigVideoMode(DSI_HandleTypeDef *hdsi, DSI_VidCfgTypeDef *VidCfg); -HAL_StatusTypeDef HAL_DSI_ConfigAdaptedCommandMode(DSI_HandleTypeDef *hdsi, DSI_CmdCfgTypeDef *CmdCfg); -HAL_StatusTypeDef HAL_DSI_ConfigCommand(DSI_HandleTypeDef *hdsi, DSI_LPCmdTypeDef *LPCmd); -HAL_StatusTypeDef HAL_DSI_ConfigFlowControl(DSI_HandleTypeDef *hdsi, uint32_t FlowControl); -HAL_StatusTypeDef HAL_DSI_ConfigPhyTimer(DSI_HandleTypeDef *hdsi, DSI_PHY_TimerTypeDef *PhyTimers); -HAL_StatusTypeDef HAL_DSI_ConfigHostTimeouts(DSI_HandleTypeDef *hdsi, DSI_HOST_TimeoutTypeDef *HostTimeouts); -HAL_StatusTypeDef HAL_DSI_Start(DSI_HandleTypeDef *hdsi); -HAL_StatusTypeDef HAL_DSI_Stop(DSI_HandleTypeDef *hdsi); -HAL_StatusTypeDef HAL_DSI_Refresh(DSI_HandleTypeDef *hdsi); -HAL_StatusTypeDef HAL_DSI_ColorMode(DSI_HandleTypeDef *hdsi, uint32_t ColorMode); -HAL_StatusTypeDef HAL_DSI_Shutdown(DSI_HandleTypeDef *hdsi, uint32_t Shutdown); -HAL_StatusTypeDef HAL_DSI_ShortWrite(DSI_HandleTypeDef *hdsi, - uint32_t ChannelID, - uint32_t Mode, - uint32_t Param1, - uint32_t Param2); -HAL_StatusTypeDef HAL_DSI_LongWrite(DSI_HandleTypeDef *hdsi, - uint32_t ChannelID, - uint32_t Mode, - uint32_t NbParams, - uint32_t Param1, - uint8_t *ParametersTable); -HAL_StatusTypeDef HAL_DSI_Read(DSI_HandleTypeDef *hdsi, - uint32_t ChannelNbr, - uint8_t *Array, - uint32_t Size, - uint32_t Mode, - uint32_t DCSCmd, - uint8_t *ParametersTable); -HAL_StatusTypeDef HAL_DSI_EnterULPMData(DSI_HandleTypeDef *hdsi); -HAL_StatusTypeDef HAL_DSI_ExitULPMData(DSI_HandleTypeDef *hdsi); -HAL_StatusTypeDef HAL_DSI_EnterULPM(DSI_HandleTypeDef *hdsi); -HAL_StatusTypeDef HAL_DSI_ExitULPM(DSI_HandleTypeDef *hdsi); - -HAL_StatusTypeDef HAL_DSI_PatternGeneratorStart(DSI_HandleTypeDef *hdsi, uint32_t Mode, uint32_t Orientation); -HAL_StatusTypeDef HAL_DSI_PatternGeneratorStop(DSI_HandleTypeDef *hdsi); - -HAL_StatusTypeDef HAL_DSI_SetSlewRateAndDelayTuning(DSI_HandleTypeDef *hdsi, uint32_t CommDelay, uint32_t Lane, - uint32_t Value); -HAL_StatusTypeDef HAL_DSI_SetLowPowerRXFilter(DSI_HandleTypeDef *hdsi, uint32_t Frequency); -HAL_StatusTypeDef HAL_DSI_SetSDD(DSI_HandleTypeDef *hdsi, FunctionalState State); -HAL_StatusTypeDef HAL_DSI_SetLanePinsConfiguration(DSI_HandleTypeDef *hdsi, uint32_t CustomLane, uint32_t Lane, - FunctionalState State); -HAL_StatusTypeDef HAL_DSI_SetPHYTimings(DSI_HandleTypeDef *hdsi, uint32_t Timing, FunctionalState State, - uint32_t Value); -HAL_StatusTypeDef HAL_DSI_ForceTXStopMode(DSI_HandleTypeDef *hdsi, uint32_t Lane, FunctionalState State); -HAL_StatusTypeDef HAL_DSI_ForceRXLowPower(DSI_HandleTypeDef *hdsi, FunctionalState State); -HAL_StatusTypeDef HAL_DSI_ForceDataLanesInRX(DSI_HandleTypeDef *hdsi, FunctionalState State); -HAL_StatusTypeDef HAL_DSI_SetPullDown(DSI_HandleTypeDef *hdsi, FunctionalState State); -HAL_StatusTypeDef HAL_DSI_SetContentionDetectionOff(DSI_HandleTypeDef *hdsi, FunctionalState State); - -uint32_t HAL_DSI_GetError(DSI_HandleTypeDef *hdsi); -HAL_StatusTypeDef HAL_DSI_ConfigErrorMonitor(DSI_HandleTypeDef *hdsi, uint32_t ActiveErrors); -HAL_DSI_StateTypeDef HAL_DSI_GetState(DSI_HandleTypeDef *hdsi); -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/** @defgroup DSI_Private_Types DSI Private Types - * @{ - */ - -/** - * @} - */ - -/* Private defines -----------------------------------------------------------*/ -/** @defgroup DSI_Private_Defines DSI Private Defines - * @{ - */ - -/** - * @} - */ - -/* Private variables ---------------------------------------------------------*/ -/** @defgroup DSI_Private_Variables DSI Private Variables - * @{ - */ - -/** - * @} - */ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup DSI_Private_Constants DSI Private Constants - * @{ - */ -#define DSI_MAX_RETURN_PKT_SIZE (0x00000037U) /*!< Maximum return packet configuration */ -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup DSI_Private_Macros DSI Private Macros - * @{ - */ -#define IS_DSI_PLL_NDIV(NDIV) ((10U <= (NDIV)) && ((NDIV) <= 125U)) -#define IS_DSI_PLL_IDF(IDF) (((IDF) == DSI_PLL_IN_DIV1) || \ - ((IDF) == DSI_PLL_IN_DIV2) || \ - ((IDF) == DSI_PLL_IN_DIV3) || \ - ((IDF) == DSI_PLL_IN_DIV4) || \ - ((IDF) == DSI_PLL_IN_DIV5) || \ - ((IDF) == DSI_PLL_IN_DIV6) || \ - ((IDF) == DSI_PLL_IN_DIV7)) -#define IS_DSI_PLL_ODF(ODF) (((ODF) == DSI_PLL_OUT_DIV1) || \ - ((ODF) == DSI_PLL_OUT_DIV2) || \ - ((ODF) == DSI_PLL_OUT_DIV4) || \ - ((ODF) == DSI_PLL_OUT_DIV8)) -#define IS_DSI_AUTO_CLKLANE_CONTROL(AutoClkLane) (((AutoClkLane) == DSI_AUTO_CLK_LANE_CTRL_DISABLE) || ((AutoClkLane) == DSI_AUTO_CLK_LANE_CTRL_ENABLE)) -#define IS_DSI_NUMBER_OF_LANES(NumberOfLanes) (((NumberOfLanes) == DSI_ONE_DATA_LANE) || ((NumberOfLanes) == DSI_TWO_DATA_LANES)) -#define IS_DSI_FLOW_CONTROL(FlowControl) (((FlowControl) | DSI_FLOW_CONTROL_ALL) == DSI_FLOW_CONTROL_ALL) -#define IS_DSI_COLOR_CODING(ColorCoding) ((ColorCoding) <= 5U) -#define IS_DSI_LOOSELY_PACKED(LooselyPacked) (((LooselyPacked) == DSI_LOOSELY_PACKED_ENABLE) || ((LooselyPacked) == DSI_LOOSELY_PACKED_DISABLE)) -#define IS_DSI_DE_POLARITY(DataEnable) (((DataEnable) == DSI_DATA_ENABLE_ACTIVE_HIGH) || ((DataEnable) == DSI_DATA_ENABLE_ACTIVE_LOW)) -#define IS_DSI_VSYNC_POLARITY(VSYNC) (((VSYNC) == DSI_VSYNC_ACTIVE_HIGH) || ((VSYNC) == DSI_VSYNC_ACTIVE_LOW)) -#define IS_DSI_HSYNC_POLARITY(HSYNC) (((HSYNC) == DSI_HSYNC_ACTIVE_HIGH) || ((HSYNC) == DSI_HSYNC_ACTIVE_LOW)) -#define IS_DSI_VIDEO_MODE_TYPE(VideoModeType) (((VideoModeType) == DSI_VID_MODE_NB_PULSES) || \ - ((VideoModeType) == DSI_VID_MODE_NB_EVENTS) || \ - ((VideoModeType) == DSI_VID_MODE_BURST)) -#define IS_DSI_COLOR_MODE(ColorMode) (((ColorMode) == DSI_COLOR_MODE_FULL) || ((ColorMode) == DSI_COLOR_MODE_EIGHT)) -#define IS_DSI_SHUT_DOWN(ShutDown) (((ShutDown) == DSI_DISPLAY_ON) || ((ShutDown) == DSI_DISPLAY_OFF)) -#define IS_DSI_LP_COMMAND(LPCommand) (((LPCommand) == DSI_LP_COMMAND_DISABLE) || ((LPCommand) == DSI_LP_COMMAND_ENABLE)) -#define IS_DSI_LP_HFP(LPHFP) (((LPHFP) == DSI_LP_HFP_DISABLE) || ((LPHFP) == DSI_LP_HFP_ENABLE)) -#define IS_DSI_LP_HBP(LPHBP) (((LPHBP) == DSI_LP_HBP_DISABLE) || ((LPHBP) == DSI_LP_HBP_ENABLE)) -#define IS_DSI_LP_VACTIVE(LPVActive) (((LPVActive) == DSI_LP_VACT_DISABLE) || ((LPVActive) == DSI_LP_VACT_ENABLE)) -#define IS_DSI_LP_VFP(LPVFP) (((LPVFP) == DSI_LP_VFP_DISABLE) || ((LPVFP) == DSI_LP_VFP_ENABLE)) -#define IS_DSI_LP_VBP(LPVBP) (((LPVBP) == DSI_LP_VBP_DISABLE) || ((LPVBP) == DSI_LP_VBP_ENABLE)) -#define IS_DSI_LP_VSYNC(LPVSYNC) (((LPVSYNC) == DSI_LP_VSYNC_DISABLE) || ((LPVSYNC) == DSI_LP_VSYNC_ENABLE)) -#define IS_DSI_FBTAA(FrameBTAAcknowledge) (((FrameBTAAcknowledge) == DSI_FBTAA_DISABLE) || ((FrameBTAAcknowledge) == DSI_FBTAA_ENABLE)) -#define IS_DSI_TE_SOURCE(TESource) (((TESource) == DSI_TE_DSILINK) || ((TESource) == DSI_TE_EXTERNAL)) -#define IS_DSI_TE_POLARITY(TEPolarity) (((TEPolarity) == DSI_TE_RISING_EDGE) || ((TEPolarity) == DSI_TE_FALLING_EDGE)) -#define IS_DSI_AUTOMATIC_REFRESH(AutomaticRefresh) (((AutomaticRefresh) == DSI_AR_DISABLE) || ((AutomaticRefresh) == DSI_AR_ENABLE)) -#define IS_DSI_VS_POLARITY(VSPolarity) (((VSPolarity) == DSI_VSYNC_FALLING) || ((VSPolarity) == DSI_VSYNC_RISING)) -#define IS_DSI_TE_ACK_REQUEST(TEAcknowledgeRequest) (((TEAcknowledgeRequest) == DSI_TE_ACKNOWLEDGE_DISABLE) || ((TEAcknowledgeRequest) == DSI_TE_ACKNOWLEDGE_ENABLE)) -#define IS_DSI_ACK_REQUEST(AcknowledgeRequest) (((AcknowledgeRequest) == DSI_ACKNOWLEDGE_DISABLE) || ((AcknowledgeRequest) == DSI_ACKNOWLEDGE_ENABLE)) -#define IS_DSI_LP_GSW0P(LP_GSW0P) (((LP_GSW0P) == DSI_LP_GSW0P_DISABLE) || ((LP_GSW0P) == DSI_LP_GSW0P_ENABLE)) -#define IS_DSI_LP_GSW1P(LP_GSW1P) (((LP_GSW1P) == DSI_LP_GSW1P_DISABLE) || ((LP_GSW1P) == DSI_LP_GSW1P_ENABLE)) -#define IS_DSI_LP_GSW2P(LP_GSW2P) (((LP_GSW2P) == DSI_LP_GSW2P_DISABLE) || ((LP_GSW2P) == DSI_LP_GSW2P_ENABLE)) -#define IS_DSI_LP_GSR0P(LP_GSR0P) (((LP_GSR0P) == DSI_LP_GSR0P_DISABLE) || ((LP_GSR0P) == DSI_LP_GSR0P_ENABLE)) -#define IS_DSI_LP_GSR1P(LP_GSR1P) (((LP_GSR1P) == DSI_LP_GSR1P_DISABLE) || ((LP_GSR1P) == DSI_LP_GSR1P_ENABLE)) -#define IS_DSI_LP_GSR2P(LP_GSR2P) (((LP_GSR2P) == DSI_LP_GSR2P_DISABLE) || ((LP_GSR2P) == DSI_LP_GSR2P_ENABLE)) -#define IS_DSI_LP_GLW(LP_GLW) (((LP_GLW) == DSI_LP_GLW_DISABLE) || ((LP_GLW) == DSI_LP_GLW_ENABLE)) -#define IS_DSI_LP_DSW0P(LP_DSW0P) (((LP_DSW0P) == DSI_LP_DSW0P_DISABLE) || ((LP_DSW0P) == DSI_LP_DSW0P_ENABLE)) -#define IS_DSI_LP_DSW1P(LP_DSW1P) (((LP_DSW1P) == DSI_LP_DSW1P_DISABLE) || ((LP_DSW1P) == DSI_LP_DSW1P_ENABLE)) -#define IS_DSI_LP_DSR0P(LP_DSR0P) (((LP_DSR0P) == DSI_LP_DSR0P_DISABLE) || ((LP_DSR0P) == DSI_LP_DSR0P_ENABLE)) -#define IS_DSI_LP_DLW(LP_DLW) (((LP_DLW) == DSI_LP_DLW_DISABLE) || ((LP_DLW) == DSI_LP_DLW_ENABLE)) -#define IS_DSI_LP_MRDP(LP_MRDP) (((LP_MRDP) == DSI_LP_MRDP_DISABLE) || ((LP_MRDP) == DSI_LP_MRDP_ENABLE)) -#define IS_DSI_SHORT_WRITE_PACKET_TYPE(MODE) (((MODE) == DSI_DCS_SHORT_PKT_WRITE_P0) || \ - ((MODE) == DSI_DCS_SHORT_PKT_WRITE_P1) || \ - ((MODE) == DSI_GEN_SHORT_PKT_WRITE_P0) || \ - ((MODE) == DSI_GEN_SHORT_PKT_WRITE_P1) || \ - ((MODE) == DSI_GEN_SHORT_PKT_WRITE_P2)) -#define IS_DSI_LONG_WRITE_PACKET_TYPE(MODE) (((MODE) == DSI_DCS_LONG_PKT_WRITE) || \ - ((MODE) == DSI_GEN_LONG_PKT_WRITE)) -#define IS_DSI_READ_PACKET_TYPE(MODE) (((MODE) == DSI_DCS_SHORT_PKT_READ) || \ - ((MODE) == DSI_GEN_SHORT_PKT_READ_P0) || \ - ((MODE) == DSI_GEN_SHORT_PKT_READ_P1) || \ - ((MODE) == DSI_GEN_SHORT_PKT_READ_P2)) -#define IS_DSI_COMMUNICATION_DELAY(CommDelay) (((CommDelay) == DSI_SLEW_RATE_HSTX) || ((CommDelay) == DSI_SLEW_RATE_LPTX) || ((CommDelay) == DSI_HS_DELAY)) -#define IS_DSI_LANE_GROUP(Lane) (((Lane) == DSI_CLOCK_LANE) || ((Lane) == DSI_DATA_LANES)) -#define IS_DSI_CUSTOM_LANE(CustomLane) (((CustomLane) == DSI_SWAP_LANE_PINS) || ((CustomLane) == DSI_INVERT_HS_SIGNAL)) -#define IS_DSI_LANE(Lane) (((Lane) == DSI_CLOCK_LANE) || ((Lane) == DSI_DATA_LANE0) || ((Lane) == DSI_DATA_LANE1)) -#define IS_DSI_PHY_TIMING(Timing) (((Timing) == DSI_TCLK_POST ) || \ - ((Timing) == DSI_TLPX_CLK ) || \ - ((Timing) == DSI_THS_EXIT ) || \ - ((Timing) == DSI_TLPX_DATA ) || \ - ((Timing) == DSI_THS_ZERO ) || \ - ((Timing) == DSI_THS_TRAIL ) || \ - ((Timing) == DSI_THS_PREPARE ) || \ - ((Timing) == DSI_TCLK_ZERO ) || \ - ((Timing) == DSI_TCLK_PREPARE)) - -/** - * @} - */ - -/* Private functions prototypes ----------------------------------------------*/ -/** @defgroup DSI_Private_Functions_Prototypes DSI Private Functions Prototypes - * @{ - */ - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup DSI_Private_Functions DSI Private Functions - * @{ - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ -#endif /* DSI */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_HAL_DSI_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_eth.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_eth.h deleted file mode 100644 index a0b0ad3..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_eth.h +++ /dev/null @@ -1,2213 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_eth.h - * @author MCD Application Team - * @brief Header file of ETH HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_ETH_H -#define __STM32F4xx_HAL_ETH_H - -#ifdef __cplusplus - extern "C" { -#endif - -#if defined(STM32F407xx) || defined(STM32F417xx) || defined(STM32F427xx) || defined(STM32F437xx) ||\ - defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup ETH - * @{ - */ - -/** @addtogroup ETH_Private_Macros - * @{ - */ -#define IS_ETH_PHY_ADDRESS(ADDRESS) ((ADDRESS) <= 0x20U) -#define IS_ETH_AUTONEGOTIATION(CMD) (((CMD) == ETH_AUTONEGOTIATION_ENABLE) || \ - ((CMD) == ETH_AUTONEGOTIATION_DISABLE)) -#define IS_ETH_SPEED(SPEED) (((SPEED) == ETH_SPEED_10M) || \ - ((SPEED) == ETH_SPEED_100M)) -#define IS_ETH_DUPLEX_MODE(MODE) (((MODE) == ETH_MODE_FULLDUPLEX) || \ - ((MODE) == ETH_MODE_HALFDUPLEX)) -#define IS_ETH_RX_MODE(MODE) (((MODE) == ETH_RXPOLLING_MODE) || \ - ((MODE) == ETH_RXINTERRUPT_MODE)) -#define IS_ETH_CHECKSUM_MODE(MODE) (((MODE) == ETH_CHECKSUM_BY_HARDWARE) || \ - ((MODE) == ETH_CHECKSUM_BY_SOFTWARE)) -#define IS_ETH_MEDIA_INTERFACE(MODE) (((MODE) == ETH_MEDIA_INTERFACE_MII) || \ - ((MODE) == ETH_MEDIA_INTERFACE_RMII)) -#define IS_ETH_WATCHDOG(CMD) (((CMD) == ETH_WATCHDOG_ENABLE) || \ - ((CMD) == ETH_WATCHDOG_DISABLE)) -#define IS_ETH_JABBER(CMD) (((CMD) == ETH_JABBER_ENABLE) || \ - ((CMD) == ETH_JABBER_DISABLE)) -#define IS_ETH_INTER_FRAME_GAP(GAP) (((GAP) == ETH_INTERFRAMEGAP_96BIT) || \ - ((GAP) == ETH_INTERFRAMEGAP_88BIT) || \ - ((GAP) == ETH_INTERFRAMEGAP_80BIT) || \ - ((GAP) == ETH_INTERFRAMEGAP_72BIT) || \ - ((GAP) == ETH_INTERFRAMEGAP_64BIT) || \ - ((GAP) == ETH_INTERFRAMEGAP_56BIT) || \ - ((GAP) == ETH_INTERFRAMEGAP_48BIT) || \ - ((GAP) == ETH_INTERFRAMEGAP_40BIT)) -#define IS_ETH_CARRIER_SENSE(CMD) (((CMD) == ETH_CARRIERSENCE_ENABLE) || \ - ((CMD) == ETH_CARRIERSENCE_DISABLE)) -#define IS_ETH_RECEIVE_OWN(CMD) (((CMD) == ETH_RECEIVEOWN_ENABLE) || \ - ((CMD) == ETH_RECEIVEOWN_DISABLE)) -#define IS_ETH_LOOPBACK_MODE(CMD) (((CMD) == ETH_LOOPBACKMODE_ENABLE) || \ - ((CMD) == ETH_LOOPBACKMODE_DISABLE)) -#define IS_ETH_CHECKSUM_OFFLOAD(CMD) (((CMD) == ETH_CHECKSUMOFFLAOD_ENABLE) || \ - ((CMD) == ETH_CHECKSUMOFFLAOD_DISABLE)) -#define IS_ETH_RETRY_TRANSMISSION(CMD) (((CMD) == ETH_RETRYTRANSMISSION_ENABLE) || \ - ((CMD) == ETH_RETRYTRANSMISSION_DISABLE)) -#define IS_ETH_AUTOMATIC_PADCRC_STRIP(CMD) (((CMD) == ETH_AUTOMATICPADCRCSTRIP_ENABLE) || \ - ((CMD) == ETH_AUTOMATICPADCRCSTRIP_DISABLE)) -#define IS_ETH_BACKOFF_LIMIT(LIMIT) (((LIMIT) == ETH_BACKOFFLIMIT_10) || \ - ((LIMIT) == ETH_BACKOFFLIMIT_8) || \ - ((LIMIT) == ETH_BACKOFFLIMIT_4) || \ - ((LIMIT) == ETH_BACKOFFLIMIT_1)) -#define IS_ETH_DEFERRAL_CHECK(CMD) (((CMD) == ETH_DEFFERRALCHECK_ENABLE) || \ - ((CMD) == ETH_DEFFERRALCHECK_DISABLE)) -#define IS_ETH_RECEIVE_ALL(CMD) (((CMD) == ETH_RECEIVEALL_ENABLE) || \ - ((CMD) == ETH_RECEIVEAll_DISABLE)) -#define IS_ETH_SOURCE_ADDR_FILTER(CMD) (((CMD) == ETH_SOURCEADDRFILTER_NORMAL_ENABLE) || \ - ((CMD) == ETH_SOURCEADDRFILTER_INVERSE_ENABLE) || \ - ((CMD) == ETH_SOURCEADDRFILTER_DISABLE)) -#define IS_ETH_CONTROL_FRAMES(PASS) (((PASS) == ETH_PASSCONTROLFRAMES_BLOCKALL) || \ - ((PASS) == ETH_PASSCONTROLFRAMES_FORWARDALL) || \ - ((PASS) == ETH_PASSCONTROLFRAMES_FORWARDPASSEDADDRFILTER)) -#define IS_ETH_BROADCAST_FRAMES_RECEPTION(CMD) (((CMD) == ETH_BROADCASTFRAMESRECEPTION_ENABLE) || \ - ((CMD) == ETH_BROADCASTFRAMESRECEPTION_DISABLE)) -#define IS_ETH_DESTINATION_ADDR_FILTER(FILTER) (((FILTER) == ETH_DESTINATIONADDRFILTER_NORMAL) || \ - ((FILTER) == ETH_DESTINATIONADDRFILTER_INVERSE)) -#define IS_ETH_PROMISCUOUS_MODE(CMD) (((CMD) == ETH_PROMISCUOUS_MODE_ENABLE) || \ - ((CMD) == ETH_PROMISCUOUS_MODE_DISABLE)) -#define IS_ETH_MULTICAST_FRAMES_FILTER(FILTER) (((FILTER) == ETH_MULTICASTFRAMESFILTER_PERFECTHASHTABLE) || \ - ((FILTER) == ETH_MULTICASTFRAMESFILTER_HASHTABLE) || \ - ((FILTER) == ETH_MULTICASTFRAMESFILTER_PERFECT) || \ - ((FILTER) == ETH_MULTICASTFRAMESFILTER_NONE)) -#define IS_ETH_UNICAST_FRAMES_FILTER(FILTER) (((FILTER) == ETH_UNICASTFRAMESFILTER_PERFECTHASHTABLE) || \ - ((FILTER) == ETH_UNICASTFRAMESFILTER_HASHTABLE) || \ - ((FILTER) == ETH_UNICASTFRAMESFILTER_PERFECT)) -#define IS_ETH_PAUSE_TIME(TIME) ((TIME) <= 0xFFFFU) -#define IS_ETH_ZEROQUANTA_PAUSE(CMD) (((CMD) == ETH_ZEROQUANTAPAUSE_ENABLE) || \ - ((CMD) == ETH_ZEROQUANTAPAUSE_DISABLE)) -#define IS_ETH_PAUSE_LOW_THRESHOLD(THRESHOLD) (((THRESHOLD) == ETH_PAUSELOWTHRESHOLD_MINUS4) || \ - ((THRESHOLD) == ETH_PAUSELOWTHRESHOLD_MINUS28) || \ - ((THRESHOLD) == ETH_PAUSELOWTHRESHOLD_MINUS144) || \ - ((THRESHOLD) == ETH_PAUSELOWTHRESHOLD_MINUS256)) -#define IS_ETH_UNICAST_PAUSE_FRAME_DETECT(CMD) (((CMD) == ETH_UNICASTPAUSEFRAMEDETECT_ENABLE) || \ - ((CMD) == ETH_UNICASTPAUSEFRAMEDETECT_DISABLE)) -#define IS_ETH_RECEIVE_FLOWCONTROL(CMD) (((CMD) == ETH_RECEIVEFLOWCONTROL_ENABLE) || \ - ((CMD) == ETH_RECEIVEFLOWCONTROL_DISABLE)) -#define IS_ETH_TRANSMIT_FLOWCONTROL(CMD) (((CMD) == ETH_TRANSMITFLOWCONTROL_ENABLE) || \ - ((CMD) == ETH_TRANSMITFLOWCONTROL_DISABLE)) -#define IS_ETH_VLAN_TAG_COMPARISON(COMPARISON) (((COMPARISON) == ETH_VLANTAGCOMPARISON_12BIT) || \ - ((COMPARISON) == ETH_VLANTAGCOMPARISON_16BIT)) -#define IS_ETH_VLAN_TAG_IDENTIFIER(IDENTIFIER) ((IDENTIFIER) <= 0xFFFFU) -#define IS_ETH_MAC_ADDRESS0123(ADDRESS) (((ADDRESS) == ETH_MAC_ADDRESS0) || \ - ((ADDRESS) == ETH_MAC_ADDRESS1) || \ - ((ADDRESS) == ETH_MAC_ADDRESS2) || \ - ((ADDRESS) == ETH_MAC_ADDRESS3)) -#define IS_ETH_MAC_ADDRESS123(ADDRESS) (((ADDRESS) == ETH_MAC_ADDRESS1) || \ - ((ADDRESS) == ETH_MAC_ADDRESS2) || \ - ((ADDRESS) == ETH_MAC_ADDRESS3)) -#define IS_ETH_MAC_ADDRESS_FILTER(FILTER) (((FILTER) == ETH_MAC_ADDRESSFILTER_SA) || \ - ((FILTER) == ETH_MAC_ADDRESSFILTER_DA)) -#define IS_ETH_MAC_ADDRESS_MASK(MASK) (((MASK) == ETH_MAC_ADDRESSMASK_BYTE6) || \ - ((MASK) == ETH_MAC_ADDRESSMASK_BYTE5) || \ - ((MASK) == ETH_MAC_ADDRESSMASK_BYTE4) || \ - ((MASK) == ETH_MAC_ADDRESSMASK_BYTE3) || \ - ((MASK) == ETH_MAC_ADDRESSMASK_BYTE2) || \ - ((MASK) == ETH_MAC_ADDRESSMASK_BYTE1)) -#define IS_ETH_DROP_TCPIP_CHECKSUM_FRAME(CMD) (((CMD) == ETH_DROPTCPIPCHECKSUMERRORFRAME_ENABLE) || \ - ((CMD) == ETH_DROPTCPIPCHECKSUMERRORFRAME_DISABLE)) -#define IS_ETH_RECEIVE_STORE_FORWARD(CMD) (((CMD) == ETH_RECEIVESTOREFORWARD_ENABLE) || \ - ((CMD) == ETH_RECEIVESTOREFORWARD_DISABLE)) -#define IS_ETH_FLUSH_RECEIVE_FRAME(CMD) (((CMD) == ETH_FLUSHRECEIVEDFRAME_ENABLE) || \ - ((CMD) == ETH_FLUSHRECEIVEDFRAME_DISABLE)) -#define IS_ETH_TRANSMIT_STORE_FORWARD(CMD) (((CMD) == ETH_TRANSMITSTOREFORWARD_ENABLE) || \ - ((CMD) == ETH_TRANSMITSTOREFORWARD_DISABLE)) -#define IS_ETH_TRANSMIT_THRESHOLD_CONTROL(THRESHOLD) (((THRESHOLD) == ETH_TRANSMITTHRESHOLDCONTROL_64BYTES) || \ - ((THRESHOLD) == ETH_TRANSMITTHRESHOLDCONTROL_128BYTES) || \ - ((THRESHOLD) == ETH_TRANSMITTHRESHOLDCONTROL_192BYTES) || \ - ((THRESHOLD) == ETH_TRANSMITTHRESHOLDCONTROL_256BYTES) || \ - ((THRESHOLD) == ETH_TRANSMITTHRESHOLDCONTROL_40BYTES) || \ - ((THRESHOLD) == ETH_TRANSMITTHRESHOLDCONTROL_32BYTES) || \ - ((THRESHOLD) == ETH_TRANSMITTHRESHOLDCONTROL_24BYTES) || \ - ((THRESHOLD) == ETH_TRANSMITTHRESHOLDCONTROL_16BYTES)) -#define IS_ETH_FORWARD_ERROR_FRAMES(CMD) (((CMD) == ETH_FORWARDERRORFRAMES_ENABLE) || \ - ((CMD) == ETH_FORWARDERRORFRAMES_DISABLE)) -#define IS_ETH_FORWARD_UNDERSIZED_GOOD_FRAMES(CMD) (((CMD) == ETH_FORWARDUNDERSIZEDGOODFRAMES_ENABLE) || \ - ((CMD) == ETH_FORWARDUNDERSIZEDGOODFRAMES_DISABLE)) -#define IS_ETH_RECEIVE_THRESHOLD_CONTROL(THRESHOLD) (((THRESHOLD) == ETH_RECEIVEDTHRESHOLDCONTROL_64BYTES) || \ - ((THRESHOLD) == ETH_RECEIVEDTHRESHOLDCONTROL_32BYTES) || \ - ((THRESHOLD) == ETH_RECEIVEDTHRESHOLDCONTROL_96BYTES) || \ - ((THRESHOLD) == ETH_RECEIVEDTHRESHOLDCONTROL_128BYTES)) -#define IS_ETH_SECOND_FRAME_OPERATE(CMD) (((CMD) == ETH_SECONDFRAMEOPERARTE_ENABLE) || \ - ((CMD) == ETH_SECONDFRAMEOPERARTE_DISABLE)) -#define IS_ETH_ADDRESS_ALIGNED_BEATS(CMD) (((CMD) == ETH_ADDRESSALIGNEDBEATS_ENABLE) || \ - ((CMD) == ETH_ADDRESSALIGNEDBEATS_DISABLE)) -#define IS_ETH_FIXED_BURST(CMD) (((CMD) == ETH_FIXEDBURST_ENABLE) || \ - ((CMD) == ETH_FIXEDBURST_DISABLE)) -#define IS_ETH_RXDMA_BURST_LENGTH(LENGTH) (((LENGTH) == ETH_RXDMABURSTLENGTH_1BEAT) || \ - ((LENGTH) == ETH_RXDMABURSTLENGTH_2BEAT) || \ - ((LENGTH) == ETH_RXDMABURSTLENGTH_4BEAT) || \ - ((LENGTH) == ETH_RXDMABURSTLENGTH_8BEAT) || \ - ((LENGTH) == ETH_RXDMABURSTLENGTH_16BEAT) || \ - ((LENGTH) == ETH_RXDMABURSTLENGTH_32BEAT) || \ - ((LENGTH) == ETH_RXDMABURSTLENGTH_4XPBL_4BEAT) || \ - ((LENGTH) == ETH_RXDMABURSTLENGTH_4XPBL_8BEAT) || \ - ((LENGTH) == ETH_RXDMABURSTLENGTH_4XPBL_16BEAT) || \ - ((LENGTH) == ETH_RXDMABURSTLENGTH_4XPBL_32BEAT) || \ - ((LENGTH) == ETH_RXDMABURSTLENGTH_4XPBL_64BEAT) || \ - ((LENGTH) == ETH_RXDMABURSTLENGTH_4XPBL_128BEAT)) -#define IS_ETH_TXDMA_BURST_LENGTH(LENGTH) (((LENGTH) == ETH_TXDMABURSTLENGTH_1BEAT) || \ - ((LENGTH) == ETH_TXDMABURSTLENGTH_2BEAT) || \ - ((LENGTH) == ETH_TXDMABURSTLENGTH_4BEAT) || \ - ((LENGTH) == ETH_TXDMABURSTLENGTH_8BEAT) || \ - ((LENGTH) == ETH_TXDMABURSTLENGTH_16BEAT) || \ - ((LENGTH) == ETH_TXDMABURSTLENGTH_32BEAT) || \ - ((LENGTH) == ETH_TXDMABURSTLENGTH_4XPBL_4BEAT) || \ - ((LENGTH) == ETH_TXDMABURSTLENGTH_4XPBL_8BEAT) || \ - ((LENGTH) == ETH_TXDMABURSTLENGTH_4XPBL_16BEAT) || \ - ((LENGTH) == ETH_TXDMABURSTLENGTH_4XPBL_32BEAT) || \ - ((LENGTH) == ETH_TXDMABURSTLENGTH_4XPBL_64BEAT) || \ - ((LENGTH) == ETH_TXDMABURSTLENGTH_4XPBL_128BEAT)) -#define IS_ETH_DMA_DESC_SKIP_LENGTH(LENGTH) ((LENGTH) <= 0x1FU) -#define IS_ETH_DMA_ARBITRATION_ROUNDROBIN_RXTX(RATIO) (((RATIO) == ETH_DMAARBITRATION_ROUNDROBIN_RXTX_1_1) || \ - ((RATIO) == ETH_DMAARBITRATION_ROUNDROBIN_RXTX_2_1) || \ - ((RATIO) == ETH_DMAARBITRATION_ROUNDROBIN_RXTX_3_1) || \ - ((RATIO) == ETH_DMAARBITRATION_ROUNDROBIN_RXTX_4_1) || \ - ((RATIO) == ETH_DMAARBITRATION_RXPRIORTX)) -#define IS_ETH_DMATXDESC_GET_FLAG(FLAG) (((FLAG) == ETH_DMATXDESC_OWN) || \ - ((FLAG) == ETH_DMATXDESC_IC) || \ - ((FLAG) == ETH_DMATXDESC_LS) || \ - ((FLAG) == ETH_DMATXDESC_FS) || \ - ((FLAG) == ETH_DMATXDESC_DC) || \ - ((FLAG) == ETH_DMATXDESC_DP) || \ - ((FLAG) == ETH_DMATXDESC_TTSE) || \ - ((FLAG) == ETH_DMATXDESC_TER) || \ - ((FLAG) == ETH_DMATXDESC_TCH) || \ - ((FLAG) == ETH_DMATXDESC_TTSS) || \ - ((FLAG) == ETH_DMATXDESC_IHE) || \ - ((FLAG) == ETH_DMATXDESC_ES) || \ - ((FLAG) == ETH_DMATXDESC_JT) || \ - ((FLAG) == ETH_DMATXDESC_FF) || \ - ((FLAG) == ETH_DMATXDESC_PCE) || \ - ((FLAG) == ETH_DMATXDESC_LCA) || \ - ((FLAG) == ETH_DMATXDESC_NC) || \ - ((FLAG) == ETH_DMATXDESC_LCO) || \ - ((FLAG) == ETH_DMATXDESC_EC) || \ - ((FLAG) == ETH_DMATXDESC_VF) || \ - ((FLAG) == ETH_DMATXDESC_CC) || \ - ((FLAG) == ETH_DMATXDESC_ED) || \ - ((FLAG) == ETH_DMATXDESC_UF) || \ - ((FLAG) == ETH_DMATXDESC_DB)) -#define IS_ETH_DMA_TXDESC_SEGMENT(SEGMENT) (((SEGMENT) == ETH_DMATXDESC_LASTSEGMENTS) || \ - ((SEGMENT) == ETH_DMATXDESC_FIRSTSEGMENT)) -#define IS_ETH_DMA_TXDESC_CHECKSUM(CHECKSUM) (((CHECKSUM) == ETH_DMATXDESC_CHECKSUMBYPASS) || \ - ((CHECKSUM) == ETH_DMATXDESC_CHECKSUMIPV4HEADER) || \ - ((CHECKSUM) == ETH_DMATXDESC_CHECKSUMTCPUDPICMPSEGMENT) || \ - ((CHECKSUM) == ETH_DMATXDESC_CHECKSUMTCPUDPICMPFULL)) -#define IS_ETH_DMATXDESC_BUFFER_SIZE(SIZE) ((SIZE) <= 0x1FFFU) -#define IS_ETH_DMARXDESC_GET_FLAG(FLAG) (((FLAG) == ETH_DMARXDESC_OWN) || \ - ((FLAG) == ETH_DMARXDESC_AFM) || \ - ((FLAG) == ETH_DMARXDESC_ES) || \ - ((FLAG) == ETH_DMARXDESC_DE) || \ - ((FLAG) == ETH_DMARXDESC_SAF) || \ - ((FLAG) == ETH_DMARXDESC_LE) || \ - ((FLAG) == ETH_DMARXDESC_OE) || \ - ((FLAG) == ETH_DMARXDESC_VLAN) || \ - ((FLAG) == ETH_DMARXDESC_FS) || \ - ((FLAG) == ETH_DMARXDESC_LS) || \ - ((FLAG) == ETH_DMARXDESC_IPV4HCE) || \ - ((FLAG) == ETH_DMARXDESC_LC) || \ - ((FLAG) == ETH_DMARXDESC_FT) || \ - ((FLAG) == ETH_DMARXDESC_RWT) || \ - ((FLAG) == ETH_DMARXDESC_RE) || \ - ((FLAG) == ETH_DMARXDESC_DBE) || \ - ((FLAG) == ETH_DMARXDESC_CE) || \ - ((FLAG) == ETH_DMARXDESC_MAMPCE)) -#define IS_ETH_DMA_RXDESC_BUFFER(BUFFER) (((BUFFER) == ETH_DMARXDESC_BUFFER1) || \ - ((BUFFER) == ETH_DMARXDESC_BUFFER2)) -#define IS_ETH_PMT_GET_FLAG(FLAG) (((FLAG) == ETH_PMT_FLAG_WUFR) || \ - ((FLAG) == ETH_PMT_FLAG_MPR)) -#define IS_ETH_DMA_FLAG(FLAG) ((((FLAG) & 0xC7FE1800U) == 0x00U) && ((FLAG) != 0x00U)) -#define IS_ETH_DMA_GET_FLAG(FLAG) (((FLAG) == ETH_DMA_FLAG_TST) || ((FLAG) == ETH_DMA_FLAG_PMT) || \ - ((FLAG) == ETH_DMA_FLAG_MMC) || ((FLAG) == ETH_DMA_FLAG_DATATRANSFERERROR) || \ - ((FLAG) == ETH_DMA_FLAG_READWRITEERROR) || ((FLAG) == ETH_DMA_FLAG_ACCESSERROR) || \ - ((FLAG) == ETH_DMA_FLAG_NIS) || ((FLAG) == ETH_DMA_FLAG_AIS) || \ - ((FLAG) == ETH_DMA_FLAG_ER) || ((FLAG) == ETH_DMA_FLAG_FBE) || \ - ((FLAG) == ETH_DMA_FLAG_ET) || ((FLAG) == ETH_DMA_FLAG_RWT) || \ - ((FLAG) == ETH_DMA_FLAG_RPS) || ((FLAG) == ETH_DMA_FLAG_RBU) || \ - ((FLAG) == ETH_DMA_FLAG_R) || ((FLAG) == ETH_DMA_FLAG_TU) || \ - ((FLAG) == ETH_DMA_FLAG_RO) || ((FLAG) == ETH_DMA_FLAG_TJT) || \ - ((FLAG) == ETH_DMA_FLAG_TBU) || ((FLAG) == ETH_DMA_FLAG_TPS) || \ - ((FLAG) == ETH_DMA_FLAG_T)) -#define IS_ETH_MAC_IT(IT) ((((IT) & 0xFFFFFDF1U) == 0x00U) && ((IT) != 0x00U)) -#define IS_ETH_MAC_GET_IT(IT) (((IT) == ETH_MAC_IT_TST) || ((IT) == ETH_MAC_IT_MMCT) || \ - ((IT) == ETH_MAC_IT_MMCR) || ((IT) == ETH_MAC_IT_MMC) || \ - ((IT) == ETH_MAC_IT_PMT)) -#define IS_ETH_MAC_GET_FLAG(FLAG) (((FLAG) == ETH_MAC_FLAG_TST) || ((FLAG) == ETH_MAC_FLAG_MMCT) || \ - ((FLAG) == ETH_MAC_FLAG_MMCR) || ((FLAG) == ETH_MAC_FLAG_MMC) || \ - ((FLAG) == ETH_MAC_FLAG_PMT)) -#define IS_ETH_DMA_IT(IT) ((((IT) & 0xC7FE1800U) == 0x00U) && ((IT) != 0x00U)) -#define IS_ETH_DMA_GET_IT(IT) (((IT) == ETH_DMA_IT_TST) || ((IT) == ETH_DMA_IT_PMT) || \ - ((IT) == ETH_DMA_IT_MMC) || ((IT) == ETH_DMA_IT_NIS) || \ - ((IT) == ETH_DMA_IT_AIS) || ((IT) == ETH_DMA_IT_ER) || \ - ((IT) == ETH_DMA_IT_FBE) || ((IT) == ETH_DMA_IT_ET) || \ - ((IT) == ETH_DMA_IT_RWT) || ((IT) == ETH_DMA_IT_RPS) || \ - ((IT) == ETH_DMA_IT_RBU) || ((IT) == ETH_DMA_IT_R) || \ - ((IT) == ETH_DMA_IT_TU) || ((IT) == ETH_DMA_IT_RO) || \ - ((IT) == ETH_DMA_IT_TJT) || ((IT) == ETH_DMA_IT_TBU) || \ - ((IT) == ETH_DMA_IT_TPS) || ((IT) == ETH_DMA_IT_T)) -#define IS_ETH_DMA_GET_OVERFLOW(OVERFLOW) (((OVERFLOW) == ETH_DMA_OVERFLOW_RXFIFOCOUNTER) || \ - ((OVERFLOW) == ETH_DMA_OVERFLOW_MISSEDFRAMECOUNTER)) -#define IS_ETH_MMC_IT(IT) (((((IT) & 0xFFDF3FFFU) == 0x00U) || (((IT) & 0xEFFDFF9FU) == 0x00U)) && \ - ((IT) != 0x00U)) -#define IS_ETH_MMC_GET_IT(IT) (((IT) == ETH_MMC_IT_TGF) || ((IT) == ETH_MMC_IT_TGFMSC) || \ - ((IT) == ETH_MMC_IT_TGFSC) || ((IT) == ETH_MMC_IT_RGUF) || \ - ((IT) == ETH_MMC_IT_RFAE) || ((IT) == ETH_MMC_IT_RFCE)) -#define IS_ETH_ENHANCED_DESCRIPTOR_FORMAT(CMD) (((CMD) == ETH_DMAENHANCEDDESCRIPTOR_ENABLE) || \ - ((CMD) == ETH_DMAENHANCEDDESCRIPTOR_DISABLE)) - -/** - * @} - */ - -/** @addtogroup ETH_Private_Defines - * @{ - */ -/* Delay to wait when writing to some Ethernet registers */ -#define ETH_REG_WRITE_DELAY 0x00000001U - -/* ETHERNET Errors */ -#define ETH_SUCCESS 0U -#define ETH_ERROR 1U - -/* ETHERNET DMA Tx descriptors Collision Count Shift */ -#define ETH_DMATXDESC_COLLISION_COUNTSHIFT 3U - -/* ETHERNET DMA Tx descriptors Buffer2 Size Shift */ -#define ETH_DMATXDESC_BUFFER2_SIZESHIFT 16U - -/* ETHERNET DMA Rx descriptors Frame Length Shift */ -#define ETH_DMARXDESC_FRAME_LENGTHSHIFT 16U - -/* ETHERNET DMA Rx descriptors Buffer2 Size Shift */ -#define ETH_DMARXDESC_BUFFER2_SIZESHIFT 16U - -/* ETHERNET DMA Rx descriptors Frame length Shift */ -#define ETH_DMARXDESC_FRAMELENGTHSHIFT 16U - -/* ETHERNET MAC address offsets */ -#define ETH_MAC_ADDR_HBASE (uint32_t)(ETH_MAC_BASE + 0x40U) /* ETHERNET MAC address high offset */ -#define ETH_MAC_ADDR_LBASE (uint32_t)(ETH_MAC_BASE + 0x44U) /* ETHERNET MAC address low offset */ - -/* ETHERNET MACMIIAR register Mask */ -#define ETH_MACMIIAR_CR_MASK 0xFFFFFFE3U - -/* ETHERNET MACCR register Mask */ -#define ETH_MACCR_CLEAR_MASK 0xFF20810FU - -/* ETHERNET MACFCR register Mask */ -#define ETH_MACFCR_CLEAR_MASK 0x0000FF41U - -/* ETHERNET DMAOMR register Mask */ -#define ETH_DMAOMR_CLEAR_MASK 0xF8DE3F23U - -/* ETHERNET Remote Wake-up frame register length */ -#define ETH_WAKEUP_REGISTER_LENGTH 8U - -/* ETHERNET Missed frames counter Shift */ -#define ETH_DMA_RX_OVERFLOW_MISSEDFRAMES_COUNTERSHIFT 17U - /** - * @} - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup ETH_Exported_Types ETH Exported Types - * @{ - */ - -/** - * @brief HAL State structures definition - */ -typedef enum -{ - HAL_ETH_STATE_RESET = 0x00U, /*!< Peripheral not yet Initialized or disabled */ - HAL_ETH_STATE_READY = 0x01U, /*!< Peripheral Initialized and ready for use */ - HAL_ETH_STATE_BUSY = 0x02U, /*!< an internal process is ongoing */ - HAL_ETH_STATE_BUSY_TX = 0x12U, /*!< Data Transmission process is ongoing */ - HAL_ETH_STATE_BUSY_RX = 0x22U, /*!< Data Reception process is ongoing */ - HAL_ETH_STATE_BUSY_TX_RX = 0x32U, /*!< Data Transmission and Reception process is ongoing */ - HAL_ETH_STATE_BUSY_WR = 0x42U, /*!< Write process is ongoing */ - HAL_ETH_STATE_BUSY_RD = 0x82U, /*!< Read process is ongoing */ - HAL_ETH_STATE_TIMEOUT = 0x03U, /*!< Timeout state */ - HAL_ETH_STATE_ERROR = 0x04U /*!< Reception process is ongoing */ -}HAL_ETH_StateTypeDef; - -/** - * @brief ETH Init Structure definition - */ - -typedef struct -{ - uint32_t AutoNegotiation; /*!< Selects or not the AutoNegotiation mode for the external PHY - The AutoNegotiation allows an automatic setting of the Speed (10/100Mbps) - and the mode (half/full-duplex). - This parameter can be a value of @ref ETH_AutoNegotiation */ - - uint32_t Speed; /*!< Sets the Ethernet speed: 10/100 Mbps. - This parameter can be a value of @ref ETH_Speed */ - - uint32_t DuplexMode; /*!< Selects the MAC duplex mode: Half-Duplex or Full-Duplex mode - This parameter can be a value of @ref ETH_Duplex_Mode */ - - uint16_t PhyAddress; /*!< Ethernet PHY address. - This parameter must be a number between Min_Data = 0 and Max_Data = 32 */ - - uint8_t *MACAddr; /*!< MAC Address of used Hardware: must be pointer on an array of 6 bytes */ - - uint32_t RxMode; /*!< Selects the Ethernet Rx mode: Polling mode, Interrupt mode. - This parameter can be a value of @ref ETH_Rx_Mode */ - - uint32_t ChecksumMode; /*!< Selects if the checksum is check by hardware or by software. - This parameter can be a value of @ref ETH_Checksum_Mode */ - - uint32_t MediaInterface; /*!< Selects the media-independent interface or the reduced media-independent interface. - This parameter can be a value of @ref ETH_Media_Interface */ - -} ETH_InitTypeDef; - - - /** - * @brief ETH MAC Configuration Structure definition - */ - -typedef struct -{ - uint32_t Watchdog; /*!< Selects or not the Watchdog timer - When enabled, the MAC allows no more then 2048 bytes to be received. - When disabled, the MAC can receive up to 16384 bytes. - This parameter can be a value of @ref ETH_Watchdog */ - - uint32_t Jabber; /*!< Selects or not Jabber timer - When enabled, the MAC allows no more then 2048 bytes to be sent. - When disabled, the MAC can send up to 16384 bytes. - This parameter can be a value of @ref ETH_Jabber */ - - uint32_t InterFrameGap; /*!< Selects the minimum IFG between frames during transmission. - This parameter can be a value of @ref ETH_Inter_Frame_Gap */ - - uint32_t CarrierSense; /*!< Selects or not the Carrier Sense. - This parameter can be a value of @ref ETH_Carrier_Sense */ - - uint32_t ReceiveOwn; /*!< Selects or not the ReceiveOwn, - ReceiveOwn allows the reception of frames when the TX_EN signal is asserted - in Half-Duplex mode. - This parameter can be a value of @ref ETH_Receive_Own */ - - uint32_t LoopbackMode; /*!< Selects or not the internal MAC MII Loopback mode. - This parameter can be a value of @ref ETH_Loop_Back_Mode */ - - uint32_t ChecksumOffload; /*!< Selects or not the IPv4 checksum checking for received frame payloads' TCP/UDP/ICMP headers. - This parameter can be a value of @ref ETH_Checksum_Offload */ - - uint32_t RetryTransmission; /*!< Selects or not the MAC attempt retries transmission, based on the settings of BL, - when a collision occurs (Half-Duplex mode). - This parameter can be a value of @ref ETH_Retry_Transmission */ - - uint32_t AutomaticPadCRCStrip; /*!< Selects or not the Automatic MAC Pad/CRC Stripping. - This parameter can be a value of @ref ETH_Automatic_Pad_CRC_Strip */ - - uint32_t BackOffLimit; /*!< Selects the BackOff limit value. - This parameter can be a value of @ref ETH_Back_Off_Limit */ - - uint32_t DeferralCheck; /*!< Selects or not the deferral check function (Half-Duplex mode). - This parameter can be a value of @ref ETH_Deferral_Check */ - - uint32_t ReceiveAll; /*!< Selects or not all frames reception by the MAC (No filtering). - This parameter can be a value of @ref ETH_Receive_All */ - - uint32_t SourceAddrFilter; /*!< Selects the Source Address Filter mode. - This parameter can be a value of @ref ETH_Source_Addr_Filter */ - - uint32_t PassControlFrames; /*!< Sets the forwarding mode of the control frames (including unicast and multicast PAUSE frames) - This parameter can be a value of @ref ETH_Pass_Control_Frames */ - - uint32_t BroadcastFramesReception; /*!< Selects or not the reception of Broadcast Frames. - This parameter can be a value of @ref ETH_Broadcast_Frames_Reception */ - - uint32_t DestinationAddrFilter; /*!< Sets the destination filter mode for both unicast and multicast frames. - This parameter can be a value of @ref ETH_Destination_Addr_Filter */ - - uint32_t PromiscuousMode; /*!< Selects or not the Promiscuous Mode - This parameter can be a value of @ref ETH_Promiscuous_Mode */ - - uint32_t MulticastFramesFilter; /*!< Selects the Multicast Frames filter mode: None/HashTableFilter/PerfectFilter/PerfectHashTableFilter. - This parameter can be a value of @ref ETH_Multicast_Frames_Filter */ - - uint32_t UnicastFramesFilter; /*!< Selects the Unicast Frames filter mode: HashTableFilter/PerfectFilter/PerfectHashTableFilter. - This parameter can be a value of @ref ETH_Unicast_Frames_Filter */ - - uint32_t HashTableHigh; /*!< This field holds the higher 32 bits of Hash table. - This parameter must be a number between Min_Data = 0x0 and Max_Data = 0xFFFFFFFFU */ - - uint32_t HashTableLow; /*!< This field holds the lower 32 bits of Hash table. - This parameter must be a number between Min_Data = 0x0 and Max_Data = 0xFFFFFFFFU */ - - uint32_t PauseTime; /*!< This field holds the value to be used in the Pause Time field in the transmit control frame. - This parameter must be a number between Min_Data = 0x0 and Max_Data = 0xFFFFU */ - - uint32_t ZeroQuantaPause; /*!< Selects or not the automatic generation of Zero-Quanta Pause Control frames. - This parameter can be a value of @ref ETH_Zero_Quanta_Pause */ - - uint32_t PauseLowThreshold; /*!< This field configures the threshold of the PAUSE to be checked for - automatic retransmission of PAUSE Frame. - This parameter can be a value of @ref ETH_Pause_Low_Threshold */ - - uint32_t UnicastPauseFrameDetect; /*!< Selects or not the MAC detection of the Pause frames (with MAC Address0 - unicast address and unique multicast address). - This parameter can be a value of @ref ETH_Unicast_Pause_Frame_Detect */ - - uint32_t ReceiveFlowControl; /*!< Enables or disables the MAC to decode the received Pause frame and - disable its transmitter for a specified time (Pause Time) - This parameter can be a value of @ref ETH_Receive_Flow_Control */ - - uint32_t TransmitFlowControl; /*!< Enables or disables the MAC to transmit Pause frames (Full-Duplex mode) - or the MAC back-pressure operation (Half-Duplex mode) - This parameter can be a value of @ref ETH_Transmit_Flow_Control */ - - uint32_t VLANTagComparison; /*!< Selects the 12-bit VLAN identifier or the complete 16-bit VLAN tag for - comparison and filtering. - This parameter can be a value of @ref ETH_VLAN_Tag_Comparison */ - - uint32_t VLANTagIdentifier; /*!< Holds the VLAN tag identifier for receive frames */ - -} ETH_MACInitTypeDef; - -/** - * @brief ETH DMA Configuration Structure definition - */ - -typedef struct -{ - uint32_t DropTCPIPChecksumErrorFrame; /*!< Selects or not the Dropping of TCP/IP Checksum Error Frames. - This parameter can be a value of @ref ETH_Drop_TCP_IP_Checksum_Error_Frame */ - - uint32_t ReceiveStoreForward; /*!< Enables or disables the Receive store and forward mode. - This parameter can be a value of @ref ETH_Receive_Store_Forward */ - - uint32_t FlushReceivedFrame; /*!< Enables or disables the flushing of received frames. - This parameter can be a value of @ref ETH_Flush_Received_Frame */ - - uint32_t TransmitStoreForward; /*!< Enables or disables Transmit store and forward mode. - This parameter can be a value of @ref ETH_Transmit_Store_Forward */ - - uint32_t TransmitThresholdControl; /*!< Selects or not the Transmit Threshold Control. - This parameter can be a value of @ref ETH_Transmit_Threshold_Control */ - - uint32_t ForwardErrorFrames; /*!< Selects or not the forward to the DMA of erroneous frames. - This parameter can be a value of @ref ETH_Forward_Error_Frames */ - - uint32_t ForwardUndersizedGoodFrames; /*!< Enables or disables the Rx FIFO to forward Undersized frames (frames with no Error - and length less than 64 bytes) including pad-bytes and CRC) - This parameter can be a value of @ref ETH_Forward_Undersized_Good_Frames */ - - uint32_t ReceiveThresholdControl; /*!< Selects the threshold level of the Receive FIFO. - This parameter can be a value of @ref ETH_Receive_Threshold_Control */ - - uint32_t SecondFrameOperate; /*!< Selects or not the Operate on second frame mode, which allows the DMA to process a second - frame of Transmit data even before obtaining the status for the first frame. - This parameter can be a value of @ref ETH_Second_Frame_Operate */ - - uint32_t AddressAlignedBeats; /*!< Enables or disables the Address Aligned Beats. - This parameter can be a value of @ref ETH_Address_Aligned_Beats */ - - uint32_t FixedBurst; /*!< Enables or disables the AHB Master interface fixed burst transfers. - This parameter can be a value of @ref ETH_Fixed_Burst */ - - uint32_t RxDMABurstLength; /*!< Indicates the maximum number of beats to be transferred in one Rx DMA transaction. - This parameter can be a value of @ref ETH_Rx_DMA_Burst_Length */ - - uint32_t TxDMABurstLength; /*!< Indicates the maximum number of beats to be transferred in one Tx DMA transaction. - This parameter can be a value of @ref ETH_Tx_DMA_Burst_Length */ - - uint32_t EnhancedDescriptorFormat; /*!< Enables the enhanced descriptor format. - This parameter can be a value of @ref ETH_DMA_Enhanced_descriptor_format */ - - uint32_t DescriptorSkipLength; /*!< Specifies the number of word to skip between two unchained descriptors (Ring mode) - This parameter must be a number between Min_Data = 0 and Max_Data = 32 */ - - uint32_t DMAArbitration; /*!< Selects the DMA Tx/Rx arbitration. - This parameter can be a value of @ref ETH_DMA_Arbitration */ -} ETH_DMAInitTypeDef; - - -/** - * @brief ETH DMA Descriptors data structure definition - */ - -typedef struct -{ - __IO uint32_t Status; /*!< Status */ - - uint32_t ControlBufferSize; /*!< Control and Buffer1, Buffer2 lengths */ - - uint32_t Buffer1Addr; /*!< Buffer1 address pointer */ - - uint32_t Buffer2NextDescAddr; /*!< Buffer2 or next descriptor address pointer */ - - /*!< Enhanced ETHERNET DMA PTP Descriptors */ - uint32_t ExtendedStatus; /*!< Extended status for PTP receive descriptor */ - - uint32_t Reserved1; /*!< Reserved */ - - uint32_t TimeStampLow; /*!< Time Stamp Low value for transmit and receive */ - - uint32_t TimeStampHigh; /*!< Time Stamp High value for transmit and receive */ - -} ETH_DMADescTypeDef; - -/** - * @brief Received Frame Informations structure definition - */ -typedef struct -{ - ETH_DMADescTypeDef *FSRxDesc; /*!< First Segment Rx Desc */ - - ETH_DMADescTypeDef *LSRxDesc; /*!< Last Segment Rx Desc */ - - uint32_t SegCount; /*!< Segment count */ - - uint32_t length; /*!< Frame length */ - - uint32_t buffer; /*!< Frame buffer */ - -} ETH_DMARxFrameInfos; - -/** - * @brief ETH Handle Structure definition - */ - -#if (USE_HAL_ETH_REGISTER_CALLBACKS == 1) -typedef struct __ETH_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_ETH_REGISTER_CALLBACKS */ -{ - ETH_TypeDef *Instance; /*!< Register base address */ - - ETH_InitTypeDef Init; /*!< Ethernet Init Configuration */ - - uint32_t LinkStatus; /*!< Ethernet link status */ - - ETH_DMADescTypeDef *RxDesc; /*!< Rx descriptor to Get */ - - ETH_DMADescTypeDef *TxDesc; /*!< Tx descriptor to Set */ - - ETH_DMARxFrameInfos RxFrameInfos; /*!< last Rx frame infos */ - - __IO HAL_ETH_StateTypeDef State; /*!< ETH communication state */ - - HAL_LockTypeDef Lock; /*!< ETH Lock */ - -#if (USE_HAL_ETH_REGISTER_CALLBACKS == 1) - - void (* TxCpltCallback) ( struct __ETH_HandleTypeDef * heth); /*!< ETH Tx Complete Callback */ - void (* RxCpltCallback) ( struct __ETH_HandleTypeDef * heth); /*!< ETH Rx Complete Callback */ - void (* DMAErrorCallback) ( struct __ETH_HandleTypeDef * heth); /*!< DMA Error Callback */ - void (* MspInitCallback) ( struct __ETH_HandleTypeDef * heth); /*!< ETH Msp Init callback */ - void (* MspDeInitCallback) ( struct __ETH_HandleTypeDef * heth); /*!< ETH Msp DeInit callback */ - -#endif /* USE_HAL_ETH_REGISTER_CALLBACKS */ - -} ETH_HandleTypeDef; - -#if (USE_HAL_ETH_REGISTER_CALLBACKS == 1) -/** - * @brief HAL ETH Callback ID enumeration definition - */ -typedef enum -{ - HAL_ETH_MSPINIT_CB_ID = 0x00U, /*!< ETH MspInit callback ID */ - HAL_ETH_MSPDEINIT_CB_ID = 0x01U, /*!< ETH MspDeInit callback ID */ - HAL_ETH_TX_COMPLETE_CB_ID = 0x02U, /*!< ETH Tx Complete Callback ID */ - HAL_ETH_RX_COMPLETE_CB_ID = 0x03U, /*!< ETH Rx Complete Callback ID */ - HAL_ETH_DMA_ERROR_CB_ID = 0x04U, /*!< ETH DMA Error Callback ID */ - -}HAL_ETH_CallbackIDTypeDef; - -/** - * @brief HAL ETH Callback pointer definition - */ -typedef void (*pETH_CallbackTypeDef)(ETH_HandleTypeDef * heth); /*!< pointer to an ETH callback function */ - -#endif /* USE_HAL_ETH_REGISTER_CALLBACKS */ - - /** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup ETH_Exported_Constants ETH Exported Constants - * @{ - */ - -/** @defgroup ETH_Buffers_setting ETH Buffers setting - * @{ - */ -#define ETH_MAX_PACKET_SIZE 1524U /*!< ETH_HEADER + ETH_EXTRA + ETH_VLAN_TAG + ETH_MAX_ETH_PAYLOAD + ETH_CRC */ -#define ETH_HEADER 14U /*!< 6 byte Dest addr, 6 byte Src addr, 2 byte length/type */ -#define ETH_CRC 4U /*!< Ethernet CRC */ -#define ETH_EXTRA 2U /*!< Extra bytes in some cases */ -#define ETH_VLAN_TAG 4U /*!< optional 802.1q VLAN Tag */ -#define ETH_MIN_ETH_PAYLOAD 46U /*!< Minimum Ethernet payload size */ -#define ETH_MAX_ETH_PAYLOAD 1500U /*!< Maximum Ethernet payload size */ -#define ETH_JUMBO_FRAME_PAYLOAD 9000U /*!< Jumbo frame payload size */ - - /* Ethernet driver receive buffers are organized in a chained linked-list, when - an ethernet packet is received, the Rx-DMA will transfer the packet from RxFIFO - to the driver receive buffers memory. - - Depending on the size of the received ethernet packet and the size of - each ethernet driver receive buffer, the received packet can take one or more - ethernet driver receive buffer. - - In below are defined the size of one ethernet driver receive buffer ETH_RX_BUF_SIZE - and the total count of the driver receive buffers ETH_RXBUFNB. - - The configured value for ETH_RX_BUF_SIZE and ETH_RXBUFNB are only provided as - example, they can be reconfigured in the application layer to fit the application - needs */ - -/* Here we configure each Ethernet driver receive buffer to fit the Max size Ethernet - packet */ -#ifndef ETH_RX_BUF_SIZE - #define ETH_RX_BUF_SIZE ETH_MAX_PACKET_SIZE -#endif - -/* 5 Ethernet driver receive buffers are used (in a chained linked list)*/ -#ifndef ETH_RXBUFNB - #define ETH_RXBUFNB 5U /* 5 Rx buffers of size ETH_RX_BUF_SIZE */ -#endif - - - /* Ethernet driver transmit buffers are organized in a chained linked-list, when - an ethernet packet is transmitted, Tx-DMA will transfer the packet from the - driver transmit buffers memory to the TxFIFO. - - Depending on the size of the Ethernet packet to be transmitted and the size of - each ethernet driver transmit buffer, the packet to be transmitted can take - one or more ethernet driver transmit buffer. - - In below are defined the size of one ethernet driver transmit buffer ETH_TX_BUF_SIZE - and the total count of the driver transmit buffers ETH_TXBUFNB. - - The configured value for ETH_TX_BUF_SIZE and ETH_TXBUFNB are only provided as - example, they can be reconfigured in the application layer to fit the application - needs */ - -/* Here we configure each Ethernet driver transmit buffer to fit the Max size Ethernet - packet */ -#ifndef ETH_TX_BUF_SIZE - #define ETH_TX_BUF_SIZE ETH_MAX_PACKET_SIZE -#endif - -/* 5 ethernet driver transmit buffers are used (in a chained linked list)*/ -#ifndef ETH_TXBUFNB - #define ETH_TXBUFNB 5U /* 5 Tx buffers of size ETH_TX_BUF_SIZE */ -#endif - - /** - * @} - */ - -/** @defgroup ETH_DMA_TX_Descriptor ETH DMA TX Descriptor - * @{ - */ - -/* - DMA Tx Descriptor - ----------------------------------------------------------------------------------------------- - TDES0 | OWN(31) | CTRL[30:26] | Reserved[25:24] | CTRL[23:20] | Reserved[19:17] | Status[16:0] | - ----------------------------------------------------------------------------------------------- - TDES1 | Reserved[31:29] | Buffer2 ByteCount[28:16] | Reserved[15:13] | Buffer1 ByteCount[12:0] | - ----------------------------------------------------------------------------------------------- - TDES2 | Buffer1 Address [31:0] | - ----------------------------------------------------------------------------------------------- - TDES3 | Buffer2 Address [31:0] / Next Descriptor Address [31:0] | - ----------------------------------------------------------------------------------------------- -*/ - -/** - * @brief Bit definition of TDES0 register: DMA Tx descriptor status register - */ -#define ETH_DMATXDESC_OWN 0x80000000U /*!< OWN bit: descriptor is owned by DMA engine */ -#define ETH_DMATXDESC_IC 0x40000000U /*!< Interrupt on Completion */ -#define ETH_DMATXDESC_LS 0x20000000U /*!< Last Segment */ -#define ETH_DMATXDESC_FS 0x10000000U /*!< First Segment */ -#define ETH_DMATXDESC_DC 0x08000000U /*!< Disable CRC */ -#define ETH_DMATXDESC_DP 0x04000000U /*!< Disable Padding */ -#define ETH_DMATXDESC_TTSE 0x02000000U /*!< Transmit Time Stamp Enable */ -#define ETH_DMATXDESC_CIC 0x00C00000U /*!< Checksum Insertion Control: 4 cases */ -#define ETH_DMATXDESC_CIC_BYPASS 0x00000000U /*!< Do Nothing: Checksum Engine is bypassed */ -#define ETH_DMATXDESC_CIC_IPV4HEADER 0x00400000U /*!< IPV4 header Checksum Insertion */ -#define ETH_DMATXDESC_CIC_TCPUDPICMP_SEGMENT 0x00800000U /*!< TCP/UDP/ICMP Checksum Insertion calculated over segment only */ -#define ETH_DMATXDESC_CIC_TCPUDPICMP_FULL 0x00C00000U /*!< TCP/UDP/ICMP Checksum Insertion fully calculated */ -#define ETH_DMATXDESC_TER 0x00200000U /*!< Transmit End of Ring */ -#define ETH_DMATXDESC_TCH 0x00100000U /*!< Second Address Chained */ -#define ETH_DMATXDESC_TTSS 0x00020000U /*!< Tx Time Stamp Status */ -#define ETH_DMATXDESC_IHE 0x00010000U /*!< IP Header Error */ -#define ETH_DMATXDESC_ES 0x00008000U /*!< Error summary: OR of the following bits: UE || ED || EC || LCO || NC || LCA || FF || JT */ -#define ETH_DMATXDESC_JT 0x00004000U /*!< Jabber Timeout */ -#define ETH_DMATXDESC_FF 0x00002000U /*!< Frame Flushed: DMA/MTL flushed the frame due to SW flush */ -#define ETH_DMATXDESC_PCE 0x00001000U /*!< Payload Checksum Error */ -#define ETH_DMATXDESC_LCA 0x00000800U /*!< Loss of Carrier: carrier lost during transmission */ -#define ETH_DMATXDESC_NC 0x00000400U /*!< No Carrier: no carrier signal from the transceiver */ -#define ETH_DMATXDESC_LCO 0x00000200U /*!< Late Collision: transmission aborted due to collision */ -#define ETH_DMATXDESC_EC 0x00000100U /*!< Excessive Collision: transmission aborted after 16 collisions */ -#define ETH_DMATXDESC_VF 0x00000080U /*!< VLAN Frame */ -#define ETH_DMATXDESC_CC 0x00000078U /*!< Collision Count */ -#define ETH_DMATXDESC_ED 0x00000004U /*!< Excessive Deferral */ -#define ETH_DMATXDESC_UF 0x00000002U /*!< Underflow Error: late data arrival from the memory */ -#define ETH_DMATXDESC_DB 0x00000001U /*!< Deferred Bit */ - -/** - * @brief Bit definition of TDES1 register - */ -#define ETH_DMATXDESC_TBS2 0x1FFF0000U /*!< Transmit Buffer2 Size */ -#define ETH_DMATXDESC_TBS1 0x00001FFFU /*!< Transmit Buffer1 Size */ - -/** - * @brief Bit definition of TDES2 register - */ -#define ETH_DMATXDESC_B1AP 0xFFFFFFFFU /*!< Buffer1 Address Pointer */ - -/** - * @brief Bit definition of TDES3 register - */ -#define ETH_DMATXDESC_B2AP 0xFFFFFFFFU /*!< Buffer2 Address Pointer */ - - /*--------------------------------------------------------------------------------------------- - TDES6 | Transmit Time Stamp Low [31:0] | - ----------------------------------------------------------------------------------------------- - TDES7 | Transmit Time Stamp High [31:0] | - ----------------------------------------------------------------------------------------------*/ - -/* Bit definition of TDES6 register */ - #define ETH_DMAPTPTXDESC_TTSL 0xFFFFFFFFU /* Transmit Time Stamp Low */ - -/* Bit definition of TDES7 register */ - #define ETH_DMAPTPTXDESC_TTSH 0xFFFFFFFFU /* Transmit Time Stamp High */ - -/** - * @} - */ -/** @defgroup ETH_DMA_RX_Descriptor ETH DMA RX Descriptor - * @{ - */ - -/* - DMA Rx Descriptor - -------------------------------------------------------------------------------------------------------------------- - RDES0 | OWN(31) | Status [30:0] | - --------------------------------------------------------------------------------------------------------------------- - RDES1 | CTRL(31) | Reserved[30:29] | Buffer2 ByteCount[28:16] | CTRL[15:14] | Reserved(13) | Buffer1 ByteCount[12:0] | - --------------------------------------------------------------------------------------------------------------------- - RDES2 | Buffer1 Address [31:0] | - --------------------------------------------------------------------------------------------------------------------- - RDES3 | Buffer2 Address [31:0] / Next Descriptor Address [31:0] | - --------------------------------------------------------------------------------------------------------------------- -*/ - -/** - * @brief Bit definition of RDES0 register: DMA Rx descriptor status register - */ -#define ETH_DMARXDESC_OWN 0x80000000U /*!< OWN bit: descriptor is owned by DMA engine */ -#define ETH_DMARXDESC_AFM 0x40000000U /*!< DA Filter Fail for the rx frame */ -#define ETH_DMARXDESC_FL 0x3FFF0000U /*!< Receive descriptor frame length */ -#define ETH_DMARXDESC_ES 0x00008000U /*!< Error summary: OR of the following bits: DE || OE || IPC || LC || RWT || RE || CE */ -#define ETH_DMARXDESC_DE 0x00004000U /*!< Descriptor error: no more descriptors for receive frame */ -#define ETH_DMARXDESC_SAF 0x00002000U /*!< SA Filter Fail for the received frame */ -#define ETH_DMARXDESC_LE 0x00001000U /*!< Frame size not matching with length field */ -#define ETH_DMARXDESC_OE 0x00000800U /*!< Overflow Error: Frame was damaged due to buffer overflow */ -#define ETH_DMARXDESC_VLAN 0x00000400U /*!< VLAN Tag: received frame is a VLAN frame */ -#define ETH_DMARXDESC_FS 0x00000200U /*!< First descriptor of the frame */ -#define ETH_DMARXDESC_LS 0x00000100U /*!< Last descriptor of the frame */ -#define ETH_DMARXDESC_IPV4HCE 0x00000080U /*!< IPC Checksum Error: Rx Ipv4 header checksum error */ -#define ETH_DMARXDESC_LC 0x00000040U /*!< Late collision occurred during reception */ -#define ETH_DMARXDESC_FT 0x00000020U /*!< Frame type - Ethernet, otherwise 802.3 */ -#define ETH_DMARXDESC_RWT 0x00000010U /*!< Receive Watchdog Timeout: watchdog timer expired during reception */ -#define ETH_DMARXDESC_RE 0x00000008U /*!< Receive error: error reported by MII interface */ -#define ETH_DMARXDESC_DBE 0x00000004U /*!< Dribble bit error: frame contains non int multiple of 8 bits */ -#define ETH_DMARXDESC_CE 0x00000002U /*!< CRC error */ -#define ETH_DMARXDESC_MAMPCE 0x00000001U /*!< Rx MAC Address/Payload Checksum Error: Rx MAC address matched/ Rx Payload Checksum Error */ - -/** - * @brief Bit definition of RDES1 register - */ -#define ETH_DMARXDESC_DIC 0x80000000U /*!< Disable Interrupt on Completion */ -#define ETH_DMARXDESC_RBS2 0x1FFF0000U /*!< Receive Buffer2 Size */ -#define ETH_DMARXDESC_RER 0x00008000U /*!< Receive End of Ring */ -#define ETH_DMARXDESC_RCH 0x00004000U /*!< Second Address Chained */ -#define ETH_DMARXDESC_RBS1 0x00001FFFU /*!< Receive Buffer1 Size */ - -/** - * @brief Bit definition of RDES2 register - */ -#define ETH_DMARXDESC_B1AP 0xFFFFFFFFU /*!< Buffer1 Address Pointer */ - -/** - * @brief Bit definition of RDES3 register - */ -#define ETH_DMARXDESC_B2AP 0xFFFFFFFFU /*!< Buffer2 Address Pointer */ - -/*--------------------------------------------------------------------------------------------------------------------- - RDES4 | Reserved[31:15] | Extended Status [14:0] | - --------------------------------------------------------------------------------------------------------------------- - RDES5 | Reserved[31:0] | - --------------------------------------------------------------------------------------------------------------------- - RDES6 | Receive Time Stamp Low [31:0] | - --------------------------------------------------------------------------------------------------------------------- - RDES7 | Receive Time Stamp High [31:0] | - --------------------------------------------------------------------------------------------------------------------*/ - -/* Bit definition of RDES4 register */ -#define ETH_DMAPTPRXDESC_PTPV 0x00002000U /* PTP Version */ -#define ETH_DMAPTPRXDESC_PTPFT 0x00001000U /* PTP Frame Type */ -#define ETH_DMAPTPRXDESC_PTPMT 0x00000F00U /* PTP Message Type */ - #define ETH_DMAPTPRXDESC_PTPMT_SYNC 0x00000100U /* SYNC message (all clock types) */ - #define ETH_DMAPTPRXDESC_PTPMT_FOLLOWUP 0x00000200U /* FollowUp message (all clock types) */ - #define ETH_DMAPTPRXDESC_PTPMT_DELAYREQ 0x00000300U /* DelayReq message (all clock types) */ - #define ETH_DMAPTPRXDESC_PTPMT_DELAYRESP 0x00000400U /* DelayResp message (all clock types) */ - #define ETH_DMAPTPRXDESC_PTPMT_PDELAYREQ_ANNOUNCE 0x00000500U /* PdelayReq message (peer-to-peer transparent clock) or Announce message (Ordinary or Boundary clock) */ - #define ETH_DMAPTPRXDESC_PTPMT_PDELAYRESP_MANAG 0x00000600U /* PdelayResp message (peer-to-peer transparent clock) or Management message (Ordinary or Boundary clock) */ - #define ETH_DMAPTPRXDESC_PTPMT_PDELAYRESPFOLLOWUP_SIGNAL 0x00000700U /* PdelayRespFollowUp message (peer-to-peer transparent clock) or Signaling message (Ordinary or Boundary clock) */ -#define ETH_DMAPTPRXDESC_IPV6PR 0x00000080U /* IPv6 Packet Received */ -#define ETH_DMAPTPRXDESC_IPV4PR 0x00000040U /* IPv4 Packet Received */ -#define ETH_DMAPTPRXDESC_IPCB 0x00000020U /* IP Checksum Bypassed */ -#define ETH_DMAPTPRXDESC_IPPE 0x00000010U /* IP Payload Error */ -#define ETH_DMAPTPRXDESC_IPHE 0x00000008U /* IP Header Error */ -#define ETH_DMAPTPRXDESC_IPPT 0x00000007U /* IP Payload Type */ - #define ETH_DMAPTPRXDESC_IPPT_UDP 0x00000001U /* UDP payload encapsulated in the IP datagram */ - #define ETH_DMAPTPRXDESC_IPPT_TCP 0x00000002U /* TCP payload encapsulated in the IP datagram */ - #define ETH_DMAPTPRXDESC_IPPT_ICMP 0x00000003U /* ICMP payload encapsulated in the IP datagram */ - -/* Bit definition of RDES6 register */ -#define ETH_DMAPTPRXDESC_RTSL 0xFFFFFFFFU /* Receive Time Stamp Low */ - -/* Bit definition of RDES7 register */ -#define ETH_DMAPTPRXDESC_RTSH 0xFFFFFFFFU /* Receive Time Stamp High */ -/** - * @} - */ - /** @defgroup ETH_AutoNegotiation ETH AutoNegotiation - * @{ - */ -#define ETH_AUTONEGOTIATION_ENABLE 0x00000001U -#define ETH_AUTONEGOTIATION_DISABLE 0x00000000U - -/** - * @} - */ -/** @defgroup ETH_Speed ETH Speed - * @{ - */ -#define ETH_SPEED_10M 0x00000000U -#define ETH_SPEED_100M 0x00004000U - -/** - * @} - */ -/** @defgroup ETH_Duplex_Mode ETH Duplex Mode - * @{ - */ -#define ETH_MODE_FULLDUPLEX 0x00000800U -#define ETH_MODE_HALFDUPLEX 0x00000000U -/** - * @} - */ -/** @defgroup ETH_Rx_Mode ETH Rx Mode - * @{ - */ -#define ETH_RXPOLLING_MODE 0x00000000U -#define ETH_RXINTERRUPT_MODE 0x00000001U -/** - * @} - */ - -/** @defgroup ETH_Checksum_Mode ETH Checksum Mode - * @{ - */ -#define ETH_CHECKSUM_BY_HARDWARE 0x00000000U -#define ETH_CHECKSUM_BY_SOFTWARE 0x00000001U -/** - * @} - */ - -/** @defgroup ETH_Media_Interface ETH Media Interface - * @{ - */ -#define ETH_MEDIA_INTERFACE_MII 0x00000000U -#define ETH_MEDIA_INTERFACE_RMII ((uint32_t)SYSCFG_PMC_MII_RMII_SEL) -/** - * @} - */ - -/** @defgroup ETH_Watchdog ETH Watchdog - * @{ - */ -#define ETH_WATCHDOG_ENABLE 0x00000000U -#define ETH_WATCHDOG_DISABLE 0x00800000U -/** - * @} - */ - -/** @defgroup ETH_Jabber ETH Jabber - * @{ - */ -#define ETH_JABBER_ENABLE 0x00000000U -#define ETH_JABBER_DISABLE 0x00400000U -/** - * @} - */ - -/** @defgroup ETH_Inter_Frame_Gap ETH Inter Frame Gap - * @{ - */ -#define ETH_INTERFRAMEGAP_96BIT 0x00000000U /*!< minimum IFG between frames during transmission is 96Bit */ -#define ETH_INTERFRAMEGAP_88BIT 0x00020000U /*!< minimum IFG between frames during transmission is 88Bit */ -#define ETH_INTERFRAMEGAP_80BIT 0x00040000U /*!< minimum IFG between frames during transmission is 80Bit */ -#define ETH_INTERFRAMEGAP_72BIT 0x00060000U /*!< minimum IFG between frames during transmission is 72Bit */ -#define ETH_INTERFRAMEGAP_64BIT 0x00080000U /*!< minimum IFG between frames during transmission is 64Bit */ -#define ETH_INTERFRAMEGAP_56BIT 0x000A0000U /*!< minimum IFG between frames during transmission is 56Bit */ -#define ETH_INTERFRAMEGAP_48BIT 0x000C0000U /*!< minimum IFG between frames during transmission is 48Bit */ -#define ETH_INTERFRAMEGAP_40BIT 0x000E0000U /*!< minimum IFG between frames during transmission is 40Bit */ -/** - * @} - */ - -/** @defgroup ETH_Carrier_Sense ETH Carrier Sense - * @{ - */ -#define ETH_CARRIERSENCE_ENABLE 0x00000000U -#define ETH_CARRIERSENCE_DISABLE 0x00010000U -/** - * @} - */ - -/** @defgroup ETH_Receive_Own ETH Receive Own - * @{ - */ -#define ETH_RECEIVEOWN_ENABLE 0x00000000U -#define ETH_RECEIVEOWN_DISABLE 0x00002000U -/** - * @} - */ - -/** @defgroup ETH_Loop_Back_Mode ETH Loop Back Mode - * @{ - */ -#define ETH_LOOPBACKMODE_ENABLE 0x00001000U -#define ETH_LOOPBACKMODE_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup ETH_Checksum_Offload ETH Checksum Offload - * @{ - */ -#define ETH_CHECKSUMOFFLAOD_ENABLE 0x00000400U -#define ETH_CHECKSUMOFFLAOD_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup ETH_Retry_Transmission ETH Retry Transmission - * @{ - */ -#define ETH_RETRYTRANSMISSION_ENABLE 0x00000000U -#define ETH_RETRYTRANSMISSION_DISABLE 0x00000200U -/** - * @} - */ - -/** @defgroup ETH_Automatic_Pad_CRC_Strip ETH Automatic Pad CRC Strip - * @{ - */ -#define ETH_AUTOMATICPADCRCSTRIP_ENABLE 0x00000080U -#define ETH_AUTOMATICPADCRCSTRIP_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup ETH_Back_Off_Limit ETH Back Off Limit - * @{ - */ -#define ETH_BACKOFFLIMIT_10 0x00000000U -#define ETH_BACKOFFLIMIT_8 0x00000020U -#define ETH_BACKOFFLIMIT_4 0x00000040U -#define ETH_BACKOFFLIMIT_1 0x00000060U -/** - * @} - */ - -/** @defgroup ETH_Deferral_Check ETH Deferral Check - * @{ - */ -#define ETH_DEFFERRALCHECK_ENABLE 0x00000010U -#define ETH_DEFFERRALCHECK_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup ETH_Receive_All ETH Receive All - * @{ - */ -#define ETH_RECEIVEALL_ENABLE 0x80000000U -#define ETH_RECEIVEAll_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup ETH_Source_Addr_Filter ETH Source Addr Filter - * @{ - */ -#define ETH_SOURCEADDRFILTER_NORMAL_ENABLE 0x00000200U -#define ETH_SOURCEADDRFILTER_INVERSE_ENABLE 0x00000300U -#define ETH_SOURCEADDRFILTER_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup ETH_Pass_Control_Frames ETH Pass Control Frames - * @{ - */ -#define ETH_PASSCONTROLFRAMES_BLOCKALL 0x00000040U /*!< MAC filters all control frames from reaching the application */ -#define ETH_PASSCONTROLFRAMES_FORWARDALL 0x00000080U /*!< MAC forwards all control frames to application even if they fail the Address Filter */ -#define ETH_PASSCONTROLFRAMES_FORWARDPASSEDADDRFILTER 0x000000C0U /*!< MAC forwards control frames that pass the Address Filter. */ -/** - * @} - */ - -/** @defgroup ETH_Broadcast_Frames_Reception ETH Broadcast Frames Reception - * @{ - */ -#define ETH_BROADCASTFRAMESRECEPTION_ENABLE 0x00000000U -#define ETH_BROADCASTFRAMESRECEPTION_DISABLE 0x00000020U -/** - * @} - */ - -/** @defgroup ETH_Destination_Addr_Filter ETH Destination Addr Filter - * @{ - */ -#define ETH_DESTINATIONADDRFILTER_NORMAL 0x00000000U -#define ETH_DESTINATIONADDRFILTER_INVERSE 0x00000008U -/** - * @} - */ - -/** @defgroup ETH_Promiscuous_Mode ETH Promiscuous Mode - * @{ - */ -#define ETH_PROMISCUOUS_MODE_ENABLE 0x00000001U -#define ETH_PROMISCUOUS_MODE_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup ETH_Multicast_Frames_Filter ETH Multicast Frames Filter - * @{ - */ -#define ETH_MULTICASTFRAMESFILTER_PERFECTHASHTABLE 0x00000404U -#define ETH_MULTICASTFRAMESFILTER_HASHTABLE 0x00000004U -#define ETH_MULTICASTFRAMESFILTER_PERFECT 0x00000000U -#define ETH_MULTICASTFRAMESFILTER_NONE 0x00000010U -/** - * @} - */ - -/** @defgroup ETH_Unicast_Frames_Filter ETH Unicast Frames Filter - * @{ - */ -#define ETH_UNICASTFRAMESFILTER_PERFECTHASHTABLE 0x00000402U -#define ETH_UNICASTFRAMESFILTER_HASHTABLE 0x00000002U -#define ETH_UNICASTFRAMESFILTER_PERFECT 0x00000000U -/** - * @} - */ - -/** @defgroup ETH_Zero_Quanta_Pause ETH Zero Quanta Pause - * @{ - */ -#define ETH_ZEROQUANTAPAUSE_ENABLE 0x00000000U -#define ETH_ZEROQUANTAPAUSE_DISABLE 0x00000080U -/** - * @} - */ - -/** @defgroup ETH_Pause_Low_Threshold ETH Pause Low Threshold - * @{ - */ -#define ETH_PAUSELOWTHRESHOLD_MINUS4 0x00000000U /*!< Pause time minus 4 slot times */ -#define ETH_PAUSELOWTHRESHOLD_MINUS28 0x00000010U /*!< Pause time minus 28 slot times */ -#define ETH_PAUSELOWTHRESHOLD_MINUS144 0x00000020U /*!< Pause time minus 144 slot times */ -#define ETH_PAUSELOWTHRESHOLD_MINUS256 0x00000030U /*!< Pause time minus 256 slot times */ -/** - * @} - */ - -/** @defgroup ETH_Unicast_Pause_Frame_Detect ETH Unicast Pause Frame Detect - * @{ - */ -#define ETH_UNICASTPAUSEFRAMEDETECT_ENABLE 0x00000008U -#define ETH_UNICASTPAUSEFRAMEDETECT_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup ETH_Receive_Flow_Control ETH Receive Flow Control - * @{ - */ -#define ETH_RECEIVEFLOWCONTROL_ENABLE 0x00000004U -#define ETH_RECEIVEFLOWCONTROL_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup ETH_Transmit_Flow_Control ETH Transmit Flow Control - * @{ - */ -#define ETH_TRANSMITFLOWCONTROL_ENABLE 0x00000002U -#define ETH_TRANSMITFLOWCONTROL_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup ETH_VLAN_Tag_Comparison ETH VLAN Tag Comparison - * @{ - */ -#define ETH_VLANTAGCOMPARISON_12BIT 0x00010000U -#define ETH_VLANTAGCOMPARISON_16BIT 0x00000000U -/** - * @} - */ - -/** @defgroup ETH_MAC_addresses ETH MAC addresses - * @{ - */ -#define ETH_MAC_ADDRESS0 0x00000000U -#define ETH_MAC_ADDRESS1 0x00000008U -#define ETH_MAC_ADDRESS2 0x00000010U -#define ETH_MAC_ADDRESS3 0x00000018U -/** - * @} - */ - -/** @defgroup ETH_MAC_addresses_filter_SA_DA ETH MAC addresses filter SA DA - * @{ - */ -#define ETH_MAC_ADDRESSFILTER_SA 0x00000000U -#define ETH_MAC_ADDRESSFILTER_DA 0x00000008U -/** - * @} - */ - -/** @defgroup ETH_MAC_addresses_filter_Mask_bytes ETH MAC addresses filter Mask bytes - * @{ - */ -#define ETH_MAC_ADDRESSMASK_BYTE6 0x20000000U /*!< Mask MAC Address high reg bits [15:8] */ -#define ETH_MAC_ADDRESSMASK_BYTE5 0x10000000U /*!< Mask MAC Address high reg bits [7:0] */ -#define ETH_MAC_ADDRESSMASK_BYTE4 0x08000000U /*!< Mask MAC Address low reg bits [31:24] */ -#define ETH_MAC_ADDRESSMASK_BYTE3 0x04000000U /*!< Mask MAC Address low reg bits [23:16] */ -#define ETH_MAC_ADDRESSMASK_BYTE2 0x02000000U /*!< Mask MAC Address low reg bits [15:8] */ -#define ETH_MAC_ADDRESSMASK_BYTE1 0x01000000U /*!< Mask MAC Address low reg bits [70] */ -/** - * @} - */ - -/** @defgroup ETH_Drop_TCP_IP_Checksum_Error_Frame ETH Drop TCP IP Checksum Error Frame - * @{ - */ -#define ETH_DROPTCPIPCHECKSUMERRORFRAME_ENABLE 0x00000000U -#define ETH_DROPTCPIPCHECKSUMERRORFRAME_DISABLE 0x04000000U -/** - * @} - */ - -/** @defgroup ETH_Receive_Store_Forward ETH Receive Store Forward - * @{ - */ -#define ETH_RECEIVESTOREFORWARD_ENABLE 0x02000000U -#define ETH_RECEIVESTOREFORWARD_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup ETH_Flush_Received_Frame ETH Flush Received Frame - * @{ - */ -#define ETH_FLUSHRECEIVEDFRAME_ENABLE 0x00000000U -#define ETH_FLUSHRECEIVEDFRAME_DISABLE 0x01000000U -/** - * @} - */ - -/** @defgroup ETH_Transmit_Store_Forward ETH Transmit Store Forward - * @{ - */ -#define ETH_TRANSMITSTOREFORWARD_ENABLE 0x00200000U -#define ETH_TRANSMITSTOREFORWARD_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup ETH_Transmit_Threshold_Control ETH Transmit Threshold Control - * @{ - */ -#define ETH_TRANSMITTHRESHOLDCONTROL_64BYTES 0x00000000U /*!< threshold level of the MTL Transmit FIFO is 64 Bytes */ -#define ETH_TRANSMITTHRESHOLDCONTROL_128BYTES 0x00004000U /*!< threshold level of the MTL Transmit FIFO is 128 Bytes */ -#define ETH_TRANSMITTHRESHOLDCONTROL_192BYTES 0x00008000U /*!< threshold level of the MTL Transmit FIFO is 192 Bytes */ -#define ETH_TRANSMITTHRESHOLDCONTROL_256BYTES 0x0000C000U /*!< threshold level of the MTL Transmit FIFO is 256 Bytes */ -#define ETH_TRANSMITTHRESHOLDCONTROL_40BYTES 0x00010000U /*!< threshold level of the MTL Transmit FIFO is 40 Bytes */ -#define ETH_TRANSMITTHRESHOLDCONTROL_32BYTES 0x00014000U /*!< threshold level of the MTL Transmit FIFO is 32 Bytes */ -#define ETH_TRANSMITTHRESHOLDCONTROL_24BYTES 0x00018000U /*!< threshold level of the MTL Transmit FIFO is 24 Bytes */ -#define ETH_TRANSMITTHRESHOLDCONTROL_16BYTES 0x0001C000U /*!< threshold level of the MTL Transmit FIFO is 16 Bytes */ -/** - * @} - */ - -/** @defgroup ETH_Forward_Error_Frames ETH Forward Error Frames - * @{ - */ -#define ETH_FORWARDERRORFRAMES_ENABLE 0x00000080U -#define ETH_FORWARDERRORFRAMES_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup ETH_Forward_Undersized_Good_Frames ETH Forward Undersized Good Frames - * @{ - */ -#define ETH_FORWARDUNDERSIZEDGOODFRAMES_ENABLE 0x00000040U -#define ETH_FORWARDUNDERSIZEDGOODFRAMES_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup ETH_Receive_Threshold_Control ETH Receive Threshold Control - * @{ - */ -#define ETH_RECEIVEDTHRESHOLDCONTROL_64BYTES 0x00000000U /*!< threshold level of the MTL Receive FIFO is 64 Bytes */ -#define ETH_RECEIVEDTHRESHOLDCONTROL_32BYTES 0x00000008U /*!< threshold level of the MTL Receive FIFO is 32 Bytes */ -#define ETH_RECEIVEDTHRESHOLDCONTROL_96BYTES 0x00000010U /*!< threshold level of the MTL Receive FIFO is 96 Bytes */ -#define ETH_RECEIVEDTHRESHOLDCONTROL_128BYTES 0x00000018U /*!< threshold level of the MTL Receive FIFO is 128 Bytes */ -/** - * @} - */ - -/** @defgroup ETH_Second_Frame_Operate ETH Second Frame Operate - * @{ - */ -#define ETH_SECONDFRAMEOPERARTE_ENABLE 0x00000004U -#define ETH_SECONDFRAMEOPERARTE_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup ETH_Address_Aligned_Beats ETH Address Aligned Beats - * @{ - */ -#define ETH_ADDRESSALIGNEDBEATS_ENABLE 0x02000000U -#define ETH_ADDRESSALIGNEDBEATS_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup ETH_Fixed_Burst ETH Fixed Burst - * @{ - */ -#define ETH_FIXEDBURST_ENABLE 0x00010000U -#define ETH_FIXEDBURST_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup ETH_Rx_DMA_Burst_Length ETH Rx DMA Burst Length - * @{ - */ -#define ETH_RXDMABURSTLENGTH_1BEAT 0x00020000U /*!< maximum number of beats to be transferred in one RxDMA transaction is 1 */ -#define ETH_RXDMABURSTLENGTH_2BEAT 0x00040000U /*!< maximum number of beats to be transferred in one RxDMA transaction is 2 */ -#define ETH_RXDMABURSTLENGTH_4BEAT 0x00080000U /*!< maximum number of beats to be transferred in one RxDMA transaction is 4 */ -#define ETH_RXDMABURSTLENGTH_8BEAT 0x00100000U /*!< maximum number of beats to be transferred in one RxDMA transaction is 8 */ -#define ETH_RXDMABURSTLENGTH_16BEAT 0x00200000U /*!< maximum number of beats to be transferred in one RxDMA transaction is 16 */ -#define ETH_RXDMABURSTLENGTH_32BEAT 0x00400000U /*!< maximum number of beats to be transferred in one RxDMA transaction is 32 */ -#define ETH_RXDMABURSTLENGTH_4XPBL_4BEAT 0x01020000U /*!< maximum number of beats to be transferred in one RxDMA transaction is 4 */ -#define ETH_RXDMABURSTLENGTH_4XPBL_8BEAT 0x01040000U /*!< maximum number of beats to be transferred in one RxDMA transaction is 8 */ -#define ETH_RXDMABURSTLENGTH_4XPBL_16BEAT 0x01080000U /*!< maximum number of beats to be transferred in one RxDMA transaction is 16 */ -#define ETH_RXDMABURSTLENGTH_4XPBL_32BEAT 0x01100000U /*!< maximum number of beats to be transferred in one RxDMA transaction is 32 */ -#define ETH_RXDMABURSTLENGTH_4XPBL_64BEAT 0x01200000U /*!< maximum number of beats to be transferred in one RxDMA transaction is 64 */ -#define ETH_RXDMABURSTLENGTH_4XPBL_128BEAT 0x01400000U /*!< maximum number of beats to be transferred in one RxDMA transaction is 128 */ -/** - * @} - */ - -/** @defgroup ETH_Tx_DMA_Burst_Length ETH Tx DMA Burst Length - * @{ - */ -#define ETH_TXDMABURSTLENGTH_1BEAT 0x00000100U /*!< maximum number of beats to be transferred in one TxDMA (or both) transaction is 1 */ -#define ETH_TXDMABURSTLENGTH_2BEAT 0x00000200U /*!< maximum number of beats to be transferred in one TxDMA (or both) transaction is 2 */ -#define ETH_TXDMABURSTLENGTH_4BEAT 0x00000400U /*!< maximum number of beats to be transferred in one TxDMA (or both) transaction is 4 */ -#define ETH_TXDMABURSTLENGTH_8BEAT 0x00000800U /*!< maximum number of beats to be transferred in one TxDMA (or both) transaction is 8 */ -#define ETH_TXDMABURSTLENGTH_16BEAT 0x00001000U /*!< maximum number of beats to be transferred in one TxDMA (or both) transaction is 16 */ -#define ETH_TXDMABURSTLENGTH_32BEAT 0x00002000U /*!< maximum number of beats to be transferred in one TxDMA (or both) transaction is 32 */ -#define ETH_TXDMABURSTLENGTH_4XPBL_4BEAT 0x01000100U /*!< maximum number of beats to be transferred in one TxDMA (or both) transaction is 4 */ -#define ETH_TXDMABURSTLENGTH_4XPBL_8BEAT 0x01000200U /*!< maximum number of beats to be transferred in one TxDMA (or both) transaction is 8 */ -#define ETH_TXDMABURSTLENGTH_4XPBL_16BEAT 0x01000400U /*!< maximum number of beats to be transferred in one TxDMA (or both) transaction is 16 */ -#define ETH_TXDMABURSTLENGTH_4XPBL_32BEAT 0x01000800U /*!< maximum number of beats to be transferred in one TxDMA (or both) transaction is 32 */ -#define ETH_TXDMABURSTLENGTH_4XPBL_64BEAT 0x01001000U /*!< maximum number of beats to be transferred in one TxDMA (or both) transaction is 64 */ -#define ETH_TXDMABURSTLENGTH_4XPBL_128BEAT 0x01002000U /*!< maximum number of beats to be transferred in one TxDMA (or both) transaction is 128 */ -/** - * @} - */ - -/** @defgroup ETH_DMA_Enhanced_descriptor_format ETH DMA Enhanced descriptor format - * @{ - */ -#define ETH_DMAENHANCEDDESCRIPTOR_ENABLE 0x00000080U -#define ETH_DMAENHANCEDDESCRIPTOR_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup ETH_DMA_Arbitration ETH DMA Arbitration - * @{ - */ -#define ETH_DMAARBITRATION_ROUNDROBIN_RXTX_1_1 0x00000000U -#define ETH_DMAARBITRATION_ROUNDROBIN_RXTX_2_1 0x00004000U -#define ETH_DMAARBITRATION_ROUNDROBIN_RXTX_3_1 0x00008000U -#define ETH_DMAARBITRATION_ROUNDROBIN_RXTX_4_1 0x0000C000U -#define ETH_DMAARBITRATION_RXPRIORTX 0x00000002U -/** - * @} - */ - -/** @defgroup ETH_DMA_Tx_descriptor_segment ETH DMA Tx descriptor segment - * @{ - */ -#define ETH_DMATXDESC_LASTSEGMENTS 0x40000000U /*!< Last Segment */ -#define ETH_DMATXDESC_FIRSTSEGMENT 0x20000000U /*!< First Segment */ -/** - * @} - */ - -/** @defgroup ETH_DMA_Tx_descriptor_Checksum_Insertion_Control ETH DMA Tx descriptor Checksum Insertion Control - * @{ - */ -#define ETH_DMATXDESC_CHECKSUMBYPASS 0x00000000U /*!< Checksum engine bypass */ -#define ETH_DMATXDESC_CHECKSUMIPV4HEADER 0x00400000U /*!< IPv4 header checksum insertion */ -#define ETH_DMATXDESC_CHECKSUMTCPUDPICMPSEGMENT 0x00800000U /*!< TCP/UDP/ICMP checksum insertion. Pseudo header checksum is assumed to be present */ -#define ETH_DMATXDESC_CHECKSUMTCPUDPICMPFULL 0x00C00000U /*!< TCP/UDP/ICMP checksum fully in hardware including pseudo header */ -/** - * @} - */ - -/** @defgroup ETH_DMA_Rx_descriptor_buffers ETH DMA Rx descriptor buffers - * @{ - */ -#define ETH_DMARXDESC_BUFFER1 0x00000000U /*!< DMA Rx Desc Buffer1 */ -#define ETH_DMARXDESC_BUFFER2 0x00000001U /*!< DMA Rx Desc Buffer2 */ -/** - * @} - */ - -/** @defgroup ETH_PMT_Flags ETH PMT Flags - * @{ - */ -#define ETH_PMT_FLAG_WUFFRPR 0x80000000U /*!< Wake-Up Frame Filter Register Pointer Reset */ -#define ETH_PMT_FLAG_WUFR 0x00000040U /*!< Wake-Up Frame Received */ -#define ETH_PMT_FLAG_MPR 0x00000020U /*!< Magic Packet Received */ -/** - * @} - */ - -/** @defgroup ETH_MMC_Tx_Interrupts ETH MMC Tx Interrupts - * @{ - */ -#define ETH_MMC_IT_TGF 0x00200000U /*!< When Tx good frame counter reaches half the maximum value */ -#define ETH_MMC_IT_TGFMSC 0x00008000U /*!< When Tx good multi col counter reaches half the maximum value */ -#define ETH_MMC_IT_TGFSC 0x00004000U /*!< When Tx good single col counter reaches half the maximum value */ -/** - * @} - */ - -/** @defgroup ETH_MMC_Rx_Interrupts ETH MMC Rx Interrupts - * @{ - */ -#define ETH_MMC_IT_RGUF 0x10020000U /*!< When Rx good unicast frames counter reaches half the maximum value */ -#define ETH_MMC_IT_RFAE 0x10000040U /*!< When Rx alignment error counter reaches half the maximum value */ -#define ETH_MMC_IT_RFCE 0x10000020U /*!< When Rx crc error counter reaches half the maximum value */ -/** - * @} - */ - -/** @defgroup ETH_MAC_Flags ETH MAC Flags - * @{ - */ -#define ETH_MAC_FLAG_TST 0x00000200U /*!< Time stamp trigger flag (on MAC) */ -#define ETH_MAC_FLAG_MMCT 0x00000040U /*!< MMC transmit flag */ -#define ETH_MAC_FLAG_MMCR 0x00000020U /*!< MMC receive flag */ -#define ETH_MAC_FLAG_MMC 0x00000010U /*!< MMC flag (on MAC) */ -#define ETH_MAC_FLAG_PMT 0x00000008U /*!< PMT flag (on MAC) */ -/** - * @} - */ - -/** @defgroup ETH_DMA_Flags ETH DMA Flags - * @{ - */ -#define ETH_DMA_FLAG_TST 0x20000000U /*!< Time-stamp trigger interrupt (on DMA) */ -#define ETH_DMA_FLAG_PMT 0x10000000U /*!< PMT interrupt (on DMA) */ -#define ETH_DMA_FLAG_MMC 0x08000000U /*!< MMC interrupt (on DMA) */ -#define ETH_DMA_FLAG_DATATRANSFERERROR 0x00800000U /*!< Error bits 0-Rx DMA, 1-Tx DMA */ -#define ETH_DMA_FLAG_READWRITEERROR 0x01000000U /*!< Error bits 0-write transfer, 1-read transfer */ -#define ETH_DMA_FLAG_ACCESSERROR 0x02000000U /*!< Error bits 0-data buffer, 1-desc. access */ -#define ETH_DMA_FLAG_NIS 0x00010000U /*!< Normal interrupt summary flag */ -#define ETH_DMA_FLAG_AIS 0x00008000U /*!< Abnormal interrupt summary flag */ -#define ETH_DMA_FLAG_ER 0x00004000U /*!< Early receive flag */ -#define ETH_DMA_FLAG_FBE 0x00002000U /*!< Fatal bus error flag */ -#define ETH_DMA_FLAG_ET 0x00000400U /*!< Early transmit flag */ -#define ETH_DMA_FLAG_RWT 0x00000200U /*!< Receive watchdog timeout flag */ -#define ETH_DMA_FLAG_RPS 0x00000100U /*!< Receive process stopped flag */ -#define ETH_DMA_FLAG_RBU 0x00000080U /*!< Receive buffer unavailable flag */ -#define ETH_DMA_FLAG_R 0x00000040U /*!< Receive flag */ -#define ETH_DMA_FLAG_TU 0x00000020U /*!< Underflow flag */ -#define ETH_DMA_FLAG_RO 0x00000010U /*!< Overflow flag */ -#define ETH_DMA_FLAG_TJT 0x00000008U /*!< Transmit jabber timeout flag */ -#define ETH_DMA_FLAG_TBU 0x00000004U /*!< Transmit buffer unavailable flag */ -#define ETH_DMA_FLAG_TPS 0x00000002U /*!< Transmit process stopped flag */ -#define ETH_DMA_FLAG_T 0x00000001U /*!< Transmit flag */ -/** - * @} - */ - -/** @defgroup ETH_MAC_Interrupts ETH MAC Interrupts - * @{ - */ -#define ETH_MAC_IT_TST 0x00000200U /*!< Time stamp trigger interrupt (on MAC) */ -#define ETH_MAC_IT_MMCT 0x00000040U /*!< MMC transmit interrupt */ -#define ETH_MAC_IT_MMCR 0x00000020U /*!< MMC receive interrupt */ -#define ETH_MAC_IT_MMC 0x00000010U /*!< MMC interrupt (on MAC) */ -#define ETH_MAC_IT_PMT 0x00000008U /*!< PMT interrupt (on MAC) */ -/** - * @} - */ - -/** @defgroup ETH_DMA_Interrupts ETH DMA Interrupts - * @{ - */ -#define ETH_DMA_IT_TST 0x20000000U /*!< Time-stamp trigger interrupt (on DMA) */ -#define ETH_DMA_IT_PMT 0x10000000U /*!< PMT interrupt (on DMA) */ -#define ETH_DMA_IT_MMC 0x08000000U /*!< MMC interrupt (on DMA) */ -#define ETH_DMA_IT_NIS 0x00010000U /*!< Normal interrupt summary */ -#define ETH_DMA_IT_AIS 0x00008000U /*!< Abnormal interrupt summary */ -#define ETH_DMA_IT_ER 0x00004000U /*!< Early receive interrupt */ -#define ETH_DMA_IT_FBE 0x00002000U /*!< Fatal bus error interrupt */ -#define ETH_DMA_IT_ET 0x00000400U /*!< Early transmit interrupt */ -#define ETH_DMA_IT_RWT 0x00000200U /*!< Receive watchdog timeout interrupt */ -#define ETH_DMA_IT_RPS 0x00000100U /*!< Receive process stopped interrupt */ -#define ETH_DMA_IT_RBU 0x00000080U /*!< Receive buffer unavailable interrupt */ -#define ETH_DMA_IT_R 0x00000040U /*!< Receive interrupt */ -#define ETH_DMA_IT_TU 0x00000020U /*!< Underflow interrupt */ -#define ETH_DMA_IT_RO 0x00000010U /*!< Overflow interrupt */ -#define ETH_DMA_IT_TJT 0x00000008U /*!< Transmit jabber timeout interrupt */ -#define ETH_DMA_IT_TBU 0x00000004U /*!< Transmit buffer unavailable interrupt */ -#define ETH_DMA_IT_TPS 0x00000002U /*!< Transmit process stopped interrupt */ -#define ETH_DMA_IT_T 0x00000001U /*!< Transmit interrupt */ -/** - * @} - */ - -/** @defgroup ETH_DMA_transmit_process_state ETH DMA transmit process state - * @{ - */ -#define ETH_DMA_TRANSMITPROCESS_STOPPED 0x00000000U /*!< Stopped - Reset or Stop Tx Command issued */ -#define ETH_DMA_TRANSMITPROCESS_FETCHING 0x00100000U /*!< Running - fetching the Tx descriptor */ -#define ETH_DMA_TRANSMITPROCESS_WAITING 0x00200000U /*!< Running - waiting for status */ -#define ETH_DMA_TRANSMITPROCESS_READING 0x00300000U /*!< Running - reading the data from host memory */ -#define ETH_DMA_TRANSMITPROCESS_SUSPENDED 0x00600000U /*!< Suspended - Tx Descriptor unavailable */ -#define ETH_DMA_TRANSMITPROCESS_CLOSING 0x00700000U /*!< Running - closing Rx descriptor */ - -/** - * @} - */ - - -/** @defgroup ETH_DMA_receive_process_state ETH DMA receive process state - * @{ - */ -#define ETH_DMA_RECEIVEPROCESS_STOPPED 0x00000000U /*!< Stopped - Reset or Stop Rx Command issued */ -#define ETH_DMA_RECEIVEPROCESS_FETCHING 0x00020000U /*!< Running - fetching the Rx descriptor */ -#define ETH_DMA_RECEIVEPROCESS_WAITING 0x00060000U /*!< Running - waiting for packet */ -#define ETH_DMA_RECEIVEPROCESS_SUSPENDED 0x00080000U /*!< Suspended - Rx Descriptor unavailable */ -#define ETH_DMA_RECEIVEPROCESS_CLOSING 0x000A0000U /*!< Running - closing descriptor */ -#define ETH_DMA_RECEIVEPROCESS_QUEUING 0x000E0000U /*!< Running - queuing the receive frame into host memory */ - -/** - * @} - */ - -/** @defgroup ETH_DMA_overflow ETH DMA overflow - * @{ - */ -#define ETH_DMA_OVERFLOW_RXFIFOCOUNTER 0x10000000U /*!< Overflow bit for FIFO overflow counter */ -#define ETH_DMA_OVERFLOW_MISSEDFRAMECOUNTER 0x00010000U /*!< Overflow bit for missed frame counter */ -/** - * @} - */ - -/** @defgroup ETH_EXTI_LINE_WAKEUP ETH EXTI LINE WAKEUP - * @{ - */ -#define ETH_EXTI_LINE_WAKEUP 0x00080000U /*!< External interrupt line 19 Connected to the ETH EXTI Line */ - -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup ETH_Exported_Macros ETH Exported Macros - * @brief macros to handle interrupts and specific clock configurations - * @{ - */ - -/** @brief Reset ETH handle state - * @param __HANDLE__ specifies the ETH handle. - * @retval None - */ -#if (USE_HAL_ETH_REGISTER_CALLBACKS == 1) -#define __HAL_ETH_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->State = HAL_ETH_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_ETH_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_ETH_STATE_RESET) -#endif /*USE_HAL_ETH_REGISTER_CALLBACKS */ - -/** - * @brief Checks whether the specified ETHERNET DMA Tx Desc flag is set or not. - * @param __HANDLE__ ETH Handle - * @param __FLAG__ specifies the flag of TDES0 to check. - * @retval the ETH_DMATxDescFlag (SET or RESET). - */ -#define __HAL_ETH_DMATXDESC_GET_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->TxDesc->Status & (__FLAG__) == (__FLAG__)) - -/** - * @brief Checks whether the specified ETHERNET DMA Rx Desc flag is set or not. - * @param __HANDLE__ ETH Handle - * @param __FLAG__ specifies the flag of RDES0 to check. - * @retval the ETH_DMATxDescFlag (SET or RESET). - */ -#define __HAL_ETH_DMARXDESC_GET_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->RxDesc->Status & (__FLAG__) == (__FLAG__)) - -/** - * @brief Enables the specified DMA Rx Desc receive interrupt. - * @param __HANDLE__ ETH Handle - * @retval None - */ -#define __HAL_ETH_DMARXDESC_ENABLE_IT(__HANDLE__) ((__HANDLE__)->RxDesc->ControlBufferSize &=(~(uint32_t)ETH_DMARXDESC_DIC)) - -/** - * @brief Disables the specified DMA Rx Desc receive interrupt. - * @param __HANDLE__ ETH Handle - * @retval None - */ -#define __HAL_ETH_DMARXDESC_DISABLE_IT(__HANDLE__) ((__HANDLE__)->RxDesc->ControlBufferSize |= ETH_DMARXDESC_DIC) - -/** - * @brief Set the specified DMA Rx Desc Own bit. - * @param __HANDLE__ ETH Handle - * @retval None - */ -#define __HAL_ETH_DMARXDESC_SET_OWN_BIT(__HANDLE__) ((__HANDLE__)->RxDesc->Status |= ETH_DMARXDESC_OWN) - -/** - * @brief Returns the specified ETHERNET DMA Tx Desc collision count. - * @param __HANDLE__ ETH Handle - * @retval The Transmit descriptor collision counter value. - */ -#define __HAL_ETH_DMATXDESC_GET_COLLISION_COUNT(__HANDLE__) (((__HANDLE__)->TxDesc->Status & ETH_DMATXDESC_CC) >> ETH_DMATXDESC_COLLISION_COUNTSHIFT) - -/** - * @brief Set the specified DMA Tx Desc Own bit. - * @param __HANDLE__ ETH Handle - * @retval None - */ -#define __HAL_ETH_DMATXDESC_SET_OWN_BIT(__HANDLE__) ((__HANDLE__)->TxDesc->Status |= ETH_DMATXDESC_OWN) - -/** - * @brief Enables the specified DMA Tx Desc Transmit interrupt. - * @param __HANDLE__ ETH Handle - * @retval None - */ -#define __HAL_ETH_DMATXDESC_ENABLE_IT(__HANDLE__) ((__HANDLE__)->TxDesc->Status |= ETH_DMATXDESC_IC) - -/** - * @brief Disables the specified DMA Tx Desc Transmit interrupt. - * @param __HANDLE__ ETH Handle - * @retval None - */ -#define __HAL_ETH_DMATXDESC_DISABLE_IT(__HANDLE__) ((__HANDLE__)->TxDesc->Status &= ~ETH_DMATXDESC_IC) - -/** - * @brief Selects the specified ETHERNET DMA Tx Desc Checksum Insertion. - * @param __HANDLE__ ETH Handle - * @param __CHECKSUM__ specifies is the DMA Tx desc checksum insertion. - * This parameter can be one of the following values: - * @arg ETH_DMATXDESC_CHECKSUMBYPASS : Checksum bypass - * @arg ETH_DMATXDESC_CHECKSUMIPV4HEADER : IPv4 header checksum - * @arg ETH_DMATXDESC_CHECKSUMTCPUDPICMPSEGMENT : TCP/UDP/ICMP checksum. Pseudo header checksum is assumed to be present - * @arg ETH_DMATXDESC_CHECKSUMTCPUDPICMPFULL : TCP/UDP/ICMP checksum fully in hardware including pseudo header - * @retval None - */ -#define __HAL_ETH_DMATXDESC_CHECKSUM_INSERTION(__HANDLE__, __CHECKSUM__) ((__HANDLE__)->TxDesc->Status |= (__CHECKSUM__)) - -/** - * @brief Enables the DMA Tx Desc CRC. - * @param __HANDLE__ ETH Handle - * @retval None - */ -#define __HAL_ETH_DMATXDESC_CRC_ENABLE(__HANDLE__) ((__HANDLE__)->TxDesc->Status &= ~ETH_DMATXDESC_DC) - -/** - * @brief Disables the DMA Tx Desc CRC. - * @param __HANDLE__ ETH Handle - * @retval None - */ -#define __HAL_ETH_DMATXDESC_CRC_DISABLE(__HANDLE__) ((__HANDLE__)->TxDesc->Status |= ETH_DMATXDESC_DC) - -/** - * @brief Enables the DMA Tx Desc padding for frame shorter than 64 bytes. - * @param __HANDLE__ ETH Handle - * @retval None - */ -#define __HAL_ETH_DMATXDESC_SHORT_FRAME_PADDING_ENABLE(__HANDLE__) ((__HANDLE__)->TxDesc->Status &= ~ETH_DMATXDESC_DP) - -/** - * @brief Disables the DMA Tx Desc padding for frame shorter than 64 bytes. - * @param __HANDLE__ ETH Handle - * @retval None - */ -#define __HAL_ETH_DMATXDESC_SHORT_FRAME_PADDING_DISABLE(__HANDLE__) ((__HANDLE__)->TxDesc->Status |= ETH_DMATXDESC_DP) - -/** - * @brief Enables the specified ETHERNET MAC interrupts. - * @param __HANDLE__ ETH Handle - * @param __INTERRUPT__ specifies the ETHERNET MAC interrupt sources to be - * enabled or disabled. - * This parameter can be any combination of the following values: - * @arg ETH_MAC_IT_TST : Time stamp trigger interrupt - * @arg ETH_MAC_IT_PMT : PMT interrupt - * @retval None - */ -#define __HAL_ETH_MAC_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->MACIMR |= (__INTERRUPT__)) - -/** - * @brief Disables the specified ETHERNET MAC interrupts. - * @param __HANDLE__ ETH Handle - * @param __INTERRUPT__ specifies the ETHERNET MAC interrupt sources to be - * enabled or disabled. - * This parameter can be any combination of the following values: - * @arg ETH_MAC_IT_TST : Time stamp trigger interrupt - * @arg ETH_MAC_IT_PMT : PMT interrupt - * @retval None - */ -#define __HAL_ETH_MAC_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->MACIMR &= ~(__INTERRUPT__)) - -/** - * @brief Initiate a Pause Control Frame (Full-duplex only). - * @param __HANDLE__ ETH Handle - * @retval None - */ -#define __HAL_ETH_INITIATE_PAUSE_CONTROL_FRAME(__HANDLE__) ((__HANDLE__)->Instance->MACFCR |= ETH_MACFCR_FCBBPA) - -/** - * @brief Checks whether the ETHERNET flow control busy bit is set or not. - * @param __HANDLE__ ETH Handle - * @retval The new state of flow control busy status bit (SET or RESET). - */ -#define __HAL_ETH_GET_FLOW_CONTROL_BUSY_STATUS(__HANDLE__) (((__HANDLE__)->Instance->MACFCR & ETH_MACFCR_FCBBPA) == ETH_MACFCR_FCBBPA) - -/** - * @brief Enables the MAC Back Pressure operation activation (Half-duplex only). - * @param __HANDLE__ ETH Handle - * @retval None - */ -#define __HAL_ETH_BACK_PRESSURE_ACTIVATION_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->MACFCR |= ETH_MACFCR_FCBBPA) - -/** - * @brief Disables the MAC BackPressure operation activation (Half-duplex only). - * @param __HANDLE__ ETH Handle - * @retval None - */ -#define __HAL_ETH_BACK_PRESSURE_ACTIVATION_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->MACFCR &= ~ETH_MACFCR_FCBBPA) - -/** - * @brief Checks whether the specified ETHERNET MAC flag is set or not. - * @param __HANDLE__ ETH Handle - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg ETH_MAC_FLAG_TST : Time stamp trigger flag - * @arg ETH_MAC_FLAG_MMCT : MMC transmit flag - * @arg ETH_MAC_FLAG_MMCR : MMC receive flag - * @arg ETH_MAC_FLAG_MMC : MMC flag - * @arg ETH_MAC_FLAG_PMT : PMT flag - * @retval The state of ETHERNET MAC flag. - */ -#define __HAL_ETH_MAC_GET_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->MACSR &( __FLAG__)) == ( __FLAG__)) - -/** - * @brief Enables the specified ETHERNET DMA interrupts. - * @param __HANDLE__ ETH Handle - * @param __INTERRUPT__ specifies the ETHERNET DMA interrupt sources to be - * enabled @ref ETH_DMA_Interrupts - * @retval None - */ -#define __HAL_ETH_DMA_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->DMAIER |= (__INTERRUPT__)) - -/** - * @brief Disables the specified ETHERNET DMA interrupts. - * @param __HANDLE__ ETH Handle - * @param __INTERRUPT__ specifies the ETHERNET DMA interrupt sources to be - * disabled. @ref ETH_DMA_Interrupts - * @retval None - */ -#define __HAL_ETH_DMA_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->DMAIER &= ~(__INTERRUPT__)) - -/** - * @brief Clears the ETHERNET DMA IT pending bit. - * @param __HANDLE__ ETH Handle - * @param __INTERRUPT__ specifies the interrupt pending bit to clear. @ref ETH_DMA_Interrupts - * @retval None - */ -#define __HAL_ETH_DMA_CLEAR_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->DMASR =(__INTERRUPT__)) - -/** - * @brief Checks whether the specified ETHERNET DMA flag is set or not. -* @param __HANDLE__ ETH Handle - * @param __FLAG__ specifies the flag to check. @ref ETH_DMA_Flags - * @retval The new state of ETH_DMA_FLAG (SET or RESET). - */ -#define __HAL_ETH_DMA_GET_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->DMASR &( __FLAG__)) == ( __FLAG__)) - -/** - * @brief Checks whether the specified ETHERNET DMA flag is set or not. - * @param __HANDLE__ ETH Handle - * @param __FLAG__ specifies the flag to clear. @ref ETH_DMA_Flags - * @retval The new state of ETH_DMA_FLAG (SET or RESET). - */ -#define __HAL_ETH_DMA_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->DMASR = (__FLAG__)) - -/** - * @brief Checks whether the specified ETHERNET DMA overflow flag is set or not. - * @param __HANDLE__ ETH Handle - * @param __OVERFLOW__ specifies the DMA overflow flag to check. - * This parameter can be one of the following values: - * @arg ETH_DMA_OVERFLOW_RXFIFOCOUNTER : Overflow for FIFO Overflows Counter - * @arg ETH_DMA_OVERFLOW_MISSEDFRAMECOUNTER : Overflow for Buffer Unavailable Missed Frame Counter - * @retval The state of ETHERNET DMA overflow Flag (SET or RESET). - */ -#define __HAL_ETH_GET_DMA_OVERFLOW_STATUS(__HANDLE__, __OVERFLOW__) (((__HANDLE__)->Instance->DMAMFBOCR & (__OVERFLOW__)) == (__OVERFLOW__)) - -/** - * @brief Set the DMA Receive status watchdog timer register value - * @param __HANDLE__ ETH Handle - * @param __VALUE__ DMA Receive status watchdog timer register value - * @retval None - */ -#define __HAL_ETH_SET_RECEIVE_WATCHDOG_TIMER(__HANDLE__, __VALUE__) ((__HANDLE__)->Instance->DMARSWTR = (__VALUE__)) - -/** - * @brief Enables any unicast packet filtered by the MAC address - * recognition to be a wake-up frame. - * @param __HANDLE__ ETH Handle. - * @retval None - */ -#define __HAL_ETH_GLOBAL_UNICAST_WAKEUP_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->MACPMTCSR |= ETH_MACPMTCSR_GU) - -/** - * @brief Disables any unicast packet filtered by the MAC address - * recognition to be a wake-up frame. - * @param __HANDLE__ ETH Handle. - * @retval None - */ -#define __HAL_ETH_GLOBAL_UNICAST_WAKEUP_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->MACPMTCSR &= ~ETH_MACPMTCSR_GU) - -/** - * @brief Enables the MAC Wake-Up Frame Detection. - * @param __HANDLE__ ETH Handle. - * @retval None - */ -#define __HAL_ETH_WAKEUP_FRAME_DETECTION_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->MACPMTCSR |= ETH_MACPMTCSR_WFE) - -/** - * @brief Disables the MAC Wake-Up Frame Detection. - * @param __HANDLE__ ETH Handle. - * @retval None - */ -#define __HAL_ETH_WAKEUP_FRAME_DETECTION_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->MACPMTCSR &= ~ETH_MACPMTCSR_WFE) - -/** - * @brief Enables the MAC Magic Packet Detection. - * @param __HANDLE__ ETH Handle. - * @retval None - */ -#define __HAL_ETH_MAGIC_PACKET_DETECTION_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->MACPMTCSR |= ETH_MACPMTCSR_MPE) - -/** - * @brief Disables the MAC Magic Packet Detection. - * @param __HANDLE__ ETH Handle. - * @retval None - */ -#define __HAL_ETH_MAGIC_PACKET_DETECTION_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->MACPMTCSR &= ~ETH_MACPMTCSR_WFE) - -/** - * @brief Enables the MAC Power Down. - * @param __HANDLE__ ETH Handle - * @retval None - */ -#define __HAL_ETH_POWER_DOWN_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->MACPMTCSR |= ETH_MACPMTCSR_PD) - -/** - * @brief Disables the MAC Power Down. - * @param __HANDLE__ ETH Handle - * @retval None - */ -#define __HAL_ETH_POWER_DOWN_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->MACPMTCSR &= ~ETH_MACPMTCSR_PD) - -/** - * @brief Checks whether the specified ETHERNET PMT flag is set or not. - * @param __HANDLE__ ETH Handle. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg ETH_PMT_FLAG_WUFFRPR : Wake-Up Frame Filter Register Pointer Reset - * @arg ETH_PMT_FLAG_WUFR : Wake-Up Frame Received - * @arg ETH_PMT_FLAG_MPR : Magic Packet Received - * @retval The new state of ETHERNET PMT Flag (SET or RESET). - */ -#define __HAL_ETH_GET_PMT_FLAG_STATUS(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->MACPMTCSR &( __FLAG__)) == ( __FLAG__)) - -/** - * @brief Preset and Initialize the MMC counters to almost-full value: 0xFFFF_FFF0 (full - 16) - * @param __HANDLE__ ETH Handle. - * @retval None - */ -#define __HAL_ETH_MMC_COUNTER_FULL_PRESET(__HANDLE__) ((__HANDLE__)->Instance->MMCCR |= (ETH_MMCCR_MCFHP | ETH_MMCCR_MCP)) - -/** - * @brief Preset and Initialize the MMC counters to almost-half value: 0x7FFF_FFF0 (half - 16) - * @param __HANDLE__ ETH Handle. - * @retval None - */ -#define __HAL_ETH_MMC_COUNTER_HALF_PRESET(__HANDLE__) do{(__HANDLE__)->Instance->MMCCR &= ~ETH_MMCCR_MCFHP;\ - (__HANDLE__)->Instance->MMCCR |= ETH_MMCCR_MCP;} while (0) - -/** - * @brief Enables the MMC Counter Freeze. - * @param __HANDLE__ ETH Handle. - * @retval None - */ -#define __HAL_ETH_MMC_COUNTER_FREEZE_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->MMCCR |= ETH_MMCCR_MCF) - -/** - * @brief Disables the MMC Counter Freeze. - * @param __HANDLE__ ETH Handle. - * @retval None - */ -#define __HAL_ETH_MMC_COUNTER_FREEZE_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->MMCCR &= ~ETH_MMCCR_MCF) - -/** - * @brief Enables the MMC Reset On Read. - * @param __HANDLE__ ETH Handle. - * @retval None - */ -#define __HAL_ETH_ETH_MMC_RESET_ONREAD_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->MMCCR |= ETH_MMCCR_ROR) - -/** - * @brief Disables the MMC Reset On Read. - * @param __HANDLE__ ETH Handle. - * @retval None - */ -#define __HAL_ETH_ETH_MMC_RESET_ONREAD_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->MMCCR &= ~ETH_MMCCR_ROR) - -/** - * @brief Enables the MMC Counter Stop Rollover. - * @param __HANDLE__ ETH Handle. - * @retval None - */ -#define __HAL_ETH_ETH_MMC_COUNTER_ROLLOVER_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->MMCCR &= ~ETH_MMCCR_CSR) - -/** - * @brief Disables the MMC Counter Stop Rollover. - * @param __HANDLE__ ETH Handle. - * @retval None - */ -#define __HAL_ETH_ETH_MMC_COUNTER_ROLLOVER_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->MMCCR |= ETH_MMCCR_CSR) - -/** - * @brief Resets the MMC Counters. - * @param __HANDLE__ ETH Handle. - * @retval None - */ -#define __HAL_ETH_MMC_COUNTERS_RESET(__HANDLE__) ((__HANDLE__)->Instance->MMCCR |= ETH_MMCCR_CR) - -/** - * @brief Enables the specified ETHERNET MMC Rx interrupts. - * @param __HANDLE__ ETH Handle. - * @param __INTERRUPT__ specifies the ETHERNET MMC interrupt sources to be enabled or disabled. - * This parameter can be one of the following values: - * @arg ETH_MMC_IT_RGUF : When Rx good unicast frames counter reaches half the maximum value - * @arg ETH_MMC_IT_RFAE : When Rx alignment error counter reaches half the maximum value - * @arg ETH_MMC_IT_RFCE : When Rx crc error counter reaches half the maximum value - * @retval None - */ -#define __HAL_ETH_MMC_RX_IT_ENABLE(__HANDLE__, __INTERRUPT__) (__HANDLE__)->Instance->MMCRIMR &= ~((__INTERRUPT__) & 0xEFFFFFFFU) -/** - * @brief Disables the specified ETHERNET MMC Rx interrupts. - * @param __HANDLE__ ETH Handle. - * @param __INTERRUPT__ specifies the ETHERNET MMC interrupt sources to be enabled or disabled. - * This parameter can be one of the following values: - * @arg ETH_MMC_IT_RGUF : When Rx good unicast frames counter reaches half the maximum value - * @arg ETH_MMC_IT_RFAE : When Rx alignment error counter reaches half the maximum value - * @arg ETH_MMC_IT_RFCE : When Rx crc error counter reaches half the maximum value - * @retval None - */ -#define __HAL_ETH_MMC_RX_IT_DISABLE(__HANDLE__, __INTERRUPT__) (__HANDLE__)->Instance->MMCRIMR |= ((__INTERRUPT__) & 0xEFFFFFFFU) -/** - * @brief Enables the specified ETHERNET MMC Tx interrupts. - * @param __HANDLE__ ETH Handle. - * @param __INTERRUPT__ specifies the ETHERNET MMC interrupt sources to be enabled or disabled. - * This parameter can be one of the following values: - * @arg ETH_MMC_IT_TGF : When Tx good frame counter reaches half the maximum value - * @arg ETH_MMC_IT_TGFMSC: When Tx good multi col counter reaches half the maximum value - * @arg ETH_MMC_IT_TGFSC : When Tx good single col counter reaches half the maximum value - * @retval None - */ -#define __HAL_ETH_MMC_TX_IT_ENABLE(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->MMCRIMR &= ~ (__INTERRUPT__)) - -/** - * @brief Disables the specified ETHERNET MMC Tx interrupts. - * @param __HANDLE__ ETH Handle. - * @param __INTERRUPT__ specifies the ETHERNET MMC interrupt sources to be enabled or disabled. - * This parameter can be one of the following values: - * @arg ETH_MMC_IT_TGF : When Tx good frame counter reaches half the maximum value - * @arg ETH_MMC_IT_TGFMSC: When Tx good multi col counter reaches half the maximum value - * @arg ETH_MMC_IT_TGFSC : When Tx good single col counter reaches half the maximum value - * @retval None - */ -#define __HAL_ETH_MMC_TX_IT_DISABLE(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->MMCRIMR |= (__INTERRUPT__)) - -/** - * @brief Enables the ETH External interrupt line. - * @retval None - */ -#define __HAL_ETH_WAKEUP_EXTI_ENABLE_IT() EXTI->IMR |= (ETH_EXTI_LINE_WAKEUP) - -/** - * @brief Disables the ETH External interrupt line. - * @retval None - */ -#define __HAL_ETH_WAKEUP_EXTI_DISABLE_IT() EXTI->IMR &= ~(ETH_EXTI_LINE_WAKEUP) - -/** - * @brief Enable event on ETH External event line. - * @retval None. - */ -#define __HAL_ETH_WAKEUP_EXTI_ENABLE_EVENT() EXTI->EMR |= (ETH_EXTI_LINE_WAKEUP) - -/** - * @brief Disable event on ETH External event line - * @retval None. - */ -#define __HAL_ETH_WAKEUP_EXTI_DISABLE_EVENT() EXTI->EMR &= ~(ETH_EXTI_LINE_WAKEUP) - -/** - * @brief Get flag of the ETH External interrupt line. - * @retval None - */ -#define __HAL_ETH_WAKEUP_EXTI_GET_FLAG() EXTI->PR & (ETH_EXTI_LINE_WAKEUP) - -/** - * @brief Clear flag of the ETH External interrupt line. - * @retval None - */ -#define __HAL_ETH_WAKEUP_EXTI_CLEAR_FLAG() EXTI->PR = (ETH_EXTI_LINE_WAKEUP) - -/** - * @brief Enables rising edge trigger to the ETH External interrupt line. - * @retval None - */ -#define __HAL_ETH_WAKEUP_EXTI_ENABLE_RISING_EDGE_TRIGGER() EXTI->RTSR |= ETH_EXTI_LINE_WAKEUP - -/** - * @brief Disables the rising edge trigger to the ETH External interrupt line. - * @retval None - */ -#define __HAL_ETH_WAKEUP_EXTI_DISABLE_RISING_EDGE_TRIGGER() EXTI->RTSR &= ~(ETH_EXTI_LINE_WAKEUP) - -/** - * @brief Enables falling edge trigger to the ETH External interrupt line. - * @retval None - */ -#define __HAL_ETH_WAKEUP_EXTI_ENABLE_FALLING_EDGE_TRIGGER() EXTI->FTSR |= (ETH_EXTI_LINE_WAKEUP) - -/** - * @brief Disables falling edge trigger to the ETH External interrupt line. - * @retval None - */ -#define __HAL_ETH_WAKEUP_EXTI_DISABLE_FALLING_EDGE_TRIGGER() EXTI->FTSR &= ~(ETH_EXTI_LINE_WAKEUP) - -/** - * @brief Enables rising/falling edge trigger to the ETH External interrupt line. - * @retval None - */ -#define __HAL_ETH_WAKEUP_EXTI_ENABLE_FALLINGRISING_TRIGGER() do{EXTI->RTSR |= ETH_EXTI_LINE_WAKEUP;\ - EXTI->FTSR |= ETH_EXTI_LINE_WAKEUP;\ - }while(0U) - -/** - * @brief Disables rising/falling edge trigger to the ETH External interrupt line. - * @retval None - */ -#define __HAL_ETH_WAKEUP_EXTI_DISABLE_FALLINGRISING_TRIGGER() do{EXTI->RTSR &= ~(ETH_EXTI_LINE_WAKEUP);\ - EXTI->FTSR &= ~(ETH_EXTI_LINE_WAKEUP);\ - }while(0U) - -/** - * @brief Generate a Software interrupt on selected EXTI line. - * @retval None. - */ -#define __HAL_ETH_WAKEUP_EXTI_GENERATE_SWIT() EXTI->SWIER|= ETH_EXTI_LINE_WAKEUP - -/** - * @} - */ -/* Exported functions --------------------------------------------------------*/ - -/** @addtogroup ETH_Exported_Functions - * @{ - */ - -/* Initialization and de-initialization functions ****************************/ - -/** @addtogroup ETH_Exported_Functions_Group1 - * @{ - */ -HAL_StatusTypeDef HAL_ETH_Init(ETH_HandleTypeDef *heth); -HAL_StatusTypeDef HAL_ETH_DeInit(ETH_HandleTypeDef *heth); -void HAL_ETH_MspInit(ETH_HandleTypeDef *heth); -void HAL_ETH_MspDeInit(ETH_HandleTypeDef *heth); -HAL_StatusTypeDef HAL_ETH_DMATxDescListInit(ETH_HandleTypeDef *heth, ETH_DMADescTypeDef *DMATxDescTab, uint8_t* TxBuff, uint32_t TxBuffCount); -HAL_StatusTypeDef HAL_ETH_DMARxDescListInit(ETH_HandleTypeDef *heth, ETH_DMADescTypeDef *DMARxDescTab, uint8_t *RxBuff, uint32_t RxBuffCount); -/* Callbacks Register/UnRegister functions ***********************************/ -#if (USE_HAL_ETH_REGISTER_CALLBACKS == 1) -HAL_StatusTypeDef HAL_ETH_RegisterCallback(ETH_HandleTypeDef *heth, HAL_ETH_CallbackIDTypeDef CallbackID, pETH_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_ETH_UnRegisterCallback(ETH_HandleTypeDef *heth, HAL_ETH_CallbackIDTypeDef CallbackID); -#endif /* USE_HAL_ETH_REGISTER_CALLBACKS */ - -/** - * @} - */ -/* IO operation functions ****************************************************/ - -/** @addtogroup ETH_Exported_Functions_Group2 - * @{ - */ -HAL_StatusTypeDef HAL_ETH_TransmitFrame(ETH_HandleTypeDef *heth, uint32_t FrameLength); -HAL_StatusTypeDef HAL_ETH_GetReceivedFrame(ETH_HandleTypeDef *heth); -/* Communication with PHY functions*/ -HAL_StatusTypeDef HAL_ETH_ReadPHYRegister(ETH_HandleTypeDef *heth, uint16_t PHYReg, uint32_t *RegValue); -HAL_StatusTypeDef HAL_ETH_WritePHYRegister(ETH_HandleTypeDef *heth, uint16_t PHYReg, uint32_t RegValue); -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_ETH_GetReceivedFrame_IT(ETH_HandleTypeDef *heth); -void HAL_ETH_IRQHandler(ETH_HandleTypeDef *heth); -/* Callback in non blocking modes (Interrupt) */ -void HAL_ETH_TxCpltCallback(ETH_HandleTypeDef *heth); -void HAL_ETH_RxCpltCallback(ETH_HandleTypeDef *heth); -void HAL_ETH_ErrorCallback(ETH_HandleTypeDef *heth); -/** - * @} - */ - -/* Peripheral Control functions **********************************************/ - -/** @addtogroup ETH_Exported_Functions_Group3 - * @{ - */ - -HAL_StatusTypeDef HAL_ETH_Start(ETH_HandleTypeDef *heth); -HAL_StatusTypeDef HAL_ETH_Stop(ETH_HandleTypeDef *heth); -HAL_StatusTypeDef HAL_ETH_ConfigMAC(ETH_HandleTypeDef *heth, ETH_MACInitTypeDef *macconf); -HAL_StatusTypeDef HAL_ETH_ConfigDMA(ETH_HandleTypeDef *heth, ETH_DMAInitTypeDef *dmaconf); -/** - * @} - */ - -/* Peripheral State functions ************************************************/ - -/** @addtogroup ETH_Exported_Functions_Group4 - * @{ - */ -HAL_ETH_StateTypeDef HAL_ETH_GetState(ETH_HandleTypeDef *heth); -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx ||\ - STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_ETH_H */ - - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_exti.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_exti.h deleted file mode 100644 index 8570112..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_exti.h +++ /dev/null @@ -1,368 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_exti.h - * @author MCD Application Team - * @brief Header file of EXTI HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2018 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32f4xx_HAL_EXTI_H -#define STM32f4xx_HAL_EXTI_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup EXTI EXTI - * @brief EXTI HAL module driver - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ - -/** @defgroup EXTI_Exported_Types EXTI Exported Types - * @{ - */ -typedef enum -{ - HAL_EXTI_COMMON_CB_ID = 0x00U -} EXTI_CallbackIDTypeDef; - -/** - * @brief EXTI Handle structure definition - */ -typedef struct -{ - uint32_t Line; /*!< Exti line number */ - void (* PendingCallback)(void); /*!< Exti pending callback */ -} EXTI_HandleTypeDef; - -/** - * @brief EXTI Configuration structure definition - */ -typedef struct -{ - uint32_t Line; /*!< The Exti line to be configured. This parameter - can be a value of @ref EXTI_Line */ - uint32_t Mode; /*!< The Exit Mode to be configured for a core. - This parameter can be a combination of @ref EXTI_Mode */ - uint32_t Trigger; /*!< The Exti Trigger to be configured. This parameter - can be a value of @ref EXTI_Trigger */ - uint32_t GPIOSel; /*!< The Exti GPIO multiplexer selection to be configured. - This parameter is only possible for line 0 to 15. It - can be a value of @ref EXTI_GPIOSel */ -} EXTI_ConfigTypeDef; - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup EXTI_Exported_Constants EXTI Exported Constants - * @{ - */ - -/** @defgroup EXTI_Line EXTI Line - * @{ - */ -#define EXTI_LINE_0 (EXTI_GPIO | 0x00u) /*!< External interrupt line 0 */ -#define EXTI_LINE_1 (EXTI_GPIO | 0x01u) /*!< External interrupt line 1 */ -#define EXTI_LINE_2 (EXTI_GPIO | 0x02u) /*!< External interrupt line 2 */ -#define EXTI_LINE_3 (EXTI_GPIO | 0x03u) /*!< External interrupt line 3 */ -#define EXTI_LINE_4 (EXTI_GPIO | 0x04u) /*!< External interrupt line 4 */ -#define EXTI_LINE_5 (EXTI_GPIO | 0x05u) /*!< External interrupt line 5 */ -#define EXTI_LINE_6 (EXTI_GPIO | 0x06u) /*!< External interrupt line 6 */ -#define EXTI_LINE_7 (EXTI_GPIO | 0x07u) /*!< External interrupt line 7 */ -#define EXTI_LINE_8 (EXTI_GPIO | 0x08u) /*!< External interrupt line 8 */ -#define EXTI_LINE_9 (EXTI_GPIO | 0x09u) /*!< External interrupt line 9 */ -#define EXTI_LINE_10 (EXTI_GPIO | 0x0Au) /*!< External interrupt line 10 */ -#define EXTI_LINE_11 (EXTI_GPIO | 0x0Bu) /*!< External interrupt line 11 */ -#define EXTI_LINE_12 (EXTI_GPIO | 0x0Cu) /*!< External interrupt line 12 */ -#define EXTI_LINE_13 (EXTI_GPIO | 0x0Du) /*!< External interrupt line 13 */ -#define EXTI_LINE_14 (EXTI_GPIO | 0x0Eu) /*!< External interrupt line 14 */ -#define EXTI_LINE_15 (EXTI_GPIO | 0x0Fu) /*!< External interrupt line 15 */ -#define EXTI_LINE_16 (EXTI_CONFIG | 0x10u) /*!< External interrupt line 16 Connected to the PVD Output */ -#define EXTI_LINE_17 (EXTI_CONFIG | 0x11u) /*!< External interrupt line 17 Connected to the RTC Alarm event */ -#if defined(EXTI_IMR_IM18) -#define EXTI_LINE_18 (EXTI_CONFIG | 0x12u) /*!< External interrupt line 18 Connected to the USB OTG FS Wakeup from suspend event */ -#else -#define EXTI_LINE_18 (EXTI_RESERVED | 0x12u) /*!< No interrupt supported in this line */ -#endif /* EXTI_IMR_IM18 */ -#if defined(EXTI_IMR_IM19) -#define EXTI_LINE_19 (EXTI_CONFIG | 0x13u) /*!< External interrupt line 19 Connected to the Ethernet Wakeup event */ -#else -#define EXTI_LINE_19 (EXTI_RESERVED | 0x13u) /*!< No interrupt supported in this line */ -#endif /* EXTI_IMR_IM19 */ -#if defined(EXTI_IMR_IM20) -#define EXTI_LINE_20 (EXTI_CONFIG | 0x14u) /*!< External interrupt line 20 Connected to the USB OTG HS (configured in FS) Wakeup event */ -#else -#define EXTI_LINE_20 (EXTI_RESERVED | 0x14u) /*!< No interrupt supported in this line */ -#endif /* EXTI_IMR_IM20 */ -#define EXTI_LINE_21 (EXTI_CONFIG | 0x15u) /*!< External interrupt line 21 Connected to the RTC Tamper and Time Stamp events */ -#define EXTI_LINE_22 (EXTI_CONFIG | 0x16u) /*!< External interrupt line 22 Connected to the RTC Wakeup event */ -#if defined(EXTI_IMR_IM23) -#define EXTI_LINE_23 (EXTI_CONFIG | 0x17u) /*!< External interrupt line 23 Connected to the LPTIM1 asynchronous event */ -#endif /* EXTI_IMR_IM23 */ - -/** - * @} - */ - -/** @defgroup EXTI_Mode EXTI Mode - * @{ - */ -#define EXTI_MODE_NONE 0x00000000u -#define EXTI_MODE_INTERRUPT 0x00000001u -#define EXTI_MODE_EVENT 0x00000002u -/** - * @} - */ - -/** @defgroup EXTI_Trigger EXTI Trigger - * @{ - */ - -#define EXTI_TRIGGER_NONE 0x00000000u -#define EXTI_TRIGGER_RISING 0x00000001u -#define EXTI_TRIGGER_FALLING 0x00000002u -#define EXTI_TRIGGER_RISING_FALLING (EXTI_TRIGGER_RISING | EXTI_TRIGGER_FALLING) -/** - * @} - */ - -/** @defgroup EXTI_GPIOSel EXTI GPIOSel - * @brief - * @{ - */ -#define EXTI_GPIOA 0x00000000u -#define EXTI_GPIOB 0x00000001u -#define EXTI_GPIOC 0x00000002u -#if defined (GPIOD) -#define EXTI_GPIOD 0x00000003u -#endif /* GPIOD */ -#if defined (GPIOE) -#define EXTI_GPIOE 0x00000004u -#endif /* GPIOE */ -#if defined (GPIOF) -#define EXTI_GPIOF 0x00000005u -#endif /* GPIOF */ -#if defined (GPIOG) -#define EXTI_GPIOG 0x00000006u -#endif /* GPIOG */ -#if defined (GPIOH) -#define EXTI_GPIOH 0x00000007u -#endif /* GPIOH */ -#if defined (GPIOI) -#define EXTI_GPIOI 0x00000008u -#endif /* GPIOI */ -#if defined (GPIOJ) -#define EXTI_GPIOJ 0x00000009u -#endif /* GPIOJ */ -#if defined (GPIOK) -#define EXTI_GPIOK 0x0000000Au -#endif /* GPIOK */ - -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup EXTI_Exported_Macros EXTI Exported Macros - * @{ - */ - -/** - * @} - */ - -/* Private constants --------------------------------------------------------*/ -/** @defgroup EXTI_Private_Constants EXTI Private Constants - * @{ - */ -/** - * @brief EXTI Line property definition - */ -#define EXTI_PROPERTY_SHIFT 24u -#define EXTI_CONFIG (0x02uL << EXTI_PROPERTY_SHIFT) -#define EXTI_GPIO ((0x04uL << EXTI_PROPERTY_SHIFT) | EXTI_CONFIG) -#define EXTI_RESERVED (0x08uL << EXTI_PROPERTY_SHIFT) -#define EXTI_PROPERTY_MASK (EXTI_CONFIG | EXTI_GPIO) - -/** - * @brief EXTI bit usage - */ -#define EXTI_PIN_MASK 0x0000001Fu - -/** - * @brief EXTI Mask for interrupt & event mode - */ -#define EXTI_MODE_MASK (EXTI_MODE_EVENT | EXTI_MODE_INTERRUPT) - -/** - * @brief EXTI Mask for trigger possibilities - */ -#define EXTI_TRIGGER_MASK (EXTI_TRIGGER_RISING | EXTI_TRIGGER_FALLING) - -/** - * @brief EXTI Line number - */ -#if defined(EXTI_IMR_IM23) -#define EXTI_LINE_NB 24UL -#else -#define EXTI_LINE_NB 23UL -#endif /* EXTI_IMR_IM23 */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup EXTI_Private_Macros EXTI Private Macros - * @{ - */ -#define IS_EXTI_LINE(__EXTI_LINE__) ((((__EXTI_LINE__) & ~(EXTI_PROPERTY_MASK | EXTI_PIN_MASK)) == 0x00u) && \ - ((((__EXTI_LINE__) & EXTI_PROPERTY_MASK) == EXTI_CONFIG) || \ - (((__EXTI_LINE__) & EXTI_PROPERTY_MASK) == EXTI_GPIO)) && \ - (((__EXTI_LINE__) & EXTI_PIN_MASK) < EXTI_LINE_NB)) - -#define IS_EXTI_MODE(__EXTI_LINE__) ((((__EXTI_LINE__) & EXTI_MODE_MASK) != 0x00u) && \ - (((__EXTI_LINE__) & ~EXTI_MODE_MASK) == 0x00u)) - -#define IS_EXTI_TRIGGER(__EXTI_LINE__) (((__EXTI_LINE__) & ~EXTI_TRIGGER_MASK) == 0x00u) - -#define IS_EXTI_PENDING_EDGE(__EXTI_LINE__) ((__EXTI_LINE__) == EXTI_TRIGGER_RISING_FALLING) - -#define IS_EXTI_CONFIG_LINE(__EXTI_LINE__) (((__EXTI_LINE__) & EXTI_CONFIG) != 0x00u) - -#if !defined (GPIOD) -#define IS_EXTI_GPIO_PORT(__PORT__) (((__PORT__) == EXTI_GPIOA) || \ - ((__PORT__) == EXTI_GPIOB) || \ - ((__PORT__) == EXTI_GPIOC) || \ - ((__PORT__) == EXTI_GPIOH)) -#elif !defined (GPIOE) -#define IS_EXTI_GPIO_PORT(__PORT__) (((__PORT__) == EXTI_GPIOA) || \ - ((__PORT__) == EXTI_GPIOB) || \ - ((__PORT__) == EXTI_GPIOC) || \ - ((__PORT__) == EXTI_GPIOD) || \ - ((__PORT__) == EXTI_GPIOH)) -#elif !defined (GPIOF) -#define IS_EXTI_GPIO_PORT(__PORT__) (((__PORT__) == EXTI_GPIOA) || \ - ((__PORT__) == EXTI_GPIOB) || \ - ((__PORT__) == EXTI_GPIOC) || \ - ((__PORT__) == EXTI_GPIOD) || \ - ((__PORT__) == EXTI_GPIOE) || \ - ((__PORT__) == EXTI_GPIOH)) -#elif !defined (GPIOI) -#define IS_EXTI_GPIO_PORT(__PORT__) (((__PORT__) == EXTI_GPIOA) || \ - ((__PORT__) == EXTI_GPIOB) || \ - ((__PORT__) == EXTI_GPIOC) || \ - ((__PORT__) == EXTI_GPIOD) || \ - ((__PORT__) == EXTI_GPIOE) || \ - ((__PORT__) == EXTI_GPIOF) || \ - ((__PORT__) == EXTI_GPIOG) || \ - ((__PORT__) == EXTI_GPIOH)) -#elif !defined (GPIOJ) -#define IS_EXTI_GPIO_PORT(__PORT__) (((__PORT__) == EXTI_GPIOA) || \ - ((__PORT__) == EXTI_GPIOB) || \ - ((__PORT__) == EXTI_GPIOC) || \ - ((__PORT__) == EXTI_GPIOD) || \ - ((__PORT__) == EXTI_GPIOE) || \ - ((__PORT__) == EXTI_GPIOF) || \ - ((__PORT__) == EXTI_GPIOG) || \ - ((__PORT__) == EXTI_GPIOH) || \ - ((__PORT__) == EXTI_GPIOI)) -#else -#define IS_EXTI_GPIO_PORT(__PORT__) (((__PORT__) == EXTI_GPIOA) || \ - ((__PORT__) == EXTI_GPIOB) || \ - ((__PORT__) == EXTI_GPIOC) || \ - ((__PORT__) == EXTI_GPIOD) || \ - ((__PORT__) == EXTI_GPIOE) || \ - ((__PORT__) == EXTI_GPIOF) || \ - ((__PORT__) == EXTI_GPIOG) || \ - ((__PORT__) == EXTI_GPIOH) || \ - ((__PORT__) == EXTI_GPIOI) || \ - ((__PORT__) == EXTI_GPIOJ) || \ - ((__PORT__) == EXTI_GPIOK)) -#endif /* GPIOD */ - -#define IS_EXTI_GPIO_PIN(__PIN__) ((__PIN__) < 16U) -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup EXTI_Exported_Functions EXTI Exported Functions - * @brief EXTI Exported Functions - * @{ - */ - -/** @defgroup EXTI_Exported_Functions_Group1 Configuration functions - * @brief Configuration functions - * @{ - */ -/* Configuration functions ****************************************************/ -HAL_StatusTypeDef HAL_EXTI_SetConfigLine(EXTI_HandleTypeDef *hexti, EXTI_ConfigTypeDef *pExtiConfig); -HAL_StatusTypeDef HAL_EXTI_GetConfigLine(EXTI_HandleTypeDef *hexti, EXTI_ConfigTypeDef *pExtiConfig); -HAL_StatusTypeDef HAL_EXTI_ClearConfigLine(EXTI_HandleTypeDef *hexti); -HAL_StatusTypeDef HAL_EXTI_RegisterCallback(EXTI_HandleTypeDef *hexti, EXTI_CallbackIDTypeDef CallbackID, void (*pPendingCbfn)(void)); -HAL_StatusTypeDef HAL_EXTI_GetHandle(EXTI_HandleTypeDef *hexti, uint32_t ExtiLine); -/** - * @} - */ - -/** @defgroup EXTI_Exported_Functions_Group2 IO operation functions - * @brief IO operation functions - * @{ - */ -/* IO operation functions *****************************************************/ -void HAL_EXTI_IRQHandler(EXTI_HandleTypeDef *hexti); -uint32_t HAL_EXTI_GetPending(EXTI_HandleTypeDef *hexti, uint32_t Edge); -void HAL_EXTI_ClearPending(EXTI_HandleTypeDef *hexti, uint32_t Edge); -void HAL_EXTI_GenerateSWI(EXTI_HandleTypeDef *hexti); - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32f4xx_HAL_EXTI_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash.h deleted file mode 100644 index b817f63..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash.h +++ /dev/null @@ -1,428 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_flash.h - * @author MCD Application Team - * @brief Header file of FLASH HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_FLASH_H -#define __STM32F4xx_HAL_FLASH_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup FLASH - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup FLASH_Exported_Types FLASH Exported Types - * @{ - */ - -/** - * @brief FLASH Procedure structure definition - */ -typedef enum -{ - FLASH_PROC_NONE = 0U, - FLASH_PROC_SECTERASE, - FLASH_PROC_MASSERASE, - FLASH_PROC_PROGRAM -} FLASH_ProcedureTypeDef; - -/** - * @brief FLASH handle Structure definition - */ -typedef struct -{ - __IO FLASH_ProcedureTypeDef ProcedureOnGoing; /*Internal variable to indicate which procedure is ongoing or not in IT context*/ - - __IO uint32_t NbSectorsToErase; /*Internal variable to save the remaining sectors to erase in IT context*/ - - __IO uint8_t VoltageForErase; /*Internal variable to provide voltage range selected by user in IT context*/ - - __IO uint32_t Sector; /*Internal variable to define the current sector which is erasing*/ - - __IO uint32_t Bank; /*Internal variable to save current bank selected during mass erase*/ - - __IO uint32_t Address; /*Internal variable to save address selected for program*/ - - HAL_LockTypeDef Lock; /* FLASH locking object */ - - __IO uint32_t ErrorCode; /* FLASH error code */ - -}FLASH_ProcessTypeDef; - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup FLASH_Exported_Constants FLASH Exported Constants - * @{ - */ -/** @defgroup FLASH_Error_Code FLASH Error Code - * @brief FLASH Error Code - * @{ - */ -#define HAL_FLASH_ERROR_NONE 0x00000000U /*!< No error */ -#define HAL_FLASH_ERROR_RD 0x00000001U /*!< Read Protection error */ -#define HAL_FLASH_ERROR_PGS 0x00000002U /*!< Programming Sequence error */ -#define HAL_FLASH_ERROR_PGP 0x00000004U /*!< Programming Parallelism error */ -#define HAL_FLASH_ERROR_PGA 0x00000008U /*!< Programming Alignment error */ -#define HAL_FLASH_ERROR_WRP 0x00000010U /*!< Write protection error */ -#define HAL_FLASH_ERROR_OPERATION 0x00000020U /*!< Operation Error */ -/** - * @} - */ - -/** @defgroup FLASH_Type_Program FLASH Type Program - * @{ - */ -#define FLASH_TYPEPROGRAM_BYTE 0x00000000U /*!< Program byte (8-bit) at a specified address */ -#define FLASH_TYPEPROGRAM_HALFWORD 0x00000001U /*!< Program a half-word (16-bit) at a specified address */ -#define FLASH_TYPEPROGRAM_WORD 0x00000002U /*!< Program a word (32-bit) at a specified address */ -#define FLASH_TYPEPROGRAM_DOUBLEWORD 0x00000003U /*!< Program a double word (64-bit) at a specified address */ -/** - * @} - */ - -/** @defgroup FLASH_Flag_definition FLASH Flag definition - * @brief Flag definition - * @{ - */ -#define FLASH_FLAG_EOP FLASH_SR_EOP /*!< FLASH End of Operation flag */ -#define FLASH_FLAG_OPERR FLASH_SR_SOP /*!< FLASH operation Error flag */ -#define FLASH_FLAG_WRPERR FLASH_SR_WRPERR /*!< FLASH Write protected error flag */ -#define FLASH_FLAG_PGAERR FLASH_SR_PGAERR /*!< FLASH Programming Alignment error flag */ -#define FLASH_FLAG_PGPERR FLASH_SR_PGPERR /*!< FLASH Programming Parallelism error flag */ -#define FLASH_FLAG_PGSERR FLASH_SR_PGSERR /*!< FLASH Programming Sequence error flag */ -#if defined(FLASH_SR_RDERR) -#define FLASH_FLAG_RDERR FLASH_SR_RDERR /*!< Read Protection error flag (PCROP) */ -#endif /* FLASH_SR_RDERR */ -#define FLASH_FLAG_BSY FLASH_SR_BSY /*!< FLASH Busy flag */ -/** - * @} - */ - -/** @defgroup FLASH_Interrupt_definition FLASH Interrupt definition - * @brief FLASH Interrupt definition - * @{ - */ -#define FLASH_IT_EOP FLASH_CR_EOPIE /*!< End of FLASH Operation Interrupt source */ -#define FLASH_IT_ERR 0x02000000U /*!< Error Interrupt source */ -/** - * @} - */ - -/** @defgroup FLASH_Program_Parallelism FLASH Program Parallelism - * @{ - */ -#define FLASH_PSIZE_BYTE 0x00000000U -#define FLASH_PSIZE_HALF_WORD 0x00000100U -#define FLASH_PSIZE_WORD 0x00000200U -#define FLASH_PSIZE_DOUBLE_WORD 0x00000300U -#define CR_PSIZE_MASK 0xFFFFFCFFU -/** - * @} - */ - -/** @defgroup FLASH_Keys FLASH Keys - * @{ - */ -#define RDP_KEY ((uint16_t)0x00A5) -#define FLASH_KEY1 0x45670123U -#define FLASH_KEY2 0xCDEF89ABU -#define FLASH_OPT_KEY1 0x08192A3BU -#define FLASH_OPT_KEY2 0x4C5D6E7FU -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup FLASH_Exported_Macros FLASH Exported Macros - * @{ - */ -/** - * @brief Set the FLASH Latency. - * @param __LATENCY__ FLASH Latency - * The value of this parameter depend on device used within the same series - * @retval none - */ -#define __HAL_FLASH_SET_LATENCY(__LATENCY__) (*(__IO uint8_t *)ACR_BYTE0_ADDRESS = (uint8_t)(__LATENCY__)) - -/** - * @brief Get the FLASH Latency. - * @retval FLASH Latency - * The value of this parameter depend on device used within the same series - */ -#define __HAL_FLASH_GET_LATENCY() (READ_BIT((FLASH->ACR), FLASH_ACR_LATENCY)) - -/** - * @brief Enable the FLASH prefetch buffer. - * @retval none - */ -#define __HAL_FLASH_PREFETCH_BUFFER_ENABLE() (FLASH->ACR |= FLASH_ACR_PRFTEN) - -/** - * @brief Disable the FLASH prefetch buffer. - * @retval none - */ -#define __HAL_FLASH_PREFETCH_BUFFER_DISABLE() (FLASH->ACR &= (~FLASH_ACR_PRFTEN)) - -/** - * @brief Enable the FLASH instruction cache. - * @retval none - */ -#define __HAL_FLASH_INSTRUCTION_CACHE_ENABLE() (FLASH->ACR |= FLASH_ACR_ICEN) - -/** - * @brief Disable the FLASH instruction cache. - * @retval none - */ -#define __HAL_FLASH_INSTRUCTION_CACHE_DISABLE() (FLASH->ACR &= (~FLASH_ACR_ICEN)) - -/** - * @brief Enable the FLASH data cache. - * @retval none - */ -#define __HAL_FLASH_DATA_CACHE_ENABLE() (FLASH->ACR |= FLASH_ACR_DCEN) - -/** - * @brief Disable the FLASH data cache. - * @retval none - */ -#define __HAL_FLASH_DATA_CACHE_DISABLE() (FLASH->ACR &= (~FLASH_ACR_DCEN)) - -/** - * @brief Resets the FLASH instruction Cache. - * @note This function must be used only when the Instruction Cache is disabled. - * @retval None - */ -#define __HAL_FLASH_INSTRUCTION_CACHE_RESET() do {FLASH->ACR |= FLASH_ACR_ICRST; \ - FLASH->ACR &= ~FLASH_ACR_ICRST; \ - }while(0U) - -/** - * @brief Resets the FLASH data Cache. - * @note This function must be used only when the data Cache is disabled. - * @retval None - */ -#define __HAL_FLASH_DATA_CACHE_RESET() do {FLASH->ACR |= FLASH_ACR_DCRST; \ - FLASH->ACR &= ~FLASH_ACR_DCRST; \ - }while(0U) -/** - * @brief Enable the specified FLASH interrupt. - * @param __INTERRUPT__ FLASH interrupt - * This parameter can be any combination of the following values: - * @arg FLASH_IT_EOP: End of FLASH Operation Interrupt - * @arg FLASH_IT_ERR: Error Interrupt - * @retval none - */ -#define __HAL_FLASH_ENABLE_IT(__INTERRUPT__) (FLASH->CR |= (__INTERRUPT__)) - -/** - * @brief Disable the specified FLASH interrupt. - * @param __INTERRUPT__ FLASH interrupt - * This parameter can be any combination of the following values: - * @arg FLASH_IT_EOP: End of FLASH Operation Interrupt - * @arg FLASH_IT_ERR: Error Interrupt - * @retval none - */ -#define __HAL_FLASH_DISABLE_IT(__INTERRUPT__) (FLASH->CR &= ~(uint32_t)(__INTERRUPT__)) - -/** - * @brief Get the specified FLASH flag status. - * @param __FLAG__ specifies the FLASH flags to check. - * This parameter can be any combination of the following values: - * @arg FLASH_FLAG_EOP : FLASH End of Operation flag - * @arg FLASH_FLAG_OPERR : FLASH operation Error flag - * @arg FLASH_FLAG_WRPERR: FLASH Write protected error flag - * @arg FLASH_FLAG_PGAERR: FLASH Programming Alignment error flag - * @arg FLASH_FLAG_PGPERR: FLASH Programming Parallelism error flag - * @arg FLASH_FLAG_PGSERR: FLASH Programming Sequence error flag - * @arg FLASH_FLAG_RDERR : FLASH Read Protection error flag (PCROP) (*) - * @arg FLASH_FLAG_BSY : FLASH Busy flag - * (*) FLASH_FLAG_RDERR is not available for STM32F405xx/407xx/415xx/417xx devices - * @retval The new state of __FLAG__ (SET or RESET). - */ -#define __HAL_FLASH_GET_FLAG(__FLAG__) ((FLASH->SR & (__FLAG__))) - -/** - * @brief Clear the specified FLASH flags. - * @param __FLAG__ specifies the FLASH flags to clear. - * This parameter can be any combination of the following values: - * @arg FLASH_FLAG_EOP : FLASH End of Operation flag - * @arg FLASH_FLAG_OPERR : FLASH operation Error flag - * @arg FLASH_FLAG_WRPERR: FLASH Write protected error flag - * @arg FLASH_FLAG_PGAERR: FLASH Programming Alignment error flag - * @arg FLASH_FLAG_PGPERR: FLASH Programming Parallelism error flag - * @arg FLASH_FLAG_PGSERR: FLASH Programming Sequence error flag - * @arg FLASH_FLAG_RDERR : FLASH Read Protection error flag (PCROP) (*) - * (*) FLASH_FLAG_RDERR is not available for STM32F405xx/407xx/415xx/417xx devices - * @retval none - */ -#define __HAL_FLASH_CLEAR_FLAG(__FLAG__) (FLASH->SR = (__FLAG__)) -/** - * @} - */ - -/* Include FLASH HAL Extension module */ -#include "stm32f4xx_hal_flash_ex.h" -#include "stm32f4xx_hal_flash_ramfunc.h" - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup FLASH_Exported_Functions - * @{ - */ -/** @addtogroup FLASH_Exported_Functions_Group1 - * @{ - */ -/* Program operation functions ***********************************************/ -HAL_StatusTypeDef HAL_FLASH_Program(uint32_t TypeProgram, uint32_t Address, uint64_t Data); -HAL_StatusTypeDef HAL_FLASH_Program_IT(uint32_t TypeProgram, uint32_t Address, uint64_t Data); -/* FLASH IRQ handler method */ -void HAL_FLASH_IRQHandler(void); -/* Callbacks in non blocking modes */ -void HAL_FLASH_EndOfOperationCallback(uint32_t ReturnValue); -void HAL_FLASH_OperationErrorCallback(uint32_t ReturnValue); -/** - * @} - */ - -/** @addtogroup FLASH_Exported_Functions_Group2 - * @{ - */ -/* Peripheral Control functions **********************************************/ -HAL_StatusTypeDef HAL_FLASH_Unlock(void); -HAL_StatusTypeDef HAL_FLASH_Lock(void); -HAL_StatusTypeDef HAL_FLASH_OB_Unlock(void); -HAL_StatusTypeDef HAL_FLASH_OB_Lock(void); -/* Option bytes control */ -HAL_StatusTypeDef HAL_FLASH_OB_Launch(void); -/** - * @} - */ - -/** @addtogroup FLASH_Exported_Functions_Group3 - * @{ - */ -/* Peripheral State functions ************************************************/ -uint32_t HAL_FLASH_GetError(void); -HAL_StatusTypeDef FLASH_WaitForLastOperation(uint32_t Timeout); -/** - * @} - */ - -/** - * @} - */ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/** @defgroup FLASH_Private_Variables FLASH Private Variables - * @{ - */ - -/** - * @} - */ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup FLASH_Private_Constants FLASH Private Constants - * @{ - */ - -/** - * @brief ACR register byte 0 (Bits[7:0]) base address - */ -#define ACR_BYTE0_ADDRESS 0x40023C00U -/** - * @brief OPTCR register byte 0 (Bits[7:0]) base address - */ -#define OPTCR_BYTE0_ADDRESS 0x40023C14U -/** - * @brief OPTCR register byte 1 (Bits[15:8]) base address - */ -#define OPTCR_BYTE1_ADDRESS 0x40023C15U -/** - * @brief OPTCR register byte 2 (Bits[23:16]) base address - */ -#define OPTCR_BYTE2_ADDRESS 0x40023C16U -/** - * @brief OPTCR register byte 3 (Bits[31:24]) base address - */ -#define OPTCR_BYTE3_ADDRESS 0x40023C17U - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup FLASH_Private_Macros FLASH Private Macros - * @{ - */ - -/** @defgroup FLASH_IS_FLASH_Definitions FLASH Private macros to check input parameters - * @{ - */ -#define IS_FLASH_TYPEPROGRAM(VALUE)(((VALUE) == FLASH_TYPEPROGRAM_BYTE) || \ - ((VALUE) == FLASH_TYPEPROGRAM_HALFWORD) || \ - ((VALUE) == FLASH_TYPEPROGRAM_WORD) || \ - ((VALUE) == FLASH_TYPEPROGRAM_DOUBLEWORD)) -/** - * @} - */ - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup FLASH_Private_Functions FLASH Private Functions - * @{ - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_FLASH_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash_ex.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash_ex.h deleted file mode 100644 index 4dbad67..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash_ex.h +++ /dev/null @@ -1,1066 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_flash_ex.h - * @author MCD Application Team - * @brief Header file of FLASH HAL Extension module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_FLASH_EX_H -#define __STM32F4xx_HAL_FLASH_EX_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup FLASHEx - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup FLASHEx_Exported_Types FLASH Exported Types - * @{ - */ - -/** - * @brief FLASH Erase structure definition - */ -typedef struct -{ - uint32_t TypeErase; /*!< Mass erase or sector Erase. - This parameter can be a value of @ref FLASHEx_Type_Erase */ - - uint32_t Banks; /*!< Select banks to erase when Mass erase is enabled. - This parameter must be a value of @ref FLASHEx_Banks */ - - uint32_t Sector; /*!< Initial FLASH sector to erase when Mass erase is disabled - This parameter must be a value of @ref FLASHEx_Sectors */ - - uint32_t NbSectors; /*!< Number of sectors to be erased. - This parameter must be a value between 1 and (max number of sectors - value of Initial sector)*/ - - uint32_t VoltageRange;/*!< The device voltage range which defines the erase parallelism - This parameter must be a value of @ref FLASHEx_Voltage_Range */ - -} FLASH_EraseInitTypeDef; - -/** - * @brief FLASH Option Bytes Program structure definition - */ -typedef struct -{ - uint32_t OptionType; /*!< Option byte to be configured. - This parameter can be a value of @ref FLASHEx_Option_Type */ - - uint32_t WRPState; /*!< Write protection activation or deactivation. - This parameter can be a value of @ref FLASHEx_WRP_State */ - - uint32_t WRPSector; /*!< Specifies the sector(s) to be write protected. - The value of this parameter depend on device used within the same series */ - - uint32_t Banks; /*!< Select banks for WRP activation/deactivation of all sectors. - This parameter must be a value of @ref FLASHEx_Banks */ - - uint32_t RDPLevel; /*!< Set the read protection level. - This parameter can be a value of @ref FLASHEx_Option_Bytes_Read_Protection */ - - uint32_t BORLevel; /*!< Set the BOR Level. - This parameter can be a value of @ref FLASHEx_BOR_Reset_Level */ - - uint8_t USERConfig; /*!< Program the FLASH User Option Byte: IWDG_SW / RST_STOP / RST_STDBY. */ - -} FLASH_OBProgramInitTypeDef; - -/** - * @brief FLASH Advanced Option Bytes Program structure definition - */ -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) ||\ - defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F469xx) ||\ - defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) ||\ - defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -typedef struct -{ - uint32_t OptionType; /*!< Option byte to be configured for extension. - This parameter can be a value of @ref FLASHEx_Advanced_Option_Type */ - - uint32_t PCROPState; /*!< PCROP activation or deactivation. - This parameter can be a value of @ref FLASHEx_PCROP_State */ - -#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) ||\ - defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) - uint16_t Sectors; /*!< specifies the sector(s) set for PCROP. - This parameter can be a value of @ref FLASHEx_Option_Bytes_PC_ReadWrite_Protection */ -#endif /* STM32F401xC || STM32F401xE || STM32F410xx || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx ||\ - STM32F412Cx || STM32F413xx || STM32F423xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) - uint32_t Banks; /*!< Select banks for PCROP activation/deactivation of all sectors. - This parameter must be a value of @ref FLASHEx_Banks */ - - uint16_t SectorsBank1; /*!< Specifies the sector(s) set for PCROP for Bank1. - This parameter can be a value of @ref FLASHEx_Option_Bytes_PC_ReadWrite_Protection */ - - uint16_t SectorsBank2; /*!< Specifies the sector(s) set for PCROP for Bank2. - This parameter can be a value of @ref FLASHEx_Option_Bytes_PC_ReadWrite_Protection */ - - uint8_t BootConfig; /*!< Specifies Option bytes for boot config. - This parameter can be a value of @ref FLASHEx_Dual_Boot */ - -#endif /*STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ -}FLASH_AdvOBProgramInitTypeDef; -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F401xC || STM32F401xE || STM32F410xx || STM32F411xE || STM32F446xx || - STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ - -/** @defgroup FLASHEx_Exported_Constants FLASH Exported Constants - * @{ - */ - -/** @defgroup FLASHEx_Type_Erase FLASH Type Erase - * @{ - */ -#define FLASH_TYPEERASE_SECTORS 0x00000000U /*!< Sectors erase only */ -#define FLASH_TYPEERASE_MASSERASE 0x00000001U /*!< Flash Mass erase activation */ -/** - * @} - */ - -/** @defgroup FLASHEx_Voltage_Range FLASH Voltage Range - * @{ - */ -#define FLASH_VOLTAGE_RANGE_1 0x00000000U /*!< Device operating range: 1.8V to 2.1V */ -#define FLASH_VOLTAGE_RANGE_2 0x00000001U /*!< Device operating range: 2.1V to 2.7V */ -#define FLASH_VOLTAGE_RANGE_3 0x00000002U /*!< Device operating range: 2.7V to 3.6V */ -#define FLASH_VOLTAGE_RANGE_4 0x00000003U /*!< Device operating range: 2.7V to 3.6V + External Vpp */ -/** - * @} - */ - -/** @defgroup FLASHEx_WRP_State FLASH WRP State - * @{ - */ -#define OB_WRPSTATE_DISABLE 0x00000000U /*!< Disable the write protection of the desired bank 1 sectors */ -#define OB_WRPSTATE_ENABLE 0x00000001U /*!< Enable the write protection of the desired bank 1 sectors */ -/** - * @} - */ - -/** @defgroup FLASHEx_Option_Type FLASH Option Type - * @{ - */ -#define OPTIONBYTE_WRP 0x00000001U /*!< WRP option byte configuration */ -#define OPTIONBYTE_RDP 0x00000002U /*!< RDP option byte configuration */ -#define OPTIONBYTE_USER 0x00000004U /*!< USER option byte configuration */ -#define OPTIONBYTE_BOR 0x00000008U /*!< BOR option byte configuration */ -/** - * @} - */ - -/** @defgroup FLASHEx_Option_Bytes_Read_Protection FLASH Option Bytes Read Protection - * @{ - */ -#define OB_RDP_LEVEL_0 ((uint8_t)0xAA) -#define OB_RDP_LEVEL_1 ((uint8_t)0x55) -#define OB_RDP_LEVEL_2 ((uint8_t)0xCC) /*!< Warning: When enabling read protection level 2 - it s no more possible to go back to level 1 or 0 */ -/** - * @} - */ - -/** @defgroup FLASHEx_Option_Bytes_IWatchdog FLASH Option Bytes IWatchdog - * @{ - */ -#define OB_IWDG_SW ((uint8_t)0x20) /*!< Software IWDG selected */ -#define OB_IWDG_HW ((uint8_t)0x00) /*!< Hardware IWDG selected */ -/** - * @} - */ - -/** @defgroup FLASHEx_Option_Bytes_nRST_STOP FLASH Option Bytes nRST_STOP - * @{ - */ -#define OB_STOP_NO_RST ((uint8_t)0x40) /*!< No reset generated when entering in STOP */ -#define OB_STOP_RST ((uint8_t)0x00) /*!< Reset generated when entering in STOP */ -/** - * @} - */ - - -/** @defgroup FLASHEx_Option_Bytes_nRST_STDBY FLASH Option Bytes nRST_STDBY - * @{ - */ -#define OB_STDBY_NO_RST ((uint8_t)0x80) /*!< No reset generated when entering in STANDBY */ -#define OB_STDBY_RST ((uint8_t)0x00) /*!< Reset generated when entering in STANDBY */ -/** - * @} - */ - -/** @defgroup FLASHEx_BOR_Reset_Level FLASH BOR Reset Level - * @{ - */ -#define OB_BOR_LEVEL3 ((uint8_t)0x00) /*!< Supply voltage ranges from 2.70 to 3.60 V */ -#define OB_BOR_LEVEL2 ((uint8_t)0x04) /*!< Supply voltage ranges from 2.40 to 2.70 V */ -#define OB_BOR_LEVEL1 ((uint8_t)0x08) /*!< Supply voltage ranges from 2.10 to 2.40 V */ -#define OB_BOR_OFF ((uint8_t)0x0C) /*!< Supply voltage ranges from 1.62 to 2.10 V */ -/** - * @} - */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) ||\ - defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F469xx) ||\ - defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) ||\ - defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/** @defgroup FLASHEx_PCROP_State FLASH PCROP State - * @{ - */ -#define OB_PCROP_STATE_DISABLE 0x00000000U /*!< Disable PCROP */ -#define OB_PCROP_STATE_ENABLE 0x00000001U /*!< Enable PCROP */ -/** - * @} - */ -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F401xC || STM32F401xE ||\ - STM32F410xx || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx ||\ - STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ - -/** @defgroup FLASHEx_Advanced_Option_Type FLASH Advanced Option Type - * @{ - */ -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F469xx) || defined(STM32F479xx) -#define OPTIONBYTE_PCROP 0x00000001U /*!< PCROP option byte configuration */ -#define OPTIONBYTE_BOOTCONFIG 0x00000002U /*!< BOOTConfig option byte configuration */ -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) ||\ - defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) ||\ - defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) ||\ - defined(STM32F423xx) -#define OPTIONBYTE_PCROP 0x00000001U /*!= FLASH_BASE) && ((ADDRESS) <= FLASH_END)) || \ - (((ADDRESS) >= FLASH_OTP_BASE) && ((ADDRESS) <= FLASH_OTP_END))) - -#define IS_FLASH_NBSECTORS(NBSECTORS) (((NBSECTORS) != 0) && ((NBSECTORS) <= FLASH_SECTOR_TOTAL)) - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) -#define IS_OB_WRP_SECTOR(SECTOR)((((SECTOR) & 0xFF000000U) == 0x00000000U) && ((SECTOR) != 0x00000000U)) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F413xx) || defined(STM32F423xx) -#define IS_OB_WRP_SECTOR(SECTOR)((((SECTOR) & 0xFFFF8000U) == 0x00000000U) && ((SECTOR) != 0x00000000U)) -#endif /* STM32F413xx || STM32F423xx */ - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) -#define IS_OB_WRP_SECTOR(SECTOR)((((SECTOR) & 0xFFFFF000U) == 0x00000000U) && ((SECTOR) != 0x00000000U)) -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ - -#if defined(STM32F401xC) -#define IS_OB_WRP_SECTOR(SECTOR)((((SECTOR) & 0xFFFFF000U) == 0x00000000U) && ((SECTOR) != 0x00000000U)) -#endif /* STM32F401xC */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -#define IS_OB_WRP_SECTOR(SECTOR)((((SECTOR) & 0xFFFFF000U) == 0x00000000U) && ((SECTOR) != 0x00000000U)) -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -#if defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) ||\ - defined(STM32F412Rx) || defined(STM32F412Cx) -#define IS_OB_WRP_SECTOR(SECTOR)((((SECTOR) & 0xFFFFF000U) == 0x00000000U) && ((SECTOR) != 0x00000000U)) -#endif /* STM32F401xE || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) -#define IS_OB_PCROP(SECTOR)((((SECTOR) & 0xFFFFF000U) == 0x00000000U) && ((SECTOR) != 0x00000000U)) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F413xx) || defined(STM32F423xx) -#define IS_OB_PCROP(SECTOR)((((SECTOR) & 0xFFFF8000U) == 0x00000000U) && ((SECTOR) != 0x00000000U)) -#endif /* STM32F413xx || STM32F423xx */ - -#if defined(STM32F401xC) -#define IS_OB_PCROP(SECTOR)((((SECTOR) & 0xFFFFF000U) == 0x00000000U) && ((SECTOR) != 0x00000000U)) -#endif /* STM32F401xC */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -#define IS_OB_PCROP(SECTOR)((((SECTOR) & 0xFFFFF000U) == 0x00000000U) && ((SECTOR) != 0x00000000U)) -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -#if defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) ||\ - defined(STM32F412Rx) || defined(STM32F412Cx) -#define IS_OB_PCROP(SECTOR)((((SECTOR) & 0xFFFFF000U) == 0x00000000U) && ((SECTOR) != 0x00000000U)) -#endif /* STM32F401xE || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F469xx) || defined(STM32F479xx) -#define IS_OB_BOOT(BOOT) (((BOOT) == OB_DUAL_BOOT_ENABLE) || ((BOOT) == OB_DUAL_BOOT_DISABLE)) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) ||\ - defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F469xx) ||\ - defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) ||\ - defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -#define IS_OB_PCROP_SELECT(PCROP) (((PCROP) == OB_PCROP_SELECTED) || ((PCROP) == OB_PCROP_DESELECTED)) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F401xC || STM32F401xE ||\ - STM32F410xx || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx ||\ - STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ -/** - * @} - */ - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup FLASHEx_Private_Functions FLASH Private Functions - * @{ - */ -void FLASH_Erase_Sector(uint32_t Sector, uint8_t VoltageRange); -void FLASH_FlushCaches(void); -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_FLASH_EX_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash_ramfunc.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash_ramfunc.h deleted file mode 100644 index 9fab0c9..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_flash_ramfunc.h +++ /dev/null @@ -1,79 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_flash_ramfunc.h - * @author MCD Application Team - * @brief Header file of FLASH RAMFUNC driver. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_FLASH_RAMFUNC_H -#define __STM32F4xx_FLASH_RAMFUNC_H - -#ifdef __cplusplus - extern "C" { -#endif -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) ||\ - defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup FLASH_RAMFUNC - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/* Exported macro ------------------------------------------------------------*/ -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup FLASH_RAMFUNC_Exported_Functions - * @{ - */ - -/** @addtogroup FLASH_RAMFUNC_Exported_Functions_Group1 - * @{ - */ -__RAM_FUNC HAL_StatusTypeDef HAL_FLASHEx_StopFlashInterfaceClk(void); -__RAM_FUNC HAL_StatusTypeDef HAL_FLASHEx_StartFlashInterfaceClk(void); -__RAM_FUNC HAL_StatusTypeDef HAL_FLASHEx_EnableFlashSleepMode(void); -__RAM_FUNC HAL_StatusTypeDef HAL_FLASHEx_DisableFlashSleepMode(void); -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* STM32F410xx || STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ -#ifdef __cplusplus -} -#endif - - -#endif /* __STM32F4xx_FLASH_RAMFUNC_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_fmpi2c.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_fmpi2c.h deleted file mode 100644 index b7f370a..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_fmpi2c.h +++ /dev/null @@ -1,840 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_fmpi2c.h - * @author MCD Application Team - * @brief Header file of FMPI2C HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_FMPI2C_H -#define STM32F4xx_HAL_FMPI2C_H - -#ifdef __cplusplus -extern "C" { -#endif - -#if defined(FMPI2C_CR1_PE) -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup FMPI2C - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup FMPI2C_Exported_Types FMPI2C Exported Types - * @{ - */ - -/** @defgroup FMPI2C_Configuration_Structure_definition FMPI2C Configuration Structure definition - * @brief FMPI2C Configuration Structure definition - * @{ - */ -typedef struct -{ - uint32_t Timing; /*!< Specifies the FMPI2C_TIMINGR_register value. - This parameter calculated by referring to FMPI2C initialization section - in Reference manual */ - - uint32_t OwnAddress1; /*!< Specifies the first device own address. - This parameter can be a 7-bit or 10-bit address. */ - - uint32_t AddressingMode; /*!< Specifies if 7-bit or 10-bit addressing mode is selected. - This parameter can be a value of @ref FMPI2C_ADDRESSING_MODE */ - - uint32_t DualAddressMode; /*!< Specifies if dual addressing mode is selected. - This parameter can be a value of @ref FMPI2C_DUAL_ADDRESSING_MODE */ - - uint32_t OwnAddress2; /*!< Specifies the second device own address if dual addressing mode is selected - This parameter can be a 7-bit address. */ - - uint32_t OwnAddress2Masks; /*!< Specifies the acknowledge mask address second device own address if dual addressing - mode is selected. - This parameter can be a value of @ref FMPI2C_OWN_ADDRESS2_MASKS */ - - uint32_t GeneralCallMode; /*!< Specifies if general call mode is selected. - This parameter can be a value of @ref FMPI2C_GENERAL_CALL_ADDRESSING_MODE */ - - uint32_t NoStretchMode; /*!< Specifies if nostretch mode is selected. - This parameter can be a value of @ref FMPI2C_NOSTRETCH_MODE */ - -} FMPI2C_InitTypeDef; - -/** - * @} - */ - -/** @defgroup HAL_state_structure_definition HAL state structure definition - * @brief HAL State structure definition - * @note HAL FMPI2C State value coding follow below described bitmap :\n - * b7-b6 Error information\n - * 00 : No Error\n - * 01 : Abort (Abort user request on going)\n - * 10 : Timeout\n - * 11 : Error\n - * b5 Peripheral initialization status\n - * 0 : Reset (peripheral not initialized)\n - * 1 : Init done (peripheral initialized and ready to use. HAL FMPI2C Init function called)\n - * b4 (not used)\n - * x : Should be set to 0\n - * b3\n - * 0 : Ready or Busy (No Listen mode ongoing)\n - * 1 : Listen (peripheral in Address Listen Mode)\n - * b2 Intrinsic process state\n - * 0 : Ready\n - * 1 : Busy (peripheral busy with some configuration or internal operations)\n - * b1 Rx state\n - * 0 : Ready (no Rx operation ongoing)\n - * 1 : Busy (Rx operation ongoing)\n - * b0 Tx state\n - * 0 : Ready (no Tx operation ongoing)\n - * 1 : Busy (Tx operation ongoing) - * @{ - */ -typedef enum -{ - HAL_FMPI2C_STATE_RESET = 0x00U, /*!< Peripheral is not yet Initialized */ - HAL_FMPI2C_STATE_READY = 0x20U, /*!< Peripheral Initialized and ready for use */ - HAL_FMPI2C_STATE_BUSY = 0x24U, /*!< An internal process is ongoing */ - HAL_FMPI2C_STATE_BUSY_TX = 0x21U, /*!< Data Transmission process is ongoing */ - HAL_FMPI2C_STATE_BUSY_RX = 0x22U, /*!< Data Reception process is ongoing */ - HAL_FMPI2C_STATE_LISTEN = 0x28U, /*!< Address Listen Mode is ongoing */ - HAL_FMPI2C_STATE_BUSY_TX_LISTEN = 0x29U, /*!< Address Listen Mode and Data Transmission - process is ongoing */ - HAL_FMPI2C_STATE_BUSY_RX_LISTEN = 0x2AU, /*!< Address Listen Mode and Data Reception - process is ongoing */ - HAL_FMPI2C_STATE_ABORT = 0x60U, /*!< Abort user request ongoing */ - HAL_FMPI2C_STATE_TIMEOUT = 0xA0U, /*!< Timeout state */ - HAL_FMPI2C_STATE_ERROR = 0xE0U /*!< Error */ - -} HAL_FMPI2C_StateTypeDef; - -/** - * @} - */ - -/** @defgroup HAL_mode_structure_definition HAL mode structure definition - * @brief HAL Mode structure definition - * @note HAL FMPI2C Mode value coding follow below described bitmap :\n - * b7 (not used)\n - * x : Should be set to 0\n - * b6\n - * 0 : None\n - * 1 : Memory (HAL FMPI2C communication is in Memory Mode)\n - * b5\n - * 0 : None\n - * 1 : Slave (HAL FMPI2C communication is in Slave Mode)\n - * b4\n - * 0 : None\n - * 1 : Master (HAL FMPI2C communication is in Master Mode)\n - * b3-b2-b1-b0 (not used)\n - * xxxx : Should be set to 0000 - * @{ - */ -typedef enum -{ - HAL_FMPI2C_MODE_NONE = 0x00U, /*!< No FMPI2C communication on going */ - HAL_FMPI2C_MODE_MASTER = 0x10U, /*!< FMPI2C communication is in Master Mode */ - HAL_FMPI2C_MODE_SLAVE = 0x20U, /*!< FMPI2C communication is in Slave Mode */ - HAL_FMPI2C_MODE_MEM = 0x40U /*!< FMPI2C communication is in Memory Mode */ - -} HAL_FMPI2C_ModeTypeDef; - -/** - * @} - */ - -/** @defgroup FMPI2C_Error_Code_definition FMPI2C Error Code definition - * @brief FMPI2C Error Code definition - * @{ - */ -#define HAL_FMPI2C_ERROR_NONE (0x00000000U) /*!< No error */ -#define HAL_FMPI2C_ERROR_BERR (0x00000001U) /*!< BERR error */ -#define HAL_FMPI2C_ERROR_ARLO (0x00000002U) /*!< ARLO error */ -#define HAL_FMPI2C_ERROR_AF (0x00000004U) /*!< ACKF error */ -#define HAL_FMPI2C_ERROR_OVR (0x00000008U) /*!< OVR error */ -#define HAL_FMPI2C_ERROR_DMA (0x00000010U) /*!< DMA transfer error */ -#define HAL_FMPI2C_ERROR_TIMEOUT (0x00000020U) /*!< Timeout error */ -#define HAL_FMPI2C_ERROR_SIZE (0x00000040U) /*!< Size Management error */ -#define HAL_FMPI2C_ERROR_DMA_PARAM (0x00000080U) /*!< DMA Parameter Error */ -#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) -#define HAL_FMPI2C_ERROR_INVALID_CALLBACK (0x00000100U) /*!< Invalid Callback error */ -#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ -#define HAL_FMPI2C_ERROR_INVALID_PARAM (0x00000200U) /*!< Invalid Parameters error */ -/** - * @} - */ - -/** @defgroup FMPI2C_handle_Structure_definition FMPI2C handle Structure definition - * @brief FMPI2C handle Structure definition - * @{ - */ -typedef struct __FMPI2C_HandleTypeDef -{ - FMPI2C_TypeDef *Instance; /*!< FMPI2C registers base address */ - - FMPI2C_InitTypeDef Init; /*!< FMPI2C communication parameters */ - - uint8_t *pBuffPtr; /*!< Pointer to FMPI2C transfer buffer */ - - uint16_t XferSize; /*!< FMPI2C transfer size */ - - __IO uint16_t XferCount; /*!< FMPI2C transfer counter */ - - __IO uint32_t XferOptions; /*!< FMPI2C sequantial transfer options, this parameter can - be a value of @ref FMPI2C_XFEROPTIONS */ - - __IO uint32_t PreviousState; /*!< FMPI2C communication Previous state */ - - HAL_StatusTypeDef(*XferISR)(struct __FMPI2C_HandleTypeDef *hfmpi2c, uint32_t ITFlags, uint32_t ITSources); - /*!< FMPI2C transfer IRQ handler function pointer */ - - DMA_HandleTypeDef *hdmatx; /*!< FMPI2C Tx DMA handle parameters */ - - DMA_HandleTypeDef *hdmarx; /*!< FMPI2C Rx DMA handle parameters */ - - HAL_LockTypeDef Lock; /*!< FMPI2C locking object */ - - __IO HAL_FMPI2C_StateTypeDef State; /*!< FMPI2C communication state */ - - __IO HAL_FMPI2C_ModeTypeDef Mode; /*!< FMPI2C communication mode */ - - __IO uint32_t ErrorCode; /*!< FMPI2C Error code */ - - __IO uint32_t AddrEventCount; /*!< FMPI2C Address Event counter */ - -#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) - void (* MasterTxCpltCallback)(struct __FMPI2C_HandleTypeDef *hfmpi2c); - /*!< FMPI2C Master Tx Transfer completed callback */ - void (* MasterRxCpltCallback)(struct __FMPI2C_HandleTypeDef *hfmpi2c); - /*!< FMPI2C Master Rx Transfer completed callback */ - void (* SlaveTxCpltCallback)(struct __FMPI2C_HandleTypeDef *hfmpi2c); - /*!< FMPI2C Slave Tx Transfer completed callback */ - void (* SlaveRxCpltCallback)(struct __FMPI2C_HandleTypeDef *hfmpi2c); - /*!< FMPI2C Slave Rx Transfer completed callback */ - void (* ListenCpltCallback)(struct __FMPI2C_HandleTypeDef *hfmpi2c); - /*!< FMPI2C Listen Complete callback */ - void (* MemTxCpltCallback)(struct __FMPI2C_HandleTypeDef *hfmpi2c); - /*!< FMPI2C Memory Tx Transfer completed callback */ - void (* MemRxCpltCallback)(struct __FMPI2C_HandleTypeDef *hfmpi2c); - /*!< FMPI2C Memory Rx Transfer completed callback */ - void (* ErrorCallback)(struct __FMPI2C_HandleTypeDef *hfmpi2c); - /*!< FMPI2C Error callback */ - void (* AbortCpltCallback)(struct __FMPI2C_HandleTypeDef *hfmpi2c); - /*!< FMPI2C Abort callback */ - - void (* AddrCallback)(struct __FMPI2C_HandleTypeDef *hfmpi2c, uint8_t TransferDirection, uint16_t AddrMatchCode); - /*!< FMPI2C Slave Address Match callback */ - - void (* MspInitCallback)(struct __FMPI2C_HandleTypeDef *hfmpi2c); - /*!< FMPI2C Msp Init callback */ - void (* MspDeInitCallback)(struct __FMPI2C_HandleTypeDef *hfmpi2c); - /*!< FMPI2C Msp DeInit callback */ - -#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ -} FMPI2C_HandleTypeDef; - -#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) -/** - * @brief HAL FMPI2C Callback ID enumeration definition - */ -typedef enum -{ - HAL_FMPI2C_MASTER_TX_COMPLETE_CB_ID = 0x00U, /*!< FMPI2C Master Tx Transfer completed callback ID */ - HAL_FMPI2C_MASTER_RX_COMPLETE_CB_ID = 0x01U, /*!< FMPI2C Master Rx Transfer completed callback ID */ - HAL_FMPI2C_SLAVE_TX_COMPLETE_CB_ID = 0x02U, /*!< FMPI2C Slave Tx Transfer completed callback ID */ - HAL_FMPI2C_SLAVE_RX_COMPLETE_CB_ID = 0x03U, /*!< FMPI2C Slave Rx Transfer completed callback ID */ - HAL_FMPI2C_LISTEN_COMPLETE_CB_ID = 0x04U, /*!< FMPI2C Listen Complete callback ID */ - HAL_FMPI2C_MEM_TX_COMPLETE_CB_ID = 0x05U, /*!< FMPI2C Memory Tx Transfer callback ID */ - HAL_FMPI2C_MEM_RX_COMPLETE_CB_ID = 0x06U, /*!< FMPI2C Memory Rx Transfer completed callback ID */ - HAL_FMPI2C_ERROR_CB_ID = 0x07U, /*!< FMPI2C Error callback ID */ - HAL_FMPI2C_ABORT_CB_ID = 0x08U, /*!< FMPI2C Abort callback ID */ - - HAL_FMPI2C_MSPINIT_CB_ID = 0x09U, /*!< FMPI2C Msp Init callback ID */ - HAL_FMPI2C_MSPDEINIT_CB_ID = 0x0AU /*!< FMPI2C Msp DeInit callback ID */ - -} HAL_FMPI2C_CallbackIDTypeDef; - -/** - * @brief HAL FMPI2C Callback pointer definition - */ -typedef void (*pFMPI2C_CallbackTypeDef)(FMPI2C_HandleTypeDef *hfmpi2c); -/*!< pointer to an FMPI2C callback function */ -typedef void (*pFMPI2C_AddrCallbackTypeDef)(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t TransferDirection, - uint16_t AddrMatchCode); -/*!< pointer to an FMPI2C Address Match callback function */ - -#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** - * @} - */ -/* Exported constants --------------------------------------------------------*/ - -/** @defgroup FMPI2C_Exported_Constants FMPI2C Exported Constants - * @{ - */ - -/** @defgroup FMPI2C_XFEROPTIONS FMPI2C Sequential Transfer Options - * @{ - */ -#define FMPI2C_FIRST_FRAME ((uint32_t)FMPI2C_SOFTEND_MODE) -#define FMPI2C_FIRST_AND_NEXT_FRAME ((uint32_t)(FMPI2C_RELOAD_MODE | FMPI2C_SOFTEND_MODE)) -#define FMPI2C_NEXT_FRAME ((uint32_t)(FMPI2C_RELOAD_MODE | FMPI2C_SOFTEND_MODE)) -#define FMPI2C_FIRST_AND_LAST_FRAME ((uint32_t)FMPI2C_AUTOEND_MODE) -#define FMPI2C_LAST_FRAME ((uint32_t)FMPI2C_AUTOEND_MODE) -#define FMPI2C_LAST_FRAME_NO_STOP ((uint32_t)FMPI2C_SOFTEND_MODE) - -/* List of XferOptions in usage of : - * 1- Restart condition in all use cases (direction change or not) - */ -#define FMPI2C_OTHER_FRAME (0x000000AAU) -#define FMPI2C_OTHER_AND_LAST_FRAME (0x0000AA00U) -/** - * @} - */ - -/** @defgroup FMPI2C_ADDRESSING_MODE FMPI2C Addressing Mode - * @{ - */ -#define FMPI2C_ADDRESSINGMODE_7BIT (0x00000001U) -#define FMPI2C_ADDRESSINGMODE_10BIT (0x00000002U) -/** - * @} - */ - -/** @defgroup FMPI2C_DUAL_ADDRESSING_MODE FMPI2C Dual Addressing Mode - * @{ - */ -#define FMPI2C_DUALADDRESS_DISABLE (0x00000000U) -#define FMPI2C_DUALADDRESS_ENABLE FMPI2C_OAR2_OA2EN -/** - * @} - */ - -/** @defgroup FMPI2C_OWN_ADDRESS2_MASKS FMPI2C Own Address2 Masks - * @{ - */ -#define FMPI2C_OA2_NOMASK ((uint8_t)0x00U) -#define FMPI2C_OA2_MASK01 ((uint8_t)0x01U) -#define FMPI2C_OA2_MASK02 ((uint8_t)0x02U) -#define FMPI2C_OA2_MASK03 ((uint8_t)0x03U) -#define FMPI2C_OA2_MASK04 ((uint8_t)0x04U) -#define FMPI2C_OA2_MASK05 ((uint8_t)0x05U) -#define FMPI2C_OA2_MASK06 ((uint8_t)0x06U) -#define FMPI2C_OA2_MASK07 ((uint8_t)0x07U) -/** - * @} - */ - -/** @defgroup FMPI2C_GENERAL_CALL_ADDRESSING_MODE FMPI2C General Call Addressing Mode - * @{ - */ -#define FMPI2C_GENERALCALL_DISABLE (0x00000000U) -#define FMPI2C_GENERALCALL_ENABLE FMPI2C_CR1_GCEN -/** - * @} - */ - -/** @defgroup FMPI2C_NOSTRETCH_MODE FMPI2C No-Stretch Mode - * @{ - */ -#define FMPI2C_NOSTRETCH_DISABLE (0x00000000U) -#define FMPI2C_NOSTRETCH_ENABLE FMPI2C_CR1_NOSTRETCH -/** - * @} - */ - -/** @defgroup FMPI2C_MEMORY_ADDRESS_SIZE FMPI2C Memory Address Size - * @{ - */ -#define FMPI2C_MEMADD_SIZE_8BIT (0x00000001U) -#define FMPI2C_MEMADD_SIZE_16BIT (0x00000002U) -/** - * @} - */ - -/** @defgroup FMPI2C_XFERDIRECTION FMPI2C Transfer Direction Master Point of View - * @{ - */ -#define FMPI2C_DIRECTION_TRANSMIT (0x00000000U) -#define FMPI2C_DIRECTION_RECEIVE (0x00000001U) -/** - * @} - */ - -/** @defgroup FMPI2C_RELOAD_END_MODE FMPI2C Reload End Mode - * @{ - */ -#define FMPI2C_RELOAD_MODE FMPI2C_CR2_RELOAD -#define FMPI2C_AUTOEND_MODE FMPI2C_CR2_AUTOEND -#define FMPI2C_SOFTEND_MODE (0x00000000U) -/** - * @} - */ - -/** @defgroup FMPI2C_START_STOP_MODE FMPI2C Start or Stop Mode - * @{ - */ -#define FMPI2C_NO_STARTSTOP (0x00000000U) -#define FMPI2C_GENERATE_STOP (uint32_t)(0x80000000U | FMPI2C_CR2_STOP) -#define FMPI2C_GENERATE_START_READ (uint32_t)(0x80000000U | FMPI2C_CR2_START | FMPI2C_CR2_RD_WRN) -#define FMPI2C_GENERATE_START_WRITE (uint32_t)(0x80000000U | FMPI2C_CR2_START) -/** - * @} - */ - -/** @defgroup FMPI2C_Interrupt_configuration_definition FMPI2C Interrupt configuration definition - * @brief FMPI2C Interrupt definition - * Elements values convention: 0xXXXXXXXX - * - XXXXXXXX : Interrupt control mask - * @{ - */ -#define FMPI2C_IT_ERRI FMPI2C_CR1_ERRIE -#define FMPI2C_IT_TCI FMPI2C_CR1_TCIE -#define FMPI2C_IT_STOPI FMPI2C_CR1_STOPIE -#define FMPI2C_IT_NACKI FMPI2C_CR1_NACKIE -#define FMPI2C_IT_ADDRI FMPI2C_CR1_ADDRIE -#define FMPI2C_IT_RXI FMPI2C_CR1_RXIE -#define FMPI2C_IT_TXI FMPI2C_CR1_TXIE -/** - * @} - */ - -/** @defgroup FMPI2C_Flag_definition FMPI2C Flag definition - * @{ - */ -#define FMPI2C_FLAG_TXE FMPI2C_ISR_TXE -#define FMPI2C_FLAG_TXIS FMPI2C_ISR_TXIS -#define FMPI2C_FLAG_RXNE FMPI2C_ISR_RXNE -#define FMPI2C_FLAG_ADDR FMPI2C_ISR_ADDR -#define FMPI2C_FLAG_AF FMPI2C_ISR_NACKF -#define FMPI2C_FLAG_STOPF FMPI2C_ISR_STOPF -#define FMPI2C_FLAG_TC FMPI2C_ISR_TC -#define FMPI2C_FLAG_TCR FMPI2C_ISR_TCR -#define FMPI2C_FLAG_BERR FMPI2C_ISR_BERR -#define FMPI2C_FLAG_ARLO FMPI2C_ISR_ARLO -#define FMPI2C_FLAG_OVR FMPI2C_ISR_OVR -#define FMPI2C_FLAG_PECERR FMPI2C_ISR_PECERR -#define FMPI2C_FLAG_TIMEOUT FMPI2C_ISR_TIMEOUT -#define FMPI2C_FLAG_ALERT FMPI2C_ISR_ALERT -#define FMPI2C_FLAG_BUSY FMPI2C_ISR_BUSY -#define FMPI2C_FLAG_DIR FMPI2C_ISR_DIR -/** - * @} - */ - -/** - * @} - */ - -/* Exported macros -----------------------------------------------------------*/ - -/** @defgroup FMPI2C_Exported_Macros FMPI2C Exported Macros - * @{ - */ - -/** @brief Reset FMPI2C handle state. - * @param __HANDLE__ specifies the FMPI2C Handle. - * @retval None - */ -#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) -#define __HAL_FMPI2C_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->State = HAL_FMPI2C_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_FMPI2C_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_FMPI2C_STATE_RESET) -#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ - -/** @brief Enable the specified FMPI2C interrupt. - * @param __HANDLE__ specifies the FMPI2C Handle. - * @param __INTERRUPT__ specifies the interrupt source to enable. - * This parameter can be one of the following values: - * @arg @ref FMPI2C_IT_ERRI Errors interrupt enable - * @arg @ref FMPI2C_IT_TCI Transfer complete interrupt enable - * @arg @ref FMPI2C_IT_STOPI STOP detection interrupt enable - * @arg @ref FMPI2C_IT_NACKI NACK received interrupt enable - * @arg @ref FMPI2C_IT_ADDRI Address match interrupt enable - * @arg @ref FMPI2C_IT_RXI RX interrupt enable - * @arg @ref FMPI2C_IT_TXI TX interrupt enable - * - * @retval None - */ -#define __HAL_FMPI2C_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR1 |= (__INTERRUPT__)) - -/** @brief Disable the specified FMPI2C interrupt. - * @param __HANDLE__ specifies the FMPI2C Handle. - * @param __INTERRUPT__ specifies the interrupt source to disable. - * This parameter can be one of the following values: - * @arg @ref FMPI2C_IT_ERRI Errors interrupt enable - * @arg @ref FMPI2C_IT_TCI Transfer complete interrupt enable - * @arg @ref FMPI2C_IT_STOPI STOP detection interrupt enable - * @arg @ref FMPI2C_IT_NACKI NACK received interrupt enable - * @arg @ref FMPI2C_IT_ADDRI Address match interrupt enable - * @arg @ref FMPI2C_IT_RXI RX interrupt enable - * @arg @ref FMPI2C_IT_TXI TX interrupt enable - * - * @retval None - */ -#define __HAL_FMPI2C_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR1 &= (~(__INTERRUPT__))) - -/** @brief Check whether the specified FMPI2C interrupt source is enabled or not. - * @param __HANDLE__ specifies the FMPI2C Handle. - * @param __INTERRUPT__ specifies the FMPI2C interrupt source to check. - * This parameter can be one of the following values: - * @arg @ref FMPI2C_IT_ERRI Errors interrupt enable - * @arg @ref FMPI2C_IT_TCI Transfer complete interrupt enable - * @arg @ref FMPI2C_IT_STOPI STOP detection interrupt enable - * @arg @ref FMPI2C_IT_NACKI NACK received interrupt enable - * @arg @ref FMPI2C_IT_ADDRI Address match interrupt enable - * @arg @ref FMPI2C_IT_RXI RX interrupt enable - * @arg @ref FMPI2C_IT_TXI TX interrupt enable - * - * @retval The new state of __INTERRUPT__ (SET or RESET). - */ -#define __HAL_FMPI2C_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((((__HANDLE__)->Instance->CR1 & \ - (__INTERRUPT__)) == (__INTERRUPT__)) ? SET : RESET) - -/** @brief Check whether the specified FMPI2C flag is set or not. - * @param __HANDLE__ specifies the FMPI2C Handle. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg @ref FMPI2C_FLAG_TXE Transmit data register empty - * @arg @ref FMPI2C_FLAG_TXIS Transmit interrupt status - * @arg @ref FMPI2C_FLAG_RXNE Receive data register not empty - * @arg @ref FMPI2C_FLAG_ADDR Address matched (slave mode) - * @arg @ref FMPI2C_FLAG_AF Acknowledge failure received flag - * @arg @ref FMPI2C_FLAG_STOPF STOP detection flag - * @arg @ref FMPI2C_FLAG_TC Transfer complete (master mode) - * @arg @ref FMPI2C_FLAG_TCR Transfer complete reload - * @arg @ref FMPI2C_FLAG_BERR Bus error - * @arg @ref FMPI2C_FLAG_ARLO Arbitration lost - * @arg @ref FMPI2C_FLAG_OVR Overrun/Underrun - * @arg @ref FMPI2C_FLAG_PECERR PEC error in reception - * @arg @ref FMPI2C_FLAG_TIMEOUT Timeout or Tlow detection flag - * @arg @ref FMPI2C_FLAG_ALERT SMBus alert - * @arg @ref FMPI2C_FLAG_BUSY Bus busy - * @arg @ref FMPI2C_FLAG_DIR Transfer direction (slave mode) - * - * @retval The new state of __FLAG__ (SET or RESET). - */ -#define FMPI2C_FLAG_MASK (0x0001FFFFU) -#define __HAL_FMPI2C_GET_FLAG(__HANDLE__, __FLAG__) (((((__HANDLE__)->Instance->ISR) & \ - (__FLAG__)) == (__FLAG__)) ? SET : RESET) - -/** @brief Clear the FMPI2C pending flags which are cleared by writing 1 in a specific bit. - * @param __HANDLE__ specifies the FMPI2C Handle. - * @param __FLAG__ specifies the flag to clear. - * This parameter can be any combination of the following values: - * @arg @ref FMPI2C_FLAG_TXE Transmit data register empty - * @arg @ref FMPI2C_FLAG_ADDR Address matched (slave mode) - * @arg @ref FMPI2C_FLAG_AF Acknowledge failure received flag - * @arg @ref FMPI2C_FLAG_STOPF STOP detection flag - * @arg @ref FMPI2C_FLAG_BERR Bus error - * @arg @ref FMPI2C_FLAG_ARLO Arbitration lost - * @arg @ref FMPI2C_FLAG_OVR Overrun/Underrun - * @arg @ref FMPI2C_FLAG_PECERR PEC error in reception - * @arg @ref FMPI2C_FLAG_TIMEOUT Timeout or Tlow detection flag - * @arg @ref FMPI2C_FLAG_ALERT SMBus alert - * - * @retval None - */ -#define __HAL_FMPI2C_CLEAR_FLAG(__HANDLE__, __FLAG__) (((__FLAG__) == FMPI2C_FLAG_TXE) ? \ - ((__HANDLE__)->Instance->ISR |= (__FLAG__)) : \ - ((__HANDLE__)->Instance->ICR = (__FLAG__))) - -/** @brief Enable the specified FMPI2C peripheral. - * @param __HANDLE__ specifies the FMPI2C Handle. - * @retval None - */ -#define __HAL_FMPI2C_ENABLE(__HANDLE__) (SET_BIT((__HANDLE__)->Instance->CR1, FMPI2C_CR1_PE)) - -/** @brief Disable the specified FMPI2C peripheral. - * @param __HANDLE__ specifies the FMPI2C Handle. - * @retval None - */ -#define __HAL_FMPI2C_DISABLE(__HANDLE__) (CLEAR_BIT((__HANDLE__)->Instance->CR1, FMPI2C_CR1_PE)) - -/** @brief Generate a Non-Acknowledge FMPI2C peripheral in Slave mode. - * @param __HANDLE__ specifies the FMPI2C Handle. - * @retval None - */ -#define __HAL_FMPI2C_GENERATE_NACK(__HANDLE__) (SET_BIT((__HANDLE__)->Instance->CR2, FMPI2C_CR2_NACK)) -/** - * @} - */ - -/* Include FMPI2C HAL Extended module */ -#include "stm32f4xx_hal_fmpi2c_ex.h" - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup FMPI2C_Exported_Functions - * @{ - */ - -/** @addtogroup FMPI2C_Exported_Functions_Group1 Initialization and de-initialization functions - * @{ - */ -/* Initialization and de-initialization functions******************************/ -HAL_StatusTypeDef HAL_FMPI2C_Init(FMPI2C_HandleTypeDef *hfmpi2c); -HAL_StatusTypeDef HAL_FMPI2C_DeInit(FMPI2C_HandleTypeDef *hfmpi2c); -void HAL_FMPI2C_MspInit(FMPI2C_HandleTypeDef *hfmpi2c); -void HAL_FMPI2C_MspDeInit(FMPI2C_HandleTypeDef *hfmpi2c); - -/* Callbacks Register/UnRegister functions ***********************************/ -#if (USE_HAL_FMPI2C_REGISTER_CALLBACKS == 1) -HAL_StatusTypeDef HAL_FMPI2C_RegisterCallback(FMPI2C_HandleTypeDef *hfmpi2c, HAL_FMPI2C_CallbackIDTypeDef CallbackID, - pFMPI2C_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_FMPI2C_UnRegisterCallback(FMPI2C_HandleTypeDef *hfmpi2c, HAL_FMPI2C_CallbackIDTypeDef CallbackID); - -HAL_StatusTypeDef HAL_FMPI2C_RegisterAddrCallback(FMPI2C_HandleTypeDef *hfmpi2c, pFMPI2C_AddrCallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_FMPI2C_UnRegisterAddrCallback(FMPI2C_HandleTypeDef *hfmpi2c); -#endif /* USE_HAL_FMPI2C_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @addtogroup FMPI2C_Exported_Functions_Group2 Input and Output operation functions - * @{ - */ -/* IO operation functions ****************************************************/ -/******* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_FMPI2C_Master_Transmit(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint8_t *pData, - uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_FMPI2C_Master_Receive(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint8_t *pData, - uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_FMPI2C_Slave_Transmit(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t *pData, uint16_t Size, - uint32_t Timeout); -HAL_StatusTypeDef HAL_FMPI2C_Slave_Receive(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t *pData, uint16_t Size, - uint32_t Timeout); -HAL_StatusTypeDef HAL_FMPI2C_Mem_Write(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint16_t MemAddress, - uint16_t MemAddSize, uint8_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_FMPI2C_Mem_Read(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint16_t MemAddress, - uint16_t MemAddSize, uint8_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_FMPI2C_IsDeviceReady(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint32_t Trials, - uint32_t Timeout); - -/******* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_FMPI2C_Master_Transmit_IT(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint8_t *pData, - uint16_t Size); -HAL_StatusTypeDef HAL_FMPI2C_Master_Receive_IT(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint8_t *pData, - uint16_t Size); -HAL_StatusTypeDef HAL_FMPI2C_Slave_Transmit_IT(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_FMPI2C_Slave_Receive_IT(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_FMPI2C_Mem_Write_IT(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint16_t MemAddress, - uint16_t MemAddSize, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_FMPI2C_Mem_Read_IT(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint16_t MemAddress, - uint16_t MemAddSize, uint8_t *pData, uint16_t Size); - -HAL_StatusTypeDef HAL_FMPI2C_Master_Seq_Transmit_IT(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint8_t *pData, - uint16_t Size, uint32_t XferOptions); -HAL_StatusTypeDef HAL_FMPI2C_Master_Seq_Receive_IT(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint8_t *pData, - uint16_t Size, uint32_t XferOptions); -HAL_StatusTypeDef HAL_FMPI2C_Slave_Seq_Transmit_IT(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t *pData, uint16_t Size, - uint32_t XferOptions); -HAL_StatusTypeDef HAL_FMPI2C_Slave_Seq_Receive_IT(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t *pData, uint16_t Size, - uint32_t XferOptions); -HAL_StatusTypeDef HAL_FMPI2C_EnableListen_IT(FMPI2C_HandleTypeDef *hfmpi2c); -HAL_StatusTypeDef HAL_FMPI2C_DisableListen_IT(FMPI2C_HandleTypeDef *hfmpi2c); -HAL_StatusTypeDef HAL_FMPI2C_Master_Abort_IT(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress); - -/******* Non-Blocking mode: DMA */ -HAL_StatusTypeDef HAL_FMPI2C_Master_Transmit_DMA(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint8_t *pData, - uint16_t Size); -HAL_StatusTypeDef HAL_FMPI2C_Master_Receive_DMA(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint8_t *pData, - uint16_t Size); -HAL_StatusTypeDef HAL_FMPI2C_Slave_Transmit_DMA(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_FMPI2C_Slave_Receive_DMA(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_FMPI2C_Mem_Write_DMA(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint16_t MemAddress, - uint16_t MemAddSize, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_FMPI2C_Mem_Read_DMA(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint16_t MemAddress, - uint16_t MemAddSize, uint8_t *pData, uint16_t Size); - -HAL_StatusTypeDef HAL_FMPI2C_Master_Seq_Transmit_DMA(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint8_t *pData, - uint16_t Size, uint32_t XferOptions); -HAL_StatusTypeDef HAL_FMPI2C_Master_Seq_Receive_DMA(FMPI2C_HandleTypeDef *hfmpi2c, uint16_t DevAddress, uint8_t *pData, - uint16_t Size, uint32_t XferOptions); -HAL_StatusTypeDef HAL_FMPI2C_Slave_Seq_Transmit_DMA(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t *pData, uint16_t Size, - uint32_t XferOptions); -HAL_StatusTypeDef HAL_FMPI2C_Slave_Seq_Receive_DMA(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t *pData, uint16_t Size, - uint32_t XferOptions); -/** - * @} - */ - -/** @addtogroup FMPI2C_IRQ_Handler_and_Callbacks IRQ Handler and Callbacks - * @{ - */ -/******* FMPI2C IRQHandler and Callbacks used in non blocking modes (Interrupt and DMA) */ -void HAL_FMPI2C_EV_IRQHandler(FMPI2C_HandleTypeDef *hfmpi2c); -void HAL_FMPI2C_ER_IRQHandler(FMPI2C_HandleTypeDef *hfmpi2c); -void HAL_FMPI2C_MasterTxCpltCallback(FMPI2C_HandleTypeDef *hfmpi2c); -void HAL_FMPI2C_MasterRxCpltCallback(FMPI2C_HandleTypeDef *hfmpi2c); -void HAL_FMPI2C_SlaveTxCpltCallback(FMPI2C_HandleTypeDef *hfmpi2c); -void HAL_FMPI2C_SlaveRxCpltCallback(FMPI2C_HandleTypeDef *hfmpi2c); -void HAL_FMPI2C_AddrCallback(FMPI2C_HandleTypeDef *hfmpi2c, uint8_t TransferDirection, uint16_t AddrMatchCode); -void HAL_FMPI2C_ListenCpltCallback(FMPI2C_HandleTypeDef *hfmpi2c); -void HAL_FMPI2C_MemTxCpltCallback(FMPI2C_HandleTypeDef *hfmpi2c); -void HAL_FMPI2C_MemRxCpltCallback(FMPI2C_HandleTypeDef *hfmpi2c); -void HAL_FMPI2C_ErrorCallback(FMPI2C_HandleTypeDef *hfmpi2c); -void HAL_FMPI2C_AbortCpltCallback(FMPI2C_HandleTypeDef *hfmpi2c); -/** - * @} - */ - -/** @addtogroup FMPI2C_Exported_Functions_Group3 Peripheral State, Mode and Error functions - * @{ - */ -/* Peripheral State, Mode and Error functions *********************************/ -HAL_FMPI2C_StateTypeDef HAL_FMPI2C_GetState(FMPI2C_HandleTypeDef *hfmpi2c); -HAL_FMPI2C_ModeTypeDef HAL_FMPI2C_GetMode(FMPI2C_HandleTypeDef *hfmpi2c); -uint32_t HAL_FMPI2C_GetError(FMPI2C_HandleTypeDef *hfmpi2c); - -/** - * @} - */ - -/** - * @} - */ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup FMPI2C_Private_Constants FMPI2C Private Constants - * @{ - */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup FMPI2C_Private_Macro FMPI2C Private Macros - * @{ - */ - -#define IS_FMPI2C_ADDRESSING_MODE(MODE) (((MODE) == FMPI2C_ADDRESSINGMODE_7BIT) || \ - ((MODE) == FMPI2C_ADDRESSINGMODE_10BIT)) - -#define IS_FMPI2C_DUAL_ADDRESS(ADDRESS) (((ADDRESS) == FMPI2C_DUALADDRESS_DISABLE) || \ - ((ADDRESS) == FMPI2C_DUALADDRESS_ENABLE)) - -#define IS_FMPI2C_OWN_ADDRESS2_MASK(MASK) (((MASK) == FMPI2C_OA2_NOMASK) || \ - ((MASK) == FMPI2C_OA2_MASK01) || \ - ((MASK) == FMPI2C_OA2_MASK02) || \ - ((MASK) == FMPI2C_OA2_MASK03) || \ - ((MASK) == FMPI2C_OA2_MASK04) || \ - ((MASK) == FMPI2C_OA2_MASK05) || \ - ((MASK) == FMPI2C_OA2_MASK06) || \ - ((MASK) == FMPI2C_OA2_MASK07)) - -#define IS_FMPI2C_GENERAL_CALL(CALL) (((CALL) == FMPI2C_GENERALCALL_DISABLE) || \ - ((CALL) == FMPI2C_GENERALCALL_ENABLE)) - -#define IS_FMPI2C_NO_STRETCH(STRETCH) (((STRETCH) == FMPI2C_NOSTRETCH_DISABLE) || \ - ((STRETCH) == FMPI2C_NOSTRETCH_ENABLE)) - -#define IS_FMPI2C_MEMADD_SIZE(SIZE) (((SIZE) == FMPI2C_MEMADD_SIZE_8BIT) || \ - ((SIZE) == FMPI2C_MEMADD_SIZE_16BIT)) - -#define IS_TRANSFER_MODE(MODE) (((MODE) == FMPI2C_RELOAD_MODE) || \ - ((MODE) == FMPI2C_AUTOEND_MODE) || \ - ((MODE) == FMPI2C_SOFTEND_MODE)) - -#define IS_TRANSFER_REQUEST(REQUEST) (((REQUEST) == FMPI2C_GENERATE_STOP) || \ - ((REQUEST) == FMPI2C_GENERATE_START_READ) || \ - ((REQUEST) == FMPI2C_GENERATE_START_WRITE) || \ - ((REQUEST) == FMPI2C_NO_STARTSTOP)) - -#define IS_FMPI2C_TRANSFER_OPTIONS_REQUEST(REQUEST) (((REQUEST) == FMPI2C_FIRST_FRAME) || \ - ((REQUEST) == FMPI2C_FIRST_AND_NEXT_FRAME) || \ - ((REQUEST) == FMPI2C_NEXT_FRAME) || \ - ((REQUEST) == FMPI2C_FIRST_AND_LAST_FRAME) || \ - ((REQUEST) == FMPI2C_LAST_FRAME) || \ - ((REQUEST) == FMPI2C_LAST_FRAME_NO_STOP) || \ - IS_FMPI2C_TRANSFER_OTHER_OPTIONS_REQUEST(REQUEST)) - -#define IS_FMPI2C_TRANSFER_OTHER_OPTIONS_REQUEST(REQUEST) (((REQUEST) == FMPI2C_OTHER_FRAME) || \ - ((REQUEST) == FMPI2C_OTHER_AND_LAST_FRAME)) - -#define FMPI2C_RESET_CR2(__HANDLE__) ((__HANDLE__)->Instance->CR2 &= \ - (uint32_t)~((uint32_t)(FMPI2C_CR2_SADD | FMPI2C_CR2_HEAD10R | \ - FMPI2C_CR2_NBYTES | FMPI2C_CR2_RELOAD | \ - FMPI2C_CR2_RD_WRN))) - -#define FMPI2C_GET_ADDR_MATCH(__HANDLE__) ((uint16_t)(((__HANDLE__)->Instance->ISR & FMPI2C_ISR_ADDCODE) \ - >> 16U)) -#define FMPI2C_GET_DIR(__HANDLE__) ((uint8_t)(((__HANDLE__)->Instance->ISR & FMPI2C_ISR_DIR) \ - >> 16U)) -#define FMPI2C_GET_STOP_MODE(__HANDLE__) ((__HANDLE__)->Instance->CR2 & FMPI2C_CR2_AUTOEND) -#define FMPI2C_GET_OWN_ADDRESS1(__HANDLE__) ((uint16_t)((__HANDLE__)->Instance->OAR1 & FMPI2C_OAR1_OA1)) -#define FMPI2C_GET_OWN_ADDRESS2(__HANDLE__) ((uint16_t)((__HANDLE__)->Instance->OAR2 & FMPI2C_OAR2_OA2)) - -#define IS_FMPI2C_OWN_ADDRESS1(ADDRESS1) ((ADDRESS1) <= 0x000003FFU) -#define IS_FMPI2C_OWN_ADDRESS2(ADDRESS2) ((ADDRESS2) <= (uint16_t)0x00FFU) - -#define FMPI2C_MEM_ADD_MSB(__ADDRESS__) ((uint8_t)((uint16_t)(((uint16_t)((__ADDRESS__) & \ - (uint16_t)(0xFF00U))) >> 8U))) -#define FMPI2C_MEM_ADD_LSB(__ADDRESS__) ((uint8_t)((uint16_t)((__ADDRESS__) & (uint16_t)(0x00FFU)))) - -#define FMPI2C_GENERATE_START(__ADDMODE__,__ADDRESS__) (((__ADDMODE__) == FMPI2C_ADDRESSINGMODE_7BIT) ? \ - (uint32_t)((((uint32_t)(__ADDRESS__) & (FMPI2C_CR2_SADD)) | \ - (FMPI2C_CR2_START) | (FMPI2C_CR2_AUTOEND)) & \ - (~FMPI2C_CR2_RD_WRN)) : \ - (uint32_t)((((uint32_t)(__ADDRESS__) & (FMPI2C_CR2_SADD)) | \ - (FMPI2C_CR2_ADD10) | (FMPI2C_CR2_START)) & \ - (~FMPI2C_CR2_RD_WRN))) - -#define FMPI2C_CHECK_FLAG(__ISR__, __FLAG__) ((((__ISR__) & ((__FLAG__) & FMPI2C_FLAG_MASK)) == \ - ((__FLAG__) & FMPI2C_FLAG_MASK)) ? SET : RESET) -#define FMPI2C_CHECK_IT_SOURCE(__CR1__, __IT__) ((((__CR1__) & (__IT__)) == (__IT__)) ? SET : RESET) -/** - * @} - */ - -/* Private Functions ---------------------------------------------------------*/ -/** @defgroup FMPI2C_Private_Functions FMPI2C Private Functions - * @{ - */ -/* Private functions are defined in stm32f4xx_hal_fmpi2c.c file */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* FMPI2C_CR1_PE */ -#ifdef __cplusplus -} -#endif - - -#endif /* STM32F4xx_HAL_FMPI2C_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_fmpi2c_ex.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_fmpi2c_ex.h deleted file mode 100644 index 6a5df0b..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_fmpi2c_ex.h +++ /dev/null @@ -1,153 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_fmpi2c_ex.h - * @author MCD Application Team - * @brief Header file of FMPI2C HAL Extended module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_FMPI2C_EX_H -#define STM32F4xx_HAL_FMPI2C_EX_H - -#ifdef __cplusplus -extern "C" { -#endif - -#if defined(FMPI2C_CR1_PE) -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup FMPI2CEx - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/** @defgroup FMPI2CEx_Exported_Constants FMPI2C Extended Exported Constants - * @{ - */ - -/** @defgroup FMPI2CEx_Analog_Filter FMPI2C Extended Analog Filter - * @{ - */ -#define FMPI2C_ANALOGFILTER_ENABLE 0x00000000U -#define FMPI2C_ANALOGFILTER_DISABLE FMPI2C_CR1_ANFOFF -/** - * @} - */ - -/** @defgroup FMPI2CEx_FastModePlus FMPI2C Extended Fast Mode Plus - * @{ - */ -#define FMPI2C_FASTMODEPLUS_SCL SYSCFG_CFGR_FMPI2C1_SCL /*!< Enable Fast Mode Plus on FMPI2C1 SCL pins */ -#define FMPI2C_FASTMODEPLUS_SDA SYSCFG_CFGR_FMPI2C1_SDA /*!< Enable Fast Mode Plus on FMPI2C1 SDA pins */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup FMPI2CEx_Exported_Macros FMPI2C Extended Exported Macros - * @{ - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup FMPI2CEx_Exported_Functions FMPI2C Extended Exported Functions - * @{ - */ - -/** @addtogroup FMPI2CEx_Exported_Functions_Group1 Filter Mode Functions - * @{ - */ -/* Peripheral Control functions ************************************************/ -HAL_StatusTypeDef HAL_FMPI2CEx_ConfigAnalogFilter(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t AnalogFilter); -HAL_StatusTypeDef HAL_FMPI2CEx_ConfigDigitalFilter(FMPI2C_HandleTypeDef *hfmpi2c, uint32_t DigitalFilter); -/** - * @} - */ - -/** @addtogroup FMPI2CEx_Exported_Functions_Group3 Fast Mode Plus Functions - * @{ - */ -void HAL_FMPI2CEx_EnableFastModePlus(uint32_t ConfigFastModePlus); -void HAL_FMPI2CEx_DisableFastModePlus(uint32_t ConfigFastModePlus); -/** - * @} - */ - -/** - * @} - */ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup FMPI2CEx_Private_Constants FMPI2C Extended Private Constants - * @{ - */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup FMPI2CEx_Private_Macro FMPI2C Extended Private Macros - * @{ - */ -#define IS_FMPI2C_ANALOG_FILTER(FILTER) (((FILTER) == FMPI2C_ANALOGFILTER_ENABLE) || \ - ((FILTER) == FMPI2C_ANALOGFILTER_DISABLE)) - -#define IS_FMPI2C_DIGITAL_FILTER(FILTER) ((FILTER) <= 0x0000000FU) - -#define IS_FMPI2C_FASTMODEPLUS(__CONFIG__) ((((__CONFIG__) & (FMPI2C_FASTMODEPLUS_SCL)) == FMPI2C_FASTMODEPLUS_SCL) || \ - (((__CONFIG__) & (FMPI2C_FASTMODEPLUS_SDA)) == FMPI2C_FASTMODEPLUS_SDA)) -/** - * @} - */ - -/* Private Functions ---------------------------------------------------------*/ -/** @defgroup FMPI2CEx_Private_Functions FMPI2C Extended Private Functions - * @{ - */ -/* Private functions are defined in stm32f4xx_hal_fmpi2c_ex.c file */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* FMPI2C_CR1_PE */ -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_HAL_FMPI2C_EX_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_fmpsmbus.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_fmpsmbus.h deleted file mode 100644 index 9d5e030..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_fmpsmbus.h +++ /dev/null @@ -1,793 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_fmpsmbus.h - * @author MCD Application Team - * @brief Header file of FMPSMBUS HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_FMPSMBUS_H -#define STM32F4xx_HAL_FMPSMBUS_H - -#ifdef __cplusplus -extern "C" { -#endif - -#if defined(FMPI2C_CR1_PE) -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup FMPSMBUS - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup FMPSMBUS_Exported_Types FMPSMBUS Exported Types - * @{ - */ - -/** @defgroup FMPSMBUS_Configuration_Structure_definition FMPSMBUS Configuration Structure definition - * @brief FMPSMBUS Configuration Structure definition - * @{ - */ -typedef struct -{ - uint32_t Timing; /*!< Specifies the FMPSMBUS_TIMINGR_register value. - This parameter calculated by referring to FMPSMBUS initialization section - in Reference manual */ - uint32_t AnalogFilter; /*!< Specifies if Analog Filter is enable or not. - This parameter can be a value of @ref FMPSMBUS_Analog_Filter */ - - uint32_t OwnAddress1; /*!< Specifies the first device own address. - This parameter can be a 7-bit or 10-bit address. */ - - uint32_t AddressingMode; /*!< Specifies if 7-bit or 10-bit addressing mode for master is selected. - This parameter can be a value of @ref FMPSMBUS_addressing_mode */ - - uint32_t DualAddressMode; /*!< Specifies if dual addressing mode is selected. - This parameter can be a value of @ref FMPSMBUS_dual_addressing_mode */ - - uint32_t OwnAddress2; /*!< Specifies the second device own address if dual addressing mode is selected - This parameter can be a 7-bit address. */ - - uint32_t OwnAddress2Masks; /*!< Specifies the acknowledge mask address second device own address - if dual addressing mode is selected - This parameter can be a value of @ref FMPSMBUS_own_address2_masks. */ - - uint32_t GeneralCallMode; /*!< Specifies if general call mode is selected. - This parameter can be a value of @ref FMPSMBUS_general_call_addressing_mode. */ - - uint32_t NoStretchMode; /*!< Specifies if nostretch mode is selected. - This parameter can be a value of @ref FMPSMBUS_nostretch_mode */ - - uint32_t PacketErrorCheckMode; /*!< Specifies if Packet Error Check mode is selected. - This parameter can be a value of @ref FMPSMBUS_packet_error_check_mode */ - - uint32_t PeripheralMode; /*!< Specifies which mode of Periphal is selected. - This parameter can be a value of @ref FMPSMBUS_peripheral_mode */ - - uint32_t SMBusTimeout; /*!< Specifies the content of the 32 Bits FMPSMBUS_TIMEOUT_register value. - (Enable bits and different timeout values) - This parameter calculated by referring to FMPSMBUS initialization section - in Reference manual */ -} FMPSMBUS_InitTypeDef; -/** - * @} - */ - -/** @defgroup HAL_state_definition HAL state definition - * @brief HAL State definition - * @{ - */ -#define HAL_FMPSMBUS_STATE_RESET (0x00000000U) /*!< FMPSMBUS not yet initialized or disabled */ -#define HAL_FMPSMBUS_STATE_READY (0x00000001U) /*!< FMPSMBUS initialized and ready for use */ -#define HAL_FMPSMBUS_STATE_BUSY (0x00000002U) /*!< FMPSMBUS internal process is ongoing */ -#define HAL_FMPSMBUS_STATE_MASTER_BUSY_TX (0x00000012U) /*!< Master Data Transmission process is ongoing */ -#define HAL_FMPSMBUS_STATE_MASTER_BUSY_RX (0x00000022U) /*!< Master Data Reception process is ongoing */ -#define HAL_FMPSMBUS_STATE_SLAVE_BUSY_TX (0x00000032U) /*!< Slave Data Transmission process is ongoing */ -#define HAL_FMPSMBUS_STATE_SLAVE_BUSY_RX (0x00000042U) /*!< Slave Data Reception process is ongoing */ -#define HAL_FMPSMBUS_STATE_TIMEOUT (0x00000003U) /*!< Timeout state */ -#define HAL_FMPSMBUS_STATE_ERROR (0x00000004U) /*!< Reception process is ongoing */ -#define HAL_FMPSMBUS_STATE_LISTEN (0x00000008U) /*!< Address Listen Mode is ongoing */ -/** - * @} - */ - -/** @defgroup FMPSMBUS_Error_Code_definition FMPSMBUS Error Code definition - * @brief FMPSMBUS Error Code definition - * @{ - */ -#define HAL_FMPSMBUS_ERROR_NONE (0x00000000U) /*!< No error */ -#define HAL_FMPSMBUS_ERROR_BERR (0x00000001U) /*!< BERR error */ -#define HAL_FMPSMBUS_ERROR_ARLO (0x00000002U) /*!< ARLO error */ -#define HAL_FMPSMBUS_ERROR_ACKF (0x00000004U) /*!< ACKF error */ -#define HAL_FMPSMBUS_ERROR_OVR (0x00000008U) /*!< OVR error */ -#define HAL_FMPSMBUS_ERROR_HALTIMEOUT (0x00000010U) /*!< Timeout error */ -#define HAL_FMPSMBUS_ERROR_BUSTIMEOUT (0x00000020U) /*!< Bus Timeout error */ -#define HAL_FMPSMBUS_ERROR_ALERT (0x00000040U) /*!< Alert error */ -#define HAL_FMPSMBUS_ERROR_PECERR (0x00000080U) /*!< PEC error */ -#if (USE_HAL_FMPSMBUS_REGISTER_CALLBACKS == 1) -#define HAL_FMPSMBUS_ERROR_INVALID_CALLBACK (0x00000100U) /*!< Invalid Callback error */ -#endif /* USE_HAL_FMPSMBUS_REGISTER_CALLBACKS */ -#define HAL_FMPSMBUS_ERROR_INVALID_PARAM (0x00000200U) /*!< Invalid Parameters error */ -/** - * @} - */ - -/** @defgroup FMPSMBUS_handle_Structure_definition FMPSMBUS handle Structure definition - * @brief FMPSMBUS handle Structure definition - * @{ - */ -#if (USE_HAL_FMPSMBUS_REGISTER_CALLBACKS == 1) -typedef struct __FMPSMBUS_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_FMPSMBUS_REGISTER_CALLBACKS */ -{ - FMPI2C_TypeDef *Instance; /*!< FMPSMBUS registers base address */ - - FMPSMBUS_InitTypeDef Init; /*!< FMPSMBUS communication parameters */ - - uint8_t *pBuffPtr; /*!< Pointer to FMPSMBUS transfer buffer */ - - uint16_t XferSize; /*!< FMPSMBUS transfer size */ - - __IO uint16_t XferCount; /*!< FMPSMBUS transfer counter */ - - __IO uint32_t XferOptions; /*!< FMPSMBUS transfer options */ - - __IO uint32_t PreviousState; /*!< FMPSMBUS communication Previous state */ - - HAL_LockTypeDef Lock; /*!< FMPSMBUS locking object */ - - __IO uint32_t State; /*!< FMPSMBUS communication state */ - - __IO uint32_t ErrorCode; /*!< FMPSMBUS Error code */ - -#if (USE_HAL_FMPSMBUS_REGISTER_CALLBACKS == 1) - void (* MasterTxCpltCallback)(struct __FMPSMBUS_HandleTypeDef *hfmpsmbus); - /*!< FMPSMBUS Master Tx Transfer completed callback */ - void (* MasterRxCpltCallback)(struct __FMPSMBUS_HandleTypeDef *hfmpsmbus); - /*!< FMPSMBUS Master Rx Transfer completed callback */ - void (* SlaveTxCpltCallback)(struct __FMPSMBUS_HandleTypeDef *hfmpsmbus); - /*!< FMPSMBUS Slave Tx Transfer completed callback */ - void (* SlaveRxCpltCallback)(struct __FMPSMBUS_HandleTypeDef *hfmpsmbus); - /*!< FMPSMBUS Slave Rx Transfer completed callback */ - void (* ListenCpltCallback)(struct __FMPSMBUS_HandleTypeDef *hfmpsmbus); - /*!< FMPSMBUS Listen Complete callback */ - void (* ErrorCallback)(struct __FMPSMBUS_HandleTypeDef *hfmpsmbus); - /*!< FMPSMBUS Error callback */ - - void (* AddrCallback)(struct __FMPSMBUS_HandleTypeDef *hfmpsmbus, uint8_t TransferDirection, uint16_t AddrMatchCode); - /*!< FMPSMBUS Slave Address Match callback */ - - void (* MspInitCallback)(struct __FMPSMBUS_HandleTypeDef *hfmpsmbus); - /*!< FMPSMBUS Msp Init callback */ - void (* MspDeInitCallback)(struct __FMPSMBUS_HandleTypeDef *hfmpsmbus); - /*!< FMPSMBUS Msp DeInit callback */ - -#endif /* USE_HAL_FMPSMBUS_REGISTER_CALLBACKS */ -} FMPSMBUS_HandleTypeDef; - -#if (USE_HAL_FMPSMBUS_REGISTER_CALLBACKS == 1) -/** - * @brief HAL FMPSMBUS Callback ID enumeration definition - */ -typedef enum -{ - HAL_FMPSMBUS_MASTER_TX_COMPLETE_CB_ID = 0x00U, /*!< FMPSMBUS Master Tx Transfer completed callback ID */ - HAL_FMPSMBUS_MASTER_RX_COMPLETE_CB_ID = 0x01U, /*!< FMPSMBUS Master Rx Transfer completed callback ID */ - HAL_FMPSMBUS_SLAVE_TX_COMPLETE_CB_ID = 0x02U, /*!< FMPSMBUS Slave Tx Transfer completed callback ID */ - HAL_FMPSMBUS_SLAVE_RX_COMPLETE_CB_ID = 0x03U, /*!< FMPSMBUS Slave Rx Transfer completed callback ID */ - HAL_FMPSMBUS_LISTEN_COMPLETE_CB_ID = 0x04U, /*!< FMPSMBUS Listen Complete callback ID */ - HAL_FMPSMBUS_ERROR_CB_ID = 0x05U, /*!< FMPSMBUS Error callback ID */ - - HAL_FMPSMBUS_MSPINIT_CB_ID = 0x06U, /*!< FMPSMBUS Msp Init callback ID */ - HAL_FMPSMBUS_MSPDEINIT_CB_ID = 0x07U /*!< FMPSMBUS Msp DeInit callback ID */ - -} HAL_FMPSMBUS_CallbackIDTypeDef; - -/** - * @brief HAL FMPSMBUS Callback pointer definition - */ -typedef void (*pFMPSMBUS_CallbackTypeDef)(FMPSMBUS_HandleTypeDef *hfmpsmbus); -/*!< pointer to an FMPSMBUS callback function */ -typedef void (*pFMPSMBUS_AddrCallbackTypeDef)(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint8_t TransferDirection, - uint16_t AddrMatchCode); -/*!< pointer to an FMPSMBUS Address Match callback function */ - -#endif /* USE_HAL_FMPSMBUS_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** - * @} - */ -/* Exported constants --------------------------------------------------------*/ - -/** @defgroup FMPSMBUS_Exported_Constants FMPSMBUS Exported Constants - * @{ - */ - -/** @defgroup FMPSMBUS_Analog_Filter FMPSMBUS Analog Filter - * @{ - */ -#define FMPSMBUS_ANALOGFILTER_ENABLE (0x00000000U) -#define FMPSMBUS_ANALOGFILTER_DISABLE FMPI2C_CR1_ANFOFF -/** - * @} - */ - -/** @defgroup FMPSMBUS_addressing_mode FMPSMBUS addressing mode - * @{ - */ -#define FMPSMBUS_ADDRESSINGMODE_7BIT (0x00000001U) -#define FMPSMBUS_ADDRESSINGMODE_10BIT (0x00000002U) -/** - * @} - */ - -/** @defgroup FMPSMBUS_dual_addressing_mode FMPSMBUS dual addressing mode - * @{ - */ - -#define FMPSMBUS_DUALADDRESS_DISABLE (0x00000000U) -#define FMPSMBUS_DUALADDRESS_ENABLE FMPI2C_OAR2_OA2EN -/** - * @} - */ - -/** @defgroup FMPSMBUS_own_address2_masks FMPSMBUS ownaddress2 masks - * @{ - */ - -#define FMPSMBUS_OA2_NOMASK ((uint8_t)0x00U) -#define FMPSMBUS_OA2_MASK01 ((uint8_t)0x01U) -#define FMPSMBUS_OA2_MASK02 ((uint8_t)0x02U) -#define FMPSMBUS_OA2_MASK03 ((uint8_t)0x03U) -#define FMPSMBUS_OA2_MASK04 ((uint8_t)0x04U) -#define FMPSMBUS_OA2_MASK05 ((uint8_t)0x05U) -#define FMPSMBUS_OA2_MASK06 ((uint8_t)0x06U) -#define FMPSMBUS_OA2_MASK07 ((uint8_t)0x07U) -/** - * @} - */ - - -/** @defgroup FMPSMBUS_general_call_addressing_mode FMPSMBUS general call addressing mode - * @{ - */ -#define FMPSMBUS_GENERALCALL_DISABLE (0x00000000U) -#define FMPSMBUS_GENERALCALL_ENABLE FMPI2C_CR1_GCEN -/** - * @} - */ - -/** @defgroup FMPSMBUS_nostretch_mode FMPSMBUS nostretch mode - * @{ - */ -#define FMPSMBUS_NOSTRETCH_DISABLE (0x00000000U) -#define FMPSMBUS_NOSTRETCH_ENABLE FMPI2C_CR1_NOSTRETCH -/** - * @} - */ - -/** @defgroup FMPSMBUS_packet_error_check_mode FMPSMBUS packet error check mode - * @{ - */ -#define FMPSMBUS_PEC_DISABLE (0x00000000U) -#define FMPSMBUS_PEC_ENABLE FMPI2C_CR1_PECEN -/** - * @} - */ - -/** @defgroup FMPSMBUS_peripheral_mode FMPSMBUS peripheral mode - * @{ - */ -#define FMPSMBUS_PERIPHERAL_MODE_FMPSMBUS_HOST FMPI2C_CR1_SMBHEN -#define FMPSMBUS_PERIPHERAL_MODE_FMPSMBUS_SLAVE (0x00000000U) -#define FMPSMBUS_PERIPHERAL_MODE_FMPSMBUS_SLAVE_ARP FMPI2C_CR1_SMBDEN -/** - * @} - */ - -/** @defgroup FMPSMBUS_ReloadEndMode_definition FMPSMBUS ReloadEndMode definition - * @{ - */ - -#define FMPSMBUS_SOFTEND_MODE (0x00000000U) -#define FMPSMBUS_RELOAD_MODE FMPI2C_CR2_RELOAD -#define FMPSMBUS_AUTOEND_MODE FMPI2C_CR2_AUTOEND -#define FMPSMBUS_SENDPEC_MODE FMPI2C_CR2_PECBYTE -/** - * @} - */ - -/** @defgroup FMPSMBUS_StartStopMode_definition FMPSMBUS StartStopMode definition - * @{ - */ - -#define FMPSMBUS_NO_STARTSTOP (0x00000000U) -#define FMPSMBUS_GENERATE_STOP (uint32_t)(0x80000000U | FMPI2C_CR2_STOP) -#define FMPSMBUS_GENERATE_START_READ (uint32_t)(0x80000000U | FMPI2C_CR2_START | FMPI2C_CR2_RD_WRN) -#define FMPSMBUS_GENERATE_START_WRITE (uint32_t)(0x80000000U | FMPI2C_CR2_START) -/** - * @} - */ - -/** @defgroup FMPSMBUS_XferOptions_definition FMPSMBUS XferOptions definition - * @{ - */ - -/* List of XferOptions in usage of : - * 1- Restart condition when direction change - * 2- No Restart condition in other use cases - */ -#define FMPSMBUS_FIRST_FRAME FMPSMBUS_SOFTEND_MODE -#define FMPSMBUS_NEXT_FRAME ((uint32_t)(FMPSMBUS_RELOAD_MODE | FMPSMBUS_SOFTEND_MODE)) -#define FMPSMBUS_FIRST_AND_LAST_FRAME_NO_PEC FMPSMBUS_AUTOEND_MODE -#define FMPSMBUS_LAST_FRAME_NO_PEC FMPSMBUS_AUTOEND_MODE -#define FMPSMBUS_FIRST_FRAME_WITH_PEC ((uint32_t)(FMPSMBUS_SOFTEND_MODE | FMPSMBUS_SENDPEC_MODE)) -#define FMPSMBUS_FIRST_AND_LAST_FRAME_WITH_PEC ((uint32_t)(FMPSMBUS_AUTOEND_MODE | FMPSMBUS_SENDPEC_MODE)) -#define FMPSMBUS_LAST_FRAME_WITH_PEC ((uint32_t)(FMPSMBUS_AUTOEND_MODE | FMPSMBUS_SENDPEC_MODE)) - -/* List of XferOptions in usage of : - * 1- Restart condition in all use cases (direction change or not) - */ -#define FMPSMBUS_OTHER_FRAME_NO_PEC (0x000000AAU) -#define FMPSMBUS_OTHER_FRAME_WITH_PEC (0x0000AA00U) -#define FMPSMBUS_OTHER_AND_LAST_FRAME_NO_PEC (0x00AA0000U) -#define FMPSMBUS_OTHER_AND_LAST_FRAME_WITH_PEC (0xAA000000U) -/** - * @} - */ - -/** @defgroup FMPSMBUS_Interrupt_configuration_definition FMPSMBUS Interrupt configuration definition - * @brief FMPSMBUS Interrupt definition - * Elements values convention: 0xXXXXXXXX - * - XXXXXXXX : Interrupt control mask - * @{ - */ -#define FMPSMBUS_IT_ERRI FMPI2C_CR1_ERRIE -#define FMPSMBUS_IT_TCI FMPI2C_CR1_TCIE -#define FMPSMBUS_IT_STOPI FMPI2C_CR1_STOPIE -#define FMPSMBUS_IT_NACKI FMPI2C_CR1_NACKIE -#define FMPSMBUS_IT_ADDRI FMPI2C_CR1_ADDRIE -#define FMPSMBUS_IT_RXI FMPI2C_CR1_RXIE -#define FMPSMBUS_IT_TXI FMPI2C_CR1_TXIE -#define FMPSMBUS_IT_TX (FMPSMBUS_IT_ERRI | FMPSMBUS_IT_TCI | FMPSMBUS_IT_STOPI | \ - FMPSMBUS_IT_NACKI | FMPSMBUS_IT_TXI) -#define FMPSMBUS_IT_RX (FMPSMBUS_IT_ERRI | FMPSMBUS_IT_TCI | FMPSMBUS_IT_NACKI | \ - FMPSMBUS_IT_RXI) -#define FMPSMBUS_IT_ALERT (FMPSMBUS_IT_ERRI) -#define FMPSMBUS_IT_ADDR (FMPSMBUS_IT_ADDRI | FMPSMBUS_IT_STOPI | FMPSMBUS_IT_NACKI) -/** - * @} - */ - -/** @defgroup FMPSMBUS_Flag_definition FMPSMBUS Flag definition - * @brief Flag definition - * Elements values convention: 0xXXXXYYYY - * - XXXXXXXX : Flag mask - * @{ - */ - -#define FMPSMBUS_FLAG_TXE FMPI2C_ISR_TXE -#define FMPSMBUS_FLAG_TXIS FMPI2C_ISR_TXIS -#define FMPSMBUS_FLAG_RXNE FMPI2C_ISR_RXNE -#define FMPSMBUS_FLAG_ADDR FMPI2C_ISR_ADDR -#define FMPSMBUS_FLAG_AF FMPI2C_ISR_NACKF -#define FMPSMBUS_FLAG_STOPF FMPI2C_ISR_STOPF -#define FMPSMBUS_FLAG_TC FMPI2C_ISR_TC -#define FMPSMBUS_FLAG_TCR FMPI2C_ISR_TCR -#define FMPSMBUS_FLAG_BERR FMPI2C_ISR_BERR -#define FMPSMBUS_FLAG_ARLO FMPI2C_ISR_ARLO -#define FMPSMBUS_FLAG_OVR FMPI2C_ISR_OVR -#define FMPSMBUS_FLAG_PECERR FMPI2C_ISR_PECERR -#define FMPSMBUS_FLAG_TIMEOUT FMPI2C_ISR_TIMEOUT -#define FMPSMBUS_FLAG_ALERT FMPI2C_ISR_ALERT -#define FMPSMBUS_FLAG_BUSY FMPI2C_ISR_BUSY -#define FMPSMBUS_FLAG_DIR FMPI2C_ISR_DIR -/** - * @} - */ - -/** - * @} - */ - -/* Exported macros ------------------------------------------------------------*/ -/** @defgroup FMPSMBUS_Exported_Macros FMPSMBUS Exported Macros - * @{ - */ - -/** @brief Reset FMPSMBUS handle state. - * @param __HANDLE__ specifies the FMPSMBUS Handle. - * @retval None - */ -#if (USE_HAL_FMPSMBUS_REGISTER_CALLBACKS == 1) -#define __HAL_FMPSMBUS_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->State = HAL_FMPSMBUS_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_FMPSMBUS_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_FMPSMBUS_STATE_RESET) -#endif /* USE_HAL_FMPSMBUS_REGISTER_CALLBACKS */ - -/** @brief Enable the specified FMPSMBUS interrupts. - * @param __HANDLE__ specifies the FMPSMBUS Handle. - * @param __INTERRUPT__ specifies the interrupt source to enable. - * This parameter can be one of the following values: - * @arg @ref FMPSMBUS_IT_ERRI Errors interrupt enable - * @arg @ref FMPSMBUS_IT_TCI Transfer complete interrupt enable - * @arg @ref FMPSMBUS_IT_STOPI STOP detection interrupt enable - * @arg @ref FMPSMBUS_IT_NACKI NACK received interrupt enable - * @arg @ref FMPSMBUS_IT_ADDRI Address match interrupt enable - * @arg @ref FMPSMBUS_IT_RXI RX interrupt enable - * @arg @ref FMPSMBUS_IT_TXI TX interrupt enable - * - * @retval None - */ -#define __HAL_FMPSMBUS_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR1 |= (__INTERRUPT__)) - -/** @brief Disable the specified FMPSMBUS interrupts. - * @param __HANDLE__ specifies the FMPSMBUS Handle. - * @param __INTERRUPT__ specifies the interrupt source to disable. - * This parameter can be one of the following values: - * @arg @ref FMPSMBUS_IT_ERRI Errors interrupt enable - * @arg @ref FMPSMBUS_IT_TCI Transfer complete interrupt enable - * @arg @ref FMPSMBUS_IT_STOPI STOP detection interrupt enable - * @arg @ref FMPSMBUS_IT_NACKI NACK received interrupt enable - * @arg @ref FMPSMBUS_IT_ADDRI Address match interrupt enable - * @arg @ref FMPSMBUS_IT_RXI RX interrupt enable - * @arg @ref FMPSMBUS_IT_TXI TX interrupt enable - * - * @retval None - */ -#define __HAL_FMPSMBUS_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR1 &= (~(__INTERRUPT__))) - -/** @brief Check whether the specified FMPSMBUS interrupt source is enabled or not. - * @param __HANDLE__ specifies the FMPSMBUS Handle. - * @param __INTERRUPT__ specifies the FMPSMBUS interrupt source to check. - * This parameter can be one of the following values: - * @arg @ref FMPSMBUS_IT_ERRI Errors interrupt enable - * @arg @ref FMPSMBUS_IT_TCI Transfer complete interrupt enable - * @arg @ref FMPSMBUS_IT_STOPI STOP detection interrupt enable - * @arg @ref FMPSMBUS_IT_NACKI NACK received interrupt enable - * @arg @ref FMPSMBUS_IT_ADDRI Address match interrupt enable - * @arg @ref FMPSMBUS_IT_RXI RX interrupt enable - * @arg @ref FMPSMBUS_IT_TXI TX interrupt enable - * - * @retval The new state of __IT__ (SET or RESET). - */ -#define __HAL_FMPSMBUS_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) \ - ((((__HANDLE__)->Instance->CR1 & (__INTERRUPT__)) == (__INTERRUPT__)) ? SET : RESET) - -/** @brief Check whether the specified FMPSMBUS flag is set or not. - * @param __HANDLE__ specifies the FMPSMBUS Handle. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg @ref FMPSMBUS_FLAG_TXE Transmit data register empty - * @arg @ref FMPSMBUS_FLAG_TXIS Transmit interrupt status - * @arg @ref FMPSMBUS_FLAG_RXNE Receive data register not empty - * @arg @ref FMPSMBUS_FLAG_ADDR Address matched (slave mode) - * @arg @ref FMPSMBUS_FLAG_AF NACK received flag - * @arg @ref FMPSMBUS_FLAG_STOPF STOP detection flag - * @arg @ref FMPSMBUS_FLAG_TC Transfer complete (master mode) - * @arg @ref FMPSMBUS_FLAG_TCR Transfer complete reload - * @arg @ref FMPSMBUS_FLAG_BERR Bus error - * @arg @ref FMPSMBUS_FLAG_ARLO Arbitration lost - * @arg @ref FMPSMBUS_FLAG_OVR Overrun/Underrun - * @arg @ref FMPSMBUS_FLAG_PECERR PEC error in reception - * @arg @ref FMPSMBUS_FLAG_TIMEOUT Timeout or Tlow detection flag - * @arg @ref FMPSMBUS_FLAG_ALERT SMBus alert - * @arg @ref FMPSMBUS_FLAG_BUSY Bus busy - * @arg @ref FMPSMBUS_FLAG_DIR Transfer direction (slave mode) - * - * @retval The new state of __FLAG__ (SET or RESET). - */ -#define FMPSMBUS_FLAG_MASK (0x0001FFFFU) -#define __HAL_FMPSMBUS_GET_FLAG(__HANDLE__, __FLAG__) \ - (((((__HANDLE__)->Instance->ISR) & ((__FLAG__) & FMPSMBUS_FLAG_MASK)) == \ - ((__FLAG__) & FMPSMBUS_FLAG_MASK)) ? SET : RESET) - -/** @brief Clear the FMPSMBUS pending flags which are cleared by writing 1 in a specific bit. - * @param __HANDLE__ specifies the FMPSMBUS Handle. - * @param __FLAG__ specifies the flag to clear. - * This parameter can be any combination of the following values: - * @arg @ref FMPSMBUS_FLAG_ADDR Address matched (slave mode) - * @arg @ref FMPSMBUS_FLAG_AF NACK received flag - * @arg @ref FMPSMBUS_FLAG_STOPF STOP detection flag - * @arg @ref FMPSMBUS_FLAG_BERR Bus error - * @arg @ref FMPSMBUS_FLAG_ARLO Arbitration lost - * @arg @ref FMPSMBUS_FLAG_OVR Overrun/Underrun - * @arg @ref FMPSMBUS_FLAG_PECERR PEC error in reception - * @arg @ref FMPSMBUS_FLAG_TIMEOUT Timeout or Tlow detection flag - * @arg @ref FMPSMBUS_FLAG_ALERT SMBus alert - * - * @retval None - */ -#define __HAL_FMPSMBUS_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->ICR = (__FLAG__)) - -/** @brief Enable the specified FMPSMBUS peripheral. - * @param __HANDLE__ specifies the FMPSMBUS Handle. - * @retval None - */ -#define __HAL_FMPSMBUS_ENABLE(__HANDLE__) (SET_BIT((__HANDLE__)->Instance->CR1, FMPI2C_CR1_PE)) - -/** @brief Disable the specified FMPSMBUS peripheral. - * @param __HANDLE__ specifies the FMPSMBUS Handle. - * @retval None - */ -#define __HAL_FMPSMBUS_DISABLE(__HANDLE__) (CLEAR_BIT((__HANDLE__)->Instance->CR1, FMPI2C_CR1_PE)) - -/** @brief Generate a Non-Acknowledge FMPSMBUS peripheral in Slave mode. - * @param __HANDLE__ specifies the FMPSMBUS Handle. - * @retval None - */ -#define __HAL_FMPSMBUS_GENERATE_NACK(__HANDLE__) (SET_BIT((__HANDLE__)->Instance->CR2, FMPI2C_CR2_NACK)) - -/** - * @} - */ - - -/* Private constants ---------------------------------------------------------*/ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup FMPSMBUS_Private_Macro FMPSMBUS Private Macros - * @{ - */ - -#define IS_FMPSMBUS_ANALOG_FILTER(FILTER) (((FILTER) == FMPSMBUS_ANALOGFILTER_ENABLE) || \ - ((FILTER) == FMPSMBUS_ANALOGFILTER_DISABLE)) - -#define IS_FMPSMBUS_DIGITAL_FILTER(FILTER) ((FILTER) <= 0x0000000FU) - -#define IS_FMPSMBUS_ADDRESSING_MODE(MODE) (((MODE) == FMPSMBUS_ADDRESSINGMODE_7BIT) || \ - ((MODE) == FMPSMBUS_ADDRESSINGMODE_10BIT)) - -#define IS_FMPSMBUS_DUAL_ADDRESS(ADDRESS) (((ADDRESS) == FMPSMBUS_DUALADDRESS_DISABLE) || \ - ((ADDRESS) == FMPSMBUS_DUALADDRESS_ENABLE)) - -#define IS_FMPSMBUS_OWN_ADDRESS2_MASK(MASK) (((MASK) == FMPSMBUS_OA2_NOMASK) || \ - ((MASK) == FMPSMBUS_OA2_MASK01) || \ - ((MASK) == FMPSMBUS_OA2_MASK02) || \ - ((MASK) == FMPSMBUS_OA2_MASK03) || \ - ((MASK) == FMPSMBUS_OA2_MASK04) || \ - ((MASK) == FMPSMBUS_OA2_MASK05) || \ - ((MASK) == FMPSMBUS_OA2_MASK06) || \ - ((MASK) == FMPSMBUS_OA2_MASK07)) - -#define IS_FMPSMBUS_GENERAL_CALL(CALL) (((CALL) == FMPSMBUS_GENERALCALL_DISABLE) || \ - ((CALL) == FMPSMBUS_GENERALCALL_ENABLE)) - -#define IS_FMPSMBUS_NO_STRETCH(STRETCH) (((STRETCH) == FMPSMBUS_NOSTRETCH_DISABLE) || \ - ((STRETCH) == FMPSMBUS_NOSTRETCH_ENABLE)) - -#define IS_FMPSMBUS_PEC(PEC) (((PEC) == FMPSMBUS_PEC_DISABLE) || \ - ((PEC) == FMPSMBUS_PEC_ENABLE)) - -#define IS_FMPSMBUS_PERIPHERAL_MODE(MODE) (((MODE) == FMPSMBUS_PERIPHERAL_MODE_FMPSMBUS_HOST) || \ - ((MODE) == FMPSMBUS_PERIPHERAL_MODE_FMPSMBUS_SLAVE) || \ - ((MODE) == FMPSMBUS_PERIPHERAL_MODE_FMPSMBUS_SLAVE_ARP)) - -#define IS_FMPSMBUS_TRANSFER_MODE(MODE) (((MODE) == FMPSMBUS_RELOAD_MODE) || \ - ((MODE) == FMPSMBUS_AUTOEND_MODE) || \ - ((MODE) == FMPSMBUS_SOFTEND_MODE) || \ - ((MODE) == FMPSMBUS_SENDPEC_MODE) || \ - ((MODE) == (FMPSMBUS_RELOAD_MODE | FMPSMBUS_SENDPEC_MODE)) || \ - ((MODE) == (FMPSMBUS_AUTOEND_MODE | FMPSMBUS_SENDPEC_MODE)) || \ - ((MODE) == (FMPSMBUS_AUTOEND_MODE | FMPSMBUS_RELOAD_MODE)) || \ - ((MODE) == (FMPSMBUS_AUTOEND_MODE | FMPSMBUS_SENDPEC_MODE | \ - FMPSMBUS_RELOAD_MODE ))) - - -#define IS_FMPSMBUS_TRANSFER_REQUEST(REQUEST) (((REQUEST) == FMPSMBUS_GENERATE_STOP) || \ - ((REQUEST) == FMPSMBUS_GENERATE_START_READ) || \ - ((REQUEST) == FMPSMBUS_GENERATE_START_WRITE) || \ - ((REQUEST) == FMPSMBUS_NO_STARTSTOP)) - - -#define IS_FMPSMBUS_TRANSFER_OPTIONS_REQUEST(REQUEST) (IS_FMPSMBUS_TRANSFER_OTHER_OPTIONS_REQUEST(REQUEST) || \ - ((REQUEST) == FMPSMBUS_FIRST_FRAME) || \ - ((REQUEST) == FMPSMBUS_NEXT_FRAME) || \ - ((REQUEST) == FMPSMBUS_FIRST_AND_LAST_FRAME_NO_PEC) || \ - ((REQUEST) == FMPSMBUS_LAST_FRAME_NO_PEC) || \ - ((REQUEST) == FMPSMBUS_FIRST_FRAME_WITH_PEC) || \ - ((REQUEST) == FMPSMBUS_FIRST_AND_LAST_FRAME_WITH_PEC) || \ - ((REQUEST) == FMPSMBUS_LAST_FRAME_WITH_PEC)) - -#define IS_FMPSMBUS_TRANSFER_OTHER_OPTIONS_REQUEST(REQUEST) (((REQUEST) == FMPSMBUS_OTHER_FRAME_NO_PEC) || \ - ((REQUEST) == FMPSMBUS_OTHER_AND_LAST_FRAME_NO_PEC) || \ - ((REQUEST) == FMPSMBUS_OTHER_FRAME_WITH_PEC) || \ - ((REQUEST) == FMPSMBUS_OTHER_AND_LAST_FRAME_WITH_PEC)) - -#define FMPSMBUS_RESET_CR1(__HANDLE__) ((__HANDLE__)->Instance->CR1 &= \ - (uint32_t)~((uint32_t)(FMPI2C_CR1_SMBHEN | FMPI2C_CR1_SMBDEN | \ - FMPI2C_CR1_PECEN))) -#define FMPSMBUS_RESET_CR2(__HANDLE__) ((__HANDLE__)->Instance->CR2 &= \ - (uint32_t)~((uint32_t)(FMPI2C_CR2_SADD | FMPI2C_CR2_HEAD10R | \ - FMPI2C_CR2_NBYTES | FMPI2C_CR2_RELOAD | \ - FMPI2C_CR2_RD_WRN))) - -#define FMPSMBUS_GENERATE_START(__ADDMODE__,__ADDRESS__) (((__ADDMODE__) == FMPSMBUS_ADDRESSINGMODE_7BIT) ? \ - (uint32_t)((((uint32_t)(__ADDRESS__) & (FMPI2C_CR2_SADD)) | \ - (FMPI2C_CR2_START) | (FMPI2C_CR2_AUTOEND)) & \ - (~FMPI2C_CR2_RD_WRN)) : \ - (uint32_t)((((uint32_t)(__ADDRESS__) & \ - (FMPI2C_CR2_SADD)) | (FMPI2C_CR2_ADD10) | \ - (FMPI2C_CR2_START)) & (~FMPI2C_CR2_RD_WRN))) - -#define FMPSMBUS_GET_ADDR_MATCH(__HANDLE__) (((__HANDLE__)->Instance->ISR & FMPI2C_ISR_ADDCODE) >> 17U) -#define FMPSMBUS_GET_DIR(__HANDLE__) (((__HANDLE__)->Instance->ISR & FMPI2C_ISR_DIR) >> 16U) -#define FMPSMBUS_GET_STOP_MODE(__HANDLE__) ((__HANDLE__)->Instance->CR2 & FMPI2C_CR2_AUTOEND) -#define FMPSMBUS_GET_PEC_MODE(__HANDLE__) ((__HANDLE__)->Instance->CR2 & FMPI2C_CR2_PECBYTE) -#define FMPSMBUS_GET_ALERT_ENABLED(__HANDLE__) ((__HANDLE__)->Instance->CR1 & FMPI2C_CR1_ALERTEN) - -#define FMPSMBUS_CHECK_FLAG(__ISR__, __FLAG__) ((((__ISR__) & ((__FLAG__) & FMPSMBUS_FLAG_MASK)) == \ - ((__FLAG__) & FMPSMBUS_FLAG_MASK)) ? SET : RESET) -#define FMPSMBUS_CHECK_IT_SOURCE(__CR1__, __IT__) ((((__CR1__) & (__IT__)) == (__IT__)) ? SET : RESET) - -#define IS_FMPSMBUS_OWN_ADDRESS1(ADDRESS1) ((ADDRESS1) <= 0x000003FFU) -#define IS_FMPSMBUS_OWN_ADDRESS2(ADDRESS2) ((ADDRESS2) <= (uint16_t)0x00FFU) - -/** - * @} - */ - -/* Include FMPSMBUS HAL Extended module */ -#include "stm32f4xx_hal_fmpsmbus_ex.h" - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup FMPSMBUS_Exported_Functions FMPSMBUS Exported Functions - * @{ - */ - -/** @addtogroup FMPSMBUS_Exported_Functions_Group1 Initialization and de-initialization functions - * @{ - */ - -/* Initialization and de-initialization functions ****************************/ -HAL_StatusTypeDef HAL_FMPSMBUS_Init(FMPSMBUS_HandleTypeDef *hfmpsmbus); -HAL_StatusTypeDef HAL_FMPSMBUS_DeInit(FMPSMBUS_HandleTypeDef *hfmpsmbus); -void HAL_FMPSMBUS_MspInit(FMPSMBUS_HandleTypeDef *hfmpsmbus); -void HAL_FMPSMBUS_MspDeInit(FMPSMBUS_HandleTypeDef *hfmpsmbus); -HAL_StatusTypeDef HAL_FMPSMBUS_ConfigAnalogFilter(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint32_t AnalogFilter); -HAL_StatusTypeDef HAL_FMPSMBUS_ConfigDigitalFilter(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint32_t DigitalFilter); - -/* Callbacks Register/UnRegister functions ***********************************/ -#if (USE_HAL_FMPSMBUS_REGISTER_CALLBACKS == 1) -HAL_StatusTypeDef HAL_FMPSMBUS_RegisterCallback(FMPSMBUS_HandleTypeDef *hfmpsmbus, - HAL_FMPSMBUS_CallbackIDTypeDef CallbackID, - pFMPSMBUS_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_FMPSMBUS_UnRegisterCallback(FMPSMBUS_HandleTypeDef *hfmpsmbus, - HAL_FMPSMBUS_CallbackIDTypeDef CallbackID); - -HAL_StatusTypeDef HAL_FMPSMBUS_RegisterAddrCallback(FMPSMBUS_HandleTypeDef *hfmpsmbus, - pFMPSMBUS_AddrCallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_FMPSMBUS_UnRegisterAddrCallback(FMPSMBUS_HandleTypeDef *hfmpsmbus); -#endif /* USE_HAL_FMPSMBUS_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @addtogroup FMPSMBUS_Exported_Functions_Group2 Input and Output operation functions - * @{ - */ - -/* IO operation functions *****************************************************/ -/** @addtogroup Blocking_mode_Polling Blocking mode Polling - * @{ - */ -/******* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_FMPSMBUS_IsDeviceReady(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint16_t DevAddress, uint32_t Trials, - uint32_t Timeout); -/** - * @} - */ - -/** @addtogroup Non-Blocking_mode_Interrupt Non-Blocking mode Interrupt - * @{ - */ -/******* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_FMPSMBUS_Master_Transmit_IT(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint16_t DevAddress, - uint8_t *pData, uint16_t Size, uint32_t XferOptions); -HAL_StatusTypeDef HAL_FMPSMBUS_Master_Receive_IT(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint16_t DevAddress, - uint8_t *pData, uint16_t Size, uint32_t XferOptions); -HAL_StatusTypeDef HAL_FMPSMBUS_Master_Abort_IT(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint16_t DevAddress); -HAL_StatusTypeDef HAL_FMPSMBUS_Slave_Transmit_IT(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint8_t *pData, uint16_t Size, - uint32_t XferOptions); -HAL_StatusTypeDef HAL_FMPSMBUS_Slave_Receive_IT(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint8_t *pData, uint16_t Size, - uint32_t XferOptions); - -HAL_StatusTypeDef HAL_FMPSMBUS_EnableAlert_IT(FMPSMBUS_HandleTypeDef *hfmpsmbus); -HAL_StatusTypeDef HAL_FMPSMBUS_DisableAlert_IT(FMPSMBUS_HandleTypeDef *hfmpsmbus); -HAL_StatusTypeDef HAL_FMPSMBUS_EnableListen_IT(FMPSMBUS_HandleTypeDef *hfmpsmbus); -HAL_StatusTypeDef HAL_FMPSMBUS_DisableListen_IT(FMPSMBUS_HandleTypeDef *hfmpsmbus); -/** - * @} - */ - -/** @addtogroup FMPSMBUS_IRQ_Handler_and_Callbacks IRQ Handler and Callbacks - * @{ - */ -/******* FMPSMBUS IRQHandler and Callbacks used in non blocking modes (Interrupt) */ -void HAL_FMPSMBUS_EV_IRQHandler(FMPSMBUS_HandleTypeDef *hfmpsmbus); -void HAL_FMPSMBUS_ER_IRQHandler(FMPSMBUS_HandleTypeDef *hfmpsmbus); -void HAL_FMPSMBUS_MasterTxCpltCallback(FMPSMBUS_HandleTypeDef *hfmpsmbus); -void HAL_FMPSMBUS_MasterRxCpltCallback(FMPSMBUS_HandleTypeDef *hfmpsmbus); -void HAL_FMPSMBUS_SlaveTxCpltCallback(FMPSMBUS_HandleTypeDef *hfmpsmbus); -void HAL_FMPSMBUS_SlaveRxCpltCallback(FMPSMBUS_HandleTypeDef *hfmpsmbus); -void HAL_FMPSMBUS_AddrCallback(FMPSMBUS_HandleTypeDef *hfmpsmbus, uint8_t TransferDirection, uint16_t AddrMatchCode); -void HAL_FMPSMBUS_ListenCpltCallback(FMPSMBUS_HandleTypeDef *hfmpsmbus); -void HAL_FMPSMBUS_ErrorCallback(FMPSMBUS_HandleTypeDef *hfmpsmbus); - -/** - * @} - */ - -/** @addtogroup FMPSMBUS_Exported_Functions_Group3 Peripheral State and Errors functions - * @{ - */ - -/* Peripheral State and Errors functions **************************************************/ -uint32_t HAL_FMPSMBUS_GetState(FMPSMBUS_HandleTypeDef *hfmpsmbus); -uint32_t HAL_FMPSMBUS_GetError(FMPSMBUS_HandleTypeDef *hfmpsmbus); - -/** - * @} - */ - -/** - * @} - */ - -/* Private Functions ---------------------------------------------------------*/ -/** @defgroup FMPSMBUS_Private_Functions FMPSMBUS Private Functions - * @{ - */ -/* Private functions are defined in stm32f4xx_hal_fmpsmbus.c file */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* FMPI2C_CR1_PE */ -#ifdef __cplusplus -} -#endif - - -#endif /* STM32F4xx_HAL_FMPSMBUS_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_fmpsmbus_ex.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_fmpsmbus_ex.h deleted file mode 100644 index d5439e7..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_fmpsmbus_ex.h +++ /dev/null @@ -1,139 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_fmpsmbus_ex.h - * @author MCD Application Team - * @brief Header file of FMPSMBUS HAL Extended module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_FMPSMBUS_EX_H -#define STM32F4xx_HAL_FMPSMBUS_EX_H - -#ifdef __cplusplus -extern "C" { -#endif - -#if defined(FMPI2C_CR1_PE) -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup FMPSMBUSEx - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/** @defgroup FMPSMBUSEx_Exported_Constants FMPSMBUS Extended Exported Constants - * @{ - */ - -/** @defgroup FMPSMBUSEx_FastModePlus FMPSMBUS Extended Fast Mode Plus - * @{ - */ -#define FMPSMBUS_FASTMODEPLUS_SCL SYSCFG_CFGR_FMPI2C1_SCL /*!< Enable Fast Mode Plus on FMPI2C1 SCL pins */ -#define FMPSMBUS_FASTMODEPLUS_SDA SYSCFG_CFGR_FMPI2C1_SDA /*!< Enable Fast Mode Plus on FMPI2C1 SDA pins */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup FMPSMBUSEx_Exported_Macros FMPSMBUS Extended Exported Macros - * @{ - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup FMPSMBUSEx_Exported_Functions FMPSMBUS Extended Exported Functions - * @{ - */ - -/** @addtogroup FMPSMBUSEx_Exported_Functions_Group2 WakeUp Mode Functions - * @{ - */ -/* Peripheral Control functions ************************************************/ -/** - * @} - */ - -/** @addtogroup FMPSMBUSEx_Exported_Functions_Group3 Fast Mode Plus Functions - * @{ - */ -void HAL_FMPSMBUSEx_EnableFastModePlus(uint32_t ConfigFastModePlus); -void HAL_FMPSMBUSEx_DisableFastModePlus(uint32_t ConfigFastModePlus); -/** - * @} - */ - -/** - * @} - */ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup FMPSMBUSEx_Private_Constants FMPSMBUS Extended Private Constants - * @{ - */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup FMPSMBUSEx_Private_Macro FMPSMBUS Extended Private Macros - * @{ - */ -#define IS_FMPSMBUS_FASTMODEPLUS(__CONFIG__) ((((__CONFIG__) & (FMPSMBUS_FASTMODEPLUS_SCL)) == \ - FMPSMBUS_FASTMODEPLUS_SCL) || \ - (((__CONFIG__) & (FMPSMBUS_FASTMODEPLUS_SDA)) == \ - FMPSMBUS_FASTMODEPLUS_SDA)) -/** - * @} - */ - -/* Private Functions ---------------------------------------------------------*/ -/** @defgroup FMPSMBUSEx_Private_Functions FMPSMBUS Extended Private Functions - * @{ - */ -/* Private functions are defined in stm32f4xx_hal_fmpsmbus_ex.c file */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* FMPI2C_CR1_PE */ -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_HAL_FMPSMBUS_EX_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h deleted file mode 100644 index cacfdee..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio.h +++ /dev/null @@ -1,327 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_gpio.h - * @author MCD Application Team - * @brief Header file of GPIO HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_GPIO_H -#define __STM32F4xx_HAL_GPIO_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup GPIO - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup GPIO_Exported_Types GPIO Exported Types - * @{ - */ - -/** - * @brief GPIO Init structure definition - */ -typedef struct -{ - uint32_t Pin; /*!< Specifies the GPIO pins to be configured. - This parameter can be any value of @ref GPIO_pins_define */ - - uint32_t Mode; /*!< Specifies the operating mode for the selected pins. - This parameter can be a value of @ref GPIO_mode_define */ - - uint32_t Pull; /*!< Specifies the Pull-up or Pull-Down activation for the selected pins. - This parameter can be a value of @ref GPIO_pull_define */ - - uint32_t Speed; /*!< Specifies the speed for the selected pins. - This parameter can be a value of @ref GPIO_speed_define */ - - uint32_t Alternate; /*!< Peripheral to be connected to the selected pins. - This parameter can be a value of @ref GPIO_Alternate_function_selection */ -}GPIO_InitTypeDef; - -/** - * @brief GPIO Bit SET and Bit RESET enumeration - */ -typedef enum -{ - GPIO_PIN_RESET = 0, - GPIO_PIN_SET -}GPIO_PinState; -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ - -/** @defgroup GPIO_Exported_Constants GPIO Exported Constants - * @{ - */ - -/** @defgroup GPIO_pins_define GPIO pins define - * @{ - */ -#define GPIO_PIN_0 ((uint16_t)0x0001) /* Pin 0 selected */ -#define GPIO_PIN_1 ((uint16_t)0x0002) /* Pin 1 selected */ -#define GPIO_PIN_2 ((uint16_t)0x0004) /* Pin 2 selected */ -#define GPIO_PIN_3 ((uint16_t)0x0008) /* Pin 3 selected */ -#define GPIO_PIN_4 ((uint16_t)0x0010) /* Pin 4 selected */ -#define GPIO_PIN_5 ((uint16_t)0x0020) /* Pin 5 selected */ -#define GPIO_PIN_6 ((uint16_t)0x0040) /* Pin 6 selected */ -#define GPIO_PIN_7 ((uint16_t)0x0080) /* Pin 7 selected */ -#define GPIO_PIN_8 ((uint16_t)0x0100) /* Pin 8 selected */ -#define GPIO_PIN_9 ((uint16_t)0x0200) /* Pin 9 selected */ -#define GPIO_PIN_10 ((uint16_t)0x0400) /* Pin 10 selected */ -#define GPIO_PIN_11 ((uint16_t)0x0800) /* Pin 11 selected */ -#define GPIO_PIN_12 ((uint16_t)0x1000) /* Pin 12 selected */ -#define GPIO_PIN_13 ((uint16_t)0x2000) /* Pin 13 selected */ -#define GPIO_PIN_14 ((uint16_t)0x4000) /* Pin 14 selected */ -#define GPIO_PIN_15 ((uint16_t)0x8000) /* Pin 15 selected */ -#define GPIO_PIN_All ((uint16_t)0xFFFF) /* All pins selected */ - -#define GPIO_PIN_MASK 0x0000FFFFU /* PIN mask for assert test */ -/** - * @} - */ - -/** @defgroup GPIO_mode_define GPIO mode define - * @brief GPIO Configuration Mode - * Elements values convention: 0x00WX00YZ - * - W : EXTI trigger detection on 3 bits - * - X : EXTI mode (IT or Event) on 2 bits - * - Y : Output type (Push Pull or Open Drain) on 1 bit - * - Z : GPIO mode (Input, Output, Alternate or Analog) on 2 bits - * @{ - */ -#define GPIO_MODE_INPUT MODE_INPUT /*!< Input Floating Mode */ -#define GPIO_MODE_OUTPUT_PP (MODE_OUTPUT | OUTPUT_PP) /*!< Output Push Pull Mode */ -#define GPIO_MODE_OUTPUT_OD (MODE_OUTPUT | OUTPUT_OD) /*!< Output Open Drain Mode */ -#define GPIO_MODE_AF_PP (MODE_AF | OUTPUT_PP) /*!< Alternate Function Push Pull Mode */ -#define GPIO_MODE_AF_OD (MODE_AF | OUTPUT_OD) /*!< Alternate Function Open Drain Mode */ - -#define GPIO_MODE_ANALOG MODE_ANALOG /*!< Analog Mode */ - -#define GPIO_MODE_IT_RISING (MODE_INPUT | EXTI_IT | TRIGGER_RISING) /*!< External Interrupt Mode with Rising edge trigger detection */ -#define GPIO_MODE_IT_FALLING (MODE_INPUT | EXTI_IT | TRIGGER_FALLING) /*!< External Interrupt Mode with Falling edge trigger detection */ -#define GPIO_MODE_IT_RISING_FALLING (MODE_INPUT | EXTI_IT | TRIGGER_RISING | TRIGGER_FALLING) /*!< External Interrupt Mode with Rising/Falling edge trigger detection */ - -#define GPIO_MODE_EVT_RISING (MODE_INPUT | EXTI_EVT | TRIGGER_RISING) /*!< External Event Mode with Rising edge trigger detection */ -#define GPIO_MODE_EVT_FALLING (MODE_INPUT | EXTI_EVT | TRIGGER_FALLING) /*!< External Event Mode with Falling edge trigger detection */ -#define GPIO_MODE_EVT_RISING_FALLING (MODE_INPUT | EXTI_EVT | TRIGGER_RISING | TRIGGER_FALLING) /*!< External Event Mode with Rising/Falling edge trigger detection */ - -/** - * @} - */ - -/** @defgroup GPIO_speed_define GPIO speed define - * @brief GPIO Output Maximum frequency - * @{ - */ -#define GPIO_SPEED_FREQ_LOW 0x00000000U /*!< IO works at 2 MHz, please refer to the product datasheet */ -#define GPIO_SPEED_FREQ_MEDIUM 0x00000001U /*!< range 12,5 MHz to 50 MHz, please refer to the product datasheet */ -#define GPIO_SPEED_FREQ_HIGH 0x00000002U /*!< range 25 MHz to 100 MHz, please refer to the product datasheet */ -#define GPIO_SPEED_FREQ_VERY_HIGH 0x00000003U /*!< range 50 MHz to 200 MHz, please refer to the product datasheet */ -/** - * @} - */ - - /** @defgroup GPIO_pull_define GPIO pull define - * @brief GPIO Pull-Up or Pull-Down Activation - * @{ - */ -#define GPIO_NOPULL 0x00000000U /*!< No Pull-up or Pull-down activation */ -#define GPIO_PULLUP 0x00000001U /*!< Pull-up activation */ -#define GPIO_PULLDOWN 0x00000002U /*!< Pull-down activation */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup GPIO_Exported_Macros GPIO Exported Macros - * @{ - */ - -/** - * @brief Checks whether the specified EXTI line flag is set or not. - * @param __EXTI_LINE__ specifies the EXTI line flag to check. - * This parameter can be GPIO_PIN_x where x can be(0..15) - * @retval The new state of __EXTI_LINE__ (SET or RESET). - */ -#define __HAL_GPIO_EXTI_GET_FLAG(__EXTI_LINE__) (EXTI->PR & (__EXTI_LINE__)) - -/** - * @brief Clears the EXTI's line pending flags. - * @param __EXTI_LINE__ specifies the EXTI lines flags to clear. - * This parameter can be any combination of GPIO_PIN_x where x can be (0..15) - * @retval None - */ -#define __HAL_GPIO_EXTI_CLEAR_FLAG(__EXTI_LINE__) (EXTI->PR = (__EXTI_LINE__)) - -/** - * @brief Checks whether the specified EXTI line is asserted or not. - * @param __EXTI_LINE__ specifies the EXTI line to check. - * This parameter can be GPIO_PIN_x where x can be(0..15) - * @retval The new state of __EXTI_LINE__ (SET or RESET). - */ -#define __HAL_GPIO_EXTI_GET_IT(__EXTI_LINE__) (EXTI->PR & (__EXTI_LINE__)) - -/** - * @brief Clears the EXTI's line pending bits. - * @param __EXTI_LINE__ specifies the EXTI lines to clear. - * This parameter can be any combination of GPIO_PIN_x where x can be (0..15) - * @retval None - */ -#define __HAL_GPIO_EXTI_CLEAR_IT(__EXTI_LINE__) (EXTI->PR = (__EXTI_LINE__)) - -/** - * @brief Generates a Software interrupt on selected EXTI line. - * @param __EXTI_LINE__ specifies the EXTI line to check. - * This parameter can be GPIO_PIN_x where x can be(0..15) - * @retval None - */ -#define __HAL_GPIO_EXTI_GENERATE_SWIT(__EXTI_LINE__) (EXTI->SWIER |= (__EXTI_LINE__)) -/** - * @} - */ - -/* Include GPIO HAL Extension module */ -#include "stm32f4xx_hal_gpio_ex.h" - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup GPIO_Exported_Functions - * @{ - */ - -/** @addtogroup GPIO_Exported_Functions_Group1 - * @{ - */ -/* Initialization and de-initialization functions *****************************/ -void HAL_GPIO_Init(GPIO_TypeDef *GPIOx, GPIO_InitTypeDef *GPIO_Init); -void HAL_GPIO_DeInit(GPIO_TypeDef *GPIOx, uint32_t GPIO_Pin); -/** - * @} - */ - -/** @addtogroup GPIO_Exported_Functions_Group2 - * @{ - */ -/* IO operation functions *****************************************************/ -GPIO_PinState HAL_GPIO_ReadPin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin); -void HAL_GPIO_WritePin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin, GPIO_PinState PinState); -void HAL_GPIO_TogglePin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin); -HAL_StatusTypeDef HAL_GPIO_LockPin(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin); -void HAL_GPIO_EXTI_IRQHandler(uint16_t GPIO_Pin); -void HAL_GPIO_EXTI_Callback(uint16_t GPIO_Pin); - -/** - * @} - */ - -/** - * @} - */ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup GPIO_Private_Constants GPIO Private Constants - * @{ - */ -#define GPIO_MODE_Pos 0U -#define GPIO_MODE (0x3UL << GPIO_MODE_Pos) -#define MODE_INPUT (0x0UL << GPIO_MODE_Pos) -#define MODE_OUTPUT (0x1UL << GPIO_MODE_Pos) -#define MODE_AF (0x2UL << GPIO_MODE_Pos) -#define MODE_ANALOG (0x3UL << GPIO_MODE_Pos) -#define OUTPUT_TYPE_Pos 4U -#define OUTPUT_TYPE (0x1UL << OUTPUT_TYPE_Pos) -#define OUTPUT_PP (0x0UL << OUTPUT_TYPE_Pos) -#define OUTPUT_OD (0x1UL << OUTPUT_TYPE_Pos) -#define EXTI_MODE_Pos 16U -#define EXTI_MODE (0x3UL << EXTI_MODE_Pos) -#define EXTI_IT (0x1UL << EXTI_MODE_Pos) -#define EXTI_EVT (0x2UL << EXTI_MODE_Pos) -#define TRIGGER_MODE_Pos 20U -#define TRIGGER_MODE (0x7UL << TRIGGER_MODE_Pos) -#define TRIGGER_RISING (0x1UL << TRIGGER_MODE_Pos) -#define TRIGGER_FALLING (0x2UL << TRIGGER_MODE_Pos) - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup GPIO_Private_Macros GPIO Private Macros - * @{ - */ -#define IS_GPIO_PIN_ACTION(ACTION) (((ACTION) == GPIO_PIN_RESET) || ((ACTION) == GPIO_PIN_SET)) -#define IS_GPIO_PIN(PIN) (((((uint32_t)PIN) & GPIO_PIN_MASK ) != 0x00U) && ((((uint32_t)PIN) & ~GPIO_PIN_MASK) == 0x00U)) -#define IS_GPIO_MODE(MODE) (((MODE) == GPIO_MODE_INPUT) ||\ - ((MODE) == GPIO_MODE_OUTPUT_PP) ||\ - ((MODE) == GPIO_MODE_OUTPUT_OD) ||\ - ((MODE) == GPIO_MODE_AF_PP) ||\ - ((MODE) == GPIO_MODE_AF_OD) ||\ - ((MODE) == GPIO_MODE_IT_RISING) ||\ - ((MODE) == GPIO_MODE_IT_FALLING) ||\ - ((MODE) == GPIO_MODE_IT_RISING_FALLING) ||\ - ((MODE) == GPIO_MODE_EVT_RISING) ||\ - ((MODE) == GPIO_MODE_EVT_FALLING) ||\ - ((MODE) == GPIO_MODE_EVT_RISING_FALLING) ||\ - ((MODE) == GPIO_MODE_ANALOG)) -#define IS_GPIO_SPEED(SPEED) (((SPEED) == GPIO_SPEED_FREQ_LOW) || ((SPEED) == GPIO_SPEED_FREQ_MEDIUM) || \ - ((SPEED) == GPIO_SPEED_FREQ_HIGH) || ((SPEED) == GPIO_SPEED_FREQ_VERY_HIGH)) -#define IS_GPIO_PULL(PULL) (((PULL) == GPIO_NOPULL) || ((PULL) == GPIO_PULLUP) || \ - ((PULL) == GPIO_PULLDOWN)) -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup GPIO_Private_Functions GPIO Private Functions - * @{ - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_GPIO_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio_ex.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio_ex.h deleted file mode 100644 index 7db36cc..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_gpio_ex.h +++ /dev/null @@ -1,1592 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_gpio_ex.h - * @author MCD Application Team - * @brief Header file of GPIO HAL Extension module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_GPIO_EX_H -#define __STM32F4xx_HAL_GPIO_EX_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup GPIOEx GPIOEx - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/** @defgroup GPIOEx_Exported_Constants GPIO Exported Constants - * @{ - */ - -/** @defgroup GPIO_Alternate_function_selection GPIO Alternate Function Selection - * @{ - */ - -/*------------------------------------------ STM32F429xx/STM32F439xx ---------*/ -#if defined(STM32F429xx) || defined(STM32F439xx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM8 ((uint8_t)0x03) /* TIM8 Alternate Function mapping */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_SPI3 ((uint8_t)0x05) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF5_SPI4 ((uint8_t)0x05) /* SPI4 Alternate Function mapping */ -#define GPIO_AF5_SPI5 ((uint8_t)0x05) /* SPI5 Alternate Function mapping */ -#define GPIO_AF5_SPI6 ((uint8_t)0x05) /* SPI6 Alternate Function mapping */ -#define GPIO_AF5_I2S3ext ((uint8_t)0x05) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06) /* I2S2ext_SD Alternate Function mapping */ -#define GPIO_AF6_SAI1 ((uint8_t)0x06) /* SAI1 Alternate Function mapping */ - -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07) /* USART3 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_UART4 ((uint8_t)0x08) /* UART4 Alternate Function mapping */ -#define GPIO_AF8_UART5 ((uint8_t)0x08) /* UART5 Alternate Function mapping */ -#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ -#define GPIO_AF8_UART7 ((uint8_t)0x08) /* UART7 Alternate Function mapping */ -#define GPIO_AF8_UART8 ((uint8_t)0x08) /* UART8 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_CAN1 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_CAN2 ((uint8_t)0x09) /* CAN2 Alternate Function mapping */ -#define GPIO_AF9_TIM12 ((uint8_t)0x09) /* TIM12 Alternate Function mapping */ -#define GPIO_AF9_TIM13 ((uint8_t)0x09) /* TIM13 Alternate Function mapping */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09) /* TIM14 Alternate Function mapping */ -#define GPIO_AF9_LTDC ((uint8_t)0x09) /* LCD-TFT Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0A) /* OTG_FS Alternate Function mapping */ -#define GPIO_AF10_OTG_HS ((uint8_t)0x0A) /* OTG_HS Alternate Function mapping */ - -/** - * @brief AF 11 selection - */ -#define GPIO_AF11_ETH ((uint8_t)0x0B) /* ETHERNET Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_FMC ((uint8_t)0x0C) /* FMC Alternate Function mapping */ -#define GPIO_AF12_OTG_HS_FS ((uint8_t)0x0C) /* OTG HS configured in FS, Alternate Function mapping */ -#define GPIO_AF12_SDIO ((uint8_t)0x0C) /* SDIO Alternate Function mapping */ - -/** - * @brief AF 13 selection - */ -#define GPIO_AF13_DCMI ((uint8_t)0x0D) /* DCMI Alternate Function mapping */ - -/** - * @brief AF 14 selection - */ -#define GPIO_AF14_LTDC ((uint8_t)0x0E) /* LCD-TFT Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F429xx || STM32F439xx */ -/*----------------------------------------------------------------------------*/ - -/*---------------------------------- STM32F427xx/STM32F437xx------------------*/ -#if defined(STM32F427xx) || defined(STM32F437xx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM8 ((uint8_t)0x03) /* TIM8 Alternate Function mapping */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_SPI3 ((uint8_t)0x05) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF5_SPI4 ((uint8_t)0x05) /* SPI4 Alternate Function mapping */ -#define GPIO_AF5_SPI5 ((uint8_t)0x05) /* SPI5 Alternate Function mapping */ -#define GPIO_AF5_SPI6 ((uint8_t)0x05) /* SPI6 Alternate Function mapping */ -/** @brief GPIO_Legacy - */ -#define GPIO_AF5_I2S3ext GPIO_AF5_SPI3 /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06) /* I2S2ext_SD Alternate Function mapping */ -#define GPIO_AF6_SAI1 ((uint8_t)0x06) /* SAI1 Alternate Function mapping */ - -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07) /* USART3 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_UART4 ((uint8_t)0x08) /* UART4 Alternate Function mapping */ -#define GPIO_AF8_UART5 ((uint8_t)0x08) /* UART5 Alternate Function mapping */ -#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ -#define GPIO_AF8_UART7 ((uint8_t)0x08) /* UART7 Alternate Function mapping */ -#define GPIO_AF8_UART8 ((uint8_t)0x08) /* UART8 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_CAN1 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_CAN2 ((uint8_t)0x09) /* CAN2 Alternate Function mapping */ -#define GPIO_AF9_TIM12 ((uint8_t)0x09) /* TIM12 Alternate Function mapping */ -#define GPIO_AF9_TIM13 ((uint8_t)0x09) /* TIM13 Alternate Function mapping */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09) /* TIM14 Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0A) /* OTG_FS Alternate Function mapping */ -#define GPIO_AF10_OTG_HS ((uint8_t)0x0A) /* OTG_HS Alternate Function mapping */ - -/** - * @brief AF 11 selection - */ -#define GPIO_AF11_ETH ((uint8_t)0x0B) /* ETHERNET Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_FMC ((uint8_t)0x0C) /* FMC Alternate Function mapping */ -#define GPIO_AF12_OTG_HS_FS ((uint8_t)0x0C) /* OTG HS configured in FS, Alternate Function mapping */ -#define GPIO_AF12_SDIO ((uint8_t)0x0C) /* SDIO Alternate Function mapping */ - -/** - * @brief AF 13 selection - */ -#define GPIO_AF13_DCMI ((uint8_t)0x0D) /* DCMI Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F427xx || STM32F437xx */ -/*----------------------------------------------------------------------------*/ - -/*---------------------------------- STM32F407xx/STM32F417xx------------------*/ -#if defined(STM32F407xx) || defined(STM32F417xx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM8 ((uint8_t)0x03) /* TIM8 Alternate Function mapping */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_I2S3ext ((uint8_t)0x05) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06) /* I2S2ext_SD Alternate Function mapping */ - -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07) /* USART3 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_UART4 ((uint8_t)0x08) /* UART4 Alternate Function mapping */ -#define GPIO_AF8_UART5 ((uint8_t)0x08) /* UART5 Alternate Function mapping */ -#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_CAN1 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_CAN2 ((uint8_t)0x09) /* CAN2 Alternate Function mapping */ -#define GPIO_AF9_TIM12 ((uint8_t)0x09) /* TIM12 Alternate Function mapping */ -#define GPIO_AF9_TIM13 ((uint8_t)0x09) /* TIM13 Alternate Function mapping */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09) /* TIM14 Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0A) /* OTG_FS Alternate Function mapping */ -#define GPIO_AF10_OTG_HS ((uint8_t)0x0A) /* OTG_HS Alternate Function mapping */ - -/** - * @brief AF 11 selection - */ -#define GPIO_AF11_ETH ((uint8_t)0x0B) /* ETHERNET Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_FSMC ((uint8_t)0x0C) /* FSMC Alternate Function mapping */ -#define GPIO_AF12_OTG_HS_FS ((uint8_t)0x0C) /* OTG HS configured in FS, Alternate Function mapping */ -#define GPIO_AF12_SDIO ((uint8_t)0x0C) /* SDIO Alternate Function mapping */ - -/** - * @brief AF 13 selection - */ -#define GPIO_AF13_DCMI ((uint8_t)0x0D) /* DCMI Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F407xx || STM32F417xx */ -/*----------------------------------------------------------------------------*/ - -/*---------------------------------- STM32F405xx/STM32F415xx------------------*/ -#if defined(STM32F405xx) || defined(STM32F415xx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM8 ((uint8_t)0x03) /* TIM8 Alternate Function mapping */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_I2S3ext ((uint8_t)0x05) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06) /* I2S2ext_SD Alternate Function mapping */ - -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07) /* USART3 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_UART4 ((uint8_t)0x08) /* UART4 Alternate Function mapping */ -#define GPIO_AF8_UART5 ((uint8_t)0x08) /* UART5 Alternate Function mapping */ -#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_CAN1 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_CAN2 ((uint8_t)0x09) /* CAN2 Alternate Function mapping */ -#define GPIO_AF9_TIM12 ((uint8_t)0x09) /* TIM12 Alternate Function mapping */ -#define GPIO_AF9_TIM13 ((uint8_t)0x09) /* TIM13 Alternate Function mapping */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09) /* TIM14 Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0A) /* OTG_FS Alternate Function mapping */ -#define GPIO_AF10_OTG_HS ((uint8_t)0x0A) /* OTG_HS Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_FSMC ((uint8_t)0x0C) /* FSMC Alternate Function mapping */ -#define GPIO_AF12_OTG_HS_FS ((uint8_t)0x0C) /* OTG HS configured in FS, Alternate Function mapping */ -#define GPIO_AF12_SDIO ((uint8_t)0x0C) /* SDIO Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F405xx || STM32F415xx */ - -/*----------------------------------------------------------------------------*/ - -/*---------------------------------------- STM32F401xx------------------------*/ -#if defined(STM32F401xC) || defined(STM32F401xE) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_SPI3 ((uint8_t)0x05) /* SPI3 Alternate Function mapping */ -#define GPIO_AF5_SPI4 ((uint8_t)0x05) /* SPI4 Alternate Function mapping */ -#define GPIO_AF5_I2S3ext ((uint8_t)0x05) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06) /* I2S2ext_SD Alternate Function mapping */ - -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_I2C2 ((uint8_t)0x09) /* I2C2 Alternate Function mapping */ -#define GPIO_AF9_I2C3 ((uint8_t)0x09) /* I2C3 Alternate Function mapping */ - - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0A) /* OTG_FS Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_SDIO ((uint8_t)0x0C) /* SDIO Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F401xC || STM32F401xE */ -/*----------------------------------------------------------------------------*/ - -/*--------------- STM32F412Zx/STM32F412Vx/STM32F412Rx/STM32F412Cx-------------*/ -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM8 ((uint8_t)0x03) /* TIM8 Alternate Function mapping */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ -#define GPIO_AF4_FMPI2C1 ((uint8_t)0x04) /* FMPI2C1 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1/I2S1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_SPI3 ((uint8_t)0x05) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF5_SPI4 ((uint8_t)0x05) /* SPI4/I2S4 Alternate Function mapping */ -#define GPIO_AF5_I2S3ext ((uint8_t)0x05) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI2 ((uint8_t)0x06) /* I2S2 Alternate Function mapping */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_SPI4 ((uint8_t)0x06) /* SPI4/I2S4 Alternate Function mapping */ -#define GPIO_AF6_SPI5 ((uint8_t)0x06) /* SPI5/I2S5 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06) /* I2S2ext_SD Alternate Function mapping */ -#define GPIO_AF6_DFSDM1 ((uint8_t)0x06) /* DFSDM1 Alternate Function mapping */ -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_SPI3 ((uint8_t)0x07) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07) /* USART3 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ -#define GPIO_AF8_USART3 ((uint8_t)0x08) /* USART3 Alternate Function mapping */ -#define GPIO_AF8_DFSDM1 ((uint8_t)0x08) /* DFSDM1 Alternate Function mapping */ -#define GPIO_AF8_CAN1 ((uint8_t)0x08) /* CAN1 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_TIM12 ((uint8_t)0x09) /* TIM12 Alternate Function mapping */ -#define GPIO_AF9_TIM13 ((uint8_t)0x09) /* TIM13 Alternate Function mapping */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09) /* TIM14 Alternate Function mapping */ -#define GPIO_AF9_I2C2 ((uint8_t)0x09) /* I2C2 Alternate Function mapping */ -#define GPIO_AF9_I2C3 ((uint8_t)0x09) /* I2C3 Alternate Function mapping */ -#define GPIO_AF9_FMPI2C1 ((uint8_t)0x09) /* FMPI2C1 Alternate Function mapping */ -#define GPIO_AF9_CAN1 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_CAN2 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_QSPI ((uint8_t)0x09) /* QSPI Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0A) /* OTG_FS Alternate Function mapping */ -#define GPIO_AF10_DFSDM1 ((uint8_t)0x0A) /* DFSDM1 Alternate Function mapping */ -#define GPIO_AF10_QSPI ((uint8_t)0x0A) /* QSPI Alternate Function mapping */ -#define GPIO_AF10_FMC ((uint8_t)0x0A) /* FMC Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_SDIO ((uint8_t)0x0C) /* SDIO Alternate Function mapping */ -#define GPIO_AF12_FSMC ((uint8_t)0x0C) /* FMC Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ - -/*----------------------------------------------------------------------------*/ - -/*--------------- STM32F413xx/STM32F423xx-------------------------------------*/ -#if defined(STM32F413xx) || defined(STM32F423xx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ -#define GPIO_AF1_LPTIM1 ((uint8_t)0x01) /* LPTIM1 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM8 ((uint8_t)0x03) /* TIM8 Alternate Function mapping */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ -#define GPIO_AF3_DFSDM2 ((uint8_t)0x03) /* DFSDM2 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ -#define GPIO_AF4_FMPI2C1 ((uint8_t)0x04) /* FMPI2C1 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1/I2S1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_SPI3 ((uint8_t)0x05) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF5_SPI4 ((uint8_t)0x05) /* SPI4/I2S4 Alternate Function mapping */ -#define GPIO_AF5_I2S3ext ((uint8_t)0x05) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI2 ((uint8_t)0x06) /* I2S2 Alternate Function mapping */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_SPI4 ((uint8_t)0x06) /* SPI4/I2S4 Alternate Function mapping */ -#define GPIO_AF6_SPI5 ((uint8_t)0x06) /* SPI5/I2S5 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06) /* I2S2ext_SD Alternate Function mapping */ -#define GPIO_AF6_DFSDM1 ((uint8_t)0x06) /* DFSDM1 Alternate Function mapping */ -#define GPIO_AF6_DFSDM2 ((uint8_t)0x06) /* DFSDM2 Alternate Function mapping */ -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_SPI3 ((uint8_t)0x07) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF7_SAI1 ((uint8_t)0x07) /* SAI1 Alternate Function mapping */ -#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07) /* USART3 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07) /* I2S3ext_SD Alternate Function mapping */ -#define GPIO_AF7_DFSDM2 ((uint8_t)0x07) /* DFSDM2 Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ -#define GPIO_AF8_USART3 ((uint8_t)0x08) /* USART3 Alternate Function mapping */ -#define GPIO_AF8_UART4 ((uint8_t)0x08) /* UART4 Alternate Function mapping */ -#define GPIO_AF8_UART5 ((uint8_t)0x08) /* UART5 Alternate Function mapping */ -#define GPIO_AF8_UART7 ((uint8_t)0x08) /* UART8 Alternate Function mapping */ -#define GPIO_AF8_UART8 ((uint8_t)0x08) /* UART8 Alternate Function mapping */ -#define GPIO_AF8_DFSDM1 ((uint8_t)0x08) /* DFSDM1 Alternate Function mapping */ -#define GPIO_AF8_CAN1 ((uint8_t)0x08) /* CAN1 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_TIM12 ((uint8_t)0x09) /* TIM12 Alternate Function mapping */ -#define GPIO_AF9_TIM13 ((uint8_t)0x09) /* TIM13 Alternate Function mapping */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09) /* TIM14 Alternate Function mapping */ -#define GPIO_AF9_I2C2 ((uint8_t)0x09) /* I2C2 Alternate Function mapping */ -#define GPIO_AF9_I2C3 ((uint8_t)0x09) /* I2C3 Alternate Function mapping */ -#define GPIO_AF9_FMPI2C1 ((uint8_t)0x09) /* FMPI2C1 Alternate Function mapping */ -#define GPIO_AF9_CAN1 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_CAN2 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_QSPI ((uint8_t)0x09) /* QSPI Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_SAI1 ((uint8_t)0x0A) /* SAI1 Alternate Function mapping */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0A) /* OTG_FS Alternate Function mapping */ -#define GPIO_AF10_DFSDM1 ((uint8_t)0x0A) /* DFSDM1 Alternate Function mapping */ -#define GPIO_AF10_DFSDM2 ((uint8_t)0x0A) /* DFSDM2 Alternate Function mapping */ -#define GPIO_AF10_QSPI ((uint8_t)0x0A) /* QSPI Alternate Function mapping */ -#define GPIO_AF10_FSMC ((uint8_t)0x0A) /* FSMC Alternate Function mapping */ - -/** - * @brief AF 11 selection - */ -#define GPIO_AF11_UART4 ((uint8_t)0x0B) /* UART4 Alternate Function mapping */ -#define GPIO_AF11_UART5 ((uint8_t)0x0B) /* UART5 Alternate Function mapping */ -#define GPIO_AF11_UART9 ((uint8_t)0x0B) /* UART9 Alternate Function mapping */ -#define GPIO_AF11_UART10 ((uint8_t)0x0B) /* UART10 Alternate Function mapping */ -#define GPIO_AF11_CAN3 ((uint8_t)0x0B) /* CAN3 Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_SDIO ((uint8_t)0x0C) /* SDIO Alternate Function mapping */ -#define GPIO_AF12_FSMC ((uint8_t)0x0C) /* FMC Alternate Function mapping */ - -/** - * @brief AF 14 selection - */ -#define GPIO_AF14_RNG ((uint8_t)0x0E) /* RNG Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F413xx || STM32F423xx */ - -/*---------------------------------------- STM32F411xx------------------------*/ -#if defined(STM32F411xE) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1/I2S1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_SPI3 ((uint8_t)0x05) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF5_SPI4 ((uint8_t)0x05) /* SPI4 Alternate Function mapping */ -#define GPIO_AF5_I2S3ext ((uint8_t)0x05) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI2 ((uint8_t)0x06) /* I2S2 Alternate Function mapping */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_SPI4 ((uint8_t)0x06) /* SPI4/I2S4 Alternate Function mapping */ -#define GPIO_AF6_SPI5 ((uint8_t)0x06) /* SPI5/I2S5 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06) /* I2S2ext_SD Alternate Function mapping */ - -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_SPI3 ((uint8_t)0x07) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09) /* TIM14 Alternate Function mapping */ -#define GPIO_AF9_I2C2 ((uint8_t)0x09) /* I2C2 Alternate Function mapping */ -#define GPIO_AF9_I2C3 ((uint8_t)0x09) /* I2C3 Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0A) /* OTG_FS Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_SDIO ((uint8_t)0x0C) /* SDIO Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F411xE */ - -/*---------------------------------------- STM32F410xx------------------------*/ -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_LPTIM1 ((uint8_t)0x01) /* LPTIM1 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_FMPI2C1 ((uint8_t)0x04) /* FMPI2C1 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1/I2S1 Alternate Function mapping */ -#if defined(STM32F410Cx) || defined(STM32F410Rx) -#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ -#endif /* STM32F410Cx || STM32F410Rx */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI1 ((uint8_t)0x06) /* SPI1 Alternate Function mapping */ -#if defined(STM32F410Cx) || defined(STM32F410Rx) -#define GPIO_AF6_SPI2 ((uint8_t)0x06) /* I2S2 Alternate Function mapping */ -#endif /* STM32F410Cx || STM32F410Rx */ -#define GPIO_AF6_SPI5 ((uint8_t)0x06) /* SPI5/I2S5 Alternate Function mapping */ -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_I2C2 ((uint8_t)0x09) /* I2C2 Alternate Function mapping */ -#define GPIO_AF9_FMPI2C1 ((uint8_t)0x09) /* FMPI2C1 Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -/*---------------------------------------- STM32F446xx -----------------------*/ -#if defined(STM32F446xx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM8 ((uint8_t)0x03) /* TIM8 Alternate Function mapping */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ -#define GPIO_AF3_CEC ((uint8_t)0x03) /* CEC Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ -#define GPIO_AF4_FMPI2C1 ((uint8_t)0x04) /* FMPI2C1 Alternate Function mapping */ -#define GPIO_AF4_CEC ((uint8_t)0x04) /* CEC Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1/I2S1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_SPI3 ((uint8_t)0x05) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF5_SPI4 ((uint8_t)0x05) /* SPI4 Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI2 ((uint8_t)0x06) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_SPI4 ((uint8_t)0x06) /* SPI4 Alternate Function mapping */ -#define GPIO_AF6_SAI1 ((uint8_t)0x06) /* SAI1 Alternate Function mapping */ - -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07) /* USART3 Alternate Function mapping */ -#define GPIO_AF7_UART5 ((uint8_t)0x07) /* UART5 Alternate Function mapping */ -#define GPIO_AF7_SPI2 ((uint8_t)0x07) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF7_SPI3 ((uint8_t)0x07) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF7_SPDIFRX ((uint8_t)0x07) /* SPDIFRX Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_UART4 ((uint8_t)0x08) /* UART4 Alternate Function mapping */ -#define GPIO_AF8_UART5 ((uint8_t)0x08) /* UART5 Alternate Function mapping */ -#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ -#define GPIO_AF8_SPDIFRX ((uint8_t)0x08) /* SPDIFRX Alternate Function mapping */ -#define GPIO_AF8_SAI2 ((uint8_t)0x08) /* SAI2 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_CAN1 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_CAN2 ((uint8_t)0x09) /* CAN2 Alternate Function mapping */ -#define GPIO_AF9_TIM12 ((uint8_t)0x09) /* TIM12 Alternate Function mapping */ -#define GPIO_AF9_TIM13 ((uint8_t)0x09) /* TIM13 Alternate Function mapping */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09) /* TIM14 Alternate Function mapping */ -#define GPIO_AF9_QSPI ((uint8_t)0x09) /* QSPI Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0A) /* OTG_FS Alternate Function mapping */ -#define GPIO_AF10_OTG_HS ((uint8_t)0x0A) /* OTG_HS Alternate Function mapping */ -#define GPIO_AF10_SAI2 ((uint8_t)0x0A) /* SAI2 Alternate Function mapping */ -#define GPIO_AF10_QSPI ((uint8_t)0x0A) /* QSPI Alternate Function mapping */ - -/** - * @brief AF 11 selection - */ -#define GPIO_AF11_ETH ((uint8_t)0x0B) /* ETHERNET Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_FMC ((uint8_t)0x0C) /* FMC Alternate Function mapping */ -#define GPIO_AF12_OTG_HS_FS ((uint8_t)0x0C) /* OTG HS configured in FS, Alternate Function mapping */ -#define GPIO_AF12_SDIO ((uint8_t)0x0C) /* SDIO Alternate Function mapping */ - -/** - * @brief AF 13 selection - */ -#define GPIO_AF13_DCMI ((uint8_t)0x0D) /* DCMI Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ - -#endif /* STM32F446xx */ -/*----------------------------------------------------------------------------*/ - -/*-------------------------------- STM32F469xx/STM32F479xx--------------------*/ -#if defined(STM32F469xx) || defined(STM32F479xx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM8 ((uint8_t)0x03) /* TIM8 Alternate Function mapping */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_SPI3 ((uint8_t)0x05) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF5_SPI4 ((uint8_t)0x05) /* SPI4 Alternate Function mapping */ -#define GPIO_AF5_SPI5 ((uint8_t)0x05) /* SPI5 Alternate Function mapping */ -#define GPIO_AF5_SPI6 ((uint8_t)0x05) /* SPI6 Alternate Function mapping */ -#define GPIO_AF5_I2S3ext ((uint8_t)0x05) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06) /* I2S2ext_SD Alternate Function mapping */ -#define GPIO_AF6_SAI1 ((uint8_t)0x06) /* SAI1 Alternate Function mapping */ - -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07) /* USART3 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_UART4 ((uint8_t)0x08) /* UART4 Alternate Function mapping */ -#define GPIO_AF8_UART5 ((uint8_t)0x08) /* UART5 Alternate Function mapping */ -#define GPIO_AF8_USART6 ((uint8_t)0x08) /* USART6 Alternate Function mapping */ -#define GPIO_AF8_UART7 ((uint8_t)0x08) /* UART7 Alternate Function mapping */ -#define GPIO_AF8_UART8 ((uint8_t)0x08) /* UART8 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_CAN1 ((uint8_t)0x09) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_CAN2 ((uint8_t)0x09) /* CAN2 Alternate Function mapping */ -#define GPIO_AF9_TIM12 ((uint8_t)0x09) /* TIM12 Alternate Function mapping */ -#define GPIO_AF9_TIM13 ((uint8_t)0x09) /* TIM13 Alternate Function mapping */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09) /* TIM14 Alternate Function mapping */ -#define GPIO_AF9_LTDC ((uint8_t)0x09) /* LCD-TFT Alternate Function mapping */ -#define GPIO_AF9_QSPI ((uint8_t)0x09) /* QSPI Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0A) /* OTG_FS Alternate Function mapping */ -#define GPIO_AF10_OTG_HS ((uint8_t)0x0A) /* OTG_HS Alternate Function mapping */ -#define GPIO_AF10_QSPI ((uint8_t)0x0A) /* QSPI Alternate Function mapping */ - -/** - * @brief AF 11 selection - */ -#define GPIO_AF11_ETH ((uint8_t)0x0B) /* ETHERNET Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_FMC ((uint8_t)0x0C) /* FMC Alternate Function mapping */ -#define GPIO_AF12_OTG_HS_FS ((uint8_t)0x0C) /* OTG HS configured in FS, Alternate Function mapping */ -#define GPIO_AF12_SDIO ((uint8_t)0x0C) /* SDIO Alternate Function mapping */ - -/** - * @brief AF 13 selection - */ -#define GPIO_AF13_DCMI ((uint8_t)0x0D) /* DCMI Alternate Function mapping */ -#define GPIO_AF13_DSI ((uint8_t)0x0D) /* DSI Alternate Function mapping */ - -/** - * @brief AF 14 selection - */ -#define GPIO_AF14_LTDC ((uint8_t)0x0E) /* LCD-TFT Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ - -#endif /* STM32F469xx || STM32F479xx */ -/*----------------------------------------------------------------------------*/ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup GPIOEx_Exported_Macros GPIO Exported Macros - * @{ - */ -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup GPIOEx_Exported_Functions GPIO Exported Functions - * @{ - */ -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup GPIOEx_Private_Constants GPIO Private Constants - * @{ - */ -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup GPIOEx_Private_Macros GPIO Private Macros - * @{ - */ -/** @defgroup GPIOEx_Get_Port_Index GPIO Get Port Index - * @{ - */ -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) -#define GPIO_GET_INDEX(__GPIOx__) (uint8_t)(((__GPIOx__) == (GPIOA))? 0U :\ - ((__GPIOx__) == (GPIOB))? 1U :\ - ((__GPIOx__) == (GPIOC))? 2U :\ - ((__GPIOx__) == (GPIOD))? 3U :\ - ((__GPIOx__) == (GPIOE))? 4U :\ - ((__GPIOx__) == (GPIOF))? 5U :\ - ((__GPIOx__) == (GPIOG))? 6U :\ - ((__GPIOx__) == (GPIOH))? 7U : 8U) -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F469xx) || defined(STM32F479xx) -#define GPIO_GET_INDEX(__GPIOx__) (uint8_t)(((__GPIOx__) == (GPIOA))? 0U :\ - ((__GPIOx__) == (GPIOB))? 1U :\ - ((__GPIOx__) == (GPIOC))? 2U :\ - ((__GPIOx__) == (GPIOD))? 3U :\ - ((__GPIOx__) == (GPIOE))? 4U :\ - ((__GPIOx__) == (GPIOF))? 5U :\ - ((__GPIOx__) == (GPIOG))? 6U :\ - ((__GPIOx__) == (GPIOH))? 7U :\ - ((__GPIOx__) == (GPIOI))? 8U :\ - ((__GPIOx__) == (GPIOJ))? 9U : 10U) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -#define GPIO_GET_INDEX(__GPIOx__) (uint8_t)(((__GPIOx__) == (GPIOA))? 0U :\ - ((__GPIOx__) == (GPIOB))? 1U :\ - ((__GPIOx__) == (GPIOC))? 2U : 7U) -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) -#define GPIO_GET_INDEX(__GPIOx__) (uint8_t)(((__GPIOx__) == (GPIOA))? 0U :\ - ((__GPIOx__) == (GPIOB))? 1U :\ - ((__GPIOx__) == (GPIOC))? 2U :\ - ((__GPIOx__) == (GPIOD))? 3U :\ - ((__GPIOx__) == (GPIOE))? 4U : 7U) -#endif /* STM32F401xC || STM32F401xE || STM32F411xE */ - -#if defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define GPIO_GET_INDEX(__GPIOx__) (uint8_t)(((__GPIOx__) == (GPIOA))? 0U :\ - ((__GPIOx__) == (GPIOB))? 1U :\ - ((__GPIOx__) == (GPIOC))? 2U :\ - ((__GPIOx__) == (GPIOD))? 3U :\ - ((__GPIOx__) == (GPIOE))? 4U :\ - ((__GPIOx__) == (GPIOF))? 5U :\ - ((__GPIOx__) == (GPIOG))? 6U : 7U) -#endif /* STM32F446xx || STM32F412Zx || STM32F413xx || STM32F423xx */ -#if defined(STM32F412Vx) -#define GPIO_GET_INDEX(__GPIOx__) (uint8_t)(((__GPIOx__) == (GPIOA))? 0U :\ - ((__GPIOx__) == (GPIOB))? 1U :\ - ((__GPIOx__) == (GPIOC))? 2U :\ - ((__GPIOx__) == (GPIOD))? 3U :\ - ((__GPIOx__) == (GPIOE))? 4U : 7U) -#endif /* STM32F412Vx */ -#if defined(STM32F412Rx) -#define GPIO_GET_INDEX(__GPIOx__) (uint8_t)(((__GPIOx__) == (GPIOA))? 0U :\ - ((__GPIOx__) == (GPIOB))? 1U :\ - ((__GPIOx__) == (GPIOC))? 2U :\ - ((__GPIOx__) == (GPIOD))? 3U : 7U) -#endif /* STM32F412Rx */ -#if defined(STM32F412Cx) -#define GPIO_GET_INDEX(__GPIOx__) (uint8_t)(((__GPIOx__) == (GPIOA))? 0U :\ - ((__GPIOx__) == (GPIOB))? 1U :\ - ((__GPIOx__) == (GPIOC))? 2U : 7U) -#endif /* STM32F412Cx */ - -/** - * @} - */ - -/** @defgroup GPIOEx_IS_Alternat_function_selection GPIO Check Alternate Function - * @{ - */ -/*------------------------- STM32F429xx/STM32F439xx---------------------------*/ -#if defined(STM32F429xx) || defined(STM32F439xx) -#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ - ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ - ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ - ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ - ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ - ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM8) || \ - ((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \ - ((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \ - ((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF9_TIM13) || \ - ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF9_TIM12) || \ - ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ - ((AF) == GPIO_AF7_USART3) || ((AF) == GPIO_AF8_UART4) || \ - ((AF) == GPIO_AF8_UART5) || ((AF) == GPIO_AF8_USART6) || \ - ((AF) == GPIO_AF9_CAN1) || ((AF) == GPIO_AF9_CAN2) || \ - ((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF10_OTG_HS) || \ - ((AF) == GPIO_AF11_ETH) || ((AF) == GPIO_AF12_OTG_HS_FS) || \ - ((AF) == GPIO_AF12_SDIO) || ((AF) == GPIO_AF13_DCMI) || \ - ((AF) == GPIO_AF15_EVENTOUT) || ((AF) == GPIO_AF5_SPI4) || \ - ((AF) == GPIO_AF5_SPI5) || ((AF) == GPIO_AF5_SPI6) || \ - ((AF) == GPIO_AF8_UART7) || ((AF) == GPIO_AF8_UART8) || \ - ((AF) == GPIO_AF12_FMC) || ((AF) == GPIO_AF6_SAI1) || \ - ((AF) == GPIO_AF14_LTDC)) - -#endif /* STM32F429xx || STM32F439xx */ -/*----------------------------------------------------------------------------*/ - -/*---------------------------------- STM32F427xx/STM32F437xx------------------*/ -#if defined(STM32F427xx) || defined(STM32F437xx) -#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ - ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ - ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ - ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ - ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ - ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM8) || \ - ((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \ - ((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \ - ((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF9_TIM13) || \ - ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF9_TIM12) || \ - ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ - ((AF) == GPIO_AF7_USART3) || ((AF) == GPIO_AF8_UART4) || \ - ((AF) == GPIO_AF8_UART5) || ((AF) == GPIO_AF8_USART6) || \ - ((AF) == GPIO_AF9_CAN1) || ((AF) == GPIO_AF9_CAN2) || \ - ((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF10_OTG_HS) || \ - ((AF) == GPIO_AF11_ETH) || ((AF) == GPIO_AF12_OTG_HS_FS) || \ - ((AF) == GPIO_AF12_SDIO) || ((AF) == GPIO_AF13_DCMI) || \ - ((AF) == GPIO_AF15_EVENTOUT) || ((AF) == GPIO_AF5_SPI4) || \ - ((AF) == GPIO_AF5_SPI5) || ((AF) == GPIO_AF5_SPI6) || \ - ((AF) == GPIO_AF8_UART7) || ((AF) == GPIO_AF8_UART8) || \ - ((AF) == GPIO_AF12_FMC) || ((AF) == GPIO_AF6_SAI1)) - -#endif /* STM32F427xx || STM32F437xx */ -/*----------------------------------------------------------------------------*/ - -/*---------------------------------- STM32F407xx/STM32F417xx------------------*/ -#if defined(STM32F407xx) || defined(STM32F417xx) -#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ - ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ - ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ - ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ - ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ - ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM8) || \ - ((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \ - ((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \ - ((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF9_TIM13) || \ - ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF9_TIM12) || \ - ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ - ((AF) == GPIO_AF7_USART3) || ((AF) == GPIO_AF8_UART4) || \ - ((AF) == GPIO_AF8_UART5) || ((AF) == GPIO_AF8_USART6) || \ - ((AF) == GPIO_AF9_CAN1) || ((AF) == GPIO_AF9_CAN2) || \ - ((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF10_OTG_HS) || \ - ((AF) == GPIO_AF11_ETH) || ((AF) == GPIO_AF12_OTG_HS_FS) || \ - ((AF) == GPIO_AF12_SDIO) || ((AF) == GPIO_AF13_DCMI) || \ - ((AF) == GPIO_AF12_FSMC) || ((AF) == GPIO_AF15_EVENTOUT)) - -#endif /* STM32F407xx || STM32F417xx */ -/*----------------------------------------------------------------------------*/ - -/*---------------------------------- STM32F405xx/STM32F415xx------------------*/ -#if defined(STM32F405xx) || defined(STM32F415xx) -#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ - ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ - ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ - ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ - ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ - ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM8) || \ - ((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \ - ((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \ - ((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF9_TIM13) || \ - ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF9_TIM12) || \ - ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ - ((AF) == GPIO_AF7_USART3) || ((AF) == GPIO_AF8_UART4) || \ - ((AF) == GPIO_AF8_UART5) || ((AF) == GPIO_AF8_USART6) || \ - ((AF) == GPIO_AF9_CAN1) || ((AF) == GPIO_AF9_CAN2) || \ - ((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF10_OTG_HS) || \ - ((AF) == GPIO_AF12_OTG_HS_FS) || ((AF) == GPIO_AF12_SDIO) || \ - ((AF) == GPIO_AF12_FSMC) || ((AF) == GPIO_AF15_EVENTOUT)) - -#endif /* STM32F405xx || STM32F415xx */ - -/*----------------------------------------------------------------------------*/ - -/*---------------------------------------- STM32F401xx------------------------*/ -#if defined(STM32F401xC) || defined(STM32F401xE) -#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF12_SDIO) || \ - ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ - ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ - ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ - ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ - ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM9) || \ - ((AF) == GPIO_AF3_TIM10) || ((AF) == GPIO_AF3_TIM11) || \ - ((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \ - ((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \ - ((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF5_SPI4) || \ - ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF7_USART1) || \ - ((AF) == GPIO_AF7_USART2) || ((AF) == GPIO_AF8_USART6) || \ - ((AF) == GPIO_AF9_I2C2) || ((AF) == GPIO_AF9_I2C3) || \ - ((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF15_EVENTOUT)) -#endif /* STM32F401xC || STM32F401xE */ -/*----------------------------------------------------------------------------*/ -/*---------------------------------------- STM32F410xx------------------------*/ -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -#define IS_GPIO_AF(AF) (((AF) < 10U) || ((AF) == 15U)) -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -/*---------------------------------------- STM32F411xx------------------------*/ -#if defined(STM32F411xE) -#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ - ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ - ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ - ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ - ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ - ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF4_I2C1) || \ - ((AF) == GPIO_AF4_I2C2) || ((AF) == GPIO_AF4_I2C3) || \ - ((AF) == GPIO_AF5_SPI1) || ((AF) == GPIO_AF5_SPI2) || \ - ((AF) == GPIO_AF5_SPI3) || ((AF) == GPIO_AF6_SPI4) || \ - ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF5_SPI4) || \ - ((AF) == GPIO_AF6_SPI5) || ((AF) == GPIO_AF7_SPI3) || \ - ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ - ((AF) == GPIO_AF8_USART6) || ((AF) == GPIO_AF10_OTG_FS) || \ - ((AF) == GPIO_AF9_I2C2) || ((AF) == GPIO_AF9_I2C3) || \ - ((AF) == GPIO_AF12_SDIO) || ((AF) == GPIO_AF15_EVENTOUT)) - -#endif /* STM32F411xE */ -/*----------------------------------------------------------------------------*/ - -/*----------------------------------------------- STM32F446xx ----------------*/ -#if defined(STM32F446xx) -#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ - ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ - ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ - ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ - ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ - ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM8) || \ - ((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \ - ((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \ - ((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF9_TIM13) || \ - ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF9_TIM12) || \ - ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ - ((AF) == GPIO_AF7_USART3) || ((AF) == GPIO_AF8_UART4) || \ - ((AF) == GPIO_AF8_UART5) || ((AF) == GPIO_AF8_USART6) || \ - ((AF) == GPIO_AF9_CAN1) || ((AF) == GPIO_AF9_CAN2) || \ - ((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF10_OTG_HS) || \ - ((AF) == GPIO_AF11_ETH) || ((AF) == GPIO_AF12_OTG_HS_FS) || \ - ((AF) == GPIO_AF12_SDIO) || ((AF) == GPIO_AF13_DCMI) || \ - ((AF) == GPIO_AF15_EVENTOUT) || ((AF) == GPIO_AF5_SPI4) || \ - ((AF) == GPIO_AF12_FMC) || ((AF) == GPIO_AF6_SAI1) || \ - ((AF) == GPIO_AF3_CEC) || ((AF) == GPIO_AF4_CEC) || \ - ((AF) == GPIO_AF5_SPI3) || ((AF) == GPIO_AF6_SPI2) || \ - ((AF) == GPIO_AF6_SPI4) || ((AF) == GPIO_AF7_UART5) || \ - ((AF) == GPIO_AF7_SPI2) || ((AF) == GPIO_AF7_SPI3) || \ - ((AF) == GPIO_AF7_SPDIFRX) || ((AF) == GPIO_AF8_SPDIFRX) || \ - ((AF) == GPIO_AF8_SAI2) || ((AF) == GPIO_AF9_QSPI) || \ - ((AF) == GPIO_AF10_SAI2) || ((AF) == GPIO_AF10_QSPI)) - -#endif /* STM32F446xx */ -/*----------------------------------------------------------------------------*/ - -/*------------------------------------------- STM32F469xx/STM32F479xx --------*/ -#if defined(STM32F469xx) || defined(STM32F479xx) -#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ - ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ - ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ - ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ - ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ - ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM8) || \ - ((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \ - ((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \ - ((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF9_TIM13) || \ - ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF9_TIM12) || \ - ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ - ((AF) == GPIO_AF7_USART3) || ((AF) == GPIO_AF8_UART4) || \ - ((AF) == GPIO_AF8_UART5) || ((AF) == GPIO_AF8_USART6) || \ - ((AF) == GPIO_AF9_CAN1) || ((AF) == GPIO_AF9_CAN2) || \ - ((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF10_OTG_HS) || \ - ((AF) == GPIO_AF11_ETH) || ((AF) == GPIO_AF12_OTG_HS_FS) || \ - ((AF) == GPIO_AF12_SDIO) || ((AF) == GPIO_AF13_DCMI) || \ - ((AF) == GPIO_AF15_EVENTOUT) || ((AF) == GPIO_AF5_SPI4) || \ - ((AF) == GPIO_AF5_SPI5) || ((AF) == GPIO_AF5_SPI6) || \ - ((AF) == GPIO_AF8_UART7) || ((AF) == GPIO_AF8_UART8) || \ - ((AF) == GPIO_AF12_FMC) || ((AF) == GPIO_AF6_SAI1) || \ - ((AF) == GPIO_AF14_LTDC) || ((AF) == GPIO_AF13_DSI) || \ - ((AF) == GPIO_AF9_QSPI) || ((AF) == GPIO_AF10_QSPI)) - -#endif /* STM32F469xx || STM32F479xx */ -/*----------------------------------------------------------------------------*/ - -/*------------------STM32F412Zx/STM32F412Vx/STM32F412Rx/STM32F412Cx-----------*/ -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) -#define IS_GPIO_AF(AF) (((AF) < 16U) && ((AF) != 11U) && ((AF) != 14U) && ((AF) != 13U)) -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ -/*----------------------------------------------------------------------------*/ - -/*------------------STM32F413xx/STM32F423xx-----------------------------------*/ -#if defined(STM32F413xx) || defined(STM32F423xx) -#define IS_GPIO_AF(AF) (((AF) < 16U) && ((AF) != 13U)) -#endif /* STM32F413xx || STM32F423xx */ -/*----------------------------------------------------------------------------*/ - -/** - * @} - */ - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup GPIOEx_Private_Functions GPIO Private Functions - * @{ - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_GPIO_EX_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_hash.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_hash.h deleted file mode 100644 index 3b73282..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_hash.h +++ /dev/null @@ -1,636 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_hash.h - * @author MCD Application Team - * @brief Header file of HASH HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_HASH_H -#define STM32F4xx_HAL_HASH_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ -#if defined (HASH) -/** @addtogroup HASH - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup HASH_Exported_Types HASH Exported Types - * @{ - */ - -/** - * @brief HASH Configuration Structure definition - */ -typedef struct -{ - uint32_t DataType; /*!< 32-bit data, 16-bit data, 8-bit data or 1-bit data. - This parameter can be a value of @ref HASH_Data_Type. */ - - uint32_t KeySize; /*!< The key size is used only in HMAC operation. */ - - uint8_t *pKey; /*!< The key is used only in HMAC operation. */ - -} HASH_InitTypeDef; - -/** - * @brief HAL State structures definition - */ -typedef enum -{ - HAL_HASH_STATE_RESET = 0x00U, /*!< Peripheral is not initialized */ - HAL_HASH_STATE_READY = 0x01U, /*!< Peripheral Initialized and ready for use */ - HAL_HASH_STATE_BUSY = 0x02U, /*!< Processing (hashing) is ongoing */ - HAL_HASH_STATE_TIMEOUT = 0x06U, /*!< Timeout state */ - HAL_HASH_STATE_ERROR = 0x07U, /*!< Error state */ - HAL_HASH_STATE_SUSPENDED = 0x08U /*!< Suspended state */ -} HAL_HASH_StateTypeDef; - -/** - * @brief HAL phase structures definition - */ -typedef enum -{ - HAL_HASH_PHASE_READY = 0x01U, /*!< HASH peripheral is ready to start */ - HAL_HASH_PHASE_PROCESS = 0x02U, /*!< HASH peripheral is in HASH processing phase */ - HAL_HASH_PHASE_HMAC_STEP_1 = 0x03U, /*!< HASH peripheral is in HMAC step 1 processing phase - (step 1 consists in entering the inner hash function key) */ - HAL_HASH_PHASE_HMAC_STEP_2 = 0x04U, /*!< HASH peripheral is in HMAC step 2 processing phase - (step 2 consists in entering the message text) */ - HAL_HASH_PHASE_HMAC_STEP_3 = 0x05U /*!< HASH peripheral is in HMAC step 3 processing phase - (step 3 consists in entering the outer hash function key) */ -} HAL_HASH_PhaseTypeDef; - -/** - * @brief HAL HASH mode suspend definitions - */ -typedef enum -{ - HAL_HASH_SUSPEND_NONE = 0x00U, /*!< HASH peripheral suspension not requested */ - HAL_HASH_SUSPEND = 0x01U /*!< HASH peripheral suspension is requested */ -} HAL_HASH_SuspendTypeDef; - -#if (USE_HAL_HASH_REGISTER_CALLBACKS == 1U) -/** - * @brief HAL HASH common Callback ID enumeration definition - */ -typedef enum -{ - HAL_HASH_MSPINIT_CB_ID = 0x00U, /*!< HASH MspInit callback ID */ - HAL_HASH_MSPDEINIT_CB_ID = 0x01U, /*!< HASH MspDeInit callback ID */ - HAL_HASH_INPUTCPLT_CB_ID = 0x02U, /*!< HASH input completion callback ID */ - HAL_HASH_DGSTCPLT_CB_ID = 0x03U, /*!< HASH digest computation completion callback ID */ - HAL_HASH_ERROR_CB_ID = 0x04U, /*!< HASH error callback ID */ -} HAL_HASH_CallbackIDTypeDef; -#endif /* USE_HAL_HASH_REGISTER_CALLBACKS */ - - -/** - * @brief HASH Handle Structure definition - */ -#if (USE_HAL_HASH_REGISTER_CALLBACKS == 1) -typedef struct __HASH_HandleTypeDef -#else -typedef struct -#endif /* (USE_HAL_HASH_REGISTER_CALLBACKS) */ -{ - HASH_InitTypeDef Init; /*!< HASH required parameters */ - - uint8_t *pHashInBuffPtr; /*!< Pointer to input buffer */ - - uint8_t *pHashOutBuffPtr; /*!< Pointer to output buffer (digest) */ - - uint8_t *pHashKeyBuffPtr; /*!< Pointer to key buffer (HMAC only) */ - - uint8_t *pHashMsgBuffPtr; /*!< Pointer to message buffer (HMAC only) */ - - uint32_t HashBuffSize; /*!< Size of buffer to be processed */ - - __IO uint32_t HashInCount; /*!< Counter of inputted data */ - - __IO uint32_t HashITCounter; /*!< Counter of issued interrupts */ - - __IO uint32_t HashKeyCount; /*!< Counter for Key inputted data (HMAC only) */ - - HAL_StatusTypeDef Status; /*!< HASH peripheral status */ - - HAL_HASH_PhaseTypeDef Phase; /*!< HASH peripheral phase */ - - DMA_HandleTypeDef *hdmain; /*!< HASH In DMA Handle parameters */ - - HAL_LockTypeDef Lock; /*!< Locking object */ - - __IO HAL_HASH_StateTypeDef State; /*!< HASH peripheral state */ - - HAL_HASH_SuspendTypeDef SuspendRequest; /*!< HASH peripheral suspension request flag */ - - FlagStatus DigestCalculationDisable; /*!< Digest calculation phase skip (MDMAT bit control) for multi-buffers DMA-based HMAC computation */ - - __IO uint32_t NbWordsAlreadyPushed; /*!< Numbers of words already pushed in FIFO before inputting new block */ - - __IO uint32_t ErrorCode; /*!< HASH Error code */ - - __IO uint32_t Accumulation; /*!< HASH multi buffers accumulation flag */ - -#if (USE_HAL_HASH_REGISTER_CALLBACKS == 1) - void (* InCpltCallback)(struct __HASH_HandleTypeDef *hhash); /*!< HASH input completion callback */ - - void (* DgstCpltCallback)(struct __HASH_HandleTypeDef *hhash); /*!< HASH digest computation completion callback */ - - void (* ErrorCallback)(struct __HASH_HandleTypeDef *hhash); /*!< HASH error callback */ - - void (* MspInitCallback)(struct __HASH_HandleTypeDef *hhash); /*!< HASH Msp Init callback */ - - void (* MspDeInitCallback)(struct __HASH_HandleTypeDef *hhash); /*!< HASH Msp DeInit callback */ - -#endif /* (USE_HAL_HASH_REGISTER_CALLBACKS) */ -} HASH_HandleTypeDef; - -#if (USE_HAL_HASH_REGISTER_CALLBACKS == 1U) -/** - * @brief HAL HASH Callback pointer definition - */ -typedef void (*pHASH_CallbackTypeDef)(HASH_HandleTypeDef *hhash); /*!< pointer to a HASH common callback functions */ -#endif /* USE_HAL_HASH_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ - -/** @defgroup HASH_Exported_Constants HASH Exported Constants - * @{ - */ - -/** @defgroup HASH_Algo_Selection HASH algorithm selection - * @{ - */ -#define HASH_ALGOSELECTION_SHA1 0x00000000U /*!< HASH function is SHA1 */ -#define HASH_ALGOSELECTION_MD5 HASH_CR_ALGO_0 /*!< HASH function is MD5 */ -#define HASH_ALGOSELECTION_SHA224 HASH_CR_ALGO_1 /*!< HASH function is SHA224 */ -#define HASH_ALGOSELECTION_SHA256 HASH_CR_ALGO /*!< HASH function is SHA256 */ -/** - * @} - */ - -/** @defgroup HASH_Algorithm_Mode HASH algorithm mode - * @{ - */ -#define HASH_ALGOMODE_HASH 0x00000000U /*!< Algorithm is HASH */ -#define HASH_ALGOMODE_HMAC HASH_CR_MODE /*!< Algorithm is HMAC */ -/** - * @} - */ - -/** @defgroup HASH_Data_Type HASH input data type - * @{ - */ -#define HASH_DATATYPE_32B 0x00000000U /*!< 32-bit data. No swapping */ -#define HASH_DATATYPE_16B HASH_CR_DATATYPE_0 /*!< 16-bit data. Each half word is swapped */ -#define HASH_DATATYPE_8B HASH_CR_DATATYPE_1 /*!< 8-bit data. All bytes are swapped */ -#define HASH_DATATYPE_1B HASH_CR_DATATYPE /*!< 1-bit data. In the word all bits are swapped */ -/** - * @} - */ - -/** @defgroup HASH_HMAC_Long_key_only_for_HMAC_mode HMAC key length type - * @{ - */ -#define HASH_HMAC_KEYTYPE_SHORTKEY 0x00000000U /*!< HMAC Key size is <= 64 bytes */ -#define HASH_HMAC_KEYTYPE_LONGKEY HASH_CR_LKEY /*!< HMAC Key size is > 64 bytes */ -/** - * @} - */ - -/** @defgroup HASH_flags_definition HASH flags definitions - * @{ - */ -#define HASH_FLAG_DINIS HASH_SR_DINIS /*!< 16 locations are free in the DIN : a new block can be entered in the Peripheral */ -#define HASH_FLAG_DCIS HASH_SR_DCIS /*!< Digest calculation complete */ -#define HASH_FLAG_DMAS HASH_SR_DMAS /*!< DMA interface is enabled (DMAE=1) or a transfer is ongoing */ -#define HASH_FLAG_BUSY HASH_SR_BUSY /*!< The hash core is Busy, processing a block of data */ -#define HASH_FLAG_DINNE HASH_CR_DINNE /*!< DIN not empty : the input buffer contains at least one word of data */ - -/** - * @} - */ - -/** @defgroup HASH_interrupts_definition HASH interrupts definitions - * @{ - */ -#define HASH_IT_DINI HASH_IMR_DINIE /*!< A new block can be entered into the input buffer (DIN) */ -#define HASH_IT_DCI HASH_IMR_DCIE /*!< Digest calculation complete */ - -/** - * @} - */ - -/** @defgroup HASH_Error_Definition HASH Error Definition - * @{ - */ -#define HAL_HASH_ERROR_NONE 0x00000000U /*!< No error */ -#define HAL_HASH_ERROR_IT 0x00000001U /*!< IT-based process error */ -#define HAL_HASH_ERROR_DMA 0x00000002U /*!< DMA-based process error */ -#if (USE_HAL_HASH_REGISTER_CALLBACKS == 1U) -#define HAL_HASH_ERROR_INVALID_CALLBACK 0x00000004U /*!< Invalid Callback error */ -#endif /* USE_HAL_HASH_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macros -----------------------------------------------------------*/ -/** @defgroup HASH_Exported_Macros HASH Exported Macros - * @{ - */ - -/** @brief Check whether or not the specified HASH flag is set. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg @ref HASH_FLAG_DINIS A new block can be entered into the input buffer. - * @arg @ref HASH_FLAG_DCIS Digest calculation complete. - * @arg @ref HASH_FLAG_DMAS DMA interface is enabled (DMAE=1) or a transfer is ongoing. - * @arg @ref HASH_FLAG_BUSY The hash core is Busy : processing a block of data. - * @arg @ref HASH_FLAG_DINNE DIN not empty : the input buffer contains at least one word of data. - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_HASH_GET_FLAG(__FLAG__) (((__FLAG__) > 8U) ? \ - ((HASH->CR & (__FLAG__)) == (__FLAG__)) :\ - ((HASH->SR & (__FLAG__)) == (__FLAG__)) ) - - -/** @brief Clear the specified HASH flag. - * @param __FLAG__ specifies the flag to clear. - * This parameter can be one of the following values: - * @arg @ref HASH_FLAG_DINIS A new block can be entered into the input buffer. - * @arg @ref HASH_FLAG_DCIS Digest calculation complete - * @retval None - */ -#define __HAL_HASH_CLEAR_FLAG(__FLAG__) CLEAR_BIT(HASH->SR, (__FLAG__)) - - -/** @brief Enable the specified HASH interrupt. - * @param __INTERRUPT__ specifies the HASH interrupt source to enable. - * This parameter can be one of the following values: - * @arg @ref HASH_IT_DINI A new block can be entered into the input buffer (DIN) - * @arg @ref HASH_IT_DCI Digest calculation complete - * @retval None - */ -#define __HAL_HASH_ENABLE_IT(__INTERRUPT__) SET_BIT(HASH->IMR, (__INTERRUPT__)) - -/** @brief Disable the specified HASH interrupt. - * @param __INTERRUPT__ specifies the HASH interrupt source to disable. - * This parameter can be one of the following values: - * @arg @ref HASH_IT_DINI A new block can be entered into the input buffer (DIN) - * @arg @ref HASH_IT_DCI Digest calculation complete - * @retval None - */ -#define __HAL_HASH_DISABLE_IT(__INTERRUPT__) CLEAR_BIT(HASH->IMR, (__INTERRUPT__)) - -/** @brief Reset HASH handle state. - * @param __HANDLE__ HASH handle. - * @retval None - */ - -#if (USE_HAL_HASH_REGISTER_CALLBACKS == 1) -#define __HAL_HASH_RESET_HANDLE_STATE(__HANDLE__) do{\ - (__HANDLE__)->State = HAL_HASH_STATE_RESET;\ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - }while(0) -#else -#define __HAL_HASH_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_HASH_STATE_RESET) -#endif /* USE_HAL_HASH_REGISTER_CALLBACKS */ - - -/** @brief Reset HASH handle status. - * @param __HANDLE__ HASH handle. - * @retval None - */ -#define __HAL_HASH_RESET_HANDLE_STATUS(__HANDLE__) ((__HANDLE__)->Status = HAL_OK) - -/** - * @brief Enable the multi-buffer DMA transfer mode. - * @note This bit is set when hashing large files when multiple DMA transfers are needed. - * @retval None - */ -#define __HAL_HASH_SET_MDMAT() SET_BIT(HASH->CR, HASH_CR_MDMAT) - -/** - * @brief Disable the multi-buffer DMA transfer mode. - * @retval None - */ -#define __HAL_HASH_RESET_MDMAT() CLEAR_BIT(HASH->CR, HASH_CR_MDMAT) - - -/** - * @brief Start the digest computation. - * @retval None - */ -#define __HAL_HASH_START_DIGEST() SET_BIT(HASH->STR, HASH_STR_DCAL) - -/** - * @brief Set the number of valid bits in the last word written in data register DIN. - * @param __SIZE__ size in bytes of last data written in Data register. - * @retval None - */ -#define __HAL_HASH_SET_NBVALIDBITS(__SIZE__) MODIFY_REG(HASH->STR, HASH_STR_NBLW, 8U * ((__SIZE__) % 4U)) - -/** - * @brief Reset the HASH core. - * @retval None - */ -#define __HAL_HASH_INIT() SET_BIT(HASH->CR, HASH_CR_INIT) - -/** - * @} - */ - - -/* Private macros --------------------------------------------------------*/ -/** @defgroup HASH_Private_Macros HASH Private Macros - * @{ - */ -/** - * @brief Return digest length in bytes. - * @retval Digest length - */ -#if defined(HASH_CR_MDMAT) -#define HASH_DIGEST_LENGTH() ((READ_BIT(HASH->CR, HASH_CR_ALGO) == HASH_ALGOSELECTION_SHA1) ? 20U : \ - ((READ_BIT(HASH->CR, HASH_CR_ALGO) == HASH_ALGOSELECTION_SHA224) ? 28U : \ - ((READ_BIT(HASH->CR, HASH_CR_ALGO) == HASH_ALGOSELECTION_SHA256) ? 32U : 16U ) ) ) -#else -#define HASH_DIGEST_LENGTH() ((READ_BIT(HASH->CR, HASH_CR_ALGO) == HASH_ALGOSELECTION_SHA1) ? 20U : 16) -#endif /* HASH_CR_MDMAT*/ -/** - * @brief Return number of words already pushed in the FIFO. - * @retval Number of words already pushed in the FIFO - */ -#define HASH_NBW_PUSHED() ((READ_BIT(HASH->CR, HASH_CR_NBW)) >> 8U) - -/** - * @brief Ensure that HASH input data type is valid. - * @param __DATATYPE__ HASH input data type. - * @retval SET (__DATATYPE__ is valid) or RESET (__DATATYPE__ is invalid) - */ -#define IS_HASH_DATATYPE(__DATATYPE__) (((__DATATYPE__) == HASH_DATATYPE_32B)|| \ - ((__DATATYPE__) == HASH_DATATYPE_16B)|| \ - ((__DATATYPE__) == HASH_DATATYPE_8B) || \ - ((__DATATYPE__) == HASH_DATATYPE_1B)) - -/** - * @brief Ensure that input data buffer size is valid for multi-buffer HASH - * processing in DMA mode. - * @note This check is valid only for multi-buffer HASH processing in DMA mode. - * @param __SIZE__ input data buffer size. - * @retval SET (__SIZE__ is valid) or RESET (__SIZE__ is invalid) - */ -#define IS_HASH_DMA_MULTIBUFFER_SIZE(__SIZE__) ((READ_BIT(HASH->CR, HASH_CR_MDMAT) == 0U) || (((__SIZE__) % 4U) == 0U)) - -/** - * @brief Ensure that input data buffer size is valid for multi-buffer HMAC - * processing in DMA mode. - * @note This check is valid only for multi-buffer HMAC processing in DMA mode. - * @param __HANDLE__ HASH handle. - * @param __SIZE__ input data buffer size. - * @retval SET (__SIZE__ is valid) or RESET (__SIZE__ is invalid) - */ -#define IS_HMAC_DMA_MULTIBUFFER_SIZE(__HANDLE__,__SIZE__) ((((__HANDLE__)->DigestCalculationDisable) == RESET)\ - || (((__SIZE__) % 4U) == 0U)) -/** - * @brief Ensure that handle phase is set to HASH processing. - * @param __HANDLE__ HASH handle. - * @retval SET (handle phase is set to HASH processing) or RESET (handle phase is not set to HASH processing) - */ -#define IS_HASH_PROCESSING(__HANDLE__) ((__HANDLE__)->Phase == HAL_HASH_PHASE_PROCESS) - -/** - * @brief Ensure that handle phase is set to HMAC processing. - * @param __HANDLE__ HASH handle. - * @retval SET (handle phase is set to HMAC processing) or RESET (handle phase is not set to HMAC processing) - */ -#define IS_HMAC_PROCESSING(__HANDLE__) (((__HANDLE__)->Phase == HAL_HASH_PHASE_HMAC_STEP_1) || \ - ((__HANDLE__)->Phase == HAL_HASH_PHASE_HMAC_STEP_2) || \ - ((__HANDLE__)->Phase == HAL_HASH_PHASE_HMAC_STEP_3)) - -/** - * @} - */ - -/* Include HASH HAL Extended module */ -#include "stm32f4xx_hal_hash_ex.h" -/* Exported functions --------------------------------------------------------*/ - -/** @addtogroup HASH_Exported_Functions HASH Exported Functions - * @{ - */ - -/** @addtogroup HASH_Exported_Functions_Group1 Initialization and de-initialization functions - * @{ - */ - -/* Initialization/de-initialization methods **********************************/ -HAL_StatusTypeDef HAL_HASH_Init(HASH_HandleTypeDef *hhash); -HAL_StatusTypeDef HAL_HASH_DeInit(HASH_HandleTypeDef *hhash); -void HAL_HASH_MspInit(HASH_HandleTypeDef *hhash); -void HAL_HASH_MspDeInit(HASH_HandleTypeDef *hhash); -void HAL_HASH_InCpltCallback(HASH_HandleTypeDef *hhash); -void HAL_HASH_DgstCpltCallback(HASH_HandleTypeDef *hhash); -void HAL_HASH_ErrorCallback(HASH_HandleTypeDef *hhash); -/* Callbacks Register/UnRegister functions ***********************************/ -#if (USE_HAL_HASH_REGISTER_CALLBACKS == 1) -HAL_StatusTypeDef HAL_HASH_RegisterCallback(HASH_HandleTypeDef *hhash, HAL_HASH_CallbackIDTypeDef CallbackID, - pHASH_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_HASH_UnRegisterCallback(HASH_HandleTypeDef *hhash, HAL_HASH_CallbackIDTypeDef CallbackID); -#endif /* USE_HAL_HASH_REGISTER_CALLBACKS */ - - -/** - * @} - */ - -/** @addtogroup HASH_Exported_Functions_Group2 HASH processing functions in polling mode - * @{ - */ - - -/* HASH processing using polling *********************************************/ -HAL_StatusTypeDef HAL_HASH_SHA1_Start(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint8_t *pOutBuffer, - uint32_t Timeout); -HAL_StatusTypeDef HAL_HASH_MD5_Start(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint8_t *pOutBuffer, - uint32_t Timeout); -HAL_StatusTypeDef HAL_HASH_MD5_Accmlt(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HASH_SHA1_Accmlt(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HASH_MD5_Accmlt_End(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer, uint32_t Timeout); -HAL_StatusTypeDef HAL_HASH_SHA1_Accmlt_End(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer, uint32_t Timeout); - - -/** - * @} - */ - -/** @addtogroup HASH_Exported_Functions_Group3 HASH processing functions in interrupt mode - * @{ - */ - -/* HASH processing using IT **************************************************/ -HAL_StatusTypeDef HAL_HASH_SHA1_Start_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer); -HAL_StatusTypeDef HAL_HASH_SHA1_Accmlt_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HASH_SHA1_Accmlt_End_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer); -HAL_StatusTypeDef HAL_HASH_MD5_Start_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer); -HAL_StatusTypeDef HAL_HASH_MD5_Accmlt_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HASH_MD5_Accmlt_End_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer); -void HAL_HASH_IRQHandler(HASH_HandleTypeDef *hhash); -/** - * @} - */ - -/** @addtogroup HASH_Exported_Functions_Group4 HASH processing functions in DMA mode - * @{ - */ - -/* HASH processing using DMA *************************************************/ -HAL_StatusTypeDef HAL_HASH_SHA1_Start_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HASH_SHA1_Finish(HASH_HandleTypeDef *hhash, uint8_t *pOutBuffer, uint32_t Timeout); -HAL_StatusTypeDef HAL_HASH_MD5_Start_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HASH_MD5_Finish(HASH_HandleTypeDef *hhash, uint8_t *pOutBuffer, uint32_t Timeout); - -/** - * @} - */ - -/** @addtogroup HASH_Exported_Functions_Group5 HMAC processing functions in polling mode - * @{ - */ - -/* HASH-MAC processing using polling *****************************************/ -HAL_StatusTypeDef HAL_HMAC_SHA1_Start(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint8_t *pOutBuffer, - uint32_t Timeout); -HAL_StatusTypeDef HAL_HMAC_MD5_Start(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint8_t *pOutBuffer, - uint32_t Timeout); - -/** - * @} - */ - -/** @addtogroup HASH_Exported_Functions_Group6 HMAC processing functions in interrupt mode - * @{ - */ - -HAL_StatusTypeDef HAL_HMAC_MD5_Start_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer); -HAL_StatusTypeDef HAL_HMAC_SHA1_Start_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer); - -/** - * @} - */ - -/** @addtogroup HASH_Exported_Functions_Group7 HMAC processing functions in DMA mode - * @{ - */ - -/* HASH-HMAC processing using DMA ********************************************/ -HAL_StatusTypeDef HAL_HMAC_SHA1_Start_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HMAC_MD5_Start_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); - -/** - * @} - */ - -/** @addtogroup HASH_Exported_Functions_Group8 Peripheral states functions - * @{ - */ - - -/* Peripheral State methods **************************************************/ -HAL_HASH_StateTypeDef HAL_HASH_GetState(HASH_HandleTypeDef *hhash); -HAL_StatusTypeDef HAL_HASH_GetStatus(HASH_HandleTypeDef *hhash); -void HAL_HASH_ContextSaving(HASH_HandleTypeDef *hhash, uint8_t *pMemBuffer); -void HAL_HASH_ContextRestoring(HASH_HandleTypeDef *hhash, uint8_t *pMemBuffer); -void HAL_HASH_SwFeed_ProcessSuspend(HASH_HandleTypeDef *hhash); -HAL_StatusTypeDef HAL_HASH_DMAFeed_ProcessSuspend(HASH_HandleTypeDef *hhash); -uint32_t HAL_HASH_GetError(HASH_HandleTypeDef *hhash); - -/** - * @} - */ - -/** - * @} - */ - -/* Private functions -----------------------------------------------------------*/ - -/** @addtogroup HASH_Private_Functions HASH Private Functions - * @{ - */ - -/* Private functions */ -HAL_StatusTypeDef HASH_Start(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint8_t *pOutBuffer, - uint32_t Timeout, uint32_t Algorithm); -HAL_StatusTypeDef HASH_Accumulate(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint32_t Algorithm); -HAL_StatusTypeDef HASH_Accumulate_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint32_t Algorithm); -HAL_StatusTypeDef HASH_Start_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint8_t *pOutBuffer, - uint32_t Algorithm); -HAL_StatusTypeDef HASH_Start_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint32_t Algorithm); -HAL_StatusTypeDef HASH_Finish(HASH_HandleTypeDef *hhash, uint8_t *pOutBuffer, uint32_t Timeout); -HAL_StatusTypeDef HMAC_Start(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint8_t *pOutBuffer, - uint32_t Timeout, uint32_t Algorithm); -HAL_StatusTypeDef HMAC_Start_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint8_t *pOutBuffer, - uint32_t Algorithm); -HAL_StatusTypeDef HMAC_Start_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, uint32_t Algorithm); - -/** - * @} - */ - -/** - * @} - */ -#endif /* HASH*/ -/** - * @} - */ - - -#ifdef __cplusplus -} -#endif - - -#endif /* STM32F4xx_HAL_HASH_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_hash_ex.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_hash_ex.h deleted file mode 100644 index 0a9844c..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_hash_ex.h +++ /dev/null @@ -1,177 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_hash_ex.h - * @author MCD Application Team - * @brief Header file of HASH HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_HASH_EX_H -#define STM32F4xx_HAL_HASH_EX_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ -#if defined (HASH) -/** @addtogroup HASHEx - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/* Exported macro ------------------------------------------------------------*/ - - -/* Exported functions --------------------------------------------------------*/ - -/** @addtogroup HASHEx_Exported_Functions HASH Extended Exported Functions - * @{ - */ - -/** @addtogroup HASHEx_Exported_Functions_Group1 HASH extended processing functions in polling mode - * @{ - */ - -HAL_StatusTypeDef HAL_HASHEx_SHA224_Start(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer, uint32_t Timeout); -HAL_StatusTypeDef HAL_HASHEx_SHA224_Accmlt(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HASHEx_SHA224_Accmlt_End(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer, uint32_t Timeout); -HAL_StatusTypeDef HAL_HASHEx_SHA256_Start(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer, uint32_t Timeout); -HAL_StatusTypeDef HAL_HASHEx_SHA256_Accmlt(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HASHEx_SHA256_Accmlt_End(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer, uint32_t Timeout); - -/** - * @} - */ - -/** @addtogroup HASHEx_Exported_Functions_Group2 HASH extended processing functions in interrupt mode - * @{ - */ - -HAL_StatusTypeDef HAL_HASHEx_SHA224_Start_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer); -HAL_StatusTypeDef HAL_HASHEx_SHA224_Accmlt_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HASHEx_SHA224_Accmlt_End_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer); -HAL_StatusTypeDef HAL_HASHEx_SHA256_Start_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer); -HAL_StatusTypeDef HAL_HASHEx_SHA256_Accmlt_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HASHEx_SHA256_Accmlt_End_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer); - -/** - * @} - */ - -/** @addtogroup HASHEx_Exported_Functions_Group3 HASH extended processing functions in DMA mode - * @{ - */ -HAL_StatusTypeDef HAL_HASHEx_SHA224_Start_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HASHEx_SHA224_Finish(HASH_HandleTypeDef *hhash, uint8_t *pOutBuffer, uint32_t Timeout); -HAL_StatusTypeDef HAL_HASHEx_SHA256_Start_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HASHEx_SHA256_Finish(HASH_HandleTypeDef *hhash, uint8_t *pOutBuffer, uint32_t Timeout); - -/** - * @} - */ - -/** @addtogroup HASHEx_Exported_Functions_Group4 HMAC extended processing functions in polling mode - * @{ - */ -HAL_StatusTypeDef HAL_HMACEx_SHA224_Start(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer, uint32_t Timeout); -HAL_StatusTypeDef HAL_HMACEx_SHA256_Start(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer, uint32_t Timeout); -/** - * @} - */ - -/** @addtogroup HASHEx_Exported_Functions_Group5 HMAC extended processing functions in interrupt mode - * @{ - */ - -HAL_StatusTypeDef HAL_HMACEx_SHA224_Start_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer); -HAL_StatusTypeDef HAL_HMACEx_SHA256_Start_IT(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size, - uint8_t *pOutBuffer); - -/** - * @} - */ - -/** @addtogroup HASHEx_Exported_Functions_Group6 HMAC extended processing functions in DMA mode - * @{ - */ - -HAL_StatusTypeDef HAL_HMACEx_SHA224_Start_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HMACEx_SHA256_Start_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); - -/** - * @} - */ - -/** @addtogroup HASHEx_Exported_Functions_Group7 Multi-buffer HMAC extended processing functions in DMA mode - * @{ - */ - -HAL_StatusTypeDef HAL_HMACEx_MD5_Step1_2_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HMACEx_MD5_Step2_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HMACEx_MD5_Step2_3_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); - -HAL_StatusTypeDef HAL_HMACEx_SHA1_Step1_2_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HMACEx_SHA1_Step2_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HMACEx_SHA1_Step2_3_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HMACEx_SHA224_Step1_2_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HMACEx_SHA224_Step2_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HMACEx_SHA224_Step2_3_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); - -HAL_StatusTypeDef HAL_HMACEx_SHA256_Step1_2_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HMACEx_SHA256_Step2_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -HAL_StatusTypeDef HAL_HMACEx_SHA256_Step2_3_DMA(HASH_HandleTypeDef *hhash, uint8_t *pInBuffer, uint32_t Size); -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ -#endif /* HASH*/ -/** - * @} - */ - - -#ifdef __cplusplus -} -#endif - - -#endif /* STM32F4xx_HAL_HASH_EX_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_hcd.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_hcd.h deleted file mode 100644 index 6025e03..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_hcd.h +++ /dev/null @@ -1,319 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_hcd.h - * @author MCD Application Team - * @brief Header file of HCD HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_HCD_H -#define STM32F4xx_HAL_HCD_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_ll_usb.h" - -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup HCD HCD - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup HCD_Exported_Types HCD Exported Types - * @{ - */ - -/** @defgroup HCD_Exported_Types_Group1 HCD State Structure definition - * @{ - */ -typedef enum -{ - HAL_HCD_STATE_RESET = 0x00, - HAL_HCD_STATE_READY = 0x01, - HAL_HCD_STATE_ERROR = 0x02, - HAL_HCD_STATE_BUSY = 0x03, - HAL_HCD_STATE_TIMEOUT = 0x04 -} HCD_StateTypeDef; - -typedef USB_OTG_GlobalTypeDef HCD_TypeDef; -typedef USB_OTG_CfgTypeDef HCD_InitTypeDef; -typedef USB_OTG_HCTypeDef HCD_HCTypeDef; -typedef USB_OTG_URBStateTypeDef HCD_URBStateTypeDef; -typedef USB_OTG_HCStateTypeDef HCD_HCStateTypeDef; -/** - * @} - */ - -/** @defgroup HCD_Exported_Types_Group2 HCD Handle Structure definition - * @{ - */ -#if (USE_HAL_HCD_REGISTER_CALLBACKS == 1U) -typedef struct __HCD_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_HCD_REGISTER_CALLBACKS */ -{ - HCD_TypeDef *Instance; /*!< Register base address */ - HCD_InitTypeDef Init; /*!< HCD required parameters */ - HCD_HCTypeDef hc[16]; /*!< Host channels parameters */ - HAL_LockTypeDef Lock; /*!< HCD peripheral status */ - __IO HCD_StateTypeDef State; /*!< HCD communication state */ - __IO uint32_t ErrorCode; /*!< HCD Error code */ - void *pData; /*!< Pointer Stack Handler */ -#if (USE_HAL_HCD_REGISTER_CALLBACKS == 1U) - void (* SOFCallback)(struct __HCD_HandleTypeDef *hhcd); /*!< USB OTG HCD SOF callback */ - void (* ConnectCallback)(struct __HCD_HandleTypeDef *hhcd); /*!< USB OTG HCD Connect callback */ - void (* DisconnectCallback)(struct __HCD_HandleTypeDef *hhcd); /*!< USB OTG HCD Disconnect callback */ - void (* PortEnabledCallback)(struct __HCD_HandleTypeDef *hhcd); /*!< USB OTG HCD Port Enable callback */ - void (* PortDisabledCallback)(struct __HCD_HandleTypeDef *hhcd); /*!< USB OTG HCD Port Disable callback */ - void (* HC_NotifyURBChangeCallback)(struct __HCD_HandleTypeDef *hhcd, uint8_t chnum, - HCD_URBStateTypeDef urb_state); /*!< USB OTG HCD Host Channel Notify URB Change callback */ - - void (* MspInitCallback)(struct __HCD_HandleTypeDef *hhcd); /*!< USB OTG HCD Msp Init callback */ - void (* MspDeInitCallback)(struct __HCD_HandleTypeDef *hhcd); /*!< USB OTG HCD Msp DeInit callback */ -#endif /* USE_HAL_HCD_REGISTER_CALLBACKS */ -} HCD_HandleTypeDef; -/** - * @} - */ - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup HCD_Exported_Constants HCD Exported Constants - * @{ - */ - -/** @defgroup HCD_Speed HCD Speed - * @{ - */ -#define HCD_SPEED_HIGH USBH_HS_SPEED -#define HCD_SPEED_FULL USBH_FSLS_SPEED -#define HCD_SPEED_LOW USBH_FSLS_SPEED -/** - * @} - */ - -/** @defgroup HCD_Device_Speed HCD Device Speed - * @{ - */ -#define HCD_DEVICE_SPEED_HIGH 0U -#define HCD_DEVICE_SPEED_FULL 1U -#define HCD_DEVICE_SPEED_LOW 2U -/** - * @} - */ - -/** @defgroup HCD_PHY_Module HCD PHY Module - * @{ - */ -#define HCD_PHY_ULPI 1U -#define HCD_PHY_EMBEDDED 2U -/** - * @} - */ - -/** @defgroup HCD_Error_Code_definition HCD Error Code definition - * @brief HCD Error Code definition - * @{ - */ -#if (USE_HAL_HCD_REGISTER_CALLBACKS == 1U) -#define HAL_HCD_ERROR_INVALID_CALLBACK (0x00000010U) /*!< Invalid Callback error */ -#endif /* USE_HAL_HCD_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup HCD_Exported_Macros HCD Exported Macros - * @brief macros to handle interrupts and specific clock configurations - * @{ - */ -#define __HAL_HCD_ENABLE(__HANDLE__) (void)USB_EnableGlobalInt ((__HANDLE__)->Instance) -#define __HAL_HCD_DISABLE(__HANDLE__) (void)USB_DisableGlobalInt ((__HANDLE__)->Instance) - -#define __HAL_HCD_GET_FLAG(__HANDLE__, __INTERRUPT__) ((USB_ReadInterrupts((__HANDLE__)->Instance)\ - & (__INTERRUPT__)) == (__INTERRUPT__)) -#define __HAL_HCD_CLEAR_FLAG(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->GINTSTS) = (__INTERRUPT__)) -#define __HAL_HCD_IS_INVALID_INTERRUPT(__HANDLE__) (USB_ReadInterrupts((__HANDLE__)->Instance) == 0U) - -#define __HAL_HCD_CLEAR_HC_INT(chnum, __INTERRUPT__) (USBx_HC(chnum)->HCINT = (__INTERRUPT__)) -#define __HAL_HCD_MASK_HALT_HC_INT(chnum) (USBx_HC(chnum)->HCINTMSK &= ~USB_OTG_HCINTMSK_CHHM) -#define __HAL_HCD_UNMASK_HALT_HC_INT(chnum) (USBx_HC(chnum)->HCINTMSK |= USB_OTG_HCINTMSK_CHHM) -#define __HAL_HCD_MASK_ACK_HC_INT(chnum) (USBx_HC(chnum)->HCINTMSK &= ~USB_OTG_HCINTMSK_ACKM) -#define __HAL_HCD_UNMASK_ACK_HC_INT(chnum) (USBx_HC(chnum)->HCINTMSK |= USB_OTG_HCINTMSK_ACKM) -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup HCD_Exported_Functions HCD Exported Functions - * @{ - */ - -/** @defgroup HCD_Exported_Functions_Group1 Initialization and de-initialization functions - * @{ - */ -HAL_StatusTypeDef HAL_HCD_Init(HCD_HandleTypeDef *hhcd); -HAL_StatusTypeDef HAL_HCD_DeInit(HCD_HandleTypeDef *hhcd); -HAL_StatusTypeDef HAL_HCD_HC_Init(HCD_HandleTypeDef *hhcd, uint8_t ch_num, - uint8_t epnum, uint8_t dev_address, - uint8_t speed, uint8_t ep_type, uint16_t mps); - -HAL_StatusTypeDef HAL_HCD_HC_Halt(HCD_HandleTypeDef *hhcd, uint8_t ch_num); -void HAL_HCD_MspInit(HCD_HandleTypeDef *hhcd); -void HAL_HCD_MspDeInit(HCD_HandleTypeDef *hhcd); - -#if (USE_HAL_HCD_REGISTER_CALLBACKS == 1U) -/** @defgroup HAL_HCD_Callback_ID_enumeration_definition HAL USB OTG HCD Callback ID enumeration definition - * @brief HAL USB OTG HCD Callback ID enumeration definition - * @{ - */ -typedef enum -{ - HAL_HCD_SOF_CB_ID = 0x01, /*!< USB HCD SOF callback ID */ - HAL_HCD_CONNECT_CB_ID = 0x02, /*!< USB HCD Connect callback ID */ - HAL_HCD_DISCONNECT_CB_ID = 0x03, /*!< USB HCD Disconnect callback ID */ - HAL_HCD_PORT_ENABLED_CB_ID = 0x04, /*!< USB HCD Port Enable callback ID */ - HAL_HCD_PORT_DISABLED_CB_ID = 0x05, /*!< USB HCD Port Disable callback ID */ - - HAL_HCD_MSPINIT_CB_ID = 0x06, /*!< USB HCD MspInit callback ID */ - HAL_HCD_MSPDEINIT_CB_ID = 0x07 /*!< USB HCD MspDeInit callback ID */ - -} HAL_HCD_CallbackIDTypeDef; -/** - * @} - */ - -/** @defgroup HAL_HCD_Callback_pointer_definition HAL USB OTG HCD Callback pointer definition - * @brief HAL USB OTG HCD Callback pointer definition - * @{ - */ - -typedef void (*pHCD_CallbackTypeDef)(HCD_HandleTypeDef *hhcd); /*!< pointer to a common USB OTG HCD callback function */ -typedef void (*pHCD_HC_NotifyURBChangeCallbackTypeDef)(HCD_HandleTypeDef *hhcd, - uint8_t epnum, - HCD_URBStateTypeDef urb_state); /*!< pointer to USB OTG HCD host channel callback */ -/** - * @} - */ - -HAL_StatusTypeDef HAL_HCD_RegisterCallback(HCD_HandleTypeDef *hhcd, - HAL_HCD_CallbackIDTypeDef CallbackID, - pHCD_CallbackTypeDef pCallback); - -HAL_StatusTypeDef HAL_HCD_UnRegisterCallback(HCD_HandleTypeDef *hhcd, - HAL_HCD_CallbackIDTypeDef CallbackID); - -HAL_StatusTypeDef HAL_HCD_RegisterHC_NotifyURBChangeCallback(HCD_HandleTypeDef *hhcd, - pHCD_HC_NotifyURBChangeCallbackTypeDef pCallback); - -HAL_StatusTypeDef HAL_HCD_UnRegisterHC_NotifyURBChangeCallback(HCD_HandleTypeDef *hhcd); -#endif /* USE_HAL_HCD_REGISTER_CALLBACKS */ -/** - * @} - */ - -/* I/O operation functions ***************************************************/ -/** @addtogroup HCD_Exported_Functions_Group2 Input and Output operation functions - * @{ - */ -HAL_StatusTypeDef HAL_HCD_HC_SubmitRequest(HCD_HandleTypeDef *hhcd, uint8_t ch_num, - uint8_t direction, uint8_t ep_type, - uint8_t token, uint8_t *pbuff, - uint16_t length, uint8_t do_ping); - -/* Non-Blocking mode: Interrupt */ -void HAL_HCD_IRQHandler(HCD_HandleTypeDef *hhcd); -void HAL_HCD_WKUP_IRQHandler(HCD_HandleTypeDef *hhcd); -void HAL_HCD_SOF_Callback(HCD_HandleTypeDef *hhcd); -void HAL_HCD_Connect_Callback(HCD_HandleTypeDef *hhcd); -void HAL_HCD_Disconnect_Callback(HCD_HandleTypeDef *hhcd); -void HAL_HCD_PortEnabled_Callback(HCD_HandleTypeDef *hhcd); -void HAL_HCD_PortDisabled_Callback(HCD_HandleTypeDef *hhcd); -void HAL_HCD_HC_NotifyURBChange_Callback(HCD_HandleTypeDef *hhcd, uint8_t chnum, - HCD_URBStateTypeDef urb_state); -/** - * @} - */ - -/* Peripheral Control functions **********************************************/ -/** @addtogroup HCD_Exported_Functions_Group3 Peripheral Control functions - * @{ - */ -HAL_StatusTypeDef HAL_HCD_ResetPort(HCD_HandleTypeDef *hhcd); -HAL_StatusTypeDef HAL_HCD_Start(HCD_HandleTypeDef *hhcd); -HAL_StatusTypeDef HAL_HCD_Stop(HCD_HandleTypeDef *hhcd); -/** - * @} - */ - -/* Peripheral State functions ************************************************/ -/** @addtogroup HCD_Exported_Functions_Group4 Peripheral State functions - * @{ - */ -HCD_StateTypeDef HAL_HCD_GetState(HCD_HandleTypeDef *hhcd); -HCD_URBStateTypeDef HAL_HCD_HC_GetURBState(HCD_HandleTypeDef *hhcd, uint8_t chnum); -HCD_HCStateTypeDef HAL_HCD_HC_GetState(HCD_HandleTypeDef *hhcd, uint8_t chnum); -uint32_t HAL_HCD_HC_GetXferCount(HCD_HandleTypeDef *hhcd, uint8_t chnum); -uint32_t HAL_HCD_GetCurrentFrame(HCD_HandleTypeDef *hhcd); -uint32_t HAL_HCD_GetCurrentSpeed(HCD_HandleTypeDef *hhcd); - -/** - * @} - */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup HCD_Private_Macros HCD Private Macros - * @{ - */ -/** - * @} - */ -/* Private functions prototypes ----------------------------------------------*/ - -/** - * @} - */ -/** - * @} - */ -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_HAL_HCD_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2c.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2c.h deleted file mode 100644 index 9a622b8..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2c.h +++ /dev/null @@ -1,743 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_i2c.h - * @author MCD Application Team - * @brief Header file of I2C HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_I2C_H -#define __STM32F4xx_HAL_I2C_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup I2C - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup I2C_Exported_Types I2C Exported Types - * @{ - */ - -/** @defgroup I2C_Configuration_Structure_definition I2C Configuration Structure definition - * @brief I2C Configuration Structure definition - * @{ - */ -typedef struct -{ - uint32_t ClockSpeed; /*!< Specifies the clock frequency. - This parameter must be set to a value lower than 400kHz */ - - uint32_t DutyCycle; /*!< Specifies the I2C fast mode duty cycle. - This parameter can be a value of @ref I2C_duty_cycle_in_fast_mode */ - - uint32_t OwnAddress1; /*!< Specifies the first device own address. - This parameter can be a 7-bit or 10-bit address. */ - - uint32_t AddressingMode; /*!< Specifies if 7-bit or 10-bit addressing mode is selected. - This parameter can be a value of @ref I2C_addressing_mode */ - - uint32_t DualAddressMode; /*!< Specifies if dual addressing mode is selected. - This parameter can be a value of @ref I2C_dual_addressing_mode */ - - uint32_t OwnAddress2; /*!< Specifies the second device own address if dual addressing mode is selected - This parameter can be a 7-bit address. */ - - uint32_t GeneralCallMode; /*!< Specifies if general call mode is selected. - This parameter can be a value of @ref I2C_general_call_addressing_mode */ - - uint32_t NoStretchMode; /*!< Specifies if nostretch mode is selected. - This parameter can be a value of @ref I2C_nostretch_mode */ - -} I2C_InitTypeDef; - -/** - * @} - */ - -/** @defgroup HAL_state_structure_definition HAL state structure definition - * @brief HAL State structure definition - * @note HAL I2C State value coding follow below described bitmap : - * b7-b6 Error information - * 00 : No Error - * 01 : Abort (Abort user request on going) - * 10 : Timeout - * 11 : Error - * b5 Peripheral initialization status - * 0 : Reset (Peripheral not initialized) - * 1 : Init done (Peripheral initialized and ready to use. HAL I2C Init function called) - * b4 (not used) - * x : Should be set to 0 - * b3 - * 0 : Ready or Busy (No Listen mode ongoing) - * 1 : Listen (Peripheral in Address Listen Mode) - * b2 Intrinsic process state - * 0 : Ready - * 1 : Busy (Peripheral busy with some configuration or internal operations) - * b1 Rx state - * 0 : Ready (no Rx operation ongoing) - * 1 : Busy (Rx operation ongoing) - * b0 Tx state - * 0 : Ready (no Tx operation ongoing) - * 1 : Busy (Tx operation ongoing) - * @{ - */ -typedef enum -{ - HAL_I2C_STATE_RESET = 0x00U, /*!< Peripheral is not yet Initialized */ - HAL_I2C_STATE_READY = 0x20U, /*!< Peripheral Initialized and ready for use */ - HAL_I2C_STATE_BUSY = 0x24U, /*!< An internal process is ongoing */ - HAL_I2C_STATE_BUSY_TX = 0x21U, /*!< Data Transmission process is ongoing */ - HAL_I2C_STATE_BUSY_RX = 0x22U, /*!< Data Reception process is ongoing */ - HAL_I2C_STATE_LISTEN = 0x28U, /*!< Address Listen Mode is ongoing */ - HAL_I2C_STATE_BUSY_TX_LISTEN = 0x29U, /*!< Address Listen Mode and Data Transmission - process is ongoing */ - HAL_I2C_STATE_BUSY_RX_LISTEN = 0x2AU, /*!< Address Listen Mode and Data Reception - process is ongoing */ - HAL_I2C_STATE_ABORT = 0x60U, /*!< Abort user request ongoing */ - HAL_I2C_STATE_TIMEOUT = 0xA0U, /*!< Timeout state */ - HAL_I2C_STATE_ERROR = 0xE0U /*!< Error */ - -} HAL_I2C_StateTypeDef; - -/** - * @} - */ - -/** @defgroup HAL_mode_structure_definition HAL mode structure definition - * @brief HAL Mode structure definition - * @note HAL I2C Mode value coding follow below described bitmap :\n - * b7 (not used)\n - * x : Should be set to 0\n - * b6\n - * 0 : None\n - * 1 : Memory (HAL I2C communication is in Memory Mode)\n - * b5\n - * 0 : None\n - * 1 : Slave (HAL I2C communication is in Slave Mode)\n - * b4\n - * 0 : None\n - * 1 : Master (HAL I2C communication is in Master Mode)\n - * b3-b2-b1-b0 (not used)\n - * xxxx : Should be set to 0000 - * @{ - */ -typedef enum -{ - HAL_I2C_MODE_NONE = 0x00U, /*!< No I2C communication on going */ - HAL_I2C_MODE_MASTER = 0x10U, /*!< I2C communication is in Master Mode */ - HAL_I2C_MODE_SLAVE = 0x20U, /*!< I2C communication is in Slave Mode */ - HAL_I2C_MODE_MEM = 0x40U /*!< I2C communication is in Memory Mode */ - -} HAL_I2C_ModeTypeDef; - -/** - * @} - */ - -/** @defgroup I2C_Error_Code_definition I2C Error Code definition - * @brief I2C Error Code definition - * @{ - */ -#define HAL_I2C_ERROR_NONE 0x00000000U /*!< No error */ -#define HAL_I2C_ERROR_BERR 0x00000001U /*!< BERR error */ -#define HAL_I2C_ERROR_ARLO 0x00000002U /*!< ARLO error */ -#define HAL_I2C_ERROR_AF 0x00000004U /*!< AF error */ -#define HAL_I2C_ERROR_OVR 0x00000008U /*!< OVR error */ -#define HAL_I2C_ERROR_DMA 0x00000010U /*!< DMA transfer error */ -#define HAL_I2C_ERROR_TIMEOUT 0x00000020U /*!< Timeout Error */ -#define HAL_I2C_ERROR_SIZE 0x00000040U /*!< Size Management error */ -#define HAL_I2C_ERROR_DMA_PARAM 0x00000080U /*!< DMA Parameter Error */ -#define HAL_I2C_WRONG_START 0x00000200U /*!< Wrong start Error */ -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) -#define HAL_I2C_ERROR_INVALID_CALLBACK 0x00000100U /*!< Invalid Callback error */ -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @defgroup I2C_handle_Structure_definition I2C handle Structure definition - * @brief I2C handle Structure definition - * @{ - */ -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) -typedef struct __I2C_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ -{ - I2C_TypeDef *Instance; /*!< I2C registers base address */ - - I2C_InitTypeDef Init; /*!< I2C communication parameters */ - - uint8_t *pBuffPtr; /*!< Pointer to I2C transfer buffer */ - - uint16_t XferSize; /*!< I2C transfer size */ - - __IO uint16_t XferCount; /*!< I2C transfer counter */ - - __IO uint32_t XferOptions; /*!< I2C transfer options */ - - __IO uint32_t PreviousState; /*!< I2C communication Previous state and mode - context for internal usage */ - - DMA_HandleTypeDef *hdmatx; /*!< I2C Tx DMA handle parameters */ - - DMA_HandleTypeDef *hdmarx; /*!< I2C Rx DMA handle parameters */ - - HAL_LockTypeDef Lock; /*!< I2C locking object */ - - __IO HAL_I2C_StateTypeDef State; /*!< I2C communication state */ - - __IO HAL_I2C_ModeTypeDef Mode; /*!< I2C communication mode */ - - __IO uint32_t ErrorCode; /*!< I2C Error code */ - - __IO uint32_t Devaddress; /*!< I2C Target device address */ - - __IO uint32_t Memaddress; /*!< I2C Target memory address */ - - __IO uint32_t MemaddSize; /*!< I2C Target memory address size */ - - __IO uint32_t EventCount; /*!< I2C Event counter */ - - -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) - void (* MasterTxCpltCallback)(struct __I2C_HandleTypeDef *hi2c); /*!< I2C Master Tx Transfer completed callback */ - void (* MasterRxCpltCallback)(struct __I2C_HandleTypeDef *hi2c); /*!< I2C Master Rx Transfer completed callback */ - void (* SlaveTxCpltCallback)(struct __I2C_HandleTypeDef *hi2c); /*!< I2C Slave Tx Transfer completed callback */ - void (* SlaveRxCpltCallback)(struct __I2C_HandleTypeDef *hi2c); /*!< I2C Slave Rx Transfer completed callback */ - void (* ListenCpltCallback)(struct __I2C_HandleTypeDef *hi2c); /*!< I2C Listen Complete callback */ - void (* MemTxCpltCallback)(struct __I2C_HandleTypeDef *hi2c); /*!< I2C Memory Tx Transfer completed callback */ - void (* MemRxCpltCallback)(struct __I2C_HandleTypeDef *hi2c); /*!< I2C Memory Rx Transfer completed callback */ - void (* ErrorCallback)(struct __I2C_HandleTypeDef *hi2c); /*!< I2C Error callback */ - void (* AbortCpltCallback)(struct __I2C_HandleTypeDef *hi2c); /*!< I2C Abort callback */ - - void (* AddrCallback)(struct __I2C_HandleTypeDef *hi2c, uint8_t TransferDirection, uint16_t AddrMatchCode); /*!< I2C Slave Address Match callback */ - - void (* MspInitCallback)(struct __I2C_HandleTypeDef *hi2c); /*!< I2C Msp Init callback */ - void (* MspDeInitCallback)(struct __I2C_HandleTypeDef *hi2c); /*!< I2C Msp DeInit callback */ - -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ -} I2C_HandleTypeDef; - -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) -/** - * @brief HAL I2C Callback ID enumeration definition - */ -typedef enum -{ - HAL_I2C_MASTER_TX_COMPLETE_CB_ID = 0x00U, /*!< I2C Master Tx Transfer completed callback ID */ - HAL_I2C_MASTER_RX_COMPLETE_CB_ID = 0x01U, /*!< I2C Master Rx Transfer completed callback ID */ - HAL_I2C_SLAVE_TX_COMPLETE_CB_ID = 0x02U, /*!< I2C Slave Tx Transfer completed callback ID */ - HAL_I2C_SLAVE_RX_COMPLETE_CB_ID = 0x03U, /*!< I2C Slave Rx Transfer completed callback ID */ - HAL_I2C_LISTEN_COMPLETE_CB_ID = 0x04U, /*!< I2C Listen Complete callback ID */ - HAL_I2C_MEM_TX_COMPLETE_CB_ID = 0x05U, /*!< I2C Memory Tx Transfer callback ID */ - HAL_I2C_MEM_RX_COMPLETE_CB_ID = 0x06U, /*!< I2C Memory Rx Transfer completed callback ID */ - HAL_I2C_ERROR_CB_ID = 0x07U, /*!< I2C Error callback ID */ - HAL_I2C_ABORT_CB_ID = 0x08U, /*!< I2C Abort callback ID */ - - HAL_I2C_MSPINIT_CB_ID = 0x09U, /*!< I2C Msp Init callback ID */ - HAL_I2C_MSPDEINIT_CB_ID = 0x0AU /*!< I2C Msp DeInit callback ID */ - -} HAL_I2C_CallbackIDTypeDef; - -/** - * @brief HAL I2C Callback pointer definition - */ -typedef void (*pI2C_CallbackTypeDef)(I2C_HandleTypeDef *hi2c); /*!< pointer to an I2C callback function */ -typedef void (*pI2C_AddrCallbackTypeDef)(I2C_HandleTypeDef *hi2c, uint8_t TransferDirection, uint16_t AddrMatchCode); /*!< pointer to an I2C Address Match callback function */ - -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** - * @} - */ -/* Exported constants --------------------------------------------------------*/ - -/** @defgroup I2C_Exported_Constants I2C Exported Constants - * @{ - */ - -/** @defgroup I2C_duty_cycle_in_fast_mode I2C duty cycle in fast mode - * @{ - */ -#define I2C_DUTYCYCLE_2 0x00000000U -#define I2C_DUTYCYCLE_16_9 I2C_CCR_DUTY -/** - * @} - */ - -/** @defgroup I2C_addressing_mode I2C addressing mode - * @{ - */ -#define I2C_ADDRESSINGMODE_7BIT 0x00004000U -#define I2C_ADDRESSINGMODE_10BIT (I2C_OAR1_ADDMODE | 0x00004000U) -/** - * @} - */ - -/** @defgroup I2C_dual_addressing_mode I2C dual addressing mode - * @{ - */ -#define I2C_DUALADDRESS_DISABLE 0x00000000U -#define I2C_DUALADDRESS_ENABLE I2C_OAR2_ENDUAL -/** - * @} - */ - -/** @defgroup I2C_general_call_addressing_mode I2C general call addressing mode - * @{ - */ -#define I2C_GENERALCALL_DISABLE 0x00000000U -#define I2C_GENERALCALL_ENABLE I2C_CR1_ENGC -/** - * @} - */ - -/** @defgroup I2C_nostretch_mode I2C nostretch mode - * @{ - */ -#define I2C_NOSTRETCH_DISABLE 0x00000000U -#define I2C_NOSTRETCH_ENABLE I2C_CR1_NOSTRETCH -/** - * @} - */ - -/** @defgroup I2C_Memory_Address_Size I2C Memory Address Size - * @{ - */ -#define I2C_MEMADD_SIZE_8BIT 0x00000001U -#define I2C_MEMADD_SIZE_16BIT 0x00000010U -/** - * @} - */ - -/** @defgroup I2C_XferDirection_definition I2C XferDirection definition - * @{ - */ -#define I2C_DIRECTION_RECEIVE 0x00000000U -#define I2C_DIRECTION_TRANSMIT 0x00000001U -/** - * @} - */ - -/** @defgroup I2C_XferOptions_definition I2C XferOptions definition - * @{ - */ -#define I2C_FIRST_FRAME 0x00000001U -#define I2C_FIRST_AND_NEXT_FRAME 0x00000002U -#define I2C_NEXT_FRAME 0x00000004U -#define I2C_FIRST_AND_LAST_FRAME 0x00000008U -#define I2C_LAST_FRAME_NO_STOP 0x00000010U -#define I2C_LAST_FRAME 0x00000020U - -/* List of XferOptions in usage of : - * 1- Restart condition in all use cases (direction change or not) - */ -#define I2C_OTHER_FRAME (0x00AA0000U) -#define I2C_OTHER_AND_LAST_FRAME (0xAA000000U) -/** - * @} - */ - -/** @defgroup I2C_Interrupt_configuration_definition I2C Interrupt configuration definition - * @brief I2C Interrupt definition - * Elements values convention: 0xXXXXXXXX - * - XXXXXXXX : Interrupt control mask - * @{ - */ -#define I2C_IT_BUF I2C_CR2_ITBUFEN -#define I2C_IT_EVT I2C_CR2_ITEVTEN -#define I2C_IT_ERR I2C_CR2_ITERREN -/** - * @} - */ - -/** @defgroup I2C_Flag_definition I2C Flag definition - * @{ - */ - -#define I2C_FLAG_OVR 0x00010800U -#define I2C_FLAG_AF 0x00010400U -#define I2C_FLAG_ARLO 0x00010200U -#define I2C_FLAG_BERR 0x00010100U -#define I2C_FLAG_TXE 0x00010080U -#define I2C_FLAG_RXNE 0x00010040U -#define I2C_FLAG_STOPF 0x00010010U -#define I2C_FLAG_ADD10 0x00010008U -#define I2C_FLAG_BTF 0x00010004U -#define I2C_FLAG_ADDR 0x00010002U -#define I2C_FLAG_SB 0x00010001U -#define I2C_FLAG_DUALF 0x00100080U -#define I2C_FLAG_GENCALL 0x00100010U -#define I2C_FLAG_TRA 0x00100004U -#define I2C_FLAG_BUSY 0x00100002U -#define I2C_FLAG_MSL 0x00100001U -/** - * @} - */ - -/** - * @} - */ - -/* Exported macros -----------------------------------------------------------*/ - -/** @defgroup I2C_Exported_Macros I2C Exported Macros - * @{ - */ - -/** @brief Reset I2C handle state. - * @param __HANDLE__ specifies the I2C Handle. - * @retval None - */ -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) -#define __HAL_I2C_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->State = HAL_I2C_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_I2C_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_I2C_STATE_RESET) -#endif - -/** @brief Enable or disable the specified I2C interrupts. - * @param __HANDLE__ specifies the I2C Handle. - * @param __INTERRUPT__ specifies the interrupt source to enable or disable. - * This parameter can be one of the following values: - * @arg I2C_IT_BUF: Buffer interrupt enable - * @arg I2C_IT_EVT: Event interrupt enable - * @arg I2C_IT_ERR: Error interrupt enable - * @retval None - */ -#define __HAL_I2C_ENABLE_IT(__HANDLE__, __INTERRUPT__) SET_BIT((__HANDLE__)->Instance->CR2,(__INTERRUPT__)) -#define __HAL_I2C_DISABLE_IT(__HANDLE__, __INTERRUPT__) CLEAR_BIT((__HANDLE__)->Instance->CR2, (__INTERRUPT__)) - -/** @brief Checks if the specified I2C interrupt source is enabled or disabled. - * @param __HANDLE__ specifies the I2C Handle. - * @param __INTERRUPT__ specifies the I2C interrupt source to check. - * This parameter can be one of the following values: - * @arg I2C_IT_BUF: Buffer interrupt enable - * @arg I2C_IT_EVT: Event interrupt enable - * @arg I2C_IT_ERR: Error interrupt enable - * @retval The new state of __INTERRUPT__ (TRUE or FALSE). - */ -#define __HAL_I2C_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((((__HANDLE__)->Instance->CR2 & (__INTERRUPT__)) == (__INTERRUPT__)) ? SET : RESET) - -/** @brief Checks whether the specified I2C flag is set or not. - * @param __HANDLE__ specifies the I2C Handle. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg I2C_FLAG_OVR: Overrun/Underrun flag - * @arg I2C_FLAG_AF: Acknowledge failure flag - * @arg I2C_FLAG_ARLO: Arbitration lost flag - * @arg I2C_FLAG_BERR: Bus error flag - * @arg I2C_FLAG_TXE: Data register empty flag - * @arg I2C_FLAG_RXNE: Data register not empty flag - * @arg I2C_FLAG_STOPF: Stop detection flag - * @arg I2C_FLAG_ADD10: 10-bit header sent flag - * @arg I2C_FLAG_BTF: Byte transfer finished flag - * @arg I2C_FLAG_ADDR: Address sent flag - * Address matched flag - * @arg I2C_FLAG_SB: Start bit flag - * @arg I2C_FLAG_DUALF: Dual flag - * @arg I2C_FLAG_GENCALL: General call header flag - * @arg I2C_FLAG_TRA: Transmitter/Receiver flag - * @arg I2C_FLAG_BUSY: Bus busy flag - * @arg I2C_FLAG_MSL: Master/Slave flag - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_I2C_GET_FLAG(__HANDLE__, __FLAG__) ((((uint8_t)((__FLAG__) >> 16U)) == 0x01U) ? \ - (((((__HANDLE__)->Instance->SR1) & ((__FLAG__) & I2C_FLAG_MASK)) == ((__FLAG__) & I2C_FLAG_MASK)) ? SET : RESET) : \ - (((((__HANDLE__)->Instance->SR2) & ((__FLAG__) & I2C_FLAG_MASK)) == ((__FLAG__) & I2C_FLAG_MASK)) ? SET : RESET)) - -/** @brief Clears the I2C pending flags which are cleared by writing 0 in a specific bit. - * @param __HANDLE__ specifies the I2C Handle. - * @param __FLAG__ specifies the flag to clear. - * This parameter can be any combination of the following values: - * @arg I2C_FLAG_OVR: Overrun/Underrun flag (Slave mode) - * @arg I2C_FLAG_AF: Acknowledge failure flag - * @arg I2C_FLAG_ARLO: Arbitration lost flag (Master mode) - * @arg I2C_FLAG_BERR: Bus error flag - * @retval None - */ -#define __HAL_I2C_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->SR1 = ~((__FLAG__) & I2C_FLAG_MASK)) - -/** @brief Clears the I2C ADDR pending flag. - * @param __HANDLE__ specifies the I2C Handle. - * This parameter can be I2C where x: 1, 2, or 3 to select the I2C peripheral. - * @retval None - */ -#define __HAL_I2C_CLEAR_ADDRFLAG(__HANDLE__) \ - do{ \ - __IO uint32_t tmpreg = 0x00U; \ - tmpreg = (__HANDLE__)->Instance->SR1; \ - tmpreg = (__HANDLE__)->Instance->SR2; \ - UNUSED(tmpreg); \ - } while(0) - -/** @brief Clears the I2C STOPF pending flag. - * @param __HANDLE__ specifies the I2C Handle. - * @retval None - */ -#define __HAL_I2C_CLEAR_STOPFLAG(__HANDLE__) \ - do{ \ - __IO uint32_t tmpreg = 0x00U; \ - tmpreg = (__HANDLE__)->Instance->SR1; \ - SET_BIT((__HANDLE__)->Instance->CR1, I2C_CR1_PE); \ - UNUSED(tmpreg); \ - } while(0) - -/** @brief Enable the specified I2C peripheral. - * @param __HANDLE__ specifies the I2C Handle. - * @retval None - */ -#define __HAL_I2C_ENABLE(__HANDLE__) SET_BIT((__HANDLE__)->Instance->CR1, I2C_CR1_PE) - -/** @brief Disable the specified I2C peripheral. - * @param __HANDLE__ specifies the I2C Handle. - * @retval None - */ -#define __HAL_I2C_DISABLE(__HANDLE__) CLEAR_BIT((__HANDLE__)->Instance->CR1, I2C_CR1_PE) - -/** - * @} - */ - -/* Include I2C HAL Extension module */ -#include "stm32f4xx_hal_i2c_ex.h" - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup I2C_Exported_Functions - * @{ - */ - -/** @addtogroup I2C_Exported_Functions_Group1 Initialization and de-initialization functions - * @{ - */ -/* Initialization and de-initialization functions******************************/ -HAL_StatusTypeDef HAL_I2C_Init(I2C_HandleTypeDef *hi2c); -HAL_StatusTypeDef HAL_I2C_DeInit(I2C_HandleTypeDef *hi2c); -void HAL_I2C_MspInit(I2C_HandleTypeDef *hi2c); -void HAL_I2C_MspDeInit(I2C_HandleTypeDef *hi2c); - -/* Callbacks Register/UnRegister functions ***********************************/ -#if (USE_HAL_I2C_REGISTER_CALLBACKS == 1) -HAL_StatusTypeDef HAL_I2C_RegisterCallback(I2C_HandleTypeDef *hi2c, HAL_I2C_CallbackIDTypeDef CallbackID, pI2C_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_I2C_UnRegisterCallback(I2C_HandleTypeDef *hi2c, HAL_I2C_CallbackIDTypeDef CallbackID); - -HAL_StatusTypeDef HAL_I2C_RegisterAddrCallback(I2C_HandleTypeDef *hi2c, pI2C_AddrCallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_I2C_UnRegisterAddrCallback(I2C_HandleTypeDef *hi2c); -#endif /* USE_HAL_I2C_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @addtogroup I2C_Exported_Functions_Group2 Input and Output operation functions - * @{ - */ -/* IO operation functions ****************************************************/ -/******* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_I2C_Master_Transmit(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_I2C_Master_Receive(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_I2C_Slave_Transmit(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_I2C_Slave_Receive(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_I2C_Mem_Write(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_I2C_Mem_Read(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_I2C_IsDeviceReady(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint32_t Trials, uint32_t Timeout); - -/******* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_I2C_Master_Transmit_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_I2C_Master_Receive_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_I2C_Slave_Transmit_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_I2C_Slave_Receive_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_I2C_Mem_Write_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_I2C_Mem_Read_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size); - -HAL_StatusTypeDef HAL_I2C_Master_Seq_Transmit_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions); -HAL_StatusTypeDef HAL_I2C_Master_Seq_Receive_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions); -HAL_StatusTypeDef HAL_I2C_Slave_Seq_Transmit_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t XferOptions); -HAL_StatusTypeDef HAL_I2C_Slave_Seq_Receive_IT(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t XferOptions); -HAL_StatusTypeDef HAL_I2C_EnableListen_IT(I2C_HandleTypeDef *hi2c); -HAL_StatusTypeDef HAL_I2C_DisableListen_IT(I2C_HandleTypeDef *hi2c); -HAL_StatusTypeDef HAL_I2C_Master_Abort_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress); - -/******* Non-Blocking mode: DMA */ -HAL_StatusTypeDef HAL_I2C_Master_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_I2C_Master_Receive_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_I2C_Slave_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_I2C_Slave_Receive_DMA(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_I2C_Mem_Write_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_I2C_Mem_Read_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size); - -HAL_StatusTypeDef HAL_I2C_Master_Seq_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions); -HAL_StatusTypeDef HAL_I2C_Master_Seq_Receive_DMA(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions); -HAL_StatusTypeDef HAL_I2C_Slave_Seq_Transmit_DMA(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t XferOptions); -HAL_StatusTypeDef HAL_I2C_Slave_Seq_Receive_DMA(I2C_HandleTypeDef *hi2c, uint8_t *pData, uint16_t Size, uint32_t XferOptions); -/** - * @} - */ - -/** @addtogroup I2C_IRQ_Handler_and_Callbacks IRQ Handler and Callbacks - * @{ - */ -/******* I2C IRQHandler and Callbacks used in non blocking modes (Interrupt and DMA) */ -void HAL_I2C_EV_IRQHandler(I2C_HandleTypeDef *hi2c); -void HAL_I2C_ER_IRQHandler(I2C_HandleTypeDef *hi2c); -void HAL_I2C_MasterTxCpltCallback(I2C_HandleTypeDef *hi2c); -void HAL_I2C_MasterRxCpltCallback(I2C_HandleTypeDef *hi2c); -void HAL_I2C_SlaveTxCpltCallback(I2C_HandleTypeDef *hi2c); -void HAL_I2C_SlaveRxCpltCallback(I2C_HandleTypeDef *hi2c); -void HAL_I2C_AddrCallback(I2C_HandleTypeDef *hi2c, uint8_t TransferDirection, uint16_t AddrMatchCode); -void HAL_I2C_ListenCpltCallback(I2C_HandleTypeDef *hi2c); -void HAL_I2C_MemTxCpltCallback(I2C_HandleTypeDef *hi2c); -void HAL_I2C_MemRxCpltCallback(I2C_HandleTypeDef *hi2c); -void HAL_I2C_ErrorCallback(I2C_HandleTypeDef *hi2c); -void HAL_I2C_AbortCpltCallback(I2C_HandleTypeDef *hi2c); -/** - * @} - */ - -/** @addtogroup I2C_Exported_Functions_Group3 Peripheral State, Mode and Error functions - * @{ - */ -/* Peripheral State, Mode and Error functions *********************************/ -HAL_I2C_StateTypeDef HAL_I2C_GetState(I2C_HandleTypeDef *hi2c); -HAL_I2C_ModeTypeDef HAL_I2C_GetMode(I2C_HandleTypeDef *hi2c); -uint32_t HAL_I2C_GetError(I2C_HandleTypeDef *hi2c); - -/** - * @} - */ - -/** - * @} - */ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup I2C_Private_Constants I2C Private Constants - * @{ - */ -#define I2C_FLAG_MASK 0x0000FFFFU -#define I2C_MIN_PCLK_FREQ_STANDARD 2000000U /*!< 2 MHz */ -#define I2C_MIN_PCLK_FREQ_FAST 4000000U /*!< 4 MHz */ -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup I2C_Private_Macros I2C Private Macros - * @{ - */ - -#define I2C_MIN_PCLK_FREQ(__PCLK__, __SPEED__) (((__SPEED__) <= 100000U) ? ((__PCLK__) < I2C_MIN_PCLK_FREQ_STANDARD) : ((__PCLK__) < I2C_MIN_PCLK_FREQ_FAST)) -#define I2C_CCR_CALCULATION(__PCLK__, __SPEED__, __COEFF__) (((((__PCLK__) - 1U)/((__SPEED__) * (__COEFF__))) + 1U) & I2C_CCR_CCR) -#define I2C_FREQRANGE(__PCLK__) ((__PCLK__)/1000000U) -#define I2C_RISE_TIME(__FREQRANGE__, __SPEED__) (((__SPEED__) <= 100000U) ? ((__FREQRANGE__) + 1U) : ((((__FREQRANGE__) * 300U) / 1000U) + 1U)) -#define I2C_SPEED_STANDARD(__PCLK__, __SPEED__) ((I2C_CCR_CALCULATION((__PCLK__), (__SPEED__), 2U) < 4U)? 4U:I2C_CCR_CALCULATION((__PCLK__), (__SPEED__), 2U)) -#define I2C_SPEED_FAST(__PCLK__, __SPEED__, __DUTYCYCLE__) (((__DUTYCYCLE__) == I2C_DUTYCYCLE_2)? I2C_CCR_CALCULATION((__PCLK__), (__SPEED__), 3U) : (I2C_CCR_CALCULATION((__PCLK__), (__SPEED__), 25U) | I2C_DUTYCYCLE_16_9)) -#define I2C_SPEED(__PCLK__, __SPEED__, __DUTYCYCLE__) (((__SPEED__) <= 100000U)? (I2C_SPEED_STANDARD((__PCLK__), (__SPEED__))) : \ - ((I2C_SPEED_FAST((__PCLK__), (__SPEED__), (__DUTYCYCLE__)) & I2C_CCR_CCR) == 0U)? 1U : \ - ((I2C_SPEED_FAST((__PCLK__), (__SPEED__), (__DUTYCYCLE__))) | I2C_CCR_FS)) - -#define I2C_7BIT_ADD_WRITE(__ADDRESS__) ((uint8_t)((__ADDRESS__) & (uint8_t)(~I2C_OAR1_ADD0))) -#define I2C_7BIT_ADD_READ(__ADDRESS__) ((uint8_t)((__ADDRESS__) | I2C_OAR1_ADD0)) - -#define I2C_10BIT_ADDRESS(__ADDRESS__) ((uint8_t)((uint16_t)((__ADDRESS__) & (uint16_t)0x00FF))) -#define I2C_10BIT_HEADER_WRITE(__ADDRESS__) ((uint8_t)((uint16_t)((uint16_t)(((uint16_t)((__ADDRESS__) & (uint16_t)0x0300)) >> 7) | (uint16_t)0x00F0))) -#define I2C_10BIT_HEADER_READ(__ADDRESS__) ((uint8_t)((uint16_t)((uint16_t)(((uint16_t)((__ADDRESS__) & (uint16_t)0x0300)) >> 7) | (uint16_t)(0x00F1)))) - -#define I2C_MEM_ADD_MSB(__ADDRESS__) ((uint8_t)((uint16_t)(((uint16_t)((__ADDRESS__) & (uint16_t)0xFF00)) >> 8))) -#define I2C_MEM_ADD_LSB(__ADDRESS__) ((uint8_t)((uint16_t)((__ADDRESS__) & (uint16_t)0x00FF))) - -/** @defgroup I2C_IS_RTC_Definitions I2C Private macros to check input parameters - * @{ - */ -#define IS_I2C_DUTY_CYCLE(CYCLE) (((CYCLE) == I2C_DUTYCYCLE_2) || \ - ((CYCLE) == I2C_DUTYCYCLE_16_9)) -#define IS_I2C_ADDRESSING_MODE(ADDRESS) (((ADDRESS) == I2C_ADDRESSINGMODE_7BIT) || \ - ((ADDRESS) == I2C_ADDRESSINGMODE_10BIT)) -#define IS_I2C_DUAL_ADDRESS(ADDRESS) (((ADDRESS) == I2C_DUALADDRESS_DISABLE) || \ - ((ADDRESS) == I2C_DUALADDRESS_ENABLE)) -#define IS_I2C_GENERAL_CALL(CALL) (((CALL) == I2C_GENERALCALL_DISABLE) || \ - ((CALL) == I2C_GENERALCALL_ENABLE)) -#define IS_I2C_NO_STRETCH(STRETCH) (((STRETCH) == I2C_NOSTRETCH_DISABLE) || \ - ((STRETCH) == I2C_NOSTRETCH_ENABLE)) -#define IS_I2C_MEMADD_SIZE(SIZE) (((SIZE) == I2C_MEMADD_SIZE_8BIT) || \ - ((SIZE) == I2C_MEMADD_SIZE_16BIT)) -#define IS_I2C_CLOCK_SPEED(SPEED) (((SPEED) > 0U) && ((SPEED) <= 400000U)) -#define IS_I2C_OWN_ADDRESS1(ADDRESS1) (((ADDRESS1) & 0xFFFFFC00U) == 0U) -#define IS_I2C_OWN_ADDRESS2(ADDRESS2) (((ADDRESS2) & 0xFFFFFF01U) == 0U) -#define IS_I2C_TRANSFER_OPTIONS_REQUEST(REQUEST) (((REQUEST) == I2C_FIRST_FRAME) || \ - ((REQUEST) == I2C_FIRST_AND_NEXT_FRAME) || \ - ((REQUEST) == I2C_NEXT_FRAME) || \ - ((REQUEST) == I2C_FIRST_AND_LAST_FRAME) || \ - ((REQUEST) == I2C_LAST_FRAME) || \ - ((REQUEST) == I2C_LAST_FRAME_NO_STOP) || \ - IS_I2C_TRANSFER_OTHER_OPTIONS_REQUEST(REQUEST)) - -#define IS_I2C_TRANSFER_OTHER_OPTIONS_REQUEST(REQUEST) (((REQUEST) == I2C_OTHER_FRAME) || \ - ((REQUEST) == I2C_OTHER_AND_LAST_FRAME)) - -#define I2C_CHECK_FLAG(__ISR__, __FLAG__) ((((__ISR__) & ((__FLAG__) & I2C_FLAG_MASK)) == ((__FLAG__) & I2C_FLAG_MASK)) ? SET : RESET) -#define I2C_CHECK_IT_SOURCE(__CR1__, __IT__) ((((__CR1__) & (__IT__)) == (__IT__)) ? SET : RESET) -/** - * @} - */ - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup I2C_Private_Functions I2C Private Functions - * @{ - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - - -#endif /* __STM32F4xx_HAL_I2C_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2c_ex.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2c_ex.h deleted file mode 100644 index 6864d83..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2c_ex.h +++ /dev/null @@ -1,117 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_i2c_ex.h - * @author MCD Application Team - * @brief Header file of I2C HAL Extension module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_I2C_EX_H -#define __STM32F4xx_HAL_I2C_EX_H - -#ifdef __cplusplus -extern "C" { -#endif - -#if defined(I2C_FLTR_ANOFF)&&defined(I2C_FLTR_DNF) -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup I2CEx - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/** @defgroup I2CEx_Exported_Constants I2C Exported Constants - * @{ - */ - -/** @defgroup I2CEx_Analog_Filter I2C Analog Filter - * @{ - */ -#define I2C_ANALOGFILTER_ENABLE 0x00000000U -#define I2C_ANALOGFILTER_DISABLE I2C_FLTR_ANOFF -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup I2CEx_Exported_Functions - * @{ - */ - -/** @addtogroup I2CEx_Exported_Functions_Group1 - * @{ - */ -/* Peripheral Control functions ************************************************/ -HAL_StatusTypeDef HAL_I2CEx_ConfigAnalogFilter(I2C_HandleTypeDef *hi2c, uint32_t AnalogFilter); -HAL_StatusTypeDef HAL_I2CEx_ConfigDigitalFilter(I2C_HandleTypeDef *hi2c, uint32_t DigitalFilter); -/** - * @} - */ - -/** - * @} - */ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup I2CEx_Private_Constants I2C Private Constants - * @{ - */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup I2CEx_Private_Macros I2C Private Macros - * @{ - */ -#define IS_I2C_ANALOG_FILTER(FILTER) (((FILTER) == I2C_ANALOGFILTER_ENABLE) || \ - ((FILTER) == I2C_ANALOGFILTER_DISABLE)) -#define IS_I2C_DIGITAL_FILTER(FILTER) ((FILTER) <= 0x0000000FU) -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_I2C_EX_H */ - - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2s.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2s.h deleted file mode 100644 index 1e9676f..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2s.h +++ /dev/null @@ -1,620 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_i2s.h - * @author MCD Application Team - * @brief Header file of I2S HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_I2S_H -#define STM32F4xx_HAL_I2S_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup I2S - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup I2S_Exported_Types I2S Exported Types - * @{ - */ - -/** - * @brief I2S Init structure definition - */ -typedef struct -{ - uint32_t Mode; /*!< Specifies the I2S operating mode. - This parameter can be a value of @ref I2S_Mode */ - - uint32_t Standard; /*!< Specifies the standard used for the I2S communication. - This parameter can be a value of @ref I2S_Standard */ - - uint32_t DataFormat; /*!< Specifies the data format for the I2S communication. - This parameter can be a value of @ref I2S_Data_Format */ - - uint32_t MCLKOutput; /*!< Specifies whether the I2S MCLK output is enabled or not. - This parameter can be a value of @ref I2S_MCLK_Output */ - - uint32_t AudioFreq; /*!< Specifies the frequency selected for the I2S communication. - This parameter can be a value of @ref I2S_Audio_Frequency */ - - uint32_t CPOL; /*!< Specifies the idle state of the I2S clock. - This parameter can be a value of @ref I2S_Clock_Polarity */ - - uint32_t ClockSource; /*!< Specifies the I2S Clock Source. - This parameter can be a value of @ref I2S_Clock_Source */ - uint32_t FullDuplexMode; /*!< Specifies the I2S FullDuplex mode. - This parameter can be a value of @ref I2S_FullDuplex_Mode */ -} I2S_InitTypeDef; - -/** - * @brief HAL State structures definition - */ -typedef enum -{ - HAL_I2S_STATE_RESET = 0x00U, /*!< I2S not yet initialized or disabled */ - HAL_I2S_STATE_READY = 0x01U, /*!< I2S initialized and ready for use */ - HAL_I2S_STATE_BUSY = 0x02U, /*!< I2S internal process is ongoing */ - HAL_I2S_STATE_BUSY_TX = 0x03U, /*!< Data Transmission process is ongoing */ - HAL_I2S_STATE_BUSY_RX = 0x04U, /*!< Data Reception process is ongoing */ - HAL_I2S_STATE_BUSY_TX_RX = 0x05U, /*!< Data Transmission and Reception process is ongoing */ - HAL_I2S_STATE_TIMEOUT = 0x06U, /*!< I2S timeout state */ - HAL_I2S_STATE_ERROR = 0x07U /*!< I2S error state */ -} HAL_I2S_StateTypeDef; - -/** - * @brief I2S handle Structure definition - */ -typedef struct __I2S_HandleTypeDef -{ - SPI_TypeDef *Instance; /*!< I2S registers base address */ - - I2S_InitTypeDef Init; /*!< I2S communication parameters */ - - uint16_t *pTxBuffPtr; /*!< Pointer to I2S Tx transfer buffer */ - - __IO uint16_t TxXferSize; /*!< I2S Tx transfer size */ - - __IO uint16_t TxXferCount; /*!< I2S Tx transfer Counter */ - - uint16_t *pRxBuffPtr; /*!< Pointer to I2S Rx transfer buffer */ - - __IO uint16_t RxXferSize; /*!< I2S Rx transfer size */ - - __IO uint16_t RxXferCount; /*!< I2S Rx transfer counter - (This field is initialized at the - same value as transfer size at the - beginning of the transfer and - decremented when a sample is received - NbSamplesReceived = RxBufferSize-RxBufferCount) */ - void (*IrqHandlerISR)(struct __I2S_HandleTypeDef *hi2s); /*!< I2S function pointer on IrqHandler */ - - DMA_HandleTypeDef *hdmatx; /*!< I2S Tx DMA handle parameters */ - - DMA_HandleTypeDef *hdmarx; /*!< I2S Rx DMA handle parameters */ - - __IO HAL_LockTypeDef Lock; /*!< I2S locking object */ - - __IO HAL_I2S_StateTypeDef State; /*!< I2S communication state */ - - __IO uint32_t ErrorCode; /*!< I2S Error code - This parameter can be a value of @ref I2S_Error */ - -#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) - void (* TxCpltCallback)(struct __I2S_HandleTypeDef *hi2s); /*!< I2S Tx Completed callback */ - void (* RxCpltCallback)(struct __I2S_HandleTypeDef *hi2s); /*!< I2S Rx Completed callback */ - void (* TxRxCpltCallback)(struct __I2S_HandleTypeDef *hi2s); /*!< I2S TxRx Completed callback */ - void (* TxHalfCpltCallback)(struct __I2S_HandleTypeDef *hi2s); /*!< I2S Tx Half Completed callback */ - void (* RxHalfCpltCallback)(struct __I2S_HandleTypeDef *hi2s); /*!< I2S Rx Half Completed callback */ - void (* TxRxHalfCpltCallback)(struct __I2S_HandleTypeDef *hi2s); /*!< I2S TxRx Half Completed callback */ - void (* ErrorCallback)(struct __I2S_HandleTypeDef *hi2s); /*!< I2S Error callback */ - void (* MspInitCallback)(struct __I2S_HandleTypeDef *hi2s); /*!< I2S Msp Init callback */ - void (* MspDeInitCallback)(struct __I2S_HandleTypeDef *hi2s); /*!< I2S Msp DeInit callback */ - -#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ -} I2S_HandleTypeDef; - -#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) -/** - * @brief HAL I2S Callback ID enumeration definition - */ -typedef enum -{ - HAL_I2S_TX_COMPLETE_CB_ID = 0x00U, /*!< I2S Tx Completed callback ID */ - HAL_I2S_RX_COMPLETE_CB_ID = 0x01U, /*!< I2S Rx Completed callback ID */ - HAL_I2S_TX_RX_COMPLETE_CB_ID = 0x02U, /*!< I2S TxRx Completed callback ID */ - HAL_I2S_TX_HALF_COMPLETE_CB_ID = 0x03U, /*!< I2S Tx Half Completed callback ID */ - HAL_I2S_RX_HALF_COMPLETE_CB_ID = 0x04U, /*!< I2S Rx Half Completed callback ID */ - HAL_I2S_TX_RX_HALF_COMPLETE_CB_ID = 0x05U, /*!< I2S TxRx Half Completed callback ID */ - HAL_I2S_ERROR_CB_ID = 0x06U, /*!< I2S Error callback ID */ - HAL_I2S_MSPINIT_CB_ID = 0x07U, /*!< I2S Msp Init callback ID */ - HAL_I2S_MSPDEINIT_CB_ID = 0x08U /*!< I2S Msp DeInit callback ID */ - -} HAL_I2S_CallbackIDTypeDef; - -/** - * @brief HAL I2S Callback pointer definition - */ -typedef void (*pI2S_CallbackTypeDef)(I2S_HandleTypeDef *hi2s); /*!< pointer to an I2S callback function */ - -#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup I2S_Exported_Constants I2S Exported Constants - * @{ - */ -/** @defgroup I2S_Error I2S Error - * @{ - */ -#define HAL_I2S_ERROR_NONE (0x00000000U) /*!< No error */ -#define HAL_I2S_ERROR_TIMEOUT (0x00000001U) /*!< Timeout error */ -#define HAL_I2S_ERROR_OVR (0x00000002U) /*!< OVR error */ -#define HAL_I2S_ERROR_UDR (0x00000004U) /*!< UDR error */ -#define HAL_I2S_ERROR_DMA (0x00000008U) /*!< DMA transfer error */ -#define HAL_I2S_ERROR_PRESCALER (0x00000010U) /*!< Prescaler Calculation error */ -#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) -#define HAL_I2S_ERROR_INVALID_CALLBACK (0x00000020U) /*!< Invalid Callback error */ -#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ -#define HAL_I2S_ERROR_BUSY_LINE_RX (0x00000040U) /*!< Busy Rx Line error */ -/** - * @} - */ - -/** @defgroup I2S_Mode I2S Mode - * @{ - */ -#define I2S_MODE_SLAVE_TX (0x00000000U) -#define I2S_MODE_SLAVE_RX (SPI_I2SCFGR_I2SCFG_0) -#define I2S_MODE_MASTER_TX (SPI_I2SCFGR_I2SCFG_1) -#define I2S_MODE_MASTER_RX ((SPI_I2SCFGR_I2SCFG_0 | SPI_I2SCFGR_I2SCFG_1)) -/** - * @} - */ - -/** @defgroup I2S_Standard I2S Standard - * @{ - */ -#define I2S_STANDARD_PHILIPS (0x00000000U) -#define I2S_STANDARD_MSB (SPI_I2SCFGR_I2SSTD_0) -#define I2S_STANDARD_LSB (SPI_I2SCFGR_I2SSTD_1) -#define I2S_STANDARD_PCM_SHORT ((SPI_I2SCFGR_I2SSTD_0 | SPI_I2SCFGR_I2SSTD_1)) -#define I2S_STANDARD_PCM_LONG ((SPI_I2SCFGR_I2SSTD_0 | SPI_I2SCFGR_I2SSTD_1 | SPI_I2SCFGR_PCMSYNC)) -/** - * @} - */ - -/** @defgroup I2S_Data_Format I2S Data Format - * @{ - */ -#define I2S_DATAFORMAT_16B (0x00000000U) -#define I2S_DATAFORMAT_16B_EXTENDED (SPI_I2SCFGR_CHLEN) -#define I2S_DATAFORMAT_24B ((SPI_I2SCFGR_CHLEN | SPI_I2SCFGR_DATLEN_0)) -#define I2S_DATAFORMAT_32B ((SPI_I2SCFGR_CHLEN | SPI_I2SCFGR_DATLEN_1)) -/** - * @} - */ - -/** @defgroup I2S_MCLK_Output I2S MCLK Output - * @{ - */ -#define I2S_MCLKOUTPUT_ENABLE (SPI_I2SPR_MCKOE) -#define I2S_MCLKOUTPUT_DISABLE (0x00000000U) -/** - * @} - */ - -/** @defgroup I2S_Audio_Frequency I2S Audio Frequency - * @{ - */ -#define I2S_AUDIOFREQ_192K (192000U) -#define I2S_AUDIOFREQ_96K (96000U) -#define I2S_AUDIOFREQ_48K (48000U) -#define I2S_AUDIOFREQ_44K (44100U) -#define I2S_AUDIOFREQ_32K (32000U) -#define I2S_AUDIOFREQ_22K (22050U) -#define I2S_AUDIOFREQ_16K (16000U) -#define I2S_AUDIOFREQ_11K (11025U) -#define I2S_AUDIOFREQ_8K (8000U) -#define I2S_AUDIOFREQ_DEFAULT (2U) -/** - * @} - */ - -/** @defgroup I2S_FullDuplex_Mode I2S FullDuplex Mode - * @{ - */ -#define I2S_FULLDUPLEXMODE_DISABLE (0x00000000U) -#define I2S_FULLDUPLEXMODE_ENABLE (0x00000001U) -/** - * @} - */ - -/** @defgroup I2S_Clock_Polarity I2S Clock Polarity - * @{ - */ -#define I2S_CPOL_LOW (0x00000000U) -#define I2S_CPOL_HIGH (SPI_I2SCFGR_CKPOL) -/** - * @} - */ - -/** @defgroup I2S_Interrupts_Definition I2S Interrupts Definition - * @{ - */ -#define I2S_IT_TXE SPI_CR2_TXEIE -#define I2S_IT_RXNE SPI_CR2_RXNEIE -#define I2S_IT_ERR SPI_CR2_ERRIE -/** - * @} - */ - -/** @defgroup I2S_Flags_Definition I2S Flags Definition - * @{ - */ -#define I2S_FLAG_TXE SPI_SR_TXE -#define I2S_FLAG_RXNE SPI_SR_RXNE - -#define I2S_FLAG_UDR SPI_SR_UDR -#define I2S_FLAG_OVR SPI_SR_OVR -#define I2S_FLAG_FRE SPI_SR_FRE - -#define I2S_FLAG_CHSIDE SPI_SR_CHSIDE -#define I2S_FLAG_BSY SPI_SR_BSY - -#define I2S_FLAG_MASK (SPI_SR_RXNE\ - | SPI_SR_TXE | SPI_SR_UDR | SPI_SR_OVR | SPI_SR_FRE | SPI_SR_CHSIDE | SPI_SR_BSY) -/** - * @} - */ - -/** @defgroup I2S_Clock_Source I2S Clock Source Definition - * @{ - */ -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F469xx) || defined(STM32F479xx) -#define I2S_CLOCK_PLL (0x00000000U) -#define I2S_CLOCK_EXTERNAL (0x00000001U) -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || - STM32F401xC || STM32F401xE || STM32F411xE || STM32F469xx || STM32F479xx */ - -#if defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -#define I2S_CLOCK_PLL (0x00000000U) -#define I2S_CLOCK_EXTERNAL (0x00000001U) -#define I2S_CLOCK_PLLR (0x00000002U) -#define I2S_CLOCK_PLLSRC (0x00000003U) -#endif /* STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -#define I2S_CLOCK_PLLSRC (0x00000000U) -#define I2S_CLOCK_EXTERNAL (0x00000001U) -#define I2S_CLOCK_PLLR (0x00000002U) -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macros -----------------------------------------------------------*/ -/** @defgroup I2S_Exported_macros I2S Exported Macros - * @{ - */ - -/** @brief Reset I2S handle state - * @param __HANDLE__ specifies the I2S Handle. - * @retval None - */ -#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) -#define __HAL_I2S_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->State = HAL_I2S_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_I2S_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_I2S_STATE_RESET) -#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ - -/** @brief Enable the specified SPI peripheral (in I2S mode). - * @param __HANDLE__ specifies the I2S Handle. - * @retval None - */ -#define __HAL_I2S_ENABLE(__HANDLE__) (SET_BIT((__HANDLE__)->Instance->I2SCFGR, SPI_I2SCFGR_I2SE)) - -/** @brief Disable the specified SPI peripheral (in I2S mode). - * @param __HANDLE__ specifies the I2S Handle. - * @retval None - */ -#define __HAL_I2S_DISABLE(__HANDLE__) (CLEAR_BIT((__HANDLE__)->Instance->I2SCFGR, SPI_I2SCFGR_I2SE)) - -/** @brief Enable the specified I2S interrupts. - * @param __HANDLE__ specifies the I2S Handle. - * @param __INTERRUPT__ specifies the interrupt source to enable or disable. - * This parameter can be one of the following values: - * @arg I2S_IT_TXE: Tx buffer empty interrupt enable - * @arg I2S_IT_RXNE: RX buffer not empty interrupt enable - * @arg I2S_IT_ERR: Error interrupt enable - * @retval None - */ -#define __HAL_I2S_ENABLE_IT(__HANDLE__, __INTERRUPT__) (SET_BIT((__HANDLE__)->Instance->CR2,(__INTERRUPT__))) - -/** @brief Disable the specified I2S interrupts. - * @param __HANDLE__ specifies the I2S Handle. - * @param __INTERRUPT__ specifies the interrupt source to enable or disable. - * This parameter can be one of the following values: - * @arg I2S_IT_TXE: Tx buffer empty interrupt enable - * @arg I2S_IT_RXNE: RX buffer not empty interrupt enable - * @arg I2S_IT_ERR: Error interrupt enable - * @retval None - */ -#define __HAL_I2S_DISABLE_IT(__HANDLE__, __INTERRUPT__) (CLEAR_BIT((__HANDLE__)->Instance->CR2,(__INTERRUPT__))) - -/** @brief Checks if the specified I2S interrupt source is enabled or disabled. - * @param __HANDLE__ specifies the I2S Handle. - * This parameter can be I2S where x: 1, 2, or 3 to select the I2S peripheral. - * @param __INTERRUPT__ specifies the I2S interrupt source to check. - * This parameter can be one of the following values: - * @arg I2S_IT_TXE: Tx buffer empty interrupt enable - * @arg I2S_IT_RXNE: RX buffer not empty interrupt enable - * @arg I2S_IT_ERR: Error interrupt enable - * @retval The new state of __IT__ (TRUE or FALSE). - */ -#define __HAL_I2S_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((((__HANDLE__)->Instance->CR2\ - & (__INTERRUPT__)) == (__INTERRUPT__)) ? SET : RESET) - -/** @brief Checks whether the specified I2S flag is set or not. - * @param __HANDLE__ specifies the I2S Handle. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg I2S_FLAG_RXNE: Receive buffer not empty flag - * @arg I2S_FLAG_TXE: Transmit buffer empty flag - * @arg I2S_FLAG_UDR: Underrun flag - * @arg I2S_FLAG_OVR: Overrun flag - * @arg I2S_FLAG_FRE: Frame error flag - * @arg I2S_FLAG_CHSIDE: Channel Side flag - * @arg I2S_FLAG_BSY: Busy flag - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_I2S_GET_FLAG(__HANDLE__, __FLAG__) ((((__HANDLE__)->Instance->SR) & (__FLAG__)) == (__FLAG__)) - -/** @brief Clears the I2S OVR pending flag. - * @param __HANDLE__ specifies the I2S Handle. - * @retval None - */ -#define __HAL_I2S_CLEAR_OVRFLAG(__HANDLE__) do{ \ - __IO uint32_t tmpreg_ovr = 0x00U; \ - tmpreg_ovr = (__HANDLE__)->Instance->DR; \ - tmpreg_ovr = (__HANDLE__)->Instance->SR; \ - UNUSED(tmpreg_ovr); \ - }while(0U) -/** @brief Clears the I2S UDR pending flag. - * @param __HANDLE__ specifies the I2S Handle. - * @retval None - */ -#define __HAL_I2S_CLEAR_UDRFLAG(__HANDLE__) do{\ - __IO uint32_t tmpreg_udr = 0x00U;\ - tmpreg_udr = ((__HANDLE__)->Instance->SR);\ - UNUSED(tmpreg_udr); \ - }while(0U) -/** @brief Flush the I2S DR Register. - * @param __HANDLE__ specifies the I2S Handle. - * @retval None - */ -#define __HAL_I2S_FLUSH_RX_DR(__HANDLE__) do{\ - __IO uint32_t tmpreg_dr = 0x00U;\ - tmpreg_dr = ((__HANDLE__)->Instance->DR);\ - UNUSED(tmpreg_dr); \ - }while(0U) -/** - * @} - */ - -/* Include I2S Extension module */ -#include "stm32f4xx_hal_i2s_ex.h" - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup I2S_Exported_Functions - * @{ - */ - -/** @addtogroup I2S_Exported_Functions_Group1 - * @{ - */ -/* Initialization/de-initialization functions ********************************/ -HAL_StatusTypeDef HAL_I2S_Init(I2S_HandleTypeDef *hi2s); -HAL_StatusTypeDef HAL_I2S_DeInit(I2S_HandleTypeDef *hi2s); -void HAL_I2S_MspInit(I2S_HandleTypeDef *hi2s); -void HAL_I2S_MspDeInit(I2S_HandleTypeDef *hi2s); - -/* Callbacks Register/UnRegister functions ***********************************/ -#if (USE_HAL_I2S_REGISTER_CALLBACKS == 1U) -HAL_StatusTypeDef HAL_I2S_RegisterCallback(I2S_HandleTypeDef *hi2s, HAL_I2S_CallbackIDTypeDef CallbackID, - pI2S_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_I2S_UnRegisterCallback(I2S_HandleTypeDef *hi2s, HAL_I2S_CallbackIDTypeDef CallbackID); -#endif /* USE_HAL_I2S_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @addtogroup I2S_Exported_Functions_Group2 - * @{ - */ -/* I/O operation functions ***************************************************/ -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_I2S_Transmit(I2S_HandleTypeDef *hi2s, uint16_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_I2S_Receive(I2S_HandleTypeDef *hi2s, uint16_t *pData, uint16_t Size, uint32_t Timeout); - -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_I2S_Transmit_IT(I2S_HandleTypeDef *hi2s, uint16_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_I2S_Receive_IT(I2S_HandleTypeDef *hi2s, uint16_t *pData, uint16_t Size); -void HAL_I2S_IRQHandler(I2S_HandleTypeDef *hi2s); - -/* Non-Blocking mode: DMA */ -HAL_StatusTypeDef HAL_I2S_Transmit_DMA(I2S_HandleTypeDef *hi2s, uint16_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_I2S_Receive_DMA(I2S_HandleTypeDef *hi2s, uint16_t *pData, uint16_t Size); - -HAL_StatusTypeDef HAL_I2S_DMAPause(I2S_HandleTypeDef *hi2s); -HAL_StatusTypeDef HAL_I2S_DMAResume(I2S_HandleTypeDef *hi2s); -HAL_StatusTypeDef HAL_I2S_DMAStop(I2S_HandleTypeDef *hi2s); - -/* Callbacks used in non blocking modes (Interrupt and DMA) *******************/ -void HAL_I2S_TxHalfCpltCallback(I2S_HandleTypeDef *hi2s); -void HAL_I2S_TxCpltCallback(I2S_HandleTypeDef *hi2s); -void HAL_I2S_RxHalfCpltCallback(I2S_HandleTypeDef *hi2s); -void HAL_I2S_RxCpltCallback(I2S_HandleTypeDef *hi2s); -void HAL_I2S_ErrorCallback(I2S_HandleTypeDef *hi2s); -/** - * @} - */ - -/** @addtogroup I2S_Exported_Functions_Group3 - * @{ - */ -/* Peripheral Control and State functions ************************************/ -HAL_I2S_StateTypeDef HAL_I2S_GetState(I2S_HandleTypeDef *hi2s); -uint32_t HAL_I2S_GetError(I2S_HandleTypeDef *hi2s); -/** - * @} - */ - -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/** @defgroup I2S_Private_Macros I2S Private Macros - * @{ - */ - -/** @brief Check whether the specified SPI flag is set or not. - * @param __SR__ copy of I2S SR register. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg I2S_FLAG_RXNE: Receive buffer not empty flag - * @arg I2S_FLAG_TXE: Transmit buffer empty flag - * @arg I2S_FLAG_UDR: Underrun error flag - * @arg I2S_FLAG_OVR: Overrun flag - * @arg I2S_FLAG_CHSIDE: Channel side flag - * @arg I2S_FLAG_BSY: Busy flag - * @retval SET or RESET. - */ -#define I2S_CHECK_FLAG(__SR__, __FLAG__) ((((__SR__)\ - & ((__FLAG__) & I2S_FLAG_MASK)) == ((__FLAG__) & I2S_FLAG_MASK)) ? SET : RESET) - -/** @brief Check whether the specified SPI Interrupt is set or not. - * @param __CR2__ copy of I2S CR2 register. - * @param __INTERRUPT__ specifies the SPI interrupt source to check. - * This parameter can be one of the following values: - * @arg I2S_IT_TXE: Tx buffer empty interrupt enable - * @arg I2S_IT_RXNE: RX buffer not empty interrupt enable - * @arg I2S_IT_ERR: Error interrupt enable - * @retval SET or RESET. - */ -#define I2S_CHECK_IT_SOURCE(__CR2__, __INTERRUPT__) ((((__CR2__)\ - & (__INTERRUPT__)) == (__INTERRUPT__)) ? SET : RESET) - -/** @brief Checks if I2S Mode parameter is in allowed range. - * @param __MODE__ specifies the I2S Mode. - * This parameter can be a value of @ref I2S_Mode - * @retval None - */ -#define IS_I2S_MODE(__MODE__) (((__MODE__) == I2S_MODE_SLAVE_TX) || \ - ((__MODE__) == I2S_MODE_SLAVE_RX) || \ - ((__MODE__) == I2S_MODE_MASTER_TX) || \ - ((__MODE__) == I2S_MODE_MASTER_RX)) - -#define IS_I2S_STANDARD(__STANDARD__) (((__STANDARD__) == I2S_STANDARD_PHILIPS) || \ - ((__STANDARD__) == I2S_STANDARD_MSB) || \ - ((__STANDARD__) == I2S_STANDARD_LSB) || \ - ((__STANDARD__) == I2S_STANDARD_PCM_SHORT) || \ - ((__STANDARD__) == I2S_STANDARD_PCM_LONG)) - -#define IS_I2S_DATA_FORMAT(__FORMAT__) (((__FORMAT__) == I2S_DATAFORMAT_16B) || \ - ((__FORMAT__) == I2S_DATAFORMAT_16B_EXTENDED) || \ - ((__FORMAT__) == I2S_DATAFORMAT_24B) || \ - ((__FORMAT__) == I2S_DATAFORMAT_32B)) - -#define IS_I2S_MCLK_OUTPUT(__OUTPUT__) (((__OUTPUT__) == I2S_MCLKOUTPUT_ENABLE) || \ - ((__OUTPUT__) == I2S_MCLKOUTPUT_DISABLE)) - -#define IS_I2S_AUDIO_FREQ(__FREQ__) ((((__FREQ__) >= I2S_AUDIOFREQ_8K) && \ - ((__FREQ__) <= I2S_AUDIOFREQ_192K)) || \ - ((__FREQ__) == I2S_AUDIOFREQ_DEFAULT)) - -#define IS_I2S_FULLDUPLEX_MODE(MODE) (((MODE) == I2S_FULLDUPLEXMODE_DISABLE) || \ - ((MODE) == I2S_FULLDUPLEXMODE_ENABLE)) - -/** @brief Checks if I2S Serial clock steady state parameter is in allowed range. - * @param __CPOL__ specifies the I2S serial clock steady state. - * This parameter can be a value of @ref I2S_Clock_Polarity - * @retval None - */ -#define IS_I2S_CPOL(__CPOL__) (((__CPOL__) == I2S_CPOL_LOW) || \ - ((__CPOL__) == I2S_CPOL_HIGH)) - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F469xx) || defined(STM32F479xx) -#define IS_I2S_CLOCKSOURCE(CLOCK) (((CLOCK) == I2S_CLOCK_EXTERNAL) ||\ - ((CLOCK) == I2S_CLOCK_PLL)) -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || - STM32F401xC || STM32F401xE || STM32F411xE || STM32F469xx || STM32F479xx */ - -#if defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined (STM32F413xx) || defined(STM32F423xx) -#define IS_I2S_CLOCKSOURCE(CLOCK) (((CLOCK) == I2S_CLOCK_EXTERNAL) ||\ - ((CLOCK) == I2S_CLOCK_PLL) ||\ - ((CLOCK) == I2S_CLOCK_PLLSRC) ||\ - ((CLOCK) == I2S_CLOCK_PLLR)) -#endif /* STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -#define IS_I2S_CLOCKSOURCE(CLOCK) (((CLOCK) == I2S_CLOCK_EXTERNAL) ||\ - ((CLOCK) == I2S_CLOCK_PLLSRC) ||\ - ((CLOCK) == I2S_CLOCK_PLLR)) -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_HAL_I2S_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2s_ex.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2s_ex.h deleted file mode 100644 index 10335f4..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_i2s_ex.h +++ /dev/null @@ -1,185 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_i2s_ex.h - * @author MCD Application Team - * @brief Header file of I2S HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_I2S_EX_H -#define STM32F4xx_HAL_I2S_EX_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ -#if defined(SPI_I2S_FULLDUPLEX_SUPPORT) -/** @addtogroup I2SEx I2SEx - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/* Exported macros -----------------------------------------------------------*/ -/** @defgroup I2SEx_Exported_Macros I2S Extended Exported Macros - * @{ - */ - -#define I2SxEXT(__INSTANCE__) ((__INSTANCE__) == (SPI2)? (SPI_TypeDef *)(I2S2ext_BASE): (SPI_TypeDef *)(I2S3ext_BASE)) - -/** @brief Enable or disable the specified I2SExt peripheral. - * @param __HANDLE__ specifies the I2S Handle. - * @retval None - */ -#define __HAL_I2SEXT_ENABLE(__HANDLE__) (I2SxEXT((__HANDLE__)->Instance)->I2SCFGR |= SPI_I2SCFGR_I2SE) -#define __HAL_I2SEXT_DISABLE(__HANDLE__) (I2SxEXT((__HANDLE__)->Instance)->I2SCFGR &= ~SPI_I2SCFGR_I2SE) - -/** @brief Enable or disable the specified I2SExt interrupts. - * @param __HANDLE__ specifies the I2S Handle. - * @param __INTERRUPT__ specifies the interrupt source to enable or disable. - * This parameter can be one of the following values: - * @arg I2S_IT_TXE: Tx buffer empty interrupt enable - * @arg I2S_IT_RXNE: RX buffer not empty interrupt enable - * @arg I2S_IT_ERR: Error interrupt enable - * @retval None - */ -#define __HAL_I2SEXT_ENABLE_IT(__HANDLE__, __INTERRUPT__) (I2SxEXT((__HANDLE__)->Instance)->CR2 |= (__INTERRUPT__)) -#define __HAL_I2SEXT_DISABLE_IT(__HANDLE__, __INTERRUPT__) (I2SxEXT((__HANDLE__)->Instance)->CR2 &= ~(__INTERRUPT__)) - -/** @brief Checks if the specified I2SExt interrupt source is enabled or disabled. - * @param __HANDLE__ specifies the I2S Handle. - * This parameter can be I2S where x: 1, 2, or 3 to select the I2S peripheral. - * @param __INTERRUPT__ specifies the I2S interrupt source to check. - * This parameter can be one of the following values: - * @arg I2S_IT_TXE: Tx buffer empty interrupt enable - * @arg I2S_IT_RXNE: RX buffer not empty interrupt enable - * @arg I2S_IT_ERR: Error interrupt enable - * @retval The new state of __IT__ (TRUE or FALSE). - */ -#define __HAL_I2SEXT_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) (((I2SxEXT((__HANDLE__)->Instance)->CR2\ - & (__INTERRUPT__)) == (__INTERRUPT__)) ? SET : RESET) - -/** @brief Checks whether the specified I2SExt flag is set or not. - * @param __HANDLE__ specifies the I2S Handle. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg I2S_FLAG_RXNE: Receive buffer not empty flag - * @arg I2S_FLAG_TXE: Transmit buffer empty flag - * @arg I2S_FLAG_UDR: Underrun flag - * @arg I2S_FLAG_OVR: Overrun flag - * @arg I2S_FLAG_FRE: Frame error flag - * @arg I2S_FLAG_CHSIDE: Channel Side flag - * @arg I2S_FLAG_BSY: Busy flag - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_I2SEXT_GET_FLAG(__HANDLE__, __FLAG__) (((I2SxEXT((__HANDLE__)->Instance)->SR) & (__FLAG__)) == (__FLAG__)) - -/** @brief Clears the I2SExt OVR pending flag. - * @param __HANDLE__ specifies the I2S Handle. - * @retval None - */ -#define __HAL_I2SEXT_CLEAR_OVRFLAG(__HANDLE__) do{ \ - __IO uint32_t tmpreg_ovr = 0x00U; \ - tmpreg_ovr = I2SxEXT((__HANDLE__)->Instance)->DR;\ - tmpreg_ovr = I2SxEXT((__HANDLE__)->Instance)->SR;\ - UNUSED(tmpreg_ovr); \ - }while(0U) -/** @brief Clears the I2SExt UDR pending flag. - * @param __HANDLE__ specifies the I2S Handle. - * @retval None - */ -#define __HAL_I2SEXT_CLEAR_UDRFLAG(__HANDLE__) do{ \ - __IO uint32_t tmpreg_udr = 0x00U; \ - tmpreg_udr = I2SxEXT((__HANDLE__)->Instance)->SR;\ - UNUSED(tmpreg_udr); \ - }while(0U) -/** @brief Flush the I2S and I2SExt DR Registers. - * @param __HANDLE__ specifies the I2S Handle. - * @retval None - */ -#define __HAL_I2SEXT_FLUSH_RX_DR(__HANDLE__) do{ \ - __IO uint32_t tmpreg_dr = 0x00U; \ - tmpreg_dr = I2SxEXT((__HANDLE__)->Instance)->DR; \ - tmpreg_dr = ((__HANDLE__)->Instance->DR); \ - UNUSED(tmpreg_dr); \ - }while(0U) -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup I2SEx_Exported_Functions I2S Extended Exported Functions - * @{ - */ - -/** @addtogroup I2SEx_Exported_Functions_Group1 I2S Extended IO operation functions - * @{ - */ - -/* Extended features functions *************************************************/ -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_I2SEx_TransmitReceive(I2S_HandleTypeDef *hi2s, uint16_t *pTxData, uint16_t *pRxData, - uint16_t Size, uint32_t Timeout); -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_I2SEx_TransmitReceive_IT(I2S_HandleTypeDef *hi2s, uint16_t *pTxData, uint16_t *pRxData, - uint16_t Size); -/* Non-Blocking mode: DMA */ -HAL_StatusTypeDef HAL_I2SEx_TransmitReceive_DMA(I2S_HandleTypeDef *hi2s, uint16_t *pTxData, uint16_t *pRxData, - uint16_t Size); -/* I2S IRQHandler and Callbacks used in non blocking modes (Interrupt and DMA) */ -void HAL_I2SEx_FullDuplex_IRQHandler(I2S_HandleTypeDef *hi2s); -void HAL_I2SEx_TxRxHalfCpltCallback(I2S_HandleTypeDef *hi2s); -void HAL_I2SEx_TxRxCpltCallback(I2S_HandleTypeDef *hi2s); -/** - * @} - */ - -/** - * @} - */ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ - -/** - * @} - */ - -#endif /* SPI_I2S_FULLDUPLEX_SUPPORT */ -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - - -#endif /* STM32F4xx_HAL_I2S_EX_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_irda.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_irda.h deleted file mode 100644 index 4d83abc..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_irda.h +++ /dev/null @@ -1,684 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_irda.h - * @author MCD Application Team - * @brief Header file of IRDA HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_IRDA_H -#define __STM32F4xx_HAL_IRDA_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup IRDA - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup IRDA_Exported_Types IRDA Exported Types - * @{ - */ -/** - * @brief IRDA Init Structure definition - */ -typedef struct -{ - uint32_t BaudRate; /*!< This member configures the IRDA communication baud rate. - The baud rate is computed using the following formula: - - IntegerDivider = ((PCLKx) / (8 * (hirda->Init.BaudRate))) - - FractionalDivider = ((IntegerDivider - ((uint32_t) IntegerDivider)) * 8) + 0.5 */ - - uint32_t WordLength; /*!< Specifies the number of data bits transmitted or received in a frame. - This parameter can be a value of @ref IRDA_Word_Length */ - - uint32_t Parity; /*!< Specifies the parity mode. - This parameter can be a value of @ref IRDA_Parity - @note When parity is enabled, the computed parity is inserted - at the MSB position of the transmitted data (9th bit when - the word length is set to 9 data bits; 8th bit when the - word length is set to 8 data bits). */ - - uint32_t Mode; /*!< Specifies whether the Receive or Transmit mode is enabled or disabled. - This parameter can be a value of @ref IRDA_Mode */ - - uint8_t Prescaler; /*!< Specifies the Prescaler value to be programmed - in the IrDA low-power Baud Register, for defining pulse width on which - burst acceptance/rejection will be decided. This value is used as divisor - of system clock to achieve required pulse width. */ - - uint32_t IrDAMode; /*!< Specifies the IrDA mode - This parameter can be a value of @ref IRDA_Low_Power */ -} IRDA_InitTypeDef; - -/** - * @brief HAL IRDA State structures definition - * @note HAL IRDA State value is a combination of 2 different substates: gState and RxState. - * - gState contains IRDA state information related to global Handle management - * and also information related to Tx operations. - * gState value coding follow below described bitmap : - * b7-b6 Error information - * 00 : No Error - * 01 : (Not Used) - * 10 : Timeout - * 11 : Error - * b5 IP initialisation status - * 0 : Reset (IP not initialized) - * 1 : Init done (IP initialized. HAL IRDA Init function already called) - * b4-b3 (not used) - * xx : Should be set to 00 - * b2 Intrinsic process state - * 0 : Ready - * 1 : Busy (IP busy with some configuration or internal operations) - * b1 (not used) - * x : Should be set to 0 - * b0 Tx state - * 0 : Ready (no Tx operation ongoing) - * 1 : Busy (Tx operation ongoing) - * - RxState contains information related to Rx operations. - * RxState value coding follow below described bitmap : - * b7-b6 (not used) - * xx : Should be set to 00 - * b5 IP initialisation status - * 0 : Reset (IP not initialized) - * 1 : Init done (IP initialized) - * b4-b2 (not used) - * xxx : Should be set to 000 - * b1 Rx state - * 0 : Ready (no Rx operation ongoing) - * 1 : Busy (Rx operation ongoing) - * b0 (not used) - * x : Should be set to 0. - */ -typedef enum -{ - HAL_IRDA_STATE_RESET = 0x00U, /*!< Peripheral is not yet Initialized - Value is allowed for gState and RxState */ - HAL_IRDA_STATE_READY = 0x20U, /*!< Peripheral Initialized and ready for use - Value is allowed for gState and RxState */ - HAL_IRDA_STATE_BUSY = 0x24U, /*!< An internal process is ongoing - Value is allowed for gState only */ - HAL_IRDA_STATE_BUSY_TX = 0x21U, /*!< Data Transmission process is ongoing - Value is allowed for gState only */ - HAL_IRDA_STATE_BUSY_RX = 0x22U, /*!< Data Reception process is ongoing - Value is allowed for RxState only */ - HAL_IRDA_STATE_BUSY_TX_RX = 0x23U, /*!< Data Transmission and Reception process is ongoing - Not to be used for neither gState nor RxState. - Value is result of combination (Or) between gState and RxState values */ - HAL_IRDA_STATE_TIMEOUT = 0xA0U, /*!< Timeout state - Value is allowed for gState only */ - HAL_IRDA_STATE_ERROR = 0xE0U /*!< Error - Value is allowed for gState only */ -} HAL_IRDA_StateTypeDef; - -/** - * @brief IRDA handle Structure definition - */ -#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) -typedef struct __IRDA_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_IRDA_REGISTER_CALLBACKS */ -{ - USART_TypeDef *Instance; /*!< USART registers base address */ - - IRDA_InitTypeDef Init; /*!< IRDA communication parameters */ - - uint8_t *pTxBuffPtr; /*!< Pointer to IRDA Tx transfer Buffer */ - - uint16_t TxXferSize; /*!< IRDA Tx Transfer size */ - - __IO uint16_t TxXferCount; /*!< IRDA Tx Transfer Counter */ - - uint8_t *pRxBuffPtr; /*!< Pointer to IRDA Rx transfer Buffer */ - - uint16_t RxXferSize; /*!< IRDA Rx Transfer size */ - - __IO uint16_t RxXferCount; /*!< IRDA Rx Transfer Counter */ - - DMA_HandleTypeDef *hdmatx; /*!< IRDA Tx DMA Handle parameters */ - - DMA_HandleTypeDef *hdmarx; /*!< IRDA Rx DMA Handle parameters */ - - HAL_LockTypeDef Lock; /*!< Locking object */ - - __IO HAL_IRDA_StateTypeDef gState; /*!< IRDA state information related to global Handle management - and also related to Tx operations. - This parameter can be a value of @ref HAL_IRDA_StateTypeDef */ - - __IO HAL_IRDA_StateTypeDef RxState; /*!< IRDA state information related to Rx operations. - This parameter can be a value of @ref HAL_IRDA_StateTypeDef */ - - __IO uint32_t ErrorCode; /*!< IRDA Error code */ - -#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) - void (* TxHalfCpltCallback)(struct __IRDA_HandleTypeDef *hirda); /*!< IRDA Tx Half Complete Callback */ - - void (* TxCpltCallback)(struct __IRDA_HandleTypeDef *hirda); /*!< IRDA Tx Complete Callback */ - - void (* RxHalfCpltCallback)(struct __IRDA_HandleTypeDef *hirda); /*!< IRDA Rx Half Complete Callback */ - - void (* RxCpltCallback)(struct __IRDA_HandleTypeDef *hirda); /*!< IRDA Rx Complete Callback */ - - void (* ErrorCallback)(struct __IRDA_HandleTypeDef *hirda); /*!< IRDA Error Callback */ - - void (* AbortCpltCallback)(struct __IRDA_HandleTypeDef *hirda); /*!< IRDA Abort Complete Callback */ - - void (* AbortTransmitCpltCallback)(struct __IRDA_HandleTypeDef *hirda); /*!< IRDA Abort Transmit Complete Callback */ - - void (* AbortReceiveCpltCallback)(struct __IRDA_HandleTypeDef *hirda); /*!< IRDA Abort Receive Complete Callback */ - - - void (* MspInitCallback)(struct __IRDA_HandleTypeDef *hirda); /*!< IRDA Msp Init callback */ - - void (* MspDeInitCallback)(struct __IRDA_HandleTypeDef *hirda); /*!< IRDA Msp DeInit callback */ -#endif /* USE_HAL_IRDA_REGISTER_CALLBACKS */ - -} IRDA_HandleTypeDef; - -#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) -/** - * @brief HAL IRDA Callback ID enumeration definition - */ -typedef enum -{ - HAL_IRDA_TX_HALFCOMPLETE_CB_ID = 0x00U, /*!< IRDA Tx Half Complete Callback ID */ - HAL_IRDA_TX_COMPLETE_CB_ID = 0x01U, /*!< IRDA Tx Complete Callback ID */ - HAL_IRDA_RX_HALFCOMPLETE_CB_ID = 0x02U, /*!< IRDA Rx Half Complete Callback ID */ - HAL_IRDA_RX_COMPLETE_CB_ID = 0x03U, /*!< IRDA Rx Complete Callback ID */ - HAL_IRDA_ERROR_CB_ID = 0x04U, /*!< IRDA Error Callback ID */ - HAL_IRDA_ABORT_COMPLETE_CB_ID = 0x05U, /*!< IRDA Abort Complete Callback ID */ - HAL_IRDA_ABORT_TRANSMIT_COMPLETE_CB_ID = 0x06U, /*!< IRDA Abort Transmit Complete Callback ID */ - HAL_IRDA_ABORT_RECEIVE_COMPLETE_CB_ID = 0x07U, /*!< IRDA Abort Receive Complete Callback ID */ - - HAL_IRDA_MSPINIT_CB_ID = 0x08U, /*!< IRDA MspInit callback ID */ - HAL_IRDA_MSPDEINIT_CB_ID = 0x09U /*!< IRDA MspDeInit callback ID */ - -} HAL_IRDA_CallbackIDTypeDef; - -/** - * @brief HAL IRDA Callback pointer definition - */ -typedef void (*pIRDA_CallbackTypeDef)(IRDA_HandleTypeDef *hirda); /*!< pointer to an IRDA callback function */ - -#endif /* USE_HAL_IRDA_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup IRDA_Exported_Constants IRDA Exported constants - * @{ - */ -/** @defgroup IRDA_Error_Code IRDA Error Code - * @{ - */ -#define HAL_IRDA_ERROR_NONE 0x00000000U /*!< No error */ -#define HAL_IRDA_ERROR_PE 0x00000001U /*!< Parity error */ -#define HAL_IRDA_ERROR_NE 0x00000002U /*!< Noise error */ -#define HAL_IRDA_ERROR_FE 0x00000004U /*!< Frame error */ -#define HAL_IRDA_ERROR_ORE 0x00000008U /*!< Overrun error */ -#define HAL_IRDA_ERROR_DMA 0x00000010U /*!< DMA transfer error */ -#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) -#define HAL_IRDA_ERROR_INVALID_CALLBACK ((uint32_t)0x00000020U) /*!< Invalid Callback error */ -#endif /* USE_HAL_IRDA_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @defgroup IRDA_Word_Length IRDA Word Length - * @{ - */ -#define IRDA_WORDLENGTH_8B 0x00000000U -#define IRDA_WORDLENGTH_9B ((uint32_t)USART_CR1_M) -/** - * @} - */ - -/** @defgroup IRDA_Parity IRDA Parity - * @{ - */ -#define IRDA_PARITY_NONE 0x00000000U -#define IRDA_PARITY_EVEN ((uint32_t)USART_CR1_PCE) -#define IRDA_PARITY_ODD ((uint32_t)(USART_CR1_PCE | USART_CR1_PS)) -/** - * @} - */ - -/** @defgroup IRDA_Mode IRDA Transfer Mode - * @{ - */ -#define IRDA_MODE_RX ((uint32_t)USART_CR1_RE) -#define IRDA_MODE_TX ((uint32_t)USART_CR1_TE) -#define IRDA_MODE_TX_RX ((uint32_t)(USART_CR1_TE |USART_CR1_RE)) -/** - * @} - */ - -/** @defgroup IRDA_Low_Power IRDA Low Power - * @{ - */ -#define IRDA_POWERMODE_LOWPOWER ((uint32_t)USART_CR3_IRLP) -#define IRDA_POWERMODE_NORMAL 0x00000000U -/** - * @} - */ - -/** @defgroup IRDA_Flags IRDA Flags - * Elements values convention: 0xXXXX - * - 0xXXXX : Flag mask in the SR register - * @{ - */ -#define IRDA_FLAG_TXE ((uint32_t)USART_SR_TXE) -#define IRDA_FLAG_TC ((uint32_t)USART_SR_TC) -#define IRDA_FLAG_RXNE ((uint32_t)USART_SR_RXNE) -#define IRDA_FLAG_IDLE ((uint32_t)USART_SR_IDLE) -#define IRDA_FLAG_ORE ((uint32_t)USART_SR_ORE) -#define IRDA_FLAG_NE ((uint32_t)USART_SR_NE) -#define IRDA_FLAG_FE ((uint32_t)USART_SR_FE) -#define IRDA_FLAG_PE ((uint32_t)USART_SR_PE) -/** - * @} - */ - -/** @defgroup IRDA_Interrupt_definition IRDA Interrupt Definitions - * Elements values convention: 0xY000XXXX - * - XXXX : Interrupt mask in the XX register - * - Y : Interrupt source register (2bits) - * - 01: CR1 register - * - 10: CR2 register - * - 11: CR3 register - * @{ - */ -#define IRDA_IT_PE ((uint32_t)(IRDA_CR1_REG_INDEX << 28U | USART_CR1_PEIE)) -#define IRDA_IT_TXE ((uint32_t)(IRDA_CR1_REG_INDEX << 28U | USART_CR1_TXEIE)) -#define IRDA_IT_TC ((uint32_t)(IRDA_CR1_REG_INDEX << 28U | USART_CR1_TCIE)) -#define IRDA_IT_RXNE ((uint32_t)(IRDA_CR1_REG_INDEX << 28U | USART_CR1_RXNEIE)) -#define IRDA_IT_IDLE ((uint32_t)(IRDA_CR1_REG_INDEX << 28U | USART_CR1_IDLEIE)) - -#define IRDA_IT_LBD ((uint32_t)(IRDA_CR2_REG_INDEX << 28U | USART_CR2_LBDIE)) - -#define IRDA_IT_CTS ((uint32_t)(IRDA_CR3_REG_INDEX << 28U | USART_CR3_CTSIE)) -#define IRDA_IT_ERR ((uint32_t)(IRDA_CR3_REG_INDEX << 28U | USART_CR3_EIE)) -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup IRDA_Exported_Macros IRDA Exported Macros - * @{ - */ - -/** @brief Reset IRDA handle gstate & RxState - * @param __HANDLE__ specifies the IRDA Handle. - * IRDA Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @retval None - */ -#if USE_HAL_IRDA_REGISTER_CALLBACKS == 1 -#define __HAL_IRDA_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->gState = HAL_IRDA_STATE_RESET; \ - (__HANDLE__)->RxState = HAL_IRDA_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0U) -#else -#define __HAL_IRDA_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->gState = HAL_IRDA_STATE_RESET; \ - (__HANDLE__)->RxState = HAL_IRDA_STATE_RESET; \ - } while(0U) -#endif /*USE_HAL_IRDA_REGISTER_CALLBACKS */ - -/** @brief Flush the IRDA DR register - * @param __HANDLE__ specifies the IRDA Handle. - * IRDA Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @retval None - */ -#define __HAL_IRDA_FLUSH_DRREGISTER(__HANDLE__) ((__HANDLE__)->Instance->DR) - -/** @brief Check whether the specified IRDA flag is set or not. - * @param __HANDLE__ specifies the IRDA Handle. - * IRDA Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg IRDA_FLAG_TXE: Transmit data register empty flag - * @arg IRDA_FLAG_TC: Transmission Complete flag - * @arg IRDA_FLAG_RXNE: Receive data register not empty flag - * @arg IRDA_FLAG_IDLE: Idle Line detection flag - * @arg IRDA_FLAG_ORE: OverRun Error flag - * @arg IRDA_FLAG_NE: Noise Error flag - * @arg IRDA_FLAG_FE: Framing Error flag - * @arg IRDA_FLAG_PE: Parity Error flag - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_IRDA_GET_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->SR & (__FLAG__)) == (__FLAG__)) - -/** @brief Clear the specified IRDA pending flag. - * @param __HANDLE__ specifies the IRDA Handle. - * IRDA Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @param __FLAG__ specifies the flag to check. - * This parameter can be any combination of the following values: - * @arg IRDA_FLAG_TC: Transmission Complete flag. - * @arg IRDA_FLAG_RXNE: Receive data register not empty flag. - * - * @note PE (Parity error), FE (Framing error), NE (Noise error), ORE (OverRun - * error) and IDLE (Idle line detected) flags are cleared by software - * sequence: a read operation to USART_SR register followed by a read - * operation to USART_DR register. - * @note RXNE flag can be also cleared by a read to the USART_DR register. - * @note TC flag can be also cleared by software sequence: a read operation to - * USART_SR register followed by a write operation to USART_DR register. - * @note TXE flag is cleared only by a write to the USART_DR register. - * @retval None - */ -#define __HAL_IRDA_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->SR = ~(__FLAG__)) - -/** @brief Clear the IRDA PE pending flag. - * @param __HANDLE__ specifies the IRDA Handle. - * IRDA Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @retval None - */ -#define __HAL_IRDA_CLEAR_PEFLAG(__HANDLE__) \ - do{ \ - __IO uint32_t tmpreg = 0x00U; \ - tmpreg = (__HANDLE__)->Instance->SR; \ - tmpreg = (__HANDLE__)->Instance->DR; \ - UNUSED(tmpreg); \ - } while(0U) - -/** @brief Clear the IRDA FE pending flag. - * @param __HANDLE__ specifies the IRDA Handle. - * IRDA Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @retval None - */ -#define __HAL_IRDA_CLEAR_FEFLAG(__HANDLE__) __HAL_IRDA_CLEAR_PEFLAG(__HANDLE__) - -/** @brief Clear the IRDA NE pending flag. - * @param __HANDLE__ specifies the IRDA Handle. - * IRDA Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @retval None - */ -#define __HAL_IRDA_CLEAR_NEFLAG(__HANDLE__) __HAL_IRDA_CLEAR_PEFLAG(__HANDLE__) - -/** @brief Clear the IRDA ORE pending flag. - * @param __HANDLE__ specifies the IRDA Handle. - * IRDA Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @retval None - */ -#define __HAL_IRDA_CLEAR_OREFLAG(__HANDLE__) __HAL_IRDA_CLEAR_PEFLAG(__HANDLE__) - -/** @brief Clear the IRDA IDLE pending flag. - * @param __HANDLE__ specifies the IRDA Handle. - * IRDA Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @retval None - */ -#define __HAL_IRDA_CLEAR_IDLEFLAG(__HANDLE__) __HAL_IRDA_CLEAR_PEFLAG(__HANDLE__) - -/** @brief Enable the specified IRDA interrupt. - * @param __HANDLE__ specifies the IRDA Handle. - * IRDA Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @param __INTERRUPT__ specifies the IRDA interrupt source to enable. - * This parameter can be one of the following values: - * @arg IRDA_IT_TXE: Transmit Data Register empty interrupt - * @arg IRDA_IT_TC: Transmission complete interrupt - * @arg IRDA_IT_RXNE: Receive Data register not empty interrupt - * @arg IRDA_IT_IDLE: Idle line detection interrupt - * @arg IRDA_IT_PE: Parity Error interrupt - * @arg IRDA_IT_ERR: Error interrupt(Frame error, noise error, overrun error) - * @retval None - */ -#define __HAL_IRDA_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((((__INTERRUPT__) >> 28U) == IRDA_CR1_REG_INDEX)? ((__HANDLE__)->Instance->CR1 |= ((__INTERRUPT__) & IRDA_IT_MASK)): \ - (((__INTERRUPT__) >> 28U) == IRDA_CR2_REG_INDEX)? ((__HANDLE__)->Instance->CR2 |= ((__INTERRUPT__) & IRDA_IT_MASK)): \ - ((__HANDLE__)->Instance->CR3 |= ((__INTERRUPT__) & IRDA_IT_MASK))) -/** @brief Disable the specified IRDA interrupt. - * @param __HANDLE__ specifies the IRDA Handle. - * IRDA Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @param __INTERRUPT__ specifies the IRDA interrupt source to disable. - * This parameter can be one of the following values: - * @arg IRDA_IT_TXE: Transmit Data Register empty interrupt - * @arg IRDA_IT_TC: Transmission complete interrupt - * @arg IRDA_IT_RXNE: Receive Data register not empty interrupt - * @arg IRDA_IT_IDLE: Idle line detection interrupt - * @arg IRDA_IT_PE: Parity Error interrupt - * @arg IRDA_IT_ERR: Error interrupt(Frame error, noise error, overrun error) - * @retval None - */ -#define __HAL_IRDA_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((((__INTERRUPT__) >> 28U) == IRDA_CR1_REG_INDEX)? ((__HANDLE__)->Instance->CR1 &= ~((__INTERRUPT__) & IRDA_IT_MASK)): \ - (((__INTERRUPT__) >> 28U) == IRDA_CR2_REG_INDEX)? ((__HANDLE__)->Instance->CR2 &= ~((__INTERRUPT__) & IRDA_IT_MASK)): \ - ((__HANDLE__)->Instance->CR3 &= ~ ((__INTERRUPT__) & IRDA_IT_MASK))) - -/** @brief Check whether the specified IRDA interrupt has occurred or not. - * @param __HANDLE__ specifies the IRDA Handle. - * IRDA Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @param __IT__ specifies the IRDA interrupt source to check. - * This parameter can be one of the following values: - * @arg IRDA_IT_TXE: Transmit Data Register empty interrupt - * @arg IRDA_IT_TC: Transmission complete interrupt - * @arg IRDA_IT_RXNE: Receive Data register not empty interrupt - * @arg IRDA_IT_IDLE: Idle line detection interrupt - * @arg IRDA_IT_ERR: Error interrupt - * @arg IRDA_IT_PE: Parity Error interrupt - * @retval The new state of __IT__ (TRUE or FALSE). - */ -#define __HAL_IRDA_GET_IT_SOURCE(__HANDLE__, __IT__) (((((__IT__) >> 28U) == IRDA_CR1_REG_INDEX)? (__HANDLE__)->Instance->CR1:(((((uint32_t)(__IT__)) >> 28U) == IRDA_CR2_REG_INDEX)? \ - (__HANDLE__)->Instance->CR2 : (__HANDLE__)->Instance->CR3)) & (((uint32_t)(__IT__)) & IRDA_IT_MASK)) - -/** @brief Macro to enable the IRDA's one bit sample method - * @param __HANDLE__ specifies the IRDA Handle. - * @retval None - */ -#define __HAL_IRDA_ONE_BIT_SAMPLE_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR3 |= USART_CR3_ONEBIT) - -/** @brief Macro to disable the IRDA's one bit sample method - * @param __HANDLE__ specifies the IRDA Handle. - * @retval None - */ -#define __HAL_IRDA_ONE_BIT_SAMPLE_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR3 &= (uint16_t)~((uint16_t)USART_CR3_ONEBIT)) - -/** @brief Enable UART/USART associated to IRDA Handle - * @param __HANDLE__ specifies the IRDA Handle. - * IRDA Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @retval None - */ -#define __HAL_IRDA_ENABLE(__HANDLE__) (SET_BIT((__HANDLE__)->Instance->CR1, USART_CR1_UE)) - -/** @brief Disable UART/USART associated to IRDA Handle - * @param __HANDLE__ specifies the IRDA Handle. - * IRDA Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @retval None - */ -#define __HAL_IRDA_DISABLE(__HANDLE__) (CLEAR_BIT((__HANDLE__)->Instance->CR1, USART_CR1_UE)) - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup IRDA_Exported_Functions - * @{ - */ - -/** @addtogroup IRDA_Exported_Functions_Group1 - * @{ - */ -/* Initialization/de-initialization functions **********************************/ -HAL_StatusTypeDef HAL_IRDA_Init(IRDA_HandleTypeDef *hirda); -HAL_StatusTypeDef HAL_IRDA_DeInit(IRDA_HandleTypeDef *hirda); -void HAL_IRDA_MspInit(IRDA_HandleTypeDef *hirda); -void HAL_IRDA_MspDeInit(IRDA_HandleTypeDef *hirda); - -#if (USE_HAL_IRDA_REGISTER_CALLBACKS == 1) -/* Callbacks Register/UnRegister functions ***********************************/ -HAL_StatusTypeDef HAL_IRDA_RegisterCallback(IRDA_HandleTypeDef *hirda, HAL_IRDA_CallbackIDTypeDef CallbackID, pIRDA_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_IRDA_UnRegisterCallback(IRDA_HandleTypeDef *hirda, HAL_IRDA_CallbackIDTypeDef CallbackID); -#endif /* USE_HAL_IRDA_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @addtogroup IRDA_Exported_Functions_Group2 - * @{ - */ -/* IO operation functions *******************************************************/ -HAL_StatusTypeDef HAL_IRDA_Transmit(IRDA_HandleTypeDef *hirda, uint8_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_IRDA_Receive(IRDA_HandleTypeDef *hirda, uint8_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_IRDA_Transmit_IT(IRDA_HandleTypeDef *hirda, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_IRDA_Receive_IT(IRDA_HandleTypeDef *hirda, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_IRDA_Transmit_DMA(IRDA_HandleTypeDef *hirda, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_IRDA_Receive_DMA(IRDA_HandleTypeDef *hirda, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_IRDA_DMAPause(IRDA_HandleTypeDef *hirda); -HAL_StatusTypeDef HAL_IRDA_DMAResume(IRDA_HandleTypeDef *hirda); -HAL_StatusTypeDef HAL_IRDA_DMAStop(IRDA_HandleTypeDef *hirda); -/* Transfer Abort functions */ -HAL_StatusTypeDef HAL_IRDA_Abort(IRDA_HandleTypeDef *hirda); -HAL_StatusTypeDef HAL_IRDA_AbortTransmit(IRDA_HandleTypeDef *hirda); -HAL_StatusTypeDef HAL_IRDA_AbortReceive(IRDA_HandleTypeDef *hirda); -HAL_StatusTypeDef HAL_IRDA_Abort_IT(IRDA_HandleTypeDef *hirda); -HAL_StatusTypeDef HAL_IRDA_AbortTransmit_IT(IRDA_HandleTypeDef *hirda); -HAL_StatusTypeDef HAL_IRDA_AbortReceive_IT(IRDA_HandleTypeDef *hirda); - -void HAL_IRDA_IRQHandler(IRDA_HandleTypeDef *hirda); -void HAL_IRDA_TxCpltCallback(IRDA_HandleTypeDef *hirda); -void HAL_IRDA_RxCpltCallback(IRDA_HandleTypeDef *hirda); -void HAL_IRDA_TxHalfCpltCallback(IRDA_HandleTypeDef *hirda); -void HAL_IRDA_RxHalfCpltCallback(IRDA_HandleTypeDef *hirda); -void HAL_IRDA_ErrorCallback(IRDA_HandleTypeDef *hirda); -void HAL_IRDA_AbortCpltCallback(IRDA_HandleTypeDef *hirda); -void HAL_IRDA_AbortTransmitCpltCallback(IRDA_HandleTypeDef *hirda); -void HAL_IRDA_AbortReceiveCpltCallback(IRDA_HandleTypeDef *hirda); -/** - * @} - */ - -/** @addtogroup IRDA_Exported_Functions_Group3 - * @{ - */ -/* Peripheral State functions **************************************************/ -HAL_IRDA_StateTypeDef HAL_IRDA_GetState(IRDA_HandleTypeDef *hirda); -uint32_t HAL_IRDA_GetError(IRDA_HandleTypeDef *hirda); -/** - * @} - */ - -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup IRDA_Private_Constants IRDA Private Constants - * @{ - */ - -/** @brief IRDA interruptions flag mask - * - */ -#define IRDA_IT_MASK ((uint32_t) USART_CR1_PEIE | USART_CR1_TXEIE | USART_CR1_TCIE | USART_CR1_RXNEIE | \ - USART_CR1_IDLEIE | USART_CR2_LBDIE | USART_CR3_CTSIE | USART_CR3_EIE ) - -#define IRDA_CR1_REG_INDEX 1U -#define IRDA_CR2_REG_INDEX 2U -#define IRDA_CR3_REG_INDEX 3U -/** - * @} - */ - -/* Private macros --------------------------------------------------------*/ -/** @defgroup IRDA_Private_Macros IRDA Private Macros - * @{ - */ -#define IS_IRDA_WORD_LENGTH(LENGTH) (((LENGTH) == IRDA_WORDLENGTH_8B) || \ - ((LENGTH) == IRDA_WORDLENGTH_9B)) - -#define IS_IRDA_PARITY(PARITY) (((PARITY) == IRDA_PARITY_NONE) || \ - ((PARITY) == IRDA_PARITY_EVEN) || \ - ((PARITY) == IRDA_PARITY_ODD)) - -#define IS_IRDA_MODE(MODE) ((((MODE) & 0x0000FFF3U) == 0x00U) && ((MODE) != 0x00000000U)) - -#define IS_IRDA_POWERMODE(MODE) (((MODE) == IRDA_POWERMODE_LOWPOWER) || \ - ((MODE) == IRDA_POWERMODE_NORMAL)) - -#define IS_IRDA_BAUDRATE(BAUDRATE) ((BAUDRATE) < 115201U) - -#define IRDA_DIV(_PCLK_, _BAUD_) ((uint32_t)((((uint64_t)(_PCLK_))*25U)/(4U*(((uint64_t)(_BAUD_)))))) - -#define IRDA_DIVMANT(_PCLK_, _BAUD_) (IRDA_DIV((_PCLK_), (_BAUD_))/100U) - -#define IRDA_DIVFRAQ(_PCLK_, _BAUD_) ((((IRDA_DIV((_PCLK_), (_BAUD_)) - (IRDA_DIVMANT((_PCLK_), (_BAUD_)) * 100U)) * 16U) + 50U) / 100U) - -/* UART BRR = mantissa + overflow + fraction - = (UART DIVMANT << 4) + (UART DIVFRAQ & 0xF0) + (UART DIVFRAQ & 0x0FU) */ -#define IRDA_BRR(_PCLK_, _BAUD_) (((IRDA_DIVMANT((_PCLK_), (_BAUD_)) << 4U) + \ - (IRDA_DIVFRAQ((_PCLK_), (_BAUD_)) & 0xF0U)) + \ - (IRDA_DIVFRAQ((_PCLK_), (_BAUD_)) & 0x0FU)) - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup IRDA_Private_Functions IRDA Private Functions - * @{ - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_IRDA_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_iwdg.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_iwdg.h deleted file mode 100644 index 32f5ff0..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_iwdg.h +++ /dev/null @@ -1,223 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_iwdg.h - * @author MCD Application Team - * @brief Header file of IWDG HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_IWDG_H -#define STM32F4xx_HAL_IWDG_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup IWDG IWDG - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup IWDG_Exported_Types IWDG Exported Types - * @{ - */ - -/** - * @brief IWDG Init structure definition - */ -typedef struct -{ - uint32_t Prescaler; /*!< Select the prescaler of the IWDG. - This parameter can be a value of @ref IWDG_Prescaler */ - - uint32_t Reload; /*!< Specifies the IWDG down-counter reload value. - This parameter must be a number between Min_Data = 0 and Max_Data = 0x0FFF */ - -} IWDG_InitTypeDef; - -/** - * @brief IWDG Handle Structure definition - */ -typedef struct -{ - IWDG_TypeDef *Instance; /*!< Register base address */ - - IWDG_InitTypeDef Init; /*!< IWDG required parameters */ -} IWDG_HandleTypeDef; - - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup IWDG_Exported_Constants IWDG Exported Constants - * @{ - */ - -/** @defgroup IWDG_Prescaler IWDG Prescaler - * @{ - */ -#define IWDG_PRESCALER_4 0x00000000u /*!< IWDG prescaler set to 4 */ -#define IWDG_PRESCALER_8 IWDG_PR_PR_0 /*!< IWDG prescaler set to 8 */ -#define IWDG_PRESCALER_16 IWDG_PR_PR_1 /*!< IWDG prescaler set to 16 */ -#define IWDG_PRESCALER_32 (IWDG_PR_PR_1 | IWDG_PR_PR_0) /*!< IWDG prescaler set to 32 */ -#define IWDG_PRESCALER_64 IWDG_PR_PR_2 /*!< IWDG prescaler set to 64 */ -#define IWDG_PRESCALER_128 (IWDG_PR_PR_2 | IWDG_PR_PR_0) /*!< IWDG prescaler set to 128 */ -#define IWDG_PRESCALER_256 (IWDG_PR_PR_2 | IWDG_PR_PR_1) /*!< IWDG prescaler set to 256 */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macros -----------------------------------------------------------*/ -/** @defgroup IWDG_Exported_Macros IWDG Exported Macros - * @{ - */ - -/** - * @brief Enable the IWDG peripheral. - * @param __HANDLE__ IWDG handle - * @retval None - */ -#define __HAL_IWDG_START(__HANDLE__) WRITE_REG((__HANDLE__)->Instance->KR, IWDG_KEY_ENABLE) - -/** - * @brief Reload IWDG counter with value defined in the reload register - * (write access to IWDG_PR and IWDG_RLR registers disabled). - * @param __HANDLE__ IWDG handle - * @retval None - */ -#define __HAL_IWDG_RELOAD_COUNTER(__HANDLE__) WRITE_REG((__HANDLE__)->Instance->KR, IWDG_KEY_RELOAD) - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup IWDG_Exported_Functions IWDG Exported Functions - * @{ - */ - -/** @defgroup IWDG_Exported_Functions_Group1 Initialization and Start functions - * @{ - */ -/* Initialization/Start functions ********************************************/ -HAL_StatusTypeDef HAL_IWDG_Init(IWDG_HandleTypeDef *hiwdg); -/** - * @} - */ - -/** @defgroup IWDG_Exported_Functions_Group2 IO operation functions - * @{ - */ -/* I/O operation functions ****************************************************/ -HAL_StatusTypeDef HAL_IWDG_Refresh(IWDG_HandleTypeDef *hiwdg); -/** - * @} - */ - -/** - * @} - */ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup IWDG_Private_Constants IWDG Private Constants - * @{ - */ - -/** - * @brief IWDG Key Register BitMask - */ -#define IWDG_KEY_RELOAD 0x0000AAAAu /*!< IWDG Reload Counter Enable */ -#define IWDG_KEY_ENABLE 0x0000CCCCu /*!< IWDG Peripheral Enable */ -#define IWDG_KEY_WRITE_ACCESS_ENABLE 0x00005555u /*!< IWDG KR Write Access Enable */ -#define IWDG_KEY_WRITE_ACCESS_DISABLE 0x00000000u /*!< IWDG KR Write Access Disable */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup IWDG_Private_Macros IWDG Private Macros - * @{ - */ - -/** - * @brief Enable write access to IWDG_PR and IWDG_RLR registers. - * @param __HANDLE__ IWDG handle - * @retval None - */ -#define IWDG_ENABLE_WRITE_ACCESS(__HANDLE__) WRITE_REG((__HANDLE__)->Instance->KR, IWDG_KEY_WRITE_ACCESS_ENABLE) - -/** - * @brief Disable write access to IWDG_PR and IWDG_RLR registers. - * @param __HANDLE__ IWDG handle - * @retval None - */ -#define IWDG_DISABLE_WRITE_ACCESS(__HANDLE__) WRITE_REG((__HANDLE__)->Instance->KR, IWDG_KEY_WRITE_ACCESS_DISABLE) - -/** - * @brief Check IWDG prescaler value. - * @param __PRESCALER__ IWDG prescaler value - * @retval None - */ -#define IS_IWDG_PRESCALER(__PRESCALER__) (((__PRESCALER__) == IWDG_PRESCALER_4) || \ - ((__PRESCALER__) == IWDG_PRESCALER_8) || \ - ((__PRESCALER__) == IWDG_PRESCALER_16) || \ - ((__PRESCALER__) == IWDG_PRESCALER_32) || \ - ((__PRESCALER__) == IWDG_PRESCALER_64) || \ - ((__PRESCALER__) == IWDG_PRESCALER_128)|| \ - ((__PRESCALER__) == IWDG_PRESCALER_256)) - -/** - * @brief Check IWDG reload value. - * @param __RELOAD__ IWDG reload value - * @retval None - */ -#define IS_IWDG_RELOAD(__RELOAD__) ((__RELOAD__) <= IWDG_RLR_RL) - - - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_HAL_IWDG_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_lptim.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_lptim.h deleted file mode 100644 index 80ea203..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_lptim.h +++ /dev/null @@ -1,858 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_lptim.h - * @author MCD Application Team - * @brief Header file of LPTIM HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_LPTIM_H -#define STM32F4xx_HAL_LPTIM_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -#if defined (LPTIM1) - -/** @addtogroup LPTIM - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup LPTIM_Exported_Types LPTIM Exported Types - * @{ - */ -#define LPTIM_EXTI_LINE_WAKEUPTIMER_EVENT EXTI_IMR_MR23 /*!< External interrupt line 23 Connected to the LPTIM EXTI Line */ - -/** - * @brief LPTIM Clock configuration definition - */ -typedef struct -{ - uint32_t Source; /*!< Selects the clock source. - This parameter can be a value of @ref LPTIM_Clock_Source */ - - uint32_t Prescaler; /*!< Specifies the counter clock Prescaler. - This parameter can be a value of @ref LPTIM_Clock_Prescaler */ - -} LPTIM_ClockConfigTypeDef; - -/** - * @brief LPTIM Clock configuration definition - */ -typedef struct -{ - uint32_t Polarity; /*!< Selects the polarity of the active edge for the counter unit - if the ULPTIM input is selected. - Note: This parameter is used only when Ultra low power clock source is used. - Note: If the polarity is configured on 'both edges', an auxiliary clock - (one of the Low power oscillator) must be active. - This parameter can be a value of @ref LPTIM_Clock_Polarity */ - - uint32_t SampleTime; /*!< Selects the clock sampling time to configure the clock glitch filter. - Note: This parameter is used only when Ultra low power clock source is used. - This parameter can be a value of @ref LPTIM_Clock_Sample_Time */ - -} LPTIM_ULPClockConfigTypeDef; - -/** - * @brief LPTIM Trigger configuration definition - */ -typedef struct -{ - uint32_t Source; /*!< Selects the Trigger source. - This parameter can be a value of @ref LPTIM_Trigger_Source */ - - uint32_t ActiveEdge; /*!< Selects the Trigger active edge. - Note: This parameter is used only when an external trigger is used. - This parameter can be a value of @ref LPTIM_External_Trigger_Polarity */ - - uint32_t SampleTime; /*!< Selects the trigger sampling time to configure the clock glitch filter. - Note: This parameter is used only when an external trigger is used. - This parameter can be a value of @ref LPTIM_Trigger_Sample_Time */ -} LPTIM_TriggerConfigTypeDef; - -/** - * @brief LPTIM Initialization Structure definition - */ -typedef struct -{ - LPTIM_ClockConfigTypeDef Clock; /*!< Specifies the clock parameters */ - - LPTIM_ULPClockConfigTypeDef UltraLowPowerClock;/*!< Specifies the Ultra Low Power clock parameters */ - - LPTIM_TriggerConfigTypeDef Trigger; /*!< Specifies the Trigger parameters */ - - uint32_t OutputPolarity; /*!< Specifies the Output polarity. - This parameter can be a value of @ref LPTIM_Output_Polarity */ - - uint32_t UpdateMode; /*!< Specifies whether the update of the autoreload and the compare - values is done immediately or after the end of current period. - This parameter can be a value of @ref LPTIM_Updating_Mode */ - - uint32_t CounterSource; /*!< Specifies whether the counter is incremented each internal event - or each external event. - This parameter can be a value of @ref LPTIM_Counter_Source */ -} LPTIM_InitTypeDef; - -/** - * @brief HAL LPTIM State structure definition - */ -typedef enum -{ - HAL_LPTIM_STATE_RESET = 0x00U, /*!< Peripheral not yet initialized or disabled */ - HAL_LPTIM_STATE_READY = 0x01U, /*!< Peripheral Initialized and ready for use */ - HAL_LPTIM_STATE_BUSY = 0x02U, /*!< An internal process is ongoing */ - HAL_LPTIM_STATE_TIMEOUT = 0x03U, /*!< Timeout state */ - HAL_LPTIM_STATE_ERROR = 0x04U /*!< Internal Process is ongoing */ -} HAL_LPTIM_StateTypeDef; - -/** - * @brief LPTIM handle Structure definition - */ -#if (USE_HAL_LPTIM_REGISTER_CALLBACKS == 1) -typedef struct __LPTIM_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_LPTIM_REGISTER_CALLBACKS */ -{ - LPTIM_TypeDef *Instance; /*!< Register base address */ - - LPTIM_InitTypeDef Init; /*!< LPTIM required parameters */ - - HAL_StatusTypeDef Status; /*!< LPTIM peripheral status */ - - HAL_LockTypeDef Lock; /*!< LPTIM locking object */ - - __IO HAL_LPTIM_StateTypeDef State; /*!< LPTIM peripheral state */ - -#if (USE_HAL_LPTIM_REGISTER_CALLBACKS == 1) - void (* MspInitCallback)(struct __LPTIM_HandleTypeDef *hlptim); /*!< LPTIM Base Msp Init Callback */ - void (* MspDeInitCallback)(struct __LPTIM_HandleTypeDef *hlptim); /*!< LPTIM Base Msp DeInit Callback */ - void (* CompareMatchCallback)(struct __LPTIM_HandleTypeDef *hlptim); /*!< Compare match Callback */ - void (* AutoReloadMatchCallback)(struct __LPTIM_HandleTypeDef *hlptim); /*!< Auto-reload match Callback */ - void (* TriggerCallback)(struct __LPTIM_HandleTypeDef *hlptim); /*!< External trigger event detection Callback */ - void (* CompareWriteCallback)(struct __LPTIM_HandleTypeDef *hlptim); /*!< Compare register write complete Callback */ - void (* AutoReloadWriteCallback)(struct __LPTIM_HandleTypeDef *hlptim); /*!< Auto-reload register write complete Callback */ - void (* DirectionUpCallback)(struct __LPTIM_HandleTypeDef *hlptim); /*!< Up-counting direction change Callback */ - void (* DirectionDownCallback)(struct __LPTIM_HandleTypeDef *hlptim); /*!< Down-counting direction change Callback */ -#endif /* USE_HAL_LPTIM_REGISTER_CALLBACKS */ -} LPTIM_HandleTypeDef; - -#if (USE_HAL_LPTIM_REGISTER_CALLBACKS == 1) -/** - * @brief HAL LPTIM Callback ID enumeration definition - */ -typedef enum -{ - HAL_LPTIM_MSPINIT_CB_ID = 0x00U, /*!< LPTIM Base Msp Init Callback ID */ - HAL_LPTIM_MSPDEINIT_CB_ID = 0x01U, /*!< LPTIM Base Msp DeInit Callback ID */ - HAL_LPTIM_COMPARE_MATCH_CB_ID = 0x02U, /*!< Compare match Callback ID */ - HAL_LPTIM_AUTORELOAD_MATCH_CB_ID = 0x03U, /*!< Auto-reload match Callback ID */ - HAL_LPTIM_TRIGGER_CB_ID = 0x04U, /*!< External trigger event detection Callback ID */ - HAL_LPTIM_COMPARE_WRITE_CB_ID = 0x05U, /*!< Compare register write complete Callback ID */ - HAL_LPTIM_AUTORELOAD_WRITE_CB_ID = 0x06U, /*!< Auto-reload register write complete Callback ID */ - HAL_LPTIM_DIRECTION_UP_CB_ID = 0x07U, /*!< Up-counting direction change Callback ID */ - HAL_LPTIM_DIRECTION_DOWN_CB_ID = 0x08U, /*!< Down-counting direction change Callback ID */ -} HAL_LPTIM_CallbackIDTypeDef; - -/** - * @brief HAL TIM Callback pointer definition - */ -typedef void (*pLPTIM_CallbackTypeDef)(LPTIM_HandleTypeDef *hlptim); /*!< pointer to the LPTIM callback function */ - -#endif /* USE_HAL_LPTIM_REGISTER_CALLBACKS */ -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup LPTIM_Exported_Constants LPTIM Exported Constants - * @{ - */ - -/** @defgroup LPTIM_Clock_Source LPTIM Clock Source - * @{ - */ -#define LPTIM_CLOCKSOURCE_APBCLOCK_LPOSC 0x00000000U -#define LPTIM_CLOCKSOURCE_ULPTIM LPTIM_CFGR_CKSEL -/** - * @} - */ - -/** @defgroup LPTIM_Clock_Prescaler LPTIM Clock Prescaler - * @{ - */ -#define LPTIM_PRESCALER_DIV1 0x00000000U -#define LPTIM_PRESCALER_DIV2 LPTIM_CFGR_PRESC_0 -#define LPTIM_PRESCALER_DIV4 LPTIM_CFGR_PRESC_1 -#define LPTIM_PRESCALER_DIV8 (LPTIM_CFGR_PRESC_0 | LPTIM_CFGR_PRESC_1) -#define LPTIM_PRESCALER_DIV16 LPTIM_CFGR_PRESC_2 -#define LPTIM_PRESCALER_DIV32 (LPTIM_CFGR_PRESC_0 | LPTIM_CFGR_PRESC_2) -#define LPTIM_PRESCALER_DIV64 (LPTIM_CFGR_PRESC_1 | LPTIM_CFGR_PRESC_2) -#define LPTIM_PRESCALER_DIV128 LPTIM_CFGR_PRESC -/** - * @} - */ - -/** @defgroup LPTIM_Output_Polarity LPTIM Output Polarity - * @{ - */ - -#define LPTIM_OUTPUTPOLARITY_HIGH 0x00000000U -#define LPTIM_OUTPUTPOLARITY_LOW LPTIM_CFGR_WAVPOL -/** - * @} - */ - -/** @defgroup LPTIM_Clock_Sample_Time LPTIM Clock Sample Time - * @{ - */ -#define LPTIM_CLOCKSAMPLETIME_DIRECTTRANSITION 0x00000000U -#define LPTIM_CLOCKSAMPLETIME_2TRANSITIONS LPTIM_CFGR_CKFLT_0 -#define LPTIM_CLOCKSAMPLETIME_4TRANSITIONS LPTIM_CFGR_CKFLT_1 -#define LPTIM_CLOCKSAMPLETIME_8TRANSITIONS LPTIM_CFGR_CKFLT -/** - * @} - */ - -/** @defgroup LPTIM_Clock_Polarity LPTIM Clock Polarity - * @{ - */ -#define LPTIM_CLOCKPOLARITY_RISING 0x00000000U -#define LPTIM_CLOCKPOLARITY_FALLING LPTIM_CFGR_CKPOL_0 -#define LPTIM_CLOCKPOLARITY_RISING_FALLING LPTIM_CFGR_CKPOL_1 -/** - * @} - */ - -/** @defgroup LPTIM_Trigger_Source LPTIM Trigger Source - * @{ - */ -#define LPTIM_TRIGSOURCE_SOFTWARE 0x0000FFFFU -#define LPTIM_TRIGSOURCE_0 0x00000000U -#define LPTIM_TRIGSOURCE_1 LPTIM_CFGR_TRIGSEL_0 -#define LPTIM_TRIGSOURCE_2 LPTIM_CFGR_TRIGSEL_1 -#define LPTIM_TRIGSOURCE_3 (LPTIM_CFGR_TRIGSEL_0 | LPTIM_CFGR_TRIGSEL_1) -#define LPTIM_TRIGSOURCE_4 LPTIM_CFGR_TRIGSEL_2 -#define LPTIM_TRIGSOURCE_5 (LPTIM_CFGR_TRIGSEL_0 | LPTIM_CFGR_TRIGSEL_2) -/** - * @} - */ - -/** @defgroup LPTIM_External_Trigger_Polarity LPTIM External Trigger Polarity - * @{ - */ -#define LPTIM_ACTIVEEDGE_RISING LPTIM_CFGR_TRIGEN_0 -#define LPTIM_ACTIVEEDGE_FALLING LPTIM_CFGR_TRIGEN_1 -#define LPTIM_ACTIVEEDGE_RISING_FALLING LPTIM_CFGR_TRIGEN -/** - * @} - */ - -/** @defgroup LPTIM_Trigger_Sample_Time LPTIM Trigger Sample Time - * @{ - */ -#define LPTIM_TRIGSAMPLETIME_DIRECTTRANSITION 0x00000000U -#define LPTIM_TRIGSAMPLETIME_2TRANSITIONS LPTIM_CFGR_TRGFLT_0 -#define LPTIM_TRIGSAMPLETIME_4TRANSITIONS LPTIM_CFGR_TRGFLT_1 -#define LPTIM_TRIGSAMPLETIME_8TRANSITIONS LPTIM_CFGR_TRGFLT -/** - * @} - */ - -/** @defgroup LPTIM_Updating_Mode LPTIM Updating Mode - * @{ - */ - -#define LPTIM_UPDATE_IMMEDIATE 0x00000000U -#define LPTIM_UPDATE_ENDOFPERIOD LPTIM_CFGR_PRELOAD -/** - * @} - */ - -/** @defgroup LPTIM_Counter_Source LPTIM Counter Source - * @{ - */ - -#define LPTIM_COUNTERSOURCE_INTERNAL 0x00000000U -#define LPTIM_COUNTERSOURCE_EXTERNAL LPTIM_CFGR_COUNTMODE -/** - * @} - */ - -/** @defgroup LPTIM_Flag_Definition LPTIM Flags Definition - * @{ - */ - -#define LPTIM_FLAG_DOWN LPTIM_ISR_DOWN -#define LPTIM_FLAG_UP LPTIM_ISR_UP -#define LPTIM_FLAG_ARROK LPTIM_ISR_ARROK -#define LPTIM_FLAG_CMPOK LPTIM_ISR_CMPOK -#define LPTIM_FLAG_EXTTRIG LPTIM_ISR_EXTTRIG -#define LPTIM_FLAG_ARRM LPTIM_ISR_ARRM -#define LPTIM_FLAG_CMPM LPTIM_ISR_CMPM -/** - * @} - */ - -/** @defgroup LPTIM_Interrupts_Definition LPTIM Interrupts Definition - * @{ - */ -#define LPTIM_IT_DOWN LPTIM_IER_DOWNIE -#define LPTIM_IT_UP LPTIM_IER_UPIE -#define LPTIM_IT_ARROK LPTIM_IER_ARROKIE -#define LPTIM_IT_CMPOK LPTIM_IER_CMPOKIE -#define LPTIM_IT_EXTTRIG LPTIM_IER_EXTTRIGIE -#define LPTIM_IT_ARRM LPTIM_IER_ARRMIE -#define LPTIM_IT_CMPM LPTIM_IER_CMPMIE -/** - * @} - */ - -/** @defgroup LPTIM_Option Register Definition - * @{ - */ -#define LPTIM_OP_PAD_AF 0x00000000U -#define LPTIM_OP_PAD_PA4 LPTIM_OR_LPT_IN1_RMP_0 -#define LPTIM_OP_PAD_PB9 LPTIM_OR_LPT_IN1_RMP_1 -#define LPTIM_OP_TIM_DAC LPTIM_OR_LPT_IN1_RMP -/** - * @} - */ - -/** - * @} - */ - -/* Exported macros -----------------------------------------------------------*/ -/** @defgroup LPTIM_Exported_Macros LPTIM Exported Macros - * @{ - */ - -/** @brief Reset LPTIM handle state. - * @param __HANDLE__ LPTIM handle - * @retval None - */ -#if (USE_HAL_LPTIM_REGISTER_CALLBACKS == 1) -#define __HAL_LPTIM_RESET_HANDLE_STATE(__HANDLE__) do { \ - (__HANDLE__)->State = HAL_LPTIM_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_LPTIM_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_LPTIM_STATE_RESET) -#endif /* USE_HAL_LPTIM_REGISTER_CALLBACKS */ - -/** - * @brief Enable the LPTIM peripheral. - * @param __HANDLE__ LPTIM handle - * @retval None - */ -#define __HAL_LPTIM_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= (LPTIM_CR_ENABLE)) - -/** - * @brief Disable the LPTIM peripheral. - * @param __HANDLE__ LPTIM handle - * @note The following sequence is required to solve LPTIM disable HW limitation. - * Please check Errata Sheet ES0335 for more details under "MCU may remain - * stuck in LPTIM interrupt when entering Stop mode" section. - * @note Please call @ref HAL_LPTIM_GetState() after a call to __HAL_LPTIM_DISABLE to - * check for TIMEOUT. - * @retval None - */ -#define __HAL_LPTIM_DISABLE(__HANDLE__) LPTIM_Disable(__HANDLE__) - -/** - * @brief Start the LPTIM peripheral in Continuous mode. - * @param __HANDLE__ LPTIM handle - * @retval None - */ -#define __HAL_LPTIM_START_CONTINUOUS(__HANDLE__) ((__HANDLE__)->Instance->CR |= LPTIM_CR_CNTSTRT) -/** - * @brief Start the LPTIM peripheral in single mode. - * @param __HANDLE__ LPTIM handle - * @retval None - */ -#define __HAL_LPTIM_START_SINGLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= LPTIM_CR_SNGSTRT) - -/** - * @brief Write the passed parameter in the Autoreload register. - * @param __HANDLE__ LPTIM handle - * @param __VALUE__ Autoreload value - * @retval None - * @note The ARR register can only be modified when the LPTIM instance is enabled. - */ -#define __HAL_LPTIM_AUTORELOAD_SET(__HANDLE__ , __VALUE__) ((__HANDLE__)->Instance->ARR = (__VALUE__)) - -/** - * @brief Write the passed parameter in the Compare register. - * @param __HANDLE__ LPTIM handle - * @param __VALUE__ Compare value - * @retval None - * @note The CMP register can only be modified when the LPTIM instance is enabled. - */ -#define __HAL_LPTIM_COMPARE_SET(__HANDLE__ , __VALUE__) ((__HANDLE__)->Instance->CMP = (__VALUE__)) - -/** - * @brief Check whether the specified LPTIM flag is set or not. - * @param __HANDLE__ LPTIM handle - * @param __FLAG__ LPTIM flag to check - * This parameter can be a value of: - * @arg LPTIM_FLAG_DOWN : Counter direction change up Flag. - * @arg LPTIM_FLAG_UP : Counter direction change down to up Flag. - * @arg LPTIM_FLAG_ARROK : Autoreload register update OK Flag. - * @arg LPTIM_FLAG_CMPOK : Compare register update OK Flag. - * @arg LPTIM_FLAG_EXTTRIG : External trigger edge event Flag. - * @arg LPTIM_FLAG_ARRM : Autoreload match Flag. - * @arg LPTIM_FLAG_CMPM : Compare match Flag. - * @retval The state of the specified flag (SET or RESET). - */ -#define __HAL_LPTIM_GET_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->ISR &(__FLAG__)) == (__FLAG__)) - -/** - * @brief Clear the specified LPTIM flag. - * @param __HANDLE__ LPTIM handle. - * @param __FLAG__ LPTIM flag to clear. - * This parameter can be a value of: - * @arg LPTIM_FLAG_DOWN : Counter direction change up Flag. - * @arg LPTIM_FLAG_UP : Counter direction change down to up Flag. - * @arg LPTIM_FLAG_ARROK : Autoreload register update OK Flag. - * @arg LPTIM_FLAG_CMPOK : Compare register update OK Flag. - * @arg LPTIM_FLAG_EXTTRIG : External trigger edge event Flag. - * @arg LPTIM_FLAG_ARRM : Autoreload match Flag. - * @arg LPTIM_FLAG_CMPM : Compare match Flag. - * @retval None. - */ -#define __HAL_LPTIM_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->ICR = (__FLAG__)) - -/** - * @brief Enable the specified LPTIM interrupt. - * @param __HANDLE__ LPTIM handle. - * @param __INTERRUPT__ LPTIM interrupt to set. - * This parameter can be a value of: - * @arg LPTIM_IT_DOWN : Counter direction change up Interrupt. - * @arg LPTIM_IT_UP : Counter direction change down to up Interrupt. - * @arg LPTIM_IT_ARROK : Autoreload register update OK Interrupt. - * @arg LPTIM_IT_CMPOK : Compare register update OK Interrupt. - * @arg LPTIM_IT_EXTTRIG : External trigger edge event Interrupt. - * @arg LPTIM_IT_ARRM : Autoreload match Interrupt. - * @arg LPTIM_IT_CMPM : Compare match Interrupt. - * @retval None. - * @note The LPTIM interrupts can only be enabled when the LPTIM instance is disabled. - */ -#define __HAL_LPTIM_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->IER |= (__INTERRUPT__)) - -/** - * @brief Disable the specified LPTIM interrupt. - * @param __HANDLE__ LPTIM handle. - * @param __INTERRUPT__ LPTIM interrupt to set. - * This parameter can be a value of: - * @arg LPTIM_IT_DOWN : Counter direction change up Interrupt. - * @arg LPTIM_IT_UP : Counter direction change down to up Interrupt. - * @arg LPTIM_IT_ARROK : Autoreload register update OK Interrupt. - * @arg LPTIM_IT_CMPOK : Compare register update OK Interrupt. - * @arg LPTIM_IT_EXTTRIG : External trigger edge event Interrupt. - * @arg LPTIM_IT_ARRM : Autoreload match Interrupt. - * @arg LPTIM_IT_CMPM : Compare match Interrupt. - * @retval None. - * @note The LPTIM interrupts can only be disabled when the LPTIM instance is disabled. - */ -#define __HAL_LPTIM_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->IER &= (~(__INTERRUPT__))) - -/** - * @brief Check whether the specified LPTIM interrupt source is enabled or not. - * @param __HANDLE__ LPTIM handle. - * @param __INTERRUPT__ LPTIM interrupt to check. - * This parameter can be a value of: - * @arg LPTIM_IT_DOWN : Counter direction change up Interrupt. - * @arg LPTIM_IT_UP : Counter direction change down to up Interrupt. - * @arg LPTIM_IT_ARROK : Autoreload register update OK Interrupt. - * @arg LPTIM_IT_CMPOK : Compare register update OK Interrupt. - * @arg LPTIM_IT_EXTTRIG : External trigger edge event Interrupt. - * @arg LPTIM_IT_ARRM : Autoreload match Interrupt. - * @arg LPTIM_IT_CMPM : Compare match Interrupt. - * @retval Interrupt status. - */ - -#define __HAL_LPTIM_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((((__HANDLE__)->Instance->IER\ - & (__INTERRUPT__)) == (__INTERRUPT__)) ? SET : RESET) - -/** @brief LPTIM Option Register - * @param __HANDLE__ LPTIM handle - * @param __VALUE__ This parameter can be a value of : - * @arg LPTIM_OP_PAD_AF - * @arg LPTIM_OP_PAD_PA4 - * @arg LPTIM_OP_PAD_PB9 - * @arg LPTIM_OP_TIM_DAC - * @retval None - */ -#define __HAL_LPTIM_OPTR_CONFIG(__HANDLE__ , __VALUE__) ((__HANDLE__)->Instance->OR = (__VALUE__)) - - -/** - * @brief Enable interrupt on the LPTIM Wake-up Timer associated Exti line. - * @retval None - */ -#define __HAL_LPTIM_WAKEUPTIMER_EXTI_ENABLE_IT() (EXTI->IMR\ - |= LPTIM_EXTI_LINE_WAKEUPTIMER_EVENT) - -/** - * @brief Disable interrupt on the LPTIM Wake-up Timer associated Exti line. - * @retval None - */ -#define __HAL_LPTIM_WAKEUPTIMER_EXTI_DISABLE_IT() (EXTI->IMR\ - &= ~(LPTIM_EXTI_LINE_WAKEUPTIMER_EVENT)) - -/** - * @brief Enable event on the LPTIM Wake-up Timer associated Exti line. - * @retval None. - */ -#define __HAL_LPTIM_WAKEUPTIMER_EXTI_ENABLE_EVENT() (EXTI->EMR\ - |= LPTIM_EXTI_LINE_WAKEUPTIMER_EVENT) - -/** - * @brief Disable event on the LPTIM Wake-up Timer associated Exti line. - * @retval None. - */ -#define __HAL_LPTIM_WAKEUPTIMER_EXTI_DISABLE_EVENT() (EXTI->EMR\ - &= ~(LPTIM_EXTI_LINE_WAKEUPTIMER_EVENT)) -#if defined(EXTI_IMR_MR23) - -/** - * @brief Enable falling edge trigger on the LPTIM Wake-up Timer associated Exti line. - * @retval None. - */ -#define __HAL_LPTIM_WAKEUPTIMER_EXTI_ENABLE_FALLING_EDGE() (EXTI->FTSR\ - |= LPTIM_EXTI_LINE_WAKEUPTIMER_EVENT) - -/** - * @brief Disable falling edge trigger on the LPTIM Wake-up Timer associated Exti line. - * @retval None. - */ -#define __HAL_LPTIM_WAKEUPTIMER_EXTI_DISABLE_FALLING_EDGE() (EXTI->FTSR\ - &= ~(LPTIM_EXTI_LINE_WAKEUPTIMER_EVENT)) - -/** - * @brief Enable rising edge trigger on the LPTIM Wake-up Timer associated Exti line. - * @retval None. - */ -#define __HAL_LPTIM_WAKEUPTIMER_EXTI_ENABLE_RISING_EDGE() (EXTI->RTSR\ - |= LPTIM_EXTI_LINE_WAKEUPTIMER_EVENT) - -/** - * @brief Disable rising edge trigger on the LPTIM Wake-up Timer associated Exti line. - * @retval None. - */ -#define __HAL_LPTIM_WAKEUPTIMER_EXTI_DISABLE_RISING_EDGE() (EXTI->RTSR\ - &= ~(LPTIM_EXTI_LINE_WAKEUPTIMER_EVENT)) - -/** - * @brief Enable rising & falling edge trigger on the LPTIM Wake-up Timer associated Exti line. - * @retval None. - */ -#define __HAL_LPTIM_WAKEUPTIMER_EXTI_ENABLE_RISING_FALLING_EDGE() do{__HAL_LPTIM_WAKEUPTIMER_EXTI_ENABLE_RISING_EDGE();\ - __HAL_LPTIM_WAKEUPTIMER_EXTI_ENABLE_FALLING_EDGE();\ - }while(0) - -/** - * @brief Disable rising & falling edge trigger on the LPTIM Wake-up Timer associated Exti line. - * @retval None. - */ -#define __HAL_LPTIM_WAKEUPTIMER_EXTI_DISABLE_RISING_FALLING_EDGE() do{__HAL_LPTIM_WAKEUPTIMER_EXTI_DISABLE_RISING_EDGE();\ - __HAL_LPTIM_WAKEUPTIMER_EXTI_DISABLE_FALLING_EDGE();\ - }while(0) - -/** - * @brief Check whether the LPTIM Wake-up Timer associated Exti line interrupt flag is set or not. - * @retval Line Status. - */ -#define __HAL_LPTIM_WAKEUPTIMER_EXTI_GET_FLAG() (EXTI->PR\ - & LPTIM_EXTI_LINE_WAKEUPTIMER_EVENT) - -/** - * @brief Clear the LPTIM Wake-up Timer associated Exti line flag. - * @retval None. - */ -#define __HAL_LPTIM_WAKEUPTIMER_EXTI_CLEAR_FLAG() (EXTI->PR\ - = LPTIM_EXTI_LINE_WAKEUPTIMER_EVENT) - -/** - * @brief Generate a Software interrupt on the LPTIM Wake-up Timer associated Exti line. - * @retval None. - */ -#define __HAL_LPTIM_WAKEUPTIMER_EXTI_GENERATE_SWIT() (EXTI->SWIER\ - |= LPTIM_EXTI_LINE_WAKEUPTIMER_EVENT) -#endif /* EXTI_IMR_MR23 */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup LPTIM_Exported_Functions LPTIM Exported Functions - * @{ - */ - -/** @addtogroup LPTIM_Exported_Functions_Group1 - * @brief Initialization and Configuration functions. - * @{ - */ -/* Initialization/de-initialization functions ********************************/ -HAL_StatusTypeDef HAL_LPTIM_Init(LPTIM_HandleTypeDef *hlptim); -HAL_StatusTypeDef HAL_LPTIM_DeInit(LPTIM_HandleTypeDef *hlptim); - -/* MSP functions *************************************************************/ -void HAL_LPTIM_MspInit(LPTIM_HandleTypeDef *hlptim); -void HAL_LPTIM_MspDeInit(LPTIM_HandleTypeDef *hlptim); -/** - * @} - */ - -/** @addtogroup LPTIM_Exported_Functions_Group2 - * @brief Start-Stop operation functions. - * @{ - */ -/* Start/Stop operation functions *********************************************/ -/* ################################# PWM Mode ################################*/ -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_LPTIM_PWM_Start(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Pulse); -HAL_StatusTypeDef HAL_LPTIM_PWM_Stop(LPTIM_HandleTypeDef *hlptim); -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_LPTIM_PWM_Start_IT(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Pulse); -HAL_StatusTypeDef HAL_LPTIM_PWM_Stop_IT(LPTIM_HandleTypeDef *hlptim); - -/* ############################# One Pulse Mode ##############################*/ -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_LPTIM_OnePulse_Start(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Pulse); -HAL_StatusTypeDef HAL_LPTIM_OnePulse_Stop(LPTIM_HandleTypeDef *hlptim); -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_LPTIM_OnePulse_Start_IT(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Pulse); -HAL_StatusTypeDef HAL_LPTIM_OnePulse_Stop_IT(LPTIM_HandleTypeDef *hlptim); - -/* ############################## Set once Mode ##############################*/ -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_LPTIM_SetOnce_Start(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Pulse); -HAL_StatusTypeDef HAL_LPTIM_SetOnce_Stop(LPTIM_HandleTypeDef *hlptim); -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_LPTIM_SetOnce_Start_IT(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Pulse); -HAL_StatusTypeDef HAL_LPTIM_SetOnce_Stop_IT(LPTIM_HandleTypeDef *hlptim); - -/* ############################### Encoder Mode ##############################*/ -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_LPTIM_Encoder_Start(LPTIM_HandleTypeDef *hlptim, uint32_t Period); -HAL_StatusTypeDef HAL_LPTIM_Encoder_Stop(LPTIM_HandleTypeDef *hlptim); -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_LPTIM_Encoder_Start_IT(LPTIM_HandleTypeDef *hlptim, uint32_t Period); -HAL_StatusTypeDef HAL_LPTIM_Encoder_Stop_IT(LPTIM_HandleTypeDef *hlptim); - -/* ############################# Time out Mode ##############################*/ -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_LPTIM_TimeOut_Start(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Timeout); -HAL_StatusTypeDef HAL_LPTIM_TimeOut_Stop(LPTIM_HandleTypeDef *hlptim); -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_LPTIM_TimeOut_Start_IT(LPTIM_HandleTypeDef *hlptim, uint32_t Period, uint32_t Timeout); -HAL_StatusTypeDef HAL_LPTIM_TimeOut_Stop_IT(LPTIM_HandleTypeDef *hlptim); - -/* ############################## Counter Mode ###############################*/ -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_LPTIM_Counter_Start(LPTIM_HandleTypeDef *hlptim, uint32_t Period); -HAL_StatusTypeDef HAL_LPTIM_Counter_Stop(LPTIM_HandleTypeDef *hlptim); -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_LPTIM_Counter_Start_IT(LPTIM_HandleTypeDef *hlptim, uint32_t Period); -HAL_StatusTypeDef HAL_LPTIM_Counter_Stop_IT(LPTIM_HandleTypeDef *hlptim); -/** - * @} - */ - -/** @addtogroup LPTIM_Exported_Functions_Group3 - * @brief Read operation functions. - * @{ - */ -/* Reading operation functions ************************************************/ -uint32_t HAL_LPTIM_ReadCounter(LPTIM_HandleTypeDef *hlptim); -uint32_t HAL_LPTIM_ReadAutoReload(LPTIM_HandleTypeDef *hlptim); -uint32_t HAL_LPTIM_ReadCompare(LPTIM_HandleTypeDef *hlptim); -/** - * @} - */ - -/** @addtogroup LPTIM_Exported_Functions_Group4 - * @brief LPTIM IRQ handler and callback functions. - * @{ - */ -/* LPTIM IRQ functions *******************************************************/ -void HAL_LPTIM_IRQHandler(LPTIM_HandleTypeDef *hlptim); - -/* CallBack functions ********************************************************/ -void HAL_LPTIM_CompareMatchCallback(LPTIM_HandleTypeDef *hlptim); -void HAL_LPTIM_AutoReloadMatchCallback(LPTIM_HandleTypeDef *hlptim); -void HAL_LPTIM_TriggerCallback(LPTIM_HandleTypeDef *hlptim); -void HAL_LPTIM_CompareWriteCallback(LPTIM_HandleTypeDef *hlptim); -void HAL_LPTIM_AutoReloadWriteCallback(LPTIM_HandleTypeDef *hlptim); -void HAL_LPTIM_DirectionUpCallback(LPTIM_HandleTypeDef *hlptim); -void HAL_LPTIM_DirectionDownCallback(LPTIM_HandleTypeDef *hlptim); - -/* Callbacks Register/UnRegister functions ***********************************/ -#if (USE_HAL_LPTIM_REGISTER_CALLBACKS == 1) -HAL_StatusTypeDef HAL_LPTIM_RegisterCallback(LPTIM_HandleTypeDef *lphtim, HAL_LPTIM_CallbackIDTypeDef CallbackID, - pLPTIM_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_LPTIM_UnRegisterCallback(LPTIM_HandleTypeDef *lphtim, HAL_LPTIM_CallbackIDTypeDef CallbackID); -#endif /* USE_HAL_LPTIM_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @addtogroup LPTIM_Group5 - * @brief Peripheral State functions. - * @{ - */ -/* Peripheral State functions ************************************************/ -HAL_LPTIM_StateTypeDef HAL_LPTIM_GetState(LPTIM_HandleTypeDef *hlptim); -/** - * @} - */ - -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/** @defgroup LPTIM_Private_Types LPTIM Private Types - * @{ - */ - -/** - * @} - */ - -/* Private variables ---------------------------------------------------------*/ -/** @defgroup LPTIM_Private_Variables LPTIM Private Variables - * @{ - */ - -/** - * @} - */ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup LPTIM_Private_Constants LPTIM Private Constants - * @{ - */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup LPTIM_Private_Macros LPTIM Private Macros - * @{ - */ - -#define IS_LPTIM_CLOCK_SOURCE(__SOURCE__) (((__SOURCE__) == LPTIM_CLOCKSOURCE_ULPTIM) || \ - ((__SOURCE__) == LPTIM_CLOCKSOURCE_APBCLOCK_LPOSC)) - - -#define IS_LPTIM_CLOCK_PRESCALER(__PRESCALER__) (((__PRESCALER__) == LPTIM_PRESCALER_DIV1 ) || \ - ((__PRESCALER__) == LPTIM_PRESCALER_DIV2 ) || \ - ((__PRESCALER__) == LPTIM_PRESCALER_DIV4 ) || \ - ((__PRESCALER__) == LPTIM_PRESCALER_DIV8 ) || \ - ((__PRESCALER__) == LPTIM_PRESCALER_DIV16 ) || \ - ((__PRESCALER__) == LPTIM_PRESCALER_DIV32 ) || \ - ((__PRESCALER__) == LPTIM_PRESCALER_DIV64 ) || \ - ((__PRESCALER__) == LPTIM_PRESCALER_DIV128)) - -#define IS_LPTIM_CLOCK_PRESCALERDIV1(__PRESCALER__) ((__PRESCALER__) == LPTIM_PRESCALER_DIV1) - -#define IS_LPTIM_OUTPUT_POLARITY(__POLARITY__) (((__POLARITY__) == LPTIM_OUTPUTPOLARITY_LOW ) || \ - ((__POLARITY__) == LPTIM_OUTPUTPOLARITY_HIGH)) - -#define IS_LPTIM_CLOCK_SAMPLE_TIME(__SAMPLETIME__) (((__SAMPLETIME__) == LPTIM_CLOCKSAMPLETIME_DIRECTTRANSITION) || \ - ((__SAMPLETIME__) == LPTIM_CLOCKSAMPLETIME_2TRANSITIONS) || \ - ((__SAMPLETIME__) == LPTIM_CLOCKSAMPLETIME_4TRANSITIONS) || \ - ((__SAMPLETIME__) == LPTIM_CLOCKSAMPLETIME_8TRANSITIONS)) - -#define IS_LPTIM_CLOCK_POLARITY(__POLARITY__) (((__POLARITY__) == LPTIM_CLOCKPOLARITY_RISING) || \ - ((__POLARITY__) == LPTIM_CLOCKPOLARITY_FALLING) || \ - ((__POLARITY__) == LPTIM_CLOCKPOLARITY_RISING_FALLING)) - -#define IS_LPTIM_TRG_SOURCE(__TRIG__) (((__TRIG__) == LPTIM_TRIGSOURCE_SOFTWARE) || \ - ((__TRIG__) == LPTIM_TRIGSOURCE_0) || \ - ((__TRIG__) == LPTIM_TRIGSOURCE_1) || \ - ((__TRIG__) == LPTIM_TRIGSOURCE_2) || \ - ((__TRIG__) == LPTIM_TRIGSOURCE_3) || \ - ((__TRIG__) == LPTIM_TRIGSOURCE_4) || \ - ((__TRIG__) == LPTIM_TRIGSOURCE_5)) - -#define IS_LPTIM_EXT_TRG_POLARITY(__POLARITY__) (((__POLARITY__) == LPTIM_ACTIVEEDGE_RISING ) || \ - ((__POLARITY__) == LPTIM_ACTIVEEDGE_FALLING ) || \ - ((__POLARITY__) == LPTIM_ACTIVEEDGE_RISING_FALLING )) - -#define IS_LPTIM_TRIG_SAMPLE_TIME(__SAMPLETIME__) (((__SAMPLETIME__) == LPTIM_TRIGSAMPLETIME_DIRECTTRANSITION) || \ - ((__SAMPLETIME__) == LPTIM_TRIGSAMPLETIME_2TRANSITIONS ) || \ - ((__SAMPLETIME__) == LPTIM_TRIGSAMPLETIME_4TRANSITIONS ) || \ - ((__SAMPLETIME__) == LPTIM_TRIGSAMPLETIME_8TRANSITIONS )) - -#define IS_LPTIM_UPDATE_MODE(__MODE__) (((__MODE__) == LPTIM_UPDATE_IMMEDIATE) || \ - ((__MODE__) == LPTIM_UPDATE_ENDOFPERIOD)) - -#define IS_LPTIM_COUNTER_SOURCE(__SOURCE__) (((__SOURCE__) == LPTIM_COUNTERSOURCE_INTERNAL) || \ - ((__SOURCE__) == LPTIM_COUNTERSOURCE_EXTERNAL)) - -#define IS_LPTIM_AUTORELOAD(__AUTORELOAD__) ((__AUTORELOAD__) <= 0x0000FFFFUL) - -#define IS_LPTIM_COMPARE(__COMPARE__) ((__COMPARE__) <= 0x0000FFFFUL) - -#define IS_LPTIM_PERIOD(__PERIOD__) ((__PERIOD__) <= 0x0000FFFFUL) - -#define IS_LPTIM_PULSE(__PULSE__) ((__PULSE__) <= 0x0000FFFFUL) - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup LPTIM_Private_Functions LPTIM Private Functions - * @{ - */ -void LPTIM_Disable(LPTIM_HandleTypeDef *hlptim); -/** - * @} - */ - -/** - * @} - */ - -#endif /* LPTIM1 */ -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_HAL_LPTIM_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_ltdc.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_ltdc.h deleted file mode 100644 index 0cab844..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_ltdc.h +++ /dev/null @@ -1,688 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_ltdc.h - * @author MCD Application Team - * @brief Header file of LTDC HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_LTDC_H -#define STM32F4xx_HAL_LTDC_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -#if defined (LTDC) - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup LTDC LTDC - * @brief LTDC HAL module driver - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup LTDC_Exported_Types LTDC Exported Types - * @{ - */ -#define MAX_LAYER 2U - -/** - * @brief LTDC color structure definition - */ -typedef struct -{ - uint8_t Blue; /*!< Configures the blue value. - This parameter must be a number between Min_Data = 0x00 and Max_Data = 0xFF. */ - - uint8_t Green; /*!< Configures the green value. - This parameter must be a number between Min_Data = 0x00 and Max_Data = 0xFF. */ - - uint8_t Red; /*!< Configures the red value. - This parameter must be a number between Min_Data = 0x00 and Max_Data = 0xFF. */ - - uint8_t Reserved; /*!< Reserved 0xFF */ -} LTDC_ColorTypeDef; - -/** - * @brief LTDC Init structure definition - */ -typedef struct -{ - uint32_t HSPolarity; /*!< configures the horizontal synchronization polarity. - This parameter can be one value of @ref LTDC_HS_POLARITY */ - - uint32_t VSPolarity; /*!< configures the vertical synchronization polarity. - This parameter can be one value of @ref LTDC_VS_POLARITY */ - - uint32_t DEPolarity; /*!< configures the data enable polarity. - This parameter can be one of value of @ref LTDC_DE_POLARITY */ - - uint32_t PCPolarity; /*!< configures the pixel clock polarity. - This parameter can be one of value of @ref LTDC_PC_POLARITY */ - - uint32_t HorizontalSync; /*!< configures the number of Horizontal synchronization width. - This parameter must be a number between Min_Data = 0x000 and Max_Data = 0xFFF. */ - - uint32_t VerticalSync; /*!< configures the number of Vertical synchronization height. - This parameter must be a number between Min_Data = 0x000 and Max_Data = 0x7FF. */ - - uint32_t AccumulatedHBP; /*!< configures the accumulated horizontal back porch width. - This parameter must be a number between Min_Data = LTDC_HorizontalSync and Max_Data = 0xFFF. */ - - uint32_t AccumulatedVBP; /*!< configures the accumulated vertical back porch height. - This parameter must be a number between Min_Data = LTDC_VerticalSync and Max_Data = 0x7FF. */ - - uint32_t AccumulatedActiveW; /*!< configures the accumulated active width. - This parameter must be a number between Min_Data = LTDC_AccumulatedHBP and Max_Data = 0xFFF. */ - - uint32_t AccumulatedActiveH; /*!< configures the accumulated active height. - This parameter must be a number between Min_Data = LTDC_AccumulatedVBP and Max_Data = 0x7FF. */ - - uint32_t TotalWidth; /*!< configures the total width. - This parameter must be a number between Min_Data = LTDC_AccumulatedActiveW and Max_Data = 0xFFF. */ - - uint32_t TotalHeigh; /*!< configures the total height. - This parameter must be a number between Min_Data = LTDC_AccumulatedActiveH and Max_Data = 0x7FF. */ - - LTDC_ColorTypeDef Backcolor; /*!< Configures the background color. */ -} LTDC_InitTypeDef; - -/** - * @brief LTDC Layer structure definition - */ -typedef struct -{ - uint32_t WindowX0; /*!< Configures the Window Horizontal Start Position. - This parameter must be a number between Min_Data = 0x000 and Max_Data = 0xFFF. */ - - uint32_t WindowX1; /*!< Configures the Window Horizontal Stop Position. - This parameter must be a number between Min_Data = 0x000 and Max_Data = 0xFFF. */ - - uint32_t WindowY0; /*!< Configures the Window vertical Start Position. - This parameter must be a number between Min_Data = 0x000 and Max_Data = 0x7FF. */ - - uint32_t WindowY1; /*!< Configures the Window vertical Stop Position. - This parameter must be a number between Min_Data = 0x0000 and Max_Data = 0x7FF. */ - - uint32_t PixelFormat; /*!< Specifies the pixel format. - This parameter can be one of value of @ref LTDC_Pixelformat */ - - uint32_t Alpha; /*!< Specifies the constant alpha used for blending. - This parameter must be a number between Min_Data = 0x00 and Max_Data = 0xFF. */ - - uint32_t Alpha0; /*!< Configures the default alpha value. - This parameter must be a number between Min_Data = 0x00 and Max_Data = 0xFF. */ - - uint32_t BlendingFactor1; /*!< Select the blending factor 1. - This parameter can be one of value of @ref LTDC_BlendingFactor1 */ - - uint32_t BlendingFactor2; /*!< Select the blending factor 2. - This parameter can be one of value of @ref LTDC_BlendingFactor2 */ - - uint32_t FBStartAdress; /*!< Configures the color frame buffer address */ - - uint32_t ImageWidth; /*!< Configures the color frame buffer line length. - This parameter must be a number between Min_Data = 0x0000 and Max_Data = 0x1FFF. */ - - uint32_t ImageHeight; /*!< Specifies the number of line in frame buffer. - This parameter must be a number between Min_Data = 0x000 and Max_Data = 0x7FF. */ - - LTDC_ColorTypeDef Backcolor; /*!< Configures the layer background color. */ -} LTDC_LayerCfgTypeDef; - -/** - * @brief HAL LTDC State structures definition - */ -typedef enum -{ - HAL_LTDC_STATE_RESET = 0x00U, /*!< LTDC not yet initialized or disabled */ - HAL_LTDC_STATE_READY = 0x01U, /*!< LTDC initialized and ready for use */ - HAL_LTDC_STATE_BUSY = 0x02U, /*!< LTDC internal process is ongoing */ - HAL_LTDC_STATE_TIMEOUT = 0x03U, /*!< LTDC Timeout state */ - HAL_LTDC_STATE_ERROR = 0x04U /*!< LTDC state error */ -} HAL_LTDC_StateTypeDef; - -/** - * @brief LTDC handle Structure definition - */ -#if (USE_HAL_LTDC_REGISTER_CALLBACKS == 1) -typedef struct __LTDC_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_LTDC_REGISTER_CALLBACKS */ -{ - LTDC_TypeDef *Instance; /*!< LTDC Register base address */ - - LTDC_InitTypeDef Init; /*!< LTDC parameters */ - - LTDC_LayerCfgTypeDef LayerCfg[MAX_LAYER]; /*!< LTDC Layers parameters */ - - HAL_LockTypeDef Lock; /*!< LTDC Lock */ - - __IO HAL_LTDC_StateTypeDef State; /*!< LTDC state */ - - __IO uint32_t ErrorCode; /*!< LTDC Error code */ - -#if (USE_HAL_LTDC_REGISTER_CALLBACKS == 1) - void (* LineEventCallback)(struct __LTDC_HandleTypeDef *hltdc); /*!< LTDC Line Event Callback */ - void (* ReloadEventCallback)(struct __LTDC_HandleTypeDef *hltdc); /*!< LTDC Reload Event Callback */ - void (* ErrorCallback)(struct __LTDC_HandleTypeDef *hltdc); /*!< LTDC Error Callback */ - - void (* MspInitCallback)(struct __LTDC_HandleTypeDef *hltdc); /*!< LTDC Msp Init callback */ - void (* MspDeInitCallback)(struct __LTDC_HandleTypeDef *hltdc); /*!< LTDC Msp DeInit callback */ - -#endif /* USE_HAL_LTDC_REGISTER_CALLBACKS */ - - -} LTDC_HandleTypeDef; - -#if (USE_HAL_LTDC_REGISTER_CALLBACKS == 1) -/** - * @brief HAL LTDC Callback ID enumeration definition - */ -typedef enum -{ - HAL_LTDC_MSPINIT_CB_ID = 0x00U, /*!< LTDC MspInit callback ID */ - HAL_LTDC_MSPDEINIT_CB_ID = 0x01U, /*!< LTDC MspDeInit callback ID */ - - HAL_LTDC_LINE_EVENT_CB_ID = 0x02U, /*!< LTDC Line Event Callback ID */ - HAL_LTDC_RELOAD_EVENT_CB_ID = 0x03U, /*!< LTDC Reload Callback ID */ - HAL_LTDC_ERROR_CB_ID = 0x04U /*!< LTDC Error Callback ID */ - -} HAL_LTDC_CallbackIDTypeDef; - -/** - * @brief HAL LTDC Callback pointer definition - */ -typedef void (*pLTDC_CallbackTypeDef)(LTDC_HandleTypeDef *hltdc); /*!< pointer to an LTDC callback function */ - -#endif /* USE_HAL_LTDC_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup LTDC_Exported_Constants LTDC Exported Constants - * @{ - */ - -/** @defgroup LTDC_Error_Code LTDC Error Code - * @{ - */ -#define HAL_LTDC_ERROR_NONE 0x00000000U /*!< LTDC No error */ -#define HAL_LTDC_ERROR_TE 0x00000001U /*!< LTDC Transfer error */ -#define HAL_LTDC_ERROR_FU 0x00000002U /*!< LTDC FIFO Underrun */ -#define HAL_LTDC_ERROR_TIMEOUT 0x00000020U /*!< LTDC Timeout error */ -#if (USE_HAL_LTDC_REGISTER_CALLBACKS == 1) -#define HAL_LTDC_ERROR_INVALID_CALLBACK 0x00000040U /*!< LTDC Invalid Callback error */ -#endif /* USE_HAL_LTDC_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @defgroup LTDC_Layer LTDC Layer - * @{ - */ -#define LTDC_LAYER_1 0x00000000U /*!< LTDC Layer 1 */ -#define LTDC_LAYER_2 0x00000001U /*!< LTDC Layer 2 */ -/** - * @} - */ - -/** @defgroup LTDC_HS_POLARITY LTDC HS POLARITY - * @{ - */ -#define LTDC_HSPOLARITY_AL 0x00000000U /*!< Horizontal Synchronization is active low. */ -#define LTDC_HSPOLARITY_AH LTDC_GCR_HSPOL /*!< Horizontal Synchronization is active high. */ -/** - * @} - */ - -/** @defgroup LTDC_VS_POLARITY LTDC VS POLARITY - * @{ - */ -#define LTDC_VSPOLARITY_AL 0x00000000U /*!< Vertical Synchronization is active low. */ -#define LTDC_VSPOLARITY_AH LTDC_GCR_VSPOL /*!< Vertical Synchronization is active high. */ -/** - * @} - */ - -/** @defgroup LTDC_DE_POLARITY LTDC DE POLARITY - * @{ - */ -#define LTDC_DEPOLARITY_AL 0x00000000U /*!< Data Enable, is active low. */ -#define LTDC_DEPOLARITY_AH LTDC_GCR_DEPOL /*!< Data Enable, is active high. */ -/** - * @} - */ - -/** @defgroup LTDC_PC_POLARITY LTDC PC POLARITY - * @{ - */ -#define LTDC_PCPOLARITY_IPC 0x00000000U /*!< input pixel clock. */ -#define LTDC_PCPOLARITY_IIPC LTDC_GCR_PCPOL /*!< inverted input pixel clock. */ -/** - * @} - */ - -/** @defgroup LTDC_SYNC LTDC SYNC - * @{ - */ -#define LTDC_HORIZONTALSYNC (LTDC_SSCR_HSW >> 16U) /*!< Horizontal synchronization width. */ -#define LTDC_VERTICALSYNC LTDC_SSCR_VSH /*!< Vertical synchronization height. */ -/** - * @} - */ - -/** @defgroup LTDC_BACK_COLOR LTDC BACK COLOR - * @{ - */ -#define LTDC_COLOR 0x000000FFU /*!< Color mask */ -/** - * @} - */ - -/** @defgroup LTDC_BlendingFactor1 LTDC Blending Factor1 - * @{ - */ -#define LTDC_BLENDING_FACTOR1_CA 0x00000400U /*!< Blending factor : Cte Alpha */ -#define LTDC_BLENDING_FACTOR1_PAxCA 0x00000600U /*!< Blending factor : Cte Alpha x Pixel Alpha*/ -/** - * @} - */ - -/** @defgroup LTDC_BlendingFactor2 LTDC Blending Factor2 - * @{ - */ -#define LTDC_BLENDING_FACTOR2_CA 0x00000005U /*!< Blending factor : Cte Alpha */ -#define LTDC_BLENDING_FACTOR2_PAxCA 0x00000007U /*!< Blending factor : Cte Alpha x Pixel Alpha*/ -/** - * @} - */ - -/** @defgroup LTDC_Pixelformat LTDC Pixel format - * @{ - */ -#define LTDC_PIXEL_FORMAT_ARGB8888 0x00000000U /*!< ARGB8888 LTDC pixel format */ -#define LTDC_PIXEL_FORMAT_RGB888 0x00000001U /*!< RGB888 LTDC pixel format */ -#define LTDC_PIXEL_FORMAT_RGB565 0x00000002U /*!< RGB565 LTDC pixel format */ -#define LTDC_PIXEL_FORMAT_ARGB1555 0x00000003U /*!< ARGB1555 LTDC pixel format */ -#define LTDC_PIXEL_FORMAT_ARGB4444 0x00000004U /*!< ARGB4444 LTDC pixel format */ -#define LTDC_PIXEL_FORMAT_L8 0x00000005U /*!< L8 LTDC pixel format */ -#define LTDC_PIXEL_FORMAT_AL44 0x00000006U /*!< AL44 LTDC pixel format */ -#define LTDC_PIXEL_FORMAT_AL88 0x00000007U /*!< AL88 LTDC pixel format */ -/** - * @} - */ - -/** @defgroup LTDC_Alpha LTDC Alpha - * @{ - */ -#define LTDC_ALPHA LTDC_LxCACR_CONSTA /*!< LTDC Constant Alpha mask */ -/** - * @} - */ - -/** @defgroup LTDC_LAYER_Config LTDC LAYER Config - * @{ - */ -#define LTDC_STOPPOSITION (LTDC_LxWHPCR_WHSPPOS >> 16U) /*!< LTDC Layer stop position */ -#define LTDC_STARTPOSITION LTDC_LxWHPCR_WHSTPOS /*!< LTDC Layer start position */ - -#define LTDC_COLOR_FRAME_BUFFER LTDC_LxCFBLR_CFBLL /*!< LTDC Layer Line length */ -#define LTDC_LINE_NUMBER LTDC_LxCFBLNR_CFBLNBR /*!< LTDC Layer Line number */ -/** - * @} - */ - -/** @defgroup LTDC_Interrupts LTDC Interrupts - * @{ - */ -#define LTDC_IT_LI LTDC_IER_LIE /*!< LTDC Line Interrupt */ -#define LTDC_IT_FU LTDC_IER_FUIE /*!< LTDC FIFO Underrun Interrupt */ -#define LTDC_IT_TE LTDC_IER_TERRIE /*!< LTDC Transfer Error Interrupt */ -#define LTDC_IT_RR LTDC_IER_RRIE /*!< LTDC Register Reload Interrupt */ -/** - * @} - */ - -/** @defgroup LTDC_Flags LTDC Flags - * @{ - */ -#define LTDC_FLAG_LI LTDC_ISR_LIF /*!< LTDC Line Interrupt Flag */ -#define LTDC_FLAG_FU LTDC_ISR_FUIF /*!< LTDC FIFO Underrun interrupt Flag */ -#define LTDC_FLAG_TE LTDC_ISR_TERRIF /*!< LTDC Transfer Error interrupt Flag */ -#define LTDC_FLAG_RR LTDC_ISR_RRIF /*!< LTDC Register Reload interrupt Flag */ -/** - * @} - */ - -/** @defgroup LTDC_Reload_Type LTDC Reload Type - * @{ - */ -#define LTDC_RELOAD_IMMEDIATE LTDC_SRCR_IMR /*!< Immediate Reload */ -#define LTDC_RELOAD_VERTICAL_BLANKING LTDC_SRCR_VBR /*!< Vertical Blanking Reload */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup LTDC_Exported_Macros LTDC Exported Macros - * @{ - */ - -/** @brief Reset LTDC handle state. - * @param __HANDLE__ LTDC handle - * @retval None - */ -#if (USE_HAL_LTDC_REGISTER_CALLBACKS == 1) -#define __HAL_LTDC_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->State = HAL_LTDC_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_LTDC_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_LTDC_STATE_RESET) -#endif /*USE_HAL_LTDC_REGISTER_CALLBACKS */ - -/** - * @brief Enable the LTDC. - * @param __HANDLE__ LTDC handle - * @retval None. - */ -#define __HAL_LTDC_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->GCR |= LTDC_GCR_LTDCEN) - -/** - * @brief Disable the LTDC. - * @param __HANDLE__ LTDC handle - * @retval None. - */ -#define __HAL_LTDC_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->GCR &= ~(LTDC_GCR_LTDCEN)) - -/** - * @brief Enable the LTDC Layer. - * @param __HANDLE__ LTDC handle - * @param __LAYER__ Specify the layer to be enabled. - * This parameter can be LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1). - * @retval None. - */ -#define __HAL_LTDC_LAYER_ENABLE(__HANDLE__, __LAYER__) ((LTDC_LAYER((__HANDLE__), (__LAYER__)))->CR |= (uint32_t)LTDC_LxCR_LEN) - -/** - * @brief Disable the LTDC Layer. - * @param __HANDLE__ LTDC handle - * @param __LAYER__ Specify the layer to be disabled. - * This parameter can be LTDC_LAYER_1 (0) or LTDC_LAYER_2 (1). - * @retval None. - */ -#define __HAL_LTDC_LAYER_DISABLE(__HANDLE__, __LAYER__) ((LTDC_LAYER((__HANDLE__), (__LAYER__)))->CR &= ~(uint32_t)LTDC_LxCR_LEN) - -/** - * @brief Reload immediately all LTDC Layers. - * @param __HANDLE__ LTDC handle - * @retval None. - */ -#define __HAL_LTDC_RELOAD_IMMEDIATE_CONFIG(__HANDLE__) ((__HANDLE__)->Instance->SRCR |= LTDC_SRCR_IMR) - -/** - * @brief Reload during vertical blanking period all LTDC Layers. - * @param __HANDLE__ LTDC handle - * @retval None. - */ -#define __HAL_LTDC_VERTICAL_BLANKING_RELOAD_CONFIG(__HANDLE__) ((__HANDLE__)->Instance->SRCR |= LTDC_SRCR_VBR) - -/* Interrupt & Flag management */ -/** - * @brief Get the LTDC pending flags. - * @param __HANDLE__ LTDC handle - * @param __FLAG__ Get the specified flag. - * This parameter can be any combination of the following values: - * @arg LTDC_FLAG_LI: Line Interrupt flag - * @arg LTDC_FLAG_FU: FIFO Underrun Interrupt flag - * @arg LTDC_FLAG_TE: Transfer Error interrupt flag - * @arg LTDC_FLAG_RR: Register Reload Interrupt Flag - * @retval The state of FLAG (SET or RESET). - */ -#define __HAL_LTDC_GET_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->ISR & (__FLAG__)) - -/** - * @brief Clears the LTDC pending flags. - * @param __HANDLE__ LTDC handle - * @param __FLAG__ Specify the flag to clear. - * This parameter can be any combination of the following values: - * @arg LTDC_FLAG_LI: Line Interrupt flag - * @arg LTDC_FLAG_FU: FIFO Underrun Interrupt flag - * @arg LTDC_FLAG_TE: Transfer Error interrupt flag - * @arg LTDC_FLAG_RR: Register Reload Interrupt Flag - * @retval None - */ -#define __HAL_LTDC_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->ICR = (__FLAG__)) - -/** - * @brief Enables the specified LTDC interrupts. - * @param __HANDLE__ LTDC handle - * @param __INTERRUPT__ Specify the LTDC interrupt sources to be enabled. - * This parameter can be any combination of the following values: - * @arg LTDC_IT_LI: Line Interrupt flag - * @arg LTDC_IT_FU: FIFO Underrun Interrupt flag - * @arg LTDC_IT_TE: Transfer Error interrupt flag - * @arg LTDC_IT_RR: Register Reload Interrupt Flag - * @retval None - */ -#define __HAL_LTDC_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->IER |= (__INTERRUPT__)) - -/** - * @brief Disables the specified LTDC interrupts. - * @param __HANDLE__ LTDC handle - * @param __INTERRUPT__ Specify the LTDC interrupt sources to be disabled. - * This parameter can be any combination of the following values: - * @arg LTDC_IT_LI: Line Interrupt flag - * @arg LTDC_IT_FU: FIFO Underrun Interrupt flag - * @arg LTDC_IT_TE: Transfer Error interrupt flag - * @arg LTDC_IT_RR: Register Reload Interrupt Flag - * @retval None - */ -#define __HAL_LTDC_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->IER &= ~(__INTERRUPT__)) - -/** - * @brief Check whether the specified LTDC interrupt has occurred or not. - * @param __HANDLE__ LTDC handle - * @param __INTERRUPT__ Specify the LTDC interrupt source to check. - * This parameter can be one of the following values: - * @arg LTDC_IT_LI: Line Interrupt flag - * @arg LTDC_IT_FU: FIFO Underrun Interrupt flag - * @arg LTDC_IT_TE: Transfer Error interrupt flag - * @arg LTDC_IT_RR: Register Reload Interrupt Flag - * @retval The state of INTERRUPT (SET or RESET). - */ -#define __HAL_LTDC_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->IER & (__INTERRUPT__)) -/** - * @} - */ - -/* Include LTDC HAL Extension module */ -#include "stm32f4xx_hal_ltdc_ex.h" - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup LTDC_Exported_Functions - * @{ - */ -/** @addtogroup LTDC_Exported_Functions_Group1 - * @{ - */ -/* Initialization and de-initialization functions *****************************/ -HAL_StatusTypeDef HAL_LTDC_Init(LTDC_HandleTypeDef *hltdc); -HAL_StatusTypeDef HAL_LTDC_DeInit(LTDC_HandleTypeDef *hltdc); -void HAL_LTDC_MspInit(LTDC_HandleTypeDef *hltdc); -void HAL_LTDC_MspDeInit(LTDC_HandleTypeDef *hltdc); -void HAL_LTDC_ErrorCallback(LTDC_HandleTypeDef *hltdc); -void HAL_LTDC_LineEventCallback(LTDC_HandleTypeDef *hltdc); -void HAL_LTDC_ReloadEventCallback(LTDC_HandleTypeDef *hltdc); - -/* Callbacks Register/UnRegister functions ***********************************/ -#if (USE_HAL_LTDC_REGISTER_CALLBACKS == 1) -HAL_StatusTypeDef HAL_LTDC_RegisterCallback(LTDC_HandleTypeDef *hltdc, HAL_LTDC_CallbackIDTypeDef CallbackID, pLTDC_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_LTDC_UnRegisterCallback(LTDC_HandleTypeDef *hltdc, HAL_LTDC_CallbackIDTypeDef CallbackID); -#endif /* USE_HAL_LTDC_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @addtogroup LTDC_Exported_Functions_Group2 - * @{ - */ -/* IO operation functions *****************************************************/ -void HAL_LTDC_IRQHandler(LTDC_HandleTypeDef *hltdc); -/** - * @} - */ - -/** @addtogroup LTDC_Exported_Functions_Group3 - * @{ - */ -/* Peripheral Control functions ***********************************************/ -HAL_StatusTypeDef HAL_LTDC_ConfigLayer(LTDC_HandleTypeDef *hltdc, LTDC_LayerCfgTypeDef *pLayerCfg, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_SetWindowSize(LTDC_HandleTypeDef *hltdc, uint32_t XSize, uint32_t YSize, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_SetWindowPosition(LTDC_HandleTypeDef *hltdc, uint32_t X0, uint32_t Y0, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_SetPixelFormat(LTDC_HandleTypeDef *hltdc, uint32_t Pixelformat, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_SetAlpha(LTDC_HandleTypeDef *hltdc, uint32_t Alpha, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_SetAddress(LTDC_HandleTypeDef *hltdc, uint32_t Address, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_SetPitch(LTDC_HandleTypeDef *hltdc, uint32_t LinePitchInPixels, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_ConfigColorKeying(LTDC_HandleTypeDef *hltdc, uint32_t RGBValue, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_ConfigCLUT(LTDC_HandleTypeDef *hltdc, uint32_t *pCLUT, uint32_t CLUTSize, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_EnableColorKeying(LTDC_HandleTypeDef *hltdc, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_DisableColorKeying(LTDC_HandleTypeDef *hltdc, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_EnableCLUT(LTDC_HandleTypeDef *hltdc, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_DisableCLUT(LTDC_HandleTypeDef *hltdc, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_ProgramLineEvent(LTDC_HandleTypeDef *hltdc, uint32_t Line); -HAL_StatusTypeDef HAL_LTDC_EnableDither(LTDC_HandleTypeDef *hltdc); -HAL_StatusTypeDef HAL_LTDC_DisableDither(LTDC_HandleTypeDef *hltdc); -HAL_StatusTypeDef HAL_LTDC_Reload(LTDC_HandleTypeDef *hltdc, uint32_t ReloadType); -HAL_StatusTypeDef HAL_LTDC_ConfigLayer_NoReload(LTDC_HandleTypeDef *hltdc, LTDC_LayerCfgTypeDef *pLayerCfg, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_SetWindowSize_NoReload(LTDC_HandleTypeDef *hltdc, uint32_t XSize, uint32_t YSize, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_SetWindowPosition_NoReload(LTDC_HandleTypeDef *hltdc, uint32_t X0, uint32_t Y0, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_SetPixelFormat_NoReload(LTDC_HandleTypeDef *hltdc, uint32_t Pixelformat, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_SetAlpha_NoReload(LTDC_HandleTypeDef *hltdc, uint32_t Alpha, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_SetAddress_NoReload(LTDC_HandleTypeDef *hltdc, uint32_t Address, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_SetPitch_NoReload(LTDC_HandleTypeDef *hltdc, uint32_t LinePitchInPixels, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_ConfigColorKeying_NoReload(LTDC_HandleTypeDef *hltdc, uint32_t RGBValue, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_EnableColorKeying_NoReload(LTDC_HandleTypeDef *hltdc, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_DisableColorKeying_NoReload(LTDC_HandleTypeDef *hltdc, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_EnableCLUT_NoReload(LTDC_HandleTypeDef *hltdc, uint32_t LayerIdx); -HAL_StatusTypeDef HAL_LTDC_DisableCLUT_NoReload(LTDC_HandleTypeDef *hltdc, uint32_t LayerIdx); - -/** - * @} - */ - -/** @addtogroup LTDC_Exported_Functions_Group4 - * @{ - */ -/* Peripheral State functions *************************************************/ -HAL_LTDC_StateTypeDef HAL_LTDC_GetState(LTDC_HandleTypeDef *hltdc); -uint32_t HAL_LTDC_GetError(LTDC_HandleTypeDef *hltdc); -/** - * @} - */ - -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/** @defgroup LTDC_Private_Macros LTDC Private Macros - * @{ - */ -#define LTDC_LAYER(__HANDLE__, __LAYER__) ((LTDC_Layer_TypeDef *)((uint32_t)(((uint32_t)((__HANDLE__)->Instance)) + 0x84U + (0x80U*(__LAYER__))))) -#define IS_LTDC_LAYER(__LAYER__) ((__LAYER__) < MAX_LAYER) -#define IS_LTDC_HSPOL(__HSPOL__) (((__HSPOL__) == LTDC_HSPOLARITY_AL) || ((__HSPOL__) == LTDC_HSPOLARITY_AH)) -#define IS_LTDC_VSPOL(__VSPOL__) (((__VSPOL__) == LTDC_VSPOLARITY_AL) || ((__VSPOL__) == LTDC_VSPOLARITY_AH)) -#define IS_LTDC_DEPOL(__DEPOL__) (((__DEPOL__) == LTDC_DEPOLARITY_AL) || ((__DEPOL__) == LTDC_DEPOLARITY_AH)) -#define IS_LTDC_PCPOL(__PCPOL__) (((__PCPOL__) == LTDC_PCPOLARITY_IPC) || ((__PCPOL__) == LTDC_PCPOLARITY_IIPC)) -#define IS_LTDC_HSYNC(__HSYNC__) ((__HSYNC__) <= LTDC_HORIZONTALSYNC) -#define IS_LTDC_VSYNC(__VSYNC__) ((__VSYNC__) <= LTDC_VERTICALSYNC) -#define IS_LTDC_AHBP(__AHBP__) ((__AHBP__) <= LTDC_HORIZONTALSYNC) -#define IS_LTDC_AVBP(__AVBP__) ((__AVBP__) <= LTDC_VERTICALSYNC) -#define IS_LTDC_AAW(__AAW__) ((__AAW__) <= LTDC_HORIZONTALSYNC) -#define IS_LTDC_AAH(__AAH__) ((__AAH__) <= LTDC_VERTICALSYNC) -#define IS_LTDC_TOTALW(__TOTALW__) ((__TOTALW__) <= LTDC_HORIZONTALSYNC) -#define IS_LTDC_TOTALH(__TOTALH__) ((__TOTALH__) <= LTDC_VERTICALSYNC) -#define IS_LTDC_BLUEVALUE(__BBLUE__) ((__BBLUE__) <= LTDC_COLOR) -#define IS_LTDC_GREENVALUE(__BGREEN__) ((__BGREEN__) <= LTDC_COLOR) -#define IS_LTDC_REDVALUE(__BRED__) ((__BRED__) <= LTDC_COLOR) -#define IS_LTDC_BLENDING_FACTOR1(__BLENDING_FACTOR1__) (((__BLENDING_FACTOR1__) == LTDC_BLENDING_FACTOR1_CA) || \ - ((__BLENDING_FACTOR1__) == LTDC_BLENDING_FACTOR1_PAxCA)) -#define IS_LTDC_BLENDING_FACTOR2(__BLENDING_FACTOR1__) (((__BLENDING_FACTOR1__) == LTDC_BLENDING_FACTOR2_CA) || \ - ((__BLENDING_FACTOR1__) == LTDC_BLENDING_FACTOR2_PAxCA)) -#define IS_LTDC_PIXEL_FORMAT(__PIXEL_FORMAT__) (((__PIXEL_FORMAT__) == LTDC_PIXEL_FORMAT_ARGB8888) || ((__PIXEL_FORMAT__) == LTDC_PIXEL_FORMAT_RGB888) || \ - ((__PIXEL_FORMAT__) == LTDC_PIXEL_FORMAT_RGB565) || ((__PIXEL_FORMAT__) == LTDC_PIXEL_FORMAT_ARGB1555) || \ - ((__PIXEL_FORMAT__) == LTDC_PIXEL_FORMAT_ARGB4444) || ((__PIXEL_FORMAT__) == LTDC_PIXEL_FORMAT_L8) || \ - ((__PIXEL_FORMAT__) == LTDC_PIXEL_FORMAT_AL44) || ((__PIXEL_FORMAT__) == LTDC_PIXEL_FORMAT_AL88)) -#define IS_LTDC_ALPHA(__ALPHA__) ((__ALPHA__) <= LTDC_ALPHA) -#define IS_LTDC_HCONFIGST(__HCONFIGST__) ((__HCONFIGST__) <= LTDC_STARTPOSITION) -#define IS_LTDC_HCONFIGSP(__HCONFIGSP__) ((__HCONFIGSP__) <= LTDC_STOPPOSITION) -#define IS_LTDC_VCONFIGST(__VCONFIGST__) ((__VCONFIGST__) <= LTDC_STARTPOSITION) -#define IS_LTDC_VCONFIGSP(__VCONFIGSP__) ((__VCONFIGSP__) <= LTDC_STOPPOSITION) -#define IS_LTDC_CFBP(__CFBP__) ((__CFBP__) <= LTDC_COLOR_FRAME_BUFFER) -#define IS_LTDC_CFBLL(__CFBLL__) ((__CFBLL__) <= LTDC_COLOR_FRAME_BUFFER) -#define IS_LTDC_CFBLNBR(__CFBLNBR__) ((__CFBLNBR__) <= LTDC_LINE_NUMBER) -#define IS_LTDC_LIPOS(__LIPOS__) ((__LIPOS__) <= 0x7FFU) -#define IS_LTDC_RELOAD(__RELOADTYPE__) (((__RELOADTYPE__) == LTDC_RELOAD_IMMEDIATE) || ((__RELOADTYPE__) == LTDC_RELOAD_VERTICAL_BLANKING)) -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup LTDC_Private_Functions LTDC Private Functions - * @{ - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* LTDC */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_HAL_LTDC_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_ltdc_ex.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_ltdc_ex.h deleted file mode 100644 index 37a5fdf..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_ltdc_ex.h +++ /dev/null @@ -1,86 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_ltdc_ex.h - * @author MCD Application Team - * @brief Header file of LTDC HAL Extension module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_LTDC_EX_H -#define STM32F4xx_HAL_LTDC_EX_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -#if defined (LTDC) && defined (DSI) - -#include "stm32f4xx_hal_dsi.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup LTDCEx - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/* Exported macro ------------------------------------------------------------*/ -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup LTDCEx_Exported_Functions - * @{ - */ - -/** @addtogroup LTDCEx_Exported_Functions_Group1 - * @{ - */ -HAL_StatusTypeDef HAL_LTDCEx_StructInitFromVideoConfig(LTDC_HandleTypeDef *hltdc, DSI_VidCfgTypeDef *VidCfg); -HAL_StatusTypeDef HAL_LTDCEx_StructInitFromAdaptedCommandConfig(LTDC_HandleTypeDef *hltdc, DSI_CmdCfgTypeDef *CmdCfg); -/** - * @} - */ - -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* LTDC && DSI */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_HAL_LTDC_EX_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_mmc.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_mmc.h deleted file mode 100644 index e65172a..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_mmc.h +++ /dev/null @@ -1,745 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_mmc.h - * @author MCD Application Team - * @brief Header file of MMC HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_MMC_H -#define STM32F4xx_HAL_MMC_H - -#if defined(SDIO) - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_ll_sdmmc.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup MMC - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup MMC_Exported_Types MMC Exported Types - * @{ - */ - -/** @defgroup MMC_Exported_Types_Group1 MMC State enumeration structure - * @{ - */ -typedef enum -{ - HAL_MMC_STATE_RESET = 0x00000000U, /*!< MMC not yet initialized or disabled */ - HAL_MMC_STATE_READY = 0x00000001U, /*!< MMC initialized and ready for use */ - HAL_MMC_STATE_TIMEOUT = 0x00000002U, /*!< MMC Timeout state */ - HAL_MMC_STATE_BUSY = 0x00000003U, /*!< MMC process ongoing */ - HAL_MMC_STATE_PROGRAMMING = 0x00000004U, /*!< MMC Programming State */ - HAL_MMC_STATE_RECEIVING = 0x00000005U, /*!< MMC Receinving State */ - HAL_MMC_STATE_TRANSFER = 0x00000006U, /*!< MMC Transfer State */ - HAL_MMC_STATE_ERROR = 0x0000000FU /*!< MMC is in error state */ -}HAL_MMC_StateTypeDef; -/** - * @} - */ - -/** @defgroup MMC_Exported_Types_Group2 MMC Card State enumeration structure - * @{ - */ -typedef uint32_t HAL_MMC_CardStateTypeDef; - -#define HAL_MMC_CARD_READY 0x00000001U /*!< Card state is ready */ -#define HAL_MMC_CARD_IDENTIFICATION 0x00000002U /*!< Card is in identification state */ -#define HAL_MMC_CARD_STANDBY 0x00000003U /*!< Card is in standby state */ -#define HAL_MMC_CARD_TRANSFER 0x00000004U /*!< Card is in transfer state */ -#define HAL_MMC_CARD_SENDING 0x00000005U /*!< Card is sending an operation */ -#define HAL_MMC_CARD_RECEIVING 0x00000006U /*!< Card is receiving operation information */ -#define HAL_MMC_CARD_PROGRAMMING 0x00000007U /*!< Card is in programming state */ -#define HAL_MMC_CARD_DISCONNECTED 0x00000008U /*!< Card is disconnected */ -#define HAL_MMC_CARD_ERROR 0x000000FFU /*!< Card response Error */ -/** - * @} - */ - -/** @defgroup MMC_Exported_Types_Group3 MMC Handle Structure definition - * @{ - */ -#define MMC_InitTypeDef SDIO_InitTypeDef -#define MMC_TypeDef SDIO_TypeDef - -/** - * @brief MMC Card Information Structure definition - */ -typedef struct -{ - uint32_t CardType; /*!< Specifies the card Type */ - - uint32_t Class; /*!< Specifies the class of the card class */ - - uint32_t RelCardAdd; /*!< Specifies the Relative Card Address */ - - uint32_t BlockNbr; /*!< Specifies the Card Capacity in blocks */ - - uint32_t BlockSize; /*!< Specifies one block size in bytes */ - - uint32_t LogBlockNbr; /*!< Specifies the Card logical Capacity in blocks */ - - uint32_t LogBlockSize; /*!< Specifies logical block size in bytes */ - -}HAL_MMC_CardInfoTypeDef; - -/** - * @brief MMC handle Structure definition - */ -#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) -typedef struct __MMC_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_MMC_REGISTER_CALLBACKS */ -{ - MMC_TypeDef *Instance; /*!< MMC registers base address */ - - MMC_InitTypeDef Init; /*!< MMC required parameters */ - - HAL_LockTypeDef Lock; /*!< MMC locking object */ - - uint8_t *pTxBuffPtr; /*!< Pointer to MMC Tx transfer Buffer */ - - uint32_t TxXferSize; /*!< MMC Tx Transfer size */ - - uint8_t *pRxBuffPtr; /*!< Pointer to MMC Rx transfer Buffer */ - - uint32_t RxXferSize; /*!< MMC Rx Transfer size */ - - __IO uint32_t Context; /*!< MMC transfer context */ - - __IO HAL_MMC_StateTypeDef State; /*!< MMC card State */ - - __IO uint32_t ErrorCode; /*!< MMC Card Error codes */ - - DMA_HandleTypeDef *hdmarx; /*!< MMC Rx DMA handle parameters */ - - DMA_HandleTypeDef *hdmatx; /*!< MMC Tx DMA handle parameters */ - - HAL_MMC_CardInfoTypeDef MmcCard; /*!< MMC Card information */ - - uint32_t CSD[4U]; /*!< MMC card specific data table */ - - uint32_t CID[4U]; /*!< MMC card identification number table */ - -#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) - void (* TxCpltCallback) (struct __MMC_HandleTypeDef *hmmc); - void (* RxCpltCallback) (struct __MMC_HandleTypeDef *hmmc); - void (* ErrorCallback) (struct __MMC_HandleTypeDef *hmmc); - void (* AbortCpltCallback) (struct __MMC_HandleTypeDef *hmmc); - - void (* MspInitCallback) (struct __MMC_HandleTypeDef *hmmc); - void (* MspDeInitCallback) (struct __MMC_HandleTypeDef *hmmc); -#endif -}MMC_HandleTypeDef; - -/** - * @} - */ - -/** @defgroup MMC_Exported_Types_Group4 Card Specific Data: CSD Register - * @{ - */ -typedef struct -{ - __IO uint8_t CSDStruct; /*!< CSD structure */ - __IO uint8_t SysSpecVersion; /*!< System specification version */ - __IO uint8_t Reserved1; /*!< Reserved */ - __IO uint8_t TAAC; /*!< Data read access time 1 */ - __IO uint8_t NSAC; /*!< Data read access time 2 in CLK cycles */ - __IO uint8_t MaxBusClkFrec; /*!< Max. bus clock frequency */ - __IO uint16_t CardComdClasses; /*!< Card command classes */ - __IO uint8_t RdBlockLen; /*!< Max. read data block length */ - __IO uint8_t PartBlockRead; /*!< Partial blocks for read allowed */ - __IO uint8_t WrBlockMisalign; /*!< Write block misalignment */ - __IO uint8_t RdBlockMisalign; /*!< Read block misalignment */ - __IO uint8_t DSRImpl; /*!< DSR implemented */ - __IO uint8_t Reserved2; /*!< Reserved */ - __IO uint32_t DeviceSize; /*!< Device Size */ - __IO uint8_t MaxRdCurrentVDDMin; /*!< Max. read current @ VDD min */ - __IO uint8_t MaxRdCurrentVDDMax; /*!< Max. read current @ VDD max */ - __IO uint8_t MaxWrCurrentVDDMin; /*!< Max. write current @ VDD min */ - __IO uint8_t MaxWrCurrentVDDMax; /*!< Max. write current @ VDD max */ - __IO uint8_t DeviceSizeMul; /*!< Device size multiplier */ - __IO uint8_t EraseGrSize; /*!< Erase group size */ - __IO uint8_t EraseGrMul; /*!< Erase group size multiplier */ - __IO uint8_t WrProtectGrSize; /*!< Write protect group size */ - __IO uint8_t WrProtectGrEnable; /*!< Write protect group enable */ - __IO uint8_t ManDeflECC; /*!< Manufacturer default ECC */ - __IO uint8_t WrSpeedFact; /*!< Write speed factor */ - __IO uint8_t MaxWrBlockLen; /*!< Max. write data block length */ - __IO uint8_t WriteBlockPaPartial; /*!< Partial blocks for write allowed */ - __IO uint8_t Reserved3; /*!< Reserved */ - __IO uint8_t ContentProtectAppli; /*!< Content protection application */ - __IO uint8_t FileFormatGroup; /*!< File format group */ - __IO uint8_t CopyFlag; /*!< Copy flag (OTP) */ - __IO uint8_t PermWrProtect; /*!< Permanent write protection */ - __IO uint8_t TempWrProtect; /*!< Temporary write protection */ - __IO uint8_t FileFormat; /*!< File format */ - __IO uint8_t ECC; /*!< ECC code */ - __IO uint8_t CSD_CRC; /*!< CSD CRC */ - __IO uint8_t Reserved4; /*!< Always 1 */ - -}HAL_MMC_CardCSDTypeDef; -/** - * @} - */ - -/** @defgroup MMC_Exported_Types_Group5 Card Identification Data: CID Register - * @{ - */ -typedef struct -{ - __IO uint8_t ManufacturerID; /*!< Manufacturer ID */ - __IO uint16_t OEM_AppliID; /*!< OEM/Application ID */ - __IO uint32_t ProdName1; /*!< Product Name part1 */ - __IO uint8_t ProdName2; /*!< Product Name part2 */ - __IO uint8_t ProdRev; /*!< Product Revision */ - __IO uint32_t ProdSN; /*!< Product Serial Number */ - __IO uint8_t Reserved1; /*!< Reserved1 */ - __IO uint16_t ManufactDate; /*!< Manufacturing Date */ - __IO uint8_t CID_CRC; /*!< CID CRC */ - __IO uint8_t Reserved2; /*!< Always 1 */ - -}HAL_MMC_CardCIDTypeDef; -/** - * @} - */ - -#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) -/** @defgroup MMC_Exported_Types_Group6 MMC Callback ID enumeration definition - * @{ - */ -typedef enum -{ - HAL_MMC_TX_CPLT_CB_ID = 0x00U, /*!< MMC Tx Complete Callback ID */ - HAL_MMC_RX_CPLT_CB_ID = 0x01U, /*!< MMC Rx Complete Callback ID */ - HAL_MMC_ERROR_CB_ID = 0x02U, /*!< MMC Error Callback ID */ - HAL_MMC_ABORT_CB_ID = 0x03U, /*!< MMC Abort Callback ID */ - - HAL_MMC_MSP_INIT_CB_ID = 0x10U, /*!< MMC MspInit Callback ID */ - HAL_MMC_MSP_DEINIT_CB_ID = 0x11U /*!< MMC MspDeInit Callback ID */ -}HAL_MMC_CallbackIDTypeDef; -/** - * @} - */ - -/** @defgroup MMC_Exported_Types_Group7 MMC Callback pointer definition - * @{ - */ -typedef void (*pMMC_CallbackTypeDef) (MMC_HandleTypeDef *hmmc); -/** - * @} - */ -#endif -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup MMC_Exported_Constants Exported Constants - * @{ - */ - -#define MMC_BLOCKSIZE 512U /*!< Block size is 512 bytes */ - -/** @defgroup MMC_Exported_Constansts_Group1 MMC Error status enumeration Structure definition - * @{ - */ -#define HAL_MMC_ERROR_NONE SDMMC_ERROR_NONE /*!< No error */ -#define HAL_MMC_ERROR_CMD_CRC_FAIL SDMMC_ERROR_CMD_CRC_FAIL /*!< Command response received (but CRC check failed) */ -#define HAL_MMC_ERROR_DATA_CRC_FAIL SDMMC_ERROR_DATA_CRC_FAIL /*!< Data block sent/received (CRC check failed) */ -#define HAL_MMC_ERROR_CMD_RSP_TIMEOUT SDMMC_ERROR_CMD_RSP_TIMEOUT /*!< Command response timeout */ -#define HAL_MMC_ERROR_DATA_TIMEOUT SDMMC_ERROR_DATA_TIMEOUT /*!< Data timeout */ -#define HAL_MMC_ERROR_TX_UNDERRUN SDMMC_ERROR_TX_UNDERRUN /*!< Transmit FIFO underrun */ -#define HAL_MMC_ERROR_RX_OVERRUN SDMMC_ERROR_RX_OVERRUN /*!< Receive FIFO overrun */ -#define HAL_MMC_ERROR_ADDR_MISALIGNED SDMMC_ERROR_ADDR_MISALIGNED /*!< Misaligned address */ -#define HAL_MMC_ERROR_BLOCK_LEN_ERR SDMMC_ERROR_BLOCK_LEN_ERR /*!< Transferred block length is not allowed for the card or the - number of transferred bytes does not match the block length */ -#define HAL_MMC_ERROR_ERASE_SEQ_ERR SDMMC_ERROR_ERASE_SEQ_ERR /*!< An error in the sequence of erase command occurs */ -#define HAL_MMC_ERROR_BAD_ERASE_PARAM SDMMC_ERROR_BAD_ERASE_PARAM /*!< An invalid selection for erase groups */ -#define HAL_MMC_ERROR_WRITE_PROT_VIOLATION SDMMC_ERROR_WRITE_PROT_VIOLATION /*!< Attempt to program a write protect block */ -#define HAL_MMC_ERROR_LOCK_UNLOCK_FAILED SDMMC_ERROR_LOCK_UNLOCK_FAILED /*!< Sequence or password error has been detected in unlock - command or if there was an attempt to access a locked card */ -#define HAL_MMC_ERROR_COM_CRC_FAILED SDMMC_ERROR_COM_CRC_FAILED /*!< CRC check of the previous command failed */ -#define HAL_MMC_ERROR_ILLEGAL_CMD SDMMC_ERROR_ILLEGAL_CMD /*!< Command is not legal for the card state */ -#define HAL_MMC_ERROR_CARD_ECC_FAILED SDMMC_ERROR_CARD_ECC_FAILED /*!< Card internal ECC was applied but failed to correct the data */ -#define HAL_MMC_ERROR_CC_ERR SDMMC_ERROR_CC_ERR /*!< Internal card controller error */ -#define HAL_MMC_ERROR_GENERAL_UNKNOWN_ERR SDMMC_ERROR_GENERAL_UNKNOWN_ERR /*!< General or unknown error */ -#define HAL_MMC_ERROR_STREAM_READ_UNDERRUN SDMMC_ERROR_STREAM_READ_UNDERRUN /*!< The card could not sustain data reading in stream rmode */ -#define HAL_MMC_ERROR_STREAM_WRITE_OVERRUN SDMMC_ERROR_STREAM_WRITE_OVERRUN /*!< The card could not sustain data programming in stream mode */ -#define HAL_MMC_ERROR_CID_CSD_OVERWRITE SDMMC_ERROR_CID_CSD_OVERWRITE /*!< CID/CSD overwrite error */ -#define HAL_MMC_ERROR_WP_ERASE_SKIP SDMMC_ERROR_WP_ERASE_SKIP /*!< Only partial address space was erased */ -#define HAL_MMC_ERROR_CARD_ECC_DISABLED SDMMC_ERROR_CARD_ECC_DISABLED /*!< Command has been executed without using internal ECC */ -#define HAL_MMC_ERROR_ERASE_RESET SDMMC_ERROR_ERASE_RESET /*!< Erase sequence was cleared before executing because an out - of erase sequence command was received */ -#define HAL_MMC_ERROR_AKE_SEQ_ERR SDMMC_ERROR_AKE_SEQ_ERR /*!< Error in sequence of authentication */ -#define HAL_MMC_ERROR_INVALID_VOLTRANGE SDMMC_ERROR_INVALID_VOLTRANGE /*!< Error in case of invalid voltage range */ -#define HAL_MMC_ERROR_ADDR_OUT_OF_RANGE SDMMC_ERROR_ADDR_OUT_OF_RANGE /*!< Error when addressed block is out of range */ -#define HAL_MMC_ERROR_REQUEST_NOT_APPLICABLE SDMMC_ERROR_REQUEST_NOT_APPLICABLE /*!< Error when command request is not applicable */ -#define HAL_MMC_ERROR_PARAM SDMMC_ERROR_INVALID_PARAMETER /*!< the used parameter is not valid */ -#define HAL_MMC_ERROR_UNSUPPORTED_FEATURE SDMMC_ERROR_UNSUPPORTED_FEATURE /*!< Error when feature is not insupported */ -#define HAL_MMC_ERROR_BUSY SDMMC_ERROR_BUSY /*!< Error when transfer process is busy */ -#define HAL_MMC_ERROR_DMA SDMMC_ERROR_DMA /*!< Error while DMA transfer */ -#define HAL_MMC_ERROR_TIMEOUT SDMMC_ERROR_TIMEOUT /*!< Timeout error */ - -#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) -#define HAL_MMC_ERROR_INVALID_CALLBACK SDMMC_ERROR_INVALID_PARAMETER /*!< Invalid callback error */ -#endif -/** - * @} - */ - -/** @defgroup MMC_Exported_Constansts_Group2 MMC context enumeration - * @{ - */ -#define MMC_CONTEXT_NONE 0x00000000U /*!< None */ -#define MMC_CONTEXT_READ_SINGLE_BLOCK 0x00000001U /*!< Read single block operation */ -#define MMC_CONTEXT_READ_MULTIPLE_BLOCK 0x00000002U /*!< Read multiple blocks operation */ -#define MMC_CONTEXT_WRITE_SINGLE_BLOCK 0x00000010U /*!< Write single block operation */ -#define MMC_CONTEXT_WRITE_MULTIPLE_BLOCK 0x00000020U /*!< Write multiple blocks operation */ -#define MMC_CONTEXT_IT 0x00000008U /*!< Process in Interrupt mode */ -#define MMC_CONTEXT_DMA 0x00000080U /*!< Process in DMA mode */ - -/** - * @} - */ - -/** @defgroup MMC_Exported_Constansts_Group3 MMC Voltage mode - * @{ - */ -/** - * @brief - */ -#define MMC_HIGH_VOLTAGE_RANGE 0x80FF8000U /*!< VALUE OF ARGUMENT */ -#define MMC_DUAL_VOLTAGE_RANGE 0x80FF8080U /*!< VALUE OF ARGUMENT */ -#define eMMC_HIGH_VOLTAGE_RANGE 0xC0FF8000U /*!< for eMMC > 2Gb sector mode */ -#define eMMC_DUAL_VOLTAGE_RANGE 0xC0FF8080U /*!< for eMMC > 2Gb sector mode */ -#define MMC_INVALID_VOLTAGE_RANGE 0x0001FF01U -/** - * @} - */ - -/** @defgroup MMC_Exported_Constansts_Group4 MMC Memory Cards - * @{ - */ -#define MMC_LOW_CAPACITY_CARD 0x00000000U /*!< MMC Card Capacity <=2Gbytes */ -#define MMC_HIGH_CAPACITY_CARD 0x00000001U /*!< MMC Card Capacity >2Gbytes and <2Tbytes */ - -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup MMC_Exported_macros MMC Exported Macros - * @brief macros to handle interrupts and specific clock configurations - * @{ - */ -/** @brief Reset MMC handle state. - * @param __HANDLE__ : MMC handle. - * @retval None - */ -#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) -#define __HAL_MMC_RESET_HANDLE_STATE(__HANDLE__) do { \ - (__HANDLE__)->State = HAL_MMC_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_MMC_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_MMC_STATE_RESET) -#endif - -/** - * @brief Enable the MMC device. - * @retval None - */ -#define __HAL_MMC_ENABLE(__HANDLE__) __SDIO_ENABLE((__HANDLE__)->Instance) - -/** - * @brief Disable the MMC device. - * @retval None - */ -#define __HAL_MMC_DISABLE(__HANDLE__) __SDIO_DISABLE((__HANDLE__)->Instance) - -/** - * @brief Enable the SDMMC DMA transfer. - * @retval None - */ -#define __HAL_MMC_DMA_ENABLE(__HANDLE__) __SDIO_DMA_ENABLE((__HANDLE__)->Instance) - -/** - * @brief Disable the SDMMC DMA transfer. - * @retval None - */ -#define __HAL_MMC_DMA_DISABLE(__HANDLE__) __SDIO_DMA_DISABLE((__HANDLE__)->Instance) - -/** - * @brief Enable the MMC device interrupt. - * @param __HANDLE__: MMC Handle - * @param __INTERRUPT__: specifies the SDMMC interrupt sources to be enabled. - * This parameter can be one or a combination of the following values: - * @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt - * @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt - * @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt - * @arg SDIO_IT_DTIMEOUT: Data timeout interrupt - * @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt - * @arg SDIO_IT_RXOVERR: Received FIFO overrun error interrupt - * @arg SDIO_IT_CMDREND: Command response received (CRC check passed) interrupt - * @arg SDIO_IT_CMDSENT: Command sent (no response required) interrupt - * @arg SDIO_IT_DATAEND: Data end (data counter, DATACOUNT, is zero) interrupt - * @arg SDIO_IT_DBCKEND: Data block sent/received (CRC check passed) interrupt - * @arg SDIO_IT_CMDACT: Command transfer in progress interrupt - * @arg SDIO_IT_TXACT: Data transmit in progress interrupt - * @arg SDIO_IT_RXACT: Data receive in progress interrupt - * @arg SDIO_IT_TXFIFOHE: Transmit FIFO Half Empty interrupt - * @arg SDIO_IT_RXFIFOHF: Receive FIFO Half Full interrupt - * @arg SDIO_IT_TXFIFOF: Transmit FIFO full interrupt - * @arg SDIO_IT_RXFIFOF: Receive FIFO full interrupt - * @arg SDIO_IT_TXFIFOE: Transmit FIFO empty interrupt - * @arg SDIO_IT_RXFIFOE: Receive FIFO empty interrupt - * @arg SDIO_IT_TXDAVL: Data available in transmit FIFO interrupt - * @arg SDIO_IT_RXDAVL: Data available in receive FIFO interrupt - * @arg SDIO_IT_SDIOIT: SD I/O interrupt received interrupt - * @retval None - */ -#define __HAL_MMC_ENABLE_IT(__HANDLE__, __INTERRUPT__) __SDIO_ENABLE_IT((__HANDLE__)->Instance, (__INTERRUPT__)) - -/** - * @brief Disable the MMC device interrupt. - * @param __HANDLE__: MMC Handle - * @param __INTERRUPT__: specifies the SDMMC interrupt sources to be disabled. - * This parameter can be one or a combination of the following values: - * @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt - * @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt - * @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt - * @arg SDIO_IT_DTIMEOUT: Data timeout interrupt - * @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt - * @arg SDIO_IT_RXOVERR: Received FIFO overrun error interrupt - * @arg SDIO_IT_CMDREND: Command response received (CRC check passed) interrupt - * @arg SDIO_IT_CMDSENT: Command sent (no response required) interrupt - * @arg SDIO_IT_DATAEND: Data end (data counter, DATACOUNT, is zero) interrupt - * @arg SDIO_IT_DBCKEND: Data block sent/received (CRC check passed) interrupt - * @arg SDIO_IT_CMDACT: Command transfer in progress interrupt - * @arg SDIO_IT_TXACT: Data transmit in progress interrupt - * @arg SDIO_IT_RXACT: Data receive in progress interrupt - * @arg SDIO_IT_TXFIFOHE: Transmit FIFO Half Empty interrupt - * @arg SDIO_IT_RXFIFOHF: Receive FIFO Half Full interrupt - * @arg SDIO_IT_TXFIFOF: Transmit FIFO full interrupt - * @arg SDIO_IT_RXFIFOF: Receive FIFO full interrupt - * @arg SDIO_IT_TXFIFOE: Transmit FIFO empty interrupt - * @arg SDIO_IT_RXFIFOE: Receive FIFO empty interrupt - * @arg SDIO_IT_TXDAVL: Data available in transmit FIFO interrupt - * @arg SDIO_IT_RXDAVL: Data available in receive FIFO interrupt - * @arg SDIO_IT_SDIOIT: SD I/O interrupt received interrupt - * @retval None - */ -#define __HAL_MMC_DISABLE_IT(__HANDLE__, __INTERRUPT__) __SDIO_DISABLE_IT((__HANDLE__)->Instance, (__INTERRUPT__)) - -/** - * @brief Check whether the specified MMC flag is set or not. - * @param __HANDLE__: MMC Handle - * @param __FLAG__: specifies the flag to check. - * This parameter can be one of the following values: - * @arg SDIO_FLAG_CCRCFAIL: Command response received (CRC check failed) - * @arg SDIO_FLAG_DCRCFAIL: Data block sent/received (CRC check failed) - * @arg SDIO_FLAG_CTIMEOUT: Command response timeout - * @arg SDIO_FLAG_DTIMEOUT: Data timeout - * @arg SDIO_FLAG_TXUNDERR: Transmit FIFO underrun error - * @arg SDIO_FLAG_RXOVERR: Received FIFO overrun error - * @arg SDIO_FLAG_CMDREND: Command response received (CRC check passed) - * @arg SDIO_FLAG_CMDSENT: Command sent (no response required) - * @arg SDIO_FLAG_DATAEND: Data end (data counter, DATACOUNT, is zero) - * @arg SDIO_FLAG_DBCKEND: Data block sent/received (CRC check passed) - * @arg SDIO_FLAG_CMDACT: Command transfer in progress - * @arg SDIO_FLAG_TXACT: Data transmit in progress - * @arg SDIO_FLAG_RXACT: Data receive in progress - * @arg SDIO_FLAG_TXFIFOHE: Transmit FIFO Half Empty - * @arg SDIO_FLAG_RXFIFOHF: Receive FIFO Half Full - * @arg SDIO_FLAG_TXFIFOF: Transmit FIFO full - * @arg SDIO_FLAG_RXFIFOF: Receive FIFO full - * @arg SDIO_FLAG_TXFIFOE: Transmit FIFO empty - * @arg SDIO_FLAG_RXFIFOE: Receive FIFO empty - * @arg SDIO_FLAG_TXDAVL: Data available in transmit FIFO - * @arg SDIO_FLAG_RXDAVL: Data available in receive FIFO - * @arg SDIO_FLAG_SDIOIT: SD I/O interrupt received - * @retval The new state of MMC FLAG (SET or RESET). - */ -#define __HAL_MMC_GET_FLAG(__HANDLE__, __FLAG__) __SDIO_GET_FLAG((__HANDLE__)->Instance, (__FLAG__)) - -/** - * @brief Clear the MMC's pending flags. - * @param __HANDLE__: MMC Handle - * @param __FLAG__: specifies the flag to clear. - * This parameter can be one or a combination of the following values: - * @arg SDIO_FLAG_CCRCFAIL: Command response received (CRC check failed) - * @arg SDIO_FLAG_DCRCFAIL: Data block sent/received (CRC check failed) - * @arg SDIO_FLAG_CTIMEOUT: Command response timeout - * @arg SDIO_FLAG_DTIMEOUT: Data timeout - * @arg SDIO_FLAG_TXUNDERR: Transmit FIFO underrun error - * @arg SDIO_FLAG_RXOVERR: Received FIFO overrun error - * @arg SDIO_FLAG_CMDREND: Command response received (CRC check passed) - * @arg SDIO_FLAG_CMDSENT: Command sent (no response required) - * @arg SDIO_FLAG_DATAEND: Data end (data counter, DATACOUNT, is zero) - * @arg SDIO_FLAG_DBCKEND: Data block sent/received (CRC check passed) - * @arg SDIO_FLAG_SDIOIT: SD I/O interrupt received - * @retval None - */ -#define __HAL_MMC_CLEAR_FLAG(__HANDLE__, __FLAG__) __SDIO_CLEAR_FLAG((__HANDLE__)->Instance, (__FLAG__)) - -/** - * @brief Check whether the specified MMC interrupt has occurred or not. - * @param __HANDLE__: MMC Handle - * @param __INTERRUPT__: specifies the SDMMC interrupt source to check. - * This parameter can be one of the following values: - * @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt - * @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt - * @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt - * @arg SDIO_IT_DTIMEOUT: Data timeout interrupt - * @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt - * @arg SDIO_IT_RXOVERR: Received FIFO overrun error interrupt - * @arg SDIO_IT_CMDREND: Command response received (CRC check passed) interrupt - * @arg SDIO_IT_CMDSENT: Command sent (no response required) interrupt - * @arg SDIO_IT_DATAEND: Data end (data counter, DATACOUNT, is zero) interrupt - * @arg SDIO_IT_DBCKEND: Data block sent/received (CRC check passed) interrupt - * @arg SDIO_IT_CMDACT: Command transfer in progress interrupt - * @arg SDIO_IT_TXACT: Data transmit in progress interrupt - * @arg SDIO_IT_RXACT: Data receive in progress interrupt - * @arg SDIO_IT_TXFIFOHE: Transmit FIFO Half Empty interrupt - * @arg SDIO_IT_RXFIFOHF: Receive FIFO Half Full interrupt - * @arg SDIO_IT_TXFIFOF: Transmit FIFO full interrupt - * @arg SDIO_IT_RXFIFOF: Receive FIFO full interrupt - * @arg SDIO_IT_TXFIFOE: Transmit FIFO empty interrupt - * @arg SDIO_IT_RXFIFOE: Receive FIFO empty interrupt - * @arg SDIO_IT_TXDAVL: Data available in transmit FIFO interrupt - * @arg SDIO_IT_RXDAVL: Data available in receive FIFO interrupt - * @arg SDIO_IT_SDIOIT: SD I/O interrupt received interrupt - * @retval The new state of MMC IT (SET or RESET). - */ -#define __HAL_MMC_GET_IT(__HANDLE__, __INTERRUPT__) __SDIO_GET_IT((__HANDLE__)->Instance, (__INTERRUPT__)) - -/** - * @brief Clear the MMC's interrupt pending bits. - * @param __HANDLE__: MMC Handle - * @param __INTERRUPT__: specifies the interrupt pending bit to clear. - * This parameter can be one or a combination of the following values: - * @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt - * @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt - * @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt - * @arg SDIO_IT_DTIMEOUT: Data timeout interrupt - * @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt - * @arg SDIO_IT_RXOVERR: Received FIFO overrun error interrupt - * @arg SDIO_IT_CMDREND: Command response received (CRC check passed) interrupt - * @arg SDIO_IT_CMDSENT: Command sent (no response required) interrupt - * @arg SDIO_IT_DATAEND: Data end (data counter, DATACOUNT, is zero) interrupt - * @arg SDIO_IT_DBCKEND: Data block sent/received (CRC check passed) interrupt - * @arg SDIO_IT_TXFIFOHE: Transmit FIFO Half Empty interrupt - * @arg SDIO_IT_RXFIFOHF: Receive FIFO Half Full interrupt - * @arg SDIO_IT_RXFIFOF: Receive FIFO full interrupt - * @arg SDIO_IT_TXFIFOE: Transmit FIFO empty interrupt - * @arg SDIO_IT_SDIOIT: SD I/O interrupt received interrupt - * @retval None - */ -#define __HAL_MMC_CLEAR_IT(__HANDLE__, __INTERRUPT__) __SDIO_CLEAR_IT((__HANDLE__)->Instance, (__INTERRUPT__)) - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup MMC_Exported_Functions MMC Exported Functions - * @{ - */ - -/** @defgroup MMC_Exported_Functions_Group1 Initialization and de-initialization functions - * @{ - */ -HAL_StatusTypeDef HAL_MMC_Init(MMC_HandleTypeDef *hmmc); -HAL_StatusTypeDef HAL_MMC_InitCard(MMC_HandleTypeDef *hmmc); -HAL_StatusTypeDef HAL_MMC_DeInit (MMC_HandleTypeDef *hmmc); -void HAL_MMC_MspInit(MMC_HandleTypeDef *hmmc); -void HAL_MMC_MspDeInit(MMC_HandleTypeDef *hmmc); - -/** - * @} - */ - -/** @defgroup MMC_Exported_Functions_Group2 Input and Output operation functions - * @{ - */ -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_MMC_ReadBlocks(MMC_HandleTypeDef *hmmc, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks, uint32_t Timeout); -HAL_StatusTypeDef HAL_MMC_WriteBlocks(MMC_HandleTypeDef *hmmc, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks, uint32_t Timeout); -HAL_StatusTypeDef HAL_MMC_Erase(MMC_HandleTypeDef *hmmc, uint32_t BlockStartAdd, uint32_t BlockEndAdd); -/* Non-Blocking mode: IT */ -HAL_StatusTypeDef HAL_MMC_ReadBlocks_IT(MMC_HandleTypeDef *hmmc, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks); -HAL_StatusTypeDef HAL_MMC_WriteBlocks_IT(MMC_HandleTypeDef *hmmc, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks); -/* Non-Blocking mode: DMA */ -HAL_StatusTypeDef HAL_MMC_ReadBlocks_DMA(MMC_HandleTypeDef *hmmc, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks); -HAL_StatusTypeDef HAL_MMC_WriteBlocks_DMA(MMC_HandleTypeDef *hmmc, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks); - -void HAL_MMC_IRQHandler(MMC_HandleTypeDef *hmmc); - -/* Callback in non blocking modes (DMA) */ -void HAL_MMC_TxCpltCallback(MMC_HandleTypeDef *hmmc); -void HAL_MMC_RxCpltCallback(MMC_HandleTypeDef *hmmc); -void HAL_MMC_ErrorCallback(MMC_HandleTypeDef *hmmc); -void HAL_MMC_AbortCallback(MMC_HandleTypeDef *hmmc); - -#if defined (USE_HAL_MMC_REGISTER_CALLBACKS) && (USE_HAL_MMC_REGISTER_CALLBACKS == 1U) -/* MMC callback registering/unregistering */ -HAL_StatusTypeDef HAL_MMC_RegisterCallback (MMC_HandleTypeDef *hmmc, HAL_MMC_CallbackIDTypeDef CallbackId, pMMC_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_MMC_UnRegisterCallback(MMC_HandleTypeDef *hmmc, HAL_MMC_CallbackIDTypeDef CallbackId); -#endif -/** - * @} - */ - -/** @defgroup MMC_Exported_Functions_Group3 Peripheral Control functions - * @{ - */ -HAL_StatusTypeDef HAL_MMC_ConfigWideBusOperation(MMC_HandleTypeDef *hmmc, uint32_t WideMode); -/** - * @} - */ - -/** @defgroup MMC_Exported_Functions_Group4 MMC card related functions - * @{ - */ -HAL_MMC_CardStateTypeDef HAL_MMC_GetCardState(MMC_HandleTypeDef *hmmc); -HAL_StatusTypeDef HAL_MMC_GetCardCID(MMC_HandleTypeDef *hmmc, HAL_MMC_CardCIDTypeDef *pCID); -HAL_StatusTypeDef HAL_MMC_GetCardCSD(MMC_HandleTypeDef *hmmc, HAL_MMC_CardCSDTypeDef *pCSD); -HAL_StatusTypeDef HAL_MMC_GetCardInfo(MMC_HandleTypeDef *hmmc, HAL_MMC_CardInfoTypeDef *pCardInfo); -/** - * @} - */ - -/** @defgroup MMC_Exported_Functions_Group5 Peripheral State and Errors functions - * @{ - */ -HAL_MMC_StateTypeDef HAL_MMC_GetState(MMC_HandleTypeDef *hmmc); -uint32_t HAL_MMC_GetError(MMC_HandleTypeDef *hmmc); -/** - * @} - */ - -/** @defgroup MMC_Exported_Functions_Group6 Perioheral Abort management - * @{ - */ -HAL_StatusTypeDef HAL_MMC_Abort(MMC_HandleTypeDef *hmmc); -HAL_StatusTypeDef HAL_MMC_Abort_IT(MMC_HandleTypeDef *hmmc); -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/** @defgroup MMC_Private_Types MMC Private Types - * @{ - */ - -/** - * @} - */ - -/* Private defines -----------------------------------------------------------*/ -/** @defgroup MMC_Private_Defines MMC Private Defines - * @{ - */ - -/** - * @} - */ - -/* Private variables ---------------------------------------------------------*/ -/** @defgroup MMC_Private_Variables MMC Private Variables - * @{ - */ - -/** - * @} - */ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup MMC_Private_Constants MMC Private Constants - * @{ - */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup MMC_Private_Macros MMC Private Macros - * @{ - */ - -/** - * @} - */ - -/* Private functions prototypes ----------------------------------------------*/ -/** @defgroup MMC_Private_Functions_Prototypes MMC Private Functions Prototypes - * @{ - */ - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup MMC_Private_Functions MMC Private Functions - * @{ - */ - -/** - * @} - */ - - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* SDIO */ - -#endif /* STM32F4xx_HAL_MMC_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_nand.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_nand.h deleted file mode 100644 index e6aaabb..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_nand.h +++ /dev/null @@ -1,381 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_nand.h - * @author MCD Application Team - * @brief Header file of NAND HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_NAND_H -#define __STM32F4xx_HAL_NAND_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) - #include "stm32f4xx_ll_fsmc.h" -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) - #include "stm32f4xx_ll_fmc.h" -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx ||\ - STM32F479xx */ - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup NAND - * @{ - */ - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || \ - defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || \ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) - -/* Exported typedef ----------------------------------------------------------*/ -/* Exported types ------------------------------------------------------------*/ -/** @defgroup NAND_Exported_Types NAND Exported Types - * @{ - */ - -/** - * @brief HAL NAND State structures definition - */ -typedef enum -{ - HAL_NAND_STATE_RESET = 0x00U, /*!< NAND not yet initialized or disabled */ - HAL_NAND_STATE_READY = 0x01U, /*!< NAND initialized and ready for use */ - HAL_NAND_STATE_BUSY = 0x02U, /*!< NAND internal process is ongoing */ - HAL_NAND_STATE_ERROR = 0x03U /*!< NAND error state */ -}HAL_NAND_StateTypeDef; - -/** - * @brief NAND Memory electronic signature Structure definition - */ -typedef struct -{ - /*State = HAL_NAND_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_NAND_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_NAND_STATE_RESET) -#endif - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup NAND_Exported_Functions NAND Exported Functions - * @{ - */ - -/** @addtogroup NAND_Exported_Functions_Group1 Initialization and de-initialization functions - * @{ - */ - -/* Initialization/de-initialization functions ********************************/ -/* Initialization/de-initialization functions ********************************/ -HAL_StatusTypeDef HAL_NAND_Init(NAND_HandleTypeDef *hnand, FMC_NAND_PCC_TimingTypeDef *ComSpace_Timing, FMC_NAND_PCC_TimingTypeDef *AttSpace_Timing); -HAL_StatusTypeDef HAL_NAND_DeInit(NAND_HandleTypeDef *hnand); - -HAL_StatusTypeDef HAL_NAND_ConfigDevice(NAND_HandleTypeDef *hnand, NAND_DeviceConfigTypeDef *pDeviceConfig); - -HAL_StatusTypeDef HAL_NAND_Read_ID(NAND_HandleTypeDef *hnand, NAND_IDTypeDef *pNAND_ID); - -void HAL_NAND_MspInit(NAND_HandleTypeDef *hnand); -void HAL_NAND_MspDeInit(NAND_HandleTypeDef *hnand); -void HAL_NAND_IRQHandler(NAND_HandleTypeDef *hnand); -void HAL_NAND_ITCallback(NAND_HandleTypeDef *hnand); - -/** - * @} - */ - -/** @addtogroup NAND_Exported_Functions_Group2 Input and Output functions - * @{ - */ - -/* IO operation functions ****************************************************/ -HAL_StatusTypeDef HAL_NAND_Reset(NAND_HandleTypeDef *hnand); - -HAL_StatusTypeDef HAL_NAND_Read_Page_8b(NAND_HandleTypeDef *hnand, NAND_AddressTypeDef *pAddress, uint8_t *pBuffer, uint32_t NumPageToRead); -HAL_StatusTypeDef HAL_NAND_Write_Page_8b(NAND_HandleTypeDef *hnand, NAND_AddressTypeDef *pAddress, uint8_t *pBuffer, uint32_t NumPageToWrite); -HAL_StatusTypeDef HAL_NAND_Read_SpareArea_8b(NAND_HandleTypeDef *hnand, NAND_AddressTypeDef *pAddress, uint8_t *pBuffer, uint32_t NumSpareAreaToRead); -HAL_StatusTypeDef HAL_NAND_Write_SpareArea_8b(NAND_HandleTypeDef *hnand, NAND_AddressTypeDef *pAddress, uint8_t *pBuffer, uint32_t NumSpareAreaTowrite); - -HAL_StatusTypeDef HAL_NAND_Read_Page_16b(NAND_HandleTypeDef *hnand, NAND_AddressTypeDef *pAddress, uint16_t *pBuffer, uint32_t NumPageToRead); -HAL_StatusTypeDef HAL_NAND_Write_Page_16b(NAND_HandleTypeDef *hnand, NAND_AddressTypeDef *pAddress, uint16_t *pBuffer, uint32_t NumPageToWrite); -HAL_StatusTypeDef HAL_NAND_Read_SpareArea_16b(NAND_HandleTypeDef *hnand, NAND_AddressTypeDef *pAddress, uint16_t *pBuffer, uint32_t NumSpareAreaToRead); -HAL_StatusTypeDef HAL_NAND_Write_SpareArea_16b(NAND_HandleTypeDef *hnand, NAND_AddressTypeDef *pAddress, uint16_t *pBuffer, uint32_t NumSpareAreaTowrite); - -HAL_StatusTypeDef HAL_NAND_Erase_Block(NAND_HandleTypeDef *hnand, NAND_AddressTypeDef *pAddress); - -uint32_t HAL_NAND_Read_Status(NAND_HandleTypeDef *hnand); -uint32_t HAL_NAND_Address_Inc(NAND_HandleTypeDef *hnand, NAND_AddressTypeDef *pAddress); - -#if (USE_HAL_NAND_REGISTER_CALLBACKS == 1) -/* NAND callback registering/unregistering */ -HAL_StatusTypeDef HAL_NAND_RegisterCallback(NAND_HandleTypeDef *hnand, HAL_NAND_CallbackIDTypeDef CallbackId, pNAND_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_NAND_UnRegisterCallback(NAND_HandleTypeDef *hnand, HAL_NAND_CallbackIDTypeDef CallbackId); -#endif - -/** - * @} - */ - -/** @addtogroup NAND_Exported_Functions_Group3 Peripheral Control functions - * @{ - */ - -/* NAND Control functions ****************************************************/ -HAL_StatusTypeDef HAL_NAND_ECC_Enable(NAND_HandleTypeDef *hnand); -HAL_StatusTypeDef HAL_NAND_ECC_Disable(NAND_HandleTypeDef *hnand); -HAL_StatusTypeDef HAL_NAND_GetECC(NAND_HandleTypeDef *hnand, uint32_t *ECCval, uint32_t Timeout); - -/** - * @} - */ - -/** @addtogroup NAND_Exported_Functions_Group4 Peripheral State functions - * @{ - */ -/* NAND State functions *******************************************************/ -HAL_NAND_StateTypeDef HAL_NAND_GetState(NAND_HandleTypeDef *hnand); -/** - * @} - */ - -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup NAND_Private_Constants NAND Private Constants - * @{ - */ -#define NAND_DEVICE1 0x70000000U -#define NAND_DEVICE2 0x80000000U -#define NAND_WRITE_TIMEOUT 0x01000000U - -#define CMD_AREA ((uint32_t)(1U<<16U)) /* A16 = CLE high */ -#define ADDR_AREA ((uint32_t)(1U<<17U)) /* A17 = ALE high */ - -#define NAND_CMD_AREA_A ((uint8_t)0x00) -#define NAND_CMD_AREA_B ((uint8_t)0x01) -#define NAND_CMD_AREA_C ((uint8_t)0x50) -#define NAND_CMD_AREA_TRUE1 ((uint8_t)0x30) - -#define NAND_CMD_WRITE0 ((uint8_t)0x80) -#define NAND_CMD_WRITE_TRUE1 ((uint8_t)0x10) -#define NAND_CMD_ERASE0 ((uint8_t)0x60) -#define NAND_CMD_ERASE1 ((uint8_t)0xD0) -#define NAND_CMD_READID ((uint8_t)0x90) -#define NAND_CMD_STATUS ((uint8_t)0x70) -#define NAND_CMD_LOCK_STATUS ((uint8_t)0x7A) -#define NAND_CMD_RESET ((uint8_t)0xFF) - -/* NAND memory status */ -#define NAND_VALID_ADDRESS 0x00000100U -#define NAND_INVALID_ADDRESS 0x00000200U -#define NAND_TIMEOUT_ERROR 0x00000400U -#define NAND_BUSY 0x00000000U -#define NAND_ERROR 0x00000001U -#define NAND_READY 0x00000040U -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup NAND_Private_Macros NAND Private Macros - * @{ - */ - -/** - * @brief NAND memory address computation. - * @param __ADDRESS__ NAND memory address. - * @param __HANDLE__ NAND handle. - * @retval NAND Raw address value - */ -#define ARRAY_ADDRESS(__ADDRESS__ , __HANDLE__) ((__ADDRESS__)->Page + \ - (((__ADDRESS__)->Block + (((__ADDRESS__)->Plane) * ((__HANDLE__)->Config.PlaneSize)))* ((__HANDLE__)->Config.BlockSize))) - -/** - * @brief NAND memory Column address computation. - * @param __HANDLE__ NAND handle. - * @retval NAND Raw address value - */ -#define COLUMN_ADDRESS( __HANDLE__) ((__HANDLE__)->Config.PageSize) - -/** - * @brief NAND memory address cycling. - * @param __ADDRESS__ NAND memory address. - * @retval NAND address cycling value. - */ -#define ADDR_1ST_CYCLE(__ADDRESS__) (uint8_t)(__ADDRESS__) /* 1st addressing cycle */ -#define ADDR_2ND_CYCLE(__ADDRESS__) (uint8_t)((__ADDRESS__) >> 8) /* 2nd addressing cycle */ -#define ADDR_3RD_CYCLE(__ADDRESS__) (uint8_t)((__ADDRESS__) >> 16) /* 3rd addressing cycle */ -#define ADDR_4TH_CYCLE(__ADDRESS__) (uint8_t)((__ADDRESS__) >> 24) /* 4th addressing cycle */ - -/** - * @brief NAND memory Columns cycling. - * @param __ADDRESS__ NAND memory address. - * @retval NAND Column address cycling value. - */ -#define COLUMN_1ST_CYCLE(__ADDRESS__) (uint8_t)(__ADDRESS__) /* 1st Column addressing cycle */ -#define COLUMN_2ND_CYCLE(__ADDRESS__) (uint8_t)((__ADDRESS__) >> 8) /* 2nd Column addressing cycle */ - -/** - * @} - */ -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx ||\ - STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx ||\ - STM32F446xx || STM32F469xx || STM32F479xx */ - -/** - * @} - */ -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_NAND_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_nor.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_nor.h deleted file mode 100644 index dcd25c5..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_nor.h +++ /dev/null @@ -1,326 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_nor.h - * @author MCD Application Team - * @brief Header file of NOR HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_NOR_H -#define __STM32F4xx_HAL_NOR_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || defined(STM32F412Zx) ||\ - defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) - #include "stm32f4xx_ll_fsmc.h" -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F413xx || STM32F423xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) - #include "stm32f4xx_ll_fmc.h" -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup NOR - * @{ - */ - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) ||\ - defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) ||\ - defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) - -/* Exported typedef ----------------------------------------------------------*/ -/** @defgroup NOR_Exported_Types NOR Exported Types - * @{ - */ - -/** - * @brief HAL SRAM State structures definition - */ -typedef enum -{ - HAL_NOR_STATE_RESET = 0x00U, /*!< NOR not yet initialized or disabled */ - HAL_NOR_STATE_READY = 0x01U, /*!< NOR initialized and ready for use */ - HAL_NOR_STATE_BUSY = 0x02U, /*!< NOR internal processing is ongoing */ - HAL_NOR_STATE_ERROR = 0x03U, /*!< NOR error state */ - HAL_NOR_STATE_PROTECTED = 0x04U /*!< NOR NORSRAM device write protected */ -}HAL_NOR_StateTypeDef; - -/** - * @brief FMC NOR Status typedef - */ -typedef enum -{ - HAL_NOR_STATUS_SUCCESS = 0U, - HAL_NOR_STATUS_ONGOING, - HAL_NOR_STATUS_ERROR, - HAL_NOR_STATUS_TIMEOUT -}HAL_NOR_StatusTypeDef; - -/** - * @brief FMC NOR ID typedef - */ -typedef struct -{ - uint16_t Manufacturer_Code; /*!< Defines the device's manufacturer code used to identify the memory */ - - uint16_t Device_Code1; - - uint16_t Device_Code2; - - uint16_t Device_Code3; /*!< Defines the device's codes used to identify the memory. - These codes can be accessed by performing read operations with specific - control signals and addresses set.They can also be accessed by issuing - an Auto Select command */ -}NOR_IDTypeDef; - -/** - * @brief FMC NOR CFI typedef - */ -typedef struct -{ - /*!< Defines the information stored in the memory's Common flash interface - which contains a description of various electrical and timing parameters, - density information and functions supported by the memory */ - - uint16_t CFI_1; - - uint16_t CFI_2; - - uint16_t CFI_3; - - uint16_t CFI_4; -}NOR_CFITypeDef; - -/** - * @brief NOR handle Structure definition - */ -#if (USE_HAL_NOR_REGISTER_CALLBACKS == 1) -typedef struct __NOR_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_NOR_REGISTER_CALLBACKS */ - -{ - FMC_NORSRAM_TypeDef *Instance; /*!< Register base address */ - - FMC_NORSRAM_EXTENDED_TypeDef *Extended; /*!< Extended mode register base address */ - - FMC_NORSRAM_InitTypeDef Init; /*!< NOR device control configuration parameters */ - - HAL_LockTypeDef Lock; /*!< NOR locking object */ - - __IO HAL_NOR_StateTypeDef State; /*!< NOR device access state */ - -#if (USE_HAL_NOR_REGISTER_CALLBACKS == 1) - void (* MspInitCallback) ( struct __NOR_HandleTypeDef * hnor); /*!< NOR Msp Init callback */ - void (* MspDeInitCallback) ( struct __NOR_HandleTypeDef * hnor); /*!< NOR Msp DeInit callback */ -#endif -} NOR_HandleTypeDef; - -#if (USE_HAL_NOR_REGISTER_CALLBACKS == 1) -/** - * @brief HAL NOR Callback ID enumeration definition - */ -typedef enum -{ - HAL_NOR_MSP_INIT_CB_ID = 0x00U, /*!< NOR MspInit Callback ID */ - HAL_NOR_MSP_DEINIT_CB_ID = 0x01U /*!< NOR MspDeInit Callback ID */ -}HAL_NOR_CallbackIDTypeDef; - -/** - * @brief HAL NOR Callback pointer definition - */ -typedef void (*pNOR_CallbackTypeDef)(NOR_HandleTypeDef *hnor); -#endif -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/* Exported macros ------------------------------------------------------------*/ -/** @defgroup NOR_Exported_Macros NOR Exported Macros - * @{ - */ -/** @brief Reset NOR handle state - * @param __HANDLE__ specifies the NOR handle. - * @retval None - */ -#if (USE_HAL_NOR_REGISTER_CALLBACKS == 1) -#define __HAL_NOR_RESET_HANDLE_STATE(__HANDLE__) do { \ - (__HANDLE__)->State = HAL_NOR_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_NOR_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_NOR_STATE_RESET) -#endif -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup NOR_Exported_Functions - * @{ - */ - -/** @addtogroup NOR_Exported_Functions_Group1 - * @{ - */ -/* Initialization/de-initialization functions ********************************/ -HAL_StatusTypeDef HAL_NOR_Init(NOR_HandleTypeDef *hnor, FMC_NORSRAM_TimingTypeDef *Timing, FMC_NORSRAM_TimingTypeDef *ExtTiming); -HAL_StatusTypeDef HAL_NOR_DeInit(NOR_HandleTypeDef *hnor); -void HAL_NOR_MspInit(NOR_HandleTypeDef *hnor); -void HAL_NOR_MspDeInit(NOR_HandleTypeDef *hnor); -void HAL_NOR_MspWait(NOR_HandleTypeDef *hnor, uint32_t Timeout); -/** - * @} - */ - -/** @addtogroup NOR_Exported_Functions_Group2 - * @{ - */ -/* I/O operation functions ***************************************************/ -HAL_StatusTypeDef HAL_NOR_Read_ID(NOR_HandleTypeDef *hnor, NOR_IDTypeDef *pNOR_ID); -HAL_StatusTypeDef HAL_NOR_ReturnToReadMode(NOR_HandleTypeDef *hnor); -HAL_StatusTypeDef HAL_NOR_Read(NOR_HandleTypeDef *hnor, uint32_t *pAddress, uint16_t *pData); -HAL_StatusTypeDef HAL_NOR_Program(NOR_HandleTypeDef *hnor, uint32_t *pAddress, uint16_t *pData); - -HAL_StatusTypeDef HAL_NOR_ReadBuffer(NOR_HandleTypeDef *hnor, uint32_t uwAddress, uint16_t *pData, uint32_t uwBufferSize); -HAL_StatusTypeDef HAL_NOR_ProgramBuffer(NOR_HandleTypeDef *hnor, uint32_t uwAddress, uint16_t *pData, uint32_t uwBufferSize); - -HAL_StatusTypeDef HAL_NOR_Erase_Block(NOR_HandleTypeDef *hnor, uint32_t BlockAddress, uint32_t Address); -HAL_StatusTypeDef HAL_NOR_Erase_Chip(NOR_HandleTypeDef *hnor, uint32_t Address); -HAL_StatusTypeDef HAL_NOR_Read_CFI(NOR_HandleTypeDef *hnor, NOR_CFITypeDef *pNOR_CFI); - -#if (USE_HAL_NOR_REGISTER_CALLBACKS == 1) -/* NOR callback registering/unregistering */ -HAL_StatusTypeDef HAL_NOR_RegisterCallback(NOR_HandleTypeDef *hnor, HAL_NOR_CallbackIDTypeDef CallbackId, pNOR_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_NOR_UnRegisterCallback(NOR_HandleTypeDef *hnor, HAL_NOR_CallbackIDTypeDef CallbackId); -#endif -/** - * @} - */ - -/** @addtogroup NOR_Exported_Functions_Group3 - * @{ - */ -/* NOR Control functions *****************************************************/ -HAL_StatusTypeDef HAL_NOR_WriteOperation_Enable(NOR_HandleTypeDef *hnor); -HAL_StatusTypeDef HAL_NOR_WriteOperation_Disable(NOR_HandleTypeDef *hnor); -/** - * @} - */ - -/** @addtogroup NOR_Exported_Functions_Group4 - * @{ - */ -/* NOR State functions ********************************************************/ -HAL_NOR_StateTypeDef HAL_NOR_GetState(NOR_HandleTypeDef *hnor); -HAL_NOR_StatusTypeDef HAL_NOR_GetStatus(NOR_HandleTypeDef *hnor, uint32_t Address, uint32_t Timeout); -/** - * @} - */ - -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup NOR_Private_Constants NOR Private Constants - * @{ - */ -/* NOR device IDs addresses */ -#define MC_ADDRESS ((uint16_t)0x0000) -#define DEVICE_CODE1_ADDR ((uint16_t)0x0001) -#define DEVICE_CODE2_ADDR ((uint16_t)0x000E) -#define DEVICE_CODE3_ADDR ((uint16_t)0x000F) - -/* NOR CFI IDs addresses */ -#define CFI1_ADDRESS ((uint16_t)0x0061) -#define CFI2_ADDRESS ((uint16_t)0x0062) -#define CFI3_ADDRESS ((uint16_t)0x0063) -#define CFI4_ADDRESS ((uint16_t)0x0064) - -/* NOR operation wait timeout */ -#define NOR_TMEOUT ((uint16_t)0xFFFF) - -/* NOR memory data width */ -#define NOR_MEMORY_8B ((uint8_t)0x00) -#define NOR_MEMORY_16B ((uint8_t)0x01) - -/* NOR memory device read/write start address */ -#define NOR_MEMORY_ADRESS1 0x60000000U -#define NOR_MEMORY_ADRESS2 0x64000000U -#define NOR_MEMORY_ADRESS3 0x68000000U -#define NOR_MEMORY_ADRESS4 0x6C000000U -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup NOR_Private_Macros NOR Private Macros - * @{ - */ -/** - * @brief NOR memory address shifting. - * @param __NOR_ADDRESS__ NOR base address - * @param NOR_MEMORY_WIDTH NOR memory width - * @param ADDRESS NOR memory address - * @retval NOR shifted address value - */ -#define NOR_ADDR_SHIFT(__NOR_ADDRESS__, NOR_MEMORY_WIDTH, ADDRESS) (uint32_t)(((NOR_MEMORY_WIDTH) == NOR_MEMORY_16B)? ((uint32_t)((__NOR_ADDRESS__) + (2U * (ADDRESS)))):\ - ((uint32_t)((__NOR_ADDRESS__) + (ADDRESS)))) - -/** - * @brief NOR memory write data to specified address. - * @param ADDRESS NOR memory address - * @param DATA Data to write - * @retval None - */ -#define NOR_WRITE(ADDRESS, DATA) (*(__IO uint16_t *)((uint32_t)(ADDRESS)) = (DATA)) - -/** - * @} - */ -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx ||\ - STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx ||\ - STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx ||\ - STM32F412Vx || STM32F412Rx || STM32F413xx || STM32F423xx */ -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_NOR_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pccard.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pccard.h deleted file mode 100644 index 41d7824..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pccard.h +++ /dev/null @@ -1,287 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_pccard.h - * @author MCD Application Team - * @brief Header file of PCCARD HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_PCCARD_H -#define __STM32F4xx_HAL_PCCARD_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) - #include "stm32f4xx_ll_fsmc.h" -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) - #include "stm32f4xx_ll_fmc.h" -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx */ - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) ||\ - defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) - -/** @addtogroup PCCARD - * @{ - */ - -/* Exported typedef ----------------------------------------------------------*/ -/** @defgroup PCCARD_Exported_Types PCCARD Exported Types - * @{ - */ - -/** - * @brief HAL PCCARD State structures definition - */ -typedef enum -{ - HAL_PCCARD_STATE_RESET = 0x00U, /*!< PCCARD peripheral not yet initialized or disabled */ - HAL_PCCARD_STATE_READY = 0x01U, /*!< PCCARD peripheral ready */ - HAL_PCCARD_STATE_BUSY = 0x02U, /*!< PCCARD peripheral busy */ - HAL_PCCARD_STATE_ERROR = 0x04U /*!< PCCARD peripheral error */ -}HAL_PCCARD_StateTypeDef; - -typedef enum -{ - HAL_PCCARD_STATUS_SUCCESS = 0U, - HAL_PCCARD_STATUS_ONGOING, - HAL_PCCARD_STATUS_ERROR, - HAL_PCCARD_STATUS_TIMEOUT -}HAL_PCCARD_StatusTypeDef; - -/** - * @brief FMC_PCCARD handle Structure definition - */ -#if (USE_HAL_PCCARD_REGISTER_CALLBACKS == 1) -typedef struct __PCCARD_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_PCCARD_REGISTER_CALLBACKS */ -{ - FMC_PCCARD_TypeDef *Instance; /*!< Register base address for PCCARD device */ - - FMC_PCCARD_InitTypeDef Init; /*!< PCCARD device control configuration parameters */ - - __IO HAL_PCCARD_StateTypeDef State; /*!< PCCARD device access state */ - - HAL_LockTypeDef Lock; /*!< PCCARD Lock */ - -#if (USE_HAL_PCCARD_REGISTER_CALLBACKS == 1) - void (* MspInitCallback) ( struct __PCCARD_HandleTypeDef * hpccard); /*!< PCCARD Msp Init callback */ - void (* MspDeInitCallback) ( struct __PCCARD_HandleTypeDef * hpccard); /*!< PCCARD Msp DeInit callback */ - void (* ItCallback) ( struct __PCCARD_HandleTypeDef * hpccard); /*!< PCCARD IT callback */ -#endif -} PCCARD_HandleTypeDef; - -#if (USE_HAL_PCCARD_REGISTER_CALLBACKS == 1) -/** - * @brief HAL PCCARD Callback ID enumeration definition - */ -typedef enum -{ - HAL_PCCARD_MSP_INIT_CB_ID = 0x00U, /*!< PCCARD MspInit Callback ID */ - HAL_PCCARD_MSP_DEINIT_CB_ID = 0x01U, /*!< PCCARD MspDeInit Callback ID */ - HAL_PCCARD_IT_CB_ID = 0x02U /*!< PCCARD IT Callback ID */ -}HAL_PCCARD_CallbackIDTypeDef; - -/** - * @brief HAL PCCARD Callback pointer definition - */ -typedef void (*pPCCARD_CallbackTypeDef)(PCCARD_HandleTypeDef *hpccard); -#endif -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup PCCARD_Exported_Macros PCCARD Exported Macros - * @{ - */ -/** @brief Reset PCCARD handle state - * @param __HANDLE__ specifies the PCCARD handle. - * @retval None - */ -#if (USE_HAL_PCCARD_REGISTER_CALLBACKS == 1) -#define __HAL_PCCARD_RESET_HANDLE_STATE(__HANDLE__) do { \ - (__HANDLE__)->State = HAL_PCCARD_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_PCCARD_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_PCCARD_STATE_RESET) -#endif -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup PCCARD_Exported_Functions - * @{ - */ - -/** @addtogroup PCCARD_Exported_Functions_Group1 - * @{ - */ -/* Initialization/de-initialization functions **********************************/ -HAL_StatusTypeDef HAL_PCCARD_Init(PCCARD_HandleTypeDef *hpccard, FMC_NAND_PCC_TimingTypeDef *ComSpaceTiming, FMC_NAND_PCC_TimingTypeDef *AttSpaceTiming, FMC_NAND_PCC_TimingTypeDef *IOSpaceTiming); -HAL_StatusTypeDef HAL_PCCARD_DeInit(PCCARD_HandleTypeDef *hpccard); -void HAL_PCCARD_MspInit(PCCARD_HandleTypeDef *hpccard); -void HAL_PCCARD_MspDeInit(PCCARD_HandleTypeDef *hpccard); -/** - * @} - */ - -/** @addtogroup PCCARD_Exported_Functions_Group2 - * @{ - */ -/* IO operation functions *****************************************************/ -HAL_StatusTypeDef HAL_PCCARD_Read_ID(PCCARD_HandleTypeDef *hpccard, uint8_t CompactFlash_ID[], uint8_t *pStatus); -HAL_StatusTypeDef HAL_PCCARD_Write_Sector(PCCARD_HandleTypeDef *hpccard, uint16_t *pBuffer, uint16_t SectorAddress, uint8_t *pStatus); -HAL_StatusTypeDef HAL_PCCARD_Read_Sector(PCCARD_HandleTypeDef *hpccard, uint16_t *pBuffer, uint16_t SectorAddress, uint8_t *pStatus); -HAL_StatusTypeDef HAL_PCCARD_Erase_Sector(PCCARD_HandleTypeDef *hpccard, uint16_t SectorAddress, uint8_t *pStatus); -HAL_StatusTypeDef HAL_PCCARD_Reset(PCCARD_HandleTypeDef *hpccard); -void HAL_PCCARD_IRQHandler(PCCARD_HandleTypeDef *hpccard); -void HAL_PCCARD_ITCallback(PCCARD_HandleTypeDef *hpccard); - -#if (USE_HAL_PCCARD_REGISTER_CALLBACKS == 1) -/* PCCARD callback registering/unregistering */ -HAL_StatusTypeDef HAL_PCCARD_RegisterCallback(PCCARD_HandleTypeDef *hpccard, HAL_PCCARD_CallbackIDTypeDef CallbackId, pPCCARD_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_PCCARD_UnRegisterCallback(PCCARD_HandleTypeDef *hpccard, HAL_PCCARD_CallbackIDTypeDef CallbackId); -#endif -/** - * @} - */ - -/** @addtogroup PCCARD_Exported_Functions_Group3 - * @{ - */ -/* PCCARD State functions *******************************************************/ -HAL_PCCARD_StateTypeDef HAL_PCCARD_GetState(PCCARD_HandleTypeDef *hpccard); -HAL_PCCARD_StatusTypeDef HAL_PCCARD_GetStatus(PCCARD_HandleTypeDef *hpccard); -HAL_PCCARD_StatusTypeDef HAL_PCCARD_ReadStatus(PCCARD_HandleTypeDef *hpccard); -/** - * @} - */ - -/** - * @} - */ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup PCCARD_Private_Constants PCCARD Private Constants - * @{ - */ -#define PCCARD_DEVICE_ADDRESS 0x90000000U -#define PCCARD_ATTRIBUTE_SPACE_ADDRESS 0x98000000U /* Attribute space size to @0x9BFF FFFF */ -#define PCCARD_COMMON_SPACE_ADDRESS PCCARD_DEVICE_ADDRESS /* Common space size to @0x93FF FFFF */ -#define PCCARD_IO_SPACE_ADDRESS 0x9C000000U /* IO space size to @0x9FFF FFFF */ -#define PCCARD_IO_SPACE_PRIMARY_ADDR 0x9C0001F0U /* IO space size to @0x9FFF FFFF */ - -/* Flash-ATA registers description */ -#define ATA_DATA ((uint8_t)0x00) /* Data register */ -#define ATA_SECTOR_COUNT ((uint8_t)0x02) /* Sector Count register */ -#define ATA_SECTOR_NUMBER ((uint8_t)0x03) /* Sector Number register */ -#define ATA_CYLINDER_LOW ((uint8_t)0x04) /* Cylinder low register */ -#define ATA_CYLINDER_HIGH ((uint8_t)0x05) /* Cylinder high register */ -#define ATA_CARD_HEAD ((uint8_t)0x06) /* Card/Head register */ -#define ATA_STATUS_CMD ((uint8_t)0x07) /* Status(read)/Command(write) register */ -#define ATA_STATUS_CMD_ALTERNATE ((uint8_t)0x0E) /* Alternate Status(read)/Command(write) register */ -#define ATA_COMMON_DATA_AREA ((uint16_t)0x0400) /* Start of data area (for Common access only!) */ -#define ATA_CARD_CONFIGURATION ((uint16_t)0x0202) /* Card Configuration and Status Register */ - -/* Flash-ATA commands */ -#define ATA_READ_SECTOR_CMD ((uint8_t)0x20) -#define ATA_WRITE_SECTOR_CMD ((uint8_t)0x30) -#define ATA_ERASE_SECTOR_CMD ((uint8_t)0xC0) -#define ATA_IDENTIFY_CMD ((uint8_t)0xEC) - -/* PC Card/Compact Flash status */ -#define PCCARD_TIMEOUT_ERROR ((uint8_t)0x60) -#define PCCARD_BUSY ((uint8_t)0x80) -#define PCCARD_PROGR ((uint8_t)0x01) -#define PCCARD_READY ((uint8_t)0x40) - -#define PCCARD_SECTOR_SIZE 255U /* In half words */ - -/** - * @} - */ -/* Compact Flash redefinition */ -#define HAL_CF_Init HAL_PCCARD_Init -#define HAL_CF_DeInit HAL_PCCARD_DeInit -#define HAL_CF_MspInit HAL_PCCARD_MspInit -#define HAL_CF_MspDeInit HAL_PCCARD_MspDeInit - -#define HAL_CF_Read_ID HAL_PCCARD_Read_ID -#define HAL_CF_Write_Sector HAL_PCCARD_Write_Sector -#define HAL_CF_Read_Sector HAL_PCCARD_Read_Sector -#define HAL_CF_Erase_Sector HAL_PCCARD_Erase_Sector -#define HAL_CF_Reset HAL_PCCARD_Reset -#define HAL_CF_IRQHandler HAL_PCCARD_IRQHandler -#define HAL_CF_ITCallback HAL_PCCARD_ITCallback - -#define HAL_CF_GetState HAL_PCCARD_GetState -#define HAL_CF_GetStatus HAL_PCCARD_GetStatus -#define HAL_CF_ReadStatus HAL_PCCARD_ReadStatus - -#define HAL_CF_STATUS_SUCCESS HAL_PCCARD_STATUS_SUCCESS -#define HAL_CF_STATUS_ONGOING HAL_PCCARD_STATUS_ONGOING -#define HAL_CF_STATUS_ERROR HAL_PCCARD_STATUS_ERROR -#define HAL_CF_STATUS_TIMEOUT HAL_PCCARD_STATUS_TIMEOUT -#define HAL_CF_StatusTypeDef HAL_PCCARD_StatusTypeDef - -#define CF_DEVICE_ADDRESS PCCARD_DEVICE_ADDRESS -#define CF_ATTRIBUTE_SPACE_ADDRESS PCCARD_ATTRIBUTE_SPACE_ADDRESS -#define CF_COMMON_SPACE_ADDRESS PCCARD_COMMON_SPACE_ADDRESS -#define CF_IO_SPACE_ADDRESS PCCARD_IO_SPACE_ADDRESS -#define CF_IO_SPACE_PRIMARY_ADDR PCCARD_IO_SPACE_PRIMARY_ADDR - -#define CF_TIMEOUT_ERROR PCCARD_TIMEOUT_ERROR -#define CF_BUSY PCCARD_BUSY -#define CF_PROGR PCCARD_PROGR -#define CF_READY PCCARD_READY - -#define CF_SECTOR_SIZE PCCARD_SECTOR_SIZE - -/* Private macros ------------------------------------------------------------*/ -/** - * @} - */ - -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx ||\ - STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx */ - - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_PCCARD_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pcd.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pcd.h deleted file mode 100644 index e28285d..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pcd.h +++ /dev/null @@ -1,472 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_pcd.h - * @author MCD Application Team - * @brief Header file of PCD HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_PCD_H -#define STM32F4xx_HAL_PCD_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_ll_usb.h" - -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup PCD - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup PCD_Exported_Types PCD Exported Types - * @{ - */ - -/** - * @brief PCD State structure definition - */ -typedef enum -{ - HAL_PCD_STATE_RESET = 0x00, - HAL_PCD_STATE_READY = 0x01, - HAL_PCD_STATE_ERROR = 0x02, - HAL_PCD_STATE_BUSY = 0x03, - HAL_PCD_STATE_TIMEOUT = 0x04 -} PCD_StateTypeDef; - -/* Device LPM suspend state */ -typedef enum -{ - LPM_L0 = 0x00, /* on */ - LPM_L1 = 0x01, /* LPM L1 sleep */ - LPM_L2 = 0x02, /* suspend */ - LPM_L3 = 0x03, /* off */ -} PCD_LPM_StateTypeDef; - -typedef enum -{ - PCD_LPM_L0_ACTIVE = 0x00, /* on */ - PCD_LPM_L1_ACTIVE = 0x01, /* LPM L1 sleep */ -} PCD_LPM_MsgTypeDef; - -typedef enum -{ - PCD_BCD_ERROR = 0xFF, - PCD_BCD_CONTACT_DETECTION = 0xFE, - PCD_BCD_STD_DOWNSTREAM_PORT = 0xFD, - PCD_BCD_CHARGING_DOWNSTREAM_PORT = 0xFC, - PCD_BCD_DEDICATED_CHARGING_PORT = 0xFB, - PCD_BCD_DISCOVERY_COMPLETED = 0x00, - -} PCD_BCD_MsgTypeDef; - -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -typedef USB_OTG_GlobalTypeDef PCD_TypeDef; -typedef USB_OTG_CfgTypeDef PCD_InitTypeDef; -typedef USB_OTG_EPTypeDef PCD_EPTypeDef; -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ - -/** - * @brief PCD Handle Structure definition - */ -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) -typedef struct __PCD_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ -{ - PCD_TypeDef *Instance; /*!< Register base address */ - PCD_InitTypeDef Init; /*!< PCD required parameters */ - __IO uint8_t USB_Address; /*!< USB Address */ - PCD_EPTypeDef IN_ep[16]; /*!< IN endpoint parameters */ - PCD_EPTypeDef OUT_ep[16]; /*!< OUT endpoint parameters */ - HAL_LockTypeDef Lock; /*!< PCD peripheral status */ - __IO PCD_StateTypeDef State; /*!< PCD communication state */ - __IO uint32_t ErrorCode; /*!< PCD Error code */ - uint32_t Setup[12]; /*!< Setup packet buffer */ - PCD_LPM_StateTypeDef LPM_State; /*!< LPM State */ - uint32_t BESL; - - - uint32_t lpm_active; /*!< Enable or disable the Link Power Management . - This parameter can be set to ENABLE or DISABLE */ - - uint32_t battery_charging_active; /*!< Enable or disable Battery charging. - This parameter can be set to ENABLE or DISABLE */ - void *pData; /*!< Pointer to upper stack Handler */ - -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) - void (* SOFCallback)(struct __PCD_HandleTypeDef *hpcd); /*!< USB OTG PCD SOF callback */ - void (* SetupStageCallback)(struct __PCD_HandleTypeDef *hpcd); /*!< USB OTG PCD Setup Stage callback */ - void (* ResetCallback)(struct __PCD_HandleTypeDef *hpcd); /*!< USB OTG PCD Reset callback */ - void (* SuspendCallback)(struct __PCD_HandleTypeDef *hpcd); /*!< USB OTG PCD Suspend callback */ - void (* ResumeCallback)(struct __PCD_HandleTypeDef *hpcd); /*!< USB OTG PCD Resume callback */ - void (* ConnectCallback)(struct __PCD_HandleTypeDef *hpcd); /*!< USB OTG PCD Connect callback */ - void (* DisconnectCallback)(struct __PCD_HandleTypeDef *hpcd); /*!< USB OTG PCD Disconnect callback */ - - void (* DataOutStageCallback)(struct __PCD_HandleTypeDef *hpcd, uint8_t epnum); /*!< USB OTG PCD Data OUT Stage callback */ - void (* DataInStageCallback)(struct __PCD_HandleTypeDef *hpcd, uint8_t epnum); /*!< USB OTG PCD Data IN Stage callback */ - void (* ISOOUTIncompleteCallback)(struct __PCD_HandleTypeDef *hpcd, uint8_t epnum); /*!< USB OTG PCD ISO OUT Incomplete callback */ - void (* ISOINIncompleteCallback)(struct __PCD_HandleTypeDef *hpcd, uint8_t epnum); /*!< USB OTG PCD ISO IN Incomplete callback */ - void (* BCDCallback)(struct __PCD_HandleTypeDef *hpcd, PCD_BCD_MsgTypeDef msg); /*!< USB OTG PCD BCD callback */ - void (* LPMCallback)(struct __PCD_HandleTypeDef *hpcd, PCD_LPM_MsgTypeDef msg); /*!< USB OTG PCD LPM callback */ - - void (* MspInitCallback)(struct __PCD_HandleTypeDef *hpcd); /*!< USB OTG PCD Msp Init callback */ - void (* MspDeInitCallback)(struct __PCD_HandleTypeDef *hpcd); /*!< USB OTG PCD Msp DeInit callback */ -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ -} PCD_HandleTypeDef; - -/** - * @} - */ - -/* Include PCD HAL Extended module */ -#include "stm32f4xx_hal_pcd_ex.h" - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup PCD_Exported_Constants PCD Exported Constants - * @{ - */ - -/** @defgroup PCD_Speed PCD Speed - * @{ - */ -#define PCD_SPEED_HIGH USBD_HS_SPEED -#define PCD_SPEED_HIGH_IN_FULL USBD_HSINFS_SPEED -#define PCD_SPEED_FULL USBD_FS_SPEED -/** - * @} - */ - -/** @defgroup PCD_PHY_Module PCD PHY Module - * @{ - */ -#define PCD_PHY_ULPI 1U -#define PCD_PHY_EMBEDDED 2U -#define PCD_PHY_UTMI 3U -/** - * @} - */ - -/** @defgroup PCD_Error_Code_definition PCD Error Code definition - * @brief PCD Error Code definition - * @{ - */ -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) -#define HAL_PCD_ERROR_INVALID_CALLBACK (0x00000010U) /*!< Invalid Callback error */ -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** - * @} - */ - -/* Exported macros -----------------------------------------------------------*/ -/** @defgroup PCD_Exported_Macros PCD Exported Macros - * @brief macros to handle interrupts and specific clock configurations - * @{ - */ -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -#define __HAL_PCD_ENABLE(__HANDLE__) (void)USB_EnableGlobalInt ((__HANDLE__)->Instance) -#define __HAL_PCD_DISABLE(__HANDLE__) (void)USB_DisableGlobalInt ((__HANDLE__)->Instance) - -#define __HAL_PCD_GET_FLAG(__HANDLE__, __INTERRUPT__) \ - ((USB_ReadInterrupts((__HANDLE__)->Instance) & (__INTERRUPT__)) == (__INTERRUPT__)) - -#define __HAL_PCD_CLEAR_FLAG(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->GINTSTS) &= (__INTERRUPT__)) -#define __HAL_PCD_IS_INVALID_INTERRUPT(__HANDLE__) (USB_ReadInterrupts((__HANDLE__)->Instance) == 0U) - -#define __HAL_PCD_UNGATE_PHYCLOCK(__HANDLE__) \ - *(__IO uint32_t *)((uint32_t)((__HANDLE__)->Instance) + USB_OTG_PCGCCTL_BASE) &= ~(USB_OTG_PCGCCTL_STOPCLK) - -#define __HAL_PCD_GATE_PHYCLOCK(__HANDLE__) \ - *(__IO uint32_t *)((uint32_t)((__HANDLE__)->Instance) + USB_OTG_PCGCCTL_BASE) |= USB_OTG_PCGCCTL_STOPCLK - -#define __HAL_PCD_IS_PHY_SUSPENDED(__HANDLE__) \ - ((*(__IO uint32_t *)((uint32_t)((__HANDLE__)->Instance) + USB_OTG_PCGCCTL_BASE)) & 0x10U) - -#define __HAL_USB_OTG_HS_WAKEUP_EXTI_ENABLE_IT() EXTI->IMR |= (USB_OTG_HS_WAKEUP_EXTI_LINE) -#define __HAL_USB_OTG_HS_WAKEUP_EXTI_DISABLE_IT() EXTI->IMR &= ~(USB_OTG_HS_WAKEUP_EXTI_LINE) -#define __HAL_USB_OTG_HS_WAKEUP_EXTI_GET_FLAG() EXTI->PR & (USB_OTG_HS_WAKEUP_EXTI_LINE) -#define __HAL_USB_OTG_HS_WAKEUP_EXTI_CLEAR_FLAG() EXTI->PR = (USB_OTG_HS_WAKEUP_EXTI_LINE) - -#define __HAL_USB_OTG_HS_WAKEUP_EXTI_ENABLE_RISING_EDGE() \ - do { \ - EXTI->FTSR &= ~(USB_OTG_HS_WAKEUP_EXTI_LINE); \ - EXTI->RTSR |= USB_OTG_HS_WAKEUP_EXTI_LINE; \ - } while(0U) -#define __HAL_USB_OTG_FS_WAKEUP_EXTI_ENABLE_IT() EXTI->IMR |= USB_OTG_FS_WAKEUP_EXTI_LINE -#define __HAL_USB_OTG_FS_WAKEUP_EXTI_DISABLE_IT() EXTI->IMR &= ~(USB_OTG_FS_WAKEUP_EXTI_LINE) -#define __HAL_USB_OTG_FS_WAKEUP_EXTI_GET_FLAG() EXTI->PR & (USB_OTG_FS_WAKEUP_EXTI_LINE) -#define __HAL_USB_OTG_FS_WAKEUP_EXTI_CLEAR_FLAG() EXTI->PR = USB_OTG_FS_WAKEUP_EXTI_LINE - -#define __HAL_USB_OTG_FS_WAKEUP_EXTI_ENABLE_RISING_EDGE() \ - do { \ - EXTI->FTSR &= ~(USB_OTG_FS_WAKEUP_EXTI_LINE); \ - EXTI->RTSR |= USB_OTG_FS_WAKEUP_EXTI_LINE; \ - } while(0U) -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ - - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup PCD_Exported_Functions PCD Exported Functions - * @{ - */ - -/* Initialization/de-initialization functions ********************************/ -/** @addtogroup PCD_Exported_Functions_Group1 Initialization and de-initialization functions - * @{ - */ -HAL_StatusTypeDef HAL_PCD_Init(PCD_HandleTypeDef *hpcd); -HAL_StatusTypeDef HAL_PCD_DeInit(PCD_HandleTypeDef *hpcd); -void HAL_PCD_MspInit(PCD_HandleTypeDef *hpcd); -void HAL_PCD_MspDeInit(PCD_HandleTypeDef *hpcd); - -#if (USE_HAL_PCD_REGISTER_CALLBACKS == 1U) -/** @defgroup HAL_PCD_Callback_ID_enumeration_definition HAL USB OTG PCD Callback ID enumeration definition - * @brief HAL USB OTG PCD Callback ID enumeration definition - * @{ - */ -typedef enum -{ - HAL_PCD_SOF_CB_ID = 0x01, /*!< USB PCD SOF callback ID */ - HAL_PCD_SETUPSTAGE_CB_ID = 0x02, /*!< USB PCD Setup Stage callback ID */ - HAL_PCD_RESET_CB_ID = 0x03, /*!< USB PCD Reset callback ID */ - HAL_PCD_SUSPEND_CB_ID = 0x04, /*!< USB PCD Suspend callback ID */ - HAL_PCD_RESUME_CB_ID = 0x05, /*!< USB PCD Resume callback ID */ - HAL_PCD_CONNECT_CB_ID = 0x06, /*!< USB PCD Connect callback ID */ - HAL_PCD_DISCONNECT_CB_ID = 0x07, /*!< USB PCD Disconnect callback ID */ - - HAL_PCD_MSPINIT_CB_ID = 0x08, /*!< USB PCD MspInit callback ID */ - HAL_PCD_MSPDEINIT_CB_ID = 0x09 /*!< USB PCD MspDeInit callback ID */ - -} HAL_PCD_CallbackIDTypeDef; -/** - * @} - */ - -/** @defgroup HAL_PCD_Callback_pointer_definition HAL USB OTG PCD Callback pointer definition - * @brief HAL USB OTG PCD Callback pointer definition - * @{ - */ - -typedef void (*pPCD_CallbackTypeDef)(PCD_HandleTypeDef *hpcd); /*!< pointer to a common USB OTG PCD callback function */ -typedef void (*pPCD_DataOutStageCallbackTypeDef)(PCD_HandleTypeDef *hpcd, uint8_t epnum); /*!< pointer to USB OTG PCD Data OUT Stage callback */ -typedef void (*pPCD_DataInStageCallbackTypeDef)(PCD_HandleTypeDef *hpcd, uint8_t epnum); /*!< pointer to USB OTG PCD Data IN Stage callback */ -typedef void (*pPCD_IsoOutIncpltCallbackTypeDef)(PCD_HandleTypeDef *hpcd, uint8_t epnum); /*!< pointer to USB OTG PCD ISO OUT Incomplete callback */ -typedef void (*pPCD_IsoInIncpltCallbackTypeDef)(PCD_HandleTypeDef *hpcd, uint8_t epnum); /*!< pointer to USB OTG PCD ISO IN Incomplete callback */ -typedef void (*pPCD_LpmCallbackTypeDef)(PCD_HandleTypeDef *hpcd, PCD_LPM_MsgTypeDef msg); /*!< pointer to USB OTG PCD LPM callback */ -typedef void (*pPCD_BcdCallbackTypeDef)(PCD_HandleTypeDef *hpcd, PCD_BCD_MsgTypeDef msg); /*!< pointer to USB OTG PCD BCD callback */ - -/** - * @} - */ - -HAL_StatusTypeDef HAL_PCD_RegisterCallback(PCD_HandleTypeDef *hpcd, - HAL_PCD_CallbackIDTypeDef CallbackID, - pPCD_CallbackTypeDef pCallback); - -HAL_StatusTypeDef HAL_PCD_UnRegisterCallback(PCD_HandleTypeDef *hpcd, - HAL_PCD_CallbackIDTypeDef CallbackID); - -HAL_StatusTypeDef HAL_PCD_RegisterDataOutStageCallback(PCD_HandleTypeDef *hpcd, - pPCD_DataOutStageCallbackTypeDef pCallback); - -HAL_StatusTypeDef HAL_PCD_UnRegisterDataOutStageCallback(PCD_HandleTypeDef *hpcd); - -HAL_StatusTypeDef HAL_PCD_RegisterDataInStageCallback(PCD_HandleTypeDef *hpcd, - pPCD_DataInStageCallbackTypeDef pCallback); - -HAL_StatusTypeDef HAL_PCD_UnRegisterDataInStageCallback(PCD_HandleTypeDef *hpcd); - -HAL_StatusTypeDef HAL_PCD_RegisterIsoOutIncpltCallback(PCD_HandleTypeDef *hpcd, - pPCD_IsoOutIncpltCallbackTypeDef pCallback); - -HAL_StatusTypeDef HAL_PCD_UnRegisterIsoOutIncpltCallback(PCD_HandleTypeDef *hpcd); - -HAL_StatusTypeDef HAL_PCD_RegisterIsoInIncpltCallback(PCD_HandleTypeDef *hpcd, - pPCD_IsoInIncpltCallbackTypeDef pCallback); - -HAL_StatusTypeDef HAL_PCD_UnRegisterIsoInIncpltCallback(PCD_HandleTypeDef *hpcd); - -HAL_StatusTypeDef HAL_PCD_RegisterBcdCallback(PCD_HandleTypeDef *hpcd, - pPCD_BcdCallbackTypeDef pCallback); - -HAL_StatusTypeDef HAL_PCD_UnRegisterBcdCallback(PCD_HandleTypeDef *hpcd); - -HAL_StatusTypeDef HAL_PCD_RegisterLpmCallback(PCD_HandleTypeDef *hpcd, - pPCD_LpmCallbackTypeDef pCallback); - -HAL_StatusTypeDef HAL_PCD_UnRegisterLpmCallback(PCD_HandleTypeDef *hpcd); -#endif /* USE_HAL_PCD_REGISTER_CALLBACKS */ -/** - * @} - */ - -/* I/O operation functions ***************************************************/ -/* Non-Blocking mode: Interrupt */ -/** @addtogroup PCD_Exported_Functions_Group2 Input and Output operation functions - * @{ - */ -HAL_StatusTypeDef HAL_PCD_Start(PCD_HandleTypeDef *hpcd); -HAL_StatusTypeDef HAL_PCD_Stop(PCD_HandleTypeDef *hpcd); -void HAL_PCD_IRQHandler(PCD_HandleTypeDef *hpcd); -void HAL_PCD_WKUP_IRQHandler(PCD_HandleTypeDef *hpcd); - -void HAL_PCD_SOFCallback(PCD_HandleTypeDef *hpcd); -void HAL_PCD_SetupStageCallback(PCD_HandleTypeDef *hpcd); -void HAL_PCD_ResetCallback(PCD_HandleTypeDef *hpcd); -void HAL_PCD_SuspendCallback(PCD_HandleTypeDef *hpcd); -void HAL_PCD_ResumeCallback(PCD_HandleTypeDef *hpcd); -void HAL_PCD_ConnectCallback(PCD_HandleTypeDef *hpcd); -void HAL_PCD_DisconnectCallback(PCD_HandleTypeDef *hpcd); - -void HAL_PCD_DataOutStageCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum); -void HAL_PCD_DataInStageCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum); -void HAL_PCD_ISOOUTIncompleteCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum); -void HAL_PCD_ISOINIncompleteCallback(PCD_HandleTypeDef *hpcd, uint8_t epnum); -/** - * @} - */ - -/* Peripheral Control functions **********************************************/ -/** @addtogroup PCD_Exported_Functions_Group3 Peripheral Control functions - * @{ - */ -HAL_StatusTypeDef HAL_PCD_DevConnect(PCD_HandleTypeDef *hpcd); -HAL_StatusTypeDef HAL_PCD_DevDisconnect(PCD_HandleTypeDef *hpcd); -HAL_StatusTypeDef HAL_PCD_SetAddress(PCD_HandleTypeDef *hpcd, uint8_t address); -HAL_StatusTypeDef HAL_PCD_EP_Open(PCD_HandleTypeDef *hpcd, uint8_t ep_addr, - uint16_t ep_mps, uint8_t ep_type); - -HAL_StatusTypeDef HAL_PCD_EP_Close(PCD_HandleTypeDef *hpcd, uint8_t ep_addr); -HAL_StatusTypeDef HAL_PCD_EP_Receive(PCD_HandleTypeDef *hpcd, uint8_t ep_addr, - uint8_t *pBuf, uint32_t len); - -HAL_StatusTypeDef HAL_PCD_EP_Transmit(PCD_HandleTypeDef *hpcd, uint8_t ep_addr, - uint8_t *pBuf, uint32_t len); - - -HAL_StatusTypeDef HAL_PCD_EP_SetStall(PCD_HandleTypeDef *hpcd, uint8_t ep_addr); -HAL_StatusTypeDef HAL_PCD_EP_ClrStall(PCD_HandleTypeDef *hpcd, uint8_t ep_addr); -HAL_StatusTypeDef HAL_PCD_EP_Flush(PCD_HandleTypeDef *hpcd, uint8_t ep_addr); -HAL_StatusTypeDef HAL_PCD_ActivateRemoteWakeup(PCD_HandleTypeDef *hpcd); -HAL_StatusTypeDef HAL_PCD_DeActivateRemoteWakeup(PCD_HandleTypeDef *hpcd); - -uint32_t HAL_PCD_EP_GetRxCount(PCD_HandleTypeDef *hpcd, uint8_t ep_addr); -/** - * @} - */ - -/* Peripheral State functions ************************************************/ -/** @addtogroup PCD_Exported_Functions_Group4 Peripheral State functions - * @{ - */ -PCD_StateTypeDef HAL_PCD_GetState(PCD_HandleTypeDef *hpcd); -/** - * @} - */ - -/** - * @} - */ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup PCD_Private_Constants PCD Private Constants - * @{ - */ -/** @defgroup USB_EXTI_Line_Interrupt USB EXTI line interrupt - * @{ - */ -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -#define USB_OTG_FS_WAKEUP_EXTI_LINE (0x1U << 18) /*!< USB FS EXTI Line WakeUp Interrupt */ -#define USB_OTG_HS_WAKEUP_EXTI_LINE (0x1U << 20) /*!< USB HS EXTI Line WakeUp Interrupt */ -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ - - -/** - * @} - */ -/** - * @} - */ - -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -#ifndef USB_OTG_DOEPINT_OTEPSPR -#define USB_OTG_DOEPINT_OTEPSPR (0x1UL << 5) /*!< Status Phase Received interrupt */ -#endif /* defined USB_OTG_DOEPINT_OTEPSPR */ - -#ifndef USB_OTG_DOEPMSK_OTEPSPRM -#define USB_OTG_DOEPMSK_OTEPSPRM (0x1UL << 5) /*!< Setup Packet Received interrupt mask */ -#endif /* defined USB_OTG_DOEPMSK_OTEPSPRM */ - -#ifndef USB_OTG_DOEPINT_NAK -#define USB_OTG_DOEPINT_NAK (0x1UL << 13) /*!< NAK interrupt */ -#endif /* defined USB_OTG_DOEPINT_NAK */ - -#ifndef USB_OTG_DOEPMSK_NAKM -#define USB_OTG_DOEPMSK_NAKM (0x1UL << 13) /*!< OUT Packet NAK interrupt mask */ -#endif /* defined USB_OTG_DOEPMSK_NAKM */ - -#ifndef USB_OTG_DOEPINT_STPKTRX -#define USB_OTG_DOEPINT_STPKTRX (0x1UL << 15) /*!< Setup Packet Received interrupt */ -#endif /* defined USB_OTG_DOEPINT_STPKTRX */ - -#ifndef USB_OTG_DOEPMSK_NYETM -#define USB_OTG_DOEPMSK_NYETM (0x1UL << 14) /*!< Setup Packet Received interrupt mask */ -#endif /* defined USB_OTG_DOEPMSK_NYETM */ -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup PCD_Private_Macros PCD Private Macros - * @{ - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_HAL_PCD_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pcd_ex.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pcd_ex.h deleted file mode 100644 index 71e9a2c..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pcd_ex.h +++ /dev/null @@ -1,91 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_pcd_ex.h - * @author MCD Application Team - * @brief Header file of PCD HAL Extension module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_PCD_EX_H -#define STM32F4xx_HAL_PCD_EX_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup PCDEx - * @{ - */ -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/* Exported macros -----------------------------------------------------------*/ -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup PCDEx_Exported_Functions PCDEx Exported Functions - * @{ - */ -/** @addtogroup PCDEx_Exported_Functions_Group1 Peripheral Control functions - * @{ - */ - -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -HAL_StatusTypeDef HAL_PCDEx_SetTxFiFo(PCD_HandleTypeDef *hpcd, uint8_t fifo, uint16_t size); -HAL_StatusTypeDef HAL_PCDEx_SetRxFiFo(PCD_HandleTypeDef *hpcd, uint16_t size); -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ - -#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -HAL_StatusTypeDef HAL_PCDEx_ActivateLPM(PCD_HandleTypeDef *hpcd); -HAL_StatusTypeDef HAL_PCDEx_DeActivateLPM(PCD_HandleTypeDef *hpcd); -#endif /* defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) */ -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -HAL_StatusTypeDef HAL_PCDEx_ActivateBCD(PCD_HandleTypeDef *hpcd); -HAL_StatusTypeDef HAL_PCDEx_DeActivateBCD(PCD_HandleTypeDef *hpcd); -void HAL_PCDEx_BCD_VBUSDetect(PCD_HandleTypeDef *hpcd); -#endif /* defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) */ -void HAL_PCDEx_LPM_Callback(PCD_HandleTypeDef *hpcd, PCD_LPM_MsgTypeDef msg); -void HAL_PCDEx_BCD_Callback(PCD_HandleTypeDef *hpcd, PCD_BCD_MsgTypeDef msg); - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ - -#ifdef __cplusplus -} -#endif - - -#endif /* STM32F4xx_HAL_PCD_EX_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pwr.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pwr.h deleted file mode 100644 index 6f3bf71..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pwr.h +++ /dev/null @@ -1,431 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_pwr.h - * @author MCD Application Team - * @brief Header file of PWR HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_PWR_H -#define __STM32F4xx_HAL_PWR_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup PWR - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ - -/** @defgroup PWR_Exported_Types PWR Exported Types - * @{ - */ - -/** - * @brief PWR PVD configuration structure definition - */ -typedef struct -{ - uint32_t PVDLevel; /*!< PVDLevel: Specifies the PVD detection level. - This parameter can be a value of @ref PWR_PVD_detection_level */ - - uint32_t Mode; /*!< Mode: Specifies the operating mode for the selected pins. - This parameter can be a value of @ref PWR_PVD_Mode */ -}PWR_PVDTypeDef; - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup PWR_Exported_Constants PWR Exported Constants - * @{ - */ - -/** @defgroup PWR_WakeUp_Pins PWR WakeUp Pins - * @{ - */ -#define PWR_WAKEUP_PIN1 0x00000100U -/** - * @} - */ - -/** @defgroup PWR_PVD_detection_level PWR PVD detection level - * @{ - */ -#define PWR_PVDLEVEL_0 PWR_CR_PLS_LEV0 -#define PWR_PVDLEVEL_1 PWR_CR_PLS_LEV1 -#define PWR_PVDLEVEL_2 PWR_CR_PLS_LEV2 -#define PWR_PVDLEVEL_3 PWR_CR_PLS_LEV3 -#define PWR_PVDLEVEL_4 PWR_CR_PLS_LEV4 -#define PWR_PVDLEVEL_5 PWR_CR_PLS_LEV5 -#define PWR_PVDLEVEL_6 PWR_CR_PLS_LEV6 -#define PWR_PVDLEVEL_7 PWR_CR_PLS_LEV7/* External input analog voltage - (Compare internally to VREFINT) */ -/** - * @} - */ - -/** @defgroup PWR_PVD_Mode PWR PVD Mode - * @{ - */ -#define PWR_PVD_MODE_NORMAL 0x00000000U /*!< basic mode is used */ -#define PWR_PVD_MODE_IT_RISING 0x00010001U /*!< External Interrupt Mode with Rising edge trigger detection */ -#define PWR_PVD_MODE_IT_FALLING 0x00010002U /*!< External Interrupt Mode with Falling edge trigger detection */ -#define PWR_PVD_MODE_IT_RISING_FALLING 0x00010003U /*!< External Interrupt Mode with Rising/Falling edge trigger detection */ -#define PWR_PVD_MODE_EVENT_RISING 0x00020001U /*!< Event Mode with Rising edge trigger detection */ -#define PWR_PVD_MODE_EVENT_FALLING 0x00020002U /*!< Event Mode with Falling edge trigger detection */ -#define PWR_PVD_MODE_EVENT_RISING_FALLING 0x00020003U /*!< Event Mode with Rising/Falling edge trigger detection */ -/** - * @} - */ - - -/** @defgroup PWR_Regulator_state_in_STOP_mode PWR Regulator state in SLEEP/STOP mode - * @{ - */ -#define PWR_MAINREGULATOR_ON 0x00000000U -#define PWR_LOWPOWERREGULATOR_ON PWR_CR_LPDS -/** - * @} - */ - -/** @defgroup PWR_SLEEP_mode_entry PWR SLEEP mode entry - * @{ - */ -#define PWR_SLEEPENTRY_WFI ((uint8_t)0x01) -#define PWR_SLEEPENTRY_WFE ((uint8_t)0x02) -/** - * @} - */ - -/** @defgroup PWR_STOP_mode_entry PWR STOP mode entry - * @{ - */ -#define PWR_STOPENTRY_WFI ((uint8_t)0x01) -#define PWR_STOPENTRY_WFE ((uint8_t)0x02) -/** - * @} - */ - -/** @defgroup PWR_Flag PWR Flag - * @{ - */ -#define PWR_FLAG_WU PWR_CSR_WUF -#define PWR_FLAG_SB PWR_CSR_SBF -#define PWR_FLAG_PVDO PWR_CSR_PVDO -#define PWR_FLAG_BRR PWR_CSR_BRR -#define PWR_FLAG_VOSRDY PWR_CSR_VOSRDY -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup PWR_Exported_Macro PWR Exported Macro - * @{ - */ - -/** @brief Check PWR flag is set or not. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg PWR_FLAG_WU: Wake Up flag. This flag indicates that a wakeup event - * was received from the WKUP pin or from the RTC alarm (Alarm A - * or Alarm B), RTC Tamper event, RTC TimeStamp event or RTC Wakeup. - * An additional wakeup event is detected if the WKUP pin is enabled - * (by setting the EWUP bit) when the WKUP pin level is already high. - * @arg PWR_FLAG_SB: StandBy flag. This flag indicates that the system was - * resumed from StandBy mode. - * @arg PWR_FLAG_PVDO: PVD Output. This flag is valid only if PVD is enabled - * by the HAL_PWR_EnablePVD() function. The PVD is stopped by Standby mode - * For this reason, this bit is equal to 0 after Standby or reset - * until the PVDE bit is set. - * @arg PWR_FLAG_BRR: Backup regulator ready flag. This bit is not reset - * when the device wakes up from Standby mode or by a system reset - * or power reset. - * @arg PWR_FLAG_VOSRDY: This flag indicates that the Regulator voltage - * scaling output selection is ready. - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_PWR_GET_FLAG(__FLAG__) ((PWR->CSR & (__FLAG__)) == (__FLAG__)) - -/** @brief Clear the PWR's pending flags. - * @param __FLAG__ specifies the flag to clear. - * This parameter can be one of the following values: - * @arg PWR_FLAG_WU: Wake Up flag - * @arg PWR_FLAG_SB: StandBy flag - */ -#define __HAL_PWR_CLEAR_FLAG(__FLAG__) (PWR->CR |= (__FLAG__) << 2U) - -/** - * @brief Enable the PVD Exti Line 16. - * @retval None. - */ -#define __HAL_PWR_PVD_EXTI_ENABLE_IT() (EXTI->IMR |= (PWR_EXTI_LINE_PVD)) - -/** - * @brief Disable the PVD EXTI Line 16. - * @retval None. - */ -#define __HAL_PWR_PVD_EXTI_DISABLE_IT() (EXTI->IMR &= ~(PWR_EXTI_LINE_PVD)) - -/** - * @brief Enable event on PVD Exti Line 16. - * @retval None. - */ -#define __HAL_PWR_PVD_EXTI_ENABLE_EVENT() (EXTI->EMR |= (PWR_EXTI_LINE_PVD)) - -/** - * @brief Disable event on PVD Exti Line 16. - * @retval None. - */ -#define __HAL_PWR_PVD_EXTI_DISABLE_EVENT() (EXTI->EMR &= ~(PWR_EXTI_LINE_PVD)) - -/** - * @brief Enable the PVD Extended Interrupt Rising Trigger. - * @retval None. - */ -#define __HAL_PWR_PVD_EXTI_ENABLE_RISING_EDGE() SET_BIT(EXTI->RTSR, PWR_EXTI_LINE_PVD) - -/** - * @brief Disable the PVD Extended Interrupt Rising Trigger. - * @retval None. - */ -#define __HAL_PWR_PVD_EXTI_DISABLE_RISING_EDGE() CLEAR_BIT(EXTI->RTSR, PWR_EXTI_LINE_PVD) - -/** - * @brief Enable the PVD Extended Interrupt Falling Trigger. - * @retval None. - */ -#define __HAL_PWR_PVD_EXTI_ENABLE_FALLING_EDGE() SET_BIT(EXTI->FTSR, PWR_EXTI_LINE_PVD) - - -/** - * @brief Disable the PVD Extended Interrupt Falling Trigger. - * @retval None. - */ -#define __HAL_PWR_PVD_EXTI_DISABLE_FALLING_EDGE() CLEAR_BIT(EXTI->FTSR, PWR_EXTI_LINE_PVD) - - -/** - * @brief PVD EXTI line configuration: set rising & falling edge trigger. - * @retval None. - */ -#define __HAL_PWR_PVD_EXTI_ENABLE_RISING_FALLING_EDGE() do{__HAL_PWR_PVD_EXTI_ENABLE_RISING_EDGE();\ - __HAL_PWR_PVD_EXTI_ENABLE_FALLING_EDGE();\ - }while(0U) - -/** - * @brief Disable the PVD Extended Interrupt Rising & Falling Trigger. - * This parameter can be: - * @retval None. - */ -#define __HAL_PWR_PVD_EXTI_DISABLE_RISING_FALLING_EDGE() do{__HAL_PWR_PVD_EXTI_DISABLE_RISING_EDGE();\ - __HAL_PWR_PVD_EXTI_DISABLE_FALLING_EDGE();\ - }while(0U) - -/** - * @brief checks whether the specified PVD Exti interrupt flag is set or not. - * @retval EXTI PVD Line Status. - */ -#define __HAL_PWR_PVD_EXTI_GET_FLAG() (EXTI->PR & (PWR_EXTI_LINE_PVD)) - -/** - * @brief Clear the PVD Exti flag. - * @retval None. - */ -#define __HAL_PWR_PVD_EXTI_CLEAR_FLAG() (EXTI->PR = (PWR_EXTI_LINE_PVD)) - -/** - * @brief Generates a Software interrupt on PVD EXTI line. - * @retval None - */ -#define __HAL_PWR_PVD_EXTI_GENERATE_SWIT() (EXTI->SWIER |= (PWR_EXTI_LINE_PVD)) - -/** - * @} - */ - -/* Include PWR HAL Extension module */ -#include "stm32f4xx_hal_pwr_ex.h" - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup PWR_Exported_Functions PWR Exported Functions - * @{ - */ - -/** @addtogroup PWR_Exported_Functions_Group1 Initialization and de-initialization functions - * @{ - */ -/* Initialization and de-initialization functions *****************************/ -void HAL_PWR_DeInit(void); -void HAL_PWR_EnableBkUpAccess(void); -void HAL_PWR_DisableBkUpAccess(void); -/** - * @} - */ - -/** @addtogroup PWR_Exported_Functions_Group2 Peripheral Control functions - * @{ - */ -/* Peripheral Control functions **********************************************/ -/* PVD configuration */ -void HAL_PWR_ConfigPVD(PWR_PVDTypeDef *sConfigPVD); -void HAL_PWR_EnablePVD(void); -void HAL_PWR_DisablePVD(void); - -/* WakeUp pins configuration */ -void HAL_PWR_EnableWakeUpPin(uint32_t WakeUpPinx); -void HAL_PWR_DisableWakeUpPin(uint32_t WakeUpPinx); - -/* Low Power modes entry */ -void HAL_PWR_EnterSTOPMode(uint32_t Regulator, uint8_t STOPEntry); -void HAL_PWR_EnterSLEEPMode(uint32_t Regulator, uint8_t SLEEPEntry); -void HAL_PWR_EnterSTANDBYMode(void); - -/* Power PVD IRQ Handler */ -void HAL_PWR_PVD_IRQHandler(void); -void HAL_PWR_PVDCallback(void); - -/* Cortex System Control functions *******************************************/ -void HAL_PWR_EnableSleepOnExit(void); -void HAL_PWR_DisableSleepOnExit(void); -void HAL_PWR_EnableSEVOnPend(void); -void HAL_PWR_DisableSEVOnPend(void); -/** - * @} - */ - -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup PWR_Private_Constants PWR Private Constants - * @{ - */ - -/** @defgroup PWR_PVD_EXTI_Line PWR PVD EXTI Line - * @{ - */ -#define PWR_EXTI_LINE_PVD ((uint32_t)EXTI_IMR_MR16) /*!< External interrupt line 16 Connected to the PVD EXTI Line */ -/** - * @} - */ - -/** @defgroup PWR_register_alias_address PWR Register alias address - * @{ - */ -/* ------------- PWR registers bit address in the alias region ---------------*/ -#define PWR_OFFSET (PWR_BASE - PERIPH_BASE) -#define PWR_CR_OFFSET 0x00U -#define PWR_CSR_OFFSET 0x04U -#define PWR_CR_OFFSET_BB (PWR_OFFSET + PWR_CR_OFFSET) -#define PWR_CSR_OFFSET_BB (PWR_OFFSET + PWR_CSR_OFFSET) -/** - * @} - */ - -/** @defgroup PWR_CR_register_alias PWR CR Register alias address - * @{ - */ -/* --- CR Register ---*/ -/* Alias word address of DBP bit */ -#define DBP_BIT_NUMBER PWR_CR_DBP_Pos -#define CR_DBP_BB (uint32_t)(PERIPH_BB_BASE + (PWR_CR_OFFSET_BB * 32U) + (DBP_BIT_NUMBER * 4U)) - -/* Alias word address of PVDE bit */ -#define PVDE_BIT_NUMBER PWR_CR_PVDE_Pos -#define CR_PVDE_BB (uint32_t)(PERIPH_BB_BASE + (PWR_CR_OFFSET_BB * 32U) + (PVDE_BIT_NUMBER * 4U)) - -/* Alias word address of VOS bit */ -#define VOS_BIT_NUMBER PWR_CR_VOS_Pos -#define CR_VOS_BB (uint32_t)(PERIPH_BB_BASE + (PWR_CR_OFFSET_BB * 32U) + (VOS_BIT_NUMBER * 4U)) -/** - * @} - */ - -/** @defgroup PWR_CSR_register_alias PWR CSR Register alias address - * @{ - */ -/* --- CSR Register ---*/ -/* Alias word address of EWUP bit */ -#define EWUP_BIT_NUMBER PWR_CSR_EWUP_Pos -#define CSR_EWUP_BB (PERIPH_BB_BASE + (PWR_CSR_OFFSET_BB * 32U) + (EWUP_BIT_NUMBER * 4U)) -/** - * @} - */ - -/** - * @} - */ -/* Private macros ------------------------------------------------------------*/ -/** @defgroup PWR_Private_Macros PWR Private Macros - * @{ - */ - -/** @defgroup PWR_IS_PWR_Definitions PWR Private macros to check input parameters - * @{ - */ -#define IS_PWR_PVD_LEVEL(LEVEL) (((LEVEL) == PWR_PVDLEVEL_0) || ((LEVEL) == PWR_PVDLEVEL_1)|| \ - ((LEVEL) == PWR_PVDLEVEL_2) || ((LEVEL) == PWR_PVDLEVEL_3)|| \ - ((LEVEL) == PWR_PVDLEVEL_4) || ((LEVEL) == PWR_PVDLEVEL_5)|| \ - ((LEVEL) == PWR_PVDLEVEL_6) || ((LEVEL) == PWR_PVDLEVEL_7)) -#define IS_PWR_PVD_MODE(MODE) (((MODE) == PWR_PVD_MODE_IT_RISING)|| ((MODE) == PWR_PVD_MODE_IT_FALLING) || \ - ((MODE) == PWR_PVD_MODE_IT_RISING_FALLING) || ((MODE) == PWR_PVD_MODE_EVENT_RISING) || \ - ((MODE) == PWR_PVD_MODE_EVENT_FALLING) || ((MODE) == PWR_PVD_MODE_EVENT_RISING_FALLING) || \ - ((MODE) == PWR_PVD_MODE_NORMAL)) -#define IS_PWR_REGULATOR(REGULATOR) (((REGULATOR) == PWR_MAINREGULATOR_ON) || \ - ((REGULATOR) == PWR_LOWPOWERREGULATOR_ON)) -#define IS_PWR_SLEEP_ENTRY(ENTRY) (((ENTRY) == PWR_SLEEPENTRY_WFI) || ((ENTRY) == PWR_SLEEPENTRY_WFE)) -#define IS_PWR_STOP_ENTRY(ENTRY) (((ENTRY) == PWR_STOPENTRY_WFI) || ((ENTRY) == PWR_STOPENTRY_WFE)) -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - - -#endif /* __STM32F4xx_HAL_PWR_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pwr_ex.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pwr_ex.h deleted file mode 100644 index 10e017a..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_pwr_ex.h +++ /dev/null @@ -1,344 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_pwr_ex.h - * @author MCD Application Team - * @brief Header file of PWR HAL Extension module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_PWR_EX_H -#define __STM32F4xx_HAL_PWR_EX_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup PWREx - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/** @defgroup PWREx_Exported_Constants PWREx Exported Constants - * @{ - */ -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) - -/** @defgroup PWREx_Regulator_state_in_UnderDrive_mode PWREx Regulator state in UnderDrive mode - * @{ - */ -#define PWR_MAINREGULATOR_UNDERDRIVE_ON PWR_CR_MRUDS -#define PWR_LOWPOWERREGULATOR_UNDERDRIVE_ON ((uint32_t)(PWR_CR_LPDS | PWR_CR_LPUDS)) -/** - * @} - */ - -/** @defgroup PWREx_Over_Under_Drive_Flag PWREx Over Under Drive Flag - * @{ - */ -#define PWR_FLAG_ODRDY PWR_CSR_ODRDY -#define PWR_FLAG_ODSWRDY PWR_CSR_ODSWRDY -#define PWR_FLAG_UDRDY PWR_CSR_UDSWRDY -/** - * @} - */ -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ - -/** @defgroup PWREx_Regulator_Voltage_Scale PWREx Regulator Voltage Scale - * @{ - */ -#if defined(STM32F405xx) || defined(STM32F407xx) || defined(STM32F415xx) || defined(STM32F417xx) -#define PWR_REGULATOR_VOLTAGE_SCALE1 PWR_CR_VOS /* Scale 1 mode(default value at reset): the maximum value of fHCLK = 168 MHz. */ -#define PWR_REGULATOR_VOLTAGE_SCALE2 0x00000000U /* Scale 2 mode: the maximum value of fHCLK = 144 MHz. */ -#else -#define PWR_REGULATOR_VOLTAGE_SCALE1 PWR_CR_VOS /* Scale 1 mode(default value at reset): the maximum value of fHCLK is 168 MHz. It can be extended to - 180 MHz by activating the over-drive mode. */ -#define PWR_REGULATOR_VOLTAGE_SCALE2 PWR_CR_VOS_1 /* Scale 2 mode: the maximum value of fHCLK is 144 MHz. It can be extended to - 168 MHz by activating the over-drive mode. */ -#define PWR_REGULATOR_VOLTAGE_SCALE3 PWR_CR_VOS_0 /* Scale 3 mode: the maximum value of fHCLK is 120 MHz. */ -#endif /* STM32F405xx || STM32F407xx || STM32F415xx || STM32F417xx */ -/** - * @} - */ -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || \ - defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/** @defgroup PWREx_WakeUp_Pins PWREx WakeUp Pins - * @{ - */ -#define PWR_WAKEUP_PIN2 0x00000080U -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F412Zx) || defined(STM32F412Vx) || \ - defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -#define PWR_WAKEUP_PIN3 0x00000040U -#endif /* STM32F410xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Zx || STM32F412Vx || \ - STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ -/** - * @} - */ -#endif /* STM32F410xx || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || - STM32F413xx || STM32F423xx */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup PWREx_Exported_Constants PWREx Exported Constants - * @{ - */ - -#if defined(STM32F405xx) || defined(STM32F407xx) || defined(STM32F415xx) || defined(STM32F417xx) -/** @brief macros configure the main internal regulator output voltage. - * @param __REGULATOR__ specifies the regulator output voltage to achieve - * a tradeoff between performance and power consumption when the device does - * not operate at the maximum frequency (refer to the datasheets for more details). - * This parameter can be one of the following values: - * @arg PWR_REGULATOR_VOLTAGE_SCALE1: Regulator voltage output Scale 1 mode - * @arg PWR_REGULATOR_VOLTAGE_SCALE2: Regulator voltage output Scale 2 mode - * @retval None - */ -#define __HAL_PWR_VOLTAGESCALING_CONFIG(__REGULATOR__) do { \ - __IO uint32_t tmpreg = 0x00U; \ - MODIFY_REG(PWR->CR, PWR_CR_VOS, (__REGULATOR__)); \ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(PWR->CR, PWR_CR_VOS); \ - UNUSED(tmpreg); \ - } while(0U) -#else -/** @brief macros configure the main internal regulator output voltage. - * @param __REGULATOR__ specifies the regulator output voltage to achieve - * a tradeoff between performance and power consumption when the device does - * not operate at the maximum frequency (refer to the datasheets for more details). - * This parameter can be one of the following values: - * @arg PWR_REGULATOR_VOLTAGE_SCALE1: Regulator voltage output Scale 1 mode - * @arg PWR_REGULATOR_VOLTAGE_SCALE2: Regulator voltage output Scale 2 mode - * @arg PWR_REGULATOR_VOLTAGE_SCALE3: Regulator voltage output Scale 3 mode - * @retval None - */ -#define __HAL_PWR_VOLTAGESCALING_CONFIG(__REGULATOR__) do { \ - __IO uint32_t tmpreg = 0x00U; \ - MODIFY_REG(PWR->CR, PWR_CR_VOS, (__REGULATOR__)); \ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(PWR->CR, PWR_CR_VOS); \ - UNUSED(tmpreg); \ - } while(0U) -#endif /* STM32F405xx || STM32F407xx || STM32F415xx || STM32F417xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -/** @brief Macros to enable or disable the Over drive mode. - * @note These macros can be used only for STM32F42xx/STM3243xx devices. - */ -#define __HAL_PWR_OVERDRIVE_ENABLE() (*(__IO uint32_t *) CR_ODEN_BB = ENABLE) -#define __HAL_PWR_OVERDRIVE_DISABLE() (*(__IO uint32_t *) CR_ODEN_BB = DISABLE) - -/** @brief Macros to enable or disable the Over drive switching. - * @note These macros can be used only for STM32F42xx/STM3243xx devices. - */ -#define __HAL_PWR_OVERDRIVESWITCHING_ENABLE() (*(__IO uint32_t *) CR_ODSWEN_BB = ENABLE) -#define __HAL_PWR_OVERDRIVESWITCHING_DISABLE() (*(__IO uint32_t *) CR_ODSWEN_BB = DISABLE) - -/** @brief Macros to enable or disable the Under drive mode. - * @note This mode is enabled only with STOP low power mode. - * In this mode, the 1.2V domain is preserved in reduced leakage mode. This - * mode is only available when the main regulator or the low power regulator - * is in low voltage mode. - * @note If the Under-drive mode was enabled, it is automatically disabled after - * exiting Stop mode. - * When the voltage regulator operates in Under-drive mode, an additional - * startup delay is induced when waking up from Stop mode. - */ -#define __HAL_PWR_UNDERDRIVE_ENABLE() (PWR->CR |= (uint32_t)PWR_CR_UDEN) -#define __HAL_PWR_UNDERDRIVE_DISABLE() (PWR->CR &= (uint32_t)(~PWR_CR_UDEN)) - -/** @brief Check PWR flag is set or not. - * @note These macros can be used only for STM32F42xx/STM3243xx devices. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg PWR_FLAG_ODRDY: This flag indicates that the Over-drive mode - * is ready - * @arg PWR_FLAG_ODSWRDY: This flag indicates that the Over-drive mode - * switching is ready - * @arg PWR_FLAG_UDRDY: This flag indicates that the Under-drive mode - * is enabled in Stop mode - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_PWR_GET_ODRUDR_FLAG(__FLAG__) ((PWR->CSR & (__FLAG__)) == (__FLAG__)) - -/** @brief Clear the Under-Drive Ready flag. - * @note These macros can be used only for STM32F42xx/STM3243xx devices. - */ -#define __HAL_PWR_CLEAR_ODRUDR_FLAG() (PWR->CSR |= PWR_FLAG_UDRDY) - -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup PWREx_Exported_Functions PWREx Exported Functions - * @{ - */ - -/** @addtogroup PWREx_Exported_Functions_Group1 - * @{ - */ -void HAL_PWREx_EnableFlashPowerDown(void); -void HAL_PWREx_DisableFlashPowerDown(void); -HAL_StatusTypeDef HAL_PWREx_EnableBkUpReg(void); -HAL_StatusTypeDef HAL_PWREx_DisableBkUpReg(void); -uint32_t HAL_PWREx_GetVoltageRange(void); -HAL_StatusTypeDef HAL_PWREx_ControlVoltageScaling(uint32_t VoltageScaling); - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F401xC) ||\ - defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F412Zx) || defined(STM32F412Vx) ||\ - defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -void HAL_PWREx_EnableMainRegulatorLowVoltage(void); -void HAL_PWREx_DisableMainRegulatorLowVoltage(void); -void HAL_PWREx_EnableLowRegulatorLowVoltage(void); -void HAL_PWREx_DisableLowRegulatorLowVoltage(void); -#endif /* STM32F410xx || STM32F401xC || STM32F401xE || STM32F411xE || STM32F412Zx || STM32F412Vx ||\ - STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F446xx) ||\ - defined(STM32F469xx) || defined(STM32F479xx) -HAL_StatusTypeDef HAL_PWREx_EnableOverDrive(void); -HAL_StatusTypeDef HAL_PWREx_DisableOverDrive(void); -HAL_StatusTypeDef HAL_PWREx_EnterUnderDriveSTOPMode(uint32_t Regulator, uint8_t STOPEntry); -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ - -/** - * @} - */ - -/** - * @} - */ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup PWREx_Private_Constants PWREx Private Constants - * @{ - */ - -/** @defgroup PWREx_register_alias_address PWREx Register alias address - * @{ - */ -/* ------------- PWR registers bit address in the alias region ---------------*/ -/* --- CR Register ---*/ -/* Alias word address of FPDS bit */ -#define FPDS_BIT_NUMBER PWR_CR_FPDS_Pos -#define CR_FPDS_BB (uint32_t)(PERIPH_BB_BASE + (PWR_CR_OFFSET_BB * 32U) + (FPDS_BIT_NUMBER * 4U)) - -/* Alias word address of ODEN bit */ -#define ODEN_BIT_NUMBER PWR_CR_ODEN_Pos -#define CR_ODEN_BB (uint32_t)(PERIPH_BB_BASE + (PWR_CR_OFFSET_BB * 32U) + (ODEN_BIT_NUMBER * 4U)) - -/* Alias word address of ODSWEN bit */ -#define ODSWEN_BIT_NUMBER PWR_CR_ODSWEN_Pos -#define CR_ODSWEN_BB (uint32_t)(PERIPH_BB_BASE + (PWR_CR_OFFSET_BB * 32U) + (ODSWEN_BIT_NUMBER * 4U)) - -/* Alias word address of MRLVDS bit */ -#define MRLVDS_BIT_NUMBER PWR_CR_MRLVDS_Pos -#define CR_MRLVDS_BB (uint32_t)(PERIPH_BB_BASE + (PWR_CR_OFFSET_BB * 32U) + (MRLVDS_BIT_NUMBER * 4U)) - -/* Alias word address of LPLVDS bit */ -#define LPLVDS_BIT_NUMBER PWR_CR_LPLVDS_Pos -#define CR_LPLVDS_BB (uint32_t)(PERIPH_BB_BASE + (PWR_CR_OFFSET_BB * 32U) + (LPLVDS_BIT_NUMBER * 4U)) - - /** - * @} - */ - -/** @defgroup PWREx_CSR_register_alias PWRx CSR Register alias address - * @{ - */ -/* --- CSR Register ---*/ -/* Alias word address of BRE bit */ -#define BRE_BIT_NUMBER PWR_CSR_BRE_Pos -#define CSR_BRE_BB (uint32_t)(PERIPH_BB_BASE + (PWR_CSR_OFFSET_BB * 32U) + (BRE_BIT_NUMBER * 4U)) - -/** - * @} - */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup PWREx_Private_Macros PWREx Private Macros - * @{ - */ - -/** @defgroup PWREx_IS_PWR_Definitions PWREx Private macros to check input parameters - * @{ - */ -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -#define IS_PWR_REGULATOR_UNDERDRIVE(REGULATOR) (((REGULATOR) == PWR_MAINREGULATOR_UNDERDRIVE_ON) || \ - ((REGULATOR) == PWR_LOWPOWERREGULATOR_UNDERDRIVE_ON)) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F405xx) || defined(STM32F407xx) || defined(STM32F415xx) || defined(STM32F417xx) -#define IS_PWR_VOLTAGE_SCALING_RANGE(VOLTAGE) (((VOLTAGE) == PWR_REGULATOR_VOLTAGE_SCALE1) || \ - ((VOLTAGE) == PWR_REGULATOR_VOLTAGE_SCALE2)) -#else -#define IS_PWR_VOLTAGE_SCALING_RANGE(VOLTAGE) (((VOLTAGE) == PWR_REGULATOR_VOLTAGE_SCALE1) || \ - ((VOLTAGE) == PWR_REGULATOR_VOLTAGE_SCALE2) || \ - ((VOLTAGE) == PWR_REGULATOR_VOLTAGE_SCALE3)) -#endif /* STM32F405xx || STM32F407xx || STM32F415xx || STM32F417xx */ - -#if defined(STM32F446xx) -#define IS_PWR_WAKEUP_PIN(PIN) (((PIN) == PWR_WAKEUP_PIN1) || ((PIN) == PWR_WAKEUP_PIN2)) -#elif defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F412Zx) ||\ - defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) ||\ - defined(STM32F423xx) -#define IS_PWR_WAKEUP_PIN(PIN) (((PIN) == PWR_WAKEUP_PIN1) || ((PIN) == PWR_WAKEUP_PIN2) || \ - ((PIN) == PWR_WAKEUP_PIN3)) -#else -#define IS_PWR_WAKEUP_PIN(PIN) ((PIN) == PWR_WAKEUP_PIN1) -#endif /* STM32F446xx */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - - -#endif /* __STM32F4xx_HAL_PWR_EX_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_qspi.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_qspi.h deleted file mode 100644 index 97e9324..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_qspi.h +++ /dev/null @@ -1,753 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_qspi.h - * @author MCD Application Team - * @brief Header file of QSPI HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_QSPI_H -#define STM32F4xx_HAL_QSPI_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -#if defined(QUADSPI) - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup QSPI - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup QSPI_Exported_Types QSPI Exported Types - * @{ - */ - -/** - * @brief QSPI Init structure definition - */ -typedef struct -{ - uint32_t ClockPrescaler; /* Specifies the prescaler factor for generating clock based on the AHB clock. - This parameter can be a number between 0 and 255 */ - uint32_t FifoThreshold; /* Specifies the threshold number of bytes in the FIFO (used only in indirect mode) - This parameter can be a value between 1 and 32 */ - uint32_t SampleShifting; /* Specifies the Sample Shift. The data is sampled 1/2 clock cycle delay later to - take in account external signal delays. (It should be QSPI_SAMPLE_SHIFTING_NONE in DDR mode) - This parameter can be a value of @ref QSPI_SampleShifting */ - uint32_t FlashSize; /* Specifies the Flash Size. FlashSize+1 is effectively the number of address bits - required to address the flash memory. The flash capacity can be up to 4GB - (addressed using 32 bits) in indirect mode, but the addressable space in - memory-mapped mode is limited to 256MB - This parameter can be a number between 0 and 31 */ - uint32_t ChipSelectHighTime; /* Specifies the Chip Select High Time. ChipSelectHighTime+1 defines the minimum number - of clock cycles which the chip select must remain high between commands. - This parameter can be a value of @ref QSPI_ChipSelectHighTime */ - uint32_t ClockMode; /* Specifies the Clock Mode. It indicates the level that clock takes between commands. - This parameter can be a value of @ref QSPI_ClockMode */ - uint32_t FlashID; /* Specifies the Flash which will be used, - This parameter can be a value of @ref QSPI_Flash_Select */ - uint32_t DualFlash; /* Specifies the Dual Flash Mode State - This parameter can be a value of @ref QSPI_DualFlash_Mode */ -}QSPI_InitTypeDef; - -/** - * @brief HAL QSPI State structures definition - */ -typedef enum -{ - HAL_QSPI_STATE_RESET = 0x00U, /*!< Peripheral not initialized */ - HAL_QSPI_STATE_READY = 0x01U, /*!< Peripheral initialized and ready for use */ - HAL_QSPI_STATE_BUSY = 0x02U, /*!< Peripheral in indirect mode and busy */ - HAL_QSPI_STATE_BUSY_INDIRECT_TX = 0x12U, /*!< Peripheral in indirect mode with transmission ongoing */ - HAL_QSPI_STATE_BUSY_INDIRECT_RX = 0x22U, /*!< Peripheral in indirect mode with reception ongoing */ - HAL_QSPI_STATE_BUSY_AUTO_POLLING = 0x42U, /*!< Peripheral in auto polling mode ongoing */ - HAL_QSPI_STATE_BUSY_MEM_MAPPED = 0x82U, /*!< Peripheral in memory mapped mode ongoing */ - HAL_QSPI_STATE_ABORT = 0x08U, /*!< Peripheral with abort request ongoing */ - HAL_QSPI_STATE_ERROR = 0x04U /*!< Peripheral in error */ -}HAL_QSPI_StateTypeDef; - -/** - * @brief QSPI Handle Structure definition - */ -#if (USE_HAL_QSPI_REGISTER_CALLBACKS == 1) -typedef struct __QSPI_HandleTypeDef -#else -typedef struct -#endif -{ - QUADSPI_TypeDef *Instance; /* QSPI registers base address */ - QSPI_InitTypeDef Init; /* QSPI communication parameters */ - uint8_t *pTxBuffPtr; /* Pointer to QSPI Tx transfer Buffer */ - __IO uint32_t TxXferSize; /* QSPI Tx Transfer size */ - __IO uint32_t TxXferCount; /* QSPI Tx Transfer Counter */ - uint8_t *pRxBuffPtr; /* Pointer to QSPI Rx transfer Buffer */ - __IO uint32_t RxXferSize; /* QSPI Rx Transfer size */ - __IO uint32_t RxXferCount; /* QSPI Rx Transfer Counter */ - DMA_HandleTypeDef *hdma; /* QSPI Rx/Tx DMA Handle parameters */ - __IO HAL_LockTypeDef Lock; /* Locking object */ - __IO HAL_QSPI_StateTypeDef State; /* QSPI communication state */ - __IO uint32_t ErrorCode; /* QSPI Error code */ - uint32_t Timeout; /* Timeout for the QSPI memory access */ -#if (USE_HAL_QSPI_REGISTER_CALLBACKS == 1) - void (* ErrorCallback) (struct __QSPI_HandleTypeDef *hqspi); - void (* AbortCpltCallback) (struct __QSPI_HandleTypeDef *hqspi); - void (* FifoThresholdCallback)(struct __QSPI_HandleTypeDef *hqspi); - void (* CmdCpltCallback) (struct __QSPI_HandleTypeDef *hqspi); - void (* RxCpltCallback) (struct __QSPI_HandleTypeDef *hqspi); - void (* TxCpltCallback) (struct __QSPI_HandleTypeDef *hqspi); - void (* RxHalfCpltCallback) (struct __QSPI_HandleTypeDef *hqspi); - void (* TxHalfCpltCallback) (struct __QSPI_HandleTypeDef *hqspi); - void (* StatusMatchCallback) (struct __QSPI_HandleTypeDef *hqspi); - void (* TimeOutCallback) (struct __QSPI_HandleTypeDef *hqspi); - - void (* MspInitCallback) (struct __QSPI_HandleTypeDef *hqspi); - void (* MspDeInitCallback) (struct __QSPI_HandleTypeDef *hqspi); -#endif -}QSPI_HandleTypeDef; - -/** - * @brief QSPI Command structure definition - */ -typedef struct -{ - uint32_t Instruction; /* Specifies the Instruction to be sent - This parameter can be a value (8-bit) between 0x00 and 0xFF */ - uint32_t Address; /* Specifies the Address to be sent (Size from 1 to 4 bytes according AddressSize) - This parameter can be a value (32-bits) between 0x0 and 0xFFFFFFFF */ - uint32_t AlternateBytes; /* Specifies the Alternate Bytes to be sent (Size from 1 to 4 bytes according AlternateBytesSize) - This parameter can be a value (32-bits) between 0x0 and 0xFFFFFFFF */ - uint32_t AddressSize; /* Specifies the Address Size - This parameter can be a value of @ref QSPI_AddressSize */ - uint32_t AlternateBytesSize; /* Specifies the Alternate Bytes Size - This parameter can be a value of @ref QSPI_AlternateBytesSize */ - uint32_t DummyCycles; /* Specifies the Number of Dummy Cycles. - This parameter can be a number between 0 and 31 */ - uint32_t InstructionMode; /* Specifies the Instruction Mode - This parameter can be a value of @ref QSPI_InstructionMode */ - uint32_t AddressMode; /* Specifies the Address Mode - This parameter can be a value of @ref QSPI_AddressMode */ - uint32_t AlternateByteMode; /* Specifies the Alternate Bytes Mode - This parameter can be a value of @ref QSPI_AlternateBytesMode */ - uint32_t DataMode; /* Specifies the Data Mode (used for dummy cycles and data phases) - This parameter can be a value of @ref QSPI_DataMode */ - uint32_t NbData; /* Specifies the number of data to transfer. (This is the number of bytes) - This parameter can be any value between 0 and 0xFFFFFFFF (0 means undefined length - until end of memory)*/ - uint32_t DdrMode; /* Specifies the double data rate mode for address, alternate byte and data phase - This parameter can be a value of @ref QSPI_DdrMode */ - uint32_t DdrHoldHalfCycle; /* Specifies if the DDR hold is enabled. When enabled it delays the data - output by one half of system clock in DDR mode. - This parameter can be a value of @ref QSPI_DdrHoldHalfCycle */ - uint32_t SIOOMode; /* Specifies the send instruction only once mode - This parameter can be a value of @ref QSPI_SIOOMode */ -}QSPI_CommandTypeDef; - -/** - * @brief QSPI Auto Polling mode configuration structure definition - */ -typedef struct -{ - uint32_t Match; /* Specifies the value to be compared with the masked status register to get a match. - This parameter can be any value between 0 and 0xFFFFFFFF */ - uint32_t Mask; /* Specifies the mask to be applied to the status bytes received. - This parameter can be any value between 0 and 0xFFFFFFFF */ - uint32_t Interval; /* Specifies the number of clock cycles between two read during automatic polling phases. - This parameter can be any value between 0 and 0xFFFF */ - uint32_t StatusBytesSize; /* Specifies the size of the status bytes received. - This parameter can be any value between 1 and 4 */ - uint32_t MatchMode; /* Specifies the method used for determining a match. - This parameter can be a value of @ref QSPI_MatchMode */ - uint32_t AutomaticStop; /* Specifies if automatic polling is stopped after a match. - This parameter can be a value of @ref QSPI_AutomaticStop */ -}QSPI_AutoPollingTypeDef; - -/** - * @brief QSPI Memory Mapped mode configuration structure definition - */ -typedef struct -{ - uint32_t TimeOutPeriod; /* Specifies the number of clock to wait when the FIFO is full before to release the chip select. - This parameter can be any value between 0 and 0xFFFF */ - uint32_t TimeOutActivation; /* Specifies if the timeout counter is enabled to release the chip select. - This parameter can be a value of @ref QSPI_TimeOutActivation */ -}QSPI_MemoryMappedTypeDef; - -#if (USE_HAL_QSPI_REGISTER_CALLBACKS == 1) -/** - * @brief HAL QSPI Callback ID enumeration definition - */ -typedef enum -{ - HAL_QSPI_ERROR_CB_ID = 0x00U, /*!< QSPI Error Callback ID */ - HAL_QSPI_ABORT_CB_ID = 0x01U, /*!< QSPI Abort Callback ID */ - HAL_QSPI_FIFO_THRESHOLD_CB_ID = 0x02U, /*!< QSPI FIFO Threshold Callback ID */ - HAL_QSPI_CMD_CPLT_CB_ID = 0x03U, /*!< QSPI Command Complete Callback ID */ - HAL_QSPI_RX_CPLT_CB_ID = 0x04U, /*!< QSPI Rx Complete Callback ID */ - HAL_QSPI_TX_CPLT_CB_ID = 0x05U, /*!< QSPI Tx Complete Callback ID */ - HAL_QSPI_RX_HALF_CPLT_CB_ID = 0x06U, /*!< QSPI Rx Half Complete Callback ID */ - HAL_QSPI_TX_HALF_CPLT_CB_ID = 0x07U, /*!< QSPI Tx Half Complete Callback ID */ - HAL_QSPI_STATUS_MATCH_CB_ID = 0x08U, /*!< QSPI Status Match Callback ID */ - HAL_QSPI_TIMEOUT_CB_ID = 0x09U, /*!< QSPI Timeout Callback ID */ - - HAL_QSPI_MSP_INIT_CB_ID = 0x0AU, /*!< QSPI MspInit Callback ID */ - HAL_QSPI_MSP_DEINIT_CB_ID = 0x0B0 /*!< QSPI MspDeInit Callback ID */ -}HAL_QSPI_CallbackIDTypeDef; - -/** - * @brief HAL QSPI Callback pointer definition - */ -typedef void (*pQSPI_CallbackTypeDef)(QSPI_HandleTypeDef *hqspi); -#endif -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup QSPI_Exported_Constants QSPI Exported Constants - * @{ - */ - -/** @defgroup QSPI_ErrorCode QSPI Error Code - * @{ - */ -#define HAL_QSPI_ERROR_NONE 0x00000000U /*!< No error */ -#define HAL_QSPI_ERROR_TIMEOUT 0x00000001U /*!< Timeout error */ -#define HAL_QSPI_ERROR_TRANSFER 0x00000002U /*!< Transfer error */ -#define HAL_QSPI_ERROR_DMA 0x00000004U /*!< DMA transfer error */ -#define HAL_QSPI_ERROR_INVALID_PARAM 0x00000008U /*!< Invalid parameters error */ -#if (USE_HAL_QSPI_REGISTER_CALLBACKS == 1) -#define HAL_QSPI_ERROR_INVALID_CALLBACK 0x00000010U /*!< Invalid callback error */ -#endif -/** - * @} - */ - -/** @defgroup QSPI_SampleShifting QSPI Sample Shifting - * @{ - */ -#define QSPI_SAMPLE_SHIFTING_NONE 0x00000000U /*!State = HAL_QSPI_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_QSPI_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_QSPI_STATE_RESET) -#endif - -/** @brief Enable the QSPI peripheral. - * @param __HANDLE__ : specifies the QSPI Handle. - * @retval None - */ -#define __HAL_QSPI_ENABLE(__HANDLE__) SET_BIT((__HANDLE__)->Instance->CR, QUADSPI_CR_EN) - -/** @brief Disable the QSPI peripheral. - * @param __HANDLE__ : specifies the QSPI Handle. - * @retval None - */ -#define __HAL_QSPI_DISABLE(__HANDLE__) CLEAR_BIT((__HANDLE__)->Instance->CR, QUADSPI_CR_EN) - -/** @brief Enable the specified QSPI interrupt. - * @param __HANDLE__ : specifies the QSPI Handle. - * @param __INTERRUPT__ : specifies the QSPI interrupt source to enable. - * This parameter can be one of the following values: - * @arg QSPI_IT_TO: QSPI Timeout interrupt - * @arg QSPI_IT_SM: QSPI Status match interrupt - * @arg QSPI_IT_FT: QSPI FIFO threshold interrupt - * @arg QSPI_IT_TC: QSPI Transfer complete interrupt - * @arg QSPI_IT_TE: QSPI Transfer error interrupt - * @retval None - */ -#define __HAL_QSPI_ENABLE_IT(__HANDLE__, __INTERRUPT__) SET_BIT((__HANDLE__)->Instance->CR, (__INTERRUPT__)) - - -/** @brief Disable the specified QSPI interrupt. - * @param __HANDLE__ : specifies the QSPI Handle. - * @param __INTERRUPT__ : specifies the QSPI interrupt source to disable. - * This parameter can be one of the following values: - * @arg QSPI_IT_TO: QSPI Timeout interrupt - * @arg QSPI_IT_SM: QSPI Status match interrupt - * @arg QSPI_IT_FT: QSPI FIFO threshold interrupt - * @arg QSPI_IT_TC: QSPI Transfer complete interrupt - * @arg QSPI_IT_TE: QSPI Transfer error interrupt - * @retval None - */ -#define __HAL_QSPI_DISABLE_IT(__HANDLE__, __INTERRUPT__) CLEAR_BIT((__HANDLE__)->Instance->CR, (__INTERRUPT__)) - -/** @brief Check whether the specified QSPI interrupt source is enabled or not. - * @param __HANDLE__ : specifies the QSPI Handle. - * @param __INTERRUPT__ : specifies the QSPI interrupt source to check. - * This parameter can be one of the following values: - * @arg QSPI_IT_TO: QSPI Timeout interrupt - * @arg QSPI_IT_SM: QSPI Status match interrupt - * @arg QSPI_IT_FT: QSPI FIFO threshold interrupt - * @arg QSPI_IT_TC: QSPI Transfer complete interrupt - * @arg QSPI_IT_TE: QSPI Transfer error interrupt - * @retval The new state of __INTERRUPT__ (TRUE or FALSE). - */ -#define __HAL_QSPI_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) (READ_BIT((__HANDLE__)->Instance->CR, (__INTERRUPT__)) == (__INTERRUPT__)) - -/** - * @brief Check whether the selected QSPI flag is set or not. - * @param __HANDLE__ : specifies the QSPI Handle. - * @param __FLAG__ : specifies the QSPI flag to check. - * This parameter can be one of the following values: - * @arg QSPI_FLAG_BUSY: QSPI Busy flag - * @arg QSPI_FLAG_TO: QSPI Timeout flag - * @arg QSPI_FLAG_SM: QSPI Status match flag - * @arg QSPI_FLAG_FT: QSPI FIFO threshold flag - * @arg QSPI_FLAG_TC: QSPI Transfer complete flag - * @arg QSPI_FLAG_TE: QSPI Transfer error flag - * @retval None - */ -#define __HAL_QSPI_GET_FLAG(__HANDLE__, __FLAG__) ((READ_BIT((__HANDLE__)->Instance->SR, (__FLAG__)) != 0U) ? SET : RESET) - -/** @brief Clears the specified QSPI's flag status. - * @param __HANDLE__ : specifies the QSPI Handle. - * @param __FLAG__ : specifies the QSPI clear register flag that needs to be set - * This parameter can be one of the following values: - * @arg QSPI_FLAG_TO: QSPI Timeout flag - * @arg QSPI_FLAG_SM: QSPI Status match flag - * @arg QSPI_FLAG_TC: QSPI Transfer complete flag - * @arg QSPI_FLAG_TE: QSPI Transfer error flag - * @retval None - */ -#define __HAL_QSPI_CLEAR_FLAG(__HANDLE__, __FLAG__) WRITE_REG((__HANDLE__)->Instance->FCR, (__FLAG__)) -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup QSPI_Exported_Functions - * @{ - */ - -/** @addtogroup QSPI_Exported_Functions_Group1 - * @{ - */ -/* Initialization/de-initialization functions ********************************/ -HAL_StatusTypeDef HAL_QSPI_Init (QSPI_HandleTypeDef *hqspi); -HAL_StatusTypeDef HAL_QSPI_DeInit (QSPI_HandleTypeDef *hqspi); -void HAL_QSPI_MspInit (QSPI_HandleTypeDef *hqspi); -void HAL_QSPI_MspDeInit(QSPI_HandleTypeDef *hqspi); -/** - * @} - */ - -/** @addtogroup QSPI_Exported_Functions_Group2 - * @{ - */ -/* IO operation functions *****************************************************/ -/* QSPI IRQ handler method */ -void HAL_QSPI_IRQHandler(QSPI_HandleTypeDef *hqspi); - -/* QSPI indirect mode */ -HAL_StatusTypeDef HAL_QSPI_Command (QSPI_HandleTypeDef *hqspi, QSPI_CommandTypeDef *cmd, uint32_t Timeout); -HAL_StatusTypeDef HAL_QSPI_Transmit (QSPI_HandleTypeDef *hqspi, uint8_t *pData, uint32_t Timeout); -HAL_StatusTypeDef HAL_QSPI_Receive (QSPI_HandleTypeDef *hqspi, uint8_t *pData, uint32_t Timeout); -HAL_StatusTypeDef HAL_QSPI_Command_IT (QSPI_HandleTypeDef *hqspi, QSPI_CommandTypeDef *cmd); -HAL_StatusTypeDef HAL_QSPI_Transmit_IT (QSPI_HandleTypeDef *hqspi, uint8_t *pData); -HAL_StatusTypeDef HAL_QSPI_Receive_IT (QSPI_HandleTypeDef *hqspi, uint8_t *pData); -HAL_StatusTypeDef HAL_QSPI_Transmit_DMA (QSPI_HandleTypeDef *hqspi, uint8_t *pData); -HAL_StatusTypeDef HAL_QSPI_Receive_DMA (QSPI_HandleTypeDef *hqspi, uint8_t *pData); - -/* QSPI status flag polling mode */ -HAL_StatusTypeDef HAL_QSPI_AutoPolling (QSPI_HandleTypeDef *hqspi, QSPI_CommandTypeDef *cmd, QSPI_AutoPollingTypeDef *cfg, uint32_t Timeout); -HAL_StatusTypeDef HAL_QSPI_AutoPolling_IT(QSPI_HandleTypeDef *hqspi, QSPI_CommandTypeDef *cmd, QSPI_AutoPollingTypeDef *cfg); - -/* QSPI memory-mapped mode */ -HAL_StatusTypeDef HAL_QSPI_MemoryMapped(QSPI_HandleTypeDef *hqspi, QSPI_CommandTypeDef *cmd, QSPI_MemoryMappedTypeDef *cfg); - -/* Callback functions in non-blocking modes ***********************************/ -void HAL_QSPI_ErrorCallback (QSPI_HandleTypeDef *hqspi); -void HAL_QSPI_AbortCpltCallback (QSPI_HandleTypeDef *hqspi); -void HAL_QSPI_FifoThresholdCallback(QSPI_HandleTypeDef *hqspi); - -/* QSPI indirect mode */ -void HAL_QSPI_CmdCpltCallback (QSPI_HandleTypeDef *hqspi); -void HAL_QSPI_RxCpltCallback (QSPI_HandleTypeDef *hqspi); -void HAL_QSPI_TxCpltCallback (QSPI_HandleTypeDef *hqspi); -void HAL_QSPI_RxHalfCpltCallback (QSPI_HandleTypeDef *hqspi); -void HAL_QSPI_TxHalfCpltCallback (QSPI_HandleTypeDef *hqspi); - -/* QSPI status flag polling mode */ -void HAL_QSPI_StatusMatchCallback (QSPI_HandleTypeDef *hqspi); - -/* QSPI memory-mapped mode */ -void HAL_QSPI_TimeOutCallback (QSPI_HandleTypeDef *hqspi); - -#if (USE_HAL_QSPI_REGISTER_CALLBACKS == 1) -/* QSPI callback registering/unregistering */ -HAL_StatusTypeDef HAL_QSPI_RegisterCallback (QSPI_HandleTypeDef *hqspi, HAL_QSPI_CallbackIDTypeDef CallbackId, pQSPI_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_QSPI_UnRegisterCallback (QSPI_HandleTypeDef *hqspi, HAL_QSPI_CallbackIDTypeDef CallbackId); -#endif -/** - * @} - */ - -/** @addtogroup QSPI_Exported_Functions_Group3 - * @{ - */ -/* Peripheral Control and State functions ************************************/ -HAL_QSPI_StateTypeDef HAL_QSPI_GetState (QSPI_HandleTypeDef *hqspi); -uint32_t HAL_QSPI_GetError (QSPI_HandleTypeDef *hqspi); -HAL_StatusTypeDef HAL_QSPI_Abort (QSPI_HandleTypeDef *hqspi); -HAL_StatusTypeDef HAL_QSPI_Abort_IT (QSPI_HandleTypeDef *hqspi); -void HAL_QSPI_SetTimeout (QSPI_HandleTypeDef *hqspi, uint32_t Timeout); -HAL_StatusTypeDef HAL_QSPI_SetFifoThreshold(QSPI_HandleTypeDef *hqspi, uint32_t Threshold); -uint32_t HAL_QSPI_GetFifoThreshold(QSPI_HandleTypeDef *hqspi); -HAL_StatusTypeDef HAL_QSPI_SetFlashID (QSPI_HandleTypeDef *hqspi, uint32_t FlashID); -/** - * @} - */ - -/** - * @} - */ -/* End of exported functions -------------------------------------------------*/ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup QSPI_Private_Macros QSPI Private Macros - * @{ - */ -#define IS_QSPI_CLOCK_PRESCALER(PRESCALER) ((PRESCALER) <= 0xFFU) - -#define IS_QSPI_FIFO_THRESHOLD(THR) (((THR) > 0U) && ((THR) <= 32U)) - -#define IS_QSPI_SSHIFT(SSHIFT) (((SSHIFT) == QSPI_SAMPLE_SHIFTING_NONE) || \ - ((SSHIFT) == QSPI_SAMPLE_SHIFTING_HALFCYCLE)) - -#define IS_QSPI_FLASH_SIZE(FSIZE) (((FSIZE) <= 31U)) - -#define IS_QSPI_CS_HIGH_TIME(CSHTIME) (((CSHTIME) == QSPI_CS_HIGH_TIME_1_CYCLE) || \ - ((CSHTIME) == QSPI_CS_HIGH_TIME_2_CYCLE) || \ - ((CSHTIME) == QSPI_CS_HIGH_TIME_3_CYCLE) || \ - ((CSHTIME) == QSPI_CS_HIGH_TIME_4_CYCLE) || \ - ((CSHTIME) == QSPI_CS_HIGH_TIME_5_CYCLE) || \ - ((CSHTIME) == QSPI_CS_HIGH_TIME_6_CYCLE) || \ - ((CSHTIME) == QSPI_CS_HIGH_TIME_7_CYCLE) || \ - ((CSHTIME) == QSPI_CS_HIGH_TIME_8_CYCLE)) - -#define IS_QSPI_CLOCK_MODE(CLKMODE) (((CLKMODE) == QSPI_CLOCK_MODE_0) || \ - ((CLKMODE) == QSPI_CLOCK_MODE_3)) - -#define IS_QSPI_FLASH_ID(FLASH_ID) (((FLASH_ID) == QSPI_FLASH_ID_1) || \ - ((FLASH_ID) == QSPI_FLASH_ID_2)) - -#define IS_QSPI_DUAL_FLASH_MODE(MODE) (((MODE) == QSPI_DUALFLASH_ENABLE) || \ - ((MODE) == QSPI_DUALFLASH_DISABLE)) - -#define IS_QSPI_INSTRUCTION(INSTRUCTION) ((INSTRUCTION) <= 0xFFU) - -#define IS_QSPI_ADDRESS_SIZE(ADDR_SIZE) (((ADDR_SIZE) == QSPI_ADDRESS_8_BITS) || \ - ((ADDR_SIZE) == QSPI_ADDRESS_16_BITS) || \ - ((ADDR_SIZE) == QSPI_ADDRESS_24_BITS) || \ - ((ADDR_SIZE) == QSPI_ADDRESS_32_BITS)) - -#define IS_QSPI_ALTERNATE_BYTES_SIZE(SIZE) (((SIZE) == QSPI_ALTERNATE_BYTES_8_BITS) || \ - ((SIZE) == QSPI_ALTERNATE_BYTES_16_BITS) || \ - ((SIZE) == QSPI_ALTERNATE_BYTES_24_BITS) || \ - ((SIZE) == QSPI_ALTERNATE_BYTES_32_BITS)) - -#define IS_QSPI_DUMMY_CYCLES(DCY) ((DCY) <= 31U) - -#define IS_QSPI_INSTRUCTION_MODE(MODE) (((MODE) == QSPI_INSTRUCTION_NONE) || \ - ((MODE) == QSPI_INSTRUCTION_1_LINE) || \ - ((MODE) == QSPI_INSTRUCTION_2_LINES) || \ - ((MODE) == QSPI_INSTRUCTION_4_LINES)) - -#define IS_QSPI_ADDRESS_MODE(MODE) (((MODE) == QSPI_ADDRESS_NONE) || \ - ((MODE) == QSPI_ADDRESS_1_LINE) || \ - ((MODE) == QSPI_ADDRESS_2_LINES) || \ - ((MODE) == QSPI_ADDRESS_4_LINES)) - -#define IS_QSPI_ALTERNATE_BYTES_MODE(MODE) (((MODE) == QSPI_ALTERNATE_BYTES_NONE) || \ - ((MODE) == QSPI_ALTERNATE_BYTES_1_LINE) || \ - ((MODE) == QSPI_ALTERNATE_BYTES_2_LINES) || \ - ((MODE) == QSPI_ALTERNATE_BYTES_4_LINES)) - -#define IS_QSPI_DATA_MODE(MODE) (((MODE) == QSPI_DATA_NONE) || \ - ((MODE) == QSPI_DATA_1_LINE) || \ - ((MODE) == QSPI_DATA_2_LINES) || \ - ((MODE) == QSPI_DATA_4_LINES)) - -#define IS_QSPI_DDR_MODE(DDR_MODE) (((DDR_MODE) == QSPI_DDR_MODE_DISABLE) || \ - ((DDR_MODE) == QSPI_DDR_MODE_ENABLE)) - -#define IS_QSPI_DDR_HHC(DDR_HHC) (((DDR_HHC) == QSPI_DDR_HHC_ANALOG_DELAY) || \ - ((DDR_HHC) == QSPI_DDR_HHC_HALF_CLK_DELAY)) - -#define IS_QSPI_SIOO_MODE(SIOO_MODE) (((SIOO_MODE) == QSPI_SIOO_INST_EVERY_CMD) || \ - ((SIOO_MODE) == QSPI_SIOO_INST_ONLY_FIRST_CMD)) - -#define IS_QSPI_INTERVAL(INTERVAL) ((INTERVAL) <= QUADSPI_PIR_INTERVAL) - -#define IS_QSPI_STATUS_BYTES_SIZE(SIZE) (((SIZE) >= 1U) && ((SIZE) <= 4U)) - -#define IS_QSPI_MATCH_MODE(MODE) (((MODE) == QSPI_MATCH_MODE_AND) || \ - ((MODE) == QSPI_MATCH_MODE_OR)) - -#define IS_QSPI_AUTOMATIC_STOP(APMS) (((APMS) == QSPI_AUTOMATIC_STOP_DISABLE) || \ - ((APMS) == QSPI_AUTOMATIC_STOP_ENABLE)) - -#define IS_QSPI_TIMEOUT_ACTIVATION(TCEN) (((TCEN) == QSPI_TIMEOUT_COUNTER_DISABLE) || \ - ((TCEN) == QSPI_TIMEOUT_COUNTER_ENABLE)) - -#define IS_QSPI_TIMEOUT_PERIOD(PERIOD) ((PERIOD) <= 0xFFFFU) -/** -* @} -*/ -/* End of private macros -----------------------------------------------------*/ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* defined(QUADSPI) || defined(QUADSPI1) || defined(QUADSPI2) */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_HAL_QSPI_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h deleted file mode 100644 index 2eeff34..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc.h +++ /dev/null @@ -1,1462 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_rcc.h - * @author MCD Application Team - * @brief Header file of RCC HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_RCC_H -#define __STM32F4xx_HAL_RCC_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/* Include RCC HAL Extended module */ -/* (include on top of file since RCC structures are defined in extended file) */ -#include "stm32f4xx_hal_rcc_ex.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup RCC - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup RCC_Exported_Types RCC Exported Types - * @{ - */ - -/** - * @brief RCC Internal/External Oscillator (HSE, HSI, LSE and LSI) configuration structure definition - */ -typedef struct -{ - uint32_t OscillatorType; /*!< The oscillators to be configured. - This parameter can be a value of @ref RCC_Oscillator_Type */ - - uint32_t HSEState; /*!< The new state of the HSE. - This parameter can be a value of @ref RCC_HSE_Config */ - - uint32_t LSEState; /*!< The new state of the LSE. - This parameter can be a value of @ref RCC_LSE_Config */ - - uint32_t HSIState; /*!< The new state of the HSI. - This parameter can be a value of @ref RCC_HSI_Config */ - - uint32_t HSICalibrationValue; /*!< The HSI calibration trimming value (default is RCC_HSICALIBRATION_DEFAULT). - This parameter must be a number between Min_Data = 0x00 and Max_Data = 0x1F */ - - uint32_t LSIState; /*!< The new state of the LSI. - This parameter can be a value of @ref RCC_LSI_Config */ - - RCC_PLLInitTypeDef PLL; /*!< PLL structure parameters */ -}RCC_OscInitTypeDef; - -/** - * @brief RCC System, AHB and APB busses clock configuration structure definition - */ -typedef struct -{ - uint32_t ClockType; /*!< The clock to be configured. - This parameter can be a value of @ref RCC_System_Clock_Type */ - - uint32_t SYSCLKSource; /*!< The clock source (SYSCLKS) used as system clock. - This parameter can be a value of @ref RCC_System_Clock_Source */ - - uint32_t AHBCLKDivider; /*!< The AHB clock (HCLK) divider. This clock is derived from the system clock (SYSCLK). - This parameter can be a value of @ref RCC_AHB_Clock_Source */ - - uint32_t APB1CLKDivider; /*!< The APB1 clock (PCLK1) divider. This clock is derived from the AHB clock (HCLK). - This parameter can be a value of @ref RCC_APB1_APB2_Clock_Source */ - - uint32_t APB2CLKDivider; /*!< The APB2 clock (PCLK2) divider. This clock is derived from the AHB clock (HCLK). - This parameter can be a value of @ref RCC_APB1_APB2_Clock_Source */ - -}RCC_ClkInitTypeDef; - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup RCC_Exported_Constants RCC Exported Constants - * @{ - */ - -/** @defgroup RCC_Oscillator_Type Oscillator Type - * @{ - */ -#define RCC_OSCILLATORTYPE_NONE 0x00000000U -#define RCC_OSCILLATORTYPE_HSE 0x00000001U -#define RCC_OSCILLATORTYPE_HSI 0x00000002U -#define RCC_OSCILLATORTYPE_LSE 0x00000004U -#define RCC_OSCILLATORTYPE_LSI 0x00000008U -/** - * @} - */ - -/** @defgroup RCC_HSE_Config HSE Config - * @{ - */ -#define RCC_HSE_OFF 0x00000000U -#define RCC_HSE_ON RCC_CR_HSEON -#define RCC_HSE_BYPASS ((uint32_t)(RCC_CR_HSEBYP | RCC_CR_HSEON)) -/** - * @} - */ - -/** @defgroup RCC_LSE_Config LSE Config - * @{ - */ -#define RCC_LSE_OFF 0x00000000U -#define RCC_LSE_ON RCC_BDCR_LSEON -#define RCC_LSE_BYPASS ((uint32_t)(RCC_BDCR_LSEBYP | RCC_BDCR_LSEON)) -/** - * @} - */ - -/** @defgroup RCC_HSI_Config HSI Config - * @{ - */ -#define RCC_HSI_OFF ((uint8_t)0x00) -#define RCC_HSI_ON ((uint8_t)0x01) - -#define RCC_HSICALIBRATION_DEFAULT 0x10U /* Default HSI calibration trimming value */ -/** - * @} - */ - -/** @defgroup RCC_LSI_Config LSI Config - * @{ - */ -#define RCC_LSI_OFF ((uint8_t)0x00) -#define RCC_LSI_ON ((uint8_t)0x01) -/** - * @} - */ - -/** @defgroup RCC_PLL_Config PLL Config - * @{ - */ -#define RCC_PLL_NONE ((uint8_t)0x00) -#define RCC_PLL_OFF ((uint8_t)0x01) -#define RCC_PLL_ON ((uint8_t)0x02) -/** - * @} - */ - -/** @defgroup RCC_PLLP_Clock_Divider PLLP Clock Divider - * @{ - */ -#define RCC_PLLP_DIV2 0x00000002U -#define RCC_PLLP_DIV4 0x00000004U -#define RCC_PLLP_DIV6 0x00000006U -#define RCC_PLLP_DIV8 0x00000008U -/** - * @} - */ - -/** @defgroup RCC_PLL_Clock_Source PLL Clock Source - * @{ - */ -#define RCC_PLLSOURCE_HSI RCC_PLLCFGR_PLLSRC_HSI -#define RCC_PLLSOURCE_HSE RCC_PLLCFGR_PLLSRC_HSE -/** - * @} - */ - -/** @defgroup RCC_System_Clock_Type System Clock Type - * @{ - */ -#define RCC_CLOCKTYPE_SYSCLK 0x00000001U -#define RCC_CLOCKTYPE_HCLK 0x00000002U -#define RCC_CLOCKTYPE_PCLK1 0x00000004U -#define RCC_CLOCKTYPE_PCLK2 0x00000008U -/** - * @} - */ - -/** @defgroup RCC_System_Clock_Source System Clock Source - * @note The RCC_SYSCLKSOURCE_PLLRCLK parameter is available only for - * STM32F446xx devices. - * @{ - */ -#define RCC_SYSCLKSOURCE_HSI RCC_CFGR_SW_HSI -#define RCC_SYSCLKSOURCE_HSE RCC_CFGR_SW_HSE -#define RCC_SYSCLKSOURCE_PLLCLK RCC_CFGR_SW_PLL -#define RCC_SYSCLKSOURCE_PLLRCLK ((uint32_t)(RCC_CFGR_SW_0 | RCC_CFGR_SW_1)) -/** - * @} - */ - -/** @defgroup RCC_System_Clock_Source_Status System Clock Source Status - * @note The RCC_SYSCLKSOURCE_STATUS_PLLRCLK parameter is available only for - * STM32F446xx devices. - * @{ - */ -#define RCC_SYSCLKSOURCE_STATUS_HSI RCC_CFGR_SWS_HSI /*!< HSI used as system clock */ -#define RCC_SYSCLKSOURCE_STATUS_HSE RCC_CFGR_SWS_HSE /*!< HSE used as system clock */ -#define RCC_SYSCLKSOURCE_STATUS_PLLCLK RCC_CFGR_SWS_PLL /*!< PLL used as system clock */ -#define RCC_SYSCLKSOURCE_STATUS_PLLRCLK ((uint32_t)(RCC_CFGR_SWS_0 | RCC_CFGR_SWS_1)) /*!< PLLR used as system clock */ -/** - * @} - */ - -/** @defgroup RCC_AHB_Clock_Source AHB Clock Source - * @{ - */ -#define RCC_SYSCLK_DIV1 RCC_CFGR_HPRE_DIV1 -#define RCC_SYSCLK_DIV2 RCC_CFGR_HPRE_DIV2 -#define RCC_SYSCLK_DIV4 RCC_CFGR_HPRE_DIV4 -#define RCC_SYSCLK_DIV8 RCC_CFGR_HPRE_DIV8 -#define RCC_SYSCLK_DIV16 RCC_CFGR_HPRE_DIV16 -#define RCC_SYSCLK_DIV64 RCC_CFGR_HPRE_DIV64 -#define RCC_SYSCLK_DIV128 RCC_CFGR_HPRE_DIV128 -#define RCC_SYSCLK_DIV256 RCC_CFGR_HPRE_DIV256 -#define RCC_SYSCLK_DIV512 RCC_CFGR_HPRE_DIV512 -/** - * @} - */ - -/** @defgroup RCC_APB1_APB2_Clock_Source APB1/APB2 Clock Source - * @{ - */ -#define RCC_HCLK_DIV1 RCC_CFGR_PPRE1_DIV1 -#define RCC_HCLK_DIV2 RCC_CFGR_PPRE1_DIV2 -#define RCC_HCLK_DIV4 RCC_CFGR_PPRE1_DIV4 -#define RCC_HCLK_DIV8 RCC_CFGR_PPRE1_DIV8 -#define RCC_HCLK_DIV16 RCC_CFGR_PPRE1_DIV16 -/** - * @} - */ - -/** @defgroup RCC_RTC_Clock_Source RTC Clock Source - * @{ - */ -#define RCC_RTCCLKSOURCE_NO_CLK 0x00000000U -#define RCC_RTCCLKSOURCE_LSE 0x00000100U -#define RCC_RTCCLKSOURCE_LSI 0x00000200U -#define RCC_RTCCLKSOURCE_HSE_DIVX 0x00000300U -#define RCC_RTCCLKSOURCE_HSE_DIV2 0x00020300U -#define RCC_RTCCLKSOURCE_HSE_DIV3 0x00030300U -#define RCC_RTCCLKSOURCE_HSE_DIV4 0x00040300U -#define RCC_RTCCLKSOURCE_HSE_DIV5 0x00050300U -#define RCC_RTCCLKSOURCE_HSE_DIV6 0x00060300U -#define RCC_RTCCLKSOURCE_HSE_DIV7 0x00070300U -#define RCC_RTCCLKSOURCE_HSE_DIV8 0x00080300U -#define RCC_RTCCLKSOURCE_HSE_DIV9 0x00090300U -#define RCC_RTCCLKSOURCE_HSE_DIV10 0x000A0300U -#define RCC_RTCCLKSOURCE_HSE_DIV11 0x000B0300U -#define RCC_RTCCLKSOURCE_HSE_DIV12 0x000C0300U -#define RCC_RTCCLKSOURCE_HSE_DIV13 0x000D0300U -#define RCC_RTCCLKSOURCE_HSE_DIV14 0x000E0300U -#define RCC_RTCCLKSOURCE_HSE_DIV15 0x000F0300U -#define RCC_RTCCLKSOURCE_HSE_DIV16 0x00100300U -#define RCC_RTCCLKSOURCE_HSE_DIV17 0x00110300U -#define RCC_RTCCLKSOURCE_HSE_DIV18 0x00120300U -#define RCC_RTCCLKSOURCE_HSE_DIV19 0x00130300U -#define RCC_RTCCLKSOURCE_HSE_DIV20 0x00140300U -#define RCC_RTCCLKSOURCE_HSE_DIV21 0x00150300U -#define RCC_RTCCLKSOURCE_HSE_DIV22 0x00160300U -#define RCC_RTCCLKSOURCE_HSE_DIV23 0x00170300U -#define RCC_RTCCLKSOURCE_HSE_DIV24 0x00180300U -#define RCC_RTCCLKSOURCE_HSE_DIV25 0x00190300U -#define RCC_RTCCLKSOURCE_HSE_DIV26 0x001A0300U -#define RCC_RTCCLKSOURCE_HSE_DIV27 0x001B0300U -#define RCC_RTCCLKSOURCE_HSE_DIV28 0x001C0300U -#define RCC_RTCCLKSOURCE_HSE_DIV29 0x001D0300U -#define RCC_RTCCLKSOURCE_HSE_DIV30 0x001E0300U -#define RCC_RTCCLKSOURCE_HSE_DIV31 0x001F0300U -/** - * @} - */ - -/** @defgroup RCC_MCO_Index MCO Index - * @{ - */ -#define RCC_MCO1 0x00000000U -#define RCC_MCO2 0x00000001U -/** - * @} - */ - -/** @defgroup RCC_MCO1_Clock_Source MCO1 Clock Source - * @{ - */ -#define RCC_MCO1SOURCE_HSI 0x00000000U -#define RCC_MCO1SOURCE_LSE RCC_CFGR_MCO1_0 -#define RCC_MCO1SOURCE_HSE RCC_CFGR_MCO1_1 -#define RCC_MCO1SOURCE_PLLCLK RCC_CFGR_MCO1 -/** - * @} - */ - -/** @defgroup RCC_MCOx_Clock_Prescaler MCOx Clock Prescaler - * @{ - */ -#define RCC_MCODIV_1 0x00000000U -#define RCC_MCODIV_2 RCC_CFGR_MCO1PRE_2 -#define RCC_MCODIV_3 ((uint32_t)RCC_CFGR_MCO1PRE_0 | RCC_CFGR_MCO1PRE_2) -#define RCC_MCODIV_4 ((uint32_t)RCC_CFGR_MCO1PRE_1 | RCC_CFGR_MCO1PRE_2) -#define RCC_MCODIV_5 RCC_CFGR_MCO1PRE -/** - * @} - */ - -/** @defgroup RCC_Interrupt Interrupts - * @{ - */ -#define RCC_IT_LSIRDY ((uint8_t)0x01) -#define RCC_IT_LSERDY ((uint8_t)0x02) -#define RCC_IT_HSIRDY ((uint8_t)0x04) -#define RCC_IT_HSERDY ((uint8_t)0x08) -#define RCC_IT_PLLRDY ((uint8_t)0x10) -#define RCC_IT_PLLI2SRDY ((uint8_t)0x20) -#define RCC_IT_CSS ((uint8_t)0x80) -/** - * @} - */ - -/** @defgroup RCC_Flag Flags - * Elements values convention: 0XXYYYYYb - * - YYYYY : Flag position in the register - * - 0XX : Register index - * - 01: CR register - * - 10: BDCR register - * - 11: CSR register - * @{ - */ -/* Flags in the CR register */ -#define RCC_FLAG_HSIRDY ((uint8_t)0x21) -#define RCC_FLAG_HSERDY ((uint8_t)0x31) -#define RCC_FLAG_PLLRDY ((uint8_t)0x39) -#define RCC_FLAG_PLLI2SRDY ((uint8_t)0x3B) - -/* Flags in the BDCR register */ -#define RCC_FLAG_LSERDY ((uint8_t)0x41) - -/* Flags in the CSR register */ -#define RCC_FLAG_LSIRDY ((uint8_t)0x61) -#define RCC_FLAG_BORRST ((uint8_t)0x79) -#define RCC_FLAG_PINRST ((uint8_t)0x7A) -#define RCC_FLAG_PORRST ((uint8_t)0x7B) -#define RCC_FLAG_SFTRST ((uint8_t)0x7C) -#define RCC_FLAG_IWDGRST ((uint8_t)0x7D) -#define RCC_FLAG_WWDGRST ((uint8_t)0x7E) -#define RCC_FLAG_LPWRRST ((uint8_t)0x7F) -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup RCC_Exported_Macros RCC Exported Macros - * @{ - */ - -/** @defgroup RCC_AHB1_Clock_Enable_Disable AHB1 Peripheral Clock Enable Disable - * @brief Enable or disable the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_GPIOA_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOAEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOAEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOB_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOBEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOBEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOCEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOCEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOH_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOHEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOHEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_DMA1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_DMA1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_DMA1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_DMA2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_DMA2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_DMA2EN);\ - UNUSED(tmpreg); \ - } while(0U) - -#define __HAL_RCC_GPIOA_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOAEN)) -#define __HAL_RCC_GPIOB_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOBEN)) -#define __HAL_RCC_GPIOC_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOCEN)) -#define __HAL_RCC_GPIOH_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOHEN)) -#define __HAL_RCC_DMA1_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_DMA1EN)) -#define __HAL_RCC_DMA2_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_DMA2EN)) -/** - * @} - */ - -/** @defgroup RCC_AHB1_Peripheral_Clock_Enable_Disable_Status AHB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_GPIOA_IS_CLK_ENABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_GPIOAEN)) != RESET) -#define __HAL_RCC_GPIOB_IS_CLK_ENABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_GPIOBEN)) != RESET) -#define __HAL_RCC_GPIOC_IS_CLK_ENABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_GPIOCEN)) != RESET) -#define __HAL_RCC_GPIOH_IS_CLK_ENABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_GPIOHEN)) != RESET) -#define __HAL_RCC_DMA1_IS_CLK_ENABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_DMA1EN)) != RESET) -#define __HAL_RCC_DMA2_IS_CLK_ENABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_DMA2EN)) != RESET) - -#define __HAL_RCC_GPIOA_IS_CLK_DISABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_GPIOAEN)) == RESET) -#define __HAL_RCC_GPIOB_IS_CLK_DISABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_GPIOBEN)) == RESET) -#define __HAL_RCC_GPIOC_IS_CLK_DISABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_GPIOCEN)) == RESET) -#define __HAL_RCC_GPIOH_IS_CLK_DISABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_GPIOHEN)) == RESET) -#define __HAL_RCC_DMA1_IS_CLK_DISABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_DMA1EN)) == RESET) -#define __HAL_RCC_DMA2_IS_CLK_DISABLED() ((RCC->AHB1ENR &(RCC_AHB1ENR_DMA2EN)) == RESET) -/** - * @} - */ - -/** @defgroup RCC_APB1_Clock_Enable_Disable APB1 Peripheral Clock Enable Disable - * @brief Enable or disable the Low Speed APB (APB1) peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM5_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM5EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM5EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_WWDG_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_WWDGEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_WWDGEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_USART2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_USART2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_USART2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_I2C1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_I2C2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_PWR_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_PWREN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_PWREN);\ - UNUSED(tmpreg); \ - } while(0U) - -#define __HAL_RCC_TIM5_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM5EN)) -#define __HAL_RCC_WWDG_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_WWDGEN)) -#define __HAL_RCC_SPI2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_SPI2EN)) -#define __HAL_RCC_USART2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_USART2EN)) -#define __HAL_RCC_I2C1_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_I2C1EN)) -#define __HAL_RCC_I2C2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_I2C2EN)) -#define __HAL_RCC_PWR_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_PWREN)) -/** - * @} - */ - -/** @defgroup RCC_APB1_Peripheral_Clock_Enable_Disable_Status APB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM5_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM5EN)) != RESET) -#define __HAL_RCC_WWDG_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_WWDGEN)) != RESET) -#define __HAL_RCC_SPI2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI2EN)) != RESET) -#define __HAL_RCC_USART2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART2EN)) != RESET) -#define __HAL_RCC_I2C1_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C1EN)) != RESET) -#define __HAL_RCC_I2C2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C2EN)) != RESET) -#define __HAL_RCC_PWR_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_PWREN)) != RESET) - -#define __HAL_RCC_TIM5_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM5EN)) == RESET) -#define __HAL_RCC_WWDG_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_WWDGEN)) == RESET) -#define __HAL_RCC_SPI2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI2EN)) == RESET) -#define __HAL_RCC_USART2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART2EN)) == RESET) -#define __HAL_RCC_I2C1_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C1EN)) == RESET) -#define __HAL_RCC_I2C2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C2EN)) == RESET) -#define __HAL_RCC_PWR_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_PWREN)) == RESET) -/** - * @} - */ - -/** @defgroup RCC_APB2_Clock_Enable_Disable APB2 Peripheral Clock Enable Disable - * @brief Enable or disable the High Speed APB (APB2) peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_USART1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_USART1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_USART1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_USART6_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_USART6EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_USART6EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ADC1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SYSCFG_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SYSCFGEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SYSCFGEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM9_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM9EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM9EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM11_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM11EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM11EN);\ - UNUSED(tmpreg); \ - } while(0U) - -#define __HAL_RCC_TIM1_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM1EN)) -#define __HAL_RCC_USART1_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_USART1EN)) -#define __HAL_RCC_USART6_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_USART6EN)) -#define __HAL_RCC_ADC1_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_ADC1EN)) -#define __HAL_RCC_SPI1_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI1EN)) -#define __HAL_RCC_SYSCFG_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SYSCFGEN)) -#define __HAL_RCC_TIM9_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM9EN)) -#define __HAL_RCC_TIM11_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM11EN)) -/** - * @} - */ - -/** @defgroup RCC_APB2_Peripheral_Clock_Enable_Disable_Status APB2 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM1_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM1EN)) != RESET) -#define __HAL_RCC_USART1_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_USART1EN)) != RESET) -#define __HAL_RCC_USART6_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_USART6EN)) != RESET) -#define __HAL_RCC_ADC1_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC1EN)) != RESET) -#define __HAL_RCC_SPI1_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI1EN)) != RESET) -#define __HAL_RCC_SYSCFG_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SYSCFGEN)) != RESET) -#define __HAL_RCC_TIM9_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM9EN)) != RESET) -#define __HAL_RCC_TIM11_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM11EN)) != RESET) - -#define __HAL_RCC_TIM1_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM1EN)) == RESET) -#define __HAL_RCC_USART1_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_USART1EN)) == RESET) -#define __HAL_RCC_USART6_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_USART6EN)) == RESET) -#define __HAL_RCC_ADC1_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC1EN)) == RESET) -#define __HAL_RCC_SPI1_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI1EN)) == RESET) -#define __HAL_RCC_SYSCFG_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SYSCFGEN)) == RESET) -#define __HAL_RCC_TIM9_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM9EN)) == RESET) -#define __HAL_RCC_TIM11_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM11EN)) == RESET) -/** - * @} - */ - -/** @defgroup RCC_AHB1_Force_Release_Reset AHB1 Force Release Reset - * @brief Force or release AHB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB1_FORCE_RESET() (RCC->AHB1RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_GPIOA_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOARST)) -#define __HAL_RCC_GPIOB_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOBRST)) -#define __HAL_RCC_GPIOC_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOCRST)) -#define __HAL_RCC_GPIOH_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOHRST)) -#define __HAL_RCC_DMA1_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_DMA1RST)) -#define __HAL_RCC_DMA2_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_DMA2RST)) - -#define __HAL_RCC_AHB1_RELEASE_RESET() (RCC->AHB1RSTR = 0x00U) -#define __HAL_RCC_GPIOA_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOARST)) -#define __HAL_RCC_GPIOB_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOBRST)) -#define __HAL_RCC_GPIOC_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOCRST)) -#define __HAL_RCC_GPIOH_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOHRST)) -#define __HAL_RCC_DMA1_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_DMA1RST)) -#define __HAL_RCC_DMA2_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_DMA2RST)) -/** - * @} - */ - -/** @defgroup RCC_APB1_Force_Release_Reset APB1 Force Release Reset - * @brief Force or release APB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_APB1_FORCE_RESET() (RCC->APB1RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_TIM5_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM5RST)) -#define __HAL_RCC_WWDG_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_WWDGRST)) -#define __HAL_RCC_SPI2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_SPI2RST)) -#define __HAL_RCC_USART2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_USART2RST)) -#define __HAL_RCC_I2C1_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_I2C1RST)) -#define __HAL_RCC_I2C2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_I2C2RST)) -#define __HAL_RCC_PWR_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_PWRRST)) - -#define __HAL_RCC_APB1_RELEASE_RESET() (RCC->APB1RSTR = 0x00U) -#define __HAL_RCC_TIM5_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM5RST)) -#define __HAL_RCC_WWDG_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_WWDGRST)) -#define __HAL_RCC_SPI2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_SPI2RST)) -#define __HAL_RCC_USART2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_USART2RST)) -#define __HAL_RCC_I2C1_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_I2C1RST)) -#define __HAL_RCC_I2C2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_I2C2RST)) -#define __HAL_RCC_PWR_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_PWRRST)) -/** - * @} - */ - -/** @defgroup RCC_APB2_Force_Release_Reset APB2 Force Release Reset - * @brief Force or release APB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_APB2_FORCE_RESET() (RCC->APB2RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_TIM1_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM1RST)) -#define __HAL_RCC_USART1_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_USART1RST)) -#define __HAL_RCC_USART6_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_USART6RST)) -#define __HAL_RCC_ADC_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_ADCRST)) -#define __HAL_RCC_SPI1_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI1RST)) -#define __HAL_RCC_SYSCFG_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SYSCFGRST)) -#define __HAL_RCC_TIM9_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM9RST)) -#define __HAL_RCC_TIM11_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM11RST)) - -#define __HAL_RCC_APB2_RELEASE_RESET() (RCC->APB2RSTR = 0x00U) -#define __HAL_RCC_TIM1_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM1RST)) -#define __HAL_RCC_USART1_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_USART1RST)) -#define __HAL_RCC_USART6_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_USART6RST)) -#define __HAL_RCC_ADC_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_ADCRST)) -#define __HAL_RCC_SPI1_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI1RST)) -#define __HAL_RCC_SYSCFG_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SYSCFGRST)) -#define __HAL_RCC_TIM9_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM9RST)) -#define __HAL_RCC_TIM11_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM11RST)) -/** - * @} - */ - -/** @defgroup RCC_AHB1_LowPower_Enable_Disable AHB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB1 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_GPIOA_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOALPEN)) -#define __HAL_RCC_GPIOB_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOBLPEN)) -#define __HAL_RCC_GPIOC_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOCLPEN)) -#define __HAL_RCC_GPIOH_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOHLPEN)) -#define __HAL_RCC_DMA1_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_DMA1LPEN)) -#define __HAL_RCC_DMA2_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_DMA2LPEN)) - -#define __HAL_RCC_GPIOA_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOALPEN)) -#define __HAL_RCC_GPIOB_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOBLPEN)) -#define __HAL_RCC_GPIOC_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOCLPEN)) -#define __HAL_RCC_GPIOH_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOHLPEN)) -#define __HAL_RCC_DMA1_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_DMA1LPEN)) -#define __HAL_RCC_DMA2_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_DMA2LPEN)) -/** - * @} - */ - -/** @defgroup RCC_APB1_LowPower_Enable_Disable APB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB1 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_TIM5_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM5LPEN)) -#define __HAL_RCC_WWDG_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_WWDGLPEN)) -#define __HAL_RCC_SPI2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_SPI2LPEN)) -#define __HAL_RCC_USART2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_USART2LPEN)) -#define __HAL_RCC_I2C1_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_I2C1LPEN)) -#define __HAL_RCC_I2C2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_I2C2LPEN)) -#define __HAL_RCC_PWR_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_PWRLPEN)) - -#define __HAL_RCC_TIM5_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM5LPEN)) -#define __HAL_RCC_WWDG_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_WWDGLPEN)) -#define __HAL_RCC_SPI2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_SPI2LPEN)) -#define __HAL_RCC_USART2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_USART2LPEN)) -#define __HAL_RCC_I2C1_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_I2C1LPEN)) -#define __HAL_RCC_I2C2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_I2C2LPEN)) -#define __HAL_RCC_PWR_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_PWRLPEN)) -/** - * @} - */ - -/** @defgroup RCC_APB2_LowPower_Enable_Disable APB2 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB2 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_TIM1_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_TIM1LPEN)) -#define __HAL_RCC_USART1_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_USART1LPEN)) -#define __HAL_RCC_USART6_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_USART6LPEN)) -#define __HAL_RCC_ADC1_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_ADC1LPEN)) -#define __HAL_RCC_SPI1_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI1LPEN)) -#define __HAL_RCC_SYSCFG_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SYSCFGLPEN)) -#define __HAL_RCC_TIM9_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_TIM9LPEN)) -#define __HAL_RCC_TIM11_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_TIM11LPEN)) - -#define __HAL_RCC_TIM1_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM1LPEN)) -#define __HAL_RCC_USART1_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_USART1LPEN)) -#define __HAL_RCC_USART6_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_USART6LPEN)) -#define __HAL_RCC_ADC1_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_ADC1LPEN)) -#define __HAL_RCC_SPI1_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI1LPEN)) -#define __HAL_RCC_SYSCFG_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SYSCFGLPEN)) -#define __HAL_RCC_TIM9_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM9LPEN)) -#define __HAL_RCC_TIM11_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM11LPEN)) -/** - * @} - */ - -/** @defgroup RCC_HSI_Configuration HSI Configuration - * @{ - */ - -/** @brief Macros to enable or disable the Internal High Speed oscillator (HSI). - * @note The HSI is stopped by hardware when entering STOP and STANDBY modes. - * It is used (enabled by hardware) as system clock source after startup - * from Reset, wake-up from STOP and STANDBY mode, or in case of failure - * of the HSE used directly or indirectly as system clock (if the Clock - * Security System CSS is enabled). - * @note HSI can not be stopped if it is used as system clock source. In this case, - * you have to select another source of the system clock then stop the HSI. - * @note After enabling the HSI, the application software should wait on HSIRDY - * flag to be set indicating that HSI clock is stable and can be used as - * system clock source. - * This parameter can be: ENABLE or DISABLE. - * @note When the HSI is stopped, HSIRDY flag goes low after 6 HSI oscillator - * clock cycles. - */ -#define __HAL_RCC_HSI_ENABLE() (*(__IO uint32_t *) RCC_CR_HSION_BB = ENABLE) -#define __HAL_RCC_HSI_DISABLE() (*(__IO uint32_t *) RCC_CR_HSION_BB = DISABLE) - -/** @brief Macro to adjust the Internal High Speed oscillator (HSI) calibration value. - * @note The calibration is used to compensate for the variations in voltage - * and temperature that influence the frequency of the internal HSI RC. - * @param __HSICalibrationValue__ specifies the calibration trimming value. - * (default is RCC_HSICALIBRATION_DEFAULT). - * This parameter must be a number between 0 and 0x1F. - */ -#define __HAL_RCC_HSI_CALIBRATIONVALUE_ADJUST(__HSICalibrationValue__) (MODIFY_REG(RCC->CR,\ - RCC_CR_HSITRIM, (uint32_t)(__HSICalibrationValue__) << RCC_CR_HSITRIM_Pos)) -/** - * @} - */ - -/** @defgroup RCC_LSI_Configuration LSI Configuration - * @{ - */ - -/** @brief Macros to enable or disable the Internal Low Speed oscillator (LSI). - * @note After enabling the LSI, the application software should wait on - * LSIRDY flag to be set indicating that LSI clock is stable and can - * be used to clock the IWDG and/or the RTC. - * @note LSI can not be disabled if the IWDG is running. - * @note When the LSI is stopped, LSIRDY flag goes low after 6 LSI oscillator - * clock cycles. - */ -#define __HAL_RCC_LSI_ENABLE() (*(__IO uint32_t *) RCC_CSR_LSION_BB = ENABLE) -#define __HAL_RCC_LSI_DISABLE() (*(__IO uint32_t *) RCC_CSR_LSION_BB = DISABLE) -/** - * @} - */ - -/** @defgroup RCC_HSE_Configuration HSE Configuration - * @{ - */ - -/** - * @brief Macro to configure the External High Speed oscillator (HSE). - * @note Transition HSE Bypass to HSE On and HSE On to HSE Bypass are not supported by this macro. - * User should request a transition to HSE Off first and then HSE On or HSE Bypass. - * @note After enabling the HSE (RCC_HSE_ON or RCC_HSE_Bypass), the application - * software should wait on HSERDY flag to be set indicating that HSE clock - * is stable and can be used to clock the PLL and/or system clock. - * @note HSE state can not be changed if it is used directly or through the - * PLL as system clock. In this case, you have to select another source - * of the system clock then change the HSE state (ex. disable it). - * @note The HSE is stopped by hardware when entering STOP and STANDBY modes. - * @note This function reset the CSSON bit, so if the clock security system(CSS) - * was previously enabled you have to enable it again after calling this - * function. - * @param __STATE__ specifies the new state of the HSE. - * This parameter can be one of the following values: - * @arg RCC_HSE_OFF: turn OFF the HSE oscillator, HSERDY flag goes low after - * 6 HSE oscillator clock cycles. - * @arg RCC_HSE_ON: turn ON the HSE oscillator. - * @arg RCC_HSE_BYPASS: HSE oscillator bypassed with external clock. - */ -#define __HAL_RCC_HSE_CONFIG(__STATE__) \ - do { \ - if ((__STATE__) == RCC_HSE_ON) \ - { \ - SET_BIT(RCC->CR, RCC_CR_HSEON); \ - } \ - else if ((__STATE__) == RCC_HSE_BYPASS) \ - { \ - SET_BIT(RCC->CR, RCC_CR_HSEBYP); \ - SET_BIT(RCC->CR, RCC_CR_HSEON); \ - } \ - else \ - { \ - CLEAR_BIT(RCC->CR, RCC_CR_HSEON); \ - CLEAR_BIT(RCC->CR, RCC_CR_HSEBYP); \ - } \ - } while(0U) -/** - * @} - */ - -/** @defgroup RCC_LSE_Configuration LSE Configuration - * @{ - */ - -/** - * @brief Macro to configure the External Low Speed oscillator (LSE). - * @note Transition LSE Bypass to LSE On and LSE On to LSE Bypass are not supported by this macro. - * User should request a transition to LSE Off first and then LSE On or LSE Bypass. - * @note As the LSE is in the Backup domain and write access is denied to - * this domain after reset, you have to enable write access using - * HAL_PWR_EnableBkUpAccess() function before to configure the LSE - * (to be done once after reset). - * @note After enabling the LSE (RCC_LSE_ON or RCC_LSE_BYPASS), the application - * software should wait on LSERDY flag to be set indicating that LSE clock - * is stable and can be used to clock the RTC. - * @param __STATE__ specifies the new state of the LSE. - * This parameter can be one of the following values: - * @arg RCC_LSE_OFF: turn OFF the LSE oscillator, LSERDY flag goes low after - * 6 LSE oscillator clock cycles. - * @arg RCC_LSE_ON: turn ON the LSE oscillator. - * @arg RCC_LSE_BYPASS: LSE oscillator bypassed with external clock. - */ -#define __HAL_RCC_LSE_CONFIG(__STATE__) \ - do { \ - if((__STATE__) == RCC_LSE_ON) \ - { \ - SET_BIT(RCC->BDCR, RCC_BDCR_LSEON); \ - } \ - else if((__STATE__) == RCC_LSE_BYPASS) \ - { \ - SET_BIT(RCC->BDCR, RCC_BDCR_LSEBYP); \ - SET_BIT(RCC->BDCR, RCC_BDCR_LSEON); \ - } \ - else \ - { \ - CLEAR_BIT(RCC->BDCR, RCC_BDCR_LSEON); \ - CLEAR_BIT(RCC->BDCR, RCC_BDCR_LSEBYP); \ - } \ - } while(0U) -/** - * @} - */ - -/** @defgroup RCC_Internal_RTC_Clock_Configuration RTC Clock Configuration - * @{ - */ - -/** @brief Macros to enable or disable the RTC clock. - * @note These macros must be used only after the RTC clock source was selected. - */ -#define __HAL_RCC_RTC_ENABLE() (*(__IO uint32_t *) RCC_BDCR_RTCEN_BB = ENABLE) -#define __HAL_RCC_RTC_DISABLE() (*(__IO uint32_t *) RCC_BDCR_RTCEN_BB = DISABLE) - -/** @brief Macros to configure the RTC clock (RTCCLK). - * @note As the RTC clock configuration bits are in the Backup domain and write - * access is denied to this domain after reset, you have to enable write - * access using the Power Backup Access macro before to configure - * the RTC clock source (to be done once after reset). - * @note Once the RTC clock is configured it can't be changed unless the - * Backup domain is reset using __HAL_RCC_BackupReset_RELEASE() macro, or by - * a Power On Reset (POR). - * @param __RTCCLKSource__ specifies the RTC clock source. - * This parameter can be one of the following values: - * @arg @ref RCC_RTCCLKSOURCE_NO_CLK : No clock selected as RTC clock. - * @arg @ref RCC_RTCCLKSOURCE_LSE : LSE selected as RTC clock. - * @arg @ref RCC_RTCCLKSOURCE_LSI : LSI selected as RTC clock. - * @arg @ref RCC_RTCCLKSOURCE_HSE_DIVX HSE divided by X selected as RTC clock (X can be retrieved thanks to @ref __HAL_RCC_GET_RTC_HSE_PRESCALER() - * @note If the LSE or LSI is used as RTC clock source, the RTC continues to - * work in STOP and STANDBY modes, and can be used as wake-up source. - * However, when the HSE clock is used as RTC clock source, the RTC - * cannot be used in STOP and STANDBY modes. - * @note The maximum input clock frequency for RTC is 1MHz (when using HSE as - * RTC clock source). - */ -#define __HAL_RCC_RTC_CLKPRESCALER(__RTCCLKSource__) (((__RTCCLKSource__) & RCC_BDCR_RTCSEL) == RCC_BDCR_RTCSEL) ? \ - MODIFY_REG(RCC->CFGR, RCC_CFGR_RTCPRE, ((__RTCCLKSource__) & 0xFFFFCFFU)) : CLEAR_BIT(RCC->CFGR, RCC_CFGR_RTCPRE) - -#define __HAL_RCC_RTC_CONFIG(__RTCCLKSource__) do { __HAL_RCC_RTC_CLKPRESCALER(__RTCCLKSource__); \ - RCC->BDCR |= ((__RTCCLKSource__) & 0x00000FFFU); \ - } while(0U) - -/** @brief Macro to get the RTC clock source. - * @retval The clock source can be one of the following values: - * @arg @ref RCC_RTCCLKSOURCE_NO_CLK No clock selected as RTC clock - * @arg @ref RCC_RTCCLKSOURCE_LSE LSE selected as RTC clock - * @arg @ref RCC_RTCCLKSOURCE_LSI LSI selected as RTC clock - * @arg @ref RCC_RTCCLKSOURCE_HSE_DIVX HSE divided by X selected as RTC clock (X can be retrieved thanks to @ref __HAL_RCC_GET_RTC_HSE_PRESCALER() - */ -#define __HAL_RCC_GET_RTC_SOURCE() (READ_BIT(RCC->BDCR, RCC_BDCR_RTCSEL)) - -/** - * @brief Get the RTC and HSE clock divider (RTCPRE). - * @retval Returned value can be one of the following values: - * @arg @ref RCC_RTCCLKSOURCE_HSE_DIVX HSE divided by X selected as RTC clock (X can be retrieved thanks to @ref __HAL_RCC_GET_RTC_HSE_PRESCALER() - */ -#define __HAL_RCC_GET_RTC_HSE_PRESCALER() (READ_BIT(RCC->CFGR, RCC_CFGR_RTCPRE) | RCC_BDCR_RTCSEL) - -/** @brief Macros to force or release the Backup domain reset. - * @note This function resets the RTC peripheral (including the backup registers) - * and the RTC clock source selection in RCC_CSR register. - * @note The BKPSRAM is not affected by this reset. - */ -#define __HAL_RCC_BACKUPRESET_FORCE() (*(__IO uint32_t *) RCC_BDCR_BDRST_BB = ENABLE) -#define __HAL_RCC_BACKUPRESET_RELEASE() (*(__IO uint32_t *) RCC_BDCR_BDRST_BB = DISABLE) -/** - * @} - */ - -/** @defgroup RCC_PLL_Configuration PLL Configuration - * @{ - */ - -/** @brief Macros to enable or disable the main PLL. - * @note After enabling the main PLL, the application software should wait on - * PLLRDY flag to be set indicating that PLL clock is stable and can - * be used as system clock source. - * @note The main PLL can not be disabled if it is used as system clock source - * @note The main PLL is disabled by hardware when entering STOP and STANDBY modes. - */ -#define __HAL_RCC_PLL_ENABLE() (*(__IO uint32_t *) RCC_CR_PLLON_BB = ENABLE) -#define __HAL_RCC_PLL_DISABLE() (*(__IO uint32_t *) RCC_CR_PLLON_BB = DISABLE) - -/** @brief Macro to configure the PLL clock source. - * @note This function must be used only when the main PLL is disabled. - * @param __PLLSOURCE__ specifies the PLL entry clock source. - * This parameter can be one of the following values: - * @arg RCC_PLLSOURCE_HSI: HSI oscillator clock selected as PLL clock entry - * @arg RCC_PLLSOURCE_HSE: HSE oscillator clock selected as PLL clock entry - * - */ -#define __HAL_RCC_PLL_PLLSOURCE_CONFIG(__PLLSOURCE__) MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC, (__PLLSOURCE__)) - -/** @brief Macro to configure the PLL multiplication factor. - * @note This function must be used only when the main PLL is disabled. - * @param __PLLM__ specifies the division factor for PLL VCO input clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 63. - * @note You have to set the PLLM parameter correctly to ensure that the VCO input - * frequency ranges from 1 to 2 MHz. It is recommended to select a frequency - * of 2 MHz to limit PLL jitter. - * - */ -#define __HAL_RCC_PLL_PLLM_CONFIG(__PLLM__) MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLM, (__PLLM__)) -/** - * @} - */ - -/** @defgroup RCC_Get_Clock_source Get Clock source - * @{ - */ -/** - * @brief Macro to configure the system clock source. - * @param __RCC_SYSCLKSOURCE__ specifies the system clock source. - * This parameter can be one of the following values: - * - RCC_SYSCLKSOURCE_HSI: HSI oscillator is used as system clock source. - * - RCC_SYSCLKSOURCE_HSE: HSE oscillator is used as system clock source. - * - RCC_SYSCLKSOURCE_PLLCLK: PLL output is used as system clock source. - * - RCC_SYSCLKSOURCE_PLLRCLK: PLLR output is used as system clock source. This - * parameter is available only for STM32F446xx devices. - */ -#define __HAL_RCC_SYSCLK_CONFIG(__RCC_SYSCLKSOURCE__) MODIFY_REG(RCC->CFGR, RCC_CFGR_SW, (__RCC_SYSCLKSOURCE__)) - -/** @brief Macro to get the clock source used as system clock. - * @retval The clock source used as system clock. The returned value can be one - * of the following: - * - RCC_SYSCLKSOURCE_STATUS_HSI: HSI used as system clock. - * - RCC_SYSCLKSOURCE_STATUS_HSE: HSE used as system clock. - * - RCC_SYSCLKSOURCE_STATUS_PLLCLK: PLL used as system clock. - * - RCC_SYSCLKSOURCE_STATUS_PLLRCLK: PLLR used as system clock. This parameter - * is available only for STM32F446xx devices. - */ -#define __HAL_RCC_GET_SYSCLK_SOURCE() (RCC->CFGR & RCC_CFGR_SWS) - -/** @brief Macro to get the oscillator used as PLL clock source. - * @retval The oscillator used as PLL clock source. The returned value can be one - * of the following: - * - RCC_PLLSOURCE_HSI: HSI oscillator is used as PLL clock source. - * - RCC_PLLSOURCE_HSE: HSE oscillator is used as PLL clock source. - */ -#define __HAL_RCC_GET_PLL_OSCSOURCE() ((uint32_t)(RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC)) -/** - * @} - */ - -/** @defgroup RCCEx_MCOx_Clock_Config RCC Extended MCOx Clock Config - * @{ - */ - -/** @brief Macro to configure the MCO1 clock. - * @param __MCOCLKSOURCE__ specifies the MCO clock source. - * This parameter can be one of the following values: - * @arg RCC_MCO1SOURCE_HSI: HSI clock selected as MCO1 source - * @arg RCC_MCO1SOURCE_LSE: LSE clock selected as MCO1 source - * @arg RCC_MCO1SOURCE_HSE: HSE clock selected as MCO1 source - * @arg RCC_MCO1SOURCE_PLLCLK: main PLL clock selected as MCO1 source - * @param __MCODIV__ specifies the MCO clock prescaler. - * This parameter can be one of the following values: - * @arg RCC_MCODIV_1: no division applied to MCOx clock - * @arg RCC_MCODIV_2: division by 2 applied to MCOx clock - * @arg RCC_MCODIV_3: division by 3 applied to MCOx clock - * @arg RCC_MCODIV_4: division by 4 applied to MCOx clock - * @arg RCC_MCODIV_5: division by 5 applied to MCOx clock - */ -#define __HAL_RCC_MCO1_CONFIG(__MCOCLKSOURCE__, __MCODIV__) \ - MODIFY_REG(RCC->CFGR, (RCC_CFGR_MCO1 | RCC_CFGR_MCO1PRE), ((__MCOCLKSOURCE__) | (__MCODIV__))) - -/** @brief Macro to configure the MCO2 clock. - * @param __MCOCLKSOURCE__ specifies the MCO clock source. - * This parameter can be one of the following values: - * @arg RCC_MCO2SOURCE_SYSCLK: System clock (SYSCLK) selected as MCO2 source - * @arg RCC_MCO2SOURCE_PLLI2SCLK: PLLI2S clock selected as MCO2 source, available for all STM32F4 devices except STM32F410xx - * @arg RCC_MCO2SOURCE_I2SCLK: I2SCLK clock selected as MCO2 source, available only for STM32F410Rx devices - * @arg RCC_MCO2SOURCE_HSE: HSE clock selected as MCO2 source - * @arg RCC_MCO2SOURCE_PLLCLK: main PLL clock selected as MCO2 source - * @param __MCODIV__ specifies the MCO clock prescaler. - * This parameter can be one of the following values: - * @arg RCC_MCODIV_1: no division applied to MCOx clock - * @arg RCC_MCODIV_2: division by 2 applied to MCOx clock - * @arg RCC_MCODIV_3: division by 3 applied to MCOx clock - * @arg RCC_MCODIV_4: division by 4 applied to MCOx clock - * @arg RCC_MCODIV_5: division by 5 applied to MCOx clock - * @note For STM32F410Rx devices, to output I2SCLK clock on MCO2, you should have - * at least one of the SPI clocks enabled (SPI1, SPI2 or SPI5). - */ -#define __HAL_RCC_MCO2_CONFIG(__MCOCLKSOURCE__, __MCODIV__) \ - MODIFY_REG(RCC->CFGR, (RCC_CFGR_MCO2 | RCC_CFGR_MCO2PRE), ((__MCOCLKSOURCE__) | ((__MCODIV__) << 3U))); -/** - * @} - */ - -/** @defgroup RCC_Flags_Interrupts_Management Flags Interrupts Management - * @brief macros to manage the specified RCC Flags and interrupts. - * @{ - */ - -/** @brief Enable RCC interrupt (Perform Byte access to RCC_CIR[14:8] bits to enable - * the selected interrupts). - * @param __INTERRUPT__ specifies the RCC interrupt sources to be enabled. - * This parameter can be any combination of the following values: - * @arg RCC_IT_LSIRDY: LSI ready interrupt. - * @arg RCC_IT_LSERDY: LSE ready interrupt. - * @arg RCC_IT_HSIRDY: HSI ready interrupt. - * @arg RCC_IT_HSERDY: HSE ready interrupt. - * @arg RCC_IT_PLLRDY: Main PLL ready interrupt. - * @arg RCC_IT_PLLI2SRDY: PLLI2S ready interrupt. - */ -#define __HAL_RCC_ENABLE_IT(__INTERRUPT__) (*(__IO uint8_t *) RCC_CIR_BYTE1_ADDRESS |= (__INTERRUPT__)) - -/** @brief Disable RCC interrupt (Perform Byte access to RCC_CIR[14:8] bits to disable - * the selected interrupts). - * @param __INTERRUPT__ specifies the RCC interrupt sources to be disabled. - * This parameter can be any combination of the following values: - * @arg RCC_IT_LSIRDY: LSI ready interrupt. - * @arg RCC_IT_LSERDY: LSE ready interrupt. - * @arg RCC_IT_HSIRDY: HSI ready interrupt. - * @arg RCC_IT_HSERDY: HSE ready interrupt. - * @arg RCC_IT_PLLRDY: Main PLL ready interrupt. - * @arg RCC_IT_PLLI2SRDY: PLLI2S ready interrupt. - */ -#define __HAL_RCC_DISABLE_IT(__INTERRUPT__) (*(__IO uint8_t *) RCC_CIR_BYTE1_ADDRESS &= (uint8_t)(~(__INTERRUPT__))) - -/** @brief Clear the RCC's interrupt pending bits (Perform Byte access to RCC_CIR[23:16] - * bits to clear the selected interrupt pending bits. - * @param __INTERRUPT__ specifies the interrupt pending bit to clear. - * This parameter can be any combination of the following values: - * @arg RCC_IT_LSIRDY: LSI ready interrupt. - * @arg RCC_IT_LSERDY: LSE ready interrupt. - * @arg RCC_IT_HSIRDY: HSI ready interrupt. - * @arg RCC_IT_HSERDY: HSE ready interrupt. - * @arg RCC_IT_PLLRDY: Main PLL ready interrupt. - * @arg RCC_IT_PLLI2SRDY: PLLI2S ready interrupt. - * @arg RCC_IT_CSS: Clock Security System interrupt - */ -#define __HAL_RCC_CLEAR_IT(__INTERRUPT__) (*(__IO uint8_t *) RCC_CIR_BYTE2_ADDRESS = (__INTERRUPT__)) - -/** @brief Check the RCC's interrupt has occurred or not. - * @param __INTERRUPT__ specifies the RCC interrupt source to check. - * This parameter can be one of the following values: - * @arg RCC_IT_LSIRDY: LSI ready interrupt. - * @arg RCC_IT_LSERDY: LSE ready interrupt. - * @arg RCC_IT_HSIRDY: HSI ready interrupt. - * @arg RCC_IT_HSERDY: HSE ready interrupt. - * @arg RCC_IT_PLLRDY: Main PLL ready interrupt. - * @arg RCC_IT_PLLI2SRDY: PLLI2S ready interrupt. - * @arg RCC_IT_CSS: Clock Security System interrupt - * @retval The new state of __INTERRUPT__ (TRUE or FALSE). - */ -#define __HAL_RCC_GET_IT(__INTERRUPT__) ((RCC->CIR & (__INTERRUPT__)) == (__INTERRUPT__)) - -/** @brief Set RMVF bit to clear the reset flags: RCC_FLAG_PINRST, RCC_FLAG_PORRST, - * RCC_FLAG_SFTRST, RCC_FLAG_IWDGRST, RCC_FLAG_WWDGRST and RCC_FLAG_LPWRRST. - */ -#define __HAL_RCC_CLEAR_RESET_FLAGS() (RCC->CSR |= RCC_CSR_RMVF) - -/** @brief Check RCC flag is set or not. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg RCC_FLAG_HSIRDY: HSI oscillator clock ready. - * @arg RCC_FLAG_HSERDY: HSE oscillator clock ready. - * @arg RCC_FLAG_PLLRDY: Main PLL clock ready. - * @arg RCC_FLAG_PLLI2SRDY: PLLI2S clock ready. - * @arg RCC_FLAG_LSERDY: LSE oscillator clock ready. - * @arg RCC_FLAG_LSIRDY: LSI oscillator clock ready. - * @arg RCC_FLAG_BORRST: POR/PDR or BOR reset. - * @arg RCC_FLAG_PINRST: Pin reset. - * @arg RCC_FLAG_PORRST: POR/PDR reset. - * @arg RCC_FLAG_SFTRST: Software reset. - * @arg RCC_FLAG_IWDGRST: Independent Watchdog reset. - * @arg RCC_FLAG_WWDGRST: Window Watchdog reset. - * @arg RCC_FLAG_LPWRRST: Low Power reset. - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define RCC_FLAG_MASK ((uint8_t)0x1FU) -#define __HAL_RCC_GET_FLAG(__FLAG__) (((((((__FLAG__) >> 5U) == 1U)? RCC->CR :((((__FLAG__) >> 5U) == 2U) ? RCC->BDCR :((((__FLAG__) >> 5U) == 3U)? RCC->CSR :RCC->CIR))) & (1U << ((__FLAG__) & RCC_FLAG_MASK)))!= 0U)? 1U : 0U) - -/** - * @} - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ - /** @addtogroup RCC_Exported_Functions - * @{ - */ - -/** @addtogroup RCC_Exported_Functions_Group1 - * @{ - */ -/* Initialization and de-initialization functions ******************************/ -HAL_StatusTypeDef HAL_RCC_DeInit(void); -HAL_StatusTypeDef HAL_RCC_OscConfig(RCC_OscInitTypeDef *RCC_OscInitStruct); -HAL_StatusTypeDef HAL_RCC_ClockConfig(RCC_ClkInitTypeDef *RCC_ClkInitStruct, uint32_t FLatency); -/** - * @} - */ - -/** @addtogroup RCC_Exported_Functions_Group2 - * @{ - */ -/* Peripheral Control functions ************************************************/ -void HAL_RCC_MCOConfig(uint32_t RCC_MCOx, uint32_t RCC_MCOSource, uint32_t RCC_MCODiv); -void HAL_RCC_EnableCSS(void); -void HAL_RCC_DisableCSS(void); -uint32_t HAL_RCC_GetSysClockFreq(void); -uint32_t HAL_RCC_GetHCLKFreq(void); -uint32_t HAL_RCC_GetPCLK1Freq(void); -uint32_t HAL_RCC_GetPCLK2Freq(void); -void HAL_RCC_GetOscConfig(RCC_OscInitTypeDef *RCC_OscInitStruct); -void HAL_RCC_GetClockConfig(RCC_ClkInitTypeDef *RCC_ClkInitStruct, uint32_t *pFLatency); - -/* CSS NMI IRQ handler */ -void HAL_RCC_NMI_IRQHandler(void); - -/* User Callbacks in non blocking mode (IT mode) */ -void HAL_RCC_CSSCallback(void); - -/** - * @} - */ - -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup RCC_Private_Constants RCC Private Constants - * @{ - */ - -/** @defgroup RCC_BitAddress_AliasRegion RCC BitAddress AliasRegion - * @brief RCC registers bit address in the alias region - * @{ - */ -#define RCC_OFFSET (RCC_BASE - PERIPH_BASE) -/* --- CR Register --- */ -/* Alias word address of HSION bit */ -#define RCC_CR_OFFSET (RCC_OFFSET + 0x00U) -#define RCC_HSION_BIT_NUMBER 0x00U -#define RCC_CR_HSION_BB (PERIPH_BB_BASE + (RCC_CR_OFFSET * 32U) + (RCC_HSION_BIT_NUMBER * 4U)) -/* Alias word address of CSSON bit */ -#define RCC_CSSON_BIT_NUMBER 0x13U -#define RCC_CR_CSSON_BB (PERIPH_BB_BASE + (RCC_CR_OFFSET * 32U) + (RCC_CSSON_BIT_NUMBER * 4U)) -/* Alias word address of PLLON bit */ -#define RCC_PLLON_BIT_NUMBER 0x18U -#define RCC_CR_PLLON_BB (PERIPH_BB_BASE + (RCC_CR_OFFSET * 32U) + (RCC_PLLON_BIT_NUMBER * 4U)) - -/* --- BDCR Register --- */ -/* Alias word address of RTCEN bit */ -#define RCC_BDCR_OFFSET (RCC_OFFSET + 0x70U) -#define RCC_RTCEN_BIT_NUMBER 0x0FU -#define RCC_BDCR_RTCEN_BB (PERIPH_BB_BASE + (RCC_BDCR_OFFSET * 32U) + (RCC_RTCEN_BIT_NUMBER * 4U)) -/* Alias word address of BDRST bit */ -#define RCC_BDRST_BIT_NUMBER 0x10U -#define RCC_BDCR_BDRST_BB (PERIPH_BB_BASE + (RCC_BDCR_OFFSET * 32U) + (RCC_BDRST_BIT_NUMBER * 4U)) - -/* --- CSR Register --- */ -/* Alias word address of LSION bit */ -#define RCC_CSR_OFFSET (RCC_OFFSET + 0x74U) -#define RCC_LSION_BIT_NUMBER 0x00U -#define RCC_CSR_LSION_BB (PERIPH_BB_BASE + (RCC_CSR_OFFSET * 32U) + (RCC_LSION_BIT_NUMBER * 4U)) - -/* CR register byte 3 (Bits[23:16]) base address */ -#define RCC_CR_BYTE2_ADDRESS 0x40023802U - -/* CIR register byte 2 (Bits[15:8]) base address */ -#define RCC_CIR_BYTE1_ADDRESS ((uint32_t)(RCC_BASE + 0x0CU + 0x01U)) - -/* CIR register byte 3 (Bits[23:16]) base address */ -#define RCC_CIR_BYTE2_ADDRESS ((uint32_t)(RCC_BASE + 0x0CU + 0x02U)) - -/* BDCR register base address */ -#define RCC_BDCR_BYTE0_ADDRESS (PERIPH_BASE + RCC_BDCR_OFFSET) - -#define RCC_DBP_TIMEOUT_VALUE 2U -#define RCC_LSE_TIMEOUT_VALUE LSE_STARTUP_TIMEOUT - -#define HSE_TIMEOUT_VALUE HSE_STARTUP_TIMEOUT -#define HSI_TIMEOUT_VALUE 2U /* 2 ms */ -#define LSI_TIMEOUT_VALUE 2U /* 2 ms */ -#define CLOCKSWITCH_TIMEOUT_VALUE 5000U /* 5 s */ - -/** - * @} - */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup RCC_Private_Macros RCC Private Macros - * @{ - */ - -/** @defgroup RCC_IS_RCC_Definitions RCC Private macros to check input parameters - * @{ - */ -#define IS_RCC_OSCILLATORTYPE(OSCILLATOR) ((OSCILLATOR) <= 15U) - -#define IS_RCC_HSE(HSE) (((HSE) == RCC_HSE_OFF) || ((HSE) == RCC_HSE_ON) || \ - ((HSE) == RCC_HSE_BYPASS)) - -#define IS_RCC_LSE(LSE) (((LSE) == RCC_LSE_OFF) || ((LSE) == RCC_LSE_ON) || \ - ((LSE) == RCC_LSE_BYPASS)) - -#define IS_RCC_HSI(HSI) (((HSI) == RCC_HSI_OFF) || ((HSI) == RCC_HSI_ON)) - -#define IS_RCC_LSI(LSI) (((LSI) == RCC_LSI_OFF) || ((LSI) == RCC_LSI_ON)) - -#define IS_RCC_PLL(PLL) (((PLL) == RCC_PLL_NONE) ||((PLL) == RCC_PLL_OFF) || ((PLL) == RCC_PLL_ON)) - -#define IS_RCC_PLLSOURCE(SOURCE) (((SOURCE) == RCC_PLLSOURCE_HSI) || \ - ((SOURCE) == RCC_PLLSOURCE_HSE)) - -#define IS_RCC_SYSCLKSOURCE(SOURCE) (((SOURCE) == RCC_SYSCLKSOURCE_HSI) || \ - ((SOURCE) == RCC_SYSCLKSOURCE_HSE) || \ - ((SOURCE) == RCC_SYSCLKSOURCE_PLLCLK) || \ - ((SOURCE) == RCC_SYSCLKSOURCE_PLLRCLK)) - -#define IS_RCC_RTCCLKSOURCE(__SOURCE__) (((__SOURCE__) == RCC_RTCCLKSOURCE_LSE) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_LSI) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV2) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV3) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV4) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV5) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV6) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV7) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV8) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV9) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV10) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV11) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV12) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV13) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV14) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV15) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV16) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV17) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV18) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV19) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV20) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV21) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV22) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV23) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV24) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV25) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV26) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV27) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV28) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV29) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV30) || \ - ((__SOURCE__) == RCC_RTCCLKSOURCE_HSE_DIV31)) - -#define IS_RCC_PLLM_VALUE(VALUE) ((VALUE) <= 63U) - -#define IS_RCC_PLLP_VALUE(VALUE) (((VALUE) == 2U) || ((VALUE) == 4U) || ((VALUE) == 6U) || ((VALUE) == 8U)) - -#define IS_RCC_PLLQ_VALUE(VALUE) ((2U <= (VALUE)) && ((VALUE) <= 15U)) - -#define IS_RCC_HCLK(HCLK) (((HCLK) == RCC_SYSCLK_DIV1) || ((HCLK) == RCC_SYSCLK_DIV2) || \ - ((HCLK) == RCC_SYSCLK_DIV4) || ((HCLK) == RCC_SYSCLK_DIV8) || \ - ((HCLK) == RCC_SYSCLK_DIV16) || ((HCLK) == RCC_SYSCLK_DIV64) || \ - ((HCLK) == RCC_SYSCLK_DIV128) || ((HCLK) == RCC_SYSCLK_DIV256) || \ - ((HCLK) == RCC_SYSCLK_DIV512)) - -#define IS_RCC_CLOCKTYPE(CLK) ((1U <= (CLK)) && ((CLK) <= 15U)) - -#define IS_RCC_PCLK(PCLK) (((PCLK) == RCC_HCLK_DIV1) || ((PCLK) == RCC_HCLK_DIV2) || \ - ((PCLK) == RCC_HCLK_DIV4) || ((PCLK) == RCC_HCLK_DIV8) || \ - ((PCLK) == RCC_HCLK_DIV16)) - -#define IS_RCC_MCO(MCOx) (((MCOx) == RCC_MCO1) || ((MCOx) == RCC_MCO2)) - -#define IS_RCC_MCO1SOURCE(SOURCE) (((SOURCE) == RCC_MCO1SOURCE_HSI) || ((SOURCE) == RCC_MCO1SOURCE_LSE) || \ - ((SOURCE) == RCC_MCO1SOURCE_HSE) || ((SOURCE) == RCC_MCO1SOURCE_PLLCLK)) - -#define IS_RCC_MCODIV(DIV) (((DIV) == RCC_MCODIV_1) || ((DIV) == RCC_MCODIV_2) || \ - ((DIV) == RCC_MCODIV_3) || ((DIV) == RCC_MCODIV_4) || \ - ((DIV) == RCC_MCODIV_5)) -#define IS_RCC_CALIBRATION_VALUE(VALUE) ((VALUE) <= 0x1FU) - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_RCC_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc_ex.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc_ex.h deleted file mode 100644 index df6a66a..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rcc_ex.h +++ /dev/null @@ -1,7114 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_rcc_ex.h - * @author MCD Application Team - * @brief Header file of RCC HAL Extension module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_RCC_EX_H -#define __STM32F4xx_HAL_RCC_EX_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup RCCEx - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup RCCEx_Exported_Types RCCEx Exported Types - * @{ - */ - -/** - * @brief RCC PLL configuration structure definition - */ -typedef struct -{ - uint32_t PLLState; /*!< The new state of the PLL. - This parameter can be a value of @ref RCC_PLL_Config */ - - uint32_t PLLSource; /*!< RCC_PLLSource: PLL entry clock source. - This parameter must be a value of @ref RCC_PLL_Clock_Source */ - - uint32_t PLLM; /*!< PLLM: Division factor for PLL VCO input clock. - This parameter must be a number between Min_Data = 0 and Max_Data = 63 */ - - uint32_t PLLN; /*!< PLLN: Multiplication factor for PLL VCO output clock. - This parameter must be a number between Min_Data = 50 and Max_Data = 432 - except for STM32F411xE devices where the Min_Data = 192 */ - - uint32_t PLLP; /*!< PLLP: Division factor for main system clock (SYSCLK). - This parameter must be a value of @ref RCC_PLLP_Clock_Divider */ - - uint32_t PLLQ; /*!< PLLQ: Division factor for OTG FS, SDIO and RNG clocks. - This parameter must be a number between Min_Data = 2 and Max_Data = 15 */ -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F446xx) || defined(STM32F469xx) ||\ - defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) ||\ - defined(STM32F413xx) || defined(STM32F423xx) - uint32_t PLLR; /*!< PLLR: PLL division factor for I2S, SAI, SYSTEM, SPDIFRX clocks. - This parameter is only available in STM32F410xx/STM32F446xx/STM32F469xx/STM32F479xx - and STM32F412Zx/STM32F412Vx/STM32F412Rx/STM32F412Cx/STM32F413xx/STM32F423xx devices. - This parameter must be a number between Min_Data = 2 and Max_Data = 7 */ -#endif /* STM32F410xx || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ -}RCC_PLLInitTypeDef; - -#if defined(STM32F446xx) -/** - * @brief PLLI2S Clock structure definition - */ -typedef struct -{ - uint32_t PLLI2SM; /*!< Specifies division factor for PLL VCO input clock. - This parameter must be a number between Min_Data = 2 and Max_Data = 63 */ - - uint32_t PLLI2SN; /*!< Specifies the multiplication factor for PLLI2S VCO output clock. - This parameter must be a number between Min_Data = 50 and Max_Data = 432 */ - - uint32_t PLLI2SP; /*!< Specifies division factor for SPDIFRX Clock. - This parameter must be a value of @ref RCCEx_PLLI2SP_Clock_Divider */ - - uint32_t PLLI2SQ; /*!< Specifies the division factor for SAI clock. - This parameter must be a number between Min_Data = 2 and Max_Data = 15. - This parameter will be used only when PLLI2S is selected as Clock Source SAI */ - - uint32_t PLLI2SR; /*!< Specifies the division factor for I2S clock. - This parameter must be a number between Min_Data = 2 and Max_Data = 7. - This parameter will be used only when PLLI2S is selected as Clock Source I2S */ -}RCC_PLLI2SInitTypeDef; - -/** - * @brief PLLSAI Clock structure definition - */ -typedef struct -{ - uint32_t PLLSAIM; /*!< Specifies division factor for PLL VCO input clock. - This parameter must be a number between Min_Data = 2 and Max_Data = 63 */ - - uint32_t PLLSAIN; /*!< Specifies the multiplication factor for PLLI2S VCO output clock. - This parameter must be a number between Min_Data = 50 and Max_Data = 432 */ - - uint32_t PLLSAIP; /*!< Specifies division factor for OTG FS, SDIO and RNG clocks. - This parameter must be a value of @ref RCCEx_PLLSAIP_Clock_Divider */ - - uint32_t PLLSAIQ; /*!< Specifies the division factor for SAI clock. - This parameter must be a number between Min_Data = 2 and Max_Data = 15. - This parameter will be used only when PLLSAI is selected as Clock Source SAI */ -}RCC_PLLSAIInitTypeDef; - -/** - * @brief RCC extended clocks structure definition - */ -typedef struct -{ - uint32_t PeriphClockSelection; /*!< The Extended Clock to be configured. - This parameter can be a value of @ref RCCEx_Periph_Clock_Selection */ - - RCC_PLLI2SInitTypeDef PLLI2S; /*!< PLL I2S structure parameters. - This parameter will be used only when PLLI2S is selected as Clock Source I2S or SAI */ - - RCC_PLLSAIInitTypeDef PLLSAI; /*!< PLL SAI structure parameters. - This parameter will be used only when PLLI2S is selected as Clock Source SAI or LTDC */ - - uint32_t PLLI2SDivQ; /*!< Specifies the PLLI2S division factor for SAI1 clock. - This parameter must be a number between Min_Data = 1 and Max_Data = 32 - This parameter will be used only when PLLI2S is selected as Clock Source SAI */ - - uint32_t PLLSAIDivQ; /*!< Specifies the PLLI2S division factor for SAI1 clock. - This parameter must be a number between Min_Data = 1 and Max_Data = 32 - This parameter will be used only when PLLSAI is selected as Clock Source SAI */ - - uint32_t Sai1ClockSelection; /*!< Specifies SAI1 Clock Source Selection. - This parameter can be a value of @ref RCCEx_SAI1_Clock_Source */ - - uint32_t Sai2ClockSelection; /*!< Specifies SAI2 Clock Source Selection. - This parameter can be a value of @ref RCCEx_SAI2_Clock_Source */ - - uint32_t I2sApb1ClockSelection; /*!< Specifies I2S APB1 Clock Source Selection. - This parameter can be a value of @ref RCCEx_I2SAPB1_Clock_Source */ - - uint32_t I2sApb2ClockSelection; /*!< Specifies I2S APB2 Clock Source Selection. - This parameter can be a value of @ref RCCEx_I2SAPB2_Clock_Source */ - - uint32_t RTCClockSelection; /*!< Specifies RTC Clock Source Selection. - This parameter can be a value of @ref RCC_RTC_Clock_Source */ - - uint32_t SdioClockSelection; /*!< Specifies SDIO Clock Source Selection. - This parameter can be a value of @ref RCCEx_SDIO_Clock_Source */ - - uint32_t CecClockSelection; /*!< Specifies CEC Clock Source Selection. - This parameter can be a value of @ref RCCEx_CEC_Clock_Source */ - - uint32_t Fmpi2c1ClockSelection; /*!< Specifies FMPI2C1 Clock Source Selection. - This parameter can be a value of @ref RCCEx_FMPI2C1_Clock_Source */ - - uint32_t SpdifClockSelection; /*!< Specifies SPDIFRX Clock Source Selection. - This parameter can be a value of @ref RCCEx_SPDIFRX_Clock_Source */ - - uint32_t Clk48ClockSelection; /*!< Specifies CLK48 Clock Selection this clock used OTG FS, SDIO and RNG clocks. - This parameter can be a value of @ref RCCEx_CLK48_Clock_Source */ - - uint8_t TIMPresSelection; /*!< Specifies TIM Clock Source Selection. - This parameter can be a value of @ref RCCEx_TIM_PRescaler_Selection */ -}RCC_PeriphCLKInitTypeDef; -#endif /* STM32F446xx */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -/** - * @brief RCC extended clocks structure definition - */ -typedef struct -{ - uint32_t PeriphClockSelection; /*!< The Extended Clock to be configured. - This parameter can be a value of @ref RCCEx_Periph_Clock_Selection */ - - uint32_t I2SClockSelection; /*!< Specifies RTC Clock Source Selection. - This parameter can be a value of @ref RCCEx_I2S_APB_Clock_Source */ - - uint32_t RTCClockSelection; /*!< Specifies RTC Clock Source Selection. - This parameter can be a value of @ref RCC_RTC_Clock_Source */ - - uint32_t Lptim1ClockSelection; /*!< Specifies LPTIM1 Clock Source Selection. - This parameter can be a value of @ref RCCEx_LPTIM1_Clock_Source */ - - uint32_t Fmpi2c1ClockSelection; /*!< Specifies FMPI2C1 Clock Source Selection. - This parameter can be a value of @ref RCCEx_FMPI2C1_Clock_Source */ - - uint8_t TIMPresSelection; /*!< Specifies TIM Clock Source Selection. - This parameter can be a value of @ref RCCEx_TIM_PRescaler_Selection */ -}RCC_PeriphCLKInitTypeDef; -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/** - * @brief PLLI2S Clock structure definition - */ -typedef struct -{ - uint32_t PLLI2SM; /*!< Specifies division factor for PLL VCO input clock. - This parameter must be a number between Min_Data = 2 and Max_Data = 63 */ - - uint32_t PLLI2SN; /*!< Specifies the multiplication factor for PLLI2S VCO output clock. - This parameter must be a number between Min_Data = 50 and Max_Data = 432 */ - - uint32_t PLLI2SQ; /*!< Specifies the division factor for SAI clock. - This parameter must be a number between Min_Data = 2 and Max_Data = 15. - This parameter will be used only when PLLI2S is selected as Clock Source SAI */ - - uint32_t PLLI2SR; /*!< Specifies the division factor for I2S clock. - This parameter must be a number between Min_Data = 2 and Max_Data = 7. - This parameter will be used only when PLLI2S is selected as Clock Source I2S */ -}RCC_PLLI2SInitTypeDef; - -/** - * @brief RCC extended clocks structure definition - */ -typedef struct -{ - uint32_t PeriphClockSelection; /*!< The Extended Clock to be configured. - This parameter can be a value of @ref RCCEx_Periph_Clock_Selection */ - - RCC_PLLI2SInitTypeDef PLLI2S; /*!< PLL I2S structure parameters. - This parameter will be used only when PLLI2S is selected as Clock Source I2S */ - -#if defined(STM32F413xx) || defined(STM32F423xx) - uint32_t PLLDivR; /*!< Specifies the PLL division factor for SAI1 clock. - This parameter must be a number between Min_Data = 1 and Max_Data = 32 - This parameter will be used only when PLL is selected as Clock Source SAI */ - - uint32_t PLLI2SDivR; /*!< Specifies the PLLI2S division factor for SAI1 clock. - This parameter must be a number between Min_Data = 1 and Max_Data = 32 - This parameter will be used only when PLLI2S is selected as Clock Source SAI */ -#endif /* STM32F413xx || STM32F423xx */ - - uint32_t I2sApb1ClockSelection; /*!< Specifies I2S APB1 Clock Source Selection. - This parameter can be a value of @ref RCCEx_I2SAPB1_Clock_Source */ - - uint32_t I2sApb2ClockSelection; /*!< Specifies I2S APB2 Clock Source Selection. - This parameter can be a value of @ref RCCEx_I2SAPB2_Clock_Source */ - - uint32_t RTCClockSelection; /*!< Specifies RTC Clock Source Selection. - This parameter can be a value of @ref RCC_RTC_Clock_Source */ - - uint32_t SdioClockSelection; /*!< Specifies SDIO Clock Source Selection. - This parameter can be a value of @ref RCCEx_SDIO_Clock_Source */ - - uint32_t Fmpi2c1ClockSelection; /*!< Specifies FMPI2C1 Clock Source Selection. - This parameter can be a value of @ref RCCEx_FMPI2C1_Clock_Source */ - - uint32_t Clk48ClockSelection; /*!< Specifies CLK48 Clock Selection this clock used OTG FS, SDIO and RNG clocks. - This parameter can be a value of @ref RCCEx_CLK48_Clock_Source */ - - uint32_t Dfsdm1ClockSelection; /*!< Specifies DFSDM1 Clock Selection. - This parameter can be a value of @ref RCCEx_DFSDM1_Kernel_Clock_Source */ - - uint32_t Dfsdm1AudioClockSelection;/*!< Specifies DFSDM1 Audio Clock Selection. - This parameter can be a value of @ref RCCEx_DFSDM1_Audio_Clock_Source */ - -#if defined(STM32F413xx) || defined(STM32F423xx) - uint32_t Dfsdm2ClockSelection; /*!< Specifies DFSDM2 Clock Selection. - This parameter can be a value of @ref RCCEx_DFSDM2_Kernel_Clock_Source */ - - uint32_t Dfsdm2AudioClockSelection;/*!< Specifies DFSDM2 Audio Clock Selection. - This parameter can be a value of @ref RCCEx_DFSDM2_Audio_Clock_Source */ - - uint32_t Lptim1ClockSelection; /*!< Specifies LPTIM1 Clock Source Selection. - This parameter can be a value of @ref RCCEx_LPTIM1_Clock_Source */ - - uint32_t SaiAClockSelection; /*!< Specifies SAI1_A Clock Prescalers Selection - This parameter can be a value of @ref RCCEx_SAI1_BlockA_Clock_Source */ - - uint32_t SaiBClockSelection; /*!< Specifies SAI1_B Clock Prescalers Selection - This parameter can be a value of @ref RCCEx_SAI1_BlockB_Clock_Source */ -#endif /* STM32F413xx || STM32F423xx */ - - uint32_t PLLI2SSelection; /*!< Specifies PLL I2S Clock Source Selection. - This parameter can be a value of @ref RCCEx_PLL_I2S_Clock_Source */ - - uint8_t TIMPresSelection; /*!< Specifies TIM Clock Source Selection. - This parameter can be a value of @ref RCCEx_TIM_PRescaler_Selection */ -}RCC_PeriphCLKInitTypeDef; -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) - -/** - * @brief PLLI2S Clock structure definition - */ -typedef struct -{ - uint32_t PLLI2SN; /*!< Specifies the multiplication factor for PLLI2S VCO output clock. - This parameter must be a number between Min_Data = 50 and Max_Data = 432. - This parameter will be used only when PLLI2S is selected as Clock Source I2S or SAI */ - - uint32_t PLLI2SR; /*!< Specifies the division factor for I2S clock. - This parameter must be a number between Min_Data = 2 and Max_Data = 7. - This parameter will be used only when PLLI2S is selected as Clock Source I2S or SAI */ - - uint32_t PLLI2SQ; /*!< Specifies the division factor for SAI1 clock. - This parameter must be a number between Min_Data = 2 and Max_Data = 15. - This parameter will be used only when PLLI2S is selected as Clock Source SAI */ -}RCC_PLLI2SInitTypeDef; - -/** - * @brief PLLSAI Clock structure definition - */ -typedef struct -{ - uint32_t PLLSAIN; /*!< Specifies the multiplication factor for PLLI2S VCO output clock. - This parameter must be a number between Min_Data = 50 and Max_Data = 432. - This parameter will be used only when PLLSAI is selected as Clock Source SAI or LTDC */ -#if defined(STM32F469xx) || defined(STM32F479xx) - uint32_t PLLSAIP; /*!< Specifies division factor for OTG FS and SDIO clocks. - This parameter is only available in STM32F469xx/STM32F479xx devices. - This parameter must be a value of @ref RCCEx_PLLSAIP_Clock_Divider */ -#endif /* STM32F469xx || STM32F479xx */ - - uint32_t PLLSAIQ; /*!< Specifies the division factor for SAI1 clock. - This parameter must be a number between Min_Data = 2 and Max_Data = 15. - This parameter will be used only when PLLSAI is selected as Clock Source SAI or LTDC */ - - uint32_t PLLSAIR; /*!< specifies the division factor for LTDC clock - This parameter must be a number between Min_Data = 2 and Max_Data = 7. - This parameter will be used only when PLLSAI is selected as Clock Source LTDC */ - -}RCC_PLLSAIInitTypeDef; - -/** - * @brief RCC extended clocks structure definition - */ -typedef struct -{ - uint32_t PeriphClockSelection; /*!< The Extended Clock to be configured. - This parameter can be a value of @ref RCCEx_Periph_Clock_Selection */ - - RCC_PLLI2SInitTypeDef PLLI2S; /*!< PLL I2S structure parameters. - This parameter will be used only when PLLI2S is selected as Clock Source I2S or SAI */ - - RCC_PLLSAIInitTypeDef PLLSAI; /*!< PLL SAI structure parameters. - This parameter will be used only when PLLI2S is selected as Clock Source SAI or LTDC */ - - uint32_t PLLI2SDivQ; /*!< Specifies the PLLI2S division factor for SAI1 clock. - This parameter must be a number between Min_Data = 1 and Max_Data = 32 - This parameter will be used only when PLLI2S is selected as Clock Source SAI */ - - uint32_t PLLSAIDivQ; /*!< Specifies the PLLI2S division factor for SAI1 clock. - This parameter must be a number between Min_Data = 1 and Max_Data = 32 - This parameter will be used only when PLLSAI is selected as Clock Source SAI */ - - uint32_t PLLSAIDivR; /*!< Specifies the PLLSAI division factor for LTDC clock. - This parameter must be one value of @ref RCCEx_PLLSAI_DIVR */ - - uint32_t RTCClockSelection; /*!< Specifies RTC Clock Prescalers Selection. - This parameter can be a value of @ref RCC_RTC_Clock_Source */ - - uint8_t TIMPresSelection; /*!< Specifies TIM Clock Prescalers Selection. - This parameter can be a value of @ref RCCEx_TIM_PRescaler_Selection */ -#if defined(STM32F469xx) || defined(STM32F479xx) - uint32_t Clk48ClockSelection; /*!< Specifies CLK48 Clock Selection this clock used OTG FS, SDIO and RNG clocks. - This parameter can be a value of @ref RCCEx_CLK48_Clock_Source */ - - uint32_t SdioClockSelection; /*!< Specifies SDIO Clock Source Selection. - This parameter can be a value of @ref RCCEx_SDIO_Clock_Source */ -#endif /* STM32F469xx || STM32F479xx */ -}RCC_PeriphCLKInitTypeDef; - -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) ||\ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) -/** - * @brief PLLI2S Clock structure definition - */ -typedef struct -{ -#if defined(STM32F411xE) - uint32_t PLLI2SM; /*!< PLLM: Division factor for PLLI2S VCO input clock. - This parameter must be a number between Min_Data = 2 and Max_Data = 62 */ -#endif /* STM32F411xE */ - - uint32_t PLLI2SN; /*!< Specifies the multiplication factor for PLLI2S VCO output clock. - This parameter must be a number between Min_Data = 50 and Max_Data = 432 - Except for STM32F411xE devices where the Min_Data = 192. - This parameter will be used only when PLLI2S is selected as Clock Source I2S or SAI */ - - uint32_t PLLI2SR; /*!< Specifies the division factor for I2S clock. - This parameter must be a number between Min_Data = 2 and Max_Data = 7. - This parameter will be used only when PLLI2S is selected as Clock Source I2S or SAI */ - -}RCC_PLLI2SInitTypeDef; - -/** - * @brief RCC extended clocks structure definition - */ -typedef struct -{ - uint32_t PeriphClockSelection; /*!< The Extended Clock to be configured. - This parameter can be a value of @ref RCCEx_Periph_Clock_Selection */ - - RCC_PLLI2SInitTypeDef PLLI2S; /*!< PLL I2S structure parameters. - This parameter will be used only when PLLI2S is selected as Clock Source I2S or SAI */ - - uint32_t RTCClockSelection; /*!< Specifies RTC Clock Prescalers Selection. - This parameter can be a value of @ref RCC_RTC_Clock_Source */ -#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) - uint8_t TIMPresSelection; /*!< Specifies TIM Clock Source Selection. - This parameter can be a value of @ref RCCEx_TIM_PRescaler_Selection */ -#endif /* STM32F401xC || STM32F401xE || STM32F411xE */ -}RCC_PeriphCLKInitTypeDef; -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F401xC || STM32F401xE || STM32F411xE */ -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup RCCEx_Exported_Constants RCCEx Exported Constants - * @{ - */ - -/** @defgroup RCCEx_Periph_Clock_Selection RCC Periph Clock Selection - * @{ - */ -/* Peripheral Clock source for STM32F412Zx/STM32F412Vx/STM32F412Rx/STM32F412Cx */ -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) ||\ - defined(STM32F413xx) || defined(STM32F423xx) -#define RCC_PERIPHCLK_I2S_APB1 0x00000001U -#define RCC_PERIPHCLK_I2S_APB2 0x00000002U -#define RCC_PERIPHCLK_TIM 0x00000004U -#define RCC_PERIPHCLK_RTC 0x00000008U -#define RCC_PERIPHCLK_FMPI2C1 0x00000010U -#define RCC_PERIPHCLK_CLK48 0x00000020U -#define RCC_PERIPHCLK_SDIO 0x00000040U -#define RCC_PERIPHCLK_PLLI2S 0x00000080U -#define RCC_PERIPHCLK_DFSDM1 0x00000100U -#define RCC_PERIPHCLK_DFSDM1_AUDIO 0x00000200U -#endif /* STM32F412Zx || STM32F412Vx) || STM32F412Rx || STM32F412Cx */ -#if defined(STM32F413xx) || defined(STM32F423xx) -#define RCC_PERIPHCLK_DFSDM2 0x00000400U -#define RCC_PERIPHCLK_DFSDM2_AUDIO 0x00000800U -#define RCC_PERIPHCLK_LPTIM1 0x00001000U -#define RCC_PERIPHCLK_SAIA 0x00002000U -#define RCC_PERIPHCLK_SAIB 0x00004000U -#endif /* STM32F413xx || STM32F423xx */ -/*----------------------------------------------------------------------------*/ - -/*------------------- Peripheral Clock source for STM32F410xx ----------------*/ -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -#define RCC_PERIPHCLK_I2S 0x00000001U -#define RCC_PERIPHCLK_TIM 0x00000002U -#define RCC_PERIPHCLK_RTC 0x00000004U -#define RCC_PERIPHCLK_FMPI2C1 0x00000008U -#define RCC_PERIPHCLK_LPTIM1 0x00000010U -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ -/*----------------------------------------------------------------------------*/ - -/*------------------- Peripheral Clock source for STM32F446xx ----------------*/ -#if defined(STM32F446xx) -#define RCC_PERIPHCLK_I2S_APB1 0x00000001U -#define RCC_PERIPHCLK_I2S_APB2 0x00000002U -#define RCC_PERIPHCLK_SAI1 0x00000004U -#define RCC_PERIPHCLK_SAI2 0x00000008U -#define RCC_PERIPHCLK_TIM 0x00000010U -#define RCC_PERIPHCLK_RTC 0x00000020U -#define RCC_PERIPHCLK_CEC 0x00000040U -#define RCC_PERIPHCLK_FMPI2C1 0x00000080U -#define RCC_PERIPHCLK_CLK48 0x00000100U -#define RCC_PERIPHCLK_SDIO 0x00000200U -#define RCC_PERIPHCLK_SPDIFRX 0x00000400U -#define RCC_PERIPHCLK_PLLI2S 0x00000800U -#endif /* STM32F446xx */ -/*-----------------------------------------------------------------------------*/ - -/*----------- Peripheral Clock source for STM32F469xx/STM32F479xx -------------*/ -#if defined(STM32F469xx) || defined(STM32F479xx) -#define RCC_PERIPHCLK_I2S 0x00000001U -#define RCC_PERIPHCLK_SAI_PLLI2S 0x00000002U -#define RCC_PERIPHCLK_SAI_PLLSAI 0x00000004U -#define RCC_PERIPHCLK_LTDC 0x00000008U -#define RCC_PERIPHCLK_TIM 0x00000010U -#define RCC_PERIPHCLK_RTC 0x00000020U -#define RCC_PERIPHCLK_PLLI2S 0x00000040U -#define RCC_PERIPHCLK_CLK48 0x00000080U -#define RCC_PERIPHCLK_SDIO 0x00000100U -#endif /* STM32F469xx || STM32F479xx */ -/*----------------------------------------------------------------------------*/ - -/*-------- Peripheral Clock source for STM32F42xxx/STM32F43xxx ---------------*/ -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) -#define RCC_PERIPHCLK_I2S 0x00000001U -#define RCC_PERIPHCLK_SAI_PLLI2S 0x00000002U -#define RCC_PERIPHCLK_SAI_PLLSAI 0x00000004U -#define RCC_PERIPHCLK_LTDC 0x00000008U -#define RCC_PERIPHCLK_TIM 0x00000010U -#define RCC_PERIPHCLK_RTC 0x00000020U -#define RCC_PERIPHCLK_PLLI2S 0x00000040U -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx */ -/*----------------------------------------------------------------------------*/ - -/*-------- Peripheral Clock source for STM32F40xxx/STM32F41xxx ---------------*/ -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx)|| defined(STM32F417xx) ||\ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) -#define RCC_PERIPHCLK_I2S 0x00000001U -#define RCC_PERIPHCLK_RTC 0x00000002U -#define RCC_PERIPHCLK_PLLI2S 0x00000004U -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F401xC || STM32F401xE || STM32F411xE */ -#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) -#define RCC_PERIPHCLK_TIM 0x00000008U -#endif /* STM32F401xC || STM32F401xE || STM32F411xE */ -/*----------------------------------------------------------------------------*/ -/** - * @} - */ -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || \ - defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || \ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F469xx) || \ - defined(STM32F479xx) -/** @defgroup RCCEx_I2S_Clock_Source I2S Clock Source - * @{ - */ -#define RCC_I2SCLKSOURCE_PLLI2S 0x00000000U -#define RCC_I2SCLKSOURCE_EXT 0x00000001U -/** - * @} - */ -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || - STM32F401xC || STM32F401xE || STM32F411xE || STM32F469xx || STM32F479xx */ - -/** @defgroup RCCEx_PLLSAI_DIVR RCC PLLSAI DIVR - * @{ - */ -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F446xx) ||\ - defined(STM32F469xx) || defined(STM32F479xx) -#define RCC_PLLSAIDIVR_2 0x00000000U -#define RCC_PLLSAIDIVR_4 0x00010000U -#define RCC_PLLSAIDIVR_8 0x00020000U -#define RCC_PLLSAIDIVR_16 0x00030000U -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ -/** - * @} - */ - -/** @defgroup RCCEx_PLLI2SP_Clock_Divider RCC PLLI2SP Clock Divider - * @{ - */ -#if defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || \ - defined(STM32F412Rx) || defined(STM32F412Cx) -#define RCC_PLLI2SP_DIV2 0x00000002U -#define RCC_PLLI2SP_DIV4 0x00000004U -#define RCC_PLLI2SP_DIV6 0x00000006U -#define RCC_PLLI2SP_DIV8 0x00000008U -#endif /* STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ -/** - * @} - */ - -/** @defgroup RCCEx_PLLSAIP_Clock_Divider RCC PLLSAIP Clock Divider - * @{ - */ -#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -#define RCC_PLLSAIP_DIV2 0x00000002U -#define RCC_PLLSAIP_DIV4 0x00000004U -#define RCC_PLLSAIP_DIV6 0x00000006U -#define RCC_PLLSAIP_DIV8 0x00000008U -#endif /* STM32F446xx || STM32F469xx || STM32F479xx */ -/** - * @} - */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) -/** @defgroup RCCEx_SAI_BlockA_Clock_Source RCC SAI BlockA Clock Source - * @{ - */ -#define RCC_SAIACLKSOURCE_PLLSAI 0x00000000U -#define RCC_SAIACLKSOURCE_PLLI2S 0x00100000U -#define RCC_SAIACLKSOURCE_EXT 0x00200000U -/** - * @} - */ - -/** @defgroup RCCEx_SAI_BlockB_Clock_Source RCC SAI BlockB Clock Source - * @{ - */ -#define RCC_SAIBCLKSOURCE_PLLSAI 0x00000000U -#define RCC_SAIBCLKSOURCE_PLLI2S 0x00400000U -#define RCC_SAIBCLKSOURCE_EXT 0x00800000U -/** - * @} - */ -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F469xx) || defined(STM32F479xx) -/** @defgroup RCCEx_CLK48_Clock_Source RCC CLK48 Clock Source - * @{ - */ -#define RCC_CLK48CLKSOURCE_PLLQ 0x00000000U -#define RCC_CLK48CLKSOURCE_PLLSAIP ((uint32_t)RCC_DCKCFGR_CK48MSEL) -/** - * @} - */ - -/** @defgroup RCCEx_SDIO_Clock_Source RCC SDIO Clock Source - * @{ - */ -#define RCC_SDIOCLKSOURCE_CLK48 0x00000000U -#define RCC_SDIOCLKSOURCE_SYSCLK ((uint32_t)RCC_DCKCFGR_SDIOSEL) -/** - * @} - */ - -/** @defgroup RCCEx_DSI_Clock_Source RCC DSI Clock Source - * @{ - */ -#define RCC_DSICLKSOURCE_DSIPHY 0x00000000U -#define RCC_DSICLKSOURCE_PLLR ((uint32_t)RCC_DCKCFGR_DSISEL) -/** - * @} - */ -#endif /* STM32F469xx || STM32F479xx */ - -#if defined(STM32F446xx) -/** @defgroup RCCEx_SAI1_Clock_Source RCC SAI1 Clock Source - * @{ - */ -#define RCC_SAI1CLKSOURCE_PLLSAI 0x00000000U -#define RCC_SAI1CLKSOURCE_PLLI2S ((uint32_t)RCC_DCKCFGR_SAI1SRC_0) -#define RCC_SAI1CLKSOURCE_PLLR ((uint32_t)RCC_DCKCFGR_SAI1SRC_1) -#define RCC_SAI1CLKSOURCE_EXT ((uint32_t)RCC_DCKCFGR_SAI1SRC) -/** - * @} - */ - -/** @defgroup RCCEx_SAI2_Clock_Source RCC SAI2 Clock Source - * @{ - */ -#define RCC_SAI2CLKSOURCE_PLLSAI 0x00000000U -#define RCC_SAI2CLKSOURCE_PLLI2S ((uint32_t)RCC_DCKCFGR_SAI2SRC_0) -#define RCC_SAI2CLKSOURCE_PLLR ((uint32_t)RCC_DCKCFGR_SAI2SRC_1) -#define RCC_SAI2CLKSOURCE_PLLSRC ((uint32_t)RCC_DCKCFGR_SAI2SRC) -/** - * @} - */ - -/** @defgroup RCCEx_I2SAPB1_Clock_Source RCC I2S APB1 Clock Source - * @{ - */ -#define RCC_I2SAPB1CLKSOURCE_PLLI2S 0x00000000U -#define RCC_I2SAPB1CLKSOURCE_EXT ((uint32_t)RCC_DCKCFGR_I2S1SRC_0) -#define RCC_I2SAPB1CLKSOURCE_PLLR ((uint32_t)RCC_DCKCFGR_I2S1SRC_1) -#define RCC_I2SAPB1CLKSOURCE_PLLSRC ((uint32_t)RCC_DCKCFGR_I2S1SRC) -/** - * @} - */ - -/** @defgroup RCCEx_I2SAPB2_Clock_Source RCC I2S APB2 Clock Source - * @{ - */ -#define RCC_I2SAPB2CLKSOURCE_PLLI2S 0x00000000U -#define RCC_I2SAPB2CLKSOURCE_EXT ((uint32_t)RCC_DCKCFGR_I2S2SRC_0) -#define RCC_I2SAPB2CLKSOURCE_PLLR ((uint32_t)RCC_DCKCFGR_I2S2SRC_1) -#define RCC_I2SAPB2CLKSOURCE_PLLSRC ((uint32_t)RCC_DCKCFGR_I2S2SRC) -/** - * @} - */ - -/** @defgroup RCCEx_FMPI2C1_Clock_Source RCC FMPI2C1 Clock Source - * @{ - */ -#define RCC_FMPI2C1CLKSOURCE_PCLK1 0x00000000U -#define RCC_FMPI2C1CLKSOURCE_SYSCLK ((uint32_t)RCC_DCKCFGR2_FMPI2C1SEL_0) -#define RCC_FMPI2C1CLKSOURCE_HSI ((uint32_t)RCC_DCKCFGR2_FMPI2C1SEL_1) -/** - * @} - */ - -/** @defgroup RCCEx_CEC_Clock_Source RCC CEC Clock Source - * @{ - */ -#define RCC_CECCLKSOURCE_HSI 0x00000000U -#define RCC_CECCLKSOURCE_LSE ((uint32_t)RCC_DCKCFGR2_CECSEL) -/** - * @} - */ - -/** @defgroup RCCEx_CLK48_Clock_Source RCC CLK48 Clock Source - * @{ - */ -#define RCC_CLK48CLKSOURCE_PLLQ 0x00000000U -#define RCC_CLK48CLKSOURCE_PLLSAIP ((uint32_t)RCC_DCKCFGR2_CK48MSEL) -/** - * @} - */ - -/** @defgroup RCCEx_SDIO_Clock_Source RCC SDIO Clock Source - * @{ - */ -#define RCC_SDIOCLKSOURCE_CLK48 0x00000000U -#define RCC_SDIOCLKSOURCE_SYSCLK ((uint32_t)RCC_DCKCFGR2_SDIOSEL) -/** - * @} - */ - -/** @defgroup RCCEx_SPDIFRX_Clock_Source RCC SPDIFRX Clock Source - * @{ - */ -#define RCC_SPDIFRXCLKSOURCE_PLLR 0x00000000U -#define RCC_SPDIFRXCLKSOURCE_PLLI2SP ((uint32_t)RCC_DCKCFGR2_SPDIFRXSEL) -/** - * @} - */ - -#endif /* STM32F446xx */ - -#if defined(STM32F413xx) || defined(STM32F423xx) -/** @defgroup RCCEx_SAI1_BlockA_Clock_Source RCC SAI BlockA Clock Source - * @{ - */ -#define RCC_SAIACLKSOURCE_PLLI2SR 0x00000000U -#define RCC_SAIACLKSOURCE_EXT ((uint32_t)RCC_DCKCFGR_SAI1ASRC_0) -#define RCC_SAIACLKSOURCE_PLLR ((uint32_t)RCC_DCKCFGR_SAI1ASRC_1) -#define RCC_SAIACLKSOURCE_PLLSRC ((uint32_t)RCC_DCKCFGR_SAI1ASRC_0 | RCC_DCKCFGR_SAI1ASRC_1) -/** - * @} - */ - -/** @defgroup RCCEx_SAI1_BlockB_Clock_Source RCC SAI BlockB Clock Source - * @{ - */ -#define RCC_SAIBCLKSOURCE_PLLI2SR 0x00000000U -#define RCC_SAIBCLKSOURCE_EXT ((uint32_t)RCC_DCKCFGR_SAI1BSRC_0) -#define RCC_SAIBCLKSOURCE_PLLR ((uint32_t)RCC_DCKCFGR_SAI1BSRC_1) -#define RCC_SAIBCLKSOURCE_PLLSRC ((uint32_t)RCC_DCKCFGR_SAI1BSRC_0 | RCC_DCKCFGR_SAI1BSRC_1) -/** - * @} - */ - -/** @defgroup RCCEx_LPTIM1_Clock_Source RCC LPTIM1 Clock Source - * @{ - */ -#define RCC_LPTIM1CLKSOURCE_PCLK1 0x00000000U -#define RCC_LPTIM1CLKSOURCE_HSI ((uint32_t)RCC_DCKCFGR2_LPTIM1SEL_0) -#define RCC_LPTIM1CLKSOURCE_LSI ((uint32_t)RCC_DCKCFGR2_LPTIM1SEL_1) -#define RCC_LPTIM1CLKSOURCE_LSE ((uint32_t)RCC_DCKCFGR2_LPTIM1SEL_0 | RCC_DCKCFGR2_LPTIM1SEL_1) -/** - * @} - */ - - -/** @defgroup RCCEx_DFSDM2_Audio_Clock_Source RCC DFSDM2 Audio Clock Source - * @{ - */ -#define RCC_DFSDM2AUDIOCLKSOURCE_I2S1 0x00000000U -#define RCC_DFSDM2AUDIOCLKSOURCE_I2S2 ((uint32_t)RCC_DCKCFGR_CKDFSDM2ASEL) -/** - * @} - */ - -/** @defgroup RCCEx_DFSDM2_Kernel_Clock_Source RCC DFSDM2 Kernel Clock Source - * @{ - */ -#define RCC_DFSDM2CLKSOURCE_PCLK2 0x00000000U -#define RCC_DFSDM2CLKSOURCE_SYSCLK ((uint32_t)RCC_DCKCFGR_CKDFSDM1SEL) -/** - * @} - */ - -#endif /* STM32F413xx || STM32F423xx */ - -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/** @defgroup RCCEx_PLL_I2S_Clock_Source PLL I2S Clock Source - * @{ - */ -#define RCC_PLLI2SCLKSOURCE_PLLSRC 0x00000000U -#define RCC_PLLI2SCLKSOURCE_EXT ((uint32_t)RCC_PLLI2SCFGR_PLLI2SSRC) -/** - * @} - */ - -/** @defgroup RCCEx_DFSDM1_Audio_Clock_Source RCC DFSDM1 Audio Clock Source - * @{ - */ -#define RCC_DFSDM1AUDIOCLKSOURCE_I2S1 0x00000000U -#define RCC_DFSDM1AUDIOCLKSOURCE_I2S2 ((uint32_t)RCC_DCKCFGR_CKDFSDM1ASEL) -/** - * @} - */ - -/** @defgroup RCCEx_DFSDM1_Kernel_Clock_Source RCC DFSDM1 Kernel Clock Source - * @{ - */ -#define RCC_DFSDM1CLKSOURCE_PCLK2 0x00000000U -#define RCC_DFSDM1CLKSOURCE_SYSCLK ((uint32_t)RCC_DCKCFGR_CKDFSDM1SEL) -/** - * @} - */ - -/** @defgroup RCCEx_I2SAPB1_Clock_Source RCC I2S APB1 Clock Source - * @{ - */ -#define RCC_I2SAPB1CLKSOURCE_PLLI2S 0x00000000U -#define RCC_I2SAPB1CLKSOURCE_EXT ((uint32_t)RCC_DCKCFGR_I2S1SRC_0) -#define RCC_I2SAPB1CLKSOURCE_PLLR ((uint32_t)RCC_DCKCFGR_I2S1SRC_1) -#define RCC_I2SAPB1CLKSOURCE_PLLSRC ((uint32_t)RCC_DCKCFGR_I2S1SRC) -/** - * @} - */ - -/** @defgroup RCCEx_I2SAPB2_Clock_Source RCC I2S APB2 Clock Source - * @{ - */ -#define RCC_I2SAPB2CLKSOURCE_PLLI2S 0x00000000U -#define RCC_I2SAPB2CLKSOURCE_EXT ((uint32_t)RCC_DCKCFGR_I2S2SRC_0) -#define RCC_I2SAPB2CLKSOURCE_PLLR ((uint32_t)RCC_DCKCFGR_I2S2SRC_1) -#define RCC_I2SAPB2CLKSOURCE_PLLSRC ((uint32_t)RCC_DCKCFGR_I2S2SRC) -/** - * @} - */ - -/** @defgroup RCCEx_FMPI2C1_Clock_Source RCC FMPI2C1 Clock Source - * @{ - */ -#define RCC_FMPI2C1CLKSOURCE_PCLK1 0x00000000U -#define RCC_FMPI2C1CLKSOURCE_SYSCLK ((uint32_t)RCC_DCKCFGR2_FMPI2C1SEL_0) -#define RCC_FMPI2C1CLKSOURCE_HSI ((uint32_t)RCC_DCKCFGR2_FMPI2C1SEL_1) -/** - * @} - */ - -/** @defgroup RCCEx_CLK48_Clock_Source RCC CLK48 Clock Source - * @{ - */ -#define RCC_CLK48CLKSOURCE_PLLQ 0x00000000U -#define RCC_CLK48CLKSOURCE_PLLI2SQ ((uint32_t)RCC_DCKCFGR2_CK48MSEL) -/** - * @} - */ - -/** @defgroup RCCEx_SDIO_Clock_Source RCC SDIO Clock Source - * @{ - */ -#define RCC_SDIOCLKSOURCE_CLK48 0x00000000U -#define RCC_SDIOCLKSOURCE_SYSCLK ((uint32_t)RCC_DCKCFGR2_SDIOSEL) -/** - * @} - */ -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) - -/** @defgroup RCCEx_I2S_APB_Clock_Source RCC I2S APB Clock Source - * @{ - */ -#define RCC_I2SAPBCLKSOURCE_PLLR 0x00000000U -#define RCC_I2SAPBCLKSOURCE_EXT ((uint32_t)RCC_DCKCFGR_I2SSRC_0) -#define RCC_I2SAPBCLKSOURCE_PLLSRC ((uint32_t)RCC_DCKCFGR_I2SSRC_1) -/** - * @} - */ - -/** @defgroup RCCEx_FMPI2C1_Clock_Source RCC FMPI2C1 Clock Source - * @{ - */ -#define RCC_FMPI2C1CLKSOURCE_PCLK1 0x00000000U -#define RCC_FMPI2C1CLKSOURCE_SYSCLK ((uint32_t)RCC_DCKCFGR2_FMPI2C1SEL_0) -#define RCC_FMPI2C1CLKSOURCE_HSI ((uint32_t)RCC_DCKCFGR2_FMPI2C1SEL_1) -/** - * @} - */ - -/** @defgroup RCCEx_LPTIM1_Clock_Source RCC LPTIM1 Clock Source - * @{ - */ -#define RCC_LPTIM1CLKSOURCE_PCLK1 0x00000000U -#define RCC_LPTIM1CLKSOURCE_HSI ((uint32_t)RCC_DCKCFGR2_LPTIM1SEL_0) -#define RCC_LPTIM1CLKSOURCE_LSI ((uint32_t)RCC_DCKCFGR2_LPTIM1SEL_1) -#define RCC_LPTIM1CLKSOURCE_LSE ((uint32_t)RCC_DCKCFGR2_LPTIM1SEL_0 | RCC_DCKCFGR2_LPTIM1SEL_1) -/** - * @} - */ -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) ||\ - defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F469xx) ||\ - defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) ||\ - defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/** @defgroup RCCEx_TIM_PRescaler_Selection RCC TIM PRescaler Selection - * @{ - */ -#define RCC_TIMPRES_DESACTIVATED ((uint8_t)0x00) -#define RCC_TIMPRES_ACTIVATED ((uint8_t)0x01) -/** - * @} - */ -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F401xC || STM32F401xE ||\ - STM32F410xx || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx ||\ - STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F411xE) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) ||\ - defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) ||\ - defined(STM32F423xx) -/** @defgroup RCCEx_LSE_Dual_Mode_Selection RCC LSE Dual Mode Selection - * @{ - */ -#define RCC_LSE_LOWPOWER_MODE ((uint8_t)0x00) -#define RCC_LSE_HIGHDRIVE_MODE ((uint8_t)0x01) -/** - * @} - */ -#endif /* STM32F410xx || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx ||\ - STM32F412Rx || STM32F412Cx */ - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || \ - defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || \ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F446xx) || \ - defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || \ - defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) -/** @defgroup RCC_MCO2_Clock_Source MCO2 Clock Source - * @{ - */ -#define RCC_MCO2SOURCE_SYSCLK 0x00000000U -#define RCC_MCO2SOURCE_PLLI2SCLK RCC_CFGR_MCO2_0 -#define RCC_MCO2SOURCE_HSE RCC_CFGR_MCO2_1 -#define RCC_MCO2SOURCE_PLLCLK RCC_CFGR_MCO2 -/** - * @} - */ -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || - STM32F401xC || STM32F401xE || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || - STM32F412Rx || STM32F413xx | STM32F423xx */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -/** @defgroup RCC_MCO2_Clock_Source MCO2 Clock Source - * @{ - */ -#define RCC_MCO2SOURCE_SYSCLK 0x00000000U -#define RCC_MCO2SOURCE_I2SCLK RCC_CFGR_MCO2_0 -#define RCC_MCO2SOURCE_HSE RCC_CFGR_MCO2_1 -#define RCC_MCO2SOURCE_PLLCLK RCC_CFGR_MCO2 -/** - * @} - */ -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup RCCEx_Exported_Macros RCCEx Exported Macros - * @{ - */ -/*------------------- STM32F42xxx/STM32F43xxx/STM32F469xx/STM32F479xx --------*/ -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx)|| defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) -/** @defgroup RCCEx_AHB1_Clock_Enable_Disable AHB1 Peripheral Clock Enable Disable - * @brief Enables or disables the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_BKPSRAM_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_BKPSRAMEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_BKPSRAMEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CCMDATARAMEN_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CCMDATARAMEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CCMDATARAMEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CRC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOD_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOE_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOI_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOIEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOIEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOF_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOFEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOFEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOG_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOGEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOGEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOJ_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOJEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOJEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOK_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOKEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOKEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_DMA2D_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_DMA2DEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_DMA2DEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ETHMAC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ETHMACTX_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACTXEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACTXEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ETHMACRX_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACRXEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACRXEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ETHMACPTP_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACPTPEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACPTPEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_USB_OTG_HS_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSULPIEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSULPIEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOD_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIODEN)) -#define __HAL_RCC_GPIOE_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOEEN)) -#define __HAL_RCC_GPIOF_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOFEN)) -#define __HAL_RCC_GPIOG_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOGEN)) -#define __HAL_RCC_GPIOI_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOIEN)) -#define __HAL_RCC_GPIOJ_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOJEN)) -#define __HAL_RCC_GPIOK_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOKEN)) -#define __HAL_RCC_DMA2D_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_DMA2DEN)) -#define __HAL_RCC_ETHMAC_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_ETHMACEN)) -#define __HAL_RCC_ETHMACTX_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_ETHMACTXEN)) -#define __HAL_RCC_ETHMACRX_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_ETHMACRXEN)) -#define __HAL_RCC_ETHMACPTP_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_ETHMACPTPEN)) -#define __HAL_RCC_USB_OTG_HS_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_OTGHSEN)) -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_OTGHSULPIEN)) -#define __HAL_RCC_BKPSRAM_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_BKPSRAMEN)) -#define __HAL_RCC_CCMDATARAMEN_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CCMDATARAMEN)) -#define __HAL_RCC_CRC_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CRCEN)) - -/** - * @brief Enable ETHERNET clock. - */ -#define __HAL_RCC_ETH_CLK_ENABLE() do { \ - __HAL_RCC_ETHMAC_CLK_ENABLE(); \ - __HAL_RCC_ETHMACTX_CLK_ENABLE(); \ - __HAL_RCC_ETHMACRX_CLK_ENABLE(); \ - } while(0U) -/** - * @brief Disable ETHERNET clock. - */ -#define __HAL_RCC_ETH_CLK_DISABLE() do { \ - __HAL_RCC_ETHMACTX_CLK_DISABLE(); \ - __HAL_RCC_ETHMACRX_CLK_DISABLE(); \ - __HAL_RCC_ETHMAC_CLK_DISABLE(); \ - } while(0U) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_Peripheral_Clock_Enable_Disable_Status AHB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_GPIOD_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) != RESET) -#define __HAL_RCC_GPIOE_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) != RESET) -#define __HAL_RCC_GPIOF_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOFEN)) != RESET) -#define __HAL_RCC_GPIOG_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOGEN)) != RESET) -#define __HAL_RCC_GPIOI_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOIEN)) != RESET) -#define __HAL_RCC_GPIOJ_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOJEN)) != RESET) -#define __HAL_RCC_GPIOK_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOKEN)) != RESET) -#define __HAL_RCC_DMA2D_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_DMA2DEN)) != RESET) -#define __HAL_RCC_ETHMAC_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACEN)) != RESET) -#define __HAL_RCC_ETHMACTX_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACTXEN)) != RESET) -#define __HAL_RCC_ETHMACRX_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACRXEN)) != RESET) -#define __HAL_RCC_ETHMACPTP_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACPTPEN)) != RESET) -#define __HAL_RCC_USB_OTG_HS_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSEN)) != RESET) -#define __HAL_RCC_USB_OTG_HS_ULPI_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSULPIEN)) != RESET) -#define __HAL_RCC_BKPSRAM_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_BKPSRAMEN)) != RESET) -#define __HAL_RCC_CCMDATARAMEN_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CCMDATARAMEN)) != RESET) -#define __HAL_RCC_CRC_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) != RESET) -#define __HAL_RCC_ETH_IS_CLK_ENABLED() (__HAL_RCC_ETHMAC_IS_CLK_ENABLED() && \ - __HAL_RCC_ETHMACTX_IS_CLK_ENABLED() && \ - __HAL_RCC_ETHMACRX_IS_CLK_ENABLED()) - -#define __HAL_RCC_GPIOD_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) == RESET) -#define __HAL_RCC_GPIOE_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) == RESET) -#define __HAL_RCC_GPIOF_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOFEN)) == RESET) -#define __HAL_RCC_GPIOG_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOGEN)) == RESET) -#define __HAL_RCC_GPIOI_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOIEN)) == RESET) -#define __HAL_RCC_GPIOJ_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOJEN)) == RESET) -#define __HAL_RCC_GPIOK_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOKEN)) == RESET) -#define __HAL_RCC_DMA2D_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_DMA2DEN)) == RESET) -#define __HAL_RCC_ETHMAC_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACEN)) == RESET) -#define __HAL_RCC_ETHMACTX_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACTXEN)) == RESET) -#define __HAL_RCC_ETHMACRX_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACRXEN)) == RESET) -#define __HAL_RCC_ETHMACPTP_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACPTPEN)) == RESET) -#define __HAL_RCC_USB_OTG_HS_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSEN)) == RESET) -#define __HAL_RCC_USB_OTG_HS_ULPI_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSULPIEN)) == RESET) -#define __HAL_RCC_BKPSRAM_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_BKPSRAMEN)) == RESET) -#define __HAL_RCC_CCMDATARAMEN_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CCMDATARAMEN)) == RESET) -#define __HAL_RCC_CRC_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) == RESET) -#define __HAL_RCC_ETH_IS_CLK_DISABLED() (__HAL_RCC_ETHMAC_IS_CLK_DISABLED() && \ - __HAL_RCC_ETHMACTX_IS_CLK_DISABLED() && \ - __HAL_RCC_ETHMACRX_IS_CLK_DISABLED()) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Clock_Enable_Disable AHB2 Peripheral Clock Enable Disable - * @brief Enable or disable the AHB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ - #define __HAL_RCC_DCMI_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_DCMIEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_DCMIEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_DCMI_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_DCMIEN)) - -#if defined(STM32F437xx)|| defined(STM32F439xx) || defined(STM32F479xx) -#define __HAL_RCC_CRYP_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_CRYPEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_CRYPEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_HASH_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_HASHEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_HASHEN);\ - UNUSED(tmpreg); \ - } while(0U) - -#define __HAL_RCC_CRYP_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_CRYPEN)) -#define __HAL_RCC_HASH_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_HASHEN)) -#endif /* STM32F437xx || STM32F439xx || STM32F479xx */ - -#define __HAL_RCC_USB_OTG_FS_CLK_ENABLE() do {(RCC->AHB2ENR |= (RCC_AHB2ENR_OTGFSEN));\ - __HAL_RCC_SYSCFG_CLK_ENABLE();\ - }while(0U) - -#define __HAL_RCC_USB_OTG_FS_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_OTGFSEN)) - -#define __HAL_RCC_RNG_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_RNGEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_RNGEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_RNG_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_RNGEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Peripheral_Clock_Enable_Disable_Status AHB2 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_DCMI_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_DCMIEN)) != RESET) -#define __HAL_RCC_DCMI_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_DCMIEN)) == RESET) - -#if defined(STM32F437xx)|| defined(STM32F439xx) || defined(STM32F479xx) -#define __HAL_RCC_CRYP_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_CRYPEN)) != RESET) -#define __HAL_RCC_CRYP_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_CRYPEN)) == RESET) - -#define __HAL_RCC_HASH_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_HASHEN)) != RESET) -#define __HAL_RCC_HASH_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_HASHEN)) == RESET) -#endif /* STM32F437xx || STM32F439xx || STM32F479xx */ - -#define __HAL_RCC_USB_OTG_FS_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) != RESET) -#define __HAL_RCC_USB_OTG_FS_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) == RESET) - -#define __HAL_RCC_RNG_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_RNGEN)) != RESET) -#define __HAL_RCC_RNG_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_RNGEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_Clock_Enable_Disable AHB3 Peripheral Clock Enable Disable - * @brief Enables or disables the AHB3 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_FMC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FMCEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FMCEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_FMC_CLK_DISABLE() (RCC->AHB3ENR &= ~(RCC_AHB3ENR_FMCEN)) -#if defined(STM32F469xx) || defined(STM32F479xx) -#define __HAL_RCC_QSPI_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB3ENR, RCC_AHB3ENR_QSPIEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB3ENR, RCC_AHB3ENR_QSPIEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_QSPI_CLK_DISABLE() (RCC->AHB3ENR &= ~(RCC_AHB3ENR_QSPIEN)) -#endif /* STM32F469xx || STM32F479xx */ -/** - * @} - */ - - -/** @defgroup RCCEx_AHB3_Peripheral_Clock_Enable_Disable_Status AHB3 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB3 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_FMC_IS_CLK_ENABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_FMCEN)) != RESET) -#define __HAL_RCC_FMC_IS_CLK_DISABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_FMCEN)) == RESET) -#if defined(STM32F469xx) || defined(STM32F479xx) -#define __HAL_RCC_QSPI_IS_CLK_ENABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_QSPIEN)) != RESET) -#define __HAL_RCC_QSPI_IS_CLK_DISABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_QSPIEN)) == RESET) -#endif /* STM32F469xx || STM32F479xx */ -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Clock_Enable_Disable APB1 Peripheral Clock Enable Disable - * @brief Enable or disable the Low Speed APB (APB1) peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM6_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM6EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM6EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM7_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM7EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM7EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM12_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM12EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM12EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM13_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM13EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM13EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM14_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM14EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM14EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM14_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM14EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM14EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_USART3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_USART3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_USART3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_UART4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_UART5_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART5EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART5EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CAN1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CAN2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_DAC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_DACEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_DACEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_UART7_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART7EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART7EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_UART8_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART8EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART8EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_I2C3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM2EN)) -#define __HAL_RCC_TIM3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM3EN)) -#define __HAL_RCC_TIM4_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM4EN)) -#define __HAL_RCC_SPI3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_SPI3EN)) -#define __HAL_RCC_I2C3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_I2C3EN)) -#define __HAL_RCC_TIM6_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM6EN)) -#define __HAL_RCC_TIM7_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM7EN)) -#define __HAL_RCC_TIM12_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM12EN)) -#define __HAL_RCC_TIM13_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM13EN)) -#define __HAL_RCC_TIM14_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM14EN)) -#define __HAL_RCC_USART3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_USART3EN)) -#define __HAL_RCC_UART4_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART4EN)) -#define __HAL_RCC_UART5_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART5EN)) -#define __HAL_RCC_CAN1_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_CAN1EN)) -#define __HAL_RCC_CAN2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_CAN2EN)) -#define __HAL_RCC_DAC_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_DACEN)) -#define __HAL_RCC_UART7_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART7EN)) -#define __HAL_RCC_UART8_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART8EN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Peripheral_Clock_Enable_Disable_Status APB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) != RESET) -#define __HAL_RCC_TIM3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) != RESET) -#define __HAL_RCC_TIM4_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) != RESET) -#define __HAL_RCC_SPI3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) != RESET) -#define __HAL_RCC_I2C3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) != RESET) -#define __HAL_RCC_TIM6_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM6EN)) != RESET) -#define __HAL_RCC_TIM7_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM7EN)) != RESET) -#define __HAL_RCC_TIM12_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM12EN)) != RESET) -#define __HAL_RCC_TIM13_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM13EN)) != RESET) -#define __HAL_RCC_TIM14_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM14EN)) != RESET) -#define __HAL_RCC_USART3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART3EN)) != RESET) -#define __HAL_RCC_UART4_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART4EN)) != RESET) -#define __HAL_RCC_UART5_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART5EN)) != RESET) -#define __HAL_RCC_CAN1_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN1EN)) != RESET) -#define __HAL_RCC_CAN2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN2EN)) != RESET) -#define __HAL_RCC_DAC_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_DACEN)) != RESET) -#define __HAL_RCC_UART7_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART7EN)) != RESET) -#define __HAL_RCC_UART8_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART8EN)) != RESET) - -#define __HAL_RCC_TIM2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) == RESET) -#define __HAL_RCC_TIM3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) == RESET) -#define __HAL_RCC_TIM4_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) == RESET) -#define __HAL_RCC_SPI3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) == RESET) -#define __HAL_RCC_I2C3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) == RESET) -#define __HAL_RCC_TIM6_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM6EN)) == RESET) -#define __HAL_RCC_TIM7_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM7EN)) == RESET) -#define __HAL_RCC_TIM12_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM12EN)) == RESET) -#define __HAL_RCC_TIM13_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM13EN)) == RESET) -#define __HAL_RCC_TIM14_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM14EN)) == RESET) -#define __HAL_RCC_USART3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART3EN)) == RESET) -#define __HAL_RCC_UART4_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART4EN)) == RESET) -#define __HAL_RCC_UART5_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART5EN)) == RESET) -#define __HAL_RCC_CAN1_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN1EN)) == RESET) -#define __HAL_RCC_CAN2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN2EN)) == RESET) -#define __HAL_RCC_DAC_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_DACEN)) == RESET) -#define __HAL_RCC_UART7_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART7EN)) == RESET) -#define __HAL_RCC_UART8_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART8EN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Clock_Enable_Disable APB2 Peripheral Clock Enable Disable - * @brief Enable or disable the High Speed APB (APB2) peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM8_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM8EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM8EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ADC2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ADC3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI5_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI5EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI5EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI6_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI6EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI6EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SAI1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SAI1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SAI1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SDIO_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM10_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SDIO_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SDIOEN)) -#define __HAL_RCC_SPI4_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI4EN)) -#define __HAL_RCC_TIM10_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM10EN)) -#define __HAL_RCC_TIM8_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM8EN)) -#define __HAL_RCC_ADC2_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_ADC2EN)) -#define __HAL_RCC_ADC3_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_ADC3EN)) -#define __HAL_RCC_SPI5_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI5EN)) -#define __HAL_RCC_SPI6_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI6EN)) -#define __HAL_RCC_SAI1_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SAI1EN)) - -#if defined(STM32F429xx)|| defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) -#define __HAL_RCC_LTDC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_LTDCEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_LTDCEN);\ - UNUSED(tmpreg); \ - } while(0U) - -#define __HAL_RCC_LTDC_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_LTDCEN)) -#endif /* STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F469xx) || defined(STM32F479xx) -#define __HAL_RCC_DSI_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_DSIEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_DSIEN);\ - UNUSED(tmpreg); \ - } while(0U) - -#define __HAL_RCC_DSI_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_DSIEN)) -#endif /* STM32F469xx || STM32F479xx */ -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Peripheral_Clock_Enable_Disable_Status APB2 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM8_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM8EN)) != RESET) -#define __HAL_RCC_ADC2_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC2EN)) != RESET) -#define __HAL_RCC_ADC3_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC3EN)) != RESET) -#define __HAL_RCC_SPI5_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI5EN)) != RESET) -#define __HAL_RCC_SPI6_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI6EN)) != RESET) -#define __HAL_RCC_SAI1_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SAI1EN)) != RESET) -#define __HAL_RCC_SDIO_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) != RESET) -#define __HAL_RCC_SPI4_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) != RESET) -#define __HAL_RCC_TIM10_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN))!= RESET) - -#define __HAL_RCC_SDIO_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) == RESET) -#define __HAL_RCC_SPI4_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) == RESET) -#define __HAL_RCC_TIM10_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN))== RESET) -#define __HAL_RCC_TIM8_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM8EN)) == RESET) -#define __HAL_RCC_ADC2_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC2EN)) == RESET) -#define __HAL_RCC_ADC3_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC3EN)) == RESET) -#define __HAL_RCC_SPI5_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI5EN)) == RESET) -#define __HAL_RCC_SPI6_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI6EN)) == RESET) -#define __HAL_RCC_SAI1_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SAI1EN)) == RESET) - -#if defined(STM32F429xx)|| defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) -#define __HAL_RCC_LTDC_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_LTDCEN)) != RESET) -#define __HAL_RCC_LTDC_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_LTDCEN)) == RESET) -#endif /* STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F469xx) || defined(STM32F479xx) -#define __HAL_RCC_DSI_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_DSIEN)) != RESET) -#define __HAL_RCC_DSI_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_DSIEN)) == RESET) -#endif /* STM32F469xx || STM32F479xx */ -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_Force_Release_Reset AHB1 Force Release Reset - * @brief Force or release AHB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_GPIOD_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIODRST)) -#define __HAL_RCC_GPIOE_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOERST)) -#define __HAL_RCC_GPIOF_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOFRST)) -#define __HAL_RCC_GPIOG_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOGRST)) -#define __HAL_RCC_GPIOI_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOIRST)) -#define __HAL_RCC_ETHMAC_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_ETHMACRST)) -#define __HAL_RCC_USB_OTG_HS_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_OTGHRST)) -#define __HAL_RCC_GPIOJ_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOJRST)) -#define __HAL_RCC_GPIOK_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOKRST)) -#define __HAL_RCC_DMA2D_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_DMA2DRST)) -#define __HAL_RCC_CRC_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_CRCRST)) - -#define __HAL_RCC_GPIOD_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIODRST)) -#define __HAL_RCC_GPIOE_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOERST)) -#define __HAL_RCC_GPIOF_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOFRST)) -#define __HAL_RCC_GPIOG_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOGRST)) -#define __HAL_RCC_GPIOI_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOIRST)) -#define __HAL_RCC_ETHMAC_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_ETHMACRST)) -#define __HAL_RCC_USB_OTG_HS_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_OTGHRST)) -#define __HAL_RCC_GPIOJ_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOJRST)) -#define __HAL_RCC_GPIOK_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOKRST)) -#define __HAL_RCC_DMA2D_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_DMA2DRST)) -#define __HAL_RCC_CRC_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_CRCRST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Force_Release_Reset AHB2 Force Release Reset - * @brief Force or release AHB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB2_FORCE_RESET() (RCC->AHB2RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_USB_OTG_FS_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_OTGFSRST)) -#define __HAL_RCC_RNG_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_RNGRST)) -#define __HAL_RCC_DCMI_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_DCMIRST)) - -#define __HAL_RCC_AHB2_RELEASE_RESET() (RCC->AHB2RSTR = 0x00U) -#define __HAL_RCC_USB_OTG_FS_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_OTGFSRST)) -#define __HAL_RCC_RNG_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_RNGRST)) -#define __HAL_RCC_DCMI_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_DCMIRST)) - -#if defined(STM32F437xx)|| defined(STM32F439xx) || defined(STM32F479xx) -#define __HAL_RCC_CRYP_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_CRYPRST)) -#define __HAL_RCC_HASH_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_HASHRST)) - -#define __HAL_RCC_CRYP_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_CRYPRST)) -#define __HAL_RCC_HASH_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_HASHRST)) -#endif /* STM32F437xx || STM32F439xx || STM32F479xx */ -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_Force_Release_Reset AHB3 Force Release Reset - * @brief Force or release AHB3 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB3_FORCE_RESET() (RCC->AHB3RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_AHB3_RELEASE_RESET() (RCC->AHB3RSTR = 0x00U) -#define __HAL_RCC_FMC_FORCE_RESET() (RCC->AHB3RSTR |= (RCC_AHB3RSTR_FMCRST)) -#define __HAL_RCC_FMC_RELEASE_RESET() (RCC->AHB3RSTR &= ~(RCC_AHB3RSTR_FMCRST)) - -#if defined(STM32F469xx) || defined(STM32F479xx) -#define __HAL_RCC_QSPI_FORCE_RESET() (RCC->AHB3RSTR |= (RCC_AHB3RSTR_QSPIRST)) -#define __HAL_RCC_QSPI_RELEASE_RESET() (RCC->AHB3RSTR &= ~(RCC_AHB3RSTR_QSPIRST)) -#endif /* STM32F469xx || STM32F479xx */ -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Force_Release_Reset APB1 Force Release Reset - * @brief Force or release APB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_TIM6_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM6RST)) -#define __HAL_RCC_TIM7_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM7RST)) -#define __HAL_RCC_TIM12_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM12RST)) -#define __HAL_RCC_TIM13_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM13RST)) -#define __HAL_RCC_TIM14_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM14RST)) -#define __HAL_RCC_USART3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_USART3RST)) -#define __HAL_RCC_UART4_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART4RST)) -#define __HAL_RCC_UART5_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART5RST)) -#define __HAL_RCC_CAN1_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_CAN1RST)) -#define __HAL_RCC_CAN2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_CAN2RST)) -#define __HAL_RCC_DAC_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_DACRST)) -#define __HAL_RCC_UART7_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART7RST)) -#define __HAL_RCC_UART8_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART8RST)) -#define __HAL_RCC_TIM2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM2RST)) -#define __HAL_RCC_TIM3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM3RST)) -#define __HAL_RCC_TIM4_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM4RST)) -#define __HAL_RCC_SPI3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_SPI3RST)) -#define __HAL_RCC_I2C3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_I2C3RST)) - -#define __HAL_RCC_TIM2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM2RST)) -#define __HAL_RCC_TIM3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM3RST)) -#define __HAL_RCC_TIM4_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM4RST)) -#define __HAL_RCC_SPI3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_SPI3RST)) -#define __HAL_RCC_I2C3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_I2C3RST)) -#define __HAL_RCC_TIM6_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM6RST)) -#define __HAL_RCC_TIM7_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM7RST)) -#define __HAL_RCC_TIM12_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM12RST)) -#define __HAL_RCC_TIM13_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM13RST)) -#define __HAL_RCC_TIM14_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM14RST)) -#define __HAL_RCC_USART3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_USART3RST)) -#define __HAL_RCC_UART4_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART4RST)) -#define __HAL_RCC_UART5_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART5RST)) -#define __HAL_RCC_CAN1_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_CAN1RST)) -#define __HAL_RCC_CAN2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_CAN2RST)) -#define __HAL_RCC_DAC_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_DACRST)) -#define __HAL_RCC_UART7_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART7RST)) -#define __HAL_RCC_UART8_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART8RST)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Force_Release_Reset APB2 Force Release Reset - * @brief Force or release APB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_TIM8_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM8RST)) -#define __HAL_RCC_SPI5_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI5RST)) -#define __HAL_RCC_SPI6_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI6RST)) -#define __HAL_RCC_SAI1_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SAI1RST)) -#define __HAL_RCC_SDIO_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SDIORST)) -#define __HAL_RCC_SPI4_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI4RST)) -#define __HAL_RCC_TIM10_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM10RST)) - -#define __HAL_RCC_SDIO_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SDIORST)) -#define __HAL_RCC_SPI4_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI4RST)) -#define __HAL_RCC_TIM10_RELEASE_RESET()(RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM10RST)) -#define __HAL_RCC_TIM8_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM8RST)) -#define __HAL_RCC_SPI5_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI5RST)) -#define __HAL_RCC_SPI6_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI6RST)) -#define __HAL_RCC_SAI1_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SAI1RST)) - -#if defined(STM32F429xx)|| defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) -#define __HAL_RCC_LTDC_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_LTDCRST)) -#define __HAL_RCC_LTDC_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_LTDCRST)) -#endif /* STM32F429xx|| STM32F439xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F469xx) || defined(STM32F479xx) -#define __HAL_RCC_DSI_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_DSIRST)) -#define __HAL_RCC_DSI_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_DSIRST)) -#endif /* STM32F469xx || STM32F479xx */ -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_LowPower_Enable_Disable AHB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB1 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_GPIOD_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIODLPEN)) -#define __HAL_RCC_GPIOE_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOELPEN)) -#define __HAL_RCC_GPIOF_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOFLPEN)) -#define __HAL_RCC_GPIOG_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOGLPEN)) -#define __HAL_RCC_GPIOI_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOILPEN)) -#define __HAL_RCC_SRAM2_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM2LPEN)) -#define __HAL_RCC_ETHMAC_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_ETHMACLPEN)) -#define __HAL_RCC_ETHMACTX_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_ETHMACTXLPEN)) -#define __HAL_RCC_ETHMACRX_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_ETHMACRXLPEN)) -#define __HAL_RCC_ETHMACPTP_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_ETHMACPTPLPEN)) -#define __HAL_RCC_USB_OTG_HS_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_OTGHSLPEN)) -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_OTGHSULPILPEN)) -#define __HAL_RCC_GPIOJ_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOJLPEN)) -#define __HAL_RCC_GPIOK_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOKLPEN)) -#define __HAL_RCC_SRAM3_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM3LPEN)) -#define __HAL_RCC_DMA2D_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_DMA2DLPEN)) -#define __HAL_RCC_CRC_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_CRCLPEN)) -#define __HAL_RCC_FLITF_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_FLITFLPEN)) -#define __HAL_RCC_SRAM1_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM1LPEN)) -#define __HAL_RCC_BKPSRAM_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_BKPSRAMLPEN)) - -#define __HAL_RCC_GPIOD_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIODLPEN)) -#define __HAL_RCC_GPIOE_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOELPEN)) -#define __HAL_RCC_GPIOF_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOFLPEN)) -#define __HAL_RCC_GPIOG_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOGLPEN)) -#define __HAL_RCC_GPIOI_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOILPEN)) -#define __HAL_RCC_SRAM2_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_SRAM2LPEN)) -#define __HAL_RCC_ETHMAC_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_ETHMACLPEN)) -#define __HAL_RCC_ETHMACTX_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_ETHMACTXLPEN)) -#define __HAL_RCC_ETHMACRX_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_ETHMACRXLPEN)) -#define __HAL_RCC_ETHMACPTP_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_ETHMACPTPLPEN)) -#define __HAL_RCC_USB_OTG_HS_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_OTGHSLPEN)) -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_OTGHSULPILPEN)) -#define __HAL_RCC_GPIOJ_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOJLPEN)) -#define __HAL_RCC_GPIOK_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOKLPEN)) -#define __HAL_RCC_DMA2D_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_DMA2DLPEN)) -#define __HAL_RCC_CRC_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_CRCLPEN)) -#define __HAL_RCC_FLITF_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_FLITFLPEN)) -#define __HAL_RCC_SRAM1_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_SRAM1LPEN)) -#define __HAL_RCC_BKPSRAM_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_BKPSRAMLPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_LowPower_Enable_Disable AHB2 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB2 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_OTGFSLPEN)) -#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_OTGFSLPEN)) - -#define __HAL_RCC_RNG_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_RNGLPEN)) -#define __HAL_RCC_RNG_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_RNGLPEN)) - -#define __HAL_RCC_DCMI_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_DCMILPEN)) -#define __HAL_RCC_DCMI_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_DCMILPEN)) - -#if defined(STM32F437xx)|| defined(STM32F439xx) || defined(STM32F479xx) -#define __HAL_RCC_CRYP_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_CRYPLPEN)) -#define __HAL_RCC_HASH_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_HASHLPEN)) - -#define __HAL_RCC_CRYP_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_CRYPLPEN)) -#define __HAL_RCC_HASH_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_HASHLPEN)) -#endif /* STM32F437xx || STM32F439xx || STM32F479xx */ -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_LowPower_Enable_Disable AHB3 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB3 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_FMC_CLK_SLEEP_ENABLE() (RCC->AHB3LPENR |= (RCC_AHB3LPENR_FMCLPEN)) -#define __HAL_RCC_FMC_CLK_SLEEP_DISABLE() (RCC->AHB3LPENR &= ~(RCC_AHB3LPENR_FMCLPEN)) - -#if defined(STM32F469xx) || defined(STM32F479xx) -#define __HAL_RCC_QSPI_CLK_SLEEP_ENABLE() (RCC->AHB3LPENR |= (RCC_AHB3LPENR_QSPILPEN)) -#define __HAL_RCC_QSPI_CLK_SLEEP_DISABLE() (RCC->AHB3LPENR &= ~(RCC_AHB3LPENR_QSPILPEN)) -#endif /* STM32F469xx || STM32F479xx */ -/** - * @} - */ - -/** @defgroup RCCEx_APB1_LowPower_Enable_Disable APB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB1 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_TIM6_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM6LPEN)) -#define __HAL_RCC_TIM7_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM7LPEN)) -#define __HAL_RCC_TIM12_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM12LPEN)) -#define __HAL_RCC_TIM13_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM13LPEN)) -#define __HAL_RCC_TIM14_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM14LPEN)) -#define __HAL_RCC_USART3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_USART3LPEN)) -#define __HAL_RCC_UART4_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART4LPEN)) -#define __HAL_RCC_UART5_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART5LPEN)) -#define __HAL_RCC_CAN1_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_CAN1LPEN)) -#define __HAL_RCC_CAN2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_CAN2LPEN)) -#define __HAL_RCC_DAC_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_DACLPEN)) -#define __HAL_RCC_UART7_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART7LPEN)) -#define __HAL_RCC_UART8_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART8LPEN)) -#define __HAL_RCC_TIM2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM2LPEN)) -#define __HAL_RCC_TIM3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM3LPEN)) -#define __HAL_RCC_TIM4_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM4LPEN)) -#define __HAL_RCC_SPI3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_SPI3LPEN)) -#define __HAL_RCC_I2C3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_I2C3LPEN)) - -#define __HAL_RCC_TIM2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM2LPEN)) -#define __HAL_RCC_TIM3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM3LPEN)) -#define __HAL_RCC_TIM4_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM4LPEN)) -#define __HAL_RCC_SPI3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_SPI3LPEN)) -#define __HAL_RCC_I2C3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_I2C3LPEN)) -#define __HAL_RCC_TIM6_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM6LPEN)) -#define __HAL_RCC_TIM7_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM7LPEN)) -#define __HAL_RCC_TIM12_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM12LPEN)) -#define __HAL_RCC_TIM13_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM13LPEN)) -#define __HAL_RCC_TIM14_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM14LPEN)) -#define __HAL_RCC_USART3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_USART3LPEN)) -#define __HAL_RCC_UART4_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART4LPEN)) -#define __HAL_RCC_UART5_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART5LPEN)) -#define __HAL_RCC_CAN1_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_CAN1LPEN)) -#define __HAL_RCC_CAN2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_CAN2LPEN)) -#define __HAL_RCC_DAC_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_DACLPEN)) -#define __HAL_RCC_UART7_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART7LPEN)) -#define __HAL_RCC_UART8_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART8LPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_LowPower_Enable_Disable APB2 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB2 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_TIM8_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_TIM8LPEN)) -#define __HAL_RCC_ADC2_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_ADC2LPEN)) -#define __HAL_RCC_ADC3_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_ADC3LPEN)) -#define __HAL_RCC_SPI5_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI5LPEN)) -#define __HAL_RCC_SPI6_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI6LPEN)) -#define __HAL_RCC_SAI1_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SAI1LPEN)) -#define __HAL_RCC_SDIO_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SDIOLPEN)) -#define __HAL_RCC_SPI4_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI4LPEN)) -#define __HAL_RCC_TIM10_CLK_SLEEP_ENABLE()(RCC->APB2LPENR |= (RCC_APB2LPENR_TIM10LPEN)) - -#define __HAL_RCC_SDIO_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SDIOLPEN)) -#define __HAL_RCC_SPI4_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI4LPEN)) -#define __HAL_RCC_TIM10_CLK_SLEEP_DISABLE()(RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM10LPEN)) -#define __HAL_RCC_TIM8_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM8LPEN)) -#define __HAL_RCC_ADC2_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_ADC2LPEN)) -#define __HAL_RCC_ADC3_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_ADC3LPEN)) -#define __HAL_RCC_SPI5_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI5LPEN)) -#define __HAL_RCC_SPI6_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI6LPEN)) -#define __HAL_RCC_SAI1_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SAI1LPEN)) - -#if defined(STM32F429xx)|| defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) -#define __HAL_RCC_LTDC_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_LTDCLPEN)) - -#define __HAL_RCC_LTDC_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_LTDCLPEN)) -#endif /* STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F469xx) || defined(STM32F479xx) -#define __HAL_RCC_DSI_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_DSILPEN)) -#define __HAL_RCC_DSI_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_DSILPEN)) -#endif /* STM32F469xx || STM32F479xx */ -/** - * @} - */ -#endif /* STM32F427xx || STM32F437xx || STM32F429xx|| STM32F439xx || STM32F469xx || STM32F479xx */ -/*----------------------------------------------------------------------------*/ - -/*----------------------------------- STM32F40xxx/STM32F41xxx-----------------*/ -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx)|| defined(STM32F417xx) -/** @defgroup RCCEx_AHB1_Clock_Enable_Disable AHB1 Peripheral Clock Enable Disable - * @brief Enables or disables the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_BKPSRAM_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_BKPSRAMEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_BKPSRAMEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CCMDATARAMEN_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CCMDATARAMEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CCMDATARAMEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CRC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOD_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOE_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOI_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOIEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOIEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOF_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOFEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOFEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOG_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOGEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOGEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_USB_OTG_HS_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSULPIEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSULPIEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOD_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIODEN)) -#define __HAL_RCC_GPIOE_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOEEN)) -#define __HAL_RCC_GPIOF_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOFEN)) -#define __HAL_RCC_GPIOG_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOGEN)) -#define __HAL_RCC_GPIOI_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOIEN)) -#define __HAL_RCC_USB_OTG_HS_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_OTGHSEN)) -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_OTGHSULPIEN)) -#define __HAL_RCC_BKPSRAM_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_BKPSRAMEN)) -#define __HAL_RCC_CCMDATARAMEN_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CCMDATARAMEN)) -#define __HAL_RCC_CRC_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CRCEN)) -#if defined(STM32F407xx)|| defined(STM32F417xx) -/** - * @brief Enable ETHERNET clock. - */ -#define __HAL_RCC_ETHMAC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ETHMACTX_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACTXEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACTXEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ETHMACRX_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACRXEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACRXEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ETHMACPTP_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACPTPEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_ETHMACPTPEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ETH_CLK_ENABLE() do { \ - __HAL_RCC_ETHMAC_CLK_ENABLE(); \ - __HAL_RCC_ETHMACTX_CLK_ENABLE(); \ - __HAL_RCC_ETHMACRX_CLK_ENABLE(); \ - } while(0U) - -/** - * @brief Disable ETHERNET clock. - */ -#define __HAL_RCC_ETHMAC_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_ETHMACEN)) -#define __HAL_RCC_ETHMACTX_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_ETHMACTXEN)) -#define __HAL_RCC_ETHMACRX_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_ETHMACRXEN)) -#define __HAL_RCC_ETHMACPTP_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_ETHMACPTPEN)) -#define __HAL_RCC_ETH_CLK_DISABLE() do { \ - __HAL_RCC_ETHMACTX_CLK_DISABLE(); \ - __HAL_RCC_ETHMACRX_CLK_DISABLE(); \ - __HAL_RCC_ETHMAC_CLK_DISABLE(); \ - } while(0U) -#endif /* STM32F407xx || STM32F417xx */ -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_Peripheral_Clock_Enable_Disable_Status AHB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_BKPSRAM_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_BKPSRAMEN)) != RESET) -#define __HAL_RCC_CCMDATARAMEN_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CCMDATARAMEN)) != RESET) -#define __HAL_RCC_CRC_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) != RESET) -#define __HAL_RCC_GPIOD_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) != RESET) -#define __HAL_RCC_GPIOE_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) != RESET) -#define __HAL_RCC_GPIOI_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOIEN)) != RESET) -#define __HAL_RCC_GPIOF_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOFEN)) != RESET) -#define __HAL_RCC_GPIOG_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOGEN)) != RESET) -#define __HAL_RCC_USB_OTG_HS_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSEN)) != RESET) -#define __HAL_RCC_USB_OTG_HS_ULPI_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSULPIEN)) != RESET) - -#define __HAL_RCC_GPIOD_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) == RESET) -#define __HAL_RCC_GPIOE_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) == RESET) -#define __HAL_RCC_GPIOF_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOFEN)) == RESET) -#define __HAL_RCC_GPIOG_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOGEN)) == RESET) -#define __HAL_RCC_GPIOI_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOIEN)) == RESET) -#define __HAL_RCC_USB_OTG_HS_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSEN)) == RESET) -#define __HAL_RCC_USB_OTG_HS_ULPI_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSULPIEN))== RESET) -#define __HAL_RCC_BKPSRAM_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_BKPSRAMEN)) == RESET) -#define __HAL_RCC_CCMDATARAMEN_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CCMDATARAMEN)) == RESET) -#define __HAL_RCC_CRC_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) == RESET) -#if defined(STM32F407xx)|| defined(STM32F417xx) -/** - * @brief Enable ETHERNET clock. - */ -#define __HAL_RCC_ETHMAC_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACEN)) != RESET) -#define __HAL_RCC_ETHMACTX_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACTXEN)) != RESET) -#define __HAL_RCC_ETHMACRX_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACRXEN)) != RESET) -#define __HAL_RCC_ETHMACPTP_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACPTPEN)) != RESET) -#define __HAL_RCC_ETH_IS_CLK_ENABLED() (__HAL_RCC_ETHMAC_IS_CLK_ENABLED() && \ - __HAL_RCC_ETHMACTX_IS_CLK_ENABLED() && \ - __HAL_RCC_ETHMACRX_IS_CLK_ENABLED()) -/** - * @brief Disable ETHERNET clock. - */ -#define __HAL_RCC_ETHMAC_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACEN)) == RESET) -#define __HAL_RCC_ETHMACTX_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACTXEN)) == RESET) -#define __HAL_RCC_ETHMACRX_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACRXEN)) == RESET) -#define __HAL_RCC_ETHMACPTP_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_ETHMACPTPEN)) == RESET) -#define __HAL_RCC_ETH_IS_CLK_DISABLED() (__HAL_RCC_ETHMAC_IS_CLK_DISABLED() && \ - __HAL_RCC_ETHMACTX_IS_CLK_DISABLED() && \ - __HAL_RCC_ETHMACRX_IS_CLK_DISABLED()) -#endif /* STM32F407xx || STM32F417xx */ -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Clock_Enable_Disable AHB2 Peripheral Clock Enable Disable - * @brief Enable or disable the AHB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_USB_OTG_FS_CLK_ENABLE() do {(RCC->AHB2ENR |= (RCC_AHB2ENR_OTGFSEN));\ - __HAL_RCC_SYSCFG_CLK_ENABLE();\ - }while(0U) - -#define __HAL_RCC_USB_OTG_FS_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_OTGFSEN)) - -#define __HAL_RCC_RNG_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_RNGEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_RNGEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_RNG_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_RNGEN)) - -#if defined(STM32F407xx)|| defined(STM32F417xx) -#define __HAL_RCC_DCMI_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_DCMIEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_DCMIEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_DCMI_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_DCMIEN)) -#endif /* STM32F407xx || STM32F417xx */ - -#if defined(STM32F415xx) || defined(STM32F417xx) -#define __HAL_RCC_CRYP_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_CRYPEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_CRYPEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_HASH_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_HASHEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_HASHEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CRYP_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_CRYPEN)) -#define __HAL_RCC_HASH_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_HASHEN)) -#endif /* STM32F415xx || STM32F417xx */ -/** - * @} - */ - - -/** @defgroup RCCEx_AHB2_Peripheral_Clock_Enable_Disable_Status AHB2 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_USB_OTG_FS_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) != RESET) -#define __HAL_RCC_USB_OTG_FS_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) == RESET) - -#define __HAL_RCC_RNG_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_RNGEN)) != RESET) -#define __HAL_RCC_RNG_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_RNGEN)) == RESET) - -#if defined(STM32F407xx)|| defined(STM32F417xx) -#define __HAL_RCC_DCMI_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_DCMIEN)) != RESET) -#define __HAL_RCC_DCMI_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_DCMIEN)) == RESET) -#endif /* STM32F407xx || STM32F417xx */ - -#if defined(STM32F415xx) || defined(STM32F417xx) -#define __HAL_RCC_CRYP_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_CRYPEN)) != RESET) -#define __HAL_RCC_HASH_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_HASHEN)) != RESET) - -#define __HAL_RCC_CRYP_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_CRYPEN)) == RESET) -#define __HAL_RCC_HASH_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_HASHEN)) == RESET) -#endif /* STM32F415xx || STM32F417xx */ -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_Clock_Enable_Disable AHB3 Peripheral Clock Enable Disable - * @brief Enables or disables the AHB3 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_FSMC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FSMCEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FSMCEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_FSMC_CLK_DISABLE() (RCC->AHB3ENR &= ~(RCC_AHB3ENR_FSMCEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_Peripheral_Clock_Enable_Disable_Status AHB3 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB3 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_FSMC_IS_CLK_ENABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_FSMCEN)) != RESET) -#define __HAL_RCC_FSMC_IS_CLK_DISABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_FSMCEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Clock_Enable_Disable APB1 Peripheral Clock Enable Disable - * @brief Enable or disable the Low Speed APB (APB1) peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM6_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM6EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM6EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM7_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM7EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM7EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM12_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM12EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM12EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM13_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM13EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM13EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM14_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM14EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM14EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_USART3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_USART3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_USART3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_UART4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_UART5_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART5EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART5EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CAN1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CAN2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_DAC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_DACEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_DACEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_I2C3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM2EN)) -#define __HAL_RCC_TIM3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM3EN)) -#define __HAL_RCC_TIM4_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM4EN)) -#define __HAL_RCC_SPI3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_SPI3EN)) -#define __HAL_RCC_I2C3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_I2C3EN)) -#define __HAL_RCC_TIM6_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM6EN)) -#define __HAL_RCC_TIM7_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM7EN)) -#define __HAL_RCC_TIM12_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM12EN)) -#define __HAL_RCC_TIM13_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM13EN)) -#define __HAL_RCC_TIM14_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM14EN)) -#define __HAL_RCC_USART3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_USART3EN)) -#define __HAL_RCC_UART4_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART4EN)) -#define __HAL_RCC_UART5_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART5EN)) -#define __HAL_RCC_CAN1_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_CAN1EN)) -#define __HAL_RCC_CAN2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_CAN2EN)) -#define __HAL_RCC_DAC_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_DACEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Peripheral_Clock_Enable_Disable_Status APB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) != RESET) -#define __HAL_RCC_TIM3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) != RESET) -#define __HAL_RCC_TIM4_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) != RESET) -#define __HAL_RCC_SPI3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) != RESET) -#define __HAL_RCC_I2C3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) != RESET) -#define __HAL_RCC_TIM6_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM6EN)) != RESET) -#define __HAL_RCC_TIM7_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM7EN)) != RESET) -#define __HAL_RCC_TIM12_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM12EN)) != RESET) -#define __HAL_RCC_TIM13_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM13EN)) != RESET) -#define __HAL_RCC_TIM14_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM14EN)) != RESET) -#define __HAL_RCC_USART3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART3EN)) != RESET) -#define __HAL_RCC_UART4_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART4EN)) != RESET) -#define __HAL_RCC_UART5_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART5EN)) != RESET) -#define __HAL_RCC_CAN1_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN1EN)) != RESET) -#define __HAL_RCC_CAN2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN2EN)) != RESET) -#define __HAL_RCC_DAC_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_DACEN)) != RESET) - -#define __HAL_RCC_TIM2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) == RESET) -#define __HAL_RCC_TIM3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) == RESET) -#define __HAL_RCC_TIM4_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) == RESET) -#define __HAL_RCC_SPI3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) == RESET) -#define __HAL_RCC_I2C3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) == RESET) -#define __HAL_RCC_TIM6_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM6EN)) == RESET) -#define __HAL_RCC_TIM7_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM7EN)) == RESET) -#define __HAL_RCC_TIM12_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM12EN)) == RESET) -#define __HAL_RCC_TIM13_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM13EN)) == RESET) -#define __HAL_RCC_TIM14_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM14EN)) == RESET) -#define __HAL_RCC_USART3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART3EN)) == RESET) -#define __HAL_RCC_UART4_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART4EN)) == RESET) -#define __HAL_RCC_UART5_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART5EN)) == RESET) -#define __HAL_RCC_CAN1_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN1EN)) == RESET) -#define __HAL_RCC_CAN2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN2EN)) == RESET) -#define __HAL_RCC_DAC_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_DACEN)) == RESET) - /** - * @} - */ - -/** @defgroup RCCEx_APB2_Clock_Enable_Disable APB2 Peripheral Clock Enable Disable - * @brief Enable or disable the High Speed APB (APB2) peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM8_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM8EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM8EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ADC2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ADC3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SDIO_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM10_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ - UNUSED(tmpreg); \ - } while(0U) - -#define __HAL_RCC_SDIO_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SDIOEN)) -#define __HAL_RCC_SPI4_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI4EN)) -#define __HAL_RCC_TIM10_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM10EN)) -#define __HAL_RCC_TIM8_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM8EN)) -#define __HAL_RCC_ADC2_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_ADC2EN)) -#define __HAL_RCC_ADC3_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_ADC3EN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Peripheral_Clock_Enable_Disable_Status APB2 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_SDIO_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) != RESET) -#define __HAL_RCC_SPI4_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) != RESET) -#define __HAL_RCC_TIM10_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN)) != RESET) -#define __HAL_RCC_TIM8_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM8EN)) != RESET) -#define __HAL_RCC_ADC2_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC2EN)) != RESET) -#define __HAL_RCC_ADC3_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC3EN)) != RESET) - -#define __HAL_RCC_SDIO_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) == RESET) -#define __HAL_RCC_SPI4_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) == RESET) -#define __HAL_RCC_TIM10_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN)) == RESET) -#define __HAL_RCC_TIM8_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM8EN)) == RESET) -#define __HAL_RCC_ADC2_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC2EN)) == RESET) -#define __HAL_RCC_ADC3_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC3EN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_Force_Release_Reset AHB1 Force Release Reset - * @brief Force or release AHB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_GPIOD_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIODRST)) -#define __HAL_RCC_GPIOE_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOERST)) -#define __HAL_RCC_GPIOF_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOFRST)) -#define __HAL_RCC_GPIOG_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOGRST)) -#define __HAL_RCC_GPIOI_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOIRST)) -#define __HAL_RCC_ETHMAC_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_ETHMACRST)) -#define __HAL_RCC_USB_OTG_HS_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_OTGHRST)) -#define __HAL_RCC_CRC_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_CRCRST)) - -#define __HAL_RCC_GPIOD_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIODRST)) -#define __HAL_RCC_GPIOE_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOERST)) -#define __HAL_RCC_GPIOF_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOFRST)) -#define __HAL_RCC_GPIOG_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOGRST)) -#define __HAL_RCC_GPIOI_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOIRST)) -#define __HAL_RCC_ETHMAC_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_ETHMACRST)) -#define __HAL_RCC_USB_OTG_HS_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_OTGHRST)) -#define __HAL_RCC_CRC_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_CRCRST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Force_Release_Reset AHB2 Force Release Reset - * @brief Force or release AHB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB2_FORCE_RESET() (RCC->AHB2RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_AHB2_RELEASE_RESET() (RCC->AHB2RSTR = 0x00U) - -#if defined(STM32F407xx)|| defined(STM32F417xx) -#define __HAL_RCC_DCMI_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_DCMIRST)) -#define __HAL_RCC_DCMI_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_DCMIRST)) -#endif /* STM32F407xx || STM32F417xx */ - -#if defined(STM32F415xx) || defined(STM32F417xx) -#define __HAL_RCC_CRYP_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_CRYPRST)) -#define __HAL_RCC_HASH_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_HASHRST)) - -#define __HAL_RCC_CRYP_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_CRYPRST)) -#define __HAL_RCC_HASH_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_HASHRST)) -#endif /* STM32F415xx || STM32F417xx */ - -#define __HAL_RCC_USB_OTG_FS_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_OTGFSRST)) -#define __HAL_RCC_USB_OTG_FS_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_OTGFSRST)) - -#define __HAL_RCC_RNG_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_RNGRST)) -#define __HAL_RCC_RNG_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_RNGRST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_Force_Release_Reset AHB3 Force Release Reset - * @brief Force or release AHB3 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB3_FORCE_RESET() (RCC->AHB3RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_AHB3_RELEASE_RESET() (RCC->AHB3RSTR = 0x00U) - -#define __HAL_RCC_FSMC_FORCE_RESET() (RCC->AHB3RSTR |= (RCC_AHB3RSTR_FSMCRST)) -#define __HAL_RCC_FSMC_RELEASE_RESET() (RCC->AHB3RSTR &= ~(RCC_AHB3RSTR_FSMCRST)) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Force_Release_Reset APB1 Force Release Reset - * @brief Force or release APB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_TIM6_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM6RST)) -#define __HAL_RCC_TIM7_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM7RST)) -#define __HAL_RCC_TIM12_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM12RST)) -#define __HAL_RCC_TIM13_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM13RST)) -#define __HAL_RCC_TIM14_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM14RST)) -#define __HAL_RCC_USART3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_USART3RST)) -#define __HAL_RCC_UART4_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART4RST)) -#define __HAL_RCC_UART5_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART5RST)) -#define __HAL_RCC_CAN1_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_CAN1RST)) -#define __HAL_RCC_CAN2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_CAN2RST)) -#define __HAL_RCC_DAC_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_DACRST)) -#define __HAL_RCC_TIM2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM2RST)) -#define __HAL_RCC_TIM3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM3RST)) -#define __HAL_RCC_TIM4_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM4RST)) -#define __HAL_RCC_SPI3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_SPI3RST)) -#define __HAL_RCC_I2C3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_I2C3RST)) - -#define __HAL_RCC_TIM2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM2RST)) -#define __HAL_RCC_TIM3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM3RST)) -#define __HAL_RCC_TIM4_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM4RST)) -#define __HAL_RCC_SPI3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_SPI3RST)) -#define __HAL_RCC_I2C3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_I2C3RST)) -#define __HAL_RCC_TIM6_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM6RST)) -#define __HAL_RCC_TIM7_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM7RST)) -#define __HAL_RCC_TIM12_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM12RST)) -#define __HAL_RCC_TIM13_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM13RST)) -#define __HAL_RCC_TIM14_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM14RST)) -#define __HAL_RCC_USART3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_USART3RST)) -#define __HAL_RCC_UART4_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART4RST)) -#define __HAL_RCC_UART5_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART5RST)) -#define __HAL_RCC_CAN1_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_CAN1RST)) -#define __HAL_RCC_CAN2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_CAN2RST)) -#define __HAL_RCC_DAC_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_DACRST)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Force_Release_Reset APB2 Force Release Reset - * @brief Force or release APB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_TIM8_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM8RST)) -#define __HAL_RCC_SDIO_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SDIORST)) -#define __HAL_RCC_SPI4_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI4RST)) -#define __HAL_RCC_TIM10_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM10RST)) - -#define __HAL_RCC_SDIO_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SDIORST)) -#define __HAL_RCC_SPI4_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI4RST)) -#define __HAL_RCC_TIM10_RELEASE_RESET()(RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM10RST)) -#define __HAL_RCC_TIM8_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM8RST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_LowPower_Enable_Disable AHB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB1 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_GPIOD_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIODLPEN)) -#define __HAL_RCC_GPIOE_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOELPEN)) -#define __HAL_RCC_GPIOF_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOFLPEN)) -#define __HAL_RCC_GPIOG_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOGLPEN)) -#define __HAL_RCC_GPIOI_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOILPEN)) -#define __HAL_RCC_SRAM2_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM2LPEN)) -#define __HAL_RCC_ETHMAC_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_ETHMACLPEN)) -#define __HAL_RCC_ETHMACTX_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_ETHMACTXLPEN)) -#define __HAL_RCC_ETHMACRX_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_ETHMACRXLPEN)) -#define __HAL_RCC_ETHMACPTP_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_ETHMACPTPLPEN)) -#define __HAL_RCC_USB_OTG_HS_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_OTGHSLPEN)) -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_OTGHSULPILPEN)) -#define __HAL_RCC_CRC_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_CRCLPEN)) -#define __HAL_RCC_FLITF_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_FLITFLPEN)) -#define __HAL_RCC_SRAM1_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM1LPEN)) -#define __HAL_RCC_BKPSRAM_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_BKPSRAMLPEN)) - -#define __HAL_RCC_GPIOD_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIODLPEN)) -#define __HAL_RCC_GPIOE_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOELPEN)) -#define __HAL_RCC_GPIOF_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOFLPEN)) -#define __HAL_RCC_GPIOG_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOGLPEN)) -#define __HAL_RCC_GPIOI_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOILPEN)) -#define __HAL_RCC_SRAM2_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_SRAM2LPEN)) -#define __HAL_RCC_ETHMAC_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_ETHMACLPEN)) -#define __HAL_RCC_ETHMACTX_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_ETHMACTXLPEN)) -#define __HAL_RCC_ETHMACRX_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_ETHMACRXLPEN)) -#define __HAL_RCC_ETHMACPTP_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_ETHMACPTPLPEN)) -#define __HAL_RCC_USB_OTG_HS_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_OTGHSLPEN)) -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_OTGHSULPILPEN)) -#define __HAL_RCC_CRC_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_CRCLPEN)) -#define __HAL_RCC_FLITF_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_FLITFLPEN)) -#define __HAL_RCC_SRAM1_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_SRAM1LPEN)) -#define __HAL_RCC_BKPSRAM_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_BKPSRAMLPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_LowPower_Enable_Disable AHB2 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB2 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_OTGFSLPEN)) -#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_OTGFSLPEN)) - -#define __HAL_RCC_RNG_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_RNGLPEN)) -#define __HAL_RCC_RNG_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_RNGLPEN)) - -#if defined(STM32F407xx)|| defined(STM32F417xx) -#define __HAL_RCC_DCMI_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_DCMILPEN)) -#define __HAL_RCC_DCMI_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_DCMILPEN)) -#endif /* STM32F407xx || STM32F417xx */ - -#if defined(STM32F415xx) || defined(STM32F417xx) -#define __HAL_RCC_CRYP_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_CRYPLPEN)) -#define __HAL_RCC_HASH_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_HASHLPEN)) - -#define __HAL_RCC_CRYP_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_CRYPLPEN)) -#define __HAL_RCC_HASH_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_HASHLPEN)) -#endif /* STM32F415xx || STM32F417xx */ -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_LowPower_Enable_Disable AHB3 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB3 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_FSMC_CLK_SLEEP_ENABLE() (RCC->AHB3LPENR |= (RCC_AHB3LPENR_FSMCLPEN)) -#define __HAL_RCC_FSMC_CLK_SLEEP_DISABLE() (RCC->AHB3LPENR &= ~(RCC_AHB3LPENR_FSMCLPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_LowPower_Enable_Disable APB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB1 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_TIM6_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM6LPEN)) -#define __HAL_RCC_TIM7_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM7LPEN)) -#define __HAL_RCC_TIM12_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM12LPEN)) -#define __HAL_RCC_TIM13_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM13LPEN)) -#define __HAL_RCC_TIM14_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM14LPEN)) -#define __HAL_RCC_USART3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_USART3LPEN)) -#define __HAL_RCC_UART4_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART4LPEN)) -#define __HAL_RCC_UART5_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART5LPEN)) -#define __HAL_RCC_CAN1_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_CAN1LPEN)) -#define __HAL_RCC_CAN2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_CAN2LPEN)) -#define __HAL_RCC_DAC_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_DACLPEN)) -#define __HAL_RCC_TIM2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM2LPEN)) -#define __HAL_RCC_TIM3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM3LPEN)) -#define __HAL_RCC_TIM4_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM4LPEN)) -#define __HAL_RCC_SPI3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_SPI3LPEN)) -#define __HAL_RCC_I2C3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_I2C3LPEN)) - -#define __HAL_RCC_TIM2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM2LPEN)) -#define __HAL_RCC_TIM3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM3LPEN)) -#define __HAL_RCC_TIM4_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM4LPEN)) -#define __HAL_RCC_SPI3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_SPI3LPEN)) -#define __HAL_RCC_I2C3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_I2C3LPEN)) -#define __HAL_RCC_TIM6_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM6LPEN)) -#define __HAL_RCC_TIM7_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM7LPEN)) -#define __HAL_RCC_TIM12_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM12LPEN)) -#define __HAL_RCC_TIM13_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM13LPEN)) -#define __HAL_RCC_TIM14_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM14LPEN)) -#define __HAL_RCC_USART3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_USART3LPEN)) -#define __HAL_RCC_UART4_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART4LPEN)) -#define __HAL_RCC_UART5_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART5LPEN)) -#define __HAL_RCC_CAN1_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_CAN1LPEN)) -#define __HAL_RCC_CAN2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_CAN2LPEN)) -#define __HAL_RCC_DAC_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_DACLPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_LowPower_Enable_Disable APB2 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB2 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_TIM8_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_TIM8LPEN)) -#define __HAL_RCC_ADC2_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_ADC2LPEN)) -#define __HAL_RCC_ADC3_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_ADC3LPEN)) -#define __HAL_RCC_SDIO_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SDIOLPEN)) -#define __HAL_RCC_SPI4_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI4LPEN)) -#define __HAL_RCC_TIM10_CLK_SLEEP_ENABLE()(RCC->APB2LPENR |= (RCC_APB2LPENR_TIM10LPEN)) - -#define __HAL_RCC_SDIO_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SDIOLPEN)) -#define __HAL_RCC_SPI4_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI4LPEN)) -#define __HAL_RCC_TIM10_CLK_SLEEP_DISABLE()(RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM10LPEN)) -#define __HAL_RCC_TIM8_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM8LPEN)) -#define __HAL_RCC_ADC2_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_ADC2LPEN)) -#define __HAL_RCC_ADC3_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_ADC3LPEN)) -/** - * @} - */ -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ -/*----------------------------------------------------------------------------*/ - -/*------------------------- STM32F401xE/STM32F401xC --------------------------*/ -#if defined(STM32F401xC) || defined(STM32F401xE) -/** @defgroup RCCEx_AHB1_Clock_Enable_Disable AHB1 Peripheral Clock Enable Disable - * @brief Enable or disable the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_GPIOD_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOE_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CRC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CCMDATARAMEN_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CCMDATARAMEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CCMDATARAMEN);\ - UNUSED(tmpreg); \ - } while(0U) - -#define __HAL_RCC_GPIOD_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIODEN)) -#define __HAL_RCC_GPIOE_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOEEN)) -#define __HAL_RCC_CRC_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CRCEN)) -#define __HAL_RCC_CCMDATARAMEN_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CCMDATARAMEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_Peripheral_Clock_Enable_Disable_Status AHB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_GPIOD_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) != RESET) -#define __HAL_RCC_GPIOE_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) != RESET) -#define __HAL_RCC_CRC_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) != RESET) -#define __HAL_RCC_CCMDATARAMEN_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CCMDATARAMEN)) != RESET) - -#define __HAL_RCC_GPIOD_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) == RESET) -#define __HAL_RCC_GPIOE_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) == RESET) -#define __HAL_RCC_CRC_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) == RESET) -#define __HAL_RCC_CCMDATARAMEN_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CCMDATARAMEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Clock_Enable_Disable AHB2 Peripheral Clock Enable Disable - * @brief Enable or disable the AHB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_USB_OTG_FS_CLK_ENABLE() do {(RCC->AHB2ENR |= (RCC_AHB2ENR_OTGFSEN));\ - __HAL_RCC_SYSCFG_CLK_ENABLE();\ - }while(0U) - -#define __HAL_RCC_USB_OTG_FS_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_OTGFSEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Peripheral_Clock_Enable_Disable_Status AHB2 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_USB_OTG_FS_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) != RESET) -#define __HAL_RCC_USB_OTG_FS_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCC_APB1_Clock_Enable_Disable APB1 Peripheral Clock Enable Disable - * @brief Enable or disable the Low Speed APB (APB1) peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_I2C3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM2EN)) -#define __HAL_RCC_TIM3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM3EN)) -#define __HAL_RCC_TIM4_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM4EN)) -#define __HAL_RCC_SPI3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_SPI3EN)) -#define __HAL_RCC_I2C3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_I2C3EN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Peripheral_Clock_Enable_Disable_Status APB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) != RESET) -#define __HAL_RCC_TIM3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) != RESET) -#define __HAL_RCC_TIM4_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) != RESET) -#define __HAL_RCC_SPI3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) != RESET) -#define __HAL_RCC_I2C3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) != RESET) - -#define __HAL_RCC_TIM2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) == RESET) -#define __HAL_RCC_TIM3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) == RESET) -#define __HAL_RCC_TIM4_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) == RESET) -#define __HAL_RCC_SPI3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) == RESET) -#define __HAL_RCC_I2C3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Clock_Enable_Disable APB2 Peripheral Clock Enable Disable - * @brief Enable or disable the High Speed APB (APB2) peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_SDIO_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM10_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ - UNUSED(tmpreg); \ - } while(0U) - -#define __HAL_RCC_SDIO_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SDIOEN)) -#define __HAL_RCC_SPI4_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI4EN)) -#define __HAL_RCC_TIM10_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM10EN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Peripheral_Clock_Enable_Disable_Status APB2 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_SDIO_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) != RESET) -#define __HAL_RCC_SPI4_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) != RESET) -#define __HAL_RCC_TIM10_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN)) != RESET) - -#define __HAL_RCC_SDIO_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) == RESET) -#define __HAL_RCC_SPI4_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) == RESET) -#define __HAL_RCC_TIM10_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN)) == RESET) -/** - * @} - */ -/** @defgroup RCCEx_AHB1_Force_Release_Reset AHB1 Force Release Reset - * @brief Force or release AHB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB1_FORCE_RESET() (RCC->AHB1RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_GPIOD_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIODRST)) -#define __HAL_RCC_GPIOE_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOERST)) -#define __HAL_RCC_CRC_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_CRCRST)) - -#define __HAL_RCC_AHB1_RELEASE_RESET() (RCC->AHB1RSTR = 0x00U) -#define __HAL_RCC_GPIOD_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIODRST)) -#define __HAL_RCC_GPIOE_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOERST)) -#define __HAL_RCC_CRC_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_CRCRST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Force_Release_Reset AHB2 Force Release Reset - * @brief Force or release AHB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB2_FORCE_RESET() (RCC->AHB2RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_USB_OTG_FS_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_OTGFSRST)) - -#define __HAL_RCC_AHB2_RELEASE_RESET() (RCC->AHB2RSTR = 0x00U) -#define __HAL_RCC_USB_OTG_FS_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_OTGFSRST)) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Force_Release_Reset APB1 Force Release Reset - * @brief Force or release APB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_APB1_FORCE_RESET() (RCC->APB1RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_TIM2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM2RST)) -#define __HAL_RCC_TIM3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM3RST)) -#define __HAL_RCC_TIM4_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM4RST)) -#define __HAL_RCC_SPI3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_SPI3RST)) -#define __HAL_RCC_I2C3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_I2C3RST)) - -#define __HAL_RCC_APB1_RELEASE_RESET() (RCC->APB1RSTR = 0x00U) -#define __HAL_RCC_TIM2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM2RST)) -#define __HAL_RCC_TIM3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM3RST)) -#define __HAL_RCC_TIM4_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM4RST)) -#define __HAL_RCC_SPI3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_SPI3RST)) -#define __HAL_RCC_I2C3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_I2C3RST)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Force_Release_Reset APB2 Force Release Reset - * @brief Force or release APB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_APB2_FORCE_RESET() (RCC->APB2RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_SDIO_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SDIORST)) -#define __HAL_RCC_SPI4_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI4RST)) -#define __HAL_RCC_TIM10_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM10RST)) - -#define __HAL_RCC_APB2_RELEASE_RESET() (RCC->APB2RSTR = 0x00U) -#define __HAL_RCC_SDIO_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SDIORST)) -#define __HAL_RCC_SPI4_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI4RST)) -#define __HAL_RCC_TIM10_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM10RST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_Force_Release_Reset AHB3 Force Release Reset - * @brief Force or release AHB3 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB3_FORCE_RESET() (RCC->AHB3RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_AHB3_RELEASE_RESET() (RCC->AHB3RSTR = 0x00U) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_LowPower_Enable_Disable AHB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB1 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_GPIOD_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIODLPEN)) -#define __HAL_RCC_GPIOE_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOELPEN)) -#define __HAL_RCC_CRC_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_CRCLPEN)) -#define __HAL_RCC_FLITF_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_FLITFLPEN)) -#define __HAL_RCC_SRAM1_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM1LPEN)) - -#define __HAL_RCC_GPIOD_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIODLPEN)) -#define __HAL_RCC_GPIOE_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOELPEN)) -#define __HAL_RCC_CRC_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_CRCLPEN)) -#define __HAL_RCC_FLITF_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_FLITFLPEN)) -#define __HAL_RCC_SRAM1_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_SRAM1LPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_LowPower_Enable_Disable AHB2 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB2 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_OTGFSLPEN)) - -#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_OTGFSLPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_LowPower_Enable_Disable APB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB1 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_TIM2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM2LPEN)) -#define __HAL_RCC_TIM3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM3LPEN)) -#define __HAL_RCC_TIM4_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM4LPEN)) -#define __HAL_RCC_SPI3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_SPI3LPEN)) -#define __HAL_RCC_I2C3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_I2C3LPEN)) - -#define __HAL_RCC_TIM2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM2LPEN)) -#define __HAL_RCC_TIM3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM3LPEN)) -#define __HAL_RCC_TIM4_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM4LPEN)) -#define __HAL_RCC_SPI3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_SPI3LPEN)) -#define __HAL_RCC_I2C3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_I2C3LPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_LowPower_Enable_Disable APB2 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB2 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_SDIO_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SDIOLPEN)) -#define __HAL_RCC_SPI4_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI4LPEN)) -#define __HAL_RCC_TIM10_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_TIM10LPEN)) - -#define __HAL_RCC_SDIO_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SDIOLPEN)) -#define __HAL_RCC_SPI4_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI4LPEN)) -#define __HAL_RCC_TIM10_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM10LPEN)) -/** - * @} - */ -#endif /* STM32F401xC || STM32F401xE*/ -/*----------------------------------------------------------------------------*/ - -/*-------------------------------- STM32F410xx -------------------------------*/ -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -/** @defgroup RCCEx_AHB1_Clock_Enable_Disable AHB1 Peripheral Clock Enable Disable - * @brief Enables or disables the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_CRC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_RNG_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_RNGEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_RNGEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CRC_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CRCEN)) -#define __HAL_RCC_RNG_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_RNGEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_Peripheral_Clock_Enable_Disable_Status AHB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_CRC_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) != RESET) -#define __HAL_RCC_RNG_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_RNGEN)) != RESET) - -#define __HAL_RCC_CRC_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) == RESET) -#define __HAL_RCC_RNG_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_RNGEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Clock_Enable_Disable APB1 Peripheral Clock Enable Disable - * @brief Enable or disable the High Speed APB (APB1) peripheral clock. - * @{ - */ -#define __HAL_RCC_TIM6_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM6EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM6EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_LPTIM1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_LPTIM1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_LPTIM1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_RTCAPB_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_RTCAPBEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_RTCAPBEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_FMPI2C1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_FMPI2C1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_FMPI2C1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_DAC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_DACEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_DACEN);\ - UNUSED(tmpreg); \ - } while(0U) - -#define __HAL_RCC_TIM6_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM6EN)) -#define __HAL_RCC_RTCAPB_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_RTCAPBEN)) -#define __HAL_RCC_LPTIM1_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_LPTIM1EN)) -#define __HAL_RCC_FMPI2C1_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_FMPI2C1EN)) -#define __HAL_RCC_DAC_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_DACEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Peripheral_Clock_Enable_Disable_Status APB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM6_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM6EN)) != RESET) -#define __HAL_RCC_RTCAPB_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_RTCAPBEN)) != RESET) -#define __HAL_RCC_LPTIM1_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_LPTIM1EN)) != RESET) -#define __HAL_RCC_FMPI2C1_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_FMPI2C1EN)) != RESET) -#define __HAL_RCC_DAC_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_DACEN)) != RESET) - -#define __HAL_RCC_TIM6_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM6EN)) == RESET) -#define __HAL_RCC_RTCAPB_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_RTCAPBEN)) == RESET) -#define __HAL_RCC_LPTIM1_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_LPTIM1EN)) == RESET) -#define __HAL_RCC_FMPI2C1_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_FMPI2C1EN)) == RESET) -#define __HAL_RCC_DAC_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_DACEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Clock_Enable_Disable APB2 Peripheral Clock Enable Disable - * @brief Enable or disable the High Speed APB (APB2) peripheral clock. - * @{ - */ -#define __HAL_RCC_SPI5_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI5EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI5EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_EXTIT_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_EXTITEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_EXTITEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI5_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI5EN)) -#define __HAL_RCC_EXTIT_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_EXTITEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Peripheral_Clock_Enable_Disable_Status APB2 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_SPI5_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI5EN)) != RESET) -#define __HAL_RCC_EXTIT_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_EXTITEN)) != RESET) - -#define __HAL_RCC_SPI5_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI5EN)) == RESET) -#define __HAL_RCC_EXTIT_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_EXTITEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_Force_Release_Reset AHB1 Force Release Reset - * @brief Force or release AHB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_CRC_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_CRCRST)) -#define __HAL_RCC_RNG_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_RNGRST)) -#define __HAL_RCC_CRC_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_CRCRST)) -#define __HAL_RCC_RNG_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_RNGRST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Force_Release_Reset AHB2 Force Release Reset - * @brief Force or release AHB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB2_FORCE_RESET() -#define __HAL_RCC_AHB2_RELEASE_RESET() -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_Force_Release_Reset AHB3 Force Release Reset - * @brief Force or release AHB3 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB3_FORCE_RESET() -#define __HAL_RCC_AHB3_RELEASE_RESET() -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Force_Release_Reset APB1 Force Release Reset - * @brief Force or release APB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_TIM6_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM6RST)) -#define __HAL_RCC_LPTIM1_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_LPTIM1RST)) -#define __HAL_RCC_FMPI2C1_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_FMPI2C1RST)) -#define __HAL_RCC_DAC_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_DACRST)) - -#define __HAL_RCC_TIM6_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM6RST)) -#define __HAL_RCC_LPTIM1_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_LPTIM1RST)) -#define __HAL_RCC_FMPI2C1_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_FMPI2C1RST)) -#define __HAL_RCC_DAC_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_DACRST)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Force_Release_Reset APB2 Force Release Reset - * @brief Force or release APB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_SPI5_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI5RST)) -#define __HAL_RCC_SPI5_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI5RST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_LowPower_Enable_Disable AHB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB1 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_RNG_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_RNGLPEN)) -#define __HAL_RCC_CRC_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_CRCLPEN)) -#define __HAL_RCC_FLITF_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_FLITFLPEN)) -#define __HAL_RCC_SRAM1_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM1LPEN)) - -#define __HAL_RCC_RNG_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_RNGLPEN)) -#define __HAL_RCC_CRC_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_CRCLPEN)) -#define __HAL_RCC_FLITF_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_FLITFLPEN)) -#define __HAL_RCC_SRAM1_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_SRAM1LPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_LowPower_Enable_Disable APB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB1 peripheral clock during Low Power (Sleep) mode. - * @{ - */ -#define __HAL_RCC_TIM6_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM6LPEN)) -#define __HAL_RCC_LPTIM1_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_LPTIM1LPEN)) -#define __HAL_RCC_RTCAPB_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_RTCAPBLPEN)) -#define __HAL_RCC_FMPI2C1_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_FMPI2C1LPEN)) -#define __HAL_RCC_DAC_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_DACLPEN)) - -#define __HAL_RCC_TIM6_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM6LPEN)) -#define __HAL_RCC_LPTIM1_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_LPTIM1LPEN)) -#define __HAL_RCC_RTCAPB_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_RTCAPBLPEN)) -#define __HAL_RCC_FMPI2C1_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_FMPI2C1LPEN)) -#define __HAL_RCC_DAC_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_DACLPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_LowPower_Enable_Disable APB2 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB2 peripheral clock during Low Power (Sleep) mode. - * @{ - */ -#define __HAL_RCC_SPI5_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI5LPEN)) -#define __HAL_RCC_EXTIT_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_EXTITLPEN)) -#define __HAL_RCC_SPI5_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI5LPEN)) -#define __HAL_RCC_EXTIT_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_EXTITLPEN)) -/** - * @} - */ - -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ -/*----------------------------------------------------------------------------*/ - -/*-------------------------------- STM32F411xx -------------------------------*/ -#if defined(STM32F411xE) -/** @defgroup RCCEx_AHB1_Clock_Enable_Disable AHB1 Peripheral Clock Enable Disable - * @brief Enables or disables the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_CCMDATARAMEN_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CCMDATARAMEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CCMDATARAMEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOD_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOE_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CRC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOD_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIODEN)) -#define __HAL_RCC_GPIOE_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOEEN)) -#define __HAL_RCC_CCMDATARAMEN_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CCMDATARAMEN)) -#define __HAL_RCC_CRC_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CRCEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_Peripheral_Clock_Enable_Disable_Status AHB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_GPIOD_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) != RESET) -#define __HAL_RCC_GPIOE_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) != RESET) -#define __HAL_RCC_CCMDATARAMEN_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CCMDATARAMEN)) != RESET) -#define __HAL_RCC_CRC_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) != RESET) - -#define __HAL_RCC_GPIOD_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) == RESET) -#define __HAL_RCC_GPIOE_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) == RESET) -#define __HAL_RCC_CCMDATARAMEN_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CCMDATARAMEN)) == RESET) -#define __HAL_RCC_CRC_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEX_AHB2_Clock_Enable_Disable AHB2 Peripheral Clock Enable Disable - * @brief Enable or disable the AHB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_USB_OTG_FS_CLK_ENABLE() do {(RCC->AHB2ENR |= (RCC_AHB2ENR_OTGFSEN));\ - __HAL_RCC_SYSCFG_CLK_ENABLE();\ - }while(0U) - -#define __HAL_RCC_USB_OTG_FS_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_OTGFSEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Peripheral_Clock_Enable_Disable_Status AHB2 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_USB_OTG_FS_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) != RESET) -#define __HAL_RCC_USB_OTG_FS_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Clock_Enable_Disable APB1 Peripheral Clock Enable Disable - * @brief Enable or disable the Low Speed APB (APB1) peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_I2C3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM2EN)) -#define __HAL_RCC_TIM3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM3EN)) -#define __HAL_RCC_TIM4_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM4EN)) -#define __HAL_RCC_SPI3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_SPI3EN)) -#define __HAL_RCC_I2C3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_I2C3EN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Peripheral_Clock_Enable_Disable_Status APB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) != RESET) -#define __HAL_RCC_TIM3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) != RESET) -#define __HAL_RCC_TIM4_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) != RESET) -#define __HAL_RCC_SPI3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) != RESET) -#define __HAL_RCC_I2C3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) != RESET) - -#define __HAL_RCC_TIM2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) == RESET) -#define __HAL_RCC_TIM3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) == RESET) -#define __HAL_RCC_TIM4_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) == RESET) -#define __HAL_RCC_SPI3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) == RESET) -#define __HAL_RCC_I2C3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Clock_Enable_Disable APB2 Peripheral Clock Enable Disable - * @brief Enable or disable the High Speed APB (APB2) peripheral clock. - * @{ - */ -#define __HAL_RCC_SPI5_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI5EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI5EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SDIO_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM10_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SDIO_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SDIOEN)) -#define __HAL_RCC_SPI4_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI4EN)) -#define __HAL_RCC_TIM10_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM10EN)) -#define __HAL_RCC_SPI5_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI5EN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Peripheral_Clock_Enable_Disable_Status APB2 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_SDIO_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) != RESET) -#define __HAL_RCC_SPI4_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) != RESET) -#define __HAL_RCC_TIM10_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN)) != RESET) -#define __HAL_RCC_SPI5_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI5EN)) != RESET) - -#define __HAL_RCC_SDIO_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) == RESET) -#define __HAL_RCC_SPI4_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) == RESET) -#define __HAL_RCC_TIM10_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN)) == RESET) -#define __HAL_RCC_SPI5_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI5EN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_Force_Release_Reset AHB1 Force Release Reset - * @brief Force or release AHB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_GPIOD_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIODRST)) -#define __HAL_RCC_GPIOE_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOERST)) -#define __HAL_RCC_CRC_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_CRCRST)) - -#define __HAL_RCC_GPIOD_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIODRST)) -#define __HAL_RCC_GPIOE_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOERST)) -#define __HAL_RCC_CRC_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_CRCRST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Force_Release_Reset AHB2 Force Release Reset - * @brief Force or release AHB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB2_FORCE_RESET() (RCC->AHB2RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_USB_OTG_FS_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_OTGFSRST)) - -#define __HAL_RCC_AHB2_RELEASE_RESET() (RCC->AHB2RSTR = 0x00U) -#define __HAL_RCC_USB_OTG_FS_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_OTGFSRST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_Force_Release_Reset AHB3 Force Release Reset - * @brief Force or release AHB3 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB3_FORCE_RESET() (RCC->AHB3RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_AHB3_RELEASE_RESET() (RCC->AHB3RSTR = 0x00U) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Force_Release_Reset APB1 Force Release Reset - * @brief Force or release APB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_TIM2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM2RST)) -#define __HAL_RCC_TIM3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM3RST)) -#define __HAL_RCC_TIM4_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM4RST)) -#define __HAL_RCC_SPI3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_SPI3RST)) -#define __HAL_RCC_I2C3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_I2C3RST)) - -#define __HAL_RCC_TIM2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM2RST)) -#define __HAL_RCC_TIM3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM3RST)) -#define __HAL_RCC_TIM4_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM4RST)) -#define __HAL_RCC_SPI3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_SPI3RST)) -#define __HAL_RCC_I2C3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_I2C3RST)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Force_Release_Reset APB2 Force Release Reset - * @brief Force or release APB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_SPI5_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI5RST)) -#define __HAL_RCC_SDIO_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SDIORST)) -#define __HAL_RCC_SPI4_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI4RST)) -#define __HAL_RCC_TIM10_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM10RST)) - -#define __HAL_RCC_SDIO_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SDIORST)) -#define __HAL_RCC_SPI4_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI4RST)) -#define __HAL_RCC_TIM10_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM10RST)) -#define __HAL_RCC_SPI5_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI5RST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_LowPower_Enable_Disable AHB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB1 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_GPIOD_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIODLPEN)) -#define __HAL_RCC_GPIOE_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOELPEN)) -#define __HAL_RCC_CRC_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_CRCLPEN)) -#define __HAL_RCC_FLITF_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_FLITFLPEN)) -#define __HAL_RCC_SRAM1_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM1LPEN)) - -#define __HAL_RCC_GPIOD_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIODLPEN)) -#define __HAL_RCC_GPIOE_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOELPEN)) -#define __HAL_RCC_CRC_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_CRCLPEN)) -#define __HAL_RCC_FLITF_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_FLITFLPEN)) -#define __HAL_RCC_SRAM1_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_SRAM1LPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_LowPower_Enable_Disable AHB2 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB2 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_OTGFSLPEN)) -#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_OTGFSLPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_LowPower_Enable_Disable APB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB1 peripheral clock during Low Power (Sleep) mode. - * @{ - */ -#define __HAL_RCC_TIM2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM2LPEN)) -#define __HAL_RCC_TIM3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM3LPEN)) -#define __HAL_RCC_TIM4_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM4LPEN)) -#define __HAL_RCC_SPI3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_SPI3LPEN)) -#define __HAL_RCC_I2C3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_I2C3LPEN)) - -#define __HAL_RCC_TIM2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM2LPEN)) -#define __HAL_RCC_TIM3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM3LPEN)) -#define __HAL_RCC_TIM4_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM4LPEN)) -#define __HAL_RCC_SPI3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_SPI3LPEN)) -#define __HAL_RCC_I2C3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_I2C3LPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_LowPower_Enable_Disable APB2 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB2 peripheral clock during Low Power (Sleep) mode. - * @{ - */ -#define __HAL_RCC_SPI5_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI5LPEN)) -#define __HAL_RCC_SDIO_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SDIOLPEN)) -#define __HAL_RCC_SPI4_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI4LPEN)) -#define __HAL_RCC_TIM10_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_TIM10LPEN)) - -#define __HAL_RCC_SDIO_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SDIOLPEN)) -#define __HAL_RCC_SPI4_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI4LPEN)) -#define __HAL_RCC_TIM10_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM10LPEN)) -#define __HAL_RCC_SPI5_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI5LPEN)) -/** - * @} - */ -#endif /* STM32F411xE */ -/*----------------------------------------------------------------------------*/ - -/*---------------------------------- STM32F446xx -----------------------------*/ -#if defined(STM32F446xx) -/** @defgroup RCCEx_AHB1_Clock_Enable_Disable AHB1 Peripheral Clock Enable Disable - * @brief Enables or disables the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_BKPSRAM_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_BKPSRAMEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_BKPSRAMEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CCMDATARAMEN_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CCMDATARAMEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CCMDATARAMEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CRC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOD_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOE_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOF_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOFEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOFEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOG_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOGEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOGEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_USB_OTG_HS_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSULPIEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_OTGHSULPIEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOD_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIODEN)) -#define __HAL_RCC_GPIOE_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOEEN)) -#define __HAL_RCC_GPIOF_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOFEN)) -#define __HAL_RCC_GPIOG_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOGEN)) -#define __HAL_RCC_USB_OTG_HS_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_OTGHSEN)) -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_OTGHSULPIEN)) -#define __HAL_RCC_BKPSRAM_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_BKPSRAMEN)) -#define __HAL_RCC_CCMDATARAMEN_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CCMDATARAMEN)) -#define __HAL_RCC_CRC_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CRCEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_Peripheral_Clock_Enable_Disable_Status AHB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_GPIOD_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) != RESET) -#define __HAL_RCC_GPIOE_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) != RESET) -#define __HAL_RCC_GPIOF_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOFEN)) != RESET) -#define __HAL_RCC_GPIOG_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOGEN)) != RESET) -#define __HAL_RCC_USB_OTG_HS_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSEN)) != RESET) -#define __HAL_RCC_USB_OTG_HS_ULPI_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSULPIEN)) != RESET) -#define __HAL_RCC_BKPSRAM_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_BKPSRAMEN)) != RESET) -#define __HAL_RCC_CCMDATARAMEN_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CCMDATARAMEN))!= RESET) -#define __HAL_RCC_CRC_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) != RESET) - -#define __HAL_RCC_GPIOD_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) == RESET) -#define __HAL_RCC_GPIOE_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) == RESET) -#define __HAL_RCC_GPIOF_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOFEN)) == RESET) -#define __HAL_RCC_GPIOG_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOGEN)) == RESET) -#define __HAL_RCC_USB_OTG_HS_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSEN)) == RESET) -#define __HAL_RCC_USB_OTG_HS_ULPI_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_OTGHSULPIEN)) == RESET) -#define __HAL_RCC_BKPSRAM_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_BKPSRAMEN)) == RESET) -#define __HAL_RCC_CCMDATARAMEN_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CCMDATARAMEN)) == RESET) -#define __HAL_RCC_CRC_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Clock_Enable_Disable AHB2 Peripheral Clock Enable Disable - * @brief Enable or disable the AHB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_DCMI_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_DCMIEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_DCMIEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_DCMI_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_DCMIEN)) -#define __HAL_RCC_USB_OTG_FS_CLK_ENABLE() do {(RCC->AHB2ENR |= (RCC_AHB2ENR_OTGFSEN));\ - __HAL_RCC_SYSCFG_CLK_ENABLE();\ - }while(0U) - -#define __HAL_RCC_USB_OTG_FS_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_OTGFSEN)) - -#define __HAL_RCC_RNG_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_RNGEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_RNGEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_RNG_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_RNGEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Peripheral_Clock_Enable_Disable_Status AHB2 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_DCMI_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_DCMIEN)) != RESET) -#define __HAL_RCC_DCMI_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_DCMIEN)) == RESET) - -#define __HAL_RCC_USB_OTG_FS_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) != RESET) -#define __HAL_RCC_USB_OTG_FS_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) == RESET) - -#define __HAL_RCC_RNG_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_RNGEN)) != RESET) -#define __HAL_RCC_RNG_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_RNGEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_Clock_Enable_Disable AHB3 Peripheral Clock Enable Disable - * @brief Enables or disables the AHB3 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_FMC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FMCEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FMCEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_QSPI_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB3ENR, RCC_AHB3ENR_QSPIEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB3ENR, RCC_AHB3ENR_QSPIEN);\ - UNUSED(tmpreg); \ - } while(0U) - -#define __HAL_RCC_FMC_CLK_DISABLE() (RCC->AHB3ENR &= ~(RCC_AHB3ENR_FMCEN)) -#define __HAL_RCC_QSPI_CLK_DISABLE() (RCC->AHB3ENR &= ~(RCC_AHB3ENR_QSPIEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_Peripheral_Clock_Enable_Disable_Status AHB3 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB3 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_FMC_IS_CLK_ENABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_FMCEN)) != RESET) -#define __HAL_RCC_QSPI_IS_CLK_ENABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_QSPIEN)) != RESET) - -#define __HAL_RCC_FMC_IS_CLK_DISABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_FMCEN)) == RESET) -#define __HAL_RCC_QSPI_IS_CLK_DISABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_QSPIEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Clock_Enable_Disable APB1 Peripheral Clock Enable Disable - * @brief Enable or disable the Low Speed APB (APB1) peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM6_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM6EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM6EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM7_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM7EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM7EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM12_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM12EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM12EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM13_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM13EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM13EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM14_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM14EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM14EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPDIFRX_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_SPDIFRXEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_SPDIFRXEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_USART3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_USART3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_USART3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_UART4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_UART5_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART5EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART5EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_FMPI2C1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_FMPI2C1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_FMPI2C1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CAN1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CAN2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CEC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_CECEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_CECEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_DAC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_DACEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_DACEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_I2C3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM2EN)) -#define __HAL_RCC_TIM3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM3EN)) -#define __HAL_RCC_TIM4_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM4EN)) -#define __HAL_RCC_SPI3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_SPI3EN)) -#define __HAL_RCC_I2C3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_I2C3EN)) -#define __HAL_RCC_TIM6_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM6EN)) -#define __HAL_RCC_TIM7_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM7EN)) -#define __HAL_RCC_TIM12_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM12EN)) -#define __HAL_RCC_TIM13_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM13EN)) -#define __HAL_RCC_TIM14_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM14EN)) -#define __HAL_RCC_SPDIFRX_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_SPDIFRXEN)) -#define __HAL_RCC_USART3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_USART3EN)) -#define __HAL_RCC_UART4_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART4EN)) -#define __HAL_RCC_UART5_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART5EN)) -#define __HAL_RCC_FMPI2C1_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_FMPI2C1EN)) -#define __HAL_RCC_CAN1_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_CAN1EN)) -#define __HAL_RCC_CAN2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_CAN2EN)) -#define __HAL_RCC_CEC_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_CECEN)) -#define __HAL_RCC_DAC_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_DACEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Peripheral_Clock_Enable_Disable_Status APB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) != RESET) -#define __HAL_RCC_TIM3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) != RESET) -#define __HAL_RCC_TIM4_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) != RESET) -#define __HAL_RCC_SPI3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) != RESET) -#define __HAL_RCC_I2C3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) != RESET) -#define __HAL_RCC_TIM6_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM6EN)) != RESET) -#define __HAL_RCC_TIM7_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM7EN)) != RESET) -#define __HAL_RCC_TIM12_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM12EN)) != RESET) -#define __HAL_RCC_TIM13_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM13EN)) != RESET) -#define __HAL_RCC_TIM14_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM14EN)) != RESET) -#define __HAL_RCC_SPDIFRX_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPDIFRXEN)) != RESET) -#define __HAL_RCC_USART3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART3EN)) != RESET) -#define __HAL_RCC_UART4_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART4EN)) != RESET) -#define __HAL_RCC_UART5_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART5EN)) != RESET) -#define __HAL_RCC_FMPI2C1_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_FMPI2C1EN)) != RESET) -#define __HAL_RCC_CAN1_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN1EN)) != RESET) -#define __HAL_RCC_CAN2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN2EN)) != RESET) -#define __HAL_RCC_CEC_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CECEN)) != RESET) -#define __HAL_RCC_DAC_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_DACEN)) != RESET) - -#define __HAL_RCC_TIM2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) == RESET) -#define __HAL_RCC_TIM3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) == RESET) -#define __HAL_RCC_TIM4_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) == RESET) -#define __HAL_RCC_SPI3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) == RESET) -#define __HAL_RCC_I2C3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) == RESET) -#define __HAL_RCC_TIM6_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM6EN)) == RESET) -#define __HAL_RCC_TIM7_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM7EN)) == RESET) -#define __HAL_RCC_TIM12_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM12EN)) == RESET) -#define __HAL_RCC_TIM13_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM13EN)) == RESET) -#define __HAL_RCC_TIM14_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM14EN)) == RESET) -#define __HAL_RCC_SPDIFRX_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPDIFRXEN)) == RESET) -#define __HAL_RCC_USART3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART3EN)) == RESET) -#define __HAL_RCC_UART4_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART4EN)) == RESET) -#define __HAL_RCC_UART5_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART5EN)) == RESET) -#define __HAL_RCC_FMPI2C1_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_FMPI2C1EN)) == RESET) -#define __HAL_RCC_CAN1_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN1EN)) == RESET) -#define __HAL_RCC_CAN2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN2EN)) == RESET) -#define __HAL_RCC_CEC_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CECEN)) == RESET) -#define __HAL_RCC_DAC_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_DACEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Clock_Enable_Disable APB2 Peripheral Clock Enable Disable - * @brief Enable or disable the High Speed APB (APB2) peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM8_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM8EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM8EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ADC2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_ADC3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_ADC3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SAI1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SAI1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SAI1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SAI2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SAI2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SAI2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SDIO_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM10_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SDIO_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SDIOEN)) -#define __HAL_RCC_SPI4_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI4EN)) -#define __HAL_RCC_TIM10_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM10EN)) -#define __HAL_RCC_TIM8_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM8EN)) -#define __HAL_RCC_ADC2_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_ADC2EN)) -#define __HAL_RCC_ADC3_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_ADC3EN)) -#define __HAL_RCC_SAI1_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SAI1EN)) -#define __HAL_RCC_SAI2_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SAI2EN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Peripheral_Clock_Enable_Disable_Status APB2 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_SDIO_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) != RESET) -#define __HAL_RCC_SPI4_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) != RESET) -#define __HAL_RCC_TIM10_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN)) != RESET) -#define __HAL_RCC_TIM8_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM8EN)) != RESET) -#define __HAL_RCC_ADC2_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC2EN)) != RESET) -#define __HAL_RCC_ADC3_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC3EN)) != RESET) -#define __HAL_RCC_SAI1_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SAI1EN)) != RESET) -#define __HAL_RCC_SAI2_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SAI2EN)) != RESET) - -#define __HAL_RCC_SDIO_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) == RESET) -#define __HAL_RCC_SPI4_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) == RESET) -#define __HAL_RCC_TIM10_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN)) == RESET) -#define __HAL_RCC_TIM8_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM8EN)) == RESET) -#define __HAL_RCC_ADC2_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC2EN)) == RESET) -#define __HAL_RCC_ADC3_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_ADC3EN)) == RESET) -#define __HAL_RCC_SAI1_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SAI1EN)) == RESET) -#define __HAL_RCC_SAI2_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SAI2EN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_Force_Release_Reset AHB1 Force Release Reset - * @brief Force or release AHB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_GPIOD_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIODRST)) -#define __HAL_RCC_GPIOE_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOERST)) -#define __HAL_RCC_GPIOF_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOFRST)) -#define __HAL_RCC_GPIOG_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOGRST)) -#define __HAL_RCC_USB_OTG_HS_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_OTGHRST)) -#define __HAL_RCC_CRC_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_CRCRST)) - -#define __HAL_RCC_GPIOD_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIODRST)) -#define __HAL_RCC_GPIOE_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOERST)) -#define __HAL_RCC_GPIOF_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOFRST)) -#define __HAL_RCC_GPIOG_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOGRST)) -#define __HAL_RCC_USB_OTG_HS_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_OTGHRST)) -#define __HAL_RCC_CRC_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_CRCRST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Force_Release_Reset AHB2 Force Release Reset - * @brief Force or release AHB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB2_FORCE_RESET() (RCC->AHB2RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_USB_OTG_FS_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_OTGFSRST)) -#define __HAL_RCC_RNG_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_RNGRST)) -#define __HAL_RCC_DCMI_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_DCMIRST)) - -#define __HAL_RCC_AHB2_RELEASE_RESET() (RCC->AHB2RSTR = 0x00U) -#define __HAL_RCC_USB_OTG_FS_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_OTGFSRST)) -#define __HAL_RCC_RNG_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_RNGRST)) -#define __HAL_RCC_DCMI_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_DCMIRST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_Force_Release_Reset AHB3 Force Release Reset - * @brief Force or release AHB3 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB3_FORCE_RESET() (RCC->AHB3RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_AHB3_RELEASE_RESET() (RCC->AHB3RSTR = 0x00U) - -#define __HAL_RCC_FMC_FORCE_RESET() (RCC->AHB3RSTR |= (RCC_AHB3RSTR_FMCRST)) -#define __HAL_RCC_QSPI_FORCE_RESET() (RCC->AHB3RSTR |= (RCC_AHB3RSTR_QSPIRST)) - -#define __HAL_RCC_FMC_RELEASE_RESET() (RCC->AHB3RSTR &= ~(RCC_AHB3RSTR_FMCRST)) -#define __HAL_RCC_QSPI_RELEASE_RESET() (RCC->AHB3RSTR &= ~(RCC_AHB3RSTR_QSPIRST)) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Force_Release_Reset APB1 Force Release Reset - * @brief Force or release APB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_TIM6_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM6RST)) -#define __HAL_RCC_TIM7_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM7RST)) -#define __HAL_RCC_TIM12_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM12RST)) -#define __HAL_RCC_TIM13_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM13RST)) -#define __HAL_RCC_TIM14_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM14RST)) -#define __HAL_RCC_SPDIFRX_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_SPDIFRXRST)) -#define __HAL_RCC_USART3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_USART3RST)) -#define __HAL_RCC_UART4_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART4RST)) -#define __HAL_RCC_UART5_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART5RST)) -#define __HAL_RCC_FMPI2C1_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_FMPI2C1RST)) -#define __HAL_RCC_CAN1_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_CAN1RST)) -#define __HAL_RCC_CAN2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_CAN2RST)) -#define __HAL_RCC_CEC_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_CECRST)) -#define __HAL_RCC_DAC_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_DACRST)) -#define __HAL_RCC_TIM2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM2RST)) -#define __HAL_RCC_TIM3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM3RST)) -#define __HAL_RCC_TIM4_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM4RST)) -#define __HAL_RCC_SPI3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_SPI3RST)) -#define __HAL_RCC_I2C3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_I2C3RST)) - -#define __HAL_RCC_TIM2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM2RST)) -#define __HAL_RCC_TIM3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM3RST)) -#define __HAL_RCC_TIM4_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM4RST)) -#define __HAL_RCC_SPI3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_SPI3RST)) -#define __HAL_RCC_I2C3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_I2C3RST)) -#define __HAL_RCC_TIM6_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM6RST)) -#define __HAL_RCC_TIM7_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM7RST)) -#define __HAL_RCC_TIM12_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM12RST)) -#define __HAL_RCC_TIM13_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM13RST)) -#define __HAL_RCC_TIM14_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM14RST)) -#define __HAL_RCC_SPDIFRX_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_SPDIFRXRST)) -#define __HAL_RCC_USART3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_USART3RST)) -#define __HAL_RCC_UART4_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART4RST)) -#define __HAL_RCC_UART5_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART5RST)) -#define __HAL_RCC_FMPI2C1_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_FMPI2C1RST)) -#define __HAL_RCC_CAN1_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_CAN1RST)) -#define __HAL_RCC_CAN2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_CAN2RST)) -#define __HAL_RCC_CEC_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_CECRST)) -#define __HAL_RCC_DAC_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_DACRST)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Force_Release_Reset APB2 Force Release Reset - * @brief Force or release APB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_TIM8_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM8RST)) -#define __HAL_RCC_SAI1_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SAI1RST)) -#define __HAL_RCC_SAI2_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SAI2RST)) -#define __HAL_RCC_SDIO_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SDIORST)) -#define __HAL_RCC_SPI4_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI4RST)) -#define __HAL_RCC_TIM10_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM10RST)) - -#define __HAL_RCC_SDIO_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SDIORST)) -#define __HAL_RCC_SPI4_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI4RST)) -#define __HAL_RCC_TIM10_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM10RST)) -#define __HAL_RCC_TIM8_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM8RST)) -#define __HAL_RCC_SAI1_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SAI1RST)) -#define __HAL_RCC_SAI2_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SAI2RST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_LowPower_Enable_Disable AHB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB1 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_GPIOD_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIODLPEN)) -#define __HAL_RCC_GPIOE_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOELPEN)) -#define __HAL_RCC_GPIOF_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOFLPEN)) -#define __HAL_RCC_GPIOG_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOGLPEN)) -#define __HAL_RCC_SRAM2_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM2LPEN)) -#define __HAL_RCC_USB_OTG_HS_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_OTGHSLPEN)) -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_OTGHSULPILPEN)) -#define __HAL_RCC_CRC_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_CRCLPEN)) -#define __HAL_RCC_FLITF_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_FLITFLPEN)) -#define __HAL_RCC_SRAM1_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM1LPEN)) -#define __HAL_RCC_BKPSRAM_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_BKPSRAMLPEN)) - -#define __HAL_RCC_GPIOD_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIODLPEN)) -#define __HAL_RCC_GPIOE_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOELPEN)) -#define __HAL_RCC_GPIOF_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOFLPEN)) -#define __HAL_RCC_GPIOG_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOGLPEN)) -#define __HAL_RCC_SRAM2_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_SRAM2LPEN)) -#define __HAL_RCC_USB_OTG_HS_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_OTGHSLPEN)) -#define __HAL_RCC_USB_OTG_HS_ULPI_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_OTGHSULPILPEN)) -#define __HAL_RCC_CRC_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_CRCLPEN)) -#define __HAL_RCC_FLITF_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_FLITFLPEN)) -#define __HAL_RCC_SRAM1_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_SRAM1LPEN)) -#define __HAL_RCC_BKPSRAM_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_BKPSRAMLPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_LowPower_Enable_Disable AHB2 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB2 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_OTGFSLPEN)) -#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_OTGFSLPEN)) - -#define __HAL_RCC_RNG_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_RNGLPEN)) -#define __HAL_RCC_RNG_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_RNGLPEN)) - -#define __HAL_RCC_DCMI_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_DCMILPEN)) -#define __HAL_RCC_DCMI_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_DCMILPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_LowPower_Enable_Disable AHB3 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB3 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_FMC_CLK_SLEEP_ENABLE() (RCC->AHB3LPENR |= (RCC_AHB3LPENR_FMCLPEN)) -#define __HAL_RCC_QSPI_CLK_SLEEP_ENABLE() (RCC->AHB3LPENR |= (RCC_AHB3LPENR_QSPILPEN)) - -#define __HAL_RCC_FMC_CLK_SLEEP_DISABLE() (RCC->AHB3LPENR &= ~(RCC_AHB3LPENR_FMCLPEN)) -#define __HAL_RCC_QSPI_CLK_SLEEP_DISABLE() (RCC->AHB3LPENR &= ~(RCC_AHB3LPENR_QSPILPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB1_LowPower_Enable_Disable APB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB1 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_TIM6_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM6LPEN)) -#define __HAL_RCC_TIM7_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM7LPEN)) -#define __HAL_RCC_TIM12_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM12LPEN)) -#define __HAL_RCC_TIM13_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM13LPEN)) -#define __HAL_RCC_TIM14_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM14LPEN)) -#define __HAL_RCC_SPDIFRX_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_SPDIFRXLPEN)) -#define __HAL_RCC_USART3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_USART3LPEN)) -#define __HAL_RCC_UART4_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART4LPEN)) -#define __HAL_RCC_UART5_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART5LPEN)) -#define __HAL_RCC_FMPI2C1_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_FMPI2C1LPEN)) -#define __HAL_RCC_CAN1_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_CAN1LPEN)) -#define __HAL_RCC_CAN2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_CAN2LPEN)) -#define __HAL_RCC_CEC_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_CECLPEN)) -#define __HAL_RCC_DAC_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_DACLPEN)) -#define __HAL_RCC_TIM2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM2LPEN)) -#define __HAL_RCC_TIM3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM3LPEN)) -#define __HAL_RCC_TIM4_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM4LPEN)) -#define __HAL_RCC_SPI3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_SPI3LPEN)) -#define __HAL_RCC_I2C3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_I2C3LPEN)) - -#define __HAL_RCC_TIM2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM2LPEN)) -#define __HAL_RCC_TIM3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM3LPEN)) -#define __HAL_RCC_TIM4_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM4LPEN)) -#define __HAL_RCC_SPI3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_SPI3LPEN)) -#define __HAL_RCC_I2C3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_I2C3LPEN)) -#define __HAL_RCC_TIM6_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM6LPEN)) -#define __HAL_RCC_TIM7_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM7LPEN)) -#define __HAL_RCC_TIM12_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM12LPEN)) -#define __HAL_RCC_TIM13_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM13LPEN)) -#define __HAL_RCC_TIM14_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM14LPEN)) -#define __HAL_RCC_SPDIFRX_CLK_SLEEP_DISABLE()(RCC->APB1LPENR &= ~(RCC_APB1LPENR_SPDIFRXLPEN)) -#define __HAL_RCC_USART3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_USART3LPEN)) -#define __HAL_RCC_UART4_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART4LPEN)) -#define __HAL_RCC_UART5_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART5LPEN)) -#define __HAL_RCC_FMPI2C1_CLK_SLEEP_DISABLE()(RCC->APB1LPENR &= ~(RCC_APB1LPENR_FMPI2C1LPEN)) -#define __HAL_RCC_CAN1_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_CAN1LPEN)) -#define __HAL_RCC_CAN2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_CAN2LPEN)) -#define __HAL_RCC_CEC_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_CECLPEN)) -#define __HAL_RCC_DAC_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_DACLPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_APB2_LowPower_Enable_Disable APB2 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB2 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_TIM8_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_TIM8LPEN)) -#define __HAL_RCC_ADC2_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_ADC2LPEN)) -#define __HAL_RCC_ADC3_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_ADC3LPEN)) -#define __HAL_RCC_SAI1_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SAI1LPEN)) -#define __HAL_RCC_SAI2_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SAI2LPEN)) -#define __HAL_RCC_SDIO_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SDIOLPEN)) -#define __HAL_RCC_SPI4_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI4LPEN)) -#define __HAL_RCC_TIM10_CLK_SLEEP_ENABLE()(RCC->APB2LPENR |= (RCC_APB2LPENR_TIM10LPEN)) - -#define __HAL_RCC_SDIO_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SDIOLPEN)) -#define __HAL_RCC_SPI4_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI4LPEN)) -#define __HAL_RCC_TIM10_CLK_SLEEP_DISABLE()(RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM10LPEN)) -#define __HAL_RCC_TIM8_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM8LPEN)) -#define __HAL_RCC_ADC2_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_ADC2LPEN)) -#define __HAL_RCC_ADC3_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_ADC3LPEN)) -#define __HAL_RCC_SAI1_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SAI1LPEN)) -#define __HAL_RCC_SAI2_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SAI2LPEN)) -/** - * @} - */ - -#endif /* STM32F446xx */ -/*----------------------------------------------------------------------------*/ - -/*-------STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx-------*/ -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/** @defgroup RCCEx_AHB1_Clock_Enable_Disable AHB1 Peripheral Clock Enable Disable - * @brief Enables or disables the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#if defined(STM32F412Rx) || defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOD_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIODEN);\ - UNUSED(tmpreg); \ - } while(0U) -#endif /* STM32F412Rx || STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ -#if defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOE_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOEEN);\ - UNUSED(tmpreg); \ - } while(0U) -#endif /* STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ -#if defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOF_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOFEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOFEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_GPIOG_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOGEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_GPIOGEN);\ - UNUSED(tmpreg); \ - } while(0U) -#endif /* STM32F412Zx || STM32F413xx || STM32F423xx */ -#define __HAL_RCC_CRC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB1ENR, RCC_AHB1ENR_CRCEN);\ - UNUSED(tmpreg); \ - } while(0U) -#if defined(STM32F412Rx) || defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOD_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIODEN)) -#endif /* STM32F412Rx || STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ -#if defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOE_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOEEN)) -#endif /* STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ -#if defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOF_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOFEN)) -#define __HAL_RCC_GPIOG_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_GPIOGEN)) -#endif /* STM32F412Zx || STM32F413xx || STM32F423xx */ -#define __HAL_RCC_CRC_CLK_DISABLE() (RCC->AHB1ENR &= ~(RCC_AHB1ENR_CRCEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_Peripheral_Clock_Enable_Disable_Status AHB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#if defined(STM32F412Rx) || defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOD_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) != RESET) -#endif /* STM32F412Rx || STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ -#if defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOE_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) != RESET) -#endif /* STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ -#if defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOF_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOFEN)) != RESET) -#define __HAL_RCC_GPIOG_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOGEN)) != RESET) -#endif /* STM32F412Zx || STM32F413xx || STM32F423xx */ -#define __HAL_RCC_CRC_IS_CLK_ENABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) != RESET) - -#if defined(STM32F412Rx) || defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOD_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIODEN)) == RESET) -#endif /* STM32F412Rx || STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ -#if defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOE_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOEEN)) == RESET) -#endif /* STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ -#if defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOF_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOFEN)) == RESET) -#define __HAL_RCC_GPIOG_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_GPIOGEN)) == RESET) -#endif /* STM32F412Zx || STM32F413xx || STM32F423xx */ -#define __HAL_RCC_CRC_IS_CLK_DISABLED() ((RCC->AHB1ENR & (RCC_AHB1ENR_CRCEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Clock_Enable_Disable AHB2 Peripheral Clock Enable Disable - * @brief Enable or disable the AHB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#if defined(STM32F423xx) -#define __HAL_RCC_AES_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_AESEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_AESEN);\ - UNUSED(tmpreg); \ - } while(0U) - -#define __HAL_RCC_AES_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_AESEN)) -#endif /* STM32F423xx */ - -#define __HAL_RCC_RNG_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB2ENR, RCC_AHB2ENR_RNGEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB2ENR, RCC_AHB2ENR_RNGEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_RNG_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_RNGEN)) - -#define __HAL_RCC_USB_OTG_FS_CLK_ENABLE() do {(RCC->AHB2ENR |= (RCC_AHB2ENR_OTGFSEN));\ - __HAL_RCC_SYSCFG_CLK_ENABLE();\ - }while(0U) - -#define __HAL_RCC_USB_OTG_FS_CLK_DISABLE() (RCC->AHB2ENR &= ~(RCC_AHB2ENR_OTGFSEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Peripheral_Clock_Enable_Disable_Status AHB2 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#if defined(STM32F423xx) -#define __HAL_RCC_AES_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_AESEN)) != RESET) -#define __HAL_RCC_AES_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_AESEN)) == RESET) -#endif /* STM32F423xx */ - -#define __HAL_RCC_USB_OTG_FS_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) != RESET) -#define __HAL_RCC_USB_OTG_FS_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_OTGFSEN)) == RESET) - -#define __HAL_RCC_RNG_IS_CLK_ENABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_RNGEN)) != RESET) -#define __HAL_RCC_RNG_IS_CLK_DISABLED() ((RCC->AHB2ENR & (RCC_AHB2ENR_RNGEN)) == RESET) -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_Clock_Enable_Disable AHB3 Peripheral Clock Enable Disable - * @brief Enables or disables the AHB3 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_FSMC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FSMCEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB3ENR, RCC_AHB3ENR_FSMCEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_QSPI_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->AHB3ENR, RCC_AHB3ENR_QSPIEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->AHB3ENR, RCC_AHB3ENR_QSPIEN);\ - UNUSED(tmpreg); \ - } while(0U) - -#define __HAL_RCC_FSMC_CLK_DISABLE() (RCC->AHB3ENR &= ~(RCC_AHB3ENR_FSMCEN)) -#define __HAL_RCC_QSPI_CLK_DISABLE() (RCC->AHB3ENR &= ~(RCC_AHB3ENR_QSPIEN)) -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F413xx || STM32F423xx */ -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_Peripheral_Clock_Enable_Disable_Status AHB3 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the AHB3 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_FSMC_IS_CLK_ENABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_FSMCEN)) != RESET) -#define __HAL_RCC_QSPI_IS_CLK_ENABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_QSPIEN)) != RESET) - -#define __HAL_RCC_FSMC_IS_CLK_DISABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_FSMCEN)) == RESET) -#define __HAL_RCC_QSPI_IS_CLK_DISABLED() ((RCC->AHB3ENR & (RCC_AHB3ENR_QSPIEN)) == RESET) -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F413xx || STM32F423xx */ - -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Clock_Enable_Disable APB1 Peripheral Clock Enable Disable - * @brief Enable or disable the Low Speed APB (APB1) peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM6_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM6EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM6EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM7_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM7EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM7EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM12_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM12EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM12EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM13_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM13EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM13EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM14_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM14EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM14EN);\ - UNUSED(tmpreg); \ - } while(0U) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_LPTIM1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_LPTIM1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_LPTIM1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_RTCAPB_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_RTCAPBEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_RTCAPBEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_USART3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_USART3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_USART3EN);\ - UNUSED(tmpreg); \ - } while(0U) - -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_UART5_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART5EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART5EN);\ - UNUSED(tmpreg); \ - } while(0U) -#endif /* STM32F413xx || STM32F423xx */ - -#define __HAL_RCC_FMPI2C1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_FMPI2C1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_FMPI2C1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CAN1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_CAN2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_CAN3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_CAN3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_TIM2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_TIM4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_SPI3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_I2C3_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_I2C3EN);\ - UNUSED(tmpreg); \ - } while(0U) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_DAC_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_DACEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_DACEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_UART7_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART7EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART7EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_UART8_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_UART8EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB1ENR, RCC_APB1ENR_UART8EN);\ - UNUSED(tmpreg); \ - } while(0U) -#endif /* STM32F413xx || STM32F423xx */ - -#define __HAL_RCC_TIM2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM2EN)) -#define __HAL_RCC_TIM3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM3EN)) -#define __HAL_RCC_TIM4_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM4EN)) -#define __HAL_RCC_TIM6_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM6EN)) -#define __HAL_RCC_TIM7_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM7EN)) -#define __HAL_RCC_TIM12_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM12EN)) -#define __HAL_RCC_TIM13_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM13EN)) -#define __HAL_RCC_TIM14_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_TIM14EN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_LPTIM1_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_LPTIM1EN)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_RTCAPB_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_RTCAPBEN)) -#define __HAL_RCC_SPI3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_SPI3EN)) -#define __HAL_RCC_USART3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_USART3EN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART4_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART4EN)) -#define __HAL_RCC_UART5_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART5EN)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_I2C3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_I2C3EN)) -#define __HAL_RCC_FMPI2C1_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_FMPI2C1EN)) -#define __HAL_RCC_CAN1_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_CAN1EN)) -#define __HAL_RCC_CAN2_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_CAN2EN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_CAN3_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_CAN3EN)) -#define __HAL_RCC_DAC_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_DACEN)) -#define __HAL_RCC_UART7_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART7EN)) -#define __HAL_RCC_UART8_CLK_DISABLE() (RCC->APB1ENR &= ~(RCC_APB1ENR_UART8EN)) -#endif /* STM32F413xx || STM32F423xx */ - -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Peripheral_Clock_Enable_Disable_Status APB1 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB1 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) != RESET) -#define __HAL_RCC_TIM3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) != RESET) -#define __HAL_RCC_TIM4_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) != RESET) -#define __HAL_RCC_TIM6_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM6EN)) != RESET) -#define __HAL_RCC_TIM7_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM7EN)) != RESET) -#define __HAL_RCC_TIM12_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM12EN)) != RESET) -#define __HAL_RCC_TIM13_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM13EN)) != RESET) -#define __HAL_RCC_TIM14_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM14EN)) != RESET) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_LPTIM1_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_LPTIM1EN)) != RESET) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_RTCAPB_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_RTCAPBEN)) != RESET) -#define __HAL_RCC_SPI3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) != RESET) -#define __HAL_RCC_USART3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART3EN)) != RESET) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART4_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART4EN)) != RESET) -#define __HAL_RCC_UART5_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART5EN)) != RESET) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_I2C3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) != RESET) -#define __HAL_RCC_FMPI2C1_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_FMPI2C1EN)) != RESET) -#define __HAL_RCC_CAN1_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN1EN))!= RESET) -#define __HAL_RCC_CAN2_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN2EN)) != RESET) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_CAN3_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN3EN)) != RESET) -#define __HAL_RCC_DAC_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_DACEN)) != RESET) -#define __HAL_RCC_UART7_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART7EN)) != RESET) -#define __HAL_RCC_UART8_IS_CLK_ENABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART8EN)) != RESET) -#endif /* STM32F413xx || STM32F423xx */ - -#define __HAL_RCC_TIM2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM2EN)) == RESET) -#define __HAL_RCC_TIM3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM3EN)) == RESET) -#define __HAL_RCC_TIM4_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM4EN)) == RESET) -#define __HAL_RCC_TIM6_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM6EN)) == RESET) -#define __HAL_RCC_TIM7_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM7EN)) == RESET) -#define __HAL_RCC_TIM12_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM12EN)) == RESET) -#define __HAL_RCC_TIM13_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM13EN)) == RESET) -#define __HAL_RCC_TIM14_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_TIM14EN)) == RESET) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_LPTIM1_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_LPTIM1EN)) == RESET) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_RTCAPB_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_RTCAPBEN)) == RESET) -#define __HAL_RCC_SPI3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_SPI3EN)) == RESET) -#define __HAL_RCC_USART3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_USART3EN)) == RESET) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART4_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART4EN)) == RESET) -#define __HAL_RCC_UART5_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART5EN)) == RESET) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_I2C3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_I2C3EN)) == RESET) -#define __HAL_RCC_FMPI2C1_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_FMPI2C1EN)) == RESET) -#define __HAL_RCC_CAN1_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN1EN)) == RESET) -#define __HAL_RCC_CAN2_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN2EN)) == RESET) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_CAN3_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_CAN3EN)) == RESET) -#define __HAL_RCC_DAC_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_DACEN)) == RESET) -#define __HAL_RCC_UART7_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART7EN)) == RESET) -#define __HAL_RCC_UART8_IS_CLK_DISABLED() ((RCC->APB1ENR & (RCC_APB1ENR_UART8EN)) == RESET) -#endif /* STM32F413xx || STM32F423xx */ -/** - * @} - */ -/** @defgroup RCCEx_APB2_Clock_Enable_Disable APB2 Peripheral Clock Enable Disable - * @brief Enable or disable the High Speed APB (APB2) peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM8_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM8EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM8EN);\ - UNUSED(tmpreg); \ - } while(0U) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART9_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_UART9EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_UART9EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_UART10_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_UART10EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_UART10EN);\ - UNUSED(tmpreg); \ - } while(0U) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_SDIO_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SDIOEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI4_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI4EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_EXTIT_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_EXTITEN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_EXTITEN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_TIM10_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_TIM10EN);\ - UNUSED(tmpreg); \ - } while(0U) -#define __HAL_RCC_SPI5_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI5EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SPI5EN);\ - UNUSED(tmpreg); \ - } while(0U) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_SAI1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_SAI1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_SAI1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_DFSDM1_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_DFSDM1EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_DFSDM1EN);\ - UNUSED(tmpreg); \ - } while(0U) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_DFSDM2_CLK_ENABLE() do { \ - __IO uint32_t tmpreg = 0x00U; \ - SET_BIT(RCC->APB2ENR, RCC_APB2ENR_DFSDM2EN);\ - /* Delay after an RCC peripheral clock enabling */ \ - tmpreg = READ_BIT(RCC->APB2ENR, RCC_APB2ENR_DFSDM2EN);\ - UNUSED(tmpreg); \ - } while(0U) -#endif /* STM32F413xx || STM32F423xx */ - -#define __HAL_RCC_TIM8_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM8EN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART9_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_UART9EN)) -#define __HAL_RCC_UART10_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_UART10EN)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_SDIO_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SDIOEN)) -#define __HAL_RCC_SPI4_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI4EN)) -#define __HAL_RCC_EXTIT_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_EXTITEN)) -#define __HAL_RCC_TIM10_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_TIM10EN)) -#define __HAL_RCC_SPI5_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SPI5EN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_SAI1_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_SAI1EN)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_DFSDM1_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_DFSDM1EN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_DFSDM2_CLK_DISABLE() (RCC->APB2ENR &= ~(RCC_APB2ENR_DFSDM2EN)) -#endif /* STM32F413xx || STM32F423xx */ -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Peripheral_Clock_Enable_Disable_Status APB2 Peripheral Clock Enable Disable Status - * @brief Get the enable or disable status of the APB2 peripheral clock. - * @note After reset, the peripheral clock (used for registers read/write access) - * is disabled and the application software has to enable this clock before - * using it. - * @{ - */ -#define __HAL_RCC_TIM8_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM8EN)) != RESET) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART9_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_UART9EN)) != RESET) -#define __HAL_RCC_UART10_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_UART10EN)) != RESET) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_SDIO_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) != RESET) -#define __HAL_RCC_SPI4_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) != RESET) -#define __HAL_RCC_EXTIT_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_EXTITEN)) != RESET) -#define __HAL_RCC_TIM10_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN)) != RESET) -#define __HAL_RCC_SPI5_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI5EN)) != RESET) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_SAI1_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SAI1EN)) != RESET) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_DFSDM1_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_DFSDM1EN)) != RESET) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_DFSDM2_IS_CLK_ENABLED() ((RCC->APB2ENR & (RCC_APB2ENR_DFSDM2EN)) != RESET) -#endif /* STM32F413xx || STM32F423xx */ - -#define __HAL_RCC_TIM8_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM8EN)) == RESET) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART9_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_UART9EN)) == RESET) -#define __HAL_RCC_UART10_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_UART10EN)) == RESET) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_SDIO_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SDIOEN)) == RESET) -#define __HAL_RCC_SPI4_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI4EN)) == RESET) -#define __HAL_RCC_EXTIT_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_EXTITEN)) == RESET) -#define __HAL_RCC_TIM10_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_TIM10EN)) == RESET) -#define __HAL_RCC_SPI5_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SPI5EN)) == RESET) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_SAI1_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_SAI1EN)) == RESET) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_DFSDM1_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_DFSDM1EN)) == RESET) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_DFSDM2_IS_CLK_DISABLED() ((RCC->APB2ENR & (RCC_APB2ENR_DFSDM2EN)) == RESET) -#endif /* STM32F413xx || STM32F423xx */ -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_Force_Release_Reset AHB1 Force Release Reset - * @brief Force or release AHB1 peripheral reset. - * @{ - */ -#if defined(STM32F412Rx) || defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOD_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIODRST)) -#endif /* STM32F412Rx || STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ -#if defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOE_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOERST)) -#endif /* STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ -#if defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOF_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOFRST)) -#define __HAL_RCC_GPIOG_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_GPIOGRST)) -#endif /* STM32F412Zx || STM32F413xx || STM32F423xx */ -#define __HAL_RCC_CRC_FORCE_RESET() (RCC->AHB1RSTR |= (RCC_AHB1RSTR_CRCRST)) - -#if defined(STM32F412Rx) || defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOD_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIODRST)) -#endif /* STM32F412Rx || STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ -#if defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOE_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOERST)) -#endif /* STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx */ -#if defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_GPIOF_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOFRST)) -#define __HAL_RCC_GPIOG_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_GPIOGRST)) -#endif /* STM32F412Zx || STM32F413xx || STM32F423xx */ -#define __HAL_RCC_CRC_RELEASE_RESET() (RCC->AHB1RSTR &= ~(RCC_AHB1RSTR_CRCRST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_Force_Release_Reset AHB2 Force Release Reset - * @brief Force or release AHB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_AHB2_FORCE_RESET() (RCC->AHB2RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_AHB2_RELEASE_RESET() (RCC->AHB2RSTR = 0x00U) - -#if defined(STM32F423xx) -#define __HAL_RCC_AES_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_AESRST)) -#define __HAL_RCC_AES_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_AESRST)) -#endif /* STM32F423xx */ - -#define __HAL_RCC_USB_OTG_FS_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_OTGFSRST)) -#define __HAL_RCC_USB_OTG_FS_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_OTGFSRST)) - -#define __HAL_RCC_RNG_FORCE_RESET() (RCC->AHB2RSTR |= (RCC_AHB2RSTR_RNGRST)) -#define __HAL_RCC_RNG_RELEASE_RESET() (RCC->AHB2RSTR &= ~(RCC_AHB2RSTR_RNGRST)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_Force_Release_Reset AHB3 Force Release Reset - * @brief Force or release AHB3 peripheral reset. - * @{ - */ -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_AHB3_FORCE_RESET() (RCC->AHB3RSTR = 0xFFFFFFFFU) -#define __HAL_RCC_AHB3_RELEASE_RESET() (RCC->AHB3RSTR = 0x00U) - -#define __HAL_RCC_FSMC_FORCE_RESET() (RCC->AHB3RSTR |= (RCC_AHB3RSTR_FSMCRST)) -#define __HAL_RCC_QSPI_FORCE_RESET() (RCC->AHB3RSTR |= (RCC_AHB3RSTR_QSPIRST)) - -#define __HAL_RCC_FSMC_RELEASE_RESET() (RCC->AHB3RSTR &= ~(RCC_AHB3RSTR_FSMCRST)) -#define __HAL_RCC_QSPI_RELEASE_RESET() (RCC->AHB3RSTR &= ~(RCC_AHB3RSTR_QSPIRST)) -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F413xx || STM32F423xx */ -#if defined(STM32F412Cx) -#define __HAL_RCC_AHB3_FORCE_RESET() -#define __HAL_RCC_AHB3_RELEASE_RESET() - -#define __HAL_RCC_FSMC_FORCE_RESET() -#define __HAL_RCC_QSPI_FORCE_RESET() - -#define __HAL_RCC_FSMC_RELEASE_RESET() -#define __HAL_RCC_QSPI_RELEASE_RESET() -#endif /* STM32F412Cx */ -/** - * @} - */ - -/** @defgroup RCCEx_APB1_Force_Release_Reset APB1 Force Release Reset - * @brief Force or release APB1 peripheral reset. - * @{ - */ -#define __HAL_RCC_TIM2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM2RST)) -#define __HAL_RCC_TIM3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM3RST)) -#define __HAL_RCC_TIM4_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM4RST)) -#define __HAL_RCC_TIM6_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM6RST)) -#define __HAL_RCC_TIM7_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM7RST)) -#define __HAL_RCC_TIM12_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM12RST)) -#define __HAL_RCC_TIM13_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM13RST)) -#define __HAL_RCC_TIM14_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_TIM14RST)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_LPTIM1_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_LPTIM1RST)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_SPI3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_SPI3RST)) -#define __HAL_RCC_USART3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_USART3RST)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART4_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART4RST)) -#define __HAL_RCC_UART5_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART5RST)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_I2C3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_I2C3RST)) -#define __HAL_RCC_FMPI2C1_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_FMPI2C1RST)) -#define __HAL_RCC_CAN1_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_CAN1RST)) -#define __HAL_RCC_CAN2_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_CAN2RST)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_CAN3_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_CAN3RST)) -#define __HAL_RCC_DAC_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_DACRST)) -#define __HAL_RCC_UART7_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART7RST)) -#define __HAL_RCC_UART8_FORCE_RESET() (RCC->APB1RSTR |= (RCC_APB1RSTR_UART8RST)) -#endif /* STM32F413xx || STM32F423xx */ - -#define __HAL_RCC_TIM2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM2RST)) -#define __HAL_RCC_TIM3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM3RST)) -#define __HAL_RCC_TIM4_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM4RST)) -#define __HAL_RCC_TIM6_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM6RST)) -#define __HAL_RCC_TIM7_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM7RST)) -#define __HAL_RCC_TIM12_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM12RST)) -#define __HAL_RCC_TIM13_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM13RST)) -#define __HAL_RCC_TIM14_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_TIM14RST)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_LPTIM1_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_LPTIM1RST)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_SPI3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_SPI3RST)) -#define __HAL_RCC_USART3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_USART3RST)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART4_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART4RST)) -#define __HAL_RCC_UART5_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART5RST)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_I2C3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_I2C3RST)) -#define __HAL_RCC_FMPI2C1_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_FMPI2C1RST)) -#define __HAL_RCC_CAN1_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_CAN1RST)) -#define __HAL_RCC_CAN2_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_CAN2RST)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_CAN3_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_CAN3RST)) -#define __HAL_RCC_DAC_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_DACRST)) -#define __HAL_RCC_UART7_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART7RST)) -#define __HAL_RCC_UART8_RELEASE_RESET() (RCC->APB1RSTR &= ~(RCC_APB1RSTR_UART8RST)) -#endif /* STM32F413xx || STM32F423xx */ -/** - * @} - */ - -/** @defgroup RCCEx_APB2_Force_Release_Reset APB2 Force Release Reset - * @brief Force or release APB2 peripheral reset. - * @{ - */ -#define __HAL_RCC_TIM8_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM8RST)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART9_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_UART9RST)) -#define __HAL_RCC_UART10_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_UART10RST)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_SDIO_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SDIORST)) -#define __HAL_RCC_SPI4_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI4RST)) -#define __HAL_RCC_TIM10_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_TIM10RST)) -#define __HAL_RCC_SPI5_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SPI5RST)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_SAI1_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_SAI1RST)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_DFSDM1_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_DFSDM1RST)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_DFSDM2_FORCE_RESET() (RCC->APB2RSTR |= (RCC_APB2RSTR_DFSDM2RST)) -#endif /* STM32F413xx || STM32F423xx */ - -#define __HAL_RCC_TIM8_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM8RST)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART9_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_UART9RST)) -#define __HAL_RCC_UART10_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_UART10RST)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_SDIO_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SDIORST)) -#define __HAL_RCC_SPI4_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI4RST)) -#define __HAL_RCC_TIM10_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_TIM10RST)) -#define __HAL_RCC_SPI5_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SPI5RST)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_SAI1_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_SAI1RST)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_DFSDM1_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_DFSDM1RST)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_DFSDM2_RELEASE_RESET() (RCC->APB2RSTR &= ~(RCC_APB2RSTR_DFSDM2RST)) -#endif /* STM32F413xx || STM32F423xx */ -/** - * @} - */ - -/** @defgroup RCCEx_AHB1_LowPower_Enable_Disable AHB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB1 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_GPIOD_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIODLPEN)) -#define __HAL_RCC_GPIOE_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOELPEN)) -#define __HAL_RCC_GPIOF_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOFLPEN)) -#define __HAL_RCC_GPIOG_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_GPIOGLPEN)) -#define __HAL_RCC_CRC_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_CRCLPEN)) -#define __HAL_RCC_FLITF_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_FLITFLPEN)) -#define __HAL_RCC_SRAM1_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM1LPEN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_SRAM2_CLK_SLEEP_ENABLE() (RCC->AHB1LPENR |= (RCC_AHB1LPENR_SRAM2LPEN)) -#endif /* STM32F413xx || STM32F423xx */ - -#define __HAL_RCC_GPIOD_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIODLPEN)) -#define __HAL_RCC_GPIOE_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOELPEN)) -#define __HAL_RCC_GPIOF_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOFLPEN)) -#define __HAL_RCC_GPIOG_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_GPIOGLPEN)) -#define __HAL_RCC_CRC_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_CRCLPEN)) -#define __HAL_RCC_FLITF_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_FLITFLPEN)) -#define __HAL_RCC_SRAM1_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_SRAM1LPEN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_SRAM2_CLK_SLEEP_DISABLE() (RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_SRAM2LPEN)) -#endif /* STM32F413xx || STM32F423xx */ -/** - * @} - */ - -/** @defgroup RCCEx_AHB2_LowPower_Enable_Disable AHB2 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB2 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wake-up from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#if defined(STM32F423xx) -#define __HAL_RCC_AES_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_AESLPEN)) -#define __HAL_RCC_AES_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_AESLPEN)) -#endif /* STM32F423xx */ - -#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_OTGFSLPEN)) -#define __HAL_RCC_USB_OTG_FS_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_OTGFSLPEN)) - -#define __HAL_RCC_RNG_CLK_SLEEP_ENABLE() (RCC->AHB2LPENR |= (RCC_AHB2LPENR_RNGLPEN)) -#define __HAL_RCC_RNG_CLK_SLEEP_DISABLE() (RCC->AHB2LPENR &= ~(RCC_AHB2LPENR_RNGLPEN)) -/** - * @} - */ - -/** @defgroup RCCEx_AHB3_LowPower_Enable_Disable AHB3 Peripheral Low Power Enable Disable - * @brief Enable or disable the AHB3 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_FSMC_CLK_SLEEP_ENABLE() (RCC->AHB3LPENR |= (RCC_AHB3LPENR_FSMCLPEN)) -#define __HAL_RCC_QSPI_CLK_SLEEP_ENABLE() (RCC->AHB3LPENR |= (RCC_AHB3LPENR_QSPILPEN)) - -#define __HAL_RCC_FSMC_CLK_SLEEP_DISABLE() (RCC->AHB3LPENR &= ~(RCC_AHB3LPENR_FSMCLPEN)) -#define __HAL_RCC_QSPI_CLK_SLEEP_DISABLE() (RCC->AHB3LPENR &= ~(RCC_AHB3LPENR_QSPILPEN)) -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F413xx || STM32F423xx */ - -/** - * @} - */ - -/** @defgroup RCCEx_APB1_LowPower_Enable_Disable APB1 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB1 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_TIM2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM2LPEN)) -#define __HAL_RCC_TIM3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM3LPEN)) -#define __HAL_RCC_TIM4_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM4LPEN)) -#define __HAL_RCC_TIM6_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM6LPEN)) -#define __HAL_RCC_TIM7_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM7LPEN)) -#define __HAL_RCC_TIM12_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM12LPEN)) -#define __HAL_RCC_TIM13_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM13LPEN)) -#define __HAL_RCC_TIM14_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_TIM14LPEN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_LPTIM1_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_LPTIM1LPEN)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_RTCAPB_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_RTCAPBLPEN)) -#define __HAL_RCC_SPI3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_SPI3LPEN)) -#define __HAL_RCC_USART3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_USART3LPEN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART4_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART4LPEN)) -#define __HAL_RCC_UART5_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART5LPEN)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_I2C3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_I2C3LPEN)) -#define __HAL_RCC_FMPI2C1_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_FMPI2C1LPEN)) -#define __HAL_RCC_CAN1_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_CAN1LPEN)) -#define __HAL_RCC_CAN2_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_CAN2LPEN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_CAN3_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_CAN3LPEN)) -#define __HAL_RCC_DAC_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_DACLPEN)) -#define __HAL_RCC_UART7_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART7LPEN)) -#define __HAL_RCC_UART8_CLK_SLEEP_ENABLE() (RCC->APB1LPENR |= (RCC_APB1LPENR_UART8LPEN)) -#endif /* STM32F413xx || STM32F423xx */ - -#define __HAL_RCC_TIM2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM2LPEN)) -#define __HAL_RCC_TIM3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM3LPEN)) -#define __HAL_RCC_TIM4_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM4LPEN)) -#define __HAL_RCC_TIM6_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM6LPEN)) -#define __HAL_RCC_TIM7_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM7LPEN)) -#define __HAL_RCC_TIM12_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM12LPEN)) -#define __HAL_RCC_TIM13_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM13LPEN)) -#define __HAL_RCC_TIM14_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_TIM14LPEN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_LPTIM1_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_LPTIM1LPEN)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_RTCAPB_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_RTCAPBLPEN)) -#define __HAL_RCC_SPI3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_SPI3LPEN)) -#define __HAL_RCC_USART3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_USART3LPEN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART4_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART4LPEN)) -#define __HAL_RCC_UART5_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART5LPEN)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_I2C3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_I2C3LPEN)) -#define __HAL_RCC_FMPI2C1_CLK_SLEEP_DISABLE()(RCC->APB1LPENR &= ~(RCC_APB1LPENR_FMPI2C1LPEN)) -#define __HAL_RCC_CAN1_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_CAN1LPEN)) -#define __HAL_RCC_CAN2_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_CAN2LPEN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_CAN3_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_CAN3LPEN)) -#define __HAL_RCC_DAC_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_DACLPEN)) -#define __HAL_RCC_UART7_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART7LPEN)) -#define __HAL_RCC_UART8_CLK_SLEEP_DISABLE() (RCC->APB1LPENR &= ~(RCC_APB1LPENR_UART8LPEN)) -#endif /* STM32F413xx || STM32F423xx */ -/** - * @} - */ - -/** @defgroup RCCEx_APB2_LowPower_Enable_Disable APB2 Peripheral Low Power Enable Disable - * @brief Enable or disable the APB2 peripheral clock during Low Power (Sleep) mode. - * @note Peripheral clock gating in SLEEP mode can be used to further reduce - * power consumption. - * @note After wakeup from SLEEP mode, the peripheral clock is enabled again. - * @note By default, all peripheral clocks are enabled during SLEEP mode. - * @{ - */ -#define __HAL_RCC_TIM8_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_TIM8LPEN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART9_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_UART9LPEN)) -#define __HAL_RCC_UART10_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_UART10LPEN)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_SDIO_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SDIOLPEN)) -#define __HAL_RCC_SPI4_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI4LPEN)) -#define __HAL_RCC_EXTIT_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_EXTITLPEN)) -#define __HAL_RCC_TIM10_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_TIM10LPEN)) -#define __HAL_RCC_SPI5_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SPI5LPEN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_SAI1_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_SAI1LPEN)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_DFSDM1_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_DFSDM1LPEN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_DFSDM2_CLK_SLEEP_ENABLE() (RCC->APB2LPENR |= (RCC_APB2LPENR_DFSDM2LPEN)) -#endif /* STM32F413xx || STM32F423xx */ - -#define __HAL_RCC_TIM8_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM8LPEN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_UART9_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_UART9LPEN)) -#define __HAL_RCC_UART10_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_UART10LPEN)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_SDIO_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SDIOLPEN)) -#define __HAL_RCC_SPI4_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI4LPEN)) -#define __HAL_RCC_EXTIT_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_EXTITLPEN)) -#define __HAL_RCC_TIM10_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_TIM10LPEN)) -#define __HAL_RCC_SPI5_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SPI5LPEN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_SAI1_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_SAI1LPEN)) -#endif /* STM32F413xx || STM32F423xx */ -#define __HAL_RCC_DFSDM1_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_DFSDM1LPEN)) -#if defined(STM32F413xx) || defined(STM32F423xx) -#define __HAL_RCC_DFSDM2_CLK_SLEEP_DISABLE() (RCC->APB2LPENR &= ~(RCC_APB2LPENR_DFSDM2LPEN)) -#endif /* STM32F413xx || STM32F423xx */ -/** - * @} - */ -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ -/*----------------------------------------------------------------------------*/ - -/*------------------------------- PLL Configuration --------------------------*/ -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F446xx) ||\ - defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || \ - defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/** @brief Macro to configure the main PLL clock source, multiplication and division factors. - * @note This function must be used only when the main PLL is disabled. - * @param __RCC_PLLSource__ specifies the PLL entry clock source. - * This parameter can be one of the following values: - * @arg RCC_PLLSOURCE_HSI: HSI oscillator clock selected as PLL clock entry - * @arg RCC_PLLSOURCE_HSE: HSE oscillator clock selected as PLL clock entry - * @note This clock source (RCC_PLLSource) is common for the main PLL and PLLI2S. - * @param __PLLM__ specifies the division factor for PLL VCO input clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 63. - * @note You have to set the PLLM parameter correctly to ensure that the VCO input - * frequency ranges from 1 to 2 MHz. It is recommended to select a frequency - * of 2 MHz to limit PLL jitter. - * @param __PLLN__ specifies the multiplication factor for PLL VCO output clock - * This parameter must be a number between Min_Data = 50 and Max_Data = 432. - * @note You have to set the PLLN parameter correctly to ensure that the VCO - * output frequency is between 100 and 432 MHz. - * - * @param __PLLP__ specifies the division factor for main system clock (SYSCLK) - * This parameter must be a number in the range {2, 4, 6, or 8}. - * - * @param __PLLQ__ specifies the division factor for OTG FS, SDIO and RNG clocks - * This parameter must be a number between Min_Data = 2 and Max_Data = 15. - * @note If the USB OTG FS is used in your application, you have to set the - * PLLQ parameter correctly to have 48 MHz clock for the USB. However, - * the SDIO and RNG need a frequency lower than or equal to 48 MHz to work - * correctly. - * - * @param __PLLR__ PLL division factor for I2S, SAI, SYSTEM, SPDIFRX clocks. - * This parameter must be a number between Min_Data = 2 and Max_Data = 7. - * @note This parameter is only available in STM32F446xx/STM32F469xx/STM32F479xx/ - STM32F412Zx/STM32F412Vx/STM32F412Rx/STM32F412Cx/STM32F413xx/STM32F423xx devices. - * - */ -#define __HAL_RCC_PLL_CONFIG(__RCC_PLLSource__, __PLLM__, __PLLN__, __PLLP__, __PLLQ__,__PLLR__) \ - (RCC->PLLCFGR = ((__RCC_PLLSource__) | (__PLLM__) | \ - ((__PLLN__) << RCC_PLLCFGR_PLLN_Pos) | \ - ((((__PLLP__) >> 1U) -1U) << RCC_PLLCFGR_PLLP_Pos) | \ - ((__PLLQ__) << RCC_PLLCFGR_PLLQ_Pos) | \ - ((__PLLR__) << RCC_PLLCFGR_PLLR_Pos))) -#else -/** @brief Macro to configure the main PLL clock source, multiplication and division factors. - * @note This function must be used only when the main PLL is disabled. - * @param __RCC_PLLSource__ specifies the PLL entry clock source. - * This parameter can be one of the following values: - * @arg RCC_PLLSOURCE_HSI: HSI oscillator clock selected as PLL clock entry - * @arg RCC_PLLSOURCE_HSE: HSE oscillator clock selected as PLL clock entry - * @note This clock source (RCC_PLLSource) is common for the main PLL and PLLI2S. - * @param __PLLM__ specifies the division factor for PLL VCO input clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 63. - * @note You have to set the PLLM parameter correctly to ensure that the VCO input - * frequency ranges from 1 to 2 MHz. It is recommended to select a frequency - * of 2 MHz to limit PLL jitter. - * @param __PLLN__ specifies the multiplication factor for PLL VCO output clock - * This parameter must be a number between Min_Data = 50 and Max_Data = 432 - * Except for STM32F411xE devices where Min_Data = 192. - * @note You have to set the PLLN parameter correctly to ensure that the VCO - * output frequency is between 100 and 432 MHz, Except for STM32F411xE devices - * where frequency is between 192 and 432 MHz. - * @param __PLLP__ specifies the division factor for main system clock (SYSCLK) - * This parameter must be a number in the range {2, 4, 6, or 8}. - * - * @param __PLLQ__ specifies the division factor for OTG FS, SDIO and RNG clocks - * This parameter must be a number between Min_Data = 2 and Max_Data = 15. - * @note If the USB OTG FS is used in your application, you have to set the - * PLLQ parameter correctly to have 48 MHz clock for the USB. However, - * the SDIO and RNG need a frequency lower than or equal to 48 MHz to work - * correctly. - * - */ -#define __HAL_RCC_PLL_CONFIG(__RCC_PLLSource__, __PLLM__, __PLLN__, __PLLP__, __PLLQ__) \ - (RCC->PLLCFGR = (0x20000000U | (__RCC_PLLSource__) | (__PLLM__)| \ - ((__PLLN__) << RCC_PLLCFGR_PLLN_Pos) | \ - ((((__PLLP__) >> 1U) -1U) << RCC_PLLCFGR_PLLP_Pos) | \ - ((__PLLQ__) << RCC_PLLCFGR_PLLQ_Pos))) - #endif /* STM32F410xx || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ -/*----------------------------------------------------------------------------*/ - -/*----------------------------PLLI2S Configuration ---------------------------*/ -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || \ - defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || \ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F446xx) || \ - defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || \ - defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) - -/** @brief Macros to enable or disable the PLLI2S. - * @note The PLLI2S is disabled by hardware when entering STOP and STANDBY modes. - */ -#define __HAL_RCC_PLLI2S_ENABLE() (*(__IO uint32_t *) RCC_CR_PLLI2SON_BB = ENABLE) -#define __HAL_RCC_PLLI2S_DISABLE() (*(__IO uint32_t *) RCC_CR_PLLI2SON_BB = DISABLE) - -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || - STM32F401xC || STM32F401xE || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || - STM32F412Rx || STM32F412Cx */ -#if defined(STM32F446xx) -/** @brief Macro to configure the PLLI2S clock multiplication and division factors . - * @note This macro must be used only when the PLLI2S is disabled. - * @note PLLI2S clock source is common with the main PLL (configured in - * HAL_RCC_ClockConfig() API). - * @param __PLLI2SM__ specifies the division factor for PLLI2S VCO input clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 63. - * @note You have to set the PLLI2SM parameter correctly to ensure that the VCO input - * frequency ranges from 1 to 2 MHz. It is recommended to select a frequency - * of 1 MHz to limit PLLI2S jitter. - * - * @param __PLLI2SN__ specifies the multiplication factor for PLLI2S VCO output clock - * This parameter must be a number between Min_Data = 50 and Max_Data = 432. - * @note You have to set the PLLI2SN parameter correctly to ensure that the VCO - * output frequency is between Min_Data = 100 and Max_Data = 432 MHz. - * - * @param __PLLI2SP__ specifies division factor for SPDIFRX Clock. - * This parameter must be a number in the range {2, 4, 6, or 8}. - * @note the PLLI2SP parameter is only available with STM32F446xx Devices - * - * @param __PLLI2SR__ specifies the division factor for I2S clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 7. - * @note You have to set the PLLI2SR parameter correctly to not exceed 192 MHz - * on the I2S clock frequency. - * - * @param __PLLI2SQ__ specifies the division factor for SAI clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 15. - */ -#define __HAL_RCC_PLLI2S_CONFIG(__PLLI2SM__, __PLLI2SN__, __PLLI2SP__, __PLLI2SQ__, __PLLI2SR__) \ - (RCC->PLLI2SCFGR = ((__PLLI2SM__) |\ - ((__PLLI2SN__) << RCC_PLLI2SCFGR_PLLI2SN_Pos) |\ - ((((__PLLI2SP__) >> 1U) -1U) << RCC_PLLI2SCFGR_PLLI2SP_Pos) |\ - ((__PLLI2SQ__) << RCC_PLLI2SCFGR_PLLI2SQ_Pos) |\ - ((__PLLI2SR__) << RCC_PLLI2SCFGR_PLLI2SR_Pos))) -#elif defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) ||\ - defined(STM32F413xx) || defined(STM32F423xx) -/** @brief Macro to configure the PLLI2S clock multiplication and division factors . - * @note This macro must be used only when the PLLI2S is disabled. - * @note PLLI2S clock source is common with the main PLL (configured in - * HAL_RCC_ClockConfig() API). - * @param __PLLI2SM__ specifies the division factor for PLLI2S VCO input clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 63. - * @note You have to set the PLLI2SM parameter correctly to ensure that the VCO input - * frequency ranges from 1 to 2 MHz. It is recommended to select a frequency - * of 1 MHz to limit PLLI2S jitter. - * - * @param __PLLI2SN__ specifies the multiplication factor for PLLI2S VCO output clock - * This parameter must be a number between Min_Data = 50 and Max_Data = 432. - * @note You have to set the PLLI2SN parameter correctly to ensure that the VCO - * output frequency is between Min_Data = 100 and Max_Data = 432 MHz. - * - * @param __PLLI2SR__ specifies the division factor for I2S clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 7. - * @note You have to set the PLLI2SR parameter correctly to not exceed 192 MHz - * on the I2S clock frequency. - * - * @param __PLLI2SQ__ specifies the division factor for SAI clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 15. - */ -#define __HAL_RCC_PLLI2S_CONFIG(__PLLI2SM__, __PLLI2SN__, __PLLI2SQ__, __PLLI2SR__) \ - (RCC->PLLI2SCFGR = ((__PLLI2SM__) |\ - ((__PLLI2SN__) << RCC_PLLI2SCFGR_PLLI2SN_Pos) |\ - ((__PLLI2SQ__) << RCC_PLLI2SCFGR_PLLI2SQ_Pos) |\ - ((__PLLI2SR__) << RCC_PLLI2SCFGR_PLLI2SR_Pos))) -#else -/** @brief Macro to configure the PLLI2S clock multiplication and division factors . - * @note This macro must be used only when the PLLI2S is disabled. - * @note PLLI2S clock source is common with the main PLL (configured in - * HAL_RCC_ClockConfig() API). - * @param __PLLI2SN__ specifies the multiplication factor for PLLI2S VCO output clock - * This parameter must be a number between Min_Data = 50 and Max_Data = 432. - * @note You have to set the PLLI2SN parameter correctly to ensure that the VCO - * output frequency is between Min_Data = 100 and Max_Data = 432 MHz. - * - * @param __PLLI2SR__ specifies the division factor for I2S clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 7. - * @note You have to set the PLLI2SR parameter correctly to not exceed 192 MHz - * on the I2S clock frequency. - * - */ -#define __HAL_RCC_PLLI2S_CONFIG(__PLLI2SN__, __PLLI2SR__) \ - (RCC->PLLI2SCFGR = (((__PLLI2SN__) << RCC_PLLI2SCFGR_PLLI2SN_Pos) |\ - ((__PLLI2SR__) << RCC_PLLI2SCFGR_PLLI2SR_Pos))) -#endif /* STM32F446xx */ - -#if defined(STM32F411xE) -/** @brief Macro to configure the PLLI2S clock multiplication and division factors . - * @note This macro must be used only when the PLLI2S is disabled. - * @note This macro must be used only when the PLLI2S is disabled. - * @note PLLI2S clock source is common with the main PLL (configured in - * HAL_RCC_ClockConfig() API). - * @param __PLLI2SM__ specifies the division factor for PLLI2S VCO input clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 63. - * @note The PLLI2SM parameter is only used with STM32F411xE/STM32F410xx Devices - * @note You have to set the PLLI2SM parameter correctly to ensure that the VCO input - * frequency ranges from 1 to 2 MHz. It is recommended to select a frequency - * of 2 MHz to limit PLLI2S jitter. - * @param __PLLI2SN__ specifies the multiplication factor for PLLI2S VCO output clock - * This parameter must be a number between Min_Data = 192 and Max_Data = 432. - * @note You have to set the PLLI2SN parameter correctly to ensure that the VCO - * output frequency is between Min_Data = 192 and Max_Data = 432 MHz. - * @param __PLLI2SR__ specifies the division factor for I2S clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 7. - * @note You have to set the PLLI2SR parameter correctly to not exceed 192 MHz - * on the I2S clock frequency. - */ -#define __HAL_RCC_PLLI2S_I2SCLK_CONFIG(__PLLI2SM__, __PLLI2SN__, __PLLI2SR__) (RCC->PLLI2SCFGR = ((__PLLI2SM__) |\ - ((__PLLI2SN__) << RCC_PLLI2SCFGR_PLLI2SN_Pos) |\ - ((__PLLI2SR__) << RCC_PLLI2SCFGR_PLLI2SR_Pos))) -#endif /* STM32F411xE */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) -/** @brief Macro used by the SAI HAL driver to configure the PLLI2S clock multiplication and division factors. - * @note This macro must be used only when the PLLI2S is disabled. - * @note PLLI2S clock source is common with the main PLL (configured in - * HAL_RCC_ClockConfig() API) - * @param __PLLI2SN__ specifies the multiplication factor for PLLI2S VCO output clock. - * This parameter must be a number between Min_Data = 50 and Max_Data = 432. - * @note You have to set the PLLI2SN parameter correctly to ensure that the VCO - * output frequency is between Min_Data = 100 and Max_Data = 432 MHz. - * @param __PLLI2SQ__ specifies the division factor for SAI1 clock. - * This parameter must be a number between Min_Data = 2 and Max_Data = 15. - * @note the PLLI2SQ parameter is only available with STM32F427xx/437xx/429xx/439xx/469xx/479xx - * Devices and can be configured using the __HAL_RCC_PLLI2S_PLLSAICLK_CONFIG() macro - * @param __PLLI2SR__ specifies the division factor for I2S clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 7. - * @note You have to set the PLLI2SR parameter correctly to not exceed 192 MHz - * on the I2S clock frequency. - */ -#define __HAL_RCC_PLLI2S_SAICLK_CONFIG(__PLLI2SN__, __PLLI2SQ__, __PLLI2SR__) (RCC->PLLI2SCFGR = ((__PLLI2SN__) << 6U) |\ - ((__PLLI2SQ__) << 24U) |\ - ((__PLLI2SR__) << 28U)) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ -/*----------------------------------------------------------------------------*/ - -/*------------------------------ PLLSAI Configuration ------------------------*/ -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -/** @brief Macros to Enable or Disable the PLLISAI. - * @note The PLLSAI is only available with STM32F429x/439x Devices. - * @note The PLLSAI is disabled by hardware when entering STOP and STANDBY modes. - */ -#define __HAL_RCC_PLLSAI_ENABLE() (*(__IO uint32_t *) RCC_CR_PLLSAION_BB = ENABLE) -#define __HAL_RCC_PLLSAI_DISABLE() (*(__IO uint32_t *) RCC_CR_PLLSAION_BB = DISABLE) - -#if defined(STM32F446xx) -/** @brief Macro to configure the PLLSAI clock multiplication and division factors. - * - * @param __PLLSAIM__ specifies the division factor for PLLSAI VCO input clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 63. - * @note You have to set the PLLSAIM parameter correctly to ensure that the VCO input - * frequency ranges from 1 to 2 MHz. It is recommended to select a frequency - * of 1 MHz to limit PLLI2S jitter. - * @note The PLLSAIM parameter is only used with STM32F446xx Devices - * - * @param __PLLSAIN__ specifies the multiplication factor for PLLSAI VCO output clock. - * This parameter must be a number between Min_Data = 50 and Max_Data = 432. - * @note You have to set the PLLSAIN parameter correctly to ensure that the VCO - * output frequency is between Min_Data = 100 and Max_Data = 432 MHz. - * - * @param __PLLSAIP__ specifies division factor for OTG FS, SDIO and RNG clocks. - * This parameter must be a number in the range {2, 4, 6, or 8}. - * @note the PLLSAIP parameter is only available with STM32F446xx Devices - * - * @param __PLLSAIQ__ specifies the division factor for SAI clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 15. - * - * @param __PLLSAIR__ specifies the division factor for LTDC clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 7. - * @note the PLLI2SR parameter is only available with STM32F427/437/429/439xx Devices - */ -#define __HAL_RCC_PLLSAI_CONFIG(__PLLSAIM__, __PLLSAIN__, __PLLSAIP__, __PLLSAIQ__, __PLLSAIR__) \ - (RCC->PLLSAICFGR = ((__PLLSAIM__) | \ - ((__PLLSAIN__) << RCC_PLLSAICFGR_PLLSAIN_Pos) | \ - ((((__PLLSAIP__) >> 1U) -1U) << RCC_PLLSAICFGR_PLLSAIP_Pos) | \ - ((__PLLSAIQ__) << RCC_PLLSAICFGR_PLLSAIQ_Pos))) -#endif /* STM32F446xx */ - -#if defined(STM32F469xx) || defined(STM32F479xx) -/** @brief Macro to configure the PLLSAI clock multiplication and division factors. - * - * @param __PLLSAIN__ specifies the multiplication factor for PLLSAI VCO output clock. - * This parameter must be a number between Min_Data = 50 and Max_Data = 432. - * @note You have to set the PLLSAIN parameter correctly to ensure that the VCO - * output frequency is between Min_Data = 100 and Max_Data = 432 MHz. - * - * @param __PLLSAIP__ specifies division factor for SDIO and CLK48 clocks. - * This parameter must be a number in the range {2, 4, 6, or 8}. - * - * @param __PLLSAIQ__ specifies the division factor for SAI clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 15. - * - * @param __PLLSAIR__ specifies the division factor for LTDC clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 7. - */ -#define __HAL_RCC_PLLSAI_CONFIG(__PLLSAIN__, __PLLSAIP__, __PLLSAIQ__, __PLLSAIR__) \ - (RCC->PLLSAICFGR = (((__PLLSAIN__) << RCC_PLLSAICFGR_PLLSAIN_Pos) |\ - ((((__PLLSAIP__) >> 1U) -1U) << RCC_PLLSAICFGR_PLLSAIP_Pos) |\ - ((__PLLSAIQ__) << RCC_PLLSAICFGR_PLLSAIQ_Pos) |\ - ((__PLLSAIR__) << RCC_PLLSAICFGR_PLLSAIR_Pos))) -#endif /* STM32F469xx || STM32F479xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) -/** @brief Macro to configure the PLLSAI clock multiplication and division factors. - * - * @param __PLLSAIN__ specifies the multiplication factor for PLLSAI VCO output clock. - * This parameter must be a number between Min_Data = 50 and Max_Data = 432. - * @note You have to set the PLLSAIN parameter correctly to ensure that the VCO - * output frequency is between Min_Data = 100 and Max_Data = 432 MHz. - * - * @param __PLLSAIQ__ specifies the division factor for SAI clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 15. - * - * @param __PLLSAIR__ specifies the division factor for LTDC clock - * This parameter must be a number between Min_Data = 2 and Max_Data = 7. - * @note the PLLI2SR parameter is only available with STM32F427/437/429/439xx Devices - */ -#define __HAL_RCC_PLLSAI_CONFIG(__PLLSAIN__, __PLLSAIQ__, __PLLSAIR__) \ - (RCC->PLLSAICFGR = (((__PLLSAIN__) << RCC_PLLSAICFGR_PLLSAIN_Pos) | \ - ((__PLLSAIQ__) << RCC_PLLSAICFGR_PLLSAIQ_Pos) | \ - ((__PLLSAIR__) << RCC_PLLSAICFGR_PLLSAIR_Pos))) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx */ - -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ -/*----------------------------------------------------------------------------*/ - -/*------------------- PLLSAI/PLLI2S Dividers Configuration -------------------*/ -#if defined(STM32F413xx) || defined(STM32F423xx) -/** @brief Macro to configure the SAI clock Divider coming from PLLI2S. - * @note This function must be called before enabling the PLLI2S. - * @param __PLLI2SDivR__ specifies the PLLI2S division factor for SAI1 clock. - * This parameter must be a number between 1 and 32. - * SAI1 clock frequency = f(PLLI2SR) / __PLLI2SDivR__ - */ -#define __HAL_RCC_PLLI2S_PLLSAICLKDIVR_CONFIG(__PLLI2SDivR__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_PLLI2SDIVR, (__PLLI2SDivR__)-1U)) - -/** @brief Macro to configure the SAI clock Divider coming from PLL. - * @param __PLLDivR__ specifies the PLL division factor for SAI1 clock. - * This parameter must be a number between 1 and 32. - * SAI1 clock frequency = f(PLLR) / __PLLDivR__ - */ -#define __HAL_RCC_PLL_PLLSAICLKDIVR_CONFIG(__PLLDivR__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_PLLDIVR, ((__PLLDivR__)-1U)<<8U)) -#endif /* STM32F413xx || STM32F423xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F446xx) ||\ - defined(STM32F469xx) || defined(STM32F479xx) -/** @brief Macro to configure the SAI clock Divider coming from PLLI2S. - * @note This function must be called before enabling the PLLI2S. - * @param __PLLI2SDivQ__ specifies the PLLI2S division factor for SAI1 clock. - * This parameter must be a number between 1 and 32. - * SAI1 clock frequency = f(PLLI2SQ) / __PLLI2SDivQ__ - */ -#define __HAL_RCC_PLLI2S_PLLSAICLKDIVQ_CONFIG(__PLLI2SDivQ__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_PLLI2SDIVQ, (__PLLI2SDivQ__)-1U)) - -/** @brief Macro to configure the SAI clock Divider coming from PLLSAI. - * @note This function must be called before enabling the PLLSAI. - * @param __PLLSAIDivQ__ specifies the PLLSAI division factor for SAI1 clock . - * This parameter must be a number between Min_Data = 1 and Max_Data = 32. - * SAI1 clock frequency = f(PLLSAIQ) / __PLLSAIDivQ__ - */ -#define __HAL_RCC_PLLSAI_PLLSAICLKDIVQ_CONFIG(__PLLSAIDivQ__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_PLLSAIDIVQ, ((__PLLSAIDivQ__)-1U)<<8U)) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) -/** @brief Macro to configure the LTDC clock Divider coming from PLLSAI. - * - * @note The LTDC peripheral is only available with STM32F427/437/429/439/469/479xx Devices. - * @note This function must be called before enabling the PLLSAI. - * @param __PLLSAIDivR__ specifies the PLLSAI division factor for LTDC clock . - * This parameter must be a number between Min_Data = 2 and Max_Data = 16. - * LTDC clock frequency = f(PLLSAIR) / __PLLSAIDivR__ - */ -#define __HAL_RCC_PLLSAI_PLLSAICLKDIVR_CONFIG(__PLLSAIDivR__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_PLLSAIDIVR, (__PLLSAIDivR__))) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ -/*----------------------------------------------------------------------------*/ - -/*------------------------- Peripheral Clock selection -----------------------*/ -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) ||\ - defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F469xx) ||\ - defined(STM32F479xx) -/** @brief Macro to configure the I2S clock source (I2SCLK). - * @note This function must be called before enabling the I2S APB clock. - * @param __SOURCE__ specifies the I2S clock source. - * This parameter can be one of the following values: - * @arg RCC_I2SCLKSOURCE_PLLI2S: PLLI2S clock used as I2S clock source. - * @arg RCC_I2SCLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin - * used as I2S clock source. - */ -#define __HAL_RCC_I2S_CONFIG(__SOURCE__) (*(__IO uint32_t *) RCC_CFGR_I2SSRC_BB = (__SOURCE__)) - - -/** @brief Macro to get the I2S clock source (I2SCLK). - * @retval The clock source can be one of the following values: - * @arg @ref RCC_I2SCLKSOURCE_PLLI2S: PLLI2S clock used as I2S clock source. - * @arg @ref RCC_I2SCLKSOURCE_EXT External clock mapped on the I2S_CKIN pin - * used as I2S clock source - */ -#define __HAL_RCC_GET_I2S_SOURCE() ((uint32_t)(READ_BIT(RCC->CFGR, RCC_CFGR_I2SSRC))) -#endif /* STM32F40xxx || STM32F41xxx || STM32F42xxx || STM32F43xxx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F469xx) || defined(STM32F479xx) - -/** @brief Macro to configure SAI1BlockA clock source selection. - * @note The SAI peripheral is only available with STM32F427/437/429/439/469/479xx Devices. - * @note This function must be called before enabling PLLSAI, PLLI2S and - * the SAI clock. - * @param __SOURCE__ specifies the SAI Block A clock source. - * This parameter can be one of the following values: - * @arg RCC_SAIACLKSOURCE_PLLI2S: PLLI2S_Q clock divided by PLLI2SDIVQ used - * as SAI1 Block A clock. - * @arg RCC_SAIACLKSOURCE_PLLSAI: PLLISAI_Q clock divided by PLLSAIDIVQ used - * as SAI1 Block A clock. - * @arg RCC_SAIACLKSOURCE_Ext: External clock mapped on the I2S_CKIN pin - * used as SAI1 Block A clock. - */ -#define __HAL_RCC_SAI_BLOCKACLKSOURCE_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_SAI1ASRC, (__SOURCE__))) - -/** @brief Macro to configure SAI1BlockB clock source selection. - * @note The SAI peripheral is only available with STM32F427/437/429/439/469/479xx Devices. - * @note This function must be called before enabling PLLSAI, PLLI2S and - * the SAI clock. - * @param __SOURCE__ specifies the SAI Block B clock source. - * This parameter can be one of the following values: - * @arg RCC_SAIBCLKSOURCE_PLLI2S: PLLI2S_Q clock divided by PLLI2SDIVQ used - * as SAI1 Block B clock. - * @arg RCC_SAIBCLKSOURCE_PLLSAI: PLLISAI_Q clock divided by PLLSAIDIVQ used - * as SAI1 Block B clock. - * @arg RCC_SAIBCLKSOURCE_Ext: External clock mapped on the I2S_CKIN pin - * used as SAI1 Block B clock. - */ -#define __HAL_RCC_SAI_BLOCKBCLKSOURCE_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_SAI1BSRC, (__SOURCE__))) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F446xx) -/** @brief Macro to configure SAI1 clock source selection. - * @note This configuration is only available with STM32F446xx Devices. - * @note This function must be called before enabling PLL, PLLSAI, PLLI2S and - * the SAI clock. - * @param __SOURCE__ specifies the SAI1 clock source. - * This parameter can be one of the following values: - * @arg RCC_SAI1CLKSOURCE_PLLI2S: PLLI2S_Q clock divided by PLLI2SDIVQ used as SAI1 clock. - * @arg RCC_SAI1CLKSOURCE_PLLSAI: PLLISAI_Q clock divided by PLLSAIDIVQ used as SAI1 clock. - * @arg RCC_SAI1CLKSOURCE_PLLR: PLL VCO Output divided by PLLR used as SAI1 clock. - * @arg RCC_SAI1CLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin used as SAI1 clock. - */ -#define __HAL_RCC_SAI1_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_SAI1SRC, (__SOURCE__))) - -/** @brief Macro to Get SAI1 clock source selection. - * @note This configuration is only available with STM32F446xx Devices. - * @retval The clock source can be one of the following values: - * @arg RCC_SAI1CLKSOURCE_PLLI2S: PLLI2S_Q clock divided by PLLI2SDIVQ used as SAI1 clock. - * @arg RCC_SAI1CLKSOURCE_PLLSAI: PLLISAI_Q clock divided by PLLSAIDIVQ used as SAI1 clock. - * @arg RCC_SAI1CLKSOURCE_PLLR: PLL VCO Output divided by PLLR used as SAI1 clock. - * @arg RCC_SAI1CLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin used as SAI1 clock. - */ -#define __HAL_RCC_GET_SAI1_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_SAI1SRC)) - -/** @brief Macro to configure SAI2 clock source selection. - * @note This configuration is only available with STM32F446xx Devices. - * @note This function must be called before enabling PLL, PLLSAI, PLLI2S and - * the SAI clock. - * @param __SOURCE__ specifies the SAI2 clock source. - * This parameter can be one of the following values: - * @arg RCC_SAI2CLKSOURCE_PLLI2S: PLLI2S_Q clock divided by PLLI2SDIVQ used as SAI2 clock. - * @arg RCC_SAI2CLKSOURCE_PLLSAI: PLLISAI_Q clock divided by PLLSAIDIVQ used as SAI2 clock. - * @arg RCC_SAI2CLKSOURCE_PLLR: PLL VCO Output divided by PLLR used as SAI2 clock. - * @arg RCC_SAI2CLKSOURCE_PLLSRC: HSI or HSE depending from PLL Source clock used as SAI2 clock. - */ -#define __HAL_RCC_SAI2_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_SAI2SRC, (__SOURCE__))) - -/** @brief Macro to Get SAI2 clock source selection. - * @note This configuration is only available with STM32F446xx Devices. - * @retval The clock source can be one of the following values: - * @arg RCC_SAI2CLKSOURCE_PLLI2S: PLLI2S_Q clock divided by PLLI2SDIVQ used as SAI2 clock. - * @arg RCC_SAI2CLKSOURCE_PLLSAI: PLLISAI_Q clock divided by PLLSAIDIVQ used as SAI2 clock. - * @arg RCC_SAI2CLKSOURCE_PLLR: PLL VCO Output divided by PLLR used as SAI2 clock. - * @arg RCC_SAI2CLKSOURCE_PLLSRC: HSI or HSE depending from PLL Source clock used as SAI2 clock. - */ -#define __HAL_RCC_GET_SAI2_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_SAI2SRC)) - -/** @brief Macro to configure I2S APB1 clock source selection. - * @note This function must be called before enabling PLL, PLLI2S and the I2S clock. - * @param __SOURCE__ specifies the I2S APB1 clock source. - * This parameter can be one of the following values: - * @arg RCC_I2SAPB1CLKSOURCE_PLLI2S: PLLI2S VCO output clock divided by PLLI2SR used as I2S clock. - * @arg RCC_I2SAPB1CLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin used as I2S APB1 clock. - * @arg RCC_I2SAPB1CLKSOURCE_PLLR: PLL VCO Output divided by PLLR used as I2S APB1 clock. - * @arg RCC_I2SAPB1CLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. - */ -#define __HAL_RCC_I2S_APB1_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_I2S1SRC, (__SOURCE__))) - -/** @brief Macro to Get I2S APB1 clock source selection. - * @retval The clock source can be one of the following values: - * @arg RCC_I2SAPB1CLKSOURCE_PLLI2S: PLLI2S VCO output clock divided by PLLI2SR used as I2S clock. - * @arg RCC_I2SAPB1CLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin used as I2S APB1 clock. - * @arg RCC_I2SAPB1CLKSOURCE_PLLR: PLL VCO Output divided by PLLR used as I2S APB1 clock. - * @arg RCC_I2SAPB1CLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. - */ -#define __HAL_RCC_GET_I2S_APB1_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_I2S1SRC)) - -/** @brief Macro to configure I2S APB2 clock source selection. - * @note This function must be called before enabling PLL, PLLI2S and the I2S clock. - * @param __SOURCE__ specifies the SAI Block A clock source. - * This parameter can be one of the following values: - * @arg RCC_I2SAPB2CLKSOURCE_PLLI2S: PLLI2S VCO output clock divided by PLLI2SR used as I2S clock. - * @arg RCC_I2SAPB2CLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin used as I2S APB2 clock. - * @arg RCC_I2SAPB2CLKSOURCE_PLLR: PLL VCO Output divided by PLLR used as I2S APB2 clock. - * @arg RCC_I2SAPB2CLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. - */ -#define __HAL_RCC_I2S_APB2_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_I2S2SRC, (__SOURCE__))) - -/** @brief Macro to Get I2S APB2 clock source selection. - * @retval The clock source can be one of the following values: - * @arg RCC_I2SAPB2CLKSOURCE_PLLI2S: PLLI2S VCO output clock divided by PLLI2SR used as I2S clock. - * @arg RCC_I2SAPB2CLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin used as I2S APB2 clock. - * @arg RCC_I2SAPB2CLKSOURCE_PLLR: PLL VCO Output divided by PLLR used as I2S APB2 clock. - * @arg RCC_I2SAPB2CLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. - */ -#define __HAL_RCC_GET_I2S_APB2_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_I2S2SRC)) - -/** @brief Macro to configure the CEC clock. - * @param __SOURCE__ specifies the CEC clock source. - * This parameter can be one of the following values: - * @arg RCC_CECCLKSOURCE_HSI: HSI selected as CEC clock - * @arg RCC_CECCLKSOURCE_LSE: LSE selected as CEC clock - */ -#define __HAL_RCC_CEC_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_CECSEL, (uint32_t)(__SOURCE__))) - -/** @brief Macro to Get the CEC clock. - * @retval The clock source can be one of the following values: - * @arg RCC_CECCLKSOURCE_HSI488: HSI selected as CEC clock - * @arg RCC_CECCLKSOURCE_LSE: LSE selected as CEC clock - */ -#define __HAL_RCC_GET_CEC_SOURCE() (READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_CECSEL)) - -/** @brief Macro to configure the FMPI2C1 clock. - * @param __SOURCE__ specifies the FMPI2C1 clock source. - * This parameter can be one of the following values: - * @arg RCC_FMPI2C1CLKSOURCE_PCLK1: PCLK1 selected as FMPI2C1 clock - * @arg RCC_FMPI2C1CLKSOURCE_SYSCLK: SYS clock selected as FMPI2C1 clock - * @arg RCC_FMPI2C1CLKSOURCE_HSI: HSI selected as FMPI2C1 clock - */ -#define __HAL_RCC_FMPI2C1_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_FMPI2C1SEL, (uint32_t)(__SOURCE__))) - -/** @brief Macro to Get the FMPI2C1 clock. - * @retval The clock source can be one of the following values: - * @arg RCC_FMPI2C1CLKSOURCE_PCLK1: PCLK1 selected as FMPI2C1 clock - * @arg RCC_FMPI2C1CLKSOURCE_SYSCLK: SYS clock selected as FMPI2C1 clock - * @arg RCC_FMPI2C1CLKSOURCE_HSI: HSI selected as FMPI2C1 clock - */ -#define __HAL_RCC_GET_FMPI2C1_SOURCE() (READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_FMPI2C1SEL)) - -/** @brief Macro to configure the CLK48 clock. - * @param __SOURCE__ specifies the CLK48 clock source. - * This parameter can be one of the following values: - * @arg RCC_CLK48CLKSOURCE_PLLQ: PLL VCO Output divided by PLLQ used as CLK48 clock. - * @arg RCC_CLK48CLKSOURCE_PLLSAIP: PLLSAI VCO Output divided by PLLSAIP used as CLK48 clock. - */ -#define __HAL_RCC_CLK48_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_CK48MSEL, (uint32_t)(__SOURCE__))) - -/** @brief Macro to Get the CLK48 clock. - * @retval The clock source can be one of the following values: - * @arg RCC_CLK48CLKSOURCE_PLLQ: PLL VCO Output divided by PLLQ used as CLK48 clock. - * @arg RCC_CLK48CLKSOURCE_PLLSAIP: PLLSAI VCO Output divided by PLLSAIP used as CLK48 clock. - */ -#define __HAL_RCC_GET_CLK48_SOURCE() (READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_CK48MSEL)) - -/** @brief Macro to configure the SDIO clock. - * @param __SOURCE__ specifies the SDIO clock source. - * This parameter can be one of the following values: - * @arg RCC_SDIOCLKSOURCE_CLK48: CLK48 output used as SDIO clock. - * @arg RCC_SDIOCLKSOURCE_SYSCLK: System clock output used as SDIO clock. - */ -#define __HAL_RCC_SDIO_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_SDIOSEL, (uint32_t)(__SOURCE__))) - -/** @brief Macro to Get the SDIO clock. - * @retval The clock source can be one of the following values: - * @arg RCC_SDIOCLKSOURCE_CLK48: CLK48 output used as SDIO clock. - * @arg RCC_SDIOCLKSOURCE_SYSCLK: System clock output used as SDIO clock. - */ -#define __HAL_RCC_GET_SDIO_SOURCE() (READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_SDIOSEL)) - -/** @brief Macro to configure the SPDIFRX clock. - * @param __SOURCE__ specifies the SPDIFRX clock source. - * This parameter can be one of the following values: - * @arg RCC_SPDIFRXCLKSOURCE_PLLR: PLL VCO Output divided by PLLR used as SPDIFRX clock. - * @arg RCC_SPDIFRXCLKSOURCE_PLLI2SP: PLLI2S VCO Output divided by PLLI2SP used as SPDIFRX clock. - */ -#define __HAL_RCC_SPDIFRX_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_SPDIFRXSEL, (uint32_t)(__SOURCE__))) - -/** @brief Macro to Get the SPDIFRX clock. - * @retval The clock source can be one of the following values: - * @arg RCC_SPDIFRXCLKSOURCE_PLLR: PLL VCO Output divided by PLLR used as SPDIFRX clock. - * @arg RCC_SPDIFRXCLKSOURCE_PLLI2SP: PLLI2S VCO Output divided by PLLI2SP used as SPDIFRX clock. - */ -#define __HAL_RCC_GET_SPDIFRX_SOURCE() (READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_SPDIFRXSEL)) -#endif /* STM32F446xx */ - -#if defined(STM32F469xx) || defined(STM32F479xx) - -/** @brief Macro to configure the CLK48 clock. - * @param __SOURCE__ specifies the CLK48 clock source. - * This parameter can be one of the following values: - * @arg RCC_CLK48CLKSOURCE_PLLQ: PLL VCO Output divided by PLLQ used as CLK48 clock. - * @arg RCC_CLK48CLKSOURCE_PLLSAIP: PLLSAI VCO Output divided by PLLSAIP used as CLK48 clock. - */ -#define __HAL_RCC_CLK48_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_CK48MSEL, (uint32_t)(__SOURCE__))) - -/** @brief Macro to Get the CLK48 clock. - * @retval The clock source can be one of the following values: - * @arg RCC_CLK48CLKSOURCE_PLLQ: PLL VCO Output divided by PLLQ used as CLK48 clock. - * @arg RCC_CLK48CLKSOURCE_PLLSAIP: PLLSAI VCO Output divided by PLLSAIP used as CLK48 clock. - */ -#define __HAL_RCC_GET_CLK48_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_CK48MSEL)) - -/** @brief Macro to configure the SDIO clock. - * @param __SOURCE__ specifies the SDIO clock source. - * This parameter can be one of the following values: - * @arg RCC_SDIOCLKSOURCE_CLK48: CLK48 output used as SDIO clock. - * @arg RCC_SDIOCLKSOURCE_SYSCLK: System clock output used as SDIO clock. - */ -#define __HAL_RCC_SDIO_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_SDIOSEL, (uint32_t)(__SOURCE__))) - -/** @brief Macro to Get the SDIO clock. - * @retval The clock source can be one of the following values: - * @arg RCC_SDIOCLKSOURCE_CLK48: CLK48 output used as SDIO clock. - * @arg RCC_SDIOCLKSOURCE_SYSCLK: System clock output used as SDIO clock. - */ -#define __HAL_RCC_GET_SDIO_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_SDIOSEL)) - -/** @brief Macro to configure the DSI clock. - * @param __SOURCE__ specifies the DSI clock source. - * This parameter can be one of the following values: - * @arg RCC_DSICLKSOURCE_PLLR: PLLR output used as DSI clock. - * @arg RCC_DSICLKSOURCE_DSIPHY: DSI-PHY output used as DSI clock. - */ -#define __HAL_RCC_DSI_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_DSISEL, (uint32_t)(__SOURCE__))) - -/** @brief Macro to Get the DSI clock. - * @retval The clock source can be one of the following values: - * @arg RCC_DSICLKSOURCE_PLLR: PLLR output used as DSI clock. - * @arg RCC_DSICLKSOURCE_DSIPHY: DSI-PHY output used as DSI clock. - */ -#define __HAL_RCC_GET_DSI_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_DSISEL)) - -#endif /* STM32F469xx || STM32F479xx */ - -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) ||\ - defined(STM32F413xx) || defined(STM32F423xx) - /** @brief Macro to configure the DFSDM1 clock. - * @param __DFSDM1_CLKSOURCE__ specifies the DFSDM1 clock source. - * This parameter can be one of the following values: - * @arg RCC_DFSDM1CLKSOURCE_PCLK2: PCLK2 clock used as kernel clock. - * @arg RCC_DFSDM1CLKSOURCE_SYSCLK: System clock used as kernel clock. - * @retval None - */ -#define __HAL_RCC_DFSDM1_CONFIG(__DFSDM1_CLKSOURCE__) MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_CKDFSDM1SEL, (__DFSDM1_CLKSOURCE__)) - -/** @brief Macro to get the DFSDM1 clock source. - * @retval The clock source can be one of the following values: - * @arg RCC_DFSDM1CLKSOURCE_PCLK2: PCLK2 clock used as kernel clock. - * @arg RCC_DFSDM1CLKSOURCE_SYSCLK: System clock used as kernel clock. - */ -#define __HAL_RCC_GET_DFSDM1_SOURCE() ((uint32_t)(READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_CKDFSDM1SEL))) - -/** @brief Macro to configure DFSDM1 Audio clock source selection. - * @note This configuration is only available with STM32F412Zx/STM32F412Vx/STM32F412Rx/STM32F412Cx/ - STM32F413xx/STM32F423xx Devices. - * @param __SOURCE__ specifies the DFSDM1 Audio clock source. - * This parameter can be one of the following values: - * @arg RCC_DFSDM1AUDIOCLKSOURCE_I2S1: CK_I2S_PCLK1 selected as audio clock - * @arg RCC_DFSDM1AUDIOCLKSOURCE_I2S2: CK_I2S_PCLK2 selected as audio clock - */ -#define __HAL_RCC_DFSDM1AUDIO_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_CKDFSDM1ASEL, (__SOURCE__))) - -/** @brief Macro to Get DFSDM1 Audio clock source selection. - * @note This configuration is only available with STM32F412Zx/STM32F412Vx/STM32F412Rx/STM32F412Cx/ - STM32F413xx/STM32F423xx Devices. - * @retval The clock source can be one of the following values: - * @arg RCC_DFSDM1AUDIOCLKSOURCE_I2S1: CK_I2S_PCLK1 selected as audio clock - * @arg RCC_DFSDM1AUDIOCLKSOURCE_I2S2: CK_I2S_PCLK2 selected as audio clock - */ -#define __HAL_RCC_GET_DFSDM1AUDIO_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_CKDFSDM1ASEL)) - -#if defined(STM32F413xx) || defined(STM32F423xx) - /** @brief Macro to configure the DFSDM2 clock. - * @param __DFSDM2_CLKSOURCE__ specifies the DFSDM1 clock source. - * This parameter can be one of the following values: - * @arg RCC_DFSDM2CLKSOURCE_PCLK2: PCLK2 clock used as kernel clock. - * @arg RCC_DFSDM2CLKSOURCE_SYSCLK: System clock used as kernel clock. - * @retval None - */ -#define __HAL_RCC_DFSDM2_CONFIG(__DFSDM2_CLKSOURCE__) MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_CKDFSDM1SEL, (__DFSDM2_CLKSOURCE__)) - -/** @brief Macro to get the DFSDM2 clock source. - * @retval The clock source can be one of the following values: - * @arg RCC_DFSDM2CLKSOURCE_PCLK2: PCLK2 clock used as kernel clock. - * @arg RCC_DFSDM2CLKSOURCE_SYSCLK: System clock used as kernel clock. - */ -#define __HAL_RCC_GET_DFSDM2_SOURCE() ((uint32_t)(READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_CKDFSDM1SEL))) - -/** @brief Macro to configure DFSDM1 Audio clock source selection. - * @note This configuration is only available with STM32F413xx/STM32F423xx Devices. - * @param __SOURCE__ specifies the DFSDM2 Audio clock source. - * This parameter can be one of the following values: - * @arg RCC_DFSDM2AUDIOCLKSOURCE_I2S1: CK_I2S_PCLK1 selected as audio clock - * @arg RCC_DFSDM2AUDIOCLKSOURCE_I2S2: CK_I2S_PCLK2 selected as audio clock - */ -#define __HAL_RCC_DFSDM2AUDIO_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_CKDFSDM2ASEL, (__SOURCE__))) - -/** @brief Macro to Get DFSDM2 Audio clock source selection. - * @note This configuration is only available with STM32F413xx/STM32F423xx Devices. - * @retval The clock source can be one of the following values: - * @arg RCC_DFSDM2AUDIOCLKSOURCE_I2S1: CK_I2S_PCLK1 selected as audio clock - * @arg RCC_DFSDM2AUDIOCLKSOURCE_I2S2: CK_I2S_PCLK2 selected as audio clock - */ -#define __HAL_RCC_GET_DFSDM2AUDIO_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_CKDFSDM2ASEL)) - -/** @brief Macro to configure SAI1BlockA clock source selection. - * @note The SAI peripheral is only available with STM32F413xx/STM32F423xx Devices. - * @note This function must be called before enabling PLLSAI, PLLI2S and - * the SAI clock. - * @param __SOURCE__ specifies the SAI Block A clock source. - * This parameter can be one of the following values: - * @arg RCC_SAIACLKSOURCE_PLLI2SR: PLLI2S_R clock divided (R2) used as SAI1 Block A clock. - * @arg RCC_SAIACLKSOURCE_EXT: External clock mapped on the I2S_CKIN pinused as SAI1 Block A clock. - * @arg RCC_SAIACLKSOURCE_PLLR: PLL_R clock divided (R1) used as SAI1 Block A clock. - * @arg RCC_SAIACLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. - */ -#define __HAL_RCC_SAI_BLOCKACLKSOURCE_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_SAI1ASRC, (__SOURCE__))) - -/** @brief Macro to Get SAI1 BlockA clock source selection. - * @note This configuration is only available with STM32F413xx/STM32F423xx Devices. - * @retval The clock source can be one of the following values: - * @arg RCC_SAIACLKSOURCE_PLLI2SR: PLLI2S_R clock divided (R2) used as SAI1 Block A clock. - * @arg RCC_SAIACLKSOURCE_EXT: External clock mapped on the I2S_CKIN pinused as SAI1 Block A clock. - * @arg RCC_SAIACLKSOURCE_PLLR: PLL_R clock divided (R1) used as SAI1 Block A clock. - * @arg RCC_SAIACLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. - */ -#define __HAL_RCC_GET_SAI_BLOCKA_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_SAI1ASRC)) - -/** @brief Macro to configure SAI1 BlockB clock source selection. - * @note The SAI peripheral is only available with STM32F413xx/STM32F423xx Devices. - * @note This function must be called before enabling PLLSAI, PLLI2S and - * the SAI clock. - * @param __SOURCE__ specifies the SAI Block B clock source. - * This parameter can be one of the following values: - * @arg RCC_SAIBCLKSOURCE_PLLI2SR: PLLI2S_R clock divided (R2) used as SAI1 Block A clock. - * @arg RCC_SAIBCLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin used as SAI1 Block A clock. - * @arg RCC_SAIBCLKSOURCE_PLLR: PLL_R clock divided (R1) used as SAI1 Block A clock. - * @arg RCC_SAIBCLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. - */ -#define __HAL_RCC_SAI_BLOCKBCLKSOURCE_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_SAI1BSRC, (__SOURCE__))) - -/** @brief Macro to Get SAI1 BlockB clock source selection. - * @note This configuration is only available with STM32F413xx/STM32F423xx Devices. - * @retval The clock source can be one of the following values: - * @arg RCC_SAIBCLKSOURCE_PLLI2SR: PLLI2S_R clock divided (R2) used as SAI1 Block A clock. - * @arg RCC_SAIBCLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin used as SAI1 Block A clock. - * @arg RCC_SAIBCLKSOURCE_PLLR: PLL_R clock divided (R1) used as SAI1 Block A clock. - * @arg RCC_SAIBCLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. - */ -#define __HAL_RCC_GET_SAI_BLOCKB_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_SAI1BSRC)) - -/** @brief Macro to configure the LPTIM1 clock. - * @param __SOURCE__ specifies the LPTIM1 clock source. - * This parameter can be one of the following values: - * @arg RCC_LPTIM1CLKSOURCE_PCLK1: PCLK selected as LPTIM1 clock - * @arg RCC_LPTIM1CLKSOURCE_HSI: HSI clock selected as LPTIM1 clock - * @arg RCC_LPTIM1CLKSOURCE_LSI: LSI selected as LPTIM1 clock - * @arg RCC_LPTIM1CLKSOURCE_LSE: LSE selected as LPTIM1 clock - */ -#define __HAL_RCC_LPTIM1_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_LPTIM1SEL, (uint32_t)(__SOURCE__))) - -/** @brief Macro to Get the LPTIM1 clock. - * @retval The clock source can be one of the following values: - * @arg RCC_LPTIM1CLKSOURCE_PCLK1: PCLK selected as LPTIM1 clock - * @arg RCC_LPTIM1CLKSOURCE_HSI: HSI clock selected as LPTIM1 clock - * @arg RCC_LPTIM1CLKSOURCE_LSI: LSI selected as LPTIM1 clock - * @arg RCC_LPTIM1CLKSOURCE_LSE: LSE selected as LPTIM1 clock - */ -#define __HAL_RCC_GET_LPTIM1_SOURCE() (READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_LPTIM1SEL)) -#endif /* STM32F413xx || STM32F423xx */ - -/** @brief Macro to configure I2S APB1 clock source selection. - * @param __SOURCE__ specifies the I2S APB1 clock source. - * This parameter can be one of the following values: - * @arg RCC_I2SAPB1CLKSOURCE_PLLI2S: PLLI2S VCO output clock divided by PLLI2SR. - * @arg RCC_I2SAPB1CLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin. - * @arg RCC_I2SAPB1CLKSOURCE_PLLR: PLL VCO Output divided by PLLR. - * @arg RCC_I2SAPB1CLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. - */ -#define __HAL_RCC_I2S_APB1_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_I2S1SRC, (__SOURCE__))) - -/** @brief Macro to Get I2S APB1 clock source selection. - * @retval The clock source can be one of the following values: - * @arg RCC_I2SAPB1CLKSOURCE_PLLI2S: PLLI2S VCO output clock divided by PLLI2SR. - * @arg RCC_I2SAPB1CLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin. - * @arg RCC_I2SAPB1CLKSOURCE_PLLR: PLL VCO Output divided by PLLR. - * @arg RCC_I2SAPB1CLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. - */ -#define __HAL_RCC_GET_I2S_APB1_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_I2S1SRC)) - -/** @brief Macro to configure I2S APB2 clock source selection. - * @param __SOURCE__ specifies the I2S APB2 clock source. - * This parameter can be one of the following values: - * @arg RCC_I2SAPB2CLKSOURCE_PLLI2S: PLLI2S VCO output clock divided by PLLI2SR. - * @arg RCC_I2SAPB2CLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin. - * @arg RCC_I2SAPB2CLKSOURCE_PLLR: PLL VCO Output divided by PLLR. - * @arg RCC_I2SAPB2CLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. - */ -#define __HAL_RCC_I2S_APB2_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_I2S2SRC, (__SOURCE__))) - -/** @brief Macro to Get I2S APB2 clock source selection. - * @retval The clock source can be one of the following values: - * @arg RCC_I2SAPB2CLKSOURCE_PLLI2S: PLLI2S VCO output clock divided by PLLI2SR. - * @arg RCC_I2SAPB2CLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin. - * @arg RCC_I2SAPB2CLKSOURCE_PLLR: PLL VCO Output divided by PLLR. - * @arg RCC_I2SAPB2CLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. - */ -#define __HAL_RCC_GET_I2S_APB2_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_I2S2SRC)) - -/** @brief Macro to configure the PLL I2S clock source (PLLI2SCLK). - * @note This macro must be called before enabling the I2S APB clock. - * @param __SOURCE__ specifies the I2S clock source. - * This parameter can be one of the following values: - * @arg RCC_PLLI2SCLKSOURCE_PLLSRC: HSI or HSE depending from PLL source Clock. - * @arg RCC_PLLI2SCLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin - * used as I2S clock source. - */ -#define __HAL_RCC_PLL_I2S_CONFIG(__SOURCE__) (*(__IO uint32_t *) RCC_PLLI2SCFGR_PLLI2SSRC_BB = (__SOURCE__)) - -/** @brief Macro to configure the FMPI2C1 clock. - * @param __SOURCE__ specifies the FMPI2C1 clock source. - * This parameter can be one of the following values: - * @arg RCC_FMPI2C1CLKSOURCE_PCLK1: PCLK1 selected as FMPI2C1 clock - * @arg RCC_FMPI2C1CLKSOURCE_SYSCLK: SYS clock selected as FMPI2C1 clock - * @arg RCC_FMPI2C1CLKSOURCE_HSI: HSI selected as FMPI2C1 clock - */ -#define __HAL_RCC_FMPI2C1_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_FMPI2C1SEL, (uint32_t)(__SOURCE__))) - -/** @brief Macro to Get the FMPI2C1 clock. - * @retval The clock source can be one of the following values: - * @arg RCC_FMPI2C1CLKSOURCE_PCLK1: PCLK1 selected as FMPI2C1 clock - * @arg RCC_FMPI2C1CLKSOURCE_SYSCLK: SYS clock selected as FMPI2C1 clock - * @arg RCC_FMPI2C1CLKSOURCE_HSI: HSI selected as FMPI2C1 clock - */ -#define __HAL_RCC_GET_FMPI2C1_SOURCE() (READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_FMPI2C1SEL)) - -/** @brief Macro to configure the CLK48 clock. - * @param __SOURCE__ specifies the CLK48 clock source. - * This parameter can be one of the following values: - * @arg RCC_CLK48CLKSOURCE_PLLQ: PLL VCO Output divided by PLLQ used as CLK48 clock. - * @arg RCC_CLK48CLKSOURCE_PLLI2SQ: PLLI2S VCO Output divided by PLLI2SQ used as CLK48 clock. - */ -#define __HAL_RCC_CLK48_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_CK48MSEL, (uint32_t)(__SOURCE__))) - -/** @brief Macro to Get the CLK48 clock. - * @retval The clock source can be one of the following values: - * @arg RCC_CLK48CLKSOURCE_PLLQ: PLL VCO Output divided by PLLQ used as CLK48 clock. - * @arg RCC_CLK48CLKSOURCE_PLLI2SQ: PLLI2S VCO Output divided by PLLI2SQ used as CLK48 clock - */ -#define __HAL_RCC_GET_CLK48_SOURCE() (READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_CK48MSEL)) - -/** @brief Macro to configure the SDIO clock. - * @param __SOURCE__ specifies the SDIO clock source. - * This parameter can be one of the following values: - * @arg RCC_SDIOCLKSOURCE_CLK48: CLK48 output used as SDIO clock. - * @arg RCC_SDIOCLKSOURCE_SYSCLK: System clock output used as SDIO clock. - */ -#define __HAL_RCC_SDIO_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_SDIOSEL, (uint32_t)(__SOURCE__))) - -/** @brief Macro to Get the SDIO clock. - * @retval The clock source can be one of the following values: - * @arg RCC_SDIOCLKSOURCE_CLK48: CLK48 output used as SDIO clock. - * @arg RCC_SDIOCLKSOURCE_SYSCLK: System clock output used as SDIO clock. - */ -#define __HAL_RCC_GET_SDIO_SOURCE() (READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_SDIOSEL)) - -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -/** @brief Macro to configure I2S clock source selection. - * @param __SOURCE__ specifies the I2S clock source. - * This parameter can be one of the following values: - * @arg RCC_I2SAPBCLKSOURCE_PLLR: PLL VCO output clock divided by PLLR. - * @arg RCC_I2SAPBCLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin. - * @arg RCC_I2SAPBCLKSOURCE_PLLSRC: HSI/HSE depends on PLLSRC. - */ -#define __HAL_RCC_I2S_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_I2SSRC, (__SOURCE__))) - -/** @brief Macro to Get I2S clock source selection. - * @retval The clock source can be one of the following values: - * @arg RCC_I2SAPBCLKSOURCE_PLLR: PLL VCO output clock divided by PLLR. - * @arg RCC_I2SAPBCLKSOURCE_EXT: External clock mapped on the I2S_CKIN pin. - * @arg RCC_I2SAPBCLKSOURCE_PLLSRC: HSI/HSE depends on PLLSRC. - */ -#define __HAL_RCC_GET_I2S_SOURCE() (READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_I2SSRC)) - -/** @brief Macro to configure the FMPI2C1 clock. - * @param __SOURCE__ specifies the FMPI2C1 clock source. - * This parameter can be one of the following values: - * @arg RCC_FMPI2C1CLKSOURCE_PCLK1: PCLK1 selected as FMPI2C1 clock - * @arg RCC_FMPI2C1CLKSOURCE_SYSCLK: SYS clock selected as FMPI2C1 clock - * @arg RCC_FMPI2C1CLKSOURCE_HSI: HSI selected as FMPI2C1 clock - */ -#define __HAL_RCC_FMPI2C1_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_FMPI2C1SEL, (uint32_t)(__SOURCE__))) - -/** @brief Macro to Get the FMPI2C1 clock. - * @retval The clock source can be one of the following values: - * @arg RCC_FMPI2C1CLKSOURCE_PCLK1: PCLK1 selected as FMPI2C1 clock - * @arg RCC_FMPI2C1CLKSOURCE_SYSCLK: SYS clock selected as FMPI2C1 clock - * @arg RCC_FMPI2C1CLKSOURCE_HSI: HSI selected as FMPI2C1 clock - */ -#define __HAL_RCC_GET_FMPI2C1_SOURCE() (READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_FMPI2C1SEL)) - -/** @brief Macro to configure the LPTIM1 clock. - * @param __SOURCE__ specifies the LPTIM1 clock source. - * This parameter can be one of the following values: - * @arg RCC_LPTIM1CLKSOURCE_PCLK1: PCLK1 selected as LPTIM1 clock - * @arg RCC_LPTIM1CLKSOURCE_HSI: HSI clock selected as LPTIM1 clock - * @arg RCC_LPTIM1CLKSOURCE_LSI: LSI selected as LPTIM1 clock - * @arg RCC_LPTIM1CLKSOURCE_LSE: LSE selected as LPTIM1 clock - */ -#define __HAL_RCC_LPTIM1_CONFIG(__SOURCE__) (MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_LPTIM1SEL, (uint32_t)(__SOURCE__))) - -/** @brief Macro to Get the LPTIM1 clock. - * @retval The clock source can be one of the following values: - * @arg RCC_LPTIM1CLKSOURCE_PCLK1: PCLK1 selected as LPTIM1 clock - * @arg RCC_LPTIM1CLKSOURCE_HSI: HSI clock selected as LPTIM1 clock - * @arg RCC_LPTIM1CLKSOURCE_LSI: LSI selected as LPTIM1 clock - * @arg RCC_LPTIM1CLKSOURCE_LSE: LSE selected as LPTIM1 clock - */ -#define __HAL_RCC_GET_LPTIM1_SOURCE() (READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_LPTIM1SEL)) -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F410Tx) || defined(STM32F410Cx) ||\ - defined(STM32F410Rx) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F469xx) ||\ - defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) ||\ - defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/** @brief Macro to configure the Timers clocks prescalers - * @note This feature is only available with STM32F429x/439x Devices. - * @param __PRESC__ specifies the Timers clocks prescalers selection - * This parameter can be one of the following values: - * @arg RCC_TIMPRES_DESACTIVATED: The Timers kernels clocks prescaler is - * equal to HPRE if PPREx is corresponding to division by 1 or 2, - * else it is equal to [(HPRE * PPREx) / 2] if PPREx is corresponding to - * division by 4 or more. - * @arg RCC_TIMPRES_ACTIVATED: The Timers kernels clocks prescaler is - * equal to HPRE if PPREx is corresponding to division by 1, 2 or 4, - * else it is equal to [(HPRE * PPREx) / 4] if PPREx is corresponding - * to division by 8 or more. - */ -#define __HAL_RCC_TIMCLKPRESCALER(__PRESC__) (*(__IO uint32_t *) RCC_DCKCFGR_TIMPRE_BB = (__PRESC__)) - -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx) || STM32F401xC || STM32F401xE || STM32F410xx || STM32F411xE ||\ - STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx ||\ - STM32F423xx */ - -/*----------------------------------------------------------------------------*/ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -/** @brief Enable PLLSAI_RDY interrupt. - */ -#define __HAL_RCC_PLLSAI_ENABLE_IT() (RCC->CIR |= (RCC_CIR_PLLSAIRDYIE)) - -/** @brief Disable PLLSAI_RDY interrupt. - */ -#define __HAL_RCC_PLLSAI_DISABLE_IT() (RCC->CIR &= ~(RCC_CIR_PLLSAIRDYIE)) - -/** @brief Clear the PLLSAI RDY interrupt pending bits. - */ -#define __HAL_RCC_PLLSAI_CLEAR_IT() (RCC->CIR |= (RCC_CIR_PLLSAIRDYF)) - -/** @brief Check the PLLSAI RDY interrupt has occurred or not. - * @retval The new state (TRUE or FALSE). - */ -#define __HAL_RCC_PLLSAI_GET_IT() ((RCC->CIR & (RCC_CIR_PLLSAIRDYIE)) == (RCC_CIR_PLLSAIRDYIE)) - -/** @brief Check PLLSAI RDY flag is set or not. - * @retval The new state (TRUE or FALSE). - */ -#define __HAL_RCC_PLLSAI_GET_FLAG() ((RCC->CR & (RCC_CR_PLLSAIRDY)) == (RCC_CR_PLLSAIRDY)) - -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -/** @brief Macros to enable or disable the RCC MCO1 feature. - */ -#define __HAL_RCC_MCO1_ENABLE() (*(__IO uint32_t *) RCC_CFGR_MCO1EN_BB = ENABLE) -#define __HAL_RCC_MCO1_DISABLE() (*(__IO uint32_t *) RCC_CFGR_MCO1EN_BB = DISABLE) - -/** @brief Macros to enable or disable the RCC MCO2 feature. - */ -#define __HAL_RCC_MCO2_ENABLE() (*(__IO uint32_t *) RCC_CFGR_MCO2EN_BB = ENABLE) -#define __HAL_RCC_MCO2_DISABLE() (*(__IO uint32_t *) RCC_CFGR_MCO2EN_BB = DISABLE) - -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup RCCEx_Exported_Functions - * @{ - */ - -/** @addtogroup RCCEx_Exported_Functions_Group1 - * @{ - */ -HAL_StatusTypeDef HAL_RCCEx_PeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit); -void HAL_RCCEx_GetPeriphCLKConfig(RCC_PeriphCLKInitTypeDef *PeriphClkInit); - -uint32_t HAL_RCCEx_GetPeriphCLKFreq(uint32_t PeriphClk); - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F411xE) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) ||\ - defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) ||\ - defined(STM32F423xx) -void HAL_RCCEx_SelectLSEMode(uint8_t Mode); -#endif /* STM32F410xx || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ -#if defined(RCC_PLLI2S_SUPPORT) -HAL_StatusTypeDef HAL_RCCEx_EnablePLLI2S(RCC_PLLI2SInitTypeDef *PLLI2SInit); -HAL_StatusTypeDef HAL_RCCEx_DisablePLLI2S(void); -#endif /* RCC_PLLI2S_SUPPORT */ -#if defined(RCC_PLLSAI_SUPPORT) -HAL_StatusTypeDef HAL_RCCEx_EnablePLLSAI(RCC_PLLSAIInitTypeDef *PLLSAIInit); -HAL_StatusTypeDef HAL_RCCEx_DisablePLLSAI(void); -#endif /* RCC_PLLSAI_SUPPORT */ -/** - * @} - */ - -/** - * @} - */ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup RCCEx_Private_Constants RCCEx Private Constants - * @{ - */ - -/** @defgroup RCCEx_BitAddress_AliasRegion RCC BitAddress AliasRegion - * @brief RCC registers bit address in the alias region - * @{ - */ -/* --- CR Register ---*/ -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -/* Alias word address of PLLSAION bit */ -#define RCC_PLLSAION_BIT_NUMBER 0x1CU -#define RCC_CR_PLLSAION_BB (PERIPH_BB_BASE + (RCC_CR_OFFSET * 32U) + (RCC_PLLSAION_BIT_NUMBER * 4U)) - -#define PLLSAI_TIMEOUT_VALUE 2U /* Timeout value fixed to 2 ms */ -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || \ - defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || \ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F446xx) || \ - defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || \ - defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/* Alias word address of PLLI2SON bit */ -#define RCC_PLLI2SON_BIT_NUMBER 0x1AU -#define RCC_CR_PLLI2SON_BB (PERIPH_BB_BASE + (RCC_CR_OFFSET * 32U) + (RCC_PLLI2SON_BIT_NUMBER * 4U)) -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || - STM32F401xC || STM32F401xE || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || - STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ - -/* --- DCKCFGR Register ---*/ -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F401xC) ||\ - defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F469xx) ||\ - defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) ||\ - defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -/* Alias word address of TIMPRE bit */ -#define RCC_DCKCFGR_OFFSET (RCC_OFFSET + 0x8CU) -#define RCC_TIMPRE_BIT_NUMBER 0x18U -#define RCC_DCKCFGR_TIMPRE_BB (PERIPH_BB_BASE + (RCC_DCKCFGR_OFFSET * 32U) + (RCC_TIMPRE_BIT_NUMBER * 4U)) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F410xx || STM32F401xC ||\ - STM32F401xE || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx ||\ - STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ - -/* --- CFGR Register ---*/ -#define RCC_CFGR_OFFSET (RCC_OFFSET + 0x08U) -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || \ - defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || \ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F446xx) || \ - defined(STM32F469xx) || defined(STM32F479xx) -/* Alias word address of I2SSRC bit */ -#define RCC_I2SSRC_BIT_NUMBER 0x17U -#define RCC_CFGR_I2SSRC_BB (PERIPH_BB_BASE + (RCC_CFGR_OFFSET * 32U) + (RCC_I2SSRC_BIT_NUMBER * 4U)) - -#define PLLI2S_TIMEOUT_VALUE 2U /* Timeout value fixed to 2 ms */ -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || - STM32F401xC || STM32F401xE || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) ||\ - defined(STM32F413xx) || defined(STM32F423xx) -/* --- PLLI2SCFGR Register ---*/ -#define RCC_PLLI2SCFGR_OFFSET (RCC_OFFSET + 0x84U) -/* Alias word address of PLLI2SSRC bit */ -#define RCC_PLLI2SSRC_BIT_NUMBER 0x16U -#define RCC_PLLI2SCFGR_PLLI2SSRC_BB (PERIPH_BB_BASE + (RCC_PLLI2SCFGR_OFFSET * 32U) + (RCC_PLLI2SSRC_BIT_NUMBER * 4U)) - -#define PLLI2S_TIMEOUT_VALUE 2U /* Timeout value fixed to 2 ms */ -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx | STM32F423xx */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -/* Alias word address of MCO1EN bit */ -#define RCC_MCO1EN_BIT_NUMBER 0x8U -#define RCC_CFGR_MCO1EN_BB (PERIPH_BB_BASE + (RCC_CFGR_OFFSET * 32U) + (RCC_MCO1EN_BIT_NUMBER * 4U)) - -/* Alias word address of MCO2EN bit */ -#define RCC_MCO2EN_BIT_NUMBER 0x9U -#define RCC_CFGR_MCO2EN_BB (PERIPH_BB_BASE + (RCC_CFGR_OFFSET * 32U) + (RCC_MCO2EN_BIT_NUMBER * 4U)) -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -#define PLL_TIMEOUT_VALUE 2U /* 2 ms */ -/** - * @} - */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup RCCEx_Private_Macros RCCEx Private Macros - * @{ - */ -/** @defgroup RCCEx_IS_RCC_Definitions RCC Private macros to check input parameters - * @{ - */ -#define IS_RCC_PLLN_VALUE(VALUE) ((50U <= (VALUE)) && ((VALUE) <= 432U)) -#define IS_RCC_PLLI2SN_VALUE(VALUE) ((50U <= (VALUE)) && ((VALUE) <= 432U)) - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx)|| defined(STM32F439xx) -#define IS_RCC_PERIPHCLOCK(SELECTION) ((1U <= (SELECTION)) && ((SELECTION) <= 0x0000007FU)) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx */ - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx)|| defined(STM32F417xx) -#define IS_RCC_PERIPHCLOCK(SELECTION) ((1U <= (SELECTION)) && ((SELECTION) <= 0x00000007U)) -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ - -#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) -#define IS_RCC_PERIPHCLOCK(SELECTION) ((1U <= (SELECTION)) && ((SELECTION) <= 0x0000000FU)) -#endif /* STM32F401xC || STM32F401xE || STM32F411xE */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -#define IS_RCC_PERIPHCLOCK(SELECTION) ((1U <= (SELECTION)) && ((SELECTION) <= 0x0000001FU)) -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -#if defined(STM32F446xx) -#define IS_RCC_PERIPHCLOCK(SELECTION) ((1U <= (SELECTION)) && ((SELECTION) <= 0x00000FFFU)) -#endif /* STM32F446xx */ - -#if defined(STM32F469xx) || defined(STM32F479xx) -#define IS_RCC_PERIPHCLOCK(SELECTION) ((1U <= (SELECTION)) && ((SELECTION) <= 0x000001FFU)) -#endif /* STM32F469xx || STM32F479xx */ - -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) -#define IS_RCC_PERIPHCLOCK(SELECTION) ((1U <= (SELECTION)) && ((SELECTION) <= 0x000003FFU)) -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ - -#if defined(STM32F413xx) || defined(STM32F423xx) -#define IS_RCC_PERIPHCLOCK(SELECTION) ((1U <= (SELECTION)) && ((SELECTION) <= 0x00007FFFU)) -#endif /* STM32F413xx || STM32F423xx */ - -#define IS_RCC_PLLI2SR_VALUE(VALUE) ((2U <= (VALUE)) && ((VALUE) <= 7U)) - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx)|| defined(STM32F439xx) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -#define IS_RCC_PLLI2SQ_VALUE(VALUE) ((2U <= (VALUE)) && ((VALUE) <= 15U)) - -#define IS_RCC_PLLSAIN_VALUE(VALUE) ((50U <= (VALUE)) && ((VALUE) <= 432U)) - -#define IS_RCC_PLLSAIQ_VALUE(VALUE) ((2U <= (VALUE)) && ((VALUE) <= 15U)) - -#define IS_RCC_PLLSAIR_VALUE(VALUE) ((2U <= (VALUE)) && ((VALUE) <= 7U)) - -#define IS_RCC_PLLSAI_DIVQ_VALUE(VALUE) ((1U <= (VALUE)) && ((VALUE) <= 32U)) - -#define IS_RCC_PLLI2S_DIVQ_VALUE(VALUE) ((1U <= (VALUE)) && ((VALUE) <= 32U)) - -#define IS_RCC_PLLSAI_DIVR_VALUE(VALUE) (((VALUE) == RCC_PLLSAIDIVR_2) ||\ - ((VALUE) == RCC_PLLSAIDIVR_4) ||\ - ((VALUE) == RCC_PLLSAIDIVR_8) ||\ - ((VALUE) == RCC_PLLSAIDIVR_16)) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F411xE) || defined(STM32F446xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || \ - defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -#define IS_RCC_PLLI2SM_VALUE(VALUE) ((2U <= (VALUE)) && ((VALUE) <= 63U)) - -#define IS_RCC_LSE_MODE(MODE) (((MODE) == RCC_LSE_LOWPOWER_MODE) ||\ - ((MODE) == RCC_LSE_HIGHDRIVE_MODE)) -#endif /* STM32F411xE || STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -#define IS_RCC_PLLR_VALUE(VALUE) ((2U <= (VALUE)) && ((VALUE) <= 7U)) - -#define IS_RCC_LSE_MODE(MODE) (((MODE) == RCC_LSE_LOWPOWER_MODE) ||\ - ((MODE) == RCC_LSE_HIGHDRIVE_MODE)) - -#define IS_RCC_FMPI2C1CLKSOURCE(SOURCE) (((SOURCE) == RCC_FMPI2C1CLKSOURCE_PCLK1) ||\ - ((SOURCE) == RCC_FMPI2C1CLKSOURCE_SYSCLK) ||\ - ((SOURCE) == RCC_FMPI2C1CLKSOURCE_HSI)) - -#define IS_RCC_LPTIM1CLKSOURCE(SOURCE) (((SOURCE) == RCC_LPTIM1CLKSOURCE_PCLK1) ||\ - ((SOURCE) == RCC_LPTIM1CLKSOURCE_HSI) ||\ - ((SOURCE) == RCC_LPTIM1CLKSOURCE_LSI) ||\ - ((SOURCE) == RCC_LPTIM1CLKSOURCE_LSE)) - -#define IS_RCC_I2SAPBCLKSOURCE(SOURCE) (((SOURCE) == RCC_I2SAPBCLKSOURCE_PLLR) ||\ - ((SOURCE) == RCC_I2SAPBCLKSOURCE_EXT) ||\ - ((SOURCE) == RCC_I2SAPBCLKSOURCE_PLLSRC)) -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -#if defined(STM32F446xx) -#define IS_RCC_PLLR_VALUE(VALUE) ((2U <= (VALUE)) && ((VALUE) <= 7U)) - -#define IS_RCC_PLLI2SP_VALUE(VALUE) (((VALUE) == RCC_PLLI2SP_DIV2) ||\ - ((VALUE) == RCC_PLLI2SP_DIV4) ||\ - ((VALUE) == RCC_PLLI2SP_DIV6) ||\ - ((VALUE) == RCC_PLLI2SP_DIV8)) - -#define IS_RCC_PLLSAIM_VALUE(VALUE) ((VALUE) <= 63U) - -#define IS_RCC_PLLSAIP_VALUE(VALUE) (((VALUE) == RCC_PLLSAIP_DIV2) ||\ - ((VALUE) == RCC_PLLSAIP_DIV4) ||\ - ((VALUE) == RCC_PLLSAIP_DIV6) ||\ - ((VALUE) == RCC_PLLSAIP_DIV8)) - -#define IS_RCC_SAI1CLKSOURCE(SOURCE) (((SOURCE) == RCC_SAI1CLKSOURCE_PLLSAI) ||\ - ((SOURCE) == RCC_SAI1CLKSOURCE_PLLI2S) ||\ - ((SOURCE) == RCC_SAI1CLKSOURCE_PLLR) ||\ - ((SOURCE) == RCC_SAI1CLKSOURCE_EXT)) - -#define IS_RCC_SAI2CLKSOURCE(SOURCE) (((SOURCE) == RCC_SAI2CLKSOURCE_PLLSAI) ||\ - ((SOURCE) == RCC_SAI2CLKSOURCE_PLLI2S) ||\ - ((SOURCE) == RCC_SAI2CLKSOURCE_PLLR) ||\ - ((SOURCE) == RCC_SAI2CLKSOURCE_PLLSRC)) - -#define IS_RCC_I2SAPB1CLKSOURCE(SOURCE) (((SOURCE) == RCC_I2SAPB1CLKSOURCE_PLLI2S) ||\ - ((SOURCE) == RCC_I2SAPB1CLKSOURCE_EXT) ||\ - ((SOURCE) == RCC_I2SAPB1CLKSOURCE_PLLR) ||\ - ((SOURCE) == RCC_I2SAPB1CLKSOURCE_PLLSRC)) - - #define IS_RCC_I2SAPB2CLKSOURCE(SOURCE) (((SOURCE) == RCC_I2SAPB2CLKSOURCE_PLLI2S) ||\ - ((SOURCE) == RCC_I2SAPB2CLKSOURCE_EXT) ||\ - ((SOURCE) == RCC_I2SAPB2CLKSOURCE_PLLR) ||\ - ((SOURCE) == RCC_I2SAPB2CLKSOURCE_PLLSRC)) - -#define IS_RCC_FMPI2C1CLKSOURCE(SOURCE) (((SOURCE) == RCC_FMPI2C1CLKSOURCE_PCLK1) ||\ - ((SOURCE) == RCC_FMPI2C1CLKSOURCE_SYSCLK) ||\ - ((SOURCE) == RCC_FMPI2C1CLKSOURCE_HSI)) - -#define IS_RCC_CECCLKSOURCE(SOURCE) (((SOURCE) == RCC_CECCLKSOURCE_HSI) ||\ - ((SOURCE) == RCC_CECCLKSOURCE_LSE)) - -#define IS_RCC_CLK48CLKSOURCE(SOURCE) (((SOURCE) == RCC_CLK48CLKSOURCE_PLLQ) ||\ - ((SOURCE) == RCC_CLK48CLKSOURCE_PLLSAIP)) - -#define IS_RCC_SDIOCLKSOURCE(SOURCE) (((SOURCE) == RCC_SDIOCLKSOURCE_CLK48) ||\ - ((SOURCE) == RCC_SDIOCLKSOURCE_SYSCLK)) - -#define IS_RCC_SPDIFRXCLKSOURCE(SOURCE) (((SOURCE) == RCC_SPDIFRXCLKSOURCE_PLLR) ||\ - ((SOURCE) == RCC_SPDIFRXCLKSOURCE_PLLI2SP)) -#endif /* STM32F446xx */ - -#if defined(STM32F469xx) || defined(STM32F479xx) -#define IS_RCC_PLLR_VALUE(VALUE) ((2U <= (VALUE)) && ((VALUE) <= 7U)) - -#define IS_RCC_PLLSAIP_VALUE(VALUE) (((VALUE) == RCC_PLLSAIP_DIV2) ||\ - ((VALUE) == RCC_PLLSAIP_DIV4) ||\ - ((VALUE) == RCC_PLLSAIP_DIV6) ||\ - ((VALUE) == RCC_PLLSAIP_DIV8)) - -#define IS_RCC_CLK48CLKSOURCE(SOURCE) (((SOURCE) == RCC_CLK48CLKSOURCE_PLLQ) ||\ - ((SOURCE) == RCC_CLK48CLKSOURCE_PLLSAIP)) - -#define IS_RCC_SDIOCLKSOURCE(SOURCE) (((SOURCE) == RCC_SDIOCLKSOURCE_CLK48) ||\ - ((SOURCE) == RCC_SDIOCLKSOURCE_SYSCLK)) - -#define IS_RCC_DSIBYTELANECLKSOURCE(SOURCE) (((SOURCE) == RCC_DSICLKSOURCE_PLLR) ||\ - ((SOURCE) == RCC_DSICLKSOURCE_DSIPHY)) - -#define IS_RCC_LSE_MODE(MODE) (((MODE) == RCC_LSE_LOWPOWER_MODE) ||\ - ((MODE) == RCC_LSE_HIGHDRIVE_MODE)) -#endif /* STM32F469xx || STM32F479xx */ - -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) ||\ - defined(STM32F413xx) || defined(STM32F423xx) -#define IS_RCC_PLLI2SQ_VALUE(VALUE) ((2U <= (VALUE)) && ((VALUE) <= 15U)) - -#define IS_RCC_PLLR_VALUE(VALUE) ((2U <= (VALUE)) && ((VALUE) <= 7U)) - -#define IS_RCC_PLLI2SCLKSOURCE(__SOURCE__) (((__SOURCE__) == RCC_PLLI2SCLKSOURCE_PLLSRC) || \ - ((__SOURCE__) == RCC_PLLI2SCLKSOURCE_EXT)) - -#define IS_RCC_I2SAPB1CLKSOURCE(SOURCE) (((SOURCE) == RCC_I2SAPB1CLKSOURCE_PLLI2S) ||\ - ((SOURCE) == RCC_I2SAPB1CLKSOURCE_EXT) ||\ - ((SOURCE) == RCC_I2SAPB1CLKSOURCE_PLLR) ||\ - ((SOURCE) == RCC_I2SAPB1CLKSOURCE_PLLSRC)) - - #define IS_RCC_I2SAPB2CLKSOURCE(SOURCE) (((SOURCE) == RCC_I2SAPB2CLKSOURCE_PLLI2S) ||\ - ((SOURCE) == RCC_I2SAPB2CLKSOURCE_EXT) ||\ - ((SOURCE) == RCC_I2SAPB2CLKSOURCE_PLLR) ||\ - ((SOURCE) == RCC_I2SAPB2CLKSOURCE_PLLSRC)) - -#define IS_RCC_FMPI2C1CLKSOURCE(SOURCE) (((SOURCE) == RCC_FMPI2C1CLKSOURCE_PCLK1) ||\ - ((SOURCE) == RCC_FMPI2C1CLKSOURCE_SYSCLK) ||\ - ((SOURCE) == RCC_FMPI2C1CLKSOURCE_HSI)) - -#define IS_RCC_CLK48CLKSOURCE(SOURCE) (((SOURCE) == RCC_CLK48CLKSOURCE_PLLQ) ||\ - ((SOURCE) == RCC_CLK48CLKSOURCE_PLLI2SQ)) - -#define IS_RCC_SDIOCLKSOURCE(SOURCE) (((SOURCE) == RCC_SDIOCLKSOURCE_CLK48) ||\ - ((SOURCE) == RCC_SDIOCLKSOURCE_SYSCLK)) - -#define IS_RCC_DFSDM1CLKSOURCE(__SOURCE__) (((__SOURCE__) == RCC_DFSDM1CLKSOURCE_PCLK2) || \ - ((__SOURCE__) == RCC_DFSDM1CLKSOURCE_SYSCLK)) - -#define IS_RCC_DFSDM1AUDIOCLKSOURCE(__SOURCE__) (((__SOURCE__) == RCC_DFSDM1AUDIOCLKSOURCE_I2S1) || \ - ((__SOURCE__) == RCC_DFSDM1AUDIOCLKSOURCE_I2S2)) - -#if defined(STM32F413xx) || defined(STM32F423xx) -#define IS_RCC_DFSDM2CLKSOURCE(__SOURCE__) (((__SOURCE__) == RCC_DFSDM2CLKSOURCE_PCLK2) || \ - ((__SOURCE__) == RCC_DFSDM2CLKSOURCE_SYSCLK)) - -#define IS_RCC_DFSDM2AUDIOCLKSOURCE(__SOURCE__) (((__SOURCE__) == RCC_DFSDM2AUDIOCLKSOURCE_I2S1) || \ - ((__SOURCE__) == RCC_DFSDM2AUDIOCLKSOURCE_I2S2)) - -#define IS_RCC_LPTIM1CLKSOURCE(SOURCE) (((SOURCE) == RCC_LPTIM1CLKSOURCE_PCLK1) ||\ - ((SOURCE) == RCC_LPTIM1CLKSOURCE_HSI) ||\ - ((SOURCE) == RCC_LPTIM1CLKSOURCE_LSI) ||\ - ((SOURCE) == RCC_LPTIM1CLKSOURCE_LSE)) - -#define IS_RCC_SAIACLKSOURCE(SOURCE) (((SOURCE) == RCC_SAIACLKSOURCE_PLLI2SR) ||\ - ((SOURCE) == RCC_SAIACLKSOURCE_EXT) ||\ - ((SOURCE) == RCC_SAIACLKSOURCE_PLLR) ||\ - ((SOURCE) == RCC_SAIACLKSOURCE_PLLSRC)) - -#define IS_RCC_SAIBCLKSOURCE(SOURCE) (((SOURCE) == RCC_SAIBCLKSOURCE_PLLI2SR) ||\ - ((SOURCE) == RCC_SAIBCLKSOURCE_EXT) ||\ - ((SOURCE) == RCC_SAIBCLKSOURCE_PLLR) ||\ - ((SOURCE) == RCC_SAIBCLKSOURCE_PLLSRC)) - -#define IS_RCC_PLL_DIVR_VALUE(VALUE) ((1U <= (VALUE)) && ((VALUE) <= 32U)) - -#define IS_RCC_PLLI2S_DIVR_VALUE(VALUE) ((1U <= (VALUE)) && ((VALUE) <= 32U)) - -#endif /* STM32F413xx || STM32F423xx */ -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || \ - defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || \ - defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) || defined(STM32F446xx) || \ - defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) || defined(STM32F412Vx) || \ - defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) - -#define IS_RCC_MCO2SOURCE(SOURCE) (((SOURCE) == RCC_MCO2SOURCE_SYSCLK) || ((SOURCE) == RCC_MCO2SOURCE_PLLI2SCLK)|| \ - ((SOURCE) == RCC_MCO2SOURCE_HSE) || ((SOURCE) == RCC_MCO2SOURCE_PLLCLK)) - -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || - STM32F401xC || STM32F401xE || STM32F411xE || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx || STM32F412Vx || \ - STM32F412Rx */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -#define IS_RCC_MCO2SOURCE(SOURCE) (((SOURCE) == RCC_MCO2SOURCE_SYSCLK) || ((SOURCE) == RCC_MCO2SOURCE_I2SCLK)|| \ - ((SOURCE) == RCC_MCO2SOURCE_HSE) || ((SOURCE) == RCC_MCO2SOURCE_PLLCLK)) -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_RCC_EX_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rng.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rng.h deleted file mode 100644 index cde4859..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rng.h +++ /dev/null @@ -1,363 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_rng.h - * @author MCD Application Team - * @brief Header file of RNG HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_RNG_H -#define STM32F4xx_HAL_RNG_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -#if defined (RNG) - -/** @defgroup RNG RNG - * @brief RNG HAL module driver - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ - -/** @defgroup RNG_Exported_Types RNG Exported Types - * @{ - */ - -/** @defgroup RNG_Exported_Types_Group1 RNG Init Structure definition - * @{ - */ - -/** - * @} - */ - -/** @defgroup RNG_Exported_Types_Group2 RNG State Structure definition - * @{ - */ -typedef enum -{ - HAL_RNG_STATE_RESET = 0x00U, /*!< RNG not yet initialized or disabled */ - HAL_RNG_STATE_READY = 0x01U, /*!< RNG initialized and ready for use */ - HAL_RNG_STATE_BUSY = 0x02U, /*!< RNG internal process is ongoing */ - HAL_RNG_STATE_TIMEOUT = 0x03U, /*!< RNG timeout state */ - HAL_RNG_STATE_ERROR = 0x04U /*!< RNG error state */ - -} HAL_RNG_StateTypeDef; - -/** - * @} - */ - -/** @defgroup RNG_Exported_Types_Group3 RNG Handle Structure definition - * @{ - */ -#if (USE_HAL_RNG_REGISTER_CALLBACKS == 1) -typedef struct __RNG_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_RNG_REGISTER_CALLBACKS */ -{ - RNG_TypeDef *Instance; /*!< Register base address */ - - HAL_LockTypeDef Lock; /*!< RNG locking object */ - - __IO HAL_RNG_StateTypeDef State; /*!< RNG communication state */ - - __IO uint32_t ErrorCode; /*!< RNG Error code */ - - uint32_t RandomNumber; /*!< Last Generated RNG Data */ - -#if (USE_HAL_RNG_REGISTER_CALLBACKS == 1) - void (* ReadyDataCallback)(struct __RNG_HandleTypeDef *hrng, uint32_t random32bit); /*!< RNG Data Ready Callback */ - void (* ErrorCallback)(struct __RNG_HandleTypeDef *hrng); /*!< RNG Error Callback */ - - void (* MspInitCallback)(struct __RNG_HandleTypeDef *hrng); /*!< RNG Msp Init callback */ - void (* MspDeInitCallback)(struct __RNG_HandleTypeDef *hrng); /*!< RNG Msp DeInit callback */ -#endif /* USE_HAL_RNG_REGISTER_CALLBACKS */ - -} RNG_HandleTypeDef; - -#if (USE_HAL_RNG_REGISTER_CALLBACKS == 1) -/** - * @brief HAL RNG Callback ID enumeration definition - */ -typedef enum -{ - HAL_RNG_ERROR_CB_ID = 0x00U, /*!< RNG Error Callback ID */ - - HAL_RNG_MSPINIT_CB_ID = 0x01U, /*!< RNG MspInit callback ID */ - HAL_RNG_MSPDEINIT_CB_ID = 0x02U /*!< RNG MspDeInit callback ID */ - -} HAL_RNG_CallbackIDTypeDef; - -/** - * @brief HAL RNG Callback pointer definition - */ -typedef void (*pRNG_CallbackTypeDef)(RNG_HandleTypeDef *hrng); /*!< pointer to a common RNG callback function */ -typedef void (*pRNG_ReadyDataCallbackTypeDef)(RNG_HandleTypeDef *hrng, uint32_t random32bit); /*!< pointer to an RNG Data Ready specific callback function */ - -#endif /* USE_HAL_RNG_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup RNG_Exported_Constants RNG Exported Constants - * @{ - */ - -/** @defgroup RNG_Exported_Constants_Group1 RNG Interrupt definition - * @{ - */ -#define RNG_IT_DRDY RNG_SR_DRDY /*!< Data Ready interrupt */ -#define RNG_IT_CEI RNG_SR_CEIS /*!< Clock error interrupt */ -#define RNG_IT_SEI RNG_SR_SEIS /*!< Seed error interrupt */ -/** - * @} - */ - -/** @defgroup RNG_Exported_Constants_Group2 RNG Flag definition - * @{ - */ -#define RNG_FLAG_DRDY RNG_SR_DRDY /*!< Data ready */ -#define RNG_FLAG_CECS RNG_SR_CECS /*!< Clock error current status */ -#define RNG_FLAG_SECS RNG_SR_SECS /*!< Seed error current status */ -/** - * @} - */ - -/** @defgroup RNG_Error_Definition RNG Error Definition - * @{ - */ -#define HAL_RNG_ERROR_NONE 0x00000000U /*!< No error */ -#if (USE_HAL_RNG_REGISTER_CALLBACKS == 1) -#define HAL_RNG_ERROR_INVALID_CALLBACK 0x00000001U /*!< Invalid Callback error */ -#endif /* USE_HAL_RNG_REGISTER_CALLBACKS */ -#define HAL_RNG_ERROR_TIMEOUT 0x00000002U /*!< Timeout error */ -#define HAL_RNG_ERROR_BUSY 0x00000004U /*!< Busy error */ -#define HAL_RNG_ERROR_SEED 0x00000008U /*!< Seed error */ -#define HAL_RNG_ERROR_CLOCK 0x00000010U /*!< Clock error */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macros -----------------------------------------------------------*/ -/** @defgroup RNG_Exported_Macros RNG Exported Macros - * @{ - */ - -/** @brief Reset RNG handle state - * @param __HANDLE__ RNG Handle - * @retval None - */ -#if (USE_HAL_RNG_REGISTER_CALLBACKS == 1) -#define __HAL_RNG_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->State = HAL_RNG_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0U) -#else -#define __HAL_RNG_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_RNG_STATE_RESET) -#endif /* USE_HAL_RNG_REGISTER_CALLBACKS */ - -/** - * @brief Enables the RNG peripheral. - * @param __HANDLE__ RNG Handle - * @retval None - */ -#define __HAL_RNG_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= RNG_CR_RNGEN) - -/** - * @brief Disables the RNG peripheral. - * @param __HANDLE__ RNG Handle - * @retval None - */ -#define __HAL_RNG_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR &= ~RNG_CR_RNGEN) - -/** - * @brief Check the selected RNG flag status. - * @param __HANDLE__ RNG Handle - * @param __FLAG__ RNG flag - * This parameter can be one of the following values: - * @arg RNG_FLAG_DRDY: Data ready - * @arg RNG_FLAG_CECS: Clock error current status - * @arg RNG_FLAG_SECS: Seed error current status - * @retval The new state of __FLAG__ (SET or RESET). - */ -#define __HAL_RNG_GET_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->SR & (__FLAG__)) == (__FLAG__)) - -/** - * @brief Clears the selected RNG flag status. - * @param __HANDLE__ RNG handle - * @param __FLAG__ RNG flag to clear - * @note WARNING: This is a dummy macro for HAL code alignment, - * flags RNG_FLAG_DRDY, RNG_FLAG_CECS and RNG_FLAG_SECS are read-only. - * @retval None - */ -#define __HAL_RNG_CLEAR_FLAG(__HANDLE__, __FLAG__) /* dummy macro */ - -/** - * @brief Enables the RNG interrupts. - * @param __HANDLE__ RNG Handle - * @retval None - */ -#define __HAL_RNG_ENABLE_IT(__HANDLE__) ((__HANDLE__)->Instance->CR |= RNG_CR_IE) - -/** - * @brief Disables the RNG interrupts. - * @param __HANDLE__ RNG Handle - * @retval None - */ -#define __HAL_RNG_DISABLE_IT(__HANDLE__) ((__HANDLE__)->Instance->CR &= ~RNG_CR_IE) - -/** - * @brief Checks whether the specified RNG interrupt has occurred or not. - * @param __HANDLE__ RNG Handle - * @param __INTERRUPT__ specifies the RNG interrupt status flag to check. - * This parameter can be one of the following values: - * @arg RNG_IT_DRDY: Data ready interrupt - * @arg RNG_IT_CEI: Clock error interrupt - * @arg RNG_IT_SEI: Seed error interrupt - * @retval The new state of __INTERRUPT__ (SET or RESET). - */ -#define __HAL_RNG_GET_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->SR & (__INTERRUPT__)) == (__INTERRUPT__)) - -/** - * @brief Clear the RNG interrupt status flags. - * @param __HANDLE__ RNG Handle - * @param __INTERRUPT__ specifies the RNG interrupt status flag to clear. - * This parameter can be one of the following values: - * @arg RNG_IT_CEI: Clock error interrupt - * @arg RNG_IT_SEI: Seed error interrupt - * @note RNG_IT_DRDY flag is read-only, reading RNG_DR register automatically clears RNG_IT_DRDY. - * @retval None - */ -#define __HAL_RNG_CLEAR_IT(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->SR) = ~(__INTERRUPT__)) - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup RNG_Exported_Functions RNG Exported Functions - * @{ - */ - -/** @defgroup RNG_Exported_Functions_Group1 Initialization and configuration functions - * @{ - */ -HAL_StatusTypeDef HAL_RNG_Init(RNG_HandleTypeDef *hrng); -HAL_StatusTypeDef HAL_RNG_DeInit(RNG_HandleTypeDef *hrng); -void HAL_RNG_MspInit(RNG_HandleTypeDef *hrng); -void HAL_RNG_MspDeInit(RNG_HandleTypeDef *hrng); - -/* Callbacks Register/UnRegister functions ***********************************/ -#if (USE_HAL_RNG_REGISTER_CALLBACKS == 1) -HAL_StatusTypeDef HAL_RNG_RegisterCallback(RNG_HandleTypeDef *hrng, HAL_RNG_CallbackIDTypeDef CallbackID, - pRNG_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_RNG_UnRegisterCallback(RNG_HandleTypeDef *hrng, HAL_RNG_CallbackIDTypeDef CallbackID); - -HAL_StatusTypeDef HAL_RNG_RegisterReadyDataCallback(RNG_HandleTypeDef *hrng, pRNG_ReadyDataCallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_RNG_UnRegisterReadyDataCallback(RNG_HandleTypeDef *hrng); -#endif /* USE_HAL_RNG_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @defgroup RNG_Exported_Functions_Group2 Peripheral Control functions - * @{ - */ -uint32_t HAL_RNG_GetRandomNumber(RNG_HandleTypeDef - *hrng); /* Obsolete, use HAL_RNG_GenerateRandomNumber() instead */ -uint32_t HAL_RNG_GetRandomNumber_IT(RNG_HandleTypeDef - *hrng); /* Obsolete, use HAL_RNG_GenerateRandomNumber_IT() instead */ -HAL_StatusTypeDef HAL_RNG_GenerateRandomNumber(RNG_HandleTypeDef *hrng, uint32_t *random32bit); -HAL_StatusTypeDef HAL_RNG_GenerateRandomNumber_IT(RNG_HandleTypeDef *hrng); -uint32_t HAL_RNG_ReadLastRandomNumber(RNG_HandleTypeDef *hrng); - -void HAL_RNG_IRQHandler(RNG_HandleTypeDef *hrng); -void HAL_RNG_ErrorCallback(RNG_HandleTypeDef *hrng); -void HAL_RNG_ReadyDataCallback(RNG_HandleTypeDef *hrng, uint32_t random32bit); - -/** - * @} - */ - -/** @defgroup RNG_Exported_Functions_Group3 Peripheral State functions - * @{ - */ -HAL_RNG_StateTypeDef HAL_RNG_GetState(RNG_HandleTypeDef *hrng); -uint32_t HAL_RNG_GetError(RNG_HandleTypeDef *hrng); -/** - * @} - */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup RNG_Private_Macros RNG Private Macros - * @{ - */ -#define IS_RNG_IT(IT) (((IT) == RNG_IT_CEI) || \ - ((IT) == RNG_IT_SEI)) - -#define IS_RNG_FLAG(FLAG) (((FLAG) == RNG_FLAG_DRDY) || \ - ((FLAG) == RNG_FLAG_CECS) || \ - ((FLAG) == RNG_FLAG_SECS)) - -/** - * @} - */ - -/** - * @} - */ - -#endif /* RNG */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - - -#endif /* STM32F4xx_HAL_RNG_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rtc.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rtc.h deleted file mode 100644 index 9afa8a1..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rtc.h +++ /dev/null @@ -1,878 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_rtc.h - * @author MCD Application Team - * @brief Header file of RTC HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_RTC_H -#define __STM32F4xx_HAL_RTC_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup RTC - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup RTC_Exported_Types RTC Exported Types - * @{ - */ - -/** - * @brief HAL State structures definition - */ -typedef enum -{ - HAL_RTC_STATE_RESET = 0x00U, /*!< RTC not yet initialized or disabled */ - HAL_RTC_STATE_READY = 0x01U, /*!< RTC initialized and ready for use */ - HAL_RTC_STATE_BUSY = 0x02U, /*!< RTC process is ongoing */ - HAL_RTC_STATE_TIMEOUT = 0x03U, /*!< RTC timeout state */ - HAL_RTC_STATE_ERROR = 0x04U /*!< RTC error state */ -}HAL_RTCStateTypeDef; - -/** - * @brief RTC Configuration Structure definition - */ -typedef struct -{ - uint32_t HourFormat; /*!< Specifies the RTC Hour Format. - This parameter can be a value of @ref RTC_Hour_Formats */ - - uint32_t AsynchPrediv; /*!< Specifies the RTC Asynchronous Predivider value. - This parameter must be a number between Min_Data = 0x00 and Max_Data = 0x7F */ - - uint32_t SynchPrediv; /*!< Specifies the RTC Synchronous Predivider value. - This parameter must be a number between Min_Data = 0x00 and Max_Data = 0x7FFFU */ - - uint32_t OutPut; /*!< Specifies which signal will be routed to the RTC output. - This parameter can be a value of @ref RTC_Output_selection_Definitions */ - - uint32_t OutPutPolarity; /*!< Specifies the polarity of the output signal. - This parameter can be a value of @ref RTC_Output_Polarity_Definitions */ - - uint32_t OutPutType; /*!< Specifies the RTC Output Pin mode. - This parameter can be a value of @ref RTC_Output_Type_ALARM_OUT */ -}RTC_InitTypeDef; - -/** - * @brief RTC Time structure definition - */ -typedef struct -{ - uint8_t Hours; /*!< Specifies the RTC Time Hour. - This parameter must be a number between Min_Data = 0 and Max_Data = 12 if the RTC_HourFormat_12 is selected. - This parameter must be a number between Min_Data = 0 and Max_Data = 23 if the RTC_HourFormat_24 is selected */ - - uint8_t Minutes; /*!< Specifies the RTC Time Minutes. - This parameter must be a number between Min_Data = 0 and Max_Data = 59 */ - - uint8_t Seconds; /*!< Specifies the RTC Time Seconds. - This parameter must be a number between Min_Data = 0 and Max_Data = 59 */ - - uint8_t TimeFormat; /*!< Specifies the RTC AM/PM Time. - This parameter can be a value of @ref RTC_AM_PM_Definitions */ - - uint32_t SubSeconds; /*!< Specifies the RTC_SSR RTC Sub Second register content. - This parameter corresponds to a time unit range between [0-1] Second - with [1 Sec / SecondFraction +1] granularity */ - - uint32_t SecondFraction; /*!< Specifies the range or granularity of Sub Second register content - corresponding to Synchronous pre-scaler factor value (PREDIV_S) - This parameter corresponds to a time unit range between [0-1] Second - with [1 Sec / SecondFraction +1] granularity. - This field will be used only by HAL_RTC_GetTime function */ - - uint32_t DayLightSaving; /*!< This interface is deprecated. To manage Daylight Saving Time, - please use HAL_RTC_DST_xxx functions */ - - uint32_t StoreOperation; /*!< This interface is deprecated. To manage Daylight Saving Time, - please use HAL_RTC_DST_xxx functions */ -}RTC_TimeTypeDef; - -/** - * @brief RTC Date structure definition - */ -typedef struct -{ - uint8_t WeekDay; /*!< Specifies the RTC Date WeekDay. - This parameter can be a value of @ref RTC_WeekDay_Definitions */ - - uint8_t Month; /*!< Specifies the RTC Date Month (in BCD format). - This parameter can be a value of @ref RTC_Month_Date_Definitions */ - - uint8_t Date; /*!< Specifies the RTC Date. - This parameter must be a number between Min_Data = 1 and Max_Data = 31 */ - - uint8_t Year; /*!< Specifies the RTC Date Year. - This parameter must be a number between Min_Data = 0 and Max_Data = 99 */ - -}RTC_DateTypeDef; - -/** - * @brief RTC Alarm structure definition - */ -typedef struct -{ - RTC_TimeTypeDef AlarmTime; /*!< Specifies the RTC Alarm Time members */ - - uint32_t AlarmMask; /*!< Specifies the RTC Alarm Masks. - This parameter can be a value of @ref RTC_AlarmMask_Definitions */ - - uint32_t AlarmSubSecondMask; /*!< Specifies the RTC Alarm SubSeconds Masks. - This parameter can be a value of @ref RTC_Alarm_Sub_Seconds_Masks_Definitions */ - - uint32_t AlarmDateWeekDaySel; /*!< Specifies the RTC Alarm is on Date or WeekDay. - This parameter can be a value of @ref RTC_AlarmDateWeekDay_Definitions */ - - uint8_t AlarmDateWeekDay; /*!< Specifies the RTC Alarm Date/WeekDay. - If the Alarm Date is selected, this parameter must be set to a value in the 1-31 range. - If the Alarm WeekDay is selected, this parameter can be a value of @ref RTC_WeekDay_Definitions */ - - uint32_t Alarm; /*!< Specifies the alarm . - This parameter can be a value of @ref RTC_Alarms_Definitions */ -}RTC_AlarmTypeDef; - -/** - * @brief RTC Handle Structure definition - */ -#if (USE_HAL_RTC_REGISTER_CALLBACKS == 1) -typedef struct __RTC_HandleTypeDef -#else -typedef struct -#endif /* (USE_HAL_RTC_REGISTER_CALLBACKS) */ -{ - RTC_TypeDef *Instance; /*!< Register base address */ - - RTC_InitTypeDef Init; /*!< RTC required parameters */ - - HAL_LockTypeDef Lock; /*!< RTC locking object */ - - __IO HAL_RTCStateTypeDef State; /*!< Time communication state */ - -#if (USE_HAL_RTC_REGISTER_CALLBACKS == 1) - void (* AlarmAEventCallback) ( struct __RTC_HandleTypeDef * hrtc); /*!< RTC Alarm A Event callback */ - - void (* AlarmBEventCallback) ( struct __RTC_HandleTypeDef * hrtc); /*!< RTC Alarm B Event callback */ - - void (* TimeStampEventCallback) ( struct __RTC_HandleTypeDef * hrtc); /*!< RTC TimeStamp Event callback */ - - void (* WakeUpTimerEventCallback) ( struct __RTC_HandleTypeDef * hrtc); /*!< RTC WakeUpTimer Event callback */ - - void (* Tamper1EventCallback) ( struct __RTC_HandleTypeDef * hrtc); /*!< RTC Tamper 1 Event callback */ - - void (* Tamper2EventCallback) ( struct __RTC_HandleTypeDef * hrtc); /*!< RTC Tamper 2 Event callback */ - - void (* MspInitCallback) ( struct __RTC_HandleTypeDef * hrtc); /*!< RTC Msp Init callback */ - - void (* MspDeInitCallback) ( struct __RTC_HandleTypeDef * hrtc); /*!< RTC Msp DeInit callback */ - -#endif /* (USE_HAL_RTC_REGISTER_CALLBACKS) */ - -}RTC_HandleTypeDef; - -#if (USE_HAL_RTC_REGISTER_CALLBACKS == 1) -/** - * @brief HAL RTC Callback ID enumeration definition - */ -typedef enum -{ - HAL_RTC_ALARM_A_EVENT_CB_ID = 0x00u, /*!< RTC Alarm A Event Callback ID */ - HAL_RTC_ALARM_B_EVENT_CB_ID = 0x01u, /*!< RTC Alarm B Event Callback ID */ - HAL_RTC_TIMESTAMP_EVENT_CB_ID = 0x02u, /*!< RTC TimeStamp Event Callback ID */ - HAL_RTC_WAKEUPTIMER_EVENT_CB_ID = 0x03u, /*!< RTC Wake-Up Timer Event Callback ID */ - HAL_RTC_TAMPER1_EVENT_CB_ID = 0x04u, /*!< RTC Tamper 1 Callback ID */ - HAL_RTC_TAMPER2_EVENT_CB_ID = 0x05u, /*!< RTC Tamper 2 Callback ID */ - HAL_RTC_MSPINIT_CB_ID = 0x0Eu, /*!< RTC Msp Init callback ID */ - HAL_RTC_MSPDEINIT_CB_ID = 0x0Fu /*!< RTC Msp DeInit callback ID */ -}HAL_RTC_CallbackIDTypeDef; - -/** - * @brief HAL RTC Callback pointer definition - */ -typedef void (*pRTC_CallbackTypeDef)(RTC_HandleTypeDef * hrtc); /*!< pointer to an RTC callback function */ -#endif /* USE_HAL_RTC_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup RTC_Exported_Constants RTC Exported Constants - * @{ - */ - -/** @defgroup RTC_Hour_Formats RTC Hour Formats - * @{ - */ -#define RTC_HOURFORMAT_24 0x00000000U -#define RTC_HOURFORMAT_12 0x00000040U -/** - * @} - */ - -/** @defgroup RTC_Output_selection_Definitions RTC Output Selection Definitions - * @{ - */ -#define RTC_OUTPUT_DISABLE 0x00000000U -#define RTC_OUTPUT_ALARMA 0x00200000U -#define RTC_OUTPUT_ALARMB 0x00400000U -#define RTC_OUTPUT_WAKEUP 0x00600000U -/** - * @} - */ - -/** @defgroup RTC_Output_Polarity_Definitions RTC Output Polarity Definitions - * @{ - */ -#define RTC_OUTPUT_POLARITY_HIGH 0x00000000U -#define RTC_OUTPUT_POLARITY_LOW 0x00100000U -/** - * @} - */ - -/** @defgroup RTC_Output_Type_ALARM_OUT RTC Output Type ALARM OUT - * @{ - */ -#define RTC_OUTPUT_TYPE_OPENDRAIN 0x00000000U -#define RTC_OUTPUT_TYPE_PUSHPULL 0x00040000U -/** - * @} - */ - -/** @defgroup RTC_AM_PM_Definitions RTC AM PM Definitions - * @{ - */ -#define RTC_HOURFORMAT12_AM ((uint8_t)0x00) -#define RTC_HOURFORMAT12_PM ((uint8_t)0x40) -/** - * @} - */ - -/** @defgroup RTC_DayLightSaving_Definitions RTC DayLight Saving Definitions - * @{ - */ -#define RTC_DAYLIGHTSAVING_SUB1H 0x00020000U -#define RTC_DAYLIGHTSAVING_ADD1H 0x00010000U -#define RTC_DAYLIGHTSAVING_NONE 0x00000000U -/** - * @} - */ - -/** @defgroup RTC_StoreOperation_Definitions RTC Store Operation Definitions - * @{ - */ -#define RTC_STOREOPERATION_RESET 0x00000000U -#define RTC_STOREOPERATION_SET 0x00040000U -/** - * @} - */ - -/** @defgroup RTC_Input_parameter_format_definitions RTC Input Parameter Format Definitions - * @{ - */ -#define RTC_FORMAT_BIN 0x00000000U -#define RTC_FORMAT_BCD 0x00000001U -/** - * @} - */ - -/** @defgroup RTC_Month_Date_Definitions RTC Month Date Definitions - * @{ - */ -/* Coded in BCD format */ -#define RTC_MONTH_JANUARY ((uint8_t)0x01) -#define RTC_MONTH_FEBRUARY ((uint8_t)0x02) -#define RTC_MONTH_MARCH ((uint8_t)0x03) -#define RTC_MONTH_APRIL ((uint8_t)0x04) -#define RTC_MONTH_MAY ((uint8_t)0x05) -#define RTC_MONTH_JUNE ((uint8_t)0x06) -#define RTC_MONTH_JULY ((uint8_t)0x07) -#define RTC_MONTH_AUGUST ((uint8_t)0x08) -#define RTC_MONTH_SEPTEMBER ((uint8_t)0x09) -#define RTC_MONTH_OCTOBER ((uint8_t)0x10) -#define RTC_MONTH_NOVEMBER ((uint8_t)0x11) -#define RTC_MONTH_DECEMBER ((uint8_t)0x12) -/** - * @} - */ - -/** @defgroup RTC_WeekDay_Definitions RTC WeekDay Definitions - * @{ - */ -#define RTC_WEEKDAY_MONDAY ((uint8_t)0x01) -#define RTC_WEEKDAY_TUESDAY ((uint8_t)0x02) -#define RTC_WEEKDAY_WEDNESDAY ((uint8_t)0x03) -#define RTC_WEEKDAY_THURSDAY ((uint8_t)0x04) -#define RTC_WEEKDAY_FRIDAY ((uint8_t)0x05) -#define RTC_WEEKDAY_SATURDAY ((uint8_t)0x06) -#define RTC_WEEKDAY_SUNDAY ((uint8_t)0x07) -/** - * @} - */ - -/** @defgroup RTC_AlarmDateWeekDay_Definitions RTC Alarm Date WeekDay Definitions - * @{ - */ -#define RTC_ALARMDATEWEEKDAYSEL_DATE 0x00000000U -#define RTC_ALARMDATEWEEKDAYSEL_WEEKDAY 0x40000000U -/** - * @} - */ - -/** @defgroup RTC_AlarmMask_Definitions RTC Alarm Mask Definitions - * @{ - */ -#define RTC_ALARMMASK_NONE 0x00000000U -#define RTC_ALARMMASK_DATEWEEKDAY RTC_ALRMAR_MSK4 -#define RTC_ALARMMASK_HOURS RTC_ALRMAR_MSK3 -#define RTC_ALARMMASK_MINUTES RTC_ALRMAR_MSK2 -#define RTC_ALARMMASK_SECONDS RTC_ALRMAR_MSK1 -#define RTC_ALARMMASK_ALL 0x80808080U -/** - * @} - */ - -/** @defgroup RTC_Alarms_Definitions RTC Alarms Definitions - * @{ - */ -#define RTC_ALARM_A RTC_CR_ALRAE -#define RTC_ALARM_B RTC_CR_ALRBE -/** - * @} - */ - -/** @defgroup RTC_Alarm_Sub_Seconds_Masks_Definitions RTC Alarm Sub Seconds Masks Definitions - * @{ - */ -#define RTC_ALARMSUBSECONDMASK_ALL 0x00000000U /*!< All Alarm SS fields are masked. - There is no comparison on sub seconds - for Alarm */ -#define RTC_ALARMSUBSECONDMASK_SS14_1 0x01000000U /*!< SS[14:1] are don't care in Alarm - comparison. Only SS[0] is compared. */ -#define RTC_ALARMSUBSECONDMASK_SS14_2 0x02000000U /*!< SS[14:2] are don't care in Alarm - comparison. Only SS[1:0] are compared */ -#define RTC_ALARMSUBSECONDMASK_SS14_3 0x03000000U /*!< SS[14:3] are don't care in Alarm - comparison. Only SS[2:0] are compared */ -#define RTC_ALARMSUBSECONDMASK_SS14_4 0x04000000U /*!< SS[14:4] are don't care in Alarm - comparison. Only SS[3:0] are compared */ -#define RTC_ALARMSUBSECONDMASK_SS14_5 0x05000000U /*!< SS[14:5] are don't care in Alarm - comparison. Only SS[4:0] are compared */ -#define RTC_ALARMSUBSECONDMASK_SS14_6 0x06000000U /*!< SS[14:6] are don't care in Alarm - comparison. Only SS[5:0] are compared */ -#define RTC_ALARMSUBSECONDMASK_SS14_7 0x07000000U /*!< SS[14:7] are don't care in Alarm - comparison. Only SS[6:0] are compared */ -#define RTC_ALARMSUBSECONDMASK_SS14_8 0x08000000U /*!< SS[14:8] are don't care in Alarm - comparison. Only SS[7:0] are compared */ -#define RTC_ALARMSUBSECONDMASK_SS14_9 0x09000000U /*!< SS[14:9] are don't care in Alarm - comparison. Only SS[8:0] are compared */ -#define RTC_ALARMSUBSECONDMASK_SS14_10 0x0A000000U /*!< SS[14:10] are don't care in Alarm - comparison. Only SS[9:0] are compared */ -#define RTC_ALARMSUBSECONDMASK_SS14_11 0x0B000000U /*!< SS[14:11] are don't care in Alarm - comparison. Only SS[10:0] are compared */ -#define RTC_ALARMSUBSECONDMASK_SS14_12 0x0C000000U /*!< SS[14:12] are don't care in Alarm - comparison.Only SS[11:0] are compared */ -#define RTC_ALARMSUBSECONDMASK_SS14_13 0x0D000000U /*!< SS[14:13] are don't care in Alarm - comparison. Only SS[12:0] are compared */ -#define RTC_ALARMSUBSECONDMASK_SS14 0x0E000000U /*!< SS[14] is don't care in Alarm - comparison.Only SS[13:0] are compared */ -#define RTC_ALARMSUBSECONDMASK_NONE 0x0F000000U /*!< SS[14:0] are compared and must match - to activate alarm. */ -/** - * @} - */ - -/** @defgroup RTC_Interrupts_Definitions RTC Interrupts Definitions - * @{ - */ -#define RTC_IT_TS 0x00008000U -#define RTC_IT_WUT 0x00004000U -#define RTC_IT_ALRB 0x00002000U -#define RTC_IT_ALRA 0x00001000U -#define RTC_IT_TAMP 0x00000004U /* Used only to Enable the Tamper Interrupt */ -#define RTC_IT_TAMP1 0x00020000U -#define RTC_IT_TAMP2 0x00040000U -/** - * @} - */ - -/** @defgroup RTC_Flags_Definitions RTC Flags Definitions - * @{ - */ -#define RTC_FLAG_RECALPF 0x00010000U -#define RTC_FLAG_TAMP2F 0x00004000U -#define RTC_FLAG_TAMP1F 0x00002000U -#define RTC_FLAG_TSOVF 0x00001000U -#define RTC_FLAG_TSF 0x00000800U -#define RTC_FLAG_WUTF 0x00000400U -#define RTC_FLAG_ALRBF 0x00000200U -#define RTC_FLAG_ALRAF 0x00000100U -#define RTC_FLAG_INITF 0x00000040U -#define RTC_FLAG_RSF 0x00000020U -#define RTC_FLAG_INITS 0x00000010U -#define RTC_FLAG_SHPF 0x00000008U -#define RTC_FLAG_WUTWF 0x00000004U -#define RTC_FLAG_ALRBWF 0x00000002U -#define RTC_FLAG_ALRAWF 0x00000001U -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup RTC_Exported_Macros RTC Exported Macros - * @{ - */ - -/** @brief Reset RTC handle state - * @param __HANDLE__ specifies the RTC handle. - * @retval None - */ -#if (USE_HAL_RTC_REGISTER_CALLBACKS == 1) -#define __HAL_RTC_RESET_HANDLE_STATE(__HANDLE__) do{\ - (__HANDLE__)->State = HAL_RTC_STATE_RESET;\ - (__HANDLE__)->MspInitCallback = NULL;\ - (__HANDLE__)->MspDeInitCallback = NULL;\ - }while(0u) -#else -#define __HAL_RTC_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_RTC_STATE_RESET) -#endif /* USE_HAL_RTC_REGISTER_CALLBACKS */ - -/** - * @brief Disable the write protection for RTC registers. - * @param __HANDLE__ specifies the RTC handle. - * @retval None - */ -#define __HAL_RTC_WRITEPROTECTION_DISABLE(__HANDLE__) \ - do{ \ - (__HANDLE__)->Instance->WPR = 0xCAU; \ - (__HANDLE__)->Instance->WPR = 0x53U; \ - } while(0U) - -/** - * @brief Enable the write protection for RTC registers. - * @param __HANDLE__ specifies the RTC handle. - * @retval None - */ -#define __HAL_RTC_WRITEPROTECTION_ENABLE(__HANDLE__) \ - do{ \ - (__HANDLE__)->Instance->WPR = 0xFFU; \ - } while(0U) - -/** - * @brief Enable the RTC ALARMA peripheral. - * @param __HANDLE__ specifies the RTC handle. - * @retval None - */ -#define __HAL_RTC_ALARMA_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= (RTC_CR_ALRAE)) - -/** - * @brief Disable the RTC ALARMA peripheral. - * @param __HANDLE__ specifies the RTC handle. - * @retval None - */ -#define __HAL_RTC_ALARMA_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR &= ~(RTC_CR_ALRAE)) - -/** - * @brief Enable the RTC ALARMB peripheral. - * @param __HANDLE__ specifies the RTC handle. - * @retval None - */ -#define __HAL_RTC_ALARMB_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= (RTC_CR_ALRBE)) - -/** - * @brief Disable the RTC ALARMB peripheral. - * @param __HANDLE__ specifies the RTC handle. - * @retval None - */ -#define __HAL_RTC_ALARMB_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR &= ~(RTC_CR_ALRBE)) - -/** - * @brief Enable the RTC Alarm interrupt. - * @param __HANDLE__ specifies the RTC handle. - * @param __INTERRUPT__ specifies the RTC Alarm interrupt sources to be enabled or disabled. - * This parameter can be any combination of the following values: - * @arg RTC_IT_ALRA: Alarm A interrupt - * @arg RTC_IT_ALRB: Alarm B interrupt - * @retval None - */ -#define __HAL_RTC_ALARM_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR |= (__INTERRUPT__)) - -/** - * @brief Disable the RTC Alarm interrupt. - * @param __HANDLE__ specifies the RTC handle. - * @param __INTERRUPT__ specifies the RTC Alarm interrupt sources to be enabled or disabled. - * This parameter can be any combination of the following values: - * @arg RTC_IT_ALRA: Alarm A interrupt - * @arg RTC_IT_ALRB: Alarm B interrupt - * @retval None - */ -#define __HAL_RTC_ALARM_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR &= ~(__INTERRUPT__)) - -/** - * @brief Check whether the specified RTC Alarm interrupt has occurred or not. - * @param __HANDLE__ specifies the RTC handle. - * @param __INTERRUPT__ specifies the RTC Alarm interrupt to check. - * This parameter can be: - * @arg RTC_IT_ALRA: Alarm A interrupt - * @arg RTC_IT_ALRB: Alarm B interrupt - * @retval None - */ -#define __HAL_RTC_ALARM_GET_IT(__HANDLE__, __INTERRUPT__) (((((__HANDLE__)->Instance->ISR)& ((__INTERRUPT__)>> 4U)) != RESET)? SET : RESET) - -/** - * @brief Get the selected RTC Alarm's flag status. - * @param __HANDLE__ specifies the RTC handle. - * @param __FLAG__ specifies the RTC Alarm Flag to check. - * This parameter can be: - * @arg RTC_FLAG_ALRAF - * @arg RTC_FLAG_ALRBF - * @arg RTC_FLAG_ALRAWF - * @arg RTC_FLAG_ALRBWF - * @retval None - */ -#define __HAL_RTC_ALARM_GET_FLAG(__HANDLE__, __FLAG__) (((((__HANDLE__)->Instance->ISR) & (__FLAG__)) != RESET)? SET : RESET) - -/** - * @brief Clear the RTC Alarm's pending flags. - * @param __HANDLE__ specifies the RTC handle. - * @param __FLAG__ specifies the RTC Alarm Flag sources to be enabled or disabled. - * This parameter can be: - * @arg RTC_FLAG_ALRAF - * @arg RTC_FLAG_ALRBF - * @retval None - */ -#define __HAL_RTC_ALARM_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->ISR) = (~((__FLAG__) | RTC_ISR_INIT)|((__HANDLE__)->Instance->ISR & RTC_ISR_INIT)) - - -/** - * @brief Check whether the specified RTC Alarm interrupt has been enabled or not. - * @param __HANDLE__ specifies the RTC handle. - * @param __INTERRUPT__ specifies the RTC Alarm interrupt sources to check. - * This parameter can be: - * @arg RTC_IT_ALRA: Alarm A interrupt - * @arg RTC_IT_ALRB: Alarm B interrupt - * @retval None - */ -#define __HAL_RTC_ALARM_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) (((((__HANDLE__)->Instance->CR) & (__INTERRUPT__)) != RESET) ? SET : RESET) - -/** - * @brief Enable interrupt on the RTC Alarm associated Exti line. - * @retval None - */ -#define __HAL_RTC_ALARM_EXTI_ENABLE_IT() (EXTI->IMR |= RTC_EXTI_LINE_ALARM_EVENT) - -/** - * @brief Disable interrupt on the RTC Alarm associated Exti line. - * @retval None - */ -#define __HAL_RTC_ALARM_EXTI_DISABLE_IT() (EXTI->IMR &= ~(RTC_EXTI_LINE_ALARM_EVENT)) - -/** - * @brief Enable event on the RTC Alarm associated Exti line. - * @retval None. - */ -#define __HAL_RTC_ALARM_EXTI_ENABLE_EVENT() (EXTI->EMR |= RTC_EXTI_LINE_ALARM_EVENT) - -/** - * @brief Disable event on the RTC Alarm associated Exti line. - * @retval None. - */ -#define __HAL_RTC_ALARM_EXTI_DISABLE_EVENT() (EXTI->EMR &= ~(RTC_EXTI_LINE_ALARM_EVENT)) - -/** - * @brief Enable falling edge trigger on the RTC Alarm associated Exti line. - * @retval None. - */ -#define __HAL_RTC_ALARM_EXTI_ENABLE_FALLING_EDGE() (EXTI->FTSR |= RTC_EXTI_LINE_ALARM_EVENT) - -/** - * @brief Disable falling edge trigger on the RTC Alarm associated Exti line. - * @retval None. - */ -#define __HAL_RTC_ALARM_EXTI_DISABLE_FALLING_EDGE() (EXTI->FTSR &= ~(RTC_EXTI_LINE_ALARM_EVENT)) - -/** - * @brief Enable rising edge trigger on the RTC Alarm associated Exti line. - * @retval None. - */ -#define __HAL_RTC_ALARM_EXTI_ENABLE_RISING_EDGE() (EXTI->RTSR |= RTC_EXTI_LINE_ALARM_EVENT) - -/** - * @brief Disable rising edge trigger on the RTC Alarm associated Exti line. - * @retval None. - */ -#define __HAL_RTC_ALARM_EXTI_DISABLE_RISING_EDGE() (EXTI->RTSR &= ~(RTC_EXTI_LINE_ALARM_EVENT)) - -/** - * @brief Enable rising & falling edge trigger on the RTC Alarm associated Exti line. - * @retval None. - */ -#define __HAL_RTC_ALARM_EXTI_ENABLE_RISING_FALLING_EDGE() do { __HAL_RTC_ALARM_EXTI_ENABLE_RISING_EDGE(); \ - __HAL_RTC_ALARM_EXTI_ENABLE_FALLING_EDGE();\ - } while(0U) - -/** - * @brief Disable rising & falling edge trigger on the RTC Alarm associated Exti line. - * @retval None. - */ -#define __HAL_RTC_ALARM_EXTI_DISABLE_RISING_FALLING_EDGE() do { __HAL_RTC_ALARM_EXTI_DISABLE_RISING_EDGE();\ - __HAL_RTC_ALARM_EXTI_DISABLE_FALLING_EDGE();\ - } while(0U) - -/** - * @brief Check whether the RTC Alarm associated Exti line interrupt flag is set or not. - * @retval Line Status. - */ -#define __HAL_RTC_ALARM_EXTI_GET_FLAG() (EXTI->PR & RTC_EXTI_LINE_ALARM_EVENT) - -/** - * @brief Clear the RTC Alarm associated Exti line flag. - * @retval None. - */ -#define __HAL_RTC_ALARM_EXTI_CLEAR_FLAG() (EXTI->PR = RTC_EXTI_LINE_ALARM_EVENT) - -/** - * @brief Generate a Software interrupt on RTC Alarm associated Exti line. - * @retval None. - */ -#define __HAL_RTC_ALARM_EXTI_GENERATE_SWIT() (EXTI->SWIER |= RTC_EXTI_LINE_ALARM_EVENT) -/** - * @} - */ - -/* Include RTC HAL Extension module */ -#include "stm32f4xx_hal_rtc_ex.h" - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup RTC_Exported_Functions - * @{ - */ - -/** @addtogroup RTC_Exported_Functions_Group1 - * @{ - */ -/* Initialization and de-initialization functions ****************************/ -HAL_StatusTypeDef HAL_RTC_Init(RTC_HandleTypeDef *hrtc); -HAL_StatusTypeDef HAL_RTC_DeInit(RTC_HandleTypeDef *hrtc); -void HAL_RTC_MspInit(RTC_HandleTypeDef *hrtc); -void HAL_RTC_MspDeInit(RTC_HandleTypeDef *hrtc); - -/* Callbacks Register/UnRegister functions ***********************************/ -#if (USE_HAL_RTC_REGISTER_CALLBACKS == 1) -HAL_StatusTypeDef HAL_RTC_RegisterCallback(RTC_HandleTypeDef *hrtc, HAL_RTC_CallbackIDTypeDef CallbackID, pRTC_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_RTC_UnRegisterCallback(RTC_HandleTypeDef *hrtc, HAL_RTC_CallbackIDTypeDef CallbackID); -#endif /* USE_HAL_RTC_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @addtogroup RTC_Exported_Functions_Group2 - * @{ - */ -/* RTC Time and Date functions ************************************************/ -HAL_StatusTypeDef HAL_RTC_SetTime(RTC_HandleTypeDef *hrtc, RTC_TimeTypeDef *sTime, uint32_t Format); -HAL_StatusTypeDef HAL_RTC_GetTime(RTC_HandleTypeDef *hrtc, RTC_TimeTypeDef *sTime, uint32_t Format); -HAL_StatusTypeDef HAL_RTC_SetDate(RTC_HandleTypeDef *hrtc, RTC_DateTypeDef *sDate, uint32_t Format); -HAL_StatusTypeDef HAL_RTC_GetDate(RTC_HandleTypeDef *hrtc, RTC_DateTypeDef *sDate, uint32_t Format); -void HAL_RTC_DST_Add1Hour(RTC_HandleTypeDef *hrtc); -void HAL_RTC_DST_Sub1Hour(RTC_HandleTypeDef *hrtc); -void HAL_RTC_DST_SetStoreOperation(RTC_HandleTypeDef *hrtc); -void HAL_RTC_DST_ClearStoreOperation(RTC_HandleTypeDef *hrtc); -uint32_t HAL_RTC_DST_ReadStoreOperation(RTC_HandleTypeDef *hrtc); -/** - * @} - */ - -/** @addtogroup RTC_Exported_Functions_Group3 - * @{ - */ -/* RTC Alarm functions ********************************************************/ -HAL_StatusTypeDef HAL_RTC_SetAlarm(RTC_HandleTypeDef *hrtc, RTC_AlarmTypeDef *sAlarm, uint32_t Format); -HAL_StatusTypeDef HAL_RTC_SetAlarm_IT(RTC_HandleTypeDef *hrtc, RTC_AlarmTypeDef *sAlarm, uint32_t Format); -HAL_StatusTypeDef HAL_RTC_DeactivateAlarm(RTC_HandleTypeDef *hrtc, uint32_t Alarm); -HAL_StatusTypeDef HAL_RTC_GetAlarm(RTC_HandleTypeDef *hrtc, RTC_AlarmTypeDef *sAlarm, uint32_t Alarm, uint32_t Format); -void HAL_RTC_AlarmIRQHandler(RTC_HandleTypeDef *hrtc); -HAL_StatusTypeDef HAL_RTC_PollForAlarmAEvent(RTC_HandleTypeDef *hrtc, uint32_t Timeout); -void HAL_RTC_AlarmAEventCallback(RTC_HandleTypeDef *hrtc); -/** - * @} - */ - -/** @addtogroup RTC_Exported_Functions_Group4 - * @{ - */ -/* Peripheral Control functions ***********************************************/ -HAL_StatusTypeDef HAL_RTC_WaitForSynchro(RTC_HandleTypeDef* hrtc); -/** - * @} - */ - -/** @addtogroup RTC_Exported_Functions_Group5 - * @{ - */ -/* Peripheral State functions *************************************************/ -HAL_RTCStateTypeDef HAL_RTC_GetState(RTC_HandleTypeDef *hrtc); -/** - * @} - */ - -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup RTC_Private_Constants RTC Private Constants - * @{ - */ -/* Masks Definition */ -#define RTC_TR_RESERVED_MASK 0x007F7F7FU -#define RTC_DR_RESERVED_MASK 0x00FFFF3FU -#define RTC_INIT_MASK 0xFFFFFFFFU -#define RTC_RSF_MASK 0xFFFFFF5FU -#define RTC_FLAGS_MASK ((uint32_t)(RTC_FLAG_TSOVF | RTC_FLAG_TSF | RTC_FLAG_WUTF | \ - RTC_FLAG_ALRBF | RTC_FLAG_ALRAF | RTC_FLAG_INITF | \ - RTC_FLAG_RSF | RTC_FLAG_INITS | RTC_FLAG_WUTWF | \ - RTC_FLAG_ALRBWF | RTC_FLAG_ALRAWF | RTC_FLAG_TAMP1F | \ - RTC_FLAG_RECALPF | RTC_FLAG_SHPF)) - -#define RTC_TIMEOUT_VALUE 1000 - -#define RTC_EXTI_LINE_ALARM_EVENT ((uint32_t)EXTI_IMR_MR17) /*!< External interrupt line 17 Connected to the RTC Alarm event */ -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup RTC_Private_Macros RTC Private Macros - * @{ - */ - -/** @defgroup RTC_IS_RTC_Definitions RTC Private macros to check input parameters - * @{ - */ -#define IS_RTC_HOUR_FORMAT(FORMAT) (((FORMAT) == RTC_HOURFORMAT_12) || \ - ((FORMAT) == RTC_HOURFORMAT_24)) -#define IS_RTC_OUTPUT(OUTPUT) (((OUTPUT) == RTC_OUTPUT_DISABLE) || \ - ((OUTPUT) == RTC_OUTPUT_ALARMA) || \ - ((OUTPUT) == RTC_OUTPUT_ALARMB) || \ - ((OUTPUT) == RTC_OUTPUT_WAKEUP)) -#define IS_RTC_OUTPUT_POL(POL) (((POL) == RTC_OUTPUT_POLARITY_HIGH) || \ - ((POL) == RTC_OUTPUT_POLARITY_LOW)) -#define IS_RTC_OUTPUT_TYPE(TYPE) (((TYPE) == RTC_OUTPUT_TYPE_OPENDRAIN) || \ - ((TYPE) == RTC_OUTPUT_TYPE_PUSHPULL)) -#define IS_RTC_HOUR12(HOUR) (((HOUR) > 0U) && ((HOUR) <= 12U)) -#define IS_RTC_HOUR24(HOUR) ((HOUR) <= 23U) -#define IS_RTC_ASYNCH_PREDIV(PREDIV) ((PREDIV) <= 0x7FU) -#define IS_RTC_SYNCH_PREDIV(PREDIV) ((PREDIV) <= 0x7FFFU) -#define IS_RTC_MINUTES(MINUTES) ((MINUTES) <= 59U) -#define IS_RTC_SECONDS(SECONDS) ((SECONDS) <= 59U) - -#define IS_RTC_HOURFORMAT12(PM) (((PM) == RTC_HOURFORMAT12_AM) || ((PM) == RTC_HOURFORMAT12_PM)) -#define IS_RTC_DAYLIGHT_SAVING(SAVE) (((SAVE) == RTC_DAYLIGHTSAVING_SUB1H) || \ - ((SAVE) == RTC_DAYLIGHTSAVING_ADD1H) || \ - ((SAVE) == RTC_DAYLIGHTSAVING_NONE)) -#define IS_RTC_STORE_OPERATION(OPERATION) (((OPERATION) == RTC_STOREOPERATION_RESET) || \ - ((OPERATION) == RTC_STOREOPERATION_SET)) -#define IS_RTC_FORMAT(FORMAT) (((FORMAT) == RTC_FORMAT_BIN) || ((FORMAT) == RTC_FORMAT_BCD)) -#define IS_RTC_YEAR(YEAR) ((YEAR) <= 99U) -#define IS_RTC_MONTH(MONTH) (((MONTH) >= 1U) && ((MONTH) <= 12U)) -#define IS_RTC_DATE(DATE) (((DATE) >= 1U) && ((DATE) <= 31U)) -#define IS_RTC_WEEKDAY(WEEKDAY) (((WEEKDAY) == RTC_WEEKDAY_MONDAY) || \ - ((WEEKDAY) == RTC_WEEKDAY_TUESDAY) || \ - ((WEEKDAY) == RTC_WEEKDAY_WEDNESDAY) || \ - ((WEEKDAY) == RTC_WEEKDAY_THURSDAY) || \ - ((WEEKDAY) == RTC_WEEKDAY_FRIDAY) || \ - ((WEEKDAY) == RTC_WEEKDAY_SATURDAY) || \ - ((WEEKDAY) == RTC_WEEKDAY_SUNDAY)) -#define IS_RTC_ALARM_DATE_WEEKDAY_DATE(DATE) (((DATE) > 0U) && ((DATE) <= 31U)) -#define IS_RTC_ALARM_DATE_WEEKDAY_WEEKDAY(WEEKDAY) (((WEEKDAY) == RTC_WEEKDAY_MONDAY) || \ - ((WEEKDAY) == RTC_WEEKDAY_TUESDAY) || \ - ((WEEKDAY) == RTC_WEEKDAY_WEDNESDAY) || \ - ((WEEKDAY) == RTC_WEEKDAY_THURSDAY) || \ - ((WEEKDAY) == RTC_WEEKDAY_FRIDAY) || \ - ((WEEKDAY) == RTC_WEEKDAY_SATURDAY) || \ - ((WEEKDAY) == RTC_WEEKDAY_SUNDAY)) -#define IS_RTC_ALARM_DATE_WEEKDAY_SEL(SEL) (((SEL) == RTC_ALARMDATEWEEKDAYSEL_DATE) || \ - ((SEL) == RTC_ALARMDATEWEEKDAYSEL_WEEKDAY)) -#define IS_RTC_ALARM_MASK(MASK) (((MASK) & 0x7F7F7F7FU) == (uint32_t)RESET) -#define IS_RTC_ALARM(ALARM) (((ALARM) == RTC_ALARM_A) || ((ALARM) == RTC_ALARM_B)) -#define IS_RTC_ALARM_SUB_SECOND_VALUE(VALUE) ((VALUE) <= 0x00007FFFU) - -#define IS_RTC_ALARM_SUB_SECOND_MASK(MASK) (((MASK) == RTC_ALARMSUBSECONDMASK_ALL) || \ - ((MASK) == RTC_ALARMSUBSECONDMASK_SS14_1) || \ - ((MASK) == RTC_ALARMSUBSECONDMASK_SS14_2) || \ - ((MASK) == RTC_ALARMSUBSECONDMASK_SS14_3) || \ - ((MASK) == RTC_ALARMSUBSECONDMASK_SS14_4) || \ - ((MASK) == RTC_ALARMSUBSECONDMASK_SS14_5) || \ - ((MASK) == RTC_ALARMSUBSECONDMASK_SS14_6) || \ - ((MASK) == RTC_ALARMSUBSECONDMASK_SS14_7) || \ - ((MASK) == RTC_ALARMSUBSECONDMASK_SS14_8) || \ - ((MASK) == RTC_ALARMSUBSECONDMASK_SS14_9) || \ - ((MASK) == RTC_ALARMSUBSECONDMASK_SS14_10) || \ - ((MASK) == RTC_ALARMSUBSECONDMASK_SS14_11) || \ - ((MASK) == RTC_ALARMSUBSECONDMASK_SS14_12) || \ - ((MASK) == RTC_ALARMSUBSECONDMASK_SS14_13) || \ - ((MASK) == RTC_ALARMSUBSECONDMASK_SS14) || \ - ((MASK) == RTC_ALARMSUBSECONDMASK_NONE)) -/** - * @} - */ - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup RTC_Private_Functions RTC Private Functions - * @{ - */ -HAL_StatusTypeDef RTC_EnterInitMode(RTC_HandleTypeDef* hrtc); -uint8_t RTC_ByteToBcd2(uint8_t Value); -uint8_t RTC_Bcd2ToByte(uint8_t Value); -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_RTC_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rtc_ex.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rtc_ex.h deleted file mode 100644 index 76859ee..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_rtc_ex.h +++ /dev/null @@ -1,1011 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_rtc_ex.h - * @author MCD Application Team - * @brief Header file of RTC HAL Extension module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_RTC_EX_H -#define __STM32F4xx_HAL_RTC_EX_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup RTCEx - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup RTCEx_Exported_Types RTCEx Exported Types - * @{ - */ - -/** - * @brief RTC Tamper structure definition - */ -typedef struct -{ - uint32_t Tamper; /*!< Specifies the Tamper Pin. - This parameter can be a value of @ref RTCEx_Tamper_Pins_Definitions */ - - uint32_t PinSelection; /*!< Specifies the Tamper Pin. - This parameter can be a value of @ref RTCEx_Tamper_Pins_Selection */ - - uint32_t Trigger; /*!< Specifies the Tamper Trigger. - This parameter can be a value of @ref RTCEx_Tamper_Trigger_Definitions */ - - uint32_t Filter; /*!< Specifies the RTC Filter Tamper. - This parameter can be a value of @ref RTCEx_Tamper_Filter_Definitions */ - - uint32_t SamplingFrequency; /*!< Specifies the sampling frequency. - This parameter can be a value of @ref RTCEx_Tamper_Sampling_Frequencies_Definitions */ - - uint32_t PrechargeDuration; /*!< Specifies the Precharge Duration . - This parameter can be a value of @ref RTCEx_Tamper_Pin_Precharge_Duration_Definitions */ - - uint32_t TamperPullUp; /*!< Specifies the Tamper PullUp . - This parameter can be a value of @ref RTCEx_Tamper_Pull_UP_Definitions */ - - uint32_t TimeStampOnTamperDetection; /*!< Specifies the TimeStampOnTamperDetection. - This parameter can be a value of @ref RTCEx_Tamper_TimeStampOnTamperDetection_Definitions */ -}RTC_TamperTypeDef; -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup RTCEx_Exported_Constants RTCEx Exported Constants - * @{ - */ - -/** @defgroup RTCEx_Backup_Registers_Definitions RTC Backup Registers Definitions - * @{ - */ -#define RTC_BKP_DR0 0x00000000U -#define RTC_BKP_DR1 0x00000001U -#define RTC_BKP_DR2 0x00000002U -#define RTC_BKP_DR3 0x00000003U -#define RTC_BKP_DR4 0x00000004U -#define RTC_BKP_DR5 0x00000005U -#define RTC_BKP_DR6 0x00000006U -#define RTC_BKP_DR7 0x00000007U -#define RTC_BKP_DR8 0x00000008U -#define RTC_BKP_DR9 0x00000009U -#define RTC_BKP_DR10 0x0000000AU -#define RTC_BKP_DR11 0x0000000BU -#define RTC_BKP_DR12 0x0000000CU -#define RTC_BKP_DR13 0x0000000DU -#define RTC_BKP_DR14 0x0000000EU -#define RTC_BKP_DR15 0x0000000FU -#define RTC_BKP_DR16 0x00000010U -#define RTC_BKP_DR17 0x00000011U -#define RTC_BKP_DR18 0x00000012U -#define RTC_BKP_DR19 0x00000013U -/** - * @} - */ - -/** @defgroup RTCEx_Time_Stamp_Edges_definitions RTC TimeStamp Edges Definitions - * @{ - */ -#define RTC_TIMESTAMPEDGE_RISING 0x00000000U -#define RTC_TIMESTAMPEDGE_FALLING 0x00000008U -/** - * @} - */ - -/** @defgroup RTCEx_Tamper_Pins_Definitions RTC Tamper Pins Definitions - * @{ - */ -#define RTC_TAMPER_1 RTC_TAFCR_TAMP1E - -#if !defined(STM32F412Zx) && !defined(STM32F412Vx) && !defined(STM32F412Rx) && !defined(STM32F412Cx) && !defined(STM32F413xx) && !defined(STM32F423xx) -#define RTC_TAMPER_2 RTC_TAFCR_TAMP2E -#endif -/** - * @} - */ - -/** @defgroup RTCEx_Tamper_Pins_Selection RTC tamper Pins Selection - * @{ - */ - -#define RTC_TAMPERPIN_DEFAULT 0x00000000U - -#if !defined(STM32F412Zx) && !defined(STM32F412Vx) && !defined(STM32F412Rx) && !defined(STM32F412Cx) && !defined(STM32F413xx) && !defined(STM32F423xx) -#define RTC_TAMPERPIN_POS1 0x00010000U -#endif -/** - * @} - */ - -/** @defgroup RTCEx_TimeStamp_Pin_Selection RTC TimeStamp Pins Selection - * @{ - */ -#define RTC_TIMESTAMPPIN_DEFAULT 0x00000000U - -#if !defined(STM32F412Zx) && !defined(STM32F412Vx) && !defined(STM32F412Rx) && !defined(STM32F412Cx) && !defined(STM32F413xx) && !defined(STM32F423xx) -#define RTC_TIMESTAMPPIN_POS1 0x00020000U -#endif -/** - * @} - */ - -/** @defgroup RTCEx_Tamper_Trigger_Definitions RTC Tamper Triggers Definitions - * @{ - */ -#define RTC_TAMPERTRIGGER_RISINGEDGE 0x00000000U -#define RTC_TAMPERTRIGGER_FALLINGEDGE 0x00000002U -#define RTC_TAMPERTRIGGER_LOWLEVEL RTC_TAMPERTRIGGER_RISINGEDGE -#define RTC_TAMPERTRIGGER_HIGHLEVEL RTC_TAMPERTRIGGER_FALLINGEDGE -/** - * @} - */ - -/** @defgroup RTCEx_Tamper_Filter_Definitions RTC Tamper Filter Definitions - * @{ - */ -#define RTC_TAMPERFILTER_DISABLE 0x00000000U /*!< Tamper filter is disabled */ - -#define RTC_TAMPERFILTER_2SAMPLE 0x00000800U /*!< Tamper is activated after 2 - consecutive samples at the active level */ -#define RTC_TAMPERFILTER_4SAMPLE 0x00001000U /*!< Tamper is activated after 4 - consecutive samples at the active level */ -#define RTC_TAMPERFILTER_8SAMPLE 0x00001800U /*!< Tamper is activated after 8 - consecutive samples at the active level. */ -/** - * @} - */ - -/** @defgroup RTCEx_Tamper_Sampling_Frequencies_Definitions RTC Tamper Sampling Frequencies Definitions - * @{ - */ -#define RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV32768 0x00000000U /*!< Each of the tamper inputs are sampled - with a frequency = RTCCLK / 32768 */ -#define RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV16384 0x00000100U /*!< Each of the tamper inputs are sampled - with a frequency = RTCCLK / 16384 */ -#define RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV8192 0x00000200U /*!< Each of the tamper inputs are sampled - with a frequency = RTCCLK / 8192 */ -#define RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV4096 0x00000300U /*!< Each of the tamper inputs are sampled - with a frequency = RTCCLK / 4096 */ -#define RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV2048 0x00000400U /*!< Each of the tamper inputs are sampled - with a frequency = RTCCLK / 2048 */ -#define RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV1024 0x00000500U /*!< Each of the tamper inputs are sampled - with a frequency = RTCCLK / 1024 */ -#define RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV512 0x00000600U /*!< Each of the tamper inputs are sampled - with a frequency = RTCCLK / 512 */ -#define RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV256 0x00000700U /*!< Each of the tamper inputs are sampled - with a frequency = RTCCLK / 256 */ -/** - * @} - */ - -/** @defgroup RTCEx_Tamper_Pin_Precharge_Duration_Definitions RTC Tamper Pin Precharge Duration Definitions - * @{ - */ -#define RTC_TAMPERPRECHARGEDURATION_1RTCCLK 0x00000000U /*!< Tamper pins are pre-charged before - sampling during 1 RTCCLK cycle */ -#define RTC_TAMPERPRECHARGEDURATION_2RTCCLK 0x00002000U /*!< Tamper pins are pre-charged before - sampling during 2 RTCCLK cycles */ -#define RTC_TAMPERPRECHARGEDURATION_4RTCCLK 0x00004000U /*!< Tamper pins are pre-charged before - sampling during 4 RTCCLK cycles */ -#define RTC_TAMPERPRECHARGEDURATION_8RTCCLK 0x00006000U /*!< Tamper pins are pre-charged before - sampling during 8 RTCCLK cycles */ -/** - * @} - */ - -/** @defgroup RTCEx_Tamper_TimeStampOnTamperDetection_Definitions RTC Tamper TimeStamp On Tamper Detection Definitions - * @{ - */ -#define RTC_TIMESTAMPONTAMPERDETECTION_ENABLE ((uint32_t)RTC_TAFCR_TAMPTS) /*!< TimeStamp on Tamper Detection event saved */ -#define RTC_TIMESTAMPONTAMPERDETECTION_DISABLE 0x00000000U /*!< TimeStamp on Tamper Detection event is not saved */ -/** - * @} - */ - -/** @defgroup RTCEx_Tamper_Pull_UP_Definitions RTC Tamper Pull Up Definitions - * @{ - */ -#define RTC_TAMPER_PULLUP_ENABLE 0x00000000U /*!< TimeStamp on Tamper Detection event saved */ -#define RTC_TAMPER_PULLUP_DISABLE ((uint32_t)RTC_TAFCR_TAMPPUDIS) /*!< TimeStamp on Tamper Detection event is not saved */ -/** - * @} - */ - -/** @defgroup RTCEx_Wakeup_Timer_Definitions RTC Wake-up Timer Definitions - * @{ - */ -#define RTC_WAKEUPCLOCK_RTCCLK_DIV16 0x00000000U -#define RTC_WAKEUPCLOCK_RTCCLK_DIV8 0x00000001U -#define RTC_WAKEUPCLOCK_RTCCLK_DIV4 0x00000002U -#define RTC_WAKEUPCLOCK_RTCCLK_DIV2 0x00000003U -#define RTC_WAKEUPCLOCK_CK_SPRE_16BITS 0x00000004U -#define RTC_WAKEUPCLOCK_CK_SPRE_17BITS 0x00000006U -/** - * @} - */ - -/** @defgroup RTCEx_Digital_Calibration_Definitions RTC Digital Calib Definitions - * @{ - */ -#define RTC_CALIBSIGN_POSITIVE 0x00000000U -#define RTC_CALIBSIGN_NEGATIVE 0x00000080U -/** - * @} - */ - -/** @defgroup RTCEx_Smooth_calib_period_Definitions RTC Smooth Calib Period Definitions - * @{ - */ -#define RTC_SMOOTHCALIB_PERIOD_32SEC 0x00000000U /*!< If RTCCLK = 32768 Hz, Smooth calibration - period is 32s, else 2exp20 RTCCLK seconds */ -#define RTC_SMOOTHCALIB_PERIOD_16SEC 0x00002000U /*!< If RTCCLK = 32768 Hz, Smooth calibration - period is 16s, else 2exp19 RTCCLK seconds */ -#define RTC_SMOOTHCALIB_PERIOD_8SEC 0x00004000U /*!< If RTCCLK = 32768 Hz, Smooth calibration - period is 8s, else 2exp18 RTCCLK seconds */ -/** - * @} - */ - -/** @defgroup RTCEx_Smooth_calib_Plus_pulses_Definitions RTC Smooth Calib Plus Pulses Definitions - * @{ - */ -#define RTC_SMOOTHCALIB_PLUSPULSES_SET 0x00008000U /*!< The number of RTCCLK pulses added - during a X -second window = Y - CALM[8:0] - with Y = 512, 256, 128 when X = 32, 16, 8 */ -#define RTC_SMOOTHCALIB_PLUSPULSES_RESET 0x00000000U /*!< The number of RTCCLK pulses subbstited - during a 32-second window = CALM[8:0] */ -/** - * @} - */ - -/** @defgroup RTCEx_Add_1_Second_Parameter_Definitions RTC Add 1 Second Parameter Definitions - * @{ - */ -#define RTC_SHIFTADD1S_RESET 0x00000000U -#define RTC_SHIFTADD1S_SET 0x80000000U -/** - * @} - */ - - - /** @defgroup RTCEx_Calib_Output_selection_Definitions RTC Calib Output Selection Definitions - * @{ - */ -#define RTC_CALIBOUTPUT_512HZ 0x00000000U -#define RTC_CALIBOUTPUT_1HZ 0x00080000U -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup RTCEx_Exported_Macros RTCEx Exported Macros - * @{ - */ - -/* ---------------------------------WAKEUPTIMER---------------------------------*/ -/** @defgroup RTCEx_WakeUp_Timer RTC WakeUp Timer - * @{ - */ - -/** - * @brief Enable the RTC WakeUp Timer peripheral. - * @param __HANDLE__ specifies the RTC handle. - * @retval None - */ -#define __HAL_RTC_WAKEUPTIMER_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= (RTC_CR_WUTE)) - -/** - * @brief Disable the RTC Wake-up Timer peripheral. - * @param __HANDLE__ specifies the RTC handle. - * @retval None - */ -#define __HAL_RTC_WAKEUPTIMER_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR &= ~(RTC_CR_WUTE)) - -/** - * @brief Enable the RTC WakeUpTimer interrupt. - * @param __HANDLE__ specifies the RTC handle. - * @param __INTERRUPT__ specifies the RTC WakeUpTimer interrupt sources to be enabled or disabled. - * This parameter can be: - * @arg RTC_IT_WUT: WakeUpTimer A interrupt - * @retval None - */ -#define __HAL_RTC_WAKEUPTIMER_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR |= (__INTERRUPT__)) - -/** - * @brief Disable the RTC WakeUpTimer interrupt. - * @param __HANDLE__ specifies the RTC handle. - * @param __INTERRUPT__ specifies the RTC WakeUpTimer interrupt sources to be enabled or disabled. - * This parameter can be: - * @arg RTC_IT_WUT: WakeUpTimer A interrupt - * @retval None - */ -#define __HAL_RTC_WAKEUPTIMER_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR &= ~(__INTERRUPT__)) - -/** - * @brief Check whether the specified RTC WakeUpTimer interrupt has occurred or not. - * @param __HANDLE__ specifies the RTC handle. - * @param __INTERRUPT__ specifies the RTC WakeUpTimer interrupt to check. - * This parameter can be: - * @arg RTC_IT_WUT: WakeUpTimer A interrupt - * @retval None - */ -#define __HAL_RTC_WAKEUPTIMER_GET_IT(__HANDLE__, __INTERRUPT__) (((((__HANDLE__)->Instance->ISR) & ((__INTERRUPT__)>> 4U)) != RESET)? SET : RESET) - -/** - * @brief Check whether the specified RTC Wake Up timer interrupt has been enabled or not. - * @param __HANDLE__ specifies the RTC handle. - * @param __INTERRUPT__ specifies the RTC Wake Up timer interrupt sources to check. - * This parameter can be: - * @arg RTC_IT_WUT: WakeUpTimer interrupt - * @retval None - */ -#define __HAL_RTC_WAKEUPTIMER_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) (((((__HANDLE__)->Instance->CR) & (__INTERRUPT__)) != RESET) ? SET : RESET) - -/** - * @brief Get the selected RTC WakeUpTimer's flag status. - * @param __HANDLE__ specifies the RTC handle. - * @param __FLAG__ specifies the RTC WakeUpTimer Flag to check. - * This parameter can be: - * @arg RTC_FLAG_WUTF - * @arg RTC_FLAG_WUTWF - * @retval None - */ -#define __HAL_RTC_WAKEUPTIMER_GET_FLAG(__HANDLE__, __FLAG__) (((((__HANDLE__)->Instance->ISR) & (__FLAG__)) != RESET)? SET : RESET) - -/** - * @brief Clear the RTC Wake Up timer's pending flags. - * @param __HANDLE__ specifies the RTC handle. - * @param __FLAG__ specifies the RTC Tamper Flag sources to be enabled or disabled. - * This parameter can be: - * @arg RTC_FLAG_WUTF - * @retval None - */ -#define __HAL_RTC_WAKEUPTIMER_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->ISR) = (~((__FLAG__) | RTC_ISR_INIT)|((__HANDLE__)->Instance->ISR & RTC_ISR_INIT)) - -/** - * @brief Enable interrupt on the RTC Wake-up Timer associated Exti line. - * @retval None - */ -#define __HAL_RTC_WAKEUPTIMER_EXTI_ENABLE_IT() (EXTI->IMR |= RTC_EXTI_LINE_WAKEUPTIMER_EVENT) - -/** - * @brief Disable interrupt on the RTC Wake-up Timer associated Exti line. - * @retval None - */ -#define __HAL_RTC_WAKEUPTIMER_EXTI_DISABLE_IT() (EXTI->IMR &= ~(RTC_EXTI_LINE_WAKEUPTIMER_EVENT)) - -/** - * @brief Enable event on the RTC Wake-up Timer associated Exti line. - * @retval None. - */ -#define __HAL_RTC_WAKEUPTIMER_EXTI_ENABLE_EVENT() (EXTI->EMR |= RTC_EXTI_LINE_WAKEUPTIMER_EVENT) - -/** - * @brief Disable event on the RTC Wake-up Timer associated Exti line. - * @retval None. - */ -#define __HAL_RTC_WAKEUPTIMER_EXTI_DISABLE_EVENT() (EXTI->EMR &= ~(RTC_EXTI_LINE_WAKEUPTIMER_EVENT)) - -/** - * @brief Enable falling edge trigger on the RTC Wake-up Timer associated Exti line. - * @retval None. - */ -#define __HAL_RTC_WAKEUPTIMER_EXTI_ENABLE_FALLING_EDGE() (EXTI->FTSR |= RTC_EXTI_LINE_WAKEUPTIMER_EVENT) - -/** - * @brief Disable falling edge trigger on the RTC Wake-up Timer associated Exti line. - * @retval None. - */ -#define __HAL_RTC_WAKEUPTIMER_EXTI_DISABLE_FALLING_EDGE() (EXTI->FTSR &= ~(RTC_EXTI_LINE_WAKEUPTIMER_EVENT)) - -/** - * @brief Enable rising edge trigger on the RTC Wake-up Timer associated Exti line. - * @retval None. - */ -#define __HAL_RTC_WAKEUPTIMER_EXTI_ENABLE_RISING_EDGE() (EXTI->RTSR |= RTC_EXTI_LINE_WAKEUPTIMER_EVENT) - -/** - * @brief Disable rising edge trigger on the RTC Wake-up Timer associated Exti line. - * @retval None. - */ -#define __HAL_RTC_WAKEUPTIMER_EXTI_DISABLE_RISING_EDGE() (EXTI->RTSR &= ~(RTC_EXTI_LINE_WAKEUPTIMER_EVENT)) - -/** - * @brief Enable rising & falling edge trigger on the RTC Wake-up Timer associated Exti line. - * @retval None. - */ -#define __HAL_RTC_WAKEUPTIMER_EXTI_ENABLE_RISING_FALLING_EDGE() do { __HAL_RTC_WAKEUPTIMER_EXTI_ENABLE_RISING_EDGE();\ - __HAL_RTC_WAKEUPTIMER_EXTI_ENABLE_FALLING_EDGE();\ - } while(0U) - -/** - * @brief Disable rising & falling edge trigger on the RTC Wake-up Timer associated Exti line. - * This parameter can be: - * @retval None. - */ -#define __HAL_RTC_WAKEUPTIMER_EXTI_DISABLE_RISING_FALLING_EDGE() do { __HAL_RTC_WAKEUPTIMER_EXTI_DISABLE_RISING_EDGE();\ - __HAL_RTC_WAKEUPTIMER_EXTI_DISABLE_FALLING_EDGE();\ - } while(0U) - -/** - * @brief Check whether the RTC Wake-up Timer associated Exti line interrupt flag is set or not. - * @retval Line Status. - */ -#define __HAL_RTC_WAKEUPTIMER_EXTI_GET_FLAG() (EXTI->PR & RTC_EXTI_LINE_WAKEUPTIMER_EVENT) - -/** - * @brief Clear the RTC Wake-up Timer associated Exti line flag. - * @retval None. - */ -#define __HAL_RTC_WAKEUPTIMER_EXTI_CLEAR_FLAG() (EXTI->PR = RTC_EXTI_LINE_WAKEUPTIMER_EVENT) - -/** - * @brief Generate a Software interrupt on the RTC Wake-up Timer associated Exti line. - * @retval None. - */ -#define __HAL_RTC_WAKEUPTIMER_EXTI_GENERATE_SWIT() (EXTI->SWIER |= RTC_EXTI_LINE_WAKEUPTIMER_EVENT) - -/** - * @} - */ - -/* ---------------------------------TIMESTAMP---------------------------------*/ -/** @defgroup RTCEx_Timestamp RTC Timestamp - * @{ - */ - -/** - * @brief Enable the RTC TimeStamp peripheral. - * @param __HANDLE__ specifies the RTC handle. - * @retval None - */ -#define __HAL_RTC_TIMESTAMP_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= (RTC_CR_TSE)) - -/** - * @brief Disable the RTC TimeStamp peripheral. - * @param __HANDLE__ specifies the RTC handle. - * @retval None - */ -#define __HAL_RTC_TIMESTAMP_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR &= ~(RTC_CR_TSE)) - -/** - * @brief Enable the RTC TimeStamp interrupt. - * @param __HANDLE__ specifies the RTC handle. - * @param __INTERRUPT__ specifies the RTC TimeStamp interrupt sources to be enabled or disabled. - * This parameter can be: - * @arg RTC_IT_TS: TimeStamp interrupt - * @retval None - */ -#define __HAL_RTC_TIMESTAMP_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR |= (__INTERRUPT__)) - -/** - * @brief Disable the RTC TimeStamp interrupt. - * @param __HANDLE__ specifies the RTC handle. - * @param __INTERRUPT__ specifies the RTC TimeStamp interrupt sources to be enabled or disabled. - * This parameter can be: - * @arg RTC_IT_TS: TimeStamp interrupt - * @retval None - */ -#define __HAL_RTC_TIMESTAMP_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR &= ~(__INTERRUPT__)) - -/** - * @brief Check whether the specified RTC TimeStamp interrupt has occurred or not. - * @param __HANDLE__ specifies the RTC handle. - * @param __INTERRUPT__ specifies the RTC TimeStamp interrupt to check. - * This parameter can be: - * @arg RTC_IT_TS: TimeStamp interrupt - * @retval None - */ -#define __HAL_RTC_TIMESTAMP_GET_IT(__HANDLE__, __INTERRUPT__) (((((__HANDLE__)->Instance->ISR) & ((__INTERRUPT__)>> 4U)) != RESET)? SET : RESET) - -/** - * @brief Check whether the specified RTC Time Stamp interrupt has been enabled or not. - * @param __HANDLE__ specifies the RTC handle. - * @param __INTERRUPT__ specifies the RTC Time Stamp interrupt source to check. - * This parameter can be: - * @arg RTC_IT_TS: TimeStamp interrupt - * @retval None - */ -#define __HAL_RTC_TIMESTAMP_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) (((((__HANDLE__)->Instance->CR) & (__INTERRUPT__)) != RESET) ? SET : RESET) - -/** - * @brief Get the selected RTC TimeStamp's flag status. - * @param __HANDLE__ specifies the RTC handle. - * @param __FLAG__ specifies the RTC TimeStamp flag to check. - * This parameter can be: - * @arg RTC_FLAG_TSF - * @arg RTC_FLAG_TSOVF - * @retval None - */ -#define __HAL_RTC_TIMESTAMP_GET_FLAG(__HANDLE__, __FLAG__) (((((__HANDLE__)->Instance->ISR) & (__FLAG__)) != RESET)? SET : RESET) - -/** - * @brief Clear the RTC Time Stamp's pending flags. - * @param __HANDLE__ specifies the RTC handle. - * @param __FLAG__ specifies the RTC Alarm Flag sources to be enabled or disabled. - * This parameter can be: - * @arg RTC_FLAG_TSF - * @retval None - */ -#define __HAL_RTC_TIMESTAMP_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->ISR) = (~((__FLAG__) | RTC_ISR_INIT)|((__HANDLE__)->Instance->ISR & RTC_ISR_INIT)) - -/** - * @} - */ - -/* ---------------------------------TAMPER------------------------------------*/ -/** @defgroup RTCEx_Tamper RTC Tamper - * @{ - */ - -/** - * @brief Enable the RTC Tamper1 input detection. - * @param __HANDLE__ specifies the RTC handle. - * @retval None - */ -#define __HAL_RTC_TAMPER1_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->TAFCR |= (RTC_TAFCR_TAMP1E)) - -/** - * @brief Disable the RTC Tamper1 input detection. - * @param __HANDLE__ specifies the RTC handle. - * @retval None - */ -#define __HAL_RTC_TAMPER1_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->TAFCR &= ~(RTC_TAFCR_TAMP1E)) - -#if !defined(STM32F412Zx) && !defined(STM32F412Vx) && !defined(STM32F412Rx) && !defined(STM32F412Cx) && !defined(STM32F413xx) && !defined(STM32F423xx) -/** - * @brief Enable the RTC Tamper2 input detection. - * @param __HANDLE__ specifies the RTC handle. - * @retval None - */ -#define __HAL_RTC_TAMPER2_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->TAFCR |= (RTC_TAFCR_TAMP2E)) - -/** - * @brief Disable the RTC Tamper2 input detection. - * @param __HANDLE__ specifies the RTC handle. - * @retval None - */ -#define __HAL_RTC_TAMPER2_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->TAFCR &= ~(RTC_TAFCR_TAMP2E)) -#endif - -/** - * @brief Check whether the specified RTC Tamper interrupt has occurred or not. - * @param __HANDLE__ specifies the RTC handle. - * @param __INTERRUPT__ specifies the RTC Tamper interrupt to check. - * This parameter can be: - * @arg RTC_IT_TAMP1 - * @arg RTC_IT_TAMP2 - * @retval None - */ -#define __HAL_RTC_TAMPER_GET_IT(__HANDLE__, __INTERRUPT__) (((((__HANDLE__)->Instance->ISR) & ((__INTERRUPT__)>> 4U)) != RESET)? SET : RESET) - -/** - * @brief Check whether the specified RTC Tamper interrupt has been enabled or not. - * @param __HANDLE__ specifies the RTC handle. - * @param __INTERRUPT__ specifies the RTC Tamper interrupt source to check. - * This parameter can be: - * @arg RTC_IT_TAMP: Tamper interrupt - * @retval None - */ -#define __HAL_RTC_TAMPER_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) (((((__HANDLE__)->Instance->TAFCR) & (__INTERRUPT__)) != RESET) ? SET : RESET) - -/** - * @brief Get the selected RTC Tamper's flag status. - * @param __HANDLE__ specifies the RTC handle. - * @param __FLAG__ specifies the RTC Tamper Flag sources to be enabled or disabled. - * This parameter can be: - * @arg RTC_FLAG_TAMP1F - * @arg RTC_FLAG_TAMP2F - * @retval None - */ -#define __HAL_RTC_TAMPER_GET_FLAG(__HANDLE__, __FLAG__) (((((__HANDLE__)->Instance->ISR) & (__FLAG__)) != RESET)? SET : RESET) - -/** - * @brief Clear the RTC Tamper's pending flags. - * @param __HANDLE__ specifies the RTC handle. - * @param __FLAG__ specifies the RTC Tamper Flag to clear. - * This parameter can be: - * @arg RTC_FLAG_TAMP1F - * @arg RTC_FLAG_TAMP2F - * @retval None - */ -#define __HAL_RTC_TAMPER_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->ISR) = (~((__FLAG__) | RTC_ISR_INIT)|((__HANDLE__)->Instance->ISR & RTC_ISR_INIT)) -/** - * @} - */ - -/* --------------------------TAMPER/TIMESTAMP---------------------------------*/ -/** @defgroup RTCEx_Tamper_Timestamp EXTI RTC Tamper Timestamp EXTI - * @{ - */ - -/** - * @brief Enable interrupt on the RTC Tamper and Timestamp associated Exti line. - * @retval None - */ -#define __HAL_RTC_TAMPER_TIMESTAMP_EXTI_ENABLE_IT() (EXTI->IMR |= RTC_EXTI_LINE_TAMPER_TIMESTAMP_EVENT) - -/** - * @brief Disable interrupt on the RTC Tamper and Timestamp associated Exti line. - * @retval None - */ -#define __HAL_RTC_TAMPER_TIMESTAMP_EXTI_DISABLE_IT() (EXTI->IMR &= ~(RTC_EXTI_LINE_TAMPER_TIMESTAMP_EVENT)) - -/** - * @brief Enable event on the RTC Tamper and Timestamp associated Exti line. - * @retval None. - */ -#define __HAL_RTC_TAMPER_TIMESTAMP_EXTI_ENABLE_EVENT() (EXTI->EMR |= RTC_EXTI_LINE_TAMPER_TIMESTAMP_EVENT) - -/** - * @brief Disable event on the RTC Tamper and Timestamp associated Exti line. - * @retval None. - */ -#define __HAL_RTC_TAMPER_TIMESTAMP_EXTI_DISABLE_EVENT() (EXTI->EMR &= ~(RTC_EXTI_LINE_TAMPER_TIMESTAMP_EVENT)) - -/** - * @brief Enable falling edge trigger on the RTC Tamper and Timestamp associated Exti line. - * @retval None. - */ -#define __HAL_RTC_TAMPER_TIMESTAMP_EXTI_ENABLE_FALLING_EDGE() (EXTI->FTSR |= RTC_EXTI_LINE_TAMPER_TIMESTAMP_EVENT) - -/** - * @brief Disable falling edge trigger on the RTC Tamper and Timestamp associated Exti line. - * @retval None. - */ -#define __HAL_RTC_TAMPER_TIMESTAMP_EXTI_DISABLE_FALLING_EDGE() (EXTI->FTSR &= ~(RTC_EXTI_LINE_TAMPER_TIMESTAMP_EVENT)) - -/** - * @brief Enable rising edge trigger on the RTC Tamper and Timestamp associated Exti line. - * @retval None. - */ -#define __HAL_RTC_TAMPER_TIMESTAMP_EXTI_ENABLE_RISING_EDGE() (EXTI->RTSR |= RTC_EXTI_LINE_TAMPER_TIMESTAMP_EVENT) - -/** - * @brief Disable rising edge trigger on the RTC Tamper and Timestamp associated Exti line. - * @retval None. - */ -#define __HAL_RTC_TAMPER_TIMESTAMP_EXTI_DISABLE_RISING_EDGE() (EXTI->RTSR &= ~(RTC_EXTI_LINE_TAMPER_TIMESTAMP_EVENT)) - -/** - * @brief Enable rising & falling edge trigger on the RTC Tamper and Timestamp associated Exti line. - * @retval None. - */ -#define __HAL_RTC_TAMPER_TIMESTAMP_EXTI_ENABLE_RISING_FALLING_EDGE() do { __HAL_RTC_TAMPER_TIMESTAMP_EXTI_ENABLE_RISING_EDGE();\ - __HAL_RTC_TAMPER_TIMESTAMP_EXTI_ENABLE_FALLING_EDGE(); \ - } while(0U) - -/** - * @brief Disable rising & falling edge trigger on the RTC Tamper and Timestamp associated Exti line. - * This parameter can be: - * @retval None. - */ -#define __HAL_RTC_TAMPER_TIMESTAMP_EXTI_DISABLE_RISING_FALLING_EDGE() do { __HAL_RTC_TAMPER_TIMESTAMP_EXTI_DISABLE_RISING_EDGE();\ - __HAL_RTC_TAMPER_TIMESTAMP_EXTI_DISABLE_FALLING_EDGE();\ - } while(0U) - -/** - * @brief Check whether the RTC Tamper and Timestamp associated Exti line interrupt flag is set or not. - * @retval Line Status. - */ -#define __HAL_RTC_TAMPER_TIMESTAMP_EXTI_GET_FLAG() (EXTI->PR & RTC_EXTI_LINE_TAMPER_TIMESTAMP_EVENT) - -/** - * @brief Clear the RTC Tamper and Timestamp associated Exti line flag. - * @retval None. - */ -#define __HAL_RTC_TAMPER_TIMESTAMP_EXTI_CLEAR_FLAG() (EXTI->PR = RTC_EXTI_LINE_TAMPER_TIMESTAMP_EVENT) - -/** - * @brief Generate a Software interrupt on the RTC Tamper and Timestamp associated Exti line - * @retval None. - */ -#define __HAL_RTC_TAMPER_TIMESTAMP_EXTI_GENERATE_SWIT() (EXTI->SWIER |= RTC_EXTI_LINE_TAMPER_TIMESTAMP_EVENT) -/** - * @} - */ - -/* ------------------------------Calibration----------------------------------*/ -/** @defgroup RTCEx_Calibration RTC Calibration - * @{ - */ - -/** - * @brief Enable the Coarse calibration process. - * @param __HANDLE__ specifies the RTC handle. - * @retval None - */ -#define __HAL_RTC_COARSE_CALIB_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= (RTC_CR_DCE)) - -/** - * @brief Disable the Coarse calibration process. - * @param __HANDLE__ specifies the RTC handle. - * @retval None - */ -#define __HAL_RTC_COARSE_CALIB_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR &= ~(RTC_CR_DCE)) - -/** - * @brief Enable the RTC calibration output. - * @param __HANDLE__ specifies the RTC handle. - * @retval None - */ -#define __HAL_RTC_CALIBRATION_OUTPUT_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= (RTC_CR_COE)) - -/** - * @brief Disable the calibration output. - * @param __HANDLE__ specifies the RTC handle. - * @retval None - */ -#define __HAL_RTC_CALIBRATION_OUTPUT_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR &= ~(RTC_CR_COE)) - -/** - * @brief Enable the clock reference detection. - * @param __HANDLE__ specifies the RTC handle. - * @retval None - */ -#define __HAL_RTC_CLOCKREF_DETECTION_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR |= (RTC_CR_REFCKON)) - -/** - * @brief Disable the clock reference detection. - * @param __HANDLE__ specifies the RTC handle. - * @retval None - */ -#define __HAL_RTC_CLOCKREF_DETECTION_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR &= ~(RTC_CR_REFCKON)) - -/** - * @brief Get the selected RTC shift operation's flag status. - * @param __HANDLE__ specifies the RTC handle. - * @param __FLAG__ specifies the RTC shift operation Flag is pending or not. - * This parameter can be: - * @arg RTC_FLAG_SHPF - * @retval None - */ -#define __HAL_RTC_SHIFT_GET_FLAG(__HANDLE__, __FLAG__) (((((__HANDLE__)->Instance->ISR) & (__FLAG__)) != RESET)? SET : RESET) -/** - * @} - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup RTCEx_Exported_Functions RTCEx Exported Functions - * @{ - */ - -/** @addtogroup RTCEx_Exported_Functions_Group1 - * @{ - */ -/* RTC TimeStamp and Tamper functions *****************************************/ -HAL_StatusTypeDef HAL_RTCEx_SetTimeStamp(RTC_HandleTypeDef *hrtc, uint32_t TimeStampEdge, uint32_t RTC_TimeStampPin); -HAL_StatusTypeDef HAL_RTCEx_SetTimeStamp_IT(RTC_HandleTypeDef *hrtc, uint32_t TimeStampEdge, uint32_t RTC_TimeStampPin); -HAL_StatusTypeDef HAL_RTCEx_DeactivateTimeStamp(RTC_HandleTypeDef *hrtc); -HAL_StatusTypeDef HAL_RTCEx_GetTimeStamp(RTC_HandleTypeDef *hrtc, RTC_TimeTypeDef *sTimeStamp, RTC_DateTypeDef *sTimeStampDate, uint32_t Format); - -HAL_StatusTypeDef HAL_RTCEx_SetTamper(RTC_HandleTypeDef *hrtc, RTC_TamperTypeDef* sTamper); -HAL_StatusTypeDef HAL_RTCEx_SetTamper_IT(RTC_HandleTypeDef *hrtc, RTC_TamperTypeDef* sTamper); -HAL_StatusTypeDef HAL_RTCEx_DeactivateTamper(RTC_HandleTypeDef *hrtc, uint32_t Tamper); -void HAL_RTCEx_TamperTimeStampIRQHandler(RTC_HandleTypeDef *hrtc); - -void HAL_RTCEx_Tamper1EventCallback(RTC_HandleTypeDef *hrtc); -void HAL_RTCEx_Tamper2EventCallback(RTC_HandleTypeDef *hrtc); -void HAL_RTCEx_TimeStampEventCallback(RTC_HandleTypeDef *hrtc); -HAL_StatusTypeDef HAL_RTCEx_PollForTimeStampEvent(RTC_HandleTypeDef *hrtc, uint32_t Timeout); -HAL_StatusTypeDef HAL_RTCEx_PollForTamper1Event(RTC_HandleTypeDef *hrtc, uint32_t Timeout); -HAL_StatusTypeDef HAL_RTCEx_PollForTamper2Event(RTC_HandleTypeDef *hrtc, uint32_t Timeout); -/** - * @} - */ - -/** @addtogroup RTCEx_Exported_Functions_Group2 - * @{ - */ -/* RTC Wake-up functions ******************************************************/ -HAL_StatusTypeDef HAL_RTCEx_SetWakeUpTimer(RTC_HandleTypeDef *hrtc, uint32_t WakeUpCounter, uint32_t WakeUpClock); -HAL_StatusTypeDef HAL_RTCEx_SetWakeUpTimer_IT(RTC_HandleTypeDef *hrtc, uint32_t WakeUpCounter, uint32_t WakeUpClock); -uint32_t HAL_RTCEx_DeactivateWakeUpTimer(RTC_HandleTypeDef *hrtc); -uint32_t HAL_RTCEx_GetWakeUpTimer(RTC_HandleTypeDef *hrtc); -void HAL_RTCEx_WakeUpTimerIRQHandler(RTC_HandleTypeDef *hrtc); -void HAL_RTCEx_WakeUpTimerEventCallback(RTC_HandleTypeDef *hrtc); -HAL_StatusTypeDef HAL_RTCEx_PollForWakeUpTimerEvent(RTC_HandleTypeDef *hrtc, uint32_t Timeout); -/** - * @} - */ - -/** @addtogroup RTCEx_Exported_Functions_Group3 - * @{ - */ -/* Extension Control functions ************************************************/ -void HAL_RTCEx_BKUPWrite(RTC_HandleTypeDef *hrtc, uint32_t BackupRegister, uint32_t Data); -uint32_t HAL_RTCEx_BKUPRead(RTC_HandleTypeDef *hrtc, uint32_t BackupRegister); - -HAL_StatusTypeDef HAL_RTCEx_SetCoarseCalib(RTC_HandleTypeDef *hrtc, uint32_t CalibSign, uint32_t Value); -HAL_StatusTypeDef HAL_RTCEx_DeactivateCoarseCalib(RTC_HandleTypeDef *hrtc); -HAL_StatusTypeDef HAL_RTCEx_SetSmoothCalib(RTC_HandleTypeDef *hrtc, uint32_t SmoothCalibPeriod, uint32_t SmoothCalibPlusPulses, uint32_t SmouthCalibMinusPulsesValue); -HAL_StatusTypeDef HAL_RTCEx_SetSynchroShift(RTC_HandleTypeDef *hrtc, uint32_t ShiftAdd1S, uint32_t ShiftSubFS); -HAL_StatusTypeDef HAL_RTCEx_SetCalibrationOutPut(RTC_HandleTypeDef *hrtc, uint32_t CalibOutput); -HAL_StatusTypeDef HAL_RTCEx_DeactivateCalibrationOutPut(RTC_HandleTypeDef *hrtc); -HAL_StatusTypeDef HAL_RTCEx_SetRefClock(RTC_HandleTypeDef *hrtc); -HAL_StatusTypeDef HAL_RTCEx_DeactivateRefClock(RTC_HandleTypeDef *hrtc); -HAL_StatusTypeDef HAL_RTCEx_EnableBypassShadow(RTC_HandleTypeDef *hrtc); -HAL_StatusTypeDef HAL_RTCEx_DisableBypassShadow(RTC_HandleTypeDef *hrtc); -/** - * @} - */ - -/** @addtogroup RTCEx_Exported_Functions_Group4 - * @{ - */ -/* Extension RTC features functions *******************************************/ -void HAL_RTCEx_AlarmBEventCallback(RTC_HandleTypeDef *hrtc); -HAL_StatusTypeDef HAL_RTCEx_PollForAlarmBEvent(RTC_HandleTypeDef *hrtc, uint32_t Timeout); -/** - * @} - */ - -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup RTCEx_Private_Constants RTCEx Private Constants - * @{ - */ -#define RTC_EXTI_LINE_TAMPER_TIMESTAMP_EVENT ((uint32_t)EXTI_IMR_MR21) /*!< External interrupt line 21 Connected to the RTC Tamper and Time Stamp events */ -#define RTC_EXTI_LINE_WAKEUPTIMER_EVENT ((uint32_t)EXTI_IMR_MR22) /*!< External interrupt line 22 Connected to the RTC Wake-up event */ -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup RTCEx_Private_Macros RTCEx Private Macros - * @{ - */ - -/** @defgroup RTCEx_IS_RTC_Definitions Private macros to check input parameters - * @{ - */ -#define IS_RTC_BKP(BKP) (((BKP) == RTC_BKP_DR0) || \ - ((BKP) == RTC_BKP_DR1) || \ - ((BKP) == RTC_BKP_DR2) || \ - ((BKP) == RTC_BKP_DR3) || \ - ((BKP) == RTC_BKP_DR4) || \ - ((BKP) == RTC_BKP_DR5) || \ - ((BKP) == RTC_BKP_DR6) || \ - ((BKP) == RTC_BKP_DR7) || \ - ((BKP) == RTC_BKP_DR8) || \ - ((BKP) == RTC_BKP_DR9) || \ - ((BKP) == RTC_BKP_DR10) || \ - ((BKP) == RTC_BKP_DR11) || \ - ((BKP) == RTC_BKP_DR12) || \ - ((BKP) == RTC_BKP_DR13) || \ - ((BKP) == RTC_BKP_DR14) || \ - ((BKP) == RTC_BKP_DR15) || \ - ((BKP) == RTC_BKP_DR16) || \ - ((BKP) == RTC_BKP_DR17) || \ - ((BKP) == RTC_BKP_DR18) || \ - ((BKP) == RTC_BKP_DR19)) -#define IS_TIMESTAMP_EDGE(EDGE) (((EDGE) == RTC_TIMESTAMPEDGE_RISING) || \ - ((EDGE) == RTC_TIMESTAMPEDGE_FALLING)) - -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -#define IS_RTC_TAMPER(TAMPER) ((((TAMPER) & ((uint32_t)!(RTC_TAFCR_TAMP1E ))) == 0x00U) && ((TAMPER) != (uint32_t)RESET)) -#else -#define IS_RTC_TAMPER(TAMPER) ((((TAMPER) & ((uint32_t)!(RTC_TAFCR_TAMP1E | RTC_TAFCR_TAMP2E))) == 0x00U) && ((TAMPER) != (uint32_t)RESET)) -#endif - -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -#define IS_RTC_TAMPER_PIN(PIN) ((PIN) == RTC_TAMPERPIN_DEFAULT) -#else -#define IS_RTC_TAMPER_PIN(PIN) (((PIN) == RTC_TAMPERPIN_DEFAULT) || \ - ((PIN) == RTC_TAMPERPIN_POS1)) -#endif - -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -#define IS_RTC_TIMESTAMP_PIN(PIN) ((PIN) == RTC_TIMESTAMPPIN_DEFAULT) -#else -#define IS_RTC_TIMESTAMP_PIN(PIN) (((PIN) == RTC_TIMESTAMPPIN_DEFAULT) || \ - ((PIN) == RTC_TIMESTAMPPIN_POS1)) -#endif -#define IS_RTC_TAMPER_TRIGGER(TRIGGER) (((TRIGGER) == RTC_TAMPERTRIGGER_RISINGEDGE) || \ - ((TRIGGER) == RTC_TAMPERTRIGGER_FALLINGEDGE) || \ - ((TRIGGER) == RTC_TAMPERTRIGGER_LOWLEVEL) || \ - ((TRIGGER) == RTC_TAMPERTRIGGER_HIGHLEVEL)) -#define IS_RTC_TAMPER_FILTER(FILTER) (((FILTER) == RTC_TAMPERFILTER_DISABLE) || \ - ((FILTER) == RTC_TAMPERFILTER_2SAMPLE) || \ - ((FILTER) == RTC_TAMPERFILTER_4SAMPLE) || \ - ((FILTER) == RTC_TAMPERFILTER_8SAMPLE)) -#define IS_RTC_TAMPER_SAMPLING_FREQ(FREQ) (((FREQ) == RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV32768)|| \ - ((FREQ) == RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV16384)|| \ - ((FREQ) == RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV8192) || \ - ((FREQ) == RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV4096) || \ - ((FREQ) == RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV2048) || \ - ((FREQ) == RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV1024) || \ - ((FREQ) == RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV512) || \ - ((FREQ) == RTC_TAMPERSAMPLINGFREQ_RTCCLK_DIV256)) -#define IS_RTC_TAMPER_PRECHARGE_DURATION(DURATION) (((DURATION) == RTC_TAMPERPRECHARGEDURATION_1RTCCLK) || \ - ((DURATION) == RTC_TAMPERPRECHARGEDURATION_2RTCCLK) || \ - ((DURATION) == RTC_TAMPERPRECHARGEDURATION_4RTCCLK) || \ - ((DURATION) == RTC_TAMPERPRECHARGEDURATION_8RTCCLK)) -#define IS_RTC_TAMPER_TIMESTAMPONTAMPER_DETECTION(DETECTION) (((DETECTION) == RTC_TIMESTAMPONTAMPERDETECTION_ENABLE) || \ - ((DETECTION) == RTC_TIMESTAMPONTAMPERDETECTION_DISABLE)) -#define IS_RTC_TAMPER_PULLUP_STATE(STATE) (((STATE) == RTC_TAMPER_PULLUP_ENABLE) || \ - ((STATE) == RTC_TAMPER_PULLUP_DISABLE)) -#define IS_RTC_WAKEUP_CLOCK(CLOCK) (((CLOCK) == RTC_WAKEUPCLOCK_RTCCLK_DIV16) || \ - ((CLOCK) == RTC_WAKEUPCLOCK_RTCCLK_DIV8) || \ - ((CLOCK) == RTC_WAKEUPCLOCK_RTCCLK_DIV4) || \ - ((CLOCK) == RTC_WAKEUPCLOCK_RTCCLK_DIV2) || \ - ((CLOCK) == RTC_WAKEUPCLOCK_CK_SPRE_16BITS) || \ - ((CLOCK) == RTC_WAKEUPCLOCK_CK_SPRE_17BITS)) - -#define IS_RTC_WAKEUP_COUNTER(COUNTER) ((COUNTER) <= 0xFFFFU) -#define IS_RTC_CALIB_SIGN(SIGN) (((SIGN) == RTC_CALIBSIGN_POSITIVE) || \ - ((SIGN) == RTC_CALIBSIGN_NEGATIVE)) - -#define IS_RTC_CALIB_VALUE(VALUE) ((VALUE) < 0x20U) - -#define IS_RTC_SMOOTH_CALIB_PERIOD(PERIOD) (((PERIOD) == RTC_SMOOTHCALIB_PERIOD_32SEC) || \ - ((PERIOD) == RTC_SMOOTHCALIB_PERIOD_16SEC) || \ - ((PERIOD) == RTC_SMOOTHCALIB_PERIOD_8SEC)) -#define IS_RTC_SMOOTH_CALIB_PLUS(PLUS) (((PLUS) == RTC_SMOOTHCALIB_PLUSPULSES_SET) || \ - ((PLUS) == RTC_SMOOTHCALIB_PLUSPULSES_RESET)) - -#define IS_RTC_SMOOTH_CALIB_MINUS(VALUE) ((VALUE) <= 0x000001FFU) -#define IS_RTC_SHIFT_ADD1S(SEL) (((SEL) == RTC_SHIFTADD1S_RESET) || \ - ((SEL) == RTC_SHIFTADD1S_SET)) -#define IS_RTC_SHIFT_SUBFS(FS) ((FS) <= 0x00007FFFU) -#define IS_RTC_CALIB_OUTPUT(OUTPUT) (((OUTPUT) == RTC_CALIBOUTPUT_512HZ) || \ - ((OUTPUT) == RTC_CALIBOUTPUT_1HZ)) -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_RTC_EX_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_sai.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_sai.h deleted file mode 100644 index 0307f92..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_sai.h +++ /dev/null @@ -1,897 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_sai.h - * @author MCD Application Team - * @brief Header file of SAI HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_SAI_H -#define __STM32F4xx_HAL_SAI_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || \ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F413xx) || \ - defined(STM32F423xx) - -/** @addtogroup SAI - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup SAI_Exported_Types SAI Exported Types - * @{ - */ - -/** - * @brief HAL State structures definition - */ -typedef enum -{ - HAL_SAI_STATE_RESET = 0x00U, /*!< SAI not yet initialized or disabled */ - HAL_SAI_STATE_READY = 0x01U, /*!< SAI initialized and ready for use */ - HAL_SAI_STATE_BUSY = 0x02U, /*!< SAI internal process is ongoing */ - HAL_SAI_STATE_BUSY_TX = 0x12U, /*!< Data transmission process is ongoing */ - HAL_SAI_STATE_BUSY_RX = 0x22U, /*!< Data reception process is ongoing */ - HAL_SAI_STATE_TIMEOUT = 0x03U, /*!< SAI timeout state */ - HAL_SAI_STATE_ERROR = 0x04U /*!< SAI error state */ -} HAL_SAI_StateTypeDef; - -/** - * @brief SAI Callback prototype - */ -typedef void (*SAIcallback)(void); - -/** @defgroup SAI_Init_Structure_definition SAI Init Structure definition - * @brief SAI Init Structure definition - * @{ - */ -typedef struct -{ - uint32_t AudioMode; /*!< Specifies the SAI Block audio Mode. - This parameter can be a value of @ref SAI_Block_Mode */ - - uint32_t Synchro; /*!< Specifies SAI Block synchronization - This parameter can be a value of @ref SAI_Block_Synchronization */ - - uint32_t SynchroExt; /*!< Specifies SAI external output synchronization, this setup is common - for BlockA and BlockB - This parameter can be a value of @ref SAI_Block_SyncExt - @note: If both audio blocks of same SAI are used, this parameter has - to be set to the same value for each audio block */ - - uint32_t OutputDrive; /*!< Specifies when SAI Block outputs are driven. - This parameter can be a value of @ref SAI_Block_Output_Drive - @note this value has to be set before enabling the audio block - but after the audio block configuration. */ - - uint32_t NoDivider; /*!< Specifies whether master clock will be divided or not. - This parameter can be a value of @ref SAI_Block_NoDivider - @note If bit NODIV in the SAI_xCR1 register is cleared, the frame length - should be aligned to a number equal to a power of 2, from 8 to 256. - If bit NODIV in the SAI_xCR1 register is set, the frame length can - take any of the values without constraint since the input clock of - the audio block should be equal to the bit clock. - There is no MCLK_x clock which can be output. */ - - uint32_t FIFOThreshold; /*!< Specifies SAI Block FIFO threshold. - This parameter can be a value of @ref SAI_Block_Fifo_Threshold */ - - uint32_t ClockSource; /*!< Specifies the SAI Block x Clock source. - This parameter is not used for STM32F446xx devices. */ - - uint32_t AudioFrequency; /*!< Specifies the audio frequency sampling. - This parameter can be a value of @ref SAI_Audio_Frequency */ - - uint32_t Mckdiv; /*!< Specifies the master clock divider. - This parameter must be a number between Min_Data = 0 and Max_Data = 15. - @note This parameter is used only if AudioFrequency is set to - SAI_AUDIO_FREQUENCY_MCKDIV otherwise it is internally computed. */ - - uint32_t MonoStereoMode; /*!< Specifies if the mono or stereo mode is selected. - This parameter can be a value of @ref SAI_Mono_Stereo_Mode */ - - uint32_t CompandingMode; /*!< Specifies the companding mode type. - This parameter can be a value of @ref SAI_Block_Companding_Mode */ - - uint32_t TriState; /*!< Specifies the companding mode type. - This parameter can be a value of @ref SAI_TRIState_Management */ - - /* This part of the structure is automatically filled if your are using the high level intialisation - function HAL_SAI_InitProtocol */ - - uint32_t Protocol; /*!< Specifies the SAI Block protocol. - This parameter can be a value of @ref SAI_Block_Protocol */ - - uint32_t DataSize; /*!< Specifies the SAI Block data size. - This parameter can be a value of @ref SAI_Block_Data_Size */ - - uint32_t FirstBit; /*!< Specifies whether data transfers start from MSB or LSB bit. - This parameter can be a value of @ref SAI_Block_MSB_LSB_transmission */ - - uint32_t ClockStrobing; /*!< Specifies the SAI Block clock strobing edge sensitivity. - This parameter can be a value of @ref SAI_Block_Clock_Strobing */ -} SAI_InitTypeDef; -/** - * @} - */ - -/** @defgroup SAI_Frame_Structure_definition SAI Frame Structure definition - * @brief SAI Frame Init structure definition - * @note For SPDIF and AC97 protocol, these parameters are not used (set by hardware). - * @{ - */ -typedef struct -{ - uint32_t FrameLength; /*!< Specifies the Frame length, the number of SCK clocks for each audio frame. - This parameter must be a number between Min_Data = 8 and Max_Data = 256. - @note If master clock MCLK_x pin is declared as an output, the frame length - should be aligned to a number equal to power of 2 in order to keep - in an audio frame, an integer number of MCLK pulses by bit Clock. */ - - uint32_t ActiveFrameLength; /*!< Specifies the Frame synchronization active level length. - This Parameter specifies the length in number of bit clock (SCK + 1) - of the active level of FS signal in audio frame. - This parameter must be a number between Min_Data = 1 and Max_Data = 128 */ - - uint32_t FSDefinition; /*!< Specifies the Frame synchronization definition. - This parameter can be a value of @ref SAI_Block_FS_Definition */ - - uint32_t FSPolarity; /*!< Specifies the Frame synchronization Polarity. - This parameter can be a value of @ref SAI_Block_FS_Polarity */ - - uint32_t FSOffset; /*!< Specifies the Frame synchronization Offset. - This parameter can be a value of @ref SAI_Block_FS_Offset */ -} SAI_FrameInitTypeDef; -/** - * @} - */ - -/** @defgroup SAI_Slot_Structure_definition SAI Slot Structure definition - * @brief SAI Block Slot Init Structure definition - * @note For SPDIF protocol, these parameters are not used (set by hardware). - * @note For AC97 protocol, only SlotActive parameter is used (the others are set by hardware). - * @{ - */ -typedef struct -{ - uint32_t FirstBitOffset; /*!< Specifies the position of first data transfer bit in the slot. - This parameter must be a number between Min_Data = 0 and Max_Data = 24 */ - - uint32_t SlotSize; /*!< Specifies the Slot Size. - This parameter can be a value of @ref SAI_Block_Slot_Size */ - - uint32_t SlotNumber; /*!< Specifies the number of slot in the audio frame. - This parameter must be a number between Min_Data = 1 and Max_Data = 16 */ - - uint32_t SlotActive; /*!< Specifies the slots in audio frame that will be activated. - This parameter can be a value of @ref SAI_Block_Slot_Active */ -} SAI_SlotInitTypeDef; -/** - * @} - */ - -/** @defgroup SAI_Handle_Structure_definition SAI Handle Structure definition - * @brief SAI handle Structure definition - * @{ - */ -typedef struct __SAI_HandleTypeDef -{ - SAI_Block_TypeDef *Instance; /*!< SAI Blockx registers base address */ - - SAI_InitTypeDef Init; /*!< SAI communication parameters */ - - SAI_FrameInitTypeDef FrameInit; /*!< SAI Frame configuration parameters */ - - SAI_SlotInitTypeDef SlotInit; /*!< SAI Slot configuration parameters */ - - uint8_t *pBuffPtr; /*!< Pointer to SAI transfer Buffer */ - - uint16_t XferSize; /*!< SAI transfer size */ - - uint16_t XferCount; /*!< SAI transfer counter */ - - DMA_HandleTypeDef *hdmatx; /*!< SAI Tx DMA handle parameters */ - - DMA_HandleTypeDef *hdmarx; /*!< SAI Rx DMA handle parameters */ - - SAIcallback mutecallback;/*!< SAI mute callback */ - - void (*InterruptServiceRoutine)(struct __SAI_HandleTypeDef *hsai); /* function pointer for IRQ handler */ - - HAL_LockTypeDef Lock; /*!< SAI locking object */ - - __IO HAL_SAI_StateTypeDef State; /*!< SAI communication state */ - - __IO uint32_t ErrorCode; /*!< SAI Error code */ - -#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) - void (*RxCpltCallback)(struct __SAI_HandleTypeDef *hsai); /*!< SAI receive complete callback */ - void (*RxHalfCpltCallback)(struct __SAI_HandleTypeDef *hsai); /*!< SAI receive half complete callback */ - void (*TxCpltCallback)(struct __SAI_HandleTypeDef *hsai); /*!< SAI transmit complete callback */ - void (*TxHalfCpltCallback)(struct __SAI_HandleTypeDef *hsai); /*!< SAI transmit half complete callback */ - void (*ErrorCallback)(struct __SAI_HandleTypeDef *hsai); /*!< SAI error callback */ - void (*MspInitCallback)(struct __SAI_HandleTypeDef *hsai); /*!< SAI MSP init callback */ - void (*MspDeInitCallback)(struct __SAI_HandleTypeDef *hsai); /*!< SAI MSP de-init callback */ -#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ -} SAI_HandleTypeDef; -/** - * @} - */ - -#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) -/** - * @brief SAI callback ID enumeration definition - */ -typedef enum -{ - HAL_SAI_RX_COMPLETE_CB_ID = 0x00U, /*!< SAI receive complete callback ID */ - HAL_SAI_RX_HALFCOMPLETE_CB_ID = 0x01U, /*!< SAI receive half complete callback ID */ - HAL_SAI_TX_COMPLETE_CB_ID = 0x02U, /*!< SAI transmit complete callback ID */ - HAL_SAI_TX_HALFCOMPLETE_CB_ID = 0x03U, /*!< SAI transmit half complete callback ID */ - HAL_SAI_ERROR_CB_ID = 0x04U, /*!< SAI error callback ID */ - HAL_SAI_MSPINIT_CB_ID = 0x05U, /*!< SAI MSP init callback ID */ - HAL_SAI_MSPDEINIT_CB_ID = 0x06U /*!< SAI MSP de-init callback ID */ -} HAL_SAI_CallbackIDTypeDef; - -/** - * @brief SAI callback pointer definition - */ -typedef void (*pSAI_CallbackTypeDef)(SAI_HandleTypeDef *hsai); -#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup SAI_Exported_Constants SAI Exported Constants - * @{ - */ - -/** @defgroup SAI_Error_Code SAI Error Code - * @{ - */ -#define HAL_SAI_ERROR_NONE 0x00000000U /*!< No error */ -#define HAL_SAI_ERROR_OVR 0x00000001U /*!< Overrun Error */ -#define HAL_SAI_ERROR_UDR 0x00000002U /*!< Underrun error */ -#define HAL_SAI_ERROR_AFSDET 0x00000004U /*!< Anticipated Frame synchronisation detection */ -#define HAL_SAI_ERROR_LFSDET 0x00000008U /*!< Late Frame synchronisation detection */ -#define HAL_SAI_ERROR_CNREADY 0x00000010U /*!< codec not ready */ -#define HAL_SAI_ERROR_WCKCFG 0x00000020U /*!< Wrong clock configuration */ -#define HAL_SAI_ERROR_TIMEOUT 0x00000040U /*!< Timeout error */ -#define HAL_SAI_ERROR_DMA 0x00000080U /*!< DMA error */ -#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) -#define HAL_SAI_ERROR_INVALID_CALLBACK 0x00000100U /*!< Invalid callback error */ -#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @defgroup SAI_Block_SyncExt SAI External synchronisation - * @{ - */ -#define SAI_SYNCEXT_DISABLE 0U -#define SAI_SYNCEXT_OUTBLOCKA_ENABLE 1U -#define SAI_SYNCEXT_OUTBLOCKB_ENABLE 2U -/** - * @} - */ - -/** @defgroup SAI_Protocol SAI Supported protocol - * @{ - */ -#define SAI_I2S_STANDARD 0U -#define SAI_I2S_MSBJUSTIFIED 1U -#define SAI_I2S_LSBJUSTIFIED 2U -#define SAI_PCM_LONG 3U -#define SAI_PCM_SHORT 4U -/** - * @} - */ - -/** @defgroup SAI_Protocol_DataSize SAI protocol data size - * @{ - */ -#define SAI_PROTOCOL_DATASIZE_16BIT 0U -#define SAI_PROTOCOL_DATASIZE_16BITEXTENDED 1U -#define SAI_PROTOCOL_DATASIZE_24BIT 2U -#define SAI_PROTOCOL_DATASIZE_32BIT 3U -/** - * @} - */ - -/** @defgroup SAI_Audio_Frequency SAI Audio Frequency - * @{ - */ -#define SAI_AUDIO_FREQUENCY_192K 192000U -#define SAI_AUDIO_FREQUENCY_96K 96000U -#define SAI_AUDIO_FREQUENCY_48K 48000U -#define SAI_AUDIO_FREQUENCY_44K 44100U -#define SAI_AUDIO_FREQUENCY_32K 32000U -#define SAI_AUDIO_FREQUENCY_22K 22050U -#define SAI_AUDIO_FREQUENCY_16K 16000U -#define SAI_AUDIO_FREQUENCY_11K 11025U -#define SAI_AUDIO_FREQUENCY_8K 8000U -#define SAI_AUDIO_FREQUENCY_MCKDIV 0U -/** - * @} - */ - -/** @defgroup SAI_Block_Mode SAI Block Mode - * @{ - */ -#define SAI_MODEMASTER_TX 0x00000000U -#define SAI_MODEMASTER_RX ((uint32_t)SAI_xCR1_MODE_0) -#define SAI_MODESLAVE_TX ((uint32_t)SAI_xCR1_MODE_1) -#define SAI_MODESLAVE_RX ((uint32_t)(SAI_xCR1_MODE_1 | SAI_xCR1_MODE_0)) -/** - * @} - */ - -/** @defgroup SAI_Block_Protocol SAI Block Protocol - * @{ - */ -#define SAI_FREE_PROTOCOL 0x00000000U -#define SAI_SPDIF_PROTOCOL ((uint32_t)SAI_xCR1_PRTCFG_0) -#define SAI_AC97_PROTOCOL ((uint32_t)SAI_xCR1_PRTCFG_1) -/** - * @} - */ - -/** @defgroup SAI_Block_Data_Size SAI Block Data Size - * @{ - */ -#define SAI_DATASIZE_8 ((uint32_t)SAI_xCR1_DS_1) -#define SAI_DATASIZE_10 ((uint32_t)(SAI_xCR1_DS_1 | SAI_xCR1_DS_0)) -#define SAI_DATASIZE_16 ((uint32_t)SAI_xCR1_DS_2) -#define SAI_DATASIZE_20 ((uint32_t)(SAI_xCR1_DS_2 | SAI_xCR1_DS_0)) -#define SAI_DATASIZE_24 ((uint32_t)(SAI_xCR1_DS_2 | SAI_xCR1_DS_1)) -#define SAI_DATASIZE_32 ((uint32_t)(SAI_xCR1_DS_2 | SAI_xCR1_DS_1 | SAI_xCR1_DS_0)) -/** - * @} - */ - -/** @defgroup SAI_Block_MSB_LSB_transmission SAI Block MSB LSB transmission - * @{ - */ -#define SAI_FIRSTBIT_MSB 0x00000000U -#define SAI_FIRSTBIT_LSB ((uint32_t)SAI_xCR1_LSBFIRST) -/** - * @} - */ - -/** @defgroup SAI_Block_Clock_Strobing SAI Block Clock Strobing - * @{ - */ -#define SAI_CLOCKSTROBING_FALLINGEDGE 0U -#define SAI_CLOCKSTROBING_RISINGEDGE 1U -/** - * @} - */ - -/** @defgroup SAI_Block_Synchronization SAI Block Synchronization - * @{ - */ -#define SAI_ASYNCHRONOUS 0U /*!< Asynchronous */ -#define SAI_SYNCHRONOUS 1U /*!< Synchronous with other block of same SAI */ -#define SAI_SYNCHRONOUS_EXT_SAI1 2U /*!< Synchronous with other SAI, SAI1 */ -#define SAI_SYNCHRONOUS_EXT_SAI2 3U /*!< Synchronous with other SAI, SAI2 */ -/** - * @} - */ - -/** @defgroup SAI_Block_Output_Drive SAI Block Output Drive - * @{ - */ -#define SAI_OUTPUTDRIVE_DISABLE 0x00000000U -#define SAI_OUTPUTDRIVE_ENABLE ((uint32_t)SAI_xCR1_OUTDRIV) -/** - * @} - */ - -/** @defgroup SAI_Block_NoDivider SAI Block NoDivider - * @{ - */ -#define SAI_MASTERDIVIDER_ENABLE 0x00000000U -#define SAI_MASTERDIVIDER_DISABLE ((uint32_t)SAI_xCR1_NODIV) -/** - * @} - */ - -/** @defgroup SAI_Block_FS_Definition SAI Block FS Definition - * @{ - */ -#define SAI_FS_STARTFRAME 0x00000000U -#define SAI_FS_CHANNEL_IDENTIFICATION ((uint32_t)SAI_xFRCR_FSDEF) -/** - * @} - */ - -/** @defgroup SAI_Block_FS_Polarity SAI Block FS Polarity - * @{ - */ -#define SAI_FS_ACTIVE_LOW 0x00000000U -#define SAI_FS_ACTIVE_HIGH ((uint32_t)SAI_xFRCR_FSPOL) -/** - * @} - */ - -/** @defgroup SAI_Block_FS_Offset SAI Block FS Offset - * @{ - */ -#define SAI_FS_FIRSTBIT 0x00000000U -#define SAI_FS_BEFOREFIRSTBIT ((uint32_t)SAI_xFRCR_FSOFF) -/** - * @} - */ - -/** @defgroup SAI_Block_Slot_Size SAI Block Slot Size - * @{ - */ -#define SAI_SLOTSIZE_DATASIZE 0x00000000U -#define SAI_SLOTSIZE_16B ((uint32_t)SAI_xSLOTR_SLOTSZ_0) -#define SAI_SLOTSIZE_32B ((uint32_t)SAI_xSLOTR_SLOTSZ_1) -/** - * @} - */ - -/** @defgroup SAI_Block_Slot_Active SAI Block Slot Active - * @{ - */ -#define SAI_SLOT_NOTACTIVE 0x00000000U -#define SAI_SLOTACTIVE_0 0x00000001U -#define SAI_SLOTACTIVE_1 0x00000002U -#define SAI_SLOTACTIVE_2 0x00000004U -#define SAI_SLOTACTIVE_3 0x00000008U -#define SAI_SLOTACTIVE_4 0x00000010U -#define SAI_SLOTACTIVE_5 0x00000020U -#define SAI_SLOTACTIVE_6 0x00000040U -#define SAI_SLOTACTIVE_7 0x00000080U -#define SAI_SLOTACTIVE_8 0x00000100U -#define SAI_SLOTACTIVE_9 0x00000200U -#define SAI_SLOTACTIVE_10 0x00000400U -#define SAI_SLOTACTIVE_11 0x00000800U -#define SAI_SLOTACTIVE_12 0x00001000U -#define SAI_SLOTACTIVE_13 0x00002000U -#define SAI_SLOTACTIVE_14 0x00004000U -#define SAI_SLOTACTIVE_15 0x00008000U -#define SAI_SLOTACTIVE_ALL 0x0000FFFFU -/** - * @} - */ - -/** @defgroup SAI_Mono_Stereo_Mode SAI Mono Stereo Mode - * @{ - */ -#define SAI_STEREOMODE 0x00000000U -#define SAI_MONOMODE ((uint32_t)SAI_xCR1_MONO) -/** - * @} - */ - -/** @defgroup SAI_TRIState_Management SAI TRIState Management - * @{ - */ -#define SAI_OUTPUT_NOTRELEASED 0x00000000U -#define SAI_OUTPUT_RELEASED ((uint32_t)SAI_xCR2_TRIS) -/** - * @} - */ - -/** @defgroup SAI_Block_Fifo_Threshold SAI Block Fifo Threshold - * @{ - */ -#define SAI_FIFOTHRESHOLD_EMPTY 0x00000000U -#define SAI_FIFOTHRESHOLD_1QF ((uint32_t)(SAI_xCR2_FTH_0)) -#define SAI_FIFOTHRESHOLD_HF ((uint32_t)(SAI_xCR2_FTH_1)) -#define SAI_FIFOTHRESHOLD_3QF ((uint32_t)(SAI_xCR2_FTH_1 | SAI_xCR2_FTH_0)) -#define SAI_FIFOTHRESHOLD_FULL ((uint32_t)(SAI_xCR2_FTH_2)) -/** - * @} - */ - -/** @defgroup SAI_Block_Companding_Mode SAI Block Companding Mode - * @{ - */ -#define SAI_NOCOMPANDING 0x00000000U -#define SAI_ULAW_1CPL_COMPANDING ((uint32_t)(SAI_xCR2_COMP_1)) -#define SAI_ALAW_1CPL_COMPANDING ((uint32_t)(SAI_xCR2_COMP_1 | SAI_xCR2_COMP_0)) -#define SAI_ULAW_2CPL_COMPANDING ((uint32_t)(SAI_xCR2_COMP_1 | SAI_xCR2_CPL)) -#define SAI_ALAW_2CPL_COMPANDING ((uint32_t)(SAI_xCR2_COMP_1 | SAI_xCR2_COMP_0 | SAI_xCR2_CPL)) -/** - * @} - */ - -/** @defgroup SAI_Block_Mute_Value SAI Block Mute Value - * @{ - */ -#define SAI_ZERO_VALUE 0x00000000U -#define SAI_LAST_SENT_VALUE ((uint32_t)SAI_xCR2_MUTEVAL) -/** - * @} - */ - -/** @defgroup SAI_Block_Interrupts_Definition SAI Block Interrupts Definition - * @{ - */ -#define SAI_IT_OVRUDR ((uint32_t)SAI_xIMR_OVRUDRIE) -#define SAI_IT_MUTEDET ((uint32_t)SAI_xIMR_MUTEDETIE) -#define SAI_IT_WCKCFG ((uint32_t)SAI_xIMR_WCKCFGIE) -#define SAI_IT_FREQ ((uint32_t)SAI_xIMR_FREQIE) -#define SAI_IT_CNRDY ((uint32_t)SAI_xIMR_CNRDYIE) -#define SAI_IT_AFSDET ((uint32_t)SAI_xIMR_AFSDETIE) -#define SAI_IT_LFSDET ((uint32_t)SAI_xIMR_LFSDETIE) -/** - * @} - */ - -/** @defgroup SAI_Block_Flags_Definition SAI Block Flags Definition - * @{ - */ -#define SAI_FLAG_OVRUDR ((uint32_t)SAI_xSR_OVRUDR) -#define SAI_FLAG_MUTEDET ((uint32_t)SAI_xSR_MUTEDET) -#define SAI_FLAG_WCKCFG ((uint32_t)SAI_xSR_WCKCFG) -#define SAI_FLAG_FREQ ((uint32_t)SAI_xSR_FREQ) -#define SAI_FLAG_CNRDY ((uint32_t)SAI_xSR_CNRDY) -#define SAI_FLAG_AFSDET ((uint32_t)SAI_xSR_AFSDET) -#define SAI_FLAG_LFSDET ((uint32_t)SAI_xSR_LFSDET) -/** - * @} - */ - -/** @defgroup SAI_Block_Fifo_Status_Level SAI Block Fifo Status Level - * @{ - */ -#define SAI_FIFOSTATUS_EMPTY 0x00000000U -#define SAI_FIFOSTATUS_LESS1QUARTERFULL 0x00010000U -#define SAI_FIFOSTATUS_1QUARTERFULL 0x00020000U -#define SAI_FIFOSTATUS_HALFFULL 0x00030000U -#define SAI_FIFOSTATUS_3QUARTERFULL 0x00040000U -#define SAI_FIFOSTATUS_FULL 0x00050000U -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup SAI_Exported_Macros SAI Exported Macros - * @brief macros to handle interrupts and specific configurations - * @{ - */ - -/** @brief Reset SAI handle state - * @param __HANDLE__ specifies the SAI Handle. - * @retval None - */ -#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) -#define __HAL_SAI_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->State = HAL_SAI_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0U) -#else -#define __HAL_SAI_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_SAI_STATE_RESET) -#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ - -/** @brief Enable or disable the specified SAI interrupts. - * @param __HANDLE__ specifies the SAI Handle. - * @param __INTERRUPT__ specifies the interrupt source to enable or disable. - * This parameter can be one of the following values: - * @arg SAI_IT_OVRUDR: Overrun underrun interrupt enable - * @arg SAI_IT_MUTEDET: Mute detection interrupt enable - * @arg SAI_IT_WCKCFG: Wrong Clock Configuration interrupt enable - * @arg SAI_IT_FREQ: FIFO request interrupt enable - * @arg SAI_IT_CNRDY: Codec not ready interrupt enable - * @arg SAI_IT_AFSDET: Anticipated frame synchronization detection interrupt enable - * @arg SAI_IT_LFSDET: Late frame synchronization detection interrupt enable - * @retval None - */ -#define __HAL_SAI_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->IMR |= (__INTERRUPT__)) -#define __HAL_SAI_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->IMR &= (~(__INTERRUPT__))) - -/** @brief Check if the specified SAI interrupt source is enabled or disabled. - * @param __HANDLE__ specifies the SAI Handle. - * This parameter can be SAI where x: 1, 2, or 3 to select the SAI peripheral. - * @param __INTERRUPT__ specifies the SAI interrupt source to check. - * This parameter can be one of the following values: - * @arg SAI_IT_OVRUDR: Overrun underrun interrupt enable - * @arg SAI_IT_MUTEDET: Mute detection interrupt enable - * @arg SAI_IT_WCKCFG: Wrong Clock Configuration interrupt enable - * @arg SAI_IT_FREQ: FIFO request interrupt enable - * @arg SAI_IT_CNRDY: Codec not ready interrupt enable - * @arg SAI_IT_AFSDET: Anticipated frame synchronization detection interrupt enable - * @arg SAI_IT_LFSDET: Late frame synchronization detection interrupt enable - * @retval The new state of __INTERRUPT__ (TRUE or FALSE). - */ -#define __HAL_SAI_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((((__HANDLE__)->Instance->IMR & (__INTERRUPT__)) == (__INTERRUPT__)) ? SET : RESET) - -/** @brief Check whether the specified SAI flag is set or not. - * @param __HANDLE__ specifies the SAI Handle. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg SAI_FLAG_OVRUDR: Overrun underrun flag. - * @arg SAI_FLAG_MUTEDET: Mute detection flag. - * @arg SAI_FLAG_WCKCFG: Wrong Clock Configuration flag. - * @arg SAI_FLAG_FREQ: FIFO request flag. - * @arg SAI_FLAG_CNRDY: Codec not ready flag. - * @arg SAI_FLAG_AFSDET: Anticipated frame synchronization detection flag. - * @arg SAI_FLAG_LFSDET: Late frame synchronization detection flag. - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_SAI_GET_FLAG(__HANDLE__, __FLAG__) ((((__HANDLE__)->Instance->SR) & (__FLAG__)) == (__FLAG__)) - -/** @brief Clear the specified SAI pending flag. - * @param __HANDLE__ specifies the SAI Handle. - * @param __FLAG__ specifies the flag to check. - * This parameter can be any combination of the following values: - * @arg SAI_FLAG_OVRUDR: Clear Overrun underrun - * @arg SAI_FLAG_MUTEDET: Clear Mute detection - * @arg SAI_FLAG_WCKCFG: Clear Wrong Clock Configuration - * @arg SAI_FLAG_FREQ: Clear FIFO request - * @arg SAI_FLAG_CNRDY: Clear Codec not ready - * @arg SAI_FLAG_AFSDET: Clear Anticipated frame synchronization detection - * @arg SAI_FLAG_LFSDET: Clear Late frame synchronization detection - * @retval None - */ -#define __HAL_SAI_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->CLRFR = (__FLAG__)) - -/** @brief Enable SAI - * @param __HANDLE__ specifies the SAI Handle. - * @retval None - */ -#define __HAL_SAI_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1 |= SAI_xCR1_SAIEN) - -/** @brief Disable SAI - * @param __HANDLE__ specifies the SAI Handle. - * @retval None - */ -#define __HAL_SAI_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1 &= ~SAI_xCR1_SAIEN) - -/** - * @} - */ - -/* Include HAL SAI Extension module */ -#include "stm32f4xx_hal_sai_ex.h" - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup SAI_Exported_Functions - * @{ - */ - -/* Initialization/de-initialization functions **********************************/ -/** @addtogroup SAI_Exported_Functions_Group1 - * @{ - */ -HAL_StatusTypeDef HAL_SAI_InitProtocol(SAI_HandleTypeDef *hsai, uint32_t protocol, uint32_t datasize, uint32_t nbslot); -HAL_StatusTypeDef HAL_SAI_Init(SAI_HandleTypeDef *hsai); -HAL_StatusTypeDef HAL_SAI_DeInit(SAI_HandleTypeDef *hsai); -void HAL_SAI_MspInit(SAI_HandleTypeDef *hsai); -void HAL_SAI_MspDeInit(SAI_HandleTypeDef *hsai); - -#if (USE_HAL_SAI_REGISTER_CALLBACKS == 1) -/* SAI callbacks register/unregister functions ********************************/ -HAL_StatusTypeDef HAL_SAI_RegisterCallback(SAI_HandleTypeDef *hsai, - HAL_SAI_CallbackIDTypeDef CallbackID, - pSAI_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_SAI_UnRegisterCallback(SAI_HandleTypeDef *hsai, - HAL_SAI_CallbackIDTypeDef CallbackID); -#endif /* USE_HAL_SAI_REGISTER_CALLBACKS */ -/** - * @} - */ - -/* I/O operation functions *****************************************************/ -/** @addtogroup SAI_Exported_Functions_Group2 - * @{ - */ -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_SAI_Transmit(SAI_HandleTypeDef *hsai, uint8_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_SAI_Receive(SAI_HandleTypeDef *hsai, uint8_t *pData, uint16_t Size, uint32_t Timeout); - -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_SAI_Transmit_IT(SAI_HandleTypeDef *hsai, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_SAI_Receive_IT(SAI_HandleTypeDef *hsai, uint8_t *pData, uint16_t Size); - -/* Non-Blocking mode: DMA */ -HAL_StatusTypeDef HAL_SAI_Transmit_DMA(SAI_HandleTypeDef *hsai, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_SAI_Receive_DMA(SAI_HandleTypeDef *hsai, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_SAI_DMAPause(SAI_HandleTypeDef *hsai); -HAL_StatusTypeDef HAL_SAI_DMAResume(SAI_HandleTypeDef *hsai); -HAL_StatusTypeDef HAL_SAI_DMAStop(SAI_HandleTypeDef *hsai); - -/* Abort function */ -HAL_StatusTypeDef HAL_SAI_Abort(SAI_HandleTypeDef *hsai); - -/* Mute management */ -HAL_StatusTypeDef HAL_SAI_EnableTxMuteMode(SAI_HandleTypeDef *hsai, uint16_t val); -HAL_StatusTypeDef HAL_SAI_DisableTxMuteMode(SAI_HandleTypeDef *hsai); -HAL_StatusTypeDef HAL_SAI_EnableRxMuteMode(SAI_HandleTypeDef *hsai, SAIcallback callback, uint16_t counter); -HAL_StatusTypeDef HAL_SAI_DisableRxMuteMode(SAI_HandleTypeDef *hsai); - -/* SAI IRQHandler and Callbacks used in non blocking modes (Interrupt and DMA) */ -void HAL_SAI_IRQHandler(SAI_HandleTypeDef *hsai); -void HAL_SAI_TxHalfCpltCallback(SAI_HandleTypeDef *hsai); -void HAL_SAI_TxCpltCallback(SAI_HandleTypeDef *hsai); -void HAL_SAI_RxHalfCpltCallback(SAI_HandleTypeDef *hsai); -void HAL_SAI_RxCpltCallback(SAI_HandleTypeDef *hsai); -void HAL_SAI_ErrorCallback(SAI_HandleTypeDef *hsai); -/** - * @} - */ - -/** @addtogroup SAI_Exported_Functions_Group3 - * @{ - */ -/* Peripheral State functions ************************************************/ -HAL_SAI_StateTypeDef HAL_SAI_GetState(SAI_HandleTypeDef *hsai); -uint32_t HAL_SAI_GetError(SAI_HandleTypeDef *hsai); -/** - * @} - */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @addtogroup SAI_Private_Macros - * @{ - */ -#define IS_SAI_BLOCK_SYNCEXT(STATE) (((STATE) == SAI_SYNCEXT_DISABLE) ||\ - ((STATE) == SAI_SYNCEXT_OUTBLOCKA_ENABLE) ||\ - ((STATE) == SAI_SYNCEXT_OUTBLOCKB_ENABLE)) - -#define IS_SAI_SUPPORTED_PROTOCOL(PROTOCOL) (((PROTOCOL) == SAI_I2S_STANDARD) ||\ - ((PROTOCOL) == SAI_I2S_MSBJUSTIFIED) ||\ - ((PROTOCOL) == SAI_I2S_LSBJUSTIFIED) ||\ - ((PROTOCOL) == SAI_PCM_LONG) ||\ - ((PROTOCOL) == SAI_PCM_SHORT)) - -#define IS_SAI_PROTOCOL_DATASIZE(DATASIZE) (((DATASIZE) == SAI_PROTOCOL_DATASIZE_16BIT) ||\ - ((DATASIZE) == SAI_PROTOCOL_DATASIZE_16BITEXTENDED) ||\ - ((DATASIZE) == SAI_PROTOCOL_DATASIZE_24BIT) ||\ - ((DATASIZE) == SAI_PROTOCOL_DATASIZE_32BIT)) - -#define IS_SAI_AUDIO_FREQUENCY(AUDIO) (((AUDIO) == SAI_AUDIO_FREQUENCY_192K) || ((AUDIO) == SAI_AUDIO_FREQUENCY_96K) || \ - ((AUDIO) == SAI_AUDIO_FREQUENCY_48K) || ((AUDIO) == SAI_AUDIO_FREQUENCY_44K) || \ - ((AUDIO) == SAI_AUDIO_FREQUENCY_32K) || ((AUDIO) == SAI_AUDIO_FREQUENCY_22K) || \ - ((AUDIO) == SAI_AUDIO_FREQUENCY_16K) || ((AUDIO) == SAI_AUDIO_FREQUENCY_11K) || \ - ((AUDIO) == SAI_AUDIO_FREQUENCY_8K) || ((AUDIO) == SAI_AUDIO_FREQUENCY_MCKDIV)) - -#define IS_SAI_BLOCK_MODE(MODE) (((MODE) == SAI_MODEMASTER_TX) || \ - ((MODE) == SAI_MODEMASTER_RX) || \ - ((MODE) == SAI_MODESLAVE_TX) || \ - ((MODE) == SAI_MODESLAVE_RX)) - -#define IS_SAI_BLOCK_PROTOCOL(PROTOCOL) (((PROTOCOL) == SAI_FREE_PROTOCOL) || \ - ((PROTOCOL) == SAI_AC97_PROTOCOL) || \ - ((PROTOCOL) == SAI_SPDIF_PROTOCOL)) - -#define IS_SAI_BLOCK_DATASIZE(DATASIZE) (((DATASIZE) == SAI_DATASIZE_8) || \ - ((DATASIZE) == SAI_DATASIZE_10) || \ - ((DATASIZE) == SAI_DATASIZE_16) || \ - ((DATASIZE) == SAI_DATASIZE_20) || \ - ((DATASIZE) == SAI_DATASIZE_24) || \ - ((DATASIZE) == SAI_DATASIZE_32)) - -#define IS_SAI_BLOCK_FIRST_BIT(BIT) (((BIT) == SAI_FIRSTBIT_MSB) || \ - ((BIT) == SAI_FIRSTBIT_LSB)) - -#define IS_SAI_BLOCK_CLOCK_STROBING(CLOCK) (((CLOCK) == SAI_CLOCKSTROBING_FALLINGEDGE) || \ - ((CLOCK) == SAI_CLOCKSTROBING_RISINGEDGE)) - -#define IS_SAI_BLOCK_SYNCHRO(SYNCHRO) (((SYNCHRO) == SAI_ASYNCHRONOUS) || \ - ((SYNCHRO) == SAI_SYNCHRONOUS) || \ - ((SYNCHRO) == SAI_SYNCHRONOUS_EXT_SAI1) ||\ - ((SYNCHRO) == SAI_SYNCHRONOUS_EXT_SAI2)) - -#define IS_SAI_BLOCK_OUTPUT_DRIVE(DRIVE) (((DRIVE) == SAI_OUTPUTDRIVE_DISABLE) || \ - ((DRIVE) == SAI_OUTPUTDRIVE_ENABLE)) - -#define IS_SAI_BLOCK_NODIVIDER(NODIVIDER) (((NODIVIDER) == SAI_MASTERDIVIDER_ENABLE) || \ - ((NODIVIDER) == SAI_MASTERDIVIDER_DISABLE)) - -#define IS_SAI_BLOCK_MUTE_COUNTER(COUNTER) ((COUNTER) <= 63U) - -#define IS_SAI_BLOCK_MUTE_VALUE(VALUE) (((VALUE) == SAI_ZERO_VALUE) || \ - ((VALUE) == SAI_LAST_SENT_VALUE)) - -#define IS_SAI_BLOCK_COMPANDING_MODE(MODE) (((MODE) == SAI_NOCOMPANDING) || \ - ((MODE) == SAI_ULAW_1CPL_COMPANDING) || \ - ((MODE) == SAI_ALAW_1CPL_COMPANDING) || \ - ((MODE) == SAI_ULAW_2CPL_COMPANDING) || \ - ((MODE) == SAI_ALAW_2CPL_COMPANDING)) - -#define IS_SAI_BLOCK_FIFO_THRESHOLD(THRESHOLD) (((THRESHOLD) == SAI_FIFOTHRESHOLD_EMPTY) || \ - ((THRESHOLD) == SAI_FIFOTHRESHOLD_1QF) || \ - ((THRESHOLD) == SAI_FIFOTHRESHOLD_HF) || \ - ((THRESHOLD) == SAI_FIFOTHRESHOLD_3QF) || \ - ((THRESHOLD) == SAI_FIFOTHRESHOLD_FULL)) - -#define IS_SAI_BLOCK_TRISTATE_MANAGEMENT(STATE) (((STATE) == SAI_OUTPUT_NOTRELEASED) ||\ - ((STATE) == SAI_OUTPUT_RELEASED)) - -#define IS_SAI_MONO_STEREO_MODE(MODE) (((MODE) == SAI_MONOMODE) ||\ - ((MODE) == SAI_STEREOMODE)) - -#define IS_SAI_SLOT_ACTIVE(ACTIVE) ((ACTIVE) <= SAI_SLOTACTIVE_ALL) - -#define IS_SAI_BLOCK_SLOT_NUMBER(NUMBER) ((1U <= (NUMBER)) && ((NUMBER) <= 16U)) - -#define IS_SAI_BLOCK_SLOT_SIZE(SIZE) (((SIZE) == SAI_SLOTSIZE_DATASIZE) || \ - ((SIZE) == SAI_SLOTSIZE_16B) || \ - ((SIZE) == SAI_SLOTSIZE_32B)) - -#define IS_SAI_BLOCK_FIRSTBIT_OFFSET(OFFSET) ((OFFSET) <= 24U) - -#define IS_SAI_BLOCK_FS_OFFSET(OFFSET) (((OFFSET) == SAI_FS_FIRSTBIT) || \ - ((OFFSET) == SAI_FS_BEFOREFIRSTBIT)) - -#define IS_SAI_BLOCK_FS_POLARITY(POLARITY) (((POLARITY) == SAI_FS_ACTIVE_LOW) || \ - ((POLARITY) == SAI_FS_ACTIVE_HIGH)) - -#define IS_SAI_BLOCK_FS_DEFINITION(DEFINITION) (((DEFINITION) == SAI_FS_STARTFRAME) || \ - ((DEFINITION) == SAI_FS_CHANNEL_IDENTIFICATION)) - -#define IS_SAI_BLOCK_MASTER_DIVIDER(DIVIDER) ((DIVIDER) <= 15U) - -#define IS_SAI_BLOCK_FRAME_LENGTH(LENGTH) ((8U <= (LENGTH)) && ((LENGTH) <= 256U)) - -#define IS_SAI_BLOCK_ACTIVE_FRAME(LENGTH) ((1U <= (LENGTH)) && ((LENGTH) <= 128U)) - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup SAI_Private_Functions SAI Private Functions - * @{ - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx || STM32F413xx || STM32F423xx */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_SAI_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_sai_ex.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_sai_ex.h deleted file mode 100644 index fbd4497..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_sai_ex.h +++ /dev/null @@ -1,116 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_sai_ex.h - * @author MCD Application Team - * @brief Header file of SAI Extension HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_SAI_EX_H -#define __STM32F4xx_HAL_SAI_EX_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup SAIEx - * @{ - */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || \ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F413xx) || \ - defined(STM32F423xx) - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/** @defgroup SAI_Clock_Source SAI Clock Source - * @{ - */ -#if defined(STM32F413xx) || defined(STM32F423xx) -#define SAI_CLKSOURCE_PLLI2S 0x00000000U -#define SAI_CLKSOURCE_EXT 0x00100000U -#define SAI_CLKSOURCE_PLLR 0x00200000U -#define SAI_CLKSOURCE_HS 0x00300000U -#else -#define SAI_CLKSOURCE_PLLSAI 0x00000000U -#define SAI_CLKSOURCE_PLLI2S 0x00100000U -#define SAI_CLKSOURCE_EXT 0x00200000U -#define SAI_CLKSOURCE_NA 0x00400000U /*!< No applicable for STM32F446xx */ -#endif - - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup SAIEx_Exported_Functions - * @{ - */ - -/** @addtogroup SAIEx_Exported_Functions_Group1 - * @{ - */ - -/* Extended features functions ************************************************/ -void SAI_BlockSynchroConfig(SAI_HandleTypeDef *hsai); -uint32_t SAI_GetInputClock(SAI_HandleTypeDef *hsai); -/** - * @} - */ - -/** - * @} - */ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -#if defined(STM32F413xx) || defined(STM32F423xx) -#define IS_SAI_CLK_SOURCE(SOURCE) (((SOURCE) == SAI_CLKSOURCE_PLLI2S) ||\ - ((SOURCE) == SAI_CLKSOURCE_EXT)||\ - ((SOURCE) == SAI_CLKSOURCE_PLLR)||\ - ((SOURCE) == SAI_CLKSOURCE_HS)) -#else -#define IS_SAI_CLK_SOURCE(SOURCE) (((SOURCE) == SAI_CLKSOURCE_PLLSAI) ||\ - ((SOURCE) == SAI_CLKSOURCE_EXT)||\ - ((SOURCE) == SAI_CLKSOURCE_PLLI2S)||\ - ((SOURCE) == SAI_CLKSOURCE_NA)) -#endif -/* Private functions ---------------------------------------------------------*/ - -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx || STM32F413xx || STM32F423xx */ -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_SAI_EX_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_sd.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_sd.h deleted file mode 100644 index e82e7e0..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_sd.h +++ /dev/null @@ -1,761 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_sd.h - * @author MCD Application Team - * @brief Header file of SD HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_SD_H -#define STM32F4xx_HAL_SD_H - -#ifdef __cplusplus - extern "C" { -#endif - -#if defined(SDIO) - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_ll_sdmmc.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup SD SD - * @brief SD HAL module driver - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup SD_Exported_Types SD Exported Types - * @{ - */ - -/** @defgroup SD_Exported_Types_Group1 SD State enumeration structure - * @{ - */ -typedef enum -{ - HAL_SD_STATE_RESET = 0x00000000U, /*!< SD not yet initialized or disabled */ - HAL_SD_STATE_READY = 0x00000001U, /*!< SD initialized and ready for use */ - HAL_SD_STATE_TIMEOUT = 0x00000002U, /*!< SD Timeout state */ - HAL_SD_STATE_BUSY = 0x00000003U, /*!< SD process ongoing */ - HAL_SD_STATE_PROGRAMMING = 0x00000004U, /*!< SD Programming State */ - HAL_SD_STATE_RECEIVING = 0x00000005U, /*!< SD Receiving State */ - HAL_SD_STATE_TRANSFER = 0x00000006U, /*!< SD Transfer State */ - HAL_SD_STATE_ERROR = 0x0000000FU /*!< SD is in error state */ -}HAL_SD_StateTypeDef; -/** - * @} - */ - -/** @defgroup SD_Exported_Types_Group2 SD Card State enumeration structure - * @{ - */ -typedef uint32_t HAL_SD_CardStateTypeDef; - -#define HAL_SD_CARD_READY 0x00000001U /*!< Card state is ready */ -#define HAL_SD_CARD_IDENTIFICATION 0x00000002U /*!< Card is in identification state */ -#define HAL_SD_CARD_STANDBY 0x00000003U /*!< Card is in standby state */ -#define HAL_SD_CARD_TRANSFER 0x00000004U /*!< Card is in transfer state */ -#define HAL_SD_CARD_SENDING 0x00000005U /*!< Card is sending an operation */ -#define HAL_SD_CARD_RECEIVING 0x00000006U /*!< Card is receiving operation information */ -#define HAL_SD_CARD_PROGRAMMING 0x00000007U /*!< Card is in programming state */ -#define HAL_SD_CARD_DISCONNECTED 0x00000008U /*!< Card is disconnected */ -#define HAL_SD_CARD_ERROR 0x000000FFU /*!< Card response Error */ -/** - * @} - */ - -/** @defgroup SD_Exported_Types_Group3 SD Handle Structure definition - * @{ - */ -#define SD_InitTypeDef SDIO_InitTypeDef -#define SD_TypeDef SDIO_TypeDef - -/** - * @brief SD Card Information Structure definition - */ -typedef struct -{ - uint32_t CardType; /*!< Specifies the card Type */ - - uint32_t CardVersion; /*!< Specifies the card version */ - - uint32_t Class; /*!< Specifies the class of the card class */ - - uint32_t RelCardAdd; /*!< Specifies the Relative Card Address */ - - uint32_t BlockNbr; /*!< Specifies the Card Capacity in blocks */ - - uint32_t BlockSize; /*!< Specifies one block size in bytes */ - - uint32_t LogBlockNbr; /*!< Specifies the Card logical Capacity in blocks */ - - uint32_t LogBlockSize; /*!< Specifies logical block size in bytes */ - -}HAL_SD_CardInfoTypeDef; - -/** - * @brief SD handle Structure definition - */ -#if defined (USE_HAL_SD_REGISTER_CALLBACKS) && (USE_HAL_SD_REGISTER_CALLBACKS == 1U) -typedef struct __SD_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_SD_REGISTER_CALLBACKS */ -{ - SD_TypeDef *Instance; /*!< SD registers base address */ - - SD_InitTypeDef Init; /*!< SD required parameters */ - - HAL_LockTypeDef Lock; /*!< SD locking object */ - - uint8_t *pTxBuffPtr; /*!< Pointer to SD Tx transfer Buffer */ - - uint32_t TxXferSize; /*!< SD Tx Transfer size */ - - uint8_t *pRxBuffPtr; /*!< Pointer to SD Rx transfer Buffer */ - - uint32_t RxXferSize; /*!< SD Rx Transfer size */ - - __IO uint32_t Context; /*!< SD transfer context */ - - __IO HAL_SD_StateTypeDef State; /*!< SD card State */ - - __IO uint32_t ErrorCode; /*!< SD Card Error codes */ - - DMA_HandleTypeDef *hdmatx; /*!< SD Tx DMA handle parameters */ - - DMA_HandleTypeDef *hdmarx; /*!< SD Rx DMA handle parameters */ - - HAL_SD_CardInfoTypeDef SdCard; /*!< SD Card information */ - - uint32_t CSD[4]; /*!< SD card specific data table */ - - uint32_t CID[4]; /*!< SD card identification number table */ - -#if defined (USE_HAL_SD_REGISTER_CALLBACKS) && (USE_HAL_SD_REGISTER_CALLBACKS == 1U) - void (* TxCpltCallback) (struct __SD_HandleTypeDef *hsd); - void (* RxCpltCallback) (struct __SD_HandleTypeDef *hsd); - void (* ErrorCallback) (struct __SD_HandleTypeDef *hsd); - void (* AbortCpltCallback) (struct __SD_HandleTypeDef *hsd); - - void (* MspInitCallback) (struct __SD_HandleTypeDef *hsd); - void (* MspDeInitCallback) (struct __SD_HandleTypeDef *hsd); -#endif /* USE_HAL_SD_REGISTER_CALLBACKS */ -}SD_HandleTypeDef; - -/** - * @} - */ - -/** @defgroup SD_Exported_Types_Group4 Card Specific Data: CSD Register - * @{ - */ -typedef struct -{ - __IO uint8_t CSDStruct; /*!< CSD structure */ - __IO uint8_t SysSpecVersion; /*!< System specification version */ - __IO uint8_t Reserved1; /*!< Reserved */ - __IO uint8_t TAAC; /*!< Data read access time 1 */ - __IO uint8_t NSAC; /*!< Data read access time 2 in CLK cycles */ - __IO uint8_t MaxBusClkFrec; /*!< Max. bus clock frequency */ - __IO uint16_t CardComdClasses; /*!< Card command classes */ - __IO uint8_t RdBlockLen; /*!< Max. read data block length */ - __IO uint8_t PartBlockRead; /*!< Partial blocks for read allowed */ - __IO uint8_t WrBlockMisalign; /*!< Write block misalignment */ - __IO uint8_t RdBlockMisalign; /*!< Read block misalignment */ - __IO uint8_t DSRImpl; /*!< DSR implemented */ - __IO uint8_t Reserved2; /*!< Reserved */ - __IO uint32_t DeviceSize; /*!< Device Size */ - __IO uint8_t MaxRdCurrentVDDMin; /*!< Max. read current @ VDD min */ - __IO uint8_t MaxRdCurrentVDDMax; /*!< Max. read current @ VDD max */ - __IO uint8_t MaxWrCurrentVDDMin; /*!< Max. write current @ VDD min */ - __IO uint8_t MaxWrCurrentVDDMax; /*!< Max. write current @ VDD max */ - __IO uint8_t DeviceSizeMul; /*!< Device size multiplier */ - __IO uint8_t EraseGrSize; /*!< Erase group size */ - __IO uint8_t EraseGrMul; /*!< Erase group size multiplier */ - __IO uint8_t WrProtectGrSize; /*!< Write protect group size */ - __IO uint8_t WrProtectGrEnable; /*!< Write protect group enable */ - __IO uint8_t ManDeflECC; /*!< Manufacturer default ECC */ - __IO uint8_t WrSpeedFact; /*!< Write speed factor */ - __IO uint8_t MaxWrBlockLen; /*!< Max. write data block length */ - __IO uint8_t WriteBlockPaPartial; /*!< Partial blocks for write allowed */ - __IO uint8_t Reserved3; /*!< Reserved */ - __IO uint8_t ContentProtectAppli; /*!< Content protection application */ - __IO uint8_t FileFormatGroup; /*!< File format group */ - __IO uint8_t CopyFlag; /*!< Copy flag (OTP) */ - __IO uint8_t PermWrProtect; /*!< Permanent write protection */ - __IO uint8_t TempWrProtect; /*!< Temporary write protection */ - __IO uint8_t FileFormat; /*!< File format */ - __IO uint8_t ECC; /*!< ECC code */ - __IO uint8_t CSD_CRC; /*!< CSD CRC */ - __IO uint8_t Reserved4; /*!< Always 1 */ -}HAL_SD_CardCSDTypeDef; -/** - * @} - */ - -/** @defgroup SD_Exported_Types_Group5 Card Identification Data: CID Register - * @{ - */ -typedef struct -{ - __IO uint8_t ManufacturerID; /*!< Manufacturer ID */ - __IO uint16_t OEM_AppliID; /*!< OEM/Application ID */ - __IO uint32_t ProdName1; /*!< Product Name part1 */ - __IO uint8_t ProdName2; /*!< Product Name part2 */ - __IO uint8_t ProdRev; /*!< Product Revision */ - __IO uint32_t ProdSN; /*!< Product Serial Number */ - __IO uint8_t Reserved1; /*!< Reserved1 */ - __IO uint16_t ManufactDate; /*!< Manufacturing Date */ - __IO uint8_t CID_CRC; /*!< CID CRC */ - __IO uint8_t Reserved2; /*!< Always 1 */ - -}HAL_SD_CardCIDTypeDef; -/** - * @} - */ - -/** @defgroup SD_Exported_Types_Group6 SD Card Status returned by ACMD13 - * @{ - */ -typedef struct -{ - __IO uint8_t DataBusWidth; /*!< Shows the currently defined data bus width */ - __IO uint8_t SecuredMode; /*!< Card is in secured mode of operation */ - __IO uint16_t CardType; /*!< Carries information about card type */ - __IO uint32_t ProtectedAreaSize; /*!< Carries information about the capacity of protected area */ - __IO uint8_t SpeedClass; /*!< Carries information about the speed class of the card */ - __IO uint8_t PerformanceMove; /*!< Carries information about the card's performance move */ - __IO uint8_t AllocationUnitSize; /*!< Carries information about the card's allocation unit size */ - __IO uint16_t EraseSize; /*!< Determines the number of AUs to be erased in one operation */ - __IO uint8_t EraseTimeout; /*!< Determines the timeout for any number of AU erase */ - __IO uint8_t EraseOffset; /*!< Carries information about the erase offset */ - -}HAL_SD_CardStatusTypeDef; -/** - * @} - */ - -#if defined (USE_HAL_SD_REGISTER_CALLBACKS) && (USE_HAL_SD_REGISTER_CALLBACKS == 1U) -/** @defgroup SD_Exported_Types_Group7 SD Callback ID enumeration definition - * @{ - */ -typedef enum -{ - HAL_SD_TX_CPLT_CB_ID = 0x00U, /*!< SD Tx Complete Callback ID */ - HAL_SD_RX_CPLT_CB_ID = 0x01U, /*!< SD Rx Complete Callback ID */ - HAL_SD_ERROR_CB_ID = 0x02U, /*!< SD Error Callback ID */ - HAL_SD_ABORT_CB_ID = 0x03U, /*!< SD Abort Callback ID */ - - HAL_SD_MSP_INIT_CB_ID = 0x10U, /*!< SD MspInit Callback ID */ - HAL_SD_MSP_DEINIT_CB_ID = 0x11U /*!< SD MspDeInit Callback ID */ -}HAL_SD_CallbackIDTypeDef; -/** - * @} - */ - -/** @defgroup SD_Exported_Types_Group8 SD Callback pointer definition - * @{ - */ -typedef void (*pSD_CallbackTypeDef) (SD_HandleTypeDef *hsd); -/** - * @} - */ -#endif /* USE_HAL_SD_REGISTER_CALLBACKS */ -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup SD_Exported_Constants Exported Constants - * @{ - */ - -#define BLOCKSIZE 512U /*!< Block size is 512 bytes */ - -/** @defgroup SD_Exported_Constansts_Group1 SD Error status enumeration Structure definition - * @{ - */ -#define HAL_SD_ERROR_NONE SDMMC_ERROR_NONE /*!< No error */ -#define HAL_SD_ERROR_CMD_CRC_FAIL SDMMC_ERROR_CMD_CRC_FAIL /*!< Command response received (but CRC check failed) */ -#define HAL_SD_ERROR_DATA_CRC_FAIL SDMMC_ERROR_DATA_CRC_FAIL /*!< Data block sent/received (CRC check failed) */ -#define HAL_SD_ERROR_CMD_RSP_TIMEOUT SDMMC_ERROR_CMD_RSP_TIMEOUT /*!< Command response timeout */ -#define HAL_SD_ERROR_DATA_TIMEOUT SDMMC_ERROR_DATA_TIMEOUT /*!< Data timeout */ -#define HAL_SD_ERROR_TX_UNDERRUN SDMMC_ERROR_TX_UNDERRUN /*!< Transmit FIFO underrun */ -#define HAL_SD_ERROR_RX_OVERRUN SDMMC_ERROR_RX_OVERRUN /*!< Receive FIFO overrun */ -#define HAL_SD_ERROR_ADDR_MISALIGNED SDMMC_ERROR_ADDR_MISALIGNED /*!< Misaligned address */ -#define HAL_SD_ERROR_BLOCK_LEN_ERR SDMMC_ERROR_BLOCK_LEN_ERR /*!< Transferred block length is not allowed for the card or the - number of transferred bytes does not match the block length */ -#define HAL_SD_ERROR_ERASE_SEQ_ERR SDMMC_ERROR_ERASE_SEQ_ERR /*!< An error in the sequence of erase command occurs */ -#define HAL_SD_ERROR_BAD_ERASE_PARAM SDMMC_ERROR_BAD_ERASE_PARAM /*!< An invalid selection for erase groups */ -#define HAL_SD_ERROR_WRITE_PROT_VIOLATION SDMMC_ERROR_WRITE_PROT_VIOLATION /*!< Attempt to program a write protect block */ -#define HAL_SD_ERROR_LOCK_UNLOCK_FAILED SDMMC_ERROR_LOCK_UNLOCK_FAILED /*!< Sequence or password error has been detected in unlock - command or if there was an attempt to access a locked card */ -#define HAL_SD_ERROR_COM_CRC_FAILED SDMMC_ERROR_COM_CRC_FAILED /*!< CRC check of the previous command failed */ -#define HAL_SD_ERROR_ILLEGAL_CMD SDMMC_ERROR_ILLEGAL_CMD /*!< Command is not legal for the card state */ -#define HAL_SD_ERROR_CARD_ECC_FAILED SDMMC_ERROR_CARD_ECC_FAILED /*!< Card internal ECC was applied but failed to correct the data */ -#define HAL_SD_ERROR_CC_ERR SDMMC_ERROR_CC_ERR /*!< Internal card controller error */ -#define HAL_SD_ERROR_GENERAL_UNKNOWN_ERR SDMMC_ERROR_GENERAL_UNKNOWN_ERR /*!< General or unknown error */ -#define HAL_SD_ERROR_STREAM_READ_UNDERRUN SDMMC_ERROR_STREAM_READ_UNDERRUN /*!< The card could not sustain data reading in stream rmode */ -#define HAL_SD_ERROR_STREAM_WRITE_OVERRUN SDMMC_ERROR_STREAM_WRITE_OVERRUN /*!< The card could not sustain data programming in stream mode */ -#define HAL_SD_ERROR_CID_CSD_OVERWRITE SDMMC_ERROR_CID_CSD_OVERWRITE /*!< CID/CSD overwrite error */ -#define HAL_SD_ERROR_WP_ERASE_SKIP SDMMC_ERROR_WP_ERASE_SKIP /*!< Only partial address space was erased */ -#define HAL_SD_ERROR_CARD_ECC_DISABLED SDMMC_ERROR_CARD_ECC_DISABLED /*!< Command has been executed without using internal ECC */ -#define HAL_SD_ERROR_ERASE_RESET SDMMC_ERROR_ERASE_RESET /*!< Erase sequence was cleared before executing because an out - of erase sequence command was received */ -#define HAL_SD_ERROR_AKE_SEQ_ERR SDMMC_ERROR_AKE_SEQ_ERR /*!< Error in sequence of authentication */ -#define HAL_SD_ERROR_INVALID_VOLTRANGE SDMMC_ERROR_INVALID_VOLTRANGE /*!< Error in case of invalid voltage range */ -#define HAL_SD_ERROR_ADDR_OUT_OF_RANGE SDMMC_ERROR_ADDR_OUT_OF_RANGE /*!< Error when addressed block is out of range */ -#define HAL_SD_ERROR_REQUEST_NOT_APPLICABLE SDMMC_ERROR_REQUEST_NOT_APPLICABLE /*!< Error when command request is not applicable */ -#define HAL_SD_ERROR_PARAM SDMMC_ERROR_INVALID_PARAMETER /*!< the used parameter is not valid */ -#define HAL_SD_ERROR_UNSUPPORTED_FEATURE SDMMC_ERROR_UNSUPPORTED_FEATURE /*!< Error when feature is not insupported */ -#define HAL_SD_ERROR_BUSY SDMMC_ERROR_BUSY /*!< Error when transfer process is busy */ -#define HAL_SD_ERROR_DMA SDMMC_ERROR_DMA /*!< Error while DMA transfer */ -#define HAL_SD_ERROR_TIMEOUT SDMMC_ERROR_TIMEOUT /*!< Timeout error */ - -#if defined (USE_HAL_SD_REGISTER_CALLBACKS) && (USE_HAL_SD_REGISTER_CALLBACKS == 1U) -#define HAL_SD_ERROR_INVALID_CALLBACK SDMMC_ERROR_INVALID_PARAMETER /*!< Invalid callback error */ -#endif /* USE_HAL_SD_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @defgroup SD_Exported_Constansts_Group2 SD context enumeration - * @{ - */ -#define SD_CONTEXT_NONE 0x00000000U /*!< None */ -#define SD_CONTEXT_READ_SINGLE_BLOCK 0x00000001U /*!< Read single block operation */ -#define SD_CONTEXT_READ_MULTIPLE_BLOCK 0x00000002U /*!< Read multiple blocks operation */ -#define SD_CONTEXT_WRITE_SINGLE_BLOCK 0x00000010U /*!< Write single block operation */ -#define SD_CONTEXT_WRITE_MULTIPLE_BLOCK 0x00000020U /*!< Write multiple blocks operation */ -#define SD_CONTEXT_IT 0x00000008U /*!< Process in Interrupt mode */ -#define SD_CONTEXT_DMA 0x00000080U /*!< Process in DMA mode */ - -/** - * @} - */ - -/** @defgroup SD_Exported_Constansts_Group3 SD Supported Memory Cards - * @{ - */ -#define CARD_SDSC 0x00000000U /*!< SD Standard Capacity <2Go */ -#define CARD_SDHC_SDXC 0x00000001U /*!< SD High Capacity <32Go, SD Extended Capacity <2To */ -#define CARD_SECURED 0x00000003U - -/** - * @} - */ - -/** @defgroup SD_Exported_Constansts_Group4 SD Supported Version - * @{ - */ -#define CARD_V1_X 0x00000000U -#define CARD_V2_X 0x00000001U -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup SD_Exported_macros SD Exported Macros - * @brief macros to handle interrupts and specific clock configurations - * @{ - */ -/** @brief Reset SD handle state. - * @param __HANDLE__ : SD handle. - * @retval None - */ -#if defined (USE_HAL_SD_REGISTER_CALLBACKS) && (USE_HAL_SD_REGISTER_CALLBACKS == 1U) -#define __HAL_SD_RESET_HANDLE_STATE(__HANDLE__) do { \ - (__HANDLE__)->State = HAL_SD_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_SD_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_SD_STATE_RESET) -#endif /* USE_HAL_SD_REGISTER_CALLBACKS */ - -/** - * @brief Enable the SD device. - * @retval None - */ -#define __HAL_SD_ENABLE(__HANDLE__) __SDIO_ENABLE((__HANDLE__)->Instance) - -/** - * @brief Disable the SD device. - * @retval None - */ -#define __HAL_SD_DISABLE(__HANDLE__) __SDIO_DISABLE((__HANDLE__)->Instance) - -/** - * @brief Enable the SDMMC DMA transfer. - * @retval None - */ -#define __HAL_SD_DMA_ENABLE(__HANDLE__) __SDIO_DMA_ENABLE((__HANDLE__)->Instance) - -/** - * @brief Disable the SDMMC DMA transfer. - * @retval None - */ -#define __HAL_SD_DMA_DISABLE(__HANDLE__) __SDIO_DMA_DISABLE((__HANDLE__)->Instance) - -/** - * @brief Enable the SD device interrupt. - * @param __HANDLE__: SD Handle - * @param __INTERRUPT__: specifies the SDMMC interrupt sources to be enabled. - * This parameter can be one or a combination of the following values: - * @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt - * @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt - * @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt - * @arg SDIO_IT_DTIMEOUT: Data timeout interrupt - * @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt - * @arg SDIO_IT_RXOVERR: Received FIFO overrun error interrupt - * @arg SDIO_IT_CMDREND: Command response received (CRC check passed) interrupt - * @arg SDIO_IT_CMDSENT: Command sent (no response required) interrupt - * @arg SDIO_IT_DATAEND: Data end (data counter, DATACOUNT, is zero) interrupt - * @arg SDIO_IT_DBCKEND: Data block sent/received (CRC check passed) interrupt - * @arg SDIO_IT_CMDACT: Command transfer in progress interrupt - * @arg SDIO_IT_TXACT: Data transmit in progress interrupt - * @arg SDIO_IT_RXACT: Data receive in progress interrupt - * @arg SDIO_IT_TXFIFOHE: Transmit FIFO Half Empty interrupt - * @arg SDIO_IT_RXFIFOHF: Receive FIFO Half Full interrupt - * @arg SDIO_IT_TXFIFOF: Transmit FIFO full interrupt - * @arg SDIO_IT_RXFIFOF: Receive FIFO full interrupt - * @arg SDIO_IT_TXFIFOE: Transmit FIFO empty interrupt - * @arg SDIO_IT_RXFIFOE: Receive FIFO empty interrupt - * @arg SDIO_IT_TXDAVL: Data available in transmit FIFO interrupt - * @arg SDIO_IT_RXDAVL: Data available in receive FIFO interrupt - * @arg SDIO_IT_SDIOIT: SDIO interrupt received interrupt - * @retval None - */ -#define __HAL_SD_ENABLE_IT(__HANDLE__, __INTERRUPT__) __SDIO_ENABLE_IT((__HANDLE__)->Instance, (__INTERRUPT__)) - -/** - * @brief Disable the SD device interrupt. - * @param __HANDLE__: SD Handle - * @param __INTERRUPT__: specifies the SDMMC interrupt sources to be disabled. - * This parameter can be one or a combination of the following values: - * @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt - * @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt - * @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt - * @arg SDIO_IT_DTIMEOUT: Data timeout interrupt - * @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt - * @arg SDIO_IT_RXOVERR: Received FIFO overrun error interrupt - * @arg SDIO_IT_CMDREND: Command response received (CRC check passed) interrupt - * @arg SDIO_IT_CMDSENT: Command sent (no response required) interrupt - * @arg SDIO_IT_DATAEND: Data end (data counter, DATACOUNT, is zero) interrupt - * @arg SDIO_IT_DBCKEND: Data block sent/received (CRC check passed) interrupt - * @arg SDIO_IT_CMDACT: Command transfer in progress interrupt - * @arg SDIO_IT_TXACT: Data transmit in progress interrupt - * @arg SDIO_IT_RXACT: Data receive in progress interrupt - * @arg SDIO_IT_TXFIFOHE: Transmit FIFO Half Empty interrupt - * @arg SDIO_IT_RXFIFOHF: Receive FIFO Half Full interrupt - * @arg SDIO_IT_TXFIFOF: Transmit FIFO full interrupt - * @arg SDIO_IT_RXFIFOF: Receive FIFO full interrupt - * @arg SDIO_IT_TXFIFOE: Transmit FIFO empty interrupt - * @arg SDIO_IT_RXFIFOE: Receive FIFO empty interrupt - * @arg SDIO_IT_TXDAVL: Data available in transmit FIFO interrupt - * @arg SDIO_IT_RXDAVL: Data available in receive FIFO interrupt - * @arg SDIO_IT_SDIOIT: SDIO interrupt received interrupt - * @retval None - */ -#define __HAL_SD_DISABLE_IT(__HANDLE__, __INTERRUPT__) __SDIO_DISABLE_IT((__HANDLE__)->Instance, (__INTERRUPT__)) - -/** - * @brief Check whether the specified SD flag is set or not. - * @param __HANDLE__: SD Handle - * @param __FLAG__: specifies the flag to check. - * This parameter can be one of the following values: - * @arg SDIO_FLAG_CCRCFAIL: Command response received (CRC check failed) - * @arg SDIO_FLAG_DCRCFAIL: Data block sent/received (CRC check failed) - * @arg SDIO_FLAG_CTIMEOUT: Command response timeout - * @arg SDIO_FLAG_DTIMEOUT: Data timeout - * @arg SDIO_FLAG_TXUNDERR: Transmit FIFO underrun error - * @arg SDIO_FLAG_RXOVERR: Received FIFO overrun error - * @arg SDIO_FLAG_CMDREND: Command response received (CRC check passed) - * @arg SDIO_FLAG_CMDSENT: Command sent (no response required) - * @arg SDIO_FLAG_DATAEND: Data end (data counter, DATACOUNT, is zero) - * @arg SDIO_FLAG_DBCKEND: Data block sent/received (CRC check passed) - * @arg SDIO_FLAG_CMDACT: Command transfer in progress - * @arg SDIO_FLAG_TXACT: Data transmit in progress - * @arg SDIO_FLAG_RXACT: Data receive in progress - * @arg SDIO_FLAG_TXFIFOHE: Transmit FIFO Half Empty - * @arg SDIO_FLAG_RXFIFOHF: Receive FIFO Half Full - * @arg SDIO_FLAG_TXFIFOF: Transmit FIFO full - * @arg SDIO_FLAG_RXFIFOF: Receive FIFO full - * @arg SDIO_FLAG_TXFIFOE: Transmit FIFO empty - * @arg SDIO_FLAG_RXFIFOE: Receive FIFO empty - * @arg SDIO_FLAG_TXDAVL: Data available in transmit FIFO - * @arg SDIO_FLAG_RXDAVL: Data available in receive FIFO - * @arg SDIO_FLAG_SDIOIT: SDIO interrupt received - * @retval The new state of SD FLAG (SET or RESET). - */ -#define __HAL_SD_GET_FLAG(__HANDLE__, __FLAG__) __SDIO_GET_FLAG((__HANDLE__)->Instance, (__FLAG__)) - -/** - * @brief Clear the SD's pending flags. - * @param __HANDLE__: SD Handle - * @param __FLAG__: specifies the flag to clear. - * This parameter can be one or a combination of the following values: - * @arg SDIO_FLAG_CCRCFAIL: Command response received (CRC check failed) - * @arg SDIO_FLAG_DCRCFAIL: Data block sent/received (CRC check failed) - * @arg SDIO_FLAG_CTIMEOUT: Command response timeout - * @arg SDIO_FLAG_DTIMEOUT: Data timeout - * @arg SDIO_FLAG_TXUNDERR: Transmit FIFO underrun error - * @arg SDIO_FLAG_RXOVERR: Received FIFO overrun error - * @arg SDIO_FLAG_CMDREND: Command response received (CRC check passed) - * @arg SDIO_FLAG_CMDSENT: Command sent (no response required) - * @arg SDIO_FLAG_DATAEND: Data end (data counter, DATACOUNT, is zero) - * @arg SDIO_FLAG_DBCKEND: Data block sent/received (CRC check passed) - * @arg SDIO_FLAG_SDIOIT: SDIO interrupt received - * @retval None - */ -#define __HAL_SD_CLEAR_FLAG(__HANDLE__, __FLAG__) __SDIO_CLEAR_FLAG((__HANDLE__)->Instance, (__FLAG__)) - -/** - * @brief Check whether the specified SD interrupt has occurred or not. - * @param __HANDLE__: SD Handle - * @param __INTERRUPT__: specifies the SDMMC interrupt source to check. - * This parameter can be one of the following values: - * @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt - * @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt - * @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt - * @arg SDIO_IT_DTIMEOUT: Data timeout interrupt - * @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt - * @arg SDIO_IT_RXOVERR: Received FIFO overrun error interrupt - * @arg SDIO_IT_CMDREND: Command response received (CRC check passed) interrupt - * @arg SDIO_IT_CMDSENT: Command sent (no response required) interrupt - * @arg SDIO_IT_DATAEND: Data end (data counter, DATACOUNT, is zero) interrupt - * @arg SDIO_IT_DBCKEND: Data block sent/received (CRC check passed) interrupt - * @arg SDIO_IT_CMDACT: Command transfer in progress interrupt - * @arg SDIO_IT_TXACT: Data transmit in progress interrupt - * @arg SDIO_IT_RXACT: Data receive in progress interrupt - * @arg SDIO_IT_TXFIFOHE: Transmit FIFO Half Empty interrupt - * @arg SDIO_IT_RXFIFOHF: Receive FIFO Half Full interrupt - * @arg SDIO_IT_TXFIFOF: Transmit FIFO full interrupt - * @arg SDIO_IT_RXFIFOF: Receive FIFO full interrupt - * @arg SDIO_IT_TXFIFOE: Transmit FIFO empty interrupt - * @arg SDIO_IT_RXFIFOE: Receive FIFO empty interrupt - * @arg SDIO_IT_TXDAVL: Data available in transmit FIFO interrupt - * @arg SDIO_IT_RXDAVL: Data available in receive FIFO interrupt - * @arg SDIO_IT_SDIOIT: SDIO interrupt received interrupt - * @retval The new state of SD IT (SET or RESET). - */ -#define __HAL_SD_GET_IT(__HANDLE__, __INTERRUPT__) __SDIO_GET_IT((__HANDLE__)->Instance, (__INTERRUPT__)) - -/** - * @brief Clear the SD's interrupt pending bits. - * @param __HANDLE__: SD Handle - * @param __INTERRUPT__: specifies the interrupt pending bit to clear. - * This parameter can be one or a combination of the following values: - * @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt - * @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt - * @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt - * @arg SDIO_IT_DTIMEOUT: Data timeout interrupt - * @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt - * @arg SDIO_IT_RXOVERR: Received FIFO overrun error interrupt - * @arg SDIO_IT_CMDREND: Command response received (CRC check passed) interrupt - * @arg SDIO_IT_CMDSENT: Command sent (no response required) interrupt - * @arg SDIO_IT_DATAEND: Data end (data counter, DATACOUNT, is zero) interrupt - * @arg SDIO_IT_SDIOIT: SDIO interrupt received interrupt - * @retval None - */ -#define __HAL_SD_CLEAR_IT(__HANDLE__, __INTERRUPT__) __SDIO_CLEAR_IT((__HANDLE__)->Instance, (__INTERRUPT__)) - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup SD_Exported_Functions SD Exported Functions - * @{ - */ - -/** @defgroup SD_Exported_Functions_Group1 Initialization and de-initialization functions - * @{ - */ -HAL_StatusTypeDef HAL_SD_Init(SD_HandleTypeDef *hsd); -HAL_StatusTypeDef HAL_SD_InitCard(SD_HandleTypeDef *hsd); -HAL_StatusTypeDef HAL_SD_DeInit (SD_HandleTypeDef *hsd); -void HAL_SD_MspInit(SD_HandleTypeDef *hsd); -void HAL_SD_MspDeInit(SD_HandleTypeDef *hsd); -/** - * @} - */ - -/** @defgroup SD_Exported_Functions_Group2 Input and Output operation functions - * @{ - */ -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_SD_ReadBlocks(SD_HandleTypeDef *hsd, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks, uint32_t Timeout); -HAL_StatusTypeDef HAL_SD_WriteBlocks(SD_HandleTypeDef *hsd, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks, uint32_t Timeout); -HAL_StatusTypeDef HAL_SD_Erase(SD_HandleTypeDef *hsd, uint32_t BlockStartAdd, uint32_t BlockEndAdd); -/* Non-Blocking mode: IT */ -HAL_StatusTypeDef HAL_SD_ReadBlocks_IT(SD_HandleTypeDef *hsd, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks); -HAL_StatusTypeDef HAL_SD_WriteBlocks_IT(SD_HandleTypeDef *hsd, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks); -/* Non-Blocking mode: DMA */ -HAL_StatusTypeDef HAL_SD_ReadBlocks_DMA(SD_HandleTypeDef *hsd, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks); -HAL_StatusTypeDef HAL_SD_WriteBlocks_DMA(SD_HandleTypeDef *hsd, uint8_t *pData, uint32_t BlockAdd, uint32_t NumberOfBlocks); - -void HAL_SD_IRQHandler(SD_HandleTypeDef *hsd); - -/* Callback in non blocking modes (DMA) */ -void HAL_SD_TxCpltCallback(SD_HandleTypeDef *hsd); -void HAL_SD_RxCpltCallback(SD_HandleTypeDef *hsd); -void HAL_SD_ErrorCallback(SD_HandleTypeDef *hsd); -void HAL_SD_AbortCallback(SD_HandleTypeDef *hsd); - -#if defined (USE_HAL_SD_REGISTER_CALLBACKS) && (USE_HAL_SD_REGISTER_CALLBACKS == 1U) -/* SD callback registering/unregistering */ -HAL_StatusTypeDef HAL_SD_RegisterCallback (SD_HandleTypeDef *hsd, HAL_SD_CallbackIDTypeDef CallbackId, pSD_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_SD_UnRegisterCallback(SD_HandleTypeDef *hsd, HAL_SD_CallbackIDTypeDef CallbackId); -#endif /* USE_HAL_SD_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @defgroup SD_Exported_Functions_Group3 Peripheral Control functions - * @{ - */ -HAL_StatusTypeDef HAL_SD_ConfigWideBusOperation(SD_HandleTypeDef *hsd, uint32_t WideMode); -/** - * @} - */ - -/** @defgroup SD_Exported_Functions_Group4 SD card related functions - * @{ - */ -HAL_StatusTypeDef HAL_SD_SendSDStatus(SD_HandleTypeDef *hsd, uint32_t *pSDstatus); -HAL_SD_CardStateTypeDef HAL_SD_GetCardState(SD_HandleTypeDef *hsd); -HAL_StatusTypeDef HAL_SD_GetCardCID(SD_HandleTypeDef *hsd, HAL_SD_CardCIDTypeDef *pCID); -HAL_StatusTypeDef HAL_SD_GetCardCSD(SD_HandleTypeDef *hsd, HAL_SD_CardCSDTypeDef *pCSD); -HAL_StatusTypeDef HAL_SD_GetCardStatus(SD_HandleTypeDef *hsd, HAL_SD_CardStatusTypeDef *pStatus); -HAL_StatusTypeDef HAL_SD_GetCardInfo(SD_HandleTypeDef *hsd, HAL_SD_CardInfoTypeDef *pCardInfo); -/** - * @} - */ - -/** @defgroup SD_Exported_Functions_Group5 Peripheral State and Errors functions - * @{ - */ -HAL_SD_StateTypeDef HAL_SD_GetState(SD_HandleTypeDef *hsd); -uint32_t HAL_SD_GetError(SD_HandleTypeDef *hsd); -/** - * @} - */ - -/** @defgroup SD_Exported_Functions_Group6 Perioheral Abort management - * @{ - */ -HAL_StatusTypeDef HAL_SD_Abort(SD_HandleTypeDef *hsd); -HAL_StatusTypeDef HAL_SD_Abort_IT(SD_HandleTypeDef *hsd); -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/** @defgroup SD_Private_Types SD Private Types - * @{ - */ - -/** - * @} - */ - -/* Private defines -----------------------------------------------------------*/ -/** @defgroup SD_Private_Defines SD Private Defines - * @{ - */ - -/** - * @} - */ - -/* Private variables ---------------------------------------------------------*/ -/** @defgroup SD_Private_Variables SD Private Variables - * @{ - */ - -/** - * @} - */ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup SD_Private_Constants SD Private Constants - * @{ - */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup SD_Private_Macros SD Private Macros - * @{ - */ - -/** - * @} - */ - -/* Private functions prototypes ----------------------------------------------*/ -/** @defgroup SD_Private_Functions_Prototypes SD Private Functions Prototypes - * @{ - */ - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup SD_Private_Functions SD Private Functions - * @{ - */ - -/** - * @} - */ - - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* SDIO */ - -#ifdef __cplusplus -} -#endif - - -#endif /* STM32F4xx_HAL_SD_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_sdram.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_sdram.h deleted file mode 100644 index 3dd7802..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_sdram.h +++ /dev/null @@ -1,226 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_sdram.h - * @author MCD Application Team - * @brief Header file of SDRAM HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_SDRAM_H -#define __STM32F4xx_HAL_SDRAM_H - -#ifdef __cplusplus - extern "C" { -#endif - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_ll_fmc.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup SDRAM - * @{ - */ - -/* Exported typedef ----------------------------------------------------------*/ -/** @defgroup SDRAM_Exported_Types SDRAM Exported Types - * @{ - */ - -/** - * @brief HAL SDRAM State structure definition - */ -typedef enum -{ - HAL_SDRAM_STATE_RESET = 0x00U, /*!< SDRAM not yet initialized or disabled */ - HAL_SDRAM_STATE_READY = 0x01U, /*!< SDRAM initialized and ready for use */ - HAL_SDRAM_STATE_BUSY = 0x02U, /*!< SDRAM internal process is ongoing */ - HAL_SDRAM_STATE_ERROR = 0x03U, /*!< SDRAM error state */ - HAL_SDRAM_STATE_WRITE_PROTECTED = 0x04U, /*!< SDRAM device write protected */ - HAL_SDRAM_STATE_PRECHARGED = 0x05U /*!< SDRAM device precharged */ - -} HAL_SDRAM_StateTypeDef; - -/** - * @brief SDRAM handle Structure definition - */ -#if (USE_HAL_SDRAM_REGISTER_CALLBACKS == 1) -typedef struct __SDRAM_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_SDRAM_REGISTER_CALLBACKS */ -{ - FMC_SDRAM_TypeDef *Instance; /*!< Register base address */ - - FMC_SDRAM_InitTypeDef Init; /*!< SDRAM device configuration parameters */ - - __IO HAL_SDRAM_StateTypeDef State; /*!< SDRAM access state */ - - HAL_LockTypeDef Lock; /*!< SDRAM locking object */ - - DMA_HandleTypeDef *hdma; /*!< Pointer DMA handler */ - -#if (USE_HAL_SDRAM_REGISTER_CALLBACKS == 1) - void (* MspInitCallback) ( struct __SDRAM_HandleTypeDef * hsdram); /*!< SDRAM Msp Init callback */ - void (* MspDeInitCallback) ( struct __SDRAM_HandleTypeDef * hsdram); /*!< SDRAM Msp DeInit callback */ - void (* RefreshErrorCallback) ( struct __SDRAM_HandleTypeDef * hsdram); /*!< SDRAM Refresh Error callback */ - void (* DmaXferCpltCallback) ( DMA_HandleTypeDef * hdma); /*!< SDRAM DMA Xfer Complete callback */ - void (* DmaXferErrorCallback) ( DMA_HandleTypeDef * hdma); /*!< SDRAM DMA Xfer Error callback */ -#endif -} SDRAM_HandleTypeDef; - -#if (USE_HAL_SDRAM_REGISTER_CALLBACKS == 1) -/** - * @brief HAL SDRAM Callback ID enumeration definition - */ -typedef enum -{ - HAL_SDRAM_MSP_INIT_CB_ID = 0x00U, /*!< SDRAM MspInit Callback ID */ - HAL_SDRAM_MSP_DEINIT_CB_ID = 0x01U, /*!< SDRAM MspDeInit Callback ID */ - HAL_SDRAM_REFRESH_ERR_CB_ID = 0x02U, /*!< SDRAM Refresh Error Callback ID */ - HAL_SDRAM_DMA_XFER_CPLT_CB_ID = 0x03U, /*!< SDRAM DMA Xfer Complete Callback ID */ - HAL_SDRAM_DMA_XFER_ERR_CB_ID = 0x04U /*!< SDRAM DMA Xfer Error Callback ID */ -}HAL_SDRAM_CallbackIDTypeDef; - -/** - * @brief HAL SDRAM Callback pointer definition - */ -typedef void (*pSDRAM_CallbackTypeDef)(SDRAM_HandleTypeDef *hsdram); -typedef void (*pSDRAM_DmaCallbackTypeDef)(DMA_HandleTypeDef *hdma); -#endif -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup SDRAM_Exported_Macros SDRAM Exported Macros - * @{ - */ - -/** @brief Reset SDRAM handle state - * @param __HANDLE__ specifies the SDRAM handle. - * @retval None - */ -#if (USE_HAL_SDRAM_REGISTER_CALLBACKS == 1) -#define __HAL_SDRAM_RESET_HANDLE_STATE(__HANDLE__) do { \ - (__HANDLE__)->State = HAL_SDRAM_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_SDRAM_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_SDRAM_STATE_RESET) -#endif -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup SDRAM_Exported_Functions SDRAM Exported Functions - * @{ - */ - -/** @addtogroup SDRAM_Exported_Functions_Group1 - * @{ - */ - -/* Initialization/de-initialization functions *********************************/ -HAL_StatusTypeDef HAL_SDRAM_Init(SDRAM_HandleTypeDef *hsdram, FMC_SDRAM_TimingTypeDef *Timing); -HAL_StatusTypeDef HAL_SDRAM_DeInit(SDRAM_HandleTypeDef *hsdram); -void HAL_SDRAM_MspInit(SDRAM_HandleTypeDef *hsdram); -void HAL_SDRAM_MspDeInit(SDRAM_HandleTypeDef *hsdram); - -void HAL_SDRAM_IRQHandler(SDRAM_HandleTypeDef *hsdram); -void HAL_SDRAM_RefreshErrorCallback(SDRAM_HandleTypeDef *hsdram); -void HAL_SDRAM_DMA_XferCpltCallback(DMA_HandleTypeDef *hdma); -void HAL_SDRAM_DMA_XferErrorCallback(DMA_HandleTypeDef *hdma); -/** - * @} - */ - -/** @addtogroup SDRAM_Exported_Functions_Group2 - * @{ - */ -/* I/O operation functions ****************************************************/ -HAL_StatusTypeDef HAL_SDRAM_Read_8b(SDRAM_HandleTypeDef *hsdram, uint32_t *pAddress, uint8_t *pDstBuffer, uint32_t BufferSize); -HAL_StatusTypeDef HAL_SDRAM_Write_8b(SDRAM_HandleTypeDef *hsdram, uint32_t *pAddress, uint8_t *pSrcBuffer, uint32_t BufferSize); -HAL_StatusTypeDef HAL_SDRAM_Read_16b(SDRAM_HandleTypeDef *hsdram, uint32_t *pAddress, uint16_t *pDstBuffer, uint32_t BufferSize); -HAL_StatusTypeDef HAL_SDRAM_Write_16b(SDRAM_HandleTypeDef *hsdram, uint32_t *pAddress, uint16_t *pSrcBuffer, uint32_t BufferSize); -HAL_StatusTypeDef HAL_SDRAM_Read_32b(SDRAM_HandleTypeDef *hsdram, uint32_t *pAddress, uint32_t *pDstBuffer, uint32_t BufferSize); -HAL_StatusTypeDef HAL_SDRAM_Write_32b(SDRAM_HandleTypeDef *hsdram, uint32_t *pAddress, uint32_t *pSrcBuffer, uint32_t BufferSize); - -HAL_StatusTypeDef HAL_SDRAM_Read_DMA(SDRAM_HandleTypeDef *hsdram, uint32_t * pAddress, uint32_t *pDstBuffer, uint32_t BufferSize); -HAL_StatusTypeDef HAL_SDRAM_Write_DMA(SDRAM_HandleTypeDef *hsdram, uint32_t *pAddress, uint32_t *pSrcBuffer, uint32_t BufferSize); - -#if (USE_HAL_SDRAM_REGISTER_CALLBACKS == 1) -/* SDRAM callback registering/unregistering */ -HAL_StatusTypeDef HAL_SDRAM_RegisterCallback(SDRAM_HandleTypeDef *hsdram, HAL_SDRAM_CallbackIDTypeDef CallbackId, pSDRAM_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_SDRAM_UnRegisterCallback(SDRAM_HandleTypeDef *hsdram, HAL_SDRAM_CallbackIDTypeDef CallbackId); -HAL_StatusTypeDef HAL_SDRAM_RegisterDmaCallback(SDRAM_HandleTypeDef *hsdram, HAL_SDRAM_CallbackIDTypeDef CallbackId, pSDRAM_DmaCallbackTypeDef pCallback); -#endif - -/** - * @} - */ - -/** @addtogroup SDRAM_Exported_Functions_Group3 - * @{ - */ -/* SDRAM Control functions *****************************************************/ -HAL_StatusTypeDef HAL_SDRAM_WriteProtection_Enable(SDRAM_HandleTypeDef *hsdram); -HAL_StatusTypeDef HAL_SDRAM_WriteProtection_Disable(SDRAM_HandleTypeDef *hsdram); -HAL_StatusTypeDef HAL_SDRAM_SendCommand(SDRAM_HandleTypeDef *hsdram, FMC_SDRAM_CommandTypeDef *Command, uint32_t Timeout); -HAL_StatusTypeDef HAL_SDRAM_ProgramRefreshRate(SDRAM_HandleTypeDef *hsdram, uint32_t RefreshRate); -HAL_StatusTypeDef HAL_SDRAM_SetAutoRefreshNumber(SDRAM_HandleTypeDef *hsdram, uint32_t AutoRefreshNumber); -uint32_t HAL_SDRAM_GetModeStatus(SDRAM_HandleTypeDef *hsdram); -/** - * @} - */ - -/** @addtogroup SDRAM_Exported_Functions_Group4 - * @{ - */ -/* SDRAM State functions ********************************************************/ -HAL_SDRAM_StateTypeDef HAL_SDRAM_GetState(SDRAM_HandleTypeDef *hsdram); -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_SDRAM_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_smartcard.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_smartcard.h deleted file mode 100644 index 36f16c7..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_smartcard.h +++ /dev/null @@ -1,757 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_smartcard.h - * @author MCD Application Team - * @brief Header file of SMARTCARD HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_SMARTCARD_H -#define __STM32F4xx_HAL_SMARTCARD_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup SMARTCARD - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup SMARTCARD_Exported_Types SMARTCARD Exported Types - * @{ - */ - -/** - * @brief SMARTCARD Init Structure definition - */ -typedef struct -{ - uint32_t BaudRate; /*!< This member configures the SmartCard communication baud rate. - The baud rate is computed using the following formula: - - IntegerDivider = ((PCLKx) / (16 * (hsc->Init.BaudRate))) - - FractionalDivider = ((IntegerDivider - ((uint32_t) IntegerDivider)) * 16) + 0.5 */ - - uint32_t WordLength; /*!< Specifies the number of data bits transmitted or received in a frame. - This parameter can be a value of @ref SMARTCARD_Word_Length */ - - uint32_t StopBits; /*!< Specifies the number of stop bits transmitted. - This parameter can be a value of @ref SMARTCARD_Stop_Bits */ - - uint32_t Parity; /*!< Specifies the parity mode. - This parameter can be a value of @ref SMARTCARD_Parity - @note When parity is enabled, the computed parity is inserted - at the MSB position of the transmitted data (9th bit when - the word length is set to 9 data bits; 8th bit when the - word length is set to 8 data bits).*/ - - uint32_t Mode; /*!< Specifies whether the Receive or Transmit mode is enabled or disabled. - This parameter can be a value of @ref SMARTCARD_Mode */ - - uint32_t CLKPolarity; /*!< Specifies the steady state of the serial clock. - This parameter can be a value of @ref SMARTCARD_Clock_Polarity */ - - uint32_t CLKPhase; /*!< Specifies the clock transition on which the bit capture is made. - This parameter can be a value of @ref SMARTCARD_Clock_Phase */ - - uint32_t CLKLastBit; /*!< Specifies whether the clock pulse corresponding to the last transmitted - data bit (MSB) has to be output on the SCLK pin in synchronous mode. - This parameter can be a value of @ref SMARTCARD_Last_Bit */ - - uint32_t Prescaler; /*!< Specifies the SmartCard Prescaler value used for dividing the system clock - to provide the smartcard clock. The value given in the register (5 significant bits) - is multiplied by 2 to give the division factor of the source clock frequency. - This parameter can be a value of @ref SMARTCARD_Prescaler */ - - uint32_t GuardTime; /*!< Specifies the SmartCard Guard Time value in terms of number of baud clocks */ - - uint32_t NACKState; /*!< Specifies the SmartCard NACK Transmission state. - This parameter can be a value of @ref SMARTCARD_NACK_State */ -}SMARTCARD_InitTypeDef; - -/** - * @brief HAL SMARTCARD State structures definition - * @note HAL SMARTCARD State value is a combination of 2 different substates: gState and RxState. - * - gState contains SMARTCARD state information related to global Handle management - * and also information related to Tx operations. - * gState value coding follow below described bitmap : - * b7-b6 Error information - * 00 : No Error - * 01 : (Not Used) - * 10 : Timeout - * 11 : Error - * b5 IP initialization status - * 0 : Reset (IP not initialized) - * 1 : Init done (IP initialized. HAL SMARTCARD Init function already called) - * b4-b3 (not used) - * xx : Should be set to 00 - * b2 Intrinsic process state - * 0 : Ready - * 1 : Busy (IP busy with some configuration or internal operations) - * b1 (not used) - * x : Should be set to 0 - * b0 Tx state - * 0 : Ready (no Tx operation ongoing) - * 1 : Busy (Tx operation ongoing) - * - RxState contains information related to Rx operations. - * RxState value coding follow below described bitmap : - * b7-b6 (not used) - * xx : Should be set to 00 - * b5 IP initialization status - * 0 : Reset (IP not initialized) - * 1 : Init done (IP initialized) - * b4-b2 (not used) - * xxx : Should be set to 000 - * b1 Rx state - * 0 : Ready (no Rx operation ongoing) - * 1 : Busy (Rx operation ongoing) - * b0 (not used) - * x : Should be set to 0. - */ -typedef enum -{ - HAL_SMARTCARD_STATE_RESET = 0x00U, /*!< Peripheral is not yet Initialized - Value is allowed for gState and RxState */ - HAL_SMARTCARD_STATE_READY = 0x20U, /*!< Peripheral Initialized and ready for use - Value is allowed for gState and RxState */ - HAL_SMARTCARD_STATE_BUSY = 0x24U, /*!< an internal process is ongoing - Value is allowed for gState only */ - HAL_SMARTCARD_STATE_BUSY_TX = 0x21U, /*!< Data Transmission process is ongoing - Value is allowed for gState only */ - HAL_SMARTCARD_STATE_BUSY_RX = 0x22U, /*!< Data Reception process is ongoing - Value is allowed for RxState only */ - HAL_SMARTCARD_STATE_BUSY_TX_RX = 0x23U, /*!< Data Transmission and Reception process is ongoing - Not to be used for neither gState nor RxState. - Value is result of combination (Or) between gState and RxState values */ - HAL_SMARTCARD_STATE_TIMEOUT = 0xA0U, /*!< Timeout state - Value is allowed for gState only */ - HAL_SMARTCARD_STATE_ERROR = 0xE0U /*!< Error - Value is allowed for gState only */ -}HAL_SMARTCARD_StateTypeDef; - -/** - * @brief SMARTCARD handle Structure definition - */ -typedef struct __SMARTCARD_HandleTypeDef -{ - USART_TypeDef *Instance; /*!< USART registers base address */ - - SMARTCARD_InitTypeDef Init; /*!< SmartCard communication parameters */ - - uint8_t *pTxBuffPtr; /*!< Pointer to SmartCard Tx transfer Buffer */ - - uint16_t TxXferSize; /*!< SmartCard Tx Transfer size */ - - __IO uint16_t TxXferCount; /*!< SmartCard Tx Transfer Counter */ - - uint8_t *pRxBuffPtr; /*!< Pointer to SmartCard Rx transfer Buffer */ - - uint16_t RxXferSize; /*!< SmartCard Rx Transfer size */ - - __IO uint16_t RxXferCount; /*!< SmartCard Rx Transfer Counter */ - - DMA_HandleTypeDef *hdmatx; /*!< SmartCard Tx DMA Handle parameters */ - - DMA_HandleTypeDef *hdmarx; /*!< SmartCard Rx DMA Handle parameters */ - - HAL_LockTypeDef Lock; /*!< Locking object */ - - __IO HAL_SMARTCARD_StateTypeDef gState; /*!< SmartCard state information related to global Handle management - and also related to Tx operations. - This parameter can be a value of @ref HAL_SMARTCARD_StateTypeDef */ - - __IO HAL_SMARTCARD_StateTypeDef RxState; /*!< SmartCard state information related to Rx operations. - This parameter can be a value of @ref HAL_SMARTCARD_StateTypeDef */ - - __IO uint32_t ErrorCode; /*!< SmartCard Error code */ - -#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) - void (* TxCpltCallback)(struct __SMARTCARD_HandleTypeDef *hsc); /*!< SMARTCARD Tx Complete Callback */ - - void (* RxCpltCallback)(struct __SMARTCARD_HandleTypeDef *hsc); /*!< SMARTCARD Rx Complete Callback */ - - void (* ErrorCallback)(struct __SMARTCARD_HandleTypeDef *hsc); /*!< SMARTCARD Error Callback */ - - void (* AbortCpltCallback)(struct __SMARTCARD_HandleTypeDef *hsc); /*!< SMARTCARD Abort Complete Callback */ - - void (* AbortTransmitCpltCallback)(struct __SMARTCARD_HandleTypeDef *hsc); /*!< SMARTCARD Abort Transmit Complete Callback */ - - void (* AbortReceiveCpltCallback)(struct __SMARTCARD_HandleTypeDef *hsc); /*!< SMARTCARD Abort Receive Complete Callback */ - - void (* MspInitCallback)(struct __SMARTCARD_HandleTypeDef *hsc); /*!< SMARTCARD Msp Init callback */ - - void (* MspDeInitCallback)(struct __SMARTCARD_HandleTypeDef *hsc); /*!< SMARTCARD Msp DeInit callback */ -#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACKS */ - -} SMARTCARD_HandleTypeDef; - -#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) -/** - * @brief HAL SMARTCARD Callback ID enumeration definition - */ -typedef enum -{ - HAL_SMARTCARD_TX_COMPLETE_CB_ID = 0x00U, /*!< SMARTCARD Tx Complete Callback ID */ - HAL_SMARTCARD_RX_COMPLETE_CB_ID = 0x01U, /*!< SMARTCARD Rx Complete Callback ID */ - HAL_SMARTCARD_ERROR_CB_ID = 0x02U, /*!< SMARTCARD Error Callback ID */ - HAL_SMARTCARD_ABORT_COMPLETE_CB_ID = 0x03U, /*!< SMARTCARD Abort Complete Callback ID */ - HAL_SMARTCARD_ABORT_TRANSMIT_COMPLETE_CB_ID = 0x04U, /*!< SMARTCARD Abort Transmit Complete Callback ID */ - HAL_SMARTCARD_ABORT_RECEIVE_COMPLETE_CB_ID = 0x05U, /*!< SMARTCARD Abort Receive Complete Callback ID */ - - HAL_SMARTCARD_MSPINIT_CB_ID = 0x08U, /*!< SMARTCARD MspInit callback ID */ - HAL_SMARTCARD_MSPDEINIT_CB_ID = 0x09U /*!< SMARTCARD MspDeInit callback ID */ - -} HAL_SMARTCARD_CallbackIDTypeDef; - -/** - * @brief HAL SMARTCARD Callback pointer definition - */ -typedef void (*pSMARTCARD_CallbackTypeDef)(SMARTCARD_HandleTypeDef *hsc); /*!< pointer to an SMARTCARD callback function */ - -#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup SMARTCARD_Exported_Constants SMARTCARD Exported constants - * @{ - */ - -/** @defgroup SMARTCARD_Error_Code SMARTCARD Error Code - * @{ - */ -#define HAL_SMARTCARD_ERROR_NONE 0x00000000U /*!< No error */ -#define HAL_SMARTCARD_ERROR_PE 0x00000001U /*!< Parity error */ -#define HAL_SMARTCARD_ERROR_NE 0x00000002U /*!< Noise error */ -#define HAL_SMARTCARD_ERROR_FE 0x00000004U /*!< Frame error */ -#define HAL_SMARTCARD_ERROR_ORE 0x00000008U /*!< Overrun error */ -#define HAL_SMARTCARD_ERROR_DMA 0x00000010U /*!< DMA transfer error */ -#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) -#define HAL_SMARTCARD_ERROR_INVALID_CALLBACK 0x00000020U /*!< Invalid Callback error */ -#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @defgroup SMARTCARD_Word_Length SMARTCARD Word Length - * @{ - */ -#define SMARTCARD_WORDLENGTH_9B ((uint32_t)USART_CR1_M) -/** - * @} - */ - -/** @defgroup SMARTCARD_Stop_Bits SMARTCARD Number of Stop Bits - * @{ - */ -#define SMARTCARD_STOPBITS_0_5 ((uint32_t)USART_CR2_STOP_0) -#define SMARTCARD_STOPBITS_1_5 ((uint32_t)(USART_CR2_STOP_0 | USART_CR2_STOP_1)) -/** - * @} - */ - -/** @defgroup SMARTCARD_Parity SMARTCARD Parity - * @{ - */ -#define SMARTCARD_PARITY_EVEN ((uint32_t)USART_CR1_PCE) -#define SMARTCARD_PARITY_ODD ((uint32_t)(USART_CR1_PCE | USART_CR1_PS)) -/** - * @} - */ - -/** @defgroup SMARTCARD_Mode SMARTCARD Mode - * @{ - */ -#define SMARTCARD_MODE_RX ((uint32_t)USART_CR1_RE) -#define SMARTCARD_MODE_TX ((uint32_t)USART_CR1_TE) -#define SMARTCARD_MODE_TX_RX ((uint32_t)(USART_CR1_TE |USART_CR1_RE)) -/** - * @} - */ - -/** @defgroup SMARTCARD_Clock_Polarity SMARTCARD Clock Polarity - * @{ - */ -#define SMARTCARD_POLARITY_LOW 0x00000000U -#define SMARTCARD_POLARITY_HIGH ((uint32_t)USART_CR2_CPOL) -/** - * @} - */ - -/** @defgroup SMARTCARD_Clock_Phase SMARTCARD Clock Phase - * @{ - */ -#define SMARTCARD_PHASE_1EDGE 0x00000000U -#define SMARTCARD_PHASE_2EDGE ((uint32_t)USART_CR2_CPHA) -/** - * @} - */ - -/** @defgroup SMARTCARD_Last_Bit SMARTCARD Last Bit - * @{ - */ -#define SMARTCARD_LASTBIT_DISABLE 0x00000000U -#define SMARTCARD_LASTBIT_ENABLE ((uint32_t)USART_CR2_LBCL) -/** - * @} - */ - -/** @defgroup SMARTCARD_NACK_State SMARTCARD NACK State - * @{ - */ -#define SMARTCARD_NACK_ENABLE ((uint32_t)USART_CR3_NACK) -#define SMARTCARD_NACK_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup SMARTCARD_DMA_Requests SMARTCARD DMA requests - * @{ - */ -#define SMARTCARD_DMAREQ_TX ((uint32_t)USART_CR3_DMAT) -#define SMARTCARD_DMAREQ_RX ((uint32_t)USART_CR3_DMAR) -/** - * @} - */ - -/** @defgroup SMARTCARD_Prescaler SMARTCARD Prescaler - * @{ - */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV2 0x00000001U /*!< SYSCLK divided by 2 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV4 0x00000002U /*!< SYSCLK divided by 4 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV6 0x00000003U /*!< SYSCLK divided by 6 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV8 0x00000004U /*!< SYSCLK divided by 8 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV10 0x00000005U /*!< SYSCLK divided by 10 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV12 0x00000006U /*!< SYSCLK divided by 12 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV14 0x00000007U /*!< SYSCLK divided by 14 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV16 0x00000008U /*!< SYSCLK divided by 16 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV18 0x00000009U /*!< SYSCLK divided by 18 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV20 0x0000000AU /*!< SYSCLK divided by 20 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV22 0x0000000BU /*!< SYSCLK divided by 22 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV24 0x0000000CU /*!< SYSCLK divided by 24 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV26 0x0000000DU /*!< SYSCLK divided by 26 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV28 0x0000000EU /*!< SYSCLK divided by 28 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV30 0x0000000FU /*!< SYSCLK divided by 30 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV32 0x00000010U /*!< SYSCLK divided by 32 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV34 0x00000011U /*!< SYSCLK divided by 34 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV36 0x00000012U /*!< SYSCLK divided by 36 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV38 0x00000013U /*!< SYSCLK divided by 38 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV40 0x00000014U /*!< SYSCLK divided by 40 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV42 0x00000015U /*!< SYSCLK divided by 42 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV44 0x00000016U /*!< SYSCLK divided by 44 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV46 0x00000017U /*!< SYSCLK divided by 46 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV48 0x00000018U /*!< SYSCLK divided by 48 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV50 0x00000019U /*!< SYSCLK divided by 50 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV52 0x0000001AU /*!< SYSCLK divided by 52 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV54 0x0000001BU /*!< SYSCLK divided by 54 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV56 0x0000001CU /*!< SYSCLK divided by 56 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV58 0x0000001DU /*!< SYSCLK divided by 58 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV60 0x0000001EU /*!< SYSCLK divided by 60 */ -#define SMARTCARD_PRESCALER_SYSCLK_DIV62 0x0000001FU /*!< SYSCLK divided by 62 */ -/** - * @} - */ - -/** @defgroup SmartCard_Flags SMARTCARD Flags - * Elements values convention: 0xXXXX - * - 0xXXXX : Flag mask in the SR register - * @{ - */ -#define SMARTCARD_FLAG_TXE ((uint32_t)USART_SR_TXE) -#define SMARTCARD_FLAG_TC ((uint32_t)USART_SR_TC) -#define SMARTCARD_FLAG_RXNE ((uint32_t)USART_SR_RXNE) -#define SMARTCARD_FLAG_IDLE ((uint32_t)USART_SR_IDLE) -#define SMARTCARD_FLAG_ORE ((uint32_t)USART_SR_ORE) -#define SMARTCARD_FLAG_NE ((uint32_t)USART_SR_NE) -#define SMARTCARD_FLAG_FE ((uint32_t)USART_SR_FE) -#define SMARTCARD_FLAG_PE ((uint32_t)USART_SR_PE) -/** - * @} - */ - -/** @defgroup SmartCard_Interrupt_definition SMARTCARD Interrupts Definition - * Elements values convention: 0xY000XXXX - * - XXXX : Interrupt mask in the Y register - * - Y : Interrupt source register (2bits) - * - 01: CR1 register - * - 11: CR3 register - * @{ - */ -#define SMARTCARD_IT_PE ((uint32_t)(SMARTCARD_CR1_REG_INDEX << 28U | USART_CR1_PEIE)) -#define SMARTCARD_IT_TXE ((uint32_t)(SMARTCARD_CR1_REG_INDEX << 28U | USART_CR1_TXEIE)) -#define SMARTCARD_IT_TC ((uint32_t)(SMARTCARD_CR1_REG_INDEX << 28U | USART_CR1_TCIE)) -#define SMARTCARD_IT_RXNE ((uint32_t)(SMARTCARD_CR1_REG_INDEX << 28U | USART_CR1_RXNEIE)) -#define SMARTCARD_IT_IDLE ((uint32_t)(SMARTCARD_CR1_REG_INDEX << 28U | USART_CR1_IDLEIE)) -#define SMARTCARD_IT_ERR ((uint32_t)(SMARTCARD_CR3_REG_INDEX << 28U | USART_CR3_EIE)) -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup SMARTCARD_Exported_Macros SMARTCARD Exported Macros - * @{ - */ - -/** @brief Reset SMARTCARD handle gstate & RxState - * @param __HANDLE__ specifies the SMARTCARD Handle. - * SMARTCARD Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @retval None - */ -#if USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1 -#define __HAL_SMARTCARD_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->gState = HAL_SMARTCARD_STATE_RESET; \ - (__HANDLE__)->RxState = HAL_SMARTCARD_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0U) -#else -#define __HAL_SMARTCARD_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->gState = HAL_SMARTCARD_STATE_RESET; \ - (__HANDLE__)->RxState = HAL_SMARTCARD_STATE_RESET; \ - } while(0U) -#endif /*USE_HAL_SMARTCARD_REGISTER_CALLBACKS */ - -/** @brief Flush the Smartcard DR register - * @param __HANDLE__ specifies the SMARTCARD Handle. - * SMARTCARD Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @retval None - */ -#define __HAL_SMARTCARD_FLUSH_DRREGISTER(__HANDLE__) ((__HANDLE__)->Instance->DR) - -/** @brief Check whether the specified Smartcard flag is set or not. - * @param __HANDLE__ specifies the SMARTCARD Handle. - * SMARTCARD Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg SMARTCARD_FLAG_TXE: Transmit data register empty flag - * @arg SMARTCARD_FLAG_TC: Transmission Complete flag - * @arg SMARTCARD_FLAG_RXNE: Receive data register not empty flag - * @arg SMARTCARD_FLAG_IDLE: Idle Line detection flag - * @arg SMARTCARD_FLAG_ORE: Overrun Error flag - * @arg SMARTCARD_FLAG_NE: Noise Error flag - * @arg SMARTCARD_FLAG_FE: Framing Error flag - * @arg SMARTCARD_FLAG_PE: Parity Error flag - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_SMARTCARD_GET_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->SR & (__FLAG__)) == (__FLAG__)) - -/** @brief Clear the specified Smartcard pending flags. - * @param __HANDLE__ specifies the SMARTCARD Handle. - * SMARTCARD Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @param __FLAG__ specifies the flag to check. - * This parameter can be any combination of the following values: - * @arg SMARTCARD_FLAG_TC: Transmission Complete flag. - * @arg SMARTCARD_FLAG_RXNE: Receive data register not empty flag. - * - * @note PE (Parity error), FE (Framing error), NE (Noise error) and ORE (Overrun - * error) flags are cleared by software sequence: a read operation to - * USART_SR register followed by a read operation to USART_DR register. - * @note RXNE flag can be also cleared by a read to the USART_DR register. - * @note TC flag can be also cleared by software sequence: a read operation to - * USART_SR register followed by a write operation to USART_DR register. - * @note TXE flag is cleared only by a write to the USART_DR register. - * @retval None - */ -#define __HAL_SMARTCARD_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->SR = ~(__FLAG__)) - -/** @brief Clear the SMARTCARD PE pending flag. - * @param __HANDLE__ specifies the USART Handle. - * SMARTCARD Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @retval None - */ -#define __HAL_SMARTCARD_CLEAR_PEFLAG(__HANDLE__) \ - do{ \ - __IO uint32_t tmpreg = 0x00U; \ - tmpreg = (__HANDLE__)->Instance->SR; \ - tmpreg = (__HANDLE__)->Instance->DR; \ - UNUSED(tmpreg); \ - } while(0U) - -/** @brief Clear the SMARTCARD FE pending flag. - * @param __HANDLE__ specifies the USART Handle. - * SMARTCARD Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @retval None - */ -#define __HAL_SMARTCARD_CLEAR_FEFLAG(__HANDLE__) __HAL_SMARTCARD_CLEAR_PEFLAG(__HANDLE__) - -/** @brief Clear the SMARTCARD NE pending flag. - * @param __HANDLE__ specifies the USART Handle. - * SMARTCARD Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @retval None - */ -#define __HAL_SMARTCARD_CLEAR_NEFLAG(__HANDLE__) __HAL_SMARTCARD_CLEAR_PEFLAG(__HANDLE__) - -/** @brief Clear the SMARTCARD ORE pending flag. - * @param __HANDLE__ specifies the USART Handle. - * SMARTCARD Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @retval None - */ -#define __HAL_SMARTCARD_CLEAR_OREFLAG(__HANDLE__) __HAL_SMARTCARD_CLEAR_PEFLAG(__HANDLE__) - -/** @brief Clear the SMARTCARD IDLE pending flag. - * @param __HANDLE__ specifies the USART Handle. - * SMARTCARD Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @retval None - */ -#define __HAL_SMARTCARD_CLEAR_IDLEFLAG(__HANDLE__) __HAL_SMARTCARD_CLEAR_PEFLAG(__HANDLE__) - -/** @brief Enable the specified SmartCard interrupt. - * @param __HANDLE__ specifies the SMARTCARD Handle. - * SMARTCARD Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @param __INTERRUPT__ specifies the SMARTCARD interrupt to enable. - * This parameter can be one of the following values: - * @arg SMARTCARD_IT_TXE: Transmit Data Register empty interrupt - * @arg SMARTCARD_IT_TC: Transmission complete interrupt - * @arg SMARTCARD_IT_RXNE: Receive Data register not empty interrupt - * @arg SMARTCARD_IT_IDLE: Idle line detection interrupt - * @arg SMARTCARD_IT_PE: Parity Error interrupt - * @arg SMARTCARD_IT_ERR: Error interrupt(Frame error, noise error, overrun error) - * @retval None - */ -#define __HAL_SMARTCARD_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((((__INTERRUPT__) >> 28U) == SMARTCARD_CR1_REG_INDEX)? ((__HANDLE__)->Instance->CR1 |= ((__INTERRUPT__) & SMARTCARD_IT_MASK)): \ - ((__HANDLE__)->Instance->CR3 |= ((__INTERRUPT__) & SMARTCARD_IT_MASK))) - -/** @brief Disable the specified SmartCard interrupt. - * @param __HANDLE__ specifies the SMARTCARD Handle. - * SMARTCARD Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @param __INTERRUPT__ specifies the SMARTCARD interrupt to disable. - * This parameter can be one of the following values: - * @arg SMARTCARD_IT_TXE: Transmit Data Register empty interrupt - * @arg SMARTCARD_IT_TC: Transmission complete interrupt - * @arg SMARTCARD_IT_RXNE: Receive Data register not empty interrupt - * @arg SMARTCARD_IT_IDLE: Idle line detection interrupt - * @arg SMARTCARD_IT_PE: Parity Error interrupt - * @arg SMARTCARD_IT_ERR: Error interrupt(Frame error, noise error, overrun error) - * @retval None - */ -#define __HAL_SMARTCARD_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((((__INTERRUPT__) >> 28U) == SMARTCARD_CR1_REG_INDEX)? ((__HANDLE__)->Instance->CR1 &= ~((__INTERRUPT__) & SMARTCARD_IT_MASK)): \ - ((__HANDLE__)->Instance->CR3 &= ~ ((__INTERRUPT__) & SMARTCARD_IT_MASK))) - -/** @brief Checks whether the specified SmartCard interrupt has occurred or not. - * @param __HANDLE__ specifies the SmartCard Handle. - * @param __IT__ specifies the SMARTCARD interrupt source to check. - * This parameter can be one of the following values: - * @arg SMARTCARD_IT_TXE: Transmit Data Register empty interrupt - * @arg SMARTCARD_IT_TC: Transmission complete interrupt - * @arg SMARTCARD_IT_RXNE: Receive Data register not empty interrupt - * @arg SMARTCARD_IT_IDLE: Idle line detection interrupt - * @arg SMARTCARD_IT_ERR: Error interrupt - * @arg SMARTCARD_IT_PE: Parity Error interrupt - * @retval The new state of __IT__ (TRUE or FALSE). - */ -#define __HAL_SMARTCARD_GET_IT_SOURCE(__HANDLE__, __IT__) (((((__IT__) >> 28U) == SMARTCARD_CR1_REG_INDEX)? (__HANDLE__)->Instance->CR1: (__HANDLE__)->Instance->CR3) & (((uint32_t)(__IT__)) & SMARTCARD_IT_MASK)) - -/** @brief Macro to enable the SMARTCARD's one bit sample method - * @param __HANDLE__ specifies the SMARTCARD Handle. - * @retval None - */ -#define __HAL_SMARTCARD_ONE_BIT_SAMPLE_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR3|= USART_CR3_ONEBIT) - -/** @brief Macro to disable the SMARTCARD's one bit sample method - * @param __HANDLE__ specifies the SMARTCARD Handle. - * @retval None - */ -#define __HAL_SMARTCARD_ONE_BIT_SAMPLE_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR3 &= (uint16_t)~((uint16_t)USART_CR3_ONEBIT)) - -/** @brief Enable the USART associated to the SMARTCARD Handle - * @param __HANDLE__ specifies the SMARTCARD Handle. - * SMARTCARD Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @retval None - */ -#define __HAL_SMARTCARD_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1 |= USART_CR1_UE) - -/** @brief Disable the USART associated to the SMARTCARD Handle - * @param __HANDLE__ specifies the SMARTCARD Handle. - * SMARTCARD Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @retval None - */ -#define __HAL_SMARTCARD_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1 &= ~USART_CR1_UE) - -/** @brief Macros to enable the SmartCard DMA request. - * @param __HANDLE__ specifies the SmartCard Handle. - * @param __REQUEST__ specifies the SmartCard DMA request. - * This parameter can be one of the following values: - * @arg SMARTCARD_DMAREQ_TX: SmartCard DMA transmit request - * @arg SMARTCARD_DMAREQ_RX: SmartCard DMA receive request - * @retval None - */ -#define __HAL_SMARTCARD_DMA_REQUEST_ENABLE(__HANDLE__, __REQUEST__) ((__HANDLE__)->Instance->CR3 |= (__REQUEST__)) - -/** @brief Macros to disable the SmartCard DMA request. - * @param __HANDLE__ specifies the SmartCard Handle. - * @param __REQUEST__ specifies the SmartCard DMA request. - * This parameter can be one of the following values: - * @arg SMARTCARD_DMAREQ_TX: SmartCard DMA transmit request - * @arg SMARTCARD_DMAREQ_RX: SmartCard DMA receive request - * @retval None - */ -#define __HAL_SMARTCARD_DMA_REQUEST_DISABLE(__HANDLE__, __REQUEST__) ((__HANDLE__)->Instance->CR3 &= ~(__REQUEST__)) - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup SMARTCARD_Exported_Functions - * @{ - */ - -/** @addtogroup SMARTCARD_Exported_Functions_Group1 - * @{ - */ -/* Initialization/de-initialization functions **********************************/ -HAL_StatusTypeDef HAL_SMARTCARD_Init(SMARTCARD_HandleTypeDef *hsc); -HAL_StatusTypeDef HAL_SMARTCARD_ReInit(SMARTCARD_HandleTypeDef *hsc); -HAL_StatusTypeDef HAL_SMARTCARD_DeInit(SMARTCARD_HandleTypeDef *hsc); -void HAL_SMARTCARD_MspInit(SMARTCARD_HandleTypeDef *hsc); -void HAL_SMARTCARD_MspDeInit(SMARTCARD_HandleTypeDef *hsc); -#if (USE_HAL_SMARTCARD_REGISTER_CALLBACKS == 1) -/* Callbacks Register/UnRegister functions ***********************************/ -HAL_StatusTypeDef HAL_SMARTCARD_RegisterCallback(SMARTCARD_HandleTypeDef *hsc, HAL_SMARTCARD_CallbackIDTypeDef CallbackID, pSMARTCARD_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_SMARTCARD_UnRegisterCallback(SMARTCARD_HandleTypeDef *hsc, HAL_SMARTCARD_CallbackIDTypeDef CallbackID); -#endif /* USE_HAL_SMARTCARD_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @addtogroup SMARTCARD_Exported_Functions_Group2 - * @{ - */ -/* IO operation functions *******************************************************/ -HAL_StatusTypeDef HAL_SMARTCARD_Transmit(SMARTCARD_HandleTypeDef *hsc, uint8_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_SMARTCARD_Receive(SMARTCARD_HandleTypeDef *hsc, uint8_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_SMARTCARD_Transmit_IT(SMARTCARD_HandleTypeDef *hsc, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_SMARTCARD_Receive_IT(SMARTCARD_HandleTypeDef *hsc, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_SMARTCARD_Transmit_DMA(SMARTCARD_HandleTypeDef *hsc, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_SMARTCARD_Receive_DMA(SMARTCARD_HandleTypeDef *hsc, uint8_t *pData, uint16_t Size); -/* Transfer Abort functions */ -HAL_StatusTypeDef HAL_SMARTCARD_Abort(SMARTCARD_HandleTypeDef *hsc); -HAL_StatusTypeDef HAL_SMARTCARD_AbortTransmit(SMARTCARD_HandleTypeDef *hsc); -HAL_StatusTypeDef HAL_SMARTCARD_AbortReceive(SMARTCARD_HandleTypeDef *hsc); -HAL_StatusTypeDef HAL_SMARTCARD_Abort_IT(SMARTCARD_HandleTypeDef *hsc); -HAL_StatusTypeDef HAL_SMARTCARD_AbortTransmit_IT(SMARTCARD_HandleTypeDef *hsc); -HAL_StatusTypeDef HAL_SMARTCARD_AbortReceive_IT(SMARTCARD_HandleTypeDef *hsc); - -void HAL_SMARTCARD_IRQHandler(SMARTCARD_HandleTypeDef *hsc); -void HAL_SMARTCARD_TxCpltCallback(SMARTCARD_HandleTypeDef *hsc); -void HAL_SMARTCARD_RxCpltCallback(SMARTCARD_HandleTypeDef *hsc); -void HAL_SMARTCARD_ErrorCallback(SMARTCARD_HandleTypeDef *hsc); -void HAL_SMARTCARD_AbortCpltCallback(SMARTCARD_HandleTypeDef *hsc); -void HAL_SMARTCARD_AbortTransmitCpltCallback(SMARTCARD_HandleTypeDef *hsc); -void HAL_SMARTCARD_AbortReceiveCpltCallback(SMARTCARD_HandleTypeDef *hsc); -/** - * @} - */ - -/** @addtogroup SMARTCARD_Exported_Functions_Group3 - * @{ - */ -/* Peripheral State functions **************************************************/ -HAL_SMARTCARD_StateTypeDef HAL_SMARTCARD_GetState(SMARTCARD_HandleTypeDef *hsc); -uint32_t HAL_SMARTCARD_GetError(SMARTCARD_HandleTypeDef *hsc); -/** - * @} - */ - -/** - * @} - */ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup SMARTCARD_Private_Constants SMARTCARD Private Constants - * @{ - */ - -/** @brief SMARTCARD interruptions flag mask - * - */ -#define SMARTCARD_IT_MASK ((uint32_t) USART_CR1_PEIE | USART_CR1_TXEIE | USART_CR1_TCIE | USART_CR1_RXNEIE | \ - USART_CR1_IDLEIE | USART_CR3_EIE ) - -#define SMARTCARD_CR1_REG_INDEX 1U -#define SMARTCARD_CR3_REG_INDEX 3U -/** - * @} - */ - -/* Private macros --------------------------------------------------------*/ -/** @defgroup SMARTCARD_Private_Macros SMARTCARD Private Macros - * @{ - */ -#define IS_SMARTCARD_WORD_LENGTH(LENGTH) ((LENGTH) == SMARTCARD_WORDLENGTH_9B) -#define IS_SMARTCARD_STOPBITS(STOPBITS) (((STOPBITS) == SMARTCARD_STOPBITS_0_5) || \ - ((STOPBITS) == SMARTCARD_STOPBITS_1_5)) -#define IS_SMARTCARD_PARITY(PARITY) (((PARITY) == SMARTCARD_PARITY_EVEN) || \ - ((PARITY) == SMARTCARD_PARITY_ODD)) -#define IS_SMARTCARD_MODE(MODE) ((((MODE) & 0x0000FFF3U) == 0x00U) && ((MODE) != 0x000000U)) -#define IS_SMARTCARD_POLARITY(CPOL) (((CPOL) == SMARTCARD_POLARITY_LOW) || ((CPOL) == SMARTCARD_POLARITY_HIGH)) -#define IS_SMARTCARD_PHASE(CPHA) (((CPHA) == SMARTCARD_PHASE_1EDGE) || ((CPHA) == SMARTCARD_PHASE_2EDGE)) -#define IS_SMARTCARD_LASTBIT(LASTBIT) (((LASTBIT) == SMARTCARD_LASTBIT_DISABLE) || \ - ((LASTBIT) == SMARTCARD_LASTBIT_ENABLE)) -#define IS_SMARTCARD_NACK_STATE(NACK) (((NACK) == SMARTCARD_NACK_ENABLE) || \ - ((NACK) == SMARTCARD_NACK_DISABLE)) -#define IS_SMARTCARD_BAUDRATE(BAUDRATE) ((BAUDRATE) < 10500001U) - -#define SMARTCARD_DIV(__PCLK__, __BAUD__) ((uint32_t)((((uint64_t)(__PCLK__))*25U)/(4U*((uint64_t)(__BAUD__))))) -#define SMARTCARD_DIVMANT(__PCLK__, __BAUD__) (SMARTCARD_DIV((__PCLK__), (__BAUD__))/100U) -#define SMARTCARD_DIVFRAQ(__PCLK__, __BAUD__) ((((SMARTCARD_DIV((__PCLK__), (__BAUD__)) - (SMARTCARD_DIVMANT((__PCLK__), (__BAUD__)) * 100U)) * 16U) + 50U) / 100U) -/* SMARTCARD BRR = mantissa + overflow + fraction - = (SMARTCARD DIVMANT << 4) + (SMARTCARD DIVFRAQ & 0xF0) + (SMARTCARD DIVFRAQ & 0x0FU) */ -#define SMARTCARD_BRR(__PCLK__, __BAUD__) (((SMARTCARD_DIVMANT((__PCLK__), (__BAUD__)) << 4U) + \ - (SMARTCARD_DIVFRAQ((__PCLK__), (__BAUD__)) & 0xF0U)) + \ - (SMARTCARD_DIVFRAQ((__PCLK__), (__BAUD__)) & 0x0FU)) - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup SMARTCARD_Private_Functions SMARTCARD Private Functions - * @{ - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_SMARTCARD_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_smbus.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_smbus.h deleted file mode 100644 index 056a600..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_smbus.h +++ /dev/null @@ -1,733 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_smbus.h - * @author MCD Application Team - * @brief Header file of SMBUS HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_SMBUS_H -#define __STM32F4xx_HAL_SMBUS_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup SMBUS - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup SMBUS_Exported_Types SMBUS Exported Types - * @{ - */ - -/** - * @brief SMBUS Configuration Structure definition - */ -typedef struct -{ - uint32_t ClockSpeed; /*!< Specifies the clock frequency. - This parameter must be set to a value lower than 100kHz */ - - uint32_t AnalogFilter; /*!< Specifies if Analog Filter is enable or not. - This parameter can be a value of @ref SMBUS_Analog_Filter */ - - uint32_t OwnAddress1; /*!< Specifies the first device own address. - This parameter can be a 7-bit or 10-bit address. */ - - uint32_t AddressingMode; /*!< Specifies if 7-bit or 10-bit addressing mode is selected. - This parameter can be a value of @ref SMBUS_addressing_mode */ - - uint32_t DualAddressMode; /*!< Specifies if dual addressing mode is selected. - This parameter can be a value of @ref SMBUS_dual_addressing_mode */ - - uint32_t OwnAddress2; /*!< Specifies the second device own address if dual addressing mode is - selected. This parameter can be a 7-bit address. */ - - uint32_t GeneralCallMode; /*!< Specifies if general call mode is selected. - This parameter can be a value of @ref SMBUS_general_call_addressing_mode */ - - uint32_t NoStretchMode; /*!< Specifies if nostretch mode is selected. - This parameter can be a value of @ref SMBUS_nostretch_mode */ - - uint32_t PacketErrorCheckMode; /*!< Specifies if Packet Error Check mode is selected. - This parameter can be a value of @ref SMBUS_packet_error_check_mode */ - - uint32_t PeripheralMode; /*!< Specifies which mode of Periphal is selected. - This parameter can be a value of @ref SMBUS_peripheral_mode */ - -} SMBUS_InitTypeDef; - -/** - * @brief HAL State structure definition - * @note HAL SMBUS State value coding follow below described bitmap : - * b7-b6 Error information - * 00 : No Error - * 01 : Abort (Abort user request on going) - * 10 : Timeout - * 11 : Error - * b5 IP initialisation status - * 0 : Reset (IP not initialized) - * 1 : Init done (IP initialized and ready to use. HAL SMBUS Init function called) - * b4 (not used) - * x : Should be set to 0 - * b3 - * 0 : Ready or Busy (No Listen mode ongoing) - * 1 : Listen (IP in Address Listen Mode) - * b2 Intrinsic process state - * 0 : Ready - * 1 : Busy (IP busy with some configuration or internal operations) - * b1 Rx state - * 0 : Ready (no Rx operation ongoing) - * 1 : Busy (Rx operation ongoing) - * b0 Tx state - * 0 : Ready (no Tx operation ongoing) - * 1 : Busy (Tx operation ongoing) - */ -typedef enum -{ - - HAL_SMBUS_STATE_RESET = 0x00U, /*!< Peripheral is not yet Initialized */ - HAL_SMBUS_STATE_READY = 0x20U, /*!< Peripheral Initialized and ready for use */ - HAL_SMBUS_STATE_BUSY = 0x24U, /*!< An internal process is ongoing */ - HAL_SMBUS_STATE_BUSY_TX = 0x21U, /*!< Data Transmission process is ongoing */ - HAL_SMBUS_STATE_BUSY_RX = 0x22U, /*!< Data Reception process is ongoing */ - HAL_SMBUS_STATE_LISTEN = 0x28U, /*!< Address Listen Mode is ongoing */ - HAL_SMBUS_STATE_BUSY_TX_LISTEN = 0x29U, /*!< Address Listen Mode and Data Transmission - process is ongoing */ - HAL_SMBUS_STATE_BUSY_RX_LISTEN = 0x2AU, /*!< Address Listen Mode and Data Reception - process is ongoing */ - HAL_SMBUS_STATE_ABORT = 0x60U, /*!< Abort user request ongoing */ - HAL_SMBUS_STATE_TIMEOUT = 0xA0U, /*!< Timeout state */ - HAL_SMBUS_STATE_ERROR = 0xE0U /*!< Error */ -} HAL_SMBUS_StateTypeDef; - -/** - * @brief HAL Mode structure definition - * @note HAL SMBUS Mode value coding follow below described bitmap : - * b7 (not used) - * x : Should be set to 0 - * b6 (not used) - * x : Should be set to 0 - * b5 - * 0 : None - * 1 : Slave (HAL SMBUS communication is in Slave/Device Mode) - * b4 - * 0 : None - * 1 : Master (HAL SMBUS communication is in Master/Host Mode) - * b3-b2-b1-b0 (not used) - * xxxx : Should be set to 0000 - */ -typedef enum -{ - HAL_SMBUS_MODE_NONE = 0x00U, /*!< No SMBUS communication on going */ - HAL_SMBUS_MODE_MASTER = 0x10U, /*!< SMBUS communication is in Master Mode */ - HAL_SMBUS_MODE_SLAVE = 0x20U, /*!< SMBUS communication is in Slave Mode */ - -} HAL_SMBUS_ModeTypeDef; - -/** - * @brief SMBUS handle Structure definition - */ -typedef struct __SMBUS_HandleTypeDef -{ - I2C_TypeDef *Instance; /*!< SMBUS registers base address */ - - SMBUS_InitTypeDef Init; /*!< SMBUS communication parameters */ - - uint8_t *pBuffPtr; /*!< Pointer to SMBUS transfer buffer */ - - uint16_t XferSize; /*!< SMBUS transfer size */ - - __IO uint16_t XferCount; /*!< SMBUS transfer counter */ - - __IO uint32_t XferOptions; /*!< SMBUS transfer options this parameter can - be a value of @ref SMBUS_OPTIONS */ - - __IO uint32_t PreviousState; /*!< SMBUS communication Previous state and mode - context for internal usage */ - - HAL_LockTypeDef Lock; /*!< SMBUS locking object */ - - __IO HAL_SMBUS_StateTypeDef State; /*!< SMBUS communication state */ - - __IO HAL_SMBUS_ModeTypeDef Mode; /*!< SMBUS communication mode */ - - __IO uint32_t ErrorCode; /*!< SMBUS Error code */ - - __IO uint32_t Devaddress; /*!< SMBUS Target device address */ - - __IO uint32_t EventCount; /*!< SMBUS Event counter */ - - uint8_t XferPEC; /*!< SMBUS PEC data in reception mode */ - -#if (USE_HAL_SMBUS_REGISTER_CALLBACKS == 1) - void (* MasterTxCpltCallback)(struct __SMBUS_HandleTypeDef *hsmbus); /*!< SMBUS Master Tx Transfer completed callback */ - void (* MasterRxCpltCallback)(struct __SMBUS_HandleTypeDef *hsmbus); /*!< SMBUS Master Rx Transfer completed callback */ - void (* SlaveTxCpltCallback)(struct __SMBUS_HandleTypeDef *hsmbus); /*!< SMBUS Slave Tx Transfer completed callback */ - void (* SlaveRxCpltCallback)(struct __SMBUS_HandleTypeDef *hsmbus); /*!< SMBUS Slave Rx Transfer completed callback */ - void (* ListenCpltCallback)(struct __SMBUS_HandleTypeDef *hsmbus); /*!< SMBUS Listen Complete callback */ - void (* MemTxCpltCallback)(struct __SMBUS_HandleTypeDef *hsmbus); /*!< SMBUS Memory Tx Transfer completed callback */ - void (* MemRxCpltCallback)(struct __SMBUS_HandleTypeDef *hsmbus); /*!< SMBUS Memory Rx Transfer completed callback */ - void (* ErrorCallback)(struct __SMBUS_HandleTypeDef *hsmbus); /*!< SMBUS Error callback */ - void (* AbortCpltCallback)(struct __SMBUS_HandleTypeDef *hsmbus); /*!< SMBUS Abort callback */ - void (* AddrCallback)(struct __SMBUS_HandleTypeDef *hsmbus, uint8_t TransferDirection, uint16_t AddrMatchCode); /*!< SMBUS Slave Address Match callback */ - void (* MspInitCallback)(struct __SMBUS_HandleTypeDef *hsmbus); /*!< SMBUS Msp Init callback */ - void (* MspDeInitCallback)(struct __SMBUS_HandleTypeDef *hsmbus); /*!< SMBUS Msp DeInit callback */ - -#endif /* USE_HAL_SMBUS_REGISTER_CALLBACKS */ -} SMBUS_HandleTypeDef; - -#if (USE_HAL_SMBUS_REGISTER_CALLBACKS == 1) -/** - * @brief HAL SMBUS Callback ID enumeration definition - */ -typedef enum -{ - HAL_SMBUS_MASTER_TX_COMPLETE_CB_ID = 0x00U, /*!< SMBUS Master Tx Transfer completed callback ID */ - HAL_SMBUS_MASTER_RX_COMPLETE_CB_ID = 0x01U, /*!< SMBUS Master Rx Transfer completed callback ID */ - HAL_SMBUS_SLAVE_TX_COMPLETE_CB_ID = 0x02U, /*!< SMBUS Slave Tx Transfer completed callback ID */ - HAL_SMBUS_SLAVE_RX_COMPLETE_CB_ID = 0x03U, /*!< SMBUS Slave Rx Transfer completed callback ID */ - HAL_SMBUS_LISTEN_COMPLETE_CB_ID = 0x04U, /*!< SMBUS Listen Complete callback ID */ - HAL_SMBUS_ERROR_CB_ID = 0x07U, /*!< SMBUS Error callback ID */ - HAL_SMBUS_ABORT_CB_ID = 0x08U, /*!< SMBUS Abort callback ID */ - HAL_SMBUS_MSPINIT_CB_ID = 0x09U, /*!< SMBUS Msp Init callback ID */ - HAL_SMBUS_MSPDEINIT_CB_ID = 0x0AU /*!< SMBUS Msp DeInit callback ID */ - -} HAL_SMBUS_CallbackIDTypeDef; - -/** - * @brief HAL SMBUS Callback pointer definition - */ -typedef void (*pSMBUS_CallbackTypeDef)(SMBUS_HandleTypeDef *hsmbus); /*!< pointer to an I2C callback function */ -typedef void (*pSMBUS_AddrCallbackTypeDef)(SMBUS_HandleTypeDef *hsmbus, uint8_t TransferDirection, uint16_t AddrMatchCode); /*!< pointer to an I2C Address Match callback function */ - -#endif /* USE_HAL_SMBUS_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup SMBUS_Exported_Constants SMBUS Exported Constants - * @{ - */ - -/** @defgroup SMBUS_Error_Code_definition SMBUS Error Code - * @brief SMBUS Error Code - * @{ - */ -#define HAL_SMBUS_ERROR_NONE 0x00000000U /*!< No error */ -#define HAL_SMBUS_ERROR_BERR 0x00000001U /*!< BERR error */ -#define HAL_SMBUS_ERROR_ARLO 0x00000002U /*!< ARLO error */ -#define HAL_SMBUS_ERROR_AF 0x00000004U /*!< AF error */ -#define HAL_SMBUS_ERROR_OVR 0x00000008U /*!< OVR error */ -#define HAL_SMBUS_ERROR_TIMEOUT 0x00000010U /*!< Timeout Error */ -#define HAL_SMBUS_ERROR_ALERT 0x00000020U /*!< Alert error */ -#define HAL_SMBUS_ERROR_PECERR 0x00000040U /*!< PEC error */ -#if (USE_HAL_SMBUS_REGISTER_CALLBACKS == 1) -#define HAL_SMBUS_ERROR_INVALID_CALLBACK 0x00000080U /*!< Invalid Callback error */ -#endif /* USE_HAL_SMBUS_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @defgroup SMBUS_Analog_Filter SMBUS Analog Filter - * @{ - */ -#define SMBUS_ANALOGFILTER_ENABLE 0x00000000U -#define SMBUS_ANALOGFILTER_DISABLE I2C_FLTR_ANOFF -/** - * @} - */ - -/** @defgroup SMBUS_addressing_mode SMBUS addressing mode - * @{ - */ -#define SMBUS_ADDRESSINGMODE_7BIT 0x00004000U -#define SMBUS_ADDRESSINGMODE_10BIT (I2C_OAR1_ADDMODE | 0x00004000U) -/** - * @} - */ - -/** @defgroup SMBUS_dual_addressing_mode SMBUS dual addressing mode - * @{ - */ -#define SMBUS_DUALADDRESS_DISABLE 0x00000000U -#define SMBUS_DUALADDRESS_ENABLE I2C_OAR2_ENDUAL -/** - * @} - */ - -/** @defgroup SMBUS_general_call_addressing_mode SMBUS general call addressing mode - * @{ - */ -#define SMBUS_GENERALCALL_DISABLE 0x00000000U -#define SMBUS_GENERALCALL_ENABLE I2C_CR1_ENGC -/** - * @} - */ - -/** @defgroup SMBUS_nostretch_mode SMBUS nostretch mode - * @{ - */ -#define SMBUS_NOSTRETCH_DISABLE 0x00000000U -#define SMBUS_NOSTRETCH_ENABLE I2C_CR1_NOSTRETCH -/** - * @} - */ - -/** @defgroup SMBUS_packet_error_check_mode SMBUS packet error check mode - * @{ - */ -#define SMBUS_PEC_DISABLE 0x00000000U -#define SMBUS_PEC_ENABLE I2C_CR1_ENPEC -/** - * @} - */ - -/** @defgroup SMBUS_peripheral_mode SMBUS peripheral mode -* @{ -*/ -#define SMBUS_PERIPHERAL_MODE_SMBUS_HOST (uint32_t)(I2C_CR1_SMBUS | I2C_CR1_SMBTYPE | I2C_CR1_ENARP) -#define SMBUS_PERIPHERAL_MODE_SMBUS_SLAVE I2C_CR1_SMBUS -#define SMBUS_PERIPHERAL_MODE_SMBUS_SLAVE_ARP (uint32_t)(I2C_CR1_SMBUS | I2C_CR1_ENARP) -/** -* @} -*/ - -/** @defgroup SMBUS_XferDirection_definition SMBUS XferDirection definition - * @{ - */ -#define SMBUS_DIRECTION_RECEIVE 0x00000000U -#define SMBUS_DIRECTION_TRANSMIT 0x00000001U -/** - * @} - */ - -/** @defgroup SMBUS_XferOptions_definition SMBUS XferOptions definition - * @{ - */ -#define SMBUS_FIRST_FRAME 0x00000001U -#define SMBUS_NEXT_FRAME 0x00000002U -#define SMBUS_FIRST_AND_LAST_FRAME_NO_PEC 0x00000003U -#define SMBUS_LAST_FRAME_NO_PEC 0x00000004U -#define SMBUS_FIRST_AND_LAST_FRAME_WITH_PEC 0x00000005U -#define SMBUS_LAST_FRAME_WITH_PEC 0x00000006U -/** - * @} - */ - -/** @defgroup SMBUS_Interrupt_configuration_definition SMBUS Interrupt configuration definition - * @{ - */ -#define SMBUS_IT_BUF I2C_CR2_ITBUFEN -#define SMBUS_IT_EVT I2C_CR2_ITEVTEN -#define SMBUS_IT_ERR I2C_CR2_ITERREN -/** - * @} - */ - -/** @defgroup SMBUS_Flag_definition SMBUS Flag definition - * @{ - */ -#define SMBUS_FLAG_SMBALERT 0x00018000U -#define SMBUS_FLAG_TIMEOUT 0x00014000U -#define SMBUS_FLAG_PECERR 0x00011000U -#define SMBUS_FLAG_OVR 0x00010800U -#define SMBUS_FLAG_AF 0x00010400U -#define SMBUS_FLAG_ARLO 0x00010200U -#define SMBUS_FLAG_BERR 0x00010100U -#define SMBUS_FLAG_TXE 0x00010080U -#define SMBUS_FLAG_RXNE 0x00010040U -#define SMBUS_FLAG_STOPF 0x00010010U -#define SMBUS_FLAG_ADD10 0x00010008U -#define SMBUS_FLAG_BTF 0x00010004U -#define SMBUS_FLAG_ADDR 0x00010002U -#define SMBUS_FLAG_SB 0x00010001U -#define SMBUS_FLAG_DUALF 0x00100080U -#define SMBUS_FLAG_SMBHOST 0x00100040U -#define SMBUS_FLAG_SMBDEFAULT 0x00100020U -#define SMBUS_FLAG_GENCALL 0x00100010U -#define SMBUS_FLAG_TRA 0x00100004U -#define SMBUS_FLAG_BUSY 0x00100002U -#define SMBUS_FLAG_MSL 0x00100001U -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup SMBUS_Exported_Macros SMBUS Exported Macros - * @{ - */ - -/** @brief Reset SMBUS handle state - * @param __HANDLE__ specifies the SMBUS Handle. - * This parameter can be SMBUS where x: 1, 2, or 3 to select the SMBUS peripheral. - * @retval None - */ -#if (USE_HAL_SMBUS_REGISTER_CALLBACKS == 1) -#define __HAL_SMBUS_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->State = HAL_SMBUS_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_SMBUS_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_SMBUS_STATE_RESET) -#endif - -/** @brief Enable or disable the specified SMBUS interrupts. - * @param __HANDLE__ specifies the SMBUS Handle. - * This parameter can be SMBUS where x: 1, 2, or 3 to select the SMBUS peripheral. - * @param __INTERRUPT__ specifies the interrupt source to enable or disable. - * This parameter can be one of the following values: - * @arg SMBUS_IT_BUF: Buffer interrupt enable - * @arg SMBUS_IT_EVT: Event interrupt enable - * @arg SMBUS_IT_ERR: Error interrupt enable - * @retval None - */ -#define __HAL_SMBUS_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR2 |= (__INTERRUPT__)) -#define __HAL_SMBUS_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->CR2 &= (~(__INTERRUPT__))) - -/** @brief Checks if the specified SMBUS interrupt source is enabled or disabled. - * @param __HANDLE__ specifies the SMBUS Handle. - * This parameter can be SMBUS where x: 1, 2, or 3 to select the SMBUS peripheral. - * @param __INTERRUPT__ specifies the SMBUS interrupt source to check. - * This parameter can be one of the following values: - * @arg SMBUS_IT_BUF: Buffer interrupt enable - * @arg SMBUS_IT_EVT: Event interrupt enable - * @arg SMBUS_IT_ERR: Error interrupt enable - * @retval The new state of __INTERRUPT__ (TRUE or FALSE). - */ -#define __HAL_SMBUS_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((((__HANDLE__)->Instance->CR2 & (__INTERRUPT__)) == (__INTERRUPT__)) ? SET : RESET) - -/** @brief Checks whether the specified SMBUS flag is set or not. - * @param __HANDLE__ specifies the SMBUS Handle. - * This parameter can be SMBUS where x: 1, 2, or 3 to select the SMBUS peripheral. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg SMBUS_FLAG_SMBALERT: SMBus Alert flag - * @arg SMBUS_FLAG_TIMEOUT: Timeout or Tlow error flag - * @arg SMBUS_FLAG_PECERR: PEC error in reception flag - * @arg SMBUS_FLAG_OVR: Overrun/Underrun flag - * @arg SMBUS_FLAG_AF: Acknowledge failure flag - * @arg SMBUS_FLAG_ARLO: Arbitration lost flag - * @arg SMBUS_FLAG_BERR: Bus error flag - * @arg SMBUS_FLAG_TXE: Data register empty flag - * @arg SMBUS_FLAG_RXNE: Data register not empty flag - * @arg SMBUS_FLAG_STOPF: Stop detection flag - * @arg SMBUS_FLAG_ADD10: 10-bit header sent flag - * @arg SMBUS_FLAG_BTF: Byte transfer finished flag - * @arg SMBUS_FLAG_ADDR: Address sent flag - * Address matched flag - * @arg SMBUS_FLAG_SB: Start bit flag - * @arg SMBUS_FLAG_DUALF: Dual flag - * @arg SMBUS_FLAG_SMBHOST: SMBus host header - * @arg SMBUS_FLAG_SMBDEFAULT: SMBus default header - * @arg SMBUS_FLAG_GENCALL: General call header flag - * @arg SMBUS_FLAG_TRA: Transmitter/Receiver flag - * @arg SMBUS_FLAG_BUSY: Bus busy flag - * @arg SMBUS_FLAG_MSL: Master/Slave flag - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_SMBUS_GET_FLAG(__HANDLE__, __FLAG__) ((((uint8_t)((__FLAG__) >> 16U)) == 0x01U)?((((__HANDLE__)->Instance->SR1) & ((__FLAG__) & SMBUS_FLAG_MASK)) == ((__FLAG__) & SMBUS_FLAG_MASK)): \ - ((((__HANDLE__)->Instance->SR2) & ((__FLAG__) & SMBUS_FLAG_MASK)) == ((__FLAG__) & SMBUS_FLAG_MASK))) - -/** @brief Clears the SMBUS pending flags which are cleared by writing 0 in a specific bit. - * @param __HANDLE__ specifies the SMBUS Handle. - * This parameter can be SMBUS where x: 1, 2, or 3 to select the SMBUS peripheral. - * @param __FLAG__ specifies the flag to clear. - * This parameter can be any combination of the following values: - * @arg SMBUS_FLAG_SMBALERT: SMBus Alert flag - * @arg SMBUS_FLAG_TIMEOUT: Timeout or Tlow error flag - * @arg SMBUS_FLAG_PECERR: PEC error in reception flag - * @arg SMBUS_FLAG_OVR: Overrun/Underrun flag (Slave mode) - * @arg SMBUS_FLAG_AF: Acknowledge failure flag - * @arg SMBUS_FLAG_ARLO: Arbitration lost flag (Master mode) - * @arg SMBUS_FLAG_BERR: Bus error flag - * @retval None - */ -#define __HAL_SMBUS_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->SR1 = ~((__FLAG__) & SMBUS_FLAG_MASK)) - -/** @brief Clears the SMBUS ADDR pending flag. - * @param __HANDLE__ specifies the SMBUS Handle. - * This parameter can be SMBUS where x: 1, 2, or 3 to select the SMBUS peripheral. - * @retval None - */ -#define __HAL_SMBUS_CLEAR_ADDRFLAG(__HANDLE__) \ - do{ \ - __IO uint32_t tmpreg = 0x00U; \ - tmpreg = (__HANDLE__)->Instance->SR1; \ - tmpreg = (__HANDLE__)->Instance->SR2; \ - UNUSED(tmpreg); \ - } while(0) - -/** @brief Clears the SMBUS STOPF pending flag. - * @param __HANDLE__ specifies the SMBUS Handle. - * This parameter can be SMBUS where x: 1, 2, or 3 to select the SMBUS peripheral. - * @retval None - */ -#define __HAL_SMBUS_CLEAR_STOPFLAG(__HANDLE__) \ - do{ \ - __IO uint32_t tmpreg = 0x00U; \ - tmpreg = (__HANDLE__)->Instance->SR1; \ - (__HANDLE__)->Instance->CR1 |= I2C_CR1_PE; \ - UNUSED(tmpreg); \ - } while(0) - -/** @brief Enable the SMBUS peripheral. - * @param __HANDLE__ specifies the SMBUS Handle. - * This parameter can be SMBUSx where x: 1 or 2 to select the SMBUS peripheral. - * @retval None - */ -#define __HAL_SMBUS_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1 |= I2C_CR1_PE) - -/** @brief Disable the SMBUS peripheral. - * @param __HANDLE__ specifies the SMBUS Handle. - * This parameter can be SMBUSx where x: 1 or 2 to select the SMBUS peripheral. - * @retval None - */ -#define __HAL_SMBUS_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1 &= ~I2C_CR1_PE) - -/** @brief Generate a Non-Acknowledge SMBUS peripheral in Slave mode. - * @param __HANDLE__ specifies the SMBUS Handle. - * @retval None - */ -#define __HAL_SMBUS_GENERATE_NACK(__HANDLE__) (CLEAR_BIT((__HANDLE__)->Instance->CR1, I2C_CR1_ACK)) - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup SMBUS_Exported_Functions - * @{ - */ - -/** @addtogroup SMBUS_Exported_Functions_Group1 Initialization and de-initialization functions - * @{ - */ - -/* Initialization/de-initialization functions **********************************/ -HAL_StatusTypeDef HAL_SMBUS_Init(SMBUS_HandleTypeDef *hsmbus); -HAL_StatusTypeDef HAL_SMBUS_DeInit(SMBUS_HandleTypeDef *hsmbus); -void HAL_SMBUS_MspInit(SMBUS_HandleTypeDef *hsmbus); -void HAL_SMBUS_MspDeInit(SMBUS_HandleTypeDef *hsmbus); - -/* Callbacks Register/UnRegister functions ************************************/ -#if (USE_HAL_SMBUS_REGISTER_CALLBACKS == 1) -HAL_StatusTypeDef HAL_SMBUS_RegisterCallback(SMBUS_HandleTypeDef *hsmbus, HAL_SMBUS_CallbackIDTypeDef CallbackID, pSMBUS_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_SMBUS_UnRegisterCallback(SMBUS_HandleTypeDef *hsmbus, HAL_SMBUS_CallbackIDTypeDef CallbackID); - -HAL_StatusTypeDef HAL_SMBUS_RegisterAddrCallback(SMBUS_HandleTypeDef *hsmbus, pSMBUS_AddrCallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_SMBUS_UnRegisterAddrCallback(SMBUS_HandleTypeDef *hsmbus); -#endif /* USE_HAL_SMBUS_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @addtogroup SMBUS_Exported_Functions_Group2 Input and Output operation functions - * @{ - */ - -/* IO operation functions *****************************************************/ -/** @addtogroup Blocking_mode_Polling Blocking mode Polling - * @{ - */ -/******* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_SMBUS_IsDeviceReady(SMBUS_HandleTypeDef *hsmbus, uint16_t DevAddress, uint32_t Trials, uint32_t Timeout); -/** - * @} - */ - -/** @addtogroup Non-Blocking_mode_Interrupt Non-Blocking mode Interrupt - * @{ - */ -/******* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_SMBUS_Master_Transmit_IT(SMBUS_HandleTypeDef *hsmbus, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions); -HAL_StatusTypeDef HAL_SMBUS_Master_Receive_IT(SMBUS_HandleTypeDef *hsmbus, uint16_t DevAddress, uint8_t *pData, uint16_t Size, uint32_t XferOptions); -HAL_StatusTypeDef HAL_SMBUS_Master_Abort_IT(SMBUS_HandleTypeDef *hsmbus, uint16_t DevAddress); -HAL_StatusTypeDef HAL_SMBUS_Slave_Transmit_IT(SMBUS_HandleTypeDef *hsmbus, uint8_t *pData, uint16_t Size, uint32_t XferOptions); -HAL_StatusTypeDef HAL_SMBUS_Slave_Receive_IT(SMBUS_HandleTypeDef *hsmbus, uint8_t *pData, uint16_t Size, uint32_t XferOptions); - -HAL_StatusTypeDef HAL_SMBUS_EnableAlert_IT(SMBUS_HandleTypeDef *hsmbus); -HAL_StatusTypeDef HAL_SMBUS_DisableAlert_IT(SMBUS_HandleTypeDef *hsmbus); -HAL_StatusTypeDef HAL_SMBUS_EnableListen_IT(SMBUS_HandleTypeDef *hsmbus); -HAL_StatusTypeDef HAL_SMBUS_DisableListen_IT(SMBUS_HandleTypeDef *hsmbus); - -/****** Filter Configuration functions */ -#if defined(I2C_FLTR_ANOFF)&&defined(I2C_FLTR_DNF) -HAL_StatusTypeDef HAL_SMBUS_ConfigAnalogFilter(SMBUS_HandleTypeDef *hsmbus, uint32_t AnalogFilter); -HAL_StatusTypeDef HAL_SMBUS_ConfigDigitalFilter(SMBUS_HandleTypeDef *hsmbus, uint32_t DigitalFilter); -#endif -/** - * @} - */ - -/** @addtogroup SMBUS_IRQ_Handler_and_Callbacks IRQ Handler and Callbacks - * @{ - */ -/******* SMBUS IRQHandler and Callbacks used in non blocking modes (Interrupt) */ -void HAL_SMBUS_EV_IRQHandler(SMBUS_HandleTypeDef *hsmbus); -void HAL_SMBUS_ER_IRQHandler(SMBUS_HandleTypeDef *hsmbus); -void HAL_SMBUS_MasterTxCpltCallback(SMBUS_HandleTypeDef *hsmbus); -void HAL_SMBUS_MasterRxCpltCallback(SMBUS_HandleTypeDef *hsmbus); -void HAL_SMBUS_SlaveTxCpltCallback(SMBUS_HandleTypeDef *hsmbus); -void HAL_SMBUS_SlaveRxCpltCallback(SMBUS_HandleTypeDef *hsmbus); -void HAL_SMBUS_AddrCallback(SMBUS_HandleTypeDef *hsmbus, uint8_t TransferDirection, uint16_t AddrMatchCode); -void HAL_SMBUS_ListenCpltCallback(SMBUS_HandleTypeDef *hsmbus); -void HAL_SMBUS_ErrorCallback(SMBUS_HandleTypeDef *hsmbus); -void HAL_SMBUS_AbortCpltCallback(SMBUS_HandleTypeDef *hsmbus); - -/** - * @} - */ - -/** @addtogroup SMBUS_Exported_Functions_Group3 Peripheral State, Mode and Error functions - * @{ - */ - -/* Peripheral State, mode and Errors functions **************************************************/ -HAL_SMBUS_StateTypeDef HAL_SMBUS_GetState(SMBUS_HandleTypeDef *hsmbus); -HAL_SMBUS_ModeTypeDef HAL_SMBUS_GetMode(SMBUS_HandleTypeDef *hsmbus); -uint32_t HAL_SMBUS_GetError(SMBUS_HandleTypeDef *hsmbus); - -/** - * @} - */ - -/** - * @} - */ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup SMBUS_Private_Constants SMBUS Private Constants - * @{ - */ -#define SMBUS_FLAG_MASK 0x0000FFFFU -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup SMBUS_Private_Macros SMBUS Private Macros - * @{ - */ - -#define SMBUS_FREQRANGE(__PCLK__) ((__PCLK__)/1000000U) - -#define SMBUS_RISE_TIME(__FREQRANGE__) ( ((__FREQRANGE__) + 1U)) - -#define SMBUS_SPEED_STANDARD(__PCLK__, __SPEED__) (((((__PCLK__)/((__SPEED__) << 1U)) & I2C_CCR_CCR) < 4U)? 4U:((__PCLK__) / ((__SPEED__) << 1U))) - -#define SMBUS_7BIT_ADD_WRITE(__ADDRESS__) ((uint8_t)((__ADDRESS__) & (~I2C_OAR1_ADD0))) - -#define SMBUS_7BIT_ADD_READ(__ADDRESS__) ((uint8_t)((__ADDRESS__) | I2C_OAR1_ADD0)) - -#define SMBUS_10BIT_ADDRESS(__ADDRESS__) ((uint8_t)((uint16_t)((__ADDRESS__) & (uint16_t)0x00FF))) - -#define SMBUS_10BIT_HEADER_WRITE(__ADDRESS__) ((uint8_t)((uint16_t)((uint16_t)(((uint16_t)((__ADDRESS__) & (uint16_t)0x0300)) >> 7) | (uint16_t)0x00F0))) - -#define SMBUS_10BIT_HEADER_READ(__ADDRESS__) ((uint8_t)((uint16_t)((uint16_t)(((uint16_t)((__ADDRESS__) & (uint16_t)0x0300)) >> 7) | (uint16_t)(0x00F1)))) - -#define SMBUS_GET_PEC_MODE(__HANDLE__) ((__HANDLE__)->Instance->CR1 & I2C_CR1_ENPEC) - -#define SMBUS_GET_PEC_VALUE(__HANDLE__) ((__HANDLE__)->XferPEC) - -#if defined(I2C_FLTR_ANOFF)&&defined(I2C_FLTR_DNF) -#define IS_SMBUS_ANALOG_FILTER(FILTER) (((FILTER) == SMBUS_ANALOGFILTER_ENABLE) || \ - ((FILTER) == SMBUS_ANALOGFILTER_DISABLE)) -#define IS_SMBUS_DIGITAL_FILTER(FILTER) ((FILTER) <= 0x0000000FU) -#endif -#define IS_SMBUS_ADDRESSING_MODE(ADDRESS) (((ADDRESS) == SMBUS_ADDRESSINGMODE_7BIT) || \ - ((ADDRESS) == SMBUS_ADDRESSINGMODE_10BIT)) - -#define IS_SMBUS_DUAL_ADDRESS(ADDRESS) (((ADDRESS) == SMBUS_DUALADDRESS_DISABLE) || \ - ((ADDRESS) == SMBUS_DUALADDRESS_ENABLE)) - -#define IS_SMBUS_GENERAL_CALL(CALL) (((CALL) == SMBUS_GENERALCALL_DISABLE) || \ - ((CALL) == SMBUS_GENERALCALL_ENABLE)) - -#define IS_SMBUS_NO_STRETCH(STRETCH) (((STRETCH) == SMBUS_NOSTRETCH_DISABLE) || \ - ((STRETCH) == SMBUS_NOSTRETCH_ENABLE)) - -#define IS_SMBUS_PEC(PEC) (((PEC) == SMBUS_PEC_DISABLE) || \ - ((PEC) == SMBUS_PEC_ENABLE)) - -#define IS_SMBUS_PERIPHERAL_MODE(MODE) (((MODE) == SMBUS_PERIPHERAL_MODE_SMBUS_HOST) || \ - ((MODE) == SMBUS_PERIPHERAL_MODE_SMBUS_SLAVE) || \ - ((MODE) == SMBUS_PERIPHERAL_MODE_SMBUS_SLAVE_ARP)) - -#define IS_SMBUS_CLOCK_SPEED(SPEED) (((SPEED) > 0U) && ((SPEED) <= 100000U)) - -#define IS_SMBUS_OWN_ADDRESS1(ADDRESS1) (((ADDRESS1) & 0xFFFFFC00U) == 0U) - -#define IS_SMBUS_OWN_ADDRESS2(ADDRESS2) (((ADDRESS2) & 0xFFFFFF01U) == 0U) - -#define IS_SMBUS_TRANSFER_OPTIONS_REQUEST(REQUEST) (((REQUEST) == SMBUS_FIRST_FRAME) || \ - ((REQUEST) == SMBUS_NEXT_FRAME) || \ - ((REQUEST) == SMBUS_FIRST_AND_LAST_FRAME_NO_PEC) || \ - ((REQUEST) == SMBUS_LAST_FRAME_NO_PEC) || \ - ((REQUEST) == SMBUS_FIRST_AND_LAST_FRAME_WITH_PEC) || \ - ((REQUEST) == SMBUS_LAST_FRAME_WITH_PEC)) - -/** - * @} - */ - -/* Private Functions ---------------------------------------------------------*/ -/** @defgroup SMBUS_Private_Functions SMBUS Private Functions - * @{ - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** -* @} -*/ - -#ifdef __cplusplus -} -#endif - - -#endif /* __STM32F4xx_HAL_SMBUS_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spdifrx.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spdifrx.h deleted file mode 100644 index 73e30d2..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spdifrx.h +++ /dev/null @@ -1,600 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_spdifrx.h - * @author MCD Application Team - * @brief Header file of SPDIFRX HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_SPDIFRX_H -#define STM32F4xx_HAL_SPDIFRX_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -#if defined(STM32F446xx) -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ -#if defined (SPDIFRX) - -/** @addtogroup SPDIFRX - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup SPDIFRX_Exported_Types SPDIFRX Exported Types - * @{ - */ - -/** - * @brief SPDIFRX Init structure definition - */ -typedef struct -{ - uint32_t InputSelection; /*!< Specifies the SPDIF input selection. - This parameter can be a value of @ref SPDIFRX_Input_Selection */ - - uint32_t Retries; /*!< Specifies the Maximum allowed re-tries during synchronization phase. - This parameter can be a value of @ref SPDIFRX_Max_Retries */ - - uint32_t WaitForActivity; /*!< Specifies the wait for activity on SPDIF selected input. - This parameter can be a value of @ref SPDIFRX_Wait_For_Activity. */ - - uint32_t ChannelSelection; /*!< Specifies whether the control flow will take the channel status from channel A or B. - This parameter can be a value of @ref SPDIFRX_Channel_Selection */ - - uint32_t DataFormat; /*!< Specifies the Data samples format (LSB, MSB, ...). - This parameter can be a value of @ref SPDIFRX_Data_Format */ - - uint32_t StereoMode; /*!< Specifies whether the peripheral is in stereo or mono mode. - This parameter can be a value of @ref SPDIFRX_Stereo_Mode */ - - uint32_t PreambleTypeMask; /*!< Specifies whether The preamble type bits are copied or not into the received frame. - This parameter can be a value of @ref SPDIFRX_PT_Mask */ - - uint32_t ChannelStatusMask; /*!< Specifies whether the channel status and user bits are copied or not into the received frame. - This parameter can be a value of @ref SPDIFRX_ChannelStatus_Mask */ - - uint32_t ValidityBitMask; /*!< Specifies whether the validity bit is copied or not into the received frame. - This parameter can be a value of @ref SPDIFRX_V_Mask */ - - uint32_t ParityErrorMask; /*!< Specifies whether the parity error bit is copied or not into the received frame. - This parameter can be a value of @ref SPDIFRX_PE_Mask */ -} SPDIFRX_InitTypeDef; - -/** - * @brief SPDIFRX SetDataFormat structure definition - */ -typedef struct -{ - uint32_t DataFormat; /*!< Specifies the Data samples format (LSB, MSB, ...). - This parameter can be a value of @ref SPDIFRX_Data_Format */ - - uint32_t StereoMode; /*!< Specifies whether the peripheral is in stereo or mono mode. - This parameter can be a value of @ref SPDIFRX_Stereo_Mode */ - - uint32_t PreambleTypeMask; /*!< Specifies whether The preamble type bits are copied or not into the received frame. - This parameter can be a value of @ref SPDIFRX_PT_Mask */ - - uint32_t ChannelStatusMask; /*!< Specifies whether the channel status and user bits are copied or not into the received frame. - This parameter can be a value of @ref SPDIFRX_ChannelStatus_Mask */ - - uint32_t ValidityBitMask; /*!< Specifies whether the validity bit is copied or not into the received frame. - This parameter can be a value of @ref SPDIFRX_V_Mask */ - - uint32_t ParityErrorMask; /*!< Specifies whether the parity error bit is copied or not into the received frame. - This parameter can be a value of @ref SPDIFRX_PE_Mask */ - -} SPDIFRX_SetDataFormatTypeDef; - -/** - * @brief HAL State structures definition - */ -typedef enum -{ - HAL_SPDIFRX_STATE_RESET = 0x00U, /*!< SPDIFRX not yet initialized or disabled */ - HAL_SPDIFRX_STATE_READY = 0x01U, /*!< SPDIFRX initialized and ready for use */ - HAL_SPDIFRX_STATE_BUSY = 0x02U, /*!< SPDIFRX internal process is ongoing */ - HAL_SPDIFRX_STATE_BUSY_RX = 0x03U, /*!< SPDIFRX internal Data Flow RX process is ongoing */ - HAL_SPDIFRX_STATE_BUSY_CX = 0x04U, /*!< SPDIFRX internal Control Flow RX process is ongoing */ - HAL_SPDIFRX_STATE_ERROR = 0x07U /*!< SPDIFRX error state */ -} HAL_SPDIFRX_StateTypeDef; - -/** - * @brief SPDIFRX handle Structure definition - */ -#if (USE_HAL_SPDIFRX_REGISTER_CALLBACKS == 1) -typedef struct __SPDIFRX_HandleTypeDef -#else -typedef struct -#endif -{ - SPDIFRX_TypeDef *Instance; /* SPDIFRX registers base address */ - - SPDIFRX_InitTypeDef Init; /* SPDIFRX communication parameters */ - - uint32_t *pRxBuffPtr; /* Pointer to SPDIFRX Rx transfer buffer */ - - uint32_t *pCsBuffPtr; /* Pointer to SPDIFRX Cx transfer buffer */ - - __IO uint16_t RxXferSize; /* SPDIFRX Rx transfer size */ - - __IO uint16_t RxXferCount; /* SPDIFRX Rx transfer counter - (This field is initialized at the - same value as transfer size at the - beginning of the transfer and - decremented when a sample is received. - NbSamplesReceived = RxBufferSize-RxBufferCount) */ - - __IO uint16_t CsXferSize; /* SPDIFRX Rx transfer size */ - - __IO uint16_t CsXferCount; /* SPDIFRX Rx transfer counter - (This field is initialized at the - same value as transfer size at the - beginning of the transfer and - decremented when a sample is received. - NbSamplesReceived = RxBufferSize-RxBufferCount) */ - - DMA_HandleTypeDef *hdmaCsRx; /* SPDIFRX EC60958_channel_status and user_information DMA handle parameters */ - - DMA_HandleTypeDef *hdmaDrRx; /* SPDIFRX Rx DMA handle parameters */ - - __IO HAL_LockTypeDef Lock; /* SPDIFRX locking object */ - - __IO HAL_SPDIFRX_StateTypeDef State; /* SPDIFRX communication state */ - - __IO uint32_t ErrorCode; /* SPDIFRX Error code */ - -#if (USE_HAL_SPDIFRX_REGISTER_CALLBACKS == 1) - void (*RxHalfCpltCallback)(struct __SPDIFRX_HandleTypeDef *hspdif); /*!< SPDIFRX Data flow half completed callback */ - void (*RxCpltCallback)(struct __SPDIFRX_HandleTypeDef *hspdif); /*!< SPDIFRX Data flow completed callback */ - void (*CxHalfCpltCallback)(struct __SPDIFRX_HandleTypeDef *hspdif); /*!< SPDIFRX Control flow half completed callback */ - void (*CxCpltCallback)(struct __SPDIFRX_HandleTypeDef *hspdif); /*!< SPDIFRX Control flow completed callback */ - void (*ErrorCallback)(struct __SPDIFRX_HandleTypeDef *hspdif); /*!< SPDIFRX error callback */ - void (* MspInitCallback)( struct __SPDIFRX_HandleTypeDef * hspdif); /*!< SPDIFRX Msp Init callback */ - void (* MspDeInitCallback)( struct __SPDIFRX_HandleTypeDef * hspdif); /*!< SPDIFRX Msp DeInit callback */ -#endif /* USE_HAL_SPDIFRX_REGISTER_CALLBACKS */ - -} SPDIFRX_HandleTypeDef; -/** - * @} - */ - -#if (USE_HAL_SPDIFRX_REGISTER_CALLBACKS == 1) -/** - * @brief HAL SPDIFRX Callback ID enumeration definition - */ -typedef enum -{ - HAL_SPDIFRX_RX_HALF_CB_ID = 0x00U, /*!< SPDIFRX Data flow half completed callback ID */ - HAL_SPDIFRX_RX_CPLT_CB_ID = 0x01U, /*!< SPDIFRX Data flow completed callback */ - HAL_SPDIFRX_CX_HALF_CB_ID = 0x02U, /*!< SPDIFRX Control flow half completed callback */ - HAL_SPDIFRX_CX_CPLT_CB_ID = 0x03U, /*!< SPDIFRX Control flow completed callback */ - HAL_SPDIFRX_ERROR_CB_ID = 0x04U, /*!< SPDIFRX error callback */ - HAL_SPDIFRX_MSPINIT_CB_ID = 0x05U, /*!< SPDIFRX Msp Init callback ID */ - HAL_SPDIFRX_MSPDEINIT_CB_ID = 0x06U /*!< SPDIFRX Msp DeInit callback ID */ -}HAL_SPDIFRX_CallbackIDTypeDef; - -/** - * @brief HAL SPDIFRX Callback pointer definition - */ -typedef void (*pSPDIFRX_CallbackTypeDef)(SPDIFRX_HandleTypeDef * hspdif); /*!< pointer to an SPDIFRX callback function */ -#endif /* USE_HAL_SPDIFRX_REGISTER_CALLBACKS */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup SPDIFRX_Exported_Constants SPDIFRX Exported Constants - * @{ - */ -/** @defgroup SPDIFRX_ErrorCode SPDIFRX Error Code - * @{ - */ -#define HAL_SPDIFRX_ERROR_NONE ((uint32_t)0x00000000U) /*!< No error */ -#define HAL_SPDIFRX_ERROR_TIMEOUT ((uint32_t)0x00000001U) /*!< Timeout error */ -#define HAL_SPDIFRX_ERROR_OVR ((uint32_t)0x00000002U) /*!< OVR error */ -#define HAL_SPDIFRX_ERROR_PE ((uint32_t)0x00000004U) /*!< Parity error */ -#define HAL_SPDIFRX_ERROR_DMA ((uint32_t)0x00000008U) /*!< DMA transfer error */ -#define HAL_SPDIFRX_ERROR_UNKNOWN ((uint32_t)0x00000010U) /*!< Unknown Error error */ -#if (USE_HAL_SPDIFRX_REGISTER_CALLBACKS == 1) -#define HAL_SPDIFRX_ERROR_INVALID_CALLBACK ((uint32_t)0x00000020U) /*!< Invalid Callback error */ -#endif /* USE_HAL_SPDIFRX_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @defgroup SPDIFRX_Input_Selection SPDIFRX Input Selection - * @{ - */ -#define SPDIFRX_INPUT_IN0 ((uint32_t)0x00000000U) -#define SPDIFRX_INPUT_IN1 ((uint32_t)0x00010000U) -#define SPDIFRX_INPUT_IN2 ((uint32_t)0x00020000U) -#define SPDIFRX_INPUT_IN3 ((uint32_t)0x00030000U) -/** - * @} - */ - -/** @defgroup SPDIFRX_Max_Retries SPDIFRX Maximum Retries - * @{ - */ -#define SPDIFRX_MAXRETRIES_NONE ((uint32_t)0x00000000U) -#define SPDIFRX_MAXRETRIES_3 ((uint32_t)0x00001000U) -#define SPDIFRX_MAXRETRIES_15 ((uint32_t)0x00002000U) -#define SPDIFRX_MAXRETRIES_63 ((uint32_t)0x00003000U) -/** - * @} - */ - -/** @defgroup SPDIFRX_Wait_For_Activity SPDIFRX Wait For Activity - * @{ - */ -#define SPDIFRX_WAITFORACTIVITY_OFF ((uint32_t)0x00000000U) -#define SPDIFRX_WAITFORACTIVITY_ON ((uint32_t)SPDIFRX_CR_WFA) -/** - * @} - */ - -/** @defgroup SPDIFRX_PT_Mask SPDIFRX Preamble Type Mask - * @{ - */ -#define SPDIFRX_PREAMBLETYPEMASK_OFF ((uint32_t)0x00000000U) -#define SPDIFRX_PREAMBLETYPEMASK_ON ((uint32_t)SPDIFRX_CR_PTMSK) -/** - * @} - */ - -/** @defgroup SPDIFRX_ChannelStatus_Mask SPDIFRX Channel Status Mask - * @{ - */ -#define SPDIFRX_CHANNELSTATUS_OFF ((uint32_t)0x00000000U) /* The channel status and user bits are copied into the SPDIF_DR */ -#define SPDIFRX_CHANNELSTATUS_ON ((uint32_t)SPDIFRX_CR_CUMSK) /* The channel status and user bits are not copied into the SPDIF_DR, zeros are written instead*/ -/** - * @} - */ - -/** @defgroup SPDIFRX_V_Mask SPDIFRX Validity Mask -* @{ -*/ -#define SPDIFRX_VALIDITYMASK_OFF ((uint32_t)0x00000000U) -#define SPDIFRX_VALIDITYMASK_ON ((uint32_t)SPDIFRX_CR_VMSK) -/** - * @} - */ - -/** @defgroup SPDIFRX_PE_Mask SPDIFRX Parity Error Mask - * @{ - */ -#define SPDIFRX_PARITYERRORMASK_OFF ((uint32_t)0x00000000U) -#define SPDIFRX_PARITYERRORMASK_ON ((uint32_t)SPDIFRX_CR_PMSK) -/** - * @} - */ - -/** @defgroup SPDIFRX_Channel_Selection SPDIFRX Channel Selection - * @{ - */ -#define SPDIFRX_CHANNEL_A ((uint32_t)0x00000000U) -#define SPDIFRX_CHANNEL_B ((uint32_t)SPDIFRX_CR_CHSEL) -/** - * @} - */ - -/** @defgroup SPDIFRX_Data_Format SPDIFRX Data Format - * @{ - */ -#define SPDIFRX_DATAFORMAT_LSB ((uint32_t)0x00000000U) -#define SPDIFRX_DATAFORMAT_MSB ((uint32_t)0x00000010U) -#define SPDIFRX_DATAFORMAT_32BITS ((uint32_t)0x00000020U) -/** - * @} - */ - -/** @defgroup SPDIFRX_Stereo_Mode SPDIFRX Stereo Mode - * @{ - */ -#define SPDIFRX_STEREOMODE_DISABLE ((uint32_t)0x00000000U) -#define SPDIFRX_STEREOMODE_ENABLE ((uint32_t)SPDIFRX_CR_RXSTEO) -/** - * @} - */ - -/** @defgroup SPDIFRX_State SPDIFRX State - * @{ - */ - -#define SPDIFRX_STATE_IDLE ((uint32_t)0xFFFFFFFCU) -#define SPDIFRX_STATE_SYNC ((uint32_t)0x00000001U) -#define SPDIFRX_STATE_RCV ((uint32_t)SPDIFRX_CR_SPDIFEN) -/** - * @} - */ - -/** @defgroup SPDIFRX_Interrupts_Definition SPDIFRX Interrupts Definition - * @{ - */ -#define SPDIFRX_IT_RXNE ((uint32_t)SPDIFRX_IMR_RXNEIE) -#define SPDIFRX_IT_CSRNE ((uint32_t)SPDIFRX_IMR_CSRNEIE) -#define SPDIFRX_IT_PERRIE ((uint32_t)SPDIFRX_IMR_PERRIE) -#define SPDIFRX_IT_OVRIE ((uint32_t)SPDIFRX_IMR_OVRIE) -#define SPDIFRX_IT_SBLKIE ((uint32_t)SPDIFRX_IMR_SBLKIE) -#define SPDIFRX_IT_SYNCDIE ((uint32_t)SPDIFRX_IMR_SYNCDIE) -#define SPDIFRX_IT_IFEIE ((uint32_t)SPDIFRX_IMR_IFEIE ) -/** - * @} - */ - -/** @defgroup SPDIFRX_Flags_Definition SPDIFRX Flags Definition - * @{ - */ -#define SPDIFRX_FLAG_RXNE ((uint32_t)SPDIFRX_SR_RXNE) -#define SPDIFRX_FLAG_CSRNE ((uint32_t)SPDIFRX_SR_CSRNE) -#define SPDIFRX_FLAG_PERR ((uint32_t)SPDIFRX_SR_PERR) -#define SPDIFRX_FLAG_OVR ((uint32_t)SPDIFRX_SR_OVR) -#define SPDIFRX_FLAG_SBD ((uint32_t)SPDIFRX_SR_SBD) -#define SPDIFRX_FLAG_SYNCD ((uint32_t)SPDIFRX_SR_SYNCD) -#define SPDIFRX_FLAG_FERR ((uint32_t)SPDIFRX_SR_FERR) -#define SPDIFRX_FLAG_SERR ((uint32_t)SPDIFRX_SR_SERR) -#define SPDIFRX_FLAG_TERR ((uint32_t)SPDIFRX_SR_TERR) -/** - * @} - */ - -/** - * @} - */ - -/* Exported macros -----------------------------------------------------------*/ -/** @defgroup SPDIFRX_Exported_macros SPDIFRX Exported Macros - * @{ - */ - -/** @brief Reset SPDIFRX handle state - * @param __HANDLE__ SPDIFRX handle. - * @retval None - */ -#if (USE_HAL_SPDIFRX_REGISTER_CALLBACKS == 1) -#define __HAL_SPDIFRX_RESET_HANDLE_STATE(__HANDLE__) do{\ - (__HANDLE__)->State = HAL_SPDIFRX_STATE_RESET;\ - (__HANDLE__)->MspInitCallback = NULL;\ - (__HANDLE__)->MspDeInitCallback = NULL;\ - }while(0) -#else -#define __HAL_SPDIFRX_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_SPDIFRX_STATE_RESET) -#endif /* USE_HAL_SPDIFRX_REGISTER_CALLBACKS */ - -/** @brief Disable the specified SPDIFRX peripheral (IDLE State). - * @param __HANDLE__ specifies the SPDIFRX Handle. - * @retval None - */ -#define __HAL_SPDIFRX_IDLE(__HANDLE__) ((__HANDLE__)->Instance->CR &= SPDIFRX_STATE_IDLE) - -/** @brief Enable the specified SPDIFRX peripheral (SYNC State). - * @param __HANDLE__ specifies the SPDIFRX Handle. - * @retval None - */ -#define __HAL_SPDIFRX_SYNC(__HANDLE__) ((__HANDLE__)->Instance->CR |= SPDIFRX_STATE_SYNC) - - -/** @brief Enable the specified SPDIFRX peripheral (RCV State). - * @param __HANDLE__ specifies the SPDIFRX Handle. - * @retval None - */ -#define __HAL_SPDIFRX_RCV(__HANDLE__) ((__HANDLE__)->Instance->CR |= SPDIFRX_STATE_RCV) - - -/** @brief Enable or disable the specified SPDIFRX interrupts. - * @param __HANDLE__ specifies the SPDIFRX Handle. - * @param __INTERRUPT__ specifies the interrupt source to enable or disable. - * This parameter can be one of the following values: - * @arg SPDIFRX_IT_RXNE - * @arg SPDIFRX_IT_CSRNE - * @arg SPDIFRX_IT_PERRIE - * @arg SPDIFRX_IT_OVRIE - * @arg SPDIFRX_IT_SBLKIE - * @arg SPDIFRX_IT_SYNCDIE - * @arg SPDIFRX_IT_IFEIE - * @retval None - */ -#define __HAL_SPDIFRX_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->IMR |= (__INTERRUPT__)) -#define __HAL_SPDIFRX_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->IMR &= (uint16_t)(~(__INTERRUPT__))) - -/** @brief Checks if the specified SPDIFRX interrupt source is enabled or disabled. - * @param __HANDLE__ specifies the SPDIFRX Handle. - * @param __INTERRUPT__ specifies the SPDIFRX interrupt source to check. - * This parameter can be one of the following values: - * @arg SPDIFRX_IT_RXNE - * @arg SPDIFRX_IT_CSRNE - * @arg SPDIFRX_IT_PERRIE - * @arg SPDIFRX_IT_OVRIE - * @arg SPDIFRX_IT_SBLKIE - * @arg SPDIFRX_IT_SYNCDIE - * @arg SPDIFRX_IT_IFEIE - * @retval The new state of __IT__ (TRUE or FALSE). - */ -#define __HAL_SPDIFRX_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((((__HANDLE__)->Instance->IMR & (__INTERRUPT__)) == (__INTERRUPT__)) ? SET : RESET) - -/** @brief Checks whether the specified SPDIFRX flag is set or not. - * @param __HANDLE__ specifies the SPDIFRX Handle. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg SPDIFRX_FLAG_RXNE - * @arg SPDIFRX_FLAG_CSRNE - * @arg SPDIFRX_FLAG_PERR - * @arg SPDIFRX_FLAG_OVR - * @arg SPDIFRX_FLAG_SBD - * @arg SPDIFRX_FLAG_SYNCD - * @arg SPDIFRX_FLAG_FERR - * @arg SPDIFRX_FLAG_SERR - * @arg SPDIFRX_FLAG_TERR - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_SPDIFRX_GET_FLAG(__HANDLE__, __FLAG__) (((((__HANDLE__)->Instance->SR) & (__FLAG__)) == (__FLAG__)) ? SET : RESET) - -/** @brief Clears the specified SPDIFRX SR flag, in setting the proper IFCR register bit. - * @param __HANDLE__ specifies the USART Handle. - * @param __IT_CLEAR__ specifies the interrupt clear register flag that needs to be set - * to clear the corresponding interrupt - * This parameter can be one of the following values: - * @arg SPDIFRX_FLAG_PERR - * @arg SPDIFRX_FLAG_OVR - * @arg SPDIFRX_SR_SBD - * @arg SPDIFRX_SR_SYNCD - * @retval None - */ -#define __HAL_SPDIFRX_CLEAR_IT(__HANDLE__, __IT_CLEAR__) ((__HANDLE__)->Instance->IFCR = (uint32_t)(__IT_CLEAR__)) - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup SPDIFRX_Exported_Functions - * @{ - */ - -/** @addtogroup SPDIFRX_Exported_Functions_Group1 - * @{ - */ -/* Initialization/de-initialization functions **********************************/ -HAL_StatusTypeDef HAL_SPDIFRX_Init(SPDIFRX_HandleTypeDef *hspdif); -HAL_StatusTypeDef HAL_SPDIFRX_DeInit (SPDIFRX_HandleTypeDef *hspdif); -void HAL_SPDIFRX_MspInit(SPDIFRX_HandleTypeDef *hspdif); -void HAL_SPDIFRX_MspDeInit(SPDIFRX_HandleTypeDef *hspdif); -HAL_StatusTypeDef HAL_SPDIFRX_SetDataFormat(SPDIFRX_HandleTypeDef *hspdif, SPDIFRX_SetDataFormatTypeDef sDataFormat); - -/* Callbacks Register/UnRegister functions ***********************************/ -#if (USE_HAL_SPDIFRX_REGISTER_CALLBACKS == 1) -HAL_StatusTypeDef HAL_SPDIFRX_RegisterCallback(SPDIFRX_HandleTypeDef *hspdif, HAL_SPDIFRX_CallbackIDTypeDef CallbackID, pSPDIFRX_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_SPDIFRX_UnRegisterCallback(SPDIFRX_HandleTypeDef *hspdif, HAL_SPDIFRX_CallbackIDTypeDef CallbackID); -#endif /* USE_HAL_SPDIFRX_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @addtogroup SPDIFRX_Exported_Functions_Group2 - * @{ - */ -/* I/O operation functions ***************************************************/ - /* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_SPDIFRX_ReceiveDataFlow(SPDIFRX_HandleTypeDef *hspdif, uint32_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_SPDIFRX_ReceiveControlFlow(SPDIFRX_HandleTypeDef *hspdif, uint32_t *pData, uint16_t Size, uint32_t Timeout); - -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_SPDIFRX_ReceiveControlFlow_IT(SPDIFRX_HandleTypeDef *hspdif, uint32_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_SPDIFRX_ReceiveDataFlow_IT(SPDIFRX_HandleTypeDef *hspdif, uint32_t *pData, uint16_t Size); -void HAL_SPDIFRX_IRQHandler(SPDIFRX_HandleTypeDef *hspdif); - -/* Non-Blocking mode: DMA */ -HAL_StatusTypeDef HAL_SPDIFRX_ReceiveControlFlow_DMA(SPDIFRX_HandleTypeDef *hspdif, uint32_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_SPDIFRX_ReceiveDataFlow_DMA(SPDIFRX_HandleTypeDef *hspdif, uint32_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_SPDIFRX_DMAStop(SPDIFRX_HandleTypeDef *hspdif); - -/* Callbacks used in non blocking modes (Interrupt and DMA) *******************/ -void HAL_SPDIFRX_RxHalfCpltCallback(SPDIFRX_HandleTypeDef *hspdif); -void HAL_SPDIFRX_RxCpltCallback(SPDIFRX_HandleTypeDef *hspdif); -void HAL_SPDIFRX_ErrorCallback(SPDIFRX_HandleTypeDef *hspdif); -void HAL_SPDIFRX_CxHalfCpltCallback(SPDIFRX_HandleTypeDef *hspdif); -void HAL_SPDIFRX_CxCpltCallback(SPDIFRX_HandleTypeDef *hspdif); -/** - * @} - */ - -/** @addtogroup SPDIFRX_Exported_Functions_Group3 - * @{ - */ -/* Peripheral Control and State functions ************************************/ -HAL_SPDIFRX_StateTypeDef HAL_SPDIFRX_GetState(SPDIFRX_HandleTypeDef const * const hspdif); -uint32_t HAL_SPDIFRX_GetError(SPDIFRX_HandleTypeDef const * const hspdif); -/** - * @} - */ - -/** - * @} - */ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/** @defgroup SPDIFRX_Private_Macros SPDIFRX Private Macros - * @{ - */ -#define IS_SPDIFRX_INPUT_SELECT(INPUT) (((INPUT) == SPDIFRX_INPUT_IN1) || \ - ((INPUT) == SPDIFRX_INPUT_IN2) || \ - ((INPUT) == SPDIFRX_INPUT_IN3) || \ - ((INPUT) == SPDIFRX_INPUT_IN0)) - -#define IS_SPDIFRX_MAX_RETRIES(RET) (((RET) == SPDIFRX_MAXRETRIES_NONE) || \ - ((RET) == SPDIFRX_MAXRETRIES_3) || \ - ((RET) == SPDIFRX_MAXRETRIES_15) || \ - ((RET) == SPDIFRX_MAXRETRIES_63)) - -#define IS_SPDIFRX_WAIT_FOR_ACTIVITY(VAL) (((VAL) == SPDIFRX_WAITFORACTIVITY_ON) || \ - ((VAL) == SPDIFRX_WAITFORACTIVITY_OFF)) - -#define IS_PREAMBLE_TYPE_MASK(VAL) (((VAL) == SPDIFRX_PREAMBLETYPEMASK_ON) || \ - ((VAL) == SPDIFRX_PREAMBLETYPEMASK_OFF)) - -#define IS_VALIDITY_MASK(VAL) (((VAL) == SPDIFRX_VALIDITYMASK_OFF) || \ - ((VAL) == SPDIFRX_VALIDITYMASK_ON)) - -#define IS_PARITY_ERROR_MASK(VAL) (((VAL) == SPDIFRX_PARITYERRORMASK_OFF) || \ - ((VAL) == SPDIFRX_PARITYERRORMASK_ON)) - -#define IS_SPDIFRX_CHANNEL(CHANNEL) (((CHANNEL) == SPDIFRX_CHANNEL_A) || \ - ((CHANNEL) == SPDIFRX_CHANNEL_B)) - -#define IS_SPDIFRX_DATA_FORMAT(FORMAT) (((FORMAT) == SPDIFRX_DATAFORMAT_LSB) || \ - ((FORMAT) == SPDIFRX_DATAFORMAT_MSB) || \ - ((FORMAT) == SPDIFRX_DATAFORMAT_32BITS)) - -#define IS_STEREO_MODE(MODE) (((MODE) == SPDIFRX_STEREOMODE_DISABLE) || \ - ((MODE) == SPDIFRX_STEREOMODE_ENABLE)) - -#define IS_CHANNEL_STATUS_MASK(VAL) (((VAL) == SPDIFRX_CHANNELSTATUS_ON) || \ - ((VAL) == SPDIFRX_CHANNELSTATUS_OFF)) - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup SPDIFRX_Private_Functions SPDIFRX Private Functions - * @{ - */ -/** - * @} - */ - -/** - * @} - */ -#endif /* SPDIFRX */ -/** - * @} - */ -#endif /* STM32F446xx */ - -#ifdef __cplusplus -} -#endif - - -#endif /* __STM32F4xx_HAL_SPDIFRX_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spi.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spi.h deleted file mode 100644 index f2e07c2..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_spi.h +++ /dev/null @@ -1,730 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_spi.h - * @author MCD Application Team - * @brief Header file of SPI HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_SPI_H -#define STM32F4xx_HAL_SPI_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup SPI - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup SPI_Exported_Types SPI Exported Types - * @{ - */ - -/** - * @brief SPI Configuration Structure definition - */ -typedef struct -{ - uint32_t Mode; /*!< Specifies the SPI operating mode. - This parameter can be a value of @ref SPI_Mode */ - - uint32_t Direction; /*!< Specifies the SPI bidirectional mode state. - This parameter can be a value of @ref SPI_Direction */ - - uint32_t DataSize; /*!< Specifies the SPI data size. - This parameter can be a value of @ref SPI_Data_Size */ - - uint32_t CLKPolarity; /*!< Specifies the serial clock steady state. - This parameter can be a value of @ref SPI_Clock_Polarity */ - - uint32_t CLKPhase; /*!< Specifies the clock active edge for the bit capture. - This parameter can be a value of @ref SPI_Clock_Phase */ - - uint32_t NSS; /*!< Specifies whether the NSS signal is managed by - hardware (NSS pin) or by software using the SSI bit. - This parameter can be a value of @ref SPI_Slave_Select_management */ - - uint32_t BaudRatePrescaler; /*!< Specifies the Baud Rate prescaler value which will be - used to configure the transmit and receive SCK clock. - This parameter can be a value of @ref SPI_BaudRate_Prescaler - @note The communication clock is derived from the master - clock. The slave clock does not need to be set. */ - - uint32_t FirstBit; /*!< Specifies whether data transfers start from MSB or LSB bit. - This parameter can be a value of @ref SPI_MSB_LSB_transmission */ - - uint32_t TIMode; /*!< Specifies if the TI mode is enabled or not. - This parameter can be a value of @ref SPI_TI_mode */ - - uint32_t CRCCalculation; /*!< Specifies if the CRC calculation is enabled or not. - This parameter can be a value of @ref SPI_CRC_Calculation */ - - uint32_t CRCPolynomial; /*!< Specifies the polynomial used for the CRC calculation. - This parameter must be an odd number between Min_Data = 1 and Max_Data = 65535 */ -} SPI_InitTypeDef; - -/** - * @brief HAL SPI State structure definition - */ -typedef enum -{ - HAL_SPI_STATE_RESET = 0x00U, /*!< Peripheral not Initialized */ - HAL_SPI_STATE_READY = 0x01U, /*!< Peripheral Initialized and ready for use */ - HAL_SPI_STATE_BUSY = 0x02U, /*!< an internal process is ongoing */ - HAL_SPI_STATE_BUSY_TX = 0x03U, /*!< Data Transmission process is ongoing */ - HAL_SPI_STATE_BUSY_RX = 0x04U, /*!< Data Reception process is ongoing */ - HAL_SPI_STATE_BUSY_TX_RX = 0x05U, /*!< Data Transmission and Reception process is ongoing */ - HAL_SPI_STATE_ERROR = 0x06U, /*!< SPI error state */ - HAL_SPI_STATE_ABORT = 0x07U /*!< SPI abort is ongoing */ -} HAL_SPI_StateTypeDef; - -/** - * @brief SPI handle Structure definition - */ -typedef struct __SPI_HandleTypeDef -{ - SPI_TypeDef *Instance; /*!< SPI registers base address */ - - SPI_InitTypeDef Init; /*!< SPI communication parameters */ - - uint8_t *pTxBuffPtr; /*!< Pointer to SPI Tx transfer Buffer */ - - uint16_t TxXferSize; /*!< SPI Tx Transfer size */ - - __IO uint16_t TxXferCount; /*!< SPI Tx Transfer Counter */ - - uint8_t *pRxBuffPtr; /*!< Pointer to SPI Rx transfer Buffer */ - - uint16_t RxXferSize; /*!< SPI Rx Transfer size */ - - __IO uint16_t RxXferCount; /*!< SPI Rx Transfer Counter */ - - void (*RxISR)(struct __SPI_HandleTypeDef *hspi); /*!< function pointer on Rx ISR */ - - void (*TxISR)(struct __SPI_HandleTypeDef *hspi); /*!< function pointer on Tx ISR */ - - DMA_HandleTypeDef *hdmatx; /*!< SPI Tx DMA Handle parameters */ - - DMA_HandleTypeDef *hdmarx; /*!< SPI Rx DMA Handle parameters */ - - HAL_LockTypeDef Lock; /*!< Locking object */ - - __IO HAL_SPI_StateTypeDef State; /*!< SPI communication state */ - - __IO uint32_t ErrorCode; /*!< SPI Error code */ - -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) - void (* TxCpltCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI Tx Completed callback */ - void (* RxCpltCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI Rx Completed callback */ - void (* TxRxCpltCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI TxRx Completed callback */ - void (* TxHalfCpltCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI Tx Half Completed callback */ - void (* RxHalfCpltCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI Rx Half Completed callback */ - void (* TxRxHalfCpltCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI TxRx Half Completed callback */ - void (* ErrorCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI Error callback */ - void (* AbortCpltCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI Abort callback */ - void (* MspInitCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI Msp Init callback */ - void (* MspDeInitCallback)(struct __SPI_HandleTypeDef *hspi); /*!< SPI Msp DeInit callback */ - -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ -} SPI_HandleTypeDef; - -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) -/** - * @brief HAL SPI Callback ID enumeration definition - */ -typedef enum -{ - HAL_SPI_TX_COMPLETE_CB_ID = 0x00U, /*!< SPI Tx Completed callback ID */ - HAL_SPI_RX_COMPLETE_CB_ID = 0x01U, /*!< SPI Rx Completed callback ID */ - HAL_SPI_TX_RX_COMPLETE_CB_ID = 0x02U, /*!< SPI TxRx Completed callback ID */ - HAL_SPI_TX_HALF_COMPLETE_CB_ID = 0x03U, /*!< SPI Tx Half Completed callback ID */ - HAL_SPI_RX_HALF_COMPLETE_CB_ID = 0x04U, /*!< SPI Rx Half Completed callback ID */ - HAL_SPI_TX_RX_HALF_COMPLETE_CB_ID = 0x05U, /*!< SPI TxRx Half Completed callback ID */ - HAL_SPI_ERROR_CB_ID = 0x06U, /*!< SPI Error callback ID */ - HAL_SPI_ABORT_CB_ID = 0x07U, /*!< SPI Abort callback ID */ - HAL_SPI_MSPINIT_CB_ID = 0x08U, /*!< SPI Msp Init callback ID */ - HAL_SPI_MSPDEINIT_CB_ID = 0x09U /*!< SPI Msp DeInit callback ID */ - -} HAL_SPI_CallbackIDTypeDef; - -/** - * @brief HAL SPI Callback pointer definition - */ -typedef void (*pSPI_CallbackTypeDef)(SPI_HandleTypeDef *hspi); /*!< pointer to an SPI callback function */ - -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup SPI_Exported_Constants SPI Exported Constants - * @{ - */ - -/** @defgroup SPI_Error_Code SPI Error Code - * @{ - */ -#define HAL_SPI_ERROR_NONE (0x00000000U) /*!< No error */ -#define HAL_SPI_ERROR_MODF (0x00000001U) /*!< MODF error */ -#define HAL_SPI_ERROR_CRC (0x00000002U) /*!< CRC error */ -#define HAL_SPI_ERROR_OVR (0x00000004U) /*!< OVR error */ -#define HAL_SPI_ERROR_FRE (0x00000008U) /*!< FRE error */ -#define HAL_SPI_ERROR_DMA (0x00000010U) /*!< DMA transfer error */ -#define HAL_SPI_ERROR_FLAG (0x00000020U) /*!< Error on RXNE/TXE/BSY Flag */ -#define HAL_SPI_ERROR_ABORT (0x00000040U) /*!< Error during SPI Abort procedure */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) -#define HAL_SPI_ERROR_INVALID_CALLBACK (0x00000080U) /*!< Invalid Callback error */ -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @defgroup SPI_Mode SPI Mode - * @{ - */ -#define SPI_MODE_SLAVE (0x00000000U) -#define SPI_MODE_MASTER (SPI_CR1_MSTR | SPI_CR1_SSI) -/** - * @} - */ - -/** @defgroup SPI_Direction SPI Direction Mode - * @{ - */ -#define SPI_DIRECTION_2LINES (0x00000000U) -#define SPI_DIRECTION_2LINES_RXONLY SPI_CR1_RXONLY -#define SPI_DIRECTION_1LINE SPI_CR1_BIDIMODE -/** - * @} - */ - -/** @defgroup SPI_Data_Size SPI Data Size - * @{ - */ -#define SPI_DATASIZE_8BIT (0x00000000U) -#define SPI_DATASIZE_16BIT SPI_CR1_DFF -/** - * @} - */ - -/** @defgroup SPI_Clock_Polarity SPI Clock Polarity - * @{ - */ -#define SPI_POLARITY_LOW (0x00000000U) -#define SPI_POLARITY_HIGH SPI_CR1_CPOL -/** - * @} - */ - -/** @defgroup SPI_Clock_Phase SPI Clock Phase - * @{ - */ -#define SPI_PHASE_1EDGE (0x00000000U) -#define SPI_PHASE_2EDGE SPI_CR1_CPHA -/** - * @} - */ - -/** @defgroup SPI_Slave_Select_management SPI Slave Select Management - * @{ - */ -#define SPI_NSS_SOFT SPI_CR1_SSM -#define SPI_NSS_HARD_INPUT (0x00000000U) -#define SPI_NSS_HARD_OUTPUT (SPI_CR2_SSOE << 16U) -/** - * @} - */ - -/** @defgroup SPI_BaudRate_Prescaler SPI BaudRate Prescaler - * @{ - */ -#define SPI_BAUDRATEPRESCALER_2 (0x00000000U) -#define SPI_BAUDRATEPRESCALER_4 (SPI_CR1_BR_0) -#define SPI_BAUDRATEPRESCALER_8 (SPI_CR1_BR_1) -#define SPI_BAUDRATEPRESCALER_16 (SPI_CR1_BR_1 | SPI_CR1_BR_0) -#define SPI_BAUDRATEPRESCALER_32 (SPI_CR1_BR_2) -#define SPI_BAUDRATEPRESCALER_64 (SPI_CR1_BR_2 | SPI_CR1_BR_0) -#define SPI_BAUDRATEPRESCALER_128 (SPI_CR1_BR_2 | SPI_CR1_BR_1) -#define SPI_BAUDRATEPRESCALER_256 (SPI_CR1_BR_2 | SPI_CR1_BR_1 | SPI_CR1_BR_0) -/** - * @} - */ - -/** @defgroup SPI_MSB_LSB_transmission SPI MSB LSB Transmission - * @{ - */ -#define SPI_FIRSTBIT_MSB (0x00000000U) -#define SPI_FIRSTBIT_LSB SPI_CR1_LSBFIRST -/** - * @} - */ - -/** @defgroup SPI_TI_mode SPI TI Mode - * @{ - */ -#define SPI_TIMODE_DISABLE (0x00000000U) -#define SPI_TIMODE_ENABLE SPI_CR2_FRF -/** - * @} - */ - -/** @defgroup SPI_CRC_Calculation SPI CRC Calculation - * @{ - */ -#define SPI_CRCCALCULATION_DISABLE (0x00000000U) -#define SPI_CRCCALCULATION_ENABLE SPI_CR1_CRCEN -/** - * @} - */ - -/** @defgroup SPI_Interrupt_definition SPI Interrupt Definition - * @{ - */ -#define SPI_IT_TXE SPI_CR2_TXEIE -#define SPI_IT_RXNE SPI_CR2_RXNEIE -#define SPI_IT_ERR SPI_CR2_ERRIE -/** - * @} - */ - -/** @defgroup SPI_Flags_definition SPI Flags Definition - * @{ - */ -#define SPI_FLAG_RXNE SPI_SR_RXNE /* SPI status flag: Rx buffer not empty flag */ -#define SPI_FLAG_TXE SPI_SR_TXE /* SPI status flag: Tx buffer empty flag */ -#define SPI_FLAG_BSY SPI_SR_BSY /* SPI status flag: Busy flag */ -#define SPI_FLAG_CRCERR SPI_SR_CRCERR /* SPI Error flag: CRC error flag */ -#define SPI_FLAG_MODF SPI_SR_MODF /* SPI Error flag: Mode fault flag */ -#define SPI_FLAG_OVR SPI_SR_OVR /* SPI Error flag: Overrun flag */ -#define SPI_FLAG_FRE SPI_SR_FRE /* SPI Error flag: TI mode frame format error flag */ -#define SPI_FLAG_MASK (SPI_SR_RXNE | SPI_SR_TXE | SPI_SR_BSY | SPI_SR_CRCERR\ - | SPI_SR_MODF | SPI_SR_OVR | SPI_SR_FRE) -/** - * @} - */ - -/** - * @} - */ - -/* Exported macros -----------------------------------------------------------*/ -/** @defgroup SPI_Exported_Macros SPI Exported Macros - * @{ - */ - -/** @brief Reset SPI handle state. - * @param __HANDLE__ specifies the SPI Handle. - * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. - * @retval None - */ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) -#define __HAL_SPI_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->State = HAL_SPI_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_SPI_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_SPI_STATE_RESET) -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ - -/** @brief Enable the specified SPI interrupts. - * @param __HANDLE__ specifies the SPI Handle. - * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. - * @param __INTERRUPT__ specifies the interrupt source to enable. - * This parameter can be one of the following values: - * @arg SPI_IT_TXE: Tx buffer empty interrupt enable - * @arg SPI_IT_RXNE: RX buffer not empty interrupt enable - * @arg SPI_IT_ERR: Error interrupt enable - * @retval None - */ -#define __HAL_SPI_ENABLE_IT(__HANDLE__, __INTERRUPT__) SET_BIT((__HANDLE__)->Instance->CR2, (__INTERRUPT__)) - -/** @brief Disable the specified SPI interrupts. - * @param __HANDLE__ specifies the SPI handle. - * This parameter can be SPIx where x: 1, 2, or 3 to select the SPI peripheral. - * @param __INTERRUPT__ specifies the interrupt source to disable. - * This parameter can be one of the following values: - * @arg SPI_IT_TXE: Tx buffer empty interrupt enable - * @arg SPI_IT_RXNE: RX buffer not empty interrupt enable - * @arg SPI_IT_ERR: Error interrupt enable - * @retval None - */ -#define __HAL_SPI_DISABLE_IT(__HANDLE__, __INTERRUPT__) CLEAR_BIT((__HANDLE__)->Instance->CR2, (__INTERRUPT__)) - -/** @brief Check whether the specified SPI interrupt source is enabled or not. - * @param __HANDLE__ specifies the SPI Handle. - * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. - * @param __INTERRUPT__ specifies the SPI interrupt source to check. - * This parameter can be one of the following values: - * @arg SPI_IT_TXE: Tx buffer empty interrupt enable - * @arg SPI_IT_RXNE: RX buffer not empty interrupt enable - * @arg SPI_IT_ERR: Error interrupt enable - * @retval The new state of __IT__ (TRUE or FALSE). - */ -#define __HAL_SPI_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((((__HANDLE__)->Instance->CR2\ - & (__INTERRUPT__)) == (__INTERRUPT__)) ? SET : RESET) - -/** @brief Check whether the specified SPI flag is set or not. - * @param __HANDLE__ specifies the SPI Handle. - * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg SPI_FLAG_RXNE: Receive buffer not empty flag - * @arg SPI_FLAG_TXE: Transmit buffer empty flag - * @arg SPI_FLAG_CRCERR: CRC error flag - * @arg SPI_FLAG_MODF: Mode fault flag - * @arg SPI_FLAG_OVR: Overrun flag - * @arg SPI_FLAG_BSY: Busy flag - * @arg SPI_FLAG_FRE: Frame format error flag - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_SPI_GET_FLAG(__HANDLE__, __FLAG__) ((((__HANDLE__)->Instance->SR) & (__FLAG__)) == (__FLAG__)) - -/** @brief Clear the SPI CRCERR pending flag. - * @param __HANDLE__ specifies the SPI Handle. - * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. - * @retval None - */ -#define __HAL_SPI_CLEAR_CRCERRFLAG(__HANDLE__) ((__HANDLE__)->Instance->SR = (uint16_t)(~SPI_FLAG_CRCERR)) - -/** @brief Clear the SPI MODF pending flag. - * @param __HANDLE__ specifies the SPI Handle. - * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. - * @retval None - */ -#define __HAL_SPI_CLEAR_MODFFLAG(__HANDLE__) \ - do{ \ - __IO uint32_t tmpreg_modf = 0x00U; \ - tmpreg_modf = (__HANDLE__)->Instance->SR; \ - CLEAR_BIT((__HANDLE__)->Instance->CR1, SPI_CR1_SPE); \ - UNUSED(tmpreg_modf); \ - } while(0U) - -/** @brief Clear the SPI OVR pending flag. - * @param __HANDLE__ specifies the SPI Handle. - * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. - * @retval None - */ -#define __HAL_SPI_CLEAR_OVRFLAG(__HANDLE__) \ - do{ \ - __IO uint32_t tmpreg_ovr = 0x00U; \ - tmpreg_ovr = (__HANDLE__)->Instance->DR; \ - tmpreg_ovr = (__HANDLE__)->Instance->SR; \ - UNUSED(tmpreg_ovr); \ - } while(0U) - -/** @brief Clear the SPI FRE pending flag. - * @param __HANDLE__ specifies the SPI Handle. - * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. - * @retval None - */ -#define __HAL_SPI_CLEAR_FREFLAG(__HANDLE__) \ - do{ \ - __IO uint32_t tmpreg_fre = 0x00U; \ - tmpreg_fre = (__HANDLE__)->Instance->SR; \ - UNUSED(tmpreg_fre); \ - }while(0U) - -/** @brief Enable the SPI peripheral. - * @param __HANDLE__ specifies the SPI Handle. - * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. - * @retval None - */ -#define __HAL_SPI_ENABLE(__HANDLE__) SET_BIT((__HANDLE__)->Instance->CR1, SPI_CR1_SPE) - -/** @brief Disable the SPI peripheral. - * @param __HANDLE__ specifies the SPI Handle. - * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. - * @retval None - */ -#define __HAL_SPI_DISABLE(__HANDLE__) CLEAR_BIT((__HANDLE__)->Instance->CR1, SPI_CR1_SPE) - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup SPI_Private_Macros SPI Private Macros - * @{ - */ - -/** @brief Set the SPI transmit-only mode. - * @param __HANDLE__ specifies the SPI Handle. - * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. - * @retval None - */ -#define SPI_1LINE_TX(__HANDLE__) SET_BIT((__HANDLE__)->Instance->CR1, SPI_CR1_BIDIOE) - -/** @brief Set the SPI receive-only mode. - * @param __HANDLE__ specifies the SPI Handle. - * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. - * @retval None - */ -#define SPI_1LINE_RX(__HANDLE__) CLEAR_BIT((__HANDLE__)->Instance->CR1, SPI_CR1_BIDIOE) - -/** @brief Reset the CRC calculation of the SPI. - * @param __HANDLE__ specifies the SPI Handle. - * This parameter can be SPI where x: 1, 2, or 3 to select the SPI peripheral. - * @retval None - */ -#define SPI_RESET_CRC(__HANDLE__) do{CLEAR_BIT((__HANDLE__)->Instance->CR1, SPI_CR1_CRCEN);\ - SET_BIT((__HANDLE__)->Instance->CR1, SPI_CR1_CRCEN);}while(0U) - -/** @brief Check whether the specified SPI flag is set or not. - * @param __SR__ copy of SPI SR register. - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg SPI_FLAG_RXNE: Receive buffer not empty flag - * @arg SPI_FLAG_TXE: Transmit buffer empty flag - * @arg SPI_FLAG_CRCERR: CRC error flag - * @arg SPI_FLAG_MODF: Mode fault flag - * @arg SPI_FLAG_OVR: Overrun flag - * @arg SPI_FLAG_BSY: Busy flag - * @arg SPI_FLAG_FRE: Frame format error flag - * @retval SET or RESET. - */ -#define SPI_CHECK_FLAG(__SR__, __FLAG__) ((((__SR__) & ((__FLAG__) & SPI_FLAG_MASK)) == \ - ((__FLAG__) & SPI_FLAG_MASK)) ? SET : RESET) - -/** @brief Check whether the specified SPI Interrupt is set or not. - * @param __CR2__ copy of SPI CR2 register. - * @param __INTERRUPT__ specifies the SPI interrupt source to check. - * This parameter can be one of the following values: - * @arg SPI_IT_TXE: Tx buffer empty interrupt enable - * @arg SPI_IT_RXNE: RX buffer not empty interrupt enable - * @arg SPI_IT_ERR: Error interrupt enable - * @retval SET or RESET. - */ -#define SPI_CHECK_IT_SOURCE(__CR2__, __INTERRUPT__) ((((__CR2__) & (__INTERRUPT__)) == \ - (__INTERRUPT__)) ? SET : RESET) - -/** @brief Checks if SPI Mode parameter is in allowed range. - * @param __MODE__ specifies the SPI Mode. - * This parameter can be a value of @ref SPI_Mode - * @retval None - */ -#define IS_SPI_MODE(__MODE__) (((__MODE__) == SPI_MODE_SLAVE) || \ - ((__MODE__) == SPI_MODE_MASTER)) - -/** @brief Checks if SPI Direction Mode parameter is in allowed range. - * @param __MODE__ specifies the SPI Direction Mode. - * This parameter can be a value of @ref SPI_Direction - * @retval None - */ -#define IS_SPI_DIRECTION(__MODE__) (((__MODE__) == SPI_DIRECTION_2LINES) || \ - ((__MODE__) == SPI_DIRECTION_2LINES_RXONLY) || \ - ((__MODE__) == SPI_DIRECTION_1LINE)) - -/** @brief Checks if SPI Direction Mode parameter is 2 lines. - * @param __MODE__ specifies the SPI Direction Mode. - * @retval None - */ -#define IS_SPI_DIRECTION_2LINES(__MODE__) ((__MODE__) == SPI_DIRECTION_2LINES) - -/** @brief Checks if SPI Direction Mode parameter is 1 or 2 lines. - * @param __MODE__ specifies the SPI Direction Mode. - * @retval None - */ -#define IS_SPI_DIRECTION_2LINES_OR_1LINE(__MODE__) (((__MODE__) == SPI_DIRECTION_2LINES) || \ - ((__MODE__) == SPI_DIRECTION_1LINE)) - -/** @brief Checks if SPI Data Size parameter is in allowed range. - * @param __DATASIZE__ specifies the SPI Data Size. - * This parameter can be a value of @ref SPI_Data_Size - * @retval None - */ -#define IS_SPI_DATASIZE(__DATASIZE__) (((__DATASIZE__) == SPI_DATASIZE_16BIT) || \ - ((__DATASIZE__) == SPI_DATASIZE_8BIT)) - -/** @brief Checks if SPI Serial clock steady state parameter is in allowed range. - * @param __CPOL__ specifies the SPI serial clock steady state. - * This parameter can be a value of @ref SPI_Clock_Polarity - * @retval None - */ -#define IS_SPI_CPOL(__CPOL__) (((__CPOL__) == SPI_POLARITY_LOW) || \ - ((__CPOL__) == SPI_POLARITY_HIGH)) - -/** @brief Checks if SPI Clock Phase parameter is in allowed range. - * @param __CPHA__ specifies the SPI Clock Phase. - * This parameter can be a value of @ref SPI_Clock_Phase - * @retval None - */ -#define IS_SPI_CPHA(__CPHA__) (((__CPHA__) == SPI_PHASE_1EDGE) || \ - ((__CPHA__) == SPI_PHASE_2EDGE)) - -/** @brief Checks if SPI Slave Select parameter is in allowed range. - * @param __NSS__ specifies the SPI Slave Select management parameter. - * This parameter can be a value of @ref SPI_Slave_Select_management - * @retval None - */ -#define IS_SPI_NSS(__NSS__) (((__NSS__) == SPI_NSS_SOFT) || \ - ((__NSS__) == SPI_NSS_HARD_INPUT) || \ - ((__NSS__) == SPI_NSS_HARD_OUTPUT)) - -/** @brief Checks if SPI Baudrate prescaler parameter is in allowed range. - * @param __PRESCALER__ specifies the SPI Baudrate prescaler. - * This parameter can be a value of @ref SPI_BaudRate_Prescaler - * @retval None - */ -#define IS_SPI_BAUDRATE_PRESCALER(__PRESCALER__) (((__PRESCALER__) == SPI_BAUDRATEPRESCALER_2) || \ - ((__PRESCALER__) == SPI_BAUDRATEPRESCALER_4) || \ - ((__PRESCALER__) == SPI_BAUDRATEPRESCALER_8) || \ - ((__PRESCALER__) == SPI_BAUDRATEPRESCALER_16) || \ - ((__PRESCALER__) == SPI_BAUDRATEPRESCALER_32) || \ - ((__PRESCALER__) == SPI_BAUDRATEPRESCALER_64) || \ - ((__PRESCALER__) == SPI_BAUDRATEPRESCALER_128) || \ - ((__PRESCALER__) == SPI_BAUDRATEPRESCALER_256)) - -/** @brief Checks if SPI MSB LSB transmission parameter is in allowed range. - * @param __BIT__ specifies the SPI MSB LSB transmission (whether data transfer starts from MSB or LSB bit). - * This parameter can be a value of @ref SPI_MSB_LSB_transmission - * @retval None - */ -#define IS_SPI_FIRST_BIT(__BIT__) (((__BIT__) == SPI_FIRSTBIT_MSB) || \ - ((__BIT__) == SPI_FIRSTBIT_LSB)) - -/** @brief Checks if SPI TI mode parameter is in allowed range. - * @param __MODE__ specifies the SPI TI mode. - * This parameter can be a value of @ref SPI_TI_mode - * @retval None - */ -#define IS_SPI_TIMODE(__MODE__) (((__MODE__) == SPI_TIMODE_DISABLE) || \ - ((__MODE__) == SPI_TIMODE_ENABLE)) - -/** @brief Checks if SPI CRC calculation enabled state is in allowed range. - * @param __CALCULATION__ specifies the SPI CRC calculation enable state. - * This parameter can be a value of @ref SPI_CRC_Calculation - * @retval None - */ -#define IS_SPI_CRC_CALCULATION(__CALCULATION__) (((__CALCULATION__) == SPI_CRCCALCULATION_DISABLE) || \ - ((__CALCULATION__) == SPI_CRCCALCULATION_ENABLE)) - -/** @brief Checks if SPI polynomial value to be used for the CRC calculation, is in allowed range. - * @param __POLYNOMIAL__ specifies the SPI polynomial value to be used for the CRC calculation. - * This parameter must be a number between Min_Data = 0 and Max_Data = 65535 - * @retval None - */ -#define IS_SPI_CRC_POLYNOMIAL(__POLYNOMIAL__) (((__POLYNOMIAL__) >= 0x1U) && \ - ((__POLYNOMIAL__) <= 0xFFFFU) && \ - (((__POLYNOMIAL__)&0x1U) != 0U)) - -/** @brief Checks if DMA handle is valid. - * @param __HANDLE__ specifies a DMA Handle. - * @retval None - */ -#define IS_SPI_DMA_HANDLE(__HANDLE__) ((__HANDLE__) != NULL) - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup SPI_Exported_Functions - * @{ - */ - -/** @addtogroup SPI_Exported_Functions_Group1 - * @{ - */ -/* Initialization/de-initialization functions ********************************/ -HAL_StatusTypeDef HAL_SPI_Init(SPI_HandleTypeDef *hspi); -HAL_StatusTypeDef HAL_SPI_DeInit(SPI_HandleTypeDef *hspi); -void HAL_SPI_MspInit(SPI_HandleTypeDef *hspi); -void HAL_SPI_MspDeInit(SPI_HandleTypeDef *hspi); - -/* Callbacks Register/UnRegister functions ***********************************/ -#if (USE_HAL_SPI_REGISTER_CALLBACKS == 1U) -HAL_StatusTypeDef HAL_SPI_RegisterCallback(SPI_HandleTypeDef *hspi, HAL_SPI_CallbackIDTypeDef CallbackID, pSPI_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_SPI_UnRegisterCallback(SPI_HandleTypeDef *hspi, HAL_SPI_CallbackIDTypeDef CallbackID); -#endif /* USE_HAL_SPI_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @addtogroup SPI_Exported_Functions_Group2 - * @{ - */ -/* I/O operation functions ***************************************************/ -HAL_StatusTypeDef HAL_SPI_Transmit(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_SPI_Receive(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_SPI_TransmitReceive(SPI_HandleTypeDef *hspi, uint8_t *pTxData, uint8_t *pRxData, uint16_t Size, - uint32_t Timeout); -HAL_StatusTypeDef HAL_SPI_Transmit_IT(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_SPI_Receive_IT(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_SPI_TransmitReceive_IT(SPI_HandleTypeDef *hspi, uint8_t *pTxData, uint8_t *pRxData, - uint16_t Size); -HAL_StatusTypeDef HAL_SPI_Transmit_DMA(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_SPI_Receive_DMA(SPI_HandleTypeDef *hspi, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_SPI_TransmitReceive_DMA(SPI_HandleTypeDef *hspi, uint8_t *pTxData, uint8_t *pRxData, - uint16_t Size); -HAL_StatusTypeDef HAL_SPI_DMAPause(SPI_HandleTypeDef *hspi); -HAL_StatusTypeDef HAL_SPI_DMAResume(SPI_HandleTypeDef *hspi); -HAL_StatusTypeDef HAL_SPI_DMAStop(SPI_HandleTypeDef *hspi); -/* Transfer Abort functions */ -HAL_StatusTypeDef HAL_SPI_Abort(SPI_HandleTypeDef *hspi); -HAL_StatusTypeDef HAL_SPI_Abort_IT(SPI_HandleTypeDef *hspi); - -void HAL_SPI_IRQHandler(SPI_HandleTypeDef *hspi); -void HAL_SPI_TxCpltCallback(SPI_HandleTypeDef *hspi); -void HAL_SPI_RxCpltCallback(SPI_HandleTypeDef *hspi); -void HAL_SPI_TxRxCpltCallback(SPI_HandleTypeDef *hspi); -void HAL_SPI_TxHalfCpltCallback(SPI_HandleTypeDef *hspi); -void HAL_SPI_RxHalfCpltCallback(SPI_HandleTypeDef *hspi); -void HAL_SPI_TxRxHalfCpltCallback(SPI_HandleTypeDef *hspi); -void HAL_SPI_ErrorCallback(SPI_HandleTypeDef *hspi); -void HAL_SPI_AbortCpltCallback(SPI_HandleTypeDef *hspi); -/** - * @} - */ - -/** @addtogroup SPI_Exported_Functions_Group3 - * @{ - */ -/* Peripheral State and Error functions ***************************************/ -HAL_SPI_StateTypeDef HAL_SPI_GetState(SPI_HandleTypeDef *hspi); -uint32_t HAL_SPI_GetError(SPI_HandleTypeDef *hspi); -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_HAL_SPI_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_sram.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_sram.h deleted file mode 100644 index 0c7b08d..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_sram.h +++ /dev/null @@ -1,232 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_sram.h - * @author MCD Application Team - * @brief Header file of SRAM HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_SRAM_H -#define __STM32F4xx_HAL_SRAM_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || defined(STM32F412Zx) ||\ - defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) - #include "stm32f4xx_ll_fsmc.h" -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F413xx || STM32F423xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx)|| defined(STM32F439xx) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) - #include "stm32f4xx_ll_fmc.h" -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ - - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) ||\ - defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) || defined(STM32F412Zx) ||\ - defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) - -/** @addtogroup SRAM - * @{ - */ - -/* Exported typedef ----------------------------------------------------------*/ - -/** @defgroup SRAM_Exported_Types SRAM Exported Types - * @{ - */ -/** - * @brief HAL SRAM State structures definition - */ -typedef enum -{ - HAL_SRAM_STATE_RESET = 0x00U, /*!< SRAM not yet initialized or disabled */ - HAL_SRAM_STATE_READY = 0x01U, /*!< SRAM initialized and ready for use */ - HAL_SRAM_STATE_BUSY = 0x02U, /*!< SRAM internal process is ongoing */ - HAL_SRAM_STATE_ERROR = 0x03U, /*!< SRAM error state */ - HAL_SRAM_STATE_PROTECTED = 0x04U /*!< SRAM peripheral NORSRAM device write protected */ - -} HAL_SRAM_StateTypeDef; - -/** - * @brief SRAM handle Structure definition - */ -#if (USE_HAL_SRAM_REGISTER_CALLBACKS == 1) -typedef struct __SRAM_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_SRAM_REGISTER_CALLBACKS */ -{ - FMC_NORSRAM_TypeDef *Instance; /*!< Register base address */ - - FMC_NORSRAM_EXTENDED_TypeDef *Extended; /*!< Extended mode register base address */ - - FMC_NORSRAM_InitTypeDef Init; /*!< SRAM device control configuration parameters */ - - HAL_LockTypeDef Lock; /*!< SRAM locking object */ - - __IO HAL_SRAM_StateTypeDef State; /*!< SRAM device access state */ - - DMA_HandleTypeDef *hdma; /*!< Pointer DMA handler */ - -#if (USE_HAL_SRAM_REGISTER_CALLBACKS == 1) - void (* MspInitCallback) ( struct __SRAM_HandleTypeDef * hsram); /*!< SRAM Msp Init callback */ - void (* MspDeInitCallback) ( struct __SRAM_HandleTypeDef * hsram); /*!< SRAM Msp DeInit callback */ - void (* DmaXferCpltCallback) ( DMA_HandleTypeDef * hdma); /*!< SRAM DMA Xfer Complete callback */ - void (* DmaXferErrorCallback) ( DMA_HandleTypeDef * hdma); /*!< SRAM DMA Xfer Error callback */ -#endif -} SRAM_HandleTypeDef; - -#if (USE_HAL_SRAM_REGISTER_CALLBACKS == 1) -/** - * @brief HAL SRAM Callback ID enumeration definition - */ -typedef enum -{ - HAL_SRAM_MSP_INIT_CB_ID = 0x00U, /*!< SRAM MspInit Callback ID */ - HAL_SRAM_MSP_DEINIT_CB_ID = 0x01U, /*!< SRAM MspDeInit Callback ID */ - HAL_SRAM_DMA_XFER_CPLT_CB_ID = 0x02U, /*!< SRAM DMA Xfer Complete Callback ID */ - HAL_SRAM_DMA_XFER_ERR_CB_ID = 0x03U /*!< SRAM DMA Xfer Complete Callback ID */ -}HAL_SRAM_CallbackIDTypeDef; - -/** - * @brief HAL SRAM Callback pointer definition - */ -typedef void (*pSRAM_CallbackTypeDef)(SRAM_HandleTypeDef *hsram); -typedef void (*pSRAM_DmaCallbackTypeDef)(DMA_HandleTypeDef *hdma); -#endif -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/* Exported macro ------------------------------------------------------------*/ - -/** @defgroup SRAM_Exported_Macros SRAM Exported Macros - * @{ - */ -/** @brief Reset SRAM handle state - * @param __HANDLE__ SRAM handle - * @retval None - */ -#if (USE_HAL_SRAM_REGISTER_CALLBACKS == 1) -#define __HAL_SRAM_RESET_HANDLE_STATE(__HANDLE__) do { \ - (__HANDLE__)->State = HAL_SRAM_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_SRAM_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_SRAM_STATE_RESET) -#endif - -/** - * @} - */ -/* Exported functions --------------------------------------------------------*/ - -/** @addtogroup SRAM_Exported_Functions - * @{ - */ - -/** @addtogroup SRAM_Exported_Functions_Group1 - * @{ - */ -/* Initialization/de-initialization functions **********************************/ -HAL_StatusTypeDef HAL_SRAM_Init(SRAM_HandleTypeDef *hsram, FMC_NORSRAM_TimingTypeDef *Timing, FMC_NORSRAM_TimingTypeDef *ExtTiming); -HAL_StatusTypeDef HAL_SRAM_DeInit(SRAM_HandleTypeDef *hsram); -void HAL_SRAM_MspInit(SRAM_HandleTypeDef *hsram); -void HAL_SRAM_MspDeInit(SRAM_HandleTypeDef *hsram); - -void HAL_SRAM_DMA_XferCpltCallback(DMA_HandleTypeDef *hdma); -void HAL_SRAM_DMA_XferErrorCallback(DMA_HandleTypeDef *hdma); -/** - * @} - */ - -/** @addtogroup SRAM_Exported_Functions_Group2 - * @{ - */ -/* I/O operation functions *****************************************************/ -HAL_StatusTypeDef HAL_SRAM_Read_8b(SRAM_HandleTypeDef *hsram, uint32_t *pAddress, uint8_t *pDstBuffer, uint32_t BufferSize); -HAL_StatusTypeDef HAL_SRAM_Write_8b(SRAM_HandleTypeDef *hsram, uint32_t *pAddress, uint8_t *pSrcBuffer, uint32_t BufferSize); -HAL_StatusTypeDef HAL_SRAM_Read_16b(SRAM_HandleTypeDef *hsram, uint32_t *pAddress, uint16_t *pDstBuffer, uint32_t BufferSize); -HAL_StatusTypeDef HAL_SRAM_Write_16b(SRAM_HandleTypeDef *hsram, uint32_t *pAddress, uint16_t *pSrcBuffer, uint32_t BufferSize); -HAL_StatusTypeDef HAL_SRAM_Read_32b(SRAM_HandleTypeDef *hsram, uint32_t *pAddress, uint32_t *pDstBuffer, uint32_t BufferSize); -HAL_StatusTypeDef HAL_SRAM_Write_32b(SRAM_HandleTypeDef *hsram, uint32_t *pAddress, uint32_t *pSrcBuffer, uint32_t BufferSize); -HAL_StatusTypeDef HAL_SRAM_Read_DMA(SRAM_HandleTypeDef *hsram, uint32_t *pAddress, uint32_t *pDstBuffer, uint32_t BufferSize); -HAL_StatusTypeDef HAL_SRAM_Write_DMA(SRAM_HandleTypeDef *hsram, uint32_t *pAddress, uint32_t *pSrcBuffer, uint32_t BufferSize); -#if (USE_HAL_SRAM_REGISTER_CALLBACKS == 1) -/* SRAM callback registering/unregistering */ -HAL_StatusTypeDef HAL_SRAM_RegisterCallback(SRAM_HandleTypeDef *hsram, HAL_SRAM_CallbackIDTypeDef CallbackId, pSRAM_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_SRAM_UnRegisterCallback(SRAM_HandleTypeDef *hsram, HAL_SRAM_CallbackIDTypeDef CallbackId); -HAL_StatusTypeDef HAL_SRAM_RegisterDmaCallback(SRAM_HandleTypeDef *hsram, HAL_SRAM_CallbackIDTypeDef CallbackId, pSRAM_DmaCallbackTypeDef pCallback); -#endif -/** - * @} - */ - -/** @addtogroup SRAM_Exported_Functions_Group3 - * @{ - */ -/* SRAM Control functions ******************************************************/ -HAL_StatusTypeDef HAL_SRAM_WriteOperation_Enable(SRAM_HandleTypeDef *hsram); -HAL_StatusTypeDef HAL_SRAM_WriteOperation_Disable(SRAM_HandleTypeDef *hsram); -/** - * @} - */ - -/** @addtogroup SRAM_Exported_Functions_Group4 - * @{ - */ -/* SRAM State functions *********************************************************/ -HAL_SRAM_StateTypeDef HAL_SRAM_GetState(SRAM_HandleTypeDef *hsram); -/** - * @} - */ - -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/* Private functions ---------------------------------------------------------*/ -/** - * @} - */ - -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F427xx || STM32F437xx ||\ - STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx || STM32F412Zx ||\ - STM32F412Vx || STM32F412Rx || STM32F413xx || STM32F423xx */ -/** - * @} - */ -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_SRAM_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_tim.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_tim.h deleted file mode 100644 index 2322bf0..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_tim.h +++ /dev/null @@ -1,2129 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_tim.h - * @author MCD Application Team - * @brief Header file of TIM HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_TIM_H -#define STM32F4xx_HAL_TIM_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup TIM - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup TIM_Exported_Types TIM Exported Types - * @{ - */ - -/** - * @brief TIM Time base Configuration Structure definition - */ -typedef struct -{ - uint32_t Prescaler; /*!< Specifies the prescaler value used to divide the TIM clock. - This parameter can be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF */ - - uint32_t CounterMode; /*!< Specifies the counter mode. - This parameter can be a value of @ref TIM_Counter_Mode */ - - uint32_t Period; /*!< Specifies the period value to be loaded into the active - Auto-Reload Register at the next update event. - This parameter can be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF. */ - - uint32_t ClockDivision; /*!< Specifies the clock division. - This parameter can be a value of @ref TIM_ClockDivision */ - - uint32_t RepetitionCounter; /*!< Specifies the repetition counter value. Each time the RCR downcounter - reaches zero, an update event is generated and counting restarts - from the RCR value (N). - This means in PWM mode that (N+1) corresponds to: - - the number of PWM periods in edge-aligned mode - - the number of half PWM period in center-aligned mode - GP timers: this parameter must be a number between Min_Data = 0x00 and - Max_Data = 0xFF. - Advanced timers: this parameter must be a number between Min_Data = 0x0000 and - Max_Data = 0xFFFF. */ - - uint32_t AutoReloadPreload; /*!< Specifies the auto-reload preload. - This parameter can be a value of @ref TIM_AutoReloadPreload */ -} TIM_Base_InitTypeDef; - -/** - * @brief TIM Output Compare Configuration Structure definition - */ -typedef struct -{ - uint32_t OCMode; /*!< Specifies the TIM mode. - This parameter can be a value of @ref TIM_Output_Compare_and_PWM_modes */ - - uint32_t Pulse; /*!< Specifies the pulse value to be loaded into the Capture Compare Register. - This parameter can be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF */ - - uint32_t OCPolarity; /*!< Specifies the output polarity. - This parameter can be a value of @ref TIM_Output_Compare_Polarity */ - - uint32_t OCNPolarity; /*!< Specifies the complementary output polarity. - This parameter can be a value of @ref TIM_Output_Compare_N_Polarity - @note This parameter is valid only for timer instances supporting break feature. */ - - uint32_t OCFastMode; /*!< Specifies the Fast mode state. - This parameter can be a value of @ref TIM_Output_Fast_State - @note This parameter is valid only in PWM1 and PWM2 mode. */ - - - uint32_t OCIdleState; /*!< Specifies the TIM Output Compare pin state during Idle state. - This parameter can be a value of @ref TIM_Output_Compare_Idle_State - @note This parameter is valid only for timer instances supporting break feature. */ - - uint32_t OCNIdleState; /*!< Specifies the TIM Output Compare pin state during Idle state. - This parameter can be a value of @ref TIM_Output_Compare_N_Idle_State - @note This parameter is valid only for timer instances supporting break feature. */ -} TIM_OC_InitTypeDef; - -/** - * @brief TIM One Pulse Mode Configuration Structure definition - */ -typedef struct -{ - uint32_t OCMode; /*!< Specifies the TIM mode. - This parameter can be a value of @ref TIM_Output_Compare_and_PWM_modes */ - - uint32_t Pulse; /*!< Specifies the pulse value to be loaded into the Capture Compare Register. - This parameter can be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF */ - - uint32_t OCPolarity; /*!< Specifies the output polarity. - This parameter can be a value of @ref TIM_Output_Compare_Polarity */ - - uint32_t OCNPolarity; /*!< Specifies the complementary output polarity. - This parameter can be a value of @ref TIM_Output_Compare_N_Polarity - @note This parameter is valid only for timer instances supporting break feature. */ - - uint32_t OCIdleState; /*!< Specifies the TIM Output Compare pin state during Idle state. - This parameter can be a value of @ref TIM_Output_Compare_Idle_State - @note This parameter is valid only for timer instances supporting break feature. */ - - uint32_t OCNIdleState; /*!< Specifies the TIM Output Compare pin state during Idle state. - This parameter can be a value of @ref TIM_Output_Compare_N_Idle_State - @note This parameter is valid only for timer instances supporting break feature. */ - - uint32_t ICPolarity; /*!< Specifies the active edge of the input signal. - This parameter can be a value of @ref TIM_Input_Capture_Polarity */ - - uint32_t ICSelection; /*!< Specifies the input. - This parameter can be a value of @ref TIM_Input_Capture_Selection */ - - uint32_t ICFilter; /*!< Specifies the input capture filter. - This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */ -} TIM_OnePulse_InitTypeDef; - -/** - * @brief TIM Input Capture Configuration Structure definition - */ -typedef struct -{ - uint32_t ICPolarity; /*!< Specifies the active edge of the input signal. - This parameter can be a value of @ref TIM_Input_Capture_Polarity */ - - uint32_t ICSelection; /*!< Specifies the input. - This parameter can be a value of @ref TIM_Input_Capture_Selection */ - - uint32_t ICPrescaler; /*!< Specifies the Input Capture Prescaler. - This parameter can be a value of @ref TIM_Input_Capture_Prescaler */ - - uint32_t ICFilter; /*!< Specifies the input capture filter. - This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */ -} TIM_IC_InitTypeDef; - -/** - * @brief TIM Encoder Configuration Structure definition - */ -typedef struct -{ - uint32_t EncoderMode; /*!< Specifies the active edge of the input signal. - This parameter can be a value of @ref TIM_Encoder_Mode */ - - uint32_t IC1Polarity; /*!< Specifies the active edge of the input signal. - This parameter can be a value of @ref TIM_Encoder_Input_Polarity */ - - uint32_t IC1Selection; /*!< Specifies the input. - This parameter can be a value of @ref TIM_Input_Capture_Selection */ - - uint32_t IC1Prescaler; /*!< Specifies the Input Capture Prescaler. - This parameter can be a value of @ref TIM_Input_Capture_Prescaler */ - - uint32_t IC1Filter; /*!< Specifies the input capture filter. - This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */ - - uint32_t IC2Polarity; /*!< Specifies the active edge of the input signal. - This parameter can be a value of @ref TIM_Encoder_Input_Polarity */ - - uint32_t IC2Selection; /*!< Specifies the input. - This parameter can be a value of @ref TIM_Input_Capture_Selection */ - - uint32_t IC2Prescaler; /*!< Specifies the Input Capture Prescaler. - This parameter can be a value of @ref TIM_Input_Capture_Prescaler */ - - uint32_t IC2Filter; /*!< Specifies the input capture filter. - This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */ -} TIM_Encoder_InitTypeDef; - -/** - * @brief Clock Configuration Handle Structure definition - */ -typedef struct -{ - uint32_t ClockSource; /*!< TIM clock sources - This parameter can be a value of @ref TIM_Clock_Source */ - uint32_t ClockPolarity; /*!< TIM clock polarity - This parameter can be a value of @ref TIM_Clock_Polarity */ - uint32_t ClockPrescaler; /*!< TIM clock prescaler - This parameter can be a value of @ref TIM_Clock_Prescaler */ - uint32_t ClockFilter; /*!< TIM clock filter - This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */ -} TIM_ClockConfigTypeDef; - -/** - * @brief TIM Clear Input Configuration Handle Structure definition - */ -typedef struct -{ - uint32_t ClearInputState; /*!< TIM clear Input state - This parameter can be ENABLE or DISABLE */ - uint32_t ClearInputSource; /*!< TIM clear Input sources - This parameter can be a value of @ref TIM_ClearInput_Source */ - uint32_t ClearInputPolarity; /*!< TIM Clear Input polarity - This parameter can be a value of @ref TIM_ClearInput_Polarity */ - uint32_t ClearInputPrescaler; /*!< TIM Clear Input prescaler - This parameter must be 0: When OCRef clear feature is used with ETR source, - ETR prescaler must be off */ - uint32_t ClearInputFilter; /*!< TIM Clear Input filter - This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */ -} TIM_ClearInputConfigTypeDef; - -/** - * @brief TIM Master configuration Structure definition - */ -typedef struct -{ - uint32_t MasterOutputTrigger; /*!< Trigger output (TRGO) selection - This parameter can be a value of @ref TIM_Master_Mode_Selection */ - uint32_t MasterSlaveMode; /*!< Master/slave mode selection - This parameter can be a value of @ref TIM_Master_Slave_Mode - @note When the Master/slave mode is enabled, the effect of - an event on the trigger input (TRGI) is delayed to allow a - perfect synchronization between the current timer and its - slaves (through TRGO). It is not mandatory in case of timer - synchronization mode. */ -} TIM_MasterConfigTypeDef; - -/** - * @brief TIM Slave configuration Structure definition - */ -typedef struct -{ - uint32_t SlaveMode; /*!< Slave mode selection - This parameter can be a value of @ref TIM_Slave_Mode */ - uint32_t InputTrigger; /*!< Input Trigger source - This parameter can be a value of @ref TIM_Trigger_Selection */ - uint32_t TriggerPolarity; /*!< Input Trigger polarity - This parameter can be a value of @ref TIM_Trigger_Polarity */ - uint32_t TriggerPrescaler; /*!< Input trigger prescaler - This parameter can be a value of @ref TIM_Trigger_Prescaler */ - uint32_t TriggerFilter; /*!< Input trigger filter - This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */ - -} TIM_SlaveConfigTypeDef; - -/** - * @brief TIM Break input(s) and Dead time configuration Structure definition - * @note 2 break inputs can be configured (BKIN and BKIN2) with configurable - * filter and polarity. - */ -typedef struct -{ - uint32_t OffStateRunMode; /*!< TIM off state in run mode, This parameter can be a value of @ref TIM_OSSR_Off_State_Selection_for_Run_mode_state */ - - uint32_t OffStateIDLEMode; /*!< TIM off state in IDLE mode, This parameter can be a value of @ref TIM_OSSI_Off_State_Selection_for_Idle_mode_state */ - - uint32_t LockLevel; /*!< TIM Lock level, This parameter can be a value of @ref TIM_Lock_level */ - - uint32_t DeadTime; /*!< TIM dead Time, This parameter can be a number between Min_Data = 0x00 and Max_Data = 0xFF */ - - uint32_t BreakState; /*!< TIM Break State, This parameter can be a value of @ref TIM_Break_Input_enable_disable */ - - uint32_t BreakPolarity; /*!< TIM Break input polarity, This parameter can be a value of @ref TIM_Break_Polarity */ - - uint32_t BreakFilter; /*!< Specifies the break input filter.This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */ - - uint32_t AutomaticOutput; /*!< TIM Automatic Output Enable state, This parameter can be a value of @ref TIM_AOE_Bit_Set_Reset */ - -} TIM_BreakDeadTimeConfigTypeDef; - -/** - * @brief HAL State structures definition - */ -typedef enum -{ - HAL_TIM_STATE_RESET = 0x00U, /*!< Peripheral not yet initialized or disabled */ - HAL_TIM_STATE_READY = 0x01U, /*!< Peripheral Initialized and ready for use */ - HAL_TIM_STATE_BUSY = 0x02U, /*!< An internal process is ongoing */ - HAL_TIM_STATE_TIMEOUT = 0x03U, /*!< Timeout state */ - HAL_TIM_STATE_ERROR = 0x04U /*!< Reception process is ongoing */ -} HAL_TIM_StateTypeDef; - -/** - * @brief TIM Channel States definition - */ -typedef enum -{ - HAL_TIM_CHANNEL_STATE_RESET = 0x00U, /*!< TIM Channel initial state */ - HAL_TIM_CHANNEL_STATE_READY = 0x01U, /*!< TIM Channel ready for use */ - HAL_TIM_CHANNEL_STATE_BUSY = 0x02U, /*!< An internal process is ongoing on the TIM channel */ -} HAL_TIM_ChannelStateTypeDef; - -/** - * @brief DMA Burst States definition - */ -typedef enum -{ - HAL_DMA_BURST_STATE_RESET = 0x00U, /*!< DMA Burst initial state */ - HAL_DMA_BURST_STATE_READY = 0x01U, /*!< DMA Burst ready for use */ - HAL_DMA_BURST_STATE_BUSY = 0x02U, /*!< Ongoing DMA Burst */ -} HAL_TIM_DMABurstStateTypeDef; - -/** - * @brief HAL Active channel structures definition - */ -typedef enum -{ - HAL_TIM_ACTIVE_CHANNEL_1 = 0x01U, /*!< The active channel is 1 */ - HAL_TIM_ACTIVE_CHANNEL_2 = 0x02U, /*!< The active channel is 2 */ - HAL_TIM_ACTIVE_CHANNEL_3 = 0x04U, /*!< The active channel is 3 */ - HAL_TIM_ACTIVE_CHANNEL_4 = 0x08U, /*!< The active channel is 4 */ - HAL_TIM_ACTIVE_CHANNEL_CLEARED = 0x00U /*!< All active channels cleared */ -} HAL_TIM_ActiveChannel; - -/** - * @brief TIM Time Base Handle Structure definition - */ -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) -typedef struct __TIM_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ -{ - TIM_TypeDef *Instance; /*!< Register base address */ - TIM_Base_InitTypeDef Init; /*!< TIM Time Base required parameters */ - HAL_TIM_ActiveChannel Channel; /*!< Active channel */ - DMA_HandleTypeDef *hdma[7]; /*!< DMA Handlers array - This array is accessed by a @ref DMA_Handle_index */ - HAL_LockTypeDef Lock; /*!< Locking object */ - __IO HAL_TIM_StateTypeDef State; /*!< TIM operation state */ - __IO HAL_TIM_ChannelStateTypeDef ChannelState[4]; /*!< TIM channel operation state */ - __IO HAL_TIM_ChannelStateTypeDef ChannelNState[4]; /*!< TIM complementary channel operation state */ - __IO HAL_TIM_DMABurstStateTypeDef DMABurstState; /*!< DMA burst operation state */ - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) - void (* Base_MspInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Base Msp Init Callback */ - void (* Base_MspDeInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Base Msp DeInit Callback */ - void (* IC_MspInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM IC Msp Init Callback */ - void (* IC_MspDeInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM IC Msp DeInit Callback */ - void (* OC_MspInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM OC Msp Init Callback */ - void (* OC_MspDeInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM OC Msp DeInit Callback */ - void (* PWM_MspInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM PWM Msp Init Callback */ - void (* PWM_MspDeInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM PWM Msp DeInit Callback */ - void (* OnePulse_MspInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM One Pulse Msp Init Callback */ - void (* OnePulse_MspDeInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM One Pulse Msp DeInit Callback */ - void (* Encoder_MspInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Encoder Msp Init Callback */ - void (* Encoder_MspDeInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Encoder Msp DeInit Callback */ - void (* HallSensor_MspInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Hall Sensor Msp Init Callback */ - void (* HallSensor_MspDeInitCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Hall Sensor Msp DeInit Callback */ - void (* PeriodElapsedCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Period Elapsed Callback */ - void (* PeriodElapsedHalfCpltCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Period Elapsed half complete Callback */ - void (* TriggerCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Trigger Callback */ - void (* TriggerHalfCpltCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Trigger half complete Callback */ - void (* IC_CaptureCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Input Capture Callback */ - void (* IC_CaptureHalfCpltCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Input Capture half complete Callback */ - void (* OC_DelayElapsedCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Output Compare Delay Elapsed Callback */ - void (* PWM_PulseFinishedCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM PWM Pulse Finished Callback */ - void (* PWM_PulseFinishedHalfCpltCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM PWM Pulse Finished half complete Callback */ - void (* ErrorCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Error Callback */ - void (* CommutationCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Commutation Callback */ - void (* CommutationHalfCpltCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Commutation half complete Callback */ - void (* BreakCallback)(struct __TIM_HandleTypeDef *htim); /*!< TIM Break Callback */ -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ -} TIM_HandleTypeDef; - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) -/** - * @brief HAL TIM Callback ID enumeration definition - */ -typedef enum -{ - HAL_TIM_BASE_MSPINIT_CB_ID = 0x00U /*!< TIM Base MspInit Callback ID */ - , HAL_TIM_BASE_MSPDEINIT_CB_ID = 0x01U /*!< TIM Base MspDeInit Callback ID */ - , HAL_TIM_IC_MSPINIT_CB_ID = 0x02U /*!< TIM IC MspInit Callback ID */ - , HAL_TIM_IC_MSPDEINIT_CB_ID = 0x03U /*!< TIM IC MspDeInit Callback ID */ - , HAL_TIM_OC_MSPINIT_CB_ID = 0x04U /*!< TIM OC MspInit Callback ID */ - , HAL_TIM_OC_MSPDEINIT_CB_ID = 0x05U /*!< TIM OC MspDeInit Callback ID */ - , HAL_TIM_PWM_MSPINIT_CB_ID = 0x06U /*!< TIM PWM MspInit Callback ID */ - , HAL_TIM_PWM_MSPDEINIT_CB_ID = 0x07U /*!< TIM PWM MspDeInit Callback ID */ - , HAL_TIM_ONE_PULSE_MSPINIT_CB_ID = 0x08U /*!< TIM One Pulse MspInit Callback ID */ - , HAL_TIM_ONE_PULSE_MSPDEINIT_CB_ID = 0x09U /*!< TIM One Pulse MspDeInit Callback ID */ - , HAL_TIM_ENCODER_MSPINIT_CB_ID = 0x0AU /*!< TIM Encoder MspInit Callback ID */ - , HAL_TIM_ENCODER_MSPDEINIT_CB_ID = 0x0BU /*!< TIM Encoder MspDeInit Callback ID */ - , HAL_TIM_HALL_SENSOR_MSPINIT_CB_ID = 0x0CU /*!< TIM Hall Sensor MspDeInit Callback ID */ - , HAL_TIM_HALL_SENSOR_MSPDEINIT_CB_ID = 0x0DU /*!< TIM Hall Sensor MspDeInit Callback ID */ - , HAL_TIM_PERIOD_ELAPSED_CB_ID = 0x0EU /*!< TIM Period Elapsed Callback ID */ - , HAL_TIM_PERIOD_ELAPSED_HALF_CB_ID = 0x0FU /*!< TIM Period Elapsed half complete Callback ID */ - , HAL_TIM_TRIGGER_CB_ID = 0x10U /*!< TIM Trigger Callback ID */ - , HAL_TIM_TRIGGER_HALF_CB_ID = 0x11U /*!< TIM Trigger half complete Callback ID */ - - , HAL_TIM_IC_CAPTURE_CB_ID = 0x12U /*!< TIM Input Capture Callback ID */ - , HAL_TIM_IC_CAPTURE_HALF_CB_ID = 0x13U /*!< TIM Input Capture half complete Callback ID */ - , HAL_TIM_OC_DELAY_ELAPSED_CB_ID = 0x14U /*!< TIM Output Compare Delay Elapsed Callback ID */ - , HAL_TIM_PWM_PULSE_FINISHED_CB_ID = 0x15U /*!< TIM PWM Pulse Finished Callback ID */ - , HAL_TIM_PWM_PULSE_FINISHED_HALF_CB_ID = 0x16U /*!< TIM PWM Pulse Finished half complete Callback ID */ - , HAL_TIM_ERROR_CB_ID = 0x17U /*!< TIM Error Callback ID */ - , HAL_TIM_COMMUTATION_CB_ID = 0x18U /*!< TIM Commutation Callback ID */ - , HAL_TIM_COMMUTATION_HALF_CB_ID = 0x19U /*!< TIM Commutation half complete Callback ID */ - , HAL_TIM_BREAK_CB_ID = 0x1AU /*!< TIM Break Callback ID */ -} HAL_TIM_CallbackIDTypeDef; - -/** - * @brief HAL TIM Callback pointer definition - */ -typedef void (*pTIM_CallbackTypeDef)(TIM_HandleTypeDef *htim); /*!< pointer to the TIM callback function */ - -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - -/** - * @} - */ -/* End of exported types -----------------------------------------------------*/ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup TIM_Exported_Constants TIM Exported Constants - * @{ - */ - -/** @defgroup TIM_ClearInput_Source TIM Clear Input Source - * @{ - */ -#define TIM_CLEARINPUTSOURCE_NONE 0x00000000U /*!< OCREF_CLR is disabled */ -#define TIM_CLEARINPUTSOURCE_ETR 0x00000001U /*!< OCREF_CLR is connected to ETRF input */ -/** - * @} - */ - -/** @defgroup TIM_DMA_Base_address TIM DMA Base Address - * @{ - */ -#define TIM_DMABASE_CR1 0x00000000U -#define TIM_DMABASE_CR2 0x00000001U -#define TIM_DMABASE_SMCR 0x00000002U -#define TIM_DMABASE_DIER 0x00000003U -#define TIM_DMABASE_SR 0x00000004U -#define TIM_DMABASE_EGR 0x00000005U -#define TIM_DMABASE_CCMR1 0x00000006U -#define TIM_DMABASE_CCMR2 0x00000007U -#define TIM_DMABASE_CCER 0x00000008U -#define TIM_DMABASE_CNT 0x00000009U -#define TIM_DMABASE_PSC 0x0000000AU -#define TIM_DMABASE_ARR 0x0000000BU -#define TIM_DMABASE_RCR 0x0000000CU -#define TIM_DMABASE_CCR1 0x0000000DU -#define TIM_DMABASE_CCR2 0x0000000EU -#define TIM_DMABASE_CCR3 0x0000000FU -#define TIM_DMABASE_CCR4 0x00000010U -#define TIM_DMABASE_BDTR 0x00000011U -#define TIM_DMABASE_DCR 0x00000012U -#define TIM_DMABASE_DMAR 0x00000013U -/** - * @} - */ - -/** @defgroup TIM_Event_Source TIM Event Source - * @{ - */ -#define TIM_EVENTSOURCE_UPDATE TIM_EGR_UG /*!< Reinitialize the counter and generates an update of the registers */ -#define TIM_EVENTSOURCE_CC1 TIM_EGR_CC1G /*!< A capture/compare event is generated on channel 1 */ -#define TIM_EVENTSOURCE_CC2 TIM_EGR_CC2G /*!< A capture/compare event is generated on channel 2 */ -#define TIM_EVENTSOURCE_CC3 TIM_EGR_CC3G /*!< A capture/compare event is generated on channel 3 */ -#define TIM_EVENTSOURCE_CC4 TIM_EGR_CC4G /*!< A capture/compare event is generated on channel 4 */ -#define TIM_EVENTSOURCE_COM TIM_EGR_COMG /*!< A commutation event is generated */ -#define TIM_EVENTSOURCE_TRIGGER TIM_EGR_TG /*!< A trigger event is generated */ -#define TIM_EVENTSOURCE_BREAK TIM_EGR_BG /*!< A break event is generated */ -/** - * @} - */ - -/** @defgroup TIM_Input_Channel_Polarity TIM Input Channel polarity - * @{ - */ -#define TIM_INPUTCHANNELPOLARITY_RISING 0x00000000U /*!< Polarity for TIx source */ -#define TIM_INPUTCHANNELPOLARITY_FALLING TIM_CCER_CC1P /*!< Polarity for TIx source */ -#define TIM_INPUTCHANNELPOLARITY_BOTHEDGE (TIM_CCER_CC1P | TIM_CCER_CC1NP) /*!< Polarity for TIx source */ -/** - * @} - */ - -/** @defgroup TIM_ETR_Polarity TIM ETR Polarity - * @{ - */ -#define TIM_ETRPOLARITY_INVERTED TIM_SMCR_ETP /*!< Polarity for ETR source */ -#define TIM_ETRPOLARITY_NONINVERTED 0x00000000U /*!< Polarity for ETR source */ -/** - * @} - */ - -/** @defgroup TIM_ETR_Prescaler TIM ETR Prescaler - * @{ - */ -#define TIM_ETRPRESCALER_DIV1 0x00000000U /*!< No prescaler is used */ -#define TIM_ETRPRESCALER_DIV2 TIM_SMCR_ETPS_0 /*!< ETR input source is divided by 2 */ -#define TIM_ETRPRESCALER_DIV4 TIM_SMCR_ETPS_1 /*!< ETR input source is divided by 4 */ -#define TIM_ETRPRESCALER_DIV8 TIM_SMCR_ETPS /*!< ETR input source is divided by 8 */ -/** - * @} - */ - -/** @defgroup TIM_Counter_Mode TIM Counter Mode - * @{ - */ -#define TIM_COUNTERMODE_UP 0x00000000U /*!< Counter used as up-counter */ -#define TIM_COUNTERMODE_DOWN TIM_CR1_DIR /*!< Counter used as down-counter */ -#define TIM_COUNTERMODE_CENTERALIGNED1 TIM_CR1_CMS_0 /*!< Center-aligned mode 1 */ -#define TIM_COUNTERMODE_CENTERALIGNED2 TIM_CR1_CMS_1 /*!< Center-aligned mode 2 */ -#define TIM_COUNTERMODE_CENTERALIGNED3 TIM_CR1_CMS /*!< Center-aligned mode 3 */ -/** - * @} - */ - -/** @defgroup TIM_ClockDivision TIM Clock Division - * @{ - */ -#define TIM_CLOCKDIVISION_DIV1 0x00000000U /*!< Clock division: tDTS=tCK_INT */ -#define TIM_CLOCKDIVISION_DIV2 TIM_CR1_CKD_0 /*!< Clock division: tDTS=2*tCK_INT */ -#define TIM_CLOCKDIVISION_DIV4 TIM_CR1_CKD_1 /*!< Clock division: tDTS=4*tCK_INT */ -/** - * @} - */ - -/** @defgroup TIM_Output_Compare_State TIM Output Compare State - * @{ - */ -#define TIM_OUTPUTSTATE_DISABLE 0x00000000U /*!< Capture/Compare 1 output disabled */ -#define TIM_OUTPUTSTATE_ENABLE TIM_CCER_CC1E /*!< Capture/Compare 1 output enabled */ -/** - * @} - */ - -/** @defgroup TIM_AutoReloadPreload TIM Auto-Reload Preload - * @{ - */ -#define TIM_AUTORELOAD_PRELOAD_DISABLE 0x00000000U /*!< TIMx_ARR register is not buffered */ -#define TIM_AUTORELOAD_PRELOAD_ENABLE TIM_CR1_ARPE /*!< TIMx_ARR register is buffered */ - -/** - * @} - */ - -/** @defgroup TIM_Output_Fast_State TIM Output Fast State - * @{ - */ -#define TIM_OCFAST_DISABLE 0x00000000U /*!< Output Compare fast disable */ -#define TIM_OCFAST_ENABLE TIM_CCMR1_OC1FE /*!< Output Compare fast enable */ -/** - * @} - */ - -/** @defgroup TIM_Output_Compare_N_State TIM Complementary Output Compare State - * @{ - */ -#define TIM_OUTPUTNSTATE_DISABLE 0x00000000U /*!< OCxN is disabled */ -#define TIM_OUTPUTNSTATE_ENABLE TIM_CCER_CC1NE /*!< OCxN is enabled */ -/** - * @} - */ - -/** @defgroup TIM_Output_Compare_Polarity TIM Output Compare Polarity - * @{ - */ -#define TIM_OCPOLARITY_HIGH 0x00000000U /*!< Capture/Compare output polarity */ -#define TIM_OCPOLARITY_LOW TIM_CCER_CC1P /*!< Capture/Compare output polarity */ -/** - * @} - */ - -/** @defgroup TIM_Output_Compare_N_Polarity TIM Complementary Output Compare Polarity - * @{ - */ -#define TIM_OCNPOLARITY_HIGH 0x00000000U /*!< Capture/Compare complementary output polarity */ -#define TIM_OCNPOLARITY_LOW TIM_CCER_CC1NP /*!< Capture/Compare complementary output polarity */ -/** - * @} - */ - -/** @defgroup TIM_Output_Compare_Idle_State TIM Output Compare Idle State - * @{ - */ -#define TIM_OCIDLESTATE_SET TIM_CR2_OIS1 /*!< Output Idle state: OCx=1 when MOE=0 */ -#define TIM_OCIDLESTATE_RESET 0x00000000U /*!< Output Idle state: OCx=0 when MOE=0 */ -/** - * @} - */ - -/** @defgroup TIM_Output_Compare_N_Idle_State TIM Complementary Output Compare Idle State - * @{ - */ -#define TIM_OCNIDLESTATE_SET TIM_CR2_OIS1N /*!< Complementary output Idle state: OCxN=1 when MOE=0 */ -#define TIM_OCNIDLESTATE_RESET 0x00000000U /*!< Complementary output Idle state: OCxN=0 when MOE=0 */ -/** - * @} - */ - -/** @defgroup TIM_Input_Capture_Polarity TIM Input Capture Polarity - * @{ - */ -#define TIM_ICPOLARITY_RISING TIM_INPUTCHANNELPOLARITY_RISING /*!< Capture triggered by rising edge on timer input */ -#define TIM_ICPOLARITY_FALLING TIM_INPUTCHANNELPOLARITY_FALLING /*!< Capture triggered by falling edge on timer input */ -#define TIM_ICPOLARITY_BOTHEDGE TIM_INPUTCHANNELPOLARITY_BOTHEDGE /*!< Capture triggered by both rising and falling edges on timer input*/ -/** - * @} - */ - -/** @defgroup TIM_Encoder_Input_Polarity TIM Encoder Input Polarity - * @{ - */ -#define TIM_ENCODERINPUTPOLARITY_RISING TIM_INPUTCHANNELPOLARITY_RISING /*!< Encoder input with rising edge polarity */ -#define TIM_ENCODERINPUTPOLARITY_FALLING TIM_INPUTCHANNELPOLARITY_FALLING /*!< Encoder input with falling edge polarity */ -/** - * @} - */ - -/** @defgroup TIM_Input_Capture_Selection TIM Input Capture Selection - * @{ - */ -#define TIM_ICSELECTION_DIRECTTI TIM_CCMR1_CC1S_0 /*!< TIM Input 1, 2, 3 or 4 is selected to be connected to IC1, IC2, IC3 or IC4, respectively */ -#define TIM_ICSELECTION_INDIRECTTI TIM_CCMR1_CC1S_1 /*!< TIM Input 1, 2, 3 or 4 is selected to be connected to IC2, IC1, IC4 or IC3, respectively */ -#define TIM_ICSELECTION_TRC TIM_CCMR1_CC1S /*!< TIM Input 1, 2, 3 or 4 is selected to be connected to TRC */ -/** - * @} - */ - -/** @defgroup TIM_Input_Capture_Prescaler TIM Input Capture Prescaler - * @{ - */ -#define TIM_ICPSC_DIV1 0x00000000U /*!< Capture performed each time an edge is detected on the capture input */ -#define TIM_ICPSC_DIV2 TIM_CCMR1_IC1PSC_0 /*!< Capture performed once every 2 events */ -#define TIM_ICPSC_DIV4 TIM_CCMR1_IC1PSC_1 /*!< Capture performed once every 4 events */ -#define TIM_ICPSC_DIV8 TIM_CCMR1_IC1PSC /*!< Capture performed once every 8 events */ -/** - * @} - */ - -/** @defgroup TIM_One_Pulse_Mode TIM One Pulse Mode - * @{ - */ -#define TIM_OPMODE_SINGLE TIM_CR1_OPM /*!< Counter stops counting at the next update event */ -#define TIM_OPMODE_REPETITIVE 0x00000000U /*!< Counter is not stopped at update event */ -/** - * @} - */ - -/** @defgroup TIM_Encoder_Mode TIM Encoder Mode - * @{ - */ -#define TIM_ENCODERMODE_TI1 TIM_SMCR_SMS_0 /*!< Quadrature encoder mode 1, x2 mode, counts up/down on TI1FP1 edge depending on TI2FP2 level */ -#define TIM_ENCODERMODE_TI2 TIM_SMCR_SMS_1 /*!< Quadrature encoder mode 2, x2 mode, counts up/down on TI2FP2 edge depending on TI1FP1 level. */ -#define TIM_ENCODERMODE_TI12 (TIM_SMCR_SMS_1 | TIM_SMCR_SMS_0) /*!< Quadrature encoder mode 3, x4 mode, counts up/down on both TI1FP1 and TI2FP2 edges depending on the level of the other input. */ -/** - * @} - */ - -/** @defgroup TIM_Interrupt_definition TIM interrupt Definition - * @{ - */ -#define TIM_IT_UPDATE TIM_DIER_UIE /*!< Update interrupt */ -#define TIM_IT_CC1 TIM_DIER_CC1IE /*!< Capture/Compare 1 interrupt */ -#define TIM_IT_CC2 TIM_DIER_CC2IE /*!< Capture/Compare 2 interrupt */ -#define TIM_IT_CC3 TIM_DIER_CC3IE /*!< Capture/Compare 3 interrupt */ -#define TIM_IT_CC4 TIM_DIER_CC4IE /*!< Capture/Compare 4 interrupt */ -#define TIM_IT_COM TIM_DIER_COMIE /*!< Commutation interrupt */ -#define TIM_IT_TRIGGER TIM_DIER_TIE /*!< Trigger interrupt */ -#define TIM_IT_BREAK TIM_DIER_BIE /*!< Break interrupt */ -/** - * @} - */ - -/** @defgroup TIM_Commutation_Source TIM Commutation Source - * @{ - */ -#define TIM_COMMUTATION_TRGI TIM_CR2_CCUS /*!< When Capture/compare control bits are preloaded, they are updated by setting the COMG bit or when an rising edge occurs on trigger input */ -#define TIM_COMMUTATION_SOFTWARE 0x00000000U /*!< When Capture/compare control bits are preloaded, they are updated by setting the COMG bit */ -/** - * @} - */ - -/** @defgroup TIM_DMA_sources TIM DMA Sources - * @{ - */ -#define TIM_DMA_UPDATE TIM_DIER_UDE /*!< DMA request is triggered by the update event */ -#define TIM_DMA_CC1 TIM_DIER_CC1DE /*!< DMA request is triggered by the capture/compare macth 1 event */ -#define TIM_DMA_CC2 TIM_DIER_CC2DE /*!< DMA request is triggered by the capture/compare macth 2 event event */ -#define TIM_DMA_CC3 TIM_DIER_CC3DE /*!< DMA request is triggered by the capture/compare macth 3 event event */ -#define TIM_DMA_CC4 TIM_DIER_CC4DE /*!< DMA request is triggered by the capture/compare macth 4 event event */ -#define TIM_DMA_COM TIM_DIER_COMDE /*!< DMA request is triggered by the commutation event */ -#define TIM_DMA_TRIGGER TIM_DIER_TDE /*!< DMA request is triggered by the trigger event */ -/** - * @} - */ - -/** @defgroup TIM_Flag_definition TIM Flag Definition - * @{ - */ -#define TIM_FLAG_UPDATE TIM_SR_UIF /*!< Update interrupt flag */ -#define TIM_FLAG_CC1 TIM_SR_CC1IF /*!< Capture/Compare 1 interrupt flag */ -#define TIM_FLAG_CC2 TIM_SR_CC2IF /*!< Capture/Compare 2 interrupt flag */ -#define TIM_FLAG_CC3 TIM_SR_CC3IF /*!< Capture/Compare 3 interrupt flag */ -#define TIM_FLAG_CC4 TIM_SR_CC4IF /*!< Capture/Compare 4 interrupt flag */ -#define TIM_FLAG_COM TIM_SR_COMIF /*!< Commutation interrupt flag */ -#define TIM_FLAG_TRIGGER TIM_SR_TIF /*!< Trigger interrupt flag */ -#define TIM_FLAG_BREAK TIM_SR_BIF /*!< Break interrupt flag */ -#define TIM_FLAG_CC1OF TIM_SR_CC1OF /*!< Capture 1 overcapture flag */ -#define TIM_FLAG_CC2OF TIM_SR_CC2OF /*!< Capture 2 overcapture flag */ -#define TIM_FLAG_CC3OF TIM_SR_CC3OF /*!< Capture 3 overcapture flag */ -#define TIM_FLAG_CC4OF TIM_SR_CC4OF /*!< Capture 4 overcapture flag */ -/** - * @} - */ - -/** @defgroup TIM_Channel TIM Channel - * @{ - */ -#define TIM_CHANNEL_1 0x00000000U /*!< Capture/compare channel 1 identifier */ -#define TIM_CHANNEL_2 0x00000004U /*!< Capture/compare channel 2 identifier */ -#define TIM_CHANNEL_3 0x00000008U /*!< Capture/compare channel 3 identifier */ -#define TIM_CHANNEL_4 0x0000000CU /*!< Capture/compare channel 4 identifier */ -#define TIM_CHANNEL_ALL 0x0000003CU /*!< Global Capture/compare channel identifier */ -/** - * @} - */ - -/** @defgroup TIM_Clock_Source TIM Clock Source - * @{ - */ -#define TIM_CLOCKSOURCE_ETRMODE2 TIM_SMCR_ETPS_1 /*!< External clock source mode 2 */ -#define TIM_CLOCKSOURCE_INTERNAL TIM_SMCR_ETPS_0 /*!< Internal clock source */ -#define TIM_CLOCKSOURCE_ITR0 TIM_TS_ITR0 /*!< External clock source mode 1 (ITR0) */ -#define TIM_CLOCKSOURCE_ITR1 TIM_TS_ITR1 /*!< External clock source mode 1 (ITR1) */ -#define TIM_CLOCKSOURCE_ITR2 TIM_TS_ITR2 /*!< External clock source mode 1 (ITR2) */ -#define TIM_CLOCKSOURCE_ITR3 TIM_TS_ITR3 /*!< External clock source mode 1 (ITR3) */ -#define TIM_CLOCKSOURCE_TI1ED TIM_TS_TI1F_ED /*!< External clock source mode 1 (TTI1FP1 + edge detect.) */ -#define TIM_CLOCKSOURCE_TI1 TIM_TS_TI1FP1 /*!< External clock source mode 1 (TTI1FP1) */ -#define TIM_CLOCKSOURCE_TI2 TIM_TS_TI2FP2 /*!< External clock source mode 1 (TTI2FP2) */ -#define TIM_CLOCKSOURCE_ETRMODE1 TIM_TS_ETRF /*!< External clock source mode 1 (ETRF) */ -/** - * @} - */ - -/** @defgroup TIM_Clock_Polarity TIM Clock Polarity - * @{ - */ -#define TIM_CLOCKPOLARITY_INVERTED TIM_ETRPOLARITY_INVERTED /*!< Polarity for ETRx clock sources */ -#define TIM_CLOCKPOLARITY_NONINVERTED TIM_ETRPOLARITY_NONINVERTED /*!< Polarity for ETRx clock sources */ -#define TIM_CLOCKPOLARITY_RISING TIM_INPUTCHANNELPOLARITY_RISING /*!< Polarity for TIx clock sources */ -#define TIM_CLOCKPOLARITY_FALLING TIM_INPUTCHANNELPOLARITY_FALLING /*!< Polarity for TIx clock sources */ -#define TIM_CLOCKPOLARITY_BOTHEDGE TIM_INPUTCHANNELPOLARITY_BOTHEDGE /*!< Polarity for TIx clock sources */ -/** - * @} - */ - -/** @defgroup TIM_Clock_Prescaler TIM Clock Prescaler - * @{ - */ -#define TIM_CLOCKPRESCALER_DIV1 TIM_ETRPRESCALER_DIV1 /*!< No prescaler is used */ -#define TIM_CLOCKPRESCALER_DIV2 TIM_ETRPRESCALER_DIV2 /*!< Prescaler for External ETR Clock: Capture performed once every 2 events. */ -#define TIM_CLOCKPRESCALER_DIV4 TIM_ETRPRESCALER_DIV4 /*!< Prescaler for External ETR Clock: Capture performed once every 4 events. */ -#define TIM_CLOCKPRESCALER_DIV8 TIM_ETRPRESCALER_DIV8 /*!< Prescaler for External ETR Clock: Capture performed once every 8 events. */ -/** - * @} - */ - -/** @defgroup TIM_ClearInput_Polarity TIM Clear Input Polarity - * @{ - */ -#define TIM_CLEARINPUTPOLARITY_INVERTED TIM_ETRPOLARITY_INVERTED /*!< Polarity for ETRx pin */ -#define TIM_CLEARINPUTPOLARITY_NONINVERTED TIM_ETRPOLARITY_NONINVERTED /*!< Polarity for ETRx pin */ -/** - * @} - */ - -/** @defgroup TIM_ClearInput_Prescaler TIM Clear Input Prescaler - * @{ - */ -#define TIM_CLEARINPUTPRESCALER_DIV1 TIM_ETRPRESCALER_DIV1 /*!< No prescaler is used */ -#define TIM_CLEARINPUTPRESCALER_DIV2 TIM_ETRPRESCALER_DIV2 /*!< Prescaler for External ETR pin: Capture performed once every 2 events. */ -#define TIM_CLEARINPUTPRESCALER_DIV4 TIM_ETRPRESCALER_DIV4 /*!< Prescaler for External ETR pin: Capture performed once every 4 events. */ -#define TIM_CLEARINPUTPRESCALER_DIV8 TIM_ETRPRESCALER_DIV8 /*!< Prescaler for External ETR pin: Capture performed once every 8 events. */ -/** - * @} - */ - -/** @defgroup TIM_OSSR_Off_State_Selection_for_Run_mode_state TIM OSSR OffState Selection for Run mode state - * @{ - */ -#define TIM_OSSR_ENABLE TIM_BDTR_OSSR /*!< When inactive, OC/OCN outputs are enabled (still controlled by the timer) */ -#define TIM_OSSR_DISABLE 0x00000000U /*!< When inactive, OC/OCN outputs are disabled (not controlled any longer by the timer) */ -/** - * @} - */ - -/** @defgroup TIM_OSSI_Off_State_Selection_for_Idle_mode_state TIM OSSI OffState Selection for Idle mode state - * @{ - */ -#define TIM_OSSI_ENABLE TIM_BDTR_OSSI /*!< When inactive, OC/OCN outputs are enabled (still controlled by the timer) */ -#define TIM_OSSI_DISABLE 0x00000000U /*!< When inactive, OC/OCN outputs are disabled (not controlled any longer by the timer) */ -/** - * @} - */ -/** @defgroup TIM_Lock_level TIM Lock level - * @{ - */ -#define TIM_LOCKLEVEL_OFF 0x00000000U /*!< LOCK OFF */ -#define TIM_LOCKLEVEL_1 TIM_BDTR_LOCK_0 /*!< LOCK Level 1 */ -#define TIM_LOCKLEVEL_2 TIM_BDTR_LOCK_1 /*!< LOCK Level 2 */ -#define TIM_LOCKLEVEL_3 TIM_BDTR_LOCK /*!< LOCK Level 3 */ -/** - * @} - */ - -/** @defgroup TIM_Break_Input_enable_disable TIM Break Input Enable - * @{ - */ -#define TIM_BREAK_ENABLE TIM_BDTR_BKE /*!< Break input BRK is enabled */ -#define TIM_BREAK_DISABLE 0x00000000U /*!< Break input BRK is disabled */ -/** - * @} - */ - -/** @defgroup TIM_Break_Polarity TIM Break Input Polarity - * @{ - */ -#define TIM_BREAKPOLARITY_LOW 0x00000000U /*!< Break input BRK is active low */ -#define TIM_BREAKPOLARITY_HIGH TIM_BDTR_BKP /*!< Break input BRK is active high */ -/** - * @} - */ - -/** @defgroup TIM_AOE_Bit_Set_Reset TIM Automatic Output Enable - * @{ - */ -#define TIM_AUTOMATICOUTPUT_DISABLE 0x00000000U /*!< MOE can be set only by software */ -#define TIM_AUTOMATICOUTPUT_ENABLE TIM_BDTR_AOE /*!< MOE can be set by software or automatically at the next update event (if none of the break inputs BRK and BRK2 is active) */ -/** - * @} - */ - -/** @defgroup TIM_Master_Mode_Selection TIM Master Mode Selection - * @{ - */ -#define TIM_TRGO_RESET 0x00000000U /*!< TIMx_EGR.UG bit is used as trigger output (TRGO) */ -#define TIM_TRGO_ENABLE TIM_CR2_MMS_0 /*!< TIMx_CR1.CEN bit is used as trigger output (TRGO) */ -#define TIM_TRGO_UPDATE TIM_CR2_MMS_1 /*!< Update event is used as trigger output (TRGO) */ -#define TIM_TRGO_OC1 (TIM_CR2_MMS_1 | TIM_CR2_MMS_0) /*!< Capture or a compare match 1 is used as trigger output (TRGO) */ -#define TIM_TRGO_OC1REF TIM_CR2_MMS_2 /*!< OC1REF signal is used as trigger output (TRGO) */ -#define TIM_TRGO_OC2REF (TIM_CR2_MMS_2 | TIM_CR2_MMS_0) /*!< OC2REF signal is used as trigger output(TRGO) */ -#define TIM_TRGO_OC3REF (TIM_CR2_MMS_2 | TIM_CR2_MMS_1) /*!< OC3REF signal is used as trigger output(TRGO) */ -#define TIM_TRGO_OC4REF (TIM_CR2_MMS_2 | TIM_CR2_MMS_1 | TIM_CR2_MMS_0) /*!< OC4REF signal is used as trigger output(TRGO) */ -/** - * @} - */ - -/** @defgroup TIM_Master_Slave_Mode TIM Master/Slave Mode - * @{ - */ -#define TIM_MASTERSLAVEMODE_ENABLE TIM_SMCR_MSM /*!< No action */ -#define TIM_MASTERSLAVEMODE_DISABLE 0x00000000U /*!< Master/slave mode is selected */ -/** - * @} - */ - -/** @defgroup TIM_Slave_Mode TIM Slave mode - * @{ - */ -#define TIM_SLAVEMODE_DISABLE 0x00000000U /*!< Slave mode disabled */ -#define TIM_SLAVEMODE_RESET TIM_SMCR_SMS_2 /*!< Reset Mode */ -#define TIM_SLAVEMODE_GATED (TIM_SMCR_SMS_2 | TIM_SMCR_SMS_0) /*!< Gated Mode */ -#define TIM_SLAVEMODE_TRIGGER (TIM_SMCR_SMS_2 | TIM_SMCR_SMS_1) /*!< Trigger Mode */ -#define TIM_SLAVEMODE_EXTERNAL1 (TIM_SMCR_SMS_2 | TIM_SMCR_SMS_1 | TIM_SMCR_SMS_0) /*!< External Clock Mode 1 */ -/** - * @} - */ - -/** @defgroup TIM_Output_Compare_and_PWM_modes TIM Output Compare and PWM Modes - * @{ - */ -#define TIM_OCMODE_TIMING 0x00000000U /*!< Frozen */ -#define TIM_OCMODE_ACTIVE TIM_CCMR1_OC1M_0 /*!< Set channel to active level on match */ -#define TIM_OCMODE_INACTIVE TIM_CCMR1_OC1M_1 /*!< Set channel to inactive level on match */ -#define TIM_OCMODE_TOGGLE (TIM_CCMR1_OC1M_1 | TIM_CCMR1_OC1M_0) /*!< Toggle */ -#define TIM_OCMODE_PWM1 (TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1M_1) /*!< PWM mode 1 */ -#define TIM_OCMODE_PWM2 (TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1M_1 | TIM_CCMR1_OC1M_0) /*!< PWM mode 2 */ -#define TIM_OCMODE_FORCED_ACTIVE (TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1M_0) /*!< Force active level */ -#define TIM_OCMODE_FORCED_INACTIVE TIM_CCMR1_OC1M_2 /*!< Force inactive level */ -/** - * @} - */ - -/** @defgroup TIM_Trigger_Selection TIM Trigger Selection - * @{ - */ -#define TIM_TS_ITR0 0x00000000U /*!< Internal Trigger 0 (ITR0) */ -#define TIM_TS_ITR1 TIM_SMCR_TS_0 /*!< Internal Trigger 1 (ITR1) */ -#define TIM_TS_ITR2 TIM_SMCR_TS_1 /*!< Internal Trigger 2 (ITR2) */ -#define TIM_TS_ITR3 (TIM_SMCR_TS_0 | TIM_SMCR_TS_1) /*!< Internal Trigger 3 (ITR3) */ -#define TIM_TS_TI1F_ED TIM_SMCR_TS_2 /*!< TI1 Edge Detector (TI1F_ED) */ -#define TIM_TS_TI1FP1 (TIM_SMCR_TS_0 | TIM_SMCR_TS_2) /*!< Filtered Timer Input 1 (TI1FP1) */ -#define TIM_TS_TI2FP2 (TIM_SMCR_TS_1 | TIM_SMCR_TS_2) /*!< Filtered Timer Input 2 (TI2FP2) */ -#define TIM_TS_ETRF (TIM_SMCR_TS_0 | TIM_SMCR_TS_1 | TIM_SMCR_TS_2) /*!< Filtered External Trigger input (ETRF) */ -#define TIM_TS_NONE 0x0000FFFFU /*!< No trigger selected */ -/** - * @} - */ - -/** @defgroup TIM_Trigger_Polarity TIM Trigger Polarity - * @{ - */ -#define TIM_TRIGGERPOLARITY_INVERTED TIM_ETRPOLARITY_INVERTED /*!< Polarity for ETRx trigger sources */ -#define TIM_TRIGGERPOLARITY_NONINVERTED TIM_ETRPOLARITY_NONINVERTED /*!< Polarity for ETRx trigger sources */ -#define TIM_TRIGGERPOLARITY_RISING TIM_INPUTCHANNELPOLARITY_RISING /*!< Polarity for TIxFPx or TI1_ED trigger sources */ -#define TIM_TRIGGERPOLARITY_FALLING TIM_INPUTCHANNELPOLARITY_FALLING /*!< Polarity for TIxFPx or TI1_ED trigger sources */ -#define TIM_TRIGGERPOLARITY_BOTHEDGE TIM_INPUTCHANNELPOLARITY_BOTHEDGE /*!< Polarity for TIxFPx or TI1_ED trigger sources */ -/** - * @} - */ - -/** @defgroup TIM_Trigger_Prescaler TIM Trigger Prescaler - * @{ - */ -#define TIM_TRIGGERPRESCALER_DIV1 TIM_ETRPRESCALER_DIV1 /*!< No prescaler is used */ -#define TIM_TRIGGERPRESCALER_DIV2 TIM_ETRPRESCALER_DIV2 /*!< Prescaler for External ETR Trigger: Capture performed once every 2 events. */ -#define TIM_TRIGGERPRESCALER_DIV4 TIM_ETRPRESCALER_DIV4 /*!< Prescaler for External ETR Trigger: Capture performed once every 4 events. */ -#define TIM_TRIGGERPRESCALER_DIV8 TIM_ETRPRESCALER_DIV8 /*!< Prescaler for External ETR Trigger: Capture performed once every 8 events. */ -/** - * @} - */ - -/** @defgroup TIM_TI1_Selection TIM TI1 Input Selection - * @{ - */ -#define TIM_TI1SELECTION_CH1 0x00000000U /*!< The TIMx_CH1 pin is connected to TI1 input */ -#define TIM_TI1SELECTION_XORCOMBINATION TIM_CR2_TI1S /*!< The TIMx_CH1, CH2 and CH3 pins are connected to the TI1 input (XOR combination) */ -/** - * @} - */ - -/** @defgroup TIM_DMA_Burst_Length TIM DMA Burst Length - * @{ - */ -#define TIM_DMABURSTLENGTH_1TRANSFER 0x00000000U /*!< The transfer is done to 1 register starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_2TRANSFERS 0x00000100U /*!< The transfer is done to 2 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_3TRANSFERS 0x00000200U /*!< The transfer is done to 3 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_4TRANSFERS 0x00000300U /*!< The transfer is done to 4 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_5TRANSFERS 0x00000400U /*!< The transfer is done to 5 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_6TRANSFERS 0x00000500U /*!< The transfer is done to 6 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_7TRANSFERS 0x00000600U /*!< The transfer is done to 7 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_8TRANSFERS 0x00000700U /*!< The transfer is done to 8 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_9TRANSFERS 0x00000800U /*!< The transfer is done to 9 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_10TRANSFERS 0x00000900U /*!< The transfer is done to 10 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_11TRANSFERS 0x00000A00U /*!< The transfer is done to 11 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_12TRANSFERS 0x00000B00U /*!< The transfer is done to 12 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_13TRANSFERS 0x00000C00U /*!< The transfer is done to 13 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_14TRANSFERS 0x00000D00U /*!< The transfer is done to 14 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_15TRANSFERS 0x00000E00U /*!< The transfer is done to 15 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_16TRANSFERS 0x00000F00U /*!< The transfer is done to 16 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_17TRANSFERS 0x00001000U /*!< The transfer is done to 17 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -#define TIM_DMABURSTLENGTH_18TRANSFERS 0x00001100U /*!< The transfer is done to 18 registers starting from TIMx_CR1 + TIMx_DCR.DBA */ -/** - * @} - */ - -/** @defgroup DMA_Handle_index TIM DMA Handle Index - * @{ - */ -#define TIM_DMA_ID_UPDATE ((uint16_t) 0x0000) /*!< Index of the DMA handle used for Update DMA requests */ -#define TIM_DMA_ID_CC1 ((uint16_t) 0x0001) /*!< Index of the DMA handle used for Capture/Compare 1 DMA requests */ -#define TIM_DMA_ID_CC2 ((uint16_t) 0x0002) /*!< Index of the DMA handle used for Capture/Compare 2 DMA requests */ -#define TIM_DMA_ID_CC3 ((uint16_t) 0x0003) /*!< Index of the DMA handle used for Capture/Compare 3 DMA requests */ -#define TIM_DMA_ID_CC4 ((uint16_t) 0x0004) /*!< Index of the DMA handle used for Capture/Compare 4 DMA requests */ -#define TIM_DMA_ID_COMMUTATION ((uint16_t) 0x0005) /*!< Index of the DMA handle used for Commutation DMA requests */ -#define TIM_DMA_ID_TRIGGER ((uint16_t) 0x0006) /*!< Index of the DMA handle used for Trigger DMA requests */ -/** - * @} - */ - -/** @defgroup Channel_CC_State TIM Capture/Compare Channel State - * @{ - */ -#define TIM_CCx_ENABLE 0x00000001U /*!< Input or output channel is enabled */ -#define TIM_CCx_DISABLE 0x00000000U /*!< Input or output channel is disabled */ -#define TIM_CCxN_ENABLE 0x00000004U /*!< Complementary output channel is enabled */ -#define TIM_CCxN_DISABLE 0x00000000U /*!< Complementary output channel is enabled */ -/** - * @} - */ - -/** - * @} - */ -/* End of exported constants -------------------------------------------------*/ - -/* Exported macros -----------------------------------------------------------*/ -/** @defgroup TIM_Exported_Macros TIM Exported Macros - * @{ - */ - -/** @brief Reset TIM handle state. - * @param __HANDLE__ TIM handle. - * @retval None - */ -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) -#define __HAL_TIM_RESET_HANDLE_STATE(__HANDLE__) do { \ - (__HANDLE__)->State = HAL_TIM_STATE_RESET; \ - (__HANDLE__)->ChannelState[0] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->ChannelState[1] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->ChannelState[2] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->ChannelState[3] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->ChannelNState[0] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->ChannelNState[1] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->ChannelNState[2] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->ChannelNState[3] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->DMABurstState = HAL_DMA_BURST_STATE_RESET; \ - (__HANDLE__)->Base_MspInitCallback = NULL; \ - (__HANDLE__)->Base_MspDeInitCallback = NULL; \ - (__HANDLE__)->IC_MspInitCallback = NULL; \ - (__HANDLE__)->IC_MspDeInitCallback = NULL; \ - (__HANDLE__)->OC_MspInitCallback = NULL; \ - (__HANDLE__)->OC_MspDeInitCallback = NULL; \ - (__HANDLE__)->PWM_MspInitCallback = NULL; \ - (__HANDLE__)->PWM_MspDeInitCallback = NULL; \ - (__HANDLE__)->OnePulse_MspInitCallback = NULL; \ - (__HANDLE__)->OnePulse_MspDeInitCallback = NULL; \ - (__HANDLE__)->Encoder_MspInitCallback = NULL; \ - (__HANDLE__)->Encoder_MspDeInitCallback = NULL; \ - (__HANDLE__)->HallSensor_MspInitCallback = NULL; \ - (__HANDLE__)->HallSensor_MspDeInitCallback = NULL; \ - } while(0) -#else -#define __HAL_TIM_RESET_HANDLE_STATE(__HANDLE__) do { \ - (__HANDLE__)->State = HAL_TIM_STATE_RESET; \ - (__HANDLE__)->ChannelState[0] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->ChannelState[1] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->ChannelState[2] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->ChannelState[3] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->ChannelNState[0] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->ChannelNState[1] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->ChannelNState[2] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->ChannelNState[3] = HAL_TIM_CHANNEL_STATE_RESET; \ - (__HANDLE__)->DMABurstState = HAL_DMA_BURST_STATE_RESET; \ - } while(0) -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - -/** - * @brief Enable the TIM peripheral. - * @param __HANDLE__ TIM handle - * @retval None - */ -#define __HAL_TIM_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1|=(TIM_CR1_CEN)) - -/** - * @brief Enable the TIM main Output. - * @param __HANDLE__ TIM handle - * @retval None - */ -#define __HAL_TIM_MOE_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->BDTR|=(TIM_BDTR_MOE)) - -/** - * @brief Disable the TIM peripheral. - * @param __HANDLE__ TIM handle - * @retval None - */ -#define __HAL_TIM_DISABLE(__HANDLE__) \ - do { \ - if (((__HANDLE__)->Instance->CCER & TIM_CCER_CCxE_MASK) == 0UL) \ - { \ - if(((__HANDLE__)->Instance->CCER & TIM_CCER_CCxNE_MASK) == 0UL) \ - { \ - (__HANDLE__)->Instance->CR1 &= ~(TIM_CR1_CEN); \ - } \ - } \ - } while(0) - -/** - * @brief Disable the TIM main Output. - * @param __HANDLE__ TIM handle - * @retval None - * @note The Main Output Enable of a timer instance is disabled only if all the CCx and CCxN channels have been - * disabled - */ -#define __HAL_TIM_MOE_DISABLE(__HANDLE__) \ - do { \ - if (((__HANDLE__)->Instance->CCER & TIM_CCER_CCxE_MASK) == 0UL) \ - { \ - if(((__HANDLE__)->Instance->CCER & TIM_CCER_CCxNE_MASK) == 0UL) \ - { \ - (__HANDLE__)->Instance->BDTR &= ~(TIM_BDTR_MOE); \ - } \ - } \ - } while(0) - -/** - * @brief Disable the TIM main Output. - * @param __HANDLE__ TIM handle - * @retval None - * @note The Main Output Enable of a timer instance is disabled unconditionally - */ -#define __HAL_TIM_MOE_DISABLE_UNCONDITIONALLY(__HANDLE__) (__HANDLE__)->Instance->BDTR &= ~(TIM_BDTR_MOE) - -/** @brief Enable the specified TIM interrupt. - * @param __HANDLE__ specifies the TIM Handle. - * @param __INTERRUPT__ specifies the TIM interrupt source to enable. - * This parameter can be one of the following values: - * @arg TIM_IT_UPDATE: Update interrupt - * @arg TIM_IT_CC1: Capture/Compare 1 interrupt - * @arg TIM_IT_CC2: Capture/Compare 2 interrupt - * @arg TIM_IT_CC3: Capture/Compare 3 interrupt - * @arg TIM_IT_CC4: Capture/Compare 4 interrupt - * @arg TIM_IT_COM: Commutation interrupt - * @arg TIM_IT_TRIGGER: Trigger interrupt - * @arg TIM_IT_BREAK: Break interrupt - * @retval None - */ -#define __HAL_TIM_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->DIER |= (__INTERRUPT__)) - -/** @brief Disable the specified TIM interrupt. - * @param __HANDLE__ specifies the TIM Handle. - * @param __INTERRUPT__ specifies the TIM interrupt source to disable. - * This parameter can be one of the following values: - * @arg TIM_IT_UPDATE: Update interrupt - * @arg TIM_IT_CC1: Capture/Compare 1 interrupt - * @arg TIM_IT_CC2: Capture/Compare 2 interrupt - * @arg TIM_IT_CC3: Capture/Compare 3 interrupt - * @arg TIM_IT_CC4: Capture/Compare 4 interrupt - * @arg TIM_IT_COM: Commutation interrupt - * @arg TIM_IT_TRIGGER: Trigger interrupt - * @arg TIM_IT_BREAK: Break interrupt - * @retval None - */ -#define __HAL_TIM_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->DIER &= ~(__INTERRUPT__)) - -/** @brief Enable the specified DMA request. - * @param __HANDLE__ specifies the TIM Handle. - * @param __DMA__ specifies the TIM DMA request to enable. - * This parameter can be one of the following values: - * @arg TIM_DMA_UPDATE: Update DMA request - * @arg TIM_DMA_CC1: Capture/Compare 1 DMA request - * @arg TIM_DMA_CC2: Capture/Compare 2 DMA request - * @arg TIM_DMA_CC3: Capture/Compare 3 DMA request - * @arg TIM_DMA_CC4: Capture/Compare 4 DMA request - * @arg TIM_DMA_COM: Commutation DMA request - * @arg TIM_DMA_TRIGGER: Trigger DMA request - * @retval None - */ -#define __HAL_TIM_ENABLE_DMA(__HANDLE__, __DMA__) ((__HANDLE__)->Instance->DIER |= (__DMA__)) - -/** @brief Disable the specified DMA request. - * @param __HANDLE__ specifies the TIM Handle. - * @param __DMA__ specifies the TIM DMA request to disable. - * This parameter can be one of the following values: - * @arg TIM_DMA_UPDATE: Update DMA request - * @arg TIM_DMA_CC1: Capture/Compare 1 DMA request - * @arg TIM_DMA_CC2: Capture/Compare 2 DMA request - * @arg TIM_DMA_CC3: Capture/Compare 3 DMA request - * @arg TIM_DMA_CC4: Capture/Compare 4 DMA request - * @arg TIM_DMA_COM: Commutation DMA request - * @arg TIM_DMA_TRIGGER: Trigger DMA request - * @retval None - */ -#define __HAL_TIM_DISABLE_DMA(__HANDLE__, __DMA__) ((__HANDLE__)->Instance->DIER &= ~(__DMA__)) - -/** @brief Check whether the specified TIM interrupt flag is set or not. - * @param __HANDLE__ specifies the TIM Handle. - * @param __FLAG__ specifies the TIM interrupt flag to check. - * This parameter can be one of the following values: - * @arg TIM_FLAG_UPDATE: Update interrupt flag - * @arg TIM_FLAG_CC1: Capture/Compare 1 interrupt flag - * @arg TIM_FLAG_CC2: Capture/Compare 2 interrupt flag - * @arg TIM_FLAG_CC3: Capture/Compare 3 interrupt flag - * @arg TIM_FLAG_CC4: Capture/Compare 4 interrupt flag - * @arg TIM_FLAG_COM: Commutation interrupt flag - * @arg TIM_FLAG_TRIGGER: Trigger interrupt flag - * @arg TIM_FLAG_BREAK: Break interrupt flag - * @arg TIM_FLAG_CC1OF: Capture/Compare 1 overcapture flag - * @arg TIM_FLAG_CC2OF: Capture/Compare 2 overcapture flag - * @arg TIM_FLAG_CC3OF: Capture/Compare 3 overcapture flag - * @arg TIM_FLAG_CC4OF: Capture/Compare 4 overcapture flag - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_TIM_GET_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->SR &(__FLAG__)) == (__FLAG__)) - -/** @brief Clear the specified TIM interrupt flag. - * @param __HANDLE__ specifies the TIM Handle. - * @param __FLAG__ specifies the TIM interrupt flag to clear. - * This parameter can be one of the following values: - * @arg TIM_FLAG_UPDATE: Update interrupt flag - * @arg TIM_FLAG_CC1: Capture/Compare 1 interrupt flag - * @arg TIM_FLAG_CC2: Capture/Compare 2 interrupt flag - * @arg TIM_FLAG_CC3: Capture/Compare 3 interrupt flag - * @arg TIM_FLAG_CC4: Capture/Compare 4 interrupt flag - * @arg TIM_FLAG_COM: Commutation interrupt flag - * @arg TIM_FLAG_TRIGGER: Trigger interrupt flag - * @arg TIM_FLAG_BREAK: Break interrupt flag - * @arg TIM_FLAG_CC1OF: Capture/Compare 1 overcapture flag - * @arg TIM_FLAG_CC2OF: Capture/Compare 2 overcapture flag - * @arg TIM_FLAG_CC3OF: Capture/Compare 3 overcapture flag - * @arg TIM_FLAG_CC4OF: Capture/Compare 4 overcapture flag - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_TIM_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->SR = ~(__FLAG__)) - -/** - * @brief Check whether the specified TIM interrupt source is enabled or not. - * @param __HANDLE__ TIM handle - * @param __INTERRUPT__ specifies the TIM interrupt source to check. - * This parameter can be one of the following values: - * @arg TIM_IT_UPDATE: Update interrupt - * @arg TIM_IT_CC1: Capture/Compare 1 interrupt - * @arg TIM_IT_CC2: Capture/Compare 2 interrupt - * @arg TIM_IT_CC3: Capture/Compare 3 interrupt - * @arg TIM_IT_CC4: Capture/Compare 4 interrupt - * @arg TIM_IT_COM: Commutation interrupt - * @arg TIM_IT_TRIGGER: Trigger interrupt - * @arg TIM_IT_BREAK: Break interrupt - * @retval The state of TIM_IT (SET or RESET). - */ -#define __HAL_TIM_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) ((((__HANDLE__)->Instance->DIER & (__INTERRUPT__)) \ - == (__INTERRUPT__)) ? SET : RESET) - -/** @brief Clear the TIM interrupt pending bits. - * @param __HANDLE__ TIM handle - * @param __INTERRUPT__ specifies the interrupt pending bit to clear. - * This parameter can be one of the following values: - * @arg TIM_IT_UPDATE: Update interrupt - * @arg TIM_IT_CC1: Capture/Compare 1 interrupt - * @arg TIM_IT_CC2: Capture/Compare 2 interrupt - * @arg TIM_IT_CC3: Capture/Compare 3 interrupt - * @arg TIM_IT_CC4: Capture/Compare 4 interrupt - * @arg TIM_IT_COM: Commutation interrupt - * @arg TIM_IT_TRIGGER: Trigger interrupt - * @arg TIM_IT_BREAK: Break interrupt - * @retval None - */ -#define __HAL_TIM_CLEAR_IT(__HANDLE__, __INTERRUPT__) ((__HANDLE__)->Instance->SR = ~(__INTERRUPT__)) - -/** - * @brief Indicates whether or not the TIM Counter is used as downcounter. - * @param __HANDLE__ TIM handle. - * @retval False (Counter used as upcounter) or True (Counter used as downcounter) - * @note This macro is particularly useful to get the counting mode when the timer operates in Center-aligned mode - * or Encoder mode. - */ -#define __HAL_TIM_IS_TIM_COUNTING_DOWN(__HANDLE__) (((__HANDLE__)->Instance->CR1 &(TIM_CR1_DIR)) == (TIM_CR1_DIR)) - -/** - * @brief Set the TIM Prescaler on runtime. - * @param __HANDLE__ TIM handle. - * @param __PRESC__ specifies the Prescaler new value. - * @retval None - */ -#define __HAL_TIM_SET_PRESCALER(__HANDLE__, __PRESC__) ((__HANDLE__)->Instance->PSC = (__PRESC__)) - -/** - * @brief Set the TIM Counter Register value on runtime. - * @param __HANDLE__ TIM handle. - * @param __COUNTER__ specifies the Counter register new value. - * @retval None - */ -#define __HAL_TIM_SET_COUNTER(__HANDLE__, __COUNTER__) ((__HANDLE__)->Instance->CNT = (__COUNTER__)) - -/** - * @brief Get the TIM Counter Register value on runtime. - * @param __HANDLE__ TIM handle. - * @retval 16-bit or 32-bit value of the timer counter register (TIMx_CNT) - */ -#define __HAL_TIM_GET_COUNTER(__HANDLE__) ((__HANDLE__)->Instance->CNT) - -/** - * @brief Set the TIM Autoreload Register value on runtime without calling another time any Init function. - * @param __HANDLE__ TIM handle. - * @param __AUTORELOAD__ specifies the Counter register new value. - * @retval None - */ -#define __HAL_TIM_SET_AUTORELOAD(__HANDLE__, __AUTORELOAD__) \ - do{ \ - (__HANDLE__)->Instance->ARR = (__AUTORELOAD__); \ - (__HANDLE__)->Init.Period = (__AUTORELOAD__); \ - } while(0) - -/** - * @brief Get the TIM Autoreload Register value on runtime. - * @param __HANDLE__ TIM handle. - * @retval 16-bit or 32-bit value of the timer auto-reload register(TIMx_ARR) - */ -#define __HAL_TIM_GET_AUTORELOAD(__HANDLE__) ((__HANDLE__)->Instance->ARR) - -/** - * @brief Set the TIM Clock Division value on runtime without calling another time any Init function. - * @param __HANDLE__ TIM handle. - * @param __CKD__ specifies the clock division value. - * This parameter can be one of the following value: - * @arg TIM_CLOCKDIVISION_DIV1: tDTS=tCK_INT - * @arg TIM_CLOCKDIVISION_DIV2: tDTS=2*tCK_INT - * @arg TIM_CLOCKDIVISION_DIV4: tDTS=4*tCK_INT - * @retval None - */ -#define __HAL_TIM_SET_CLOCKDIVISION(__HANDLE__, __CKD__) \ - do{ \ - (__HANDLE__)->Instance->CR1 &= (~TIM_CR1_CKD); \ - (__HANDLE__)->Instance->CR1 |= (__CKD__); \ - (__HANDLE__)->Init.ClockDivision = (__CKD__); \ - } while(0) - -/** - * @brief Get the TIM Clock Division value on runtime. - * @param __HANDLE__ TIM handle. - * @retval The clock division can be one of the following values: - * @arg TIM_CLOCKDIVISION_DIV1: tDTS=tCK_INT - * @arg TIM_CLOCKDIVISION_DIV2: tDTS=2*tCK_INT - * @arg TIM_CLOCKDIVISION_DIV4: tDTS=4*tCK_INT - */ -#define __HAL_TIM_GET_CLOCKDIVISION(__HANDLE__) ((__HANDLE__)->Instance->CR1 & TIM_CR1_CKD) - -/** - * @brief Set the TIM Input Capture prescaler on runtime without calling another time HAL_TIM_IC_ConfigChannel() - * function. - * @param __HANDLE__ TIM handle. - * @param __CHANNEL__ TIM Channels to be configured. - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @param __ICPSC__ specifies the Input Capture4 prescaler new value. - * This parameter can be one of the following values: - * @arg TIM_ICPSC_DIV1: no prescaler - * @arg TIM_ICPSC_DIV2: capture is done once every 2 events - * @arg TIM_ICPSC_DIV4: capture is done once every 4 events - * @arg TIM_ICPSC_DIV8: capture is done once every 8 events - * @retval None - */ -#define __HAL_TIM_SET_ICPRESCALER(__HANDLE__, __CHANNEL__, __ICPSC__) \ - do{ \ - TIM_RESET_ICPRESCALERVALUE((__HANDLE__), (__CHANNEL__)); \ - TIM_SET_ICPRESCALERVALUE((__HANDLE__), (__CHANNEL__), (__ICPSC__)); \ - } while(0) - -/** - * @brief Get the TIM Input Capture prescaler on runtime. - * @param __HANDLE__ TIM handle. - * @param __CHANNEL__ TIM Channels to be configured. - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: get input capture 1 prescaler value - * @arg TIM_CHANNEL_2: get input capture 2 prescaler value - * @arg TIM_CHANNEL_3: get input capture 3 prescaler value - * @arg TIM_CHANNEL_4: get input capture 4 prescaler value - * @retval The input capture prescaler can be one of the following values: - * @arg TIM_ICPSC_DIV1: no prescaler - * @arg TIM_ICPSC_DIV2: capture is done once every 2 events - * @arg TIM_ICPSC_DIV4: capture is done once every 4 events - * @arg TIM_ICPSC_DIV8: capture is done once every 8 events - */ -#define __HAL_TIM_GET_ICPRESCALER(__HANDLE__, __CHANNEL__) \ - (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCMR1 & TIM_CCMR1_IC1PSC) :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? (((__HANDLE__)->Instance->CCMR1 & TIM_CCMR1_IC2PSC) >> 8U) :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCMR2 & TIM_CCMR2_IC3PSC) :\ - (((__HANDLE__)->Instance->CCMR2 & TIM_CCMR2_IC4PSC)) >> 8U) - -/** - * @brief Set the TIM Capture Compare Register value on runtime without calling another time ConfigChannel function. - * @param __HANDLE__ TIM handle. - * @param __CHANNEL__ TIM Channels to be configured. - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @param __COMPARE__ specifies the Capture Compare register new value. - * @retval None - */ -#define __HAL_TIM_SET_COMPARE(__HANDLE__, __CHANNEL__, __COMPARE__) \ - (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCR1 = (__COMPARE__)) :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCR2 = (__COMPARE__)) :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCR3 = (__COMPARE__)) :\ - ((__HANDLE__)->Instance->CCR4 = (__COMPARE__))) - -/** - * @brief Get the TIM Capture Compare Register value on runtime. - * @param __HANDLE__ TIM handle. - * @param __CHANNEL__ TIM Channel associated with the capture compare register - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: get capture/compare 1 register value - * @arg TIM_CHANNEL_2: get capture/compare 2 register value - * @arg TIM_CHANNEL_3: get capture/compare 3 register value - * @arg TIM_CHANNEL_4: get capture/compare 4 register value - * @retval 16-bit or 32-bit value of the capture/compare register (TIMx_CCRy) - */ -#define __HAL_TIM_GET_COMPARE(__HANDLE__, __CHANNEL__) \ - (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCR1) :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCR2) :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCR3) :\ - ((__HANDLE__)->Instance->CCR4)) - -/** - * @brief Set the TIM Output compare preload. - * @param __HANDLE__ TIM handle. - * @param __CHANNEL__ TIM Channels to be configured. - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @retval None - */ -#define __HAL_TIM_ENABLE_OCxPRELOAD(__HANDLE__, __CHANNEL__) \ - (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCMR1 |= TIM_CCMR1_OC1PE) :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCMR1 |= TIM_CCMR1_OC2PE) :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCMR2 |= TIM_CCMR2_OC3PE) :\ - ((__HANDLE__)->Instance->CCMR2 |= TIM_CCMR2_OC4PE)) - -/** - * @brief Reset the TIM Output compare preload. - * @param __HANDLE__ TIM handle. - * @param __CHANNEL__ TIM Channels to be configured. - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @retval None - */ -#define __HAL_TIM_DISABLE_OCxPRELOAD(__HANDLE__, __CHANNEL__) \ - (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCMR1 &= ~TIM_CCMR1_OC1PE) :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCMR1 &= ~TIM_CCMR1_OC2PE) :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCMR2 &= ~TIM_CCMR2_OC3PE) :\ - ((__HANDLE__)->Instance->CCMR2 &= ~TIM_CCMR2_OC4PE)) - -/** - * @brief Enable fast mode for a given channel. - * @param __HANDLE__ TIM handle. - * @param __CHANNEL__ TIM Channels to be configured. - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @note When fast mode is enabled an active edge on the trigger input acts - * like a compare match on CCx output. Delay to sample the trigger - * input and to activate CCx output is reduced to 3 clock cycles. - * @note Fast mode acts only if the channel is configured in PWM1 or PWM2 mode. - * @retval None - */ -#define __HAL_TIM_ENABLE_OCxFAST(__HANDLE__, __CHANNEL__) \ - (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCMR1 |= TIM_CCMR1_OC1FE) :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCMR1 |= TIM_CCMR1_OC2FE) :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCMR2 |= TIM_CCMR2_OC3FE) :\ - ((__HANDLE__)->Instance->CCMR2 |= TIM_CCMR2_OC4FE)) - -/** - * @brief Disable fast mode for a given channel. - * @param __HANDLE__ TIM handle. - * @param __CHANNEL__ TIM Channels to be configured. - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @note When fast mode is disabled CCx output behaves normally depending - * on counter and CCRx values even when the trigger is ON. The minimum - * delay to activate CCx output when an active edge occurs on the - * trigger input is 5 clock cycles. - * @retval None - */ -#define __HAL_TIM_DISABLE_OCxFAST(__HANDLE__, __CHANNEL__) \ - (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCMR1 &= ~TIM_CCMR1_OC1FE) :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCMR1 &= ~TIM_CCMR1_OC2FE) :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCMR2 &= ~TIM_CCMR2_OC3FE) :\ - ((__HANDLE__)->Instance->CCMR2 &= ~TIM_CCMR2_OC4FE)) - -/** - * @brief Set the Update Request Source (URS) bit of the TIMx_CR1 register. - * @param __HANDLE__ TIM handle. - * @note When the URS bit of the TIMx_CR1 register is set, only counter - * overflow/underflow generates an update interrupt or DMA request (if - * enabled) - * @retval None - */ -#define __HAL_TIM_URS_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1|= TIM_CR1_URS) - -/** - * @brief Reset the Update Request Source (URS) bit of the TIMx_CR1 register. - * @param __HANDLE__ TIM handle. - * @note When the URS bit of the TIMx_CR1 register is reset, any of the - * following events generate an update interrupt or DMA request (if - * enabled): - * _ Counter overflow underflow - * _ Setting the UG bit - * _ Update generation through the slave mode controller - * @retval None - */ -#define __HAL_TIM_URS_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1&=~TIM_CR1_URS) - -/** - * @brief Set the TIM Capture x input polarity on runtime. - * @param __HANDLE__ TIM handle. - * @param __CHANNEL__ TIM Channels to be configured. - * This parameter can be one of the following values: - * @arg TIM_CHANNEL_1: TIM Channel 1 selected - * @arg TIM_CHANNEL_2: TIM Channel 2 selected - * @arg TIM_CHANNEL_3: TIM Channel 3 selected - * @arg TIM_CHANNEL_4: TIM Channel 4 selected - * @param __POLARITY__ Polarity for TIx source - * @arg TIM_INPUTCHANNELPOLARITY_RISING: Rising Edge - * @arg TIM_INPUTCHANNELPOLARITY_FALLING: Falling Edge - * @arg TIM_INPUTCHANNELPOLARITY_BOTHEDGE: Rising and Falling Edge - * @retval None - */ -#define __HAL_TIM_SET_CAPTUREPOLARITY(__HANDLE__, __CHANNEL__, __POLARITY__) \ - do{ \ - TIM_RESET_CAPTUREPOLARITY((__HANDLE__), (__CHANNEL__)); \ - TIM_SET_CAPTUREPOLARITY((__HANDLE__), (__CHANNEL__), (__POLARITY__)); \ - }while(0) - -/** - * @} - */ -/* End of exported macros ----------------------------------------------------*/ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup TIM_Private_Constants TIM Private Constants - * @{ - */ -/* The counter of a timer instance is disabled only if all the CCx and CCxN - channels have been disabled */ -#define TIM_CCER_CCxE_MASK ((uint32_t)(TIM_CCER_CC1E | TIM_CCER_CC2E | TIM_CCER_CC3E | TIM_CCER_CC4E)) -#define TIM_CCER_CCxNE_MASK ((uint32_t)(TIM_CCER_CC1NE | TIM_CCER_CC2NE | TIM_CCER_CC3NE)) -/** - * @} - */ -/* End of private constants --------------------------------------------------*/ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup TIM_Private_Macros TIM Private Macros - * @{ - */ -#define IS_TIM_CLEARINPUT_SOURCE(__MODE__) (((__MODE__) == TIM_CLEARINPUTSOURCE_NONE) || \ - ((__MODE__) == TIM_CLEARINPUTSOURCE_ETR)) - -#define IS_TIM_DMA_BASE(__BASE__) (((__BASE__) == TIM_DMABASE_CR1) || \ - ((__BASE__) == TIM_DMABASE_CR2) || \ - ((__BASE__) == TIM_DMABASE_SMCR) || \ - ((__BASE__) == TIM_DMABASE_DIER) || \ - ((__BASE__) == TIM_DMABASE_SR) || \ - ((__BASE__) == TIM_DMABASE_EGR) || \ - ((__BASE__) == TIM_DMABASE_CCMR1) || \ - ((__BASE__) == TIM_DMABASE_CCMR2) || \ - ((__BASE__) == TIM_DMABASE_CCER) || \ - ((__BASE__) == TIM_DMABASE_CNT) || \ - ((__BASE__) == TIM_DMABASE_PSC) || \ - ((__BASE__) == TIM_DMABASE_ARR) || \ - ((__BASE__) == TIM_DMABASE_RCR) || \ - ((__BASE__) == TIM_DMABASE_CCR1) || \ - ((__BASE__) == TIM_DMABASE_CCR2) || \ - ((__BASE__) == TIM_DMABASE_CCR3) || \ - ((__BASE__) == TIM_DMABASE_CCR4) || \ - ((__BASE__) == TIM_DMABASE_BDTR)) - -#define IS_TIM_EVENT_SOURCE(__SOURCE__) ((((__SOURCE__) & 0xFFFFFF00U) == 0x00000000U) && ((__SOURCE__) != 0x00000000U)) - -#define IS_TIM_COUNTER_MODE(__MODE__) (((__MODE__) == TIM_COUNTERMODE_UP) || \ - ((__MODE__) == TIM_COUNTERMODE_DOWN) || \ - ((__MODE__) == TIM_COUNTERMODE_CENTERALIGNED1) || \ - ((__MODE__) == TIM_COUNTERMODE_CENTERALIGNED2) || \ - ((__MODE__) == TIM_COUNTERMODE_CENTERALIGNED3)) - -#define IS_TIM_CLOCKDIVISION_DIV(__DIV__) (((__DIV__) == TIM_CLOCKDIVISION_DIV1) || \ - ((__DIV__) == TIM_CLOCKDIVISION_DIV2) || \ - ((__DIV__) == TIM_CLOCKDIVISION_DIV4)) - -#define IS_TIM_AUTORELOAD_PRELOAD(PRELOAD) (((PRELOAD) == TIM_AUTORELOAD_PRELOAD_DISABLE) || \ - ((PRELOAD) == TIM_AUTORELOAD_PRELOAD_ENABLE)) - -#define IS_TIM_FAST_STATE(__STATE__) (((__STATE__) == TIM_OCFAST_DISABLE) || \ - ((__STATE__) == TIM_OCFAST_ENABLE)) - -#define IS_TIM_OC_POLARITY(__POLARITY__) (((__POLARITY__) == TIM_OCPOLARITY_HIGH) || \ - ((__POLARITY__) == TIM_OCPOLARITY_LOW)) - -#define IS_TIM_OCN_POLARITY(__POLARITY__) (((__POLARITY__) == TIM_OCNPOLARITY_HIGH) || \ - ((__POLARITY__) == TIM_OCNPOLARITY_LOW)) - -#define IS_TIM_OCIDLE_STATE(__STATE__) (((__STATE__) == TIM_OCIDLESTATE_SET) || \ - ((__STATE__) == TIM_OCIDLESTATE_RESET)) - -#define IS_TIM_OCNIDLE_STATE(__STATE__) (((__STATE__) == TIM_OCNIDLESTATE_SET) || \ - ((__STATE__) == TIM_OCNIDLESTATE_RESET)) - -#define IS_TIM_ENCODERINPUT_POLARITY(__POLARITY__) (((__POLARITY__) == TIM_ENCODERINPUTPOLARITY_RISING) || \ - ((__POLARITY__) == TIM_ENCODERINPUTPOLARITY_FALLING)) - -#define IS_TIM_IC_POLARITY(__POLARITY__) (((__POLARITY__) == TIM_ICPOLARITY_RISING) || \ - ((__POLARITY__) == TIM_ICPOLARITY_FALLING) || \ - ((__POLARITY__) == TIM_ICPOLARITY_BOTHEDGE)) - -#define IS_TIM_IC_SELECTION(__SELECTION__) (((__SELECTION__) == TIM_ICSELECTION_DIRECTTI) || \ - ((__SELECTION__) == TIM_ICSELECTION_INDIRECTTI) || \ - ((__SELECTION__) == TIM_ICSELECTION_TRC)) - -#define IS_TIM_IC_PRESCALER(__PRESCALER__) (((__PRESCALER__) == TIM_ICPSC_DIV1) || \ - ((__PRESCALER__) == TIM_ICPSC_DIV2) || \ - ((__PRESCALER__) == TIM_ICPSC_DIV4) || \ - ((__PRESCALER__) == TIM_ICPSC_DIV8)) - -#define IS_TIM_OPM_MODE(__MODE__) (((__MODE__) == TIM_OPMODE_SINGLE) || \ - ((__MODE__) == TIM_OPMODE_REPETITIVE)) - -#define IS_TIM_ENCODER_MODE(__MODE__) (((__MODE__) == TIM_ENCODERMODE_TI1) || \ - ((__MODE__) == TIM_ENCODERMODE_TI2) || \ - ((__MODE__) == TIM_ENCODERMODE_TI12)) - -#define IS_TIM_DMA_SOURCE(__SOURCE__) ((((__SOURCE__) & 0xFFFF80FFU) == 0x00000000U) && ((__SOURCE__) != 0x00000000U)) - -#define IS_TIM_CHANNELS(__CHANNEL__) (((__CHANNEL__) == TIM_CHANNEL_1) || \ - ((__CHANNEL__) == TIM_CHANNEL_2) || \ - ((__CHANNEL__) == TIM_CHANNEL_3) || \ - ((__CHANNEL__) == TIM_CHANNEL_4) || \ - ((__CHANNEL__) == TIM_CHANNEL_ALL)) - -#define IS_TIM_OPM_CHANNELS(__CHANNEL__) (((__CHANNEL__) == TIM_CHANNEL_1) || \ - ((__CHANNEL__) == TIM_CHANNEL_2)) - -#define IS_TIM_COMPLEMENTARY_CHANNELS(__CHANNEL__) (((__CHANNEL__) == TIM_CHANNEL_1) || \ - ((__CHANNEL__) == TIM_CHANNEL_2) || \ - ((__CHANNEL__) == TIM_CHANNEL_3)) - -#define IS_TIM_CLOCKSOURCE(__CLOCK__) (((__CLOCK__) == TIM_CLOCKSOURCE_INTERNAL) || \ - ((__CLOCK__) == TIM_CLOCKSOURCE_ETRMODE2) || \ - ((__CLOCK__) == TIM_CLOCKSOURCE_ITR0) || \ - ((__CLOCK__) == TIM_CLOCKSOURCE_ITR1) || \ - ((__CLOCK__) == TIM_CLOCKSOURCE_ITR2) || \ - ((__CLOCK__) == TIM_CLOCKSOURCE_ITR3) || \ - ((__CLOCK__) == TIM_CLOCKSOURCE_TI1ED) || \ - ((__CLOCK__) == TIM_CLOCKSOURCE_TI1) || \ - ((__CLOCK__) == TIM_CLOCKSOURCE_TI2) || \ - ((__CLOCK__) == TIM_CLOCKSOURCE_ETRMODE1)) - -#define IS_TIM_CLOCKPOLARITY(__POLARITY__) (((__POLARITY__) == TIM_CLOCKPOLARITY_INVERTED) || \ - ((__POLARITY__) == TIM_CLOCKPOLARITY_NONINVERTED) || \ - ((__POLARITY__) == TIM_CLOCKPOLARITY_RISING) || \ - ((__POLARITY__) == TIM_CLOCKPOLARITY_FALLING) || \ - ((__POLARITY__) == TIM_CLOCKPOLARITY_BOTHEDGE)) - -#define IS_TIM_CLOCKPRESCALER(__PRESCALER__) (((__PRESCALER__) == TIM_CLOCKPRESCALER_DIV1) || \ - ((__PRESCALER__) == TIM_CLOCKPRESCALER_DIV2) || \ - ((__PRESCALER__) == TIM_CLOCKPRESCALER_DIV4) || \ - ((__PRESCALER__) == TIM_CLOCKPRESCALER_DIV8)) - -#define IS_TIM_CLOCKFILTER(__ICFILTER__) ((__ICFILTER__) <= 0xFU) - -#define IS_TIM_CLEARINPUT_POLARITY(__POLARITY__) (((__POLARITY__) == TIM_CLEARINPUTPOLARITY_INVERTED) || \ - ((__POLARITY__) == TIM_CLEARINPUTPOLARITY_NONINVERTED)) - -#define IS_TIM_CLEARINPUT_PRESCALER(__PRESCALER__) (((__PRESCALER__) == TIM_CLEARINPUTPRESCALER_DIV1) || \ - ((__PRESCALER__) == TIM_CLEARINPUTPRESCALER_DIV2) || \ - ((__PRESCALER__) == TIM_CLEARINPUTPRESCALER_DIV4) || \ - ((__PRESCALER__) == TIM_CLEARINPUTPRESCALER_DIV8)) - -#define IS_TIM_CLEARINPUT_FILTER(__ICFILTER__) ((__ICFILTER__) <= 0xFU) - -#define IS_TIM_OSSR_STATE(__STATE__) (((__STATE__) == TIM_OSSR_ENABLE) || \ - ((__STATE__) == TIM_OSSR_DISABLE)) - -#define IS_TIM_OSSI_STATE(__STATE__) (((__STATE__) == TIM_OSSI_ENABLE) || \ - ((__STATE__) == TIM_OSSI_DISABLE)) - -#define IS_TIM_LOCK_LEVEL(__LEVEL__) (((__LEVEL__) == TIM_LOCKLEVEL_OFF) || \ - ((__LEVEL__) == TIM_LOCKLEVEL_1) || \ - ((__LEVEL__) == TIM_LOCKLEVEL_2) || \ - ((__LEVEL__) == TIM_LOCKLEVEL_3)) - -#define IS_TIM_BREAK_FILTER(__BRKFILTER__) ((__BRKFILTER__) <= 0xFUL) - - -#define IS_TIM_BREAK_STATE(__STATE__) (((__STATE__) == TIM_BREAK_ENABLE) || \ - ((__STATE__) == TIM_BREAK_DISABLE)) - -#define IS_TIM_BREAK_POLARITY(__POLARITY__) (((__POLARITY__) == TIM_BREAKPOLARITY_LOW) || \ - ((__POLARITY__) == TIM_BREAKPOLARITY_HIGH)) - -#define IS_TIM_AUTOMATIC_OUTPUT_STATE(__STATE__) (((__STATE__) == TIM_AUTOMATICOUTPUT_ENABLE) || \ - ((__STATE__) == TIM_AUTOMATICOUTPUT_DISABLE)) - -#define IS_TIM_TRGO_SOURCE(__SOURCE__) (((__SOURCE__) == TIM_TRGO_RESET) || \ - ((__SOURCE__) == TIM_TRGO_ENABLE) || \ - ((__SOURCE__) == TIM_TRGO_UPDATE) || \ - ((__SOURCE__) == TIM_TRGO_OC1) || \ - ((__SOURCE__) == TIM_TRGO_OC1REF) || \ - ((__SOURCE__) == TIM_TRGO_OC2REF) || \ - ((__SOURCE__) == TIM_TRGO_OC3REF) || \ - ((__SOURCE__) == TIM_TRGO_OC4REF)) - -#define IS_TIM_MSM_STATE(__STATE__) (((__STATE__) == TIM_MASTERSLAVEMODE_ENABLE) || \ - ((__STATE__) == TIM_MASTERSLAVEMODE_DISABLE)) - -#define IS_TIM_SLAVE_MODE(__MODE__) (((__MODE__) == TIM_SLAVEMODE_DISABLE) || \ - ((__MODE__) == TIM_SLAVEMODE_RESET) || \ - ((__MODE__) == TIM_SLAVEMODE_GATED) || \ - ((__MODE__) == TIM_SLAVEMODE_TRIGGER) || \ - ((__MODE__) == TIM_SLAVEMODE_EXTERNAL1)) - -#define IS_TIM_PWM_MODE(__MODE__) (((__MODE__) == TIM_OCMODE_PWM1) || \ - ((__MODE__) == TIM_OCMODE_PWM2)) - -#define IS_TIM_OC_MODE(__MODE__) (((__MODE__) == TIM_OCMODE_TIMING) || \ - ((__MODE__) == TIM_OCMODE_ACTIVE) || \ - ((__MODE__) == TIM_OCMODE_INACTIVE) || \ - ((__MODE__) == TIM_OCMODE_TOGGLE) || \ - ((__MODE__) == TIM_OCMODE_FORCED_ACTIVE) || \ - ((__MODE__) == TIM_OCMODE_FORCED_INACTIVE)) - -#define IS_TIM_TRIGGER_SELECTION(__SELECTION__) (((__SELECTION__) == TIM_TS_ITR0) || \ - ((__SELECTION__) == TIM_TS_ITR1) || \ - ((__SELECTION__) == TIM_TS_ITR2) || \ - ((__SELECTION__) == TIM_TS_ITR3) || \ - ((__SELECTION__) == TIM_TS_TI1F_ED) || \ - ((__SELECTION__) == TIM_TS_TI1FP1) || \ - ((__SELECTION__) == TIM_TS_TI2FP2) || \ - ((__SELECTION__) == TIM_TS_ETRF)) - -#define IS_TIM_INTERNAL_TRIGGEREVENT_SELECTION(__SELECTION__) (((__SELECTION__) == TIM_TS_ITR0) || \ - ((__SELECTION__) == TIM_TS_ITR1) || \ - ((__SELECTION__) == TIM_TS_ITR2) || \ - ((__SELECTION__) == TIM_TS_ITR3) || \ - ((__SELECTION__) == TIM_TS_NONE)) - -#define IS_TIM_TRIGGERPOLARITY(__POLARITY__) (((__POLARITY__) == TIM_TRIGGERPOLARITY_INVERTED ) || \ - ((__POLARITY__) == TIM_TRIGGERPOLARITY_NONINVERTED) || \ - ((__POLARITY__) == TIM_TRIGGERPOLARITY_RISING ) || \ - ((__POLARITY__) == TIM_TRIGGERPOLARITY_FALLING ) || \ - ((__POLARITY__) == TIM_TRIGGERPOLARITY_BOTHEDGE )) - -#define IS_TIM_TRIGGERPRESCALER(__PRESCALER__) (((__PRESCALER__) == TIM_TRIGGERPRESCALER_DIV1) || \ - ((__PRESCALER__) == TIM_TRIGGERPRESCALER_DIV2) || \ - ((__PRESCALER__) == TIM_TRIGGERPRESCALER_DIV4) || \ - ((__PRESCALER__) == TIM_TRIGGERPRESCALER_DIV8)) - -#define IS_TIM_TRIGGERFILTER(__ICFILTER__) ((__ICFILTER__) <= 0xFU) - -#define IS_TIM_TI1SELECTION(__TI1SELECTION__) (((__TI1SELECTION__) == TIM_TI1SELECTION_CH1) || \ - ((__TI1SELECTION__) == TIM_TI1SELECTION_XORCOMBINATION)) - -#define IS_TIM_DMA_LENGTH(__LENGTH__) (((__LENGTH__) == TIM_DMABURSTLENGTH_1TRANSFER) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_2TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_3TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_4TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_5TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_6TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_7TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_8TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_9TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_10TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_11TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_12TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_13TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_14TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_15TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_16TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_17TRANSFERS) || \ - ((__LENGTH__) == TIM_DMABURSTLENGTH_18TRANSFERS)) - -#define IS_TIM_DMA_DATA_LENGTH(LENGTH) (((LENGTH) >= 0x1U) && ((LENGTH) < 0x10000U)) - -#define IS_TIM_IC_FILTER(__ICFILTER__) ((__ICFILTER__) <= 0xFU) - -#define IS_TIM_DEADTIME(__DEADTIME__) ((__DEADTIME__) <= 0xFFU) - -#define IS_TIM_SLAVEMODE_TRIGGER_ENABLED(__TRIGGER__) ((__TRIGGER__) == TIM_SLAVEMODE_TRIGGER) - -#define TIM_SET_ICPRESCALERVALUE(__HANDLE__, __CHANNEL__, __ICPSC__) \ - (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCMR1 |= (__ICPSC__)) :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCMR1 |= ((__ICPSC__) << 8U)) :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCMR2 |= (__ICPSC__)) :\ - ((__HANDLE__)->Instance->CCMR2 |= ((__ICPSC__) << 8U))) - -#define TIM_RESET_ICPRESCALERVALUE(__HANDLE__, __CHANNEL__) \ - (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCMR1 &= ~TIM_CCMR1_IC1PSC) :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCMR1 &= ~TIM_CCMR1_IC2PSC) :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCMR2 &= ~TIM_CCMR2_IC3PSC) :\ - ((__HANDLE__)->Instance->CCMR2 &= ~TIM_CCMR2_IC4PSC)) - -#define TIM_SET_CAPTUREPOLARITY(__HANDLE__, __CHANNEL__, __POLARITY__) \ - (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCER |= (__POLARITY__)) :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCER |= ((__POLARITY__) << 4U)) :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCER |= ((__POLARITY__) << 8U)) :\ - ((__HANDLE__)->Instance->CCER |= (((__POLARITY__) << 12U)))) - -#define TIM_RESET_CAPTUREPOLARITY(__HANDLE__, __CHANNEL__) \ - (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->Instance->CCER &= ~(TIM_CCER_CC1P | TIM_CCER_CC1NP)) :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->Instance->CCER &= ~(TIM_CCER_CC2P | TIM_CCER_CC2NP)) :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->Instance->CCER &= ~(TIM_CCER_CC3P | TIM_CCER_CC3NP)) :\ - ((__HANDLE__)->Instance->CCER &= ~(TIM_CCER_CC4P | TIM_CCER_CC4NP))) - -#define TIM_CHANNEL_STATE_GET(__HANDLE__, __CHANNEL__)\ - (((__CHANNEL__) == TIM_CHANNEL_1) ? (__HANDLE__)->ChannelState[0] :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? (__HANDLE__)->ChannelState[1] :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? (__HANDLE__)->ChannelState[2] :\ - (__HANDLE__)->ChannelState[3]) - -#define TIM_CHANNEL_STATE_SET(__HANDLE__, __CHANNEL__, __CHANNEL_STATE__) \ - (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->ChannelState[0] = (__CHANNEL_STATE__)) :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->ChannelState[1] = (__CHANNEL_STATE__)) :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->ChannelState[2] = (__CHANNEL_STATE__)) :\ - ((__HANDLE__)->ChannelState[3] = (__CHANNEL_STATE__))) - -#define TIM_CHANNEL_STATE_SET_ALL(__HANDLE__, __CHANNEL_STATE__) do { \ - (__HANDLE__)->ChannelState[0] = (__CHANNEL_STATE__); \ - (__HANDLE__)->ChannelState[1] = (__CHANNEL_STATE__); \ - (__HANDLE__)->ChannelState[2] = (__CHANNEL_STATE__); \ - (__HANDLE__)->ChannelState[3] = (__CHANNEL_STATE__); \ - } while(0) - -#define TIM_CHANNEL_N_STATE_GET(__HANDLE__, __CHANNEL__)\ - (((__CHANNEL__) == TIM_CHANNEL_1) ? (__HANDLE__)->ChannelNState[0] :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? (__HANDLE__)->ChannelNState[1] :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? (__HANDLE__)->ChannelNState[2] :\ - (__HANDLE__)->ChannelNState[3]) - -#define TIM_CHANNEL_N_STATE_SET(__HANDLE__, __CHANNEL__, __CHANNEL_STATE__) \ - (((__CHANNEL__) == TIM_CHANNEL_1) ? ((__HANDLE__)->ChannelNState[0] = (__CHANNEL_STATE__)) :\ - ((__CHANNEL__) == TIM_CHANNEL_2) ? ((__HANDLE__)->ChannelNState[1] = (__CHANNEL_STATE__)) :\ - ((__CHANNEL__) == TIM_CHANNEL_3) ? ((__HANDLE__)->ChannelNState[2] = (__CHANNEL_STATE__)) :\ - ((__HANDLE__)->ChannelNState[3] = (__CHANNEL_STATE__))) - -#define TIM_CHANNEL_N_STATE_SET_ALL(__HANDLE__, __CHANNEL_STATE__) do { \ - (__HANDLE__)->ChannelNState[0] = \ - (__CHANNEL_STATE__); \ - (__HANDLE__)->ChannelNState[1] = \ - (__CHANNEL_STATE__); \ - (__HANDLE__)->ChannelNState[2] = \ - (__CHANNEL_STATE__); \ - (__HANDLE__)->ChannelNState[3] = \ - (__CHANNEL_STATE__); \ - } while(0) - -/** - * @} - */ -/* End of private macros -----------------------------------------------------*/ - -/* Include TIM HAL Extended module */ -#include "stm32f4xx_hal_tim_ex.h" - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup TIM_Exported_Functions TIM Exported Functions - * @{ - */ - -/** @addtogroup TIM_Exported_Functions_Group1 TIM Time Base functions - * @brief Time Base functions - * @{ - */ -/* Time Base functions ********************************************************/ -HAL_StatusTypeDef HAL_TIM_Base_Init(TIM_HandleTypeDef *htim); -HAL_StatusTypeDef HAL_TIM_Base_DeInit(TIM_HandleTypeDef *htim); -void HAL_TIM_Base_MspInit(TIM_HandleTypeDef *htim); -void HAL_TIM_Base_MspDeInit(TIM_HandleTypeDef *htim); -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_TIM_Base_Start(TIM_HandleTypeDef *htim); -HAL_StatusTypeDef HAL_TIM_Base_Stop(TIM_HandleTypeDef *htim); -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_TIM_Base_Start_IT(TIM_HandleTypeDef *htim); -HAL_StatusTypeDef HAL_TIM_Base_Stop_IT(TIM_HandleTypeDef *htim); -/* Non-Blocking mode: DMA */ -HAL_StatusTypeDef HAL_TIM_Base_Start_DMA(TIM_HandleTypeDef *htim, uint32_t *pData, uint16_t Length); -HAL_StatusTypeDef HAL_TIM_Base_Stop_DMA(TIM_HandleTypeDef *htim); -/** - * @} - */ - -/** @addtogroup TIM_Exported_Functions_Group2 TIM Output Compare functions - * @brief TIM Output Compare functions - * @{ - */ -/* Timer Output Compare functions *********************************************/ -HAL_StatusTypeDef HAL_TIM_OC_Init(TIM_HandleTypeDef *htim); -HAL_StatusTypeDef HAL_TIM_OC_DeInit(TIM_HandleTypeDef *htim); -void HAL_TIM_OC_MspInit(TIM_HandleTypeDef *htim); -void HAL_TIM_OC_MspDeInit(TIM_HandleTypeDef *htim); -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_TIM_OC_Start(TIM_HandleTypeDef *htim, uint32_t Channel); -HAL_StatusTypeDef HAL_TIM_OC_Stop(TIM_HandleTypeDef *htim, uint32_t Channel); -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_TIM_OC_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel); -HAL_StatusTypeDef HAL_TIM_OC_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel); -/* Non-Blocking mode: DMA */ -HAL_StatusTypeDef HAL_TIM_OC_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length); -HAL_StatusTypeDef HAL_TIM_OC_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel); -/** - * @} - */ - -/** @addtogroup TIM_Exported_Functions_Group3 TIM PWM functions - * @brief TIM PWM functions - * @{ - */ -/* Timer PWM functions ********************************************************/ -HAL_StatusTypeDef HAL_TIM_PWM_Init(TIM_HandleTypeDef *htim); -HAL_StatusTypeDef HAL_TIM_PWM_DeInit(TIM_HandleTypeDef *htim); -void HAL_TIM_PWM_MspInit(TIM_HandleTypeDef *htim); -void HAL_TIM_PWM_MspDeInit(TIM_HandleTypeDef *htim); -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_TIM_PWM_Start(TIM_HandleTypeDef *htim, uint32_t Channel); -HAL_StatusTypeDef HAL_TIM_PWM_Stop(TIM_HandleTypeDef *htim, uint32_t Channel); -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_TIM_PWM_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel); -HAL_StatusTypeDef HAL_TIM_PWM_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel); -/* Non-Blocking mode: DMA */ -HAL_StatusTypeDef HAL_TIM_PWM_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length); -HAL_StatusTypeDef HAL_TIM_PWM_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel); -/** - * @} - */ - -/** @addtogroup TIM_Exported_Functions_Group4 TIM Input Capture functions - * @brief TIM Input Capture functions - * @{ - */ -/* Timer Input Capture functions **********************************************/ -HAL_StatusTypeDef HAL_TIM_IC_Init(TIM_HandleTypeDef *htim); -HAL_StatusTypeDef HAL_TIM_IC_DeInit(TIM_HandleTypeDef *htim); -void HAL_TIM_IC_MspInit(TIM_HandleTypeDef *htim); -void HAL_TIM_IC_MspDeInit(TIM_HandleTypeDef *htim); -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_TIM_IC_Start(TIM_HandleTypeDef *htim, uint32_t Channel); -HAL_StatusTypeDef HAL_TIM_IC_Stop(TIM_HandleTypeDef *htim, uint32_t Channel); -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_TIM_IC_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel); -HAL_StatusTypeDef HAL_TIM_IC_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel); -/* Non-Blocking mode: DMA */ -HAL_StatusTypeDef HAL_TIM_IC_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length); -HAL_StatusTypeDef HAL_TIM_IC_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel); -/** - * @} - */ - -/** @addtogroup TIM_Exported_Functions_Group5 TIM One Pulse functions - * @brief TIM One Pulse functions - * @{ - */ -/* Timer One Pulse functions **************************************************/ -HAL_StatusTypeDef HAL_TIM_OnePulse_Init(TIM_HandleTypeDef *htim, uint32_t OnePulseMode); -HAL_StatusTypeDef HAL_TIM_OnePulse_DeInit(TIM_HandleTypeDef *htim); -void HAL_TIM_OnePulse_MspInit(TIM_HandleTypeDef *htim); -void HAL_TIM_OnePulse_MspDeInit(TIM_HandleTypeDef *htim); -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_TIM_OnePulse_Start(TIM_HandleTypeDef *htim, uint32_t OutputChannel); -HAL_StatusTypeDef HAL_TIM_OnePulse_Stop(TIM_HandleTypeDef *htim, uint32_t OutputChannel); -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_TIM_OnePulse_Start_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel); -HAL_StatusTypeDef HAL_TIM_OnePulse_Stop_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel); -/** - * @} - */ - -/** @addtogroup TIM_Exported_Functions_Group6 TIM Encoder functions - * @brief TIM Encoder functions - * @{ - */ -/* Timer Encoder functions ****************************************************/ -HAL_StatusTypeDef HAL_TIM_Encoder_Init(TIM_HandleTypeDef *htim, TIM_Encoder_InitTypeDef *sConfig); -HAL_StatusTypeDef HAL_TIM_Encoder_DeInit(TIM_HandleTypeDef *htim); -void HAL_TIM_Encoder_MspInit(TIM_HandleTypeDef *htim); -void HAL_TIM_Encoder_MspDeInit(TIM_HandleTypeDef *htim); -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_TIM_Encoder_Start(TIM_HandleTypeDef *htim, uint32_t Channel); -HAL_StatusTypeDef HAL_TIM_Encoder_Stop(TIM_HandleTypeDef *htim, uint32_t Channel); -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_TIM_Encoder_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel); -HAL_StatusTypeDef HAL_TIM_Encoder_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel); -/* Non-Blocking mode: DMA */ -HAL_StatusTypeDef HAL_TIM_Encoder_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData1, - uint32_t *pData2, uint16_t Length); -HAL_StatusTypeDef HAL_TIM_Encoder_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel); -/** - * @} - */ - -/** @addtogroup TIM_Exported_Functions_Group7 TIM IRQ handler management - * @brief IRQ handler management - * @{ - */ -/* Interrupt Handler functions ***********************************************/ -void HAL_TIM_IRQHandler(TIM_HandleTypeDef *htim); -/** - * @} - */ - -/** @defgroup TIM_Exported_Functions_Group8 TIM Peripheral Control functions - * @brief Peripheral Control functions - * @{ - */ -/* Control functions *********************************************************/ -HAL_StatusTypeDef HAL_TIM_OC_ConfigChannel(TIM_HandleTypeDef *htim, TIM_OC_InitTypeDef *sConfig, uint32_t Channel); -HAL_StatusTypeDef HAL_TIM_PWM_ConfigChannel(TIM_HandleTypeDef *htim, TIM_OC_InitTypeDef *sConfig, uint32_t Channel); -HAL_StatusTypeDef HAL_TIM_IC_ConfigChannel(TIM_HandleTypeDef *htim, TIM_IC_InitTypeDef *sConfig, uint32_t Channel); -HAL_StatusTypeDef HAL_TIM_OnePulse_ConfigChannel(TIM_HandleTypeDef *htim, TIM_OnePulse_InitTypeDef *sConfig, - uint32_t OutputChannel, uint32_t InputChannel); -HAL_StatusTypeDef HAL_TIM_ConfigOCrefClear(TIM_HandleTypeDef *htim, TIM_ClearInputConfigTypeDef *sClearInputConfig, - uint32_t Channel); -HAL_StatusTypeDef HAL_TIM_ConfigClockSource(TIM_HandleTypeDef *htim, TIM_ClockConfigTypeDef *sClockSourceConfig); -HAL_StatusTypeDef HAL_TIM_ConfigTI1Input(TIM_HandleTypeDef *htim, uint32_t TI1_Selection); -HAL_StatusTypeDef HAL_TIM_SlaveConfigSynchro(TIM_HandleTypeDef *htim, TIM_SlaveConfigTypeDef *sSlaveConfig); -HAL_StatusTypeDef HAL_TIM_SlaveConfigSynchro_IT(TIM_HandleTypeDef *htim, TIM_SlaveConfigTypeDef *sSlaveConfig); -HAL_StatusTypeDef HAL_TIM_DMABurst_WriteStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress, - uint32_t BurstRequestSrc, uint32_t *BurstBuffer, uint32_t BurstLength); -HAL_StatusTypeDef HAL_TIM_DMABurst_MultiWriteStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress, - uint32_t BurstRequestSrc, uint32_t *BurstBuffer, - uint32_t BurstLength, uint32_t DataLength); -HAL_StatusTypeDef HAL_TIM_DMABurst_WriteStop(TIM_HandleTypeDef *htim, uint32_t BurstRequestSrc); -HAL_StatusTypeDef HAL_TIM_DMABurst_ReadStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress, - uint32_t BurstRequestSrc, uint32_t *BurstBuffer, uint32_t BurstLength); -HAL_StatusTypeDef HAL_TIM_DMABurst_MultiReadStart(TIM_HandleTypeDef *htim, uint32_t BurstBaseAddress, - uint32_t BurstRequestSrc, uint32_t *BurstBuffer, - uint32_t BurstLength, uint32_t DataLength); -HAL_StatusTypeDef HAL_TIM_DMABurst_ReadStop(TIM_HandleTypeDef *htim, uint32_t BurstRequestSrc); -HAL_StatusTypeDef HAL_TIM_GenerateEvent(TIM_HandleTypeDef *htim, uint32_t EventSource); -uint32_t HAL_TIM_ReadCapturedValue(TIM_HandleTypeDef *htim, uint32_t Channel); -/** - * @} - */ - -/** @defgroup TIM_Exported_Functions_Group9 TIM Callbacks functions - * @brief TIM Callbacks functions - * @{ - */ -/* Callback in non blocking modes (Interrupt and DMA) *************************/ -void HAL_TIM_PeriodElapsedCallback(TIM_HandleTypeDef *htim); -void HAL_TIM_PeriodElapsedHalfCpltCallback(TIM_HandleTypeDef *htim); -void HAL_TIM_OC_DelayElapsedCallback(TIM_HandleTypeDef *htim); -void HAL_TIM_IC_CaptureCallback(TIM_HandleTypeDef *htim); -void HAL_TIM_IC_CaptureHalfCpltCallback(TIM_HandleTypeDef *htim); -void HAL_TIM_PWM_PulseFinishedCallback(TIM_HandleTypeDef *htim); -void HAL_TIM_PWM_PulseFinishedHalfCpltCallback(TIM_HandleTypeDef *htim); -void HAL_TIM_TriggerCallback(TIM_HandleTypeDef *htim); -void HAL_TIM_TriggerHalfCpltCallback(TIM_HandleTypeDef *htim); -void HAL_TIM_ErrorCallback(TIM_HandleTypeDef *htim); - -/* Callbacks Register/UnRegister functions ***********************************/ -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) -HAL_StatusTypeDef HAL_TIM_RegisterCallback(TIM_HandleTypeDef *htim, HAL_TIM_CallbackIDTypeDef CallbackID, - pTIM_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_TIM_UnRegisterCallback(TIM_HandleTypeDef *htim, HAL_TIM_CallbackIDTypeDef CallbackID); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @defgroup TIM_Exported_Functions_Group10 TIM Peripheral State functions - * @brief Peripheral State functions - * @{ - */ -/* Peripheral State functions ************************************************/ -HAL_TIM_StateTypeDef HAL_TIM_Base_GetState(TIM_HandleTypeDef *htim); -HAL_TIM_StateTypeDef HAL_TIM_OC_GetState(TIM_HandleTypeDef *htim); -HAL_TIM_StateTypeDef HAL_TIM_PWM_GetState(TIM_HandleTypeDef *htim); -HAL_TIM_StateTypeDef HAL_TIM_IC_GetState(TIM_HandleTypeDef *htim); -HAL_TIM_StateTypeDef HAL_TIM_OnePulse_GetState(TIM_HandleTypeDef *htim); -HAL_TIM_StateTypeDef HAL_TIM_Encoder_GetState(TIM_HandleTypeDef *htim); - -/* Peripheral Channel state functions ************************************************/ -HAL_TIM_ActiveChannel HAL_TIM_GetActiveChannel(TIM_HandleTypeDef *htim); -HAL_TIM_ChannelStateTypeDef HAL_TIM_GetChannelState(TIM_HandleTypeDef *htim, uint32_t Channel); -HAL_TIM_DMABurstStateTypeDef HAL_TIM_DMABurstState(TIM_HandleTypeDef *htim); -/** - * @} - */ - -/** - * @} - */ -/* End of exported functions -------------------------------------------------*/ - -/* Private functions----------------------------------------------------------*/ -/** @defgroup TIM_Private_Functions TIM Private Functions - * @{ - */ -void TIM_Base_SetConfig(TIM_TypeDef *TIMx, TIM_Base_InitTypeDef *Structure); -void TIM_TI1_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ICPolarity, uint32_t TIM_ICSelection, uint32_t TIM_ICFilter); -void TIM_OC2_SetConfig(TIM_TypeDef *TIMx, TIM_OC_InitTypeDef *OC_Config); -void TIM_ETR_SetConfig(TIM_TypeDef *TIMx, uint32_t TIM_ExtTRGPrescaler, - uint32_t TIM_ExtTRGPolarity, uint32_t ExtTRGFilter); - -void TIM_DMADelayPulseHalfCplt(DMA_HandleTypeDef *hdma); -void TIM_DMAError(DMA_HandleTypeDef *hdma); -void TIM_DMACaptureCplt(DMA_HandleTypeDef *hdma); -void TIM_DMACaptureHalfCplt(DMA_HandleTypeDef *hdma); -void TIM_CCxChannelCmd(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t ChannelState); - -#if (USE_HAL_TIM_REGISTER_CALLBACKS == 1) -void TIM_ResetCallback(TIM_HandleTypeDef *htim); -#endif /* USE_HAL_TIM_REGISTER_CALLBACKS */ - -/** - * @} - */ -/* End of private functions --------------------------------------------------*/ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_HAL_TIM_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_tim_ex.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_tim_ex.h deleted file mode 100644 index 737fdc4..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_tim_ex.h +++ /dev/null @@ -1,357 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_tim_ex.h - * @author MCD Application Team - * @brief Header file of TIM HAL Extended module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_TIM_EX_H -#define STM32F4xx_HAL_TIM_EX_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup TIMEx - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup TIMEx_Exported_Types TIM Extended Exported Types - * @{ - */ - -/** - * @brief TIM Hall sensor Configuration Structure definition - */ - -typedef struct -{ - uint32_t IC1Polarity; /*!< Specifies the active edge of the input signal. - This parameter can be a value of @ref TIM_Input_Capture_Polarity */ - - uint32_t IC1Prescaler; /*!< Specifies the Input Capture Prescaler. - This parameter can be a value of @ref TIM_Input_Capture_Prescaler */ - - uint32_t IC1Filter; /*!< Specifies the input capture filter. - This parameter can be a number between Min_Data = 0x0 and Max_Data = 0xF */ - - uint32_t Commutation_Delay; /*!< Specifies the pulse value to be loaded into the Capture Compare Register. - This parameter can be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF */ -} TIM_HallSensor_InitTypeDef; -/** - * @} - */ -/* End of exported types -----------------------------------------------------*/ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup TIMEx_Exported_Constants TIM Extended Exported Constants - * @{ - */ - -/** @defgroup TIMEx_Remap TIM Extended Remapping - * @{ - */ -#if defined (TIM2) -#if defined(TIM8) -#define TIM_TIM2_TIM8_TRGO 0x00000000U /*!< TIM2 ITR1 is connected to TIM8 TRGO */ -#else -#define TIM_TIM2_ETH_PTP TIM_OR_ITR1_RMP_0 /*!< TIM2 ITR1 is connected to PTP trigger output */ -#endif /* TIM8 */ -#define TIM_TIM2_USBFS_SOF TIM_OR_ITR1_RMP_1 /*!< TIM2 ITR1 is connected to OTG FS SOF */ -#define TIM_TIM2_USBHS_SOF (TIM_OR_ITR1_RMP_1 | TIM_OR_ITR1_RMP_0) /*!< TIM2 ITR1 is connected to OTG HS SOF */ -#endif /* TIM2 */ - -#define TIM_TIM5_GPIO 0x00000000U /*!< TIM5 TI4 is connected to GPIO */ -#define TIM_TIM5_LSI TIM_OR_TI4_RMP_0 /*!< TIM5 TI4 is connected to LSI */ -#define TIM_TIM5_LSE TIM_OR_TI4_RMP_1 /*!< TIM5 TI4 is connected to LSE */ -#define TIM_TIM5_RTC (TIM_OR_TI4_RMP_1 | TIM_OR_TI4_RMP_0) /*!< TIM5 TI4 is connected to the RTC wakeup interrupt */ - -#define TIM_TIM11_GPIO 0x00000000U /*!< TIM11 TI1 is connected to GPIO */ -#define TIM_TIM11_HSE TIM_OR_TI1_RMP_1 /*!< TIM11 TI1 is connected to HSE_RTC clock */ -#if defined(SPDIFRX) -#define TIM_TIM11_SPDIFRX TIM_OR_TI1_RMP_0 /*!< TIM11 TI1 is connected to SPDIFRX_FRAME_SYNC */ -#endif /* SPDIFRX*/ - -#if defined(LPTIM_OR_TIM1_ITR2_RMP) && defined(LPTIM_OR_TIM5_ITR1_RMP) && defined(LPTIM_OR_TIM5_ITR1_RMP) -#define LPTIM_REMAP_MASK 0x10000000U - -#define TIM_TIM9_TIM3_TRGO LPTIM_REMAP_MASK /*!< TIM9 ITR1 is connected to TIM3 TRGO */ -#define TIM_TIM9_LPTIM (LPTIM_REMAP_MASK | LPTIM_OR_TIM9_ITR1_RMP) /*!< TIM9 ITR1 is connected to LPTIM1 output */ - -#define TIM_TIM5_TIM3_TRGO LPTIM_REMAP_MASK /*!< TIM5 ITR1 is connected to TIM3 TRGO */ -#define TIM_TIM5_LPTIM (LPTIM_REMAP_MASK | LPTIM_OR_TIM5_ITR1_RMP) /*!< TIM5 ITR1 is connected to LPTIM1 output */ - -#define TIM_TIM1_TIM3_TRGO LPTIM_REMAP_MASK /*!< TIM1 ITR2 is connected to TIM3 TRGO */ -#define TIM_TIM1_LPTIM (LPTIM_REMAP_MASK | LPTIM_OR_TIM1_ITR2_RMP) /*!< TIM1 ITR2 is connected to LPTIM1 output */ -#endif /* LPTIM_OR_TIM1_ITR2_RMP && LPTIM_OR_TIM5_ITR1_RMP && LPTIM_OR_TIM5_ITR1_RMP */ -/** - * @} - */ - -/** - * @} - */ -/* End of exported constants -------------------------------------------------*/ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup TIMEx_Exported_Macros TIM Extended Exported Macros - * @{ - */ - -/** - * @} - */ -/* End of exported macro -----------------------------------------------------*/ - -/* Private macro -------------------------------------------------------------*/ -/** @defgroup TIMEx_Private_Macros TIM Extended Private Macros - * @{ - */ -#if defined(SPDIFRX) -#define IS_TIM_REMAP(INSTANCE, TIM_REMAP) \ - ((((INSTANCE) == TIM2) && (((TIM_REMAP) == TIM_TIM2_TIM8_TRGO) || \ - ((TIM_REMAP) == TIM_TIM2_USBFS_SOF) || \ - ((TIM_REMAP) == TIM_TIM2_USBHS_SOF))) || \ - (((INSTANCE) == TIM5) && (((TIM_REMAP) == TIM_TIM5_GPIO) || \ - ((TIM_REMAP) == TIM_TIM5_LSI) || \ - ((TIM_REMAP) == TIM_TIM5_LSE) || \ - ((TIM_REMAP) == TIM_TIM5_RTC))) || \ - (((INSTANCE) == TIM11) && (((TIM_REMAP) == TIM_TIM11_GPIO) || \ - ((TIM_REMAP) == TIM_TIM11_SPDIFRX) || \ - ((TIM_REMAP) == TIM_TIM11_HSE)))) -#elif defined(TIM2) -#if defined(LPTIM_OR_TIM1_ITR2_RMP) && defined(LPTIM_OR_TIM5_ITR1_RMP) && defined(LPTIM_OR_TIM5_ITR1_RMP) -#define IS_TIM_REMAP(INSTANCE, TIM_REMAP) \ - ((((INSTANCE) == TIM2) && (((TIM_REMAP) == TIM_TIM2_TIM8_TRGO) || \ - ((TIM_REMAP) == TIM_TIM2_USBFS_SOF) || \ - ((TIM_REMAP) == TIM_TIM2_USBHS_SOF))) || \ - (((INSTANCE) == TIM5) && (((TIM_REMAP) == TIM_TIM5_GPIO) || \ - ((TIM_REMAP) == TIM_TIM5_LSI) || \ - ((TIM_REMAP) == TIM_TIM5_LSE) || \ - ((TIM_REMAP) == TIM_TIM5_RTC))) || \ - (((INSTANCE) == TIM11) && (((TIM_REMAP) == TIM_TIM11_GPIO) || \ - ((TIM_REMAP) == TIM_TIM11_HSE))) || \ - (((INSTANCE) == TIM1) && (((TIM_REMAP) == TIM_TIM1_TIM3_TRGO) || \ - ((TIM_REMAP) == TIM_TIM1_LPTIM))) || \ - (((INSTANCE) == TIM5) && (((TIM_REMAP) == TIM_TIM5_TIM3_TRGO) || \ - ((TIM_REMAP) == TIM_TIM5_LPTIM))) || \ - (((INSTANCE) == TIM9) && (((TIM_REMAP) == TIM_TIM9_TIM3_TRGO) || \ - ((TIM_REMAP) == TIM_TIM9_LPTIM)))) -#elif defined(TIM8) -#define IS_TIM_REMAP(INSTANCE, TIM_REMAP) \ - ((((INSTANCE) == TIM2) && (((TIM_REMAP) == TIM_TIM2_TIM8_TRGO) || \ - ((TIM_REMAP) == TIM_TIM2_USBFS_SOF) || \ - ((TIM_REMAP) == TIM_TIM2_USBHS_SOF))) || \ - (((INSTANCE) == TIM5) && (((TIM_REMAP) == TIM_TIM5_GPIO) || \ - ((TIM_REMAP) == TIM_TIM5_LSI) || \ - ((TIM_REMAP) == TIM_TIM5_LSE) || \ - ((TIM_REMAP) == TIM_TIM5_RTC))) || \ - (((INSTANCE) == TIM11) && (((TIM_REMAP) == TIM_TIM11_GPIO) || \ - ((TIM_REMAP) == TIM_TIM11_HSE)))) -#else -#define IS_TIM_REMAP(INSTANCE, TIM_REMAP) \ - ((((INSTANCE) == TIM2) && (((TIM_REMAP) == TIM_TIM2_ETH_PTP) || \ - ((TIM_REMAP) == TIM_TIM2_USBFS_SOF) || \ - ((TIM_REMAP) == TIM_TIM2_USBHS_SOF))) || \ - (((INSTANCE) == TIM5) && (((TIM_REMAP) == TIM_TIM5_GPIO) || \ - ((TIM_REMAP) == TIM_TIM5_LSI) || \ - ((TIM_REMAP) == TIM_TIM5_LSE) || \ - ((TIM_REMAP) == TIM_TIM5_RTC))) || \ - (((INSTANCE) == TIM11) && (((TIM_REMAP) == TIM_TIM11_GPIO) || \ - ((TIM_REMAP) == TIM_TIM11_HSE)))) -#endif /* LPTIM_OR_TIM1_ITR2_RMP && LPTIM_OR_TIM5_ITR1_RMP && LPTIM_OR_TIM5_ITR1_RMP */ -#else -#define IS_TIM_REMAP(INSTANCE, TIM_REMAP) \ - ((((INSTANCE) == TIM5) && (((TIM_REMAP) == TIM_TIM5_GPIO) || \ - ((TIM_REMAP) == TIM_TIM5_LSI) || \ - ((TIM_REMAP) == TIM_TIM5_LSE) || \ - ((TIM_REMAP) == TIM_TIM5_RTC))) || \ - (((INSTANCE) == TIM11) && (((TIM_REMAP) == TIM_TIM11_GPIO) || \ - ((TIM_REMAP) == TIM_TIM11_HSE)))) -#endif /* SPDIFRX */ - -/** - * @} - */ -/* End of private macro ------------------------------------------------------*/ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup TIMEx_Exported_Functions TIM Extended Exported Functions - * @{ - */ - -/** @addtogroup TIMEx_Exported_Functions_Group1 Extended Timer Hall Sensor functions - * @brief Timer Hall Sensor functions - * @{ - */ -/* Timer Hall Sensor functions **********************************************/ -HAL_StatusTypeDef HAL_TIMEx_HallSensor_Init(TIM_HandleTypeDef *htim, TIM_HallSensor_InitTypeDef *sConfig); -HAL_StatusTypeDef HAL_TIMEx_HallSensor_DeInit(TIM_HandleTypeDef *htim); - -void HAL_TIMEx_HallSensor_MspInit(TIM_HandleTypeDef *htim); -void HAL_TIMEx_HallSensor_MspDeInit(TIM_HandleTypeDef *htim); - -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_TIMEx_HallSensor_Start(TIM_HandleTypeDef *htim); -HAL_StatusTypeDef HAL_TIMEx_HallSensor_Stop(TIM_HandleTypeDef *htim); -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_TIMEx_HallSensor_Start_IT(TIM_HandleTypeDef *htim); -HAL_StatusTypeDef HAL_TIMEx_HallSensor_Stop_IT(TIM_HandleTypeDef *htim); -/* Non-Blocking mode: DMA */ -HAL_StatusTypeDef HAL_TIMEx_HallSensor_Start_DMA(TIM_HandleTypeDef *htim, uint32_t *pData, uint16_t Length); -HAL_StatusTypeDef HAL_TIMEx_HallSensor_Stop_DMA(TIM_HandleTypeDef *htim); -/** - * @} - */ - -/** @addtogroup TIMEx_Exported_Functions_Group2 Extended Timer Complementary Output Compare functions - * @brief Timer Complementary Output Compare functions - * @{ - */ -/* Timer Complementary Output Compare functions *****************************/ -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_TIMEx_OCN_Start(TIM_HandleTypeDef *htim, uint32_t Channel); -HAL_StatusTypeDef HAL_TIMEx_OCN_Stop(TIM_HandleTypeDef *htim, uint32_t Channel); - -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_TIMEx_OCN_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel); -HAL_StatusTypeDef HAL_TIMEx_OCN_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel); - -/* Non-Blocking mode: DMA */ -HAL_StatusTypeDef HAL_TIMEx_OCN_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length); -HAL_StatusTypeDef HAL_TIMEx_OCN_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel); -/** - * @} - */ - -/** @addtogroup TIMEx_Exported_Functions_Group3 Extended Timer Complementary PWM functions - * @brief Timer Complementary PWM functions - * @{ - */ -/* Timer Complementary PWM functions ****************************************/ -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_TIMEx_PWMN_Start(TIM_HandleTypeDef *htim, uint32_t Channel); -HAL_StatusTypeDef HAL_TIMEx_PWMN_Stop(TIM_HandleTypeDef *htim, uint32_t Channel); - -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_TIMEx_PWMN_Start_IT(TIM_HandleTypeDef *htim, uint32_t Channel); -HAL_StatusTypeDef HAL_TIMEx_PWMN_Stop_IT(TIM_HandleTypeDef *htim, uint32_t Channel); -/* Non-Blocking mode: DMA */ -HAL_StatusTypeDef HAL_TIMEx_PWMN_Start_DMA(TIM_HandleTypeDef *htim, uint32_t Channel, uint32_t *pData, uint16_t Length); -HAL_StatusTypeDef HAL_TIMEx_PWMN_Stop_DMA(TIM_HandleTypeDef *htim, uint32_t Channel); -/** - * @} - */ - -/** @addtogroup TIMEx_Exported_Functions_Group4 Extended Timer Complementary One Pulse functions - * @brief Timer Complementary One Pulse functions - * @{ - */ -/* Timer Complementary One Pulse functions **********************************/ -/* Blocking mode: Polling */ -HAL_StatusTypeDef HAL_TIMEx_OnePulseN_Start(TIM_HandleTypeDef *htim, uint32_t OutputChannel); -HAL_StatusTypeDef HAL_TIMEx_OnePulseN_Stop(TIM_HandleTypeDef *htim, uint32_t OutputChannel); - -/* Non-Blocking mode: Interrupt */ -HAL_StatusTypeDef HAL_TIMEx_OnePulseN_Start_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel); -HAL_StatusTypeDef HAL_TIMEx_OnePulseN_Stop_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel); -/** - * @} - */ - -/** @addtogroup TIMEx_Exported_Functions_Group5 Extended Peripheral Control functions - * @brief Peripheral Control functions - * @{ - */ -/* Extended Control functions ************************************************/ -HAL_StatusTypeDef HAL_TIMEx_ConfigCommutEvent(TIM_HandleTypeDef *htim, uint32_t InputTrigger, - uint32_t CommutationSource); -HAL_StatusTypeDef HAL_TIMEx_ConfigCommutEvent_IT(TIM_HandleTypeDef *htim, uint32_t InputTrigger, - uint32_t CommutationSource); -HAL_StatusTypeDef HAL_TIMEx_ConfigCommutEvent_DMA(TIM_HandleTypeDef *htim, uint32_t InputTrigger, - uint32_t CommutationSource); -HAL_StatusTypeDef HAL_TIMEx_MasterConfigSynchronization(TIM_HandleTypeDef *htim, - TIM_MasterConfigTypeDef *sMasterConfig); -HAL_StatusTypeDef HAL_TIMEx_ConfigBreakDeadTime(TIM_HandleTypeDef *htim, - TIM_BreakDeadTimeConfigTypeDef *sBreakDeadTimeConfig); -HAL_StatusTypeDef HAL_TIMEx_RemapConfig(TIM_HandleTypeDef *htim, uint32_t Remap); -/** - * @} - */ - -/** @addtogroup TIMEx_Exported_Functions_Group6 Extended Callbacks functions - * @brief Extended Callbacks functions - * @{ - */ -/* Extended Callback **********************************************************/ -void HAL_TIMEx_CommutCallback(TIM_HandleTypeDef *htim); -void HAL_TIMEx_CommutHalfCpltCallback(TIM_HandleTypeDef *htim); -void HAL_TIMEx_BreakCallback(TIM_HandleTypeDef *htim); -/** - * @} - */ - -/** @addtogroup TIMEx_Exported_Functions_Group7 Extended Peripheral State functions - * @brief Extended Peripheral State functions - * @{ - */ -/* Extended Peripheral State functions ***************************************/ -HAL_TIM_StateTypeDef HAL_TIMEx_HallSensor_GetState(TIM_HandleTypeDef *htim); -HAL_TIM_ChannelStateTypeDef HAL_TIMEx_GetChannelNState(TIM_HandleTypeDef *htim, uint32_t ChannelN); -/** - * @} - */ - -/** - * @} - */ -/* End of exported functions -------------------------------------------------*/ - -/* Private functions----------------------------------------------------------*/ -/** @addtogroup TIMEx_Private_Functions TIMEx Private Functions - * @{ - */ -void TIMEx_DMACommutationCplt(DMA_HandleTypeDef *hdma); -void TIMEx_DMACommutationHalfCplt(DMA_HandleTypeDef *hdma); -/** - * @} - */ -/* End of private functions --------------------------------------------------*/ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - - -#endif /* STM32F4xx_HAL_TIM_EX_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_uart.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_uart.h deleted file mode 100644 index 14526e8..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_uart.h +++ /dev/null @@ -1,886 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_uart.h - * @author MCD Application Team - * @brief Header file of UART HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_UART_H -#define __STM32F4xx_HAL_UART_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup UART - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup UART_Exported_Types UART Exported Types - * @{ - */ - -/** - * @brief UART Init Structure definition - */ -typedef struct -{ - uint32_t BaudRate; /*!< This member configures the UART communication baud rate. - The baud rate is computed using the following formula: - - IntegerDivider = ((PCLKx) / (8 * (OVR8+1) * (huart->Init.BaudRate))) - - FractionalDivider = ((IntegerDivider - ((uint32_t) IntegerDivider)) * 8 * (OVR8+1)) + 0.5 - Where OVR8 is the "oversampling by 8 mode" configuration bit in the CR1 register. */ - - uint32_t WordLength; /*!< Specifies the number of data bits transmitted or received in a frame. - This parameter can be a value of @ref UART_Word_Length */ - - uint32_t StopBits; /*!< Specifies the number of stop bits transmitted. - This parameter can be a value of @ref UART_Stop_Bits */ - - uint32_t Parity; /*!< Specifies the parity mode. - This parameter can be a value of @ref UART_Parity - @note When parity is enabled, the computed parity is inserted - at the MSB position of the transmitted data (9th bit when - the word length is set to 9 data bits; 8th bit when the - word length is set to 8 data bits). */ - - uint32_t Mode; /*!< Specifies whether the Receive or Transmit mode is enabled or disabled. - This parameter can be a value of @ref UART_Mode */ - - uint32_t HwFlowCtl; /*!< Specifies whether the hardware flow control mode is enabled or disabled. - This parameter can be a value of @ref UART_Hardware_Flow_Control */ - - uint32_t OverSampling; /*!< Specifies whether the Over sampling 8 is enabled or disabled, to achieve higher speed (up to fPCLK/8). - This parameter can be a value of @ref UART_Over_Sampling */ -} UART_InitTypeDef; - -/** - * @brief HAL UART State structures definition - * @note HAL UART State value is a combination of 2 different substates: gState and RxState. - * - gState contains UART state information related to global Handle management - * and also information related to Tx operations. - * gState value coding follow below described bitmap : - * b7-b6 Error information - * 00 : No Error - * 01 : (Not Used) - * 10 : Timeout - * 11 : Error - * b5 Peripheral initialization status - * 0 : Reset (Peripheral not initialized) - * 1 : Init done (Peripheral initialized. HAL UART Init function already called) - * b4-b3 (not used) - * xx : Should be set to 00 - * b2 Intrinsic process state - * 0 : Ready - * 1 : Busy (Peripheral busy with some configuration or internal operations) - * b1 (not used) - * x : Should be set to 0 - * b0 Tx state - * 0 : Ready (no Tx operation ongoing) - * 1 : Busy (Tx operation ongoing) - * - RxState contains information related to Rx operations. - * RxState value coding follow below described bitmap : - * b7-b6 (not used) - * xx : Should be set to 00 - * b5 Peripheral initialization status - * 0 : Reset (Peripheral not initialized) - * 1 : Init done (Peripheral initialized) - * b4-b2 (not used) - * xxx : Should be set to 000 - * b1 Rx state - * 0 : Ready (no Rx operation ongoing) - * 1 : Busy (Rx operation ongoing) - * b0 (not used) - * x : Should be set to 0. - */ -typedef enum -{ - HAL_UART_STATE_RESET = 0x00U, /*!< Peripheral is not yet Initialized - Value is allowed for gState and RxState */ - HAL_UART_STATE_READY = 0x20U, /*!< Peripheral Initialized and ready for use - Value is allowed for gState and RxState */ - HAL_UART_STATE_BUSY = 0x24U, /*!< an internal process is ongoing - Value is allowed for gState only */ - HAL_UART_STATE_BUSY_TX = 0x21U, /*!< Data Transmission process is ongoing - Value is allowed for gState only */ - HAL_UART_STATE_BUSY_RX = 0x22U, /*!< Data Reception process is ongoing - Value is allowed for RxState only */ - HAL_UART_STATE_BUSY_TX_RX = 0x23U, /*!< Data Transmission and Reception process is ongoing - Not to be used for neither gState nor RxState. - Value is result of combination (Or) between gState and RxState values */ - HAL_UART_STATE_TIMEOUT = 0xA0U, /*!< Timeout state - Value is allowed for gState only */ - HAL_UART_STATE_ERROR = 0xE0U /*!< Error - Value is allowed for gState only */ -} HAL_UART_StateTypeDef; - -/** - * @brief HAL UART Reception type definition - * @note HAL UART Reception type value aims to identify which type of Reception is ongoing. - * It is expected to admit following values : - * HAL_UART_RECEPTION_STANDARD = 0x00U, - * HAL_UART_RECEPTION_TOIDLE = 0x01U, - */ -typedef uint32_t HAL_UART_RxTypeTypeDef; - -/** - * @brief UART handle Structure definition - */ -typedef struct __UART_HandleTypeDef -{ - USART_TypeDef *Instance; /*!< UART registers base address */ - - UART_InitTypeDef Init; /*!< UART communication parameters */ - - uint8_t *pTxBuffPtr; /*!< Pointer to UART Tx transfer Buffer */ - - uint16_t TxXferSize; /*!< UART Tx Transfer size */ - - __IO uint16_t TxXferCount; /*!< UART Tx Transfer Counter */ - - uint8_t *pRxBuffPtr; /*!< Pointer to UART Rx transfer Buffer */ - - uint16_t RxXferSize; /*!< UART Rx Transfer size */ - - __IO uint16_t RxXferCount; /*!< UART Rx Transfer Counter */ - - __IO HAL_UART_RxTypeTypeDef ReceptionType; /*!< Type of ongoing reception */ - - DMA_HandleTypeDef *hdmatx; /*!< UART Tx DMA Handle parameters */ - - DMA_HandleTypeDef *hdmarx; /*!< UART Rx DMA Handle parameters */ - - HAL_LockTypeDef Lock; /*!< Locking object */ - - __IO HAL_UART_StateTypeDef gState; /*!< UART state information related to global Handle management - and also related to Tx operations. - This parameter can be a value of @ref HAL_UART_StateTypeDef */ - - __IO HAL_UART_StateTypeDef RxState; /*!< UART state information related to Rx operations. - This parameter can be a value of @ref HAL_UART_StateTypeDef */ - - __IO uint32_t ErrorCode; /*!< UART Error code */ - -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) - void (* TxHalfCpltCallback)(struct __UART_HandleTypeDef *huart); /*!< UART Tx Half Complete Callback */ - void (* TxCpltCallback)(struct __UART_HandleTypeDef *huart); /*!< UART Tx Complete Callback */ - void (* RxHalfCpltCallback)(struct __UART_HandleTypeDef *huart); /*!< UART Rx Half Complete Callback */ - void (* RxCpltCallback)(struct __UART_HandleTypeDef *huart); /*!< UART Rx Complete Callback */ - void (* ErrorCallback)(struct __UART_HandleTypeDef *huart); /*!< UART Error Callback */ - void (* AbortCpltCallback)(struct __UART_HandleTypeDef *huart); /*!< UART Abort Complete Callback */ - void (* AbortTransmitCpltCallback)(struct __UART_HandleTypeDef *huart); /*!< UART Abort Transmit Complete Callback */ - void (* AbortReceiveCpltCallback)(struct __UART_HandleTypeDef *huart); /*!< UART Abort Receive Complete Callback */ - void (* WakeupCallback)(struct __UART_HandleTypeDef *huart); /*!< UART Wakeup Callback */ - void (* RxEventCallback)(struct __UART_HandleTypeDef *huart, uint16_t Pos); /*!< UART Reception Event Callback */ - - void (* MspInitCallback)(struct __UART_HandleTypeDef *huart); /*!< UART Msp Init callback */ - void (* MspDeInitCallback)(struct __UART_HandleTypeDef *huart); /*!< UART Msp DeInit callback */ -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - -} UART_HandleTypeDef; - -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) -/** - * @brief HAL UART Callback ID enumeration definition - */ -typedef enum -{ - HAL_UART_TX_HALFCOMPLETE_CB_ID = 0x00U, /*!< UART Tx Half Complete Callback ID */ - HAL_UART_TX_COMPLETE_CB_ID = 0x01U, /*!< UART Tx Complete Callback ID */ - HAL_UART_RX_HALFCOMPLETE_CB_ID = 0x02U, /*!< UART Rx Half Complete Callback ID */ - HAL_UART_RX_COMPLETE_CB_ID = 0x03U, /*!< UART Rx Complete Callback ID */ - HAL_UART_ERROR_CB_ID = 0x04U, /*!< UART Error Callback ID */ - HAL_UART_ABORT_COMPLETE_CB_ID = 0x05U, /*!< UART Abort Complete Callback ID */ - HAL_UART_ABORT_TRANSMIT_COMPLETE_CB_ID = 0x06U, /*!< UART Abort Transmit Complete Callback ID */ - HAL_UART_ABORT_RECEIVE_COMPLETE_CB_ID = 0x07U, /*!< UART Abort Receive Complete Callback ID */ - HAL_UART_WAKEUP_CB_ID = 0x08U, /*!< UART Wakeup Callback ID */ - - HAL_UART_MSPINIT_CB_ID = 0x0BU, /*!< UART MspInit callback ID */ - HAL_UART_MSPDEINIT_CB_ID = 0x0CU /*!< UART MspDeInit callback ID */ - -} HAL_UART_CallbackIDTypeDef; - -/** - * @brief HAL UART Callback pointer definition - */ -typedef void (*pUART_CallbackTypeDef)(UART_HandleTypeDef *huart); /*!< pointer to an UART callback function */ -typedef void (*pUART_RxEventCallbackTypeDef)(struct __UART_HandleTypeDef *huart, uint16_t Pos); /*!< pointer to a UART Rx Event specific callback function */ - -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup UART_Exported_Constants UART Exported Constants - * @{ - */ - -/** @defgroup UART_Error_Code UART Error Code - * @{ - */ -#define HAL_UART_ERROR_NONE 0x00000000U /*!< No error */ -#define HAL_UART_ERROR_PE 0x00000001U /*!< Parity error */ -#define HAL_UART_ERROR_NE 0x00000002U /*!< Noise error */ -#define HAL_UART_ERROR_FE 0x00000004U /*!< Frame error */ -#define HAL_UART_ERROR_ORE 0x00000008U /*!< Overrun error */ -#define HAL_UART_ERROR_DMA 0x00000010U /*!< DMA transfer error */ -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) -#define HAL_UART_ERROR_INVALID_CALLBACK 0x00000020U /*!< Invalid Callback error */ -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @defgroup UART_Word_Length UART Word Length - * @{ - */ -#define UART_WORDLENGTH_8B 0x00000000U -#define UART_WORDLENGTH_9B ((uint32_t)USART_CR1_M) -/** - * @} - */ - -/** @defgroup UART_Stop_Bits UART Number of Stop Bits - * @{ - */ -#define UART_STOPBITS_1 0x00000000U -#define UART_STOPBITS_2 ((uint32_t)USART_CR2_STOP_1) -/** - * @} - */ - -/** @defgroup UART_Parity UART Parity - * @{ - */ -#define UART_PARITY_NONE 0x00000000U -#define UART_PARITY_EVEN ((uint32_t)USART_CR1_PCE) -#define UART_PARITY_ODD ((uint32_t)(USART_CR1_PCE | USART_CR1_PS)) -/** - * @} - */ - -/** @defgroup UART_Hardware_Flow_Control UART Hardware Flow Control - * @{ - */ -#define UART_HWCONTROL_NONE 0x00000000U -#define UART_HWCONTROL_RTS ((uint32_t)USART_CR3_RTSE) -#define UART_HWCONTROL_CTS ((uint32_t)USART_CR3_CTSE) -#define UART_HWCONTROL_RTS_CTS ((uint32_t)(USART_CR3_RTSE | USART_CR3_CTSE)) -/** - * @} - */ - -/** @defgroup UART_Mode UART Transfer Mode - * @{ - */ -#define UART_MODE_RX ((uint32_t)USART_CR1_RE) -#define UART_MODE_TX ((uint32_t)USART_CR1_TE) -#define UART_MODE_TX_RX ((uint32_t)(USART_CR1_TE | USART_CR1_RE)) -/** - * @} - */ - -/** @defgroup UART_State UART State - * @{ - */ -#define UART_STATE_DISABLE 0x00000000U -#define UART_STATE_ENABLE ((uint32_t)USART_CR1_UE) -/** - * @} - */ - -/** @defgroup UART_Over_Sampling UART Over Sampling - * @{ - */ -#define UART_OVERSAMPLING_16 0x00000000U -#define UART_OVERSAMPLING_8 ((uint32_t)USART_CR1_OVER8) -/** - * @} - */ - -/** @defgroup UART_LIN_Break_Detection_Length UART LIN Break Detection Length - * @{ - */ -#define UART_LINBREAKDETECTLENGTH_10B 0x00000000U -#define UART_LINBREAKDETECTLENGTH_11B ((uint32_t)USART_CR2_LBDL) -/** - * @} - */ - -/** @defgroup UART_WakeUp_functions UART Wakeup Functions - * @{ - */ -#define UART_WAKEUPMETHOD_IDLELINE 0x00000000U -#define UART_WAKEUPMETHOD_ADDRESSMARK ((uint32_t)USART_CR1_WAKE) -/** - * @} - */ - -/** @defgroup UART_Flags UART FLags - * Elements values convention: 0xXXXX - * - 0xXXXX : Flag mask in the SR register - * @{ - */ -#define UART_FLAG_CTS ((uint32_t)USART_SR_CTS) -#define UART_FLAG_LBD ((uint32_t)USART_SR_LBD) -#define UART_FLAG_TXE ((uint32_t)USART_SR_TXE) -#define UART_FLAG_TC ((uint32_t)USART_SR_TC) -#define UART_FLAG_RXNE ((uint32_t)USART_SR_RXNE) -#define UART_FLAG_IDLE ((uint32_t)USART_SR_IDLE) -#define UART_FLAG_ORE ((uint32_t)USART_SR_ORE) -#define UART_FLAG_NE ((uint32_t)USART_SR_NE) -#define UART_FLAG_FE ((uint32_t)USART_SR_FE) -#define UART_FLAG_PE ((uint32_t)USART_SR_PE) -/** - * @} - */ - -/** @defgroup UART_Interrupt_definition UART Interrupt Definitions - * Elements values convention: 0xY000XXXX - * - XXXX : Interrupt mask (16 bits) in the Y register - * - Y : Interrupt source register (2bits) - * - 0001: CR1 register - * - 0010: CR2 register - * - 0011: CR3 register - * @{ - */ - -#define UART_IT_PE ((uint32_t)(UART_CR1_REG_INDEX << 28U | USART_CR1_PEIE)) -#define UART_IT_TXE ((uint32_t)(UART_CR1_REG_INDEX << 28U | USART_CR1_TXEIE)) -#define UART_IT_TC ((uint32_t)(UART_CR1_REG_INDEX << 28U | USART_CR1_TCIE)) -#define UART_IT_RXNE ((uint32_t)(UART_CR1_REG_INDEX << 28U | USART_CR1_RXNEIE)) -#define UART_IT_IDLE ((uint32_t)(UART_CR1_REG_INDEX << 28U | USART_CR1_IDLEIE)) - -#define UART_IT_LBD ((uint32_t)(UART_CR2_REG_INDEX << 28U | USART_CR2_LBDIE)) - -#define UART_IT_CTS ((uint32_t)(UART_CR3_REG_INDEX << 28U | USART_CR3_CTSIE)) -#define UART_IT_ERR ((uint32_t)(UART_CR3_REG_INDEX << 28U | USART_CR3_EIE)) -/** - * @} - */ - -/** @defgroup UART_RECEPTION_TYPE_Values UART Reception type values - * @{ - */ -#define HAL_UART_RECEPTION_STANDARD (0x00000000U) /*!< Standard reception */ -#define HAL_UART_RECEPTION_TOIDLE (0x00000001U) /*!< Reception till completion or IDLE event */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup UART_Exported_Macros UART Exported Macros - * @{ - */ - -/** @brief Reset UART handle gstate & RxState - * @param __HANDLE__ specifies the UART Handle. - * UART Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @retval None - */ -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) -#define __HAL_UART_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->gState = HAL_UART_STATE_RESET; \ - (__HANDLE__)->RxState = HAL_UART_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0U) -#else -#define __HAL_UART_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->gState = HAL_UART_STATE_RESET; \ - (__HANDLE__)->RxState = HAL_UART_STATE_RESET; \ - } while(0U) -#endif /*USE_HAL_UART_REGISTER_CALLBACKS */ - -/** @brief Flushes the UART DR register - * @param __HANDLE__ specifies the UART Handle. - * UART Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - */ -#define __HAL_UART_FLUSH_DRREGISTER(__HANDLE__) ((__HANDLE__)->Instance->DR) - -/** @brief Checks whether the specified UART flag is set or not. - * @param __HANDLE__ specifies the UART Handle. - * UART Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg UART_FLAG_CTS: CTS Change flag (not available for UART4 and UART5) - * @arg UART_FLAG_LBD: LIN Break detection flag - * @arg UART_FLAG_TXE: Transmit data register empty flag - * @arg UART_FLAG_TC: Transmission Complete flag - * @arg UART_FLAG_RXNE: Receive data register not empty flag - * @arg UART_FLAG_IDLE: Idle Line detection flag - * @arg UART_FLAG_ORE: Overrun Error flag - * @arg UART_FLAG_NE: Noise Error flag - * @arg UART_FLAG_FE: Framing Error flag - * @arg UART_FLAG_PE: Parity Error flag - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_UART_GET_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->SR & (__FLAG__)) == (__FLAG__)) - -/** @brief Clears the specified UART pending flag. - * @param __HANDLE__ specifies the UART Handle. - * UART Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @param __FLAG__ specifies the flag to check. - * This parameter can be any combination of the following values: - * @arg UART_FLAG_CTS: CTS Change flag (not available for UART4 and UART5). - * @arg UART_FLAG_LBD: LIN Break detection flag. - * @arg UART_FLAG_TC: Transmission Complete flag. - * @arg UART_FLAG_RXNE: Receive data register not empty flag. - * - * @note PE (Parity error), FE (Framing error), NE (Noise error), ORE (Overrun - * error) and IDLE (Idle line detected) flags are cleared by software - * sequence: a read operation to USART_SR register followed by a read - * operation to USART_DR register. - * @note RXNE flag can be also cleared by a read to the USART_DR register. - * @note TC flag can be also cleared by software sequence: a read operation to - * USART_SR register followed by a write operation to USART_DR register. - * @note TXE flag is cleared only by a write to the USART_DR register. - * - * @retval None - */ -#define __HAL_UART_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->SR = ~(__FLAG__)) - -/** @brief Clears the UART PE pending flag. - * @param __HANDLE__ specifies the UART Handle. - * UART Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @retval None - */ -#define __HAL_UART_CLEAR_PEFLAG(__HANDLE__) \ - do{ \ - __IO uint32_t tmpreg = 0x00U; \ - tmpreg = (__HANDLE__)->Instance->SR; \ - tmpreg = (__HANDLE__)->Instance->DR; \ - UNUSED(tmpreg); \ - } while(0U) - -/** @brief Clears the UART FE pending flag. - * @param __HANDLE__ specifies the UART Handle. - * UART Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @retval None - */ -#define __HAL_UART_CLEAR_FEFLAG(__HANDLE__) __HAL_UART_CLEAR_PEFLAG(__HANDLE__) - -/** @brief Clears the UART NE pending flag. - * @param __HANDLE__ specifies the UART Handle. - * UART Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @retval None - */ -#define __HAL_UART_CLEAR_NEFLAG(__HANDLE__) __HAL_UART_CLEAR_PEFLAG(__HANDLE__) - -/** @brief Clears the UART ORE pending flag. - * @param __HANDLE__ specifies the UART Handle. - * UART Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @retval None - */ -#define __HAL_UART_CLEAR_OREFLAG(__HANDLE__) __HAL_UART_CLEAR_PEFLAG(__HANDLE__) - -/** @brief Clears the UART IDLE pending flag. - * @param __HANDLE__ specifies the UART Handle. - * UART Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @retval None - */ -#define __HAL_UART_CLEAR_IDLEFLAG(__HANDLE__) __HAL_UART_CLEAR_PEFLAG(__HANDLE__) - -/** @brief Enable the specified UART interrupt. - * @param __HANDLE__ specifies the UART Handle. - * UART Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @param __INTERRUPT__ specifies the UART interrupt source to enable. - * This parameter can be one of the following values: - * @arg UART_IT_CTS: CTS change interrupt - * @arg UART_IT_LBD: LIN Break detection interrupt - * @arg UART_IT_TXE: Transmit Data Register empty interrupt - * @arg UART_IT_TC: Transmission complete interrupt - * @arg UART_IT_RXNE: Receive Data register not empty interrupt - * @arg UART_IT_IDLE: Idle line detection interrupt - * @arg UART_IT_PE: Parity Error interrupt - * @arg UART_IT_ERR: Error interrupt(Frame error, noise error, overrun error) - * @retval None - */ -#define __HAL_UART_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((((__INTERRUPT__) >> 28U) == UART_CR1_REG_INDEX)? ((__HANDLE__)->Instance->CR1 |= ((__INTERRUPT__) & UART_IT_MASK)): \ - (((__INTERRUPT__) >> 28U) == UART_CR2_REG_INDEX)? ((__HANDLE__)->Instance->CR2 |= ((__INTERRUPT__) & UART_IT_MASK)): \ - ((__HANDLE__)->Instance->CR3 |= ((__INTERRUPT__) & UART_IT_MASK))) - -/** @brief Disable the specified UART interrupt. - * @param __HANDLE__ specifies the UART Handle. - * UART Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @param __INTERRUPT__ specifies the UART interrupt source to disable. - * This parameter can be one of the following values: - * @arg UART_IT_CTS: CTS change interrupt - * @arg UART_IT_LBD: LIN Break detection interrupt - * @arg UART_IT_TXE: Transmit Data Register empty interrupt - * @arg UART_IT_TC: Transmission complete interrupt - * @arg UART_IT_RXNE: Receive Data register not empty interrupt - * @arg UART_IT_IDLE: Idle line detection interrupt - * @arg UART_IT_PE: Parity Error interrupt - * @arg UART_IT_ERR: Error interrupt(Frame error, noise error, overrun error) - * @retval None - */ -#define __HAL_UART_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((((__INTERRUPT__) >> 28U) == UART_CR1_REG_INDEX)? ((__HANDLE__)->Instance->CR1 &= ~((__INTERRUPT__) & UART_IT_MASK)): \ - (((__INTERRUPT__) >> 28U) == UART_CR2_REG_INDEX)? ((__HANDLE__)->Instance->CR2 &= ~((__INTERRUPT__) & UART_IT_MASK)): \ - ((__HANDLE__)->Instance->CR3 &= ~ ((__INTERRUPT__) & UART_IT_MASK))) - -/** @brief Checks whether the specified UART interrupt source is enabled or not. - * @param __HANDLE__ specifies the UART Handle. - * UART Handle selects the USARTx or UARTy peripheral - * (USART,UART availability and x,y values depending on device). - * @param __IT__ specifies the UART interrupt source to check. - * This parameter can be one of the following values: - * @arg UART_IT_CTS: CTS change interrupt (not available for UART4 and UART5) - * @arg UART_IT_LBD: LIN Break detection interrupt - * @arg UART_IT_TXE: Transmit Data Register empty interrupt - * @arg UART_IT_TC: Transmission complete interrupt - * @arg UART_IT_RXNE: Receive Data register not empty interrupt - * @arg UART_IT_IDLE: Idle line detection interrupt - * @arg UART_IT_ERR: Error interrupt - * @retval The new state of __IT__ (TRUE or FALSE). - */ -#define __HAL_UART_GET_IT_SOURCE(__HANDLE__, __IT__) (((((__IT__) >> 28U) == UART_CR1_REG_INDEX)? (__HANDLE__)->Instance->CR1:(((((uint32_t)(__IT__)) >> 28U) == UART_CR2_REG_INDEX)? \ - (__HANDLE__)->Instance->CR2 : (__HANDLE__)->Instance->CR3)) & (((uint32_t)(__IT__)) & UART_IT_MASK)) - -/** @brief Enable CTS flow control - * @note This macro allows to enable CTS hardware flow control for a given UART instance, - * without need to call HAL_UART_Init() function. - * As involving direct access to UART registers, usage of this macro should be fully endorsed by user. - * @note As macro is expected to be used for modifying CTS Hw flow control feature activation, without need - * for USART instance Deinit/Init, following conditions for macro call should be fulfilled : - * - UART instance should have already been initialised (through call of HAL_UART_Init() ) - * - macro could only be called when corresponding UART instance is disabled (i.e __HAL_UART_DISABLE(__HANDLE__)) - * and should be followed by an Enable macro (i.e __HAL_UART_ENABLE(__HANDLE__)). - * @param __HANDLE__ specifies the UART Handle. - * The Handle Instance can be any USARTx (supporting the HW Flow control feature). - * It is used to select the USART peripheral (USART availability and x value depending on device). - * @retval None - */ -#define __HAL_UART_HWCONTROL_CTS_ENABLE(__HANDLE__) \ - do{ \ - ATOMIC_SET_BIT((__HANDLE__)->Instance->CR3, USART_CR3_CTSE); \ - (__HANDLE__)->Init.HwFlowCtl |= USART_CR3_CTSE; \ - } while(0U) - -/** @brief Disable CTS flow control - * @note This macro allows to disable CTS hardware flow control for a given UART instance, - * without need to call HAL_UART_Init() function. - * As involving direct access to UART registers, usage of this macro should be fully endorsed by user. - * @note As macro is expected to be used for modifying CTS Hw flow control feature activation, without need - * for USART instance Deinit/Init, following conditions for macro call should be fulfilled : - * - UART instance should have already been initialised (through call of HAL_UART_Init() ) - * - macro could only be called when corresponding UART instance is disabled (i.e __HAL_UART_DISABLE(__HANDLE__)) - * and should be followed by an Enable macro (i.e __HAL_UART_ENABLE(__HANDLE__)). - * @param __HANDLE__ specifies the UART Handle. - * The Handle Instance can be any USARTx (supporting the HW Flow control feature). - * It is used to select the USART peripheral (USART availability and x value depending on device). - * @retval None - */ -#define __HAL_UART_HWCONTROL_CTS_DISABLE(__HANDLE__) \ - do{ \ - ATOMIC_CLEAR_BIT((__HANDLE__)->Instance->CR3, USART_CR3_CTSE); \ - (__HANDLE__)->Init.HwFlowCtl &= ~(USART_CR3_CTSE); \ - } while(0U) - -/** @brief Enable RTS flow control - * This macro allows to enable RTS hardware flow control for a given UART instance, - * without need to call HAL_UART_Init() function. - * As involving direct access to UART registers, usage of this macro should be fully endorsed by user. - * @note As macro is expected to be used for modifying RTS Hw flow control feature activation, without need - * for USART instance Deinit/Init, following conditions for macro call should be fulfilled : - * - UART instance should have already been initialised (through call of HAL_UART_Init() ) - * - macro could only be called when corresponding UART instance is disabled (i.e __HAL_UART_DISABLE(__HANDLE__)) - * and should be followed by an Enable macro (i.e __HAL_UART_ENABLE(__HANDLE__)). - * @param __HANDLE__ specifies the UART Handle. - * The Handle Instance can be any USARTx (supporting the HW Flow control feature). - * It is used to select the USART peripheral (USART availability and x value depending on device). - * @retval None - */ -#define __HAL_UART_HWCONTROL_RTS_ENABLE(__HANDLE__) \ - do{ \ - ATOMIC_SET_BIT((__HANDLE__)->Instance->CR3, USART_CR3_RTSE); \ - (__HANDLE__)->Init.HwFlowCtl |= USART_CR3_RTSE; \ - } while(0U) - -/** @brief Disable RTS flow control - * This macro allows to disable RTS hardware flow control for a given UART instance, - * without need to call HAL_UART_Init() function. - * As involving direct access to UART registers, usage of this macro should be fully endorsed by user. - * @note As macro is expected to be used for modifying RTS Hw flow control feature activation, without need - * for USART instance Deinit/Init, following conditions for macro call should be fulfilled : - * - UART instance should have already been initialised (through call of HAL_UART_Init() ) - * - macro could only be called when corresponding UART instance is disabled (i.e __HAL_UART_DISABLE(__HANDLE__)) - * and should be followed by an Enable macro (i.e __HAL_UART_ENABLE(__HANDLE__)). - * @param __HANDLE__ specifies the UART Handle. - * The Handle Instance can be any USARTx (supporting the HW Flow control feature). - * It is used to select the USART peripheral (USART availability and x value depending on device). - * @retval None - */ -#define __HAL_UART_HWCONTROL_RTS_DISABLE(__HANDLE__) \ - do{ \ - ATOMIC_CLEAR_BIT((__HANDLE__)->Instance->CR3, USART_CR3_RTSE);\ - (__HANDLE__)->Init.HwFlowCtl &= ~(USART_CR3_RTSE); \ - } while(0U) - -/** @brief Macro to enable the UART's one bit sample method - * @param __HANDLE__ specifies the UART Handle. - * @retval None - */ -#define __HAL_UART_ONE_BIT_SAMPLE_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR3|= USART_CR3_ONEBIT) - -/** @brief Macro to disable the UART's one bit sample method - * @param __HANDLE__ specifies the UART Handle. - * @retval None - */ -#define __HAL_UART_ONE_BIT_SAMPLE_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR3\ - &= (uint16_t)~((uint16_t)USART_CR3_ONEBIT)) - -/** @brief Enable UART - * @param __HANDLE__ specifies the UART Handle. - * @retval None - */ -#define __HAL_UART_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1 |= USART_CR1_UE) - -/** @brief Disable UART - * @param __HANDLE__ specifies the UART Handle. - * @retval None - */ -#define __HAL_UART_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1 &= ~USART_CR1_UE) -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup UART_Exported_Functions - * @{ - */ - -/** @addtogroup UART_Exported_Functions_Group1 Initialization and de-initialization functions - * @{ - */ - -/* Initialization/de-initialization functions **********************************/ -HAL_StatusTypeDef HAL_UART_Init(UART_HandleTypeDef *huart); -HAL_StatusTypeDef HAL_HalfDuplex_Init(UART_HandleTypeDef *huart); -HAL_StatusTypeDef HAL_LIN_Init(UART_HandleTypeDef *huart, uint32_t BreakDetectLength); -HAL_StatusTypeDef HAL_MultiProcessor_Init(UART_HandleTypeDef *huart, uint8_t Address, uint32_t WakeUpMethod); -HAL_StatusTypeDef HAL_UART_DeInit(UART_HandleTypeDef *huart); -void HAL_UART_MspInit(UART_HandleTypeDef *huart); -void HAL_UART_MspDeInit(UART_HandleTypeDef *huart); - -/* Callbacks Register/UnRegister functions ***********************************/ -#if (USE_HAL_UART_REGISTER_CALLBACKS == 1) -HAL_StatusTypeDef HAL_UART_RegisterCallback(UART_HandleTypeDef *huart, HAL_UART_CallbackIDTypeDef CallbackID, - pUART_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_UART_UnRegisterCallback(UART_HandleTypeDef *huart, HAL_UART_CallbackIDTypeDef CallbackID); - -HAL_StatusTypeDef HAL_UART_RegisterRxEventCallback(UART_HandleTypeDef *huart, pUART_RxEventCallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_UART_UnRegisterRxEventCallback(UART_HandleTypeDef *huart); -#endif /* USE_HAL_UART_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @addtogroup UART_Exported_Functions_Group2 IO operation functions - * @{ - */ - -/* IO operation functions *******************************************************/ -HAL_StatusTypeDef HAL_UART_Transmit(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_UART_Receive(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_UART_Transmit_IT(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_UART_Receive_IT(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_UART_Transmit_DMA(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_UART_Receive_DMA(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_UART_DMAPause(UART_HandleTypeDef *huart); -HAL_StatusTypeDef HAL_UART_DMAResume(UART_HandleTypeDef *huart); -HAL_StatusTypeDef HAL_UART_DMAStop(UART_HandleTypeDef *huart); - -HAL_StatusTypeDef HAL_UARTEx_ReceiveToIdle(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size, uint16_t *RxLen, - uint32_t Timeout); -HAL_StatusTypeDef HAL_UARTEx_ReceiveToIdle_IT(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef HAL_UARTEx_ReceiveToIdle_DMA(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size); - -/* Transfer Abort functions */ -HAL_StatusTypeDef HAL_UART_Abort(UART_HandleTypeDef *huart); -HAL_StatusTypeDef HAL_UART_AbortTransmit(UART_HandleTypeDef *huart); -HAL_StatusTypeDef HAL_UART_AbortReceive(UART_HandleTypeDef *huart); -HAL_StatusTypeDef HAL_UART_Abort_IT(UART_HandleTypeDef *huart); -HAL_StatusTypeDef HAL_UART_AbortTransmit_IT(UART_HandleTypeDef *huart); -HAL_StatusTypeDef HAL_UART_AbortReceive_IT(UART_HandleTypeDef *huart); - -void HAL_UART_IRQHandler(UART_HandleTypeDef *huart); -void HAL_UART_TxCpltCallback(UART_HandleTypeDef *huart); -void HAL_UART_TxHalfCpltCallback(UART_HandleTypeDef *huart); -void HAL_UART_RxCpltCallback(UART_HandleTypeDef *huart); -void HAL_UART_RxHalfCpltCallback(UART_HandleTypeDef *huart); -void HAL_UART_ErrorCallback(UART_HandleTypeDef *huart); -void HAL_UART_AbortCpltCallback(UART_HandleTypeDef *huart); -void HAL_UART_AbortTransmitCpltCallback(UART_HandleTypeDef *huart); -void HAL_UART_AbortReceiveCpltCallback(UART_HandleTypeDef *huart); - -void HAL_UARTEx_RxEventCallback(UART_HandleTypeDef *huart, uint16_t Size); - -/** - * @} - */ - -/** @addtogroup UART_Exported_Functions_Group3 - * @{ - */ -/* Peripheral Control functions ************************************************/ -HAL_StatusTypeDef HAL_LIN_SendBreak(UART_HandleTypeDef *huart); -HAL_StatusTypeDef HAL_MultiProcessor_EnterMuteMode(UART_HandleTypeDef *huart); -HAL_StatusTypeDef HAL_MultiProcessor_ExitMuteMode(UART_HandleTypeDef *huart); -HAL_StatusTypeDef HAL_HalfDuplex_EnableTransmitter(UART_HandleTypeDef *huart); -HAL_StatusTypeDef HAL_HalfDuplex_EnableReceiver(UART_HandleTypeDef *huart); -/** - * @} - */ - -/** @addtogroup UART_Exported_Functions_Group4 - * @{ - */ -/* Peripheral State functions **************************************************/ -HAL_UART_StateTypeDef HAL_UART_GetState(UART_HandleTypeDef *huart); -uint32_t HAL_UART_GetError(UART_HandleTypeDef *huart); -/** - * @} - */ - -/** - * @} - */ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup UART_Private_Constants UART Private Constants - * @{ - */ -/** @brief UART interruptions flag mask - * - */ -#define UART_IT_MASK 0x0000FFFFU - -#define UART_CR1_REG_INDEX 1U -#define UART_CR2_REG_INDEX 2U -#define UART_CR3_REG_INDEX 3U -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup UART_Private_Macros UART Private Macros - * @{ - */ -#define IS_UART_WORD_LENGTH(LENGTH) (((LENGTH) == UART_WORDLENGTH_8B) || \ - ((LENGTH) == UART_WORDLENGTH_9B)) -#define IS_UART_LIN_WORD_LENGTH(LENGTH) (((LENGTH) == UART_WORDLENGTH_8B)) -#define IS_UART_STOPBITS(STOPBITS) (((STOPBITS) == UART_STOPBITS_1) || \ - ((STOPBITS) == UART_STOPBITS_2)) -#define IS_UART_PARITY(PARITY) (((PARITY) == UART_PARITY_NONE) || \ - ((PARITY) == UART_PARITY_EVEN) || \ - ((PARITY) == UART_PARITY_ODD)) -#define IS_UART_HARDWARE_FLOW_CONTROL(CONTROL)\ - (((CONTROL) == UART_HWCONTROL_NONE) || \ - ((CONTROL) == UART_HWCONTROL_RTS) || \ - ((CONTROL) == UART_HWCONTROL_CTS) || \ - ((CONTROL) == UART_HWCONTROL_RTS_CTS)) -#define IS_UART_MODE(MODE) ((((MODE) & 0x0000FFF3U) == 0x00U) && ((MODE) != 0x00U)) -#define IS_UART_STATE(STATE) (((STATE) == UART_STATE_DISABLE) || \ - ((STATE) == UART_STATE_ENABLE)) -#define IS_UART_OVERSAMPLING(SAMPLING) (((SAMPLING) == UART_OVERSAMPLING_16) || \ - ((SAMPLING) == UART_OVERSAMPLING_8)) -#define IS_UART_LIN_OVERSAMPLING(SAMPLING) (((SAMPLING) == UART_OVERSAMPLING_16)) -#define IS_UART_LIN_BREAK_DETECT_LENGTH(LENGTH) (((LENGTH) == UART_LINBREAKDETECTLENGTH_10B) || \ - ((LENGTH) == UART_LINBREAKDETECTLENGTH_11B)) -#define IS_UART_WAKEUPMETHOD(WAKEUP) (((WAKEUP) == UART_WAKEUPMETHOD_IDLELINE) || \ - ((WAKEUP) == UART_WAKEUPMETHOD_ADDRESSMARK)) -#define IS_UART_BAUDRATE(BAUDRATE) ((BAUDRATE) <= 10500000U) -#define IS_UART_ADDRESS(ADDRESS) ((ADDRESS) <= 0x0FU) - -#define UART_DIV_SAMPLING16(_PCLK_, _BAUD_) ((uint32_t)((((uint64_t)(_PCLK_))*25U)/(4U*((uint64_t)(_BAUD_))))) -#define UART_DIVMANT_SAMPLING16(_PCLK_, _BAUD_) (UART_DIV_SAMPLING16((_PCLK_), (_BAUD_))/100U) -#define UART_DIVFRAQ_SAMPLING16(_PCLK_, _BAUD_) ((((UART_DIV_SAMPLING16((_PCLK_), (_BAUD_)) - (UART_DIVMANT_SAMPLING16((_PCLK_), (_BAUD_)) * 100U)) * 16U)\ - + 50U) / 100U) -/* UART BRR = mantissa + overflow + fraction - = (UART DIVMANT << 4) + (UART DIVFRAQ & 0xF0) + (UART DIVFRAQ & 0x0FU) */ -#define UART_BRR_SAMPLING16(_PCLK_, _BAUD_) ((UART_DIVMANT_SAMPLING16((_PCLK_), (_BAUD_)) << 4U) + \ - (UART_DIVFRAQ_SAMPLING16((_PCLK_), (_BAUD_)) & 0xF0U) + \ - (UART_DIVFRAQ_SAMPLING16((_PCLK_), (_BAUD_)) & 0x0FU)) - -#define UART_DIV_SAMPLING8(_PCLK_, _BAUD_) ((uint32_t)((((uint64_t)(_PCLK_))*25U)/(2U*((uint64_t)(_BAUD_))))) -#define UART_DIVMANT_SAMPLING8(_PCLK_, _BAUD_) (UART_DIV_SAMPLING8((_PCLK_), (_BAUD_))/100U) -#define UART_DIVFRAQ_SAMPLING8(_PCLK_, _BAUD_) ((((UART_DIV_SAMPLING8((_PCLK_), (_BAUD_)) - (UART_DIVMANT_SAMPLING8((_PCLK_), (_BAUD_)) * 100U)) * 8U)\ - + 50U) / 100U) -/* UART BRR = mantissa + overflow + fraction - = (UART DIVMANT << 4) + ((UART DIVFRAQ & 0xF8) << 1) + (UART DIVFRAQ & 0x07U) */ -#define UART_BRR_SAMPLING8(_PCLK_, _BAUD_) ((UART_DIVMANT_SAMPLING8((_PCLK_), (_BAUD_)) << 4U) + \ - ((UART_DIVFRAQ_SAMPLING8((_PCLK_), (_BAUD_)) & 0xF8U) << 1U) + \ - (UART_DIVFRAQ_SAMPLING8((_PCLK_), (_BAUD_)) & 0x07U)) - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup UART_Private_Functions UART Private Functions - * @{ - */ - -HAL_StatusTypeDef UART_Start_Receive_IT(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size); -HAL_StatusTypeDef UART_Start_Receive_DMA(UART_HandleTypeDef *huart, uint8_t *pData, uint16_t Size); - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_UART_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_usart.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_usart.h deleted file mode 100644 index 5b83753..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_usart.h +++ /dev/null @@ -1,650 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_usart.h - * @author MCD Application Team - * @brief Header file of USART HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_USART_H -#define __STM32F4xx_HAL_USART_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup USART - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup USART_Exported_Types USART Exported Types - * @{ - */ - -/** - * @brief USART Init Structure definition - */ -typedef struct -{ - uint32_t BaudRate; /*!< This member configures the Usart communication baud rate. - The baud rate is computed using the following formula: - - IntegerDivider = ((PCLKx) / (8 * (husart->Init.BaudRate))) - - FractionalDivider = ((IntegerDivider - ((uint32_t) IntegerDivider)) * 8) + 0.5 */ - - uint32_t WordLength; /*!< Specifies the number of data bits transmitted or received in a frame. - This parameter can be a value of @ref USART_Word_Length */ - - uint32_t StopBits; /*!< Specifies the number of stop bits transmitted. - This parameter can be a value of @ref USART_Stop_Bits */ - - uint32_t Parity; /*!< Specifies the parity mode. - This parameter can be a value of @ref USART_Parity - @note When parity is enabled, the computed parity is inserted - at the MSB position of the transmitted data (9th bit when - the word length is set to 9 data bits; 8th bit when the - word length is set to 8 data bits). */ - - uint32_t Mode; /*!< Specifies whether the Receive or Transmit mode is enabled or disabled. - This parameter can be a value of @ref USART_Mode */ - - uint32_t CLKPolarity; /*!< Specifies the steady state of the serial clock. - This parameter can be a value of @ref USART_Clock_Polarity */ - - uint32_t CLKPhase; /*!< Specifies the clock transition on which the bit capture is made. - This parameter can be a value of @ref USART_Clock_Phase */ - - uint32_t CLKLastBit; /*!< Specifies whether the clock pulse corresponding to the last transmitted - data bit (MSB) has to be output on the SCLK pin in synchronous mode. - This parameter can be a value of @ref USART_Last_Bit */ -} USART_InitTypeDef; - -/** - * @brief HAL State structures definition - */ -typedef enum -{ - HAL_USART_STATE_RESET = 0x00U, /*!< Peripheral is not yet Initialized */ - HAL_USART_STATE_READY = 0x01U, /*!< Peripheral Initialized and ready for use */ - HAL_USART_STATE_BUSY = 0x02U, /*!< an internal process is ongoing */ - HAL_USART_STATE_BUSY_TX = 0x12U, /*!< Data Transmission process is ongoing */ - HAL_USART_STATE_BUSY_RX = 0x22U, /*!< Data Reception process is ongoing */ - HAL_USART_STATE_BUSY_TX_RX = 0x32U, /*!< Data Transmission Reception process is ongoing */ - HAL_USART_STATE_TIMEOUT = 0x03U, /*!< Timeout state */ - HAL_USART_STATE_ERROR = 0x04U /*!< Error */ -} HAL_USART_StateTypeDef; - -/** - * @brief USART handle Structure definition - */ -typedef struct __USART_HandleTypeDef -{ - USART_TypeDef *Instance; /*!< USART registers base address */ - - USART_InitTypeDef Init; /*!< Usart communication parameters */ - - uint8_t *pTxBuffPtr; /*!< Pointer to Usart Tx transfer Buffer */ - - uint16_t TxXferSize; /*!< Usart Tx Transfer size */ - - __IO uint16_t TxXferCount; /*!< Usart Tx Transfer Counter */ - - uint8_t *pRxBuffPtr; /*!< Pointer to Usart Rx transfer Buffer */ - - uint16_t RxXferSize; /*!< Usart Rx Transfer size */ - - __IO uint16_t RxXferCount; /*!< Usart Rx Transfer Counter */ - - DMA_HandleTypeDef *hdmatx; /*!< Usart Tx DMA Handle parameters */ - - DMA_HandleTypeDef *hdmarx; /*!< Usart Rx DMA Handle parameters */ - - HAL_LockTypeDef Lock; /*!< Locking object */ - - __IO HAL_USART_StateTypeDef State; /*!< Usart communication state */ - - __IO uint32_t ErrorCode; /*!< USART Error code */ - -#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) - void (* TxHalfCpltCallback)(struct __USART_HandleTypeDef *husart); /*!< USART Tx Half Complete Callback */ - void (* TxCpltCallback)(struct __USART_HandleTypeDef *husart); /*!< USART Tx Complete Callback */ - void (* RxHalfCpltCallback)(struct __USART_HandleTypeDef *husart); /*!< USART Rx Half Complete Callback */ - void (* RxCpltCallback)(struct __USART_HandleTypeDef *husart); /*!< USART Rx Complete Callback */ - void (* TxRxCpltCallback)(struct __USART_HandleTypeDef *husart); /*!< USART Tx Rx Complete Callback */ - void (* ErrorCallback)(struct __USART_HandleTypeDef *husart); /*!< USART Error Callback */ - void (* AbortCpltCallback)(struct __USART_HandleTypeDef *husart); /*!< USART Abort Complete Callback */ - - void (* MspInitCallback)(struct __USART_HandleTypeDef *husart); /*!< USART Msp Init callback */ - void (* MspDeInitCallback)(struct __USART_HandleTypeDef *husart); /*!< USART Msp DeInit callback */ -#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ - -} USART_HandleTypeDef; - -#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) -/** - * @brief HAL USART Callback ID enumeration definition - */ -typedef enum -{ - HAL_USART_TX_HALFCOMPLETE_CB_ID = 0x00U, /*!< USART Tx Half Complete Callback ID */ - HAL_USART_TX_COMPLETE_CB_ID = 0x01U, /*!< USART Tx Complete Callback ID */ - HAL_USART_RX_HALFCOMPLETE_CB_ID = 0x02U, /*!< USART Rx Half Complete Callback ID */ - HAL_USART_RX_COMPLETE_CB_ID = 0x03U, /*!< USART Rx Complete Callback ID */ - HAL_USART_TX_RX_COMPLETE_CB_ID = 0x04U, /*!< USART Tx Rx Complete Callback ID */ - HAL_USART_ERROR_CB_ID = 0x05U, /*!< USART Error Callback ID */ - HAL_USART_ABORT_COMPLETE_CB_ID = 0x06U, /*!< USART Abort Complete Callback ID */ - - HAL_USART_MSPINIT_CB_ID = 0x07U, /*!< USART MspInit callback ID */ - HAL_USART_MSPDEINIT_CB_ID = 0x08U /*!< USART MspDeInit callback ID */ - -} HAL_USART_CallbackIDTypeDef; - -/** - * @brief HAL USART Callback pointer definition - */ -typedef void (*pUSART_CallbackTypeDef)(USART_HandleTypeDef *husart); /*!< pointer to an USART callback function */ - -#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup USART_Exported_Constants USART Exported Constants - * @{ - */ - -/** @defgroup USART_Error_Code USART Error Code - * @brief USART Error Code - * @{ - */ -#define HAL_USART_ERROR_NONE 0x00000000U /*!< No error */ -#define HAL_USART_ERROR_PE 0x00000001U /*!< Parity error */ -#define HAL_USART_ERROR_NE 0x00000002U /*!< Noise error */ -#define HAL_USART_ERROR_FE 0x00000004U /*!< Frame error */ -#define HAL_USART_ERROR_ORE 0x00000008U /*!< Overrun error */ -#define HAL_USART_ERROR_DMA 0x00000010U /*!< DMA transfer error */ -#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) -#define HAL_USART_ERROR_INVALID_CALLBACK 0x00000020U /*!< Invalid Callback error */ -#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ -/** - * @} - */ - -/** @defgroup USART_Word_Length USART Word Length - * @{ - */ -#define USART_WORDLENGTH_8B 0x00000000U -#define USART_WORDLENGTH_9B ((uint32_t)USART_CR1_M) -/** - * @} - */ - -/** @defgroup USART_Stop_Bits USART Number of Stop Bits - * @{ - */ -#define USART_STOPBITS_1 0x00000000U -#define USART_STOPBITS_0_5 ((uint32_t)USART_CR2_STOP_0) -#define USART_STOPBITS_2 ((uint32_t)USART_CR2_STOP_1) -#define USART_STOPBITS_1_5 ((uint32_t)(USART_CR2_STOP_0 | USART_CR2_STOP_1)) -/** - * @} - */ - -/** @defgroup USART_Parity USART Parity - * @{ - */ -#define USART_PARITY_NONE 0x00000000U -#define USART_PARITY_EVEN ((uint32_t)USART_CR1_PCE) -#define USART_PARITY_ODD ((uint32_t)(USART_CR1_PCE | USART_CR1_PS)) -/** - * @} - */ - -/** @defgroup USART_Mode USART Mode - * @{ - */ -#define USART_MODE_RX ((uint32_t)USART_CR1_RE) -#define USART_MODE_TX ((uint32_t)USART_CR1_TE) -#define USART_MODE_TX_RX ((uint32_t)(USART_CR1_TE | USART_CR1_RE)) -/** - * @} - */ - -/** @defgroup USART_Clock USART Clock - * @{ - */ -#define USART_CLOCK_DISABLE 0x00000000U -#define USART_CLOCK_ENABLE ((uint32_t)USART_CR2_CLKEN) -/** - * @} - */ - -/** @defgroup USART_Clock_Polarity USART Clock Polarity - * @{ - */ -#define USART_POLARITY_LOW 0x00000000U -#define USART_POLARITY_HIGH ((uint32_t)USART_CR2_CPOL) -/** - * @} - */ - -/** @defgroup USART_Clock_Phase USART Clock Phase - * @{ - */ -#define USART_PHASE_1EDGE 0x00000000U -#define USART_PHASE_2EDGE ((uint32_t)USART_CR2_CPHA) -/** - * @} - */ - -/** @defgroup USART_Last_Bit USART Last Bit - * @{ - */ -#define USART_LASTBIT_DISABLE 0x00000000U -#define USART_LASTBIT_ENABLE ((uint32_t)USART_CR2_LBCL) -/** - * @} - */ - -/** @defgroup USART_NACK_State USART NACK State - * @{ - */ -#define USART_NACK_ENABLE ((uint32_t)USART_CR3_NACK) -#define USART_NACK_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup USART_Flags USART Flags - * Elements values convention: 0xXXXX - * - 0xXXXX : Flag mask in the SR register - * @{ - */ -#define USART_FLAG_TXE ((uint32_t)USART_SR_TXE) -#define USART_FLAG_TC ((uint32_t)USART_SR_TC) -#define USART_FLAG_RXNE ((uint32_t)USART_SR_RXNE) -#define USART_FLAG_IDLE ((uint32_t)USART_SR_IDLE) -#define USART_FLAG_ORE ((uint32_t)USART_SR_ORE) -#define USART_FLAG_NE ((uint32_t)USART_SR_NE) -#define USART_FLAG_FE ((uint32_t)USART_SR_FE) -#define USART_FLAG_PE ((uint32_t)USART_SR_PE) -/** - * @} - */ - -/** @defgroup USART_Interrupt_definition USART Interrupts Definition - * Elements values convention: 0xY000XXXX - * - XXXX : Interrupt mask in the XX register - * - Y : Interrupt source register (2bits) - * - 01: CR1 register - * - 10: CR2 register - * - 11: CR3 register - * @{ - */ -#define USART_IT_PE ((uint32_t)(USART_CR1_REG_INDEX << 28U | USART_CR1_PEIE)) -#define USART_IT_TXE ((uint32_t)(USART_CR1_REG_INDEX << 28U | USART_CR1_TXEIE)) -#define USART_IT_TC ((uint32_t)(USART_CR1_REG_INDEX << 28U | USART_CR1_TCIE)) -#define USART_IT_RXNE ((uint32_t)(USART_CR1_REG_INDEX << 28U | USART_CR1_RXNEIE)) -#define USART_IT_IDLE ((uint32_t)(USART_CR1_REG_INDEX << 28U | USART_CR1_IDLEIE)) -#define USART_IT_ERR ((uint32_t)(USART_CR3_REG_INDEX << 28U | USART_CR3_EIE)) -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup USART_Exported_Macros USART Exported Macros - * @{ - */ - -/** @brief Reset USART handle state - * @param __HANDLE__ specifies the USART Handle. - * USART Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @retval None - */ -#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) -#define __HAL_USART_RESET_HANDLE_STATE(__HANDLE__) do{ \ - (__HANDLE__)->State = HAL_USART_STATE_RESET; \ - (__HANDLE__)->MspInitCallback = NULL; \ - (__HANDLE__)->MspDeInitCallback = NULL; \ - } while(0U) -#else -#define __HAL_USART_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = HAL_USART_STATE_RESET) -#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ - -/** @brief Check whether the specified USART flag is set or not. - * @param __HANDLE__ specifies the USART Handle. - * USART Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg USART_FLAG_TXE: Transmit data register empty flag - * @arg USART_FLAG_TC: Transmission Complete flag - * @arg USART_FLAG_RXNE: Receive data register not empty flag - * @arg USART_FLAG_IDLE: Idle Line detection flag - * @arg USART_FLAG_ORE: Overrun Error flag - * @arg USART_FLAG_NE: Noise Error flag - * @arg USART_FLAG_FE: Framing Error flag - * @arg USART_FLAG_PE: Parity Error flag - * @retval The new state of __FLAG__ (TRUE or FALSE). - */ -#define __HAL_USART_GET_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->SR & (__FLAG__)) == (__FLAG__)) - -/** @brief Clear the specified USART pending flags. - * @param __HANDLE__ specifies the USART Handle. - * USART Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @param __FLAG__ specifies the flag to check. - * This parameter can be any combination of the following values: - * @arg USART_FLAG_TC: Transmission Complete flag. - * @arg USART_FLAG_RXNE: Receive data register not empty flag. - * - * @note PE (Parity error), FE (Framing error), NE (Noise error), ORE (Overrun - * error) and IDLE (Idle line detected) flags are cleared by software - * sequence: a read operation to USART_SR register followed by a read - * operation to USART_DR register. - * @note RXNE flag can be also cleared by a read to the USART_DR register. - * @note TC flag can be also cleared by software sequence: a read operation to - * USART_SR register followed by a write operation to USART_DR register. - * @note TXE flag is cleared only by a write to the USART_DR register. - * - * @retval None - */ -#define __HAL_USART_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->SR = ~(__FLAG__)) - -/** @brief Clear the USART PE pending flag. - * @param __HANDLE__ specifies the USART Handle. - * USART Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @retval None - */ -#define __HAL_USART_CLEAR_PEFLAG(__HANDLE__) \ - do{ \ - __IO uint32_t tmpreg = 0x00U; \ - tmpreg = (__HANDLE__)->Instance->SR; \ - tmpreg = (__HANDLE__)->Instance->DR; \ - UNUSED(tmpreg); \ - } while(0U) - -/** @brief Clear the USART FE pending flag. - * @param __HANDLE__ specifies the USART Handle. - * USART Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @retval None - */ -#define __HAL_USART_CLEAR_FEFLAG(__HANDLE__) __HAL_USART_CLEAR_PEFLAG(__HANDLE__) - -/** @brief Clear the USART NE pending flag. - * @param __HANDLE__ specifies the USART Handle. - * USART Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @retval None - */ -#define __HAL_USART_CLEAR_NEFLAG(__HANDLE__) __HAL_USART_CLEAR_PEFLAG(__HANDLE__) - -/** @brief Clear the USART ORE pending flag. - * @param __HANDLE__ specifies the USART Handle. - * USART Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @retval None - */ -#define __HAL_USART_CLEAR_OREFLAG(__HANDLE__) __HAL_USART_CLEAR_PEFLAG(__HANDLE__) - -/** @brief Clear the USART IDLE pending flag. - * @param __HANDLE__ specifies the USART Handle. - * USART Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @retval None - */ -#define __HAL_USART_CLEAR_IDLEFLAG(__HANDLE__) __HAL_USART_CLEAR_PEFLAG(__HANDLE__) - -/** @brief Enables or disables the specified USART interrupts. - * @param __HANDLE__ specifies the USART Handle. - * USART Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @param __INTERRUPT__ specifies the USART interrupt source to check. - * This parameter can be one of the following values: - * @arg USART_IT_TXE: Transmit Data Register empty interrupt - * @arg USART_IT_TC: Transmission complete interrupt - * @arg USART_IT_RXNE: Receive Data register not empty interrupt - * @arg USART_IT_IDLE: Idle line detection interrupt - * @arg USART_IT_PE: Parity Error interrupt - * @arg USART_IT_ERR: Error interrupt(Frame error, noise error, overrun error) - * @retval None - */ -#define __HAL_USART_ENABLE_IT(__HANDLE__, __INTERRUPT__) ((((__INTERRUPT__) >> 28U) == USART_CR1_REG_INDEX)? ((__HANDLE__)->Instance->CR1 |= ((__INTERRUPT__) & USART_IT_MASK)): \ - (((__INTERRUPT__) >> 28U) == USART_CR2_REG_INDEX)? ((__HANDLE__)->Instance->CR2 |= ((__INTERRUPT__) & USART_IT_MASK)): \ - ((__HANDLE__)->Instance->CR3 |= ((__INTERRUPT__) & USART_IT_MASK))) -#define __HAL_USART_DISABLE_IT(__HANDLE__, __INTERRUPT__) ((((__INTERRUPT__) >> 28U) == USART_CR1_REG_INDEX)? ((__HANDLE__)->Instance->CR1 &= ~((__INTERRUPT__) & USART_IT_MASK)): \ - (((__INTERRUPT__) >> 28U) == USART_CR2_REG_INDEX)? ((__HANDLE__)->Instance->CR2 &= ~((__INTERRUPT__) & USART_IT_MASK)): \ - ((__HANDLE__)->Instance->CR3 &= ~ ((__INTERRUPT__) & USART_IT_MASK))) - -/** @brief Checks whether the specified USART interrupt has occurred or not. - * @param __HANDLE__ specifies the USART Handle. - * USART Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @param __IT__ specifies the USART interrupt source to check. - * This parameter can be one of the following values: - * @arg USART_IT_TXE: Transmit Data Register empty interrupt - * @arg USART_IT_TC: Transmission complete interrupt - * @arg USART_IT_RXNE: Receive Data register not empty interrupt - * @arg USART_IT_IDLE: Idle line detection interrupt - * @arg USART_IT_ERR: Error interrupt - * @arg USART_IT_PE: Parity Error interrupt - * @retval The new state of __IT__ (TRUE or FALSE). - */ -#define __HAL_USART_GET_IT_SOURCE(__HANDLE__, __IT__) (((((__IT__) >> 28U) == USART_CR1_REG_INDEX)? (__HANDLE__)->Instance->CR1:(((((uint32_t)(__IT__)) >> 28U) == USART_CR2_REG_INDEX)? \ - (__HANDLE__)->Instance->CR2 : (__HANDLE__)->Instance->CR3)) & (((uint32_t)(__IT__)) & USART_IT_MASK)) - -/** @brief Macro to enable the USART's one bit sample method - * @param __HANDLE__ specifies the USART Handle. - * @retval None - */ -#define __HAL_USART_ONE_BIT_SAMPLE_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR3 |= USART_CR3_ONEBIT) - -/** @brief Macro to disable the USART's one bit sample method - * @param __HANDLE__ specifies the USART Handle. - * @retval None - */ -#define __HAL_USART_ONE_BIT_SAMPLE_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR3\ - &= (uint16_t)~((uint16_t)USART_CR3_ONEBIT)) - -/** @brief Enable USART - * @param __HANDLE__ specifies the USART Handle. - * USART Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @retval None - */ -#define __HAL_USART_ENABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1 |= USART_CR1_UE) - -/** @brief Disable USART - * @param __HANDLE__ specifies the USART Handle. - * USART Handle selects the USARTx peripheral (USART availability and x value depending on device). - * @retval None - */ -#define __HAL_USART_DISABLE(__HANDLE__) ((__HANDLE__)->Instance->CR1 &= ~USART_CR1_UE) - -/** - * @} - */ -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup USART_Exported_Functions - * @{ - */ - -/** @addtogroup USART_Exported_Functions_Group1 - * @{ - */ -/* Initialization/de-initialization functions **********************************/ -HAL_StatusTypeDef HAL_USART_Init(USART_HandleTypeDef *husart); -HAL_StatusTypeDef HAL_USART_DeInit(USART_HandleTypeDef *husart); -void HAL_USART_MspInit(USART_HandleTypeDef *husart); -void HAL_USART_MspDeInit(USART_HandleTypeDef *husart); - -/* Callbacks Register/UnRegister functions ***********************************/ -#if (USE_HAL_USART_REGISTER_CALLBACKS == 1) -HAL_StatusTypeDef HAL_USART_RegisterCallback(USART_HandleTypeDef *husart, HAL_USART_CallbackIDTypeDef CallbackID, - pUSART_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_USART_UnRegisterCallback(USART_HandleTypeDef *husart, HAL_USART_CallbackIDTypeDef CallbackID); -#endif /* USE_HAL_USART_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @addtogroup USART_Exported_Functions_Group2 - * @{ - */ -/* IO operation functions *******************************************************/ -HAL_StatusTypeDef HAL_USART_Transmit(USART_HandleTypeDef *husart, uint8_t *pTxData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_USART_Receive(USART_HandleTypeDef *husart, uint8_t *pRxData, uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_USART_TransmitReceive(USART_HandleTypeDef *husart, uint8_t *pTxData, uint8_t *pRxData, - uint16_t Size, uint32_t Timeout); -HAL_StatusTypeDef HAL_USART_Transmit_IT(USART_HandleTypeDef *husart, uint8_t *pTxData, uint16_t Size); -HAL_StatusTypeDef HAL_USART_Receive_IT(USART_HandleTypeDef *husart, uint8_t *pRxData, uint16_t Size); -HAL_StatusTypeDef HAL_USART_TransmitReceive_IT(USART_HandleTypeDef *husart, uint8_t *pTxData, uint8_t *pRxData, - uint16_t Size); -HAL_StatusTypeDef HAL_USART_Transmit_DMA(USART_HandleTypeDef *husart, uint8_t *pTxData, uint16_t Size); -HAL_StatusTypeDef HAL_USART_Receive_DMA(USART_HandleTypeDef *husart, uint8_t *pRxData, uint16_t Size); -HAL_StatusTypeDef HAL_USART_TransmitReceive_DMA(USART_HandleTypeDef *husart, uint8_t *pTxData, uint8_t *pRxData, - uint16_t Size); -HAL_StatusTypeDef HAL_USART_DMAPause(USART_HandleTypeDef *husart); -HAL_StatusTypeDef HAL_USART_DMAResume(USART_HandleTypeDef *husart); -HAL_StatusTypeDef HAL_USART_DMAStop(USART_HandleTypeDef *husart); -/* Transfer Abort functions */ -HAL_StatusTypeDef HAL_USART_Abort(USART_HandleTypeDef *husart); -HAL_StatusTypeDef HAL_USART_Abort_IT(USART_HandleTypeDef *husart); - -void HAL_USART_IRQHandler(USART_HandleTypeDef *husart); -void HAL_USART_TxCpltCallback(USART_HandleTypeDef *husart); -void HAL_USART_TxHalfCpltCallback(USART_HandleTypeDef *husart); -void HAL_USART_RxCpltCallback(USART_HandleTypeDef *husart); -void HAL_USART_RxHalfCpltCallback(USART_HandleTypeDef *husart); -void HAL_USART_TxRxCpltCallback(USART_HandleTypeDef *husart); -void HAL_USART_ErrorCallback(USART_HandleTypeDef *husart); -void HAL_USART_AbortCpltCallback(USART_HandleTypeDef *husart); -/** - * @} - */ - -/** @addtogroup USART_Exported_Functions_Group3 - * @{ - */ -/* Peripheral State functions ************************************************/ -HAL_USART_StateTypeDef HAL_USART_GetState(USART_HandleTypeDef *husart); -uint32_t HAL_USART_GetError(USART_HandleTypeDef *husart); -/** - * @} - */ - -/** - * @} - */ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup USART_Private_Constants USART Private Constants - * @{ - */ -/** @brief USART interruptions flag mask - * - */ -#define USART_IT_MASK ((uint32_t) USART_CR1_PEIE | USART_CR1_TXEIE | USART_CR1_TCIE | USART_CR1_RXNEIE | \ - USART_CR1_IDLEIE | USART_CR2_LBDIE | USART_CR3_CTSIE | USART_CR3_EIE ) - -#define USART_CR1_REG_INDEX 1U -#define USART_CR2_REG_INDEX 2U -#define USART_CR3_REG_INDEX 3U -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup USART_Private_Macros USART Private Macros - * @{ - */ -#define IS_USART_NACK_STATE(NACK) (((NACK) == USART_NACK_ENABLE) || \ - ((NACK) == USART_NACK_DISABLE)) - -#define IS_USART_LASTBIT(LASTBIT) (((LASTBIT) == USART_LASTBIT_DISABLE) || \ - ((LASTBIT) == USART_LASTBIT_ENABLE)) - -#define IS_USART_PHASE(CPHA) (((CPHA) == USART_PHASE_1EDGE) || \ - ((CPHA) == USART_PHASE_2EDGE)) - -#define IS_USART_POLARITY(CPOL) (((CPOL) == USART_POLARITY_LOW) || \ - ((CPOL) == USART_POLARITY_HIGH)) - -#define IS_USART_CLOCK(CLOCK) (((CLOCK) == USART_CLOCK_DISABLE) || \ - ((CLOCK) == USART_CLOCK_ENABLE)) - -#define IS_USART_WORD_LENGTH(LENGTH) (((LENGTH) == USART_WORDLENGTH_8B) || \ - ((LENGTH) == USART_WORDLENGTH_9B)) - -#define IS_USART_STOPBITS(STOPBITS) (((STOPBITS) == USART_STOPBITS_1) || \ - ((STOPBITS) == USART_STOPBITS_0_5) || \ - ((STOPBITS) == USART_STOPBITS_1_5) || \ - ((STOPBITS) == USART_STOPBITS_2)) - -#define IS_USART_PARITY(PARITY) (((PARITY) == USART_PARITY_NONE) || \ - ((PARITY) == USART_PARITY_EVEN) || \ - ((PARITY) == USART_PARITY_ODD)) - -#define IS_USART_MODE(MODE) ((((MODE) & (~((uint32_t)USART_MODE_TX_RX))) == 0x00U) && ((MODE) != 0x00U)) - -#define IS_USART_BAUDRATE(BAUDRATE) ((BAUDRATE) <= 12500000U) - -#define USART_DIV(_PCLK_, _BAUD_) ((uint32_t)((((uint64_t)(_PCLK_))*25U)/(2U*((uint64_t)(_BAUD_))))) - -#define USART_DIVMANT(_PCLK_, _BAUD_) (USART_DIV((_PCLK_), (_BAUD_))/100U) - -#define USART_DIVFRAQ(_PCLK_, _BAUD_) ((((USART_DIV((_PCLK_), (_BAUD_)) - (USART_DIVMANT((_PCLK_), (_BAUD_)) * 100U)) * 8U) + 50U) / 100U) - - /* UART BRR = mantissa + overflow + fraction - = (UART DIVMANT << 4) + ((UART DIVFRAQ & 0xF8) << 1) + (UART DIVFRAQ & 0x07U) */ - -#define USART_BRR(_PCLK_, _BAUD_) (((USART_DIVMANT((_PCLK_), (_BAUD_)) << 4U) + \ - ((USART_DIVFRAQ((_PCLK_), (_BAUD_)) & 0xF8U) << 1U)) + \ - (USART_DIVFRAQ((_PCLK_), (_BAUD_)) & 0x07U)) -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup USART_Private_Functions USART Private Functions - * @{ - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_USART_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_wwdg.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_wwdg.h deleted file mode 100644 index 017b34d..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_hal_wwdg.h +++ /dev/null @@ -1,301 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_wwdg.h - * @author MCD Application Team - * @brief Header file of WWDG HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_HAL_WWDG_H -#define STM32F4xx_HAL_WWDG_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup WWDG - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ - -/** @defgroup WWDG_Exported_Types WWDG Exported Types - * @{ - */ - -/** - * @brief WWDG Init structure definition - */ -typedef struct -{ - uint32_t Prescaler; /*!< Specifies the prescaler value of the WWDG. - This parameter can be a value of @ref WWDG_Prescaler */ - - uint32_t Window; /*!< Specifies the WWDG window value to be compared to the downcounter. - This parameter must be a number Min_Data = 0x40 and Max_Data = 0x7F */ - - uint32_t Counter; /*!< Specifies the WWDG free-running downcounter value. - This parameter must be a number between Min_Data = 0x40 and Max_Data = 0x7F */ - - uint32_t EWIMode ; /*!< Specifies if WWDG Early Wakeup Interrupt is enable or not. - This parameter can be a value of @ref WWDG_EWI_Mode */ - -} WWDG_InitTypeDef; - -/** - * @brief WWDG handle Structure definition - */ -#if (USE_HAL_WWDG_REGISTER_CALLBACKS == 1) -typedef struct __WWDG_HandleTypeDef -#else -typedef struct -#endif /* USE_HAL_WWDG_REGISTER_CALLBACKS */ -{ - WWDG_TypeDef *Instance; /*!< Register base address */ - - WWDG_InitTypeDef Init; /*!< WWDG required parameters */ - -#if (USE_HAL_WWDG_REGISTER_CALLBACKS == 1) - void (* EwiCallback)(struct __WWDG_HandleTypeDef *hwwdg); /*!< WWDG Early WakeUp Interrupt callback */ - - void (* MspInitCallback)(struct __WWDG_HandleTypeDef *hwwdg); /*!< WWDG Msp Init callback */ -#endif /* USE_HAL_WWDG_REGISTER_CALLBACKS */ -} WWDG_HandleTypeDef; - -#if (USE_HAL_WWDG_REGISTER_CALLBACKS == 1) -/** - * @brief HAL WWDG common Callback ID enumeration definition - */ -typedef enum -{ - HAL_WWDG_EWI_CB_ID = 0x00U, /*!< WWDG EWI callback ID */ - HAL_WWDG_MSPINIT_CB_ID = 0x01U, /*!< WWDG MspInit callback ID */ -} HAL_WWDG_CallbackIDTypeDef; - -/** - * @brief HAL WWDG Callback pointer definition - */ -typedef void (*pWWDG_CallbackTypeDef)(WWDG_HandleTypeDef *hppp); /*!< pointer to a WWDG common callback functions */ - -#endif /* USE_HAL_WWDG_REGISTER_CALLBACKS */ -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ - -/** @defgroup WWDG_Exported_Constants WWDG Exported Constants - * @{ - */ - -/** @defgroup WWDG_Interrupt_definition WWDG Interrupt definition - * @{ - */ -#define WWDG_IT_EWI WWDG_CFR_EWI /*!< Early wakeup interrupt */ -/** - * @} - */ - -/** @defgroup WWDG_Flag_definition WWDG Flag definition - * @brief WWDG Flag definition - * @{ - */ -#define WWDG_FLAG_EWIF WWDG_SR_EWIF /*!< Early wakeup interrupt flag */ -/** - * @} - */ - -/** @defgroup WWDG_Prescaler WWDG Prescaler - * @{ - */ -#define WWDG_PRESCALER_1 0x00000000u /*!< WWDG counter clock = (PCLK1/4096)/1 */ -#define WWDG_PRESCALER_2 WWDG_CFR_WDGTB_0 /*!< WWDG counter clock = (PCLK1/4096)/2 */ -#define WWDG_PRESCALER_4 WWDG_CFR_WDGTB_1 /*!< WWDG counter clock = (PCLK1/4096)/4 */ -#define WWDG_PRESCALER_8 (WWDG_CFR_WDGTB_1 | WWDG_CFR_WDGTB_0) /*!< WWDG counter clock = (PCLK1/4096)/8 */ -/** - * @} - */ - -/** @defgroup WWDG_EWI_Mode WWDG Early Wakeup Interrupt Mode - * @{ - */ -#define WWDG_EWI_DISABLE 0x00000000u /*!< EWI Disable */ -#define WWDG_EWI_ENABLE WWDG_CFR_EWI /*!< EWI Enable */ -/** - * @} - */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ - -/** @defgroup WWDG_Private_Macros WWDG Private Macros - * @{ - */ -#define IS_WWDG_PRESCALER(__PRESCALER__) (((__PRESCALER__) == WWDG_PRESCALER_1) || \ - ((__PRESCALER__) == WWDG_PRESCALER_2) || \ - ((__PRESCALER__) == WWDG_PRESCALER_4) || \ - ((__PRESCALER__) == WWDG_PRESCALER_8)) - -#define IS_WWDG_WINDOW(__WINDOW__) (((__WINDOW__) >= WWDG_CFR_W_6) && ((__WINDOW__) <= WWDG_CFR_W)) - -#define IS_WWDG_COUNTER(__COUNTER__) (((__COUNTER__) >= WWDG_CR_T_6) && ((__COUNTER__) <= WWDG_CR_T)) - -#define IS_WWDG_EWI_MODE(__MODE__) (((__MODE__) == WWDG_EWI_ENABLE) || \ - ((__MODE__) == WWDG_EWI_DISABLE)) -/** - * @} - */ - - -/* Exported macros ------------------------------------------------------------*/ - -/** @defgroup WWDG_Exported_Macros WWDG Exported Macros - * @{ - */ - -/** - * @brief Enable the WWDG peripheral. - * @param __HANDLE__ WWDG handle - * @retval None - */ -#define __HAL_WWDG_ENABLE(__HANDLE__) SET_BIT((__HANDLE__)->Instance->CR, WWDG_CR_WDGA) - -/** - * @brief Enable the WWDG early wakeup interrupt. - * @param __HANDLE__: WWDG handle - * @param __INTERRUPT__ specifies the interrupt to enable. - * This parameter can be one of the following values: - * @arg WWDG_IT_EWI: Early wakeup interrupt - * @note Once enabled this interrupt cannot be disabled except by a system reset. - * @retval None - */ -#define __HAL_WWDG_ENABLE_IT(__HANDLE__, __INTERRUPT__) SET_BIT((__HANDLE__)->Instance->CFR, (__INTERRUPT__)) - -/** - * @brief Check whether the selected WWDG interrupt has occurred or not. - * @param __HANDLE__ WWDG handle - * @param __INTERRUPT__ specifies the it to check. - * This parameter can be one of the following values: - * @arg WWDG_FLAG_EWIF: Early wakeup interrupt IT - * @retval The new state of WWDG_FLAG (SET or RESET). - */ -#define __HAL_WWDG_GET_IT(__HANDLE__, __INTERRUPT__) __HAL_WWDG_GET_FLAG((__HANDLE__),(__INTERRUPT__)) - -/** @brief Clear the WWDG interrupt pending bits. - * bits to clear the selected interrupt pending bits. - * @param __HANDLE__ WWDG handle - * @param __INTERRUPT__ specifies the interrupt pending bit to clear. - * This parameter can be one of the following values: - * @arg WWDG_FLAG_EWIF: Early wakeup interrupt flag - */ -#define __HAL_WWDG_CLEAR_IT(__HANDLE__, __INTERRUPT__) __HAL_WWDG_CLEAR_FLAG((__HANDLE__), (__INTERRUPT__)) - -/** - * @brief Check whether the specified WWDG flag is set or not. - * @param __HANDLE__ WWDG handle - * @param __FLAG__ specifies the flag to check. - * This parameter can be one of the following values: - * @arg WWDG_FLAG_EWIF: Early wakeup interrupt flag - * @retval The new state of WWDG_FLAG (SET or RESET). - */ -#define __HAL_WWDG_GET_FLAG(__HANDLE__, __FLAG__) (((__HANDLE__)->Instance->SR & (__FLAG__)) == (__FLAG__)) - -/** - * @brief Clear the WWDG's pending flags. - * @param __HANDLE__ WWDG handle - * @param __FLAG__ specifies the flag to clear. - * This parameter can be one of the following values: - * @arg WWDG_FLAG_EWIF: Early wakeup interrupt flag - * @retval None - */ -#define __HAL_WWDG_CLEAR_FLAG(__HANDLE__, __FLAG__) ((__HANDLE__)->Instance->SR = ~(__FLAG__)) - -/** @brief Check whether the specified WWDG interrupt source is enabled or not. - * @param __HANDLE__ WWDG Handle. - * @param __INTERRUPT__ specifies the WWDG interrupt source to check. - * This parameter can be one of the following values: - * @arg WWDG_IT_EWI: Early Wakeup Interrupt - * @retval state of __INTERRUPT__ (TRUE or FALSE). - */ -#define __HAL_WWDG_GET_IT_SOURCE(__HANDLE__, __INTERRUPT__) (((__HANDLE__)->Instance->CFR\ - & (__INTERRUPT__)) == (__INTERRUPT__)) - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ - -/** @addtogroup WWDG_Exported_Functions - * @{ - */ - -/** @addtogroup WWDG_Exported_Functions_Group1 - * @{ - */ -/* Initialization/de-initialization functions **********************************/ -HAL_StatusTypeDef HAL_WWDG_Init(WWDG_HandleTypeDef *hwwdg); -void HAL_WWDG_MspInit(WWDG_HandleTypeDef *hwwdg); -/* Callbacks Register/UnRegister functions ***********************************/ -#if (USE_HAL_WWDG_REGISTER_CALLBACKS == 1) -HAL_StatusTypeDef HAL_WWDG_RegisterCallback(WWDG_HandleTypeDef *hwwdg, HAL_WWDG_CallbackIDTypeDef CallbackID, - pWWDG_CallbackTypeDef pCallback); -HAL_StatusTypeDef HAL_WWDG_UnRegisterCallback(WWDG_HandleTypeDef *hwwdg, HAL_WWDG_CallbackIDTypeDef CallbackID); -#endif /* USE_HAL_WWDG_REGISTER_CALLBACKS */ - -/** - * @} - */ - -/** @addtogroup WWDG_Exported_Functions_Group2 - * @{ - */ -/* I/O operation functions ******************************************************/ -HAL_StatusTypeDef HAL_WWDG_Refresh(WWDG_HandleTypeDef *hwwdg); -void HAL_WWDG_IRQHandler(WWDG_HandleTypeDef *hwwdg); -void HAL_WWDG_EarlyWakeupCallback(WWDG_HandleTypeDef *hwwdg); -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_HAL_WWDG_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_adc.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_adc.h deleted file mode 100644 index 8375c4f..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_adc.h +++ /dev/null @@ -1,4783 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_adc.h - * @author MCD Application Team - * @brief Header file of ADC LL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_LL_ADC_H -#define __STM32F4xx_LL_ADC_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (ADC1) || defined (ADC2) || defined (ADC3) - -/** @defgroup ADC_LL ADC - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup ADC_LL_Private_Constants ADC Private Constants - * @{ - */ - -/* Internal mask for ADC group regular sequencer: */ -/* To select into literal LL_ADC_REG_RANK_x the relevant bits for: */ -/* - sequencer register offset */ -/* - sequencer rank bits position into the selected register */ - -/* Internal register offset for ADC group regular sequencer configuration */ -/* (offset placed into a spare area of literal definition) */ -#define ADC_SQR1_REGOFFSET 0x00000000UL -#define ADC_SQR2_REGOFFSET 0x00000100UL -#define ADC_SQR3_REGOFFSET 0x00000200UL -#define ADC_SQR4_REGOFFSET 0x00000300UL - -#define ADC_REG_SQRX_REGOFFSET_MASK (ADC_SQR1_REGOFFSET | ADC_SQR2_REGOFFSET | ADC_SQR3_REGOFFSET | ADC_SQR4_REGOFFSET) -#define ADC_REG_RANK_ID_SQRX_MASK (ADC_CHANNEL_ID_NUMBER_MASK_POSBIT0) - -/* Definition of ADC group regular sequencer bits information to be inserted */ -/* into ADC group regular sequencer ranks literals definition. */ -#define ADC_REG_RANK_1_SQRX_BITOFFSET_POS ( 0UL) /* Value equivalent to POSITION_VAL(ADC_SQR3_SQ1) */ -#define ADC_REG_RANK_2_SQRX_BITOFFSET_POS ( 5UL) /* Value equivalent to POSITION_VAL(ADC_SQR3_SQ2) */ -#define ADC_REG_RANK_3_SQRX_BITOFFSET_POS (10UL) /* Value equivalent to POSITION_VAL(ADC_SQR3_SQ3) */ -#define ADC_REG_RANK_4_SQRX_BITOFFSET_POS (15UL) /* Value equivalent to POSITION_VAL(ADC_SQR3_SQ4) */ -#define ADC_REG_RANK_5_SQRX_BITOFFSET_POS (20UL) /* Value equivalent to POSITION_VAL(ADC_SQR3_SQ5) */ -#define ADC_REG_RANK_6_SQRX_BITOFFSET_POS (25UL) /* Value equivalent to POSITION_VAL(ADC_SQR3_SQ6) */ -#define ADC_REG_RANK_7_SQRX_BITOFFSET_POS ( 0UL) /* Value equivalent to POSITION_VAL(ADC_SQR2_SQ7) */ -#define ADC_REG_RANK_8_SQRX_BITOFFSET_POS ( 5UL) /* Value equivalent to POSITION_VAL(ADC_SQR2_SQ8) */ -#define ADC_REG_RANK_9_SQRX_BITOFFSET_POS (10UL) /* Value equivalent to POSITION_VAL(ADC_SQR2_SQ9) */ -#define ADC_REG_RANK_10_SQRX_BITOFFSET_POS (15UL) /* Value equivalent to POSITION_VAL(ADC_SQR2_SQ10) */ -#define ADC_REG_RANK_11_SQRX_BITOFFSET_POS (20UL) /* Value equivalent to POSITION_VAL(ADC_SQR2_SQ11) */ -#define ADC_REG_RANK_12_SQRX_BITOFFSET_POS (25UL) /* Value equivalent to POSITION_VAL(ADC_SQR2_SQ12) */ -#define ADC_REG_RANK_13_SQRX_BITOFFSET_POS ( 0UL) /* Value equivalent to POSITION_VAL(ADC_SQR1_SQ13) */ -#define ADC_REG_RANK_14_SQRX_BITOFFSET_POS ( 5UL) /* Value equivalent to POSITION_VAL(ADC_SQR1_SQ14) */ -#define ADC_REG_RANK_15_SQRX_BITOFFSET_POS (10UL) /* Value equivalent to POSITION_VAL(ADC_SQR1_SQ15) */ -#define ADC_REG_RANK_16_SQRX_BITOFFSET_POS (15UL) /* Value equivalent to POSITION_VAL(ADC_SQR1_SQ16) */ - -/* Internal mask for ADC group injected sequencer: */ -/* To select into literal LL_ADC_INJ_RANK_x the relevant bits for: */ -/* - data register offset */ -/* - offset register offset */ -/* - sequencer rank bits position into the selected register */ - -/* Internal register offset for ADC group injected data register */ -/* (offset placed into a spare area of literal definition) */ -#define ADC_JDR1_REGOFFSET 0x00000000UL -#define ADC_JDR2_REGOFFSET 0x00000100UL -#define ADC_JDR3_REGOFFSET 0x00000200UL -#define ADC_JDR4_REGOFFSET 0x00000300UL - -/* Internal register offset for ADC group injected offset configuration */ -/* (offset placed into a spare area of literal definition) */ -#define ADC_JOFR1_REGOFFSET 0x00000000UL -#define ADC_JOFR2_REGOFFSET 0x00001000UL -#define ADC_JOFR3_REGOFFSET 0x00002000UL -#define ADC_JOFR4_REGOFFSET 0x00003000UL - -#define ADC_INJ_JDRX_REGOFFSET_MASK (ADC_JDR1_REGOFFSET | ADC_JDR2_REGOFFSET | ADC_JDR3_REGOFFSET | ADC_JDR4_REGOFFSET) -#define ADC_INJ_JOFRX_REGOFFSET_MASK (ADC_JOFR1_REGOFFSET | ADC_JOFR2_REGOFFSET | ADC_JOFR3_REGOFFSET | ADC_JOFR4_REGOFFSET) -#define ADC_INJ_RANK_ID_JSQR_MASK (ADC_CHANNEL_ID_NUMBER_MASK_POSBIT0) - -/* Internal mask for ADC group regular trigger: */ -/* To select into literal LL_ADC_REG_TRIG_x the relevant bits for: */ -/* - regular trigger source */ -/* - regular trigger edge */ -#define ADC_REG_TRIG_EXT_EDGE_DEFAULT (ADC_CR2_EXTEN_0) /* Trigger edge set to rising edge (default setting for compatibility with some ADC on other STM32 families having this setting set by HW default value) */ - -/* Mask containing trigger source masks for each of possible */ -/* trigger edge selection duplicated with shifts [0; 4; 8; 12] */ -/* corresponding to {SW start; ext trigger; ext trigger; ext trigger}. */ -#define ADC_REG_TRIG_SOURCE_MASK (((LL_ADC_REG_TRIG_SOFTWARE & ADC_CR2_EXTSEL) >> (4UL * 0UL)) | \ - ((ADC_CR2_EXTSEL) >> (4UL * 1UL)) | \ - ((ADC_CR2_EXTSEL) >> (4UL * 2UL)) | \ - ((ADC_CR2_EXTSEL) >> (4UL * 3UL))) - -/* Mask containing trigger edge masks for each of possible */ -/* trigger edge selection duplicated with shifts [0; 4; 8; 12] */ -/* corresponding to {SW start; ext trigger; ext trigger; ext trigger}. */ -#define ADC_REG_TRIG_EDGE_MASK (((LL_ADC_REG_TRIG_SOFTWARE & ADC_CR2_EXTEN) >> (4UL * 0UL)) | \ - ((ADC_REG_TRIG_EXT_EDGE_DEFAULT) >> (4UL * 1UL)) | \ - ((ADC_REG_TRIG_EXT_EDGE_DEFAULT) >> (4UL * 2UL)) | \ - ((ADC_REG_TRIG_EXT_EDGE_DEFAULT) >> (4UL * 3UL))) - -/* Definition of ADC group regular trigger bits information. */ -#define ADC_REG_TRIG_EXTSEL_BITOFFSET_POS (24UL) /* Value equivalent to POSITION_VAL(ADC_CR2_EXTSEL) */ -#define ADC_REG_TRIG_EXTEN_BITOFFSET_POS (28UL) /* Value equivalent to POSITION_VAL(ADC_CR2_EXTEN) */ - - - -/* Internal mask for ADC group injected trigger: */ -/* To select into literal LL_ADC_INJ_TRIG_x the relevant bits for: */ -/* - injected trigger source */ -/* - injected trigger edge */ -#define ADC_INJ_TRIG_EXT_EDGE_DEFAULT (ADC_CR2_JEXTEN_0) /* Trigger edge set to rising edge (default setting for compatibility with some ADC on other STM32 families having this setting set by HW default value) */ - -/* Mask containing trigger source masks for each of possible */ -/* trigger edge selection duplicated with shifts [0; 4; 8; 12] */ -/* corresponding to {SW start; ext trigger; ext trigger; ext trigger}. */ -#define ADC_INJ_TRIG_SOURCE_MASK (((LL_ADC_REG_TRIG_SOFTWARE & ADC_CR2_JEXTSEL) >> (4UL * 0UL)) | \ - ((ADC_CR2_JEXTSEL) >> (4UL * 1UL)) | \ - ((ADC_CR2_JEXTSEL) >> (4UL * 2UL)) | \ - ((ADC_CR2_JEXTSEL) >> (4UL * 3UL))) - -/* Mask containing trigger edge masks for each of possible */ -/* trigger edge selection duplicated with shifts [0; 4; 8; 12] */ -/* corresponding to {SW start; ext trigger; ext trigger; ext trigger}. */ -#define ADC_INJ_TRIG_EDGE_MASK (((LL_ADC_INJ_TRIG_SOFTWARE & ADC_CR2_JEXTEN) >> (4UL * 0UL)) | \ - ((ADC_INJ_TRIG_EXT_EDGE_DEFAULT) >> (4UL * 1UL)) | \ - ((ADC_INJ_TRIG_EXT_EDGE_DEFAULT) >> (4UL * 2UL)) | \ - ((ADC_INJ_TRIG_EXT_EDGE_DEFAULT) >> (4UL * 3UL))) - -/* Definition of ADC group injected trigger bits information. */ -#define ADC_INJ_TRIG_EXTSEL_BITOFFSET_POS (16UL) /* Value equivalent to POSITION_VAL(ADC_CR2_JEXTSEL) */ -#define ADC_INJ_TRIG_EXTEN_BITOFFSET_POS (20UL) /* Value equivalent to POSITION_VAL(ADC_CR2_JEXTEN) */ - -/* Internal mask for ADC channel: */ -/* To select into literal LL_ADC_CHANNEL_x the relevant bits for: */ -/* - channel identifier defined by number */ -/* - channel differentiation between external channels (connected to */ -/* GPIO pins) and internal channels (connected to internal paths) */ -/* - channel sampling time defined by SMPRx register offset */ -/* and SMPx bits positions into SMPRx register */ -#define ADC_CHANNEL_ID_NUMBER_MASK (ADC_CR1_AWDCH) -#define ADC_CHANNEL_ID_NUMBER_BITOFFSET_POS ( 0UL)/* Value equivalent to POSITION_VAL(ADC_CHANNEL_ID_NUMBER_MASK) */ -#define ADC_CHANNEL_ID_MASK (ADC_CHANNEL_ID_NUMBER_MASK | ADC_CHANNEL_ID_INTERNAL_CH_MASK) -/* Equivalent mask of ADC_CHANNEL_NUMBER_MASK aligned on register LSB (bit 0) */ -#define ADC_CHANNEL_ID_NUMBER_MASK_POSBIT0 0x0000001FU /* Equivalent to shift: (ADC_CHANNEL_NUMBER_MASK >> POSITION_VAL(ADC_CHANNEL_NUMBER_MASK)) */ - -/* Channel differentiation between external and internal channels */ -#define ADC_CHANNEL_ID_INTERNAL_CH 0x80000000UL /* Marker of internal channel */ -#define ADC_CHANNEL_ID_INTERNAL_CH_2 0x40000000UL /* Marker of internal channel for other ADC instances, in case of different ADC internal channels mapped on same channel number on different ADC instances */ -#define ADC_CHANNEL_DIFFERENCIATION_TEMPSENSOR_VBAT 0x10000000U /* Dummy bit for driver internal usage, not used in ADC channel setting registers CR1 or SQRx */ -#define ADC_CHANNEL_ID_INTERNAL_CH_MASK (ADC_CHANNEL_ID_INTERNAL_CH | ADC_CHANNEL_ID_INTERNAL_CH_2 | ADC_CHANNEL_DIFFERENCIATION_TEMPSENSOR_VBAT) - -/* Internal register offset for ADC channel sampling time configuration */ -/* (offset placed into a spare area of literal definition) */ -#define ADC_SMPR1_REGOFFSET 0x00000000UL -#define ADC_SMPR2_REGOFFSET 0x02000000UL -#define ADC_CHANNEL_SMPRX_REGOFFSET_MASK (ADC_SMPR1_REGOFFSET | ADC_SMPR2_REGOFFSET) - -#define ADC_CHANNEL_SMPx_BITOFFSET_MASK 0x01F00000UL -#define ADC_CHANNEL_SMPx_BITOFFSET_POS (20UL) /* Value equivalent to POSITION_VAL(ADC_CHANNEL_SMPx_BITOFFSET_MASK) */ - -/* Definition of channels ID number information to be inserted into */ -/* channels literals definition. */ -#define ADC_CHANNEL_0_NUMBER 0x00000000UL -#define ADC_CHANNEL_1_NUMBER ( ADC_CR1_AWDCH_0) -#define ADC_CHANNEL_2_NUMBER ( ADC_CR1_AWDCH_1 ) -#define ADC_CHANNEL_3_NUMBER ( ADC_CR1_AWDCH_1 | ADC_CR1_AWDCH_0) -#define ADC_CHANNEL_4_NUMBER ( ADC_CR1_AWDCH_2 ) -#define ADC_CHANNEL_5_NUMBER ( ADC_CR1_AWDCH_2 | ADC_CR1_AWDCH_0) -#define ADC_CHANNEL_6_NUMBER ( ADC_CR1_AWDCH_2 | ADC_CR1_AWDCH_1 ) -#define ADC_CHANNEL_7_NUMBER ( ADC_CR1_AWDCH_2 | ADC_CR1_AWDCH_1 | ADC_CR1_AWDCH_0) -#define ADC_CHANNEL_8_NUMBER ( ADC_CR1_AWDCH_3 ) -#define ADC_CHANNEL_9_NUMBER ( ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_0) -#define ADC_CHANNEL_10_NUMBER ( ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_1 ) -#define ADC_CHANNEL_11_NUMBER ( ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_1 | ADC_CR1_AWDCH_0) -#define ADC_CHANNEL_12_NUMBER ( ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_2 ) -#define ADC_CHANNEL_13_NUMBER ( ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_2 | ADC_CR1_AWDCH_0) -#define ADC_CHANNEL_14_NUMBER ( ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_2 | ADC_CR1_AWDCH_1 ) -#define ADC_CHANNEL_15_NUMBER ( ADC_CR1_AWDCH_3 | ADC_CR1_AWDCH_2 | ADC_CR1_AWDCH_1 | ADC_CR1_AWDCH_0) -#define ADC_CHANNEL_16_NUMBER (ADC_CR1_AWDCH_4 ) -#define ADC_CHANNEL_17_NUMBER (ADC_CR1_AWDCH_4 | ADC_CR1_AWDCH_0) -#define ADC_CHANNEL_18_NUMBER (ADC_CR1_AWDCH_4 | ADC_CR1_AWDCH_1 ) - -/* Definition of channels sampling time information to be inserted into */ -/* channels literals definition. */ -#define ADC_CHANNEL_0_SMP (ADC_SMPR2_REGOFFSET | (( 0UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR2_SMP0) */ -#define ADC_CHANNEL_1_SMP (ADC_SMPR2_REGOFFSET | (( 3UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR2_SMP1) */ -#define ADC_CHANNEL_2_SMP (ADC_SMPR2_REGOFFSET | (( 6UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR2_SMP2) */ -#define ADC_CHANNEL_3_SMP (ADC_SMPR2_REGOFFSET | (( 9UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR2_SMP3) */ -#define ADC_CHANNEL_4_SMP (ADC_SMPR2_REGOFFSET | ((12UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR2_SMP4) */ -#define ADC_CHANNEL_5_SMP (ADC_SMPR2_REGOFFSET | ((15UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR2_SMP5) */ -#define ADC_CHANNEL_6_SMP (ADC_SMPR2_REGOFFSET | ((18UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR2_SMP6) */ -#define ADC_CHANNEL_7_SMP (ADC_SMPR2_REGOFFSET | ((21UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR2_SMP7) */ -#define ADC_CHANNEL_8_SMP (ADC_SMPR2_REGOFFSET | ((24UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR2_SMP8) */ -#define ADC_CHANNEL_9_SMP (ADC_SMPR2_REGOFFSET | ((27UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR2_SMP9) */ -#define ADC_CHANNEL_10_SMP (ADC_SMPR1_REGOFFSET | (( 0UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR1_SMP10) */ -#define ADC_CHANNEL_11_SMP (ADC_SMPR1_REGOFFSET | (( 3UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR1_SMP11) */ -#define ADC_CHANNEL_12_SMP (ADC_SMPR1_REGOFFSET | (( 6UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR1_SMP12) */ -#define ADC_CHANNEL_13_SMP (ADC_SMPR1_REGOFFSET | (( 9UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR1_SMP13) */ -#define ADC_CHANNEL_14_SMP (ADC_SMPR1_REGOFFSET | ((12UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR1_SMP14) */ -#define ADC_CHANNEL_15_SMP (ADC_SMPR1_REGOFFSET | ((15UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR1_SMP15) */ -#define ADC_CHANNEL_16_SMP (ADC_SMPR1_REGOFFSET | ((18UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR1_SMP16) */ -#define ADC_CHANNEL_17_SMP (ADC_SMPR1_REGOFFSET | ((21UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR1_SMP17) */ -#define ADC_CHANNEL_18_SMP (ADC_SMPR1_REGOFFSET | ((24UL) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) /* Value shifted is equivalent to POSITION_VAL(ADC_SMPR1_SMP18) */ - -/* Internal mask for ADC analog watchdog: */ -/* To select into literals LL_ADC_AWD_CHANNELx_xxx the relevant bits for: */ -/* (concatenation of multiple bits used in different analog watchdogs, */ -/* (feature of several watchdogs not available on all STM32 families)). */ -/* - analog watchdog 1: monitored channel defined by number, */ -/* selection of ADC group (ADC groups regular and-or injected). */ - -/* Internal register offset for ADC analog watchdog channel configuration */ -#define ADC_AWD_CR1_REGOFFSET 0x00000000UL - -#define ADC_AWD_CRX_REGOFFSET_MASK (ADC_AWD_CR1_REGOFFSET) - -#define ADC_AWD_CR1_CHANNEL_MASK (ADC_CR1_AWDCH | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) -#define ADC_AWD_CR_ALL_CHANNEL_MASK (ADC_AWD_CR1_CHANNEL_MASK) - -/* Internal register offset for ADC analog watchdog threshold configuration */ -#define ADC_AWD_TR1_HIGH_REGOFFSET 0x00000000UL -#define ADC_AWD_TR1_LOW_REGOFFSET 0x00000001UL -#define ADC_AWD_TRX_REGOFFSET_MASK (ADC_AWD_TR1_HIGH_REGOFFSET | ADC_AWD_TR1_LOW_REGOFFSET) - -/* ADC registers bits positions */ -#define ADC_CR1_RES_BITOFFSET_POS (24UL) /* Value equivalent to POSITION_VAL(ADC_CR1_RES) */ -#define ADC_TR_HT_BITOFFSET_POS (16UL) /* Value equivalent to POSITION_VAL(ADC_TR_HT) */ - -/* ADC internal channels related definitions */ -/* Internal voltage reference VrefInt */ -#define VREFINT_CAL_ADDR ((uint16_t*) (0x1FFF7A2AU)) /* Internal voltage reference, address of parameter VREFINT_CAL: VrefInt ADC raw data acquired at temperature 30 DegC (tolerance: +-5 DegC), Vref+ = 3.3 V (tolerance: +-10 mV). */ -#define VREFINT_CAL_VREF ( 3300UL) /* Analog voltage reference (Vref+) value with which temperature sensor has been calibrated in production (tolerance: +-10 mV) (unit: mV). */ -/* Temperature sensor */ -#define TEMPSENSOR_CAL1_ADDR ((uint16_t*) (0x1FFF7A2CU)) /* Internal temperature sensor, address of parameter TS_CAL1: On STM32F4, temperature sensor ADC raw data acquired at temperature 30 DegC (tolerance: +-5 DegC), Vref+ = 3.3 V (tolerance: +-10 mV). */ -#define TEMPSENSOR_CAL2_ADDR ((uint16_t*) (0x1FFF7A2EU)) /* Internal temperature sensor, address of parameter TS_CAL2: On STM32F4, temperature sensor ADC raw data acquired at temperature 110 DegC (tolerance: +-5 DegC), Vref+ = 3.3 V (tolerance: +-10 mV). */ -#define TEMPSENSOR_CAL1_TEMP (( int32_t) 30) /* Internal temperature sensor, temperature at which temperature sensor has been calibrated in production for data into TEMPSENSOR_CAL1_ADDR (tolerance: +-5 DegC) (unit: DegC). */ -#define TEMPSENSOR_CAL2_TEMP (( int32_t) 110) /* Internal temperature sensor, temperature at which temperature sensor has been calibrated in production for data into TEMPSENSOR_CAL2_ADDR (tolerance: +-5 DegC) (unit: DegC). */ -#define TEMPSENSOR_CAL_VREFANALOG ( 3300UL) /* Analog voltage reference (Vref+) voltage with which temperature sensor has been calibrated in production (+-10 mV) (unit: mV). */ - -/** - * @} - */ - - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup ADC_LL_Private_Macros ADC Private Macros - * @{ - */ - -/** - * @brief Driver macro reserved for internal use: isolate bits with the - * selected mask and shift them to the register LSB - * (shift mask on register position bit 0). - * @param __BITS__ Bits in register 32 bits - * @param __MASK__ Mask in register 32 bits - * @retval Bits in register 32 bits - */ -#define __ADC_MASK_SHIFT(__BITS__, __MASK__) \ - (((__BITS__) & (__MASK__)) >> POSITION_VAL((__MASK__))) - -/** - * @brief Driver macro reserved for internal use: set a pointer to - * a register from a register basis from which an offset - * is applied. - * @param __REG__ Register basis from which the offset is applied. - * @param __REG_OFFFSET__ Offset to be applied (unit number of registers). - * @retval Pointer to register address - */ -#define __ADC_PTR_REG_OFFSET(__REG__, __REG_OFFFSET__) \ - ((__IO uint32_t *)((uint32_t) ((uint32_t)(&(__REG__)) + ((__REG_OFFFSET__) << 2UL)))) - -/** - * @} - */ - - -/* Exported types ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup ADC_LL_ES_INIT ADC Exported Init structure - * @{ - */ - -/** - * @brief Structure definition of some features of ADC common parameters - * and multimode - * (all ADC instances belonging to the same ADC common instance). - * @note The setting of these parameters by function @ref LL_ADC_CommonInit() - * is conditioned to ADC instances state (all ADC instances - * sharing the same ADC common instance): - * All ADC instances sharing the same ADC common instance must be - * disabled. - */ -typedef struct -{ - uint32_t CommonClock; /*!< Set parameter common to several ADC: Clock source and prescaler. - This parameter can be a value of @ref ADC_LL_EC_COMMON_CLOCK_SOURCE - - This feature can be modified afterwards using unitary function @ref LL_ADC_SetCommonClock(). */ - -#if defined(ADC_MULTIMODE_SUPPORT) - uint32_t Multimode; /*!< Set ADC multimode configuration to operate in independent mode or multimode (for devices with several ADC instances). - This parameter can be a value of @ref ADC_LL_EC_MULTI_MODE - - This feature can be modified afterwards using unitary function @ref LL_ADC_SetMultimode(). */ - - uint32_t MultiDMATransfer; /*!< Set ADC multimode conversion data transfer: no transfer or transfer by DMA. - This parameter can be a value of @ref ADC_LL_EC_MULTI_DMA_TRANSFER - - This feature can be modified afterwards using unitary function @ref LL_ADC_SetMultiDMATransfer(). */ - - uint32_t MultiTwoSamplingDelay; /*!< Set ADC multimode delay between 2 sampling phases. - This parameter can be a value of @ref ADC_LL_EC_MULTI_TWOSMP_DELAY - - This feature can be modified afterwards using unitary function @ref LL_ADC_SetMultiTwoSamplingDelay(). */ -#endif /* ADC_MULTIMODE_SUPPORT */ - -} LL_ADC_CommonInitTypeDef; - -/** - * @brief Structure definition of some features of ADC instance. - * @note These parameters have an impact on ADC scope: ADC instance. - * Affects both group regular and group injected (availability - * of ADC group injected depends on STM32 families). - * Refer to corresponding unitary functions into - * @ref ADC_LL_EF_Configuration_ADC_Instance . - * @note The setting of these parameters by function @ref LL_ADC_Init() - * is conditioned to ADC state: - * ADC instance must be disabled. - * This condition is applied to all ADC features, for efficiency - * and compatibility over all STM32 families. However, the different - * features can be set under different ADC state conditions - * (setting possible with ADC enabled without conversion on going, - * ADC enabled with conversion on going, ...) - * Each feature can be updated afterwards with a unitary function - * and potentially with ADC in a different state than disabled, - * refer to description of each function for setting - * conditioned to ADC state. - */ -typedef struct -{ - uint32_t Resolution; /*!< Set ADC resolution. - This parameter can be a value of @ref ADC_LL_EC_RESOLUTION - - This feature can be modified afterwards using unitary function @ref LL_ADC_SetResolution(). */ - - uint32_t DataAlignment; /*!< Set ADC conversion data alignment. - This parameter can be a value of @ref ADC_LL_EC_DATA_ALIGN - - This feature can be modified afterwards using unitary function @ref LL_ADC_SetDataAlignment(). */ - - uint32_t SequencersScanMode; /*!< Set ADC scan selection. - This parameter can be a value of @ref ADC_LL_EC_SCAN_SELECTION - - This feature can be modified afterwards using unitary function @ref LL_ADC_SetSequencersScanMode(). */ - -} LL_ADC_InitTypeDef; - -/** - * @brief Structure definition of some features of ADC group regular. - * @note These parameters have an impact on ADC scope: ADC group regular. - * Refer to corresponding unitary functions into - * @ref ADC_LL_EF_Configuration_ADC_Group_Regular - * (functions with prefix "REG"). - * @note The setting of these parameters by function @ref LL_ADC_REG_Init() - * is conditioned to ADC state: - * ADC instance must be disabled. - * This condition is applied to all ADC features, for efficiency - * and compatibility over all STM32 families. However, the different - * features can be set under different ADC state conditions - * (setting possible with ADC enabled without conversion on going, - * ADC enabled with conversion on going, ...) - * Each feature can be updated afterwards with a unitary function - * and potentially with ADC in a different state than disabled, - * refer to description of each function for setting - * conditioned to ADC state. - */ -typedef struct -{ - uint32_t TriggerSource; /*!< Set ADC group regular conversion trigger source: internal (SW start) or from external IP (timer event, external interrupt line). - This parameter can be a value of @ref ADC_LL_EC_REG_TRIGGER_SOURCE - @note On this STM32 series, setting of external trigger edge is performed - using function @ref LL_ADC_REG_StartConversionExtTrig(). - - This feature can be modified afterwards using unitary function @ref LL_ADC_REG_SetTriggerSource(). */ - - uint32_t SequencerLength; /*!< Set ADC group regular sequencer length. - This parameter can be a value of @ref ADC_LL_EC_REG_SEQ_SCAN_LENGTH - @note This parameter is discarded if scan mode is disabled (refer to parameter 'ADC_SequencersScanMode'). - - This feature can be modified afterwards using unitary function @ref LL_ADC_REG_SetSequencerLength(). */ - - uint32_t SequencerDiscont; /*!< Set ADC group regular sequencer discontinuous mode: sequence subdivided and scan conversions interrupted every selected number of ranks. - This parameter can be a value of @ref ADC_LL_EC_REG_SEQ_DISCONT_MODE - @note This parameter has an effect only if group regular sequencer is enabled - (scan length of 2 ranks or more). - - This feature can be modified afterwards using unitary function @ref LL_ADC_REG_SetSequencerDiscont(). */ - - uint32_t ContinuousMode; /*!< Set ADC continuous conversion mode on ADC group regular, whether ADC conversions are performed in single mode (one conversion per trigger) or in continuous mode (after the first trigger, following conversions launched successively automatically). - This parameter can be a value of @ref ADC_LL_EC_REG_CONTINUOUS_MODE - Note: It is not possible to enable both ADC group regular continuous mode and discontinuous mode. - - This feature can be modified afterwards using unitary function @ref LL_ADC_REG_SetContinuousMode(). */ - - uint32_t DMATransfer; /*!< Set ADC group regular conversion data transfer: no transfer or transfer by DMA, and DMA requests mode. - This parameter can be a value of @ref ADC_LL_EC_REG_DMA_TRANSFER - - This feature can be modified afterwards using unitary function @ref LL_ADC_REG_SetDMATransfer(). */ - -} LL_ADC_REG_InitTypeDef; - -/** - * @brief Structure definition of some features of ADC group injected. - * @note These parameters have an impact on ADC scope: ADC group injected. - * Refer to corresponding unitary functions into - * @ref ADC_LL_EF_Configuration_ADC_Group_Regular - * (functions with prefix "INJ"). - * @note The setting of these parameters by function @ref LL_ADC_INJ_Init() - * is conditioned to ADC state: - * ADC instance must be disabled. - * This condition is applied to all ADC features, for efficiency - * and compatibility over all STM32 families. However, the different - * features can be set under different ADC state conditions - * (setting possible with ADC enabled without conversion on going, - * ADC enabled with conversion on going, ...) - * Each feature can be updated afterwards with a unitary function - * and potentially with ADC in a different state than disabled, - * refer to description of each function for setting - * conditioned to ADC state. - */ -typedef struct -{ - uint32_t TriggerSource; /*!< Set ADC group injected conversion trigger source: internal (SW start) or from external IP (timer event, external interrupt line). - This parameter can be a value of @ref ADC_LL_EC_INJ_TRIGGER_SOURCE - @note On this STM32 series, setting of external trigger edge is performed - using function @ref LL_ADC_INJ_StartConversionExtTrig(). - - This feature can be modified afterwards using unitary function @ref LL_ADC_INJ_SetTriggerSource(). */ - - uint32_t SequencerLength; /*!< Set ADC group injected sequencer length. - This parameter can be a value of @ref ADC_LL_EC_INJ_SEQ_SCAN_LENGTH - @note This parameter is discarded if scan mode is disabled (refer to parameter 'ADC_SequencersScanMode'). - - This feature can be modified afterwards using unitary function @ref LL_ADC_INJ_SetSequencerLength(). */ - - uint32_t SequencerDiscont; /*!< Set ADC group injected sequencer discontinuous mode: sequence subdivided and scan conversions interrupted every selected number of ranks. - This parameter can be a value of @ref ADC_LL_EC_INJ_SEQ_DISCONT_MODE - @note This parameter has an effect only if group injected sequencer is enabled - (scan length of 2 ranks or more). - - This feature can be modified afterwards using unitary function @ref LL_ADC_INJ_SetSequencerDiscont(). */ - - uint32_t TrigAuto; /*!< Set ADC group injected conversion trigger: independent or from ADC group regular. - This parameter can be a value of @ref ADC_LL_EC_INJ_TRIG_AUTO - Note: This parameter must be set to set to independent trigger if injected trigger source is set to an external trigger. - - This feature can be modified afterwards using unitary function @ref LL_ADC_INJ_SetTrigAuto(). */ - -} LL_ADC_INJ_InitTypeDef; - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup ADC_LL_Exported_Constants ADC Exported Constants - * @{ - */ - -/** @defgroup ADC_LL_EC_FLAG ADC flags - * @brief Flags defines which can be used with LL_ADC_ReadReg function - * @{ - */ -#define LL_ADC_FLAG_STRT ADC_SR_STRT /*!< ADC flag ADC group regular conversion start */ -#define LL_ADC_FLAG_EOCS ADC_SR_EOC /*!< ADC flag ADC group regular end of unitary conversion or sequence conversions (to configure flag of end of conversion, use function @ref LL_ADC_REG_SetFlagEndOfConversion() ) */ -#define LL_ADC_FLAG_OVR ADC_SR_OVR /*!< ADC flag ADC group regular overrun */ -#define LL_ADC_FLAG_JSTRT ADC_SR_JSTRT /*!< ADC flag ADC group injected conversion start */ -#define LL_ADC_FLAG_JEOS ADC_SR_JEOC /*!< ADC flag ADC group injected end of sequence conversions (Note: on this STM32 series, there is no flag ADC group injected end of unitary conversion. Flag noted as "JEOC" is corresponding to flag "JEOS" in other STM32 families) */ -#define LL_ADC_FLAG_AWD1 ADC_SR_AWD /*!< ADC flag ADC analog watchdog 1 */ -#if defined(ADC_MULTIMODE_SUPPORT) -#define LL_ADC_FLAG_EOCS_MST ADC_CSR_EOC1 /*!< ADC flag ADC multimode master group regular end of unitary conversion or sequence conversions (to configure flag of end of conversion, use function @ref LL_ADC_REG_SetFlagEndOfConversion() ) */ -#define LL_ADC_FLAG_EOCS_SLV1 ADC_CSR_EOC2 /*!< ADC flag ADC multimode slave 1 group regular end of unitary conversion or sequence conversions (to configure flag of end of conversion, use function @ref LL_ADC_REG_SetFlagEndOfConversion() ) */ -#define LL_ADC_FLAG_EOCS_SLV2 ADC_CSR_EOC3 /*!< ADC flag ADC multimode slave 2 group regular end of unitary conversion or sequence conversions (to configure flag of end of conversion, use function @ref LL_ADC_REG_SetFlagEndOfConversion() ) */ -#define LL_ADC_FLAG_OVR_MST ADC_CSR_OVR1 /*!< ADC flag ADC multimode master group regular overrun */ -#define LL_ADC_FLAG_OVR_SLV1 ADC_CSR_OVR2 /*!< ADC flag ADC multimode slave 1 group regular overrun */ -#define LL_ADC_FLAG_OVR_SLV2 ADC_CSR_OVR3 /*!< ADC flag ADC multimode slave 2 group regular overrun */ -#define LL_ADC_FLAG_JEOS_MST ADC_CSR_JEOC1 /*!< ADC flag ADC multimode master group injected end of sequence conversions (Note: on this STM32 series, there is no flag ADC group injected end of unitary conversion. Flag noted as "JEOC" is corresponding to flag "JEOS" in other STM32 families) */ -#define LL_ADC_FLAG_JEOS_SLV1 ADC_CSR_JEOC2 /*!< ADC flag ADC multimode slave 1 group injected end of sequence conversions (Note: on this STM32 series, there is no flag ADC group injected end of unitary conversion. Flag noted as "JEOC" is corresponding to flag "JEOS" in other STM32 families) */ -#define LL_ADC_FLAG_JEOS_SLV2 ADC_CSR_JEOC3 /*!< ADC flag ADC multimode slave 2 group injected end of sequence conversions (Note: on this STM32 series, there is no flag ADC group injected end of unitary conversion. Flag noted as "JEOC" is corresponding to flag "JEOS" in other STM32 families) */ -#define LL_ADC_FLAG_AWD1_MST ADC_CSR_AWD1 /*!< ADC flag ADC multimode master analog watchdog 1 of the ADC master */ -#define LL_ADC_FLAG_AWD1_SLV1 ADC_CSR_AWD2 /*!< ADC flag ADC multimode slave 1 analog watchdog 1 */ -#define LL_ADC_FLAG_AWD1_SLV2 ADC_CSR_AWD3 /*!< ADC flag ADC multimode slave 2 analog watchdog 1 */ -#endif -/** - * @} - */ - -/** @defgroup ADC_LL_EC_IT ADC interruptions for configuration (interruption enable or disable) - * @brief IT defines which can be used with LL_ADC_ReadReg and LL_ADC_WriteReg functions - * @{ - */ -#define LL_ADC_IT_EOCS ADC_CR1_EOCIE /*!< ADC interruption ADC group regular end of unitary conversion or sequence conversions (to configure flag of end of conversion, use function @ref LL_ADC_REG_SetFlagEndOfConversion() ) */ -#define LL_ADC_IT_OVR ADC_CR1_OVRIE /*!< ADC interruption ADC group regular overrun */ -#define LL_ADC_IT_JEOS ADC_CR1_JEOCIE /*!< ADC interruption ADC group injected end of sequence conversions (Note: on this STM32 series, there is no flag ADC group injected end of unitary conversion. Flag noted as "JEOC" is corresponding to flag "JEOS" in other STM32 families) */ -#define LL_ADC_IT_AWD1 ADC_CR1_AWDIE /*!< ADC interruption ADC analog watchdog 1 */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_REGISTERS ADC registers compliant with specific purpose - * @{ - */ -/* List of ADC registers intended to be used (most commonly) with */ -/* DMA transfer. */ -/* Refer to function @ref LL_ADC_DMA_GetRegAddr(). */ -#define LL_ADC_DMA_REG_REGULAR_DATA 0x00000000UL /* ADC group regular conversion data register (corresponding to register DR) to be used with ADC configured in independent mode. Without DMA transfer, register accessed by LL function @ref LL_ADC_REG_ReadConversionData32() and other functions @ref LL_ADC_REG_ReadConversionDatax() */ -#if defined(ADC_MULTIMODE_SUPPORT) -#define LL_ADC_DMA_REG_REGULAR_DATA_MULTI 0x00000001UL /* ADC group regular conversion data register (corresponding to register CDR) to be used with ADC configured in multimode (available on STM32 devices with several ADC instances). Without DMA transfer, register accessed by LL function @ref LL_ADC_REG_ReadMultiConversionData32() */ -#endif -/** - * @} - */ - -/** @defgroup ADC_LL_EC_COMMON_CLOCK_SOURCE ADC common - Clock source - * @{ - */ -#define LL_ADC_CLOCK_SYNC_PCLK_DIV2 0x00000000UL /*!< ADC synchronous clock derived from AHB clock with prescaler division by 2 */ -#define LL_ADC_CLOCK_SYNC_PCLK_DIV4 ( ADC_CCR_ADCPRE_0) /*!< ADC synchronous clock derived from AHB clock with prescaler division by 4 */ -#define LL_ADC_CLOCK_SYNC_PCLK_DIV6 (ADC_CCR_ADCPRE_1 ) /*!< ADC synchronous clock derived from AHB clock with prescaler division by 6 */ -#define LL_ADC_CLOCK_SYNC_PCLK_DIV8 (ADC_CCR_ADCPRE_1 | ADC_CCR_ADCPRE_0) /*!< ADC synchronous clock derived from AHB clock with prescaler division by 8 */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_COMMON_PATH_INTERNAL ADC common - Measurement path to internal channels - * @{ - */ -/* Note: Other measurement paths to internal channels may be available */ -/* (connections to other peripherals). */ -/* If they are not listed below, they do not require any specific */ -/* path enable. In this case, Access to measurement path is done */ -/* only by selecting the corresponding ADC internal channel. */ -#define LL_ADC_PATH_INTERNAL_NONE 0x00000000UL /*!< ADC measurement paths all disabled */ -#define LL_ADC_PATH_INTERNAL_VREFINT (ADC_CCR_TSVREFE) /*!< ADC measurement path to internal channel VrefInt */ -#define LL_ADC_PATH_INTERNAL_TEMPSENSOR (ADC_CCR_TSVREFE) /*!< ADC measurement path to internal channel temperature sensor */ -#define LL_ADC_PATH_INTERNAL_VBAT (ADC_CCR_VBATE) /*!< ADC measurement path to internal channel Vbat */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_RESOLUTION ADC instance - Resolution - * @{ - */ -#define LL_ADC_RESOLUTION_12B 0x00000000UL /*!< ADC resolution 12 bits */ -#define LL_ADC_RESOLUTION_10B ( ADC_CR1_RES_0) /*!< ADC resolution 10 bits */ -#define LL_ADC_RESOLUTION_8B (ADC_CR1_RES_1 ) /*!< ADC resolution 8 bits */ -#define LL_ADC_RESOLUTION_6B (ADC_CR1_RES_1 | ADC_CR1_RES_0) /*!< ADC resolution 6 bits */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_DATA_ALIGN ADC instance - Data alignment - * @{ - */ -#define LL_ADC_DATA_ALIGN_RIGHT 0x00000000UL /*!< ADC conversion data alignment: right aligned (alignment on data register LSB bit 0)*/ -#define LL_ADC_DATA_ALIGN_LEFT (ADC_CR2_ALIGN) /*!< ADC conversion data alignment: left aligned (alignment on data register MSB bit 15)*/ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_SCAN_SELECTION ADC instance - Scan selection - * @{ - */ -#define LL_ADC_SEQ_SCAN_DISABLE 0x00000000UL /*!< ADC conversion is performed in unitary conversion mode (one channel converted, that defined in rank 1). Configuration of both groups regular and injected sequencers (sequence length, ...) is discarded: equivalent to length of 1 rank.*/ -#define LL_ADC_SEQ_SCAN_ENABLE (ADC_CR1_SCAN) /*!< ADC conversions are performed in sequence conversions mode, according to configuration of both groups regular and injected sequencers (sequence length, ...). */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_GROUPS ADC instance - Groups - * @{ - */ -#define LL_ADC_GROUP_REGULAR 0x00000001UL /*!< ADC group regular (available on all STM32 devices) */ -#define LL_ADC_GROUP_INJECTED 0x00000002UL /*!< ADC group injected (not available on all STM32 devices)*/ -#define LL_ADC_GROUP_REGULAR_INJECTED 0x00000003UL /*!< ADC both groups regular and injected */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_CHANNEL ADC instance - Channel number - * @{ - */ -#define LL_ADC_CHANNEL_0 (ADC_CHANNEL_0_NUMBER | ADC_CHANNEL_0_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN0 */ -#define LL_ADC_CHANNEL_1 (ADC_CHANNEL_1_NUMBER | ADC_CHANNEL_1_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN1 */ -#define LL_ADC_CHANNEL_2 (ADC_CHANNEL_2_NUMBER | ADC_CHANNEL_2_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN2 */ -#define LL_ADC_CHANNEL_3 (ADC_CHANNEL_3_NUMBER | ADC_CHANNEL_3_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN3 */ -#define LL_ADC_CHANNEL_4 (ADC_CHANNEL_4_NUMBER | ADC_CHANNEL_4_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN4 */ -#define LL_ADC_CHANNEL_5 (ADC_CHANNEL_5_NUMBER | ADC_CHANNEL_5_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN5 */ -#define LL_ADC_CHANNEL_6 (ADC_CHANNEL_6_NUMBER | ADC_CHANNEL_6_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN6 */ -#define LL_ADC_CHANNEL_7 (ADC_CHANNEL_7_NUMBER | ADC_CHANNEL_7_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN7 */ -#define LL_ADC_CHANNEL_8 (ADC_CHANNEL_8_NUMBER | ADC_CHANNEL_8_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN8 */ -#define LL_ADC_CHANNEL_9 (ADC_CHANNEL_9_NUMBER | ADC_CHANNEL_9_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN9 */ -#define LL_ADC_CHANNEL_10 (ADC_CHANNEL_10_NUMBER | ADC_CHANNEL_10_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN10 */ -#define LL_ADC_CHANNEL_11 (ADC_CHANNEL_11_NUMBER | ADC_CHANNEL_11_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN11 */ -#define LL_ADC_CHANNEL_12 (ADC_CHANNEL_12_NUMBER | ADC_CHANNEL_12_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN12 */ -#define LL_ADC_CHANNEL_13 (ADC_CHANNEL_13_NUMBER | ADC_CHANNEL_13_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN13 */ -#define LL_ADC_CHANNEL_14 (ADC_CHANNEL_14_NUMBER | ADC_CHANNEL_14_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN14 */ -#define LL_ADC_CHANNEL_15 (ADC_CHANNEL_15_NUMBER | ADC_CHANNEL_15_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN15 */ -#define LL_ADC_CHANNEL_16 (ADC_CHANNEL_16_NUMBER | ADC_CHANNEL_16_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN16 */ -#define LL_ADC_CHANNEL_17 (ADC_CHANNEL_17_NUMBER | ADC_CHANNEL_17_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN17 */ -#define LL_ADC_CHANNEL_18 (ADC_CHANNEL_18_NUMBER | ADC_CHANNEL_18_SMP) /*!< ADC external channel (channel connected to GPIO pin) ADCx_IN18 */ -#define LL_ADC_CHANNEL_VREFINT (LL_ADC_CHANNEL_17 | ADC_CHANNEL_ID_INTERNAL_CH) /*!< ADC internal channel connected to VrefInt: Internal voltage reference. On STM32F4, ADC channel available only on ADC instance: ADC1. */ -#define LL_ADC_CHANNEL_VBAT (LL_ADC_CHANNEL_18 | ADC_CHANNEL_ID_INTERNAL_CH) /*!< ADC internal channel connected to Vbat/3: Vbat voltage through a divider ladder of factor 1/3 to have Vbat always below Vdda. On STM32F4, ADC channel available only on ADC instance: ADC1. */ -#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F405xx) || defined(STM32F407xx) || defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F415xx) || defined(STM32F417xx) -#define LL_ADC_CHANNEL_TEMPSENSOR (LL_ADC_CHANNEL_16 | ADC_CHANNEL_ID_INTERNAL_CH) /*!< ADC internal channel connected to Temperature sensor. On STM32F4, ADC channel available only on ADC instance: ADC1. */ -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F401xC || STM32F401xE || STM32F410xx */ -#if defined(STM32F411xE) || defined(STM32F412Cx) || defined(STM32F412Rx) || defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) || defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -#define LL_ADC_CHANNEL_TEMPSENSOR (LL_ADC_CHANNEL_18 | ADC_CHANNEL_ID_INTERNAL_CH | ADC_CHANNEL_DIFFERENCIATION_TEMPSENSOR_VBAT) /*!< ADC internal channel connected to Temperature sensor. On STM32F4, ADC channel available only on ADC instance: ADC1. This internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled. */ -#endif /* STM32F411xE || STM32F412Cx || STM32F412Rx || STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx || STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_REG_TRIGGER_SOURCE ADC group regular - Trigger source - * @{ - */ -#define LL_ADC_REG_TRIG_SOFTWARE 0x00000000UL /*!< ADC group regular conversion trigger internal: SW start. */ -#define LL_ADC_REG_TRIG_EXT_TIM1_CH1 (ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM1 channel 1 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_REG_TRIG_EXT_TIM1_CH2 (ADC_CR2_EXTSEL_0 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM1 channel 2 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_REG_TRIG_EXT_TIM1_CH3 (ADC_CR2_EXTSEL_1 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM1 channel 3 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_REG_TRIG_EXT_TIM2_CH2 (ADC_CR2_EXTSEL_1 | ADC_CR2_EXTSEL_0 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM2 channel 2 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_REG_TRIG_EXT_TIM2_CH3 (ADC_CR2_EXTSEL_2 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM2 channel 3 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_REG_TRIG_EXT_TIM2_CH4 (ADC_CR2_EXTSEL_2 | ADC_CR2_EXTSEL_0 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM2 channel 4 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_REG_TRIG_EXT_TIM2_TRGO (ADC_CR2_EXTSEL_2 | ADC_CR2_EXTSEL_1 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM2 TRGO. Trigger edge set to rising edge (default setting). */ -#define LL_ADC_REG_TRIG_EXT_TIM3_CH1 (ADC_CR2_EXTSEL_2 | ADC_CR2_EXTSEL_1 | ADC_CR2_EXTSEL_0 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM3 channel 1 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_REG_TRIG_EXT_TIM3_TRGO (ADC_CR2_EXTSEL_3 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM3 TRGO. Trigger edge set to rising edge (default setting). */ -#define LL_ADC_REG_TRIG_EXT_TIM4_CH4 (ADC_CR2_EXTSEL_3 | ADC_CR2_EXTSEL_0 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM4 channel 4 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_REG_TRIG_EXT_TIM5_CH1 (ADC_CR2_EXTSEL_3 | ADC_CR2_EXTSEL_1 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM5 channel 1 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_REG_TRIG_EXT_TIM5_CH2 (ADC_CR2_EXTSEL_3 | ADC_CR2_EXTSEL_1 | ADC_CR2_EXTSEL_0 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM5 channel 2 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_REG_TRIG_EXT_TIM5_CH3 (ADC_CR2_EXTSEL_3 | ADC_CR2_EXTSEL_2 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM5 channel 3 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_REG_TRIG_EXT_TIM8_CH1 (ADC_CR2_EXTSEL_3 | ADC_CR2_EXTSEL_2 | ADC_CR2_EXTSEL_0 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM8 channel 1 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_REG_TRIG_EXT_TIM8_TRGO (ADC_CR2_EXTSEL_3 | ADC_CR2_EXTSEL_2 | ADC_CR2_EXTSEL_1 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: TIM8 TRGO. Trigger edge set to rising edge (default setting). */ -#define LL_ADC_REG_TRIG_EXT_EXTI_LINE11 (ADC_CR2_EXTSEL_3 | ADC_CR2_EXTSEL_2 | ADC_CR2_EXTSEL_1 | ADC_CR2_EXTSEL_0 | ADC_REG_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group regular conversion trigger from external IP: external interrupt line 11. Trigger edge set to rising edge (default setting). */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_REG_TRIGGER_EDGE ADC group regular - Trigger edge - * @{ - */ -#define LL_ADC_REG_TRIG_EXT_RISING ( ADC_CR2_EXTEN_0) /*!< ADC group regular conversion trigger polarity set to rising edge */ -#define LL_ADC_REG_TRIG_EXT_FALLING (ADC_CR2_EXTEN_1 ) /*!< ADC group regular conversion trigger polarity set to falling edge */ -#define LL_ADC_REG_TRIG_EXT_RISINGFALLING (ADC_CR2_EXTEN_1 | ADC_CR2_EXTEN_0) /*!< ADC group regular conversion trigger polarity set to both rising and falling edges */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_REG_CONTINUOUS_MODE ADC group regular - Continuous mode -* @{ -*/ -#define LL_ADC_REG_CONV_SINGLE 0x00000000UL /*!< ADC conversions are performed in single mode: one conversion per trigger */ -#define LL_ADC_REG_CONV_CONTINUOUS (ADC_CR2_CONT) /*!< ADC conversions are performed in continuous mode: after the first trigger, following conversions launched successively automatically */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_REG_DMA_TRANSFER ADC group regular - DMA transfer of ADC conversion data - * @{ - */ -#define LL_ADC_REG_DMA_TRANSFER_NONE 0x00000000UL /*!< ADC conversions are not transferred by DMA */ -#define LL_ADC_REG_DMA_TRANSFER_LIMITED ( ADC_CR2_DMA) /*!< ADC conversion data are transferred by DMA, in limited mode (one shot mode): DMA transfer requests are stopped when number of DMA data transfers (number of ADC conversions) is reached. This ADC mode is intended to be used with DMA mode non-circular. */ -#define LL_ADC_REG_DMA_TRANSFER_UNLIMITED (ADC_CR2_DDS | ADC_CR2_DMA) /*!< ADC conversion data are transferred by DMA, in unlimited mode: DMA transfer requests are unlimited, whatever number of DMA data transferred (number of ADC conversions). This ADC mode is intended to be used with DMA mode circular. */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_REG_FLAG_EOC_SELECTION ADC group regular - Flag EOC selection (unitary or sequence conversions) - * @{ - */ -#define LL_ADC_REG_FLAG_EOC_SEQUENCE_CONV 0x00000000UL /*!< ADC flag EOC (end of unitary conversion) selected */ -#define LL_ADC_REG_FLAG_EOC_UNITARY_CONV (ADC_CR2_EOCS) /*!< ADC flag EOS (end of sequence conversions) selected */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_REG_SEQ_SCAN_LENGTH ADC group regular - Sequencer scan length - * @{ - */ -#define LL_ADC_REG_SEQ_SCAN_DISABLE 0x00000000UL /*!< ADC group regular sequencer disable (equivalent to sequencer of 1 rank: ADC conversion on only 1 channel) */ -#define LL_ADC_REG_SEQ_SCAN_ENABLE_2RANKS ( ADC_SQR1_L_0) /*!< ADC group regular sequencer enable with 2 ranks in the sequence */ -#define LL_ADC_REG_SEQ_SCAN_ENABLE_3RANKS ( ADC_SQR1_L_1 ) /*!< ADC group regular sequencer enable with 3 ranks in the sequence */ -#define LL_ADC_REG_SEQ_SCAN_ENABLE_4RANKS ( ADC_SQR1_L_1 | ADC_SQR1_L_0) /*!< ADC group regular sequencer enable with 4 ranks in the sequence */ -#define LL_ADC_REG_SEQ_SCAN_ENABLE_5RANKS ( ADC_SQR1_L_2 ) /*!< ADC group regular sequencer enable with 5 ranks in the sequence */ -#define LL_ADC_REG_SEQ_SCAN_ENABLE_6RANKS ( ADC_SQR1_L_2 | ADC_SQR1_L_0) /*!< ADC group regular sequencer enable with 6 ranks in the sequence */ -#define LL_ADC_REG_SEQ_SCAN_ENABLE_7RANKS ( ADC_SQR1_L_2 | ADC_SQR1_L_1 ) /*!< ADC group regular sequencer enable with 7 ranks in the sequence */ -#define LL_ADC_REG_SEQ_SCAN_ENABLE_8RANKS ( ADC_SQR1_L_2 | ADC_SQR1_L_1 | ADC_SQR1_L_0) /*!< ADC group regular sequencer enable with 8 ranks in the sequence */ -#define LL_ADC_REG_SEQ_SCAN_ENABLE_9RANKS (ADC_SQR1_L_3 ) /*!< ADC group regular sequencer enable with 9 ranks in the sequence */ -#define LL_ADC_REG_SEQ_SCAN_ENABLE_10RANKS (ADC_SQR1_L_3 | ADC_SQR1_L_0) /*!< ADC group regular sequencer enable with 10 ranks in the sequence */ -#define LL_ADC_REG_SEQ_SCAN_ENABLE_11RANKS (ADC_SQR1_L_3 | ADC_SQR1_L_1 ) /*!< ADC group regular sequencer enable with 11 ranks in the sequence */ -#define LL_ADC_REG_SEQ_SCAN_ENABLE_12RANKS (ADC_SQR1_L_3 | ADC_SQR1_L_1 | ADC_SQR1_L_0) /*!< ADC group regular sequencer enable with 12 ranks in the sequence */ -#define LL_ADC_REG_SEQ_SCAN_ENABLE_13RANKS (ADC_SQR1_L_3 | ADC_SQR1_L_2 ) /*!< ADC group regular sequencer enable with 13 ranks in the sequence */ -#define LL_ADC_REG_SEQ_SCAN_ENABLE_14RANKS (ADC_SQR1_L_3 | ADC_SQR1_L_2 | ADC_SQR1_L_0) /*!< ADC group regular sequencer enable with 14 ranks in the sequence */ -#define LL_ADC_REG_SEQ_SCAN_ENABLE_15RANKS (ADC_SQR1_L_3 | ADC_SQR1_L_2 | ADC_SQR1_L_1 ) /*!< ADC group regular sequencer enable with 15 ranks in the sequence */ -#define LL_ADC_REG_SEQ_SCAN_ENABLE_16RANKS (ADC_SQR1_L_3 | ADC_SQR1_L_2 | ADC_SQR1_L_1 | ADC_SQR1_L_0) /*!< ADC group regular sequencer enable with 16 ranks in the sequence */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_REG_SEQ_DISCONT_MODE ADC group regular - Sequencer discontinuous mode - * @{ - */ -#define LL_ADC_REG_SEQ_DISCONT_DISABLE 0x00000000UL /*!< ADC group regular sequencer discontinuous mode disable */ -#define LL_ADC_REG_SEQ_DISCONT_1RANK ( ADC_CR1_DISCEN) /*!< ADC group regular sequencer discontinuous mode enable with sequence interruption every rank */ -#define LL_ADC_REG_SEQ_DISCONT_2RANKS ( ADC_CR1_DISCNUM_0 | ADC_CR1_DISCEN) /*!< ADC group regular sequencer discontinuous mode enabled with sequence interruption every 2 ranks */ -#define LL_ADC_REG_SEQ_DISCONT_3RANKS ( ADC_CR1_DISCNUM_1 | ADC_CR1_DISCEN) /*!< ADC group regular sequencer discontinuous mode enable with sequence interruption every 3 ranks */ -#define LL_ADC_REG_SEQ_DISCONT_4RANKS ( ADC_CR1_DISCNUM_1 | ADC_CR1_DISCNUM_0 | ADC_CR1_DISCEN) /*!< ADC group regular sequencer discontinuous mode enable with sequence interruption every 4 ranks */ -#define LL_ADC_REG_SEQ_DISCONT_5RANKS (ADC_CR1_DISCNUM_2 | ADC_CR1_DISCEN) /*!< ADC group regular sequencer discontinuous mode enable with sequence interruption every 5 ranks */ -#define LL_ADC_REG_SEQ_DISCONT_6RANKS (ADC_CR1_DISCNUM_2 | ADC_CR1_DISCNUM_0 | ADC_CR1_DISCEN) /*!< ADC group regular sequencer discontinuous mode enable with sequence interruption every 6 ranks */ -#define LL_ADC_REG_SEQ_DISCONT_7RANKS (ADC_CR1_DISCNUM_2 | ADC_CR1_DISCNUM_1 | ADC_CR1_DISCEN) /*!< ADC group regular sequencer discontinuous mode enable with sequence interruption every 7 ranks */ -#define LL_ADC_REG_SEQ_DISCONT_8RANKS (ADC_CR1_DISCNUM_2 | ADC_CR1_DISCNUM_1 | ADC_CR1_DISCNUM_0 | ADC_CR1_DISCEN) /*!< ADC group regular sequencer discontinuous mode enable with sequence interruption every 8 ranks */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_REG_SEQ_RANKS ADC group regular - Sequencer ranks - * @{ - */ -#define LL_ADC_REG_RANK_1 (ADC_SQR3_REGOFFSET | ADC_REG_RANK_1_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 1 */ -#define LL_ADC_REG_RANK_2 (ADC_SQR3_REGOFFSET | ADC_REG_RANK_2_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 2 */ -#define LL_ADC_REG_RANK_3 (ADC_SQR3_REGOFFSET | ADC_REG_RANK_3_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 3 */ -#define LL_ADC_REG_RANK_4 (ADC_SQR3_REGOFFSET | ADC_REG_RANK_4_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 4 */ -#define LL_ADC_REG_RANK_5 (ADC_SQR3_REGOFFSET | ADC_REG_RANK_5_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 5 */ -#define LL_ADC_REG_RANK_6 (ADC_SQR3_REGOFFSET | ADC_REG_RANK_6_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 6 */ -#define LL_ADC_REG_RANK_7 (ADC_SQR2_REGOFFSET | ADC_REG_RANK_7_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 7 */ -#define LL_ADC_REG_RANK_8 (ADC_SQR2_REGOFFSET | ADC_REG_RANK_8_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 8 */ -#define LL_ADC_REG_RANK_9 (ADC_SQR2_REGOFFSET | ADC_REG_RANK_9_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 9 */ -#define LL_ADC_REG_RANK_10 (ADC_SQR2_REGOFFSET | ADC_REG_RANK_10_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 10 */ -#define LL_ADC_REG_RANK_11 (ADC_SQR2_REGOFFSET | ADC_REG_RANK_11_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 11 */ -#define LL_ADC_REG_RANK_12 (ADC_SQR2_REGOFFSET | ADC_REG_RANK_12_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 12 */ -#define LL_ADC_REG_RANK_13 (ADC_SQR1_REGOFFSET | ADC_REG_RANK_13_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 13 */ -#define LL_ADC_REG_RANK_14 (ADC_SQR1_REGOFFSET | ADC_REG_RANK_14_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 14 */ -#define LL_ADC_REG_RANK_15 (ADC_SQR1_REGOFFSET | ADC_REG_RANK_15_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 15 */ -#define LL_ADC_REG_RANK_16 (ADC_SQR1_REGOFFSET | ADC_REG_RANK_16_SQRX_BITOFFSET_POS) /*!< ADC group regular sequencer rank 16 */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_INJ_TRIGGER_SOURCE ADC group injected - Trigger source - * @{ - */ -#define LL_ADC_INJ_TRIG_SOFTWARE 0x00000000UL /*!< ADC group injected conversion trigger internal: SW start. */ -#define LL_ADC_INJ_TRIG_EXT_TIM1_CH4 (ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM1 channel 4 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_INJ_TRIG_EXT_TIM1_TRGO (ADC_CR2_JEXTSEL_0 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM1 TRGO. Trigger edge set to rising edge (default setting). */ -#define LL_ADC_INJ_TRIG_EXT_TIM2_CH1 (ADC_CR2_JEXTSEL_1 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM2 channel 1 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_INJ_TRIG_EXT_TIM2_TRGO (ADC_CR2_JEXTSEL_1 | ADC_CR2_JEXTSEL_0 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM2 TRGO. Trigger edge set to rising edge (default setting). */ -#define LL_ADC_INJ_TRIG_EXT_TIM3_CH2 (ADC_CR2_JEXTSEL_2 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM3 channel 2 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_INJ_TRIG_EXT_TIM3_CH4 (ADC_CR2_JEXTSEL_2 | ADC_CR2_JEXTSEL_0 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM3 channel 4 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_INJ_TRIG_EXT_TIM4_CH1 (ADC_CR2_JEXTSEL_2 | ADC_CR2_JEXTSEL_1 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM4 channel 1 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_INJ_TRIG_EXT_TIM4_CH2 (ADC_CR2_JEXTSEL_2 | ADC_CR2_JEXTSEL_1 | ADC_CR2_JEXTSEL_0 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM4 channel 2 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_INJ_TRIG_EXT_TIM4_CH3 (ADC_CR2_JEXTSEL_3 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM4 channel 3 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_INJ_TRIG_EXT_TIM4_TRGO (ADC_CR2_JEXTSEL_3 | ADC_CR2_JEXTSEL_0 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM4 TRGO. Trigger edge set to rising edge (default setting). */ -#define LL_ADC_INJ_TRIG_EXT_TIM5_CH4 (ADC_CR2_JEXTSEL_3 | ADC_CR2_JEXTSEL_1 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM5 channel 4 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_INJ_TRIG_EXT_TIM5_TRGO (ADC_CR2_JEXTSEL_3 | ADC_CR2_JEXTSEL_1 | ADC_CR2_JEXTSEL_0 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM5 TRGO. Trigger edge set to rising edge (default setting). */ -#define LL_ADC_INJ_TRIG_EXT_TIM8_CH2 (ADC_CR2_JEXTSEL_3 | ADC_CR2_JEXTSEL_2 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM8 channel 2 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_INJ_TRIG_EXT_TIM8_CH3 (ADC_CR2_JEXTSEL_3 | ADC_CR2_JEXTSEL_2 | ADC_CR2_JEXTSEL_0 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM8 channel 3 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_INJ_TRIG_EXT_TIM8_CH4 (ADC_CR2_JEXTSEL_3 | ADC_CR2_JEXTSEL_2 | ADC_CR2_JEXTSEL_1 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: TIM8 channel 4 event (capture compare: input capture or output capture). Trigger edge set to rising edge (default setting). */ -#define LL_ADC_INJ_TRIG_EXT_EXTI_LINE15 (ADC_CR2_JEXTSEL_3 | ADC_CR2_JEXTSEL_2 | ADC_CR2_JEXTSEL_1 | ADC_CR2_JEXTSEL_0 | ADC_INJ_TRIG_EXT_EDGE_DEFAULT) /*!< ADC group injected conversion trigger from external IP: external interrupt line 15. Trigger edge set to rising edge (default setting). */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_INJ_TRIGGER_EDGE ADC group injected - Trigger edge - * @{ - */ -#define LL_ADC_INJ_TRIG_EXT_RISING ( ADC_CR2_JEXTEN_0) /*!< ADC group injected conversion trigger polarity set to rising edge */ -#define LL_ADC_INJ_TRIG_EXT_FALLING (ADC_CR2_JEXTEN_1 ) /*!< ADC group injected conversion trigger polarity set to falling edge */ -#define LL_ADC_INJ_TRIG_EXT_RISINGFALLING (ADC_CR2_JEXTEN_1 | ADC_CR2_JEXTEN_0) /*!< ADC group injected conversion trigger polarity set to both rising and falling edges */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_INJ_TRIG_AUTO ADC group injected - Automatic trigger mode -* @{ -*/ -#define LL_ADC_INJ_TRIG_INDEPENDENT 0x00000000UL /*!< ADC group injected conversion trigger independent. Setting mandatory if ADC group injected injected trigger source is set to an external trigger. */ -#define LL_ADC_INJ_TRIG_FROM_GRP_REGULAR (ADC_CR1_JAUTO) /*!< ADC group injected conversion trigger from ADC group regular. Setting compliant only with group injected trigger source set to SW start, without any further action on ADC group injected conversion start or stop: in this case, ADC group injected is controlled only from ADC group regular. */ -/** - * @} - */ - - -/** @defgroup ADC_LL_EC_INJ_SEQ_SCAN_LENGTH ADC group injected - Sequencer scan length - * @{ - */ -#define LL_ADC_INJ_SEQ_SCAN_DISABLE 0x00000000UL /*!< ADC group injected sequencer disable (equivalent to sequencer of 1 rank: ADC conversion on only 1 channel) */ -#define LL_ADC_INJ_SEQ_SCAN_ENABLE_2RANKS ( ADC_JSQR_JL_0) /*!< ADC group injected sequencer enable with 2 ranks in the sequence */ -#define LL_ADC_INJ_SEQ_SCAN_ENABLE_3RANKS (ADC_JSQR_JL_1 ) /*!< ADC group injected sequencer enable with 3 ranks in the sequence */ -#define LL_ADC_INJ_SEQ_SCAN_ENABLE_4RANKS (ADC_JSQR_JL_1 | ADC_JSQR_JL_0) /*!< ADC group injected sequencer enable with 4 ranks in the sequence */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_INJ_SEQ_DISCONT_MODE ADC group injected - Sequencer discontinuous mode - * @{ - */ -#define LL_ADC_INJ_SEQ_DISCONT_DISABLE 0x00000000UL /*!< ADC group injected sequencer discontinuous mode disable */ -#define LL_ADC_INJ_SEQ_DISCONT_1RANK (ADC_CR1_JDISCEN) /*!< ADC group injected sequencer discontinuous mode enable with sequence interruption every rank */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_INJ_SEQ_RANKS ADC group injected - Sequencer ranks - * @{ - */ -#define LL_ADC_INJ_RANK_1 (ADC_JDR1_REGOFFSET | ADC_JOFR1_REGOFFSET | 0x00000001UL) /*!< ADC group injected sequencer rank 1 */ -#define LL_ADC_INJ_RANK_2 (ADC_JDR2_REGOFFSET | ADC_JOFR2_REGOFFSET | 0x00000002UL) /*!< ADC group injected sequencer rank 2 */ -#define LL_ADC_INJ_RANK_3 (ADC_JDR3_REGOFFSET | ADC_JOFR3_REGOFFSET | 0x00000003UL) /*!< ADC group injected sequencer rank 3 */ -#define LL_ADC_INJ_RANK_4 (ADC_JDR4_REGOFFSET | ADC_JOFR4_REGOFFSET | 0x00000004UL) /*!< ADC group injected sequencer rank 4 */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_CHANNEL_SAMPLINGTIME Channel - Sampling time - * @{ - */ -#define LL_ADC_SAMPLINGTIME_3CYCLES 0x00000000UL /*!< Sampling time 3 ADC clock cycles */ -#define LL_ADC_SAMPLINGTIME_15CYCLES (ADC_SMPR1_SMP10_0) /*!< Sampling time 15 ADC clock cycles */ -#define LL_ADC_SAMPLINGTIME_28CYCLES (ADC_SMPR1_SMP10_1) /*!< Sampling time 28 ADC clock cycles */ -#define LL_ADC_SAMPLINGTIME_56CYCLES (ADC_SMPR1_SMP10_1 | ADC_SMPR1_SMP10_0) /*!< Sampling time 56 ADC clock cycles */ -#define LL_ADC_SAMPLINGTIME_84CYCLES (ADC_SMPR1_SMP10_2) /*!< Sampling time 84 ADC clock cycles */ -#define LL_ADC_SAMPLINGTIME_112CYCLES (ADC_SMPR1_SMP10_2 | ADC_SMPR1_SMP10_0) /*!< Sampling time 112 ADC clock cycles */ -#define LL_ADC_SAMPLINGTIME_144CYCLES (ADC_SMPR1_SMP10_2 | ADC_SMPR1_SMP10_1) /*!< Sampling time 144 ADC clock cycles */ -#define LL_ADC_SAMPLINGTIME_480CYCLES (ADC_SMPR1_SMP10) /*!< Sampling time 480 ADC clock cycles */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_AWD_NUMBER Analog watchdog - Analog watchdog number - * @{ - */ -#define LL_ADC_AWD1 (ADC_AWD_CR1_CHANNEL_MASK | ADC_AWD_CR1_REGOFFSET) /*!< ADC analog watchdog number 1 */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_AWD_CHANNELS Analog watchdog - Monitored channels - * @{ - */ -#define LL_ADC_AWD_DISABLE 0x00000000UL /*!< ADC analog watchdog monitoring disabled */ -#define LL_ADC_AWD_ALL_CHANNELS_REG ( ADC_CR1_AWDEN ) /*!< ADC analog watchdog monitoring of all channels, converted by group regular only */ -#define LL_ADC_AWD_ALL_CHANNELS_INJ ( ADC_CR1_JAWDEN ) /*!< ADC analog watchdog monitoring of all channels, converted by group injected only */ -#define LL_ADC_AWD_ALL_CHANNELS_REG_INJ ( ADC_CR1_JAWDEN | ADC_CR1_AWDEN ) /*!< ADC analog watchdog monitoring of all channels, converted by either group regular or injected */ -#define LL_ADC_AWD_CHANNEL_0_REG ((LL_ADC_CHANNEL_0 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN0, converted by group regular only */ -#define LL_ADC_AWD_CHANNEL_0_INJ ((LL_ADC_CHANNEL_0 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN0, converted by group injected only */ -#define LL_ADC_AWD_CHANNEL_0_REG_INJ ((LL_ADC_CHANNEL_0 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN0, converted by either group regular or injected */ -#define LL_ADC_AWD_CHANNEL_1_REG ((LL_ADC_CHANNEL_1 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN1, converted by group regular only */ -#define LL_ADC_AWD_CHANNEL_1_INJ ((LL_ADC_CHANNEL_1 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN1, converted by group injected only */ -#define LL_ADC_AWD_CHANNEL_1_REG_INJ ((LL_ADC_CHANNEL_1 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN1, converted by either group regular or injected */ -#define LL_ADC_AWD_CHANNEL_2_REG ((LL_ADC_CHANNEL_2 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN2, converted by group regular only */ -#define LL_ADC_AWD_CHANNEL_2_INJ ((LL_ADC_CHANNEL_2 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN2, converted by group injected only */ -#define LL_ADC_AWD_CHANNEL_2_REG_INJ ((LL_ADC_CHANNEL_2 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN2, converted by either group regular or injected */ -#define LL_ADC_AWD_CHANNEL_3_REG ((LL_ADC_CHANNEL_3 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN3, converted by group regular only */ -#define LL_ADC_AWD_CHANNEL_3_INJ ((LL_ADC_CHANNEL_3 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN3, converted by group injected only */ -#define LL_ADC_AWD_CHANNEL_3_REG_INJ ((LL_ADC_CHANNEL_3 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN3, converted by either group regular or injected */ -#define LL_ADC_AWD_CHANNEL_4_REG ((LL_ADC_CHANNEL_4 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN4, converted by group regular only */ -#define LL_ADC_AWD_CHANNEL_4_INJ ((LL_ADC_CHANNEL_4 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN4, converted by group injected only */ -#define LL_ADC_AWD_CHANNEL_4_REG_INJ ((LL_ADC_CHANNEL_4 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN4, converted by either group regular or injected */ -#define LL_ADC_AWD_CHANNEL_5_REG ((LL_ADC_CHANNEL_5 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN5, converted by group regular only */ -#define LL_ADC_AWD_CHANNEL_5_INJ ((LL_ADC_CHANNEL_5 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN5, converted by group injected only */ -#define LL_ADC_AWD_CHANNEL_5_REG_INJ ((LL_ADC_CHANNEL_5 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN5, converted by either group regular or injected */ -#define LL_ADC_AWD_CHANNEL_6_REG ((LL_ADC_CHANNEL_6 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN6, converted by group regular only */ -#define LL_ADC_AWD_CHANNEL_6_INJ ((LL_ADC_CHANNEL_6 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN6, converted by group injected only */ -#define LL_ADC_AWD_CHANNEL_6_REG_INJ ((LL_ADC_CHANNEL_6 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN6, converted by either group regular or injected */ -#define LL_ADC_AWD_CHANNEL_7_REG ((LL_ADC_CHANNEL_7 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN7, converted by group regular only */ -#define LL_ADC_AWD_CHANNEL_7_INJ ((LL_ADC_CHANNEL_7 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN7, converted by group injected only */ -#define LL_ADC_AWD_CHANNEL_7_REG_INJ ((LL_ADC_CHANNEL_7 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN7, converted by either group regular or injected */ -#define LL_ADC_AWD_CHANNEL_8_REG ((LL_ADC_CHANNEL_8 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN8, converted by group regular only */ -#define LL_ADC_AWD_CHANNEL_8_INJ ((LL_ADC_CHANNEL_8 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN8, converted by group injected only */ -#define LL_ADC_AWD_CHANNEL_8_REG_INJ ((LL_ADC_CHANNEL_8 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN8, converted by either group regular or injected */ -#define LL_ADC_AWD_CHANNEL_9_REG ((LL_ADC_CHANNEL_9 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN9, converted by group regular only */ -#define LL_ADC_AWD_CHANNEL_9_INJ ((LL_ADC_CHANNEL_9 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN9, converted by group injected only */ -#define LL_ADC_AWD_CHANNEL_9_REG_INJ ((LL_ADC_CHANNEL_9 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN9, converted by either group regular or injected */ -#define LL_ADC_AWD_CHANNEL_10_REG ((LL_ADC_CHANNEL_10 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN10, converted by group regular only */ -#define LL_ADC_AWD_CHANNEL_10_INJ ((LL_ADC_CHANNEL_10 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN10, converted by group injected only */ -#define LL_ADC_AWD_CHANNEL_10_REG_INJ ((LL_ADC_CHANNEL_10 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN10, converted by either group regular or injected */ -#define LL_ADC_AWD_CHANNEL_11_REG ((LL_ADC_CHANNEL_11 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN11, converted by group regular only */ -#define LL_ADC_AWD_CHANNEL_11_INJ ((LL_ADC_CHANNEL_11 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN11, converted by group injected only */ -#define LL_ADC_AWD_CHANNEL_11_REG_INJ ((LL_ADC_CHANNEL_11 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN11, converted by either group regular or injected */ -#define LL_ADC_AWD_CHANNEL_12_REG ((LL_ADC_CHANNEL_12 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN12, converted by group regular only */ -#define LL_ADC_AWD_CHANNEL_12_INJ ((LL_ADC_CHANNEL_12 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN12, converted by group injected only */ -#define LL_ADC_AWD_CHANNEL_12_REG_INJ ((LL_ADC_CHANNEL_12 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN12, converted by either group regular or injected */ -#define LL_ADC_AWD_CHANNEL_13_REG ((LL_ADC_CHANNEL_13 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN13, converted by group regular only */ -#define LL_ADC_AWD_CHANNEL_13_INJ ((LL_ADC_CHANNEL_13 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN13, converted by group injected only */ -#define LL_ADC_AWD_CHANNEL_13_REG_INJ ((LL_ADC_CHANNEL_13 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN13, converted by either group regular or injected */ -#define LL_ADC_AWD_CHANNEL_14_REG ((LL_ADC_CHANNEL_14 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN14, converted by group regular only */ -#define LL_ADC_AWD_CHANNEL_14_INJ ((LL_ADC_CHANNEL_14 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN14, converted by group injected only */ -#define LL_ADC_AWD_CHANNEL_14_REG_INJ ((LL_ADC_CHANNEL_14 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN14, converted by either group regular or injected */ -#define LL_ADC_AWD_CHANNEL_15_REG ((LL_ADC_CHANNEL_15 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN15, converted by group regular only */ -#define LL_ADC_AWD_CHANNEL_15_INJ ((LL_ADC_CHANNEL_15 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN15, converted by group injected only */ -#define LL_ADC_AWD_CHANNEL_15_REG_INJ ((LL_ADC_CHANNEL_15 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN15, converted by either group regular or injected */ -#define LL_ADC_AWD_CHANNEL_16_REG ((LL_ADC_CHANNEL_16 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN16, converted by group regular only */ -#define LL_ADC_AWD_CHANNEL_16_INJ ((LL_ADC_CHANNEL_16 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN16, converted by group injected only */ -#define LL_ADC_AWD_CHANNEL_16_REG_INJ ((LL_ADC_CHANNEL_16 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN16, converted by either group regular or injected */ -#define LL_ADC_AWD_CHANNEL_17_REG ((LL_ADC_CHANNEL_17 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN17, converted by group regular only */ -#define LL_ADC_AWD_CHANNEL_17_INJ ((LL_ADC_CHANNEL_17 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN17, converted by group injected only */ -#define LL_ADC_AWD_CHANNEL_17_REG_INJ ((LL_ADC_CHANNEL_17 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN17, converted by either group regular or injected */ -#define LL_ADC_AWD_CHANNEL_18_REG ((LL_ADC_CHANNEL_18 & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN18, converted by group regular only */ -#define LL_ADC_AWD_CHANNEL_18_INJ ((LL_ADC_CHANNEL_18 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN18, converted by group injected only */ -#define LL_ADC_AWD_CHANNEL_18_REG_INJ ((LL_ADC_CHANNEL_18 & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC external channel (channel connected to GPIO pin) ADCx_IN18, converted by either group regular or injected */ -#define LL_ADC_AWD_CH_VREFINT_REG ((LL_ADC_CHANNEL_VREFINT & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC internal channel connected to VrefInt: Internal voltage reference, converted by group regular only */ -#define LL_ADC_AWD_CH_VREFINT_INJ ((LL_ADC_CHANNEL_VREFINT & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC internal channel connected to VrefInt: Internal voltage reference, converted by group injected only */ -#define LL_ADC_AWD_CH_VREFINT_REG_INJ ((LL_ADC_CHANNEL_VREFINT & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC internal channel connected to VrefInt: Internal voltage reference, converted by either group regular or injected */ -#define LL_ADC_AWD_CH_VBAT_REG ((LL_ADC_CHANNEL_VBAT & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC internal channel connected to Vbat/3: Vbat voltage through a divider ladder of factor 1/3 to have Vbat always below Vdda, converted by group regular only */ -#define LL_ADC_AWD_CH_VBAT_INJ ((LL_ADC_CHANNEL_VBAT & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC internal channel connected to Vbat/3: Vbat voltage through a divider ladder of factor 1/3 to have Vbat always below Vdda, converted by group injected only */ -#define LL_ADC_AWD_CH_VBAT_REG_INJ ((LL_ADC_CHANNEL_VBAT & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC internal channel connected to Vbat/3: Vbat voltage through a divider ladder of factor 1/3 to have Vbat always below Vdda */ -#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F405xx) || defined(STM32F407xx) || defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) || defined(STM32F415xx) || defined(STM32F417xx) -#define LL_ADC_AWD_CH_TEMPSENSOR_REG ((LL_ADC_CHANNEL_TEMPSENSOR & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC internal channel connected to Temperature sensor, converted by group regular only */ -#define LL_ADC_AWD_CH_TEMPSENSOR_INJ ((LL_ADC_CHANNEL_TEMPSENSOR & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC internal channel connected to Temperature sensor, converted by group injected only */ -#define LL_ADC_AWD_CH_TEMPSENSOR_REG_INJ ((LL_ADC_CHANNEL_TEMPSENSOR & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC internal channel connected to Temperature sensor, converted by either group regular or injected */ -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F401xC || STM32F401xE || STM32F410xx */ -#if defined(STM32F411xE) || defined(STM32F412Cx) || defined(STM32F412Rx) || defined(STM32F412Vx) || defined(STM32F412Zx) || defined(STM32F413xx) || defined(STM32F423xx) || defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) || defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -#define LL_ADC_AWD_CH_TEMPSENSOR_REG ((LL_ADC_CHANNEL_TEMPSENSOR & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC internal channel connected to Temperature sensor, converted by group regular only. This internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled. */ -#define LL_ADC_AWD_CH_TEMPSENSOR_INJ ((LL_ADC_CHANNEL_TEMPSENSOR & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC internal channel connected to Temperature sensor, converted by group injected only. This internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled. */ -#define LL_ADC_AWD_CH_TEMPSENSOR_REG_INJ ((LL_ADC_CHANNEL_TEMPSENSOR & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) /*!< ADC analog watchdog monitoring of ADC internal channel connected to Temperature sensor, converted by either group regular or injected. This internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled. */ -#endif /* STM32F411xE || STM32F412Cx || STM32F412Rx || STM32F412Vx || STM32F412Zx || STM32F413xx || STM32F423xx || STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_AWD_THRESHOLDS Analog watchdog - Thresholds - * @{ - */ -#define LL_ADC_AWD_THRESHOLD_HIGH (ADC_AWD_TR1_HIGH_REGOFFSET) /*!< ADC analog watchdog threshold high */ -#define LL_ADC_AWD_THRESHOLD_LOW (ADC_AWD_TR1_LOW_REGOFFSET) /*!< ADC analog watchdog threshold low */ -/** - * @} - */ - -#if defined(ADC_MULTIMODE_SUPPORT) -/** @defgroup ADC_LL_EC_MULTI_MODE Multimode - Mode - * @{ - */ -#define LL_ADC_MULTI_INDEPENDENT 0x00000000UL /*!< ADC dual mode disabled (ADC independent mode) */ -#define LL_ADC_MULTI_DUAL_REG_SIMULT ( ADC_CCR_MULTI_2 | ADC_CCR_MULTI_1 ) /*!< ADC dual mode enabled: group regular simultaneous */ -#define LL_ADC_MULTI_DUAL_REG_INTERL ( ADC_CCR_MULTI_2 | ADC_CCR_MULTI_1 | ADC_CCR_MULTI_0) /*!< ADC dual mode enabled: Combined group regular interleaved */ -#define LL_ADC_MULTI_DUAL_INJ_SIMULT ( ADC_CCR_MULTI_2 | ADC_CCR_MULTI_0) /*!< ADC dual mode enabled: group injected simultaneous */ -#define LL_ADC_MULTI_DUAL_INJ_ALTERN (ADC_CCR_MULTI_3 | ADC_CCR_MULTI_0) /*!< ADC dual mode enabled: group injected alternate trigger. Works only with external triggers (not internal SW start) */ -#define LL_ADC_MULTI_DUAL_REG_SIM_INJ_SIM ( ADC_CCR_MULTI_0) /*!< ADC dual mode enabled: Combined group regular simultaneous + group injected simultaneous */ -#define LL_ADC_MULTI_DUAL_REG_SIM_INJ_ALT ( ADC_CCR_MULTI_1 ) /*!< ADC dual mode enabled: Combined group regular simultaneous + group injected alternate trigger */ -#define LL_ADC_MULTI_DUAL_REG_INT_INJ_SIM ( ADC_CCR_MULTI_1 | ADC_CCR_MULTI_0) /*!< ADC dual mode enabled: Combined group regular interleaved + group injected simultaneous */ -#if defined(ADC3) -#define LL_ADC_MULTI_TRIPLE_REG_SIM_INJ_SIM (ADC_CCR_MULTI_4 | ADC_CCR_MULTI_0) /*!< ADC triple mode enabled: Combined group regular simultaneous + group injected simultaneous */ -#define LL_ADC_MULTI_TRIPLE_REG_SIM_INJ_ALT (ADC_CCR_MULTI_4 | ADC_CCR_MULTI_1 ) /*!< ADC triple mode enabled: Combined group regular simultaneous + group injected alternate trigger */ -#define LL_ADC_MULTI_TRIPLE_INJ_SIMULT (ADC_CCR_MULTI_4 | ADC_CCR_MULTI_2 | ADC_CCR_MULTI_0) /*!< ADC triple mode enabled: group injected simultaneous */ -#define LL_ADC_MULTI_TRIPLE_REG_SIMULT (ADC_CCR_MULTI_4 | ADC_CCR_MULTI_2 | ADC_CCR_MULTI_1 ) /*!< ADC triple mode enabled: group regular simultaneous */ -#define LL_ADC_MULTI_TRIPLE_REG_INTERL (ADC_CCR_MULTI_4 | ADC_CCR_MULTI_2 | ADC_CCR_MULTI_1 | ADC_CCR_MULTI_0) /*!< ADC triple mode enabled: Combined group regular interleaved */ -#define LL_ADC_MULTI_TRIPLE_INJ_ALTERN (ADC_CCR_MULTI_4 | ADC_CCR_MULTI_0) /*!< ADC triple mode enabled: group injected alternate trigger. Works only with external triggers (not internal SW start) */ -#endif -/** - * @} - */ - -/** @defgroup ADC_LL_EC_MULTI_DMA_TRANSFER Multimode - DMA transfer - * @{ - */ -#define LL_ADC_MULTI_REG_DMA_EACH_ADC 0x00000000UL /*!< ADC multimode group regular conversions are transferred by DMA: each ADC uses its own DMA channel, with its individual DMA transfer settings */ -#define LL_ADC_MULTI_REG_DMA_LIMIT_1 ( ADC_CCR_DMA_0) /*!< ADC multimode group regular conversions are transferred by DMA, one DMA channel for all ADC instances (DMA of ADC master), in limited mode (one shot mode): DMA transfer requests are stopped when number of DMA data transfers (number of ADC conversions) is reached. This ADC mode is intended to be used with DMA mode non-circular. Setting of DMA mode 1: 2 or 3 (dual or triple mode) half-words one by one, ADC1 then ADC2 then ADC3. */ -#define LL_ADC_MULTI_REG_DMA_LIMIT_2 ( ADC_CCR_DMA_1 ) /*!< ADC multimode group regular conversions are transferred by DMA, one DMA channel for all ADC instances (DMA of ADC master), in limited mode (one shot mode): DMA transfer requests are stopped when number of DMA data transfers (number of ADC conversions) is reached. This ADC mode is intended to be used with DMA mode non-circular. Setting of DMA mode 2: 2 or 3 (dual or triple mode) half-words one by one, ADC2&1 then ADC1&3 then ADC3&2. */ -#define LL_ADC_MULTI_REG_DMA_LIMIT_3 ( ADC_CCR_DMA_1 | ADC_CCR_DMA_0) /*!< ADC multimode group regular conversions are transferred by DMA, one DMA channel for all ADC instances (DMA of ADC master), in limited mode (one shot mode): DMA transfer requests are stopped when number of DMA data transfers (number of ADC conversions) is reached. This ADC mode is intended to be used with DMA mode non-circular. Setting of DMA mode 3: 2 or 3 (dual or triple mode) bytes one by one, ADC2&1 then ADC1&3 then ADC3&2. */ -#define LL_ADC_MULTI_REG_DMA_UNLMT_1 (ADC_CCR_DDS | ADC_CCR_DMA_0) /*!< ADC multimode group regular conversions are transferred by DMA, one DMA channel for all ADC instances (DMA of ADC master), in unlimited mode: DMA transfer requests are unlimited, whatever number of DMA data transferred (number of ADC conversions) is reached. This ADC mode is intended to be used with DMA mode non-circular. Setting of DMA mode 1: 2 or 3 (dual or triple mode) half-words one by one, ADC1 then ADC2 then ADC3. */ -#define LL_ADC_MULTI_REG_DMA_UNLMT_2 (ADC_CCR_DDS | ADC_CCR_DMA_1 ) /*!< ADC multimode group regular conversions are transferred by DMA, one DMA channel for all ADC instances (DMA of ADC master), in unlimited mode: DMA transfer requests are unlimited, whatever number of DMA data transferred (number of ADC conversions) is reached. This ADC mode is intended to be used with DMA mode non-circular. Setting of DMA mode 2: 2 or 3 (dual or triple mode) half-words by pairs, ADC2&1 then ADC1&3 then ADC3&2. */ -#define LL_ADC_MULTI_REG_DMA_UNLMT_3 (ADC_CCR_DDS | ADC_CCR_DMA_1 | ADC_CCR_DMA_0) /*!< ADC multimode group regular conversions are transferred by DMA, one DMA channel for all ADC instances (DMA of ADC master), in unlimited mode: DMA transfer requests are unlimited, whatever number of DMA data transferred (number of ADC conversions) is reached. This ADC mode is intended to be used with DMA mode non-circular. Setting of DMA mode 3: 2 or 3 (dual or triple mode) bytes one by one, ADC2&1 then ADC1&3 then ADC3&2. */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_MULTI_TWOSMP_DELAY Multimode - Delay between two sampling phases - * @{ - */ -#define LL_ADC_MULTI_TWOSMP_DELAY_5CYCLES 0x00000000UL /*!< ADC multimode delay between two sampling phases: 5 ADC clock cycles*/ -#define LL_ADC_MULTI_TWOSMP_DELAY_6CYCLES ( ADC_CCR_DELAY_0) /*!< ADC multimode delay between two sampling phases: 6 ADC clock cycles */ -#define LL_ADC_MULTI_TWOSMP_DELAY_7CYCLES ( ADC_CCR_DELAY_1 ) /*!< ADC multimode delay between two sampling phases: 7 ADC clock cycles */ -#define LL_ADC_MULTI_TWOSMP_DELAY_8CYCLES ( ADC_CCR_DELAY_1 | ADC_CCR_DELAY_0) /*!< ADC multimode delay between two sampling phases: 8 ADC clock cycles */ -#define LL_ADC_MULTI_TWOSMP_DELAY_9CYCLES ( ADC_CCR_DELAY_2 ) /*!< ADC multimode delay between two sampling phases: 9 ADC clock cycles */ -#define LL_ADC_MULTI_TWOSMP_DELAY_10CYCLES ( ADC_CCR_DELAY_2 | ADC_CCR_DELAY_0) /*!< ADC multimode delay between two sampling phases: 10 ADC clock cycles */ -#define LL_ADC_MULTI_TWOSMP_DELAY_11CYCLES ( ADC_CCR_DELAY_2 | ADC_CCR_DELAY_1 ) /*!< ADC multimode delay between two sampling phases: 11 ADC clock cycles */ -#define LL_ADC_MULTI_TWOSMP_DELAY_12CYCLES ( ADC_CCR_DELAY_2 | ADC_CCR_DELAY_1 | ADC_CCR_DELAY_0) /*!< ADC multimode delay between two sampling phases: 12 ADC clock cycles */ -#define LL_ADC_MULTI_TWOSMP_DELAY_13CYCLES (ADC_CCR_DELAY_3 ) /*!< ADC multimode delay between two sampling phases: 13 ADC clock cycles */ -#define LL_ADC_MULTI_TWOSMP_DELAY_14CYCLES (ADC_CCR_DELAY_3 | ADC_CCR_DELAY_0) /*!< ADC multimode delay between two sampling phases: 14 ADC clock cycles */ -#define LL_ADC_MULTI_TWOSMP_DELAY_15CYCLES (ADC_CCR_DELAY_3 | ADC_CCR_DELAY_1 ) /*!< ADC multimode delay between two sampling phases: 15 ADC clock cycles */ -#define LL_ADC_MULTI_TWOSMP_DELAY_16CYCLES (ADC_CCR_DELAY_3 | ADC_CCR_DELAY_1 | ADC_CCR_DELAY_0) /*!< ADC multimode delay between two sampling phases: 16 ADC clock cycles */ -#define LL_ADC_MULTI_TWOSMP_DELAY_17CYCLES (ADC_CCR_DELAY_3 | ADC_CCR_DELAY_2 ) /*!< ADC multimode delay between two sampling phases: 17 ADC clock cycles */ -#define LL_ADC_MULTI_TWOSMP_DELAY_18CYCLES (ADC_CCR_DELAY_3 | ADC_CCR_DELAY_2 | ADC_CCR_DELAY_0) /*!< ADC multimode delay between two sampling phases: 18 ADC clock cycles */ -#define LL_ADC_MULTI_TWOSMP_DELAY_19CYCLES (ADC_CCR_DELAY_3 | ADC_CCR_DELAY_2 | ADC_CCR_DELAY_1 ) /*!< ADC multimode delay between two sampling phases: 19 ADC clock cycles */ -#define LL_ADC_MULTI_TWOSMP_DELAY_20CYCLES (ADC_CCR_DELAY_3 | ADC_CCR_DELAY_2 | ADC_CCR_DELAY_1 | ADC_CCR_DELAY_0) /*!< ADC multimode delay between two sampling phases: 20 ADC clock cycles */ -/** - * @} - */ - -/** @defgroup ADC_LL_EC_MULTI_MASTER_SLAVE Multimode - ADC master or slave - * @{ - */ -#define LL_ADC_MULTI_MASTER ( ADC_CDR_RDATA_MST) /*!< In multimode, selection among several ADC instances: ADC master */ -#define LL_ADC_MULTI_SLAVE (ADC_CDR_RDATA_SLV ) /*!< In multimode, selection among several ADC instances: ADC slave */ -#define LL_ADC_MULTI_MASTER_SLAVE (ADC_CDR_RDATA_SLV | ADC_CDR_RDATA_MST) /*!< In multimode, selection among several ADC instances: both ADC master and ADC slave */ -/** - * @} - */ - -#endif /* ADC_MULTIMODE_SUPPORT */ - - -/** @defgroup ADC_LL_EC_HW_DELAYS Definitions of ADC hardware constraints delays - * @note Only ADC IP HW delays are defined in ADC LL driver driver, - * not timeout values. - * For details on delays values, refer to descriptions in source code - * above each literal definition. - * @{ - */ - -/* Note: Only ADC IP HW delays are defined in ADC LL driver driver, */ -/* not timeout values. */ -/* Timeout values for ADC operations are dependent to device clock */ -/* configuration (system clock versus ADC clock), */ -/* and therefore must be defined in user application. */ -/* Indications for estimation of ADC timeout delays, for this */ -/* STM32 series: */ -/* - ADC enable time: maximum delay is 2us */ -/* (refer to device datasheet, parameter "tSTAB") */ -/* - ADC conversion time: duration depending on ADC clock and ADC */ -/* configuration. */ -/* (refer to device reference manual, section "Timing") */ - -/* Delay for internal voltage reference stabilization time. */ -/* Delay set to maximum value (refer to device datasheet, */ -/* parameter "tSTART"). */ -/* Unit: us */ -#define LL_ADC_DELAY_VREFINT_STAB_US ( 10UL) /*!< Delay for internal voltage reference stabilization time */ - -/* Delay for temperature sensor stabilization time. */ -/* Literal set to maximum value (refer to device datasheet, */ -/* parameter "tSTART"). */ -/* Unit: us */ -#define LL_ADC_DELAY_TEMPSENSOR_STAB_US ( 10UL) /*!< Delay for internal voltage reference stabilization time */ - -/** - * @} - */ - -/** - * @} - */ - - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup ADC_LL_Exported_Macros ADC Exported Macros - * @{ - */ - -/** @defgroup ADC_LL_EM_WRITE_READ Common write and read registers Macros - * @{ - */ - -/** - * @brief Write a value in ADC register - * @param __INSTANCE__ ADC Instance - * @param __REG__ Register to be written - * @param __VALUE__ Value to be written in the register - * @retval None - */ -#define LL_ADC_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__)) - -/** - * @brief Read a value in ADC register - * @param __INSTANCE__ ADC Instance - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_ADC_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__) -/** - * @} - */ - -/** @defgroup ADC_LL_EM_HELPER_MACRO ADC helper macro - * @{ - */ - -/** - * @brief Helper macro to get ADC channel number in decimal format - * from literals LL_ADC_CHANNEL_x. - * @note Example: - * __LL_ADC_CHANNEL_TO_DECIMAL_NB(LL_ADC_CHANNEL_4) - * will return decimal number "4". - * @note The input can be a value from functions where a channel - * number is returned, either defined with number - * or with bitfield (only one bit must be set). - * @param __CHANNEL__ This parameter can be one of the following values: - * @arg @ref LL_ADC_CHANNEL_0 - * @arg @ref LL_ADC_CHANNEL_1 - * @arg @ref LL_ADC_CHANNEL_2 - * @arg @ref LL_ADC_CHANNEL_3 - * @arg @ref LL_ADC_CHANNEL_4 - * @arg @ref LL_ADC_CHANNEL_5 - * @arg @ref LL_ADC_CHANNEL_6 - * @arg @ref LL_ADC_CHANNEL_7 - * @arg @ref LL_ADC_CHANNEL_8 - * @arg @ref LL_ADC_CHANNEL_9 - * @arg @ref LL_ADC_CHANNEL_10 - * @arg @ref LL_ADC_CHANNEL_11 - * @arg @ref LL_ADC_CHANNEL_12 - * @arg @ref LL_ADC_CHANNEL_13 - * @arg @ref LL_ADC_CHANNEL_14 - * @arg @ref LL_ADC_CHANNEL_15 - * @arg @ref LL_ADC_CHANNEL_16 - * @arg @ref LL_ADC_CHANNEL_17 - * @arg @ref LL_ADC_CHANNEL_18 - * @arg @ref LL_ADC_CHANNEL_VREFINT (1) - * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)(2) - * @arg @ref LL_ADC_CHANNEL_VBAT (1) - * - * (1) On STM32F4, parameter available only on ADC instance: ADC1.\n - * (2) On devices STM32F42x and STM32F43x, limitation: this internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled. - * @retval Value between Min_Data=0 and Max_Data=18 - */ -#define __LL_ADC_CHANNEL_TO_DECIMAL_NB(__CHANNEL__) \ - (((__CHANNEL__) & ADC_CHANNEL_ID_NUMBER_MASK) >> ADC_CHANNEL_ID_NUMBER_BITOFFSET_POS) - -/** - * @brief Helper macro to get ADC channel in literal format LL_ADC_CHANNEL_x - * from number in decimal format. - * @note Example: - * __LL_ADC_DECIMAL_NB_TO_CHANNEL(4) - * will return a data equivalent to "LL_ADC_CHANNEL_4". - * @param __DECIMAL_NB__ Value between Min_Data=0 and Max_Data=18 - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_CHANNEL_0 - * @arg @ref LL_ADC_CHANNEL_1 - * @arg @ref LL_ADC_CHANNEL_2 - * @arg @ref LL_ADC_CHANNEL_3 - * @arg @ref LL_ADC_CHANNEL_4 - * @arg @ref LL_ADC_CHANNEL_5 - * @arg @ref LL_ADC_CHANNEL_6 - * @arg @ref LL_ADC_CHANNEL_7 - * @arg @ref LL_ADC_CHANNEL_8 - * @arg @ref LL_ADC_CHANNEL_9 - * @arg @ref LL_ADC_CHANNEL_10 - * @arg @ref LL_ADC_CHANNEL_11 - * @arg @ref LL_ADC_CHANNEL_12 - * @arg @ref LL_ADC_CHANNEL_13 - * @arg @ref LL_ADC_CHANNEL_14 - * @arg @ref LL_ADC_CHANNEL_15 - * @arg @ref LL_ADC_CHANNEL_16 - * @arg @ref LL_ADC_CHANNEL_17 - * @arg @ref LL_ADC_CHANNEL_18 - * @arg @ref LL_ADC_CHANNEL_VREFINT (1) - * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)(2) - * @arg @ref LL_ADC_CHANNEL_VBAT (1) - * - * (1) On STM32F4, parameter available only on ADC instance: ADC1.\n - * (2) On devices STM32F42x and STM32F43x, limitation: this internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled.\n - * (1) For ADC channel read back from ADC register, - * comparison with internal channel parameter to be done - * using helper macro @ref __LL_ADC_CHANNEL_INTERNAL_TO_EXTERNAL(). - */ -#define __LL_ADC_DECIMAL_NB_TO_CHANNEL(__DECIMAL_NB__) \ - (((__DECIMAL_NB__) <= 9UL) \ - ? ( \ - ((__DECIMAL_NB__) << ADC_CHANNEL_ID_NUMBER_BITOFFSET_POS) | \ - (ADC_SMPR2_REGOFFSET | (((uint32_t) (3UL * (__DECIMAL_NB__))) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) \ - ) \ - : \ - ( \ - ((__DECIMAL_NB__) << ADC_CHANNEL_ID_NUMBER_BITOFFSET_POS) | \ - (ADC_SMPR1_REGOFFSET | (((uint32_t) (3UL * ((__DECIMAL_NB__) - 10UL))) << ADC_CHANNEL_SMPx_BITOFFSET_POS)) \ - ) \ - ) - -/** - * @brief Helper macro to determine whether the selected channel - * corresponds to literal definitions of driver. - * @note The different literal definitions of ADC channels are: - * - ADC internal channel: - * LL_ADC_CHANNEL_VREFINT, LL_ADC_CHANNEL_TEMPSENSOR, ... - * - ADC external channel (channel connected to a GPIO pin): - * LL_ADC_CHANNEL_1, LL_ADC_CHANNEL_2, ... - * @note The channel parameter must be a value defined from literal - * definition of a ADC internal channel (LL_ADC_CHANNEL_VREFINT, - * LL_ADC_CHANNEL_TEMPSENSOR, ...), - * ADC external channel (LL_ADC_CHANNEL_1, LL_ADC_CHANNEL_2, ...), - * must not be a value from functions where a channel number is - * returned from ADC registers, - * because internal and external channels share the same channel - * number in ADC registers. The differentiation is made only with - * parameters definitions of driver. - * @param __CHANNEL__ This parameter can be one of the following values: - * @arg @ref LL_ADC_CHANNEL_0 - * @arg @ref LL_ADC_CHANNEL_1 - * @arg @ref LL_ADC_CHANNEL_2 - * @arg @ref LL_ADC_CHANNEL_3 - * @arg @ref LL_ADC_CHANNEL_4 - * @arg @ref LL_ADC_CHANNEL_5 - * @arg @ref LL_ADC_CHANNEL_6 - * @arg @ref LL_ADC_CHANNEL_7 - * @arg @ref LL_ADC_CHANNEL_8 - * @arg @ref LL_ADC_CHANNEL_9 - * @arg @ref LL_ADC_CHANNEL_10 - * @arg @ref LL_ADC_CHANNEL_11 - * @arg @ref LL_ADC_CHANNEL_12 - * @arg @ref LL_ADC_CHANNEL_13 - * @arg @ref LL_ADC_CHANNEL_14 - * @arg @ref LL_ADC_CHANNEL_15 - * @arg @ref LL_ADC_CHANNEL_16 - * @arg @ref LL_ADC_CHANNEL_17 - * @arg @ref LL_ADC_CHANNEL_18 - * @arg @ref LL_ADC_CHANNEL_VREFINT (1) - * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)(2) - * @arg @ref LL_ADC_CHANNEL_VBAT (1) - * - * (1) On STM32F4, parameter available only on ADC instance: ADC1.\n - * (2) On devices STM32F42x and STM32F43x, limitation: this internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled. - * @retval Value "0" if the channel corresponds to a parameter definition of a ADC external channel (channel connected to a GPIO pin). - * Value "1" if the channel corresponds to a parameter definition of a ADC internal channel. - */ -#define __LL_ADC_IS_CHANNEL_INTERNAL(__CHANNEL__) \ - (((__CHANNEL__) & ADC_CHANNEL_ID_INTERNAL_CH_MASK) != 0UL) - -/** - * @brief Helper macro to convert a channel defined from parameter - * definition of a ADC internal channel (LL_ADC_CHANNEL_VREFINT, - * LL_ADC_CHANNEL_TEMPSENSOR, ...), - * to its equivalent parameter definition of a ADC external channel - * (LL_ADC_CHANNEL_1, LL_ADC_CHANNEL_2, ...). - * @note The channel parameter can be, additionally to a value - * defined from parameter definition of a ADC internal channel - * (LL_ADC_CHANNEL_VREFINT, LL_ADC_CHANNEL_TEMPSENSOR, ...), - * a value defined from parameter definition of - * ADC external channel (LL_ADC_CHANNEL_1, LL_ADC_CHANNEL_2, ...) - * or a value from functions where a channel number is returned - * from ADC registers. - * @param __CHANNEL__ This parameter can be one of the following values: - * @arg @ref LL_ADC_CHANNEL_0 - * @arg @ref LL_ADC_CHANNEL_1 - * @arg @ref LL_ADC_CHANNEL_2 - * @arg @ref LL_ADC_CHANNEL_3 - * @arg @ref LL_ADC_CHANNEL_4 - * @arg @ref LL_ADC_CHANNEL_5 - * @arg @ref LL_ADC_CHANNEL_6 - * @arg @ref LL_ADC_CHANNEL_7 - * @arg @ref LL_ADC_CHANNEL_8 - * @arg @ref LL_ADC_CHANNEL_9 - * @arg @ref LL_ADC_CHANNEL_10 - * @arg @ref LL_ADC_CHANNEL_11 - * @arg @ref LL_ADC_CHANNEL_12 - * @arg @ref LL_ADC_CHANNEL_13 - * @arg @ref LL_ADC_CHANNEL_14 - * @arg @ref LL_ADC_CHANNEL_15 - * @arg @ref LL_ADC_CHANNEL_16 - * @arg @ref LL_ADC_CHANNEL_17 - * @arg @ref LL_ADC_CHANNEL_18 - * @arg @ref LL_ADC_CHANNEL_VREFINT (1) - * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)(2) - * @arg @ref LL_ADC_CHANNEL_VBAT (1) - * - * (1) On STM32F4, parameter available only on ADC instance: ADC1.\n - * (2) On devices STM32F42x and STM32F43x, limitation: this internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled. - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_CHANNEL_0 - * @arg @ref LL_ADC_CHANNEL_1 - * @arg @ref LL_ADC_CHANNEL_2 - * @arg @ref LL_ADC_CHANNEL_3 - * @arg @ref LL_ADC_CHANNEL_4 - * @arg @ref LL_ADC_CHANNEL_5 - * @arg @ref LL_ADC_CHANNEL_6 - * @arg @ref LL_ADC_CHANNEL_7 - * @arg @ref LL_ADC_CHANNEL_8 - * @arg @ref LL_ADC_CHANNEL_9 - * @arg @ref LL_ADC_CHANNEL_10 - * @arg @ref LL_ADC_CHANNEL_11 - * @arg @ref LL_ADC_CHANNEL_12 - * @arg @ref LL_ADC_CHANNEL_13 - * @arg @ref LL_ADC_CHANNEL_14 - * @arg @ref LL_ADC_CHANNEL_15 - * @arg @ref LL_ADC_CHANNEL_16 - * @arg @ref LL_ADC_CHANNEL_17 - * @arg @ref LL_ADC_CHANNEL_18 - */ -#define __LL_ADC_CHANNEL_INTERNAL_TO_EXTERNAL(__CHANNEL__) \ - ((__CHANNEL__) & ~ADC_CHANNEL_ID_INTERNAL_CH_MASK) - -/** - * @brief Helper macro to determine whether the internal channel - * selected is available on the ADC instance selected. - * @note The channel parameter must be a value defined from parameter - * definition of a ADC internal channel (LL_ADC_CHANNEL_VREFINT, - * LL_ADC_CHANNEL_TEMPSENSOR, ...), - * must not be a value defined from parameter definition of - * ADC external channel (LL_ADC_CHANNEL_1, LL_ADC_CHANNEL_2, ...) - * or a value from functions where a channel number is - * returned from ADC registers, - * because internal and external channels share the same channel - * number in ADC registers. The differentiation is made only with - * parameters definitions of driver. - * @param __ADC_INSTANCE__ ADC instance - * @param __CHANNEL__ This parameter can be one of the following values: - * @arg @ref LL_ADC_CHANNEL_VREFINT (1) - * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)(2) - * @arg @ref LL_ADC_CHANNEL_VBAT (1) - * - * (1) On STM32F4, parameter available only on ADC instance: ADC1. - * (2) On devices STM32F42x and STM32F43x, limitation: this internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled. - * @retval Value "0" if the internal channel selected is not available on the ADC instance selected. - * Value "1" if the internal channel selected is available on the ADC instance selected. - */ -#define __LL_ADC_IS_CHANNEL_INTERNAL_AVAILABLE(__ADC_INSTANCE__, __CHANNEL__) \ - ( \ - ((__CHANNEL__) == LL_ADC_CHANNEL_VREFINT) || \ - ((__CHANNEL__) == LL_ADC_CHANNEL_TEMPSENSOR) || \ - ((__CHANNEL__) == LL_ADC_CHANNEL_VBAT) \ - ) -/** - * @brief Helper macro to define ADC analog watchdog parameter: - * define a single channel to monitor with analog watchdog - * from sequencer channel and groups definition. - * @note To be used with function @ref LL_ADC_SetAnalogWDMonitChannels(). - * Example: - * LL_ADC_SetAnalogWDMonitChannels( - * ADC1, LL_ADC_AWD1, - * __LL_ADC_ANALOGWD_CHANNEL_GROUP(LL_ADC_CHANNEL4, LL_ADC_GROUP_REGULAR)) - * @param __CHANNEL__ This parameter can be one of the following values: - * @arg @ref LL_ADC_CHANNEL_0 - * @arg @ref LL_ADC_CHANNEL_1 - * @arg @ref LL_ADC_CHANNEL_2 - * @arg @ref LL_ADC_CHANNEL_3 - * @arg @ref LL_ADC_CHANNEL_4 - * @arg @ref LL_ADC_CHANNEL_5 - * @arg @ref LL_ADC_CHANNEL_6 - * @arg @ref LL_ADC_CHANNEL_7 - * @arg @ref LL_ADC_CHANNEL_8 - * @arg @ref LL_ADC_CHANNEL_9 - * @arg @ref LL_ADC_CHANNEL_10 - * @arg @ref LL_ADC_CHANNEL_11 - * @arg @ref LL_ADC_CHANNEL_12 - * @arg @ref LL_ADC_CHANNEL_13 - * @arg @ref LL_ADC_CHANNEL_14 - * @arg @ref LL_ADC_CHANNEL_15 - * @arg @ref LL_ADC_CHANNEL_16 - * @arg @ref LL_ADC_CHANNEL_17 - * @arg @ref LL_ADC_CHANNEL_18 - * @arg @ref LL_ADC_CHANNEL_VREFINT (1) - * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)(2) - * @arg @ref LL_ADC_CHANNEL_VBAT (1) - * - * (1) On STM32F4, parameter available only on ADC instance: ADC1.\n - * (2) On devices STM32F42x and STM32F43x, limitation: this internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled.\n - * (1) For ADC channel read back from ADC register, - * comparison with internal channel parameter to be done - * using helper macro @ref __LL_ADC_CHANNEL_INTERNAL_TO_EXTERNAL(). - * @param __GROUP__ This parameter can be one of the following values: - * @arg @ref LL_ADC_GROUP_REGULAR - * @arg @ref LL_ADC_GROUP_INJECTED - * @arg @ref LL_ADC_GROUP_REGULAR_INJECTED - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_AWD_DISABLE - * @arg @ref LL_ADC_AWD_ALL_CHANNELS_REG - * @arg @ref LL_ADC_AWD_ALL_CHANNELS_INJ - * @arg @ref LL_ADC_AWD_ALL_CHANNELS_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_0_REG - * @arg @ref LL_ADC_AWD_CHANNEL_0_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_0_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_1_REG - * @arg @ref LL_ADC_AWD_CHANNEL_1_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_1_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_2_REG - * @arg @ref LL_ADC_AWD_CHANNEL_2_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_2_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_3_REG - * @arg @ref LL_ADC_AWD_CHANNEL_3_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_3_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_4_REG - * @arg @ref LL_ADC_AWD_CHANNEL_4_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_4_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_5_REG - * @arg @ref LL_ADC_AWD_CHANNEL_5_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_5_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_6_REG - * @arg @ref LL_ADC_AWD_CHANNEL_6_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_6_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_7_REG - * @arg @ref LL_ADC_AWD_CHANNEL_7_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_7_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_8_REG - * @arg @ref LL_ADC_AWD_CHANNEL_8_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_8_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_9_REG - * @arg @ref LL_ADC_AWD_CHANNEL_9_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_9_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_10_REG - * @arg @ref LL_ADC_AWD_CHANNEL_10_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_10_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_11_REG - * @arg @ref LL_ADC_AWD_CHANNEL_11_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_11_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_12_REG - * @arg @ref LL_ADC_AWD_CHANNEL_12_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_12_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_13_REG - * @arg @ref LL_ADC_AWD_CHANNEL_13_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_13_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_14_REG - * @arg @ref LL_ADC_AWD_CHANNEL_14_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_14_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_15_REG - * @arg @ref LL_ADC_AWD_CHANNEL_15_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_15_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_16_REG - * @arg @ref LL_ADC_AWD_CHANNEL_16_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_16_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_17_REG - * @arg @ref LL_ADC_AWD_CHANNEL_17_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_17_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_18_REG - * @arg @ref LL_ADC_AWD_CHANNEL_18_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_18_REG_INJ - * @arg @ref LL_ADC_AWD_CH_VREFINT_REG (1) - * @arg @ref LL_ADC_AWD_CH_VREFINT_INJ (1) - * @arg @ref LL_ADC_AWD_CH_VREFINT_REG_INJ (1) - * @arg @ref LL_ADC_AWD_CH_TEMPSENSOR_REG (1)(2) - * @arg @ref LL_ADC_AWD_CH_TEMPSENSOR_INJ (1)(2) - * @arg @ref LL_ADC_AWD_CH_TEMPSENSOR_REG_INJ (1)(2) - * @arg @ref LL_ADC_AWD_CH_VBAT_REG (1) - * @arg @ref LL_ADC_AWD_CH_VBAT_INJ (1) - * @arg @ref LL_ADC_AWD_CH_VBAT_REG_INJ (1) - * - * (1) On STM32F4, parameter available only on ADC instance: ADC1.\n - * (2) On devices STM32F42x and STM32F43x, limitation: this internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled. - */ -#define __LL_ADC_ANALOGWD_CHANNEL_GROUP(__CHANNEL__, __GROUP__) \ - (((__GROUP__) == LL_ADC_GROUP_REGULAR) \ - ? (((__CHANNEL__) & ADC_CHANNEL_ID_MASK) | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) \ - : \ - ((__GROUP__) == LL_ADC_GROUP_INJECTED) \ - ? (((__CHANNEL__) & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL) \ - : \ - (((__CHANNEL__) & ADC_CHANNEL_ID_MASK) | ADC_CR1_JAWDEN | ADC_CR1_AWDEN | ADC_CR1_AWDSGL) \ - ) - -/** - * @brief Helper macro to set the value of ADC analog watchdog threshold high - * or low in function of ADC resolution, when ADC resolution is - * different of 12 bits. - * @note To be used with function @ref LL_ADC_SetAnalogWDThresholds(). - * Example, with a ADC resolution of 8 bits, to set the value of - * analog watchdog threshold high (on 8 bits): - * LL_ADC_SetAnalogWDThresholds - * (< ADCx param >, - * __LL_ADC_ANALOGWD_SET_THRESHOLD_RESOLUTION(LL_ADC_RESOLUTION_8B, ) - * ); - * @param __ADC_RESOLUTION__ This parameter can be one of the following values: - * @arg @ref LL_ADC_RESOLUTION_12B - * @arg @ref LL_ADC_RESOLUTION_10B - * @arg @ref LL_ADC_RESOLUTION_8B - * @arg @ref LL_ADC_RESOLUTION_6B - * @param __AWD_THRESHOLD__ Value between Min_Data=0x000 and Max_Data=0xFFF - * @retval Value between Min_Data=0x000 and Max_Data=0xFFF - */ -#define __LL_ADC_ANALOGWD_SET_THRESHOLD_RESOLUTION(__ADC_RESOLUTION__, __AWD_THRESHOLD__) \ - ((__AWD_THRESHOLD__) << ((__ADC_RESOLUTION__) >> (ADC_CR1_RES_BITOFFSET_POS - 1UL ))) - -/** - * @brief Helper macro to get the value of ADC analog watchdog threshold high - * or low in function of ADC resolution, when ADC resolution is - * different of 12 bits. - * @note To be used with function @ref LL_ADC_GetAnalogWDThresholds(). - * Example, with a ADC resolution of 8 bits, to get the value of - * analog watchdog threshold high (on 8 bits): - * < threshold_value_6_bits > = __LL_ADC_ANALOGWD_GET_THRESHOLD_RESOLUTION - * (LL_ADC_RESOLUTION_8B, - * LL_ADC_GetAnalogWDThresholds(, LL_ADC_AWD_THRESHOLD_HIGH) - * ); - * @param __ADC_RESOLUTION__ This parameter can be one of the following values: - * @arg @ref LL_ADC_RESOLUTION_12B - * @arg @ref LL_ADC_RESOLUTION_10B - * @arg @ref LL_ADC_RESOLUTION_8B - * @arg @ref LL_ADC_RESOLUTION_6B - * @param __AWD_THRESHOLD_12_BITS__ Value between Min_Data=0x000 and Max_Data=0xFFF - * @retval Value between Min_Data=0x000 and Max_Data=0xFFF - */ -#define __LL_ADC_ANALOGWD_GET_THRESHOLD_RESOLUTION(__ADC_RESOLUTION__, __AWD_THRESHOLD_12_BITS__) \ - ((__AWD_THRESHOLD_12_BITS__) >> ((__ADC_RESOLUTION__) >> (ADC_CR1_RES_BITOFFSET_POS - 1UL ))) - -#if defined(ADC_MULTIMODE_SUPPORT) -/** - * @brief Helper macro to get the ADC multimode conversion data of ADC master - * or ADC slave from raw value with both ADC conversion data concatenated. - * @note This macro is intended to be used when multimode transfer by DMA - * is enabled: refer to function @ref LL_ADC_SetMultiDMATransfer(). - * In this case the transferred data need to processed with this macro - * to separate the conversion data of ADC master and ADC slave. - * @param __ADC_MULTI_MASTER_SLAVE__ This parameter can be one of the following values: - * @arg @ref LL_ADC_MULTI_MASTER - * @arg @ref LL_ADC_MULTI_SLAVE - * @param __ADC_MULTI_CONV_DATA__ Value between Min_Data=0x000 and Max_Data=0xFFF - * @retval Value between Min_Data=0x000 and Max_Data=0xFFF - */ -#define __LL_ADC_MULTI_CONV_DATA_MASTER_SLAVE(__ADC_MULTI_MASTER_SLAVE__, __ADC_MULTI_CONV_DATA__) \ - (((__ADC_MULTI_CONV_DATA__) >> POSITION_VAL((__ADC_MULTI_MASTER_SLAVE__))) & ADC_CDR_RDATA_MST) -#endif - -/** - * @brief Helper macro to select the ADC common instance - * to which is belonging the selected ADC instance. - * @note ADC common register instance can be used for: - * - Set parameters common to several ADC instances - * - Multimode (for devices with several ADC instances) - * Refer to functions having argument "ADCxy_COMMON" as parameter. - * @param __ADCx__ ADC instance - * @retval ADC common register instance - */ -#if defined(ADC1) && defined(ADC2) && defined(ADC3) -#define __LL_ADC_COMMON_INSTANCE(__ADCx__) \ - (ADC123_COMMON) -#elif defined(ADC1) && defined(ADC2) -#define __LL_ADC_COMMON_INSTANCE(__ADCx__) \ - (ADC12_COMMON) -#else -#define __LL_ADC_COMMON_INSTANCE(__ADCx__) \ - (ADC1_COMMON) -#endif - -/** - * @brief Helper macro to check if all ADC instances sharing the same - * ADC common instance are disabled. - * @note This check is required by functions with setting conditioned to - * ADC state: - * All ADC instances of the ADC common group must be disabled. - * Refer to functions having argument "ADCxy_COMMON" as parameter. - * @note On devices with only 1 ADC common instance, parameter of this macro - * is useless and can be ignored (parameter kept for compatibility - * with devices featuring several ADC common instances). - * @param __ADCXY_COMMON__ ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @retval Value "0" if all ADC instances sharing the same ADC common instance - * are disabled. - * Value "1" if at least one ADC instance sharing the same ADC common instance - * is enabled. - */ -#if defined(ADC1) && defined(ADC2) && defined(ADC3) -#define __LL_ADC_IS_ENABLED_ALL_COMMON_INSTANCE(__ADCXY_COMMON__) \ - (LL_ADC_IsEnabled(ADC1) | \ - LL_ADC_IsEnabled(ADC2) | \ - LL_ADC_IsEnabled(ADC3) ) -#elif defined(ADC1) && defined(ADC2) -#define __LL_ADC_IS_ENABLED_ALL_COMMON_INSTANCE(__ADCXY_COMMON__) \ - (LL_ADC_IsEnabled(ADC1) | \ - LL_ADC_IsEnabled(ADC2) ) -#else -#define __LL_ADC_IS_ENABLED_ALL_COMMON_INSTANCE(__ADCXY_COMMON__) \ - (LL_ADC_IsEnabled(ADC1)) -#endif - -/** - * @brief Helper macro to define the ADC conversion data full-scale digital - * value corresponding to the selected ADC resolution. - * @note ADC conversion data full-scale corresponds to voltage range - * determined by analog voltage references Vref+ and Vref- - * (refer to reference manual). - * @param __ADC_RESOLUTION__ This parameter can be one of the following values: - * @arg @ref LL_ADC_RESOLUTION_12B - * @arg @ref LL_ADC_RESOLUTION_10B - * @arg @ref LL_ADC_RESOLUTION_8B - * @arg @ref LL_ADC_RESOLUTION_6B - * @retval ADC conversion data equivalent voltage value (unit: mVolt) - */ -#define __LL_ADC_DIGITAL_SCALE(__ADC_RESOLUTION__) \ - (0xFFFU >> ((__ADC_RESOLUTION__) >> (ADC_CR1_RES_BITOFFSET_POS - 1UL))) - -/** - * @brief Helper macro to convert the ADC conversion data from - * a resolution to another resolution. - * @param __DATA__ ADC conversion data to be converted - * @param __ADC_RESOLUTION_CURRENT__ Resolution of to the data to be converted - * This parameter can be one of the following values: - * @arg @ref LL_ADC_RESOLUTION_12B - * @arg @ref LL_ADC_RESOLUTION_10B - * @arg @ref LL_ADC_RESOLUTION_8B - * @arg @ref LL_ADC_RESOLUTION_6B - * @param __ADC_RESOLUTION_TARGET__ Resolution of the data after conversion - * This parameter can be one of the following values: - * @arg @ref LL_ADC_RESOLUTION_12B - * @arg @ref LL_ADC_RESOLUTION_10B - * @arg @ref LL_ADC_RESOLUTION_8B - * @arg @ref LL_ADC_RESOLUTION_6B - * @retval ADC conversion data to the requested resolution - */ -#define __LL_ADC_CONVERT_DATA_RESOLUTION(__DATA__, __ADC_RESOLUTION_CURRENT__, __ADC_RESOLUTION_TARGET__) \ - (((__DATA__) \ - << ((__ADC_RESOLUTION_CURRENT__) >> (ADC_CR1_RES_BITOFFSET_POS - 1UL))) \ - >> ((__ADC_RESOLUTION_TARGET__) >> (ADC_CR1_RES_BITOFFSET_POS - 1UL)) \ - ) - -/** - * @brief Helper macro to calculate the voltage (unit: mVolt) - * corresponding to a ADC conversion data (unit: digital value). - * @note Analog reference voltage (Vref+) must be either known from - * user board environment or can be calculated using ADC measurement - * and ADC helper macro @ref __LL_ADC_CALC_VREFANALOG_VOLTAGE(). - * @param __VREFANALOG_VOLTAGE__ Analog reference voltage (unit mV) - * @param __ADC_DATA__ ADC conversion data (resolution 12 bits) - * (unit: digital value). - * @param __ADC_RESOLUTION__ This parameter can be one of the following values: - * @arg @ref LL_ADC_RESOLUTION_12B - * @arg @ref LL_ADC_RESOLUTION_10B - * @arg @ref LL_ADC_RESOLUTION_8B - * @arg @ref LL_ADC_RESOLUTION_6B - * @retval ADC conversion data equivalent voltage value (unit: mVolt) - */ -#define __LL_ADC_CALC_DATA_TO_VOLTAGE(__VREFANALOG_VOLTAGE__,\ - __ADC_DATA__,\ - __ADC_RESOLUTION__) \ - ((__ADC_DATA__) * (__VREFANALOG_VOLTAGE__) \ - / __LL_ADC_DIGITAL_SCALE(__ADC_RESOLUTION__) \ - ) - -/** - * @brief Helper macro to calculate analog reference voltage (Vref+) - * (unit: mVolt) from ADC conversion data of internal voltage - * reference VrefInt. - * @note Computation is using VrefInt calibration value - * stored in system memory for each device during production. - * @note This voltage depends on user board environment: voltage level - * connected to pin Vref+. - * On devices with small package, the pin Vref+ is not present - * and internally bonded to pin Vdda. - * @note On this STM32 series, calibration data of internal voltage reference - * VrefInt corresponds to a resolution of 12 bits, - * this is the recommended ADC resolution to convert voltage of - * internal voltage reference VrefInt. - * Otherwise, this macro performs the processing to scale - * ADC conversion data to 12 bits. - * @param __VREFINT_ADC_DATA__ ADC conversion data (resolution 12 bits) - * of internal voltage reference VrefInt (unit: digital value). - * @param __ADC_RESOLUTION__ This parameter can be one of the following values: - * @arg @ref LL_ADC_RESOLUTION_12B - * @arg @ref LL_ADC_RESOLUTION_10B - * @arg @ref LL_ADC_RESOLUTION_8B - * @arg @ref LL_ADC_RESOLUTION_6B - * @retval Analog reference voltage (unit: mV) - */ -#define __LL_ADC_CALC_VREFANALOG_VOLTAGE(__VREFINT_ADC_DATA__,\ - __ADC_RESOLUTION__) \ - (((uint32_t)(*VREFINT_CAL_ADDR) * VREFINT_CAL_VREF) \ - / __LL_ADC_CONVERT_DATA_RESOLUTION((__VREFINT_ADC_DATA__), \ - (__ADC_RESOLUTION__), \ - LL_ADC_RESOLUTION_12B)) - -/* Note: On device STM32F4x9, calibration parameter TS_CAL2 is not available. */ -/* Therefore, helper macro __LL_ADC_CALC_TEMPERATURE() is not available.*/ -/* Use helper macro @ref __LL_ADC_CALC_TEMPERATURE_TYP_PARAMS(). */ -#if !defined(STM32F469) && !defined(STM32F479xx) && !defined(STM32F429xx) && !defined(STM32F439xx) -/** - * @brief Helper macro to calculate the temperature (unit: degree Celsius) - * from ADC conversion data of internal temperature sensor. - * @note Computation is using temperature sensor calibration values - * stored in system memory for each device during production. - * @note Calculation formula: - * Temperature = ((TS_ADC_DATA - TS_CAL1) - * * (TS_CAL2_TEMP - TS_CAL1_TEMP)) - * / (TS_CAL2 - TS_CAL1) + TS_CAL1_TEMP - * with TS_ADC_DATA = temperature sensor raw data measured by ADC - * Avg_Slope = (TS_CAL2 - TS_CAL1) - * / (TS_CAL2_TEMP - TS_CAL1_TEMP) - * TS_CAL1 = equivalent TS_ADC_DATA at temperature - * TEMP_DEGC_CAL1 (calibrated in factory) - * TS_CAL2 = equivalent TS_ADC_DATA at temperature - * TEMP_DEGC_CAL2 (calibrated in factory) - * Caution: Calculation relevancy under reserve that calibration - * parameters are correct (address and data). - * To calculate temperature using temperature sensor - * datasheet typical values (generic values less, therefore - * less accurate than calibrated values), - * use helper macro @ref __LL_ADC_CALC_TEMPERATURE_TYP_PARAMS(). - * @note As calculation input, the analog reference voltage (Vref+) must be - * defined as it impacts the ADC LSB equivalent voltage. - * @note Analog reference voltage (Vref+) must be either known from - * user board environment or can be calculated using ADC measurement - * and ADC helper macro @ref __LL_ADC_CALC_VREFANALOG_VOLTAGE(). - * @note On this STM32 series, calibration data of temperature sensor - * corresponds to a resolution of 12 bits, - * this is the recommended ADC resolution to convert voltage of - * temperature sensor. - * Otherwise, this macro performs the processing to scale - * ADC conversion data to 12 bits. - * @param __VREFANALOG_VOLTAGE__ Analog reference voltage (unit mV) - * @param __TEMPSENSOR_ADC_DATA__ ADC conversion data of internal - * temperature sensor (unit: digital value). - * @param __ADC_RESOLUTION__ ADC resolution at which internal temperature - * sensor voltage has been measured. - * This parameter can be one of the following values: - * @arg @ref LL_ADC_RESOLUTION_12B - * @arg @ref LL_ADC_RESOLUTION_10B - * @arg @ref LL_ADC_RESOLUTION_8B - * @arg @ref LL_ADC_RESOLUTION_6B - * @retval Temperature (unit: degree Celsius) - */ -#define __LL_ADC_CALC_TEMPERATURE(__VREFANALOG_VOLTAGE__,\ - __TEMPSENSOR_ADC_DATA__,\ - __ADC_RESOLUTION__) \ - (((( ((int32_t)((__LL_ADC_CONVERT_DATA_RESOLUTION((__TEMPSENSOR_ADC_DATA__), \ - (__ADC_RESOLUTION__), \ - LL_ADC_RESOLUTION_12B) \ - * (__VREFANALOG_VOLTAGE__)) \ - / TEMPSENSOR_CAL_VREFANALOG) \ - - (int32_t) *TEMPSENSOR_CAL1_ADDR) \ - ) * (int32_t)(TEMPSENSOR_CAL2_TEMP - TEMPSENSOR_CAL1_TEMP) \ - ) / (int32_t)((int32_t)*TEMPSENSOR_CAL2_ADDR - (int32_t)*TEMPSENSOR_CAL1_ADDR) \ - ) + TEMPSENSOR_CAL1_TEMP \ - ) -#endif - -/** - * @brief Helper macro to calculate the temperature (unit: degree Celsius) - * from ADC conversion data of internal temperature sensor. - * @note Computation is using temperature sensor typical values - * (refer to device datasheet). - * @note Calculation formula: - * Temperature = (TS_TYP_CALx_VOLT(uV) - TS_ADC_DATA * Conversion_uV) - * / Avg_Slope + CALx_TEMP - * with TS_ADC_DATA = temperature sensor raw data measured by ADC - * (unit: digital value) - * Avg_Slope = temperature sensor slope - * (unit: uV/Degree Celsius) - * TS_TYP_CALx_VOLT = temperature sensor digital value at - * temperature CALx_TEMP (unit: mV) - * Caution: Calculation relevancy under reserve the temperature sensor - * of the current device has characteristics in line with - * datasheet typical values. - * If temperature sensor calibration values are available on - * on this device (presence of macro __LL_ADC_CALC_TEMPERATURE()), - * temperature calculation will be more accurate using - * helper macro @ref __LL_ADC_CALC_TEMPERATURE(). - * @note As calculation input, the analog reference voltage (Vref+) must be - * defined as it impacts the ADC LSB equivalent voltage. - * @note Analog reference voltage (Vref+) must be either known from - * user board environment or can be calculated using ADC measurement - * and ADC helper macro @ref __LL_ADC_CALC_VREFANALOG_VOLTAGE(). - * @note ADC measurement data must correspond to a resolution of 12bits - * (full scale digital value 4095). If not the case, the data must be - * preliminarily rescaled to an equivalent resolution of 12 bits. - * @param __TEMPSENSOR_TYP_AVGSLOPE__ Device datasheet data Temperature sensor slope typical value (unit uV/DegCelsius). - * On STM32F4, refer to device datasheet parameter "Avg_Slope". - * @param __TEMPSENSOR_TYP_CALX_V__ Device datasheet data Temperature sensor voltage typical value (at temperature and Vref+ defined in parameters below) (unit mV). - * On STM32F4, refer to device datasheet parameter "V25". - * @param __TEMPSENSOR_CALX_TEMP__ Device datasheet data Temperature at which temperature sensor voltage (see parameter above) is corresponding (unit mV) - * @param __VREFANALOG_VOLTAGE__ Analog voltage reference (Vref+) voltage (unit mV) - * @param __TEMPSENSOR_ADC_DATA__ ADC conversion data of internal temperature sensor (unit digital value). - * @param __ADC_RESOLUTION__ ADC resolution at which internal temperature sensor voltage has been measured. - * This parameter can be one of the following values: - * @arg @ref LL_ADC_RESOLUTION_12B - * @arg @ref LL_ADC_RESOLUTION_10B - * @arg @ref LL_ADC_RESOLUTION_8B - * @arg @ref LL_ADC_RESOLUTION_6B - * @retval Temperature (unit: degree Celsius) - */ -#define __LL_ADC_CALC_TEMPERATURE_TYP_PARAMS(__TEMPSENSOR_TYP_AVGSLOPE__,\ - __TEMPSENSOR_TYP_CALX_V__,\ - __TEMPSENSOR_CALX_TEMP__,\ - __VREFANALOG_VOLTAGE__,\ - __TEMPSENSOR_ADC_DATA__,\ - __ADC_RESOLUTION__) \ - ((( ( \ - (int32_t)(((__TEMPSENSOR_TYP_CALX_V__)) \ - * 1000) \ - - \ - (int32_t)((((__TEMPSENSOR_ADC_DATA__) * (__VREFANALOG_VOLTAGE__)) \ - / __LL_ADC_DIGITAL_SCALE(__ADC_RESOLUTION__)) \ - * 1000) \ - ) \ - ) / (__TEMPSENSOR_TYP_AVGSLOPE__) \ - ) + (__TEMPSENSOR_CALX_TEMP__) \ - ) - -/** - * @} - */ - -/** - * @} - */ - - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup ADC_LL_Exported_Functions ADC Exported Functions - * @{ - */ - -/** @defgroup ADC_LL_EF_DMA_Management ADC DMA management - * @{ - */ -/* Note: LL ADC functions to set DMA transfer are located into sections of */ -/* configuration of ADC instance, groups and multimode (if available): */ -/* @ref LL_ADC_REG_SetDMATransfer(), ... */ - -/** - * @brief Function to help to configure DMA transfer from ADC: retrieve the - * ADC register address from ADC instance and a list of ADC registers - * intended to be used (most commonly) with DMA transfer. - * @note These ADC registers are data registers: - * when ADC conversion data is available in ADC data registers, - * ADC generates a DMA transfer request. - * @note This macro is intended to be used with LL DMA driver, refer to - * function "LL_DMA_ConfigAddresses()". - * Example: - * LL_DMA_ConfigAddresses(DMA1, - * LL_DMA_CHANNEL_1, - * LL_ADC_DMA_GetRegAddr(ADC1, LL_ADC_DMA_REG_REGULAR_DATA), - * (uint32_t)&< array or variable >, - * LL_DMA_DIRECTION_PERIPH_TO_MEMORY); - * @note For devices with several ADC: in multimode, some devices - * use a different data register outside of ADC instance scope - * (common data register). This macro manages this register difference, - * only ADC instance has to be set as parameter. - * @rmtoll DR RDATA LL_ADC_DMA_GetRegAddr\n - * CDR RDATA_MST LL_ADC_DMA_GetRegAddr\n - * CDR RDATA_SLV LL_ADC_DMA_GetRegAddr - * @param ADCx ADC instance - * @param Register This parameter can be one of the following values: - * @arg @ref LL_ADC_DMA_REG_REGULAR_DATA - * @arg @ref LL_ADC_DMA_REG_REGULAR_DATA_MULTI (1) - * - * (1) Available on devices with several ADC instances. - * @retval ADC register address - */ -#if defined(ADC_MULTIMODE_SUPPORT) -__STATIC_INLINE uint32_t LL_ADC_DMA_GetRegAddr(ADC_TypeDef *ADCx, uint32_t Register) -{ - uint32_t data_reg_addr = 0UL; - UNUSED(Register); - - if (Register == LL_ADC_DMA_REG_REGULAR_DATA) - { - /* Retrieve address of register DR */ - data_reg_addr = (uint32_t)&(ADCx->DR); - } - else /* (Register == LL_ADC_DMA_REG_REGULAR_DATA_MULTI) */ - { - /* Retrieve address of register CDR */ - data_reg_addr = (uint32_t)&((__LL_ADC_COMMON_INSTANCE(ADCx))->CDR); - } - - return data_reg_addr; -} -#else -__STATIC_INLINE uint32_t LL_ADC_DMA_GetRegAddr(ADC_TypeDef *ADCx, uint32_t Register) -{ - UNUSED(Register); - /* Retrieve address of register DR */ - return (uint32_t)&(ADCx->DR); -} -#endif - -/** - * @} - */ - -/** @defgroup ADC_LL_EF_Configuration_ADC_Common Configuration of ADC hierarchical scope: common to several ADC instances - * @{ - */ - -/** - * @brief Set parameter common to several ADC: Clock source and prescaler. - * @rmtoll CCR ADCPRE LL_ADC_SetCommonClock - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @param CommonClock This parameter can be one of the following values: - * @arg @ref LL_ADC_CLOCK_SYNC_PCLK_DIV2 - * @arg @ref LL_ADC_CLOCK_SYNC_PCLK_DIV4 - * @arg @ref LL_ADC_CLOCK_SYNC_PCLK_DIV6 - * @arg @ref LL_ADC_CLOCK_SYNC_PCLK_DIV8 - * @retval None - */ -__STATIC_INLINE void LL_ADC_SetCommonClock(ADC_Common_TypeDef *ADCxy_COMMON, uint32_t CommonClock) -{ - MODIFY_REG(ADCxy_COMMON->CCR, ADC_CCR_ADCPRE, CommonClock); -} - -/** - * @brief Get parameter common to several ADC: Clock source and prescaler. - * @rmtoll CCR ADCPRE LL_ADC_GetCommonClock - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_CLOCK_SYNC_PCLK_DIV2 - * @arg @ref LL_ADC_CLOCK_SYNC_PCLK_DIV4 - * @arg @ref LL_ADC_CLOCK_SYNC_PCLK_DIV6 - * @arg @ref LL_ADC_CLOCK_SYNC_PCLK_DIV8 - */ -__STATIC_INLINE uint32_t LL_ADC_GetCommonClock(ADC_Common_TypeDef *ADCxy_COMMON) -{ - return (uint32_t)(READ_BIT(ADCxy_COMMON->CCR, ADC_CCR_ADCPRE)); -} - -/** - * @brief Set parameter common to several ADC: measurement path to internal - * channels (VrefInt, temperature sensor, ...). - * @note One or several values can be selected. - * Example: (LL_ADC_PATH_INTERNAL_VREFINT | - * LL_ADC_PATH_INTERNAL_TEMPSENSOR) - * @note Stabilization time of measurement path to internal channel: - * After enabling internal paths, before starting ADC conversion, - * a delay is required for internal voltage reference and - * temperature sensor stabilization time. - * Refer to device datasheet. - * Refer to literal @ref LL_ADC_DELAY_VREFINT_STAB_US. - * Refer to literal @ref LL_ADC_DELAY_TEMPSENSOR_STAB_US. - * @note ADC internal channel sampling time constraint: - * For ADC conversion of internal channels, - * a sampling time minimum value is required. - * Refer to device datasheet. - * @rmtoll CCR TSVREFE LL_ADC_SetCommonPathInternalCh\n - * CCR VBATE LL_ADC_SetCommonPathInternalCh - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @param PathInternal This parameter can be a combination of the following values: - * @arg @ref LL_ADC_PATH_INTERNAL_NONE - * @arg @ref LL_ADC_PATH_INTERNAL_VREFINT - * @arg @ref LL_ADC_PATH_INTERNAL_TEMPSENSOR - * @arg @ref LL_ADC_PATH_INTERNAL_VBAT - * @retval None - */ -__STATIC_INLINE void LL_ADC_SetCommonPathInternalCh(ADC_Common_TypeDef *ADCxy_COMMON, uint32_t PathInternal) -{ - MODIFY_REG(ADCxy_COMMON->CCR, ADC_CCR_TSVREFE | ADC_CCR_VBATE, PathInternal); -} - -/** - * @brief Get parameter common to several ADC: measurement path to internal - * channels (VrefInt, temperature sensor, ...). - * @note One or several values can be selected. - * Example: (LL_ADC_PATH_INTERNAL_VREFINT | - * LL_ADC_PATH_INTERNAL_TEMPSENSOR) - * @rmtoll CCR TSVREFE LL_ADC_GetCommonPathInternalCh\n - * CCR VBATE LL_ADC_GetCommonPathInternalCh - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @retval Returned value can be a combination of the following values: - * @arg @ref LL_ADC_PATH_INTERNAL_NONE - * @arg @ref LL_ADC_PATH_INTERNAL_VREFINT - * @arg @ref LL_ADC_PATH_INTERNAL_TEMPSENSOR - * @arg @ref LL_ADC_PATH_INTERNAL_VBAT - */ -__STATIC_INLINE uint32_t LL_ADC_GetCommonPathInternalCh(ADC_Common_TypeDef *ADCxy_COMMON) -{ - return (uint32_t)(READ_BIT(ADCxy_COMMON->CCR, ADC_CCR_TSVREFE | ADC_CCR_VBATE)); -} - -/** - * @} - */ - -/** @defgroup ADC_LL_EF_Configuration_ADC_Instance Configuration of ADC hierarchical scope: ADC instance - * @{ - */ - -/** - * @brief Set ADC resolution. - * Refer to reference manual for alignments formats - * dependencies to ADC resolutions. - * @rmtoll CR1 RES LL_ADC_SetResolution - * @param ADCx ADC instance - * @param Resolution This parameter can be one of the following values: - * @arg @ref LL_ADC_RESOLUTION_12B - * @arg @ref LL_ADC_RESOLUTION_10B - * @arg @ref LL_ADC_RESOLUTION_8B - * @arg @ref LL_ADC_RESOLUTION_6B - * @retval None - */ -__STATIC_INLINE void LL_ADC_SetResolution(ADC_TypeDef *ADCx, uint32_t Resolution) -{ - MODIFY_REG(ADCx->CR1, ADC_CR1_RES, Resolution); -} - -/** - * @brief Get ADC resolution. - * Refer to reference manual for alignments formats - * dependencies to ADC resolutions. - * @rmtoll CR1 RES LL_ADC_GetResolution - * @param ADCx ADC instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_RESOLUTION_12B - * @arg @ref LL_ADC_RESOLUTION_10B - * @arg @ref LL_ADC_RESOLUTION_8B - * @arg @ref LL_ADC_RESOLUTION_6B - */ -__STATIC_INLINE uint32_t LL_ADC_GetResolution(ADC_TypeDef *ADCx) -{ - return (uint32_t)(READ_BIT(ADCx->CR1, ADC_CR1_RES)); -} - -/** - * @brief Set ADC conversion data alignment. - * @note Refer to reference manual for alignments formats - * dependencies to ADC resolutions. - * @rmtoll CR2 ALIGN LL_ADC_SetDataAlignment - * @param ADCx ADC instance - * @param DataAlignment This parameter can be one of the following values: - * @arg @ref LL_ADC_DATA_ALIGN_RIGHT - * @arg @ref LL_ADC_DATA_ALIGN_LEFT - * @retval None - */ -__STATIC_INLINE void LL_ADC_SetDataAlignment(ADC_TypeDef *ADCx, uint32_t DataAlignment) -{ - MODIFY_REG(ADCx->CR2, ADC_CR2_ALIGN, DataAlignment); -} - -/** - * @brief Get ADC conversion data alignment. - * @note Refer to reference manual for alignments formats - * dependencies to ADC resolutions. - * @rmtoll CR2 ALIGN LL_ADC_SetDataAlignment - * @param ADCx ADC instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_DATA_ALIGN_RIGHT - * @arg @ref LL_ADC_DATA_ALIGN_LEFT - */ -__STATIC_INLINE uint32_t LL_ADC_GetDataAlignment(ADC_TypeDef *ADCx) -{ - return (uint32_t)(READ_BIT(ADCx->CR2, ADC_CR2_ALIGN)); -} - -/** - * @brief Set ADC sequencers scan mode, for all ADC groups - * (group regular, group injected). - * @note According to sequencers scan mode : - * - If disabled: ADC conversion is performed in unitary conversion - * mode (one channel converted, that defined in rank 1). - * Configuration of sequencers of all ADC groups - * (sequencer scan length, ...) is discarded: equivalent to - * scan length of 1 rank. - * - If enabled: ADC conversions are performed in sequence conversions - * mode, according to configuration of sequencers of - * each ADC group (sequencer scan length, ...). - * Refer to function @ref LL_ADC_REG_SetSequencerLength() - * and to function @ref LL_ADC_INJ_SetSequencerLength(). - * @rmtoll CR1 SCAN LL_ADC_SetSequencersScanMode - * @param ADCx ADC instance - * @param ScanMode This parameter can be one of the following values: - * @arg @ref LL_ADC_SEQ_SCAN_DISABLE - * @arg @ref LL_ADC_SEQ_SCAN_ENABLE - * @retval None - */ -__STATIC_INLINE void LL_ADC_SetSequencersScanMode(ADC_TypeDef *ADCx, uint32_t ScanMode) -{ - MODIFY_REG(ADCx->CR1, ADC_CR1_SCAN, ScanMode); -} - -/** - * @brief Get ADC sequencers scan mode, for all ADC groups - * (group regular, group injected). - * @note According to sequencers scan mode : - * - If disabled: ADC conversion is performed in unitary conversion - * mode (one channel converted, that defined in rank 1). - * Configuration of sequencers of all ADC groups - * (sequencer scan length, ...) is discarded: equivalent to - * scan length of 1 rank. - * - If enabled: ADC conversions are performed in sequence conversions - * mode, according to configuration of sequencers of - * each ADC group (sequencer scan length, ...). - * Refer to function @ref LL_ADC_REG_SetSequencerLength() - * and to function @ref LL_ADC_INJ_SetSequencerLength(). - * @rmtoll CR1 SCAN LL_ADC_GetSequencersScanMode - * @param ADCx ADC instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_SEQ_SCAN_DISABLE - * @arg @ref LL_ADC_SEQ_SCAN_ENABLE - */ -__STATIC_INLINE uint32_t LL_ADC_GetSequencersScanMode(ADC_TypeDef *ADCx) -{ - return (uint32_t)(READ_BIT(ADCx->CR1, ADC_CR1_SCAN)); -} - -/** - * @} - */ - -/** @defgroup ADC_LL_EF_Configuration_ADC_Group_Regular Configuration of ADC hierarchical scope: group regular - * @{ - */ - -/** - * @brief Set ADC group regular conversion trigger source: - * internal (SW start) or from external IP (timer event, - * external interrupt line). - * @note On this STM32 series, setting of external trigger edge is performed - * using function @ref LL_ADC_REG_StartConversionExtTrig(). - * @note Availability of parameters of trigger sources from timer - * depends on timers availability on the selected device. - * @rmtoll CR2 EXTSEL LL_ADC_REG_SetTriggerSource\n - * CR2 EXTEN LL_ADC_REG_SetTriggerSource - * @param ADCx ADC instance - * @param TriggerSource This parameter can be one of the following values: - * @arg @ref LL_ADC_REG_TRIG_SOFTWARE - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM1_CH1 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM1_CH2 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM1_CH3 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM2_CH2 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM2_CH3 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM2_CH4 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM2_TRGO - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM3_CH1 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM3_TRGO - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM4_CH4 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM5_CH1 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM5_CH2 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM5_CH3 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM8_CH1 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM8_TRGO - * @arg @ref LL_ADC_REG_TRIG_EXT_EXTI_LINE11 - * @retval None - */ -__STATIC_INLINE void LL_ADC_REG_SetTriggerSource(ADC_TypeDef *ADCx, uint32_t TriggerSource) -{ -/* Note: On this STM32 series, ADC group regular external trigger edge */ -/* is used to perform a ADC conversion start. */ -/* This function does not set external trigger edge. */ -/* This feature is set using function */ -/* @ref LL_ADC_REG_StartConversionExtTrig(). */ - MODIFY_REG(ADCx->CR2, ADC_CR2_EXTSEL, (TriggerSource & ADC_CR2_EXTSEL)); -} - -/** - * @brief Get ADC group regular conversion trigger source: - * internal (SW start) or from external IP (timer event, - * external interrupt line). - * @note To determine whether group regular trigger source is - * internal (SW start) or external, without detail - * of which peripheral is selected as external trigger, - * (equivalent to - * "if(LL_ADC_REG_GetTriggerSource(ADC1) == LL_ADC_REG_TRIG_SOFTWARE)") - * use function @ref LL_ADC_REG_IsTriggerSourceSWStart. - * @note Availability of parameters of trigger sources from timer - * depends on timers availability on the selected device. - * @rmtoll CR2 EXTSEL LL_ADC_REG_GetTriggerSource\n - * CR2 EXTEN LL_ADC_REG_GetTriggerSource - * @param ADCx ADC instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_REG_TRIG_SOFTWARE - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM1_CH1 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM1_CH2 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM1_CH3 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM2_CH2 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM2_CH3 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM2_CH4 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM2_TRGO - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM3_CH1 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM3_TRGO - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM4_CH4 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM5_CH1 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM5_CH2 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM5_CH3 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM8_CH1 - * @arg @ref LL_ADC_REG_TRIG_EXT_TIM8_TRGO - * @arg @ref LL_ADC_REG_TRIG_EXT_EXTI_LINE11 - */ -__STATIC_INLINE uint32_t LL_ADC_REG_GetTriggerSource(ADC_TypeDef *ADCx) -{ - uint32_t TriggerSource = READ_BIT(ADCx->CR2, ADC_CR2_EXTSEL | ADC_CR2_EXTEN); - - /* Value for shift of {0; 4; 8; 12} depending on value of bitfield */ - /* corresponding to ADC_CR2_EXTEN {0; 1; 2; 3}. */ - uint32_t ShiftExten = ((TriggerSource & ADC_CR2_EXTEN) >> (ADC_REG_TRIG_EXTEN_BITOFFSET_POS - 2UL)); - - /* Set bitfield corresponding to ADC_CR2_EXTEN and ADC_CR2_EXTSEL */ - /* to match with triggers literals definition. */ - return ((TriggerSource - & (ADC_REG_TRIG_SOURCE_MASK << ShiftExten) & ADC_CR2_EXTSEL) - | ((ADC_REG_TRIG_EDGE_MASK << ShiftExten) & ADC_CR2_EXTEN) - ); -} - -/** - * @brief Get ADC group regular conversion trigger source internal (SW start) - or external. - * @note In case of group regular trigger source set to external trigger, - * to determine which peripheral is selected as external trigger, - * use function @ref LL_ADC_REG_GetTriggerSource(). - * @rmtoll CR2 EXTEN LL_ADC_REG_IsTriggerSourceSWStart - * @param ADCx ADC instance - * @retval Value "0" if trigger source external trigger - * Value "1" if trigger source SW start. - */ -__STATIC_INLINE uint32_t LL_ADC_REG_IsTriggerSourceSWStart(ADC_TypeDef *ADCx) -{ - return (READ_BIT(ADCx->CR2, ADC_CR2_EXTEN) == (LL_ADC_REG_TRIG_SOFTWARE & ADC_CR2_EXTEN)); -} - -/** - * @brief Get ADC group regular conversion trigger polarity. - * @note Applicable only for trigger source set to external trigger. - * @note On this STM32 series, setting of external trigger edge is performed - * using function @ref LL_ADC_REG_StartConversionExtTrig(). - * @rmtoll CR2 EXTEN LL_ADC_REG_GetTriggerEdge - * @param ADCx ADC instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_REG_TRIG_EXT_RISING - * @arg @ref LL_ADC_REG_TRIG_EXT_FALLING - * @arg @ref LL_ADC_REG_TRIG_EXT_RISINGFALLING - */ -__STATIC_INLINE uint32_t LL_ADC_REG_GetTriggerEdge(ADC_TypeDef *ADCx) -{ - return (uint32_t)(READ_BIT(ADCx->CR2, ADC_CR2_EXTEN)); -} - - -/** - * @brief Set ADC group regular sequencer length and scan direction. - * @note Description of ADC group regular sequencer features: - * - For devices with sequencer fully configurable - * (function "LL_ADC_REG_SetSequencerRanks()" available): - * sequencer length and each rank affectation to a channel - * are configurable. - * This function performs configuration of: - * - Sequence length: Number of ranks in the scan sequence. - * - Sequence direction: Unless specified in parameters, sequencer - * scan direction is forward (from rank 1 to rank n). - * Sequencer ranks are selected using - * function "LL_ADC_REG_SetSequencerRanks()". - * - For devices with sequencer not fully configurable - * (function "LL_ADC_REG_SetSequencerChannels()" available): - * sequencer length and each rank affectation to a channel - * are defined by channel number. - * This function performs configuration of: - * - Sequence length: Number of ranks in the scan sequence is - * defined by number of channels set in the sequence, - * rank of each channel is fixed by channel HW number. - * (channel 0 fixed on rank 0, channel 1 fixed on rank1, ...). - * - Sequence direction: Unless specified in parameters, sequencer - * scan direction is forward (from lowest channel number to - * highest channel number). - * Sequencer ranks are selected using - * function "LL_ADC_REG_SetSequencerChannels()". - * @note On this STM32 series, group regular sequencer configuration - * is conditioned to ADC instance sequencer mode. - * If ADC instance sequencer mode is disabled, sequencers of - * all groups (group regular, group injected) can be configured - * but their execution is disabled (limited to rank 1). - * Refer to function @ref LL_ADC_SetSequencersScanMode(). - * @note Sequencer disabled is equivalent to sequencer of 1 rank: - * ADC conversion on only 1 channel. - * @rmtoll SQR1 L LL_ADC_REG_SetSequencerLength - * @param ADCx ADC instance - * @param SequencerNbRanks This parameter can be one of the following values: - * @arg @ref LL_ADC_REG_SEQ_SCAN_DISABLE - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_2RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_3RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_4RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_5RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_6RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_7RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_8RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_9RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_10RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_11RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_12RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_13RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_14RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_15RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_16RANKS - * @retval None - */ -__STATIC_INLINE void LL_ADC_REG_SetSequencerLength(ADC_TypeDef *ADCx, uint32_t SequencerNbRanks) -{ - MODIFY_REG(ADCx->SQR1, ADC_SQR1_L, SequencerNbRanks); -} - -/** - * @brief Get ADC group regular sequencer length and scan direction. - * @note Description of ADC group regular sequencer features: - * - For devices with sequencer fully configurable - * (function "LL_ADC_REG_SetSequencerRanks()" available): - * sequencer length and each rank affectation to a channel - * are configurable. - * This function retrieves: - * - Sequence length: Number of ranks in the scan sequence. - * - Sequence direction: Unless specified in parameters, sequencer - * scan direction is forward (from rank 1 to rank n). - * Sequencer ranks are selected using - * function "LL_ADC_REG_SetSequencerRanks()". - * - For devices with sequencer not fully configurable - * (function "LL_ADC_REG_SetSequencerChannels()" available): - * sequencer length and each rank affectation to a channel - * are defined by channel number. - * This function retrieves: - * - Sequence length: Number of ranks in the scan sequence is - * defined by number of channels set in the sequence, - * rank of each channel is fixed by channel HW number. - * (channel 0 fixed on rank 0, channel 1 fixed on rank1, ...). - * - Sequence direction: Unless specified in parameters, sequencer - * scan direction is forward (from lowest channel number to - * highest channel number). - * Sequencer ranks are selected using - * function "LL_ADC_REG_SetSequencerChannels()". - * @note On this STM32 series, group regular sequencer configuration - * is conditioned to ADC instance sequencer mode. - * If ADC instance sequencer mode is disabled, sequencers of - * all groups (group regular, group injected) can be configured - * but their execution is disabled (limited to rank 1). - * Refer to function @ref LL_ADC_SetSequencersScanMode(). - * @note Sequencer disabled is equivalent to sequencer of 1 rank: - * ADC conversion on only 1 channel. - * @rmtoll SQR1 L LL_ADC_REG_SetSequencerLength - * @param ADCx ADC instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_REG_SEQ_SCAN_DISABLE - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_2RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_3RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_4RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_5RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_6RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_7RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_8RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_9RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_10RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_11RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_12RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_13RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_14RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_15RANKS - * @arg @ref LL_ADC_REG_SEQ_SCAN_ENABLE_16RANKS - */ -__STATIC_INLINE uint32_t LL_ADC_REG_GetSequencerLength(ADC_TypeDef *ADCx) -{ - return (uint32_t)(READ_BIT(ADCx->SQR1, ADC_SQR1_L)); -} - -/** - * @brief Set ADC group regular sequencer discontinuous mode: - * sequence subdivided and scan conversions interrupted every selected - * number of ranks. - * @note It is not possible to enable both ADC group regular - * continuous mode and sequencer discontinuous mode. - * @note It is not possible to enable both ADC auto-injected mode - * and ADC group regular sequencer discontinuous mode. - * @rmtoll CR1 DISCEN LL_ADC_REG_SetSequencerDiscont\n - * CR1 DISCNUM LL_ADC_REG_SetSequencerDiscont - * @param ADCx ADC instance - * @param SeqDiscont This parameter can be one of the following values: - * @arg @ref LL_ADC_REG_SEQ_DISCONT_DISABLE - * @arg @ref LL_ADC_REG_SEQ_DISCONT_1RANK - * @arg @ref LL_ADC_REG_SEQ_DISCONT_2RANKS - * @arg @ref LL_ADC_REG_SEQ_DISCONT_3RANKS - * @arg @ref LL_ADC_REG_SEQ_DISCONT_4RANKS - * @arg @ref LL_ADC_REG_SEQ_DISCONT_5RANKS - * @arg @ref LL_ADC_REG_SEQ_DISCONT_6RANKS - * @arg @ref LL_ADC_REG_SEQ_DISCONT_7RANKS - * @arg @ref LL_ADC_REG_SEQ_DISCONT_8RANKS - * @retval None - */ -__STATIC_INLINE void LL_ADC_REG_SetSequencerDiscont(ADC_TypeDef *ADCx, uint32_t SeqDiscont) -{ - MODIFY_REG(ADCx->CR1, ADC_CR1_DISCEN | ADC_CR1_DISCNUM, SeqDiscont); -} - -/** - * @brief Get ADC group regular sequencer discontinuous mode: - * sequence subdivided and scan conversions interrupted every selected - * number of ranks. - * @rmtoll CR1 DISCEN LL_ADC_REG_GetSequencerDiscont\n - * CR1 DISCNUM LL_ADC_REG_GetSequencerDiscont - * @param ADCx ADC instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_REG_SEQ_DISCONT_DISABLE - * @arg @ref LL_ADC_REG_SEQ_DISCONT_1RANK - * @arg @ref LL_ADC_REG_SEQ_DISCONT_2RANKS - * @arg @ref LL_ADC_REG_SEQ_DISCONT_3RANKS - * @arg @ref LL_ADC_REG_SEQ_DISCONT_4RANKS - * @arg @ref LL_ADC_REG_SEQ_DISCONT_5RANKS - * @arg @ref LL_ADC_REG_SEQ_DISCONT_6RANKS - * @arg @ref LL_ADC_REG_SEQ_DISCONT_7RANKS - * @arg @ref LL_ADC_REG_SEQ_DISCONT_8RANKS - */ -__STATIC_INLINE uint32_t LL_ADC_REG_GetSequencerDiscont(ADC_TypeDef *ADCx) -{ - return (uint32_t)(READ_BIT(ADCx->CR1, ADC_CR1_DISCEN | ADC_CR1_DISCNUM)); -} - -/** - * @brief Set ADC group regular sequence: channel on the selected - * scan sequence rank. - * @note This function performs configuration of: - * - Channels ordering into each rank of scan sequence: - * whatever channel can be placed into whatever rank. - * @note On this STM32 series, ADC group regular sequencer is - * fully configurable: sequencer length and each rank - * affectation to a channel are configurable. - * Refer to description of function @ref LL_ADC_REG_SetSequencerLength(). - * @note Depending on devices and packages, some channels may not be available. - * Refer to device datasheet for channels availability. - * @note On this STM32 series, to measure internal channels (VrefInt, - * TempSensor, ...), measurement paths to internal channels must be - * enabled separately. - * This can be done using function @ref LL_ADC_SetCommonPathInternalCh(). - * @rmtoll SQR3 SQ1 LL_ADC_REG_SetSequencerRanks\n - * SQR3 SQ2 LL_ADC_REG_SetSequencerRanks\n - * SQR3 SQ3 LL_ADC_REG_SetSequencerRanks\n - * SQR3 SQ4 LL_ADC_REG_SetSequencerRanks\n - * SQR3 SQ5 LL_ADC_REG_SetSequencerRanks\n - * SQR3 SQ6 LL_ADC_REG_SetSequencerRanks\n - * SQR2 SQ7 LL_ADC_REG_SetSequencerRanks\n - * SQR2 SQ8 LL_ADC_REG_SetSequencerRanks\n - * SQR2 SQ9 LL_ADC_REG_SetSequencerRanks\n - * SQR2 SQ10 LL_ADC_REG_SetSequencerRanks\n - * SQR2 SQ11 LL_ADC_REG_SetSequencerRanks\n - * SQR2 SQ12 LL_ADC_REG_SetSequencerRanks\n - * SQR1 SQ13 LL_ADC_REG_SetSequencerRanks\n - * SQR1 SQ14 LL_ADC_REG_SetSequencerRanks\n - * SQR1 SQ15 LL_ADC_REG_SetSequencerRanks\n - * SQR1 SQ16 LL_ADC_REG_SetSequencerRanks - * @param ADCx ADC instance - * @param Rank This parameter can be one of the following values: - * @arg @ref LL_ADC_REG_RANK_1 - * @arg @ref LL_ADC_REG_RANK_2 - * @arg @ref LL_ADC_REG_RANK_3 - * @arg @ref LL_ADC_REG_RANK_4 - * @arg @ref LL_ADC_REG_RANK_5 - * @arg @ref LL_ADC_REG_RANK_6 - * @arg @ref LL_ADC_REG_RANK_7 - * @arg @ref LL_ADC_REG_RANK_8 - * @arg @ref LL_ADC_REG_RANK_9 - * @arg @ref LL_ADC_REG_RANK_10 - * @arg @ref LL_ADC_REG_RANK_11 - * @arg @ref LL_ADC_REG_RANK_12 - * @arg @ref LL_ADC_REG_RANK_13 - * @arg @ref LL_ADC_REG_RANK_14 - * @arg @ref LL_ADC_REG_RANK_15 - * @arg @ref LL_ADC_REG_RANK_16 - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_ADC_CHANNEL_0 - * @arg @ref LL_ADC_CHANNEL_1 - * @arg @ref LL_ADC_CHANNEL_2 - * @arg @ref LL_ADC_CHANNEL_3 - * @arg @ref LL_ADC_CHANNEL_4 - * @arg @ref LL_ADC_CHANNEL_5 - * @arg @ref LL_ADC_CHANNEL_6 - * @arg @ref LL_ADC_CHANNEL_7 - * @arg @ref LL_ADC_CHANNEL_8 - * @arg @ref LL_ADC_CHANNEL_9 - * @arg @ref LL_ADC_CHANNEL_10 - * @arg @ref LL_ADC_CHANNEL_11 - * @arg @ref LL_ADC_CHANNEL_12 - * @arg @ref LL_ADC_CHANNEL_13 - * @arg @ref LL_ADC_CHANNEL_14 - * @arg @ref LL_ADC_CHANNEL_15 - * @arg @ref LL_ADC_CHANNEL_16 - * @arg @ref LL_ADC_CHANNEL_17 - * @arg @ref LL_ADC_CHANNEL_18 - * @arg @ref LL_ADC_CHANNEL_VREFINT (1) - * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)(2) - * @arg @ref LL_ADC_CHANNEL_VBAT (1) - * - * (1) On STM32F4, parameter available only on ADC instance: ADC1.\n - * (2) On devices STM32F42x and STM32F43x, limitation: this internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled. - * @retval None - */ -__STATIC_INLINE void LL_ADC_REG_SetSequencerRanks(ADC_TypeDef *ADCx, uint32_t Rank, uint32_t Channel) -{ - /* Set bits with content of parameter "Channel" with bits position */ - /* in register and register position depending on parameter "Rank". */ - /* Parameters "Rank" and "Channel" are used with masks because containing */ - /* other bits reserved for other purpose. */ - __IO uint32_t *preg = __ADC_PTR_REG_OFFSET(ADCx->SQR1, __ADC_MASK_SHIFT(Rank, ADC_REG_SQRX_REGOFFSET_MASK)); - - MODIFY_REG(*preg, - ADC_CHANNEL_ID_NUMBER_MASK << (Rank & ADC_REG_RANK_ID_SQRX_MASK), - (Channel & ADC_CHANNEL_ID_NUMBER_MASK) << (Rank & ADC_REG_RANK_ID_SQRX_MASK)); -} - -/** - * @brief Get ADC group regular sequence: channel on the selected - * scan sequence rank. - * @note On this STM32 series, ADC group regular sequencer is - * fully configurable: sequencer length and each rank - * affectation to a channel are configurable. - * Refer to description of function @ref LL_ADC_REG_SetSequencerLength(). - * @note Depending on devices and packages, some channels may not be available. - * Refer to device datasheet for channels availability. - * @note Usage of the returned channel number: - * - To reinject this channel into another function LL_ADC_xxx: - * the returned channel number is only partly formatted on definition - * of literals LL_ADC_CHANNEL_x. Therefore, it has to be compared - * with parts of literals LL_ADC_CHANNEL_x or using - * helper macro @ref __LL_ADC_CHANNEL_TO_DECIMAL_NB(). - * Then the selected literal LL_ADC_CHANNEL_x can be used - * as parameter for another function. - * - To get the channel number in decimal format: - * process the returned value with the helper macro - * @ref __LL_ADC_CHANNEL_TO_DECIMAL_NB(). - * @rmtoll SQR3 SQ1 LL_ADC_REG_GetSequencerRanks\n - * SQR3 SQ2 LL_ADC_REG_GetSequencerRanks\n - * SQR3 SQ3 LL_ADC_REG_GetSequencerRanks\n - * SQR3 SQ4 LL_ADC_REG_GetSequencerRanks\n - * SQR3 SQ5 LL_ADC_REG_GetSequencerRanks\n - * SQR3 SQ6 LL_ADC_REG_GetSequencerRanks\n - * SQR2 SQ7 LL_ADC_REG_GetSequencerRanks\n - * SQR2 SQ8 LL_ADC_REG_GetSequencerRanks\n - * SQR2 SQ9 LL_ADC_REG_GetSequencerRanks\n - * SQR2 SQ10 LL_ADC_REG_GetSequencerRanks\n - * SQR2 SQ11 LL_ADC_REG_GetSequencerRanks\n - * SQR2 SQ12 LL_ADC_REG_GetSequencerRanks\n - * SQR1 SQ13 LL_ADC_REG_GetSequencerRanks\n - * SQR1 SQ14 LL_ADC_REG_GetSequencerRanks\n - * SQR1 SQ15 LL_ADC_REG_GetSequencerRanks\n - * SQR1 SQ16 LL_ADC_REG_GetSequencerRanks - * @param ADCx ADC instance - * @param Rank This parameter can be one of the following values: - * @arg @ref LL_ADC_REG_RANK_1 - * @arg @ref LL_ADC_REG_RANK_2 - * @arg @ref LL_ADC_REG_RANK_3 - * @arg @ref LL_ADC_REG_RANK_4 - * @arg @ref LL_ADC_REG_RANK_5 - * @arg @ref LL_ADC_REG_RANK_6 - * @arg @ref LL_ADC_REG_RANK_7 - * @arg @ref LL_ADC_REG_RANK_8 - * @arg @ref LL_ADC_REG_RANK_9 - * @arg @ref LL_ADC_REG_RANK_10 - * @arg @ref LL_ADC_REG_RANK_11 - * @arg @ref LL_ADC_REG_RANK_12 - * @arg @ref LL_ADC_REG_RANK_13 - * @arg @ref LL_ADC_REG_RANK_14 - * @arg @ref LL_ADC_REG_RANK_15 - * @arg @ref LL_ADC_REG_RANK_16 - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_CHANNEL_0 - * @arg @ref LL_ADC_CHANNEL_1 - * @arg @ref LL_ADC_CHANNEL_2 - * @arg @ref LL_ADC_CHANNEL_3 - * @arg @ref LL_ADC_CHANNEL_4 - * @arg @ref LL_ADC_CHANNEL_5 - * @arg @ref LL_ADC_CHANNEL_6 - * @arg @ref LL_ADC_CHANNEL_7 - * @arg @ref LL_ADC_CHANNEL_8 - * @arg @ref LL_ADC_CHANNEL_9 - * @arg @ref LL_ADC_CHANNEL_10 - * @arg @ref LL_ADC_CHANNEL_11 - * @arg @ref LL_ADC_CHANNEL_12 - * @arg @ref LL_ADC_CHANNEL_13 - * @arg @ref LL_ADC_CHANNEL_14 - * @arg @ref LL_ADC_CHANNEL_15 - * @arg @ref LL_ADC_CHANNEL_16 - * @arg @ref LL_ADC_CHANNEL_17 - * @arg @ref LL_ADC_CHANNEL_18 - * @arg @ref LL_ADC_CHANNEL_VREFINT (1) - * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)(2) - * @arg @ref LL_ADC_CHANNEL_VBAT (1) - * - * (1) On STM32F4, parameter available only on ADC instance: ADC1.\n - * (2) On devices STM32F42x and STM32F43x, limitation: this internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled.\n - * (1) For ADC channel read back from ADC register, - * comparison with internal channel parameter to be done - * using helper macro @ref __LL_ADC_CHANNEL_INTERNAL_TO_EXTERNAL(). - */ -__STATIC_INLINE uint32_t LL_ADC_REG_GetSequencerRanks(ADC_TypeDef *ADCx, uint32_t Rank) -{ - __IO uint32_t *preg = __ADC_PTR_REG_OFFSET(ADCx->SQR1, __ADC_MASK_SHIFT(Rank, ADC_REG_SQRX_REGOFFSET_MASK)); - - return (uint32_t) (READ_BIT(*preg, - ADC_CHANNEL_ID_NUMBER_MASK << (Rank & ADC_REG_RANK_ID_SQRX_MASK)) - >> (Rank & ADC_REG_RANK_ID_SQRX_MASK) - ); -} - -/** - * @brief Set ADC continuous conversion mode on ADC group regular. - * @note Description of ADC continuous conversion mode: - * - single mode: one conversion per trigger - * - continuous mode: after the first trigger, following - * conversions launched successively automatically. - * @note It is not possible to enable both ADC group regular - * continuous mode and sequencer discontinuous mode. - * @rmtoll CR2 CONT LL_ADC_REG_SetContinuousMode - * @param ADCx ADC instance - * @param Continuous This parameter can be one of the following values: - * @arg @ref LL_ADC_REG_CONV_SINGLE - * @arg @ref LL_ADC_REG_CONV_CONTINUOUS - * @retval None - */ -__STATIC_INLINE void LL_ADC_REG_SetContinuousMode(ADC_TypeDef *ADCx, uint32_t Continuous) -{ - MODIFY_REG(ADCx->CR2, ADC_CR2_CONT, Continuous); -} - -/** - * @brief Get ADC continuous conversion mode on ADC group regular. - * @note Description of ADC continuous conversion mode: - * - single mode: one conversion per trigger - * - continuous mode: after the first trigger, following - * conversions launched successively automatically. - * @rmtoll CR2 CONT LL_ADC_REG_GetContinuousMode - * @param ADCx ADC instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_REG_CONV_SINGLE - * @arg @ref LL_ADC_REG_CONV_CONTINUOUS - */ -__STATIC_INLINE uint32_t LL_ADC_REG_GetContinuousMode(ADC_TypeDef *ADCx) -{ - return (uint32_t)(READ_BIT(ADCx->CR2, ADC_CR2_CONT)); -} - -/** - * @brief Set ADC group regular conversion data transfer: no transfer or - * transfer by DMA, and DMA requests mode. - * @note If transfer by DMA selected, specifies the DMA requests - * mode: - * - Limited mode (One shot mode): DMA transfer requests are stopped - * when number of DMA data transfers (number of - * ADC conversions) is reached. - * This ADC mode is intended to be used with DMA mode non-circular. - * - Unlimited mode: DMA transfer requests are unlimited, - * whatever number of DMA data transfers (number of - * ADC conversions). - * This ADC mode is intended to be used with DMA mode circular. - * @note If ADC DMA requests mode is set to unlimited and DMA is set to - * mode non-circular: - * when DMA transfers size will be reached, DMA will stop transfers of - * ADC conversions data ADC will raise an overrun error - * (overrun flag and interruption if enabled). - * @note For devices with several ADC instances: ADC multimode DMA - * settings are available using function @ref LL_ADC_SetMultiDMATransfer(). - * @note To configure DMA source address (peripheral address), - * use function @ref LL_ADC_DMA_GetRegAddr(). - * @rmtoll CR2 DMA LL_ADC_REG_SetDMATransfer\n - * CR2 DDS LL_ADC_REG_SetDMATransfer - * @param ADCx ADC instance - * @param DMATransfer This parameter can be one of the following values: - * @arg @ref LL_ADC_REG_DMA_TRANSFER_NONE - * @arg @ref LL_ADC_REG_DMA_TRANSFER_LIMITED - * @arg @ref LL_ADC_REG_DMA_TRANSFER_UNLIMITED - * @retval None - */ -__STATIC_INLINE void LL_ADC_REG_SetDMATransfer(ADC_TypeDef *ADCx, uint32_t DMATransfer) -{ - MODIFY_REG(ADCx->CR2, ADC_CR2_DMA | ADC_CR2_DDS, DMATransfer); -} - -/** - * @brief Get ADC group regular conversion data transfer: no transfer or - * transfer by DMA, and DMA requests mode. - * @note If transfer by DMA selected, specifies the DMA requests - * mode: - * - Limited mode (One shot mode): DMA transfer requests are stopped - * when number of DMA data transfers (number of - * ADC conversions) is reached. - * This ADC mode is intended to be used with DMA mode non-circular. - * - Unlimited mode: DMA transfer requests are unlimited, - * whatever number of DMA data transfers (number of - * ADC conversions). - * This ADC mode is intended to be used with DMA mode circular. - * @note If ADC DMA requests mode is set to unlimited and DMA is set to - * mode non-circular: - * when DMA transfers size will be reached, DMA will stop transfers of - * ADC conversions data ADC will raise an overrun error - * (overrun flag and interruption if enabled). - * @note For devices with several ADC instances: ADC multimode DMA - * settings are available using function @ref LL_ADC_GetMultiDMATransfer(). - * @note To configure DMA source address (peripheral address), - * use function @ref LL_ADC_DMA_GetRegAddr(). - * @rmtoll CR2 DMA LL_ADC_REG_GetDMATransfer\n - * CR2 DDS LL_ADC_REG_GetDMATransfer - * @param ADCx ADC instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_REG_DMA_TRANSFER_NONE - * @arg @ref LL_ADC_REG_DMA_TRANSFER_LIMITED - * @arg @ref LL_ADC_REG_DMA_TRANSFER_UNLIMITED - */ -__STATIC_INLINE uint32_t LL_ADC_REG_GetDMATransfer(ADC_TypeDef *ADCx) -{ - return (uint32_t)(READ_BIT(ADCx->CR2, ADC_CR2_DMA | ADC_CR2_DDS)); -} - -/** - * @brief Specify which ADC flag between EOC (end of unitary conversion) - * or EOS (end of sequence conversions) is used to indicate - * the end of conversion. - * @note This feature is aimed to be set when using ADC with - * programming model by polling or interruption - * (programming model by DMA usually uses DMA interruptions - * to indicate end of conversion and data transfer). - * @note For ADC group injected, end of conversion (flag&IT) is raised - * only at the end of the sequence. - * @rmtoll CR2 EOCS LL_ADC_REG_SetFlagEndOfConversion - * @param ADCx ADC instance - * @param EocSelection This parameter can be one of the following values: - * @arg @ref LL_ADC_REG_FLAG_EOC_SEQUENCE_CONV - * @arg @ref LL_ADC_REG_FLAG_EOC_UNITARY_CONV - * @retval None - */ -__STATIC_INLINE void LL_ADC_REG_SetFlagEndOfConversion(ADC_TypeDef *ADCx, uint32_t EocSelection) -{ - MODIFY_REG(ADCx->CR2, ADC_CR2_EOCS, EocSelection); -} - -/** - * @brief Get which ADC flag between EOC (end of unitary conversion) - * or EOS (end of sequence conversions) is used to indicate - * the end of conversion. - * @rmtoll CR2 EOCS LL_ADC_REG_GetFlagEndOfConversion - * @param ADCx ADC instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_REG_FLAG_EOC_SEQUENCE_CONV - * @arg @ref LL_ADC_REG_FLAG_EOC_UNITARY_CONV - */ -__STATIC_INLINE uint32_t LL_ADC_REG_GetFlagEndOfConversion(ADC_TypeDef *ADCx) -{ - return (uint32_t)(READ_BIT(ADCx->CR2, ADC_CR2_EOCS)); -} - -/** - * @} - */ - -/** @defgroup ADC_LL_EF_Configuration_ADC_Group_Injected Configuration of ADC hierarchical scope: group injected - * @{ - */ - -/** - * @brief Set ADC group injected conversion trigger source: - * internal (SW start) or from external IP (timer event, - * external interrupt line). - * @note On this STM32 series, setting of external trigger edge is performed - * using function @ref LL_ADC_INJ_StartConversionExtTrig(). - * @note Availability of parameters of trigger sources from timer - * depends on timers availability on the selected device. - * @rmtoll CR2 JEXTSEL LL_ADC_INJ_SetTriggerSource\n - * CR2 JEXTEN LL_ADC_INJ_SetTriggerSource - * @param ADCx ADC instance - * @param TriggerSource This parameter can be one of the following values: - * @arg @ref LL_ADC_INJ_TRIG_SOFTWARE - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM1_CH4 - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM1_TRGO - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM2_CH1 - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM2_TRGO - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM3_CH2 - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM3_CH4 - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM4_CH1 - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM4_CH2 - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM4_CH3 - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM4_TRGO - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM5_CH4 - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM5_TRGO - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM8_CH2 - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM8_CH3 - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM8_CH4 - * @arg @ref LL_ADC_INJ_TRIG_EXT_EXTI_LINE15 - * @retval None - */ -__STATIC_INLINE void LL_ADC_INJ_SetTriggerSource(ADC_TypeDef *ADCx, uint32_t TriggerSource) -{ -/* Note: On this STM32 series, ADC group injected external trigger edge */ -/* is used to perform a ADC conversion start. */ -/* This function does not set external trigger edge. */ -/* This feature is set using function */ -/* @ref LL_ADC_INJ_StartConversionExtTrig(). */ - MODIFY_REG(ADCx->CR2, ADC_CR2_JEXTSEL, (TriggerSource & ADC_CR2_JEXTSEL)); -} - -/** - * @brief Get ADC group injected conversion trigger source: - * internal (SW start) or from external IP (timer event, - * external interrupt line). - * @note To determine whether group injected trigger source is - * internal (SW start) or external, without detail - * of which peripheral is selected as external trigger, - * (equivalent to - * "if(LL_ADC_INJ_GetTriggerSource(ADC1) == LL_ADC_INJ_TRIG_SOFTWARE)") - * use function @ref LL_ADC_INJ_IsTriggerSourceSWStart. - * @note Availability of parameters of trigger sources from timer - * depends on timers availability on the selected device. - * @rmtoll CR2 JEXTSEL LL_ADC_INJ_GetTriggerSource\n - * CR2 JEXTEN LL_ADC_INJ_GetTriggerSource - * @param ADCx ADC instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_INJ_TRIG_SOFTWARE - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM1_CH4 - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM1_TRGO - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM2_CH1 - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM2_TRGO - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM3_CH2 - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM3_CH4 - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM4_CH1 - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM4_CH2 - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM4_CH3 - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM4_TRGO - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM5_CH4 - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM5_TRGO - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM8_CH2 - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM8_CH3 - * @arg @ref LL_ADC_INJ_TRIG_EXT_TIM8_CH4 - * @arg @ref LL_ADC_INJ_TRIG_EXT_EXTI_LINE15 - */ -__STATIC_INLINE uint32_t LL_ADC_INJ_GetTriggerSource(ADC_TypeDef *ADCx) -{ - uint32_t TriggerSource = READ_BIT(ADCx->CR2, ADC_CR2_JEXTSEL | ADC_CR2_JEXTEN); - - /* Value for shift of {0; 4; 8; 12} depending on value of bitfield */ - /* corresponding to ADC_CR2_JEXTEN {0; 1; 2; 3}. */ - uint32_t ShiftExten = ((TriggerSource & ADC_CR2_JEXTEN) >> (ADC_INJ_TRIG_EXTEN_BITOFFSET_POS - 2UL)); - - /* Set bitfield corresponding to ADC_CR2_JEXTEN and ADC_CR2_JEXTSEL */ - /* to match with triggers literals definition. */ - return ((TriggerSource - & (ADC_INJ_TRIG_SOURCE_MASK << ShiftExten) & ADC_CR2_JEXTSEL) - | ((ADC_INJ_TRIG_EDGE_MASK << ShiftExten) & ADC_CR2_JEXTEN) - ); -} - -/** - * @brief Get ADC group injected conversion trigger source internal (SW start) - or external - * @note In case of group injected trigger source set to external trigger, - * to determine which peripheral is selected as external trigger, - * use function @ref LL_ADC_INJ_GetTriggerSource. - * @rmtoll CR2 JEXTEN LL_ADC_INJ_IsTriggerSourceSWStart - * @param ADCx ADC instance - * @retval Value "0" if trigger source external trigger - * Value "1" if trigger source SW start. - */ -__STATIC_INLINE uint32_t LL_ADC_INJ_IsTriggerSourceSWStart(ADC_TypeDef *ADCx) -{ - return (READ_BIT(ADCx->CR2, ADC_CR2_JEXTEN) == (LL_ADC_INJ_TRIG_SOFTWARE & ADC_CR2_JEXTEN)); -} - -/** - * @brief Get ADC group injected conversion trigger polarity. - * Applicable only for trigger source set to external trigger. - * @rmtoll CR2 JEXTEN LL_ADC_INJ_GetTriggerEdge - * @param ADCx ADC instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_INJ_TRIG_EXT_RISING - * @arg @ref LL_ADC_INJ_TRIG_EXT_FALLING - * @arg @ref LL_ADC_INJ_TRIG_EXT_RISINGFALLING - */ -__STATIC_INLINE uint32_t LL_ADC_INJ_GetTriggerEdge(ADC_TypeDef *ADCx) -{ - return (uint32_t)(READ_BIT(ADCx->CR2, ADC_CR2_JEXTEN)); -} - -/** - * @brief Set ADC group injected sequencer length and scan direction. - * @note This function performs configuration of: - * - Sequence length: Number of ranks in the scan sequence. - * - Sequence direction: Unless specified in parameters, sequencer - * scan direction is forward (from rank 1 to rank n). - * @note On this STM32 series, group injected sequencer configuration - * is conditioned to ADC instance sequencer mode. - * If ADC instance sequencer mode is disabled, sequencers of - * all groups (group regular, group injected) can be configured - * but their execution is disabled (limited to rank 1). - * Refer to function @ref LL_ADC_SetSequencersScanMode(). - * @note Sequencer disabled is equivalent to sequencer of 1 rank: - * ADC conversion on only 1 channel. - * @rmtoll JSQR JL LL_ADC_INJ_SetSequencerLength - * @param ADCx ADC instance - * @param SequencerNbRanks This parameter can be one of the following values: - * @arg @ref LL_ADC_INJ_SEQ_SCAN_DISABLE - * @arg @ref LL_ADC_INJ_SEQ_SCAN_ENABLE_2RANKS - * @arg @ref LL_ADC_INJ_SEQ_SCAN_ENABLE_3RANKS - * @arg @ref LL_ADC_INJ_SEQ_SCAN_ENABLE_4RANKS - * @retval None - */ -__STATIC_INLINE void LL_ADC_INJ_SetSequencerLength(ADC_TypeDef *ADCx, uint32_t SequencerNbRanks) -{ - MODIFY_REG(ADCx->JSQR, ADC_JSQR_JL, SequencerNbRanks); -} - -/** - * @brief Get ADC group injected sequencer length and scan direction. - * @note This function retrieves: - * - Sequence length: Number of ranks in the scan sequence. - * - Sequence direction: Unless specified in parameters, sequencer - * scan direction is forward (from rank 1 to rank n). - * @note On this STM32 series, group injected sequencer configuration - * is conditioned to ADC instance sequencer mode. - * If ADC instance sequencer mode is disabled, sequencers of - * all groups (group regular, group injected) can be configured - * but their execution is disabled (limited to rank 1). - * Refer to function @ref LL_ADC_SetSequencersScanMode(). - * @note Sequencer disabled is equivalent to sequencer of 1 rank: - * ADC conversion on only 1 channel. - * @rmtoll JSQR JL LL_ADC_INJ_GetSequencerLength - * @param ADCx ADC instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_INJ_SEQ_SCAN_DISABLE - * @arg @ref LL_ADC_INJ_SEQ_SCAN_ENABLE_2RANKS - * @arg @ref LL_ADC_INJ_SEQ_SCAN_ENABLE_3RANKS - * @arg @ref LL_ADC_INJ_SEQ_SCAN_ENABLE_4RANKS - */ -__STATIC_INLINE uint32_t LL_ADC_INJ_GetSequencerLength(ADC_TypeDef *ADCx) -{ - return (uint32_t)(READ_BIT(ADCx->JSQR, ADC_JSQR_JL)); -} - -/** - * @brief Set ADC group injected sequencer discontinuous mode: - * sequence subdivided and scan conversions interrupted every selected - * number of ranks. - * @note It is not possible to enable both ADC group injected - * auto-injected mode and sequencer discontinuous mode. - * @rmtoll CR1 DISCEN LL_ADC_INJ_SetSequencerDiscont - * @param ADCx ADC instance - * @param SeqDiscont This parameter can be one of the following values: - * @arg @ref LL_ADC_INJ_SEQ_DISCONT_DISABLE - * @arg @ref LL_ADC_INJ_SEQ_DISCONT_1RANK - * @retval None - */ -__STATIC_INLINE void LL_ADC_INJ_SetSequencerDiscont(ADC_TypeDef *ADCx, uint32_t SeqDiscont) -{ - MODIFY_REG(ADCx->CR1, ADC_CR1_JDISCEN, SeqDiscont); -} - -/** - * @brief Get ADC group injected sequencer discontinuous mode: - * sequence subdivided and scan conversions interrupted every selected - * number of ranks. - * @rmtoll CR1 DISCEN LL_ADC_REG_GetSequencerDiscont - * @param ADCx ADC instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_INJ_SEQ_DISCONT_DISABLE - * @arg @ref LL_ADC_INJ_SEQ_DISCONT_1RANK - */ -__STATIC_INLINE uint32_t LL_ADC_INJ_GetSequencerDiscont(ADC_TypeDef *ADCx) -{ - return (uint32_t)(READ_BIT(ADCx->CR1, ADC_CR1_JDISCEN)); -} - -/** - * @brief Set ADC group injected sequence: channel on the selected - * sequence rank. - * @note Depending on devices and packages, some channels may not be available. - * Refer to device datasheet for channels availability. - * @note On this STM32 series, to measure internal channels (VrefInt, - * TempSensor, ...), measurement paths to internal channels must be - * enabled separately. - * This can be done using function @ref LL_ADC_SetCommonPathInternalCh(). - * @rmtoll JSQR JSQ1 LL_ADC_INJ_SetSequencerRanks\n - * JSQR JSQ2 LL_ADC_INJ_SetSequencerRanks\n - * JSQR JSQ3 LL_ADC_INJ_SetSequencerRanks\n - * JSQR JSQ4 LL_ADC_INJ_SetSequencerRanks - * @param ADCx ADC instance - * @param Rank This parameter can be one of the following values: - * @arg @ref LL_ADC_INJ_RANK_1 - * @arg @ref LL_ADC_INJ_RANK_2 - * @arg @ref LL_ADC_INJ_RANK_3 - * @arg @ref LL_ADC_INJ_RANK_4 - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_ADC_CHANNEL_0 - * @arg @ref LL_ADC_CHANNEL_1 - * @arg @ref LL_ADC_CHANNEL_2 - * @arg @ref LL_ADC_CHANNEL_3 - * @arg @ref LL_ADC_CHANNEL_4 - * @arg @ref LL_ADC_CHANNEL_5 - * @arg @ref LL_ADC_CHANNEL_6 - * @arg @ref LL_ADC_CHANNEL_7 - * @arg @ref LL_ADC_CHANNEL_8 - * @arg @ref LL_ADC_CHANNEL_9 - * @arg @ref LL_ADC_CHANNEL_10 - * @arg @ref LL_ADC_CHANNEL_11 - * @arg @ref LL_ADC_CHANNEL_12 - * @arg @ref LL_ADC_CHANNEL_13 - * @arg @ref LL_ADC_CHANNEL_14 - * @arg @ref LL_ADC_CHANNEL_15 - * @arg @ref LL_ADC_CHANNEL_16 - * @arg @ref LL_ADC_CHANNEL_17 - * @arg @ref LL_ADC_CHANNEL_18 - * @arg @ref LL_ADC_CHANNEL_VREFINT (1) - * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)(2) - * @arg @ref LL_ADC_CHANNEL_VBAT (1) - * - * (1) On STM32F4, parameter available only on ADC instance: ADC1.\n - * (2) On devices STM32F42x and STM32F43x, limitation: this internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled. - * @retval None - */ -__STATIC_INLINE void LL_ADC_INJ_SetSequencerRanks(ADC_TypeDef *ADCx, uint32_t Rank, uint32_t Channel) -{ - /* Set bits with content of parameter "Channel" with bits position */ - /* in register depending on parameter "Rank". */ - /* Parameters "Rank" and "Channel" are used with masks because containing */ - /* other bits reserved for other purpose. */ - uint32_t tmpreg1 = (READ_BIT(ADCx->JSQR, ADC_JSQR_JL) >> ADC_JSQR_JL_Pos) + 1UL; - - MODIFY_REG(ADCx->JSQR, - ADC_CHANNEL_ID_NUMBER_MASK << (5UL * (uint8_t)(((Rank) + 3UL) - (tmpreg1))), - (Channel & ADC_CHANNEL_ID_NUMBER_MASK) << (5UL * (uint8_t)(((Rank) + 3UL) - (tmpreg1)))); -} - -/** - * @brief Get ADC group injected sequence: channel on the selected - * sequence rank. - * @note Depending on devices and packages, some channels may not be available. - * Refer to device datasheet for channels availability. - * @note Usage of the returned channel number: - * - To reinject this channel into another function LL_ADC_xxx: - * the returned channel number is only partly formatted on definition - * of literals LL_ADC_CHANNEL_x. Therefore, it has to be compared - * with parts of literals LL_ADC_CHANNEL_x or using - * helper macro @ref __LL_ADC_CHANNEL_TO_DECIMAL_NB(). - * Then the selected literal LL_ADC_CHANNEL_x can be used - * as parameter for another function. - * - To get the channel number in decimal format: - * process the returned value with the helper macro - * @ref __LL_ADC_CHANNEL_TO_DECIMAL_NB(). - * @rmtoll JSQR JSQ1 LL_ADC_INJ_SetSequencerRanks\n - * JSQR JSQ2 LL_ADC_INJ_SetSequencerRanks\n - * JSQR JSQ3 LL_ADC_INJ_SetSequencerRanks\n - * JSQR JSQ4 LL_ADC_INJ_SetSequencerRanks - * @param ADCx ADC instance - * @param Rank This parameter can be one of the following values: - * @arg @ref LL_ADC_INJ_RANK_1 - * @arg @ref LL_ADC_INJ_RANK_2 - * @arg @ref LL_ADC_INJ_RANK_3 - * @arg @ref LL_ADC_INJ_RANK_4 - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_CHANNEL_0 - * @arg @ref LL_ADC_CHANNEL_1 - * @arg @ref LL_ADC_CHANNEL_2 - * @arg @ref LL_ADC_CHANNEL_3 - * @arg @ref LL_ADC_CHANNEL_4 - * @arg @ref LL_ADC_CHANNEL_5 - * @arg @ref LL_ADC_CHANNEL_6 - * @arg @ref LL_ADC_CHANNEL_7 - * @arg @ref LL_ADC_CHANNEL_8 - * @arg @ref LL_ADC_CHANNEL_9 - * @arg @ref LL_ADC_CHANNEL_10 - * @arg @ref LL_ADC_CHANNEL_11 - * @arg @ref LL_ADC_CHANNEL_12 - * @arg @ref LL_ADC_CHANNEL_13 - * @arg @ref LL_ADC_CHANNEL_14 - * @arg @ref LL_ADC_CHANNEL_15 - * @arg @ref LL_ADC_CHANNEL_16 - * @arg @ref LL_ADC_CHANNEL_17 - * @arg @ref LL_ADC_CHANNEL_18 - * @arg @ref LL_ADC_CHANNEL_VREFINT (1) - * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)(2) - * @arg @ref LL_ADC_CHANNEL_VBAT (1) - * - * (1) On STM32F4, parameter available only on ADC instance: ADC1.\n - * (2) On devices STM32F42x and STM32F43x, limitation: this internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled.\n - * (1) For ADC channel read back from ADC register, - * comparison with internal channel parameter to be done - * using helper macro @ref __LL_ADC_CHANNEL_INTERNAL_TO_EXTERNAL(). - */ -__STATIC_INLINE uint32_t LL_ADC_INJ_GetSequencerRanks(ADC_TypeDef *ADCx, uint32_t Rank) -{ - uint32_t tmpreg1 = (READ_BIT(ADCx->JSQR, ADC_JSQR_JL) >> ADC_JSQR_JL_Pos) + 1UL; - - return (uint32_t)(READ_BIT(ADCx->JSQR, - ADC_CHANNEL_ID_NUMBER_MASK << (5UL * (uint8_t)(((Rank) + 3UL) - (tmpreg1)))) - >> (5UL * (uint8_t)(((Rank) + 3UL) - (tmpreg1))) - ); -} - -/** - * @brief Set ADC group injected conversion trigger: - * independent or from ADC group regular. - * @note This mode can be used to extend number of data registers - * updated after one ADC conversion trigger and with data - * permanently kept (not erased by successive conversions of scan of - * ADC sequencer ranks), up to 5 data registers: - * 1 data register on ADC group regular, 4 data registers - * on ADC group injected. - * @note If ADC group injected injected trigger source is set to an - * external trigger, this feature must be must be set to - * independent trigger. - * ADC group injected automatic trigger is compliant only with - * group injected trigger source set to SW start, without any - * further action on ADC group injected conversion start or stop: - * in this case, ADC group injected is controlled only - * from ADC group regular. - * @note It is not possible to enable both ADC group injected - * auto-injected mode and sequencer discontinuous mode. - * @rmtoll CR1 JAUTO LL_ADC_INJ_SetTrigAuto - * @param ADCx ADC instance - * @param TrigAuto This parameter can be one of the following values: - * @arg @ref LL_ADC_INJ_TRIG_INDEPENDENT - * @arg @ref LL_ADC_INJ_TRIG_FROM_GRP_REGULAR - * @retval None - */ -__STATIC_INLINE void LL_ADC_INJ_SetTrigAuto(ADC_TypeDef *ADCx, uint32_t TrigAuto) -{ - MODIFY_REG(ADCx->CR1, ADC_CR1_JAUTO, TrigAuto); -} - -/** - * @brief Get ADC group injected conversion trigger: - * independent or from ADC group regular. - * @rmtoll CR1 JAUTO LL_ADC_INJ_GetTrigAuto - * @param ADCx ADC instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_INJ_TRIG_INDEPENDENT - * @arg @ref LL_ADC_INJ_TRIG_FROM_GRP_REGULAR - */ -__STATIC_INLINE uint32_t LL_ADC_INJ_GetTrigAuto(ADC_TypeDef *ADCx) -{ - return (uint32_t)(READ_BIT(ADCx->CR1, ADC_CR1_JAUTO)); -} - -/** - * @brief Set ADC group injected offset. - * @note It sets: - * - ADC group injected rank to which the offset programmed - * will be applied - * - Offset level (offset to be subtracted from the raw - * converted data). - * Caution: Offset format is dependent to ADC resolution: - * offset has to be left-aligned on bit 11, the LSB (right bits) - * are set to 0. - * @note Offset cannot be enabled or disabled. - * To emulate offset disabled, set an offset value equal to 0. - * @rmtoll JOFR1 JOFFSET1 LL_ADC_INJ_SetOffset\n - * JOFR2 JOFFSET2 LL_ADC_INJ_SetOffset\n - * JOFR3 JOFFSET3 LL_ADC_INJ_SetOffset\n - * JOFR4 JOFFSET4 LL_ADC_INJ_SetOffset - * @param ADCx ADC instance - * @param Rank This parameter can be one of the following values: - * @arg @ref LL_ADC_INJ_RANK_1 - * @arg @ref LL_ADC_INJ_RANK_2 - * @arg @ref LL_ADC_INJ_RANK_3 - * @arg @ref LL_ADC_INJ_RANK_4 - * @param OffsetLevel Value between Min_Data=0x000 and Max_Data=0xFFF - * @retval None - */ -__STATIC_INLINE void LL_ADC_INJ_SetOffset(ADC_TypeDef *ADCx, uint32_t Rank, uint32_t OffsetLevel) -{ - __IO uint32_t *preg = __ADC_PTR_REG_OFFSET(ADCx->JOFR1, __ADC_MASK_SHIFT(Rank, ADC_INJ_JOFRX_REGOFFSET_MASK)); - - MODIFY_REG(*preg, - ADC_JOFR1_JOFFSET1, - OffsetLevel); -} - -/** - * @brief Get ADC group injected offset. - * @note It gives offset level (offset to be subtracted from the raw converted data). - * Caution: Offset format is dependent to ADC resolution: - * offset has to be left-aligned on bit 11, the LSB (right bits) - * are set to 0. - * @rmtoll JOFR1 JOFFSET1 LL_ADC_INJ_GetOffset\n - * JOFR2 JOFFSET2 LL_ADC_INJ_GetOffset\n - * JOFR3 JOFFSET3 LL_ADC_INJ_GetOffset\n - * JOFR4 JOFFSET4 LL_ADC_INJ_GetOffset - * @param ADCx ADC instance - * @param Rank This parameter can be one of the following values: - * @arg @ref LL_ADC_INJ_RANK_1 - * @arg @ref LL_ADC_INJ_RANK_2 - * @arg @ref LL_ADC_INJ_RANK_3 - * @arg @ref LL_ADC_INJ_RANK_4 - * @retval Value between Min_Data=0x000 and Max_Data=0xFFF - */ -__STATIC_INLINE uint32_t LL_ADC_INJ_GetOffset(ADC_TypeDef *ADCx, uint32_t Rank) -{ - __IO uint32_t *preg = __ADC_PTR_REG_OFFSET(ADCx->JOFR1, __ADC_MASK_SHIFT(Rank, ADC_INJ_JOFRX_REGOFFSET_MASK)); - - return (uint32_t)(READ_BIT(*preg, - ADC_JOFR1_JOFFSET1) - ); -} - -/** - * @} - */ - -/** @defgroup ADC_LL_EF_Configuration_Channels Configuration of ADC hierarchical scope: channels - * @{ - */ - -/** - * @brief Set sampling time of the selected ADC channel - * Unit: ADC clock cycles. - * @note On this device, sampling time is on channel scope: independently - * of channel mapped on ADC group regular or injected. - * @note In case of internal channel (VrefInt, TempSensor, ...) to be - * converted: - * sampling time constraints must be respected (sampling time can be - * adjusted in function of ADC clock frequency and sampling time - * setting). - * Refer to device datasheet for timings values (parameters TS_vrefint, - * TS_temp, ...). - * @note Conversion time is the addition of sampling time and processing time. - * Refer to reference manual for ADC processing time of - * this STM32 series. - * @note In case of ADC conversion of internal channel (VrefInt, - * temperature sensor, ...), a sampling time minimum value - * is required. - * Refer to device datasheet. - * @rmtoll SMPR1 SMP18 LL_ADC_SetChannelSamplingTime\n - * SMPR1 SMP17 LL_ADC_SetChannelSamplingTime\n - * SMPR1 SMP16 LL_ADC_SetChannelSamplingTime\n - * SMPR1 SMP15 LL_ADC_SetChannelSamplingTime\n - * SMPR1 SMP14 LL_ADC_SetChannelSamplingTime\n - * SMPR1 SMP13 LL_ADC_SetChannelSamplingTime\n - * SMPR1 SMP12 LL_ADC_SetChannelSamplingTime\n - * SMPR1 SMP11 LL_ADC_SetChannelSamplingTime\n - * SMPR1 SMP10 LL_ADC_SetChannelSamplingTime\n - * SMPR2 SMP9 LL_ADC_SetChannelSamplingTime\n - * SMPR2 SMP8 LL_ADC_SetChannelSamplingTime\n - * SMPR2 SMP7 LL_ADC_SetChannelSamplingTime\n - * SMPR2 SMP6 LL_ADC_SetChannelSamplingTime\n - * SMPR2 SMP5 LL_ADC_SetChannelSamplingTime\n - * SMPR2 SMP4 LL_ADC_SetChannelSamplingTime\n - * SMPR2 SMP3 LL_ADC_SetChannelSamplingTime\n - * SMPR2 SMP2 LL_ADC_SetChannelSamplingTime\n - * SMPR2 SMP1 LL_ADC_SetChannelSamplingTime\n - * SMPR2 SMP0 LL_ADC_SetChannelSamplingTime - * @param ADCx ADC instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_ADC_CHANNEL_0 - * @arg @ref LL_ADC_CHANNEL_1 - * @arg @ref LL_ADC_CHANNEL_2 - * @arg @ref LL_ADC_CHANNEL_3 - * @arg @ref LL_ADC_CHANNEL_4 - * @arg @ref LL_ADC_CHANNEL_5 - * @arg @ref LL_ADC_CHANNEL_6 - * @arg @ref LL_ADC_CHANNEL_7 - * @arg @ref LL_ADC_CHANNEL_8 - * @arg @ref LL_ADC_CHANNEL_9 - * @arg @ref LL_ADC_CHANNEL_10 - * @arg @ref LL_ADC_CHANNEL_11 - * @arg @ref LL_ADC_CHANNEL_12 - * @arg @ref LL_ADC_CHANNEL_13 - * @arg @ref LL_ADC_CHANNEL_14 - * @arg @ref LL_ADC_CHANNEL_15 - * @arg @ref LL_ADC_CHANNEL_16 - * @arg @ref LL_ADC_CHANNEL_17 - * @arg @ref LL_ADC_CHANNEL_18 - * @arg @ref LL_ADC_CHANNEL_VREFINT (1) - * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)(2) - * @arg @ref LL_ADC_CHANNEL_VBAT (1) - * - * (1) On STM32F4, parameter available only on ADC instance: ADC1.\n - * (2) On devices STM32F42x and STM32F43x, limitation: this internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled. - * @param SamplingTime This parameter can be one of the following values: - * @arg @ref LL_ADC_SAMPLINGTIME_3CYCLES - * @arg @ref LL_ADC_SAMPLINGTIME_15CYCLES - * @arg @ref LL_ADC_SAMPLINGTIME_28CYCLES - * @arg @ref LL_ADC_SAMPLINGTIME_56CYCLES - * @arg @ref LL_ADC_SAMPLINGTIME_84CYCLES - * @arg @ref LL_ADC_SAMPLINGTIME_112CYCLES - * @arg @ref LL_ADC_SAMPLINGTIME_144CYCLES - * @arg @ref LL_ADC_SAMPLINGTIME_480CYCLES - * @retval None - */ -__STATIC_INLINE void LL_ADC_SetChannelSamplingTime(ADC_TypeDef *ADCx, uint32_t Channel, uint32_t SamplingTime) -{ - /* Set bits with content of parameter "SamplingTime" with bits position */ - /* in register and register position depending on parameter "Channel". */ - /* Parameter "Channel" is used with masks because containing */ - /* other bits reserved for other purpose. */ - __IO uint32_t *preg = __ADC_PTR_REG_OFFSET(ADCx->SMPR1, __ADC_MASK_SHIFT(Channel, ADC_CHANNEL_SMPRX_REGOFFSET_MASK)); - - MODIFY_REG(*preg, - ADC_SMPR2_SMP0 << __ADC_MASK_SHIFT(Channel, ADC_CHANNEL_SMPx_BITOFFSET_MASK), - SamplingTime << __ADC_MASK_SHIFT(Channel, ADC_CHANNEL_SMPx_BITOFFSET_MASK)); -} - -/** - * @brief Get sampling time of the selected ADC channel - * Unit: ADC clock cycles. - * @note On this device, sampling time is on channel scope: independently - * of channel mapped on ADC group regular or injected. - * @note Conversion time is the addition of sampling time and processing time. - * Refer to reference manual for ADC processing time of - * this STM32 series. - * @rmtoll SMPR1 SMP18 LL_ADC_GetChannelSamplingTime\n - * SMPR1 SMP17 LL_ADC_GetChannelSamplingTime\n - * SMPR1 SMP16 LL_ADC_GetChannelSamplingTime\n - * SMPR1 SMP15 LL_ADC_GetChannelSamplingTime\n - * SMPR1 SMP14 LL_ADC_GetChannelSamplingTime\n - * SMPR1 SMP13 LL_ADC_GetChannelSamplingTime\n - * SMPR1 SMP12 LL_ADC_GetChannelSamplingTime\n - * SMPR1 SMP11 LL_ADC_GetChannelSamplingTime\n - * SMPR1 SMP10 LL_ADC_GetChannelSamplingTime\n - * SMPR2 SMP9 LL_ADC_GetChannelSamplingTime\n - * SMPR2 SMP8 LL_ADC_GetChannelSamplingTime\n - * SMPR2 SMP7 LL_ADC_GetChannelSamplingTime\n - * SMPR2 SMP6 LL_ADC_GetChannelSamplingTime\n - * SMPR2 SMP5 LL_ADC_GetChannelSamplingTime\n - * SMPR2 SMP4 LL_ADC_GetChannelSamplingTime\n - * SMPR2 SMP3 LL_ADC_GetChannelSamplingTime\n - * SMPR2 SMP2 LL_ADC_GetChannelSamplingTime\n - * SMPR2 SMP1 LL_ADC_GetChannelSamplingTime\n - * SMPR2 SMP0 LL_ADC_GetChannelSamplingTime - * @param ADCx ADC instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_ADC_CHANNEL_0 - * @arg @ref LL_ADC_CHANNEL_1 - * @arg @ref LL_ADC_CHANNEL_2 - * @arg @ref LL_ADC_CHANNEL_3 - * @arg @ref LL_ADC_CHANNEL_4 - * @arg @ref LL_ADC_CHANNEL_5 - * @arg @ref LL_ADC_CHANNEL_6 - * @arg @ref LL_ADC_CHANNEL_7 - * @arg @ref LL_ADC_CHANNEL_8 - * @arg @ref LL_ADC_CHANNEL_9 - * @arg @ref LL_ADC_CHANNEL_10 - * @arg @ref LL_ADC_CHANNEL_11 - * @arg @ref LL_ADC_CHANNEL_12 - * @arg @ref LL_ADC_CHANNEL_13 - * @arg @ref LL_ADC_CHANNEL_14 - * @arg @ref LL_ADC_CHANNEL_15 - * @arg @ref LL_ADC_CHANNEL_16 - * @arg @ref LL_ADC_CHANNEL_17 - * @arg @ref LL_ADC_CHANNEL_18 - * @arg @ref LL_ADC_CHANNEL_VREFINT (1) - * @arg @ref LL_ADC_CHANNEL_TEMPSENSOR (1)(2) - * @arg @ref LL_ADC_CHANNEL_VBAT (1) - * - * (1) On STM32F4, parameter available only on ADC instance: ADC1.\n - * (2) On devices STM32F42x and STM32F43x, limitation: this internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled. - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_SAMPLINGTIME_3CYCLES - * @arg @ref LL_ADC_SAMPLINGTIME_15CYCLES - * @arg @ref LL_ADC_SAMPLINGTIME_28CYCLES - * @arg @ref LL_ADC_SAMPLINGTIME_56CYCLES - * @arg @ref LL_ADC_SAMPLINGTIME_84CYCLES - * @arg @ref LL_ADC_SAMPLINGTIME_112CYCLES - * @arg @ref LL_ADC_SAMPLINGTIME_144CYCLES - * @arg @ref LL_ADC_SAMPLINGTIME_480CYCLES - */ -__STATIC_INLINE uint32_t LL_ADC_GetChannelSamplingTime(ADC_TypeDef *ADCx, uint32_t Channel) -{ - __IO uint32_t *preg = __ADC_PTR_REG_OFFSET(ADCx->SMPR1, __ADC_MASK_SHIFT(Channel, ADC_CHANNEL_SMPRX_REGOFFSET_MASK)); - - return (uint32_t)(READ_BIT(*preg, - ADC_SMPR2_SMP0 << __ADC_MASK_SHIFT(Channel, ADC_CHANNEL_SMPx_BITOFFSET_MASK)) - >> __ADC_MASK_SHIFT(Channel, ADC_CHANNEL_SMPx_BITOFFSET_MASK) - ); -} - -/** - * @} - */ - -/** @defgroup ADC_LL_EF_Configuration_ADC_AnalogWatchdog Configuration of ADC transversal scope: analog watchdog - * @{ - */ - -/** - * @brief Set ADC analog watchdog monitored channels: - * a single channel or all channels, - * on ADC groups regular and-or injected. - * @note Once monitored channels are selected, analog watchdog - * is enabled. - * @note In case of need to define a single channel to monitor - * with analog watchdog from sequencer channel definition, - * use helper macro @ref __LL_ADC_ANALOGWD_CHANNEL_GROUP(). - * @note On this STM32 series, there is only 1 kind of analog watchdog - * instance: - * - AWD standard (instance AWD1): - * - channels monitored: can monitor 1 channel or all channels. - * - groups monitored: ADC groups regular and-or injected. - * - resolution: resolution is not limited (corresponds to - * ADC resolution configured). - * @rmtoll CR1 AWD1CH LL_ADC_SetAnalogWDMonitChannels\n - * CR1 AWD1SGL LL_ADC_SetAnalogWDMonitChannels\n - * CR1 AWD1EN LL_ADC_SetAnalogWDMonitChannels - * @param ADCx ADC instance - * @param AWDChannelGroup This parameter can be one of the following values: - * @arg @ref LL_ADC_AWD_DISABLE - * @arg @ref LL_ADC_AWD_ALL_CHANNELS_REG - * @arg @ref LL_ADC_AWD_ALL_CHANNELS_INJ - * @arg @ref LL_ADC_AWD_ALL_CHANNELS_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_0_REG - * @arg @ref LL_ADC_AWD_CHANNEL_0_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_0_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_1_REG - * @arg @ref LL_ADC_AWD_CHANNEL_1_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_1_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_2_REG - * @arg @ref LL_ADC_AWD_CHANNEL_2_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_2_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_3_REG - * @arg @ref LL_ADC_AWD_CHANNEL_3_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_3_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_4_REG - * @arg @ref LL_ADC_AWD_CHANNEL_4_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_4_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_5_REG - * @arg @ref LL_ADC_AWD_CHANNEL_5_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_5_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_6_REG - * @arg @ref LL_ADC_AWD_CHANNEL_6_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_6_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_7_REG - * @arg @ref LL_ADC_AWD_CHANNEL_7_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_7_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_8_REG - * @arg @ref LL_ADC_AWD_CHANNEL_8_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_8_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_9_REG - * @arg @ref LL_ADC_AWD_CHANNEL_9_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_9_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_10_REG - * @arg @ref LL_ADC_AWD_CHANNEL_10_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_10_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_11_REG - * @arg @ref LL_ADC_AWD_CHANNEL_11_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_11_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_12_REG - * @arg @ref LL_ADC_AWD_CHANNEL_12_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_12_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_13_REG - * @arg @ref LL_ADC_AWD_CHANNEL_13_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_13_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_14_REG - * @arg @ref LL_ADC_AWD_CHANNEL_14_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_14_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_15_REG - * @arg @ref LL_ADC_AWD_CHANNEL_15_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_15_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_16_REG - * @arg @ref LL_ADC_AWD_CHANNEL_16_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_16_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_17_REG - * @arg @ref LL_ADC_AWD_CHANNEL_17_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_17_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_18_REG - * @arg @ref LL_ADC_AWD_CHANNEL_18_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_18_REG_INJ - * @arg @ref LL_ADC_AWD_CH_VREFINT_REG (1) - * @arg @ref LL_ADC_AWD_CH_VREFINT_INJ (1) - * @arg @ref LL_ADC_AWD_CH_VREFINT_REG_INJ (1) - * @arg @ref LL_ADC_AWD_CH_TEMPSENSOR_REG (1)(2) - * @arg @ref LL_ADC_AWD_CH_TEMPSENSOR_INJ (1)(2) - * @arg @ref LL_ADC_AWD_CH_TEMPSENSOR_REG_INJ (1)(2) - * @arg @ref LL_ADC_AWD_CH_VBAT_REG (1) - * @arg @ref LL_ADC_AWD_CH_VBAT_INJ (1) - * @arg @ref LL_ADC_AWD_CH_VBAT_REG_INJ (1) - * - * (1) On STM32F4, parameter available only on ADC instance: ADC1.\n - * (2) On devices STM32F42x and STM32F43x, limitation: this internal channel is shared between temperature sensor and Vbat, only 1 measurement path must be enabled. - * @retval None - */ -__STATIC_INLINE void LL_ADC_SetAnalogWDMonitChannels(ADC_TypeDef *ADCx, uint32_t AWDChannelGroup) -{ - MODIFY_REG(ADCx->CR1, - (ADC_CR1_AWDEN | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL | ADC_CR1_AWDCH), - AWDChannelGroup); -} - -/** - * @brief Get ADC analog watchdog monitored channel. - * @note Usage of the returned channel number: - * - To reinject this channel into another function LL_ADC_xxx: - * the returned channel number is only partly formatted on definition - * of literals LL_ADC_CHANNEL_x. Therefore, it has to be compared - * with parts of literals LL_ADC_CHANNEL_x or using - * helper macro @ref __LL_ADC_CHANNEL_TO_DECIMAL_NB(). - * Then the selected literal LL_ADC_CHANNEL_x can be used - * as parameter for another function. - * - To get the channel number in decimal format: - * process the returned value with the helper macro - * @ref __LL_ADC_CHANNEL_TO_DECIMAL_NB(). - * Applicable only when the analog watchdog is set to monitor - * one channel. - * @note On this STM32 series, there is only 1 kind of analog watchdog - * instance: - * - AWD standard (instance AWD1): - * - channels monitored: can monitor 1 channel or all channels. - * - groups monitored: ADC groups regular and-or injected. - * - resolution: resolution is not limited (corresponds to - * ADC resolution configured). - * @rmtoll CR1 AWD1CH LL_ADC_GetAnalogWDMonitChannels\n - * CR1 AWD1SGL LL_ADC_GetAnalogWDMonitChannels\n - * CR1 AWD1EN LL_ADC_GetAnalogWDMonitChannels - * @param ADCx ADC instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_AWD_DISABLE - * @arg @ref LL_ADC_AWD_ALL_CHANNELS_REG - * @arg @ref LL_ADC_AWD_ALL_CHANNELS_INJ - * @arg @ref LL_ADC_AWD_ALL_CHANNELS_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_0_REG - * @arg @ref LL_ADC_AWD_CHANNEL_0_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_0_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_1_REG - * @arg @ref LL_ADC_AWD_CHANNEL_1_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_1_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_2_REG - * @arg @ref LL_ADC_AWD_CHANNEL_2_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_2_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_3_REG - * @arg @ref LL_ADC_AWD_CHANNEL_3_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_3_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_4_REG - * @arg @ref LL_ADC_AWD_CHANNEL_4_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_4_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_5_REG - * @arg @ref LL_ADC_AWD_CHANNEL_5_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_5_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_6_REG - * @arg @ref LL_ADC_AWD_CHANNEL_6_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_6_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_7_REG - * @arg @ref LL_ADC_AWD_CHANNEL_7_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_7_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_8_REG - * @arg @ref LL_ADC_AWD_CHANNEL_8_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_8_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_9_REG - * @arg @ref LL_ADC_AWD_CHANNEL_9_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_9_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_10_REG - * @arg @ref LL_ADC_AWD_CHANNEL_10_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_10_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_11_REG - * @arg @ref LL_ADC_AWD_CHANNEL_11_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_11_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_12_REG - * @arg @ref LL_ADC_AWD_CHANNEL_12_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_12_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_13_REG - * @arg @ref LL_ADC_AWD_CHANNEL_13_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_13_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_14_REG - * @arg @ref LL_ADC_AWD_CHANNEL_14_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_14_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_15_REG - * @arg @ref LL_ADC_AWD_CHANNEL_15_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_15_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_16_REG - * @arg @ref LL_ADC_AWD_CHANNEL_16_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_16_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_17_REG - * @arg @ref LL_ADC_AWD_CHANNEL_17_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_17_REG_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_18_REG - * @arg @ref LL_ADC_AWD_CHANNEL_18_INJ - * @arg @ref LL_ADC_AWD_CHANNEL_18_REG_INJ - */ -__STATIC_INLINE uint32_t LL_ADC_GetAnalogWDMonitChannels(ADC_TypeDef *ADCx) -{ - return (uint32_t)(READ_BIT(ADCx->CR1, (ADC_CR1_AWDEN | ADC_CR1_JAWDEN | ADC_CR1_AWDSGL | ADC_CR1_AWDCH))); -} - -/** - * @brief Set ADC analog watchdog threshold value of threshold - * high or low. - * @note In case of ADC resolution different of 12 bits, - * analog watchdog thresholds data require a specific shift. - * Use helper macro @ref __LL_ADC_ANALOGWD_SET_THRESHOLD_RESOLUTION(). - * @note On this STM32 series, there is only 1 kind of analog watchdog - * instance: - * - AWD standard (instance AWD1): - * - channels monitored: can monitor 1 channel or all channels. - * - groups monitored: ADC groups regular and-or injected. - * - resolution: resolution is not limited (corresponds to - * ADC resolution configured). - * @rmtoll HTR HT LL_ADC_SetAnalogWDThresholds\n - * LTR LT LL_ADC_SetAnalogWDThresholds - * @param ADCx ADC instance - * @param AWDThresholdsHighLow This parameter can be one of the following values: - * @arg @ref LL_ADC_AWD_THRESHOLD_HIGH - * @arg @ref LL_ADC_AWD_THRESHOLD_LOW - * @param AWDThresholdValue Value between Min_Data=0x000 and Max_Data=0xFFF - * @retval None - */ -__STATIC_INLINE void LL_ADC_SetAnalogWDThresholds(ADC_TypeDef *ADCx, uint32_t AWDThresholdsHighLow, uint32_t AWDThresholdValue) -{ - __IO uint32_t *preg = __ADC_PTR_REG_OFFSET(ADCx->HTR, AWDThresholdsHighLow); - - MODIFY_REG(*preg, - ADC_HTR_HT, - AWDThresholdValue); -} - -/** - * @brief Get ADC analog watchdog threshold value of threshold high or - * threshold low. - * @note In case of ADC resolution different of 12 bits, - * analog watchdog thresholds data require a specific shift. - * Use helper macro @ref __LL_ADC_ANALOGWD_GET_THRESHOLD_RESOLUTION(). - * @rmtoll HTR HT LL_ADC_GetAnalogWDThresholds\n - * LTR LT LL_ADC_GetAnalogWDThresholds - * @param ADCx ADC instance - * @param AWDThresholdsHighLow This parameter can be one of the following values: - * @arg @ref LL_ADC_AWD_THRESHOLD_HIGH - * @arg @ref LL_ADC_AWD_THRESHOLD_LOW - * @retval Value between Min_Data=0x000 and Max_Data=0xFFF -*/ -__STATIC_INLINE uint32_t LL_ADC_GetAnalogWDThresholds(ADC_TypeDef *ADCx, uint32_t AWDThresholdsHighLow) -{ - __IO uint32_t *preg = __ADC_PTR_REG_OFFSET(ADCx->HTR, AWDThresholdsHighLow); - - return (uint32_t)(READ_BIT(*preg, ADC_HTR_HT)); -} - -/** - * @} - */ - -/** @defgroup ADC_LL_EF_Configuration_ADC_Multimode Configuration of ADC hierarchical scope: multimode - * @{ - */ - -#if defined(ADC_MULTIMODE_SUPPORT) -/** - * @brief Set ADC multimode configuration to operate in independent mode - * or multimode (for devices with several ADC instances). - * @note If multimode configuration: the selected ADC instance is - * either master or slave depending on hardware. - * Refer to reference manual. - * @rmtoll CCR MULTI LL_ADC_SetMultimode - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @param Multimode This parameter can be one of the following values: - * @arg @ref LL_ADC_MULTI_INDEPENDENT - * @arg @ref LL_ADC_MULTI_DUAL_REG_SIMULT - * @arg @ref LL_ADC_MULTI_DUAL_REG_INTERL - * @arg @ref LL_ADC_MULTI_DUAL_INJ_SIMULT - * @arg @ref LL_ADC_MULTI_DUAL_INJ_ALTERN - * @arg @ref LL_ADC_MULTI_DUAL_REG_SIM_INJ_SIM - * @arg @ref LL_ADC_MULTI_DUAL_REG_SIM_INJ_ALT - * @arg @ref LL_ADC_MULTI_DUAL_REG_INT_INJ_SIM - * @arg @ref LL_ADC_MULTI_TRIPLE_REG_SIM_INJ_SIM - * @arg @ref LL_ADC_MULTI_TRIPLE_REG_SIM_INJ_ALT - * @arg @ref LL_ADC_MULTI_TRIPLE_INJ_SIMULT - * @arg @ref LL_ADC_MULTI_TRIPLE_REG_SIMULT - * @arg @ref LL_ADC_MULTI_TRIPLE_REG_INTERL - * @arg @ref LL_ADC_MULTI_TRIPLE_INJ_ALTERN - * @retval None - */ -__STATIC_INLINE void LL_ADC_SetMultimode(ADC_Common_TypeDef *ADCxy_COMMON, uint32_t Multimode) -{ - MODIFY_REG(ADCxy_COMMON->CCR, ADC_CCR_MULTI, Multimode); -} - -/** - * @brief Get ADC multimode configuration to operate in independent mode - * or multimode (for devices with several ADC instances). - * @note If multimode configuration: the selected ADC instance is - * either master or slave depending on hardware. - * Refer to reference manual. - * @rmtoll CCR MULTI LL_ADC_GetMultimode - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_MULTI_INDEPENDENT - * @arg @ref LL_ADC_MULTI_DUAL_REG_SIMULT - * @arg @ref LL_ADC_MULTI_DUAL_REG_INTERL - * @arg @ref LL_ADC_MULTI_DUAL_INJ_SIMULT - * @arg @ref LL_ADC_MULTI_DUAL_INJ_ALTERN - * @arg @ref LL_ADC_MULTI_DUAL_REG_SIM_INJ_SIM - * @arg @ref LL_ADC_MULTI_DUAL_REG_SIM_INJ_ALT - * @arg @ref LL_ADC_MULTI_DUAL_REG_INT_INJ_SIM - * @arg @ref LL_ADC_MULTI_TRIPLE_REG_SIM_INJ_SIM - * @arg @ref LL_ADC_MULTI_TRIPLE_REG_SIM_INJ_ALT - * @arg @ref LL_ADC_MULTI_TRIPLE_INJ_SIMULT - * @arg @ref LL_ADC_MULTI_TRIPLE_REG_SIMULT - * @arg @ref LL_ADC_MULTI_TRIPLE_REG_INTERL - * @arg @ref LL_ADC_MULTI_TRIPLE_INJ_ALTERN - */ -__STATIC_INLINE uint32_t LL_ADC_GetMultimode(ADC_Common_TypeDef *ADCxy_COMMON) -{ - return (uint32_t)(READ_BIT(ADCxy_COMMON->CCR, ADC_CCR_MULTI)); -} - -/** - * @brief Set ADC multimode conversion data transfer: no transfer - * or transfer by DMA. - * @note If ADC multimode transfer by DMA is not selected: - * each ADC uses its own DMA channel, with its individual - * DMA transfer settings. - * If ADC multimode transfer by DMA is selected: - * One DMA channel is used for both ADC (DMA of ADC master) - * Specifies the DMA requests mode: - * - Limited mode (One shot mode): DMA transfer requests are stopped - * when number of DMA data transfers (number of - * ADC conversions) is reached. - * This ADC mode is intended to be used with DMA mode non-circular. - * - Unlimited mode: DMA transfer requests are unlimited, - * whatever number of DMA data transfers (number of - * ADC conversions). - * This ADC mode is intended to be used with DMA mode circular. - * @note If ADC DMA requests mode is set to unlimited and DMA is set to - * mode non-circular: - * when DMA transfers size will be reached, DMA will stop transfers of - * ADC conversions data ADC will raise an overrun error - * (overrun flag and interruption if enabled). - * @note How to retrieve multimode conversion data: - * Whatever multimode transfer by DMA setting: using function - * @ref LL_ADC_REG_ReadMultiConversionData32(). - * If ADC multimode transfer by DMA is selected: conversion data - * is a raw data with ADC master and slave concatenated. - * A macro is available to get the conversion data of - * ADC master or ADC slave: see helper macro - * @ref __LL_ADC_MULTI_CONV_DATA_MASTER_SLAVE(). - * @rmtoll CCR MDMA LL_ADC_SetMultiDMATransfer\n - * CCR DDS LL_ADC_SetMultiDMATransfer - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @param MultiDMATransfer This parameter can be one of the following values: - * @arg @ref LL_ADC_MULTI_REG_DMA_EACH_ADC - * @arg @ref LL_ADC_MULTI_REG_DMA_LIMIT_1 - * @arg @ref LL_ADC_MULTI_REG_DMA_LIMIT_2 - * @arg @ref LL_ADC_MULTI_REG_DMA_LIMIT_3 - * @arg @ref LL_ADC_MULTI_REG_DMA_UNLMT_1 - * @arg @ref LL_ADC_MULTI_REG_DMA_UNLMT_2 - * @arg @ref LL_ADC_MULTI_REG_DMA_UNLMT_3 - * @retval None - */ -__STATIC_INLINE void LL_ADC_SetMultiDMATransfer(ADC_Common_TypeDef *ADCxy_COMMON, uint32_t MultiDMATransfer) -{ - MODIFY_REG(ADCxy_COMMON->CCR, ADC_CCR_DMA | ADC_CCR_DDS, MultiDMATransfer); -} - -/** - * @brief Get ADC multimode conversion data transfer: no transfer - * or transfer by DMA. - * @note If ADC multimode transfer by DMA is not selected: - * each ADC uses its own DMA channel, with its individual - * DMA transfer settings. - * If ADC multimode transfer by DMA is selected: - * One DMA channel is used for both ADC (DMA of ADC master) - * Specifies the DMA requests mode: - * - Limited mode (One shot mode): DMA transfer requests are stopped - * when number of DMA data transfers (number of - * ADC conversions) is reached. - * This ADC mode is intended to be used with DMA mode non-circular. - * - Unlimited mode: DMA transfer requests are unlimited, - * whatever number of DMA data transfers (number of - * ADC conversions). - * This ADC mode is intended to be used with DMA mode circular. - * @note If ADC DMA requests mode is set to unlimited and DMA is set to - * mode non-circular: - * when DMA transfers size will be reached, DMA will stop transfers of - * ADC conversions data ADC will raise an overrun error - * (overrun flag and interruption if enabled). - * @note How to retrieve multimode conversion data: - * Whatever multimode transfer by DMA setting: using function - * @ref LL_ADC_REG_ReadMultiConversionData32(). - * If ADC multimode transfer by DMA is selected: conversion data - * is a raw data with ADC master and slave concatenated. - * A macro is available to get the conversion data of - * ADC master or ADC slave: see helper macro - * @ref __LL_ADC_MULTI_CONV_DATA_MASTER_SLAVE(). - * @rmtoll CCR MDMA LL_ADC_GetMultiDMATransfer\n - * CCR DDS LL_ADC_GetMultiDMATransfer - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_MULTI_REG_DMA_EACH_ADC - * @arg @ref LL_ADC_MULTI_REG_DMA_LIMIT_1 - * @arg @ref LL_ADC_MULTI_REG_DMA_LIMIT_2 - * @arg @ref LL_ADC_MULTI_REG_DMA_LIMIT_3 - * @arg @ref LL_ADC_MULTI_REG_DMA_UNLMT_1 - * @arg @ref LL_ADC_MULTI_REG_DMA_UNLMT_2 - * @arg @ref LL_ADC_MULTI_REG_DMA_UNLMT_3 - */ -__STATIC_INLINE uint32_t LL_ADC_GetMultiDMATransfer(ADC_Common_TypeDef *ADCxy_COMMON) -{ - return (uint32_t)(READ_BIT(ADCxy_COMMON->CCR, ADC_CCR_DMA | ADC_CCR_DDS)); -} - -/** - * @brief Set ADC multimode delay between 2 sampling phases. - * @note The sampling delay range depends on ADC resolution: - * - ADC resolution 12 bits can have maximum delay of 12 cycles. - * - ADC resolution 10 bits can have maximum delay of 10 cycles. - * - ADC resolution 8 bits can have maximum delay of 8 cycles. - * - ADC resolution 6 bits can have maximum delay of 6 cycles. - * @rmtoll CCR DELAY LL_ADC_SetMultiTwoSamplingDelay - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @param MultiTwoSamplingDelay This parameter can be one of the following values: - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_5CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_6CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_7CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_8CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_9CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_10CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_11CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_12CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_13CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_14CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_15CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_16CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_17CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_18CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_19CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_20CYCLES - * @retval None - */ -__STATIC_INLINE void LL_ADC_SetMultiTwoSamplingDelay(ADC_Common_TypeDef *ADCxy_COMMON, uint32_t MultiTwoSamplingDelay) -{ - MODIFY_REG(ADCxy_COMMON->CCR, ADC_CCR_DELAY, MultiTwoSamplingDelay); -} - -/** - * @brief Get ADC multimode delay between 2 sampling phases. - * @rmtoll CCR DELAY LL_ADC_GetMultiTwoSamplingDelay - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @retval Returned value can be one of the following values: - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_5CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_6CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_7CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_8CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_9CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_10CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_11CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_12CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_13CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_14CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_15CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_16CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_17CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_18CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_19CYCLES - * @arg @ref LL_ADC_MULTI_TWOSMP_DELAY_20CYCLES - */ -__STATIC_INLINE uint32_t LL_ADC_GetMultiTwoSamplingDelay(ADC_Common_TypeDef *ADCxy_COMMON) -{ - return (uint32_t)(READ_BIT(ADCxy_COMMON->CCR, ADC_CCR_DELAY)); -} -#endif /* ADC_MULTIMODE_SUPPORT */ - -/** - * @} - */ -/** @defgroup ADC_LL_EF_Operation_ADC_Instance Operation on ADC hierarchical scope: ADC instance - * @{ - */ - -/** - * @brief Enable the selected ADC instance. - * @note On this STM32 series, after ADC enable, a delay for - * ADC internal analog stabilization is required before performing a - * ADC conversion start. - * Refer to device datasheet, parameter tSTAB. - * @rmtoll CR2 ADON LL_ADC_Enable - * @param ADCx ADC instance - * @retval None - */ -__STATIC_INLINE void LL_ADC_Enable(ADC_TypeDef *ADCx) -{ - SET_BIT(ADCx->CR2, ADC_CR2_ADON); -} - -/** - * @brief Disable the selected ADC instance. - * @rmtoll CR2 ADON LL_ADC_Disable - * @param ADCx ADC instance - * @retval None - */ -__STATIC_INLINE void LL_ADC_Disable(ADC_TypeDef *ADCx) -{ - CLEAR_BIT(ADCx->CR2, ADC_CR2_ADON); -} - -/** - * @brief Get the selected ADC instance enable state. - * @rmtoll CR2 ADON LL_ADC_IsEnabled - * @param ADCx ADC instance - * @retval 0: ADC is disabled, 1: ADC is enabled. - */ -__STATIC_INLINE uint32_t LL_ADC_IsEnabled(ADC_TypeDef *ADCx) -{ - return (READ_BIT(ADCx->CR2, ADC_CR2_ADON) == (ADC_CR2_ADON)); -} - -/** - * @} - */ - -/** @defgroup ADC_LL_EF_Operation_ADC_Group_Regular Operation on ADC hierarchical scope: group regular - * @{ - */ - -/** - * @brief Start ADC group regular conversion. - * @note On this STM32 series, this function is relevant only for - * internal trigger (SW start), not for external trigger: - * - If ADC trigger has been set to software start, ADC conversion - * starts immediately. - * - If ADC trigger has been set to external trigger, ADC conversion - * start must be performed using function - * @ref LL_ADC_REG_StartConversionExtTrig(). - * (if external trigger edge would have been set during ADC other - * settings, ADC conversion would start at trigger event - * as soon as ADC is enabled). - * @rmtoll CR2 SWSTART LL_ADC_REG_StartConversionSWStart - * @param ADCx ADC instance - * @retval None - */ -__STATIC_INLINE void LL_ADC_REG_StartConversionSWStart(ADC_TypeDef *ADCx) -{ - SET_BIT(ADCx->CR2, ADC_CR2_SWSTART); -} - -/** - * @brief Start ADC group regular conversion from external trigger. - * @note ADC conversion will start at next trigger event (on the selected - * trigger edge) following the ADC start conversion command. - * @note On this STM32 series, this function is relevant for - * ADC conversion start from external trigger. - * If internal trigger (SW start) is needed, perform ADC conversion - * start using function @ref LL_ADC_REG_StartConversionSWStart(). - * @rmtoll CR2 EXTEN LL_ADC_REG_StartConversionExtTrig - * @param ExternalTriggerEdge This parameter can be one of the following values: - * @arg @ref LL_ADC_REG_TRIG_EXT_RISING - * @arg @ref LL_ADC_REG_TRIG_EXT_FALLING - * @arg @ref LL_ADC_REG_TRIG_EXT_RISINGFALLING - * @param ADCx ADC instance - * @retval None - */ -__STATIC_INLINE void LL_ADC_REG_StartConversionExtTrig(ADC_TypeDef *ADCx, uint32_t ExternalTriggerEdge) -{ - SET_BIT(ADCx->CR2, ExternalTriggerEdge); -} - -/** - * @brief Stop ADC group regular conversion from external trigger. - * @note No more ADC conversion will start at next trigger event - * following the ADC stop conversion command. - * If a conversion is on-going, it will be completed. - * @note On this STM32 series, there is no specific command - * to stop a conversion on-going or to stop ADC converting - * in continuous mode. These actions can be performed - * using function @ref LL_ADC_Disable(). - * @rmtoll CR2 EXTEN LL_ADC_REG_StopConversionExtTrig - * @param ADCx ADC instance - * @retval None - */ -__STATIC_INLINE void LL_ADC_REG_StopConversionExtTrig(ADC_TypeDef *ADCx) -{ - CLEAR_BIT(ADCx->CR2, ADC_CR2_EXTEN); -} - -/** - * @brief Get ADC group regular conversion data, range fit for - * all ADC configurations: all ADC resolutions and - * all oversampling increased data width (for devices - * with feature oversampling). - * @rmtoll DR RDATA LL_ADC_REG_ReadConversionData32 - * @param ADCx ADC instance - * @retval Value between Min_Data=0x00000000 and Max_Data=0xFFFFFFFF - */ -__STATIC_INLINE uint32_t LL_ADC_REG_ReadConversionData32(ADC_TypeDef *ADCx) -{ - return (uint16_t)(READ_BIT(ADCx->DR, ADC_DR_DATA)); -} - -/** - * @brief Get ADC group regular conversion data, range fit for - * ADC resolution 12 bits. - * @note For devices with feature oversampling: Oversampling - * can increase data width, function for extended range - * may be needed: @ref LL_ADC_REG_ReadConversionData32. - * @rmtoll DR RDATA LL_ADC_REG_ReadConversionData12 - * @param ADCx ADC instance - * @retval Value between Min_Data=0x000 and Max_Data=0xFFF - */ -__STATIC_INLINE uint16_t LL_ADC_REG_ReadConversionData12(ADC_TypeDef *ADCx) -{ - return (uint16_t)(READ_BIT(ADCx->DR, ADC_DR_DATA)); -} - -/** - * @brief Get ADC group regular conversion data, range fit for - * ADC resolution 10 bits. - * @note For devices with feature oversampling: Oversampling - * can increase data width, function for extended range - * may be needed: @ref LL_ADC_REG_ReadConversionData32. - * @rmtoll DR RDATA LL_ADC_REG_ReadConversionData10 - * @param ADCx ADC instance - * @retval Value between Min_Data=0x000 and Max_Data=0x3FF - */ -__STATIC_INLINE uint16_t LL_ADC_REG_ReadConversionData10(ADC_TypeDef *ADCx) -{ - return (uint16_t)(READ_BIT(ADCx->DR, ADC_DR_DATA)); -} - -/** - * @brief Get ADC group regular conversion data, range fit for - * ADC resolution 8 bits. - * @note For devices with feature oversampling: Oversampling - * can increase data width, function for extended range - * may be needed: @ref LL_ADC_REG_ReadConversionData32. - * @rmtoll DR RDATA LL_ADC_REG_ReadConversionData8 - * @param ADCx ADC instance - * @retval Value between Min_Data=0x00 and Max_Data=0xFF - */ -__STATIC_INLINE uint8_t LL_ADC_REG_ReadConversionData8(ADC_TypeDef *ADCx) -{ - return (uint16_t)(READ_BIT(ADCx->DR, ADC_DR_DATA)); -} - -/** - * @brief Get ADC group regular conversion data, range fit for - * ADC resolution 6 bits. - * @note For devices with feature oversampling: Oversampling - * can increase data width, function for extended range - * may be needed: @ref LL_ADC_REG_ReadConversionData32. - * @rmtoll DR RDATA LL_ADC_REG_ReadConversionData6 - * @param ADCx ADC instance - * @retval Value between Min_Data=0x00 and Max_Data=0x3F - */ -__STATIC_INLINE uint8_t LL_ADC_REG_ReadConversionData6(ADC_TypeDef *ADCx) -{ - return (uint16_t)(READ_BIT(ADCx->DR, ADC_DR_DATA)); -} - -#if defined(ADC_MULTIMODE_SUPPORT) -/** - * @brief Get ADC multimode conversion data of ADC master, ADC slave - * or raw data with ADC master and slave concatenated. - * @note If raw data with ADC master and slave concatenated is retrieved, - * a macro is available to get the conversion data of - * ADC master or ADC slave: see helper macro - * @ref __LL_ADC_MULTI_CONV_DATA_MASTER_SLAVE(). - * (however this macro is mainly intended for multimode - * transfer by DMA, because this function can do the same - * by getting multimode conversion data of ADC master or ADC slave - * separately). - * @rmtoll CDR DATA1 LL_ADC_REG_ReadMultiConversionData32\n - * CDR DATA2 LL_ADC_REG_ReadMultiConversionData32 - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @param ConversionData This parameter can be one of the following values: - * @arg @ref LL_ADC_MULTI_MASTER - * @arg @ref LL_ADC_MULTI_SLAVE - * @arg @ref LL_ADC_MULTI_MASTER_SLAVE - * @retval Value between Min_Data=0x00000000 and Max_Data=0xFFFFFFFF - */ -__STATIC_INLINE uint32_t LL_ADC_REG_ReadMultiConversionData32(ADC_Common_TypeDef *ADCxy_COMMON, uint32_t ConversionData) -{ - return (uint32_t)(READ_BIT(ADCxy_COMMON->CDR, - ADC_DR_ADC2DATA) - >> POSITION_VAL(ConversionData) - ); -} -#endif /* ADC_MULTIMODE_SUPPORT */ - -/** - * @} - */ - -/** @defgroup ADC_LL_EF_Operation_ADC_Group_Injected Operation on ADC hierarchical scope: group injected - * @{ - */ - -/** - * @brief Start ADC group injected conversion. - * @note On this STM32 series, this function is relevant only for - * internal trigger (SW start), not for external trigger: - * - If ADC trigger has been set to software start, ADC conversion - * starts immediately. - * - If ADC trigger has been set to external trigger, ADC conversion - * start must be performed using function - * @ref LL_ADC_INJ_StartConversionExtTrig(). - * (if external trigger edge would have been set during ADC other - * settings, ADC conversion would start at trigger event - * as soon as ADC is enabled). - * @rmtoll CR2 JSWSTART LL_ADC_INJ_StartConversionSWStart - * @param ADCx ADC instance - * @retval None - */ -__STATIC_INLINE void LL_ADC_INJ_StartConversionSWStart(ADC_TypeDef *ADCx) -{ - SET_BIT(ADCx->CR2, ADC_CR2_JSWSTART); -} - -/** - * @brief Start ADC group injected conversion from external trigger. - * @note ADC conversion will start at next trigger event (on the selected - * trigger edge) following the ADC start conversion command. - * @note On this STM32 series, this function is relevant for - * ADC conversion start from external trigger. - * If internal trigger (SW start) is needed, perform ADC conversion - * start using function @ref LL_ADC_INJ_StartConversionSWStart(). - * @rmtoll CR2 JEXTEN LL_ADC_INJ_StartConversionExtTrig - * @param ExternalTriggerEdge This parameter can be one of the following values: - * @arg @ref LL_ADC_INJ_TRIG_EXT_RISING - * @arg @ref LL_ADC_INJ_TRIG_EXT_FALLING - * @arg @ref LL_ADC_INJ_TRIG_EXT_RISINGFALLING - * @param ADCx ADC instance - * @retval None - */ -__STATIC_INLINE void LL_ADC_INJ_StartConversionExtTrig(ADC_TypeDef *ADCx, uint32_t ExternalTriggerEdge) -{ - SET_BIT(ADCx->CR2, ExternalTriggerEdge); -} - -/** - * @brief Stop ADC group injected conversion from external trigger. - * @note No more ADC conversion will start at next trigger event - * following the ADC stop conversion command. - * If a conversion is on-going, it will be completed. - * @note On this STM32 series, there is no specific command - * to stop a conversion on-going or to stop ADC converting - * in continuous mode. These actions can be performed - * using function @ref LL_ADC_Disable(). - * @rmtoll CR2 JEXTEN LL_ADC_INJ_StopConversionExtTrig - * @param ADCx ADC instance - * @retval None - */ -__STATIC_INLINE void LL_ADC_INJ_StopConversionExtTrig(ADC_TypeDef *ADCx) -{ - CLEAR_BIT(ADCx->CR2, ADC_CR2_JEXTEN); -} - -/** - * @brief Get ADC group regular conversion data, range fit for - * all ADC configurations: all ADC resolutions and - * all oversampling increased data width (for devices - * with feature oversampling). - * @rmtoll JDR1 JDATA LL_ADC_INJ_ReadConversionData32\n - * JDR2 JDATA LL_ADC_INJ_ReadConversionData32\n - * JDR3 JDATA LL_ADC_INJ_ReadConversionData32\n - * JDR4 JDATA LL_ADC_INJ_ReadConversionData32 - * @param ADCx ADC instance - * @param Rank This parameter can be one of the following values: - * @arg @ref LL_ADC_INJ_RANK_1 - * @arg @ref LL_ADC_INJ_RANK_2 - * @arg @ref LL_ADC_INJ_RANK_3 - * @arg @ref LL_ADC_INJ_RANK_4 - * @retval Value between Min_Data=0x00000000 and Max_Data=0xFFFFFFFF - */ -__STATIC_INLINE uint32_t LL_ADC_INJ_ReadConversionData32(ADC_TypeDef *ADCx, uint32_t Rank) -{ - __IO uint32_t *preg = __ADC_PTR_REG_OFFSET(ADCx->JDR1, __ADC_MASK_SHIFT(Rank, ADC_INJ_JDRX_REGOFFSET_MASK)); - - return (uint32_t)(READ_BIT(*preg, - ADC_JDR1_JDATA) - ); -} - -/** - * @brief Get ADC group injected conversion data, range fit for - * ADC resolution 12 bits. - * @note For devices with feature oversampling: Oversampling - * can increase data width, function for extended range - * may be needed: @ref LL_ADC_INJ_ReadConversionData32. - * @rmtoll JDR1 JDATA LL_ADC_INJ_ReadConversionData12\n - * JDR2 JDATA LL_ADC_INJ_ReadConversionData12\n - * JDR3 JDATA LL_ADC_INJ_ReadConversionData12\n - * JDR4 JDATA LL_ADC_INJ_ReadConversionData12 - * @param ADCx ADC instance - * @param Rank This parameter can be one of the following values: - * @arg @ref LL_ADC_INJ_RANK_1 - * @arg @ref LL_ADC_INJ_RANK_2 - * @arg @ref LL_ADC_INJ_RANK_3 - * @arg @ref LL_ADC_INJ_RANK_4 - * @retval Value between Min_Data=0x000 and Max_Data=0xFFF - */ -__STATIC_INLINE uint16_t LL_ADC_INJ_ReadConversionData12(ADC_TypeDef *ADCx, uint32_t Rank) -{ - __IO uint32_t *preg = __ADC_PTR_REG_OFFSET(ADCx->JDR1, __ADC_MASK_SHIFT(Rank, ADC_INJ_JDRX_REGOFFSET_MASK)); - - return (uint16_t)(READ_BIT(*preg, - ADC_JDR1_JDATA) - ); -} - -/** - * @brief Get ADC group injected conversion data, range fit for - * ADC resolution 10 bits. - * @note For devices with feature oversampling: Oversampling - * can increase data width, function for extended range - * may be needed: @ref LL_ADC_INJ_ReadConversionData32. - * @rmtoll JDR1 JDATA LL_ADC_INJ_ReadConversionData10\n - * JDR2 JDATA LL_ADC_INJ_ReadConversionData10\n - * JDR3 JDATA LL_ADC_INJ_ReadConversionData10\n - * JDR4 JDATA LL_ADC_INJ_ReadConversionData10 - * @param ADCx ADC instance - * @param Rank This parameter can be one of the following values: - * @arg @ref LL_ADC_INJ_RANK_1 - * @arg @ref LL_ADC_INJ_RANK_2 - * @arg @ref LL_ADC_INJ_RANK_3 - * @arg @ref LL_ADC_INJ_RANK_4 - * @retval Value between Min_Data=0x000 and Max_Data=0x3FF - */ -__STATIC_INLINE uint16_t LL_ADC_INJ_ReadConversionData10(ADC_TypeDef *ADCx, uint32_t Rank) -{ - __IO uint32_t *preg = __ADC_PTR_REG_OFFSET(ADCx->JDR1, __ADC_MASK_SHIFT(Rank, ADC_INJ_JDRX_REGOFFSET_MASK)); - - return (uint16_t)(READ_BIT(*preg, - ADC_JDR1_JDATA) - ); -} - -/** - * @brief Get ADC group injected conversion data, range fit for - * ADC resolution 8 bits. - * @note For devices with feature oversampling: Oversampling - * can increase data width, function for extended range - * may be needed: @ref LL_ADC_INJ_ReadConversionData32. - * @rmtoll JDR1 JDATA LL_ADC_INJ_ReadConversionData8\n - * JDR2 JDATA LL_ADC_INJ_ReadConversionData8\n - * JDR3 JDATA LL_ADC_INJ_ReadConversionData8\n - * JDR4 JDATA LL_ADC_INJ_ReadConversionData8 - * @param ADCx ADC instance - * @param Rank This parameter can be one of the following values: - * @arg @ref LL_ADC_INJ_RANK_1 - * @arg @ref LL_ADC_INJ_RANK_2 - * @arg @ref LL_ADC_INJ_RANK_3 - * @arg @ref LL_ADC_INJ_RANK_4 - * @retval Value between Min_Data=0x00 and Max_Data=0xFF - */ -__STATIC_INLINE uint8_t LL_ADC_INJ_ReadConversionData8(ADC_TypeDef *ADCx, uint32_t Rank) -{ - __IO uint32_t *preg = __ADC_PTR_REG_OFFSET(ADCx->JDR1, __ADC_MASK_SHIFT(Rank, ADC_INJ_JDRX_REGOFFSET_MASK)); - - return (uint8_t)(READ_BIT(*preg, - ADC_JDR1_JDATA) - ); -} - -/** - * @brief Get ADC group injected conversion data, range fit for - * ADC resolution 6 bits. - * @note For devices with feature oversampling: Oversampling - * can increase data width, function for extended range - * may be needed: @ref LL_ADC_INJ_ReadConversionData32. - * @rmtoll JDR1 JDATA LL_ADC_INJ_ReadConversionData6\n - * JDR2 JDATA LL_ADC_INJ_ReadConversionData6\n - * JDR3 JDATA LL_ADC_INJ_ReadConversionData6\n - * JDR4 JDATA LL_ADC_INJ_ReadConversionData6 - * @param ADCx ADC instance - * @param Rank This parameter can be one of the following values: - * @arg @ref LL_ADC_INJ_RANK_1 - * @arg @ref LL_ADC_INJ_RANK_2 - * @arg @ref LL_ADC_INJ_RANK_3 - * @arg @ref LL_ADC_INJ_RANK_4 - * @retval Value between Min_Data=0x00 and Max_Data=0x3F - */ -__STATIC_INLINE uint8_t LL_ADC_INJ_ReadConversionData6(ADC_TypeDef *ADCx, uint32_t Rank) -{ - __IO uint32_t *preg = __ADC_PTR_REG_OFFSET(ADCx->JDR1, __ADC_MASK_SHIFT(Rank, ADC_INJ_JDRX_REGOFFSET_MASK)); - - return (uint8_t)(READ_BIT(*preg, - ADC_JDR1_JDATA) - ); -} - -/** - * @} - */ - -/** @defgroup ADC_LL_EF_FLAG_Management ADC flag management - * @{ - */ - -/** - * @brief Get flag ADC group regular end of unitary conversion - * or end of sequence conversions, depending on - * ADC configuration. - * @note To configure flag of end of conversion, - * use function @ref LL_ADC_REG_SetFlagEndOfConversion(). - * @rmtoll SR EOC LL_ADC_IsActiveFlag_EOCS - * @param ADCx ADC instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_EOCS(ADC_TypeDef *ADCx) -{ - return (READ_BIT(ADCx->SR, LL_ADC_FLAG_EOCS) == (LL_ADC_FLAG_EOCS)); -} - -/** - * @brief Get flag ADC group regular overrun. - * @rmtoll SR OVR LL_ADC_IsActiveFlag_OVR - * @param ADCx ADC instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_OVR(ADC_TypeDef *ADCx) -{ - return (READ_BIT(ADCx->SR, LL_ADC_FLAG_OVR) == (LL_ADC_FLAG_OVR)); -} - - -/** - * @brief Get flag ADC group injected end of sequence conversions. - * @rmtoll SR JEOC LL_ADC_IsActiveFlag_JEOS - * @param ADCx ADC instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_JEOS(ADC_TypeDef *ADCx) -{ - /* Note: on this STM32 series, there is no flag ADC group injected */ - /* end of unitary conversion. */ - /* Flag noted as "JEOC" is corresponding to flag "JEOS" */ - /* in other STM32 families). */ - return (READ_BIT(ADCx->SR, LL_ADC_FLAG_JEOS) == (LL_ADC_FLAG_JEOS)); -} - -/** - * @brief Get flag ADC analog watchdog 1 flag - * @rmtoll SR AWD LL_ADC_IsActiveFlag_AWD1 - * @param ADCx ADC instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_AWD1(ADC_TypeDef *ADCx) -{ - return (READ_BIT(ADCx->SR, LL_ADC_FLAG_AWD1) == (LL_ADC_FLAG_AWD1)); -} - -/** - * @brief Clear flag ADC group regular end of unitary conversion - * or end of sequence conversions, depending on - * ADC configuration. - * @note To configure flag of end of conversion, - * use function @ref LL_ADC_REG_SetFlagEndOfConversion(). - * @rmtoll SR EOC LL_ADC_ClearFlag_EOCS - * @param ADCx ADC instance - * @retval None - */ -__STATIC_INLINE void LL_ADC_ClearFlag_EOCS(ADC_TypeDef *ADCx) -{ - WRITE_REG(ADCx->SR, ~LL_ADC_FLAG_EOCS); -} - -/** - * @brief Clear flag ADC group regular overrun. - * @rmtoll SR OVR LL_ADC_ClearFlag_OVR - * @param ADCx ADC instance - * @retval None - */ -__STATIC_INLINE void LL_ADC_ClearFlag_OVR(ADC_TypeDef *ADCx) -{ - WRITE_REG(ADCx->SR, ~LL_ADC_FLAG_OVR); -} - - -/** - * @brief Clear flag ADC group injected end of sequence conversions. - * @rmtoll SR JEOC LL_ADC_ClearFlag_JEOS - * @param ADCx ADC instance - * @retval None - */ -__STATIC_INLINE void LL_ADC_ClearFlag_JEOS(ADC_TypeDef *ADCx) -{ - /* Note: on this STM32 series, there is no flag ADC group injected */ - /* end of unitary conversion. */ - /* Flag noted as "JEOC" is corresponding to flag "JEOS" */ - /* in other STM32 families). */ - WRITE_REG(ADCx->SR, ~LL_ADC_FLAG_JEOS); -} - -/** - * @brief Clear flag ADC analog watchdog 1. - * @rmtoll SR AWD LL_ADC_ClearFlag_AWD1 - * @param ADCx ADC instance - * @retval None - */ -__STATIC_INLINE void LL_ADC_ClearFlag_AWD1(ADC_TypeDef *ADCx) -{ - WRITE_REG(ADCx->SR, ~LL_ADC_FLAG_AWD1); -} - -#if defined(ADC_MULTIMODE_SUPPORT) -/** - * @brief Get flag multimode ADC group regular end of unitary conversion - * or end of sequence conversions, depending on - * ADC configuration, of the ADC master. - * @note To configure flag of end of conversion, - * use function @ref LL_ADC_REG_SetFlagEndOfConversion(). - * @rmtoll CSR EOC1 LL_ADC_IsActiveFlag_MST_EOCS - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_MST_EOCS(ADC_Common_TypeDef *ADCxy_COMMON) -{ - return (READ_BIT(ADC1->SR, LL_ADC_FLAG_EOCS) == (LL_ADC_FLAG_EOCS)); -} - -/** - * @brief Get flag multimode ADC group regular end of unitary conversion - * or end of sequence conversions, depending on - * ADC configuration, of the ADC slave 1. - * @note To configure flag of end of conversion, - * use function @ref LL_ADC_REG_SetFlagEndOfConversion(). - * @rmtoll CSR EOC2 LL_ADC_IsActiveFlag_SLV1_EOCS - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_SLV1_EOCS(ADC_Common_TypeDef *ADCxy_COMMON) -{ - return (READ_BIT(ADCxy_COMMON->CSR, LL_ADC_FLAG_EOCS_SLV1) == (LL_ADC_FLAG_EOCS_SLV1)); -} - -/** - * @brief Get flag multimode ADC group regular end of unitary conversion - * or end of sequence conversions, depending on - * ADC configuration, of the ADC slave 2. - * @note To configure flag of end of conversion, - * use function @ref LL_ADC_REG_SetFlagEndOfConversion(). - * @rmtoll CSR EOC3 LL_ADC_IsActiveFlag_SLV2_EOCS - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_SLV2_EOCS(ADC_Common_TypeDef *ADCxy_COMMON) -{ - return (READ_BIT(ADCxy_COMMON->CSR, LL_ADC_FLAG_EOCS_SLV2) == (LL_ADC_FLAG_EOCS_SLV2)); -} -/** - * @brief Get flag multimode ADC group regular overrun of the ADC master. - * @rmtoll CSR OVR1 LL_ADC_IsActiveFlag_MST_OVR - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_MST_OVR(ADC_Common_TypeDef *ADCxy_COMMON) -{ - return (READ_BIT(ADCxy_COMMON->CSR, LL_ADC_FLAG_OVR_MST) == (LL_ADC_FLAG_OVR_MST)); -} - -/** - * @brief Get flag multimode ADC group regular overrun of the ADC slave 1. - * @rmtoll CSR OVR2 LL_ADC_IsActiveFlag_SLV1_OVR - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_SLV1_OVR(ADC_Common_TypeDef *ADCxy_COMMON) -{ - return (READ_BIT(ADCxy_COMMON->CSR, LL_ADC_FLAG_OVR_SLV1) == (LL_ADC_FLAG_OVR_SLV1)); -} - -/** - * @brief Get flag multimode ADC group regular overrun of the ADC slave 2. - * @rmtoll CSR OVR3 LL_ADC_IsActiveFlag_SLV2_OVR - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_SLV2_OVR(ADC_Common_TypeDef *ADCxy_COMMON) -{ - return (READ_BIT(ADCxy_COMMON->CSR, LL_ADC_FLAG_OVR_SLV2) == (LL_ADC_FLAG_OVR_SLV2)); -} - - -/** - * @brief Get flag multimode ADC group injected end of sequence conversions of the ADC master. - * @rmtoll CSR JEOC LL_ADC_IsActiveFlag_MST_EOCS - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_MST_JEOS(ADC_Common_TypeDef *ADCxy_COMMON) -{ - /* Note: on this STM32 series, there is no flag ADC group injected */ - /* end of unitary conversion. */ - /* Flag noted as "JEOC" is corresponding to flag "JEOS" */ - /* in other STM32 families). */ - return (READ_BIT(ADCxy_COMMON->CSR, ADC_CSR_JEOC1) == (ADC_CSR_JEOC1)); -} - -/** - * @brief Get flag multimode ADC group injected end of sequence conversions of the ADC slave 1. - * @rmtoll CSR JEOC2 LL_ADC_IsActiveFlag_SLV1_JEOS - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_SLV1_JEOS(ADC_Common_TypeDef *ADCxy_COMMON) -{ - /* Note: on this STM32 series, there is no flag ADC group injected */ - /* end of unitary conversion. */ - /* Flag noted as "JEOC" is corresponding to flag "JEOS" */ - /* in other STM32 families). */ - return (READ_BIT(ADCxy_COMMON->CSR, ADC_CSR_JEOC2) == (ADC_CSR_JEOC2)); -} - -/** - * @brief Get flag multimode ADC group injected end of sequence conversions of the ADC slave 2. - * @rmtoll CSR JEOC3 LL_ADC_IsActiveFlag_SLV2_JEOS - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_SLV2_JEOS(ADC_Common_TypeDef *ADCxy_COMMON) -{ - /* Note: on this STM32 series, there is no flag ADC group injected */ - /* end of unitary conversion. */ - /* Flag noted as "JEOC" is corresponding to flag "JEOS" */ - /* in other STM32 families). */ - return (READ_BIT(ADCxy_COMMON->CSR, ADC_CSR_JEOC3) == (ADC_CSR_JEOC3)); -} - -/** - * @brief Get flag multimode ADC analog watchdog 1 of the ADC master. - * @rmtoll CSR AWD1 LL_ADC_IsActiveFlag_MST_AWD1 - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_MST_AWD1(ADC_Common_TypeDef *ADCxy_COMMON) -{ - return (READ_BIT(ADCxy_COMMON->CSR, LL_ADC_FLAG_AWD1_MST) == (LL_ADC_FLAG_AWD1_MST)); -} - -/** - * @brief Get flag multimode analog watchdog 1 of the ADC slave 1. - * @rmtoll CSR AWD2 LL_ADC_IsActiveFlag_SLV1_AWD1 - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_SLV1_AWD1(ADC_Common_TypeDef *ADCxy_COMMON) -{ - return (READ_BIT(ADCxy_COMMON->CSR, LL_ADC_FLAG_AWD1_SLV1) == (LL_ADC_FLAG_AWD1_SLV1)); -} - -/** - * @brief Get flag multimode analog watchdog 1 of the ADC slave 2. - * @rmtoll CSR AWD3 LL_ADC_IsActiveFlag_SLV2_AWD1 - * @param ADCxy_COMMON ADC common instance - * (can be set directly from CMSIS definition or by using helper macro @ref __LL_ADC_COMMON_INSTANCE() ) - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_ADC_IsActiveFlag_SLV2_AWD1(ADC_Common_TypeDef *ADCxy_COMMON) -{ - return (READ_BIT(ADCxy_COMMON->CSR, LL_ADC_FLAG_AWD1_SLV2) == (LL_ADC_FLAG_AWD1_SLV2)); -} - -#endif /* ADC_MULTIMODE_SUPPORT */ - -/** - * @} - */ - -/** @defgroup ADC_LL_EF_IT_Management ADC IT management - * @{ - */ - -/** - * @brief Enable interruption ADC group regular end of unitary conversion - * or end of sequence conversions, depending on - * ADC configuration. - * @note To configure flag of end of conversion, - * use function @ref LL_ADC_REG_SetFlagEndOfConversion(). - * @rmtoll CR1 EOCIE LL_ADC_EnableIT_EOCS - * @param ADCx ADC instance - * @retval None - */ -__STATIC_INLINE void LL_ADC_EnableIT_EOCS(ADC_TypeDef *ADCx) -{ - SET_BIT(ADCx->CR1, LL_ADC_IT_EOCS); -} - -/** - * @brief Enable ADC group regular interruption overrun. - * @rmtoll CR1 OVRIE LL_ADC_EnableIT_OVR - * @param ADCx ADC instance - * @retval None - */ -__STATIC_INLINE void LL_ADC_EnableIT_OVR(ADC_TypeDef *ADCx) -{ - SET_BIT(ADCx->CR1, LL_ADC_IT_OVR); -} - - -/** - * @brief Enable interruption ADC group injected end of sequence conversions. - * @rmtoll CR1 JEOCIE LL_ADC_EnableIT_JEOS - * @param ADCx ADC instance - * @retval None - */ -__STATIC_INLINE void LL_ADC_EnableIT_JEOS(ADC_TypeDef *ADCx) -{ - /* Note: on this STM32 series, there is no flag ADC group injected */ - /* end of unitary conversion. */ - /* Flag noted as "JEOC" is corresponding to flag "JEOS" */ - /* in other STM32 families). */ - SET_BIT(ADCx->CR1, LL_ADC_IT_JEOS); -} - -/** - * @brief Enable interruption ADC analog watchdog 1. - * @rmtoll CR1 AWDIE LL_ADC_EnableIT_AWD1 - * @param ADCx ADC instance - * @retval None - */ -__STATIC_INLINE void LL_ADC_EnableIT_AWD1(ADC_TypeDef *ADCx) -{ - SET_BIT(ADCx->CR1, LL_ADC_IT_AWD1); -} - -/** - * @brief Disable interruption ADC group regular end of unitary conversion - * or end of sequence conversions, depending on - * ADC configuration. - * @note To configure flag of end of conversion, - * use function @ref LL_ADC_REG_SetFlagEndOfConversion(). - * @rmtoll CR1 EOCIE LL_ADC_DisableIT_EOCS - * @param ADCx ADC instance - * @retval None - */ -__STATIC_INLINE void LL_ADC_DisableIT_EOCS(ADC_TypeDef *ADCx) -{ - CLEAR_BIT(ADCx->CR1, LL_ADC_IT_EOCS); -} - -/** - * @brief Disable interruption ADC group regular overrun. - * @rmtoll CR1 OVRIE LL_ADC_DisableIT_OVR - * @param ADCx ADC instance - * @retval None - */ -__STATIC_INLINE void LL_ADC_DisableIT_OVR(ADC_TypeDef *ADCx) -{ - CLEAR_BIT(ADCx->CR1, LL_ADC_IT_OVR); -} - - -/** - * @brief Disable interruption ADC group injected end of sequence conversions. - * @rmtoll CR1 JEOCIE LL_ADC_EnableIT_JEOS - * @param ADCx ADC instance - * @retval None - */ -__STATIC_INLINE void LL_ADC_DisableIT_JEOS(ADC_TypeDef *ADCx) -{ - /* Note: on this STM32 series, there is no flag ADC group injected */ - /* end of unitary conversion. */ - /* Flag noted as "JEOC" is corresponding to flag "JEOS" */ - /* in other STM32 families). */ - CLEAR_BIT(ADCx->CR1, LL_ADC_IT_JEOS); -} - -/** - * @brief Disable interruption ADC analog watchdog 1. - * @rmtoll CR1 AWDIE LL_ADC_EnableIT_AWD1 - * @param ADCx ADC instance - * @retval None - */ -__STATIC_INLINE void LL_ADC_DisableIT_AWD1(ADC_TypeDef *ADCx) -{ - CLEAR_BIT(ADCx->CR1, LL_ADC_IT_AWD1); -} - -/** - * @brief Get state of interruption ADC group regular end of unitary conversion - * or end of sequence conversions, depending on - * ADC configuration. - * @note To configure flag of end of conversion, - * use function @ref LL_ADC_REG_SetFlagEndOfConversion(). - * (0: interrupt disabled, 1: interrupt enabled) - * @rmtoll CR1 EOCIE LL_ADC_IsEnabledIT_EOCS - * @param ADCx ADC instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_ADC_IsEnabledIT_EOCS(ADC_TypeDef *ADCx) -{ - return (READ_BIT(ADCx->CR1, LL_ADC_IT_EOCS) == (LL_ADC_IT_EOCS)); -} - -/** - * @brief Get state of interruption ADC group regular overrun - * (0: interrupt disabled, 1: interrupt enabled). - * @rmtoll CR1 OVRIE LL_ADC_IsEnabledIT_OVR - * @param ADCx ADC instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_ADC_IsEnabledIT_OVR(ADC_TypeDef *ADCx) -{ - return (READ_BIT(ADCx->CR1, LL_ADC_IT_OVR) == (LL_ADC_IT_OVR)); -} - - -/** - * @brief Get state of interruption ADC group injected end of sequence conversions - * (0: interrupt disabled, 1: interrupt enabled). - * @rmtoll CR1 JEOCIE LL_ADC_EnableIT_JEOS - * @param ADCx ADC instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_ADC_IsEnabledIT_JEOS(ADC_TypeDef *ADCx) -{ - /* Note: on this STM32 series, there is no flag ADC group injected */ - /* end of unitary conversion. */ - /* Flag noted as "JEOC" is corresponding to flag "JEOS" */ - /* in other STM32 families). */ - return (READ_BIT(ADCx->CR1, LL_ADC_IT_JEOS) == (LL_ADC_IT_JEOS)); -} - -/** - * @brief Get state of interruption ADC analog watchdog 1 - * (0: interrupt disabled, 1: interrupt enabled). - * @rmtoll CR1 AWDIE LL_ADC_EnableIT_AWD1 - * @param ADCx ADC instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_ADC_IsEnabledIT_AWD1(ADC_TypeDef *ADCx) -{ - return (READ_BIT(ADCx->CR1, LL_ADC_IT_AWD1) == (LL_ADC_IT_AWD1)); -} - -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup ADC_LL_EF_Init Initialization and de-initialization functions - * @{ - */ - -/* Initialization of some features of ADC common parameters and multimode */ -ErrorStatus LL_ADC_CommonDeInit(ADC_Common_TypeDef *ADCxy_COMMON); -ErrorStatus LL_ADC_CommonInit(ADC_Common_TypeDef *ADCxy_COMMON, LL_ADC_CommonInitTypeDef *ADC_CommonInitStruct); -void LL_ADC_CommonStructInit(LL_ADC_CommonInitTypeDef *ADC_CommonInitStruct); - -/* De-initialization of ADC instance, ADC group regular and ADC group injected */ -/* (availability of ADC group injected depends on STM32 families) */ -ErrorStatus LL_ADC_DeInit(ADC_TypeDef *ADCx); - -/* Initialization of some features of ADC instance */ -ErrorStatus LL_ADC_Init(ADC_TypeDef *ADCx, LL_ADC_InitTypeDef *ADC_InitStruct); -void LL_ADC_StructInit(LL_ADC_InitTypeDef *ADC_InitStruct); - -/* Initialization of some features of ADC instance and ADC group regular */ -ErrorStatus LL_ADC_REG_Init(ADC_TypeDef *ADCx, LL_ADC_REG_InitTypeDef *ADC_REG_InitStruct); -void LL_ADC_REG_StructInit(LL_ADC_REG_InitTypeDef *ADC_REG_InitStruct); - -/* Initialization of some features of ADC instance and ADC group injected */ -ErrorStatus LL_ADC_INJ_Init(ADC_TypeDef *ADCx, LL_ADC_INJ_InitTypeDef *ADC_INJ_InitStruct); -void LL_ADC_INJ_StructInit(LL_ADC_INJ_InitTypeDef *ADC_INJ_InitStruct); - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* ADC1 || ADC2 || ADC3 */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_ADC_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_bus.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_bus.h deleted file mode 100644 index 66da28f..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_bus.h +++ /dev/null @@ -1,2108 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_bus.h - * @author MCD Application Team - * @brief Header file of BUS LL module. - - @verbatim - ##### RCC Limitations ##### - ============================================================================== - [..] - A delay between an RCC peripheral clock enable and the effective peripheral - enabling should be taken into account in order to manage the peripheral read/write - from/to registers. - (+) This delay depends on the peripheral mapping. - (++) AHB & APB peripherals, 1 dummy read is necessary - - [..] - Workarounds: - (#) For AHB & APB peripherals, a dummy read to the peripheral register has been - inserted in each LL_{BUS}_GRP{x}_EnableClock() function. - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_LL_BUS_H -#define __STM32F4xx_LL_BUS_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined(RCC) - -/** @defgroup BUS_LL BUS - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/** @defgroup BUS_LL_Exported_Constants BUS Exported Constants - * @{ - */ - -/** @defgroup BUS_LL_EC_AHB1_GRP1_PERIPH AHB1 GRP1 PERIPH - * @{ - */ -#define LL_AHB1_GRP1_PERIPH_ALL 0xFFFFFFFFU -#define LL_AHB1_GRP1_PERIPH_GPIOA RCC_AHB1ENR_GPIOAEN -#define LL_AHB1_GRP1_PERIPH_GPIOB RCC_AHB1ENR_GPIOBEN -#define LL_AHB1_GRP1_PERIPH_GPIOC RCC_AHB1ENR_GPIOCEN -#if defined(GPIOD) -#define LL_AHB1_GRP1_PERIPH_GPIOD RCC_AHB1ENR_GPIODEN -#endif /* GPIOD */ -#if defined(GPIOE) -#define LL_AHB1_GRP1_PERIPH_GPIOE RCC_AHB1ENR_GPIOEEN -#endif /* GPIOE */ -#if defined(GPIOF) -#define LL_AHB1_GRP1_PERIPH_GPIOF RCC_AHB1ENR_GPIOFEN -#endif /* GPIOF */ -#if defined(GPIOG) -#define LL_AHB1_GRP1_PERIPH_GPIOG RCC_AHB1ENR_GPIOGEN -#endif /* GPIOG */ -#if defined(GPIOH) -#define LL_AHB1_GRP1_PERIPH_GPIOH RCC_AHB1ENR_GPIOHEN -#endif /* GPIOH */ -#if defined(GPIOI) -#define LL_AHB1_GRP1_PERIPH_GPIOI RCC_AHB1ENR_GPIOIEN -#endif /* GPIOI */ -#if defined(GPIOJ) -#define LL_AHB1_GRP1_PERIPH_GPIOJ RCC_AHB1ENR_GPIOJEN -#endif /* GPIOJ */ -#if defined(GPIOK) -#define LL_AHB1_GRP1_PERIPH_GPIOK RCC_AHB1ENR_GPIOKEN -#endif /* GPIOK */ -#define LL_AHB1_GRP1_PERIPH_CRC RCC_AHB1ENR_CRCEN -#if defined(RCC_AHB1ENR_BKPSRAMEN) -#define LL_AHB1_GRP1_PERIPH_BKPSRAM RCC_AHB1ENR_BKPSRAMEN -#endif /* RCC_AHB1ENR_BKPSRAMEN */ -#if defined(RCC_AHB1ENR_CCMDATARAMEN) -#define LL_AHB1_GRP1_PERIPH_CCMDATARAM RCC_AHB1ENR_CCMDATARAMEN -#endif /* RCC_AHB1ENR_CCMDATARAMEN */ -#define LL_AHB1_GRP1_PERIPH_DMA1 RCC_AHB1ENR_DMA1EN -#define LL_AHB1_GRP1_PERIPH_DMA2 RCC_AHB1ENR_DMA2EN -#if defined(RCC_AHB1ENR_RNGEN) -#define LL_AHB1_GRP1_PERIPH_RNG RCC_AHB1ENR_RNGEN -#endif /* RCC_AHB1ENR_RNGEN */ -#if defined(DMA2D) -#define LL_AHB1_GRP1_PERIPH_DMA2D RCC_AHB1ENR_DMA2DEN -#endif /* DMA2D */ -#if defined(ETH) -#define LL_AHB1_GRP1_PERIPH_ETHMAC RCC_AHB1ENR_ETHMACEN -#define LL_AHB1_GRP1_PERIPH_ETHMACTX RCC_AHB1ENR_ETHMACTXEN -#define LL_AHB1_GRP1_PERIPH_ETHMACRX RCC_AHB1ENR_ETHMACRXEN -#define LL_AHB1_GRP1_PERIPH_ETHMACPTP RCC_AHB1ENR_ETHMACPTPEN -#endif /* ETH */ -#if defined(USB_OTG_HS) -#define LL_AHB1_GRP1_PERIPH_OTGHS RCC_AHB1ENR_OTGHSEN -#define LL_AHB1_GRP1_PERIPH_OTGHSULPI RCC_AHB1ENR_OTGHSULPIEN -#endif /* USB_OTG_HS */ -#define LL_AHB1_GRP1_PERIPH_FLITF RCC_AHB1LPENR_FLITFLPEN -#define LL_AHB1_GRP1_PERIPH_SRAM1 RCC_AHB1LPENR_SRAM1LPEN -#if defined(RCC_AHB1LPENR_SRAM2LPEN) -#define LL_AHB1_GRP1_PERIPH_SRAM2 RCC_AHB1LPENR_SRAM2LPEN -#endif /* RCC_AHB1LPENR_SRAM2LPEN */ -#if defined(RCC_AHB1LPENR_SRAM3LPEN) -#define LL_AHB1_GRP1_PERIPH_SRAM3 RCC_AHB1LPENR_SRAM3LPEN -#endif /* RCC_AHB1LPENR_SRAM3LPEN */ -/** - * @} - */ - -#if defined(RCC_AHB2_SUPPORT) -/** @defgroup BUS_LL_EC_AHB2_GRP1_PERIPH AHB2 GRP1 PERIPH - * @{ - */ -#define LL_AHB2_GRP1_PERIPH_ALL 0xFFFFFFFFU -#if defined(DCMI) -#define LL_AHB2_GRP1_PERIPH_DCMI RCC_AHB2ENR_DCMIEN -#endif /* DCMI */ -#if defined(CRYP) -#define LL_AHB2_GRP1_PERIPH_CRYP RCC_AHB2ENR_CRYPEN -#endif /* CRYP */ -#if defined(AES) -#define LL_AHB2_GRP1_PERIPH_AES RCC_AHB2ENR_AESEN -#endif /* AES */ -#if defined(HASH) -#define LL_AHB2_GRP1_PERIPH_HASH RCC_AHB2ENR_HASHEN -#endif /* HASH */ -#if defined(RCC_AHB2ENR_RNGEN) -#define LL_AHB2_GRP1_PERIPH_RNG RCC_AHB2ENR_RNGEN -#endif /* RCC_AHB2ENR_RNGEN */ -#if defined(USB_OTG_FS) -#define LL_AHB2_GRP1_PERIPH_OTGFS RCC_AHB2ENR_OTGFSEN -#endif /* USB_OTG_FS */ -/** - * @} - */ -#endif /* RCC_AHB2_SUPPORT */ - -#if defined(RCC_AHB3_SUPPORT) -/** @defgroup BUS_LL_EC_AHB3_GRP1_PERIPH AHB3 GRP1 PERIPH - * @{ - */ -#define LL_AHB3_GRP1_PERIPH_ALL 0xFFFFFFFFU -#if defined(FSMC_Bank1) -#define LL_AHB3_GRP1_PERIPH_FSMC RCC_AHB3ENR_FSMCEN -#endif /* FSMC_Bank1 */ -#if defined(FMC_Bank1) -#define LL_AHB3_GRP1_PERIPH_FMC RCC_AHB3ENR_FMCEN -#endif /* FMC_Bank1 */ -#if defined(QUADSPI) -#define LL_AHB3_GRP1_PERIPH_QSPI RCC_AHB3ENR_QSPIEN -#endif /* QUADSPI */ -/** - * @} - */ -#endif /* RCC_AHB3_SUPPORT */ - -/** @defgroup BUS_LL_EC_APB1_GRP1_PERIPH APB1 GRP1 PERIPH - * @{ - */ -#define LL_APB1_GRP1_PERIPH_ALL 0xFFFFFFFFU -#if defined(TIM2) -#define LL_APB1_GRP1_PERIPH_TIM2 RCC_APB1ENR_TIM2EN -#endif /* TIM2 */ -#if defined(TIM3) -#define LL_APB1_GRP1_PERIPH_TIM3 RCC_APB1ENR_TIM3EN -#endif /* TIM3 */ -#if defined(TIM4) -#define LL_APB1_GRP1_PERIPH_TIM4 RCC_APB1ENR_TIM4EN -#endif /* TIM4 */ -#define LL_APB1_GRP1_PERIPH_TIM5 RCC_APB1ENR_TIM5EN -#if defined(TIM6) -#define LL_APB1_GRP1_PERIPH_TIM6 RCC_APB1ENR_TIM6EN -#endif /* TIM6 */ -#if defined(TIM7) -#define LL_APB1_GRP1_PERIPH_TIM7 RCC_APB1ENR_TIM7EN -#endif /* TIM7 */ -#if defined(TIM12) -#define LL_APB1_GRP1_PERIPH_TIM12 RCC_APB1ENR_TIM12EN -#endif /* TIM12 */ -#if defined(TIM13) -#define LL_APB1_GRP1_PERIPH_TIM13 RCC_APB1ENR_TIM13EN -#endif /* TIM13 */ -#if defined(TIM14) -#define LL_APB1_GRP1_PERIPH_TIM14 RCC_APB1ENR_TIM14EN -#endif /* TIM14 */ -#if defined(LPTIM1) -#define LL_APB1_GRP1_PERIPH_LPTIM1 RCC_APB1ENR_LPTIM1EN -#endif /* LPTIM1 */ -#if defined(RCC_APB1ENR_RTCAPBEN) -#define LL_APB1_GRP1_PERIPH_RTCAPB RCC_APB1ENR_RTCAPBEN -#endif /* RCC_APB1ENR_RTCAPBEN */ -#define LL_APB1_GRP1_PERIPH_WWDG RCC_APB1ENR_WWDGEN -#if defined(SPI2) -#define LL_APB1_GRP1_PERIPH_SPI2 RCC_APB1ENR_SPI2EN -#endif /* SPI2 */ -#if defined(SPI3) -#define LL_APB1_GRP1_PERIPH_SPI3 RCC_APB1ENR_SPI3EN -#endif /* SPI3 */ -#if defined(SPDIFRX) -#define LL_APB1_GRP1_PERIPH_SPDIFRX RCC_APB1ENR_SPDIFRXEN -#endif /* SPDIFRX */ -#define LL_APB1_GRP1_PERIPH_USART2 RCC_APB1ENR_USART2EN -#if defined(USART3) -#define LL_APB1_GRP1_PERIPH_USART3 RCC_APB1ENR_USART3EN -#endif /* USART3 */ -#if defined(UART4) -#define LL_APB1_GRP1_PERIPH_UART4 RCC_APB1ENR_UART4EN -#endif /* UART4 */ -#if defined(UART5) -#define LL_APB1_GRP1_PERIPH_UART5 RCC_APB1ENR_UART5EN -#endif /* UART5 */ -#define LL_APB1_GRP1_PERIPH_I2C1 RCC_APB1ENR_I2C1EN -#define LL_APB1_GRP1_PERIPH_I2C2 RCC_APB1ENR_I2C2EN -#if defined(I2C3) -#define LL_APB1_GRP1_PERIPH_I2C3 RCC_APB1ENR_I2C3EN -#endif /* I2C3 */ -#if defined(FMPI2C1) -#define LL_APB1_GRP1_PERIPH_FMPI2C1 RCC_APB1ENR_FMPI2C1EN -#endif /* FMPI2C1 */ -#if defined(CAN1) -#define LL_APB1_GRP1_PERIPH_CAN1 RCC_APB1ENR_CAN1EN -#endif /* CAN1 */ -#if defined(CAN2) -#define LL_APB1_GRP1_PERIPH_CAN2 RCC_APB1ENR_CAN2EN -#endif /* CAN2 */ -#if defined(CAN3) -#define LL_APB1_GRP1_PERIPH_CAN3 RCC_APB1ENR_CAN3EN -#endif /* CAN3 */ -#if defined(CEC) -#define LL_APB1_GRP1_PERIPH_CEC RCC_APB1ENR_CECEN -#endif /* CEC */ -#define LL_APB1_GRP1_PERIPH_PWR RCC_APB1ENR_PWREN -#if defined(DAC1) -#define LL_APB1_GRP1_PERIPH_DAC1 RCC_APB1ENR_DACEN -#endif /* DAC1 */ -#if defined(UART7) -#define LL_APB1_GRP1_PERIPH_UART7 RCC_APB1ENR_UART7EN -#endif /* UART7 */ -#if defined(UART8) -#define LL_APB1_GRP1_PERIPH_UART8 RCC_APB1ENR_UART8EN -#endif /* UART8 */ -/** - * @} - */ - -/** @defgroup BUS_LL_EC_APB2_GRP1_PERIPH APB2 GRP1 PERIPH - * @{ - */ -#define LL_APB2_GRP1_PERIPH_ALL 0xFFFFFFFFU -#define LL_APB2_GRP1_PERIPH_TIM1 RCC_APB2ENR_TIM1EN -#if defined(TIM8) -#define LL_APB2_GRP1_PERIPH_TIM8 RCC_APB2ENR_TIM8EN -#endif /* TIM8 */ -#define LL_APB2_GRP1_PERIPH_USART1 RCC_APB2ENR_USART1EN -#if defined(USART6) -#define LL_APB2_GRP1_PERIPH_USART6 RCC_APB2ENR_USART6EN -#endif /* USART6 */ -#if defined(UART9) -#define LL_APB2_GRP1_PERIPH_UART9 RCC_APB2ENR_UART9EN -#endif /* UART9 */ -#if defined(UART10) -#define LL_APB2_GRP1_PERIPH_UART10 RCC_APB2ENR_UART10EN -#endif /* UART10 */ -#define LL_APB2_GRP1_PERIPH_ADC1 RCC_APB2ENR_ADC1EN -#if defined(ADC2) -#define LL_APB2_GRP1_PERIPH_ADC2 RCC_APB2ENR_ADC2EN -#endif /* ADC2 */ -#if defined(ADC3) -#define LL_APB2_GRP1_PERIPH_ADC3 RCC_APB2ENR_ADC3EN -#endif /* ADC3 */ -#if defined(SDIO) -#define LL_APB2_GRP1_PERIPH_SDIO RCC_APB2ENR_SDIOEN -#endif /* SDIO */ -#define LL_APB2_GRP1_PERIPH_SPI1 RCC_APB2ENR_SPI1EN -#if defined(SPI4) -#define LL_APB2_GRP1_PERIPH_SPI4 RCC_APB2ENR_SPI4EN -#endif /* SPI4 */ -#define LL_APB2_GRP1_PERIPH_SYSCFG RCC_APB2ENR_SYSCFGEN -#if defined(RCC_APB2ENR_EXTITEN) -#define LL_APB2_GRP1_PERIPH_EXTI RCC_APB2ENR_EXTITEN -#endif /* RCC_APB2ENR_EXTITEN */ -#define LL_APB2_GRP1_PERIPH_TIM9 RCC_APB2ENR_TIM9EN -#if defined(TIM10) -#define LL_APB2_GRP1_PERIPH_TIM10 RCC_APB2ENR_TIM10EN -#endif /* TIM10 */ -#define LL_APB2_GRP1_PERIPH_TIM11 RCC_APB2ENR_TIM11EN -#if defined(SPI5) -#define LL_APB2_GRP1_PERIPH_SPI5 RCC_APB2ENR_SPI5EN -#endif /* SPI5 */ -#if defined(SPI6) -#define LL_APB2_GRP1_PERIPH_SPI6 RCC_APB2ENR_SPI6EN -#endif /* SPI6 */ -#if defined(SAI1) -#define LL_APB2_GRP1_PERIPH_SAI1 RCC_APB2ENR_SAI1EN -#endif /* SAI1 */ -#if defined(SAI2) -#define LL_APB2_GRP1_PERIPH_SAI2 RCC_APB2ENR_SAI2EN -#endif /* SAI2 */ -#if defined(LTDC) -#define LL_APB2_GRP1_PERIPH_LTDC RCC_APB2ENR_LTDCEN -#endif /* LTDC */ -#if defined(DSI) -#define LL_APB2_GRP1_PERIPH_DSI RCC_APB2ENR_DSIEN -#endif /* DSI */ -#if defined(DFSDM1_Channel0) -#define LL_APB2_GRP1_PERIPH_DFSDM1 RCC_APB2ENR_DFSDM1EN -#endif /* DFSDM1_Channel0 */ -#if defined(DFSDM2_Channel0) -#define LL_APB2_GRP1_PERIPH_DFSDM2 RCC_APB2ENR_DFSDM2EN -#endif /* DFSDM2_Channel0 */ -#define LL_APB2_GRP1_PERIPH_ADC RCC_APB2RSTR_ADCRST -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/* Exported functions --------------------------------------------------------*/ -/** @defgroup BUS_LL_Exported_Functions BUS Exported Functions - * @{ - */ - -/** @defgroup BUS_LL_EF_AHB1 AHB1 - * @{ - */ - -/** - * @brief Enable AHB1 peripherals clock. - * @rmtoll AHB1ENR GPIOAEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR GPIOBEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR GPIOCEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR GPIODEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR GPIOEEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR GPIOFEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR GPIOGEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR GPIOHEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR GPIOIEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR GPIOJEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR GPIOKEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR CRCEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR BKPSRAMEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR CCMDATARAMEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR DMA1EN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR DMA2EN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR RNGEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR DMA2DEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR ETHMACEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR ETHMACTXEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR ETHMACRXEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR ETHMACPTPEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR OTGHSEN LL_AHB1_GRP1_EnableClock\n - * AHB1ENR OTGHSULPIEN LL_AHB1_GRP1_EnableClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOA - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOB - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOC - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOD (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOE (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOF (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOG (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOH (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOI (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOJ (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOK (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_CRC - * @arg @ref LL_AHB1_GRP1_PERIPH_BKPSRAM (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_CCMDATARAM (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA1 - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2 - * @arg @ref LL_AHB1_GRP1_PERIPH_RNG (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2D (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMAC (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACTX (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACRX (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACPTP (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHS (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHSULPI (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB1_GRP1_EnableClock(uint32_t Periphs) -{ - __IO uint32_t tmpreg; - SET_BIT(RCC->AHB1ENR, Periphs); - /* Delay after an RCC peripheral clock enabling */ - tmpreg = READ_BIT(RCC->AHB1ENR, Periphs); - (void)tmpreg; -} - -/** - * @brief Check if AHB1 peripheral clock is enabled or not - * @rmtoll AHB1ENR GPIOAEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR GPIOBEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR GPIOCEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR GPIODEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR GPIOEEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR GPIOFEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR GPIOGEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR GPIOHEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR GPIOIEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR GPIOJEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR GPIOKEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR CRCEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR BKPSRAMEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR CCMDATARAMEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR DMA1EN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR DMA2EN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR RNGEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR DMA2DEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR ETHMACEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR ETHMACTXEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR ETHMACRXEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR ETHMACPTPEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR OTGHSEN LL_AHB1_GRP1_IsEnabledClock\n - * AHB1ENR OTGHSULPIEN LL_AHB1_GRP1_IsEnabledClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOA - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOB - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOC - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOD (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOE (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOF (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOG (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOH (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOI (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOJ (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOK (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_CRC - * @arg @ref LL_AHB1_GRP1_PERIPH_BKPSRAM (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_CCMDATARAM (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA1 - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2 - * @arg @ref LL_AHB1_GRP1_PERIPH_RNG (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2D (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMAC (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACTX (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACRX (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACPTP (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHS (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHSULPI (*) - * - * (*) value not defined in all devices. - * @retval State of Periphs (1 or 0). -*/ -__STATIC_INLINE uint32_t LL_AHB1_GRP1_IsEnabledClock(uint32_t Periphs) -{ - return (READ_BIT(RCC->AHB1ENR, Periphs) == Periphs); -} - -/** - * @brief Disable AHB1 peripherals clock. - * @rmtoll AHB1ENR GPIOAEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR GPIOBEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR GPIOCEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR GPIODEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR GPIOEEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR GPIOFEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR GPIOGEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR GPIOHEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR GPIOIEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR GPIOJEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR GPIOKEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR CRCEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR BKPSRAMEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR CCMDATARAMEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR DMA1EN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR DMA2EN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR RNGEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR DMA2DEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR ETHMACEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR ETHMACTXEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR ETHMACRXEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR ETHMACPTPEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR OTGHSEN LL_AHB1_GRP1_DisableClock\n - * AHB1ENR OTGHSULPIEN LL_AHB1_GRP1_DisableClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOA - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOB - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOC - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOD (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOE (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOF (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOG (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOH (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOI (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOJ (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOK (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_CRC - * @arg @ref LL_AHB1_GRP1_PERIPH_BKPSRAM (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_CCMDATARAM (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA1 - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2 - * @arg @ref LL_AHB1_GRP1_PERIPH_RNG (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2D (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMAC (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACTX (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACRX (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACPTP (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHS (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHSULPI (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB1_GRP1_DisableClock(uint32_t Periphs) -{ - CLEAR_BIT(RCC->AHB1ENR, Periphs); -} - -/** - * @brief Force AHB1 peripherals reset. - * @rmtoll AHB1RSTR GPIOARST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR GPIOBRST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR GPIOCRST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR GPIODRST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR GPIOERST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR GPIOFRST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR GPIOGRST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR GPIOHRST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR GPIOIRST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR GPIOJRST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR GPIOKRST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR CRCRST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR DMA1RST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR DMA2RST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR RNGRST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR DMA2DRST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR ETHMACRST LL_AHB1_GRP1_ForceReset\n - * AHB1RSTR OTGHSRST LL_AHB1_GRP1_ForceReset - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB1_GRP1_PERIPH_ALL - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOA - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOB - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOC - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOD (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOE (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOF (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOG (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOH (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOI (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOJ (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOK (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_CRC - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA1 - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2 - * @arg @ref LL_AHB1_GRP1_PERIPH_RNG (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2D (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMAC (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHS (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB1_GRP1_ForceReset(uint32_t Periphs) -{ - SET_BIT(RCC->AHB1RSTR, Periphs); -} - -/** - * @brief Release AHB1 peripherals reset. - * @rmtoll AHB1RSTR GPIOARST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR GPIOBRST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR GPIOCRST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR GPIODRST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR GPIOERST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR GPIOFRST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR GPIOGRST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR GPIOHRST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR GPIOIRST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR GPIOJRST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR GPIOKRST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR CRCRST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR DMA1RST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR DMA2RST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR RNGRST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR DMA2DRST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR ETHMACRST LL_AHB1_GRP1_ReleaseReset\n - * AHB1RSTR OTGHSRST LL_AHB1_GRP1_ReleaseReset - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB1_GRP1_PERIPH_ALL - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOA - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOB - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOC - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOD (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOE (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOF (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOG (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOH (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOI (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOJ (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOK (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_CRC - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA1 - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2 - * @arg @ref LL_AHB1_GRP1_PERIPH_RNG (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2D (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMAC (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHS (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB1_GRP1_ReleaseReset(uint32_t Periphs) -{ - CLEAR_BIT(RCC->AHB1RSTR, Periphs); -} - -/** - * @brief Enable AHB1 peripheral clocks in low-power mode - * @rmtoll AHB1LPENR GPIOALPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR GPIOBLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR GPIOCLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR GPIODLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR GPIOELPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR GPIOFLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR GPIOGLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR GPIOHLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR GPIOILPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR GPIOJLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR GPIOKLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR CRCLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR BKPSRAMLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR FLITFLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR SRAM1LPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR SRAM2LPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR SRAM3LPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR BKPSRAMLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR DMA1LPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR DMA2LPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR DMA2DLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR RNGLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR ETHMACLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR ETHMACTXLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR ETHMACRXLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR ETHMACPTPLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR OTGHSLPEN LL_AHB1_GRP1_EnableClockLowPower\n - * AHB1LPENR OTGHSULPILPEN LL_AHB1_GRP1_EnableClockLowPower - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOA - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOB - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOC - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOD (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOE (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOF (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOG (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOH (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOI (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOJ (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOK (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_CRC - * @arg @ref LL_AHB1_GRP1_PERIPH_BKPSRAM (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_FLITF - * @arg @ref LL_AHB1_GRP1_PERIPH_SRAM1 - * @arg @ref LL_AHB1_GRP1_PERIPH_SRAM2 (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_SRAM3 (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA1 - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2 - * @arg @ref LL_AHB1_GRP1_PERIPH_RNG (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2D (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMAC (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACTX (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACRX (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACPTP (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHS (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHSULPI (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB1_GRP1_EnableClockLowPower(uint32_t Periphs) -{ - __IO uint32_t tmpreg; - SET_BIT(RCC->AHB1LPENR, Periphs); - /* Delay after an RCC peripheral clock enabling */ - tmpreg = READ_BIT(RCC->AHB1LPENR, Periphs); - (void)tmpreg; -} - -/** - * @brief Disable AHB1 peripheral clocks in low-power mode - * @rmtoll AHB1LPENR GPIOALPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR GPIOBLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR GPIOCLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR GPIODLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR GPIOELPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR GPIOFLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR GPIOGLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR GPIOHLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR GPIOILPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR GPIOJLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR GPIOKLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR CRCLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR BKPSRAMLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR FLITFLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR SRAM1LPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR SRAM2LPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR SRAM3LPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR BKPSRAMLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR DMA1LPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR DMA2LPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR DMA2DLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR RNGLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR ETHMACLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR ETHMACTXLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR ETHMACRXLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR ETHMACPTPLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR OTGHSLPEN LL_AHB1_GRP1_DisableClockLowPower\n - * AHB1LPENR OTGHSULPILPEN LL_AHB1_GRP1_DisableClockLowPower - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOA - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOB - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOC - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOD (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOE (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOF (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOG (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOH (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOI (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOJ (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_GPIOK (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_CRC - * @arg @ref LL_AHB1_GRP1_PERIPH_BKPSRAM (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_FLITF - * @arg @ref LL_AHB1_GRP1_PERIPH_SRAM1 - * @arg @ref LL_AHB1_GRP1_PERIPH_SRAM2 (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_SRAM3 (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA1 - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2 - * @arg @ref LL_AHB1_GRP1_PERIPH_RNG (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_DMA2D (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMAC (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACTX (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACRX (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_ETHMACPTP (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHS (*) - * @arg @ref LL_AHB1_GRP1_PERIPH_OTGHSULPI (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB1_GRP1_DisableClockLowPower(uint32_t Periphs) -{ - CLEAR_BIT(RCC->AHB1LPENR, Periphs); -} - -/** - * @} - */ - -#if defined(RCC_AHB2_SUPPORT) -/** @defgroup BUS_LL_EF_AHB2 AHB2 - * @{ - */ - -/** - * @brief Enable AHB2 peripherals clock. - * @rmtoll AHB2ENR DCMIEN LL_AHB2_GRP1_EnableClock\n - * AHB2ENR CRYPEN LL_AHB2_GRP1_EnableClock\n - * AHB2ENR AESEN LL_AHB2_GRP1_EnableClock\n - * AHB2ENR HASHEN LL_AHB2_GRP1_EnableClock\n - * AHB2ENR RNGEN LL_AHB2_GRP1_EnableClock\n - * AHB2ENR OTGFSEN LL_AHB2_GRP1_EnableClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB2_GRP1_PERIPH_DCMI (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_CRYP (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_AES (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_HASH (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_RNG (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_OTGFS (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB2_GRP1_EnableClock(uint32_t Periphs) -{ - __IO uint32_t tmpreg; - SET_BIT(RCC->AHB2ENR, Periphs); - /* Delay after an RCC peripheral clock enabling */ - tmpreg = READ_BIT(RCC->AHB2ENR, Periphs); - (void)tmpreg; -} - -/** - * @brief Check if AHB2 peripheral clock is enabled or not - * @rmtoll AHB2ENR DCMIEN LL_AHB2_GRP1_IsEnabledClock\n - * AHB2ENR CRYPEN LL_AHB2_GRP1_IsEnabledClock\n - * AHB2ENR AESEN LL_AHB2_GRP1_IsEnabledClock\n - * AHB2ENR HASHEN LL_AHB2_GRP1_IsEnabledClock\n - * AHB2ENR RNGEN LL_AHB2_GRP1_IsEnabledClock\n - * AHB2ENR OTGFSEN LL_AHB2_GRP1_IsEnabledClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB2_GRP1_PERIPH_DCMI (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_CRYP (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_AES (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_HASH (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_RNG (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_OTGFS (*) - * - * (*) value not defined in all devices. - * @retval State of Periphs (1 or 0). -*/ -__STATIC_INLINE uint32_t LL_AHB2_GRP1_IsEnabledClock(uint32_t Periphs) -{ - return (READ_BIT(RCC->AHB2ENR, Periphs) == Periphs); -} - -/** - * @brief Disable AHB2 peripherals clock. - * @rmtoll AHB2ENR DCMIEN LL_AHB2_GRP1_DisableClock\n - * AHB2ENR CRYPEN LL_AHB2_GRP1_DisableClock\n - * AHB2ENR AESEN LL_AHB2_GRP1_DisableClock\n - * AHB2ENR HASHEN LL_AHB2_GRP1_DisableClock\n - * AHB2ENR RNGEN LL_AHB2_GRP1_DisableClock\n - * AHB2ENR OTGFSEN LL_AHB2_GRP1_DisableClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB2_GRP1_PERIPH_DCMI (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_CRYP (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_AES (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_HASH (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_RNG (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_OTGFS (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB2_GRP1_DisableClock(uint32_t Periphs) -{ - CLEAR_BIT(RCC->AHB2ENR, Periphs); -} - -/** - * @brief Force AHB2 peripherals reset. - * @rmtoll AHB2RSTR DCMIRST LL_AHB2_GRP1_ForceReset\n - * AHB2RSTR CRYPRST LL_AHB2_GRP1_ForceReset\n - * AHB2RSTR AESRST LL_AHB2_GRP1_ForceReset\n - * AHB2RSTR HASHRST LL_AHB2_GRP1_ForceReset\n - * AHB2RSTR RNGRST LL_AHB2_GRP1_ForceReset\n - * AHB2RSTR OTGFSRST LL_AHB2_GRP1_ForceReset - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB2_GRP1_PERIPH_ALL - * @arg @ref LL_AHB2_GRP1_PERIPH_DCMI (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_CRYP (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_AES (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_HASH (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_RNG (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_OTGFS (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB2_GRP1_ForceReset(uint32_t Periphs) -{ - SET_BIT(RCC->AHB2RSTR, Periphs); -} - -/** - * @brief Release AHB2 peripherals reset. - * @rmtoll AHB2RSTR DCMIRST LL_AHB2_GRP1_ReleaseReset\n - * AHB2RSTR CRYPRST LL_AHB2_GRP1_ReleaseReset\n - * AHB2RSTR AESRST LL_AHB2_GRP1_ReleaseReset\n - * AHB2RSTR HASHRST LL_AHB2_GRP1_ReleaseReset\n - * AHB2RSTR RNGRST LL_AHB2_GRP1_ReleaseReset\n - * AHB2RSTR OTGFSRST LL_AHB2_GRP1_ReleaseReset - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB2_GRP1_PERIPH_ALL - * @arg @ref LL_AHB2_GRP1_PERIPH_DCMI (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_CRYP (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_AES (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_HASH (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_RNG (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_OTGFS (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB2_GRP1_ReleaseReset(uint32_t Periphs) -{ - CLEAR_BIT(RCC->AHB2RSTR, Periphs); -} - -/** - * @brief Enable AHB2 peripheral clocks in low-power mode - * @rmtoll AHB2LPENR DCMILPEN LL_AHB2_GRP1_EnableClockLowPower\n - * AHB2LPENR CRYPLPEN LL_AHB2_GRP1_EnableClockLowPower\n - * AHB2LPENR AESLPEN LL_AHB2_GRP1_EnableClockLowPower\n - * AHB2LPENR HASHLPEN LL_AHB2_GRP1_EnableClockLowPower\n - * AHB2LPENR RNGLPEN LL_AHB2_GRP1_EnableClockLowPower\n - * AHB2LPENR OTGFSLPEN LL_AHB2_GRP1_EnableClockLowPower - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB2_GRP1_PERIPH_DCMI (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_CRYP (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_AES (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_HASH (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_RNG (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_OTGFS (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB2_GRP1_EnableClockLowPower(uint32_t Periphs) -{ - __IO uint32_t tmpreg; - SET_BIT(RCC->AHB2LPENR, Periphs); - /* Delay after an RCC peripheral clock enabling */ - tmpreg = READ_BIT(RCC->AHB2LPENR, Periphs); - (void)tmpreg; -} - -/** - * @brief Disable AHB2 peripheral clocks in low-power mode - * @rmtoll AHB2LPENR DCMILPEN LL_AHB2_GRP1_DisableClockLowPower\n - * AHB2LPENR CRYPLPEN LL_AHB2_GRP1_DisableClockLowPower\n - * AHB2LPENR AESLPEN LL_AHB2_GRP1_DisableClockLowPower\n - * AHB2LPENR HASHLPEN LL_AHB2_GRP1_DisableClockLowPower\n - * AHB2LPENR RNGLPEN LL_AHB2_GRP1_DisableClockLowPower\n - * AHB2LPENR OTGFSLPEN LL_AHB2_GRP1_DisableClockLowPower - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB2_GRP1_PERIPH_DCMI (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_CRYP (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_AES (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_HASH (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_RNG (*) - * @arg @ref LL_AHB2_GRP1_PERIPH_OTGFS (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB2_GRP1_DisableClockLowPower(uint32_t Periphs) -{ - CLEAR_BIT(RCC->AHB2LPENR, Periphs); -} - -/** - * @} - */ -#endif /* RCC_AHB2_SUPPORT */ - -#if defined(RCC_AHB3_SUPPORT) -/** @defgroup BUS_LL_EF_AHB3 AHB3 - * @{ - */ - -/** - * @brief Enable AHB3 peripherals clock. - * @rmtoll AHB3ENR FMCEN LL_AHB3_GRP1_EnableClock\n - * AHB3ENR FSMCEN LL_AHB3_GRP1_EnableClock\n - * AHB3ENR QSPIEN LL_AHB3_GRP1_EnableClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB3_GRP1_PERIPH_FMC (*) - * @arg @ref LL_AHB3_GRP1_PERIPH_FSMC (*) - * @arg @ref LL_AHB3_GRP1_PERIPH_QSPI (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB3_GRP1_EnableClock(uint32_t Periphs) -{ - __IO uint32_t tmpreg; - SET_BIT(RCC->AHB3ENR, Periphs); - /* Delay after an RCC peripheral clock enabling */ - tmpreg = READ_BIT(RCC->AHB3ENR, Periphs); - (void)tmpreg; -} - -/** - * @brief Check if AHB3 peripheral clock is enabled or not - * @rmtoll AHB3ENR FMCEN LL_AHB3_GRP1_IsEnabledClock\n - * AHB3ENR FSMCEN LL_AHB3_GRP1_IsEnabledClock\n - * AHB3ENR QSPIEN LL_AHB3_GRP1_IsEnabledClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB3_GRP1_PERIPH_FMC (*) - * @arg @ref LL_AHB3_GRP1_PERIPH_FSMC (*) - * @arg @ref LL_AHB3_GRP1_PERIPH_QSPI (*) - * - * (*) value not defined in all devices. - * @retval State of Periphs (1 or 0). -*/ -__STATIC_INLINE uint32_t LL_AHB3_GRP1_IsEnabledClock(uint32_t Periphs) -{ - return (READ_BIT(RCC->AHB3ENR, Periphs) == Periphs); -} - -/** - * @brief Disable AHB3 peripherals clock. - * @rmtoll AHB3ENR FMCEN LL_AHB3_GRP1_DisableClock\n - * AHB3ENR FSMCEN LL_AHB3_GRP1_DisableClock\n - * AHB3ENR QSPIEN LL_AHB3_GRP1_DisableClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB3_GRP1_PERIPH_FMC (*) - * @arg @ref LL_AHB3_GRP1_PERIPH_FSMC (*) - * @arg @ref LL_AHB3_GRP1_PERIPH_QSPI (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB3_GRP1_DisableClock(uint32_t Periphs) -{ - CLEAR_BIT(RCC->AHB3ENR, Periphs); -} - -/** - * @brief Force AHB3 peripherals reset. - * @rmtoll AHB3RSTR FMCRST LL_AHB3_GRP1_ForceReset\n - * AHB3RSTR FSMCRST LL_AHB3_GRP1_ForceReset\n - * AHB3RSTR QSPIRST LL_AHB3_GRP1_ForceReset - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB3_GRP1_PERIPH_ALL - * @arg @ref LL_AHB3_GRP1_PERIPH_FMC (*) - * @arg @ref LL_AHB3_GRP1_PERIPH_FSMC (*) - * @arg @ref LL_AHB3_GRP1_PERIPH_QSPI (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB3_GRP1_ForceReset(uint32_t Periphs) -{ - SET_BIT(RCC->AHB3RSTR, Periphs); -} - -/** - * @brief Release AHB3 peripherals reset. - * @rmtoll AHB3RSTR FMCRST LL_AHB3_GRP1_ReleaseReset\n - * AHB3RSTR FSMCRST LL_AHB3_GRP1_ReleaseReset\n - * AHB3RSTR QSPIRST LL_AHB3_GRP1_ReleaseReset - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB2_GRP1_PERIPH_ALL - * @arg @ref LL_AHB3_GRP1_PERIPH_FMC (*) - * @arg @ref LL_AHB3_GRP1_PERIPH_FSMC (*) - * @arg @ref LL_AHB3_GRP1_PERIPH_QSPI (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB3_GRP1_ReleaseReset(uint32_t Periphs) -{ - CLEAR_BIT(RCC->AHB3RSTR, Periphs); -} - -/** - * @brief Enable AHB3 peripheral clocks in low-power mode - * @rmtoll AHB3LPENR FMCLPEN LL_AHB3_GRP1_EnableClockLowPower\n - * AHB3LPENR FSMCLPEN LL_AHB3_GRP1_EnableClockLowPower\n - * AHB3LPENR QSPILPEN LL_AHB3_GRP1_EnableClockLowPower - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB3_GRP1_PERIPH_FMC (*) - * @arg @ref LL_AHB3_GRP1_PERIPH_FSMC (*) - * @arg @ref LL_AHB3_GRP1_PERIPH_QSPI (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB3_GRP1_EnableClockLowPower(uint32_t Periphs) -{ - __IO uint32_t tmpreg; - SET_BIT(RCC->AHB3LPENR, Periphs); - /* Delay after an RCC peripheral clock enabling */ - tmpreg = READ_BIT(RCC->AHB3LPENR, Periphs); - (void)tmpreg; -} - -/** - * @brief Disable AHB3 peripheral clocks in low-power mode - * @rmtoll AHB3LPENR FMCLPEN LL_AHB3_GRP1_DisableClockLowPower\n - * AHB3LPENR FSMCLPEN LL_AHB3_GRP1_DisableClockLowPower\n - * AHB3LPENR QSPILPEN LL_AHB3_GRP1_DisableClockLowPower - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_AHB3_GRP1_PERIPH_FMC (*) - * @arg @ref LL_AHB3_GRP1_PERIPH_FSMC (*) - * @arg @ref LL_AHB3_GRP1_PERIPH_QSPI (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_AHB3_GRP1_DisableClockLowPower(uint32_t Periphs) -{ - CLEAR_BIT(RCC->AHB3LPENR, Periphs); -} - -/** - * @} - */ -#endif /* RCC_AHB3_SUPPORT */ - -/** @defgroup BUS_LL_EF_APB1 APB1 - * @{ - */ - -/** - * @brief Enable APB1 peripherals clock. - * @rmtoll APB1ENR TIM2EN LL_APB1_GRP1_EnableClock\n - * APB1ENR TIM3EN LL_APB1_GRP1_EnableClock\n - * APB1ENR TIM4EN LL_APB1_GRP1_EnableClock\n - * APB1ENR TIM5EN LL_APB1_GRP1_EnableClock\n - * APB1ENR TIM6EN LL_APB1_GRP1_EnableClock\n - * APB1ENR TIM7EN LL_APB1_GRP1_EnableClock\n - * APB1ENR TIM12EN LL_APB1_GRP1_EnableClock\n - * APB1ENR TIM13EN LL_APB1_GRP1_EnableClock\n - * APB1ENR TIM14EN LL_APB1_GRP1_EnableClock\n - * APB1ENR LPTIM1EN LL_APB1_GRP1_EnableClock\n - * APB1ENR WWDGEN LL_APB1_GRP1_EnableClock\n - * APB1ENR SPI2EN LL_APB1_GRP1_EnableClock\n - * APB1ENR SPI3EN LL_APB1_GRP1_EnableClock\n - * APB1ENR SPDIFRXEN LL_APB1_GRP1_EnableClock\n - * APB1ENR USART2EN LL_APB1_GRP1_EnableClock\n - * APB1ENR USART3EN LL_APB1_GRP1_EnableClock\n - * APB1ENR UART4EN LL_APB1_GRP1_EnableClock\n - * APB1ENR UART5EN LL_APB1_GRP1_EnableClock\n - * APB1ENR I2C1EN LL_APB1_GRP1_EnableClock\n - * APB1ENR I2C2EN LL_APB1_GRP1_EnableClock\n - * APB1ENR I2C3EN LL_APB1_GRP1_EnableClock\n - * APB1ENR FMPI2C1EN LL_APB1_GRP1_EnableClock\n - * APB1ENR CAN1EN LL_APB1_GRP1_EnableClock\n - * APB1ENR CAN2EN LL_APB1_GRP1_EnableClock\n - * APB1ENR CAN3EN LL_APB1_GRP1_EnableClock\n - * APB1ENR CECEN LL_APB1_GRP1_EnableClock\n - * APB1ENR PWREN LL_APB1_GRP1_EnableClock\n - * APB1ENR DACEN LL_APB1_GRP1_EnableClock\n - * APB1ENR UART7EN LL_APB1_GRP1_EnableClock\n - * APB1ENR UART8EN LL_APB1_GRP1_EnableClock\n - * APB1ENR RTCAPBEN LL_APB1_GRP1_EnableClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_APB1_GRP1_PERIPH_TIM2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM4 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM5 - * @arg @ref LL_APB1_GRP1_PERIPH_TIM6 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM7 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM12 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM13 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM14 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_LPTIM1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_WWDG - * @arg @ref LL_APB1_GRP1_PERIPH_SPI2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_SPI3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_SPDIFRX (*) - * @arg @ref LL_APB1_GRP1_PERIPH_USART2 - * @arg @ref LL_APB1_GRP1_PERIPH_USART3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART4 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART5 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_I2C1 - * @arg @ref LL_APB1_GRP1_PERIPH_I2C2 - * @arg @ref LL_APB1_GRP1_PERIPH_I2C3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_FMPI2C1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CEC (*) - * @arg @ref LL_APB1_GRP1_PERIPH_PWR - * @arg @ref LL_APB1_GRP1_PERIPH_DAC1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART7 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART8 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_RTCAPB (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_APB1_GRP1_EnableClock(uint32_t Periphs) -{ - __IO uint32_t tmpreg; - SET_BIT(RCC->APB1ENR, Periphs); - /* Delay after an RCC peripheral clock enabling */ - tmpreg = READ_BIT(RCC->APB1ENR, Periphs); - (void)tmpreg; -} - -/** - * @brief Check if APB1 peripheral clock is enabled or not - * @rmtoll APB1ENR TIM2EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR TIM3EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR TIM4EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR TIM5EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR TIM6EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR TIM7EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR TIM12EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR TIM13EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR TIM14EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR LPTIM1EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR WWDGEN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR SPI2EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR SPI3EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR SPDIFRXEN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR USART2EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR USART3EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR UART4EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR UART5EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR I2C1EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR I2C2EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR I2C3EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR FMPI2C1EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR CAN1EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR CAN2EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR CAN3EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR CECEN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR PWREN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR DACEN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR UART7EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR UART8EN LL_APB1_GRP1_IsEnabledClock\n - * APB1ENR RTCAPBEN LL_APB1_GRP1_IsEnabledClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_APB1_GRP1_PERIPH_TIM2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM4 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM5 - * @arg @ref LL_APB1_GRP1_PERIPH_TIM6 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM7 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM12 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM13 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM14 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_LPTIM1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_WWDG - * @arg @ref LL_APB1_GRP1_PERIPH_SPI2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_SPI3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_SPDIFRX (*) - * @arg @ref LL_APB1_GRP1_PERIPH_USART2 - * @arg @ref LL_APB1_GRP1_PERIPH_USART3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART4 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART5 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_I2C1 - * @arg @ref LL_APB1_GRP1_PERIPH_I2C2 - * @arg @ref LL_APB1_GRP1_PERIPH_I2C3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_FMPI2C1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CEC (*) - * @arg @ref LL_APB1_GRP1_PERIPH_PWR - * @arg @ref LL_APB1_GRP1_PERIPH_DAC1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART7 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART8 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_RTCAPB (*) - * - * (*) value not defined in all devices. - * @retval State of Periphs (1 or 0). -*/ -__STATIC_INLINE uint32_t LL_APB1_GRP1_IsEnabledClock(uint32_t Periphs) -{ - return (READ_BIT(RCC->APB1ENR, Periphs) == Periphs); -} - -/** - * @brief Disable APB1 peripherals clock. - * @rmtoll APB1ENR TIM2EN LL_APB1_GRP1_DisableClock\n - * APB1ENR TIM3EN LL_APB1_GRP1_DisableClock\n - * APB1ENR TIM4EN LL_APB1_GRP1_DisableClock\n - * APB1ENR TIM5EN LL_APB1_GRP1_DisableClock\n - * APB1ENR TIM6EN LL_APB1_GRP1_DisableClock\n - * APB1ENR TIM7EN LL_APB1_GRP1_DisableClock\n - * APB1ENR TIM12EN LL_APB1_GRP1_DisableClock\n - * APB1ENR TIM13EN LL_APB1_GRP1_DisableClock\n - * APB1ENR TIM14EN LL_APB1_GRP1_DisableClock\n - * APB1ENR LPTIM1EN LL_APB1_GRP1_DisableClock\n - * APB1ENR WWDGEN LL_APB1_GRP1_DisableClock\n - * APB1ENR SPI2EN LL_APB1_GRP1_DisableClock\n - * APB1ENR SPI3EN LL_APB1_GRP1_DisableClock\n - * APB1ENR SPDIFRXEN LL_APB1_GRP1_DisableClock\n - * APB1ENR USART2EN LL_APB1_GRP1_DisableClock\n - * APB1ENR USART3EN LL_APB1_GRP1_DisableClock\n - * APB1ENR UART4EN LL_APB1_GRP1_DisableClock\n - * APB1ENR UART5EN LL_APB1_GRP1_DisableClock\n - * APB1ENR I2C1EN LL_APB1_GRP1_DisableClock\n - * APB1ENR I2C2EN LL_APB1_GRP1_DisableClock\n - * APB1ENR I2C3EN LL_APB1_GRP1_DisableClock\n - * APB1ENR FMPI2C1EN LL_APB1_GRP1_DisableClock\n - * APB1ENR CAN1EN LL_APB1_GRP1_DisableClock\n - * APB1ENR CAN2EN LL_APB1_GRP1_DisableClock\n - * APB1ENR CAN3EN LL_APB1_GRP1_DisableClock\n - * APB1ENR CECEN LL_APB1_GRP1_DisableClock\n - * APB1ENR PWREN LL_APB1_GRP1_DisableClock\n - * APB1ENR DACEN LL_APB1_GRP1_DisableClock\n - * APB1ENR UART7EN LL_APB1_GRP1_DisableClock\n - * APB1ENR UART8EN LL_APB1_GRP1_DisableClock\n - * APB1ENR RTCAPBEN LL_APB1_GRP1_DisableClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_APB1_GRP1_PERIPH_TIM2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM4 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM5 - * @arg @ref LL_APB1_GRP1_PERIPH_TIM6 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM7 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM12 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM13 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM14 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_LPTIM1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_WWDG - * @arg @ref LL_APB1_GRP1_PERIPH_SPI2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_SPI3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_SPDIFRX (*) - * @arg @ref LL_APB1_GRP1_PERIPH_USART2 - * @arg @ref LL_APB1_GRP1_PERIPH_USART3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART4 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART5 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_I2C1 - * @arg @ref LL_APB1_GRP1_PERIPH_I2C2 - * @arg @ref LL_APB1_GRP1_PERIPH_I2C3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_FMPI2C1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CEC (*) - * @arg @ref LL_APB1_GRP1_PERIPH_PWR - * @arg @ref LL_APB1_GRP1_PERIPH_DAC1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART7 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART8 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_RTCAPB (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_APB1_GRP1_DisableClock(uint32_t Periphs) -{ - CLEAR_BIT(RCC->APB1ENR, Periphs); -} - -/** - * @brief Force APB1 peripherals reset. - * @rmtoll APB1RSTR TIM2RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR TIM3RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR TIM4RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR TIM5RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR TIM6RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR TIM7RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR TIM12RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR TIM13RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR TIM14RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR LPTIM1RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR WWDGRST LL_APB1_GRP1_ForceReset\n - * APB1RSTR SPI2RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR SPI3RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR SPDIFRXRST LL_APB1_GRP1_ForceReset\n - * APB1RSTR USART2RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR USART3RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR UART4RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR UART5RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR I2C1RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR I2C2RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR I2C3RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR FMPI2C1RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR CAN1RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR CAN2RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR CAN3RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR CECRST LL_APB1_GRP1_ForceReset\n - * APB1RSTR PWRRST LL_APB1_GRP1_ForceReset\n - * APB1RSTR DACRST LL_APB1_GRP1_ForceReset\n - * APB1RSTR UART7RST LL_APB1_GRP1_ForceReset\n - * APB1RSTR UART8RST LL_APB1_GRP1_ForceReset - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_APB1_GRP1_PERIPH_TIM2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM4 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM5 - * @arg @ref LL_APB1_GRP1_PERIPH_TIM6 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM7 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM12 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM13 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM14 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_LPTIM1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_WWDG - * @arg @ref LL_APB1_GRP1_PERIPH_SPI2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_SPI3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_SPDIFRX (*) - * @arg @ref LL_APB1_GRP1_PERIPH_USART2 - * @arg @ref LL_APB1_GRP1_PERIPH_USART3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART4 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART5 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_I2C1 - * @arg @ref LL_APB1_GRP1_PERIPH_I2C2 - * @arg @ref LL_APB1_GRP1_PERIPH_I2C3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_FMPI2C1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CEC (*) - * @arg @ref LL_APB1_GRP1_PERIPH_PWR - * @arg @ref LL_APB1_GRP1_PERIPH_DAC1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART7 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART8 (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_APB1_GRP1_ForceReset(uint32_t Periphs) -{ - SET_BIT(RCC->APB1RSTR, Periphs); -} - -/** - * @brief Release APB1 peripherals reset. - * @rmtoll APB1RSTR TIM2RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR TIM3RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR TIM4RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR TIM5RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR TIM6RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR TIM7RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR TIM12RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR TIM13RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR TIM14RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR LPTIM1RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR WWDGRST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR SPI2RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR SPI3RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR SPDIFRXRST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR USART2RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR USART3RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR UART4RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR UART5RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR I2C1RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR I2C2RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR I2C3RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR FMPI2C1RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR CAN1RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR CAN2RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR CAN3RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR CECRST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR PWRRST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR DACRST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR UART7RST LL_APB1_GRP1_ReleaseReset\n - * APB1RSTR UART8RST LL_APB1_GRP1_ReleaseReset - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_APB1_GRP1_PERIPH_TIM2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM4 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM5 - * @arg @ref LL_APB1_GRP1_PERIPH_TIM6 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM7 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM12 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM13 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM14 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_LPTIM1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_WWDG - * @arg @ref LL_APB1_GRP1_PERIPH_SPI2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_SPI3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_SPDIFRX (*) - * @arg @ref LL_APB1_GRP1_PERIPH_USART2 - * @arg @ref LL_APB1_GRP1_PERIPH_USART3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART4 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART5 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_I2C1 - * @arg @ref LL_APB1_GRP1_PERIPH_I2C2 - * @arg @ref LL_APB1_GRP1_PERIPH_I2C3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_FMPI2C1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CEC (*) - * @arg @ref LL_APB1_GRP1_PERIPH_PWR - * @arg @ref LL_APB1_GRP1_PERIPH_DAC1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART7 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART8 (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_APB1_GRP1_ReleaseReset(uint32_t Periphs) -{ - CLEAR_BIT(RCC->APB1RSTR, Periphs); -} - -/** - * @brief Enable APB1 peripheral clocks in low-power mode - * @rmtoll APB1LPENR TIM2LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR TIM3LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR TIM4LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR TIM5LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR TIM6LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR TIM7LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR TIM12LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR TIM13LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR TIM14LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR LPTIM1LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR WWDGLPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR SPI2LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR SPI3LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR SPDIFRXLPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR USART2LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR USART3LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR UART4LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR UART5LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR I2C1LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR I2C2LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR I2C3LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR FMPI2C1LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR CAN1LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR CAN2LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR CAN3LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR CECLPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR PWRLPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR DACLPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR UART7LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR UART8LPEN LL_APB1_GRP1_EnableClockLowPower\n - * APB1LPENR RTCAPBLPEN LL_APB1_GRP1_EnableClockLowPower - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_APB1_GRP1_PERIPH_TIM2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM4 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM5 - * @arg @ref LL_APB1_GRP1_PERIPH_TIM6 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM7 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM12 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM13 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM14 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_LPTIM1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_WWDG - * @arg @ref LL_APB1_GRP1_PERIPH_SPI2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_SPI3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_SPDIFRX (*) - * @arg @ref LL_APB1_GRP1_PERIPH_USART2 - * @arg @ref LL_APB1_GRP1_PERIPH_USART3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART4 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART5 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_I2C1 - * @arg @ref LL_APB1_GRP1_PERIPH_I2C2 - * @arg @ref LL_APB1_GRP1_PERIPH_I2C3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_FMPI2C1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CEC (*) - * @arg @ref LL_APB1_GRP1_PERIPH_PWR - * @arg @ref LL_APB1_GRP1_PERIPH_DAC1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART7 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART8 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_RTCAPB (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_APB1_GRP1_EnableClockLowPower(uint32_t Periphs) -{ - __IO uint32_t tmpreg; - SET_BIT(RCC->APB1LPENR, Periphs); - /* Delay after an RCC peripheral clock enabling */ - tmpreg = READ_BIT(RCC->APB1LPENR, Periphs); - (void)tmpreg; -} - -/** - * @brief Disable APB1 peripheral clocks in low-power mode - * @rmtoll APB1LPENR TIM2LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR TIM3LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR TIM4LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR TIM5LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR TIM6LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR TIM7LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR TIM12LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR TIM13LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR TIM14LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR LPTIM1LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR WWDGLPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR SPI2LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR SPI3LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR SPDIFRXLPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR USART2LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR USART3LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR UART4LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR UART5LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR I2C1LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR I2C2LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR I2C3LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR FMPI2C1LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR CAN1LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR CAN2LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR CAN3LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR CECLPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR PWRLPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR DACLPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR UART7LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR UART8LPEN LL_APB1_GRP1_DisableClockLowPower\n - * APB1LPENR RTCAPBLPEN LL_APB1_GRP1_DisableClockLowPower - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_APB1_GRP1_PERIPH_TIM2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM4 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM5 - * @arg @ref LL_APB1_GRP1_PERIPH_TIM6 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM7 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM12 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM13 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_TIM14 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_LPTIM1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_WWDG - * @arg @ref LL_APB1_GRP1_PERIPH_SPI2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_SPI3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_SPDIFRX (*) - * @arg @ref LL_APB1_GRP1_PERIPH_USART2 - * @arg @ref LL_APB1_GRP1_PERIPH_USART3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART4 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART5 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_I2C1 - * @arg @ref LL_APB1_GRP1_PERIPH_I2C2 - * @arg @ref LL_APB1_GRP1_PERIPH_I2C3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_FMPI2C1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN2 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CAN3 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_CEC (*) - * @arg @ref LL_APB1_GRP1_PERIPH_PWR - * @arg @ref LL_APB1_GRP1_PERIPH_DAC1 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART7 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_UART8 (*) - * @arg @ref LL_APB1_GRP1_PERIPH_RTCAPB (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_APB1_GRP1_DisableClockLowPower(uint32_t Periphs) -{ - CLEAR_BIT(RCC->APB1LPENR, Periphs); -} - -/** - * @} - */ - -/** @defgroup BUS_LL_EF_APB2 APB2 - * @{ - */ - -/** - * @brief Enable APB2 peripherals clock. - * @rmtoll APB2ENR TIM1EN LL_APB2_GRP1_EnableClock\n - * APB2ENR TIM8EN LL_APB2_GRP1_EnableClock\n - * APB2ENR USART1EN LL_APB2_GRP1_EnableClock\n - * APB2ENR USART6EN LL_APB2_GRP1_EnableClock\n - * APB2ENR UART9EN LL_APB2_GRP1_EnableClock\n - * APB2ENR UART10EN LL_APB2_GRP1_EnableClock\n - * APB2ENR ADC1EN LL_APB2_GRP1_EnableClock\n - * APB2ENR ADC2EN LL_APB2_GRP1_EnableClock\n - * APB2ENR ADC3EN LL_APB2_GRP1_EnableClock\n - * APB2ENR SDIOEN LL_APB2_GRP1_EnableClock\n - * APB2ENR SPI1EN LL_APB2_GRP1_EnableClock\n - * APB2ENR SPI4EN LL_APB2_GRP1_EnableClock\n - * APB2ENR SYSCFGEN LL_APB2_GRP1_EnableClock\n - * APB2ENR EXTITEN LL_APB2_GRP1_EnableClock\n - * APB2ENR TIM9EN LL_APB2_GRP1_EnableClock\n - * APB2ENR TIM10EN LL_APB2_GRP1_EnableClock\n - * APB2ENR TIM11EN LL_APB2_GRP1_EnableClock\n - * APB2ENR SPI5EN LL_APB2_GRP1_EnableClock\n - * APB2ENR SPI6EN LL_APB2_GRP1_EnableClock\n - * APB2ENR SAI1EN LL_APB2_GRP1_EnableClock\n - * APB2ENR SAI2EN LL_APB2_GRP1_EnableClock\n - * APB2ENR LTDCEN LL_APB2_GRP1_EnableClock\n - * APB2ENR DSIEN LL_APB2_GRP1_EnableClock\n - * APB2ENR DFSDM1EN LL_APB2_GRP1_EnableClock\n - * APB2ENR DFSDM2EN LL_APB2_GRP1_EnableClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_APB2_GRP1_PERIPH_TIM1 - * @arg @ref LL_APB2_GRP1_PERIPH_TIM8 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_USART1 - * @arg @ref LL_APB2_GRP1_PERIPH_USART6 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_UART9 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_UART10 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_ADC1 - * @arg @ref LL_APB2_GRP1_PERIPH_ADC2 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_ADC3 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SDIO (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SPI1 - * @arg @ref LL_APB2_GRP1_PERIPH_SPI4 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SYSCFG - * @arg @ref LL_APB2_GRP1_PERIPH_EXTI (*) - * @arg @ref LL_APB2_GRP1_PERIPH_TIM9 - * @arg @ref LL_APB2_GRP1_PERIPH_TIM10 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_TIM11 - * @arg @ref LL_APB2_GRP1_PERIPH_SPI5 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SPI6 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SAI1 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SAI2 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_LTDC (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DSI (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM1 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM2 (*) - - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_APB2_GRP1_EnableClock(uint32_t Periphs) -{ - __IO uint32_t tmpreg; - SET_BIT(RCC->APB2ENR, Periphs); - /* Delay after an RCC peripheral clock enabling */ - tmpreg = READ_BIT(RCC->APB2ENR, Periphs); - (void)tmpreg; -} - -/** - * @brief Check if APB2 peripheral clock is enabled or not - * @rmtoll APB2ENR TIM1EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR TIM8EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR USART1EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR USART6EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR UART9EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR UART10EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR ADC1EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR ADC2EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR ADC3EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR SDIOEN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR SPI1EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR SPI4EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR SYSCFGEN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR EXTITEN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR TIM9EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR TIM10EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR TIM11EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR SPI5EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR SPI6EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR SAI1EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR SAI2EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR LTDCEN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR DSIEN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR DFSDM1EN LL_APB2_GRP1_IsEnabledClock\n - * APB2ENR DFSDM2EN LL_APB2_GRP1_IsEnabledClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_APB2_GRP1_PERIPH_TIM1 - * @arg @ref LL_APB2_GRP1_PERIPH_TIM8 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_USART1 - * @arg @ref LL_APB2_GRP1_PERIPH_USART6 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_UART9 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_UART10 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_ADC1 - * @arg @ref LL_APB2_GRP1_PERIPH_ADC2 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_ADC3 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SDIO (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SPI1 - * @arg @ref LL_APB2_GRP1_PERIPH_SPI4 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SYSCFG - * @arg @ref LL_APB2_GRP1_PERIPH_EXTI (*) - * @arg @ref LL_APB2_GRP1_PERIPH_TIM9 - * @arg @ref LL_APB2_GRP1_PERIPH_TIM10 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_TIM11 - * @arg @ref LL_APB2_GRP1_PERIPH_SPI5 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SPI6 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SAI1 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SAI2 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_LTDC (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DSI (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM1 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM2 (*) - * - * (*) value not defined in all devices. - * @retval State of Periphs (1 or 0). -*/ -__STATIC_INLINE uint32_t LL_APB2_GRP1_IsEnabledClock(uint32_t Periphs) -{ - return (READ_BIT(RCC->APB2ENR, Periphs) == Periphs); -} - -/** - * @brief Disable APB2 peripherals clock. - * @rmtoll APB2ENR TIM1EN LL_APB2_GRP1_DisableClock\n - * APB2ENR TIM8EN LL_APB2_GRP1_DisableClock\n - * APB2ENR USART1EN LL_APB2_GRP1_DisableClock\n - * APB2ENR USART6EN LL_APB2_GRP1_DisableClock\n - * APB2ENR UART9EN LL_APB2_GRP1_DisableClock\n - * APB2ENR UART10EN LL_APB2_GRP1_DisableClock\n - * APB2ENR ADC1EN LL_APB2_GRP1_DisableClock\n - * APB2ENR ADC2EN LL_APB2_GRP1_DisableClock\n - * APB2ENR ADC3EN LL_APB2_GRP1_DisableClock\n - * APB2ENR SDIOEN LL_APB2_GRP1_DisableClock\n - * APB2ENR SPI1EN LL_APB2_GRP1_DisableClock\n - * APB2ENR SPI4EN LL_APB2_GRP1_DisableClock\n - * APB2ENR SYSCFGEN LL_APB2_GRP1_DisableClock\n - * APB2ENR EXTITEN LL_APB2_GRP1_DisableClock\n - * APB2ENR TIM9EN LL_APB2_GRP1_DisableClock\n - * APB2ENR TIM10EN LL_APB2_GRP1_DisableClock\n - * APB2ENR TIM11EN LL_APB2_GRP1_DisableClock\n - * APB2ENR SPI5EN LL_APB2_GRP1_DisableClock\n - * APB2ENR SPI6EN LL_APB2_GRP1_DisableClock\n - * APB2ENR SAI1EN LL_APB2_GRP1_DisableClock\n - * APB2ENR SAI2EN LL_APB2_GRP1_DisableClock\n - * APB2ENR LTDCEN LL_APB2_GRP1_DisableClock\n - * APB2ENR DSIEN LL_APB2_GRP1_DisableClock\n - * APB2ENR DFSDM1EN LL_APB2_GRP1_DisableClock\n - * APB2ENR DFSDM2EN LL_APB2_GRP1_DisableClock - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_APB2_GRP1_PERIPH_TIM1 - * @arg @ref LL_APB2_GRP1_PERIPH_TIM8 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_USART1 - * @arg @ref LL_APB2_GRP1_PERIPH_USART6 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_UART9 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_UART10 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_ADC1 - * @arg @ref LL_APB2_GRP1_PERIPH_ADC2 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_ADC3 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SDIO (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SPI1 - * @arg @ref LL_APB2_GRP1_PERIPH_SPI4 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SYSCFG - * @arg @ref LL_APB2_GRP1_PERIPH_EXTI (*) - * @arg @ref LL_APB2_GRP1_PERIPH_TIM9 - * @arg @ref LL_APB2_GRP1_PERIPH_TIM10 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_TIM11 - * @arg @ref LL_APB2_GRP1_PERIPH_SPI5 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SPI6 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SAI1 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SAI2 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_LTDC (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DSI (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM1 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM2 (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_APB2_GRP1_DisableClock(uint32_t Periphs) -{ - CLEAR_BIT(RCC->APB2ENR, Periphs); -} - -/** - * @brief Force APB2 peripherals reset. - * @rmtoll APB2RSTR TIM1RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR TIM8RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR USART1RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR USART6RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR UART9RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR UART10RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR ADCRST LL_APB2_GRP1_ForceReset\n - * APB2RSTR SDIORST LL_APB2_GRP1_ForceReset\n - * APB2RSTR SPI1RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR SPI4RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR SYSCFGRST LL_APB2_GRP1_ForceReset\n - * APB2RSTR TIM9RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR TIM10RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR TIM11RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR SPI5RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR SPI6RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR SAI1RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR SAI2RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR LTDCRST LL_APB2_GRP1_ForceReset\n - * APB2RSTR DSIRST LL_APB2_GRP1_ForceReset\n - * APB2RSTR DFSDM1RST LL_APB2_GRP1_ForceReset\n - * APB2RSTR DFSDM2RST LL_APB2_GRP1_ForceReset - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_APB2_GRP1_PERIPH_ALL - * @arg @ref LL_APB2_GRP1_PERIPH_TIM1 - * @arg @ref LL_APB2_GRP1_PERIPH_TIM8 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_USART1 - * @arg @ref LL_APB2_GRP1_PERIPH_USART6 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_UART9 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_UART10 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_ADC - * @arg @ref LL_APB2_GRP1_PERIPH_SDIO (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SPI1 - * @arg @ref LL_APB2_GRP1_PERIPH_SPI4 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SYSCFG - * @arg @ref LL_APB2_GRP1_PERIPH_TIM9 - * @arg @ref LL_APB2_GRP1_PERIPH_TIM10 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_TIM11 - * @arg @ref LL_APB2_GRP1_PERIPH_SPI5 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SPI6 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SAI1 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SAI2 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_LTDC (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DSI (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM1 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM2 (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_APB2_GRP1_ForceReset(uint32_t Periphs) -{ - SET_BIT(RCC->APB2RSTR, Periphs); -} - -/** - * @brief Release APB2 peripherals reset. - * @rmtoll APB2RSTR TIM1RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR TIM8RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR USART1RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR USART6RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR UART9RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR UART10RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR ADCRST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR SDIORST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR SPI1RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR SPI4RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR SYSCFGRST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR TIM9RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR TIM10RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR TIM11RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR SPI5RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR SPI6RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR SAI1RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR SAI2RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR LTDCRST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR DSIRST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR DFSDM1RST LL_APB2_GRP1_ReleaseReset\n - * APB2RSTR DFSDM2RST LL_APB2_GRP1_ReleaseReset - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_APB2_GRP1_PERIPH_ALL - * @arg @ref LL_APB2_GRP1_PERIPH_TIM1 - * @arg @ref LL_APB2_GRP1_PERIPH_TIM8 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_USART1 - * @arg @ref LL_APB2_GRP1_PERIPH_USART6 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_UART9 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_UART10 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_ADC - * @arg @ref LL_APB2_GRP1_PERIPH_SDIO (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SPI1 - * @arg @ref LL_APB2_GRP1_PERIPH_SPI4 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SYSCFG - * @arg @ref LL_APB2_GRP1_PERIPH_EXTI (*) - * @arg @ref LL_APB2_GRP1_PERIPH_TIM9 - * @arg @ref LL_APB2_GRP1_PERIPH_TIM10 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_TIM11 - * @arg @ref LL_APB2_GRP1_PERIPH_SPI5 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SPI6 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SAI1 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SAI2 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_LTDC (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DSI (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM1 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM2 (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_APB2_GRP1_ReleaseReset(uint32_t Periphs) -{ - CLEAR_BIT(RCC->APB2RSTR, Periphs); -} - -/** - * @brief Enable APB2 peripheral clocks in low-power mode - * @rmtoll APB2LPENR TIM1LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR TIM8LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR USART1LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR USART6LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR UART9LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR UART10LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR ADC1LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR ADC2LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR ADC3LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR SDIOLPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR SPI1LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR SPI4LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR SYSCFGLPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR EXTITLPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR TIM9LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR TIM10LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR TIM11LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR SPI5LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR SPI6LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR SAI1LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR SAI2LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR LTDCLPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR DSILPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR DFSDM1LPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR DSILPEN LL_APB2_GRP1_EnableClockLowPower\n - * APB2LPENR DFSDM2LPEN LL_APB2_GRP1_EnableClockLowPower - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_APB2_GRP1_PERIPH_TIM1 - * @arg @ref LL_APB2_GRP1_PERIPH_TIM8 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_USART1 - * @arg @ref LL_APB2_GRP1_PERIPH_USART6 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_UART9 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_UART10 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_ADC1 - * @arg @ref LL_APB2_GRP1_PERIPH_ADC2 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_ADC3 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SDIO (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SPI1 - * @arg @ref LL_APB2_GRP1_PERIPH_SPI4 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SYSCFG - * @arg @ref LL_APB2_GRP1_PERIPH_EXTI (*) - * @arg @ref LL_APB2_GRP1_PERIPH_TIM9 - * @arg @ref LL_APB2_GRP1_PERIPH_TIM10 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_TIM11 - * @arg @ref LL_APB2_GRP1_PERIPH_SPI5 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SPI6 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SAI1 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SAI2 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_LTDC (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DSI (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM1 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM2 (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_APB2_GRP1_EnableClockLowPower(uint32_t Periphs) -{ - __IO uint32_t tmpreg; - SET_BIT(RCC->APB2LPENR, Periphs); - /* Delay after an RCC peripheral clock enabling */ - tmpreg = READ_BIT(RCC->APB2LPENR, Periphs); - (void)tmpreg; -} - -/** - * @brief Disable APB2 peripheral clocks in low-power mode - * @rmtoll APB2LPENR TIM1LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR TIM8LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR USART1LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR USART6LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR UART9LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR UART10LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR ADC1LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR ADC2LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR ADC3LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR SDIOLPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR SPI1LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR SPI4LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR SYSCFGLPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR EXTITLPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR TIM9LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR TIM10LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR TIM11LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR SPI5LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR SPI6LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR SAI1LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR SAI2LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR LTDCLPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR DSILPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR DFSDM1LPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR DSILPEN LL_APB2_GRP1_DisableClockLowPower\n - * APB2LPENR DFSDM2LPEN LL_APB2_GRP1_DisableClockLowPower - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_APB2_GRP1_PERIPH_TIM1 - * @arg @ref LL_APB2_GRP1_PERIPH_TIM8 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_USART1 - * @arg @ref LL_APB2_GRP1_PERIPH_USART6 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_UART9 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_UART10 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_ADC1 - * @arg @ref LL_APB2_GRP1_PERIPH_ADC2 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_ADC3 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SDIO (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SPI1 - * @arg @ref LL_APB2_GRP1_PERIPH_SPI4 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SYSCFG - * @arg @ref LL_APB2_GRP1_PERIPH_EXTI (*) - * @arg @ref LL_APB2_GRP1_PERIPH_TIM9 - * @arg @ref LL_APB2_GRP1_PERIPH_TIM10 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_TIM11 - * @arg @ref LL_APB2_GRP1_PERIPH_SPI5 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SPI6 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SAI1 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_SAI2 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_LTDC (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DSI (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM1 (*) - * @arg @ref LL_APB2_GRP1_PERIPH_DFSDM2 (*) - * - * (*) value not defined in all devices. - * @retval None -*/ -__STATIC_INLINE void LL_APB2_GRP1_DisableClockLowPower(uint32_t Periphs) -{ - CLEAR_BIT(RCC->APB2LPENR, Periphs); -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* defined(RCC) */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_BUS_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_cortex.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_cortex.h deleted file mode 100644 index eddcc97..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_cortex.h +++ /dev/null @@ -1,640 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_cortex.h - * @author MCD Application Team - * @brief Header file of CORTEX LL module. - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - The LL CORTEX driver contains a set of generic APIs that can be - used by user: - (+) SYSTICK configuration used by LL_mDelay and LL_Init1msTick - functions - (+) Low power mode configuration (SCB register of Cortex-MCU) - (+) MPU API to configure and enable regions - (MPU services provided only on some devices) - (+) API to access to MCU info (CPUID register) - (+) API to enable fault handler (SHCSR accesses) - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_LL_CORTEX_H -#define __STM32F4xx_LL_CORTEX_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -/** @defgroup CORTEX_LL CORTEX - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ - -/* Private constants ---------------------------------------------------------*/ - -/* Private macros ------------------------------------------------------------*/ - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/** @defgroup CORTEX_LL_Exported_Constants CORTEX Exported Constants - * @{ - */ - -/** @defgroup CORTEX_LL_EC_CLKSOURCE_HCLK SYSTICK Clock Source - * @{ - */ -#define LL_SYSTICK_CLKSOURCE_HCLK_DIV8 0x00000000U /*!< AHB clock divided by 8 selected as SysTick clock source.*/ -#define LL_SYSTICK_CLKSOURCE_HCLK SysTick_CTRL_CLKSOURCE_Msk /*!< AHB clock selected as SysTick clock source. */ -/** - * @} - */ - -/** @defgroup CORTEX_LL_EC_FAULT Handler Fault type - * @{ - */ -#define LL_HANDLER_FAULT_USG SCB_SHCSR_USGFAULTENA_Msk /*!< Usage fault */ -#define LL_HANDLER_FAULT_BUS SCB_SHCSR_BUSFAULTENA_Msk /*!< Bus fault */ -#define LL_HANDLER_FAULT_MEM SCB_SHCSR_MEMFAULTENA_Msk /*!< Memory management fault */ -/** - * @} - */ - -#if __MPU_PRESENT - -/** @defgroup CORTEX_LL_EC_CTRL_HFNMI_PRIVDEF MPU Control - * @{ - */ -#define LL_MPU_CTRL_HFNMI_PRIVDEF_NONE 0x00000000U /*!< Disable NMI and privileged SW access */ -#define LL_MPU_CTRL_HARDFAULT_NMI MPU_CTRL_HFNMIENA_Msk /*!< Enables the operation of MPU during hard fault, NMI, and FAULTMASK handlers */ -#define LL_MPU_CTRL_PRIVILEGED_DEFAULT MPU_CTRL_PRIVDEFENA_Msk /*!< Enable privileged software access to default memory map */ -#define LL_MPU_CTRL_HFNMI_PRIVDEF (MPU_CTRL_HFNMIENA_Msk | MPU_CTRL_PRIVDEFENA_Msk) /*!< Enable NMI and privileged SW access */ -/** - * @} - */ - -/** @defgroup CORTEX_LL_EC_REGION MPU Region Number - * @{ - */ -#define LL_MPU_REGION_NUMBER0 0x00U /*!< REGION Number 0 */ -#define LL_MPU_REGION_NUMBER1 0x01U /*!< REGION Number 1 */ -#define LL_MPU_REGION_NUMBER2 0x02U /*!< REGION Number 2 */ -#define LL_MPU_REGION_NUMBER3 0x03U /*!< REGION Number 3 */ -#define LL_MPU_REGION_NUMBER4 0x04U /*!< REGION Number 4 */ -#define LL_MPU_REGION_NUMBER5 0x05U /*!< REGION Number 5 */ -#define LL_MPU_REGION_NUMBER6 0x06U /*!< REGION Number 6 */ -#define LL_MPU_REGION_NUMBER7 0x07U /*!< REGION Number 7 */ -/** - * @} - */ - -/** @defgroup CORTEX_LL_EC_REGION_SIZE MPU Region Size - * @{ - */ -#define LL_MPU_REGION_SIZE_32B (0x04U << MPU_RASR_SIZE_Pos) /*!< 32B Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_64B (0x05U << MPU_RASR_SIZE_Pos) /*!< 64B Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_128B (0x06U << MPU_RASR_SIZE_Pos) /*!< 128B Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_256B (0x07U << MPU_RASR_SIZE_Pos) /*!< 256B Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_512B (0x08U << MPU_RASR_SIZE_Pos) /*!< 512B Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_1KB (0x09U << MPU_RASR_SIZE_Pos) /*!< 1KB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_2KB (0x0AU << MPU_RASR_SIZE_Pos) /*!< 2KB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_4KB (0x0BU << MPU_RASR_SIZE_Pos) /*!< 4KB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_8KB (0x0CU << MPU_RASR_SIZE_Pos) /*!< 8KB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_16KB (0x0DU << MPU_RASR_SIZE_Pos) /*!< 16KB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_32KB (0x0EU << MPU_RASR_SIZE_Pos) /*!< 32KB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_64KB (0x0FU << MPU_RASR_SIZE_Pos) /*!< 64KB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_128KB (0x10U << MPU_RASR_SIZE_Pos) /*!< 128KB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_256KB (0x11U << MPU_RASR_SIZE_Pos) /*!< 256KB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_512KB (0x12U << MPU_RASR_SIZE_Pos) /*!< 512KB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_1MB (0x13U << MPU_RASR_SIZE_Pos) /*!< 1MB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_2MB (0x14U << MPU_RASR_SIZE_Pos) /*!< 2MB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_4MB (0x15U << MPU_RASR_SIZE_Pos) /*!< 4MB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_8MB (0x16U << MPU_RASR_SIZE_Pos) /*!< 8MB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_16MB (0x17U << MPU_RASR_SIZE_Pos) /*!< 16MB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_32MB (0x18U << MPU_RASR_SIZE_Pos) /*!< 32MB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_64MB (0x19U << MPU_RASR_SIZE_Pos) /*!< 64MB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_128MB (0x1AU << MPU_RASR_SIZE_Pos) /*!< 128MB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_256MB (0x1BU << MPU_RASR_SIZE_Pos) /*!< 256MB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_512MB (0x1CU << MPU_RASR_SIZE_Pos) /*!< 512MB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_1GB (0x1DU << MPU_RASR_SIZE_Pos) /*!< 1GB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_2GB (0x1EU << MPU_RASR_SIZE_Pos) /*!< 2GB Size of the MPU protection region */ -#define LL_MPU_REGION_SIZE_4GB (0x1FU << MPU_RASR_SIZE_Pos) /*!< 4GB Size of the MPU protection region */ -/** - * @} - */ - -/** @defgroup CORTEX_LL_EC_REGION_PRIVILEDGES MPU Region Privileges - * @{ - */ -#define LL_MPU_REGION_NO_ACCESS (0x00U << MPU_RASR_AP_Pos) /*!< No access*/ -#define LL_MPU_REGION_PRIV_RW (0x01U << MPU_RASR_AP_Pos) /*!< RW privileged (privileged access only)*/ -#define LL_MPU_REGION_PRIV_RW_URO (0x02U << MPU_RASR_AP_Pos) /*!< RW privileged - RO user (Write in a user program generates a fault) */ -#define LL_MPU_REGION_FULL_ACCESS (0x03U << MPU_RASR_AP_Pos) /*!< RW privileged & user (Full access) */ -#define LL_MPU_REGION_PRIV_RO (0x05U << MPU_RASR_AP_Pos) /*!< RO privileged (privileged read only)*/ -#define LL_MPU_REGION_PRIV_RO_URO (0x06U << MPU_RASR_AP_Pos) /*!< RO privileged & user (read only) */ -/** - * @} - */ - -/** @defgroup CORTEX_LL_EC_TEX MPU TEX Level - * @{ - */ -#define LL_MPU_TEX_LEVEL0 (0x00U << MPU_RASR_TEX_Pos) /*!< b000 for TEX bits */ -#define LL_MPU_TEX_LEVEL1 (0x01U << MPU_RASR_TEX_Pos) /*!< b001 for TEX bits */ -#define LL_MPU_TEX_LEVEL2 (0x02U << MPU_RASR_TEX_Pos) /*!< b010 for TEX bits */ -#define LL_MPU_TEX_LEVEL4 (0x04U << MPU_RASR_TEX_Pos) /*!< b100 for TEX bits */ -/** - * @} - */ - -/** @defgroup CORTEX_LL_EC_INSTRUCTION_ACCESS MPU Instruction Access - * @{ - */ -#define LL_MPU_INSTRUCTION_ACCESS_ENABLE 0x00U /*!< Instruction fetches enabled */ -#define LL_MPU_INSTRUCTION_ACCESS_DISABLE MPU_RASR_XN_Msk /*!< Instruction fetches disabled*/ -/** - * @} - */ - -/** @defgroup CORTEX_LL_EC_SHAREABLE_ACCESS MPU Shareable Access - * @{ - */ -#define LL_MPU_ACCESS_SHAREABLE MPU_RASR_S_Msk /*!< Shareable memory attribute */ -#define LL_MPU_ACCESS_NOT_SHAREABLE 0x00U /*!< Not Shareable memory attribute */ -/** - * @} - */ - -/** @defgroup CORTEX_LL_EC_CACHEABLE_ACCESS MPU Cacheable Access - * @{ - */ -#define LL_MPU_ACCESS_CACHEABLE MPU_RASR_C_Msk /*!< Cacheable memory attribute */ -#define LL_MPU_ACCESS_NOT_CACHEABLE 0x00U /*!< Not Cacheable memory attribute */ -/** - * @} - */ - -/** @defgroup CORTEX_LL_EC_BUFFERABLE_ACCESS MPU Bufferable Access - * @{ - */ -#define LL_MPU_ACCESS_BUFFERABLE MPU_RASR_B_Msk /*!< Bufferable memory attribute */ -#define LL_MPU_ACCESS_NOT_BUFFERABLE 0x00U /*!< Not Bufferable memory attribute */ -/** - * @} - */ -#endif /* __MPU_PRESENT */ -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup CORTEX_LL_Exported_Functions CORTEX Exported Functions - * @{ - */ - -/** @defgroup CORTEX_LL_EF_SYSTICK SYSTICK - * @{ - */ - -/** - * @brief This function checks if the Systick counter flag is active or not. - * @note It can be used in timeout function on application side. - * @rmtoll STK_CTRL COUNTFLAG LL_SYSTICK_IsActiveCounterFlag - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_SYSTICK_IsActiveCounterFlag(void) -{ - return ((SysTick->CTRL & SysTick_CTRL_COUNTFLAG_Msk) == (SysTick_CTRL_COUNTFLAG_Msk)); -} - -/** - * @brief Configures the SysTick clock source - * @rmtoll STK_CTRL CLKSOURCE LL_SYSTICK_SetClkSource - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSTICK_CLKSOURCE_HCLK_DIV8 - * @arg @ref LL_SYSTICK_CLKSOURCE_HCLK - * @retval None - */ -__STATIC_INLINE void LL_SYSTICK_SetClkSource(uint32_t Source) -{ - if (Source == LL_SYSTICK_CLKSOURCE_HCLK) - { - SET_BIT(SysTick->CTRL, LL_SYSTICK_CLKSOURCE_HCLK); - } - else - { - CLEAR_BIT(SysTick->CTRL, LL_SYSTICK_CLKSOURCE_HCLK); - } -} - -/** - * @brief Get the SysTick clock source - * @rmtoll STK_CTRL CLKSOURCE LL_SYSTICK_GetClkSource - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSTICK_CLKSOURCE_HCLK_DIV8 - * @arg @ref LL_SYSTICK_CLKSOURCE_HCLK - */ -__STATIC_INLINE uint32_t LL_SYSTICK_GetClkSource(void) -{ - return READ_BIT(SysTick->CTRL, LL_SYSTICK_CLKSOURCE_HCLK); -} - -/** - * @brief Enable SysTick exception request - * @rmtoll STK_CTRL TICKINT LL_SYSTICK_EnableIT - * @retval None - */ -__STATIC_INLINE void LL_SYSTICK_EnableIT(void) -{ - SET_BIT(SysTick->CTRL, SysTick_CTRL_TICKINT_Msk); -} - -/** - * @brief Disable SysTick exception request - * @rmtoll STK_CTRL TICKINT LL_SYSTICK_DisableIT - * @retval None - */ -__STATIC_INLINE void LL_SYSTICK_DisableIT(void) -{ - CLEAR_BIT(SysTick->CTRL, SysTick_CTRL_TICKINT_Msk); -} - -/** - * @brief Checks if the SYSTICK interrupt is enabled or disabled. - * @rmtoll STK_CTRL TICKINT LL_SYSTICK_IsEnabledIT - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_SYSTICK_IsEnabledIT(void) -{ - return (READ_BIT(SysTick->CTRL, SysTick_CTRL_TICKINT_Msk) == (SysTick_CTRL_TICKINT_Msk)); -} - -/** - * @} - */ - -/** @defgroup CORTEX_LL_EF_LOW_POWER_MODE LOW POWER MODE - * @{ - */ - -/** - * @brief Processor uses sleep as its low power mode - * @rmtoll SCB_SCR SLEEPDEEP LL_LPM_EnableSleep - * @retval None - */ -__STATIC_INLINE void LL_LPM_EnableSleep(void) -{ - /* Clear SLEEPDEEP bit of Cortex System Control Register */ - CLEAR_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SLEEPDEEP_Msk)); -} - -/** - * @brief Processor uses deep sleep as its low power mode - * @rmtoll SCB_SCR SLEEPDEEP LL_LPM_EnableDeepSleep - * @retval None - */ -__STATIC_INLINE void LL_LPM_EnableDeepSleep(void) -{ - /* Set SLEEPDEEP bit of Cortex System Control Register */ - SET_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SLEEPDEEP_Msk)); -} - -/** - * @brief Configures sleep-on-exit when returning from Handler mode to Thread mode. - * @note Setting this bit to 1 enables an interrupt-driven application to avoid returning to an - * empty main application. - * @rmtoll SCB_SCR SLEEPONEXIT LL_LPM_EnableSleepOnExit - * @retval None - */ -__STATIC_INLINE void LL_LPM_EnableSleepOnExit(void) -{ - /* Set SLEEPONEXIT bit of Cortex System Control Register */ - SET_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SLEEPONEXIT_Msk)); -} - -/** - * @brief Do not sleep when returning to Thread mode. - * @rmtoll SCB_SCR SLEEPONEXIT LL_LPM_DisableSleepOnExit - * @retval None - */ -__STATIC_INLINE void LL_LPM_DisableSleepOnExit(void) -{ - /* Clear SLEEPONEXIT bit of Cortex System Control Register */ - CLEAR_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SLEEPONEXIT_Msk)); -} - -/** - * @brief Enabled events and all interrupts, including disabled interrupts, can wakeup the - * processor. - * @rmtoll SCB_SCR SEVEONPEND LL_LPM_EnableEventOnPend - * @retval None - */ -__STATIC_INLINE void LL_LPM_EnableEventOnPend(void) -{ - /* Set SEVEONPEND bit of Cortex System Control Register */ - SET_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SEVONPEND_Msk)); -} - -/** - * @brief Only enabled interrupts or events can wakeup the processor, disabled interrupts are - * excluded - * @rmtoll SCB_SCR SEVEONPEND LL_LPM_DisableEventOnPend - * @retval None - */ -__STATIC_INLINE void LL_LPM_DisableEventOnPend(void) -{ - /* Clear SEVEONPEND bit of Cortex System Control Register */ - CLEAR_BIT(SCB->SCR, ((uint32_t)SCB_SCR_SEVONPEND_Msk)); -} - -/** - * @} - */ - -/** @defgroup CORTEX_LL_EF_HANDLER HANDLER - * @{ - */ - -/** - * @brief Enable a fault in System handler control register (SHCSR) - * @rmtoll SCB_SHCSR MEMFAULTENA LL_HANDLER_EnableFault - * @param Fault This parameter can be a combination of the following values: - * @arg @ref LL_HANDLER_FAULT_USG - * @arg @ref LL_HANDLER_FAULT_BUS - * @arg @ref LL_HANDLER_FAULT_MEM - * @retval None - */ -__STATIC_INLINE void LL_HANDLER_EnableFault(uint32_t Fault) -{ - /* Enable the system handler fault */ - SET_BIT(SCB->SHCSR, Fault); -} - -/** - * @brief Disable a fault in System handler control register (SHCSR) - * @rmtoll SCB_SHCSR MEMFAULTENA LL_HANDLER_DisableFault - * @param Fault This parameter can be a combination of the following values: - * @arg @ref LL_HANDLER_FAULT_USG - * @arg @ref LL_HANDLER_FAULT_BUS - * @arg @ref LL_HANDLER_FAULT_MEM - * @retval None - */ -__STATIC_INLINE void LL_HANDLER_DisableFault(uint32_t Fault) -{ - /* Disable the system handler fault */ - CLEAR_BIT(SCB->SHCSR, Fault); -} - -/** - * @} - */ - -/** @defgroup CORTEX_LL_EF_MCU_INFO MCU INFO - * @{ - */ - -/** - * @brief Get Implementer code - * @rmtoll SCB_CPUID IMPLEMENTER LL_CPUID_GetImplementer - * @retval Value should be equal to 0x41 for ARM - */ -__STATIC_INLINE uint32_t LL_CPUID_GetImplementer(void) -{ - return (uint32_t)(READ_BIT(SCB->CPUID, SCB_CPUID_IMPLEMENTER_Msk) >> SCB_CPUID_IMPLEMENTER_Pos); -} - -/** - * @brief Get Variant number (The r value in the rnpn product revision identifier) - * @rmtoll SCB_CPUID VARIANT LL_CPUID_GetVariant - * @retval Value between 0 and 255 (0x0: revision 0) - */ -__STATIC_INLINE uint32_t LL_CPUID_GetVariant(void) -{ - return (uint32_t)(READ_BIT(SCB->CPUID, SCB_CPUID_VARIANT_Msk) >> SCB_CPUID_VARIANT_Pos); -} - -/** - * @brief Get Constant number - * @rmtoll SCB_CPUID ARCHITECTURE LL_CPUID_GetConstant - * @retval Value should be equal to 0xF for Cortex-M4 devices - */ -__STATIC_INLINE uint32_t LL_CPUID_GetConstant(void) -{ - return (uint32_t)(READ_BIT(SCB->CPUID, SCB_CPUID_ARCHITECTURE_Msk) >> SCB_CPUID_ARCHITECTURE_Pos); -} - -/** - * @brief Get Part number - * @rmtoll SCB_CPUID PARTNO LL_CPUID_GetParNo - * @retval Value should be equal to 0xC24 for Cortex-M4 - */ -__STATIC_INLINE uint32_t LL_CPUID_GetParNo(void) -{ - return (uint32_t)(READ_BIT(SCB->CPUID, SCB_CPUID_PARTNO_Msk) >> SCB_CPUID_PARTNO_Pos); -} - -/** - * @brief Get Revision number (The p value in the rnpn product revision identifier, indicates patch release) - * @rmtoll SCB_CPUID REVISION LL_CPUID_GetRevision - * @retval Value between 0 and 255 (0x1: patch 1) - */ -__STATIC_INLINE uint32_t LL_CPUID_GetRevision(void) -{ - return (uint32_t)(READ_BIT(SCB->CPUID, SCB_CPUID_REVISION_Msk) >> SCB_CPUID_REVISION_Pos); -} - -/** - * @} - */ - -#if __MPU_PRESENT -/** @defgroup CORTEX_LL_EF_MPU MPU - * @{ - */ - -/** - * @brief Enable MPU with input options - * @rmtoll MPU_CTRL ENABLE LL_MPU_Enable - * @param Options This parameter can be one of the following values: - * @arg @ref LL_MPU_CTRL_HFNMI_PRIVDEF_NONE - * @arg @ref LL_MPU_CTRL_HARDFAULT_NMI - * @arg @ref LL_MPU_CTRL_PRIVILEGED_DEFAULT - * @arg @ref LL_MPU_CTRL_HFNMI_PRIVDEF - * @retval None - */ -__STATIC_INLINE void LL_MPU_Enable(uint32_t Options) -{ - /* Enable the MPU*/ - WRITE_REG(MPU->CTRL, (MPU_CTRL_ENABLE_Msk | Options)); - /* Ensure MPU settings take effects */ - __DSB(); - /* Sequence instruction fetches using update settings */ - __ISB(); -} - -/** - * @brief Disable MPU - * @rmtoll MPU_CTRL ENABLE LL_MPU_Disable - * @retval None - */ -__STATIC_INLINE void LL_MPU_Disable(void) -{ - /* Make sure outstanding transfers are done */ - __DMB(); - /* Disable MPU*/ - WRITE_REG(MPU->CTRL, 0U); -} - -/** - * @brief Check if MPU is enabled or not - * @rmtoll MPU_CTRL ENABLE LL_MPU_IsEnabled - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_MPU_IsEnabled(void) -{ - return (READ_BIT(MPU->CTRL, MPU_CTRL_ENABLE_Msk) == (MPU_CTRL_ENABLE_Msk)); -} - -/** - * @brief Enable a MPU region - * @rmtoll MPU_RASR ENABLE LL_MPU_EnableRegion - * @param Region This parameter can be one of the following values: - * @arg @ref LL_MPU_REGION_NUMBER0 - * @arg @ref LL_MPU_REGION_NUMBER1 - * @arg @ref LL_MPU_REGION_NUMBER2 - * @arg @ref LL_MPU_REGION_NUMBER3 - * @arg @ref LL_MPU_REGION_NUMBER4 - * @arg @ref LL_MPU_REGION_NUMBER5 - * @arg @ref LL_MPU_REGION_NUMBER6 - * @arg @ref LL_MPU_REGION_NUMBER7 - * @retval None - */ -__STATIC_INLINE void LL_MPU_EnableRegion(uint32_t Region) -{ - /* Set Region number */ - WRITE_REG(MPU->RNR, Region); - /* Enable the MPU region */ - SET_BIT(MPU->RASR, MPU_RASR_ENABLE_Msk); -} - -/** - * @brief Configure and enable a region - * @rmtoll MPU_RNR REGION LL_MPU_ConfigRegion\n - * MPU_RBAR REGION LL_MPU_ConfigRegion\n - * MPU_RBAR ADDR LL_MPU_ConfigRegion\n - * MPU_RASR XN LL_MPU_ConfigRegion\n - * MPU_RASR AP LL_MPU_ConfigRegion\n - * MPU_RASR S LL_MPU_ConfigRegion\n - * MPU_RASR C LL_MPU_ConfigRegion\n - * MPU_RASR B LL_MPU_ConfigRegion\n - * MPU_RASR SIZE LL_MPU_ConfigRegion - * @param Region This parameter can be one of the following values: - * @arg @ref LL_MPU_REGION_NUMBER0 - * @arg @ref LL_MPU_REGION_NUMBER1 - * @arg @ref LL_MPU_REGION_NUMBER2 - * @arg @ref LL_MPU_REGION_NUMBER3 - * @arg @ref LL_MPU_REGION_NUMBER4 - * @arg @ref LL_MPU_REGION_NUMBER5 - * @arg @ref LL_MPU_REGION_NUMBER6 - * @arg @ref LL_MPU_REGION_NUMBER7 - * @param Address Value of region base address - * @param SubRegionDisable Sub-region disable value between Min_Data = 0x00 and Max_Data = 0xFF - * @param Attributes This parameter can be a combination of the following values: - * @arg @ref LL_MPU_REGION_SIZE_32B or @ref LL_MPU_REGION_SIZE_64B or @ref LL_MPU_REGION_SIZE_128B or @ref LL_MPU_REGION_SIZE_256B or @ref LL_MPU_REGION_SIZE_512B - * or @ref LL_MPU_REGION_SIZE_1KB or @ref LL_MPU_REGION_SIZE_2KB or @ref LL_MPU_REGION_SIZE_4KB or @ref LL_MPU_REGION_SIZE_8KB or @ref LL_MPU_REGION_SIZE_16KB - * or @ref LL_MPU_REGION_SIZE_32KB or @ref LL_MPU_REGION_SIZE_64KB or @ref LL_MPU_REGION_SIZE_128KB or @ref LL_MPU_REGION_SIZE_256KB or @ref LL_MPU_REGION_SIZE_512KB - * or @ref LL_MPU_REGION_SIZE_1MB or @ref LL_MPU_REGION_SIZE_2MB or @ref LL_MPU_REGION_SIZE_4MB or @ref LL_MPU_REGION_SIZE_8MB or @ref LL_MPU_REGION_SIZE_16MB - * or @ref LL_MPU_REGION_SIZE_32MB or @ref LL_MPU_REGION_SIZE_64MB or @ref LL_MPU_REGION_SIZE_128MB or @ref LL_MPU_REGION_SIZE_256MB or @ref LL_MPU_REGION_SIZE_512MB - * or @ref LL_MPU_REGION_SIZE_1GB or @ref LL_MPU_REGION_SIZE_2GB or @ref LL_MPU_REGION_SIZE_4GB - * @arg @ref LL_MPU_REGION_NO_ACCESS or @ref LL_MPU_REGION_PRIV_RW or @ref LL_MPU_REGION_PRIV_RW_URO or @ref LL_MPU_REGION_FULL_ACCESS - * or @ref LL_MPU_REGION_PRIV_RO or @ref LL_MPU_REGION_PRIV_RO_URO - * @arg @ref LL_MPU_TEX_LEVEL0 or @ref LL_MPU_TEX_LEVEL1 or @ref LL_MPU_TEX_LEVEL2 or @ref LL_MPU_TEX_LEVEL4 - * @arg @ref LL_MPU_INSTRUCTION_ACCESS_ENABLE or @ref LL_MPU_INSTRUCTION_ACCESS_DISABLE - * @arg @ref LL_MPU_ACCESS_SHAREABLE or @ref LL_MPU_ACCESS_NOT_SHAREABLE - * @arg @ref LL_MPU_ACCESS_CACHEABLE or @ref LL_MPU_ACCESS_NOT_CACHEABLE - * @arg @ref LL_MPU_ACCESS_BUFFERABLE or @ref LL_MPU_ACCESS_NOT_BUFFERABLE - * @retval None - */ -__STATIC_INLINE void LL_MPU_ConfigRegion(uint32_t Region, uint32_t SubRegionDisable, uint32_t Address, uint32_t Attributes) -{ - /* Set Region number */ - WRITE_REG(MPU->RNR, Region); - /* Set base address */ - WRITE_REG(MPU->RBAR, (Address & 0xFFFFFFE0U)); - /* Configure MPU */ - WRITE_REG(MPU->RASR, (MPU_RASR_ENABLE_Msk | Attributes | SubRegionDisable << MPU_RASR_SRD_Pos)); -} - -/** - * @brief Disable a region - * @rmtoll MPU_RNR REGION LL_MPU_DisableRegion\n - * MPU_RASR ENABLE LL_MPU_DisableRegion - * @param Region This parameter can be one of the following values: - * @arg @ref LL_MPU_REGION_NUMBER0 - * @arg @ref LL_MPU_REGION_NUMBER1 - * @arg @ref LL_MPU_REGION_NUMBER2 - * @arg @ref LL_MPU_REGION_NUMBER3 - * @arg @ref LL_MPU_REGION_NUMBER4 - * @arg @ref LL_MPU_REGION_NUMBER5 - * @arg @ref LL_MPU_REGION_NUMBER6 - * @arg @ref LL_MPU_REGION_NUMBER7 - * @retval None - */ -__STATIC_INLINE void LL_MPU_DisableRegion(uint32_t Region) -{ - /* Set Region number */ - WRITE_REG(MPU->RNR, Region); - /* Disable the MPU region */ - CLEAR_BIT(MPU->RASR, MPU_RASR_ENABLE_Msk); -} - -/** - * @} - */ - -#endif /* __MPU_PRESENT */ -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_CORTEX_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_crc.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_crc.h deleted file mode 100644 index 2d05b67..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_crc.h +++ /dev/null @@ -1,204 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_crc.h - * @author MCD Application Team - * @brief Header file of CRC LL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_LL_CRC_H -#define STM32F4xx_LL_CRC_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined(CRC) - -/** @defgroup CRC_LL CRC - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/** @defgroup CRC_LL_Exported_Constants CRC Exported Constants - * @{ - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup CRC_LL_Exported_Macros CRC Exported Macros - * @{ - */ - -/** @defgroup CRC_LL_EM_WRITE_READ Common Write and read registers Macros - * @{ - */ - -/** - * @brief Write a value in CRC register - * @param __INSTANCE__ CRC Instance - * @param __REG__ Register to be written - * @param __VALUE__ Value to be written in the register - * @retval None - */ -#define LL_CRC_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, __VALUE__) - -/** - * @brief Read a value in CRC register - * @param __INSTANCE__ CRC Instance - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_CRC_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__) -/** - * @} - */ - -/** - * @} - */ - - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup CRC_LL_Exported_Functions CRC Exported Functions - * @{ - */ - -/** @defgroup CRC_LL_EF_Configuration CRC Configuration functions - * @{ - */ - -/** - * @brief Reset the CRC calculation unit. - * @note If Programmable Initial CRC value feature - * is available, also set the Data Register to the value stored in the - * CRC_INIT register, otherwise, reset Data Register to its default value. - * @rmtoll CR RESET LL_CRC_ResetCRCCalculationUnit - * @param CRCx CRC Instance - * @retval None - */ -__STATIC_INLINE void LL_CRC_ResetCRCCalculationUnit(CRC_TypeDef *CRCx) -{ - SET_BIT(CRCx->CR, CRC_CR_RESET); -} - -/** - * @} - */ - -/** @defgroup CRC_LL_EF_Data_Management Data_Management - * @{ - */ - -/** - * @brief Write given 32-bit data to the CRC calculator - * @rmtoll DR DR LL_CRC_FeedData32 - * @param CRCx CRC Instance - * @param InData value to be provided to CRC calculator between between Min_Data=0 and Max_Data=0xFFFFFFFF - * @retval None - */ -__STATIC_INLINE void LL_CRC_FeedData32(CRC_TypeDef *CRCx, uint32_t InData) -{ - WRITE_REG(CRCx->DR, InData); -} - -/** - * @brief Return current CRC calculation result. 32 bits value is returned. - * @rmtoll DR DR LL_CRC_ReadData32 - * @param CRCx CRC Instance - * @retval Current CRC calculation result as stored in CRC_DR register (32 bits). - */ -__STATIC_INLINE uint32_t LL_CRC_ReadData32(CRC_TypeDef *CRCx) -{ - return (uint32_t)(READ_REG(CRCx->DR)); -} - -/** - * @brief Return data stored in the Independent Data(IDR) register. - * @note This register can be used as a temporary storage location for one byte. - * @rmtoll IDR IDR LL_CRC_Read_IDR - * @param CRCx CRC Instance - * @retval Value stored in CRC_IDR register (General-purpose 8-bit data register). - */ -__STATIC_INLINE uint32_t LL_CRC_Read_IDR(CRC_TypeDef *CRCx) -{ - return (uint32_t)(READ_REG(CRCx->IDR)); -} - -/** - * @brief Store data in the Independent Data(IDR) register. - * @note This register can be used as a temporary storage location for one byte. - * @rmtoll IDR IDR LL_CRC_Write_IDR - * @param CRCx CRC Instance - * @param InData value to be stored in CRC_IDR register (8-bit) between Min_Data=0 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_CRC_Write_IDR(CRC_TypeDef *CRCx, uint32_t InData) -{ - *((uint8_t __IO *)(&CRCx->IDR)) = (uint8_t) InData; -} -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup CRC_LL_EF_Init Initialization and de-initialization functions - * @{ - */ - -ErrorStatus LL_CRC_DeInit(CRC_TypeDef *CRCx); - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* defined(CRC) */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_LL_CRC_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_dac.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_dac.h deleted file mode 100644 index 98bf40b..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_dac.h +++ /dev/null @@ -1,1457 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_dac.h - * @author MCD Application Team - * @brief Header file of DAC LL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_LL_DAC_H -#define STM32F4xx_LL_DAC_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined(DAC) - -/** @defgroup DAC_LL DAC - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup DAC_LL_Private_Constants DAC Private Constants - * @{ - */ - -/* Internal masks for DAC channels definition */ -/* To select into literal LL_DAC_CHANNEL_x the relevant bits for: */ -/* - channel bits position into registers CR, MCR, CCR, SHHR, SHRR */ -/* - channel bits position into register SWTRIG */ -/* - channel register offset of data holding register DHRx */ -/* - channel register offset of data output register DORx */ -#define DAC_CR_CH1_BITOFFSET 0UL /* Position of channel bits into registers - CR, MCR, CCR, SHHR, SHRR of channel 1 */ -#if defined(DAC_CHANNEL2_SUPPORT) -#define DAC_CR_CH2_BITOFFSET 16UL /* Position of channel bits into registers - CR, MCR, CCR, SHHR, SHRR of channel 2 */ -#define DAC_CR_CHX_BITOFFSET_MASK (DAC_CR_CH1_BITOFFSET | DAC_CR_CH2_BITOFFSET) -#else -#define DAC_CR_CHX_BITOFFSET_MASK (DAC_CR_CH1_BITOFFSET) -#endif /* DAC_CHANNEL2_SUPPORT */ - -#define DAC_SWTR_CH1 (DAC_SWTRIGR_SWTRIG1) /* Channel bit into register SWTRIGR of channel 1. */ -#if defined(DAC_CHANNEL2_SUPPORT) -#define DAC_SWTR_CH2 (DAC_SWTRIGR_SWTRIG2) /* Channel bit into register SWTRIGR of channel 2. */ -#define DAC_SWTR_CHX_MASK (DAC_SWTR_CH1 | DAC_SWTR_CH2) -#else -#define DAC_SWTR_CHX_MASK (DAC_SWTR_CH1) -#endif /* DAC_CHANNEL2_SUPPORT */ - -#define DAC_REG_DHR12R1_REGOFFSET 0x00000000UL /* Register DHR12Rx channel 1 taken as reference */ -#define DAC_REG_DHR12L1_REGOFFSET 0x00100000UL /* Register offset of DHR12Lx channel 1 versus - DHR12Rx channel 1 (shifted left of 20 bits) */ -#define DAC_REG_DHR8R1_REGOFFSET 0x02000000UL /* Register offset of DHR8Rx channel 1 versus - DHR12Rx channel 1 (shifted left of 24 bits) */ -#if defined(DAC_CHANNEL2_SUPPORT) -#define DAC_REG_DHR12R2_REGOFFSET 0x00030000UL /* Register offset of DHR12Rx channel 2 versus - DHR12Rx channel 1 (shifted left of 16 bits) */ -#define DAC_REG_DHR12L2_REGOFFSET 0x00400000UL /* Register offset of DHR12Lx channel 2 versus - DHR12Rx channel 1 (shifted left of 20 bits) */ -#define DAC_REG_DHR8R2_REGOFFSET 0x05000000UL /* Register offset of DHR8Rx channel 2 versus - DHR12Rx channel 1 (shifted left of 24 bits) */ -#endif /* DAC_CHANNEL2_SUPPORT */ -#define DAC_REG_DHR12RX_REGOFFSET_MASK 0x000F0000UL -#define DAC_REG_DHR12LX_REGOFFSET_MASK 0x00F00000UL -#define DAC_REG_DHR8RX_REGOFFSET_MASK 0x0F000000UL -#define DAC_REG_DHRX_REGOFFSET_MASK (DAC_REG_DHR12RX_REGOFFSET_MASK\ - | DAC_REG_DHR12LX_REGOFFSET_MASK | DAC_REG_DHR8RX_REGOFFSET_MASK) - -#define DAC_REG_DOR1_REGOFFSET 0x00000000UL /* Register DORx channel 1 taken as reference */ -#if defined(DAC_CHANNEL2_SUPPORT) -#define DAC_REG_DOR2_REGOFFSET 0x10000000UL /* Register offset of DORx channel 1 versus - DORx channel 2 (shifted left of 28 bits) */ -#define DAC_REG_DORX_REGOFFSET_MASK (DAC_REG_DOR1_REGOFFSET | DAC_REG_DOR2_REGOFFSET) -#endif /* DAC_CHANNEL2_SUPPORT */ - - -#define DAC_REG_DHR_REGOFFSET_MASK_POSBIT0 0x0000000FUL /* Mask of data hold registers offset (DHR12Rx, - DHR12Lx, DHR8Rx, ...) when shifted to position 0 */ -#define DAC_REG_DORX_REGOFFSET_MASK_POSBIT0 0x00000001UL /* Mask of DORx registers offset when shifted - to position 0 */ -#define DAC_REG_SHSRX_REGOFFSET_MASK_POSBIT0 0x00000001UL /* Mask of SHSRx registers offset when shifted - to position 0 */ - -#define DAC_REG_DHR12RX_REGOFFSET_BITOFFSET_POS 16UL /* Position of bits register offset of DHR12Rx - channel 1 or 2 versus DHR12Rx channel 1 - (shifted left of 16 bits) */ -#define DAC_REG_DHR12LX_REGOFFSET_BITOFFSET_POS 20UL /* Position of bits register offset of DHR12Lx - channel 1 or 2 versus DHR12Rx channel 1 - (shifted left of 20 bits) */ -#define DAC_REG_DHR8RX_REGOFFSET_BITOFFSET_POS 24UL /* Position of bits register offset of DHR8Rx - channel 1 or 2 versus DHR12Rx channel 1 - (shifted left of 24 bits) */ -#define DAC_REG_DORX_REGOFFSET_BITOFFSET_POS 28UL /* Position of bits register offset of DORx - channel 1 or 2 versus DORx channel 1 - (shifted left of 28 bits) */ - -/* DAC registers bits positions */ -#if defined(DAC_CHANNEL2_SUPPORT) -#endif -#define DAC_DHR12RD_DACC2DHR_BITOFFSET_POS DAC_DHR12RD_DACC2DHR_Pos -#define DAC_DHR12LD_DACC2DHR_BITOFFSET_POS DAC_DHR12LD_DACC2DHR_Pos -#define DAC_DHR8RD_DACC2DHR_BITOFFSET_POS DAC_DHR8RD_DACC2DHR_Pos - -/* Miscellaneous data */ -#define DAC_DIGITAL_SCALE_12BITS 4095UL /* Full-scale digital value with a resolution of 12 - bits (voltage range determined by analog voltage - references Vref+ and Vref-, refer to reference manual) */ - -/** - * @} - */ - - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup DAC_LL_Private_Macros DAC Private Macros - * @{ - */ - -/** - * @brief Driver macro reserved for internal use: set a pointer to - * a register from a register basis from which an offset - * is applied. - * @param __REG__ Register basis from which the offset is applied. - * @param __REG_OFFFSET__ Offset to be applied (unit: number of registers). - * @retval Pointer to register address - */ -#define __DAC_PTR_REG_OFFSET(__REG__, __REG_OFFFSET__) \ - ((uint32_t *)((uint32_t) ((uint32_t)(&(__REG__)) + ((__REG_OFFFSET__) << 2UL)))) - -/** - * @} - */ - - -/* Exported types ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup DAC_LL_ES_INIT DAC Exported Init structure - * @{ - */ - -/** - * @brief Structure definition of some features of DAC instance. - */ -typedef struct -{ - uint32_t TriggerSource; /*!< Set the conversion trigger source for the selected DAC channel: - internal (SW start) or from external peripheral - (timer event, external interrupt line). - This parameter can be a value of @ref DAC_LL_EC_TRIGGER_SOURCE - - This feature can be modified afterwards using unitary - function @ref LL_DAC_SetTriggerSource(). */ - - uint32_t WaveAutoGeneration; /*!< Set the waveform automatic generation mode for the selected DAC channel. - This parameter can be a value of @ref DAC_LL_EC_WAVE_AUTO_GENERATION_MODE - - This feature can be modified afterwards using unitary - function @ref LL_DAC_SetWaveAutoGeneration(). */ - - uint32_t WaveAutoGenerationConfig; /*!< Set the waveform automatic generation mode for the selected DAC channel. - If waveform automatic generation mode is set to noise, this parameter - can be a value of @ref DAC_LL_EC_WAVE_NOISE_LFSR_UNMASK_BITS - If waveform automatic generation mode is set to triangle, - this parameter can be a value of @ref DAC_LL_EC_WAVE_TRIANGLE_AMPLITUDE - @note If waveform automatic generation mode is disabled, - this parameter is discarded. - - This feature can be modified afterwards using unitary - function @ref LL_DAC_SetWaveNoiseLFSR(), - @ref LL_DAC_SetWaveTriangleAmplitude() - depending on the wave automatic generation selected. */ - - uint32_t OutputBuffer; /*!< Set the output buffer for the selected DAC channel. - This parameter can be a value of @ref DAC_LL_EC_OUTPUT_BUFFER - - This feature can be modified afterwards using unitary - function @ref LL_DAC_SetOutputBuffer(). */ -} LL_DAC_InitTypeDef; - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup DAC_LL_Exported_Constants DAC Exported Constants - * @{ - */ - -/** @defgroup DAC_LL_EC_GET_FLAG DAC flags - * @brief Flags defines which can be used with LL_DAC_ReadReg function - * @{ - */ -/* DAC channel 1 flags */ -#define LL_DAC_FLAG_DMAUDR1 (DAC_SR_DMAUDR1) /*!< DAC channel 1 flag DMA underrun */ -#if defined(DAC_CHANNEL2_SUPPORT) -/* DAC channel 2 flags */ -#define LL_DAC_FLAG_DMAUDR2 (DAC_SR_DMAUDR2) /*!< DAC channel 2 flag DMA underrun */ -#endif /* DAC_CHANNEL2_SUPPORT */ -/** - * @} - */ - -/** @defgroup DAC_LL_EC_IT DAC interruptions - * @brief IT defines which can be used with LL_DAC_ReadReg and LL_DAC_WriteReg functions - * @{ - */ -#define LL_DAC_IT_DMAUDRIE1 (DAC_CR_DMAUDRIE1) /*!< DAC channel 1 interruption DMA underrun */ -#if defined(DAC_CHANNEL2_SUPPORT) -#define LL_DAC_IT_DMAUDRIE2 (DAC_CR_DMAUDRIE2) /*!< DAC channel 2 interruption DMA underrun */ -#endif /* DAC_CHANNEL2_SUPPORT */ -/** - * @} - */ - -/** @defgroup DAC_LL_EC_CHANNEL DAC channels - * @{ - */ -#define LL_DAC_CHANNEL_1 (DAC_REG_DOR1_REGOFFSET | DAC_REG_DHR12R1_REGOFFSET | DAC_REG_DHR12L1_REGOFFSET | DAC_REG_DHR8R1_REGOFFSET | DAC_CR_CH1_BITOFFSET | DAC_SWTR_CH1) /*!< DAC channel 1 */ -#if defined(DAC_CHANNEL2_SUPPORT) -#define LL_DAC_CHANNEL_2 (DAC_REG_DOR2_REGOFFSET | DAC_REG_DHR12R2_REGOFFSET | DAC_REG_DHR12L2_REGOFFSET | DAC_REG_DHR8R2_REGOFFSET | DAC_CR_CH2_BITOFFSET | DAC_SWTR_CH2) /*!< DAC channel 2 */ -#endif /* DAC_CHANNEL2_SUPPORT */ -/** - * @} - */ - -/** @defgroup DAC_LL_EC_TRIGGER_SOURCE DAC trigger source - * @{ - */ -#define LL_DAC_TRIG_SOFTWARE (DAC_CR_TSEL1_2 | DAC_CR_TSEL1_1 | DAC_CR_TSEL1_0) /*!< DAC channel conversion trigger internal (SW start) */ -#define LL_DAC_TRIG_EXT_TIM2_TRGO (DAC_CR_TSEL1_2 ) /*!< DAC channel conversion trigger from external peripheral: TIM2 TRGO. */ -#define LL_DAC_TRIG_EXT_TIM8_TRGO ( DAC_CR_TSEL1_0) /*!< DAC channel conversion trigger from external peripheral: TIM8 TRGO. */ -#define LL_DAC_TRIG_EXT_TIM4_TRGO (DAC_CR_TSEL1_2 | DAC_CR_TSEL1_0) /*!< DAC channel conversion trigger from external peripheral: TIM4 TRGO. */ -#define LL_DAC_TRIG_EXT_TIM6_TRGO 0x00000000UL /*!< DAC channel conversion trigger from external peripheral: TIM6 TRGO. */ -#define LL_DAC_TRIG_EXT_TIM7_TRGO ( DAC_CR_TSEL1_1 ) /*!< DAC channel conversion trigger from external peripheral: TIM7 TRGO. */ -#define LL_DAC_TRIG_EXT_TIM5_TRGO ( DAC_CR_TSEL1_1 | DAC_CR_TSEL1_0) /*!< DAC channel conversion trigger from external peripheral: TIM5 TRGO. */ -#define LL_DAC_TRIG_EXT_EXTI_LINE9 (DAC_CR_TSEL1_2 | DAC_CR_TSEL1_1 ) /*!< DAC channel conversion trigger from external peripheral: external interrupt line 9. */ -/** - * @} - */ - -/** @defgroup DAC_LL_EC_WAVE_AUTO_GENERATION_MODE DAC waveform automatic generation mode - * @{ - */ -#define LL_DAC_WAVE_AUTO_GENERATION_NONE 0x00000000UL /*!< DAC channel wave auto generation mode disabled. */ -#define LL_DAC_WAVE_AUTO_GENERATION_NOISE ( DAC_CR_WAVE1_0) /*!< DAC channel wave auto generation mode enabled, set generated noise waveform. */ -#define LL_DAC_WAVE_AUTO_GENERATION_TRIANGLE (DAC_CR_WAVE1_1 ) /*!< DAC channel wave auto generation mode enabled, set generated triangle waveform. */ -/** - * @} - */ - -/** @defgroup DAC_LL_EC_WAVE_NOISE_LFSR_UNMASK_BITS DAC wave generation - Noise LFSR unmask bits - * @{ - */ -#define LL_DAC_NOISE_LFSR_UNMASK_BIT0 0x00000000UL /*!< Noise wave generation, unmask LFSR bit0, for the selected DAC channel */ -#define LL_DAC_NOISE_LFSR_UNMASK_BITS1_0 ( DAC_CR_MAMP1_0) /*!< Noise wave generation, unmask LFSR bits[1:0], for the selected DAC channel */ -#define LL_DAC_NOISE_LFSR_UNMASK_BITS2_0 ( DAC_CR_MAMP1_1 ) /*!< Noise wave generation, unmask LFSR bits[2:0], for the selected DAC channel */ -#define LL_DAC_NOISE_LFSR_UNMASK_BITS3_0 ( DAC_CR_MAMP1_1 | DAC_CR_MAMP1_0) /*!< Noise wave generation, unmask LFSR bits[3:0], for the selected DAC channel */ -#define LL_DAC_NOISE_LFSR_UNMASK_BITS4_0 ( DAC_CR_MAMP1_2 ) /*!< Noise wave generation, unmask LFSR bits[4:0], for the selected DAC channel */ -#define LL_DAC_NOISE_LFSR_UNMASK_BITS5_0 ( DAC_CR_MAMP1_2 | DAC_CR_MAMP1_0) /*!< Noise wave generation, unmask LFSR bits[5:0], for the selected DAC channel */ -#define LL_DAC_NOISE_LFSR_UNMASK_BITS6_0 ( DAC_CR_MAMP1_2 | DAC_CR_MAMP1_1 ) /*!< Noise wave generation, unmask LFSR bits[6:0], for the selected DAC channel */ -#define LL_DAC_NOISE_LFSR_UNMASK_BITS7_0 ( DAC_CR_MAMP1_2 | DAC_CR_MAMP1_1 | DAC_CR_MAMP1_0) /*!< Noise wave generation, unmask LFSR bits[7:0], for the selected DAC channel */ -#define LL_DAC_NOISE_LFSR_UNMASK_BITS8_0 (DAC_CR_MAMP1_3 ) /*!< Noise wave generation, unmask LFSR bits[8:0], for the selected DAC channel */ -#define LL_DAC_NOISE_LFSR_UNMASK_BITS9_0 (DAC_CR_MAMP1_3 | DAC_CR_MAMP1_0) /*!< Noise wave generation, unmask LFSR bits[9:0], for the selected DAC channel */ -#define LL_DAC_NOISE_LFSR_UNMASK_BITS10_0 (DAC_CR_MAMP1_3 | DAC_CR_MAMP1_1 ) /*!< Noise wave generation, unmask LFSR bits[10:0], for the selected DAC channel */ -#define LL_DAC_NOISE_LFSR_UNMASK_BITS11_0 (DAC_CR_MAMP1_3 | DAC_CR_MAMP1_1 | DAC_CR_MAMP1_0) /*!< Noise wave generation, unmask LFSR bits[11:0], for the selected DAC channel */ -/** - * @} - */ - -/** @defgroup DAC_LL_EC_WAVE_TRIANGLE_AMPLITUDE DAC wave generation - Triangle amplitude - * @{ - */ -#define LL_DAC_TRIANGLE_AMPLITUDE_1 0x00000000UL /*!< Triangle wave generation, amplitude of 1 LSB of DAC output range, for the selected DAC channel */ -#define LL_DAC_TRIANGLE_AMPLITUDE_3 ( DAC_CR_MAMP1_0) /*!< Triangle wave generation, amplitude of 3 LSB of DAC output range, for the selected DAC channel */ -#define LL_DAC_TRIANGLE_AMPLITUDE_7 ( DAC_CR_MAMP1_1 ) /*!< Triangle wave generation, amplitude of 7 LSB of DAC output range, for the selected DAC channel */ -#define LL_DAC_TRIANGLE_AMPLITUDE_15 ( DAC_CR_MAMP1_1 | DAC_CR_MAMP1_0) /*!< Triangle wave generation, amplitude of 15 LSB of DAC output range, for the selected DAC channel */ -#define LL_DAC_TRIANGLE_AMPLITUDE_31 ( DAC_CR_MAMP1_2 ) /*!< Triangle wave generation, amplitude of 31 LSB of DAC output range, for the selected DAC channel */ -#define LL_DAC_TRIANGLE_AMPLITUDE_63 ( DAC_CR_MAMP1_2 | DAC_CR_MAMP1_0) /*!< Triangle wave generation, amplitude of 63 LSB of DAC output range, for the selected DAC channel */ -#define LL_DAC_TRIANGLE_AMPLITUDE_127 ( DAC_CR_MAMP1_2 | DAC_CR_MAMP1_1 ) /*!< Triangle wave generation, amplitude of 127 LSB of DAC output range, for the selected DAC channel */ -#define LL_DAC_TRIANGLE_AMPLITUDE_255 ( DAC_CR_MAMP1_2 | DAC_CR_MAMP1_1 | DAC_CR_MAMP1_0) /*!< Triangle wave generation, amplitude of 255 LSB of DAC output range, for the selected DAC channel */ -#define LL_DAC_TRIANGLE_AMPLITUDE_511 (DAC_CR_MAMP1_3 ) /*!< Triangle wave generation, amplitude of 512 LSB of DAC output range, for the selected DAC channel */ -#define LL_DAC_TRIANGLE_AMPLITUDE_1023 (DAC_CR_MAMP1_3 | DAC_CR_MAMP1_0) /*!< Triangle wave generation, amplitude of 1023 LSB of DAC output range, for the selected DAC channel */ -#define LL_DAC_TRIANGLE_AMPLITUDE_2047 (DAC_CR_MAMP1_3 | DAC_CR_MAMP1_1 ) /*!< Triangle wave generation, amplitude of 2047 LSB of DAC output range, for the selected DAC channel */ -#define LL_DAC_TRIANGLE_AMPLITUDE_4095 (DAC_CR_MAMP1_3 | DAC_CR_MAMP1_1 | DAC_CR_MAMP1_0) /*!< Triangle wave generation, amplitude of 4095 LSB of DAC output range, for the selected DAC channel */ -/** - * @} - */ - -/** @defgroup DAC_LL_EC_OUTPUT_BUFFER DAC channel output buffer - * @{ - */ -#define LL_DAC_OUTPUT_BUFFER_ENABLE 0x00000000UL /*!< The selected DAC channel output is buffered: higher drive current capability, but also higher current consumption */ -#define LL_DAC_OUTPUT_BUFFER_DISABLE (DAC_CR_BOFF1) /*!< The selected DAC channel output is not buffered: lower drive current capability, but also lower current consumption */ -/** - * @} - */ - -/** @defgroup DAC_LL_EC_RESOLUTION DAC channel output resolution - * @{ - */ -#define LL_DAC_RESOLUTION_12B 0x00000000UL /*!< DAC channel resolution 12 bits */ -#define LL_DAC_RESOLUTION_8B 0x00000002UL /*!< DAC channel resolution 8 bits */ -/** - * @} - */ - -/** @defgroup DAC_LL_EC_REGISTERS DAC registers compliant with specific purpose - * @{ - */ -/* List of DAC registers intended to be used (most commonly) with */ -/* DMA transfer. */ -/* Refer to function @ref LL_DAC_DMA_GetRegAddr(). */ -#define LL_DAC_DMA_REG_DATA_12BITS_RIGHT_ALIGNED DAC_REG_DHR12RX_REGOFFSET_BITOFFSET_POS /*!< DAC channel data holding register 12 bits right aligned */ -#define LL_DAC_DMA_REG_DATA_12BITS_LEFT_ALIGNED DAC_REG_DHR12LX_REGOFFSET_BITOFFSET_POS /*!< DAC channel data holding register 12 bits left aligned */ -#define LL_DAC_DMA_REG_DATA_8BITS_RIGHT_ALIGNED DAC_REG_DHR8RX_REGOFFSET_BITOFFSET_POS /*!< DAC channel data holding register 8 bits right aligned */ -/** - * @} - */ - -/** @defgroup DAC_LL_EC_HW_DELAYS Definitions of DAC hardware constraints delays - * @note Only DAC peripheral HW delays are defined in DAC LL driver driver, - * not timeout values. - * For details on delays values, refer to descriptions in source code - * above each literal definition. - * @{ - */ - -/* Delay for DAC channel voltage settling time from DAC channel startup */ -/* (transition from disable to enable). */ -/* Note: DAC channel startup time depends on board application environment: */ -/* impedance connected to DAC channel output. */ -/* The delay below is specified under conditions: */ -/* - voltage maximum transition (lowest to highest value) */ -/* - until voltage reaches final value +-1LSB */ -/* - DAC channel output buffer enabled */ -/* - load impedance of 5kOhm (min), 50pF (max) */ -/* Literal set to maximum value (refer to device datasheet, */ -/* parameter "tWAKEUP"). */ -/* Unit: us */ -#define LL_DAC_DELAY_STARTUP_VOLTAGE_SETTLING_US 15UL /*!< Delay for DAC channel voltage settling time from DAC channel startup (transition from disable to enable) */ - -/* Delay for DAC channel voltage settling time. */ -/* Note: DAC channel startup time depends on board application environment: */ -/* impedance connected to DAC channel output. */ -/* The delay below is specified under conditions: */ -/* - voltage maximum transition (lowest to highest value) */ -/* - until voltage reaches final value +-1LSB */ -/* - DAC channel output buffer enabled */ -/* - load impedance of 5kOhm min, 50pF max */ -/* Literal set to maximum value (refer to device datasheet, */ -/* parameter "tSETTLING"). */ -/* Unit: us */ -#define LL_DAC_DELAY_VOLTAGE_SETTLING_US 12UL /*!< Delay for DAC channel voltage settling time */ - -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup DAC_LL_Exported_Macros DAC Exported Macros - * @{ - */ - -/** @defgroup DAC_LL_EM_WRITE_READ Common write and read registers macros - * @{ - */ - -/** - * @brief Write a value in DAC register - * @param __INSTANCE__ DAC Instance - * @param __REG__ Register to be written - * @param __VALUE__ Value to be written in the register - * @retval None - */ -#define LL_DAC_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__)) - -/** - * @brief Read a value in DAC register - * @param __INSTANCE__ DAC Instance - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_DAC_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__) - -/** - * @} - */ - -/** @defgroup DAC_LL_EM_HELPER_MACRO DAC helper macro - * @{ - */ - -/** - * @brief Helper macro to get DAC channel number in decimal format - * from literals LL_DAC_CHANNEL_x. - * Example: - * __LL_DAC_CHANNEL_TO_DECIMAL_NB(LL_DAC_CHANNEL_1) - * will return decimal number "1". - * @note The input can be a value from functions where a channel - * number is returned. - * @param __CHANNEL__ This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @retval 1...2 (value "2" depending on DAC channel 2 availability) - */ -#define __LL_DAC_CHANNEL_TO_DECIMAL_NB(__CHANNEL__) \ - ((__CHANNEL__) & DAC_SWTR_CHX_MASK) - -/** - * @brief Helper macro to get DAC channel in literal format LL_DAC_CHANNEL_x - * from number in decimal format. - * Example: - * __LL_DAC_DECIMAL_NB_TO_CHANNEL(1) - * will return a data equivalent to "LL_DAC_CHANNEL_1". - * @note If the input parameter does not correspond to a DAC channel, - * this macro returns value '0'. - * @param __DECIMAL_NB__ 1...2 (value "2" depending on DAC channel 2 availability) - * @retval Returned value can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - */ -#if defined(DAC_CHANNEL2_SUPPORT) -#define __LL_DAC_DECIMAL_NB_TO_CHANNEL(__DECIMAL_NB__) \ - (((__DECIMAL_NB__) == 1UL) \ - ? ( \ - LL_DAC_CHANNEL_1 \ - ) \ - : \ - (((__DECIMAL_NB__) == 2UL) \ - ? ( \ - LL_DAC_CHANNEL_2 \ - ) \ - : \ - ( \ - 0UL \ - ) \ - ) \ - ) -#else -#define __LL_DAC_DECIMAL_NB_TO_CHANNEL(__DECIMAL_NB__) \ - (((__DECIMAL_NB__) == 1UL) \ - ? ( \ - LL_DAC_CHANNEL_1 \ - ) \ - : \ - ( \ - 0UL \ - ) \ - ) -#endif /* DAC_CHANNEL2_SUPPORT */ - -/** - * @brief Helper macro to define the DAC conversion data full-scale digital - * value corresponding to the selected DAC resolution. - * @note DAC conversion data full-scale corresponds to voltage range - * determined by analog voltage references Vref+ and Vref- - * (refer to reference manual). - * @param __DAC_RESOLUTION__ This parameter can be one of the following values: - * @arg @ref LL_DAC_RESOLUTION_12B - * @arg @ref LL_DAC_RESOLUTION_8B - * @retval ADC conversion data equivalent voltage value (unit: mVolt) - */ -#define __LL_DAC_DIGITAL_SCALE(__DAC_RESOLUTION__) \ - ((0x00000FFFUL) >> ((__DAC_RESOLUTION__) << 1UL)) - -/** - * @brief Helper macro to calculate the DAC conversion data (unit: digital - * value) corresponding to a voltage (unit: mVolt). - * @note This helper macro is intended to provide input data in voltage - * rather than digital value, - * to be used with LL DAC functions such as - * @ref LL_DAC_ConvertData12RightAligned(). - * @note Analog reference voltage (Vref+) must be either known from - * user board environment or can be calculated using ADC measurement - * and ADC helper macro __LL_ADC_CALC_VREFANALOG_VOLTAGE(). - * @param __VREFANALOG_VOLTAGE__ Analog reference voltage (unit: mV) - * @param __DAC_VOLTAGE__ Voltage to be generated by DAC channel - * (unit: mVolt). - * @param __DAC_RESOLUTION__ This parameter can be one of the following values: - * @arg @ref LL_DAC_RESOLUTION_12B - * @arg @ref LL_DAC_RESOLUTION_8B - * @retval DAC conversion data (unit: digital value) - */ -#define __LL_DAC_CALC_VOLTAGE_TO_DATA(__VREFANALOG_VOLTAGE__,\ - __DAC_VOLTAGE__,\ - __DAC_RESOLUTION__) \ -((__DAC_VOLTAGE__) * __LL_DAC_DIGITAL_SCALE(__DAC_RESOLUTION__) \ - / (__VREFANALOG_VOLTAGE__) \ -) - -/** - * @} - */ - -/** - * @} - */ - - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup DAC_LL_Exported_Functions DAC Exported Functions - * @{ - */ -/** - * @brief Set the conversion trigger source for the selected DAC channel. - * @note For conversion trigger source to be effective, DAC trigger - * must be enabled using function @ref LL_DAC_EnableTrigger(). - * @note To set conversion trigger source, DAC channel must be disabled. - * Otherwise, the setting is discarded. - * @note Availability of parameters of trigger sources from timer - * depends on timers availability on the selected device. - * @rmtoll CR TSEL1 LL_DAC_SetTriggerSource\n - * CR TSEL2 LL_DAC_SetTriggerSource - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @param TriggerSource This parameter can be one of the following values: - * @arg @ref LL_DAC_TRIG_SOFTWARE - * @arg @ref LL_DAC_TRIG_EXT_TIM8_TRGO - * @arg @ref LL_DAC_TRIG_EXT_TIM7_TRGO - * @arg @ref LL_DAC_TRIG_EXT_TIM6_TRGO - * @arg @ref LL_DAC_TRIG_EXT_TIM5_TRGO - * @arg @ref LL_DAC_TRIG_EXT_TIM4_TRGO - * @arg @ref LL_DAC_TRIG_EXT_TIM2_TRGO - * @arg @ref LL_DAC_TRIG_EXT_EXTI_LINE9 - * @retval None - */ -__STATIC_INLINE void LL_DAC_SetTriggerSource(DAC_TypeDef *DACx, uint32_t DAC_Channel, uint32_t TriggerSource) -{ - MODIFY_REG(DACx->CR, - DAC_CR_TSEL1 << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK), - TriggerSource << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK)); -} - -/** - * @brief Get the conversion trigger source for the selected DAC channel. - * @note For conversion trigger source to be effective, DAC trigger - * must be enabled using function @ref LL_DAC_EnableTrigger(). - * @note Availability of parameters of trigger sources from timer - * depends on timers availability on the selected device. - * @rmtoll CR TSEL1 LL_DAC_GetTriggerSource\n - * CR TSEL2 LL_DAC_GetTriggerSource - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @retval Returned value can be one of the following values: - * @arg @ref LL_DAC_TRIG_SOFTWARE - * @arg @ref LL_DAC_TRIG_EXT_TIM8_TRGO - * @arg @ref LL_DAC_TRIG_EXT_TIM7_TRGO - * @arg @ref LL_DAC_TRIG_EXT_TIM6_TRGO - * @arg @ref LL_DAC_TRIG_EXT_TIM5_TRGO - * @arg @ref LL_DAC_TRIG_EXT_TIM4_TRGO - * @arg @ref LL_DAC_TRIG_EXT_TIM2_TRGO - * @arg @ref LL_DAC_TRIG_EXT_EXTI_LINE9 - */ -__STATIC_INLINE uint32_t LL_DAC_GetTriggerSource(DAC_TypeDef *DACx, uint32_t DAC_Channel) -{ - return (uint32_t)(READ_BIT(DACx->CR, DAC_CR_TSEL1 << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK)) - >> (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK) - ); -} - -/** - * @brief Set the waveform automatic generation mode - * for the selected DAC channel. - * @rmtoll CR WAVE1 LL_DAC_SetWaveAutoGeneration\n - * CR WAVE2 LL_DAC_SetWaveAutoGeneration - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @param WaveAutoGeneration This parameter can be one of the following values: - * @arg @ref LL_DAC_WAVE_AUTO_GENERATION_NONE - * @arg @ref LL_DAC_WAVE_AUTO_GENERATION_NOISE - * @arg @ref LL_DAC_WAVE_AUTO_GENERATION_TRIANGLE - * @retval None - */ -__STATIC_INLINE void LL_DAC_SetWaveAutoGeneration(DAC_TypeDef *DACx, uint32_t DAC_Channel, uint32_t WaveAutoGeneration) -{ - MODIFY_REG(DACx->CR, - DAC_CR_WAVE1 << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK), - WaveAutoGeneration << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK)); -} - -/** - * @brief Get the waveform automatic generation mode - * for the selected DAC channel. - * @rmtoll CR WAVE1 LL_DAC_GetWaveAutoGeneration\n - * CR WAVE2 LL_DAC_GetWaveAutoGeneration - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @retval Returned value can be one of the following values: - * @arg @ref LL_DAC_WAVE_AUTO_GENERATION_NONE - * @arg @ref LL_DAC_WAVE_AUTO_GENERATION_NOISE - * @arg @ref LL_DAC_WAVE_AUTO_GENERATION_TRIANGLE - */ -__STATIC_INLINE uint32_t LL_DAC_GetWaveAutoGeneration(DAC_TypeDef *DACx, uint32_t DAC_Channel) -{ - return (uint32_t)(READ_BIT(DACx->CR, DAC_CR_WAVE1 << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK)) - >> (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK) - ); -} - -/** - * @brief Set the noise waveform generation for the selected DAC channel: - * Noise mode and parameters LFSR (linear feedback shift register). - * @note For wave generation to be effective, DAC channel - * wave generation mode must be enabled using - * function @ref LL_DAC_SetWaveAutoGeneration(). - * @note This setting can be set when the selected DAC channel is disabled - * (otherwise, the setting operation is ignored). - * @rmtoll CR MAMP1 LL_DAC_SetWaveNoiseLFSR\n - * CR MAMP2 LL_DAC_SetWaveNoiseLFSR - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @param NoiseLFSRMask This parameter can be one of the following values: - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BIT0 - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BITS1_0 - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BITS2_0 - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BITS3_0 - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BITS4_0 - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BITS5_0 - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BITS6_0 - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BITS7_0 - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BITS8_0 - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BITS9_0 - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BITS10_0 - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BITS11_0 - * @retval None - */ -__STATIC_INLINE void LL_DAC_SetWaveNoiseLFSR(DAC_TypeDef *DACx, uint32_t DAC_Channel, uint32_t NoiseLFSRMask) -{ - MODIFY_REG(DACx->CR, - DAC_CR_MAMP1 << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK), - NoiseLFSRMask << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK)); -} - -/** - * @brief Get the noise waveform generation for the selected DAC channel: - * Noise mode and parameters LFSR (linear feedback shift register). - * @rmtoll CR MAMP1 LL_DAC_GetWaveNoiseLFSR\n - * CR MAMP2 LL_DAC_GetWaveNoiseLFSR - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @retval Returned value can be one of the following values: - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BIT0 - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BITS1_0 - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BITS2_0 - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BITS3_0 - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BITS4_0 - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BITS5_0 - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BITS6_0 - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BITS7_0 - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BITS8_0 - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BITS9_0 - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BITS10_0 - * @arg @ref LL_DAC_NOISE_LFSR_UNMASK_BITS11_0 - */ -__STATIC_INLINE uint32_t LL_DAC_GetWaveNoiseLFSR(DAC_TypeDef *DACx, uint32_t DAC_Channel) -{ - return (uint32_t)(READ_BIT(DACx->CR, DAC_CR_MAMP1 << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK)) - >> (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK) - ); -} - -/** - * @brief Set the triangle waveform generation for the selected DAC channel: - * triangle mode and amplitude. - * @note For wave generation to be effective, DAC channel - * wave generation mode must be enabled using - * function @ref LL_DAC_SetWaveAutoGeneration(). - * @note This setting can be set when the selected DAC channel is disabled - * (otherwise, the setting operation is ignored). - * @rmtoll CR MAMP1 LL_DAC_SetWaveTriangleAmplitude\n - * CR MAMP2 LL_DAC_SetWaveTriangleAmplitude - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @param TriangleAmplitude This parameter can be one of the following values: - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_1 - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_3 - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_7 - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_15 - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_31 - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_63 - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_127 - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_255 - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_511 - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_1023 - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_2047 - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_4095 - * @retval None - */ -__STATIC_INLINE void LL_DAC_SetWaveTriangleAmplitude(DAC_TypeDef *DACx, uint32_t DAC_Channel, - uint32_t TriangleAmplitude) -{ - MODIFY_REG(DACx->CR, - DAC_CR_MAMP1 << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK), - TriangleAmplitude << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK)); -} - -/** - * @brief Get the triangle waveform generation for the selected DAC channel: - * triangle mode and amplitude. - * @rmtoll CR MAMP1 LL_DAC_GetWaveTriangleAmplitude\n - * CR MAMP2 LL_DAC_GetWaveTriangleAmplitude - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @retval Returned value can be one of the following values: - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_1 - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_3 - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_7 - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_15 - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_31 - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_63 - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_127 - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_255 - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_511 - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_1023 - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_2047 - * @arg @ref LL_DAC_TRIANGLE_AMPLITUDE_4095 - */ -__STATIC_INLINE uint32_t LL_DAC_GetWaveTriangleAmplitude(DAC_TypeDef *DACx, uint32_t DAC_Channel) -{ - return (uint32_t)(READ_BIT(DACx->CR, DAC_CR_MAMP1 << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK)) - >> (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK) - ); -} - -/** - * @brief Set the output buffer for the selected DAC channel. - * @rmtoll CR BOFF1 LL_DAC_SetOutputBuffer\n - * CR BOFF2 LL_DAC_SetOutputBuffer - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @param OutputBuffer This parameter can be one of the following values: - * @arg @ref LL_DAC_OUTPUT_BUFFER_ENABLE - * @arg @ref LL_DAC_OUTPUT_BUFFER_DISABLE - * @retval None - */ -__STATIC_INLINE void LL_DAC_SetOutputBuffer(DAC_TypeDef *DACx, uint32_t DAC_Channel, uint32_t OutputBuffer) -{ - MODIFY_REG(DACx->CR, - DAC_CR_BOFF1 << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK), - OutputBuffer << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK)); -} - -/** - * @brief Get the output buffer state for the selected DAC channel. - * @rmtoll CR BOFF1 LL_DAC_GetOutputBuffer\n - * CR BOFF2 LL_DAC_GetOutputBuffer - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @retval Returned value can be one of the following values: - * @arg @ref LL_DAC_OUTPUT_BUFFER_ENABLE - * @arg @ref LL_DAC_OUTPUT_BUFFER_DISABLE - */ -__STATIC_INLINE uint32_t LL_DAC_GetOutputBuffer(DAC_TypeDef *DACx, uint32_t DAC_Channel) -{ - return (uint32_t)(READ_BIT(DACx->CR, DAC_CR_BOFF1 << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK)) - >> (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK) - ); -} - -/** - * @} - */ - -/** @defgroup DAC_LL_EF_DMA_Management DMA Management - * @{ - */ - -/** - * @brief Enable DAC DMA transfer request of the selected channel. - * @note To configure DMA source address (peripheral address), - * use function @ref LL_DAC_DMA_GetRegAddr(). - * @rmtoll CR DMAEN1 LL_DAC_EnableDMAReq\n - * CR DMAEN2 LL_DAC_EnableDMAReq - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @retval None - */ -__STATIC_INLINE void LL_DAC_EnableDMAReq(DAC_TypeDef *DACx, uint32_t DAC_Channel) -{ - SET_BIT(DACx->CR, - DAC_CR_DMAEN1 << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK)); -} - -/** - * @brief Disable DAC DMA transfer request of the selected channel. - * @note To configure DMA source address (peripheral address), - * use function @ref LL_DAC_DMA_GetRegAddr(). - * @rmtoll CR DMAEN1 LL_DAC_DisableDMAReq\n - * CR DMAEN2 LL_DAC_DisableDMAReq - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @retval None - */ -__STATIC_INLINE void LL_DAC_DisableDMAReq(DAC_TypeDef *DACx, uint32_t DAC_Channel) -{ - CLEAR_BIT(DACx->CR, - DAC_CR_DMAEN1 << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK)); -} - -/** - * @brief Get DAC DMA transfer request state of the selected channel. - * (0: DAC DMA transfer request is disabled, 1: DAC DMA transfer request is enabled) - * @rmtoll CR DMAEN1 LL_DAC_IsDMAReqEnabled\n - * CR DMAEN2 LL_DAC_IsDMAReqEnabled - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DAC_IsDMAReqEnabled(DAC_TypeDef *DACx, uint32_t DAC_Channel) -{ - return ((READ_BIT(DACx->CR, - DAC_CR_DMAEN1 << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK)) - == (DAC_CR_DMAEN1 << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK))) ? 1UL : 0UL); -} - -/** - * @brief Function to help to configure DMA transfer to DAC: retrieve the - * DAC register address from DAC instance and a list of DAC registers - * intended to be used (most commonly) with DMA transfer. - * @note These DAC registers are data holding registers: - * when DAC conversion is requested, DAC generates a DMA transfer - * request to have data available in DAC data holding registers. - * @note This macro is intended to be used with LL DMA driver, refer to - * function "LL_DMA_ConfigAddresses()". - * Example: - * LL_DMA_ConfigAddresses(DMA1, - * LL_DMA_CHANNEL_1, - * (uint32_t)&< array or variable >, - * LL_DAC_DMA_GetRegAddr(DAC1, LL_DAC_CHANNEL_1, - * LL_DAC_DMA_REG_DATA_12BITS_RIGHT_ALIGNED), - * LL_DMA_DIRECTION_MEMORY_TO_PERIPH); - * @rmtoll DHR12R1 DACC1DHR LL_DAC_DMA_GetRegAddr\n - * DHR12L1 DACC1DHR LL_DAC_DMA_GetRegAddr\n - * DHR8R1 DACC1DHR LL_DAC_DMA_GetRegAddr\n - * DHR12R2 DACC2DHR LL_DAC_DMA_GetRegAddr\n - * DHR12L2 DACC2DHR LL_DAC_DMA_GetRegAddr\n - * DHR8R2 DACC2DHR LL_DAC_DMA_GetRegAddr - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @param Register This parameter can be one of the following values: - * @arg @ref LL_DAC_DMA_REG_DATA_12BITS_RIGHT_ALIGNED - * @arg @ref LL_DAC_DMA_REG_DATA_12BITS_LEFT_ALIGNED - * @arg @ref LL_DAC_DMA_REG_DATA_8BITS_RIGHT_ALIGNED - * @retval DAC register address - */ -__STATIC_INLINE uint32_t LL_DAC_DMA_GetRegAddr(DAC_TypeDef *DACx, uint32_t DAC_Channel, uint32_t Register) -{ - /* Retrieve address of register DHR12Rx, DHR12Lx or DHR8Rx depending on */ - /* DAC channel selected. */ - return ((uint32_t)(__DAC_PTR_REG_OFFSET((DACx)->DHR12R1, ((DAC_Channel >> (Register & 0x1FUL)) - & DAC_REG_DHR_REGOFFSET_MASK_POSBIT0)))); -} -/** - * @} - */ - -/** @defgroup DAC_LL_EF_Operation Operation on DAC channels - * @{ - */ - -/** - * @brief Enable DAC selected channel. - * @rmtoll CR EN1 LL_DAC_Enable\n - * CR EN2 LL_DAC_Enable - * @note After enable from off state, DAC channel requires a delay - * for output voltage to reach accuracy +/- 1 LSB. - * Refer to device datasheet, parameter "tWAKEUP". - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @retval None - */ -__STATIC_INLINE void LL_DAC_Enable(DAC_TypeDef *DACx, uint32_t DAC_Channel) -{ - SET_BIT(DACx->CR, - DAC_CR_EN1 << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK)); -} - -/** - * @brief Disable DAC selected channel. - * @rmtoll CR EN1 LL_DAC_Disable\n - * CR EN2 LL_DAC_Disable - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @retval None - */ -__STATIC_INLINE void LL_DAC_Disable(DAC_TypeDef *DACx, uint32_t DAC_Channel) -{ - CLEAR_BIT(DACx->CR, - DAC_CR_EN1 << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK)); -} - -/** - * @brief Get DAC enable state of the selected channel. - * (0: DAC channel is disabled, 1: DAC channel is enabled) - * @rmtoll CR EN1 LL_DAC_IsEnabled\n - * CR EN2 LL_DAC_IsEnabled - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DAC_IsEnabled(DAC_TypeDef *DACx, uint32_t DAC_Channel) -{ - return ((READ_BIT(DACx->CR, - DAC_CR_EN1 << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK)) - == (DAC_CR_EN1 << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK))) ? 1UL : 0UL); -} - -/** - * @brief Enable DAC trigger of the selected channel. - * @note - If DAC trigger is disabled, DAC conversion is performed - * automatically once the data holding register is updated, - * using functions "LL_DAC_ConvertData{8; 12}{Right; Left} Aligned()": - * @ref LL_DAC_ConvertData12RightAligned(), ... - * - If DAC trigger is enabled, DAC conversion is performed - * only when a hardware of software trigger event is occurring. - * Select trigger source using - * function @ref LL_DAC_SetTriggerSource(). - * @rmtoll CR TEN1 LL_DAC_EnableTrigger\n - * CR TEN2 LL_DAC_EnableTrigger - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @retval None - */ -__STATIC_INLINE void LL_DAC_EnableTrigger(DAC_TypeDef *DACx, uint32_t DAC_Channel) -{ - SET_BIT(DACx->CR, - DAC_CR_TEN1 << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK)); -} - -/** - * @brief Disable DAC trigger of the selected channel. - * @rmtoll CR TEN1 LL_DAC_DisableTrigger\n - * CR TEN2 LL_DAC_DisableTrigger - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @retval None - */ -__STATIC_INLINE void LL_DAC_DisableTrigger(DAC_TypeDef *DACx, uint32_t DAC_Channel) -{ - CLEAR_BIT(DACx->CR, - DAC_CR_TEN1 << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK)); -} - -/** - * @brief Get DAC trigger state of the selected channel. - * (0: DAC trigger is disabled, 1: DAC trigger is enabled) - * @rmtoll CR TEN1 LL_DAC_IsTriggerEnabled\n - * CR TEN2 LL_DAC_IsTriggerEnabled - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DAC_IsTriggerEnabled(DAC_TypeDef *DACx, uint32_t DAC_Channel) -{ - return ((READ_BIT(DACx->CR, - DAC_CR_TEN1 << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK)) - == (DAC_CR_TEN1 << (DAC_Channel & DAC_CR_CHX_BITOFFSET_MASK))) ? 1UL : 0UL); -} - -/** - * @brief Trig DAC conversion by software for the selected DAC channel. - * @note Preliminarily, DAC trigger must be set to software trigger - * using function - * @ref LL_DAC_Init() - * @ref LL_DAC_SetTriggerSource() - * with parameter "LL_DAC_TRIGGER_SOFTWARE". - * and DAC trigger must be enabled using - * function @ref LL_DAC_EnableTrigger(). - * @note For devices featuring DAC with 2 channels: this function - * can perform a SW start of both DAC channels simultaneously. - * Two channels can be selected as parameter. - * Example: (LL_DAC_CHANNEL_1 | LL_DAC_CHANNEL_2) - * @rmtoll SWTRIGR SWTRIG1 LL_DAC_TrigSWConversion\n - * SWTRIGR SWTRIG2 LL_DAC_TrigSWConversion - * @param DACx DAC instance - * @param DAC_Channel This parameter can a combination of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @retval None - */ -__STATIC_INLINE void LL_DAC_TrigSWConversion(DAC_TypeDef *DACx, uint32_t DAC_Channel) -{ - SET_BIT(DACx->SWTRIGR, - (DAC_Channel & DAC_SWTR_CHX_MASK)); -} - -/** - * @brief Set the data to be loaded in the data holding register - * in format 12 bits left alignment (LSB aligned on bit 0), - * for the selected DAC channel. - * @rmtoll DHR12R1 DACC1DHR LL_DAC_ConvertData12RightAligned\n - * DHR12R2 DACC2DHR LL_DAC_ConvertData12RightAligned - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @param Data Value between Min_Data=0x000 and Max_Data=0xFFF - * @retval None - */ -__STATIC_INLINE void LL_DAC_ConvertData12RightAligned(DAC_TypeDef *DACx, uint32_t DAC_Channel, uint32_t Data) -{ - __IO uint32_t *preg = __DAC_PTR_REG_OFFSET(DACx->DHR12R1, (DAC_Channel >> DAC_REG_DHR12RX_REGOFFSET_BITOFFSET_POS) - & DAC_REG_DHR_REGOFFSET_MASK_POSBIT0); - - MODIFY_REG(*preg, DAC_DHR12R1_DACC1DHR, Data); -} - -/** - * @brief Set the data to be loaded in the data holding register - * in format 12 bits left alignment (MSB aligned on bit 15), - * for the selected DAC channel. - * @rmtoll DHR12L1 DACC1DHR LL_DAC_ConvertData12LeftAligned\n - * DHR12L2 DACC2DHR LL_DAC_ConvertData12LeftAligned - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @param Data Value between Min_Data=0x000 and Max_Data=0xFFF - * @retval None - */ -__STATIC_INLINE void LL_DAC_ConvertData12LeftAligned(DAC_TypeDef *DACx, uint32_t DAC_Channel, uint32_t Data) -{ - __IO uint32_t *preg = __DAC_PTR_REG_OFFSET(DACx->DHR12R1, (DAC_Channel >> DAC_REG_DHR12LX_REGOFFSET_BITOFFSET_POS) - & DAC_REG_DHR_REGOFFSET_MASK_POSBIT0); - - MODIFY_REG(*preg, DAC_DHR12L1_DACC1DHR, Data); -} - -/** - * @brief Set the data to be loaded in the data holding register - * in format 8 bits left alignment (LSB aligned on bit 0), - * for the selected DAC channel. - * @rmtoll DHR8R1 DACC1DHR LL_DAC_ConvertData8RightAligned\n - * DHR8R2 DACC2DHR LL_DAC_ConvertData8RightAligned - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @param Data Value between Min_Data=0x00 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_DAC_ConvertData8RightAligned(DAC_TypeDef *DACx, uint32_t DAC_Channel, uint32_t Data) -{ - __IO uint32_t *preg = __DAC_PTR_REG_OFFSET(DACx->DHR12R1, (DAC_Channel >> DAC_REG_DHR8RX_REGOFFSET_BITOFFSET_POS) - & DAC_REG_DHR_REGOFFSET_MASK_POSBIT0); - - MODIFY_REG(*preg, DAC_DHR8R1_DACC1DHR, Data); -} - -#if defined(DAC_CHANNEL2_SUPPORT) -/** - * @brief Set the data to be loaded in the data holding register - * in format 12 bits left alignment (LSB aligned on bit 0), - * for both DAC channels. - * @rmtoll DHR12RD DACC1DHR LL_DAC_ConvertDualData12RightAligned\n - * DHR12RD DACC2DHR LL_DAC_ConvertDualData12RightAligned - * @param DACx DAC instance - * @param DataChannel1 Value between Min_Data=0x000 and Max_Data=0xFFF - * @param DataChannel2 Value between Min_Data=0x000 and Max_Data=0xFFF - * @retval None - */ -__STATIC_INLINE void LL_DAC_ConvertDualData12RightAligned(DAC_TypeDef *DACx, uint32_t DataChannel1, - uint32_t DataChannel2) -{ - MODIFY_REG(DACx->DHR12RD, - (DAC_DHR12RD_DACC2DHR | DAC_DHR12RD_DACC1DHR), - ((DataChannel2 << DAC_DHR12RD_DACC2DHR_BITOFFSET_POS) | DataChannel1)); -} - -/** - * @brief Set the data to be loaded in the data holding register - * in format 12 bits left alignment (MSB aligned on bit 15), - * for both DAC channels. - * @rmtoll DHR12LD DACC1DHR LL_DAC_ConvertDualData12LeftAligned\n - * DHR12LD DACC2DHR LL_DAC_ConvertDualData12LeftAligned - * @param DACx DAC instance - * @param DataChannel1 Value between Min_Data=0x000 and Max_Data=0xFFF - * @param DataChannel2 Value between Min_Data=0x000 and Max_Data=0xFFF - * @retval None - */ -__STATIC_INLINE void LL_DAC_ConvertDualData12LeftAligned(DAC_TypeDef *DACx, uint32_t DataChannel1, - uint32_t DataChannel2) -{ - /* Note: Data of DAC channel 2 shift value subtracted of 4 because */ - /* data on 16 bits and DAC channel 2 bits field is on the 12 MSB, */ - /* the 4 LSB must be taken into account for the shift value. */ - MODIFY_REG(DACx->DHR12LD, - (DAC_DHR12LD_DACC2DHR | DAC_DHR12LD_DACC1DHR), - ((DataChannel2 << (DAC_DHR12LD_DACC2DHR_BITOFFSET_POS - 4U)) | DataChannel1)); -} - -/** - * @brief Set the data to be loaded in the data holding register - * in format 8 bits left alignment (LSB aligned on bit 0), - * for both DAC channels. - * @rmtoll DHR8RD DACC1DHR LL_DAC_ConvertDualData8RightAligned\n - * DHR8RD DACC2DHR LL_DAC_ConvertDualData8RightAligned - * @param DACx DAC instance - * @param DataChannel1 Value between Min_Data=0x00 and Max_Data=0xFF - * @param DataChannel2 Value between Min_Data=0x00 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_DAC_ConvertDualData8RightAligned(DAC_TypeDef *DACx, uint32_t DataChannel1, - uint32_t DataChannel2) -{ - MODIFY_REG(DACx->DHR8RD, - (DAC_DHR8RD_DACC2DHR | DAC_DHR8RD_DACC1DHR), - ((DataChannel2 << DAC_DHR8RD_DACC2DHR_BITOFFSET_POS) | DataChannel1)); -} -#endif /* DAC_CHANNEL2_SUPPORT */ - -/** - * @brief Retrieve output data currently generated for the selected DAC channel. - * @note Whatever alignment and resolution settings - * (using functions "LL_DAC_ConvertData{8; 12}{Right; Left} Aligned()": - * @ref LL_DAC_ConvertData12RightAligned(), ...), - * output data format is 12 bits right aligned (LSB aligned on bit 0). - * @rmtoll DOR1 DACC1DOR LL_DAC_RetrieveOutputData\n - * DOR2 DACC2DOR LL_DAC_RetrieveOutputData - * @param DACx DAC instance - * @param DAC_Channel This parameter can be one of the following values: - * @arg @ref LL_DAC_CHANNEL_1 - * @arg @ref LL_DAC_CHANNEL_2 (1) - * - * (1) On this STM32 serie, parameter not available on all devices. - * Refer to device datasheet for channels availability. - * @retval Value between Min_Data=0x000 and Max_Data=0xFFF - */ -__STATIC_INLINE uint32_t LL_DAC_RetrieveOutputData(DAC_TypeDef *DACx, uint32_t DAC_Channel) -{ - __IO uint32_t const *preg = __DAC_PTR_REG_OFFSET(DACx->DOR1, (DAC_Channel >> DAC_REG_DORX_REGOFFSET_BITOFFSET_POS) - & DAC_REG_DORX_REGOFFSET_MASK_POSBIT0); - - return (uint16_t) READ_BIT(*preg, DAC_DOR1_DACC1DOR); -} - -/** - * @} - */ - -/** @defgroup DAC_LL_EF_FLAG_Management FLAG Management - * @{ - */ - -/** - * @brief Get DAC underrun flag for DAC channel 1 - * @rmtoll SR DMAUDR1 LL_DAC_IsActiveFlag_DMAUDR1 - * @param DACx DAC instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DAC_IsActiveFlag_DMAUDR1(DAC_TypeDef *DACx) -{ - return ((READ_BIT(DACx->SR, LL_DAC_FLAG_DMAUDR1) == (LL_DAC_FLAG_DMAUDR1)) ? 1UL : 0UL); -} - -#if defined(DAC_CHANNEL2_SUPPORT) -/** - * @brief Get DAC underrun flag for DAC channel 2 - * @rmtoll SR DMAUDR2 LL_DAC_IsActiveFlag_DMAUDR2 - * @param DACx DAC instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DAC_IsActiveFlag_DMAUDR2(DAC_TypeDef *DACx) -{ - return ((READ_BIT(DACx->SR, LL_DAC_FLAG_DMAUDR2) == (LL_DAC_FLAG_DMAUDR2)) ? 1UL : 0UL); -} -#endif /* DAC_CHANNEL2_SUPPORT */ - -/** - * @brief Clear DAC underrun flag for DAC channel 1 - * @rmtoll SR DMAUDR1 LL_DAC_ClearFlag_DMAUDR1 - * @param DACx DAC instance - * @retval None - */ -__STATIC_INLINE void LL_DAC_ClearFlag_DMAUDR1(DAC_TypeDef *DACx) -{ - WRITE_REG(DACx->SR, LL_DAC_FLAG_DMAUDR1); -} - -#if defined(DAC_CHANNEL2_SUPPORT) -/** - * @brief Clear DAC underrun flag for DAC channel 2 - * @rmtoll SR DMAUDR2 LL_DAC_ClearFlag_DMAUDR2 - * @param DACx DAC instance - * @retval None - */ -__STATIC_INLINE void LL_DAC_ClearFlag_DMAUDR2(DAC_TypeDef *DACx) -{ - WRITE_REG(DACx->SR, LL_DAC_FLAG_DMAUDR2); -} -#endif /* DAC_CHANNEL2_SUPPORT */ - -/** - * @} - */ - -/** @defgroup DAC_LL_EF_IT_Management IT management - * @{ - */ - -/** - * @brief Enable DMA underrun interrupt for DAC channel 1 - * @rmtoll CR DMAUDRIE1 LL_DAC_EnableIT_DMAUDR1 - * @param DACx DAC instance - * @retval None - */ -__STATIC_INLINE void LL_DAC_EnableIT_DMAUDR1(DAC_TypeDef *DACx) -{ - SET_BIT(DACx->CR, LL_DAC_IT_DMAUDRIE1); -} - -#if defined(DAC_CHANNEL2_SUPPORT) -/** - * @brief Enable DMA underrun interrupt for DAC channel 2 - * @rmtoll CR DMAUDRIE2 LL_DAC_EnableIT_DMAUDR2 - * @param DACx DAC instance - * @retval None - */ -__STATIC_INLINE void LL_DAC_EnableIT_DMAUDR2(DAC_TypeDef *DACx) -{ - SET_BIT(DACx->CR, LL_DAC_IT_DMAUDRIE2); -} -#endif /* DAC_CHANNEL2_SUPPORT */ - -/** - * @brief Disable DMA underrun interrupt for DAC channel 1 - * @rmtoll CR DMAUDRIE1 LL_DAC_DisableIT_DMAUDR1 - * @param DACx DAC instance - * @retval None - */ -__STATIC_INLINE void LL_DAC_DisableIT_DMAUDR1(DAC_TypeDef *DACx) -{ - CLEAR_BIT(DACx->CR, LL_DAC_IT_DMAUDRIE1); -} - -#if defined(DAC_CHANNEL2_SUPPORT) -/** - * @brief Disable DMA underrun interrupt for DAC channel 2 - * @rmtoll CR DMAUDRIE2 LL_DAC_DisableIT_DMAUDR2 - * @param DACx DAC instance - * @retval None - */ -__STATIC_INLINE void LL_DAC_DisableIT_DMAUDR2(DAC_TypeDef *DACx) -{ - CLEAR_BIT(DACx->CR, LL_DAC_IT_DMAUDRIE2); -} -#endif /* DAC_CHANNEL2_SUPPORT */ - -/** - * @brief Get DMA underrun interrupt for DAC channel 1 - * @rmtoll CR DMAUDRIE1 LL_DAC_IsEnabledIT_DMAUDR1 - * @param DACx DAC instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DAC_IsEnabledIT_DMAUDR1(DAC_TypeDef *DACx) -{ - return ((READ_BIT(DACx->CR, LL_DAC_IT_DMAUDRIE1) == (LL_DAC_IT_DMAUDRIE1)) ? 1UL : 0UL); -} - -#if defined(DAC_CHANNEL2_SUPPORT) -/** - * @brief Get DMA underrun interrupt for DAC channel 2 - * @rmtoll CR DMAUDRIE2 LL_DAC_IsEnabledIT_DMAUDR2 - * @param DACx DAC instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DAC_IsEnabledIT_DMAUDR2(DAC_TypeDef *DACx) -{ - return ((READ_BIT(DACx->CR, LL_DAC_IT_DMAUDRIE2) == (LL_DAC_IT_DMAUDRIE2)) ? 1UL : 0UL); -} -#endif /* DAC_CHANNEL2_SUPPORT */ - -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup DAC_LL_EF_Init Initialization and de-initialization functions - * @{ - */ - -ErrorStatus LL_DAC_DeInit(DAC_TypeDef *DACx); -ErrorStatus LL_DAC_Init(DAC_TypeDef *DACx, uint32_t DAC_Channel, LL_DAC_InitTypeDef *DAC_InitStruct); -void LL_DAC_StructInit(LL_DAC_InitTypeDef *DAC_InitStruct); - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* DAC */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_LL_DAC_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_dma.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_dma.h deleted file mode 100644 index 63264e6..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_dma.h +++ /dev/null @@ -1,2870 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_dma.h - * @author MCD Application Team - * @brief Header file of DMA LL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_LL_DMA_H -#define __STM32F4xx_LL_DMA_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (DMA1) || defined (DMA2) - -/** @defgroup DMA_LL DMA - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/** @defgroup DMA_LL_Private_Variables DMA Private Variables - * @{ - */ -/* Array used to get the DMA stream register offset versus stream index LL_DMA_STREAM_x */ -static const uint8_t STREAM_OFFSET_TAB[] = -{ - (uint8_t)(DMA1_Stream0_BASE - DMA1_BASE), - (uint8_t)(DMA1_Stream1_BASE - DMA1_BASE), - (uint8_t)(DMA1_Stream2_BASE - DMA1_BASE), - (uint8_t)(DMA1_Stream3_BASE - DMA1_BASE), - (uint8_t)(DMA1_Stream4_BASE - DMA1_BASE), - (uint8_t)(DMA1_Stream5_BASE - DMA1_BASE), - (uint8_t)(DMA1_Stream6_BASE - DMA1_BASE), - (uint8_t)(DMA1_Stream7_BASE - DMA1_BASE) -}; - -/** - * @} - */ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup DMA_LL_Private_Constants DMA Private Constants - * @{ - */ -/** - * @} - */ - - -/* Private macros ------------------------------------------------------------*/ -/* Exported types ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup DMA_LL_ES_INIT DMA Exported Init structure - * @{ - */ -typedef struct -{ - uint32_t PeriphOrM2MSrcAddress; /*!< Specifies the peripheral base address for DMA transfer - or as Source base address in case of memory to memory transfer direction. - - This parameter must be a value between Min_Data = 0 and Max_Data = 0xFFFFFFFF. */ - - uint32_t MemoryOrM2MDstAddress; /*!< Specifies the memory base address for DMA transfer - or as Destination base address in case of memory to memory transfer direction. - - This parameter must be a value between Min_Data = 0 and Max_Data = 0xFFFFFFFF. */ - - uint32_t Direction; /*!< Specifies if the data will be transferred from memory to peripheral, - from memory to memory or from peripheral to memory. - This parameter can be a value of @ref DMA_LL_EC_DIRECTION - - This feature can be modified afterwards using unitary function @ref LL_DMA_SetDataTransferDirection(). */ - - uint32_t Mode; /*!< Specifies the normal or circular operation mode. - This parameter can be a value of @ref DMA_LL_EC_MODE - @note The circular buffer mode cannot be used if the memory to memory - data transfer direction is configured on the selected Stream - - This feature can be modified afterwards using unitary function @ref LL_DMA_SetMode(). */ - - uint32_t PeriphOrM2MSrcIncMode; /*!< Specifies whether the Peripheral address or Source address in case of memory to memory transfer direction - is incremented or not. - This parameter can be a value of @ref DMA_LL_EC_PERIPH - - This feature can be modified afterwards using unitary function @ref LL_DMA_SetPeriphIncMode(). */ - - uint32_t MemoryOrM2MDstIncMode; /*!< Specifies whether the Memory address or Destination address in case of memory to memory transfer direction - is incremented or not. - This parameter can be a value of @ref DMA_LL_EC_MEMORY - - This feature can be modified afterwards using unitary function @ref LL_DMA_SetMemoryIncMode(). */ - - uint32_t PeriphOrM2MSrcDataSize; /*!< Specifies the Peripheral data size alignment or Source data size alignment (byte, half word, word) - in case of memory to memory transfer direction. - This parameter can be a value of @ref DMA_LL_EC_PDATAALIGN - - This feature can be modified afterwards using unitary function @ref LL_DMA_SetPeriphSize(). */ - - uint32_t MemoryOrM2MDstDataSize; /*!< Specifies the Memory data size alignment or Destination data size alignment (byte, half word, word) - in case of memory to memory transfer direction. - This parameter can be a value of @ref DMA_LL_EC_MDATAALIGN - - This feature can be modified afterwards using unitary function @ref LL_DMA_SetMemorySize(). */ - - uint32_t NbData; /*!< Specifies the number of data to transfer, in data unit. - The data unit is equal to the source buffer configuration set in PeripheralSize - or MemorySize parameters depending in the transfer direction. - This parameter must be a value between Min_Data = 0 and Max_Data = 0x0000FFFF - - This feature can be modified afterwards using unitary function @ref LL_DMA_SetDataLength(). */ - - uint32_t Channel; /*!< Specifies the peripheral channel. - This parameter can be a value of @ref DMA_LL_EC_CHANNEL - - This feature can be modified afterwards using unitary function @ref LL_DMA_SetChannelSelection(). */ - - uint32_t Priority; /*!< Specifies the channel priority level. - This parameter can be a value of @ref DMA_LL_EC_PRIORITY - - This feature can be modified afterwards using unitary function @ref LL_DMA_SetStreamPriorityLevel(). */ - - uint32_t FIFOMode; /*!< Specifies if the FIFO mode or Direct mode will be used for the specified stream. - This parameter can be a value of @ref DMA_LL_FIFOMODE - @note The Direct mode (FIFO mode disabled) cannot be used if the - memory-to-memory data transfer is configured on the selected stream - - This feature can be modified afterwards using unitary functions @ref LL_DMA_EnableFifoMode() or @ref LL_DMA_EnableFifoMode() . */ - - uint32_t FIFOThreshold; /*!< Specifies the FIFO threshold level. - This parameter can be a value of @ref DMA_LL_EC_FIFOTHRESHOLD - - This feature can be modified afterwards using unitary function @ref LL_DMA_SetFIFOThreshold(). */ - - uint32_t MemBurst; /*!< Specifies the Burst transfer configuration for the memory transfers. - It specifies the amount of data to be transferred in a single non interruptible - transaction. - This parameter can be a value of @ref DMA_LL_EC_MBURST - @note The burst mode is possible only if the address Increment mode is enabled. - - This feature can be modified afterwards using unitary function @ref LL_DMA_SetMemoryBurstxfer(). */ - - uint32_t PeriphBurst; /*!< Specifies the Burst transfer configuration for the peripheral transfers. - It specifies the amount of data to be transferred in a single non interruptible - transaction. - This parameter can be a value of @ref DMA_LL_EC_PBURST - @note The burst mode is possible only if the address Increment mode is enabled. - - This feature can be modified afterwards using unitary function @ref LL_DMA_SetPeriphBurstxfer(). */ - -} LL_DMA_InitTypeDef; -/** - * @} - */ -#endif /*USE_FULL_LL_DRIVER*/ -/* Exported constants --------------------------------------------------------*/ -/** @defgroup DMA_LL_Exported_Constants DMA Exported Constants - * @{ - */ - -/** @defgroup DMA_LL_EC_STREAM STREAM - * @{ - */ -#define LL_DMA_STREAM_0 0x00000000U -#define LL_DMA_STREAM_1 0x00000001U -#define LL_DMA_STREAM_2 0x00000002U -#define LL_DMA_STREAM_3 0x00000003U -#define LL_DMA_STREAM_4 0x00000004U -#define LL_DMA_STREAM_5 0x00000005U -#define LL_DMA_STREAM_6 0x00000006U -#define LL_DMA_STREAM_7 0x00000007U -#define LL_DMA_STREAM_ALL 0xFFFF0000U -/** - * @} - */ - -/** @defgroup DMA_LL_EC_DIRECTION DIRECTION - * @{ - */ -#define LL_DMA_DIRECTION_PERIPH_TO_MEMORY 0x00000000U /*!< Peripheral to memory direction */ -#define LL_DMA_DIRECTION_MEMORY_TO_PERIPH DMA_SxCR_DIR_0 /*!< Memory to peripheral direction */ -#define LL_DMA_DIRECTION_MEMORY_TO_MEMORY DMA_SxCR_DIR_1 /*!< Memory to memory direction */ -/** - * @} - */ - -/** @defgroup DMA_LL_EC_MODE MODE - * @{ - */ -#define LL_DMA_MODE_NORMAL 0x00000000U /*!< Normal Mode */ -#define LL_DMA_MODE_CIRCULAR DMA_SxCR_CIRC /*!< Circular Mode */ -#define LL_DMA_MODE_PFCTRL DMA_SxCR_PFCTRL /*!< Peripheral flow control mode */ -/** - * @} - */ - -/** @defgroup DMA_LL_EC_DOUBLEBUFFER_MODE DOUBLEBUFFER MODE - * @{ - */ -#define LL_DMA_DOUBLEBUFFER_MODE_DISABLE 0x00000000U /*!< Disable double buffering mode */ -#define LL_DMA_DOUBLEBUFFER_MODE_ENABLE DMA_SxCR_DBM /*!< Enable double buffering mode */ -/** - * @} - */ - -/** @defgroup DMA_LL_EC_PERIPH PERIPH - * @{ - */ -#define LL_DMA_PERIPH_NOINCREMENT 0x00000000U /*!< Peripheral increment mode Disable */ -#define LL_DMA_PERIPH_INCREMENT DMA_SxCR_PINC /*!< Peripheral increment mode Enable */ -/** - * @} - */ - -/** @defgroup DMA_LL_EC_MEMORY MEMORY - * @{ - */ -#define LL_DMA_MEMORY_NOINCREMENT 0x00000000U /*!< Memory increment mode Disable */ -#define LL_DMA_MEMORY_INCREMENT DMA_SxCR_MINC /*!< Memory increment mode Enable */ -/** - * @} - */ - -/** @defgroup DMA_LL_EC_PDATAALIGN PDATAALIGN - * @{ - */ -#define LL_DMA_PDATAALIGN_BYTE 0x00000000U /*!< Peripheral data alignment : Byte */ -#define LL_DMA_PDATAALIGN_HALFWORD DMA_SxCR_PSIZE_0 /*!< Peripheral data alignment : HalfWord */ -#define LL_DMA_PDATAALIGN_WORD DMA_SxCR_PSIZE_1 /*!< Peripheral data alignment : Word */ -/** - * @} - */ - -/** @defgroup DMA_LL_EC_MDATAALIGN MDATAALIGN - * @{ - */ -#define LL_DMA_MDATAALIGN_BYTE 0x00000000U /*!< Memory data alignment : Byte */ -#define LL_DMA_MDATAALIGN_HALFWORD DMA_SxCR_MSIZE_0 /*!< Memory data alignment : HalfWord */ -#define LL_DMA_MDATAALIGN_WORD DMA_SxCR_MSIZE_1 /*!< Memory data alignment : Word */ -/** - * @} - */ - -/** @defgroup DMA_LL_EC_OFFSETSIZE OFFSETSIZE - * @{ - */ -#define LL_DMA_OFFSETSIZE_PSIZE 0x00000000U /*!< Peripheral increment offset size is linked to the PSIZE */ -#define LL_DMA_OFFSETSIZE_FIXEDTO4 DMA_SxCR_PINCOS /*!< Peripheral increment offset size is fixed to 4 (32-bit alignment) */ -/** - * @} - */ - -/** @defgroup DMA_LL_EC_PRIORITY PRIORITY - * @{ - */ -#define LL_DMA_PRIORITY_LOW 0x00000000U /*!< Priority level : Low */ -#define LL_DMA_PRIORITY_MEDIUM DMA_SxCR_PL_0 /*!< Priority level : Medium */ -#define LL_DMA_PRIORITY_HIGH DMA_SxCR_PL_1 /*!< Priority level : High */ -#define LL_DMA_PRIORITY_VERYHIGH DMA_SxCR_PL /*!< Priority level : Very_High */ -/** - * @} - */ - -/** @defgroup DMA_LL_EC_CHANNEL CHANNEL - * @{ - */ -#define LL_DMA_CHANNEL_0 0x00000000U /* Select Channel0 of DMA Instance */ -#define LL_DMA_CHANNEL_1 DMA_SxCR_CHSEL_0 /* Select Channel1 of DMA Instance */ -#define LL_DMA_CHANNEL_2 DMA_SxCR_CHSEL_1 /* Select Channel2 of DMA Instance */ -#define LL_DMA_CHANNEL_3 (DMA_SxCR_CHSEL_0 | DMA_SxCR_CHSEL_1) /* Select Channel3 of DMA Instance */ -#define LL_DMA_CHANNEL_4 DMA_SxCR_CHSEL_2 /* Select Channel4 of DMA Instance */ -#define LL_DMA_CHANNEL_5 (DMA_SxCR_CHSEL_2 | DMA_SxCR_CHSEL_0) /* Select Channel5 of DMA Instance */ -#define LL_DMA_CHANNEL_6 (DMA_SxCR_CHSEL_2 | DMA_SxCR_CHSEL_1) /* Select Channel6 of DMA Instance */ -#define LL_DMA_CHANNEL_7 (DMA_SxCR_CHSEL_2 | DMA_SxCR_CHSEL_1 | DMA_SxCR_CHSEL_0) /* Select Channel7 of DMA Instance */ -#if defined (DMA_SxCR_CHSEL_3) -#define LL_DMA_CHANNEL_8 DMA_SxCR_CHSEL_3 /* Select Channel8 of DMA Instance */ -#define LL_DMA_CHANNEL_9 (DMA_SxCR_CHSEL_3 | DMA_SxCR_CHSEL_0) /* Select Channel9 of DMA Instance */ -#define LL_DMA_CHANNEL_10 (DMA_SxCR_CHSEL_3 | DMA_SxCR_CHSEL_1) /* Select Channel10 of DMA Instance */ -#define LL_DMA_CHANNEL_11 (DMA_SxCR_CHSEL_3 | DMA_SxCR_CHSEL_1 | DMA_SxCR_CHSEL_0) /* Select Channel11 of DMA Instance */ -#define LL_DMA_CHANNEL_12 (DMA_SxCR_CHSEL_3 | DMA_SxCR_CHSEL_2) /* Select Channel12 of DMA Instance */ -#define LL_DMA_CHANNEL_13 (DMA_SxCR_CHSEL_3 | DMA_SxCR_CHSEL_2 | DMA_SxCR_CHSEL_0) /* Select Channel13 of DMA Instance */ -#define LL_DMA_CHANNEL_14 (DMA_SxCR_CHSEL_3 | DMA_SxCR_CHSEL_2 | DMA_SxCR_CHSEL_1) /* Select Channel14 of DMA Instance */ -#define LL_DMA_CHANNEL_15 (DMA_SxCR_CHSEL_3 | DMA_SxCR_CHSEL_2 | DMA_SxCR_CHSEL_1 | DMA_SxCR_CHSEL_0) /* Select Channel15 of DMA Instance */ -#endif /* DMA_SxCR_CHSEL_3 */ -/** - * @} - */ - -/** @defgroup DMA_LL_EC_MBURST MBURST - * @{ - */ -#define LL_DMA_MBURST_SINGLE 0x00000000U /*!< Memory burst single transfer configuration */ -#define LL_DMA_MBURST_INC4 DMA_SxCR_MBURST_0 /*!< Memory burst of 4 beats transfer configuration */ -#define LL_DMA_MBURST_INC8 DMA_SxCR_MBURST_1 /*!< Memory burst of 8 beats transfer configuration */ -#define LL_DMA_MBURST_INC16 (DMA_SxCR_MBURST_0 | DMA_SxCR_MBURST_1) /*!< Memory burst of 16 beats transfer configuration */ -/** - * @} - */ - -/** @defgroup DMA_LL_EC_PBURST PBURST - * @{ - */ -#define LL_DMA_PBURST_SINGLE 0x00000000U /*!< Peripheral burst single transfer configuration */ -#define LL_DMA_PBURST_INC4 DMA_SxCR_PBURST_0 /*!< Peripheral burst of 4 beats transfer configuration */ -#define LL_DMA_PBURST_INC8 DMA_SxCR_PBURST_1 /*!< Peripheral burst of 8 beats transfer configuration */ -#define LL_DMA_PBURST_INC16 (DMA_SxCR_PBURST_0 | DMA_SxCR_PBURST_1) /*!< Peripheral burst of 16 beats transfer configuration */ -/** - * @} - */ - -/** @defgroup DMA_LL_FIFOMODE DMA_LL_FIFOMODE - * @{ - */ -#define LL_DMA_FIFOMODE_DISABLE 0x00000000U /*!< FIFO mode disable (direct mode is enabled) */ -#define LL_DMA_FIFOMODE_ENABLE DMA_SxFCR_DMDIS /*!< FIFO mode enable */ -/** - * @} - */ - -/** @defgroup DMA_LL_EC_FIFOSTATUS_0 FIFOSTATUS 0 - * @{ - */ -#define LL_DMA_FIFOSTATUS_0_25 0x00000000U /*!< 0 < fifo_level < 1/4 */ -#define LL_DMA_FIFOSTATUS_25_50 DMA_SxFCR_FS_0 /*!< 1/4 < fifo_level < 1/2 */ -#define LL_DMA_FIFOSTATUS_50_75 DMA_SxFCR_FS_1 /*!< 1/2 < fifo_level < 3/4 */ -#define LL_DMA_FIFOSTATUS_75_100 (DMA_SxFCR_FS_1 | DMA_SxFCR_FS_0) /*!< 3/4 < fifo_level < full */ -#define LL_DMA_FIFOSTATUS_EMPTY DMA_SxFCR_FS_2 /*!< FIFO is empty */ -#define LL_DMA_FIFOSTATUS_FULL (DMA_SxFCR_FS_2 | DMA_SxFCR_FS_0) /*!< FIFO is full */ -/** - * @} - */ - -/** @defgroup DMA_LL_EC_FIFOTHRESHOLD FIFOTHRESHOLD - * @{ - */ -#define LL_DMA_FIFOTHRESHOLD_1_4 0x00000000U /*!< FIFO threshold 1 quart full configuration */ -#define LL_DMA_FIFOTHRESHOLD_1_2 DMA_SxFCR_FTH_0 /*!< FIFO threshold half full configuration */ -#define LL_DMA_FIFOTHRESHOLD_3_4 DMA_SxFCR_FTH_1 /*!< FIFO threshold 3 quarts full configuration */ -#define LL_DMA_FIFOTHRESHOLD_FULL DMA_SxFCR_FTH /*!< FIFO threshold full configuration */ -/** - * @} - */ - -/** @defgroup DMA_LL_EC_CURRENTTARGETMEM CURRENTTARGETMEM - * @{ - */ -#define LL_DMA_CURRENTTARGETMEM0 0x00000000U /*!< Set CurrentTarget Memory to Memory 0 */ -#define LL_DMA_CURRENTTARGETMEM1 DMA_SxCR_CT /*!< Set CurrentTarget Memory to Memory 1 */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup DMA_LL_Exported_Macros DMA Exported Macros - * @{ - */ - -/** @defgroup DMA_LL_EM_WRITE_READ Common Write and read registers macros - * @{ - */ -/** - * @brief Write a value in DMA register - * @param __INSTANCE__ DMA Instance - * @param __REG__ Register to be written - * @param __VALUE__ Value to be written in the register - * @retval None - */ -#define LL_DMA_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__)) - -/** - * @brief Read a value in DMA register - * @param __INSTANCE__ DMA Instance - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_DMA_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__) -/** - * @} - */ - -/** @defgroup DMA_LL_EM_CONVERT_DMAxCHANNELy Convert DMAxStreamy - * @{ - */ -/** - * @brief Convert DMAx_Streamy into DMAx - * @param __STREAM_INSTANCE__ DMAx_Streamy - * @retval DMAx - */ -#define __LL_DMA_GET_INSTANCE(__STREAM_INSTANCE__) \ -(((uint32_t)(__STREAM_INSTANCE__) > ((uint32_t)DMA1_Stream7)) ? DMA2 : DMA1) - -/** - * @brief Convert DMAx_Streamy into LL_DMA_STREAM_y - * @param __STREAM_INSTANCE__ DMAx_Streamy - * @retval LL_DMA_CHANNEL_y - */ -#define __LL_DMA_GET_STREAM(__STREAM_INSTANCE__) \ -(((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA1_Stream0)) ? LL_DMA_STREAM_0 : \ - ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA2_Stream0)) ? LL_DMA_STREAM_0 : \ - ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA1_Stream1)) ? LL_DMA_STREAM_1 : \ - ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA2_Stream1)) ? LL_DMA_STREAM_1 : \ - ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA1_Stream2)) ? LL_DMA_STREAM_2 : \ - ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA2_Stream2)) ? LL_DMA_STREAM_2 : \ - ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA1_Stream3)) ? LL_DMA_STREAM_3 : \ - ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA2_Stream3)) ? LL_DMA_STREAM_3 : \ - ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA1_Stream4)) ? LL_DMA_STREAM_4 : \ - ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA2_Stream4)) ? LL_DMA_STREAM_4 : \ - ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA1_Stream5)) ? LL_DMA_STREAM_5 : \ - ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA2_Stream5)) ? LL_DMA_STREAM_5 : \ - ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA1_Stream6)) ? LL_DMA_STREAM_6 : \ - ((uint32_t)(__STREAM_INSTANCE__) == ((uint32_t)DMA2_Stream6)) ? LL_DMA_STREAM_6 : \ - LL_DMA_STREAM_7) - -/** - * @brief Convert DMA Instance DMAx and LL_DMA_STREAM_y into DMAx_Streamy - * @param __DMA_INSTANCE__ DMAx - * @param __STREAM__ LL_DMA_STREAM_y - * @retval DMAx_Streamy - */ -#define __LL_DMA_GET_STREAM_INSTANCE(__DMA_INSTANCE__, __STREAM__) \ -((((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA1)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_0))) ? DMA1_Stream0 : \ - (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA2)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_0))) ? DMA2_Stream0 : \ - (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA1)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_1))) ? DMA1_Stream1 : \ - (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA2)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_1))) ? DMA2_Stream1 : \ - (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA1)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_2))) ? DMA1_Stream2 : \ - (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA2)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_2))) ? DMA2_Stream2 : \ - (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA1)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_3))) ? DMA1_Stream3 : \ - (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA2)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_3))) ? DMA2_Stream3 : \ - (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA1)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_4))) ? DMA1_Stream4 : \ - (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA2)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_4))) ? DMA2_Stream4 : \ - (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA1)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_5))) ? DMA1_Stream5 : \ - (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA2)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_5))) ? DMA2_Stream5 : \ - (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA1)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_6))) ? DMA1_Stream6 : \ - (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA2)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_6))) ? DMA2_Stream6 : \ - (((uint32_t)(__DMA_INSTANCE__) == ((uint32_t)DMA1)) && ((uint32_t)(__STREAM__) == ((uint32_t)LL_DMA_STREAM_7))) ? DMA1_Stream7 : \ - DMA2_Stream7) - -/** - * @} - */ - -/** - * @} - */ - - -/* Exported functions --------------------------------------------------------*/ - /** @defgroup DMA_LL_Exported_Functions DMA Exported Functions - * @{ - */ - -/** @defgroup DMA_LL_EF_Configuration Configuration - * @{ - */ -/** - * @brief Enable DMA stream. - * @rmtoll CR EN LL_DMA_EnableStream - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_EnableStream(DMA_TypeDef *DMAx, uint32_t Stream) -{ - SET_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_EN); -} - -/** - * @brief Disable DMA stream. - * @rmtoll CR EN LL_DMA_DisableStream - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_DisableStream(DMA_TypeDef *DMAx, uint32_t Stream) -{ - CLEAR_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_EN); -} - -/** - * @brief Check if DMA stream is enabled or disabled. - * @rmtoll CR EN LL_DMA_IsEnabledStream - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsEnabledStream(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_EN) == (DMA_SxCR_EN)); -} - -/** - * @brief Configure all parameters linked to DMA transfer. - * @rmtoll CR DIR LL_DMA_ConfigTransfer\n - * CR CIRC LL_DMA_ConfigTransfer\n - * CR PINC LL_DMA_ConfigTransfer\n - * CR MINC LL_DMA_ConfigTransfer\n - * CR PSIZE LL_DMA_ConfigTransfer\n - * CR MSIZE LL_DMA_ConfigTransfer\n - * CR PL LL_DMA_ConfigTransfer\n - * CR PFCTRL LL_DMA_ConfigTransfer - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param Configuration This parameter must be a combination of all the following values: - * @arg @ref LL_DMA_DIRECTION_PERIPH_TO_MEMORY or @ref LL_DMA_DIRECTION_MEMORY_TO_PERIPH or @ref LL_DMA_DIRECTION_MEMORY_TO_MEMORY - * @arg @ref LL_DMA_MODE_NORMAL or @ref LL_DMA_MODE_CIRCULAR or @ref LL_DMA_MODE_PFCTRL - * @arg @ref LL_DMA_PERIPH_INCREMENT or @ref LL_DMA_PERIPH_NOINCREMENT - * @arg @ref LL_DMA_MEMORY_INCREMENT or @ref LL_DMA_MEMORY_NOINCREMENT - * @arg @ref LL_DMA_PDATAALIGN_BYTE or @ref LL_DMA_PDATAALIGN_HALFWORD or @ref LL_DMA_PDATAALIGN_WORD - * @arg @ref LL_DMA_MDATAALIGN_BYTE or @ref LL_DMA_MDATAALIGN_HALFWORD or @ref LL_DMA_MDATAALIGN_WORD - * @arg @ref LL_DMA_PRIORITY_LOW or @ref LL_DMA_PRIORITY_MEDIUM or @ref LL_DMA_PRIORITY_HIGH or @ref LL_DMA_PRIORITY_VERYHIGH - *@retval None - */ -__STATIC_INLINE void LL_DMA_ConfigTransfer(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t Configuration) -{ - MODIFY_REG(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, - DMA_SxCR_DIR | DMA_SxCR_CIRC | DMA_SxCR_PINC | DMA_SxCR_MINC | DMA_SxCR_PSIZE | DMA_SxCR_MSIZE | DMA_SxCR_PL | DMA_SxCR_PFCTRL, - Configuration); -} - -/** - * @brief Set Data transfer direction (read from peripheral or from memory). - * @rmtoll CR DIR LL_DMA_SetDataTransferDirection - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param Direction This parameter can be one of the following values: - * @arg @ref LL_DMA_DIRECTION_PERIPH_TO_MEMORY - * @arg @ref LL_DMA_DIRECTION_MEMORY_TO_PERIPH - * @arg @ref LL_DMA_DIRECTION_MEMORY_TO_MEMORY - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetDataTransferDirection(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t Direction) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_DIR, Direction); -} - -/** - * @brief Get Data transfer direction (read from peripheral or from memory). - * @rmtoll CR DIR LL_DMA_GetDataTransferDirection - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA_DIRECTION_PERIPH_TO_MEMORY - * @arg @ref LL_DMA_DIRECTION_MEMORY_TO_PERIPH - * @arg @ref LL_DMA_DIRECTION_MEMORY_TO_MEMORY - */ -__STATIC_INLINE uint32_t LL_DMA_GetDataTransferDirection(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_DIR)); -} - -/** - * @brief Set DMA mode normal, circular or peripheral flow control. - * @rmtoll CR CIRC LL_DMA_SetMode\n - * CR PFCTRL LL_DMA_SetMode - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param Mode This parameter can be one of the following values: - * @arg @ref LL_DMA_MODE_NORMAL - * @arg @ref LL_DMA_MODE_CIRCULAR - * @arg @ref LL_DMA_MODE_PFCTRL - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetMode(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t Mode) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_CIRC | DMA_SxCR_PFCTRL, Mode); -} - -/** - * @brief Get DMA mode normal, circular or peripheral flow control. - * @rmtoll CR CIRC LL_DMA_GetMode\n - * CR PFCTRL LL_DMA_GetMode - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA_MODE_NORMAL - * @arg @ref LL_DMA_MODE_CIRCULAR - * @arg @ref LL_DMA_MODE_PFCTRL - */ -__STATIC_INLINE uint32_t LL_DMA_GetMode(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_CIRC | DMA_SxCR_PFCTRL)); -} - -/** - * @brief Set Peripheral increment mode. - * @rmtoll CR PINC LL_DMA_SetPeriphIncMode - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param IncrementMode This parameter can be one of the following values: - * @arg @ref LL_DMA_PERIPH_NOINCREMENT - * @arg @ref LL_DMA_PERIPH_INCREMENT - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetPeriphIncMode(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t IncrementMode) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_PINC, IncrementMode); -} - -/** - * @brief Get Peripheral increment mode. - * @rmtoll CR PINC LL_DMA_GetPeriphIncMode - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA_PERIPH_NOINCREMENT - * @arg @ref LL_DMA_PERIPH_INCREMENT - */ -__STATIC_INLINE uint32_t LL_DMA_GetPeriphIncMode(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_PINC)); -} - -/** - * @brief Set Memory increment mode. - * @rmtoll CR MINC LL_DMA_SetMemoryIncMode - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param IncrementMode This parameter can be one of the following values: - * @arg @ref LL_DMA_MEMORY_NOINCREMENT - * @arg @ref LL_DMA_MEMORY_INCREMENT - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetMemoryIncMode(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t IncrementMode) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_MINC, IncrementMode); -} - -/** - * @brief Get Memory increment mode. - * @rmtoll CR MINC LL_DMA_GetMemoryIncMode - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA_MEMORY_NOINCREMENT - * @arg @ref LL_DMA_MEMORY_INCREMENT - */ -__STATIC_INLINE uint32_t LL_DMA_GetMemoryIncMode(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_MINC)); -} - -/** - * @brief Set Peripheral size. - * @rmtoll CR PSIZE LL_DMA_SetPeriphSize - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param Size This parameter can be one of the following values: - * @arg @ref LL_DMA_PDATAALIGN_BYTE - * @arg @ref LL_DMA_PDATAALIGN_HALFWORD - * @arg @ref LL_DMA_PDATAALIGN_WORD - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetPeriphSize(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t Size) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_PSIZE, Size); -} - -/** - * @brief Get Peripheral size. - * @rmtoll CR PSIZE LL_DMA_GetPeriphSize - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA_PDATAALIGN_BYTE - * @arg @ref LL_DMA_PDATAALIGN_HALFWORD - * @arg @ref LL_DMA_PDATAALIGN_WORD - */ -__STATIC_INLINE uint32_t LL_DMA_GetPeriphSize(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_PSIZE)); -} - -/** - * @brief Set Memory size. - * @rmtoll CR MSIZE LL_DMA_SetMemorySize - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param Size This parameter can be one of the following values: - * @arg @ref LL_DMA_MDATAALIGN_BYTE - * @arg @ref LL_DMA_MDATAALIGN_HALFWORD - * @arg @ref LL_DMA_MDATAALIGN_WORD - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetMemorySize(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t Size) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_MSIZE, Size); -} - -/** - * @brief Get Memory size. - * @rmtoll CR MSIZE LL_DMA_GetMemorySize - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA_MDATAALIGN_BYTE - * @arg @ref LL_DMA_MDATAALIGN_HALFWORD - * @arg @ref LL_DMA_MDATAALIGN_WORD - */ -__STATIC_INLINE uint32_t LL_DMA_GetMemorySize(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_MSIZE)); -} - -/** - * @brief Set Peripheral increment offset size. - * @rmtoll CR PINCOS LL_DMA_SetIncOffsetSize - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param OffsetSize This parameter can be one of the following values: - * @arg @ref LL_DMA_OFFSETSIZE_PSIZE - * @arg @ref LL_DMA_OFFSETSIZE_FIXEDTO4 - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetIncOffsetSize(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t OffsetSize) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_PINCOS, OffsetSize); -} - -/** - * @brief Get Peripheral increment offset size. - * @rmtoll CR PINCOS LL_DMA_GetIncOffsetSize - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA_OFFSETSIZE_PSIZE - * @arg @ref LL_DMA_OFFSETSIZE_FIXEDTO4 - */ -__STATIC_INLINE uint32_t LL_DMA_GetIncOffsetSize(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_PINCOS)); -} - -/** - * @brief Set Stream priority level. - * @rmtoll CR PL LL_DMA_SetStreamPriorityLevel - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param Priority This parameter can be one of the following values: - * @arg @ref LL_DMA_PRIORITY_LOW - * @arg @ref LL_DMA_PRIORITY_MEDIUM - * @arg @ref LL_DMA_PRIORITY_HIGH - * @arg @ref LL_DMA_PRIORITY_VERYHIGH - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetStreamPriorityLevel(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t Priority) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_PL, Priority); -} - -/** - * @brief Get Stream priority level. - * @rmtoll CR PL LL_DMA_GetStreamPriorityLevel - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA_PRIORITY_LOW - * @arg @ref LL_DMA_PRIORITY_MEDIUM - * @arg @ref LL_DMA_PRIORITY_HIGH - * @arg @ref LL_DMA_PRIORITY_VERYHIGH - */ -__STATIC_INLINE uint32_t LL_DMA_GetStreamPriorityLevel(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_PL)); -} - -/** - * @brief Set Number of data to transfer. - * @rmtoll NDTR NDT LL_DMA_SetDataLength - * @note This action has no effect if - * stream is enabled. - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param NbData Between 0 to 0xFFFFFFFF - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetDataLength(DMA_TypeDef* DMAx, uint32_t Stream, uint32_t NbData) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->NDTR, DMA_SxNDT, NbData); -} - -/** - * @brief Get Number of data to transfer. - * @rmtoll NDTR NDT LL_DMA_GetDataLength - * @note Once the stream is enabled, the return value indicate the - * remaining bytes to be transmitted. - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Between 0 to 0xFFFFFFFF - */ -__STATIC_INLINE uint32_t LL_DMA_GetDataLength(DMA_TypeDef* DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->NDTR, DMA_SxNDT)); -} - -/** - * @brief Select Channel number associated to the Stream. - * @rmtoll CR CHSEL LL_DMA_SetChannelSelection - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_DMA_CHANNEL_0 - * @arg @ref LL_DMA_CHANNEL_1 - * @arg @ref LL_DMA_CHANNEL_2 - * @arg @ref LL_DMA_CHANNEL_3 - * @arg @ref LL_DMA_CHANNEL_4 - * @arg @ref LL_DMA_CHANNEL_5 - * @arg @ref LL_DMA_CHANNEL_6 - * @arg @ref LL_DMA_CHANNEL_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetChannelSelection(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t Channel) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_CHSEL, Channel); -} - -/** - * @brief Get the Channel number associated to the Stream. - * @rmtoll CR CHSEL LL_DMA_GetChannelSelection - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA_CHANNEL_0 - * @arg @ref LL_DMA_CHANNEL_1 - * @arg @ref LL_DMA_CHANNEL_2 - * @arg @ref LL_DMA_CHANNEL_3 - * @arg @ref LL_DMA_CHANNEL_4 - * @arg @ref LL_DMA_CHANNEL_5 - * @arg @ref LL_DMA_CHANNEL_6 - * @arg @ref LL_DMA_CHANNEL_7 - */ -__STATIC_INLINE uint32_t LL_DMA_GetChannelSelection(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_CHSEL)); -} - -/** - * @brief Set Memory burst transfer configuration. - * @rmtoll CR MBURST LL_DMA_SetMemoryBurstxfer - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param Mburst This parameter can be one of the following values: - * @arg @ref LL_DMA_MBURST_SINGLE - * @arg @ref LL_DMA_MBURST_INC4 - * @arg @ref LL_DMA_MBURST_INC8 - * @arg @ref LL_DMA_MBURST_INC16 - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetMemoryBurstxfer(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t Mburst) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_MBURST, Mburst); -} - -/** - * @brief Get Memory burst transfer configuration. - * @rmtoll CR MBURST LL_DMA_GetMemoryBurstxfer - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA_MBURST_SINGLE - * @arg @ref LL_DMA_MBURST_INC4 - * @arg @ref LL_DMA_MBURST_INC8 - * @arg @ref LL_DMA_MBURST_INC16 - */ -__STATIC_INLINE uint32_t LL_DMA_GetMemoryBurstxfer(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_MBURST)); -} - -/** - * @brief Set Peripheral burst transfer configuration. - * @rmtoll CR PBURST LL_DMA_SetPeriphBurstxfer - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param Pburst This parameter can be one of the following values: - * @arg @ref LL_DMA_PBURST_SINGLE - * @arg @ref LL_DMA_PBURST_INC4 - * @arg @ref LL_DMA_PBURST_INC8 - * @arg @ref LL_DMA_PBURST_INC16 - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetPeriphBurstxfer(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t Pburst) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_PBURST, Pburst); -} - -/** - * @brief Get Peripheral burst transfer configuration. - * @rmtoll CR PBURST LL_DMA_GetPeriphBurstxfer - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA_PBURST_SINGLE - * @arg @ref LL_DMA_PBURST_INC4 - * @arg @ref LL_DMA_PBURST_INC8 - * @arg @ref LL_DMA_PBURST_INC16 - */ -__STATIC_INLINE uint32_t LL_DMA_GetPeriphBurstxfer(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_PBURST)); -} - -/** - * @brief Set Current target (only in double buffer mode) to Memory 1 or Memory 0. - * @rmtoll CR CT LL_DMA_SetCurrentTargetMem - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param CurrentMemory This parameter can be one of the following values: - * @arg @ref LL_DMA_CURRENTTARGETMEM0 - * @arg @ref LL_DMA_CURRENTTARGETMEM1 - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetCurrentTargetMem(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t CurrentMemory) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_CT, CurrentMemory); -} - -/** - * @brief Set Current target (only in double buffer mode) to Memory 1 or Memory 0. - * @rmtoll CR CT LL_DMA_GetCurrentTargetMem - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA_CURRENTTARGETMEM0 - * @arg @ref LL_DMA_CURRENTTARGETMEM1 - */ -__STATIC_INLINE uint32_t LL_DMA_GetCurrentTargetMem(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_CT)); -} - -/** - * @brief Enable the double buffer mode. - * @rmtoll CR DBM LL_DMA_EnableDoubleBufferMode - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_EnableDoubleBufferMode(DMA_TypeDef *DMAx, uint32_t Stream) -{ - SET_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_DBM); -} - -/** - * @brief Disable the double buffer mode. - * @rmtoll CR DBM LL_DMA_DisableDoubleBufferMode - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_DisableDoubleBufferMode(DMA_TypeDef *DMAx, uint32_t Stream) -{ - CLEAR_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_DBM); -} - -/** - * @brief Get FIFO status. - * @rmtoll FCR FS LL_DMA_GetFIFOStatus - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA_FIFOSTATUS_0_25 - * @arg @ref LL_DMA_FIFOSTATUS_25_50 - * @arg @ref LL_DMA_FIFOSTATUS_50_75 - * @arg @ref LL_DMA_FIFOSTATUS_75_100 - * @arg @ref LL_DMA_FIFOSTATUS_EMPTY - * @arg @ref LL_DMA_FIFOSTATUS_FULL - */ -__STATIC_INLINE uint32_t LL_DMA_GetFIFOStatus(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->FCR, DMA_SxFCR_FS)); -} - -/** - * @brief Disable Fifo mode. - * @rmtoll FCR DMDIS LL_DMA_DisableFifoMode - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_DisableFifoMode(DMA_TypeDef *DMAx, uint32_t Stream) -{ - CLEAR_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->FCR, DMA_SxFCR_DMDIS); -} - -/** - * @brief Enable Fifo mode. - * @rmtoll FCR DMDIS LL_DMA_EnableFifoMode - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_EnableFifoMode(DMA_TypeDef *DMAx, uint32_t Stream) -{ - SET_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->FCR, DMA_SxFCR_DMDIS); -} - -/** - * @brief Select FIFO threshold. - * @rmtoll FCR FTH LL_DMA_SetFIFOThreshold - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param Threshold This parameter can be one of the following values: - * @arg @ref LL_DMA_FIFOTHRESHOLD_1_4 - * @arg @ref LL_DMA_FIFOTHRESHOLD_1_2 - * @arg @ref LL_DMA_FIFOTHRESHOLD_3_4 - * @arg @ref LL_DMA_FIFOTHRESHOLD_FULL - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetFIFOThreshold(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t Threshold) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->FCR, DMA_SxFCR_FTH, Threshold); -} - -/** - * @brief Get FIFO threshold. - * @rmtoll FCR FTH LL_DMA_GetFIFOThreshold - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA_FIFOTHRESHOLD_1_4 - * @arg @ref LL_DMA_FIFOTHRESHOLD_1_2 - * @arg @ref LL_DMA_FIFOTHRESHOLD_3_4 - * @arg @ref LL_DMA_FIFOTHRESHOLD_FULL - */ -__STATIC_INLINE uint32_t LL_DMA_GetFIFOThreshold(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->FCR, DMA_SxFCR_FTH)); -} - -/** - * @brief Configure the FIFO . - * @rmtoll FCR FTH LL_DMA_ConfigFifo\n - * FCR DMDIS LL_DMA_ConfigFifo - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param FifoMode This parameter can be one of the following values: - * @arg @ref LL_DMA_FIFOMODE_ENABLE - * @arg @ref LL_DMA_FIFOMODE_DISABLE - * @param FifoThreshold This parameter can be one of the following values: - * @arg @ref LL_DMA_FIFOTHRESHOLD_1_4 - * @arg @ref LL_DMA_FIFOTHRESHOLD_1_2 - * @arg @ref LL_DMA_FIFOTHRESHOLD_3_4 - * @arg @ref LL_DMA_FIFOTHRESHOLD_FULL - * @retval None - */ -__STATIC_INLINE void LL_DMA_ConfigFifo(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t FifoMode, uint32_t FifoThreshold) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->FCR, DMA_SxFCR_FTH|DMA_SxFCR_DMDIS, FifoMode|FifoThreshold); -} - -/** - * @brief Configure the Source and Destination addresses. - * @note This API must not be called when the DMA stream is enabled. - * @rmtoll M0AR M0A LL_DMA_ConfigAddresses\n - * PAR PA LL_DMA_ConfigAddresses - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param SrcAddress Between 0 to 0xFFFFFFFF - * @param DstAddress Between 0 to 0xFFFFFFFF - * @param Direction This parameter can be one of the following values: - * @arg @ref LL_DMA_DIRECTION_PERIPH_TO_MEMORY - * @arg @ref LL_DMA_DIRECTION_MEMORY_TO_PERIPH - * @arg @ref LL_DMA_DIRECTION_MEMORY_TO_MEMORY - * @retval None - */ -__STATIC_INLINE void LL_DMA_ConfigAddresses(DMA_TypeDef* DMAx, uint32_t Stream, uint32_t SrcAddress, uint32_t DstAddress, uint32_t Direction) -{ - /* Direction Memory to Periph */ - if (Direction == LL_DMA_DIRECTION_MEMORY_TO_PERIPH) - { - WRITE_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->M0AR, SrcAddress); - WRITE_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->PAR, DstAddress); - } - /* Direction Periph to Memory and Memory to Memory */ - else - { - WRITE_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->PAR, SrcAddress); - WRITE_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->M0AR, DstAddress); - } -} - -/** - * @brief Set the Memory address. - * @rmtoll M0AR M0A LL_DMA_SetMemoryAddress - * @note Interface used for direction LL_DMA_DIRECTION_PERIPH_TO_MEMORY or LL_DMA_DIRECTION_MEMORY_TO_PERIPH only. - * @note This API must not be called when the DMA channel is enabled. - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param MemoryAddress Between 0 to 0xFFFFFFFF - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetMemoryAddress(DMA_TypeDef* DMAx, uint32_t Stream, uint32_t MemoryAddress) -{ - WRITE_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->M0AR, MemoryAddress); -} - -/** - * @brief Set the Peripheral address. - * @rmtoll PAR PA LL_DMA_SetPeriphAddress - * @note Interface used for direction LL_DMA_DIRECTION_PERIPH_TO_MEMORY or LL_DMA_DIRECTION_MEMORY_TO_PERIPH only. - * @note This API must not be called when the DMA channel is enabled. - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param PeriphAddress Between 0 to 0xFFFFFFFF - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetPeriphAddress(DMA_TypeDef* DMAx, uint32_t Stream, uint32_t PeriphAddress) -{ - WRITE_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->PAR, PeriphAddress); -} - -/** - * @brief Get the Memory address. - * @rmtoll M0AR M0A LL_DMA_GetMemoryAddress - * @note Interface used for direction LL_DMA_DIRECTION_PERIPH_TO_MEMORY or LL_DMA_DIRECTION_MEMORY_TO_PERIPH only. - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Between 0 to 0xFFFFFFFF - */ -__STATIC_INLINE uint32_t LL_DMA_GetMemoryAddress(DMA_TypeDef* DMAx, uint32_t Stream) -{ - return (READ_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->M0AR)); -} - -/** - * @brief Get the Peripheral address. - * @rmtoll PAR PA LL_DMA_GetPeriphAddress - * @note Interface used for direction LL_DMA_DIRECTION_PERIPH_TO_MEMORY or LL_DMA_DIRECTION_MEMORY_TO_PERIPH only. - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Between 0 to 0xFFFFFFFF - */ -__STATIC_INLINE uint32_t LL_DMA_GetPeriphAddress(DMA_TypeDef* DMAx, uint32_t Stream) -{ - return (READ_REG(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->PAR)); -} - -/** - * @brief Set the Memory to Memory Source address. - * @rmtoll PAR PA LL_DMA_SetM2MSrcAddress - * @note Interface used for direction LL_DMA_DIRECTION_MEMORY_TO_MEMORY only. - * @note This API must not be called when the DMA channel is enabled. - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param MemoryAddress Between 0 to 0xFFFFFFFF - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetM2MSrcAddress(DMA_TypeDef* DMAx, uint32_t Stream, uint32_t MemoryAddress) -{ - WRITE_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->PAR, MemoryAddress); -} - -/** - * @brief Set the Memory to Memory Destination address. - * @rmtoll M0AR M0A LL_DMA_SetM2MDstAddress - * @note Interface used for direction LL_DMA_DIRECTION_MEMORY_TO_MEMORY only. - * @note This API must not be called when the DMA channel is enabled. - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param MemoryAddress Between 0 to 0xFFFFFFFF - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetM2MDstAddress(DMA_TypeDef* DMAx, uint32_t Stream, uint32_t MemoryAddress) - { - WRITE_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->M0AR, MemoryAddress); - } - -/** - * @brief Get the Memory to Memory Source address. - * @rmtoll PAR PA LL_DMA_GetM2MSrcAddress - * @note Interface used for direction LL_DMA_DIRECTION_MEMORY_TO_MEMORY only. - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Between 0 to 0xFFFFFFFF - */ -__STATIC_INLINE uint32_t LL_DMA_GetM2MSrcAddress(DMA_TypeDef* DMAx, uint32_t Stream) - { - return (READ_REG(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->PAR)); - } - -/** - * @brief Get the Memory to Memory Destination address. - * @rmtoll M0AR M0A LL_DMA_GetM2MDstAddress - * @note Interface used for direction LL_DMA_DIRECTION_MEMORY_TO_MEMORY only. - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Between 0 to 0xFFFFFFFF - */ -__STATIC_INLINE uint32_t LL_DMA_GetM2MDstAddress(DMA_TypeDef* DMAx, uint32_t Stream) -{ - return (READ_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->M0AR)); -} - -/** - * @brief Set Memory 1 address (used in case of Double buffer mode). - * @rmtoll M1AR M1A LL_DMA_SetMemory1Address - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @param Address Between 0 to 0xFFFFFFFF - * @retval None - */ -__STATIC_INLINE void LL_DMA_SetMemory1Address(DMA_TypeDef *DMAx, uint32_t Stream, uint32_t Address) -{ - MODIFY_REG(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->M1AR, DMA_SxM1AR_M1A, Address); -} - -/** - * @brief Get Memory 1 address (used in case of Double buffer mode). - * @rmtoll M1AR M1A LL_DMA_GetMemory1Address - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval Between 0 to 0xFFFFFFFF - */ -__STATIC_INLINE uint32_t LL_DMA_GetMemory1Address(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->M1AR); -} - -/** - * @} - */ - -/** @defgroup DMA_LL_EF_FLAG_Management FLAG_Management - * @{ - */ - -/** - * @brief Get Stream 0 half transfer flag. - * @rmtoll LISR HTIF0 LL_DMA_IsActiveFlag_HT0 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_HT0(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_HTIF0)==(DMA_LISR_HTIF0)); -} - -/** - * @brief Get Stream 1 half transfer flag. - * @rmtoll LISR HTIF1 LL_DMA_IsActiveFlag_HT1 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_HT1(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_HTIF1)==(DMA_LISR_HTIF1)); -} - -/** - * @brief Get Stream 2 half transfer flag. - * @rmtoll LISR HTIF2 LL_DMA_IsActiveFlag_HT2 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_HT2(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_HTIF2)==(DMA_LISR_HTIF2)); -} - -/** - * @brief Get Stream 3 half transfer flag. - * @rmtoll LISR HTIF3 LL_DMA_IsActiveFlag_HT3 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_HT3(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_HTIF3)==(DMA_LISR_HTIF3)); -} - -/** - * @brief Get Stream 4 half transfer flag. - * @rmtoll HISR HTIF4 LL_DMA_IsActiveFlag_HT4 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_HT4(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_HTIF4)==(DMA_HISR_HTIF4)); -} - -/** - * @brief Get Stream 5 half transfer flag. - * @rmtoll HISR HTIF0 LL_DMA_IsActiveFlag_HT5 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_HT5(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_HTIF5)==(DMA_HISR_HTIF5)); -} - -/** - * @brief Get Stream 6 half transfer flag. - * @rmtoll HISR HTIF6 LL_DMA_IsActiveFlag_HT6 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_HT6(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_HTIF6)==(DMA_HISR_HTIF6)); -} - -/** - * @brief Get Stream 7 half transfer flag. - * @rmtoll HISR HTIF7 LL_DMA_IsActiveFlag_HT7 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_HT7(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_HTIF7)==(DMA_HISR_HTIF7)); -} - -/** - * @brief Get Stream 0 transfer complete flag. - * @rmtoll LISR TCIF0 LL_DMA_IsActiveFlag_TC0 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TC0(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_TCIF0)==(DMA_LISR_TCIF0)); -} - -/** - * @brief Get Stream 1 transfer complete flag. - * @rmtoll LISR TCIF1 LL_DMA_IsActiveFlag_TC1 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TC1(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_TCIF1)==(DMA_LISR_TCIF1)); -} - -/** - * @brief Get Stream 2 transfer complete flag. - * @rmtoll LISR TCIF2 LL_DMA_IsActiveFlag_TC2 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TC2(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_TCIF2)==(DMA_LISR_TCIF2)); -} - -/** - * @brief Get Stream 3 transfer complete flag. - * @rmtoll LISR TCIF3 LL_DMA_IsActiveFlag_TC3 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TC3(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_TCIF3)==(DMA_LISR_TCIF3)); -} - -/** - * @brief Get Stream 4 transfer complete flag. - * @rmtoll HISR TCIF4 LL_DMA_IsActiveFlag_TC4 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TC4(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_TCIF4)==(DMA_HISR_TCIF4)); -} - -/** - * @brief Get Stream 5 transfer complete flag. - * @rmtoll HISR TCIF0 LL_DMA_IsActiveFlag_TC5 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TC5(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_TCIF5)==(DMA_HISR_TCIF5)); -} - -/** - * @brief Get Stream 6 transfer complete flag. - * @rmtoll HISR TCIF6 LL_DMA_IsActiveFlag_TC6 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TC6(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_TCIF6)==(DMA_HISR_TCIF6)); -} - -/** - * @brief Get Stream 7 transfer complete flag. - * @rmtoll HISR TCIF7 LL_DMA_IsActiveFlag_TC7 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TC7(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_TCIF7)==(DMA_HISR_TCIF7)); -} - -/** - * @brief Get Stream 0 transfer error flag. - * @rmtoll LISR TEIF0 LL_DMA_IsActiveFlag_TE0 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TE0(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_TEIF0)==(DMA_LISR_TEIF0)); -} - -/** - * @brief Get Stream 1 transfer error flag. - * @rmtoll LISR TEIF1 LL_DMA_IsActiveFlag_TE1 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TE1(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_TEIF1)==(DMA_LISR_TEIF1)); -} - -/** - * @brief Get Stream 2 transfer error flag. - * @rmtoll LISR TEIF2 LL_DMA_IsActiveFlag_TE2 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TE2(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_TEIF2)==(DMA_LISR_TEIF2)); -} - -/** - * @brief Get Stream 3 transfer error flag. - * @rmtoll LISR TEIF3 LL_DMA_IsActiveFlag_TE3 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TE3(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_TEIF3)==(DMA_LISR_TEIF3)); -} - -/** - * @brief Get Stream 4 transfer error flag. - * @rmtoll HISR TEIF4 LL_DMA_IsActiveFlag_TE4 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TE4(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_TEIF4)==(DMA_HISR_TEIF4)); -} - -/** - * @brief Get Stream 5 transfer error flag. - * @rmtoll HISR TEIF0 LL_DMA_IsActiveFlag_TE5 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TE5(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_TEIF5)==(DMA_HISR_TEIF5)); -} - -/** - * @brief Get Stream 6 transfer error flag. - * @rmtoll HISR TEIF6 LL_DMA_IsActiveFlag_TE6 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TE6(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_TEIF6)==(DMA_HISR_TEIF6)); -} - -/** - * @brief Get Stream 7 transfer error flag. - * @rmtoll HISR TEIF7 LL_DMA_IsActiveFlag_TE7 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_TE7(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_TEIF7)==(DMA_HISR_TEIF7)); -} - -/** - * @brief Get Stream 0 direct mode error flag. - * @rmtoll LISR DMEIF0 LL_DMA_IsActiveFlag_DME0 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_DME0(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_DMEIF0)==(DMA_LISR_DMEIF0)); -} - -/** - * @brief Get Stream 1 direct mode error flag. - * @rmtoll LISR DMEIF1 LL_DMA_IsActiveFlag_DME1 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_DME1(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_DMEIF1)==(DMA_LISR_DMEIF1)); -} - -/** - * @brief Get Stream 2 direct mode error flag. - * @rmtoll LISR DMEIF2 LL_DMA_IsActiveFlag_DME2 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_DME2(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_DMEIF2)==(DMA_LISR_DMEIF2)); -} - -/** - * @brief Get Stream 3 direct mode error flag. - * @rmtoll LISR DMEIF3 LL_DMA_IsActiveFlag_DME3 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_DME3(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_DMEIF3)==(DMA_LISR_DMEIF3)); -} - -/** - * @brief Get Stream 4 direct mode error flag. - * @rmtoll HISR DMEIF4 LL_DMA_IsActiveFlag_DME4 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_DME4(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_DMEIF4)==(DMA_HISR_DMEIF4)); -} - -/** - * @brief Get Stream 5 direct mode error flag. - * @rmtoll HISR DMEIF0 LL_DMA_IsActiveFlag_DME5 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_DME5(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_DMEIF5)==(DMA_HISR_DMEIF5)); -} - -/** - * @brief Get Stream 6 direct mode error flag. - * @rmtoll HISR DMEIF6 LL_DMA_IsActiveFlag_DME6 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_DME6(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_DMEIF6)==(DMA_HISR_DMEIF6)); -} - -/** - * @brief Get Stream 7 direct mode error flag. - * @rmtoll HISR DMEIF7 LL_DMA_IsActiveFlag_DME7 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_DME7(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_DMEIF7)==(DMA_HISR_DMEIF7)); -} - -/** - * @brief Get Stream 0 FIFO error flag. - * @rmtoll LISR FEIF0 LL_DMA_IsActiveFlag_FE0 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_FE0(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_FEIF0)==(DMA_LISR_FEIF0)); -} - -/** - * @brief Get Stream 1 FIFO error flag. - * @rmtoll LISR FEIF1 LL_DMA_IsActiveFlag_FE1 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_FE1(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_FEIF1)==(DMA_LISR_FEIF1)); -} - -/** - * @brief Get Stream 2 FIFO error flag. - * @rmtoll LISR FEIF2 LL_DMA_IsActiveFlag_FE2 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_FE2(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_FEIF2)==(DMA_LISR_FEIF2)); -} - -/** - * @brief Get Stream 3 FIFO error flag. - * @rmtoll LISR FEIF3 LL_DMA_IsActiveFlag_FE3 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_FE3(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->LISR ,DMA_LISR_FEIF3)==(DMA_LISR_FEIF3)); -} - -/** - * @brief Get Stream 4 FIFO error flag. - * @rmtoll HISR FEIF4 LL_DMA_IsActiveFlag_FE4 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_FE4(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_FEIF4)==(DMA_HISR_FEIF4)); -} - -/** - * @brief Get Stream 5 FIFO error flag. - * @rmtoll HISR FEIF0 LL_DMA_IsActiveFlag_FE5 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_FE5(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_FEIF5)==(DMA_HISR_FEIF5)); -} - -/** - * @brief Get Stream 6 FIFO error flag. - * @rmtoll HISR FEIF6 LL_DMA_IsActiveFlag_FE6 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_FE6(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_FEIF6)==(DMA_HISR_FEIF6)); -} - -/** - * @brief Get Stream 7 FIFO error flag. - * @rmtoll HISR FEIF7 LL_DMA_IsActiveFlag_FE7 - * @param DMAx DMAx Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsActiveFlag_FE7(DMA_TypeDef *DMAx) -{ - return (READ_BIT(DMAx->HISR ,DMA_HISR_FEIF7)==(DMA_HISR_FEIF7)); -} - -/** - * @brief Clear Stream 0 half transfer flag. - * @rmtoll LIFCR CHTIF0 LL_DMA_ClearFlag_HT0 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_HT0(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CHTIF0); -} - -/** - * @brief Clear Stream 1 half transfer flag. - * @rmtoll LIFCR CHTIF1 LL_DMA_ClearFlag_HT1 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_HT1(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CHTIF1); -} - -/** - * @brief Clear Stream 2 half transfer flag. - * @rmtoll LIFCR CHTIF2 LL_DMA_ClearFlag_HT2 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_HT2(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CHTIF2); -} - -/** - * @brief Clear Stream 3 half transfer flag. - * @rmtoll LIFCR CHTIF3 LL_DMA_ClearFlag_HT3 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_HT3(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CHTIF3); -} - -/** - * @brief Clear Stream 4 half transfer flag. - * @rmtoll HIFCR CHTIF4 LL_DMA_ClearFlag_HT4 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_HT4(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CHTIF4); -} - -/** - * @brief Clear Stream 5 half transfer flag. - * @rmtoll HIFCR CHTIF5 LL_DMA_ClearFlag_HT5 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_HT5(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CHTIF5); -} - -/** - * @brief Clear Stream 6 half transfer flag. - * @rmtoll HIFCR CHTIF6 LL_DMA_ClearFlag_HT6 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_HT6(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CHTIF6); -} - -/** - * @brief Clear Stream 7 half transfer flag. - * @rmtoll HIFCR CHTIF7 LL_DMA_ClearFlag_HT7 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_HT7(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CHTIF7); -} - -/** - * @brief Clear Stream 0 transfer complete flag. - * @rmtoll LIFCR CTCIF0 LL_DMA_ClearFlag_TC0 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TC0(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CTCIF0); -} - -/** - * @brief Clear Stream 1 transfer complete flag. - * @rmtoll LIFCR CTCIF1 LL_DMA_ClearFlag_TC1 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TC1(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CTCIF1); -} - -/** - * @brief Clear Stream 2 transfer complete flag. - * @rmtoll LIFCR CTCIF2 LL_DMA_ClearFlag_TC2 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TC2(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CTCIF2); -} - -/** - * @brief Clear Stream 3 transfer complete flag. - * @rmtoll LIFCR CTCIF3 LL_DMA_ClearFlag_TC3 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TC3(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CTCIF3); -} - -/** - * @brief Clear Stream 4 transfer complete flag. - * @rmtoll HIFCR CTCIF4 LL_DMA_ClearFlag_TC4 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TC4(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CTCIF4); -} - -/** - * @brief Clear Stream 5 transfer complete flag. - * @rmtoll HIFCR CTCIF5 LL_DMA_ClearFlag_TC5 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TC5(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CTCIF5); -} - -/** - * @brief Clear Stream 6 transfer complete flag. - * @rmtoll HIFCR CTCIF6 LL_DMA_ClearFlag_TC6 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TC6(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CTCIF6); -} - -/** - * @brief Clear Stream 7 transfer complete flag. - * @rmtoll HIFCR CTCIF7 LL_DMA_ClearFlag_TC7 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TC7(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CTCIF7); -} - -/** - * @brief Clear Stream 0 transfer error flag. - * @rmtoll LIFCR CTEIF0 LL_DMA_ClearFlag_TE0 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TE0(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CTEIF0); -} - -/** - * @brief Clear Stream 1 transfer error flag. - * @rmtoll LIFCR CTEIF1 LL_DMA_ClearFlag_TE1 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TE1(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CTEIF1); -} - -/** - * @brief Clear Stream 2 transfer error flag. - * @rmtoll LIFCR CTEIF2 LL_DMA_ClearFlag_TE2 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TE2(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CTEIF2); -} - -/** - * @brief Clear Stream 3 transfer error flag. - * @rmtoll LIFCR CTEIF3 LL_DMA_ClearFlag_TE3 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TE3(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CTEIF3); -} - -/** - * @brief Clear Stream 4 transfer error flag. - * @rmtoll HIFCR CTEIF4 LL_DMA_ClearFlag_TE4 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TE4(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CTEIF4); -} - -/** - * @brief Clear Stream 5 transfer error flag. - * @rmtoll HIFCR CTEIF5 LL_DMA_ClearFlag_TE5 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TE5(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CTEIF5); -} - -/** - * @brief Clear Stream 6 transfer error flag. - * @rmtoll HIFCR CTEIF6 LL_DMA_ClearFlag_TE6 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TE6(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CTEIF6); -} - -/** - * @brief Clear Stream 7 transfer error flag. - * @rmtoll HIFCR CTEIF7 LL_DMA_ClearFlag_TE7 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_TE7(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CTEIF7); -} - -/** - * @brief Clear Stream 0 direct mode error flag. - * @rmtoll LIFCR CDMEIF0 LL_DMA_ClearFlag_DME0 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_DME0(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CDMEIF0); -} - -/** - * @brief Clear Stream 1 direct mode error flag. - * @rmtoll LIFCR CDMEIF1 LL_DMA_ClearFlag_DME1 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_DME1(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CDMEIF1); -} - -/** - * @brief Clear Stream 2 direct mode error flag. - * @rmtoll LIFCR CDMEIF2 LL_DMA_ClearFlag_DME2 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_DME2(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CDMEIF2); -} - -/** - * @brief Clear Stream 3 direct mode error flag. - * @rmtoll LIFCR CDMEIF3 LL_DMA_ClearFlag_DME3 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_DME3(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CDMEIF3); -} - -/** - * @brief Clear Stream 4 direct mode error flag. - * @rmtoll HIFCR CDMEIF4 LL_DMA_ClearFlag_DME4 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_DME4(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CDMEIF4); -} - -/** - * @brief Clear Stream 5 direct mode error flag. - * @rmtoll HIFCR CDMEIF5 LL_DMA_ClearFlag_DME5 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_DME5(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CDMEIF5); -} - -/** - * @brief Clear Stream 6 direct mode error flag. - * @rmtoll HIFCR CDMEIF6 LL_DMA_ClearFlag_DME6 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_DME6(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CDMEIF6); -} - -/** - * @brief Clear Stream 7 direct mode error flag. - * @rmtoll HIFCR CDMEIF7 LL_DMA_ClearFlag_DME7 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_DME7(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CDMEIF7); -} - -/** - * @brief Clear Stream 0 FIFO error flag. - * @rmtoll LIFCR CFEIF0 LL_DMA_ClearFlag_FE0 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_FE0(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CFEIF0); -} - -/** - * @brief Clear Stream 1 FIFO error flag. - * @rmtoll LIFCR CFEIF1 LL_DMA_ClearFlag_FE1 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_FE1(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CFEIF1); -} - -/** - * @brief Clear Stream 2 FIFO error flag. - * @rmtoll LIFCR CFEIF2 LL_DMA_ClearFlag_FE2 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_FE2(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CFEIF2); -} - -/** - * @brief Clear Stream 3 FIFO error flag. - * @rmtoll LIFCR CFEIF3 LL_DMA_ClearFlag_FE3 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_FE3(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->LIFCR , DMA_LIFCR_CFEIF3); -} - -/** - * @brief Clear Stream 4 FIFO error flag. - * @rmtoll HIFCR CFEIF4 LL_DMA_ClearFlag_FE4 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_FE4(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CFEIF4); -} - -/** - * @brief Clear Stream 5 FIFO error flag. - * @rmtoll HIFCR CFEIF5 LL_DMA_ClearFlag_FE5 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_FE5(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CFEIF5); -} - -/** - * @brief Clear Stream 6 FIFO error flag. - * @rmtoll HIFCR CFEIF6 LL_DMA_ClearFlag_FE6 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_FE6(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CFEIF6); -} - -/** - * @brief Clear Stream 7 FIFO error flag. - * @rmtoll HIFCR CFEIF7 LL_DMA_ClearFlag_FE7 - * @param DMAx DMAx Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA_ClearFlag_FE7(DMA_TypeDef *DMAx) -{ - WRITE_REG(DMAx->HIFCR , DMA_HIFCR_CFEIF7); -} - -/** - * @} - */ - -/** @defgroup DMA_LL_EF_IT_Management IT_Management - * @{ - */ - -/** - * @brief Enable Half transfer interrupt. - * @rmtoll CR HTIE LL_DMA_EnableIT_HT - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_EnableIT_HT(DMA_TypeDef *DMAx, uint32_t Stream) -{ - SET_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_HTIE); -} - -/** - * @brief Enable Transfer error interrupt. - * @rmtoll CR TEIE LL_DMA_EnableIT_TE - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_EnableIT_TE(DMA_TypeDef *DMAx, uint32_t Stream) -{ - SET_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_TEIE); -} - -/** - * @brief Enable Transfer complete interrupt. - * @rmtoll CR TCIE LL_DMA_EnableIT_TC - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_EnableIT_TC(DMA_TypeDef *DMAx, uint32_t Stream) -{ - SET_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_TCIE); -} - -/** - * @brief Enable Direct mode error interrupt. - * @rmtoll CR DMEIE LL_DMA_EnableIT_DME - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_EnableIT_DME(DMA_TypeDef *DMAx, uint32_t Stream) -{ - SET_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_DMEIE); -} - -/** - * @brief Enable FIFO error interrupt. - * @rmtoll FCR FEIE LL_DMA_EnableIT_FE - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_EnableIT_FE(DMA_TypeDef *DMAx, uint32_t Stream) -{ - SET_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->FCR, DMA_SxFCR_FEIE); -} - -/** - * @brief Disable Half transfer interrupt. - * @rmtoll CR HTIE LL_DMA_DisableIT_HT - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_DisableIT_HT(DMA_TypeDef *DMAx, uint32_t Stream) -{ - CLEAR_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_HTIE); -} - -/** - * @brief Disable Transfer error interrupt. - * @rmtoll CR TEIE LL_DMA_DisableIT_TE - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_DisableIT_TE(DMA_TypeDef *DMAx, uint32_t Stream) -{ - CLEAR_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_TEIE); -} - -/** - * @brief Disable Transfer complete interrupt. - * @rmtoll CR TCIE LL_DMA_DisableIT_TC - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_DisableIT_TC(DMA_TypeDef *DMAx, uint32_t Stream) -{ - CLEAR_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_TCIE); -} - -/** - * @brief Disable Direct mode error interrupt. - * @rmtoll CR DMEIE LL_DMA_DisableIT_DME - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_DisableIT_DME(DMA_TypeDef *DMAx, uint32_t Stream) -{ - CLEAR_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_DMEIE); -} - -/** - * @brief Disable FIFO error interrupt. - * @rmtoll FCR FEIE LL_DMA_DisableIT_FE - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval None - */ -__STATIC_INLINE void LL_DMA_DisableIT_FE(DMA_TypeDef *DMAx, uint32_t Stream) -{ - CLEAR_BIT(((DMA_Stream_TypeDef *)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->FCR, DMA_SxFCR_FEIE); -} - -/** - * @brief Check if Half transfer interrup is enabled. - * @rmtoll CR HTIE LL_DMA_IsEnabledIT_HT - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsEnabledIT_HT(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_HTIE) == DMA_SxCR_HTIE); -} - -/** - * @brief Check if Transfer error nterrup is enabled. - * @rmtoll CR TEIE LL_DMA_IsEnabledIT_TE - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsEnabledIT_TE(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_TEIE) == DMA_SxCR_TEIE); -} - -/** - * @brief Check if Transfer complete interrup is enabled. - * @rmtoll CR TCIE LL_DMA_IsEnabledIT_TC - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsEnabledIT_TC(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_TCIE) == DMA_SxCR_TCIE); -} - -/** - * @brief Check if Direct mode error interrupt is enabled. - * @rmtoll CR DMEIE LL_DMA_IsEnabledIT_DME - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsEnabledIT_DME(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->CR, DMA_SxCR_DMEIE) == DMA_SxCR_DMEIE); -} - -/** - * @brief Check if FIFO error interrup is enabled. - * @rmtoll FCR FEIE LL_DMA_IsEnabledIT_FE - * @param DMAx DMAx Instance - * @param Stream This parameter can be one of the following values: - * @arg @ref LL_DMA_STREAM_0 - * @arg @ref LL_DMA_STREAM_1 - * @arg @ref LL_DMA_STREAM_2 - * @arg @ref LL_DMA_STREAM_3 - * @arg @ref LL_DMA_STREAM_4 - * @arg @ref LL_DMA_STREAM_5 - * @arg @ref LL_DMA_STREAM_6 - * @arg @ref LL_DMA_STREAM_7 - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA_IsEnabledIT_FE(DMA_TypeDef *DMAx, uint32_t Stream) -{ - return (READ_BIT(((DMA_Stream_TypeDef*)((uint32_t)((uint32_t)DMAx + STREAM_OFFSET_TAB[Stream])))->FCR, DMA_SxFCR_FEIE) == DMA_SxFCR_FEIE); -} - -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup DMA_LL_EF_Init Initialization and de-initialization functions - * @{ - */ - -uint32_t LL_DMA_Init(DMA_TypeDef *DMAx, uint32_t Stream, LL_DMA_InitTypeDef *DMA_InitStruct); -uint32_t LL_DMA_DeInit(DMA_TypeDef *DMAx, uint32_t Stream); -void LL_DMA_StructInit(LL_DMA_InitTypeDef *DMA_InitStruct); - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* DMA1 || DMA2 */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_DMA_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_dma2d.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_dma2d.h deleted file mode 100644 index a783d05..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_dma2d.h +++ /dev/null @@ -1,1904 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_dma2d.h - * @author MCD Application Team - * @brief Header file of DMA2D LL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_LL_DMA2D_H -#define STM32F4xx_LL_DMA2D_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (DMA2D) - -/** @defgroup DMA2D_LL DMA2D - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup DMA2D_LL_Private_Macros DMA2D Private Macros - * @{ - */ - -/** - * @} - */ -#endif /*USE_FULL_LL_DRIVER*/ - -/* Exported types ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup DMA2D_LL_ES_Init_Struct DMA2D Exported Init structures - * @{ - */ - -/** - * @brief LL DMA2D Init Structure Definition - */ -typedef struct -{ - uint32_t Mode; /*!< Specifies the DMA2D transfer mode. - - This parameter can be one value of @ref DMA2D_LL_EC_MODE. - - This parameter can be modified afterwards, - using unitary function @ref LL_DMA2D_SetMode(). */ - - uint32_t ColorMode; /*!< Specifies the color format of the output image. - - This parameter can be one value of @ref DMA2D_LL_EC_OUTPUT_COLOR_MODE. - - This parameter can be modified afterwards using, - unitary function @ref LL_DMA2D_SetOutputColorMode(). */ - - uint32_t OutputBlue; /*!< Specifies the Blue value of the output image. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0xFF if ARGB8888 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0xFF if RGB888 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0x1F if RGB565 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0x1F if ARGB1555 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0x0F if ARGB4444 color mode is selected. - - This parameter can be modified afterwards, - using unitary function @ref LL_DMA2D_SetOutputColor() or configuration - function @ref LL_DMA2D_ConfigOutputColor(). */ - - uint32_t OutputGreen; /*!< Specifies the Green value of the output image. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0xFF if ARGB8888 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0xFF if RGB888 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0x3F if RGB565 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0x1F if ARGB1555 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0x0F if ARGB4444 color mode is selected. - - This parameter can be modified afterwards - using unitary function @ref LL_DMA2D_SetOutputColor() or configuration - function @ref LL_DMA2D_ConfigOutputColor(). */ - - uint32_t OutputRed; /*!< Specifies the Red value of the output image. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0xFF if ARGB8888 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0xFF if RGB888 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0x1F if RGB565 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0x1F if ARGB1555 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0x0F if ARGB4444 color mode is selected. - - This parameter can be modified afterwards - using unitary function @ref LL_DMA2D_SetOutputColor() or configuration - function @ref LL_DMA2D_ConfigOutputColor(). */ - - uint32_t OutputAlpha; /*!< Specifies the Alpha channel of the output image. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0xFF if ARGB8888 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0x01 if ARGB1555 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0x0F if ARGB4444 color mode is selected. - - This parameter is not considered if RGB888 or RGB565 color mode is selected. - - This parameter can be modified afterwards using, - unitary function @ref LL_DMA2D_SetOutputColor() or configuration - function @ref LL_DMA2D_ConfigOutputColor(). */ - - uint32_t OutputMemoryAddress; /*!< Specifies the memory address. - - This parameter must be a number between: - Min_Data = 0x0000 and Max_Data = 0xFFFFFFFF. - - This parameter can be modified afterwards, - using unitary function @ref LL_DMA2D_SetOutputMemAddr(). */ - - - - uint32_t LineOffset; /*!< Specifies the output line offset value. - - This parameter must be a number between Min_Data = 0x0000 and Max_Data = 0x3FFF. - - This parameter can be modified afterwards, - using unitary function @ref LL_DMA2D_SetLineOffset(). */ - - uint32_t NbrOfLines; /*!< Specifies the number of lines of the area to be transferred. - - This parameter must be a number between: - Min_Data = 0x0000 and Max_Data = 0xFFFF. - - This parameter can be modified afterwards, - using unitary function @ref LL_DMA2D_SetNbrOfLines(). */ - - uint32_t NbrOfPixelsPerLines; /*!< Specifies the number of pixels per lines of the area to be transferred. - - This parameter must be a number between Min_Data = 0x0000 and Max_Data = 0x3FFF. - - This parameter can be modified afterwards using, - unitary function @ref LL_DMA2D_SetNbrOfPixelsPerLines(). */ - - -} LL_DMA2D_InitTypeDef; - -/** - * @brief LL DMA2D Layer Configuration Structure Definition - */ -typedef struct -{ - uint32_t MemoryAddress; /*!< Specifies the foreground or background memory address. - - This parameter must be a number between: - Min_Data = 0x0000 and Max_Data = 0xFFFFFFFF. - - This parameter can be modified afterwards using unitary functions - - @ref LL_DMA2D_FGND_SetMemAddr() for foreground layer, - - @ref LL_DMA2D_BGND_SetMemAddr() for background layer. */ - - uint32_t LineOffset; /*!< Specifies the foreground or background line offset value. - - This parameter must be a number between Min_Data = 0x0000 and Max_Data = 0x3FFF. - - This parameter can be modified afterwards using unitary functions - - @ref LL_DMA2D_FGND_SetLineOffset() for foreground layer, - - @ref LL_DMA2D_BGND_SetLineOffset() for background layer. */ - - uint32_t ColorMode; /*!< Specifies the foreground or background color mode. - - This parameter can be one value of @ref DMA2D_LL_EC_INPUT_COLOR_MODE. - - This parameter can be modified afterwards using unitary functions - - @ref LL_DMA2D_FGND_SetColorMode() for foreground layer, - - @ref LL_DMA2D_BGND_SetColorMode() for background layer. */ - - uint32_t CLUTColorMode; /*!< Specifies the foreground or background CLUT color mode. - - This parameter can be one value of @ref DMA2D_LL_EC_CLUT_COLOR_MODE. - - This parameter can be modified afterwards using unitary functions - - @ref LL_DMA2D_FGND_SetCLUTColorMode() for foreground layer, - - @ref LL_DMA2D_BGND_SetCLUTColorMode() for background layer. */ - - uint32_t CLUTSize; /*!< Specifies the foreground or background CLUT size. - - This parameter must be a number between Min_Data = 0x00 and Max_Data = 0xFF. - - This parameter can be modified afterwards using unitary functions - - @ref LL_DMA2D_FGND_SetCLUTSize() for foreground layer, - - @ref LL_DMA2D_BGND_SetCLUTSize() for background layer. */ - - uint32_t AlphaMode; /*!< Specifies the foreground or background alpha mode. - - This parameter can be one value of @ref DMA2D_LL_EC_ALPHA_MODE. - - This parameter can be modified afterwards using unitary functions - - @ref LL_DMA2D_FGND_SetAlphaMode() for foreground layer, - - @ref LL_DMA2D_BGND_SetAlphaMode() for background layer. */ - - uint32_t Alpha; /*!< Specifies the foreground or background Alpha value. - - This parameter must be a number between Min_Data = 0x00 and Max_Data = 0xFF. - - This parameter can be modified afterwards using unitary functions - - @ref LL_DMA2D_FGND_SetAlpha() for foreground layer, - - @ref LL_DMA2D_BGND_SetAlpha() for background layer. */ - - uint32_t Blue; /*!< Specifies the foreground or background Blue color value. - - This parameter must be a number between Min_Data = 0x00 and Max_Data = 0xFF. - - This parameter can be modified afterwards using unitary functions - - @ref LL_DMA2D_FGND_SetBlueColor() for foreground layer, - - @ref LL_DMA2D_BGND_SetBlueColor() for background layer. */ - - uint32_t Green; /*!< Specifies the foreground or background Green color value. - - This parameter must be a number between Min_Data = 0x00 and Max_Data = 0xFF. - - This parameter can be modified afterwards using unitary functions - - @ref LL_DMA2D_FGND_SetGreenColor() for foreground layer, - - @ref LL_DMA2D_BGND_SetGreenColor() for background layer. */ - - uint32_t Red; /*!< Specifies the foreground or background Red color value. - - This parameter must be a number between Min_Data = 0x00 and Max_Data = 0xFF. - - This parameter can be modified afterwards using unitary functions - - @ref LL_DMA2D_FGND_SetRedColor() for foreground layer, - - @ref LL_DMA2D_BGND_SetRedColor() for background layer. */ - - uint32_t CLUTMemoryAddress; /*!< Specifies the foreground or background CLUT memory address. - - This parameter must be a number between: - Min_Data = 0x0000 and Max_Data = 0xFFFFFFFF. - - This parameter can be modified afterwards using unitary functions - - @ref LL_DMA2D_FGND_SetCLUTMemAddr() for foreground layer, - - @ref LL_DMA2D_BGND_SetCLUTMemAddr() for background layer. */ - - - -} LL_DMA2D_LayerCfgTypeDef; - -/** - * @brief LL DMA2D Output Color Structure Definition - */ -typedef struct -{ - uint32_t ColorMode; /*!< Specifies the color format of the output image. - - This parameter can be one value of @ref DMA2D_LL_EC_OUTPUT_COLOR_MODE. - - This parameter can be modified afterwards using - unitary function @ref LL_DMA2D_SetOutputColorMode(). */ - - uint32_t OutputBlue; /*!< Specifies the Blue value of the output image. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0xFF if ARGB8888 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0xFF if RGB888 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0x1F if RGB565 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0x1F if ARGB1555 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0x0F if ARGB4444 color mode is selected. - - This parameter can be modified afterwards using, - unitary function @ref LL_DMA2D_SetOutputColor() or configuration - function @ref LL_DMA2D_ConfigOutputColor(). */ - - uint32_t OutputGreen; /*!< Specifies the Green value of the output image. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0xFF if ARGB8888 color mode is selected. - - This parameter must be a number between - Min_Data = 0x00 and Max_Data = 0xFF if RGB888 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0x3F if RGB565 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0x1F if ARGB1555 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0x0F if ARGB4444 color mode is selected. - - This parameter can be modified afterwards, - using unitary function @ref LL_DMA2D_SetOutputColor() or configuration - function @ref LL_DMA2D_ConfigOutputColor(). */ - - uint32_t OutputRed; /*!< Specifies the Red value of the output image. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0xFF if ARGB8888 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0xFF if RGB888 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0x1F if RGB565 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0x1F if ARGB1555 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0x0F if ARGB4444 color mode is selected. - - This parameter can be modified afterwards, - using unitary function @ref LL_DMA2D_SetOutputColor() or configuration - function @ref LL_DMA2D_ConfigOutputColor(). */ - - uint32_t OutputAlpha; /*!< Specifies the Alpha channel of the output image. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0xFF if ARGB8888 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0x01 if ARGB1555 color mode is selected. - - This parameter must be a number between: - Min_Data = 0x00 and Max_Data = 0x0F if ARGB4444 color mode is selected. - - This parameter is not considered if RGB888 or RGB565 color mode is selected. - - This parameter can be modified afterwards, - using unitary function @ref LL_DMA2D_SetOutputColor() or configuration - function @ref LL_DMA2D_ConfigOutputColor(). */ - -} LL_DMA2D_ColorTypeDef; - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup DMA2D_LL_Exported_Constants DMA2D Exported Constants - * @{ - */ - -/** @defgroup DMA2D_LL_EC_GET_FLAG Get Flags Defines - * @brief Flags defines which can be used with LL_DMA2D_ReadReg function - * @{ - */ -#define LL_DMA2D_FLAG_CEIF DMA2D_ISR_CEIF /*!< Configuration Error Interrupt Flag */ -#define LL_DMA2D_FLAG_CTCIF DMA2D_ISR_CTCIF /*!< CLUT Transfer Complete Interrupt Flag */ -#define LL_DMA2D_FLAG_CAEIF DMA2D_ISR_CAEIF /*!< CLUT Access Error Interrupt Flag */ -#define LL_DMA2D_FLAG_TWIF DMA2D_ISR_TWIF /*!< Transfer Watermark Interrupt Flag */ -#define LL_DMA2D_FLAG_TCIF DMA2D_ISR_TCIF /*!< Transfer Complete Interrupt Flag */ -#define LL_DMA2D_FLAG_TEIF DMA2D_ISR_TEIF /*!< Transfer Error Interrupt Flag */ -/** - * @} - */ - -/** @defgroup DMA2D_LL_EC_IT IT Defines - * @brief IT defines which can be used with LL_DMA2D_ReadReg and LL_DMA2D_WriteReg functions - * @{ - */ -#define LL_DMA2D_IT_CEIE DMA2D_CR_CEIE /*!< Configuration Error Interrupt */ -#define LL_DMA2D_IT_CTCIE DMA2D_CR_CTCIE /*!< CLUT Transfer Complete Interrupt */ -#define LL_DMA2D_IT_CAEIE DMA2D_CR_CAEIE /*!< CLUT Access Error Interrupt */ -#define LL_DMA2D_IT_TWIE DMA2D_CR_TWIE /*!< Transfer Watermark Interrupt */ -#define LL_DMA2D_IT_TCIE DMA2D_CR_TCIE /*!< Transfer Complete Interrupt */ -#define LL_DMA2D_IT_TEIE DMA2D_CR_TEIE /*!< Transfer Error Interrupt */ -/** - * @} - */ - -/** @defgroup DMA2D_LL_EC_MODE Mode - * @{ - */ -#define LL_DMA2D_MODE_M2M 0x00000000U /*!< DMA2D memory to memory transfer mode */ -#define LL_DMA2D_MODE_M2M_PFC DMA2D_CR_MODE_0 /*!< DMA2D memory to memory with pixel format conversion transfer mode */ -#define LL_DMA2D_MODE_M2M_BLEND DMA2D_CR_MODE_1 /*!< DMA2D memory to memory with blending transfer mode */ -#define LL_DMA2D_MODE_R2M DMA2D_CR_MODE /*!< DMA2D register to memory transfer mode */ -/** - * @} - */ - -/** @defgroup DMA2D_LL_EC_OUTPUT_COLOR_MODE Output Color Mode - * @{ - */ -#define LL_DMA2D_OUTPUT_MODE_ARGB8888 0x00000000U /*!< ARGB8888 */ -#define LL_DMA2D_OUTPUT_MODE_RGB888 DMA2D_OPFCCR_CM_0 /*!< RGB888 */ -#define LL_DMA2D_OUTPUT_MODE_RGB565 DMA2D_OPFCCR_CM_1 /*!< RGB565 */ -#define LL_DMA2D_OUTPUT_MODE_ARGB1555 (DMA2D_OPFCCR_CM_0|DMA2D_OPFCCR_CM_1) /*!< ARGB1555 */ -#define LL_DMA2D_OUTPUT_MODE_ARGB4444 DMA2D_OPFCCR_CM_2 /*!< ARGB4444 */ -/** - * @} - */ - -/** @defgroup DMA2D_LL_EC_INPUT_COLOR_MODE Input Color Mode - * @{ - */ -#define LL_DMA2D_INPUT_MODE_ARGB8888 0x00000000U /*!< ARGB8888 */ -#define LL_DMA2D_INPUT_MODE_RGB888 DMA2D_FGPFCCR_CM_0 /*!< RGB888 */ -#define LL_DMA2D_INPUT_MODE_RGB565 DMA2D_FGPFCCR_CM_1 /*!< RGB565 */ -#define LL_DMA2D_INPUT_MODE_ARGB1555 (DMA2D_FGPFCCR_CM_0|DMA2D_FGPFCCR_CM_1) /*!< ARGB1555 */ -#define LL_DMA2D_INPUT_MODE_ARGB4444 DMA2D_FGPFCCR_CM_2 /*!< ARGB4444 */ -#define LL_DMA2D_INPUT_MODE_L8 (DMA2D_FGPFCCR_CM_0|DMA2D_FGPFCCR_CM_2) /*!< L8 */ -#define LL_DMA2D_INPUT_MODE_AL44 (DMA2D_FGPFCCR_CM_1|DMA2D_FGPFCCR_CM_2) /*!< AL44 */ -#define LL_DMA2D_INPUT_MODE_AL88 (DMA2D_FGPFCCR_CM_0|DMA2D_FGPFCCR_CM_1|DMA2D_FGPFCCR_CM_2) /*!< AL88 */ -#define LL_DMA2D_INPUT_MODE_L4 DMA2D_FGPFCCR_CM_3 /*!< L4 */ -#define LL_DMA2D_INPUT_MODE_A8 (DMA2D_FGPFCCR_CM_0|DMA2D_FGPFCCR_CM_3) /*!< A8 */ -#define LL_DMA2D_INPUT_MODE_A4 (DMA2D_FGPFCCR_CM_1|DMA2D_FGPFCCR_CM_3) /*!< A4 */ -/** - * @} - */ - -/** @defgroup DMA2D_LL_EC_ALPHA_MODE Alpha Mode - * @{ - */ -#define LL_DMA2D_ALPHA_MODE_NO_MODIF 0x00000000U /*!< No modification of the alpha channel value */ -#define LL_DMA2D_ALPHA_MODE_REPLACE DMA2D_FGPFCCR_AM_0 /*!< Replace original alpha channel value by - programmed alpha value */ -#define LL_DMA2D_ALPHA_MODE_COMBINE DMA2D_FGPFCCR_AM_1 /*!< Replace original alpha channel value by - programmed alpha value with, - original alpha channel value */ -/** - * @} - */ - - - - -/** @defgroup DMA2D_LL_EC_CLUT_COLOR_MODE CLUT Color Mode - * @{ - */ -#define LL_DMA2D_CLUT_COLOR_MODE_ARGB8888 0x00000000U /*!< ARGB8888 */ -#define LL_DMA2D_CLUT_COLOR_MODE_RGB888 DMA2D_FGPFCCR_CCM /*!< RGB888 */ -/** - * @} - */ - - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup DMA2D_LL_Exported_Macros DMA2D Exported Macros - * @{ - */ - -/** @defgroup DMA2D_LL_EM_WRITE_READ Common Write and read registers Macros - * @{ - */ - -/** - * @brief Write a value in DMA2D register. - * @param __INSTANCE__ DMA2D Instance - * @param __REG__ Register to be written - * @param __VALUE__ Value to be written in the register - * @retval None - */ -#define LL_DMA2D_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG((__INSTANCE__)->__REG__, (__VALUE__)) - -/** - * @brief Read a value in DMA2D register. - * @param __INSTANCE__ DMA2D Instance - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_DMA2D_ReadReg(__INSTANCE__, __REG__) READ_REG((__INSTANCE__)->__REG__) -/** - * @} - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup DMA2D_LL_Exported_Functions DMA2D Exported Functions - * @{ - */ - -/** @defgroup DMA2D_LL_EF_Configuration Configuration Functions - * @{ - */ - -/** - * @brief Start a DMA2D transfer. - * @rmtoll CR START LL_DMA2D_Start - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_Start(DMA2D_TypeDef *DMA2Dx) -{ - SET_BIT(DMA2Dx->CR, DMA2D_CR_START); -} - -/** - * @brief Indicate if a DMA2D transfer is ongoing. - * @rmtoll CR START LL_DMA2D_IsTransferOngoing - * @param DMA2Dx DMA2D Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA2D_IsTransferOngoing(DMA2D_TypeDef *DMA2Dx) -{ - return ((READ_BIT(DMA2Dx->CR, DMA2D_CR_START) == (DMA2D_CR_START)) ? 1UL : 0UL); -} - -/** - * @brief Suspend DMA2D transfer. - * @note This API can be used to suspend automatic foreground or background CLUT loading. - * @rmtoll CR SUSP LL_DMA2D_Suspend - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_Suspend(DMA2D_TypeDef *DMA2Dx) -{ - MODIFY_REG(DMA2Dx->CR, DMA2D_CR_SUSP | DMA2D_CR_START, DMA2D_CR_SUSP); -} - -/** - * @brief Resume DMA2D transfer. - * @note This API can be used to resume automatic foreground or background CLUT loading. - * @rmtoll CR SUSP LL_DMA2D_Resume - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_Resume(DMA2D_TypeDef *DMA2Dx) -{ - CLEAR_BIT(DMA2Dx->CR, DMA2D_CR_SUSP | DMA2D_CR_START); -} - -/** - * @brief Indicate if DMA2D transfer is suspended. - * @note This API can be used to indicate whether or not automatic foreground or - * background CLUT loading is suspended. - * @rmtoll CR SUSP LL_DMA2D_IsSuspended - * @param DMA2Dx DMA2D Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA2D_IsSuspended(DMA2D_TypeDef *DMA2Dx) -{ - return ((READ_BIT(DMA2Dx->CR, DMA2D_CR_SUSP) == (DMA2D_CR_SUSP)) ? 1UL : 0UL); -} - -/** - * @brief Abort DMA2D transfer. - * @note This API can be used to abort automatic foreground or background CLUT loading. - * @rmtoll CR ABORT LL_DMA2D_Abort - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_Abort(DMA2D_TypeDef *DMA2Dx) -{ - MODIFY_REG(DMA2Dx->CR, DMA2D_CR_ABORT | DMA2D_CR_START, DMA2D_CR_ABORT); -} - -/** - * @brief Indicate if DMA2D transfer is aborted. - * @note This API can be used to indicate whether or not automatic foreground or - * background CLUT loading is aborted. - * @rmtoll CR ABORT LL_DMA2D_IsAborted - * @param DMA2Dx DMA2D Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA2D_IsAborted(DMA2D_TypeDef *DMA2Dx) -{ - return ((READ_BIT(DMA2Dx->CR, DMA2D_CR_ABORT) == (DMA2D_CR_ABORT)) ? 1UL : 0UL); -} - -/** - * @brief Set DMA2D mode. - * @rmtoll CR MODE LL_DMA2D_SetMode - * @param DMA2Dx DMA2D Instance - * @param Mode This parameter can be one of the following values: - * @arg @ref LL_DMA2D_MODE_M2M - * @arg @ref LL_DMA2D_MODE_M2M_PFC - * @arg @ref LL_DMA2D_MODE_M2M_BLEND - * @arg @ref LL_DMA2D_MODE_R2M - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_SetMode(DMA2D_TypeDef *DMA2Dx, uint32_t Mode) -{ - MODIFY_REG(DMA2Dx->CR, DMA2D_CR_MODE, Mode); -} - -/** - * @brief Return DMA2D mode - * @rmtoll CR MODE LL_DMA2D_GetMode - * @param DMA2Dx DMA2D Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA2D_MODE_M2M - * @arg @ref LL_DMA2D_MODE_M2M_PFC - * @arg @ref LL_DMA2D_MODE_M2M_BLEND - * @arg @ref LL_DMA2D_MODE_R2M - */ -__STATIC_INLINE uint32_t LL_DMA2D_GetMode(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->CR, DMA2D_CR_MODE)); -} - -/** - * @brief Set DMA2D output color mode. - * @rmtoll OPFCCR CM LL_DMA2D_SetOutputColorMode - * @param DMA2Dx DMA2D Instance - * @param ColorMode This parameter can be one of the following values: - * @arg @ref LL_DMA2D_OUTPUT_MODE_ARGB8888 - * @arg @ref LL_DMA2D_OUTPUT_MODE_RGB888 - * @arg @ref LL_DMA2D_OUTPUT_MODE_RGB565 - * @arg @ref LL_DMA2D_OUTPUT_MODE_ARGB1555 - * @arg @ref LL_DMA2D_OUTPUT_MODE_ARGB4444 - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_SetOutputColorMode(DMA2D_TypeDef *DMA2Dx, uint32_t ColorMode) -{ - MODIFY_REG(DMA2Dx->OPFCCR, DMA2D_OPFCCR_CM, ColorMode); -} - -/** - * @brief Return DMA2D output color mode. - * @rmtoll OPFCCR CM LL_DMA2D_GetOutputColorMode - * @param DMA2Dx DMA2D Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA2D_OUTPUT_MODE_ARGB8888 - * @arg @ref LL_DMA2D_OUTPUT_MODE_RGB888 - * @arg @ref LL_DMA2D_OUTPUT_MODE_RGB565 - * @arg @ref LL_DMA2D_OUTPUT_MODE_ARGB1555 - * @arg @ref LL_DMA2D_OUTPUT_MODE_ARGB4444 - */ -__STATIC_INLINE uint32_t LL_DMA2D_GetOutputColorMode(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->OPFCCR, DMA2D_OPFCCR_CM)); -} - - - - -/** - * @brief Set DMA2D line offset, expressed on 14 bits ([13:0] bits). - * @rmtoll OOR LO LL_DMA2D_SetLineOffset - * @param DMA2Dx DMA2D Instance - * @param LineOffset Value between Min_Data=0 and Max_Data=0x3FFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_SetLineOffset(DMA2D_TypeDef *DMA2Dx, uint32_t LineOffset) -{ - MODIFY_REG(DMA2Dx->OOR, DMA2D_OOR_LO, LineOffset); -} - -/** - * @brief Return DMA2D line offset, expressed on 14 bits ([13:0] bits). - * @rmtoll OOR LO LL_DMA2D_GetLineOffset - * @param DMA2Dx DMA2D Instance - * @retval Line offset value between Min_Data=0 and Max_Data=0x3FFF - */ -__STATIC_INLINE uint32_t LL_DMA2D_GetLineOffset(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->OOR, DMA2D_OOR_LO)); -} - -/** - * @brief Set DMA2D number of pixels per lines, expressed on 14 bits ([13:0] bits). - * @rmtoll NLR PL LL_DMA2D_SetNbrOfPixelsPerLines - * @param DMA2Dx DMA2D Instance - * @param NbrOfPixelsPerLines Value between Min_Data=0 and Max_Data=0x3FFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_SetNbrOfPixelsPerLines(DMA2D_TypeDef *DMA2Dx, uint32_t NbrOfPixelsPerLines) -{ - MODIFY_REG(DMA2Dx->NLR, DMA2D_NLR_PL, (NbrOfPixelsPerLines << DMA2D_NLR_PL_Pos)); -} - -/** - * @brief Return DMA2D number of pixels per lines, expressed on 14 bits ([13:0] bits) - * @rmtoll NLR PL LL_DMA2D_GetNbrOfPixelsPerLines - * @param DMA2Dx DMA2D Instance - * @retval Number of pixels per lines value between Min_Data=0 and Max_Data=0x3FFF - */ -__STATIC_INLINE uint32_t LL_DMA2D_GetNbrOfPixelsPerLines(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->NLR, DMA2D_NLR_PL) >> DMA2D_NLR_PL_Pos); -} - -/** - * @brief Set DMA2D number of lines, expressed on 16 bits ([15:0] bits). - * @rmtoll NLR NL LL_DMA2D_SetNbrOfLines - * @param DMA2Dx DMA2D Instance - * @param NbrOfLines Value between Min_Data=0 and Max_Data=0xFFFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_SetNbrOfLines(DMA2D_TypeDef *DMA2Dx, uint32_t NbrOfLines) -{ - MODIFY_REG(DMA2Dx->NLR, DMA2D_NLR_NL, NbrOfLines); -} - -/** - * @brief Return DMA2D number of lines, expressed on 16 bits ([15:0] bits). - * @rmtoll NLR NL LL_DMA2D_GetNbrOfLines - * @param DMA2Dx DMA2D Instance - * @retval Number of lines value between Min_Data=0 and Max_Data=0xFFFF - */ -__STATIC_INLINE uint32_t LL_DMA2D_GetNbrOfLines(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->NLR, DMA2D_NLR_NL)); -} - -/** - * @brief Set DMA2D output memory address, expressed on 32 bits ([31:0] bits). - * @rmtoll OMAR MA LL_DMA2D_SetOutputMemAddr - * @param DMA2Dx DMA2D Instance - * @param OutputMemoryAddress Value between Min_Data=0 and Max_Data=0xFFFFFFFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_SetOutputMemAddr(DMA2D_TypeDef *DMA2Dx, uint32_t OutputMemoryAddress) -{ - LL_DMA2D_WriteReg(DMA2Dx, OMAR, OutputMemoryAddress); -} - -/** - * @brief Get DMA2D output memory address, expressed on 32 bits ([31:0] bits). - * @rmtoll OMAR MA LL_DMA2D_GetOutputMemAddr - * @param DMA2Dx DMA2D Instance - * @retval Output memory address value between Min_Data=0 and Max_Data=0xFFFFFFFF - */ -__STATIC_INLINE uint32_t LL_DMA2D_GetOutputMemAddr(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(LL_DMA2D_ReadReg(DMA2Dx, OMAR)); -} - -/** - * @brief Set DMA2D output color, expressed on 32 bits ([31:0] bits). - * @note Output color format depends on output color mode, ARGB8888, RGB888, - * RGB565, ARGB1555 or ARGB4444. - * @note LL_DMA2D_ConfigOutputColor() API may be used instead if colors values formatting - * with respect to color mode is not done by the user code. - * @rmtoll OCOLR BLUE LL_DMA2D_SetOutputColor\n - * OCOLR GREEN LL_DMA2D_SetOutputColor\n - * OCOLR RED LL_DMA2D_SetOutputColor\n - * OCOLR ALPHA LL_DMA2D_SetOutputColor - * @param DMA2Dx DMA2D Instance - * @param OutputColor Value between Min_Data=0 and Max_Data=0xFFFFFFFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_SetOutputColor(DMA2D_TypeDef *DMA2Dx, uint32_t OutputColor) -{ - MODIFY_REG(DMA2Dx->OCOLR, (DMA2D_OCOLR_BLUE_1 | DMA2D_OCOLR_GREEN_1 | DMA2D_OCOLR_RED_1 | DMA2D_OCOLR_ALPHA_1), \ - OutputColor); -} - -/** - * @brief Get DMA2D output color, expressed on 32 bits ([31:0] bits). - * @note Alpha channel and red, green, blue color values must be retrieved from the returned - * value based on the output color mode (ARGB8888, RGB888, RGB565, ARGB1555 or ARGB4444) - * as set by @ref LL_DMA2D_SetOutputColorMode. - * @rmtoll OCOLR BLUE LL_DMA2D_GetOutputColor\n - * OCOLR GREEN LL_DMA2D_GetOutputColor\n - * OCOLR RED LL_DMA2D_GetOutputColor\n - * OCOLR ALPHA LL_DMA2D_GetOutputColor - * @param DMA2Dx DMA2D Instance - * @retval Output color value between Min_Data=0 and Max_Data=0xFFFFFFFF - */ -__STATIC_INLINE uint32_t LL_DMA2D_GetOutputColor(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->OCOLR, \ - (DMA2D_OCOLR_BLUE_1 | DMA2D_OCOLR_GREEN_1 | DMA2D_OCOLR_RED_1 | DMA2D_OCOLR_ALPHA_1))); -} - -/** - * @brief Set DMA2D line watermark, expressed on 16 bits ([15:0] bits). - * @rmtoll LWR LW LL_DMA2D_SetLineWatermark - * @param DMA2Dx DMA2D Instance - * @param LineWatermark Value between Min_Data=0 and Max_Data=0xFFFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_SetLineWatermark(DMA2D_TypeDef *DMA2Dx, uint32_t LineWatermark) -{ - MODIFY_REG(DMA2Dx->LWR, DMA2D_LWR_LW, LineWatermark); -} - -/** - * @brief Return DMA2D line watermark, expressed on 16 bits ([15:0] bits). - * @rmtoll LWR LW LL_DMA2D_GetLineWatermark - * @param DMA2Dx DMA2D Instance - * @retval Line watermark value between Min_Data=0 and Max_Data=0xFFFF - */ -__STATIC_INLINE uint32_t LL_DMA2D_GetLineWatermark(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->LWR, DMA2D_LWR_LW)); -} - -/** - * @brief Set DMA2D dead time, expressed on 8 bits ([7:0] bits). - * @rmtoll AMTCR DT LL_DMA2D_SetDeadTime - * @param DMA2Dx DMA2D Instance - * @param DeadTime Value between Min_Data=0 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_SetDeadTime(DMA2D_TypeDef *DMA2Dx, uint32_t DeadTime) -{ - MODIFY_REG(DMA2Dx->AMTCR, DMA2D_AMTCR_DT, (DeadTime << DMA2D_AMTCR_DT_Pos)); -} - -/** - * @brief Return DMA2D dead time, expressed on 8 bits ([7:0] bits). - * @rmtoll AMTCR DT LL_DMA2D_GetDeadTime - * @param DMA2Dx DMA2D Instance - * @retval Dead time value between Min_Data=0 and Max_Data=0xFF - */ -__STATIC_INLINE uint32_t LL_DMA2D_GetDeadTime(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->AMTCR, DMA2D_AMTCR_DT) >> DMA2D_AMTCR_DT_Pos); -} - -/** - * @brief Enable DMA2D dead time functionality. - * @rmtoll AMTCR EN LL_DMA2D_EnableDeadTime - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_EnableDeadTime(DMA2D_TypeDef *DMA2Dx) -{ - SET_BIT(DMA2Dx->AMTCR, DMA2D_AMTCR_EN); -} - -/** - * @brief Disable DMA2D dead time functionality. - * @rmtoll AMTCR EN LL_DMA2D_DisableDeadTime - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_DisableDeadTime(DMA2D_TypeDef *DMA2Dx) -{ - CLEAR_BIT(DMA2Dx->AMTCR, DMA2D_AMTCR_EN); -} - -/** - * @brief Indicate if DMA2D dead time functionality is enabled. - * @rmtoll AMTCR EN LL_DMA2D_IsEnabledDeadTime - * @param DMA2Dx DMA2D Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA2D_IsEnabledDeadTime(DMA2D_TypeDef *DMA2Dx) -{ - return ((READ_BIT(DMA2Dx->AMTCR, DMA2D_AMTCR_EN) == (DMA2D_AMTCR_EN)) ? 1UL : 0UL); -} - -/** @defgroup DMA2D_LL_EF_FGND_Configuration Foreground Configuration Functions - * @{ - */ - -/** - * @brief Set DMA2D foreground memory address, expressed on 32 bits ([31:0] bits). - * @rmtoll FGMAR MA LL_DMA2D_FGND_SetMemAddr - * @param DMA2Dx DMA2D Instance - * @param MemoryAddress Value between Min_Data=0 and Max_Data=0xFFFFFFFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_FGND_SetMemAddr(DMA2D_TypeDef *DMA2Dx, uint32_t MemoryAddress) -{ - LL_DMA2D_WriteReg(DMA2Dx, FGMAR, MemoryAddress); -} - -/** - * @brief Get DMA2D foreground memory address, expressed on 32 bits ([31:0] bits). - * @rmtoll FGMAR MA LL_DMA2D_FGND_GetMemAddr - * @param DMA2Dx DMA2D Instance - * @retval Foreground memory address value between Min_Data=0 and Max_Data=0xFFFFFFFF - */ -__STATIC_INLINE uint32_t LL_DMA2D_FGND_GetMemAddr(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(LL_DMA2D_ReadReg(DMA2Dx, FGMAR)); -} - -/** - * @brief Enable DMA2D foreground CLUT loading. - * @rmtoll FGPFCCR START LL_DMA2D_FGND_EnableCLUTLoad - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_FGND_EnableCLUTLoad(DMA2D_TypeDef *DMA2Dx) -{ - SET_BIT(DMA2Dx->FGPFCCR, DMA2D_FGPFCCR_START); -} - -/** - * @brief Indicate if DMA2D foreground CLUT loading is enabled. - * @rmtoll FGPFCCR START LL_DMA2D_FGND_IsEnabledCLUTLoad - * @param DMA2Dx DMA2D Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA2D_FGND_IsEnabledCLUTLoad(DMA2D_TypeDef *DMA2Dx) -{ - return ((READ_BIT(DMA2Dx->FGPFCCR, DMA2D_FGPFCCR_START) == (DMA2D_FGPFCCR_START)) ? 1UL : 0UL); -} - -/** - * @brief Set DMA2D foreground color mode. - * @rmtoll FGPFCCR CM LL_DMA2D_FGND_SetColorMode - * @param DMA2Dx DMA2D Instance - * @param ColorMode This parameter can be one of the following values: - * @arg @ref LL_DMA2D_INPUT_MODE_ARGB8888 - * @arg @ref LL_DMA2D_INPUT_MODE_RGB888 - * @arg @ref LL_DMA2D_INPUT_MODE_RGB565 - * @arg @ref LL_DMA2D_INPUT_MODE_ARGB1555 - * @arg @ref LL_DMA2D_INPUT_MODE_ARGB4444 - * @arg @ref LL_DMA2D_INPUT_MODE_L8 - * @arg @ref LL_DMA2D_INPUT_MODE_AL44 - * @arg @ref LL_DMA2D_INPUT_MODE_AL88 - * @arg @ref LL_DMA2D_INPUT_MODE_L4 - * @arg @ref LL_DMA2D_INPUT_MODE_A8 - * @arg @ref LL_DMA2D_INPUT_MODE_A4 - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_FGND_SetColorMode(DMA2D_TypeDef *DMA2Dx, uint32_t ColorMode) -{ - MODIFY_REG(DMA2Dx->FGPFCCR, DMA2D_FGPFCCR_CM, ColorMode); -} - -/** - * @brief Return DMA2D foreground color mode. - * @rmtoll FGPFCCR CM LL_DMA2D_FGND_GetColorMode - * @param DMA2Dx DMA2D Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA2D_INPUT_MODE_ARGB8888 - * @arg @ref LL_DMA2D_INPUT_MODE_RGB888 - * @arg @ref LL_DMA2D_INPUT_MODE_RGB565 - * @arg @ref LL_DMA2D_INPUT_MODE_ARGB1555 - * @arg @ref LL_DMA2D_INPUT_MODE_ARGB4444 - * @arg @ref LL_DMA2D_INPUT_MODE_L8 - * @arg @ref LL_DMA2D_INPUT_MODE_AL44 - * @arg @ref LL_DMA2D_INPUT_MODE_AL88 - * @arg @ref LL_DMA2D_INPUT_MODE_L4 - * @arg @ref LL_DMA2D_INPUT_MODE_A8 - * @arg @ref LL_DMA2D_INPUT_MODE_A4 - */ -__STATIC_INLINE uint32_t LL_DMA2D_FGND_GetColorMode(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->FGPFCCR, DMA2D_FGPFCCR_CM)); -} - -/** - * @brief Set DMA2D foreground alpha mode. - * @rmtoll FGPFCCR AM LL_DMA2D_FGND_SetAlphaMode - * @param DMA2Dx DMA2D Instance - * @param AphaMode This parameter can be one of the following values: - * @arg @ref LL_DMA2D_ALPHA_MODE_NO_MODIF - * @arg @ref LL_DMA2D_ALPHA_MODE_REPLACE - * @arg @ref LL_DMA2D_ALPHA_MODE_COMBINE - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_FGND_SetAlphaMode(DMA2D_TypeDef *DMA2Dx, uint32_t AphaMode) -{ - MODIFY_REG(DMA2Dx->FGPFCCR, DMA2D_FGPFCCR_AM, AphaMode); -} - -/** - * @brief Return DMA2D foreground alpha mode. - * @rmtoll FGPFCCR AM LL_DMA2D_FGND_GetAlphaMode - * @param DMA2Dx DMA2D Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA2D_ALPHA_MODE_NO_MODIF - * @arg @ref LL_DMA2D_ALPHA_MODE_REPLACE - * @arg @ref LL_DMA2D_ALPHA_MODE_COMBINE - */ -__STATIC_INLINE uint32_t LL_DMA2D_FGND_GetAlphaMode(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->FGPFCCR, DMA2D_FGPFCCR_AM)); -} - -/** - * @brief Set DMA2D foreground alpha value, expressed on 8 bits ([7:0] bits). - * @rmtoll FGPFCCR ALPHA LL_DMA2D_FGND_SetAlpha - * @param DMA2Dx DMA2D Instance - * @param Alpha Value between Min_Data=0 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_FGND_SetAlpha(DMA2D_TypeDef *DMA2Dx, uint32_t Alpha) -{ - MODIFY_REG(DMA2Dx->FGPFCCR, DMA2D_FGPFCCR_ALPHA, (Alpha << DMA2D_FGPFCCR_ALPHA_Pos)); -} - -/** - * @brief Return DMA2D foreground alpha value, expressed on 8 bits ([7:0] bits). - * @rmtoll FGPFCCR ALPHA LL_DMA2D_FGND_GetAlpha - * @param DMA2Dx DMA2D Instance - * @retval Alpha value between Min_Data=0 and Max_Data=0xFF - */ -__STATIC_INLINE uint32_t LL_DMA2D_FGND_GetAlpha(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->FGPFCCR, DMA2D_FGPFCCR_ALPHA) >> DMA2D_FGPFCCR_ALPHA_Pos); -} - - -/** - * @brief Set DMA2D foreground line offset, expressed on 14 bits ([13:0] bits). - * @rmtoll FGOR LO LL_DMA2D_FGND_SetLineOffset - * @param DMA2Dx DMA2D Instance - * @param LineOffset Value between Min_Data=0 and Max_Data=0x3FF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_FGND_SetLineOffset(DMA2D_TypeDef *DMA2Dx, uint32_t LineOffset) -{ - MODIFY_REG(DMA2Dx->FGOR, DMA2D_FGOR_LO, LineOffset); -} - -/** - * @brief Return DMA2D foreground line offset, expressed on 14 bits ([13:0] bits). - * @rmtoll FGOR LO LL_DMA2D_FGND_GetLineOffset - * @param DMA2Dx DMA2D Instance - * @retval Foreground line offset value between Min_Data=0 and Max_Data=0x3FF - */ -__STATIC_INLINE uint32_t LL_DMA2D_FGND_GetLineOffset(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->FGOR, DMA2D_FGOR_LO)); -} - -/** - * @brief Set DMA2D foreground color values, expressed on 24 bits ([23:0] bits). - * @rmtoll FGCOLR RED LL_DMA2D_FGND_SetColor - * @rmtoll FGCOLR GREEN LL_DMA2D_FGND_SetColor - * @rmtoll FGCOLR BLUE LL_DMA2D_FGND_SetColor - * @param DMA2Dx DMA2D Instance - * @param Red Value between Min_Data=0 and Max_Data=0xFF - * @param Green Value between Min_Data=0 and Max_Data=0xFF - * @param Blue Value between Min_Data=0 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_FGND_SetColor(DMA2D_TypeDef *DMA2Dx, uint32_t Red, uint32_t Green, uint32_t Blue) -{ - MODIFY_REG(DMA2Dx->FGCOLR, (DMA2D_FGCOLR_RED | DMA2D_FGCOLR_GREEN | DMA2D_FGCOLR_BLUE), \ - ((Red << DMA2D_FGCOLR_RED_Pos) | (Green << DMA2D_FGCOLR_GREEN_Pos) | Blue)); -} - -/** - * @brief Set DMA2D foreground red color value, expressed on 8 bits ([7:0] bits). - * @rmtoll FGCOLR RED LL_DMA2D_FGND_SetRedColor - * @param DMA2Dx DMA2D Instance - * @param Red Value between Min_Data=0 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_FGND_SetRedColor(DMA2D_TypeDef *DMA2Dx, uint32_t Red) -{ - MODIFY_REG(DMA2Dx->FGCOLR, DMA2D_FGCOLR_RED, (Red << DMA2D_FGCOLR_RED_Pos)); -} - -/** - * @brief Return DMA2D foreground red color value, expressed on 8 bits ([7:0] bits). - * @rmtoll FGCOLR RED LL_DMA2D_FGND_GetRedColor - * @param DMA2Dx DMA2D Instance - * @retval Red color value between Min_Data=0 and Max_Data=0xFF - */ -__STATIC_INLINE uint32_t LL_DMA2D_FGND_GetRedColor(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->FGCOLR, DMA2D_FGCOLR_RED) >> DMA2D_FGCOLR_RED_Pos); -} - -/** - * @brief Set DMA2D foreground green color value, expressed on 8 bits ([7:0] bits). - * @rmtoll FGCOLR GREEN LL_DMA2D_FGND_SetGreenColor - * @param DMA2Dx DMA2D Instance - * @param Green Value between Min_Data=0 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_FGND_SetGreenColor(DMA2D_TypeDef *DMA2Dx, uint32_t Green) -{ - MODIFY_REG(DMA2Dx->FGCOLR, DMA2D_FGCOLR_GREEN, (Green << DMA2D_FGCOLR_GREEN_Pos)); -} - -/** - * @brief Return DMA2D foreground green color value, expressed on 8 bits ([7:0] bits). - * @rmtoll FGCOLR GREEN LL_DMA2D_FGND_GetGreenColor - * @param DMA2Dx DMA2D Instance - * @retval Green color value between Min_Data=0 and Max_Data=0xFF - */ -__STATIC_INLINE uint32_t LL_DMA2D_FGND_GetGreenColor(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->FGCOLR, DMA2D_FGCOLR_GREEN) >> DMA2D_FGCOLR_GREEN_Pos); -} - -/** - * @brief Set DMA2D foreground blue color value, expressed on 8 bits ([7:0] bits). - * @rmtoll FGCOLR BLUE LL_DMA2D_FGND_SetBlueColor - * @param DMA2Dx DMA2D Instance - * @param Blue Value between Min_Data=0 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_FGND_SetBlueColor(DMA2D_TypeDef *DMA2Dx, uint32_t Blue) -{ - MODIFY_REG(DMA2Dx->FGCOLR, DMA2D_FGCOLR_BLUE, Blue); -} - -/** - * @brief Return DMA2D foreground blue color value, expressed on 8 bits ([7:0] bits). - * @rmtoll FGCOLR BLUE LL_DMA2D_FGND_GetBlueColor - * @param DMA2Dx DMA2D Instance - * @retval Blue color value between Min_Data=0 and Max_Data=0xFF - */ -__STATIC_INLINE uint32_t LL_DMA2D_FGND_GetBlueColor(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->FGCOLR, DMA2D_FGCOLR_BLUE)); -} - -/** - * @brief Set DMA2D foreground CLUT memory address, expressed on 32 bits ([31:0] bits). - * @rmtoll FGCMAR MA LL_DMA2D_FGND_SetCLUTMemAddr - * @param DMA2Dx DMA2D Instance - * @param CLUTMemoryAddress Value between Min_Data=0 and Max_Data=0xFFFFFFFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_FGND_SetCLUTMemAddr(DMA2D_TypeDef *DMA2Dx, uint32_t CLUTMemoryAddress) -{ - LL_DMA2D_WriteReg(DMA2Dx, FGCMAR, CLUTMemoryAddress); -} - -/** - * @brief Get DMA2D foreground CLUT memory address, expressed on 32 bits ([31:0] bits). - * @rmtoll FGCMAR MA LL_DMA2D_FGND_GetCLUTMemAddr - * @param DMA2Dx DMA2D Instance - * @retval Foreground CLUT memory address value between Min_Data=0 and Max_Data=0xFFFFFFFF - */ -__STATIC_INLINE uint32_t LL_DMA2D_FGND_GetCLUTMemAddr(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(LL_DMA2D_ReadReg(DMA2Dx, FGCMAR)); -} - -/** - * @brief Set DMA2D foreground CLUT size, expressed on 8 bits ([7:0] bits). - * @rmtoll FGPFCCR CS LL_DMA2D_FGND_SetCLUTSize - * @param DMA2Dx DMA2D Instance - * @param CLUTSize Value between Min_Data=0 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_FGND_SetCLUTSize(DMA2D_TypeDef *DMA2Dx, uint32_t CLUTSize) -{ - MODIFY_REG(DMA2Dx->FGPFCCR, DMA2D_FGPFCCR_CS, (CLUTSize << DMA2D_FGPFCCR_CS_Pos)); -} - -/** - * @brief Get DMA2D foreground CLUT size, expressed on 8 bits ([7:0] bits). - * @rmtoll FGPFCCR CS LL_DMA2D_FGND_GetCLUTSize - * @param DMA2Dx DMA2D Instance - * @retval Foreground CLUT size value between Min_Data=0 and Max_Data=0xFF - */ -__STATIC_INLINE uint32_t LL_DMA2D_FGND_GetCLUTSize(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->FGPFCCR, DMA2D_FGPFCCR_CS) >> DMA2D_FGPFCCR_CS_Pos); -} - -/** - * @brief Set DMA2D foreground CLUT color mode. - * @rmtoll FGPFCCR CCM LL_DMA2D_FGND_SetCLUTColorMode - * @param DMA2Dx DMA2D Instance - * @param CLUTColorMode This parameter can be one of the following values: - * @arg @ref LL_DMA2D_CLUT_COLOR_MODE_ARGB8888 - * @arg @ref LL_DMA2D_CLUT_COLOR_MODE_RGB888 - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_FGND_SetCLUTColorMode(DMA2D_TypeDef *DMA2Dx, uint32_t CLUTColorMode) -{ - MODIFY_REG(DMA2Dx->FGPFCCR, DMA2D_FGPFCCR_CCM, CLUTColorMode); -} - -/** - * @brief Return DMA2D foreground CLUT color mode. - * @rmtoll FGPFCCR CCM LL_DMA2D_FGND_GetCLUTColorMode - * @param DMA2Dx DMA2D Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA2D_CLUT_COLOR_MODE_ARGB8888 - * @arg @ref LL_DMA2D_CLUT_COLOR_MODE_RGB888 - */ -__STATIC_INLINE uint32_t LL_DMA2D_FGND_GetCLUTColorMode(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->FGPFCCR, DMA2D_FGPFCCR_CCM)); -} - -/** - * @} - */ - -/** @defgroup DMA2D_LL_EF_BGND_Configuration Background Configuration Functions - * @{ - */ - -/** - * @brief Set DMA2D background memory address, expressed on 32 bits ([31:0] bits). - * @rmtoll BGMAR MA LL_DMA2D_BGND_SetMemAddr - * @param DMA2Dx DMA2D Instance - * @param MemoryAddress Value between Min_Data=0 and Max_Data=0xFFFFFFFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_BGND_SetMemAddr(DMA2D_TypeDef *DMA2Dx, uint32_t MemoryAddress) -{ - LL_DMA2D_WriteReg(DMA2Dx, BGMAR, MemoryAddress); -} - -/** - * @brief Get DMA2D background memory address, expressed on 32 bits ([31:0] bits). - * @rmtoll BGMAR MA LL_DMA2D_BGND_GetMemAddr - * @param DMA2Dx DMA2D Instance - * @retval Background memory address value between Min_Data=0 and Max_Data=0xFFFFFFFF - */ -__STATIC_INLINE uint32_t LL_DMA2D_BGND_GetMemAddr(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(LL_DMA2D_ReadReg(DMA2Dx, BGMAR)); -} - -/** - * @brief Enable DMA2D background CLUT loading. - * @rmtoll BGPFCCR START LL_DMA2D_BGND_EnableCLUTLoad - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_BGND_EnableCLUTLoad(DMA2D_TypeDef *DMA2Dx) -{ - SET_BIT(DMA2Dx->BGPFCCR, DMA2D_BGPFCCR_START); -} - -/** - * @brief Indicate if DMA2D background CLUT loading is enabled. - * @rmtoll BGPFCCR START LL_DMA2D_BGND_IsEnabledCLUTLoad - * @param DMA2Dx DMA2D Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA2D_BGND_IsEnabledCLUTLoad(DMA2D_TypeDef *DMA2Dx) -{ - return ((READ_BIT(DMA2Dx->BGPFCCR, DMA2D_BGPFCCR_START) == (DMA2D_BGPFCCR_START)) ? 1UL : 0UL); -} - -/** - * @brief Set DMA2D background color mode. - * @rmtoll BGPFCCR CM LL_DMA2D_BGND_SetColorMode - * @param DMA2Dx DMA2D Instance - * @param ColorMode This parameter can be one of the following values: - * @arg @ref LL_DMA2D_INPUT_MODE_ARGB8888 - * @arg @ref LL_DMA2D_INPUT_MODE_RGB888 - * @arg @ref LL_DMA2D_INPUT_MODE_RGB565 - * @arg @ref LL_DMA2D_INPUT_MODE_ARGB1555 - * @arg @ref LL_DMA2D_INPUT_MODE_ARGB4444 - * @arg @ref LL_DMA2D_INPUT_MODE_L8 - * @arg @ref LL_DMA2D_INPUT_MODE_AL44 - * @arg @ref LL_DMA2D_INPUT_MODE_AL88 - * @arg @ref LL_DMA2D_INPUT_MODE_L4 - * @arg @ref LL_DMA2D_INPUT_MODE_A8 - * @arg @ref LL_DMA2D_INPUT_MODE_A4 - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_BGND_SetColorMode(DMA2D_TypeDef *DMA2Dx, uint32_t ColorMode) -{ - MODIFY_REG(DMA2Dx->BGPFCCR, DMA2D_BGPFCCR_CM, ColorMode); -} - -/** - * @brief Return DMA2D background color mode. - * @rmtoll BGPFCCR CM LL_DMA2D_BGND_GetColorMode - * @param DMA2Dx DMA2D Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA2D_INPUT_MODE_ARGB8888 - * @arg @ref LL_DMA2D_INPUT_MODE_RGB888 - * @arg @ref LL_DMA2D_INPUT_MODE_RGB565 - * @arg @ref LL_DMA2D_INPUT_MODE_ARGB1555 - * @arg @ref LL_DMA2D_INPUT_MODE_ARGB4444 - * @arg @ref LL_DMA2D_INPUT_MODE_L8 - * @arg @ref LL_DMA2D_INPUT_MODE_AL44 - * @arg @ref LL_DMA2D_INPUT_MODE_AL88 - * @arg @ref LL_DMA2D_INPUT_MODE_L4 - * @arg @ref LL_DMA2D_INPUT_MODE_A8 - * @arg @ref LL_DMA2D_INPUT_MODE_A4 - */ -__STATIC_INLINE uint32_t LL_DMA2D_BGND_GetColorMode(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->BGPFCCR, DMA2D_BGPFCCR_CM)); -} - -/** - * @brief Set DMA2D background alpha mode. - * @rmtoll BGPFCCR AM LL_DMA2D_BGND_SetAlphaMode - * @param DMA2Dx DMA2D Instance - * @param AphaMode This parameter can be one of the following values: - * @arg @ref LL_DMA2D_ALPHA_MODE_NO_MODIF - * @arg @ref LL_DMA2D_ALPHA_MODE_REPLACE - * @arg @ref LL_DMA2D_ALPHA_MODE_COMBINE - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_BGND_SetAlphaMode(DMA2D_TypeDef *DMA2Dx, uint32_t AphaMode) -{ - MODIFY_REG(DMA2Dx->BGPFCCR, DMA2D_BGPFCCR_AM, AphaMode); -} - -/** - * @brief Return DMA2D background alpha mode. - * @rmtoll BGPFCCR AM LL_DMA2D_BGND_GetAlphaMode - * @param DMA2Dx DMA2D Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA2D_ALPHA_MODE_NO_MODIF - * @arg @ref LL_DMA2D_ALPHA_MODE_REPLACE - * @arg @ref LL_DMA2D_ALPHA_MODE_COMBINE - */ -__STATIC_INLINE uint32_t LL_DMA2D_BGND_GetAlphaMode(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->BGPFCCR, DMA2D_BGPFCCR_AM)); -} - -/** - * @brief Set DMA2D background alpha value, expressed on 8 bits ([7:0] bits). - * @rmtoll BGPFCCR ALPHA LL_DMA2D_BGND_SetAlpha - * @param DMA2Dx DMA2D Instance - * @param Alpha Value between Min_Data=0 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_BGND_SetAlpha(DMA2D_TypeDef *DMA2Dx, uint32_t Alpha) -{ - MODIFY_REG(DMA2Dx->BGPFCCR, DMA2D_BGPFCCR_ALPHA, (Alpha << DMA2D_BGPFCCR_ALPHA_Pos)); -} - -/** - * @brief Return DMA2D background alpha value, expressed on 8 bits ([7:0] bits). - * @rmtoll BGPFCCR ALPHA LL_DMA2D_BGND_GetAlpha - * @param DMA2Dx DMA2D Instance - * @retval Alpha value between Min_Data=0 and Max_Data=0xFF - */ -__STATIC_INLINE uint32_t LL_DMA2D_BGND_GetAlpha(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->BGPFCCR, DMA2D_BGPFCCR_ALPHA) >> DMA2D_BGPFCCR_ALPHA_Pos); -} - - -/** - * @brief Set DMA2D background line offset, expressed on 14 bits ([13:0] bits). - * @rmtoll BGOR LO LL_DMA2D_BGND_SetLineOffset - * @param DMA2Dx DMA2D Instance - * @param LineOffset Value between Min_Data=0 and Max_Data=0x3FF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_BGND_SetLineOffset(DMA2D_TypeDef *DMA2Dx, uint32_t LineOffset) -{ - MODIFY_REG(DMA2Dx->BGOR, DMA2D_BGOR_LO, LineOffset); -} - -/** - * @brief Return DMA2D background line offset, expressed on 14 bits ([13:0] bits). - * @rmtoll BGOR LO LL_DMA2D_BGND_GetLineOffset - * @param DMA2Dx DMA2D Instance - * @retval Background line offset value between Min_Data=0 and Max_Data=0x3FF - */ -__STATIC_INLINE uint32_t LL_DMA2D_BGND_GetLineOffset(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->BGOR, DMA2D_BGOR_LO)); -} - -/** - * @brief Set DMA2D background color values, expressed on 24 bits ([23:0] bits). - * @rmtoll BGCOLR RED LL_DMA2D_BGND_SetColor - * @rmtoll BGCOLR GREEN LL_DMA2D_BGND_SetColor - * @rmtoll BGCOLR BLUE LL_DMA2D_BGND_SetColor - * @param DMA2Dx DMA2D Instance - * @param Red Value between Min_Data=0 and Max_Data=0xFF - * @param Green Value between Min_Data=0 and Max_Data=0xFF - * @param Blue Value between Min_Data=0 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_BGND_SetColor(DMA2D_TypeDef *DMA2Dx, uint32_t Red, uint32_t Green, uint32_t Blue) -{ - MODIFY_REG(DMA2Dx->BGCOLR, (DMA2D_BGCOLR_RED | DMA2D_BGCOLR_GREEN | DMA2D_BGCOLR_BLUE), \ - ((Red << DMA2D_BGCOLR_RED_Pos) | (Green << DMA2D_BGCOLR_GREEN_Pos) | Blue)); -} - -/** - * @brief Set DMA2D background red color value, expressed on 8 bits ([7:0] bits). - * @rmtoll BGCOLR RED LL_DMA2D_BGND_SetRedColor - * @param DMA2Dx DMA2D Instance - * @param Red Value between Min_Data=0 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_BGND_SetRedColor(DMA2D_TypeDef *DMA2Dx, uint32_t Red) -{ - MODIFY_REG(DMA2Dx->BGCOLR, DMA2D_BGCOLR_RED, (Red << DMA2D_BGCOLR_RED_Pos)); -} - -/** - * @brief Return DMA2D background red color value, expressed on 8 bits ([7:0] bits). - * @rmtoll BGCOLR RED LL_DMA2D_BGND_GetRedColor - * @param DMA2Dx DMA2D Instance - * @retval Red color value between Min_Data=0 and Max_Data=0xFF - */ -__STATIC_INLINE uint32_t LL_DMA2D_BGND_GetRedColor(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->BGCOLR, DMA2D_BGCOLR_RED) >> DMA2D_BGCOLR_RED_Pos); -} - -/** - * @brief Set DMA2D background green color value, expressed on 8 bits ([7:0] bits). - * @rmtoll BGCOLR GREEN LL_DMA2D_BGND_SetGreenColor - * @param DMA2Dx DMA2D Instance - * @param Green Value between Min_Data=0 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_BGND_SetGreenColor(DMA2D_TypeDef *DMA2Dx, uint32_t Green) -{ - MODIFY_REG(DMA2Dx->BGCOLR, DMA2D_BGCOLR_GREEN, (Green << DMA2D_BGCOLR_GREEN_Pos)); -} - -/** - * @brief Return DMA2D background green color value, expressed on 8 bits ([7:0] bits). - * @rmtoll BGCOLR GREEN LL_DMA2D_BGND_GetGreenColor - * @param DMA2Dx DMA2D Instance - * @retval Green color value between Min_Data=0 and Max_Data=0xFF - */ -__STATIC_INLINE uint32_t LL_DMA2D_BGND_GetGreenColor(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->BGCOLR, DMA2D_BGCOLR_GREEN) >> DMA2D_BGCOLR_GREEN_Pos); -} - -/** - * @brief Set DMA2D background blue color value, expressed on 8 bits ([7:0] bits). - * @rmtoll BGCOLR BLUE LL_DMA2D_BGND_SetBlueColor - * @param DMA2Dx DMA2D Instance - * @param Blue Value between Min_Data=0 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_BGND_SetBlueColor(DMA2D_TypeDef *DMA2Dx, uint32_t Blue) -{ - MODIFY_REG(DMA2Dx->BGCOLR, DMA2D_BGCOLR_BLUE, Blue); -} - -/** - * @brief Return DMA2D background blue color value, expressed on 8 bits ([7:0] bits). - * @rmtoll BGCOLR BLUE LL_DMA2D_BGND_GetBlueColor - * @param DMA2Dx DMA2D Instance - * @retval Blue color value between Min_Data=0 and Max_Data=0xFF - */ -__STATIC_INLINE uint32_t LL_DMA2D_BGND_GetBlueColor(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->BGCOLR, DMA2D_BGCOLR_BLUE)); -} - -/** - * @brief Set DMA2D background CLUT memory address, expressed on 32 bits ([31:0] bits). - * @rmtoll BGCMAR MA LL_DMA2D_BGND_SetCLUTMemAddr - * @param DMA2Dx DMA2D Instance - * @param CLUTMemoryAddress Value between Min_Data=0 and Max_Data=0xFFFFFFFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_BGND_SetCLUTMemAddr(DMA2D_TypeDef *DMA2Dx, uint32_t CLUTMemoryAddress) -{ - LL_DMA2D_WriteReg(DMA2Dx, BGCMAR, CLUTMemoryAddress); -} - -/** - * @brief Get DMA2D background CLUT memory address, expressed on 32 bits ([31:0] bits). - * @rmtoll BGCMAR MA LL_DMA2D_BGND_GetCLUTMemAddr - * @param DMA2Dx DMA2D Instance - * @retval Background CLUT memory address value between Min_Data=0 and Max_Data=0xFFFFFFFF - */ -__STATIC_INLINE uint32_t LL_DMA2D_BGND_GetCLUTMemAddr(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(LL_DMA2D_ReadReg(DMA2Dx, BGCMAR)); -} - -/** - * @brief Set DMA2D background CLUT size, expressed on 8 bits ([7:0] bits). - * @rmtoll BGPFCCR CS LL_DMA2D_BGND_SetCLUTSize - * @param DMA2Dx DMA2D Instance - * @param CLUTSize Value between Min_Data=0 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_BGND_SetCLUTSize(DMA2D_TypeDef *DMA2Dx, uint32_t CLUTSize) -{ - MODIFY_REG(DMA2Dx->BGPFCCR, DMA2D_BGPFCCR_CS, (CLUTSize << DMA2D_BGPFCCR_CS_Pos)); -} - -/** - * @brief Get DMA2D background CLUT size, expressed on 8 bits ([7:0] bits). - * @rmtoll BGPFCCR CS LL_DMA2D_BGND_GetCLUTSize - * @param DMA2Dx DMA2D Instance - * @retval Background CLUT size value between Min_Data=0 and Max_Data=0xFF - */ -__STATIC_INLINE uint32_t LL_DMA2D_BGND_GetCLUTSize(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->BGPFCCR, DMA2D_BGPFCCR_CS) >> DMA2D_BGPFCCR_CS_Pos); -} - -/** - * @brief Set DMA2D background CLUT color mode. - * @rmtoll BGPFCCR CCM LL_DMA2D_BGND_SetCLUTColorMode - * @param DMA2Dx DMA2D Instance - * @param CLUTColorMode This parameter can be one of the following values: - * @arg @ref LL_DMA2D_CLUT_COLOR_MODE_ARGB8888 - * @arg @ref LL_DMA2D_CLUT_COLOR_MODE_RGB888 - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_BGND_SetCLUTColorMode(DMA2D_TypeDef *DMA2Dx, uint32_t CLUTColorMode) -{ - MODIFY_REG(DMA2Dx->BGPFCCR, DMA2D_BGPFCCR_CCM, CLUTColorMode); -} - -/** - * @brief Return DMA2D background CLUT color mode. - * @rmtoll BGPFCCR CCM LL_DMA2D_BGND_GetCLUTColorMode - * @param DMA2Dx DMA2D Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_DMA2D_CLUT_COLOR_MODE_ARGB8888 - * @arg @ref LL_DMA2D_CLUT_COLOR_MODE_RGB888 - */ -__STATIC_INLINE uint32_t LL_DMA2D_BGND_GetCLUTColorMode(DMA2D_TypeDef *DMA2Dx) -{ - return (uint32_t)(READ_BIT(DMA2Dx->BGPFCCR, DMA2D_BGPFCCR_CCM)); -} - -/** - * @} - */ - -/** - * @} - */ - - -/** @defgroup DMA2D_LL_EF_FLAG_MANAGEMENT Flag Management - * @{ - */ - -/** - * @brief Check if the DMA2D Configuration Error Interrupt Flag is set or not - * @rmtoll ISR CEIF LL_DMA2D_IsActiveFlag_CE - * @param DMA2Dx DMA2D Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA2D_IsActiveFlag_CE(DMA2D_TypeDef *DMA2Dx) -{ - return ((READ_BIT(DMA2Dx->ISR, DMA2D_ISR_CEIF) == (DMA2D_ISR_CEIF)) ? 1UL : 0UL); -} - -/** - * @brief Check if the DMA2D CLUT Transfer Complete Interrupt Flag is set or not - * @rmtoll ISR CTCIF LL_DMA2D_IsActiveFlag_CTC - * @param DMA2Dx DMA2D Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA2D_IsActiveFlag_CTC(DMA2D_TypeDef *DMA2Dx) -{ - return ((READ_BIT(DMA2Dx->ISR, DMA2D_ISR_CTCIF) == (DMA2D_ISR_CTCIF)) ? 1UL : 0UL); -} - -/** - * @brief Check if the DMA2D CLUT Access Error Interrupt Flag is set or not - * @rmtoll ISR CAEIF LL_DMA2D_IsActiveFlag_CAE - * @param DMA2Dx DMA2D Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA2D_IsActiveFlag_CAE(DMA2D_TypeDef *DMA2Dx) -{ - return ((READ_BIT(DMA2Dx->ISR, DMA2D_ISR_CAEIF) == (DMA2D_ISR_CAEIF)) ? 1UL : 0UL); -} - -/** - * @brief Check if the DMA2D Transfer Watermark Interrupt Flag is set or not - * @rmtoll ISR TWIF LL_DMA2D_IsActiveFlag_TW - * @param DMA2Dx DMA2D Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA2D_IsActiveFlag_TW(DMA2D_TypeDef *DMA2Dx) -{ - return ((READ_BIT(DMA2Dx->ISR, DMA2D_ISR_TWIF) == (DMA2D_ISR_TWIF)) ? 1UL : 0UL); -} - -/** - * @brief Check if the DMA2D Transfer Complete Interrupt Flag is set or not - * @rmtoll ISR TCIF LL_DMA2D_IsActiveFlag_TC - * @param DMA2Dx DMA2D Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA2D_IsActiveFlag_TC(DMA2D_TypeDef *DMA2Dx) -{ - return ((READ_BIT(DMA2Dx->ISR, DMA2D_ISR_TCIF) == (DMA2D_ISR_TCIF)) ? 1UL : 0UL); -} - -/** - * @brief Check if the DMA2D Transfer Error Interrupt Flag is set or not - * @rmtoll ISR TEIF LL_DMA2D_IsActiveFlag_TE - * @param DMA2Dx DMA2D Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA2D_IsActiveFlag_TE(DMA2D_TypeDef *DMA2Dx) -{ - return ((READ_BIT(DMA2Dx->ISR, DMA2D_ISR_TEIF) == (DMA2D_ISR_TEIF)) ? 1UL : 0UL); -} - -/** - * @brief Clear DMA2D Configuration Error Interrupt Flag - * @rmtoll IFCR CCEIF LL_DMA2D_ClearFlag_CE - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_ClearFlag_CE(DMA2D_TypeDef *DMA2Dx) -{ - WRITE_REG(DMA2Dx->IFCR, DMA2D_IFCR_CCEIF); -} - -/** - * @brief Clear DMA2D CLUT Transfer Complete Interrupt Flag - * @rmtoll IFCR CCTCIF LL_DMA2D_ClearFlag_CTC - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_ClearFlag_CTC(DMA2D_TypeDef *DMA2Dx) -{ - WRITE_REG(DMA2Dx->IFCR, DMA2D_IFCR_CCTCIF); -} - -/** - * @brief Clear DMA2D CLUT Access Error Interrupt Flag - * @rmtoll IFCR CAECIF LL_DMA2D_ClearFlag_CAE - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_ClearFlag_CAE(DMA2D_TypeDef *DMA2Dx) -{ - WRITE_REG(DMA2Dx->IFCR, DMA2D_IFCR_CAECIF); -} - -/** - * @brief Clear DMA2D Transfer Watermark Interrupt Flag - * @rmtoll IFCR CTWIF LL_DMA2D_ClearFlag_TW - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_ClearFlag_TW(DMA2D_TypeDef *DMA2Dx) -{ - WRITE_REG(DMA2Dx->IFCR, DMA2D_IFCR_CTWIF); -} - -/** - * @brief Clear DMA2D Transfer Complete Interrupt Flag - * @rmtoll IFCR CTCIF LL_DMA2D_ClearFlag_TC - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_ClearFlag_TC(DMA2D_TypeDef *DMA2Dx) -{ - WRITE_REG(DMA2Dx->IFCR, DMA2D_IFCR_CTCIF); -} - -/** - * @brief Clear DMA2D Transfer Error Interrupt Flag - * @rmtoll IFCR CTEIF LL_DMA2D_ClearFlag_TE - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_ClearFlag_TE(DMA2D_TypeDef *DMA2Dx) -{ - WRITE_REG(DMA2Dx->IFCR, DMA2D_IFCR_CTEIF); -} - -/** - * @} - */ - -/** @defgroup DMA2D_LL_EF_IT_MANAGEMENT Interruption Management - * @{ - */ - -/** - * @brief Enable Configuration Error Interrupt - * @rmtoll CR CEIE LL_DMA2D_EnableIT_CE - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_EnableIT_CE(DMA2D_TypeDef *DMA2Dx) -{ - SET_BIT(DMA2Dx->CR, DMA2D_CR_CEIE); -} - -/** - * @brief Enable CLUT Transfer Complete Interrupt - * @rmtoll CR CTCIE LL_DMA2D_EnableIT_CTC - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_EnableIT_CTC(DMA2D_TypeDef *DMA2Dx) -{ - SET_BIT(DMA2Dx->CR, DMA2D_CR_CTCIE); -} - -/** - * @brief Enable CLUT Access Error Interrupt - * @rmtoll CR CAEIE LL_DMA2D_EnableIT_CAE - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_EnableIT_CAE(DMA2D_TypeDef *DMA2Dx) -{ - SET_BIT(DMA2Dx->CR, DMA2D_CR_CAEIE); -} - -/** - * @brief Enable Transfer Watermark Interrupt - * @rmtoll CR TWIE LL_DMA2D_EnableIT_TW - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_EnableIT_TW(DMA2D_TypeDef *DMA2Dx) -{ - SET_BIT(DMA2Dx->CR, DMA2D_CR_TWIE); -} - -/** - * @brief Enable Transfer Complete Interrupt - * @rmtoll CR TCIE LL_DMA2D_EnableIT_TC - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_EnableIT_TC(DMA2D_TypeDef *DMA2Dx) -{ - SET_BIT(DMA2Dx->CR, DMA2D_CR_TCIE); -} - -/** - * @brief Enable Transfer Error Interrupt - * @rmtoll CR TEIE LL_DMA2D_EnableIT_TE - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_EnableIT_TE(DMA2D_TypeDef *DMA2Dx) -{ - SET_BIT(DMA2Dx->CR, DMA2D_CR_TEIE); -} - -/** - * @brief Disable Configuration Error Interrupt - * @rmtoll CR CEIE LL_DMA2D_DisableIT_CE - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_DisableIT_CE(DMA2D_TypeDef *DMA2Dx) -{ - CLEAR_BIT(DMA2Dx->CR, DMA2D_CR_CEIE); -} - -/** - * @brief Disable CLUT Transfer Complete Interrupt - * @rmtoll CR CTCIE LL_DMA2D_DisableIT_CTC - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_DisableIT_CTC(DMA2D_TypeDef *DMA2Dx) -{ - CLEAR_BIT(DMA2Dx->CR, DMA2D_CR_CTCIE); -} - -/** - * @brief Disable CLUT Access Error Interrupt - * @rmtoll CR CAEIE LL_DMA2D_DisableIT_CAE - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_DisableIT_CAE(DMA2D_TypeDef *DMA2Dx) -{ - CLEAR_BIT(DMA2Dx->CR, DMA2D_CR_CAEIE); -} - -/** - * @brief Disable Transfer Watermark Interrupt - * @rmtoll CR TWIE LL_DMA2D_DisableIT_TW - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_DisableIT_TW(DMA2D_TypeDef *DMA2Dx) -{ - CLEAR_BIT(DMA2Dx->CR, DMA2D_CR_TWIE); -} - -/** - * @brief Disable Transfer Complete Interrupt - * @rmtoll CR TCIE LL_DMA2D_DisableIT_TC - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_DisableIT_TC(DMA2D_TypeDef *DMA2Dx) -{ - CLEAR_BIT(DMA2Dx->CR, DMA2D_CR_TCIE); -} - -/** - * @brief Disable Transfer Error Interrupt - * @rmtoll CR TEIE LL_DMA2D_DisableIT_TE - * @param DMA2Dx DMA2D Instance - * @retval None - */ -__STATIC_INLINE void LL_DMA2D_DisableIT_TE(DMA2D_TypeDef *DMA2Dx) -{ - CLEAR_BIT(DMA2Dx->CR, DMA2D_CR_TEIE); -} - -/** - * @brief Check if the DMA2D Configuration Error interrupt source is enabled or disabled. - * @rmtoll CR CEIE LL_DMA2D_IsEnabledIT_CE - * @param DMA2Dx DMA2D Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA2D_IsEnabledIT_CE(DMA2D_TypeDef *DMA2Dx) -{ - return ((READ_BIT(DMA2Dx->CR, DMA2D_CR_CEIE) == (DMA2D_CR_CEIE)) ? 1UL : 0UL); -} - -/** - * @brief Check if the DMA2D CLUT Transfer Complete interrupt source is enabled or disabled. - * @rmtoll CR CTCIE LL_DMA2D_IsEnabledIT_CTC - * @param DMA2Dx DMA2D Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA2D_IsEnabledIT_CTC(DMA2D_TypeDef *DMA2Dx) -{ - return ((READ_BIT(DMA2Dx->CR, DMA2D_CR_CTCIE) == (DMA2D_CR_CTCIE)) ? 1UL : 0UL); -} - -/** - * @brief Check if the DMA2D CLUT Access Error interrupt source is enabled or disabled. - * @rmtoll CR CAEIE LL_DMA2D_IsEnabledIT_CAE - * @param DMA2Dx DMA2D Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA2D_IsEnabledIT_CAE(DMA2D_TypeDef *DMA2Dx) -{ - return ((READ_BIT(DMA2Dx->CR, DMA2D_CR_CAEIE) == (DMA2D_CR_CAEIE)) ? 1UL : 0UL); -} - -/** - * @brief Check if the DMA2D Transfer Watermark interrupt source is enabled or disabled. - * @rmtoll CR TWIE LL_DMA2D_IsEnabledIT_TW - * @param DMA2Dx DMA2D Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA2D_IsEnabledIT_TW(DMA2D_TypeDef *DMA2Dx) -{ - return ((READ_BIT(DMA2Dx->CR, DMA2D_CR_TWIE) == (DMA2D_CR_TWIE)) ? 1UL : 0UL); -} - -/** - * @brief Check if the DMA2D Transfer Complete interrupt source is enabled or disabled. - * @rmtoll CR TCIE LL_DMA2D_IsEnabledIT_TC - * @param DMA2Dx DMA2D Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA2D_IsEnabledIT_TC(DMA2D_TypeDef *DMA2Dx) -{ - return ((READ_BIT(DMA2Dx->CR, DMA2D_CR_TCIE) == (DMA2D_CR_TCIE)) ? 1UL : 0UL); -} - -/** - * @brief Check if the DMA2D Transfer Error interrupt source is enabled or disabled. - * @rmtoll CR TEIE LL_DMA2D_IsEnabledIT_TE - * @param DMA2Dx DMA2D Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_DMA2D_IsEnabledIT_TE(DMA2D_TypeDef *DMA2Dx) -{ - return ((READ_BIT(DMA2Dx->CR, DMA2D_CR_TEIE) == (DMA2D_CR_TEIE)) ? 1UL : 0UL); -} - - - -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup DMA2D_LL_EF_Init_Functions Initialization and De-initialization Functions - * @{ - */ - -ErrorStatus LL_DMA2D_DeInit(DMA2D_TypeDef *DMA2Dx); -ErrorStatus LL_DMA2D_Init(DMA2D_TypeDef *DMA2Dx, LL_DMA2D_InitTypeDef *DMA2D_InitStruct); -void LL_DMA2D_StructInit(LL_DMA2D_InitTypeDef *DMA2D_InitStruct); -void LL_DMA2D_ConfigLayer(DMA2D_TypeDef *DMA2Dx, LL_DMA2D_LayerCfgTypeDef *DMA2D_LayerCfg, uint32_t LayerIdx); -void LL_DMA2D_LayerCfgStructInit(LL_DMA2D_LayerCfgTypeDef *DMA2D_LayerCfg); -void LL_DMA2D_ConfigOutputColor(DMA2D_TypeDef *DMA2Dx, LL_DMA2D_ColorTypeDef *DMA2D_ColorStruct); -uint32_t LL_DMA2D_GetOutputBlueColor(DMA2D_TypeDef *DMA2Dx, uint32_t ColorMode); -uint32_t LL_DMA2D_GetOutputGreenColor(DMA2D_TypeDef *DMA2Dx, uint32_t ColorMode); -uint32_t LL_DMA2D_GetOutputRedColor(DMA2D_TypeDef *DMA2Dx, uint32_t ColorMode); -uint32_t LL_DMA2D_GetOutputAlphaColor(DMA2D_TypeDef *DMA2Dx, uint32_t ColorMode); -void LL_DMA2D_ConfigSize(DMA2D_TypeDef *DMA2Dx, uint32_t NbrOfLines, uint32_t NbrOfPixelsPerLines); - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* defined (DMA2D) */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_LL_DMA2D_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_exti.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_exti.h deleted file mode 100644 index c816e26..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_exti.h +++ /dev/null @@ -1,956 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_exti.h - * @author MCD Application Team - * @brief Header file of EXTI LL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_LL_EXTI_H -#define __STM32F4xx_LL_EXTI_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (EXTI) - -/** @defgroup EXTI_LL EXTI - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private Macros ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup EXTI_LL_Private_Macros EXTI Private Macros - * @{ - */ -/** - * @} - */ -#endif /*USE_FULL_LL_DRIVER*/ -/* Exported types ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup EXTI_LL_ES_INIT EXTI Exported Init structure - * @{ - */ -typedef struct -{ - - uint32_t Line_0_31; /*!< Specifies the EXTI lines to be enabled or disabled for Lines in range 0 to 31 - This parameter can be any combination of @ref EXTI_LL_EC_LINE */ - - FunctionalState LineCommand; /*!< Specifies the new state of the selected EXTI lines. - This parameter can be set either to ENABLE or DISABLE */ - - uint8_t Mode; /*!< Specifies the mode for the EXTI lines. - This parameter can be a value of @ref EXTI_LL_EC_MODE. */ - - uint8_t Trigger; /*!< Specifies the trigger signal active edge for the EXTI lines. - This parameter can be a value of @ref EXTI_LL_EC_TRIGGER. */ -} LL_EXTI_InitTypeDef; - -/** - * @} - */ -#endif /*USE_FULL_LL_DRIVER*/ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup EXTI_LL_Exported_Constants EXTI Exported Constants - * @{ - */ - -/** @defgroup EXTI_LL_EC_LINE LINE - * @{ - */ -#define LL_EXTI_LINE_0 EXTI_IMR_IM0 /*!< Extended line 0 */ -#define LL_EXTI_LINE_1 EXTI_IMR_IM1 /*!< Extended line 1 */ -#define LL_EXTI_LINE_2 EXTI_IMR_IM2 /*!< Extended line 2 */ -#define LL_EXTI_LINE_3 EXTI_IMR_IM3 /*!< Extended line 3 */ -#define LL_EXTI_LINE_4 EXTI_IMR_IM4 /*!< Extended line 4 */ -#define LL_EXTI_LINE_5 EXTI_IMR_IM5 /*!< Extended line 5 */ -#define LL_EXTI_LINE_6 EXTI_IMR_IM6 /*!< Extended line 6 */ -#define LL_EXTI_LINE_7 EXTI_IMR_IM7 /*!< Extended line 7 */ -#define LL_EXTI_LINE_8 EXTI_IMR_IM8 /*!< Extended line 8 */ -#define LL_EXTI_LINE_9 EXTI_IMR_IM9 /*!< Extended line 9 */ -#define LL_EXTI_LINE_10 EXTI_IMR_IM10 /*!< Extended line 10 */ -#define LL_EXTI_LINE_11 EXTI_IMR_IM11 /*!< Extended line 11 */ -#define LL_EXTI_LINE_12 EXTI_IMR_IM12 /*!< Extended line 12 */ -#define LL_EXTI_LINE_13 EXTI_IMR_IM13 /*!< Extended line 13 */ -#define LL_EXTI_LINE_14 EXTI_IMR_IM14 /*!< Extended line 14 */ -#define LL_EXTI_LINE_15 EXTI_IMR_IM15 /*!< Extended line 15 */ -#if defined(EXTI_IMR_IM16) -#define LL_EXTI_LINE_16 EXTI_IMR_IM16 /*!< Extended line 16 */ -#endif -#define LL_EXTI_LINE_17 EXTI_IMR_IM17 /*!< Extended line 17 */ -#if defined(EXTI_IMR_IM18) -#define LL_EXTI_LINE_18 EXTI_IMR_IM18 /*!< Extended line 18 */ -#endif -#define LL_EXTI_LINE_19 EXTI_IMR_IM19 /*!< Extended line 19 */ -#if defined(EXTI_IMR_IM20) -#define LL_EXTI_LINE_20 EXTI_IMR_IM20 /*!< Extended line 20 */ -#endif -#if defined(EXTI_IMR_IM21) -#define LL_EXTI_LINE_21 EXTI_IMR_IM21 /*!< Extended line 21 */ -#endif -#if defined(EXTI_IMR_IM22) -#define LL_EXTI_LINE_22 EXTI_IMR_IM22 /*!< Extended line 22 */ -#endif -#if defined(EXTI_IMR_IM23) -#define LL_EXTI_LINE_23 EXTI_IMR_IM23 /*!< Extended line 23 */ -#endif -#if defined(EXTI_IMR_IM24) -#define LL_EXTI_LINE_24 EXTI_IMR_IM24 /*!< Extended line 24 */ -#endif -#if defined(EXTI_IMR_IM25) -#define LL_EXTI_LINE_25 EXTI_IMR_IM25 /*!< Extended line 25 */ -#endif -#if defined(EXTI_IMR_IM26) -#define LL_EXTI_LINE_26 EXTI_IMR_IM26 /*!< Extended line 26 */ -#endif -#if defined(EXTI_IMR_IM27) -#define LL_EXTI_LINE_27 EXTI_IMR_IM27 /*!< Extended line 27 */ -#endif -#if defined(EXTI_IMR_IM28) -#define LL_EXTI_LINE_28 EXTI_IMR_IM28 /*!< Extended line 28 */ -#endif -#if defined(EXTI_IMR_IM29) -#define LL_EXTI_LINE_29 EXTI_IMR_IM29 /*!< Extended line 29 */ -#endif -#if defined(EXTI_IMR_IM30) -#define LL_EXTI_LINE_30 EXTI_IMR_IM30 /*!< Extended line 30 */ -#endif -#if defined(EXTI_IMR_IM31) -#define LL_EXTI_LINE_31 EXTI_IMR_IM31 /*!< Extended line 31 */ -#endif -#define LL_EXTI_LINE_ALL_0_31 EXTI_IMR_IM /*!< All Extended line not reserved*/ - - -#define LL_EXTI_LINE_ALL ((uint32_t)0xFFFFFFFFU) /*!< All Extended line */ - -#if defined(USE_FULL_LL_DRIVER) -#define LL_EXTI_LINE_NONE ((uint32_t)0x00000000U) /*!< None Extended line */ -#endif /*USE_FULL_LL_DRIVER*/ - -/** - * @} - */ -#if defined(USE_FULL_LL_DRIVER) - -/** @defgroup EXTI_LL_EC_MODE Mode - * @{ - */ -#define LL_EXTI_MODE_IT ((uint8_t)0x00U) /*!< Interrupt Mode */ -#define LL_EXTI_MODE_EVENT ((uint8_t)0x01U) /*!< Event Mode */ -#define LL_EXTI_MODE_IT_EVENT ((uint8_t)0x02U) /*!< Interrupt & Event Mode */ -/** - * @} - */ - -/** @defgroup EXTI_LL_EC_TRIGGER Edge Trigger - * @{ - */ -#define LL_EXTI_TRIGGER_NONE ((uint8_t)0x00U) /*!< No Trigger Mode */ -#define LL_EXTI_TRIGGER_RISING ((uint8_t)0x01U) /*!< Trigger Rising Mode */ -#define LL_EXTI_TRIGGER_FALLING ((uint8_t)0x02U) /*!< Trigger Falling Mode */ -#define LL_EXTI_TRIGGER_RISING_FALLING ((uint8_t)0x03U) /*!< Trigger Rising & Falling Mode */ - -/** - * @} - */ - - -#endif /*USE_FULL_LL_DRIVER*/ - - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup EXTI_LL_Exported_Macros EXTI Exported Macros - * @{ - */ - -/** @defgroup EXTI_LL_EM_WRITE_READ Common Write and read registers Macros - * @{ - */ - -/** - * @brief Write a value in EXTI register - * @param __REG__ Register to be written - * @param __VALUE__ Value to be written in the register - * @retval None - */ -#define LL_EXTI_WriteReg(__REG__, __VALUE__) WRITE_REG(EXTI->__REG__, (__VALUE__)) - -/** - * @brief Read a value in EXTI register - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_EXTI_ReadReg(__REG__) READ_REG(EXTI->__REG__) -/** - * @} - */ - - -/** - * @} - */ - - - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup EXTI_LL_Exported_Functions EXTI Exported Functions - * @{ - */ -/** @defgroup EXTI_LL_EF_IT_Management IT_Management - * @{ - */ - -/** - * @brief Enable ExtiLine Interrupt request for Lines in range 0 to 31 - * @note The reset value for the direct or internal lines (see RM) - * is set to 1 in order to enable the interrupt by default. - * Bits are set automatically at Power on. - * @rmtoll IMR IMx LL_EXTI_EnableIT_0_31 - * @param ExtiLine This parameter can be one of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_17 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @arg @ref LL_EXTI_LINE_23(*) - * @arg @ref LL_EXTI_LINE_ALL_0_31 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval None - */ -__STATIC_INLINE void LL_EXTI_EnableIT_0_31(uint32_t ExtiLine) -{ - SET_BIT(EXTI->IMR, ExtiLine); -} - -/** - * @brief Disable ExtiLine Interrupt request for Lines in range 0 to 31 - * @note The reset value for the direct or internal lines (see RM) - * is set to 1 in order to enable the interrupt by default. - * Bits are set automatically at Power on. - * @rmtoll IMR IMx LL_EXTI_DisableIT_0_31 - * @param ExtiLine This parameter can be one of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_17 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @arg @ref LL_EXTI_LINE_23(*) - * @arg @ref LL_EXTI_LINE_ALL_0_31 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval None - */ -__STATIC_INLINE void LL_EXTI_DisableIT_0_31(uint32_t ExtiLine) -{ - CLEAR_BIT(EXTI->IMR, ExtiLine); -} - - -/** - * @brief Indicate if ExtiLine Interrupt request is enabled for Lines in range 0 to 31 - * @note The reset value for the direct or internal lines (see RM) - * is set to 1 in order to enable the interrupt by default. - * Bits are set automatically at Power on. - * @rmtoll IMR IMx LL_EXTI_IsEnabledIT_0_31 - * @param ExtiLine This parameter can be one of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_17 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @arg @ref LL_EXTI_LINE_23(*) - * @arg @ref LL_EXTI_LINE_ALL_0_31 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_EXTI_IsEnabledIT_0_31(uint32_t ExtiLine) -{ - return (READ_BIT(EXTI->IMR, ExtiLine) == (ExtiLine)); -} - - -/** - * @} - */ - -/** @defgroup EXTI_LL_EF_Event_Management Event_Management - * @{ - */ - -/** - * @brief Enable ExtiLine Event request for Lines in range 0 to 31 - * @rmtoll EMR EMx LL_EXTI_EnableEvent_0_31 - * @param ExtiLine This parameter can be one of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_17 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @arg @ref LL_EXTI_LINE_23(*) - * @arg @ref LL_EXTI_LINE_ALL_0_31 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval None - */ -__STATIC_INLINE void LL_EXTI_EnableEvent_0_31(uint32_t ExtiLine) -{ - SET_BIT(EXTI->EMR, ExtiLine); - -} - - -/** - * @brief Disable ExtiLine Event request for Lines in range 0 to 31 - * @rmtoll EMR EMx LL_EXTI_DisableEvent_0_31 - * @param ExtiLine This parameter can be one of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_17 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @arg @ref LL_EXTI_LINE_23(*) - * @arg @ref LL_EXTI_LINE_ALL_0_31 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval None - */ -__STATIC_INLINE void LL_EXTI_DisableEvent_0_31(uint32_t ExtiLine) -{ - CLEAR_BIT(EXTI->EMR, ExtiLine); -} - - -/** - * @brief Indicate if ExtiLine Event request is enabled for Lines in range 0 to 31 - * @rmtoll EMR EMx LL_EXTI_IsEnabledEvent_0_31 - * @param ExtiLine This parameter can be one of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_17 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @arg @ref LL_EXTI_LINE_23(*) - * @arg @ref LL_EXTI_LINE_ALL_0_31 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_EXTI_IsEnabledEvent_0_31(uint32_t ExtiLine) -{ - return (READ_BIT(EXTI->EMR, ExtiLine) == (ExtiLine)); - -} - - -/** - * @} - */ - -/** @defgroup EXTI_LL_EF_Rising_Trigger_Management Rising_Trigger_Management - * @{ - */ - -/** - * @brief Enable ExtiLine Rising Edge Trigger for Lines in range 0 to 31 - * @note The configurable wakeup lines are edge-triggered. No glitch must be - * generated on these lines. If a rising edge on a configurable interrupt - * line occurs during a write operation in the EXTI_RTSR register, the - * pending bit is not set. - * Rising and falling edge triggers can be set for - * the same interrupt line. In this case, both generate a trigger - * condition. - * @rmtoll RTSR RTx LL_EXTI_EnableRisingTrig_0_31 - * @param ExtiLine This parameter can be a combination of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval None - */ -__STATIC_INLINE void LL_EXTI_EnableRisingTrig_0_31(uint32_t ExtiLine) -{ - SET_BIT(EXTI->RTSR, ExtiLine); - -} - - -/** - * @brief Disable ExtiLine Rising Edge Trigger for Lines in range 0 to 31 - * @note The configurable wakeup lines are edge-triggered. No glitch must be - * generated on these lines. If a rising edge on a configurable interrupt - * line occurs during a write operation in the EXTI_RTSR register, the - * pending bit is not set. - * Rising and falling edge triggers can be set for - * the same interrupt line. In this case, both generate a trigger - * condition. - * @rmtoll RTSR RTx LL_EXTI_DisableRisingTrig_0_31 - * @param ExtiLine This parameter can be a combination of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval None - */ -__STATIC_INLINE void LL_EXTI_DisableRisingTrig_0_31(uint32_t ExtiLine) -{ - CLEAR_BIT(EXTI->RTSR, ExtiLine); - -} - - -/** - * @brief Check if rising edge trigger is enabled for Lines in range 0 to 31 - * @rmtoll RTSR RTx LL_EXTI_IsEnabledRisingTrig_0_31 - * @param ExtiLine This parameter can be a combination of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_EXTI_IsEnabledRisingTrig_0_31(uint32_t ExtiLine) -{ - return (READ_BIT(EXTI->RTSR, ExtiLine) == (ExtiLine)); -} - - -/** - * @} - */ - -/** @defgroup EXTI_LL_EF_Falling_Trigger_Management Falling_Trigger_Management - * @{ - */ - -/** - * @brief Enable ExtiLine Falling Edge Trigger for Lines in range 0 to 31 - * @note The configurable wakeup lines are edge-triggered. No glitch must be - * generated on these lines. If a falling edge on a configurable interrupt - * line occurs during a write operation in the EXTI_FTSR register, the - * pending bit is not set. - * Rising and falling edge triggers can be set for - * the same interrupt line. In this case, both generate a trigger - * condition. - * @rmtoll FTSR FTx LL_EXTI_EnableFallingTrig_0_31 - * @param ExtiLine This parameter can be a combination of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval None - */ -__STATIC_INLINE void LL_EXTI_EnableFallingTrig_0_31(uint32_t ExtiLine) -{ - SET_BIT(EXTI->FTSR, ExtiLine); -} - - -/** - * @brief Disable ExtiLine Falling Edge Trigger for Lines in range 0 to 31 - * @note The configurable wakeup lines are edge-triggered. No glitch must be - * generated on these lines. If a Falling edge on a configurable interrupt - * line occurs during a write operation in the EXTI_FTSR register, the - * pending bit is not set. - * Rising and falling edge triggers can be set for the same interrupt line. - * In this case, both generate a trigger condition. - * @rmtoll FTSR FTx LL_EXTI_DisableFallingTrig_0_31 - * @param ExtiLine This parameter can be a combination of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval None - */ -__STATIC_INLINE void LL_EXTI_DisableFallingTrig_0_31(uint32_t ExtiLine) -{ - CLEAR_BIT(EXTI->FTSR, ExtiLine); -} - - -/** - * @brief Check if falling edge trigger is enabled for Lines in range 0 to 31 - * @rmtoll FTSR FTx LL_EXTI_IsEnabledFallingTrig_0_31 - * @param ExtiLine This parameter can be a combination of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_EXTI_IsEnabledFallingTrig_0_31(uint32_t ExtiLine) -{ - return (READ_BIT(EXTI->FTSR, ExtiLine) == (ExtiLine)); -} - - -/** - * @} - */ - -/** @defgroup EXTI_LL_EF_Software_Interrupt_Management Software_Interrupt_Management - * @{ - */ - -/** - * @brief Generate a software Interrupt Event for Lines in range 0 to 31 - * @note If the interrupt is enabled on this line in the EXTI_IMR, writing a 1 to - * this bit when it is at '0' sets the corresponding pending bit in EXTI_PR - * resulting in an interrupt request generation. - * This bit is cleared by clearing the corresponding bit in the EXTI_PR - * register (by writing a 1 into the bit) - * @rmtoll SWIER SWIx LL_EXTI_GenerateSWI_0_31 - * @param ExtiLine This parameter can be a combination of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval None - */ -__STATIC_INLINE void LL_EXTI_GenerateSWI_0_31(uint32_t ExtiLine) -{ - SET_BIT(EXTI->SWIER, ExtiLine); -} - - -/** - * @} - */ - -/** @defgroup EXTI_LL_EF_Flag_Management Flag_Management - * @{ - */ - -/** - * @brief Check if the ExtLine Flag is set or not for Lines in range 0 to 31 - * @note This bit is set when the selected edge event arrives on the interrupt - * line. This bit is cleared by writing a 1 to the bit. - * @rmtoll PR PIFx LL_EXTI_IsActiveFlag_0_31 - * @param ExtiLine This parameter can be a combination of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_EXTI_IsActiveFlag_0_31(uint32_t ExtiLine) -{ - return (READ_BIT(EXTI->PR, ExtiLine) == (ExtiLine)); -} - - -/** - * @brief Read ExtLine Combination Flag for Lines in range 0 to 31 - * @note This bit is set when the selected edge event arrives on the interrupt - * line. This bit is cleared by writing a 1 to the bit. - * @rmtoll PR PIFx LL_EXTI_ReadFlag_0_31 - * @param ExtiLine This parameter can be a combination of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval @note This bit is set when the selected edge event arrives on the interrupt - */ -__STATIC_INLINE uint32_t LL_EXTI_ReadFlag_0_31(uint32_t ExtiLine) -{ - return (uint32_t)(READ_BIT(EXTI->PR, ExtiLine)); -} - - -/** - * @brief Clear ExtLine Flags for Lines in range 0 to 31 - * @note This bit is set when the selected edge event arrives on the interrupt - * line. This bit is cleared by writing a 1 to the bit. - * @rmtoll PR PIFx LL_EXTI_ClearFlag_0_31 - * @param ExtiLine This parameter can be a combination of the following values: - * @arg @ref LL_EXTI_LINE_0 - * @arg @ref LL_EXTI_LINE_1 - * @arg @ref LL_EXTI_LINE_2 - * @arg @ref LL_EXTI_LINE_3 - * @arg @ref LL_EXTI_LINE_4 - * @arg @ref LL_EXTI_LINE_5 - * @arg @ref LL_EXTI_LINE_6 - * @arg @ref LL_EXTI_LINE_7 - * @arg @ref LL_EXTI_LINE_8 - * @arg @ref LL_EXTI_LINE_9 - * @arg @ref LL_EXTI_LINE_10 - * @arg @ref LL_EXTI_LINE_11 - * @arg @ref LL_EXTI_LINE_12 - * @arg @ref LL_EXTI_LINE_13 - * @arg @ref LL_EXTI_LINE_14 - * @arg @ref LL_EXTI_LINE_15 - * @arg @ref LL_EXTI_LINE_16 - * @arg @ref LL_EXTI_LINE_18 - * @arg @ref LL_EXTI_LINE_19(*) - * @arg @ref LL_EXTI_LINE_20(*) - * @arg @ref LL_EXTI_LINE_21 - * @arg @ref LL_EXTI_LINE_22 - * @note (*): Available in some devices - * @note Please check each device line mapping for EXTI Line availability - * @retval None - */ -__STATIC_INLINE void LL_EXTI_ClearFlag_0_31(uint32_t ExtiLine) -{ - WRITE_REG(EXTI->PR, ExtiLine); -} - - -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup EXTI_LL_EF_Init Initialization and de-initialization functions - * @{ - */ - -uint32_t LL_EXTI_Init(LL_EXTI_InitTypeDef *EXTI_InitStruct); -uint32_t LL_EXTI_DeInit(void); -void LL_EXTI_StructInit(LL_EXTI_InitTypeDef *EXTI_InitStruct); - - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* EXTI */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_EXTI_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_fmc.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_fmc.h deleted file mode 100644 index 71e7c74..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_fmc.h +++ /dev/null @@ -1,1403 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_fmc.h - * @author MCD Application Team - * @brief Header file of FMC HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_LL_FMC_H -#define __STM32F4xx_LL_FMC_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup FMC_LL - * @{ - */ -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -/* Private types -------------------------------------------------------------*/ -/** @defgroup FMC_LL_Private_Types FMC Private Types - * @{ - */ - -/** - * @brief FMC NORSRAM Configuration Structure definition - */ -typedef struct -{ - uint32_t NSBank; /*!< Specifies the NORSRAM memory device that will be used. - This parameter can be a value of @ref FMC_NORSRAM_Bank */ - - uint32_t DataAddressMux; /*!< Specifies whether the address and data values are - multiplexed on the data bus or not. - This parameter can be a value of @ref FMC_Data_Address_Bus_Multiplexing */ - - uint32_t MemoryType; /*!< Specifies the type of external memory attached to - the corresponding memory device. - This parameter can be a value of @ref FMC_Memory_Type */ - - uint32_t MemoryDataWidth; /*!< Specifies the external memory device width. - This parameter can be a value of @ref FMC_NORSRAM_Data_Width */ - - uint32_t BurstAccessMode; /*!< Enables or disables the burst access mode for Flash memory, - valid only with synchronous burst Flash memories. - This parameter can be a value of @ref FMC_Burst_Access_Mode */ - - uint32_t WaitSignalPolarity; /*!< Specifies the wait signal polarity, valid only when accessing - the Flash memory in burst mode. - This parameter can be a value of @ref FMC_Wait_Signal_Polarity */ - - uint32_t WrapMode; /*!< Enables or disables the Wrapped burst access mode for Flash - memory, valid only when accessing Flash memories in burst mode. - This parameter can be a value of @ref FMC_Wrap_Mode - This mode is not available for the STM32F446/467/479xx devices */ - - uint32_t WaitSignalActive; /*!< Specifies if the wait signal is asserted by the memory one - clock cycle before the wait state or during the wait state, - valid only when accessing memories in burst mode. - This parameter can be a value of @ref FMC_Wait_Timing */ - - uint32_t WriteOperation; /*!< Enables or disables the write operation in the selected device by the FMC. - This parameter can be a value of @ref FMC_Write_Operation */ - - uint32_t WaitSignal; /*!< Enables or disables the wait state insertion via wait - signal, valid for Flash memory access in burst mode. - This parameter can be a value of @ref FMC_Wait_Signal */ - - uint32_t ExtendedMode; /*!< Enables or disables the extended mode. - This parameter can be a value of @ref FMC_Extended_Mode */ - - uint32_t AsynchronousWait; /*!< Enables or disables wait signal during asynchronous transfers, - valid only with asynchronous Flash memories. - This parameter can be a value of @ref FMC_AsynchronousWait */ - - uint32_t WriteBurst; /*!< Enables or disables the write burst operation. - This parameter can be a value of @ref FMC_Write_Burst */ - - uint32_t ContinuousClock; /*!< Enables or disables the FMC clock output to external memory devices. - This parameter is only enabled through the FMC_BCR1 register, and don't care - through FMC_BCR2..4 registers. - This parameter can be a value of @ref FMC_Continous_Clock */ - - uint32_t WriteFifo; /*!< Enables or disables the write FIFO used by the FMC controller. - This parameter is only enabled through the FMC_BCR1 register, and don't care - through FMC_BCR2..4 registers. - This parameter can be a value of @ref FMC_Write_FIFO - This mode is available only for the STM32F446/469/479xx devices */ - - uint32_t PageSize; /*!< Specifies the memory page size. - This parameter can be a value of @ref FMC_Page_Size */ -}FMC_NORSRAM_InitTypeDef; - -/** - * @brief FMC NORSRAM Timing parameters structure definition - */ -typedef struct -{ - uint32_t AddressSetupTime; /*!< Defines the number of HCLK cycles to configure - the duration of the address setup time. - This parameter can be a value between Min_Data = 0 and Max_Data = 15. - @note This parameter is not used with synchronous NOR Flash memories. */ - - uint32_t AddressHoldTime; /*!< Defines the number of HCLK cycles to configure - the duration of the address hold time. - This parameter can be a value between Min_Data = 1 and Max_Data = 15. - @note This parameter is not used with synchronous NOR Flash memories. */ - - uint32_t DataSetupTime; /*!< Defines the number of HCLK cycles to configure - the duration of the data setup time. - This parameter can be a value between Min_Data = 1 and Max_Data = 255. - @note This parameter is used for SRAMs, ROMs and asynchronous multiplexed - NOR Flash memories. */ - - uint32_t BusTurnAroundDuration; /*!< Defines the number of HCLK cycles to configure - the duration of the bus turnaround. - This parameter can be a value between Min_Data = 0 and Max_Data = 15. - @note This parameter is only used for multiplexed NOR Flash memories. */ - - uint32_t CLKDivision; /*!< Defines the period of CLK clock output signal, expressed in number of - HCLK cycles. This parameter can be a value between Min_Data = 2 and Max_Data = 16. - @note This parameter is not used for asynchronous NOR Flash, SRAM or ROM - accesses. */ - - uint32_t DataLatency; /*!< Defines the number of memory clock cycles to issue - to the memory before getting the first data. - The parameter value depends on the memory type as shown below: - - It must be set to 0 in case of a CRAM - - It is don't care in asynchronous NOR, SRAM or ROM accesses - - It may assume a value between Min_Data = 2 and Max_Data = 17 in NOR Flash memories - with synchronous burst mode enable */ - - uint32_t AccessMode; /*!< Specifies the asynchronous access mode. - This parameter can be a value of @ref FMC_Access_Mode */ -}FMC_NORSRAM_TimingTypeDef; - -/** - * @brief FMC NAND Configuration Structure definition - */ -typedef struct -{ - uint32_t NandBank; /*!< Specifies the NAND memory device that will be used. - This parameter can be a value of @ref FMC_NAND_Bank */ - - uint32_t Waitfeature; /*!< Enables or disables the Wait feature for the NAND Memory device. - This parameter can be any value of @ref FMC_Wait_feature */ - - uint32_t MemoryDataWidth; /*!< Specifies the external memory device width. - This parameter can be any value of @ref FMC_NAND_Data_Width */ - - uint32_t EccComputation; /*!< Enables or disables the ECC computation. - This parameter can be any value of @ref FMC_ECC */ - - uint32_t ECCPageSize; /*!< Defines the page size for the extended ECC. - This parameter can be any value of @ref FMC_ECC_Page_Size */ - - uint32_t TCLRSetupTime; /*!< Defines the number of HCLK cycles to configure the - delay between CLE low and RE low. - This parameter can be a value between Min_Data = 0 and Max_Data = 255 */ - - uint32_t TARSetupTime; /*!< Defines the number of HCLK cycles to configure the - delay between ALE low and RE low. - This parameter can be a number between Min_Data = 0 and Max_Data = 255 */ -}FMC_NAND_InitTypeDef; - -/** - * @brief FMC NAND/PCCARD Timing parameters structure definition - */ -typedef struct -{ - uint32_t SetupTime; /*!< Defines the number of HCLK cycles to setup address before - the command assertion for NAND-Flash read or write access - to common/Attribute or I/O memory space (depending on - the memory space timing to be configured). - This parameter can be a value between Min_Data = 0 and Max_Data = 255 */ - - uint32_t WaitSetupTime; /*!< Defines the minimum number of HCLK cycles to assert the - command for NAND-Flash read or write access to - common/Attribute or I/O memory space (depending on the - memory space timing to be configured). - This parameter can be a number between Min_Data = 0 and Max_Data = 255 */ - - uint32_t HoldSetupTime; /*!< Defines the number of HCLK clock cycles to hold address - (and data for write access) after the command de-assertion - for NAND-Flash read or write access to common/Attribute - or I/O memory space (depending on the memory space timing - to be configured). - This parameter can be a number between Min_Data = 0 and Max_Data = 255 */ - - uint32_t HiZSetupTime; /*!< Defines the number of HCLK clock cycles during which the - data bus is kept in HiZ after the start of a NAND-Flash - write access to common/Attribute or I/O memory space (depending - on the memory space timing to be configured). - This parameter can be a number between Min_Data = 0 and Max_Data = 255 */ -}FMC_NAND_PCC_TimingTypeDef; - -/** - * @brief FMC NAND Configuration Structure definition - */ -typedef struct -{ - uint32_t Waitfeature; /*!< Enables or disables the Wait feature for the PCCARD Memory device. - This parameter can be any value of @ref FMC_Wait_feature */ - - uint32_t TCLRSetupTime; /*!< Defines the number of HCLK cycles to configure the - delay between CLE low and RE low. - This parameter can be a value between Min_Data = 0 and Max_Data = 255 */ - - uint32_t TARSetupTime; /*!< Defines the number of HCLK cycles to configure the - delay between ALE low and RE low. - This parameter can be a number between Min_Data = 0 and Max_Data = 255 */ -}FMC_PCCARD_InitTypeDef; - -/** - * @brief FMC SDRAM Configuration Structure definition - */ -typedef struct -{ - uint32_t SDBank; /*!< Specifies the SDRAM memory device that will be used. - This parameter can be a value of @ref FMC_SDRAM_Bank */ - - uint32_t ColumnBitsNumber; /*!< Defines the number of bits of column address. - This parameter can be a value of @ref FMC_SDRAM_Column_Bits_number. */ - - uint32_t RowBitsNumber; /*!< Defines the number of bits of column address. - This parameter can be a value of @ref FMC_SDRAM_Row_Bits_number. */ - - uint32_t MemoryDataWidth; /*!< Defines the memory device width. - This parameter can be a value of @ref FMC_SDRAM_Memory_Bus_Width. */ - - uint32_t InternalBankNumber; /*!< Defines the number of the device's internal banks. - This parameter can be of @ref FMC_SDRAM_Internal_Banks_Number. */ - - uint32_t CASLatency; /*!< Defines the SDRAM CAS latency in number of memory clock cycles. - This parameter can be a value of @ref FMC_SDRAM_CAS_Latency. */ - - uint32_t WriteProtection; /*!< Enables the SDRAM device to be accessed in write mode. - This parameter can be a value of @ref FMC_SDRAM_Write_Protection. */ - - uint32_t SDClockPeriod; /*!< Define the SDRAM Clock Period for both SDRAM devices and they allow - to disable the clock before changing frequency. - This parameter can be a value of @ref FMC_SDRAM_Clock_Period. */ - - uint32_t ReadBurst; /*!< This bit enable the SDRAM controller to anticipate the next read - commands during the CAS latency and stores data in the Read FIFO. - This parameter can be a value of @ref FMC_SDRAM_Read_Burst. */ - - uint32_t ReadPipeDelay; /*!< Define the delay in system clock cycles on read data path. - This parameter can be a value of @ref FMC_SDRAM_Read_Pipe_Delay. */ -}FMC_SDRAM_InitTypeDef; - -/** - * @brief FMC SDRAM Timing parameters structure definition - */ -typedef struct -{ - uint32_t LoadToActiveDelay; /*!< Defines the delay between a Load Mode Register command and - an active or Refresh command in number of memory clock cycles. - This parameter can be a value between Min_Data = 1 and Max_Data = 16 */ - - uint32_t ExitSelfRefreshDelay; /*!< Defines the delay from releasing the self refresh command to - issuing the Activate command in number of memory clock cycles. - This parameter can be a value between Min_Data = 1 and Max_Data = 16 */ - - uint32_t SelfRefreshTime; /*!< Defines the minimum Self Refresh period in number of memory clock - cycles. - This parameter can be a value between Min_Data = 1 and Max_Data = 16 */ - - uint32_t RowCycleDelay; /*!< Defines the delay between the Refresh command and the Activate command - and the delay between two consecutive Refresh commands in number of - memory clock cycles. - This parameter can be a value between Min_Data = 1 and Max_Data = 16 */ - - uint32_t WriteRecoveryTime; /*!< Defines the Write recovery Time in number of memory clock cycles. - This parameter can be a value between Min_Data = 1 and Max_Data = 16 */ - - uint32_t RPDelay; /*!< Defines the delay between a Precharge Command and an other command - in number of memory clock cycles. - This parameter can be a value between Min_Data = 1 and Max_Data = 16 */ - - uint32_t RCDDelay; /*!< Defines the delay between the Activate Command and a Read/Write - command in number of memory clock cycles. - This parameter can be a value between Min_Data = 1 and Max_Data = 16 */ -}FMC_SDRAM_TimingTypeDef; - -/** - * @brief SDRAM command parameters structure definition - */ -typedef struct -{ - uint32_t CommandMode; /*!< Defines the command issued to the SDRAM device. - This parameter can be a value of @ref FMC_SDRAM_Command_Mode. */ - - uint32_t CommandTarget; /*!< Defines which device (1 or 2) the command will be issued to. - This parameter can be a value of @ref FMC_SDRAM_Command_Target. */ - - uint32_t AutoRefreshNumber; /*!< Defines the number of consecutive auto refresh command issued - in auto refresh mode. - This parameter can be a value between Min_Data = 1 and Max_Data = 16 */ - uint32_t ModeRegisterDefinition; /*!< Defines the SDRAM Mode register content */ -}FMC_SDRAM_CommandTypeDef; -/** - * @} - */ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup FMC_LL_Private_Constants FMC Private Constants - * @{ - */ - -/** @defgroup FMC_LL_NOR_SRAM_Controller FMC NOR/SRAM Controller - * @{ - */ -/** @defgroup FMC_NORSRAM_Bank FMC NOR/SRAM Bank - * @{ - */ -#define FMC_NORSRAM_BANK1 0x00000000U -#define FMC_NORSRAM_BANK2 0x00000002U -#define FMC_NORSRAM_BANK3 0x00000004U -#define FMC_NORSRAM_BANK4 0x00000006U -/** - * @} - */ - -/** @defgroup FMC_Data_Address_Bus_Multiplexing FMC Data Address Bus Multiplexing - * @{ - */ -#define FMC_DATA_ADDRESS_MUX_DISABLE 0x00000000U -#define FMC_DATA_ADDRESS_MUX_ENABLE 0x00000002U -/** - * @} - */ - -/** @defgroup FMC_Memory_Type FMC Memory Type - * @{ - */ -#define FMC_MEMORY_TYPE_SRAM 0x00000000U -#define FMC_MEMORY_TYPE_PSRAM 0x00000004U -#define FMC_MEMORY_TYPE_NOR 0x00000008U -/** - * @} - */ - -/** @defgroup FMC_NORSRAM_Data_Width FMC NORSRAM Data Width - * @{ - */ -#define FMC_NORSRAM_MEM_BUS_WIDTH_8 0x00000000U -#define FMC_NORSRAM_MEM_BUS_WIDTH_16 0x00000010U -#define FMC_NORSRAM_MEM_BUS_WIDTH_32 0x00000020U -/** - * @} - */ - -/** @defgroup FMC_NORSRAM_Flash_Access FMC NOR/SRAM Flash Access - * @{ - */ -#define FMC_NORSRAM_FLASH_ACCESS_ENABLE 0x00000040U -#define FMC_NORSRAM_FLASH_ACCESS_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup FMC_Burst_Access_Mode FMC Burst Access Mode - * @{ - */ -#define FMC_BURST_ACCESS_MODE_DISABLE 0x00000000U -#define FMC_BURST_ACCESS_MODE_ENABLE 0x00000100U -/** - * @} - */ - -/** @defgroup FMC_Wait_Signal_Polarity FMC Wait Signal Polarity - * @{ - */ -#define FMC_WAIT_SIGNAL_POLARITY_LOW 0x00000000U -#define FMC_WAIT_SIGNAL_POLARITY_HIGH 0x00000200U -/** - * @} - */ - -/** @defgroup FMC_Wrap_Mode FMC Wrap Mode - * @{ - */ -/** @note This mode is not available for the STM32F446/469/479xx devices - */ -#define FMC_WRAP_MODE_DISABLE 0x00000000U -#define FMC_WRAP_MODE_ENABLE 0x00000400U -/** - * @} - */ - -/** @defgroup FMC_Wait_Timing FMC Wait Timing - * @{ - */ -#define FMC_WAIT_TIMING_BEFORE_WS 0x00000000U -#define FMC_WAIT_TIMING_DURING_WS 0x00000800U -/** - * @} - */ - -/** @defgroup FMC_Write_Operation FMC Write Operation - * @{ - */ -#define FMC_WRITE_OPERATION_DISABLE 0x00000000U -#define FMC_WRITE_OPERATION_ENABLE 0x00001000U -/** - * @} - */ - -/** @defgroup FMC_Wait_Signal FMC Wait Signal - * @{ - */ -#define FMC_WAIT_SIGNAL_DISABLE 0x00000000U -#define FMC_WAIT_SIGNAL_ENABLE 0x00002000U -/** - * @} - */ - -/** @defgroup FMC_Extended_Mode FMC Extended Mode - * @{ - */ -#define FMC_EXTENDED_MODE_DISABLE 0x00000000U -#define FMC_EXTENDED_MODE_ENABLE 0x00004000U -/** - * @} - */ - -/** @defgroup FMC_AsynchronousWait FMC Asynchronous Wait - * @{ - */ -#define FMC_ASYNCHRONOUS_WAIT_DISABLE 0x00000000U -#define FMC_ASYNCHRONOUS_WAIT_ENABLE 0x00008000U -/** - * @} - */ - -/** @defgroup FMC_Page_Size FMC Page Size - * @{ - */ -#define FMC_PAGE_SIZE_NONE 0x00000000U -#define FMC_PAGE_SIZE_128 ((uint32_t)FMC_BCR1_CPSIZE_0) -#define FMC_PAGE_SIZE_256 ((uint32_t)FMC_BCR1_CPSIZE_1) -#define FMC_PAGE_SIZE_512 ((uint32_t)(FMC_BCR1_CPSIZE_0 | FMC_BCR1_CPSIZE_1)) -#define FMC_PAGE_SIZE_1024 ((uint32_t)FMC_BCR1_CPSIZE_2) -/** - * @} - */ - -/** @defgroup FMC_Write_FIFO FMC Write FIFO - * @note These values are available only for the STM32F446/469/479xx devices. - * @{ - */ -#define FMC_WRITE_FIFO_DISABLE ((uint32_t)FMC_BCR1_WFDIS) -#define FMC_WRITE_FIFO_ENABLE 0x00000000U -/** - * @} - */ - -/** @defgroup FMC_Write_Burst FMC Write Burst - * @{ - */ -#define FMC_WRITE_BURST_DISABLE 0x00000000U -#define FMC_WRITE_BURST_ENABLE 0x00080000U -/** - * @} - */ - -/** @defgroup FMC_Continous_Clock FMC Continuous Clock - * @{ - */ -#define FMC_CONTINUOUS_CLOCK_SYNC_ONLY 0x00000000U -#define FMC_CONTINUOUS_CLOCK_SYNC_ASYNC 0x00100000U -/** - * @} - */ - -/** @defgroup FMC_Access_Mode FMC Access Mode - * @{ - */ -#define FMC_ACCESS_MODE_A 0x00000000U -#define FMC_ACCESS_MODE_B 0x10000000U -#define FMC_ACCESS_MODE_C 0x20000000U -#define FMC_ACCESS_MODE_D 0x30000000U -/** - * @} - */ - -/** - * @} - */ - -/** @defgroup FMC_LL_NAND_Controller FMC NAND Controller - * @{ - */ -/** @defgroup FMC_NAND_Bank FMC NAND Bank - * @{ - */ -#define FMC_NAND_BANK2 0x00000010U -#define FMC_NAND_BANK3 0x00000100U -/** - * @} - */ - -/** @defgroup FMC_Wait_feature FMC Wait feature - * @{ - */ -#define FMC_NAND_PCC_WAIT_FEATURE_DISABLE 0x00000000U -#define FMC_NAND_PCC_WAIT_FEATURE_ENABLE 0x00000002U -/** - * @} - */ - -/** @defgroup FMC_PCR_Memory_Type FMC PCR Memory Type - * @{ - */ -#define FMC_PCR_MEMORY_TYPE_PCCARD 0x00000000U -#define FMC_PCR_MEMORY_TYPE_NAND 0x00000008U -/** - * @} - */ - -/** @defgroup FMC_NAND_Data_Width FMC NAND Data Width - * @{ - */ -#define FMC_NAND_PCC_MEM_BUS_WIDTH_8 0x00000000U -#define FMC_NAND_PCC_MEM_BUS_WIDTH_16 0x00000010U -/** - * @} - */ - -/** @defgroup FMC_ECC FMC ECC - * @{ - */ -#define FMC_NAND_ECC_DISABLE 0x00000000U -#define FMC_NAND_ECC_ENABLE 0x00000040U -/** - * @} - */ - -/** @defgroup FMC_ECC_Page_Size FMC ECC Page Size - * @{ - */ -#define FMC_NAND_ECC_PAGE_SIZE_256BYTE 0x00000000U -#define FMC_NAND_ECC_PAGE_SIZE_512BYTE 0x00020000U -#define FMC_NAND_ECC_PAGE_SIZE_1024BYTE 0x00040000U -#define FMC_NAND_ECC_PAGE_SIZE_2048BYTE 0x00060000U -#define FMC_NAND_ECC_PAGE_SIZE_4096BYTE 0x00080000U -#define FMC_NAND_ECC_PAGE_SIZE_8192BYTE 0x000A0000U -/** - * @} - */ - -/** - * @} - */ - -/** @defgroup FMC_LL_SDRAM_Controller FMC SDRAM Controller - * @{ - */ -/** @defgroup FMC_SDRAM_Bank FMC SDRAM Bank - * @{ - */ -#define FMC_SDRAM_BANK1 0x00000000U -#define FMC_SDRAM_BANK2 0x00000001U -/** - * @} - */ - -/** @defgroup FMC_SDRAM_Column_Bits_number FMC SDRAM Column Bits number - * @{ - */ -#define FMC_SDRAM_COLUMN_BITS_NUM_8 0x00000000U -#define FMC_SDRAM_COLUMN_BITS_NUM_9 0x00000001U -#define FMC_SDRAM_COLUMN_BITS_NUM_10 0x00000002U -#define FMC_SDRAM_COLUMN_BITS_NUM_11 0x00000003U -/** - * @} - */ - -/** @defgroup FMC_SDRAM_Row_Bits_number FMC SDRAM Row Bits number - * @{ - */ -#define FMC_SDRAM_ROW_BITS_NUM_11 0x00000000U -#define FMC_SDRAM_ROW_BITS_NUM_12 0x00000004U -#define FMC_SDRAM_ROW_BITS_NUM_13 0x00000008U -/** - * @} - */ - -/** @defgroup FMC_SDRAM_Memory_Bus_Width FMC SDRAM Memory Bus Width - * @{ - */ -#define FMC_SDRAM_MEM_BUS_WIDTH_8 0x00000000U -#define FMC_SDRAM_MEM_BUS_WIDTH_16 0x00000010U -#define FMC_SDRAM_MEM_BUS_WIDTH_32 0x00000020U -/** - * @} - */ - -/** @defgroup FMC_SDRAM_Internal_Banks_Number FMC SDRAM Internal Banks Number - * @{ - */ -#define FMC_SDRAM_INTERN_BANKS_NUM_2 0x00000000U -#define FMC_SDRAM_INTERN_BANKS_NUM_4 0x00000040U -/** - * @} - */ - -/** @defgroup FMC_SDRAM_CAS_Latency FMC SDRAM CAS Latency - * @{ - */ -#define FMC_SDRAM_CAS_LATENCY_1 0x00000080U -#define FMC_SDRAM_CAS_LATENCY_2 0x00000100U -#define FMC_SDRAM_CAS_LATENCY_3 0x00000180U -/** - * @} - */ - -/** @defgroup FMC_SDRAM_Write_Protection FMC SDRAM Write Protection - * @{ - */ -#define FMC_SDRAM_WRITE_PROTECTION_DISABLE 0x00000000U -#define FMC_SDRAM_WRITE_PROTECTION_ENABLE 0x00000200U - -/** - * @} - */ - -/** @defgroup FMC_SDRAM_Clock_Period FMC SDRAM Clock Period - * @{ - */ -#define FMC_SDRAM_CLOCK_DISABLE 0x00000000U -#define FMC_SDRAM_CLOCK_PERIOD_2 0x00000800U -#define FMC_SDRAM_CLOCK_PERIOD_3 0x00000C00U -/** - * @} - */ - -/** @defgroup FMC_SDRAM_Read_Burst FMC SDRAM Read Burst - * @{ - */ -#define FMC_SDRAM_RBURST_DISABLE 0x00000000U -#define FMC_SDRAM_RBURST_ENABLE 0x00001000U -/** - * @} - */ - -/** @defgroup FMC_SDRAM_Read_Pipe_Delay FMC SDRAM Read Pipe Delay - * @{ - */ -#define FMC_SDRAM_RPIPE_DELAY_0 0x00000000U -#define FMC_SDRAM_RPIPE_DELAY_1 0x00002000U -#define FMC_SDRAM_RPIPE_DELAY_2 0x00004000U -/** - * @} - */ - -/** @defgroup FMC_SDRAM_Command_Mode FMC SDRAM Command Mode - * @{ - */ -#define FMC_SDRAM_CMD_NORMAL_MODE 0x00000000U -#define FMC_SDRAM_CMD_CLK_ENABLE 0x00000001U -#define FMC_SDRAM_CMD_PALL 0x00000002U -#define FMC_SDRAM_CMD_AUTOREFRESH_MODE 0x00000003U -#define FMC_SDRAM_CMD_LOAD_MODE 0x00000004U -#define FMC_SDRAM_CMD_SELFREFRESH_MODE 0x00000005U -#define FMC_SDRAM_CMD_POWERDOWN_MODE 0x00000006U -/** - * @} - */ - -/** @defgroup FMC_SDRAM_Command_Target FMC SDRAM Command Target - * @{ - */ -#define FMC_SDRAM_CMD_TARGET_BANK2 FMC_SDCMR_CTB2 -#define FMC_SDRAM_CMD_TARGET_BANK1 FMC_SDCMR_CTB1 -#define FMC_SDRAM_CMD_TARGET_BANK1_2 0x00000018U -/** - * @} - */ - -/** @defgroup FMC_SDRAM_Mode_Status FMC SDRAM Mode Status - * @{ - */ -#define FMC_SDRAM_NORMAL_MODE 0x00000000U -#define FMC_SDRAM_SELF_REFRESH_MODE FMC_SDSR_MODES1_0 -#define FMC_SDRAM_POWER_DOWN_MODE FMC_SDSR_MODES1_1 -/** - * @} - */ - -/** - * @} - */ - -/** @defgroup FMC_LL_Interrupt_definition FMC Interrupt definition - * @{ - */ -#define FMC_IT_RISING_EDGE 0x00000008U -#define FMC_IT_LEVEL 0x00000010U -#define FMC_IT_FALLING_EDGE 0x00000020U -#define FMC_IT_REFRESH_ERROR 0x00004000U -/** - * @} - */ - -/** @defgroup FMC_LL_Flag_definition FMC Flag definition - * @{ - */ -#define FMC_FLAG_RISING_EDGE 0x00000001U -#define FMC_FLAG_LEVEL 0x00000002U -#define FMC_FLAG_FALLING_EDGE 0x00000004U -#define FMC_FLAG_FEMPT 0x00000040U -#define FMC_SDRAM_FLAG_REFRESH_IT FMC_SDSR_RE -#define FMC_SDRAM_FLAG_BUSY FMC_SDSR_BUSY -#define FMC_SDRAM_FLAG_REFRESH_ERROR FMC_SDRTR_CRE -/** - * @} - */ - -/** @defgroup FMC_LL_Alias_definition FMC Alias definition - * @{ - */ -#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) - #define FMC_NAND_TypeDef FMC_Bank3_TypeDef -#else - #define FMC_NAND_TypeDef FMC_Bank2_3_TypeDef - #define FMC_PCCARD_TypeDef FMC_Bank4_TypeDef -#endif /* STM32F446xx || STM32F469xx || STM32F479xx */ - #define FMC_NORSRAM_TypeDef FMC_Bank1_TypeDef - #define FMC_NORSRAM_EXTENDED_TypeDef FMC_Bank1E_TypeDef - #define FMC_SDRAM_TypeDef FMC_Bank5_6_TypeDef - - -#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) - #define FMC_NAND_DEVICE FMC_Bank3 -#else - #define FMC_NAND_DEVICE FMC_Bank2_3 - #define FMC_PCCARD_DEVICE FMC_Bank4 -#endif /* STM32F446xx || STM32F469xx || STM32F479xx */ - #define FMC_NORSRAM_DEVICE FMC_Bank1 - #define FMC_NORSRAM_EXTENDED_DEVICE FMC_Bank1E - #define FMC_SDRAM_DEVICE FMC_Bank5_6 -/** - * @} - */ - -/** - * @} - */ - -/* Private macro -------------------------------------------------------------*/ -/** @defgroup FMC_LL_Private_Macros FMC Private Macros - * @{ - */ - -/** @defgroup FMC_LL_NOR_Macros FMC NOR/SRAM Macros - * @brief macros to handle NOR device enable/disable and read/write operations - * @{ - */ -/** - * @brief Enable the NORSRAM device access. - * @param __INSTANCE__ FMC_NORSRAM Instance - * @param __BANK__ FMC_NORSRAM Bank - * @retval None - */ -#define __FMC_NORSRAM_ENABLE(__INSTANCE__, __BANK__) ((__INSTANCE__)->BTCR[(__BANK__)] |= FMC_BCR1_MBKEN) - -/** - * @brief Disable the NORSRAM device access. - * @param __INSTANCE__ FMC_NORSRAM Instance - * @param __BANK__ FMC_NORSRAM Bank - * @retval None - */ -#define __FMC_NORSRAM_DISABLE(__INSTANCE__, __BANK__) ((__INSTANCE__)->BTCR[(__BANK__)] &= ~FMC_BCR1_MBKEN) -/** - * @} - */ - -/** @defgroup FMC_LL_NAND_Macros FMC NAND Macros - * @brief macros to handle NAND device enable/disable - * @{ - */ -#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -/** - * @brief Enable the NAND device access. - * @param __INSTANCE__ FMC_NAND Instance - * @param __BANK__ FMC_NAND Bank - * @retval None - */ -#define __FMC_NAND_ENABLE(__INSTANCE__, __BANK__) ((__INSTANCE__)->PCR |= FMC_PCR_PBKEN) - -/** - * @brief Disable the NAND device access. - * @param __INSTANCE__ FMC_NAND Instance - * @param __BANK__ FMC_NAND Bank - * @retval None - */ -#define __FMC_NAND_DISABLE(__INSTANCE__, __BANK__) ((__INSTANCE__)->PCR &= ~FMC_PCR_PBKEN) -#else /* defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) */ -/** - * @brief Enable the NAND device access. - * @param __INSTANCE__ FMC_NAND Instance - * @param __BANK__ FMC_NAND Bank - * @retval None - */ -#define __FMC_NAND_ENABLE(__INSTANCE__, __BANK__) (((__BANK__) == FMC_NAND_BANK2)? ((__INSTANCE__)->PCR2 |= FMC_PCR2_PBKEN): \ - ((__INSTANCE__)->PCR3 |= FMC_PCR3_PBKEN)) - -/** - * @brief Disable the NAND device access. - * @param __INSTANCE__ FMC_NAND Instance - * @param __BANK__ FMC_NAND Bank - * @retval None - */ -#define __FMC_NAND_DISABLE(__INSTANCE__, __BANK__) (((__BANK__) == FMC_NAND_BANK2)? ((__INSTANCE__)->PCR2 &= ~FMC_PCR2_PBKEN): \ - ((__INSTANCE__)->PCR3 &= ~FMC_PCR3_PBKEN)) - -#endif /* defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) */ -/** - * @} - */ -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) -/** @defgroup FMC_LL_PCCARD_Macros FMC PCCARD Macros - * @brief macros to handle SRAM read/write operations - * @{ - */ -/** - * @brief Enable the PCCARD device access. - * @param __INSTANCE__ FMC_PCCARD Instance - * @retval None - */ -#define __FMC_PCCARD_ENABLE(__INSTANCE__) ((__INSTANCE__)->PCR4 |= FMC_PCR4_PBKEN) - -/** - * @brief Disable the PCCARD device access. - * @param __INSTANCE__ FMC_PCCARD Instance - * @retval None - */ -#define __FMC_PCCARD_DISABLE(__INSTANCE__) ((__INSTANCE__)->PCR4 &= ~FMC_PCR4_PBKEN) -/** - * @} - */ -#endif /* defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) */ - -/** @defgroup FMC_LL_Flag_Interrupt_Macros FMC Flag&Interrupt Macros - * @brief macros to handle FMC flags and interrupts - * @{ - */ -#if defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -/** - * @brief Enable the NAND device interrupt. - * @param __INSTANCE__ FMC_NAND instance - * @param __BANK__ FMC_NAND Bank - * @param __INTERRUPT__ FMC_NAND interrupt - * This parameter can be any combination of the following values: - * @arg FMC_IT_RISING_EDGE: Interrupt rising edge. - * @arg FMC_IT_LEVEL: Interrupt level. - * @arg FMC_IT_FALLING_EDGE: Interrupt falling edge. - * @retval None - */ -#define __FMC_NAND_ENABLE_IT(__INSTANCE__, __BANK__, __INTERRUPT__) ((__INSTANCE__)->SR |= (__INTERRUPT__)) - -/** - * @brief Disable the NAND device interrupt. - * @param __INSTANCE__ FMC_NAND Instance - * @param __BANK__ FMC_NAND Bank - * @param __INTERRUPT__ FMC_NAND interrupt - * This parameter can be any combination of the following values: - * @arg FMC_IT_RISING_EDGE: Interrupt rising edge. - * @arg FMC_IT_LEVEL: Interrupt level. - * @arg FMC_IT_FALLING_EDGE: Interrupt falling edge. - * @retval None - */ -#define __FMC_NAND_DISABLE_IT(__INSTANCE__, __BANK__, __INTERRUPT__) ((__INSTANCE__)->SR &= ~(__INTERRUPT__)) - -/** - * @brief Get flag status of the NAND device. - * @param __INSTANCE__ FMC_NAND Instance - * @param __BANK__ FMC_NAND Bank - * @param __FLAG__ FMC_NAND flag - * This parameter can be any combination of the following values: - * @arg FMC_FLAG_RISING_EDGE: Interrupt rising edge flag. - * @arg FMC_FLAG_LEVEL: Interrupt level edge flag. - * @arg FMC_FLAG_FALLING_EDGE: Interrupt falling edge flag. - * @arg FMC_FLAG_FEMPT: FIFO empty flag. - * @retval The state of FLAG (SET or RESET). - */ -#define __FMC_NAND_GET_FLAG(__INSTANCE__, __BANK__, __FLAG__) (((__INSTANCE__)->SR &(__FLAG__)) == (__FLAG__)) -/** - * @brief Clear flag status of the NAND device. - * @param __INSTANCE__ FMC_NAND Instance - * @param __BANK__ FMC_NAND Bank - * @param __FLAG__ FMC_NAND flag - * This parameter can be any combination of the following values: - * @arg FMC_FLAG_RISING_EDGE: Interrupt rising edge flag. - * @arg FMC_FLAG_LEVEL: Interrupt level edge flag. - * @arg FMC_FLAG_FALLING_EDGE: Interrupt falling edge flag. - * @arg FMC_FLAG_FEMPT: FIFO empty flag. - * @retval None - */ -#define __FMC_NAND_CLEAR_FLAG(__INSTANCE__, __BANK__, __FLAG__) ((__INSTANCE__)->SR &= ~(__FLAG__)) -#else /* defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) */ -/** - * @brief Enable the NAND device interrupt. - * @param __INSTANCE__ FMC_NAND instance - * @param __BANK__ FMC_NAND Bank - * @param __INTERRUPT__ FMC_NAND interrupt - * This parameter can be any combination of the following values: - * @arg FMC_IT_RISING_EDGE: Interrupt rising edge. - * @arg FMC_IT_LEVEL: Interrupt level. - * @arg FMC_IT_FALLING_EDGE: Interrupt falling edge. - * @retval None - */ -#define __FMC_NAND_ENABLE_IT(__INSTANCE__, __BANK__, __INTERRUPT__) (((__BANK__) == FMC_NAND_BANK2)? ((__INSTANCE__)->SR2 |= (__INTERRUPT__)): \ - ((__INSTANCE__)->SR3 |= (__INTERRUPT__))) - -/** - * @brief Disable the NAND device interrupt. - * @param __INSTANCE__ FMC_NAND Instance - * @param __BANK__ FMC_NAND Bank - * @param __INTERRUPT__ FMC_NAND interrupt - * This parameter can be any combination of the following values: - * @arg FMC_IT_RISING_EDGE: Interrupt rising edge. - * @arg FMC_IT_LEVEL: Interrupt level. - * @arg FMC_IT_FALLING_EDGE: Interrupt falling edge. - * @retval None - */ -#define __FMC_NAND_DISABLE_IT(__INSTANCE__, __BANK__, __INTERRUPT__) (((__BANK__) == FMC_NAND_BANK2)? ((__INSTANCE__)->SR2 &= ~(__INTERRUPT__)): \ - ((__INSTANCE__)->SR3 &= ~(__INTERRUPT__))) - -/** - * @brief Get flag status of the NAND device. - * @param __INSTANCE__ FMC_NAND Instance - * @param __BANK__ FMC_NAND Bank - * @param __FLAG__ FMC_NAND flag - * This parameter can be any combination of the following values: - * @arg FMC_FLAG_RISING_EDGE: Interrupt rising edge flag. - * @arg FMC_FLAG_LEVEL: Interrupt level edge flag. - * @arg FMC_FLAG_FALLING_EDGE: Interrupt falling edge flag. - * @arg FMC_FLAG_FEMPT: FIFO empty flag. - * @retval The state of FLAG (SET or RESET). - */ -#define __FMC_NAND_GET_FLAG(__INSTANCE__, __BANK__, __FLAG__) (((__BANK__) == FMC_NAND_BANK2)? (((__INSTANCE__)->SR2 &(__FLAG__)) == (__FLAG__)): \ - (((__INSTANCE__)->SR3 &(__FLAG__)) == (__FLAG__))) -/** - * @brief Clear flag status of the NAND device. - * @param __INSTANCE__ FMC_NAND Instance - * @param __BANK__ FMC_NAND Bank - * @param __FLAG__ FMC_NAND flag - * This parameter can be any combination of the following values: - * @arg FMC_FLAG_RISING_EDGE: Interrupt rising edge flag. - * @arg FMC_FLAG_LEVEL: Interrupt level edge flag. - * @arg FMC_FLAG_FALLING_EDGE: Interrupt falling edge flag. - * @arg FMC_FLAG_FEMPT: FIFO empty flag. - * @retval None - */ -#define __FMC_NAND_CLEAR_FLAG(__INSTANCE__, __BANK__, __FLAG__) (((__BANK__) == FMC_NAND_BANK2)? ((__INSTANCE__)->SR2 &= ~(__FLAG__)): \ - ((__INSTANCE__)->SR3 &= ~(__FLAG__))) -#endif /* defined(STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) -/** - * @brief Enable the PCCARD device interrupt. - * @param __INSTANCE__ FMC_PCCARD instance - * @param __INTERRUPT__ FMC_PCCARD interrupt - * This parameter can be any combination of the following values: - * @arg FMC_IT_RISING_EDGE: Interrupt rising edge. - * @arg FMC_IT_LEVEL: Interrupt level. - * @arg FMC_IT_FALLING_EDGE: Interrupt falling edge. - * @retval None - */ -#define __FMC_PCCARD_ENABLE_IT(__INSTANCE__, __INTERRUPT__) ((__INSTANCE__)->SR4 |= (__INTERRUPT__)) - -/** - * @brief Disable the PCCARD device interrupt. - * @param __INSTANCE__ FMC_PCCARD instance - * @param __INTERRUPT__ FMC_PCCARD interrupt - * This parameter can be any combination of the following values: - * @arg FMC_IT_RISING_EDGE: Interrupt rising edge. - * @arg FMC_IT_LEVEL: Interrupt level. - * @arg FMC_IT_FALLING_EDGE: Interrupt falling edge. - * @retval None - */ -#define __FMC_PCCARD_DISABLE_IT(__INSTANCE__, __INTERRUPT__) ((__INSTANCE__)->SR4 &= ~(__INTERRUPT__)) - -/** - * @brief Get flag status of the PCCARD device. - * @param __INSTANCE__ FMC_PCCARD instance - * @param __FLAG__ FMC_PCCARD flag - * This parameter can be any combination of the following values: - * @arg FMC_FLAG_RISING_EDGE: Interrupt rising edge flag. - * @arg FMC_FLAG_LEVEL: Interrupt level edge flag. - * @arg FMC_FLAG_FALLING_EDGE: Interrupt falling edge flag. - * @arg FMC_FLAG_FEMPT: FIFO empty flag. - * @retval The state of FLAG (SET or RESET). - */ -#define __FMC_PCCARD_GET_FLAG(__INSTANCE__, __FLAG__) (((__INSTANCE__)->SR4 &(__FLAG__)) == (__FLAG__)) - -/** - * @brief Clear flag status of the PCCARD device. - * @param __INSTANCE__ FMC_PCCARD instance - * @param __FLAG__ FMC_PCCARD flag - * This parameter can be any combination of the following values: - * @arg FMC_FLAG_RISING_EDGE: Interrupt rising edge flag. - * @arg FMC_FLAG_LEVEL: Interrupt level edge flag. - * @arg FMC_FLAG_FALLING_EDGE: Interrupt falling edge flag. - * @arg FMC_FLAG_FEMPT: FIFO empty flag. - * @retval None - */ -#define __FMC_PCCARD_CLEAR_FLAG(__INSTANCE__, __FLAG__) ((__INSTANCE__)->SR4 &= ~(__FLAG__)) -#endif /* defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) */ - -/** - * @brief Enable the SDRAM device interrupt. - * @param __INSTANCE__ FMC_SDRAM instance - * @param __INTERRUPT__ FMC_SDRAM interrupt - * This parameter can be any combination of the following values: - * @arg FMC_IT_REFRESH_ERROR: Interrupt refresh error - * @retval None - */ -#define __FMC_SDRAM_ENABLE_IT(__INSTANCE__, __INTERRUPT__) ((__INSTANCE__)->SDRTR |= (__INTERRUPT__)) - -/** - * @brief Disable the SDRAM device interrupt. - * @param __INSTANCE__ FMC_SDRAM instance - * @param __INTERRUPT__ FMC_SDRAM interrupt - * This parameter can be any combination of the following values: - * @arg FMC_IT_REFRESH_ERROR: Interrupt refresh error - * @retval None - */ -#define __FMC_SDRAM_DISABLE_IT(__INSTANCE__, __INTERRUPT__) ((__INSTANCE__)->SDRTR &= ~(__INTERRUPT__)) - -/** - * @brief Get flag status of the SDRAM device. - * @param __INSTANCE__ FMC_SDRAM instance - * @param __FLAG__ FMC_SDRAM flag - * This parameter can be any combination of the following values: - * @arg FMC_SDRAM_FLAG_REFRESH_IT: Interrupt refresh error. - * @arg FMC_SDRAM_FLAG_BUSY: SDRAM busy flag. - * @arg FMC_SDRAM_FLAG_REFRESH_ERROR: Refresh error flag. - * @retval The state of FLAG (SET or RESET). - */ -#define __FMC_SDRAM_GET_FLAG(__INSTANCE__, __FLAG__) (((__INSTANCE__)->SDSR &(__FLAG__)) == (__FLAG__)) - -/** - * @brief Clear flag status of the SDRAM device. - * @param __INSTANCE__ FMC_SDRAM instance - * @param __FLAG__ FMC_SDRAM flag - * This parameter can be any combination of the following values: - * @arg FMC_SDRAM_FLAG_REFRESH_ERROR - * @retval None - */ -#define __FMC_SDRAM_CLEAR_FLAG(__INSTANCE__, __FLAG__) ((__INSTANCE__)->SDRTR |= (__FLAG__)) -/** - * @} - */ - -/** @defgroup FSMC_LL_Assert_Macros FSMC Assert Macros - * @{ - */ -#define IS_FMC_NORSRAM_BANK(BANK) (((BANK) == FMC_NORSRAM_BANK1) || \ - ((BANK) == FMC_NORSRAM_BANK2) || \ - ((BANK) == FMC_NORSRAM_BANK3) || \ - ((BANK) == FMC_NORSRAM_BANK4)) - -#define IS_FMC_MUX(__MUX__) (((__MUX__) == FMC_DATA_ADDRESS_MUX_DISABLE) || \ - ((__MUX__) == FMC_DATA_ADDRESS_MUX_ENABLE)) - -#define IS_FMC_MEMORY(__MEMORY__) (((__MEMORY__) == FMC_MEMORY_TYPE_SRAM) || \ - ((__MEMORY__) == FMC_MEMORY_TYPE_PSRAM)|| \ - ((__MEMORY__) == FMC_MEMORY_TYPE_NOR)) - -#define IS_FMC_NORSRAM_MEMORY_WIDTH(__WIDTH__) (((__WIDTH__) == FMC_NORSRAM_MEM_BUS_WIDTH_8) || \ - ((__WIDTH__) == FMC_NORSRAM_MEM_BUS_WIDTH_16) || \ - ((__WIDTH__) == FMC_NORSRAM_MEM_BUS_WIDTH_32)) - -#define IS_FMC_ACCESS_MODE(__MODE__) (((__MODE__) == FMC_ACCESS_MODE_A) || \ - ((__MODE__) == FMC_ACCESS_MODE_B) || \ - ((__MODE__) == FMC_ACCESS_MODE_C) || \ - ((__MODE__) == FMC_ACCESS_MODE_D)) - -#define IS_FMC_NAND_BANK(BANK) (((BANK) == FMC_NAND_BANK2) || \ - ((BANK) == FMC_NAND_BANK3)) - -#define IS_FMC_WAIT_FEATURE(FEATURE) (((FEATURE) == FMC_NAND_PCC_WAIT_FEATURE_DISABLE) || \ - ((FEATURE) == FMC_NAND_PCC_WAIT_FEATURE_ENABLE)) - -#define IS_FMC_NAND_MEMORY_WIDTH(WIDTH) (((WIDTH) == FMC_NAND_PCC_MEM_BUS_WIDTH_8) || \ - ((WIDTH) == FMC_NAND_PCC_MEM_BUS_WIDTH_16)) - -#define IS_FMC_ECC_STATE(STATE) (((STATE) == FMC_NAND_ECC_DISABLE) || \ - ((STATE) == FMC_NAND_ECC_ENABLE)) - -#define IS_FMC_ECCPAGE_SIZE(SIZE) (((SIZE) == FMC_NAND_ECC_PAGE_SIZE_256BYTE) || \ - ((SIZE) == FMC_NAND_ECC_PAGE_SIZE_512BYTE) || \ - ((SIZE) == FMC_NAND_ECC_PAGE_SIZE_1024BYTE) || \ - ((SIZE) == FMC_NAND_ECC_PAGE_SIZE_2048BYTE) || \ - ((SIZE) == FMC_NAND_ECC_PAGE_SIZE_4096BYTE) || \ - ((SIZE) == FMC_NAND_ECC_PAGE_SIZE_8192BYTE)) - -#define IS_FMC_TCLR_TIME(TIME) ((TIME) <= 255U) - -#define IS_FMC_TAR_TIME(TIME) ((TIME) <= 255U) - -#define IS_FMC_SETUP_TIME(TIME) ((TIME) <= 255U) - -#define IS_FMC_WAIT_TIME(TIME) ((TIME) <= 255U) - -#define IS_FMC_HOLD_TIME(TIME) ((TIME) <= 255U) - -#define IS_FMC_HIZ_TIME(TIME) ((TIME) <= 255U) - -#define IS_FMC_NORSRAM_DEVICE(__INSTANCE__) ((__INSTANCE__) == FMC_NORSRAM_DEVICE) - -#define IS_FMC_NORSRAM_EXTENDED_DEVICE(__INSTANCE__) ((__INSTANCE__) == FMC_NORSRAM_EXTENDED_DEVICE) - -#define IS_FMC_NAND_DEVICE(__INSTANCE__) ((__INSTANCE__) == FMC_NAND_DEVICE) - -#define IS_FMC_PCCARD_DEVICE(__INSTANCE__) ((__INSTANCE__) == FMC_PCCARD_DEVICE) - -#define IS_FMC_BURSTMODE(__STATE__) (((__STATE__) == FMC_BURST_ACCESS_MODE_DISABLE) || \ - ((__STATE__) == FMC_BURST_ACCESS_MODE_ENABLE)) - -#define IS_FMC_WAIT_POLARITY(__POLARITY__) (((__POLARITY__) == FMC_WAIT_SIGNAL_POLARITY_LOW) || \ - ((__POLARITY__) == FMC_WAIT_SIGNAL_POLARITY_HIGH)) - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) -#define IS_FMC_WRAP_MODE(__MODE__) (((__MODE__) == FMC_WRAP_MODE_DISABLE) || \ - ((__MODE__) == FMC_WRAP_MODE_ENABLE)) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx */ - -#define IS_FMC_WAIT_SIGNAL_ACTIVE(__ACTIVE__) (((__ACTIVE__) == FMC_WAIT_TIMING_BEFORE_WS) || \ - ((__ACTIVE__) == FMC_WAIT_TIMING_DURING_WS)) - -#define IS_FMC_WRITE_OPERATION(__OPERATION__) (((__OPERATION__) == FMC_WRITE_OPERATION_DISABLE) || \ - ((__OPERATION__) == FMC_WRITE_OPERATION_ENABLE)) - -#define IS_FMC_WAITE_SIGNAL(__SIGNAL__) (((__SIGNAL__) == FMC_WAIT_SIGNAL_DISABLE) || \ - ((__SIGNAL__) == FMC_WAIT_SIGNAL_ENABLE)) - -#define IS_FMC_EXTENDED_MODE(__MODE__) (((__MODE__) == FMC_EXTENDED_MODE_DISABLE) || \ - ((__MODE__) == FMC_EXTENDED_MODE_ENABLE)) - -#define IS_FMC_ASYNWAIT(__STATE__) (((__STATE__) == FMC_ASYNCHRONOUS_WAIT_DISABLE) || \ - ((__STATE__) == FMC_ASYNCHRONOUS_WAIT_ENABLE)) - -#define IS_FMC_WRITE_BURST(__BURST__) (((__BURST__) == FMC_WRITE_BURST_DISABLE) || \ - ((__BURST__) == FMC_WRITE_BURST_ENABLE)) - -#define IS_FMC_CONTINOUS_CLOCK(CCLOCK) (((CCLOCK) == FMC_CONTINUOUS_CLOCK_SYNC_ONLY) || \ - ((CCLOCK) == FMC_CONTINUOUS_CLOCK_SYNC_ASYNC)) - -#define IS_FMC_ADDRESS_SETUP_TIME(__TIME__) ((__TIME__) <= 15U) - -#define IS_FMC_ADDRESS_HOLD_TIME(__TIME__) (((__TIME__) > 0U) && ((__TIME__) <= 15U)) - -#define IS_FMC_DATASETUP_TIME(__TIME__) (((__TIME__) > 0U) && ((__TIME__) <= 255U)) - -#define IS_FMC_TURNAROUND_TIME(__TIME__) ((__TIME__) <= 15U) - -#define IS_FMC_DATA_LATENCY(__LATENCY__) (((__LATENCY__) > 1U) && ((__LATENCY__) <= 17U)) - -#define IS_FMC_CLK_DIV(DIV) (((DIV) > 1U) && ((DIV) <= 16U)) - -#define IS_FMC_SDRAM_BANK(BANK) (((BANK) == FMC_SDRAM_BANK1) || \ - ((BANK) == FMC_SDRAM_BANK2)) - -#define IS_FMC_COLUMNBITS_NUMBER(COLUMN) (((COLUMN) == FMC_SDRAM_COLUMN_BITS_NUM_8) || \ - ((COLUMN) == FMC_SDRAM_COLUMN_BITS_NUM_9) || \ - ((COLUMN) == FMC_SDRAM_COLUMN_BITS_NUM_10) || \ - ((COLUMN) == FMC_SDRAM_COLUMN_BITS_NUM_11)) - -#define IS_FMC_ROWBITS_NUMBER(ROW) (((ROW) == FMC_SDRAM_ROW_BITS_NUM_11) || \ - ((ROW) == FMC_SDRAM_ROW_BITS_NUM_12) || \ - ((ROW) == FMC_SDRAM_ROW_BITS_NUM_13)) - -#define IS_FMC_SDMEMORY_WIDTH(WIDTH) (((WIDTH) == FMC_SDRAM_MEM_BUS_WIDTH_8) || \ - ((WIDTH) == FMC_SDRAM_MEM_BUS_WIDTH_16) || \ - ((WIDTH) == FMC_SDRAM_MEM_BUS_WIDTH_32)) - -#define IS_FMC_INTERNALBANK_NUMBER(NUMBER) (((NUMBER) == FMC_SDRAM_INTERN_BANKS_NUM_2) || \ - ((NUMBER) == FMC_SDRAM_INTERN_BANKS_NUM_4)) - - -#define IS_FMC_CAS_LATENCY(LATENCY) (((LATENCY) == FMC_SDRAM_CAS_LATENCY_1) || \ - ((LATENCY) == FMC_SDRAM_CAS_LATENCY_2) || \ - ((LATENCY) == FMC_SDRAM_CAS_LATENCY_3)) - -#define IS_FMC_SDCLOCK_PERIOD(PERIOD) (((PERIOD) == FMC_SDRAM_CLOCK_DISABLE) || \ - ((PERIOD) == FMC_SDRAM_CLOCK_PERIOD_2) || \ - ((PERIOD) == FMC_SDRAM_CLOCK_PERIOD_3)) - -#define IS_FMC_READ_BURST(RBURST) (((RBURST) == FMC_SDRAM_RBURST_DISABLE) || \ - ((RBURST) == FMC_SDRAM_RBURST_ENABLE)) - - -#define IS_FMC_READPIPE_DELAY(DELAY) (((DELAY) == FMC_SDRAM_RPIPE_DELAY_0) || \ - ((DELAY) == FMC_SDRAM_RPIPE_DELAY_1) || \ - ((DELAY) == FMC_SDRAM_RPIPE_DELAY_2)) - -#define IS_FMC_LOADTOACTIVE_DELAY(DELAY) (((DELAY) > 0U) && ((DELAY) <= 16U)) - -#define IS_FMC_EXITSELFREFRESH_DELAY(DELAY) (((DELAY) > 0U) && ((DELAY) <= 16U)) - -#define IS_FMC_SELFREFRESH_TIME(TIME) (((TIME) > 0U) && ((TIME) <= 16U)) - -#define IS_FMC_ROWCYCLE_DELAY(DELAY) (((DELAY) > 0U) && ((DELAY) <= 16U)) - -#define IS_FMC_WRITE_RECOVERY_TIME(TIME) (((TIME) > 0U) && ((TIME) <= 16U)) - -#define IS_FMC_RP_DELAY(DELAY) (((DELAY) > 0U) && ((DELAY) <= 16U)) - -#define IS_FMC_RCD_DELAY(DELAY) (((DELAY) > 0U) && ((DELAY) <= 16U)) - -#define IS_FMC_COMMAND_MODE(COMMAND) (((COMMAND) == FMC_SDRAM_CMD_NORMAL_MODE) || \ - ((COMMAND) == FMC_SDRAM_CMD_CLK_ENABLE) || \ - ((COMMAND) == FMC_SDRAM_CMD_PALL) || \ - ((COMMAND) == FMC_SDRAM_CMD_AUTOREFRESH_MODE) || \ - ((COMMAND) == FMC_SDRAM_CMD_LOAD_MODE) || \ - ((COMMAND) == FMC_SDRAM_CMD_SELFREFRESH_MODE) || \ - ((COMMAND) == FMC_SDRAM_CMD_POWERDOWN_MODE)) - -#define IS_FMC_COMMAND_TARGET(TARGET) (((TARGET) == FMC_SDRAM_CMD_TARGET_BANK1) || \ - ((TARGET) == FMC_SDRAM_CMD_TARGET_BANK2) || \ - ((TARGET) == FMC_SDRAM_CMD_TARGET_BANK1_2)) - -#define IS_FMC_AUTOREFRESH_NUMBER(NUMBER) (((NUMBER) > 0U) && ((NUMBER) <= 16U)) - -#define IS_FMC_MODE_REGISTER(CONTENT) ((CONTENT) <= 8191U) - -#define IS_FMC_REFRESH_RATE(RATE) ((RATE) <= 8191U) - -#define IS_FMC_SDRAM_DEVICE(INSTANCE) ((INSTANCE) == FMC_SDRAM_DEVICE) - -#define IS_FMC_WRITE_PROTECTION(WRITE) (((WRITE) == FMC_SDRAM_WRITE_PROTECTION_DISABLE) || \ - ((WRITE) == FMC_SDRAM_WRITE_PROTECTION_ENABLE)) - -#define IS_FMC_PAGESIZE(SIZE) (((SIZE) == FMC_PAGE_SIZE_NONE) || \ - ((SIZE) == FMC_PAGE_SIZE_128) || \ - ((SIZE) == FMC_PAGE_SIZE_256) || \ - ((SIZE) == FMC_PAGE_SIZE_512) || \ - ((SIZE) == FMC_PAGE_SIZE_1024)) - -#if defined (STM32F446xx) || defined(STM32F469xx) || defined(STM32F479xx) -#define IS_FMC_WRITE_FIFO(FIFO) (((FIFO) == FMC_WRITE_FIFO_DISABLE) || \ - ((FIFO) == FMC_WRITE_FIFO_ENABLE)) -#endif /* STM32F446xx || STM32F469xx || STM32F479xx */ - -/** - * @} - */ - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup FMC_LL_Private_Functions FMC LL Private Functions - * @{ - */ - -/** @defgroup FMC_LL_NORSRAM NOR SRAM - * @{ - */ -/** @defgroup FMC_LL_NORSRAM_Private_Functions_Group1 NOR SRAM Initialization/de-initialization functions - * @{ - */ -HAL_StatusTypeDef FMC_NORSRAM_Init(FMC_NORSRAM_TypeDef *Device, FMC_NORSRAM_InitTypeDef *Init); -HAL_StatusTypeDef FMC_NORSRAM_Timing_Init(FMC_NORSRAM_TypeDef *Device, FMC_NORSRAM_TimingTypeDef *Timing, uint32_t Bank); -HAL_StatusTypeDef FMC_NORSRAM_Extended_Timing_Init(FMC_NORSRAM_EXTENDED_TypeDef *Device, FMC_NORSRAM_TimingTypeDef *Timing, uint32_t Bank, uint32_t ExtendedMode); -HAL_StatusTypeDef FMC_NORSRAM_DeInit(FMC_NORSRAM_TypeDef *Device, FMC_NORSRAM_EXTENDED_TypeDef *ExDevice, uint32_t Bank); -/** - * @} - */ - -/** @defgroup FMC_LL_NORSRAM_Private_Functions_Group2 NOR SRAM Control functions - * @{ - */ -HAL_StatusTypeDef FMC_NORSRAM_WriteOperation_Enable(FMC_NORSRAM_TypeDef *Device, uint32_t Bank); -HAL_StatusTypeDef FMC_NORSRAM_WriteOperation_Disable(FMC_NORSRAM_TypeDef *Device, uint32_t Bank); -/** - * @} - */ -/** - * @} - */ - -/** @defgroup FMC_LL_NAND NAND - * @{ - */ -/** @defgroup FMC_LL_NAND_Private_Functions_Group1 NAND Initialization/de-initialization functions - * @{ - */ -HAL_StatusTypeDef FMC_NAND_Init(FMC_NAND_TypeDef *Device, FMC_NAND_InitTypeDef *Init); -HAL_StatusTypeDef FMC_NAND_CommonSpace_Timing_Init(FMC_NAND_TypeDef *Device, FMC_NAND_PCC_TimingTypeDef *Timing, uint32_t Bank); -HAL_StatusTypeDef FMC_NAND_AttributeSpace_Timing_Init(FMC_NAND_TypeDef *Device, FMC_NAND_PCC_TimingTypeDef *Timing, uint32_t Bank); -HAL_StatusTypeDef FMC_NAND_DeInit(FMC_NAND_TypeDef *Device, uint32_t Bank); -/** - * @} - */ - -/** @defgroup FMC_LL_NAND_Private_Functions_Group2 NAND Control functions - * @{ - */ -HAL_StatusTypeDef FMC_NAND_ECC_Enable(FMC_NAND_TypeDef *Device, uint32_t Bank); -HAL_StatusTypeDef FMC_NAND_ECC_Disable(FMC_NAND_TypeDef *Device, uint32_t Bank); -HAL_StatusTypeDef FMC_NAND_GetECC(FMC_NAND_TypeDef *Device, uint32_t *ECCval, uint32_t Bank, uint32_t Timeout); - -/** - * @} - */ -/** - * @} - */ -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) -/** @defgroup FMC_LL_PCCARD PCCARD - * @{ - */ -/** @defgroup FMC_LL_PCCARD_Private_Functions_Group1 PCCARD Initialization/de-initialization functions - * @{ - */ -HAL_StatusTypeDef FMC_PCCARD_Init(FMC_PCCARD_TypeDef *Device, FMC_PCCARD_InitTypeDef *Init); -HAL_StatusTypeDef FMC_PCCARD_CommonSpace_Timing_Init(FMC_PCCARD_TypeDef *Device, FMC_NAND_PCC_TimingTypeDef *Timing); -HAL_StatusTypeDef FMC_PCCARD_AttributeSpace_Timing_Init(FMC_PCCARD_TypeDef *Device, FMC_NAND_PCC_TimingTypeDef *Timing); -HAL_StatusTypeDef FMC_PCCARD_IOSpace_Timing_Init(FMC_PCCARD_TypeDef *Device, FMC_NAND_PCC_TimingTypeDef *Timing); -HAL_StatusTypeDef FMC_PCCARD_DeInit(FMC_PCCARD_TypeDef *Device); -/** - * @} - */ -/** - * @} - */ -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx */ - -/** @defgroup FMC_LL_SDRAM SDRAM - * @{ - */ -/** @defgroup FMC_LL_SDRAM_Private_Functions_Group1 SDRAM Initialization/de-initialization functions - * @{ - */ -HAL_StatusTypeDef FMC_SDRAM_Init(FMC_SDRAM_TypeDef *Device, FMC_SDRAM_InitTypeDef *Init); -HAL_StatusTypeDef FMC_SDRAM_Timing_Init(FMC_SDRAM_TypeDef *Device, FMC_SDRAM_TimingTypeDef *Timing, uint32_t Bank); -HAL_StatusTypeDef FMC_SDRAM_DeInit(FMC_SDRAM_TypeDef *Device, uint32_t Bank); -/** - * @} - */ - -/** @defgroup FMC_LL_SDRAM_Private_Functions_Group2 SDRAM Control functions - * @{ - */ -HAL_StatusTypeDef FMC_SDRAM_WriteProtection_Enable(FMC_SDRAM_TypeDef *Device, uint32_t Bank); -HAL_StatusTypeDef FMC_SDRAM_WriteProtection_Disable(FMC_SDRAM_TypeDef *Device, uint32_t Bank); -HAL_StatusTypeDef FMC_SDRAM_SendCommand(FMC_SDRAM_TypeDef *Device, FMC_SDRAM_CommandTypeDef *Command, uint32_t Timeout); -HAL_StatusTypeDef FMC_SDRAM_ProgramRefreshRate(FMC_SDRAM_TypeDef *Device, uint32_t RefreshRate); -HAL_StatusTypeDef FMC_SDRAM_SetAutoRefreshNumber(FMC_SDRAM_TypeDef *Device, uint32_t AutoRefreshNumber); -uint32_t FMC_SDRAM_GetModeStatus(FMC_SDRAM_TypeDef *Device, uint32_t Bank); -/** - * @} - */ -/** - * @} - */ - -/** - * @} - */ - -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F446xx || STM32F469xx || STM32F479xx */ -/** - * @} - */ - -/** - * @} - */ -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_FMC_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_fmpi2c.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_fmpi2c.h deleted file mode 100644 index dd08b77..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_fmpi2c.h +++ /dev/null @@ -1,2237 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_fmpi2c.h - * @author MCD Application Team - * @brief Header file of FMPI2C LL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_LL_FMPI2C_H -#define STM32F4xx_LL_FMPI2C_H - -#ifdef __cplusplus -extern "C" { -#endif - -#if defined(FMPI2C_CR1_PE) -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (FMPI2C1) - -/** @defgroup FMPI2C_LL FMPI2C - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup FMPI2C_LL_Private_Constants FMPI2C Private Constants - * @{ - */ -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup FMPI2C_LL_Private_Macros FMPI2C Private Macros - * @{ - */ -/** - * @} - */ -#endif /*USE_FULL_LL_DRIVER*/ - -/* Exported types ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup FMPI2C_LL_ES_INIT FMPI2C Exported Init structure - * @{ - */ -typedef struct -{ - uint32_t PeripheralMode; /*!< Specifies the peripheral mode. - This parameter can be a value of @ref FMPI2C_LL_EC_PERIPHERAL_MODE. - - This feature can be modified afterwards using unitary function - @ref LL_FMPI2C_SetMode(). */ - - uint32_t Timing; /*!< Specifies the SDA setup, hold time and the SCL high, low period values. - This parameter must be set by referring to the STM32CubeMX Tool and - the helper macro @ref __LL_FMPI2C_CONVERT_TIMINGS(). - - This feature can be modified afterwards using unitary function - @ref LL_FMPI2C_SetTiming(). */ - - uint32_t AnalogFilter; /*!< Enables or disables analog noise filter. - This parameter can be a value of @ref FMPI2C_LL_EC_ANALOGFILTER_SELECTION. - - This feature can be modified afterwards using unitary functions - @ref LL_FMPI2C_EnableAnalogFilter() or LL_FMPI2C_DisableAnalogFilter(). */ - - uint32_t DigitalFilter; /*!< Configures the digital noise filter. - This parameter can be a number between Min_Data = 0x00 and Max_Data = 0x0F. - - This feature can be modified afterwards using unitary function - @ref LL_FMPI2C_SetDigitalFilter(). */ - - uint32_t OwnAddress1; /*!< Specifies the device own address 1. - This parameter must be a value between Min_Data = 0x00 and Max_Data = 0x3FF. - - This feature can be modified afterwards using unitary function - @ref LL_FMPI2C_SetOwnAddress1(). */ - - uint32_t TypeAcknowledge; /*!< Specifies the ACKnowledge or Non ACKnowledge condition after the address receive - match code or next received byte. - This parameter can be a value of @ref FMPI2C_LL_EC_I2C_ACKNOWLEDGE. - - This feature can be modified afterwards using unitary function - @ref LL_FMPI2C_AcknowledgeNextData(). */ - - uint32_t OwnAddrSize; /*!< Specifies the device own address 1 size (7-bit or 10-bit). - This parameter can be a value of @ref FMPI2C_LL_EC_OWNADDRESS1. - - This feature can be modified afterwards using unitary function - @ref LL_FMPI2C_SetOwnAddress1(). */ -} LL_FMPI2C_InitTypeDef; -/** - * @} - */ -#endif /*USE_FULL_LL_DRIVER*/ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup FMPI2C_LL_Exported_Constants FMPI2C Exported Constants - * @{ - */ - -/** @defgroup FMPI2C_LL_EC_CLEAR_FLAG Clear Flags Defines - * @brief Flags defines which can be used with LL_FMPI2C_WriteReg function - * @{ - */ -#define LL_FMPI2C_ICR_ADDRCF FMPI2C_ICR_ADDRCF /*!< Address Matched flag */ -#define LL_FMPI2C_ICR_NACKCF FMPI2C_ICR_NACKCF /*!< Not Acknowledge flag */ -#define LL_FMPI2C_ICR_STOPCF FMPI2C_ICR_STOPCF /*!< Stop detection flag */ -#define LL_FMPI2C_ICR_BERRCF FMPI2C_ICR_BERRCF /*!< Bus error flag */ -#define LL_FMPI2C_ICR_ARLOCF FMPI2C_ICR_ARLOCF /*!< Arbitration Lost flag */ -#define LL_FMPI2C_ICR_OVRCF FMPI2C_ICR_OVRCF /*!< Overrun/Underrun flag */ -#define LL_FMPI2C_ICR_PECCF FMPI2C_ICR_PECCF /*!< PEC error flag */ -#define LL_FMPI2C_ICR_TIMOUTCF FMPI2C_ICR_TIMOUTCF /*!< Timeout detection flag */ -#define LL_FMPI2C_ICR_ALERTCF FMPI2C_ICR_ALERTCF /*!< Alert flag */ -/** - * @} - */ - -/** @defgroup FMPI2C_LL_EC_GET_FLAG Get Flags Defines - * @brief Flags defines which can be used with LL_FMPI2C_ReadReg function - * @{ - */ -#define LL_FMPI2C_ISR_TXE FMPI2C_ISR_TXE /*!< Transmit data register empty */ -#define LL_FMPI2C_ISR_TXIS FMPI2C_ISR_TXIS /*!< Transmit interrupt status */ -#define LL_FMPI2C_ISR_RXNE FMPI2C_ISR_RXNE /*!< Receive data register not empty */ -#define LL_FMPI2C_ISR_ADDR FMPI2C_ISR_ADDR /*!< Address matched (slave mode) */ -#define LL_FMPI2C_ISR_NACKF FMPI2C_ISR_NACKF /*!< Not Acknowledge received flag */ -#define LL_FMPI2C_ISR_STOPF FMPI2C_ISR_STOPF /*!< Stop detection flag */ -#define LL_FMPI2C_ISR_TC FMPI2C_ISR_TC /*!< Transfer Complete (master mode) */ -#define LL_FMPI2C_ISR_TCR FMPI2C_ISR_TCR /*!< Transfer Complete Reload */ -#define LL_FMPI2C_ISR_BERR FMPI2C_ISR_BERR /*!< Bus error */ -#define LL_FMPI2C_ISR_ARLO FMPI2C_ISR_ARLO /*!< Arbitration lost */ -#define LL_FMPI2C_ISR_OVR FMPI2C_ISR_OVR /*!< Overrun/Underrun (slave mode) */ -#define LL_FMPI2C_ISR_PECERR FMPI2C_ISR_PECERR /*!< PEC Error in reception (SMBus mode) */ -#define LL_FMPI2C_ISR_TIMEOUT FMPI2C_ISR_TIMEOUT /*!< Timeout detection flag (SMBus mode) */ -#define LL_FMPI2C_ISR_ALERT FMPI2C_ISR_ALERT /*!< SMBus alert (SMBus mode) */ -#define LL_FMPI2C_ISR_BUSY FMPI2C_ISR_BUSY /*!< Bus busy */ -/** - * @} - */ - -/** @defgroup FMPI2C_LL_EC_IT IT Defines - * @brief IT defines which can be used with LL_FMPI2C_ReadReg and LL_FMPI2C_WriteReg functions - * @{ - */ -#define LL_FMPI2C_CR1_TXIE FMPI2C_CR1_TXIE /*!< TX Interrupt enable */ -#define LL_FMPI2C_CR1_RXIE FMPI2C_CR1_RXIE /*!< RX Interrupt enable */ -#define LL_FMPI2C_CR1_ADDRIE FMPI2C_CR1_ADDRIE /*!< Address match Interrupt enable (slave only) */ -#define LL_FMPI2C_CR1_NACKIE FMPI2C_CR1_NACKIE /*!< Not acknowledge received Interrupt enable */ -#define LL_FMPI2C_CR1_STOPIE FMPI2C_CR1_STOPIE /*!< STOP detection Interrupt enable */ -#define LL_FMPI2C_CR1_TCIE FMPI2C_CR1_TCIE /*!< Transfer Complete interrupt enable */ -#define LL_FMPI2C_CR1_ERRIE FMPI2C_CR1_ERRIE /*!< Error interrupts enable */ -/** - * @} - */ - -/** @defgroup FMPI2C_LL_EC_PERIPHERAL_MODE Peripheral Mode - * @{ - */ -#define LL_FMPI2C_MODE_I2C 0x00000000U /*!< FMPI2C Master or Slave mode */ -#define LL_FMPI2C_MODE_SMBUS_HOST FMPI2C_CR1_SMBHEN /*!< SMBus Host address acknowledge */ -#define LL_FMPI2C_MODE_SMBUS_DEVICE 0x00000000U /*!< SMBus Device default mode - (Default address not acknowledge) */ -#define LL_FMPI2C_MODE_SMBUS_DEVICE_ARP FMPI2C_CR1_SMBDEN /*!< SMBus Device Default address acknowledge */ -/** - * @} - */ - -/** @defgroup FMPI2C_LL_EC_ANALOGFILTER_SELECTION Analog Filter Selection - * @{ - */ -#define LL_FMPI2C_ANALOGFILTER_ENABLE 0x00000000U /*!< Analog filter is enabled. */ -#define LL_FMPI2C_ANALOGFILTER_DISABLE FMPI2C_CR1_ANFOFF /*!< Analog filter is disabled. */ -/** - * @} - */ - -/** @defgroup FMPI2C_LL_EC_ADDRESSING_MODE Master Addressing Mode - * @{ - */ -#define LL_FMPI2C_ADDRESSING_MODE_7BIT 0x00000000U /*!< Master operates in 7-bit addressing mode. */ -#define LL_FMPI2C_ADDRESSING_MODE_10BIT FMPI2C_CR2_ADD10 /*!< Master operates in 10-bit addressing mode.*/ -/** - * @} - */ - -/** @defgroup FMPI2C_LL_EC_OWNADDRESS1 Own Address 1 Length - * @{ - */ -#define LL_FMPI2C_OWNADDRESS1_7BIT 0x00000000U /*!< Own address 1 is a 7-bit address. */ -#define LL_FMPI2C_OWNADDRESS1_10BIT FMPI2C_OAR1_OA1MODE /*!< Own address 1 is a 10-bit address.*/ -/** - * @} - */ - -/** @defgroup FMPI2C_LL_EC_OWNADDRESS2 Own Address 2 Masks - * @{ - */ -#define LL_FMPI2C_OWNADDRESS2_NOMASK FMPI2C_OAR2_OA2NOMASK /*!< Own Address2 No mask. */ -#define LL_FMPI2C_OWNADDRESS2_MASK01 FMPI2C_OAR2_OA2MASK01 /*!< Only Address2 bits[7:2] are compared. */ -#define LL_FMPI2C_OWNADDRESS2_MASK02 FMPI2C_OAR2_OA2MASK02 /*!< Only Address2 bits[7:3] are compared. */ -#define LL_FMPI2C_OWNADDRESS2_MASK03 FMPI2C_OAR2_OA2MASK03 /*!< Only Address2 bits[7:4] are compared. */ -#define LL_FMPI2C_OWNADDRESS2_MASK04 FMPI2C_OAR2_OA2MASK04 /*!< Only Address2 bits[7:5] are compared. */ -#define LL_FMPI2C_OWNADDRESS2_MASK05 FMPI2C_OAR2_OA2MASK05 /*!< Only Address2 bits[7:6] are compared. */ -#define LL_FMPI2C_OWNADDRESS2_MASK06 FMPI2C_OAR2_OA2MASK06 /*!< Only Address2 bits[7] are compared. */ -#define LL_FMPI2C_OWNADDRESS2_MASK07 FMPI2C_OAR2_OA2MASK07 /*!< No comparison is done. - All Address2 are acknowledged. */ -/** - * @} - */ - -/** @defgroup FMPI2C_LL_EC_I2C_ACKNOWLEDGE Acknowledge Generation - * @{ - */ -#define LL_FMPI2C_ACK 0x00000000U /*!< ACK is sent after current received byte. */ -#define LL_FMPI2C_NACK FMPI2C_CR2_NACK /*!< NACK is sent after current received byte.*/ -/** - * @} - */ - -/** @defgroup FMPI2C_LL_EC_ADDRSLAVE Slave Address Length - * @{ - */ -#define LL_FMPI2C_ADDRSLAVE_7BIT 0x00000000U /*!< Slave Address in 7-bit. */ -#define LL_FMPI2C_ADDRSLAVE_10BIT FMPI2C_CR2_ADD10 /*!< Slave Address in 10-bit.*/ -/** - * @} - */ - -/** @defgroup FMPI2C_LL_EC_REQUEST Transfer Request Direction - * @{ - */ -#define LL_FMPI2C_REQUEST_WRITE 0x00000000U /*!< Master request a write transfer. */ -#define LL_FMPI2C_REQUEST_READ FMPI2C_CR2_RD_WRN /*!< Master request a read transfer. */ -/** - * @} - */ - -/** @defgroup FMPI2C_LL_EC_MODE Transfer End Mode - * @{ - */ -#define LL_FMPI2C_MODE_RELOAD FMPI2C_CR2_RELOAD /*!< Enable FMPI2C Reload mode. */ -#define LL_FMPI2C_MODE_AUTOEND FMPI2C_CR2_AUTOEND /*!< Enable FMPI2C Automatic end mode - with no HW PEC comparison. */ -#define LL_FMPI2C_MODE_SOFTEND 0x00000000U /*!< Enable FMPI2C Software end mode - with no HW PEC comparison. */ -#define LL_FMPI2C_MODE_SMBUS_RELOAD LL_FMPI2C_MODE_RELOAD /*!< Enable FMPSMBUS Automatic end mode - with HW PEC comparison. */ -#define LL_FMPI2C_MODE_SMBUS_AUTOEND_NO_PEC LL_FMPI2C_MODE_AUTOEND /*!< Enable FMPSMBUS Automatic end mode - with HW PEC comparison. */ -#define LL_FMPI2C_MODE_SMBUS_SOFTEND_NO_PEC LL_FMPI2C_MODE_SOFTEND /*!< Enable FMPSMBUS Software end mode - with HW PEC comparison. */ -#define LL_FMPI2C_MODE_SMBUS_AUTOEND_WITH_PEC (uint32_t)(LL_FMPI2C_MODE_AUTOEND | FMPI2C_CR2_PECBYTE) -/*!< Enable FMPSMBUS Automatic end mode with HW PEC comparison. */ -#define LL_FMPI2C_MODE_SMBUS_SOFTEND_WITH_PEC (uint32_t)(LL_FMPI2C_MODE_SOFTEND | FMPI2C_CR2_PECBYTE) -/*!< Enable FMPSMBUS Software end mode with HW PEC comparison. */ -/** - * @} - */ - -/** @defgroup FMPI2C_LL_EC_GENERATE Start And Stop Generation - * @{ - */ -#define LL_FMPI2C_GENERATE_NOSTARTSTOP 0x00000000U -/*!< Don't Generate Stop and Start condition. */ -#define LL_FMPI2C_GENERATE_STOP (uint32_t)(0x80000000U | FMPI2C_CR2_STOP) -/*!< Generate Stop condition (Size should be set to 0). */ -#define LL_FMPI2C_GENERATE_START_READ (uint32_t)(0x80000000U | FMPI2C_CR2_START | FMPI2C_CR2_RD_WRN) -/*!< Generate Start for read request. */ -#define LL_FMPI2C_GENERATE_START_WRITE (uint32_t)(0x80000000U | FMPI2C_CR2_START) -/*!< Generate Start for write request. */ -#define LL_FMPI2C_GENERATE_RESTART_7BIT_READ (uint32_t)(0x80000000U | FMPI2C_CR2_START | FMPI2C_CR2_RD_WRN) -/*!< Generate Restart for read request, slave 7Bit address. */ -#define LL_FMPI2C_GENERATE_RESTART_7BIT_WRITE (uint32_t)(0x80000000U | FMPI2C_CR2_START) -/*!< Generate Restart for write request, slave 7Bit address. */ -#define LL_FMPI2C_GENERATE_RESTART_10BIT_READ (uint32_t)(0x80000000U | FMPI2C_CR2_START | \ - FMPI2C_CR2_RD_WRN | FMPI2C_CR2_HEAD10R) -/*!< Generate Restart for read request, slave 10Bit address. */ -#define LL_FMPI2C_GENERATE_RESTART_10BIT_WRITE (uint32_t)(0x80000000U | FMPI2C_CR2_START) -/*!< Generate Restart for write request, slave 10Bit address.*/ -/** - * @} - */ - -/** @defgroup FMPI2C_LL_EC_DIRECTION Read Write Direction - * @{ - */ -#define LL_FMPI2C_DIRECTION_WRITE 0x00000000U /*!< Write transfer request by master, - slave enters receiver mode. */ -#define LL_FMPI2C_DIRECTION_READ FMPI2C_ISR_DIR /*!< Read transfer request by master, - slave enters transmitter mode.*/ -/** - * @} - */ - -/** @defgroup FMPI2C_LL_EC_DMA_REG_DATA DMA Register Data - * @{ - */ -#define LL_FMPI2C_DMA_REG_DATA_TRANSMIT 0x00000000U /*!< Get address of data register used for - transmission */ -#define LL_FMPI2C_DMA_REG_DATA_RECEIVE 0x00000001U /*!< Get address of data register used for - reception */ -/** - * @} - */ - -/** @defgroup FMPI2C_LL_EC_SMBUS_TIMEOUTA_MODE SMBus TimeoutA Mode SCL SDA Timeout - * @{ - */ -#define LL_FMPI2C_FMPSMBUS_TIMEOUTA_MODE_SCL_LOW 0x00000000U /*!< TimeoutA is used to detect - SCL low level timeout. */ -#define LL_FMPI2C_FMPSMBUS_TIMEOUTA_MODE_SDA_SCL_HIGH FMPI2C_TIMEOUTR_TIDLE /*!< TimeoutA is used to detect - both SCL and SDA high level timeout.*/ -/** - * @} - */ - -/** @defgroup FMPI2C_LL_EC_SMBUS_TIMEOUT_SELECTION SMBus Timeout Selection - * @{ - */ -#define LL_FMPI2C_FMPSMBUS_TIMEOUTA FMPI2C_TIMEOUTR_TIMOUTEN /*!< TimeoutA enable bit */ -#define LL_FMPI2C_FMPSMBUS_TIMEOUTB FMPI2C_TIMEOUTR_TEXTEN /*!< TimeoutB (extended clock) - enable bit */ -#define LL_FMPI2C_FMPSMBUS_ALL_TIMEOUT (uint32_t)(FMPI2C_TIMEOUTR_TIMOUTEN | \ - FMPI2C_TIMEOUTR_TEXTEN) /*!< TimeoutA and TimeoutB -(extended clock) enable bits */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup FMPI2C_LL_Exported_Macros FMPI2C Exported Macros - * @{ - */ - -/** @defgroup FMPI2C_LL_EM_WRITE_READ Common Write and read registers Macros - * @{ - */ - -/** - * @brief Write a value in FMPI2C register - * @param __INSTANCE__ FMPI2C Instance - * @param __REG__ Register to be written - * @param __VALUE__ Value to be written in the register - * @retval None - */ -#define LL_FMPI2C_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__)) - -/** - * @brief Read a value in FMPI2C register - * @param __INSTANCE__ FMPI2C Instance - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_FMPI2C_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__) -/** - * @} - */ - -/** @defgroup FMPI2C_LL_EM_CONVERT_TIMINGS Convert SDA SCL timings - * @{ - */ -/** - * @brief Configure the SDA setup, hold time and the SCL high, low period. - * @param __PRESCALER__ This parameter must be a value between Min_Data=0 and Max_Data=0xF. - * @param __SETUP_TIME__ This parameter must be a value between Min_Data=0 and Max_Data=0xF. - (tscldel = (SCLDEL+1)xtpresc) - * @param __HOLD_TIME__ This parameter must be a value between Min_Data=0 and Max_Data=0xF. - (tsdadel = SDADELxtpresc) - * @param __SCLH_PERIOD__ This parameter must be a value between Min_Data=0 and Max_Data=0xFF. - (tsclh = (SCLH+1)xtpresc) - * @param __SCLL_PERIOD__ This parameter must be a value between Min_Data=0 and Max_Data=0xFF. - (tscll = (SCLL+1)xtpresc) - * @retval Value between Min_Data=0 and Max_Data=0xFFFFFFFF - */ -#define __LL_FMPI2C_CONVERT_TIMINGS(__PRESCALER__, __SETUP_TIME__, __HOLD_TIME__, __SCLH_PERIOD__, __SCLL_PERIOD__) \ - ((((uint32_t)(__PRESCALER__) << FMPI2C_TIMINGR_PRESC_Pos) & FMPI2C_TIMINGR_PRESC) | \ - (((uint32_t)(__SETUP_TIME__) << FMPI2C_TIMINGR_SCLDEL_Pos) & FMPI2C_TIMINGR_SCLDEL) | \ - (((uint32_t)(__HOLD_TIME__) << FMPI2C_TIMINGR_SDADEL_Pos) & FMPI2C_TIMINGR_SDADEL) | \ - (((uint32_t)(__SCLH_PERIOD__) << FMPI2C_TIMINGR_SCLH_Pos) & FMPI2C_TIMINGR_SCLH) | \ - (((uint32_t)(__SCLL_PERIOD__) << FMPI2C_TIMINGR_SCLL_Pos) & FMPI2C_TIMINGR_SCLL)) -/** - * @} - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup FMPI2C_LL_Exported_Functions FMPI2C Exported Functions - * @{ - */ - -/** @defgroup FMPI2C_LL_EF_Configuration Configuration - * @{ - */ - -/** - * @brief Enable FMPI2C peripheral (PE = 1). - * @rmtoll CR1 PE LL_FMPI2C_Enable - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_Enable(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->CR1, FMPI2C_CR1_PE); -} - -/** - * @brief Disable FMPI2C peripheral (PE = 0). - * @note When PE = 0, the FMPI2C SCL and SDA lines are released. - * Internal state machines and status bits are put back to their reset value. - * When cleared, PE must be kept low for at least 3 APB clock cycles. - * @rmtoll CR1 PE LL_FMPI2C_Disable - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_Disable(FMPI2C_TypeDef *FMPI2Cx) -{ - CLEAR_BIT(FMPI2Cx->CR1, FMPI2C_CR1_PE); -} - -/** - * @brief Check if the FMPI2C peripheral is enabled or disabled. - * @rmtoll CR1 PE LL_FMPI2C_IsEnabled - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabled(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->CR1, FMPI2C_CR1_PE) == (FMPI2C_CR1_PE)) ? 1UL : 0UL); -} - -/** - * @brief Configure Noise Filters (Analog and Digital). - * @note If the analog filter is also enabled, the digital filter is added to analog filter. - * The filters can only be programmed when the FMPI2C is disabled (PE = 0). - * @rmtoll CR1 ANFOFF LL_FMPI2C_ConfigFilters\n - * CR1 DNF LL_FMPI2C_ConfigFilters - * @param FMPI2Cx FMPI2C Instance. - * @param AnalogFilter This parameter can be one of the following values: - * @arg @ref LL_FMPI2C_ANALOGFILTER_ENABLE - * @arg @ref LL_FMPI2C_ANALOGFILTER_DISABLE - * @param DigitalFilter This parameter must be a value between Min_Data=0x00 (Digital filter disabled) - and Max_Data=0x0F (Digital filter enabled and filtering capability up to 15*tfmpi2cclk). - * This parameter is used to configure the digital noise filter on SDA and SCL input. - * The digital filter will filter spikes with a length of up to DNF[3:0]*tfmpi2cclk. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_ConfigFilters(FMPI2C_TypeDef *FMPI2Cx, uint32_t AnalogFilter, uint32_t DigitalFilter) -{ - MODIFY_REG(FMPI2Cx->CR1, FMPI2C_CR1_ANFOFF | FMPI2C_CR1_DNF, AnalogFilter | (DigitalFilter << FMPI2C_CR1_DNF_Pos)); -} - -/** - * @brief Configure Digital Noise Filter. - * @note If the analog filter is also enabled, the digital filter is added to analog filter. - * This filter can only be programmed when the FMPI2C is disabled (PE = 0). - * @rmtoll CR1 DNF LL_FMPI2C_SetDigitalFilter - * @param FMPI2Cx FMPI2C Instance. - * @param DigitalFilter This parameter must be a value between Min_Data=0x00 (Digital filter disabled) - and Max_Data=0x0F (Digital filter enabled and filtering capability up to 15*tfmpi2cclk). - * This parameter is used to configure the digital noise filter on SDA and SCL input. - * The digital filter will filter spikes with a length of up to DNF[3:0]*tfmpi2cclk. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_SetDigitalFilter(FMPI2C_TypeDef *FMPI2Cx, uint32_t DigitalFilter) -{ - MODIFY_REG(FMPI2Cx->CR1, FMPI2C_CR1_DNF, DigitalFilter << FMPI2C_CR1_DNF_Pos); -} - -/** - * @brief Get the current Digital Noise Filter configuration. - * @rmtoll CR1 DNF LL_FMPI2C_GetDigitalFilter - * @param FMPI2Cx FMPI2C Instance. - * @retval Value between Min_Data=0x0 and Max_Data=0xF - */ -__STATIC_INLINE uint32_t LL_FMPI2C_GetDigitalFilter(FMPI2C_TypeDef *FMPI2Cx) -{ - return (uint32_t)(READ_BIT(FMPI2Cx->CR1, FMPI2C_CR1_DNF) >> FMPI2C_CR1_DNF_Pos); -} - -/** - * @brief Enable Analog Noise Filter. - * @note This filter can only be programmed when the FMPI2C is disabled (PE = 0). - * @rmtoll CR1 ANFOFF LL_FMPI2C_EnableAnalogFilter - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_EnableAnalogFilter(FMPI2C_TypeDef *FMPI2Cx) -{ - CLEAR_BIT(FMPI2Cx->CR1, FMPI2C_CR1_ANFOFF); -} - -/** - * @brief Disable Analog Noise Filter. - * @note This filter can only be programmed when the FMPI2C is disabled (PE = 0). - * @rmtoll CR1 ANFOFF LL_FMPI2C_DisableAnalogFilter - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_DisableAnalogFilter(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->CR1, FMPI2C_CR1_ANFOFF); -} - -/** - * @brief Check if Analog Noise Filter is enabled or disabled. - * @rmtoll CR1 ANFOFF LL_FMPI2C_IsEnabledAnalogFilter - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabledAnalogFilter(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->CR1, FMPI2C_CR1_ANFOFF) != (FMPI2C_CR1_ANFOFF)) ? 1UL : 0UL); -} - -/** - * @brief Enable DMA transmission requests. - * @rmtoll CR1 TXDMAEN LL_FMPI2C_EnableDMAReq_TX - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_EnableDMAReq_TX(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->CR1, FMPI2C_CR1_TXDMAEN); -} - -/** - * @brief Disable DMA transmission requests. - * @rmtoll CR1 TXDMAEN LL_FMPI2C_DisableDMAReq_TX - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_DisableDMAReq_TX(FMPI2C_TypeDef *FMPI2Cx) -{ - CLEAR_BIT(FMPI2Cx->CR1, FMPI2C_CR1_TXDMAEN); -} - -/** - * @brief Check if DMA transmission requests are enabled or disabled. - * @rmtoll CR1 TXDMAEN LL_FMPI2C_IsEnabledDMAReq_TX - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabledDMAReq_TX(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->CR1, FMPI2C_CR1_TXDMAEN) == (FMPI2C_CR1_TXDMAEN)) ? 1UL : 0UL); -} - -/** - * @brief Enable DMA reception requests. - * @rmtoll CR1 RXDMAEN LL_FMPI2C_EnableDMAReq_RX - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_EnableDMAReq_RX(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->CR1, FMPI2C_CR1_RXDMAEN); -} - -/** - * @brief Disable DMA reception requests. - * @rmtoll CR1 RXDMAEN LL_FMPI2C_DisableDMAReq_RX - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_DisableDMAReq_RX(FMPI2C_TypeDef *FMPI2Cx) -{ - CLEAR_BIT(FMPI2Cx->CR1, FMPI2C_CR1_RXDMAEN); -} - -/** - * @brief Check if DMA reception requests are enabled or disabled. - * @rmtoll CR1 RXDMAEN LL_FMPI2C_IsEnabledDMAReq_RX - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabledDMAReq_RX(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->CR1, FMPI2C_CR1_RXDMAEN) == (FMPI2C_CR1_RXDMAEN)) ? 1UL : 0UL); -} - -/** - * @brief Get the data register address used for DMA transfer - * @rmtoll TXDR TXDATA LL_FMPI2C_DMA_GetRegAddr\n - * RXDR RXDATA LL_FMPI2C_DMA_GetRegAddr - * @param FMPI2Cx FMPI2C Instance - * @param Direction This parameter can be one of the following values: - * @arg @ref LL_FMPI2C_DMA_REG_DATA_TRANSMIT - * @arg @ref LL_FMPI2C_DMA_REG_DATA_RECEIVE - * @retval Address of data register - */ -__STATIC_INLINE uint32_t LL_FMPI2C_DMA_GetRegAddr(FMPI2C_TypeDef *FMPI2Cx, uint32_t Direction) -{ - uint32_t data_reg_addr; - - if (Direction == LL_FMPI2C_DMA_REG_DATA_TRANSMIT) - { - /* return address of TXDR register */ - data_reg_addr = (uint32_t) &(FMPI2Cx->TXDR); - } - else - { - /* return address of RXDR register */ - data_reg_addr = (uint32_t) &(FMPI2Cx->RXDR); - } - - return data_reg_addr; -} - -/** - * @brief Enable Clock stretching. - * @note This bit can only be programmed when the FMPI2C is disabled (PE = 0). - * @rmtoll CR1 NOSTRETCH LL_FMPI2C_EnableClockStretching - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_EnableClockStretching(FMPI2C_TypeDef *FMPI2Cx) -{ - CLEAR_BIT(FMPI2Cx->CR1, FMPI2C_CR1_NOSTRETCH); -} - -/** - * @brief Disable Clock stretching. - * @note This bit can only be programmed when the FMPI2C is disabled (PE = 0). - * @rmtoll CR1 NOSTRETCH LL_FMPI2C_DisableClockStretching - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_DisableClockStretching(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->CR1, FMPI2C_CR1_NOSTRETCH); -} - -/** - * @brief Check if Clock stretching is enabled or disabled. - * @rmtoll CR1 NOSTRETCH LL_FMPI2C_IsEnabledClockStretching - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabledClockStretching(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->CR1, FMPI2C_CR1_NOSTRETCH) != (FMPI2C_CR1_NOSTRETCH)) ? 1UL : 0UL); -} - -/** - * @brief Enable hardware byte control in slave mode. - * @rmtoll CR1 SBC LL_FMPI2C_EnableSlaveByteControl - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_EnableSlaveByteControl(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->CR1, FMPI2C_CR1_SBC); -} - -/** - * @brief Disable hardware byte control in slave mode. - * @rmtoll CR1 SBC LL_FMPI2C_DisableSlaveByteControl - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_DisableSlaveByteControl(FMPI2C_TypeDef *FMPI2Cx) -{ - CLEAR_BIT(FMPI2Cx->CR1, FMPI2C_CR1_SBC); -} - -/** - * @brief Check if hardware byte control in slave mode is enabled or disabled. - * @rmtoll CR1 SBC LL_FMPI2C_IsEnabledSlaveByteControl - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabledSlaveByteControl(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->CR1, FMPI2C_CR1_SBC) == (FMPI2C_CR1_SBC)) ? 1UL : 0UL); -} - -/** - * @brief Enable General Call. - * @note When enabled the Address 0x00 is ACKed. - * @rmtoll CR1 GCEN LL_FMPI2C_EnableGeneralCall - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_EnableGeneralCall(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->CR1, FMPI2C_CR1_GCEN); -} - -/** - * @brief Disable General Call. - * @note When disabled the Address 0x00 is NACKed. - * @rmtoll CR1 GCEN LL_FMPI2C_DisableGeneralCall - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_DisableGeneralCall(FMPI2C_TypeDef *FMPI2Cx) -{ - CLEAR_BIT(FMPI2Cx->CR1, FMPI2C_CR1_GCEN); -} - -/** - * @brief Check if General Call is enabled or disabled. - * @rmtoll CR1 GCEN LL_FMPI2C_IsEnabledGeneralCall - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabledGeneralCall(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->CR1, FMPI2C_CR1_GCEN) == (FMPI2C_CR1_GCEN)) ? 1UL : 0UL); -} - -/** - * @brief Configure the Master to operate in 7-bit or 10-bit addressing mode. - * @note Changing this bit is not allowed, when the START bit is set. - * @rmtoll CR2 ADD10 LL_FMPI2C_SetMasterAddressingMode - * @param FMPI2Cx FMPI2C Instance. - * @param AddressingMode This parameter can be one of the following values: - * @arg @ref LL_FMPI2C_ADDRESSING_MODE_7BIT - * @arg @ref LL_FMPI2C_ADDRESSING_MODE_10BIT - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_SetMasterAddressingMode(FMPI2C_TypeDef *FMPI2Cx, uint32_t AddressingMode) -{ - MODIFY_REG(FMPI2Cx->CR2, FMPI2C_CR2_ADD10, AddressingMode); -} - -/** - * @brief Get the Master addressing mode. - * @rmtoll CR2 ADD10 LL_FMPI2C_GetMasterAddressingMode - * @param FMPI2Cx FMPI2C Instance. - * @retval Returned value can be one of the following values: - * @arg @ref LL_FMPI2C_ADDRESSING_MODE_7BIT - * @arg @ref LL_FMPI2C_ADDRESSING_MODE_10BIT - */ -__STATIC_INLINE uint32_t LL_FMPI2C_GetMasterAddressingMode(FMPI2C_TypeDef *FMPI2Cx) -{ - return (uint32_t)(READ_BIT(FMPI2Cx->CR2, FMPI2C_CR2_ADD10)); -} - -/** - * @brief Set the Own Address1. - * @rmtoll OAR1 OA1 LL_FMPI2C_SetOwnAddress1\n - * OAR1 OA1MODE LL_FMPI2C_SetOwnAddress1 - * @param FMPI2Cx FMPI2C Instance. - * @param OwnAddress1 This parameter must be a value between Min_Data=0 and Max_Data=0x3FF. - * @param OwnAddrSize This parameter can be one of the following values: - * @arg @ref LL_FMPI2C_OWNADDRESS1_7BIT - * @arg @ref LL_FMPI2C_OWNADDRESS1_10BIT - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_SetOwnAddress1(FMPI2C_TypeDef *FMPI2Cx, uint32_t OwnAddress1, uint32_t OwnAddrSize) -{ - MODIFY_REG(FMPI2Cx->OAR1, FMPI2C_OAR1_OA1 | FMPI2C_OAR1_OA1MODE, OwnAddress1 | OwnAddrSize); -} - -/** - * @brief Enable acknowledge on Own Address1 match address. - * @rmtoll OAR1 OA1EN LL_FMPI2C_EnableOwnAddress1 - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_EnableOwnAddress1(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->OAR1, FMPI2C_OAR1_OA1EN); -} - -/** - * @brief Disable acknowledge on Own Address1 match address. - * @rmtoll OAR1 OA1EN LL_FMPI2C_DisableOwnAddress1 - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_DisableOwnAddress1(FMPI2C_TypeDef *FMPI2Cx) -{ - CLEAR_BIT(FMPI2Cx->OAR1, FMPI2C_OAR1_OA1EN); -} - -/** - * @brief Check if Own Address1 acknowledge is enabled or disabled. - * @rmtoll OAR1 OA1EN LL_FMPI2C_IsEnabledOwnAddress1 - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabledOwnAddress1(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->OAR1, FMPI2C_OAR1_OA1EN) == (FMPI2C_OAR1_OA1EN)) ? 1UL : 0UL); -} - -/** - * @brief Set the 7bits Own Address2. - * @note This action has no effect if own address2 is enabled. - * @rmtoll OAR2 OA2 LL_FMPI2C_SetOwnAddress2\n - * OAR2 OA2MSK LL_FMPI2C_SetOwnAddress2 - * @param FMPI2Cx FMPI2C Instance. - * @param OwnAddress2 Value between Min_Data=0 and Max_Data=0x7F. - * @param OwnAddrMask This parameter can be one of the following values: - * @arg @ref LL_FMPI2C_OWNADDRESS2_NOMASK - * @arg @ref LL_FMPI2C_OWNADDRESS2_MASK01 - * @arg @ref LL_FMPI2C_OWNADDRESS2_MASK02 - * @arg @ref LL_FMPI2C_OWNADDRESS2_MASK03 - * @arg @ref LL_FMPI2C_OWNADDRESS2_MASK04 - * @arg @ref LL_FMPI2C_OWNADDRESS2_MASK05 - * @arg @ref LL_FMPI2C_OWNADDRESS2_MASK06 - * @arg @ref LL_FMPI2C_OWNADDRESS2_MASK07 - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_SetOwnAddress2(FMPI2C_TypeDef *FMPI2Cx, uint32_t OwnAddress2, uint32_t OwnAddrMask) -{ - MODIFY_REG(FMPI2Cx->OAR2, FMPI2C_OAR2_OA2 | FMPI2C_OAR2_OA2MSK, OwnAddress2 | OwnAddrMask); -} - -/** - * @brief Enable acknowledge on Own Address2 match address. - * @rmtoll OAR2 OA2EN LL_FMPI2C_EnableOwnAddress2 - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_EnableOwnAddress2(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->OAR2, FMPI2C_OAR2_OA2EN); -} - -/** - * @brief Disable acknowledge on Own Address2 match address. - * @rmtoll OAR2 OA2EN LL_FMPI2C_DisableOwnAddress2 - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_DisableOwnAddress2(FMPI2C_TypeDef *FMPI2Cx) -{ - CLEAR_BIT(FMPI2Cx->OAR2, FMPI2C_OAR2_OA2EN); -} - -/** - * @brief Check if Own Address1 acknowledge is enabled or disabled. - * @rmtoll OAR2 OA2EN LL_FMPI2C_IsEnabledOwnAddress2 - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabledOwnAddress2(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->OAR2, FMPI2C_OAR2_OA2EN) == (FMPI2C_OAR2_OA2EN)) ? 1UL : 0UL); -} - -/** - * @brief Configure the SDA setup, hold time and the SCL high, low period. - * @note This bit can only be programmed when the FMPI2C is disabled (PE = 0). - * @rmtoll TIMINGR TIMINGR LL_FMPI2C_SetTiming - * @param FMPI2Cx FMPI2C Instance. - * @param Timing This parameter must be a value between Min_Data=0 and Max_Data=0xFFFFFFFF. - * @note This parameter is computed with the STM32CubeMX Tool. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_SetTiming(FMPI2C_TypeDef *FMPI2Cx, uint32_t Timing) -{ - WRITE_REG(FMPI2Cx->TIMINGR, Timing); -} - -/** - * @brief Get the Timing Prescaler setting. - * @rmtoll TIMINGR PRESC LL_FMPI2C_GetTimingPrescaler - * @param FMPI2Cx FMPI2C Instance. - * @retval Value between Min_Data=0x0 and Max_Data=0xF - */ -__STATIC_INLINE uint32_t LL_FMPI2C_GetTimingPrescaler(FMPI2C_TypeDef *FMPI2Cx) -{ - return (uint32_t)(READ_BIT(FMPI2Cx->TIMINGR, FMPI2C_TIMINGR_PRESC) >> FMPI2C_TIMINGR_PRESC_Pos); -} - -/** - * @brief Get the SCL low period setting. - * @rmtoll TIMINGR SCLL LL_FMPI2C_GetClockLowPeriod - * @param FMPI2Cx FMPI2C Instance. - * @retval Value between Min_Data=0x00 and Max_Data=0xFF - */ -__STATIC_INLINE uint32_t LL_FMPI2C_GetClockLowPeriod(FMPI2C_TypeDef *FMPI2Cx) -{ - return (uint32_t)(READ_BIT(FMPI2Cx->TIMINGR, FMPI2C_TIMINGR_SCLL) >> FMPI2C_TIMINGR_SCLL_Pos); -} - -/** - * @brief Get the SCL high period setting. - * @rmtoll TIMINGR SCLH LL_FMPI2C_GetClockHighPeriod - * @param FMPI2Cx FMPI2C Instance. - * @retval Value between Min_Data=0x00 and Max_Data=0xFF - */ -__STATIC_INLINE uint32_t LL_FMPI2C_GetClockHighPeriod(FMPI2C_TypeDef *FMPI2Cx) -{ - return (uint32_t)(READ_BIT(FMPI2Cx->TIMINGR, FMPI2C_TIMINGR_SCLH) >> FMPI2C_TIMINGR_SCLH_Pos); -} - -/** - * @brief Get the SDA hold time. - * @rmtoll TIMINGR SDADEL LL_FMPI2C_GetDataHoldTime - * @param FMPI2Cx FMPI2C Instance. - * @retval Value between Min_Data=0x0 and Max_Data=0xF - */ -__STATIC_INLINE uint32_t LL_FMPI2C_GetDataHoldTime(FMPI2C_TypeDef *FMPI2Cx) -{ - return (uint32_t)(READ_BIT(FMPI2Cx->TIMINGR, FMPI2C_TIMINGR_SDADEL) >> FMPI2C_TIMINGR_SDADEL_Pos); -} - -/** - * @brief Get the SDA setup time. - * @rmtoll TIMINGR SCLDEL LL_FMPI2C_GetDataSetupTime - * @param FMPI2Cx FMPI2C Instance. - * @retval Value between Min_Data=0x0 and Max_Data=0xF - */ -__STATIC_INLINE uint32_t LL_FMPI2C_GetDataSetupTime(FMPI2C_TypeDef *FMPI2Cx) -{ - return (uint32_t)(READ_BIT(FMPI2Cx->TIMINGR, FMPI2C_TIMINGR_SCLDEL) >> FMPI2C_TIMINGR_SCLDEL_Pos); -} - -/** - * @brief Configure peripheral mode. - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @rmtoll CR1 SMBHEN LL_FMPI2C_SetMode\n - * CR1 SMBDEN LL_FMPI2C_SetMode - * @param FMPI2Cx FMPI2C Instance. - * @param PeripheralMode This parameter can be one of the following values: - * @arg @ref LL_FMPI2C_MODE_I2C - * @arg @ref LL_FMPI2C_MODE_SMBUS_HOST - * @arg @ref LL_FMPI2C_MODE_SMBUS_DEVICE - * @arg @ref LL_FMPI2C_MODE_SMBUS_DEVICE_ARP - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_SetMode(FMPI2C_TypeDef *FMPI2Cx, uint32_t PeripheralMode) -{ - MODIFY_REG(FMPI2Cx->CR1, FMPI2C_CR1_SMBHEN | FMPI2C_CR1_SMBDEN, PeripheralMode); -} - -/** - * @brief Get peripheral mode. - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @rmtoll CR1 SMBHEN LL_FMPI2C_GetMode\n - * CR1 SMBDEN LL_FMPI2C_GetMode - * @param FMPI2Cx FMPI2C Instance. - * @retval Returned value can be one of the following values: - * @arg @ref LL_FMPI2C_MODE_I2C - * @arg @ref LL_FMPI2C_MODE_SMBUS_HOST - * @arg @ref LL_FMPI2C_MODE_SMBUS_DEVICE - * @arg @ref LL_FMPI2C_MODE_SMBUS_DEVICE_ARP - */ -__STATIC_INLINE uint32_t LL_FMPI2C_GetMode(FMPI2C_TypeDef *FMPI2Cx) -{ - return (uint32_t)(READ_BIT(FMPI2Cx->CR1, FMPI2C_CR1_SMBHEN | FMPI2C_CR1_SMBDEN)); -} - -/** - * @brief Enable SMBus alert (Host or Device mode) - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @note SMBus Device mode: - * - SMBus Alert pin is drived low and - * Alert Response Address Header acknowledge is enabled. - * SMBus Host mode: - * - SMBus Alert pin management is supported. - * @rmtoll CR1 ALERTEN LL_FMPI2C_EnableSMBusAlert - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_EnableSMBusAlert(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->CR1, FMPI2C_CR1_ALERTEN); -} - -/** - * @brief Disable SMBus alert (Host or Device mode) - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @note SMBus Device mode: - * - SMBus Alert pin is not drived (can be used as a standard GPIO) and - * Alert Response Address Header acknowledge is disabled. - * SMBus Host mode: - * - SMBus Alert pin management is not supported. - * @rmtoll CR1 ALERTEN LL_FMPI2C_DisableSMBusAlert - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_DisableSMBusAlert(FMPI2C_TypeDef *FMPI2Cx) -{ - CLEAR_BIT(FMPI2Cx->CR1, FMPI2C_CR1_ALERTEN); -} - -/** - * @brief Check if SMBus alert (Host or Device mode) is enabled or disabled. - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @rmtoll CR1 ALERTEN LL_FMPI2C_IsEnabledSMBusAlert - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabledSMBusAlert(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->CR1, FMPI2C_CR1_ALERTEN) == (FMPI2C_CR1_ALERTEN)) ? 1UL : 0UL); -} - -/** - * @brief Enable SMBus Packet Error Calculation (PEC). - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @rmtoll CR1 PECEN LL_FMPI2C_EnableSMBusPEC - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_EnableSMBusPEC(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->CR1, FMPI2C_CR1_PECEN); -} - -/** - * @brief Disable SMBus Packet Error Calculation (PEC). - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @rmtoll CR1 PECEN LL_FMPI2C_DisableSMBusPEC - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_DisableSMBusPEC(FMPI2C_TypeDef *FMPI2Cx) -{ - CLEAR_BIT(FMPI2Cx->CR1, FMPI2C_CR1_PECEN); -} - -/** - * @brief Check if SMBus Packet Error Calculation (PEC) is enabled or disabled. - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @rmtoll CR1 PECEN LL_FMPI2C_IsEnabledSMBusPEC - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabledSMBusPEC(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->CR1, FMPI2C_CR1_PECEN) == (FMPI2C_CR1_PECEN)) ? 1UL : 0UL); -} - -/** - * @brief Configure the SMBus Clock Timeout. - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @note This configuration can only be programmed when associated Timeout is disabled (TimeoutA and/orTimeoutB). - * @rmtoll TIMEOUTR TIMEOUTA LL_FMPI2C_ConfigSMBusTimeout\n - * TIMEOUTR TIDLE LL_FMPI2C_ConfigSMBusTimeout\n - * TIMEOUTR TIMEOUTB LL_FMPI2C_ConfigSMBusTimeout - * @param FMPI2Cx FMPI2C Instance. - * @param TimeoutA This parameter must be a value between Min_Data=0 and Max_Data=0xFFF. - * @param TimeoutAMode This parameter can be one of the following values: - * @arg @ref LL_FMPI2C_FMPSMBUS_TIMEOUTA_MODE_SCL_LOW - * @arg @ref LL_FMPI2C_FMPSMBUS_TIMEOUTA_MODE_SDA_SCL_HIGH - * @param TimeoutB - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_ConfigSMBusTimeout(FMPI2C_TypeDef *FMPI2Cx, uint32_t TimeoutA, uint32_t TimeoutAMode, - uint32_t TimeoutB) -{ - MODIFY_REG(FMPI2Cx->TIMEOUTR, FMPI2C_TIMEOUTR_TIMEOUTA | FMPI2C_TIMEOUTR_TIDLE | FMPI2C_TIMEOUTR_TIMEOUTB, - TimeoutA | TimeoutAMode | (TimeoutB << FMPI2C_TIMEOUTR_TIMEOUTB_Pos)); -} - -/** - * @brief Configure the SMBus Clock TimeoutA (SCL low timeout or SCL and SDA high timeout depends on TimeoutA mode). - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @note These bits can only be programmed when TimeoutA is disabled. - * @rmtoll TIMEOUTR TIMEOUTA LL_FMPI2C_SetSMBusTimeoutA - * @param FMPI2Cx FMPI2C Instance. - * @param TimeoutA This parameter must be a value between Min_Data=0 and Max_Data=0xFFF. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_SetSMBusTimeoutA(FMPI2C_TypeDef *FMPI2Cx, uint32_t TimeoutA) -{ - WRITE_REG(FMPI2Cx->TIMEOUTR, TimeoutA); -} - -/** - * @brief Get the SMBus Clock TimeoutA setting. - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @rmtoll TIMEOUTR TIMEOUTA LL_FMPI2C_GetSMBusTimeoutA - * @param FMPI2Cx FMPI2C Instance. - * @retval Value between Min_Data=0 and Max_Data=0xFFF - */ -__STATIC_INLINE uint32_t LL_FMPI2C_GetSMBusTimeoutA(FMPI2C_TypeDef *FMPI2Cx) -{ - return (uint32_t)(READ_BIT(FMPI2Cx->TIMEOUTR, FMPI2C_TIMEOUTR_TIMEOUTA)); -} - -/** - * @brief Set the SMBus Clock TimeoutA mode. - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @note This bit can only be programmed when TimeoutA is disabled. - * @rmtoll TIMEOUTR TIDLE LL_FMPI2C_SetSMBusTimeoutAMode - * @param FMPI2Cx FMPI2C Instance. - * @param TimeoutAMode This parameter can be one of the following values: - * @arg @ref LL_FMPI2C_FMPSMBUS_TIMEOUTA_MODE_SCL_LOW - * @arg @ref LL_FMPI2C_FMPSMBUS_TIMEOUTA_MODE_SDA_SCL_HIGH - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_SetSMBusTimeoutAMode(FMPI2C_TypeDef *FMPI2Cx, uint32_t TimeoutAMode) -{ - WRITE_REG(FMPI2Cx->TIMEOUTR, TimeoutAMode); -} - -/** - * @brief Get the SMBus Clock TimeoutA mode. - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @rmtoll TIMEOUTR TIDLE LL_FMPI2C_GetSMBusTimeoutAMode - * @param FMPI2Cx FMPI2C Instance. - * @retval Returned value can be one of the following values: - * @arg @ref LL_FMPI2C_FMPSMBUS_TIMEOUTA_MODE_SCL_LOW - * @arg @ref LL_FMPI2C_FMPSMBUS_TIMEOUTA_MODE_SDA_SCL_HIGH - */ -__STATIC_INLINE uint32_t LL_FMPI2C_GetSMBusTimeoutAMode(FMPI2C_TypeDef *FMPI2Cx) -{ - return (uint32_t)(READ_BIT(FMPI2Cx->TIMEOUTR, FMPI2C_TIMEOUTR_TIDLE)); -} - -/** - * @brief Configure the SMBus Extended Cumulative Clock TimeoutB (Master or Slave mode). - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @note These bits can only be programmed when TimeoutB is disabled. - * @rmtoll TIMEOUTR TIMEOUTB LL_FMPI2C_SetSMBusTimeoutB - * @param FMPI2Cx FMPI2C Instance. - * @param TimeoutB This parameter must be a value between Min_Data=0 and Max_Data=0xFFF. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_SetSMBusTimeoutB(FMPI2C_TypeDef *FMPI2Cx, uint32_t TimeoutB) -{ - WRITE_REG(FMPI2Cx->TIMEOUTR, TimeoutB << FMPI2C_TIMEOUTR_TIMEOUTB_Pos); -} - -/** - * @brief Get the SMBus Extended Cumulative Clock TimeoutB setting. - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @rmtoll TIMEOUTR TIMEOUTB LL_FMPI2C_GetSMBusTimeoutB - * @param FMPI2Cx FMPI2C Instance. - * @retval Value between Min_Data=0 and Max_Data=0xFFF - */ -__STATIC_INLINE uint32_t LL_FMPI2C_GetSMBusTimeoutB(FMPI2C_TypeDef *FMPI2Cx) -{ - return (uint32_t)(READ_BIT(FMPI2Cx->TIMEOUTR, FMPI2C_TIMEOUTR_TIMEOUTB) >> FMPI2C_TIMEOUTR_TIMEOUTB_Pos); -} - -/** - * @brief Enable the SMBus Clock Timeout. - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @rmtoll TIMEOUTR TIMOUTEN LL_FMPI2C_EnableSMBusTimeout\n - * TIMEOUTR TEXTEN LL_FMPI2C_EnableSMBusTimeout - * @param FMPI2Cx FMPI2C Instance. - * @param ClockTimeout This parameter can be one of the following values: - * @arg @ref LL_FMPI2C_FMPSMBUS_TIMEOUTA - * @arg @ref LL_FMPI2C_FMPSMBUS_TIMEOUTB - * @arg @ref LL_FMPI2C_FMPSMBUS_ALL_TIMEOUT - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_EnableSMBusTimeout(FMPI2C_TypeDef *FMPI2Cx, uint32_t ClockTimeout) -{ - SET_BIT(FMPI2Cx->TIMEOUTR, ClockTimeout); -} - -/** - * @brief Disable the SMBus Clock Timeout. - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @rmtoll TIMEOUTR TIMOUTEN LL_FMPI2C_DisableSMBusTimeout\n - * TIMEOUTR TEXTEN LL_FMPI2C_DisableSMBusTimeout - * @param FMPI2Cx FMPI2C Instance. - * @param ClockTimeout This parameter can be one of the following values: - * @arg @ref LL_FMPI2C_FMPSMBUS_TIMEOUTA - * @arg @ref LL_FMPI2C_FMPSMBUS_TIMEOUTB - * @arg @ref LL_FMPI2C_FMPSMBUS_ALL_TIMEOUT - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_DisableSMBusTimeout(FMPI2C_TypeDef *FMPI2Cx, uint32_t ClockTimeout) -{ - CLEAR_BIT(FMPI2Cx->TIMEOUTR, ClockTimeout); -} - -/** - * @brief Check if the SMBus Clock Timeout is enabled or disabled. - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @rmtoll TIMEOUTR TIMOUTEN LL_FMPI2C_IsEnabledSMBusTimeout\n - * TIMEOUTR TEXTEN LL_FMPI2C_IsEnabledSMBusTimeout - * @param FMPI2Cx FMPI2C Instance. - * @param ClockTimeout This parameter can be one of the following values: - * @arg @ref LL_FMPI2C_FMPSMBUS_TIMEOUTA - * @arg @ref LL_FMPI2C_FMPSMBUS_TIMEOUTB - * @arg @ref LL_FMPI2C_FMPSMBUS_ALL_TIMEOUT - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabledSMBusTimeout(FMPI2C_TypeDef *FMPI2Cx, uint32_t ClockTimeout) -{ - return ((READ_BIT(FMPI2Cx->TIMEOUTR, (FMPI2C_TIMEOUTR_TIMOUTEN | FMPI2C_TIMEOUTR_TEXTEN)) == \ - (ClockTimeout)) ? 1UL : 0UL); -} - -/** - * @} - */ - -/** @defgroup FMPI2C_LL_EF_IT_Management IT_Management - * @{ - */ - -/** - * @brief Enable TXIS interrupt. - * @rmtoll CR1 TXIE LL_FMPI2C_EnableIT_TX - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_EnableIT_TX(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->CR1, FMPI2C_CR1_TXIE); -} - -/** - * @brief Disable TXIS interrupt. - * @rmtoll CR1 TXIE LL_FMPI2C_DisableIT_TX - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_DisableIT_TX(FMPI2C_TypeDef *FMPI2Cx) -{ - CLEAR_BIT(FMPI2Cx->CR1, FMPI2C_CR1_TXIE); -} - -/** - * @brief Check if the TXIS Interrupt is enabled or disabled. - * @rmtoll CR1 TXIE LL_FMPI2C_IsEnabledIT_TX - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabledIT_TX(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->CR1, FMPI2C_CR1_TXIE) == (FMPI2C_CR1_TXIE)) ? 1UL : 0UL); -} - -/** - * @brief Enable RXNE interrupt. - * @rmtoll CR1 RXIE LL_FMPI2C_EnableIT_RX - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_EnableIT_RX(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->CR1, FMPI2C_CR1_RXIE); -} - -/** - * @brief Disable RXNE interrupt. - * @rmtoll CR1 RXIE LL_FMPI2C_DisableIT_RX - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_DisableIT_RX(FMPI2C_TypeDef *FMPI2Cx) -{ - CLEAR_BIT(FMPI2Cx->CR1, FMPI2C_CR1_RXIE); -} - -/** - * @brief Check if the RXNE Interrupt is enabled or disabled. - * @rmtoll CR1 RXIE LL_FMPI2C_IsEnabledIT_RX - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabledIT_RX(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->CR1, FMPI2C_CR1_RXIE) == (FMPI2C_CR1_RXIE)) ? 1UL : 0UL); -} - -/** - * @brief Enable Address match interrupt (slave mode only). - * @rmtoll CR1 ADDRIE LL_FMPI2C_EnableIT_ADDR - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_EnableIT_ADDR(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->CR1, FMPI2C_CR1_ADDRIE); -} - -/** - * @brief Disable Address match interrupt (slave mode only). - * @rmtoll CR1 ADDRIE LL_FMPI2C_DisableIT_ADDR - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_DisableIT_ADDR(FMPI2C_TypeDef *FMPI2Cx) -{ - CLEAR_BIT(FMPI2Cx->CR1, FMPI2C_CR1_ADDRIE); -} - -/** - * @brief Check if Address match interrupt is enabled or disabled. - * @rmtoll CR1 ADDRIE LL_FMPI2C_IsEnabledIT_ADDR - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabledIT_ADDR(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->CR1, FMPI2C_CR1_ADDRIE) == (FMPI2C_CR1_ADDRIE)) ? 1UL : 0UL); -} - -/** - * @brief Enable Not acknowledge received interrupt. - * @rmtoll CR1 NACKIE LL_FMPI2C_EnableIT_NACK - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_EnableIT_NACK(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->CR1, FMPI2C_CR1_NACKIE); -} - -/** - * @brief Disable Not acknowledge received interrupt. - * @rmtoll CR1 NACKIE LL_FMPI2C_DisableIT_NACK - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_DisableIT_NACK(FMPI2C_TypeDef *FMPI2Cx) -{ - CLEAR_BIT(FMPI2Cx->CR1, FMPI2C_CR1_NACKIE); -} - -/** - * @brief Check if Not acknowledge received interrupt is enabled or disabled. - * @rmtoll CR1 NACKIE LL_FMPI2C_IsEnabledIT_NACK - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabledIT_NACK(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->CR1, FMPI2C_CR1_NACKIE) == (FMPI2C_CR1_NACKIE)) ? 1UL : 0UL); -} - -/** - * @brief Enable STOP detection interrupt. - * @rmtoll CR1 STOPIE LL_FMPI2C_EnableIT_STOP - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_EnableIT_STOP(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->CR1, FMPI2C_CR1_STOPIE); -} - -/** - * @brief Disable STOP detection interrupt. - * @rmtoll CR1 STOPIE LL_FMPI2C_DisableIT_STOP - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_DisableIT_STOP(FMPI2C_TypeDef *FMPI2Cx) -{ - CLEAR_BIT(FMPI2Cx->CR1, FMPI2C_CR1_STOPIE); -} - -/** - * @brief Check if STOP detection interrupt is enabled or disabled. - * @rmtoll CR1 STOPIE LL_FMPI2C_IsEnabledIT_STOP - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabledIT_STOP(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->CR1, FMPI2C_CR1_STOPIE) == (FMPI2C_CR1_STOPIE)) ? 1UL : 0UL); -} - -/** - * @brief Enable Transfer Complete interrupt. - * @note Any of these events will generate interrupt : - * Transfer Complete (TC) - * Transfer Complete Reload (TCR) - * @rmtoll CR1 TCIE LL_FMPI2C_EnableIT_TC - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_EnableIT_TC(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->CR1, FMPI2C_CR1_TCIE); -} - -/** - * @brief Disable Transfer Complete interrupt. - * @note Any of these events will generate interrupt : - * Transfer Complete (TC) - * Transfer Complete Reload (TCR) - * @rmtoll CR1 TCIE LL_FMPI2C_DisableIT_TC - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_DisableIT_TC(FMPI2C_TypeDef *FMPI2Cx) -{ - CLEAR_BIT(FMPI2Cx->CR1, FMPI2C_CR1_TCIE); -} - -/** - * @brief Check if Transfer Complete interrupt is enabled or disabled. - * @rmtoll CR1 TCIE LL_FMPI2C_IsEnabledIT_TC - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabledIT_TC(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->CR1, FMPI2C_CR1_TCIE) == (FMPI2C_CR1_TCIE)) ? 1UL : 0UL); -} - -/** - * @brief Enable Error interrupts. - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @note Any of these errors will generate interrupt : - * Arbitration Loss (ARLO) - * Bus Error detection (BERR) - * Overrun/Underrun (OVR) - * SMBus Timeout detection (TIMEOUT) - * SMBus PEC error detection (PECERR) - * SMBus Alert pin event detection (ALERT) - * @rmtoll CR1 ERRIE LL_FMPI2C_EnableIT_ERR - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_EnableIT_ERR(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->CR1, FMPI2C_CR1_ERRIE); -} - -/** - * @brief Disable Error interrupts. - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @note Any of these errors will generate interrupt : - * Arbitration Loss (ARLO) - * Bus Error detection (BERR) - * Overrun/Underrun (OVR) - * SMBus Timeout detection (TIMEOUT) - * SMBus PEC error detection (PECERR) - * SMBus Alert pin event detection (ALERT) - * @rmtoll CR1 ERRIE LL_FMPI2C_DisableIT_ERR - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_DisableIT_ERR(FMPI2C_TypeDef *FMPI2Cx) -{ - CLEAR_BIT(FMPI2Cx->CR1, FMPI2C_CR1_ERRIE); -} - -/** - * @brief Check if Error interrupts are enabled or disabled. - * @rmtoll CR1 ERRIE LL_FMPI2C_IsEnabledIT_ERR - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabledIT_ERR(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->CR1, FMPI2C_CR1_ERRIE) == (FMPI2C_CR1_ERRIE)) ? 1UL : 0UL); -} - -/** - * @} - */ - -/** @defgroup FMPI2C_LL_EF_FLAG_management FLAG_management - * @{ - */ - -/** - * @brief Indicate the status of Transmit data register empty flag. - * @note RESET: When next data is written in Transmit data register. - * SET: When Transmit data register is empty. - * @rmtoll ISR TXE LL_FMPI2C_IsActiveFlag_TXE - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsActiveFlag_TXE(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->ISR, FMPI2C_ISR_TXE) == (FMPI2C_ISR_TXE)) ? 1UL : 0UL); -} - -/** - * @brief Indicate the status of Transmit interrupt flag. - * @note RESET: When next data is written in Transmit data register. - * SET: When Transmit data register is empty. - * @rmtoll ISR TXIS LL_FMPI2C_IsActiveFlag_TXIS - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsActiveFlag_TXIS(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->ISR, FMPI2C_ISR_TXIS) == (FMPI2C_ISR_TXIS)) ? 1UL : 0UL); -} - -/** - * @brief Indicate the status of Receive data register not empty flag. - * @note RESET: When Receive data register is read. - * SET: When the received data is copied in Receive data register. - * @rmtoll ISR RXNE LL_FMPI2C_IsActiveFlag_RXNE - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsActiveFlag_RXNE(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->ISR, FMPI2C_ISR_RXNE) == (FMPI2C_ISR_RXNE)) ? 1UL : 0UL); -} - -/** - * @brief Indicate the status of Address matched flag (slave mode). - * @note RESET: Clear default value. - * SET: When the received slave address matched with one of the enabled slave address. - * @rmtoll ISR ADDR LL_FMPI2C_IsActiveFlag_ADDR - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsActiveFlag_ADDR(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->ISR, FMPI2C_ISR_ADDR) == (FMPI2C_ISR_ADDR)) ? 1UL : 0UL); -} - -/** - * @brief Indicate the status of Not Acknowledge received flag. - * @note RESET: Clear default value. - * SET: When a NACK is received after a byte transmission. - * @rmtoll ISR NACKF LL_FMPI2C_IsActiveFlag_NACK - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsActiveFlag_NACK(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->ISR, FMPI2C_ISR_NACKF) == (FMPI2C_ISR_NACKF)) ? 1UL : 0UL); -} - -/** - * @brief Indicate the status of Stop detection flag. - * @note RESET: Clear default value. - * SET: When a Stop condition is detected. - * @rmtoll ISR STOPF LL_FMPI2C_IsActiveFlag_STOP - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsActiveFlag_STOP(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->ISR, FMPI2C_ISR_STOPF) == (FMPI2C_ISR_STOPF)) ? 1UL : 0UL); -} - -/** - * @brief Indicate the status of Transfer complete flag (master mode). - * @note RESET: Clear default value. - * SET: When RELOAD=0, AUTOEND=0 and NBYTES date have been transferred. - * @rmtoll ISR TC LL_FMPI2C_IsActiveFlag_TC - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsActiveFlag_TC(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->ISR, FMPI2C_ISR_TC) == (FMPI2C_ISR_TC)) ? 1UL : 0UL); -} - -/** - * @brief Indicate the status of Transfer complete flag (master mode). - * @note RESET: Clear default value. - * SET: When RELOAD=1 and NBYTES date have been transferred. - * @rmtoll ISR TCR LL_FMPI2C_IsActiveFlag_TCR - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsActiveFlag_TCR(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->ISR, FMPI2C_ISR_TCR) == (FMPI2C_ISR_TCR)) ? 1UL : 0UL); -} - -/** - * @brief Indicate the status of Bus error flag. - * @note RESET: Clear default value. - * SET: When a misplaced Start or Stop condition is detected. - * @rmtoll ISR BERR LL_FMPI2C_IsActiveFlag_BERR - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsActiveFlag_BERR(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->ISR, FMPI2C_ISR_BERR) == (FMPI2C_ISR_BERR)) ? 1UL : 0UL); -} - -/** - * @brief Indicate the status of Arbitration lost flag. - * @note RESET: Clear default value. - * SET: When arbitration lost. - * @rmtoll ISR ARLO LL_FMPI2C_IsActiveFlag_ARLO - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsActiveFlag_ARLO(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->ISR, FMPI2C_ISR_ARLO) == (FMPI2C_ISR_ARLO)) ? 1UL : 0UL); -} - -/** - * @brief Indicate the status of Overrun/Underrun flag (slave mode). - * @note RESET: Clear default value. - * SET: When an overrun/underrun error occurs (Clock Stretching Disabled). - * @rmtoll ISR OVR LL_FMPI2C_IsActiveFlag_OVR - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsActiveFlag_OVR(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->ISR, FMPI2C_ISR_OVR) == (FMPI2C_ISR_OVR)) ? 1UL : 0UL); -} - -/** - * @brief Indicate the status of SMBus PEC error flag in reception. - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @note RESET: Clear default value. - * SET: When the received PEC does not match with the PEC register content. - * @rmtoll ISR PECERR LL_FMPI2C_IsActiveSMBusFlag_PECERR - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsActiveSMBusFlag_PECERR(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->ISR, FMPI2C_ISR_PECERR) == (FMPI2C_ISR_PECERR)) ? 1UL : 0UL); -} - -/** - * @brief Indicate the status of SMBus Timeout detection flag. - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @note RESET: Clear default value. - * SET: When a timeout or extended clock timeout occurs. - * @rmtoll ISR TIMEOUT LL_FMPI2C_IsActiveSMBusFlag_TIMEOUT - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsActiveSMBusFlag_TIMEOUT(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->ISR, FMPI2C_ISR_TIMEOUT) == (FMPI2C_ISR_TIMEOUT)) ? 1UL : 0UL); -} - -/** - * @brief Indicate the status of SMBus alert flag. - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @note RESET: Clear default value. - * SET: When SMBus host configuration, SMBus alert enabled and - * a falling edge event occurs on SMBA pin. - * @rmtoll ISR ALERT LL_FMPI2C_IsActiveSMBusFlag_ALERT - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsActiveSMBusFlag_ALERT(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->ISR, FMPI2C_ISR_ALERT) == (FMPI2C_ISR_ALERT)) ? 1UL : 0UL); -} - -/** - * @brief Indicate the status of Bus Busy flag. - * @note RESET: Clear default value. - * SET: When a Start condition is detected. - * @rmtoll ISR BUSY LL_FMPI2C_IsActiveFlag_BUSY - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsActiveFlag_BUSY(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->ISR, FMPI2C_ISR_BUSY) == (FMPI2C_ISR_BUSY)) ? 1UL : 0UL); -} - -/** - * @brief Clear Address Matched flag. - * @rmtoll ICR ADDRCF LL_FMPI2C_ClearFlag_ADDR - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_ClearFlag_ADDR(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->ICR, FMPI2C_ICR_ADDRCF); -} - -/** - * @brief Clear Not Acknowledge flag. - * @rmtoll ICR NACKCF LL_FMPI2C_ClearFlag_NACK - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_ClearFlag_NACK(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->ICR, FMPI2C_ICR_NACKCF); -} - -/** - * @brief Clear Stop detection flag. - * @rmtoll ICR STOPCF LL_FMPI2C_ClearFlag_STOP - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_ClearFlag_STOP(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->ICR, FMPI2C_ICR_STOPCF); -} - -/** - * @brief Clear Transmit data register empty flag (TXE). - * @note This bit can be clear by software in order to flush the transmit data register (TXDR). - * @rmtoll ISR TXE LL_FMPI2C_ClearFlag_TXE - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_ClearFlag_TXE(FMPI2C_TypeDef *FMPI2Cx) -{ - WRITE_REG(FMPI2Cx->ISR, FMPI2C_ISR_TXE); -} - -/** - * @brief Clear Bus error flag. - * @rmtoll ICR BERRCF LL_FMPI2C_ClearFlag_BERR - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_ClearFlag_BERR(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->ICR, FMPI2C_ICR_BERRCF); -} - -/** - * @brief Clear Arbitration lost flag. - * @rmtoll ICR ARLOCF LL_FMPI2C_ClearFlag_ARLO - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_ClearFlag_ARLO(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->ICR, FMPI2C_ICR_ARLOCF); -} - -/** - * @brief Clear Overrun/Underrun flag. - * @rmtoll ICR OVRCF LL_FMPI2C_ClearFlag_OVR - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_ClearFlag_OVR(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->ICR, FMPI2C_ICR_OVRCF); -} - -/** - * @brief Clear SMBus PEC error flag. - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @rmtoll ICR PECCF LL_FMPI2C_ClearSMBusFlag_PECERR - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_ClearSMBusFlag_PECERR(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->ICR, FMPI2C_ICR_PECCF); -} - -/** - * @brief Clear SMBus Timeout detection flag. - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @rmtoll ICR TIMOUTCF LL_FMPI2C_ClearSMBusFlag_TIMEOUT - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_ClearSMBusFlag_TIMEOUT(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->ICR, FMPI2C_ICR_TIMOUTCF); -} - -/** - * @brief Clear SMBus Alert flag. - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @rmtoll ICR ALERTCF LL_FMPI2C_ClearSMBusFlag_ALERT - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_ClearSMBusFlag_ALERT(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->ICR, FMPI2C_ICR_ALERTCF); -} - -/** - * @} - */ - -/** @defgroup FMPI2C_LL_EF_Data_Management Data_Management - * @{ - */ - -/** - * @brief Enable automatic STOP condition generation (master mode). - * @note Automatic end mode : a STOP condition is automatically sent when NBYTES data are transferred. - * This bit has no effect in slave mode or when RELOAD bit is set. - * @rmtoll CR2 AUTOEND LL_FMPI2C_EnableAutoEndMode - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_EnableAutoEndMode(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->CR2, FMPI2C_CR2_AUTOEND); -} - -/** - * @brief Disable automatic STOP condition generation (master mode). - * @note Software end mode : TC flag is set when NBYTES data are transferre, stretching SCL low. - * @rmtoll CR2 AUTOEND LL_FMPI2C_DisableAutoEndMode - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_DisableAutoEndMode(FMPI2C_TypeDef *FMPI2Cx) -{ - CLEAR_BIT(FMPI2Cx->CR2, FMPI2C_CR2_AUTOEND); -} - -/** - * @brief Check if automatic STOP condition is enabled or disabled. - * @rmtoll CR2 AUTOEND LL_FMPI2C_IsEnabledAutoEndMode - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabledAutoEndMode(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->CR2, FMPI2C_CR2_AUTOEND) == (FMPI2C_CR2_AUTOEND)) ? 1UL : 0UL); -} - -/** - * @brief Enable reload mode (master mode). - * @note The transfer is not completed after the NBYTES data transfer, NBYTES will be reloaded when TCR flag is set. - * @rmtoll CR2 RELOAD LL_FMPI2C_EnableReloadMode - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_EnableReloadMode(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->CR2, FMPI2C_CR2_RELOAD); -} - -/** - * @brief Disable reload mode (master mode). - * @note The transfer is completed after the NBYTES data transfer(STOP or RESTART will follow). - * @rmtoll CR2 RELOAD LL_FMPI2C_DisableReloadMode - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_DisableReloadMode(FMPI2C_TypeDef *FMPI2Cx) -{ - CLEAR_BIT(FMPI2Cx->CR2, FMPI2C_CR2_RELOAD); -} - -/** - * @brief Check if reload mode is enabled or disabled. - * @rmtoll CR2 RELOAD LL_FMPI2C_IsEnabledReloadMode - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabledReloadMode(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->CR2, FMPI2C_CR2_RELOAD) == (FMPI2C_CR2_RELOAD)) ? 1UL : 0UL); -} - -/** - * @brief Configure the number of bytes for transfer. - * @note Changing these bits when START bit is set is not allowed. - * @rmtoll CR2 NBYTES LL_FMPI2C_SetTransferSize - * @param FMPI2Cx FMPI2C Instance. - * @param TransferSize This parameter must be a value between Min_Data=0x00 and Max_Data=0xFF. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_SetTransferSize(FMPI2C_TypeDef *FMPI2Cx, uint32_t TransferSize) -{ - MODIFY_REG(FMPI2Cx->CR2, FMPI2C_CR2_NBYTES, TransferSize << FMPI2C_CR2_NBYTES_Pos); -} - -/** - * @brief Get the number of bytes configured for transfer. - * @rmtoll CR2 NBYTES LL_FMPI2C_GetTransferSize - * @param FMPI2Cx FMPI2C Instance. - * @retval Value between Min_Data=0x0 and Max_Data=0xFF - */ -__STATIC_INLINE uint32_t LL_FMPI2C_GetTransferSize(FMPI2C_TypeDef *FMPI2Cx) -{ - return (uint32_t)(READ_BIT(FMPI2Cx->CR2, FMPI2C_CR2_NBYTES) >> FMPI2C_CR2_NBYTES_Pos); -} - -/** - * @brief Prepare the generation of a ACKnowledge or Non ACKnowledge condition after the address receive match code - or next received byte. - * @note Usage in Slave mode only. - * @rmtoll CR2 NACK LL_FMPI2C_AcknowledgeNextData - * @param FMPI2Cx FMPI2C Instance. - * @param TypeAcknowledge This parameter can be one of the following values: - * @arg @ref LL_FMPI2C_ACK - * @arg @ref LL_FMPI2C_NACK - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_AcknowledgeNextData(FMPI2C_TypeDef *FMPI2Cx, uint32_t TypeAcknowledge) -{ - MODIFY_REG(FMPI2Cx->CR2, FMPI2C_CR2_NACK, TypeAcknowledge); -} - -/** - * @brief Generate a START or RESTART condition - * @note The START bit can be set even if bus is BUSY or FMPI2C is in slave mode. - * This action has no effect when RELOAD is set. - * @rmtoll CR2 START LL_FMPI2C_GenerateStartCondition - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_GenerateStartCondition(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->CR2, FMPI2C_CR2_START); -} - -/** - * @brief Generate a STOP condition after the current byte transfer (master mode). - * @rmtoll CR2 STOP LL_FMPI2C_GenerateStopCondition - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_GenerateStopCondition(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->CR2, FMPI2C_CR2_STOP); -} - -/** - * @brief Enable automatic RESTART Read request condition for 10bit address header (master mode). - * @note The master sends the complete 10bit slave address read sequence : - * Start + 2 bytes 10bit address in Write direction + Restart + first 7 bits of 10bit address - in Read direction. - * @rmtoll CR2 HEAD10R LL_FMPI2C_EnableAuto10BitRead - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_EnableAuto10BitRead(FMPI2C_TypeDef *FMPI2Cx) -{ - CLEAR_BIT(FMPI2Cx->CR2, FMPI2C_CR2_HEAD10R); -} - -/** - * @brief Disable automatic RESTART Read request condition for 10bit address header (master mode). - * @note The master only sends the first 7 bits of 10bit address in Read direction. - * @rmtoll CR2 HEAD10R LL_FMPI2C_DisableAuto10BitRead - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_DisableAuto10BitRead(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->CR2, FMPI2C_CR2_HEAD10R); -} - -/** - * @brief Check if automatic RESTART Read request condition for 10bit address header is enabled or disabled. - * @rmtoll CR2 HEAD10R LL_FMPI2C_IsEnabledAuto10BitRead - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabledAuto10BitRead(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->CR2, FMPI2C_CR2_HEAD10R) != (FMPI2C_CR2_HEAD10R)) ? 1UL : 0UL); -} - -/** - * @brief Configure the transfer direction (master mode). - * @note Changing these bits when START bit is set is not allowed. - * @rmtoll CR2 RD_WRN LL_FMPI2C_SetTransferRequest - * @param FMPI2Cx FMPI2C Instance. - * @param TransferRequest This parameter can be one of the following values: - * @arg @ref LL_FMPI2C_REQUEST_WRITE - * @arg @ref LL_FMPI2C_REQUEST_READ - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_SetTransferRequest(FMPI2C_TypeDef *FMPI2Cx, uint32_t TransferRequest) -{ - MODIFY_REG(FMPI2Cx->CR2, FMPI2C_CR2_RD_WRN, TransferRequest); -} - -/** - * @brief Get the transfer direction requested (master mode). - * @rmtoll CR2 RD_WRN LL_FMPI2C_GetTransferRequest - * @param FMPI2Cx FMPI2C Instance. - * @retval Returned value can be one of the following values: - * @arg @ref LL_FMPI2C_REQUEST_WRITE - * @arg @ref LL_FMPI2C_REQUEST_READ - */ -__STATIC_INLINE uint32_t LL_FMPI2C_GetTransferRequest(FMPI2C_TypeDef *FMPI2Cx) -{ - return (uint32_t)(READ_BIT(FMPI2Cx->CR2, FMPI2C_CR2_RD_WRN)); -} - -/** - * @brief Configure the slave address for transfer (master mode). - * @note Changing these bits when START bit is set is not allowed. - * @rmtoll CR2 SADD LL_FMPI2C_SetSlaveAddr - * @param FMPI2Cx FMPI2C Instance. - * @param SlaveAddr This parameter must be a value between Min_Data=0x00 and Max_Data=0x3F. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_SetSlaveAddr(FMPI2C_TypeDef *FMPI2Cx, uint32_t SlaveAddr) -{ - MODIFY_REG(FMPI2Cx->CR2, FMPI2C_CR2_SADD, SlaveAddr); -} - -/** - * @brief Get the slave address programmed for transfer. - * @rmtoll CR2 SADD LL_FMPI2C_GetSlaveAddr - * @param FMPI2Cx FMPI2C Instance. - * @retval Value between Min_Data=0x0 and Max_Data=0x3F - */ -__STATIC_INLINE uint32_t LL_FMPI2C_GetSlaveAddr(FMPI2C_TypeDef *FMPI2Cx) -{ - return (uint32_t)(READ_BIT(FMPI2Cx->CR2, FMPI2C_CR2_SADD)); -} - -/** - * @brief Handles FMPI2Cx communication when starting transfer or during transfer (TC or TCR flag are set). - * @rmtoll CR2 SADD LL_FMPI2C_HandleTransfer\n - * CR2 ADD10 LL_FMPI2C_HandleTransfer\n - * CR2 RD_WRN LL_FMPI2C_HandleTransfer\n - * CR2 START LL_FMPI2C_HandleTransfer\n - * CR2 STOP LL_FMPI2C_HandleTransfer\n - * CR2 RELOAD LL_FMPI2C_HandleTransfer\n - * CR2 NBYTES LL_FMPI2C_HandleTransfer\n - * CR2 AUTOEND LL_FMPI2C_HandleTransfer\n - * CR2 HEAD10R LL_FMPI2C_HandleTransfer - * @param FMPI2Cx FMPI2C Instance. - * @param SlaveAddr Specifies the slave address to be programmed. - * @param SlaveAddrSize This parameter can be one of the following values: - * @arg @ref LL_FMPI2C_ADDRSLAVE_7BIT - * @arg @ref LL_FMPI2C_ADDRSLAVE_10BIT - * @param TransferSize Specifies the number of bytes to be programmed. - * This parameter must be a value between Min_Data=0 and Max_Data=255. - * @param EndMode This parameter can be one of the following values: - * @arg @ref LL_FMPI2C_MODE_RELOAD - * @arg @ref LL_FMPI2C_MODE_AUTOEND - * @arg @ref LL_FMPI2C_MODE_SOFTEND - * @arg @ref LL_FMPI2C_MODE_SMBUS_RELOAD - * @arg @ref LL_FMPI2C_MODE_SMBUS_AUTOEND_NO_PEC - * @arg @ref LL_FMPI2C_MODE_SMBUS_SOFTEND_NO_PEC - * @arg @ref LL_FMPI2C_MODE_SMBUS_AUTOEND_WITH_PEC - * @arg @ref LL_FMPI2C_MODE_SMBUS_SOFTEND_WITH_PEC - * @param Request This parameter can be one of the following values: - * @arg @ref LL_FMPI2C_GENERATE_NOSTARTSTOP - * @arg @ref LL_FMPI2C_GENERATE_STOP - * @arg @ref LL_FMPI2C_GENERATE_START_READ - * @arg @ref LL_FMPI2C_GENERATE_START_WRITE - * @arg @ref LL_FMPI2C_GENERATE_RESTART_7BIT_READ - * @arg @ref LL_FMPI2C_GENERATE_RESTART_7BIT_WRITE - * @arg @ref LL_FMPI2C_GENERATE_RESTART_10BIT_READ - * @arg @ref LL_FMPI2C_GENERATE_RESTART_10BIT_WRITE - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_HandleTransfer(FMPI2C_TypeDef *FMPI2Cx, uint32_t SlaveAddr, uint32_t SlaveAddrSize, - uint32_t TransferSize, uint32_t EndMode, uint32_t Request) -{ - MODIFY_REG(FMPI2Cx->CR2, FMPI2C_CR2_SADD | FMPI2C_CR2_ADD10 | - (FMPI2C_CR2_RD_WRN & (uint32_t)(Request >> (31U - FMPI2C_CR2_RD_WRN_Pos))) | - FMPI2C_CR2_START | FMPI2C_CR2_STOP | FMPI2C_CR2_RELOAD | - FMPI2C_CR2_NBYTES | FMPI2C_CR2_AUTOEND | FMPI2C_CR2_HEAD10R, - SlaveAddr | SlaveAddrSize | (TransferSize << FMPI2C_CR2_NBYTES_Pos) | EndMode | Request); -} - -/** - * @brief Indicate the value of transfer direction (slave mode). - * @note RESET: Write transfer, Slave enters in receiver mode. - * SET: Read transfer, Slave enters in transmitter mode. - * @rmtoll ISR DIR LL_FMPI2C_GetTransferDirection - * @param FMPI2Cx FMPI2C Instance. - * @retval Returned value can be one of the following values: - * @arg @ref LL_FMPI2C_DIRECTION_WRITE - * @arg @ref LL_FMPI2C_DIRECTION_READ - */ -__STATIC_INLINE uint32_t LL_FMPI2C_GetTransferDirection(FMPI2C_TypeDef *FMPI2Cx) -{ - return (uint32_t)(READ_BIT(FMPI2Cx->ISR, FMPI2C_ISR_DIR)); -} - -/** - * @brief Return the slave matched address. - * @rmtoll ISR ADDCODE LL_FMPI2C_GetAddressMatchCode - * @param FMPI2Cx FMPI2C Instance. - * @retval Value between Min_Data=0x00 and Max_Data=0x3F - */ -__STATIC_INLINE uint32_t LL_FMPI2C_GetAddressMatchCode(FMPI2C_TypeDef *FMPI2Cx) -{ - return (uint32_t)(READ_BIT(FMPI2Cx->ISR, FMPI2C_ISR_ADDCODE) >> FMPI2C_ISR_ADDCODE_Pos << 1); -} - -/** - * @brief Enable internal comparison of the SMBus Packet Error byte (transmission or reception mode). - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @note This feature is cleared by hardware when the PEC byte is transferred, or when a STOP condition - or an Address Matched is received. - * This bit has no effect when RELOAD bit is set. - * This bit has no effect in device mode when SBC bit is not set. - * @rmtoll CR2 PECBYTE LL_FMPI2C_EnableSMBusPECCompare - * @param FMPI2Cx FMPI2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_EnableSMBusPECCompare(FMPI2C_TypeDef *FMPI2Cx) -{ - SET_BIT(FMPI2Cx->CR2, FMPI2C_CR2_PECBYTE); -} - -/** - * @brief Check if the SMBus Packet Error byte internal comparison is requested or not. - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @rmtoll CR2 PECBYTE LL_FMPI2C_IsEnabledSMBusPECCompare - * @param FMPI2Cx FMPI2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FMPI2C_IsEnabledSMBusPECCompare(FMPI2C_TypeDef *FMPI2Cx) -{ - return ((READ_BIT(FMPI2Cx->CR2, FMPI2C_CR2_PECBYTE) == (FMPI2C_CR2_PECBYTE)) ? 1UL : 0UL); -} - -/** - * @brief Get the SMBus Packet Error byte calculated. - * @note The macro IS_FMPSMBUS_ALL_INSTANCE(FMPI2Cx) can be used to check whether or not - * SMBus feature is supported by the FMPI2Cx Instance. - * @rmtoll PECR PEC LL_FMPI2C_GetSMBusPEC - * @param FMPI2Cx FMPI2C Instance. - * @retval Value between Min_Data=0x00 and Max_Data=0xFF - */ -__STATIC_INLINE uint32_t LL_FMPI2C_GetSMBusPEC(FMPI2C_TypeDef *FMPI2Cx) -{ - return (uint32_t)(READ_BIT(FMPI2Cx->PECR, FMPI2C_PECR_PEC)); -} - -/** - * @brief Read Receive Data register. - * @rmtoll RXDR RXDATA LL_FMPI2C_ReceiveData8 - * @param FMPI2Cx FMPI2C Instance. - * @retval Value between Min_Data=0x00 and Max_Data=0xFF - */ -__STATIC_INLINE uint8_t LL_FMPI2C_ReceiveData8(FMPI2C_TypeDef *FMPI2Cx) -{ - return (uint8_t)(READ_BIT(FMPI2Cx->RXDR, FMPI2C_RXDR_RXDATA)); -} - -/** - * @brief Write in Transmit Data Register . - * @rmtoll TXDR TXDATA LL_FMPI2C_TransmitData8 - * @param FMPI2Cx FMPI2C Instance. - * @param Data Value between Min_Data=0x00 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_FMPI2C_TransmitData8(FMPI2C_TypeDef *FMPI2Cx, uint8_t Data) -{ - WRITE_REG(FMPI2Cx->TXDR, Data); -} - -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup FMPI2C_LL_EF_Init Initialization and de-initialization functions - * @{ - */ - -ErrorStatus LL_FMPI2C_Init(FMPI2C_TypeDef *FMPI2Cx, LL_FMPI2C_InitTypeDef *FMPI2C_InitStruct); -ErrorStatus LL_FMPI2C_DeInit(FMPI2C_TypeDef *FMPI2Cx); -void LL_FMPI2C_StructInit(LL_FMPI2C_InitTypeDef *FMPI2C_InitStruct); - - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* FMPI2C1 */ - -/** - * @} - */ - -#endif /* FMPI2C_CR1_PE */ -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_LL_FMPI2C_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_fsmc.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_fsmc.h deleted file mode 100644 index 12f3a14..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_fsmc.h +++ /dev/null @@ -1,1033 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_fsmc.h - * @author MCD Application Team - * @brief Header file of FSMC HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_LL_FSMC_H -#define __STM32F4xx_LL_FSMC_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup FSMC_LL - * @{ - */ - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) || defined(STM32F412Zx) ||\ - defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F413xx) || defined(STM32F423xx) -/* Private types -------------------------------------------------------------*/ -/** @defgroup FSMC_LL_Private_Types FSMC Private Types - * @{ - */ - -/** - * @brief FSMC NORSRAM Configuration Structure definition - */ -typedef struct -{ - uint32_t NSBank; /*!< Specifies the NORSRAM memory device that will be used. - This parameter can be a value of @ref FSMC_NORSRAM_Bank */ - - uint32_t DataAddressMux; /*!< Specifies whether the address and data values are - multiplexed on the data bus or not. - This parameter can be a value of @ref FSMC_Data_Address_Bus_Multiplexing */ - - uint32_t MemoryType; /*!< Specifies the type of external memory attached to - the corresponding memory device. - This parameter can be a value of @ref FSMC_Memory_Type */ - - uint32_t MemoryDataWidth; /*!< Specifies the external memory device width. - This parameter can be a value of @ref FSMC_NORSRAM_Data_Width */ - - uint32_t BurstAccessMode; /*!< Enables or disables the burst access mode for Flash memory, - valid only with synchronous burst Flash memories. - This parameter can be a value of @ref FSMC_Burst_Access_Mode */ - - uint32_t WaitSignalPolarity; /*!< Specifies the wait signal polarity, valid only when accessing - the Flash memory in burst mode. - This parameter can be a value of @ref FSMC_Wait_Signal_Polarity */ - - uint32_t WrapMode; /*!< Enables or disables the Wrapped burst access mode for Flash - memory, valid only when accessing Flash memories in burst mode. - This parameter can be a value of @ref FSMC_Wrap_Mode - This mode is available only for the STM32F405/407/4015/417xx devices */ - - uint32_t WaitSignalActive; /*!< Specifies if the wait signal is asserted by the memory one - clock cycle before the wait state or during the wait state, - valid only when accessing memories in burst mode. - This parameter can be a value of @ref FSMC_Wait_Timing */ - - uint32_t WriteOperation; /*!< Enables or disables the write operation in the selected device by the FSMC. - This parameter can be a value of @ref FSMC_Write_Operation */ - - uint32_t WaitSignal; /*!< Enables or disables the wait state insertion via wait - signal, valid for Flash memory access in burst mode. - This parameter can be a value of @ref FSMC_Wait_Signal */ - - uint32_t ExtendedMode; /*!< Enables or disables the extended mode. - This parameter can be a value of @ref FSMC_Extended_Mode */ - - uint32_t AsynchronousWait; /*!< Enables or disables wait signal during asynchronous transfers, - valid only with asynchronous Flash memories. - This parameter can be a value of @ref FSMC_AsynchronousWait */ - - uint32_t WriteBurst; /*!< Enables or disables the write burst operation. - This parameter can be a value of @ref FSMC_Write_Burst */ - - uint32_t ContinuousClock; /*!< Enables or disables the FMC clock output to external memory devices. - This parameter is only enabled through the FMC_BCR1 register, and don't care - through FMC_BCR2..4 registers. - This parameter can be a value of @ref FMC_Continous_Clock - This mode is available only for the STM32F412Vx/Zx/Rx devices */ - - uint32_t WriteFifo; /*!< Enables or disables the write FIFO used by the FMC controller. - This parameter is only enabled through the FMC_BCR1 register, and don't care - through FMC_BCR2..4 registers. - This parameter can be a value of @ref FMC_Write_FIFO - This mode is available only for the STM32F412Vx/Vx devices */ - - uint32_t PageSize; /*!< Specifies the memory page size. - This parameter can be a value of @ref FMC_Page_Size */ -}FSMC_NORSRAM_InitTypeDef; - -/** - * @brief FSMC NORSRAM Timing parameters structure definition - */ -typedef struct -{ - uint32_t AddressSetupTime; /*!< Defines the number of HCLK cycles to configure - the duration of the address setup time. - This parameter can be a value between Min_Data = 0 and Max_Data = 15. - @note This parameter is not used with synchronous NOR Flash memories. */ - - uint32_t AddressHoldTime; /*!< Defines the number of HCLK cycles to configure - the duration of the address hold time. - This parameter can be a value between Min_Data = 1 and Max_Data = 15. - @note This parameter is not used with synchronous NOR Flash memories. */ - - uint32_t DataSetupTime; /*!< Defines the number of HCLK cycles to configure - the duration of the data setup time. - This parameter can be a value between Min_Data = 1 and Max_Data = 255. - @note This parameter is used for SRAMs, ROMs and asynchronous multiplexed - NOR Flash memories. */ - - uint32_t BusTurnAroundDuration; /*!< Defines the number of HCLK cycles to configure - the duration of the bus turnaround. - This parameter can be a value between Min_Data = 0 and Max_Data = 15. - @note This parameter is only used for multiplexed NOR Flash memories. */ - - uint32_t CLKDivision; /*!< Defines the period of CLK clock output signal, expressed in number of - HCLK cycles. This parameter can be a value between Min_Data = 2 and Max_Data = 16. - @note This parameter is not used for asynchronous NOR Flash, SRAM or ROM - accesses. */ - - uint32_t DataLatency; /*!< Defines the number of memory clock cycles to issue - to the memory before getting the first data. - The parameter value depends on the memory type as shown below: - - It must be set to 0 in case of a CRAM - - It is don't care in asynchronous NOR, SRAM or ROM accesses - - It may assume a value between Min_Data = 2 and Max_Data = 17 in NOR Flash memories - with synchronous burst mode enable */ - - uint32_t AccessMode; /*!< Specifies the asynchronous access mode. - This parameter can be a value of @ref FSMC_Access_Mode */ - -}FSMC_NORSRAM_TimingTypeDef; - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) -/** - * @brief FSMC NAND Configuration Structure definition - */ -typedef struct -{ - uint32_t NandBank; /*!< Specifies the NAND memory device that will be used. - This parameter can be a value of @ref FSMC_NAND_Bank */ - - uint32_t Waitfeature; /*!< Enables or disables the Wait feature for the NAND Memory device. - This parameter can be any value of @ref FSMC_Wait_feature */ - - uint32_t MemoryDataWidth; /*!< Specifies the external memory device width. - This parameter can be any value of @ref FSMC_NAND_Data_Width */ - - uint32_t EccComputation; /*!< Enables or disables the ECC computation. - This parameter can be any value of @ref FSMC_ECC */ - - uint32_t ECCPageSize; /*!< Defines the page size for the extended ECC. - This parameter can be any value of @ref FSMC_ECC_Page_Size */ - - uint32_t TCLRSetupTime; /*!< Defines the number of HCLK cycles to configure the - delay between CLE low and RE low. - This parameter can be a value between Min_Data = 0 and Max_Data = 255 */ - - uint32_t TARSetupTime; /*!< Defines the number of HCLK cycles to configure the - delay between ALE low and RE low. - This parameter can be a number between Min_Data = 0 and Max_Data = 255 */ - -}FSMC_NAND_InitTypeDef; - -/** - * @brief FSMC NAND/PCCARD Timing parameters structure definition - */ -typedef struct -{ - uint32_t SetupTime; /*!< Defines the number of HCLK cycles to setup address before - the command assertion for NAND-Flash read or write access - to common/Attribute or I/O memory space (depending on - the memory space timing to be configured). - This parameter can be a value between Min_Data = 0 and Max_Data = 255 */ - - uint32_t WaitSetupTime; /*!< Defines the minimum number of HCLK cycles to assert the - command for NAND-Flash read or write access to - common/Attribute or I/O memory space (depending on the - memory space timing to be configured). - This parameter can be a number between Min_Data = 0 and Max_Data = 255 */ - - uint32_t HoldSetupTime; /*!< Defines the number of HCLK clock cycles to hold address - (and data for write access) after the command de-assertion - for NAND-Flash read or write access to common/Attribute - or I/O memory space (depending on the memory space timing - to be configured). - This parameter can be a number between Min_Data = 0 and Max_Data = 255 */ - - uint32_t HiZSetupTime; /*!< Defines the number of HCLK clock cycles during which the - data bus is kept in HiZ after the start of a NAND-Flash - write access to common/Attribute or I/O memory space (depending - on the memory space timing to be configured). - This parameter can be a number between Min_Data = 0 and Max_Data = 255 */ - -}FSMC_NAND_PCC_TimingTypeDef; - -/** - * @brief FSMC NAND Configuration Structure definition - */ -typedef struct -{ - uint32_t Waitfeature; /*!< Enables or disables the Wait feature for the PCCARD Memory device. - This parameter can be any value of @ref FSMC_Wait_feature */ - - uint32_t TCLRSetupTime; /*!< Defines the number of HCLK cycles to configure the - delay between CLE low and RE low. - This parameter can be a value between Min_Data = 0 and Max_Data = 255 */ - - uint32_t TARSetupTime; /*!< Defines the number of HCLK cycles to configure the - delay between ALE low and RE low. - This parameter can be a number between Min_Data = 0 and Max_Data = 255 */ - -}FSMC_PCCARD_InitTypeDef; -/** - * @} - */ -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup FSMC_LL_Private_Constants FSMC Private Constants - * @{ - */ - -/** @defgroup FSMC_LL_NOR_SRAM_Controller FSMC NOR/SRAM Controller - * @{ - */ -/** @defgroup FSMC_NORSRAM_Bank FSMC NOR/SRAM Bank - * @{ - */ -#define FSMC_NORSRAM_BANK1 0x00000000U -#define FSMC_NORSRAM_BANK2 0x00000002U -#define FSMC_NORSRAM_BANK3 0x00000004U -#define FSMC_NORSRAM_BANK4 0x00000006U -/** - * @} - */ - -/** @defgroup FSMC_Data_Address_Bus_Multiplexing FSMC Data Address Bus Multiplexing - * @{ - */ -#define FSMC_DATA_ADDRESS_MUX_DISABLE 0x00000000U -#define FSMC_DATA_ADDRESS_MUX_ENABLE 0x00000002U -/** - * @} - */ - -/** @defgroup FSMC_Memory_Type FSMC Memory Type - * @{ - */ -#define FSMC_MEMORY_TYPE_SRAM 0x00000000U -#define FSMC_MEMORY_TYPE_PSRAM 0x00000004U -#define FSMC_MEMORY_TYPE_NOR 0x00000008U -/** - * @} - */ - -/** @defgroup FSMC_NORSRAM_Data_Width FSMC NOR/SRAM Data Width - * @{ - */ -#define FSMC_NORSRAM_MEM_BUS_WIDTH_8 0x00000000U -#define FSMC_NORSRAM_MEM_BUS_WIDTH_16 0x00000010U -#define FSMC_NORSRAM_MEM_BUS_WIDTH_32 0x00000020U -/** - * @} - */ - -/** @defgroup FSMC_NORSRAM_Flash_Access FSMC NOR/SRAM Flash Access - * @{ - */ -#define FSMC_NORSRAM_FLASH_ACCESS_ENABLE 0x00000040U -#define FSMC_NORSRAM_FLASH_ACCESS_DISABLE 0x00000000U -/** - * @} - */ - -/** @defgroup FSMC_Burst_Access_Mode FSMC Burst Access Mode - * @{ - */ -#define FSMC_BURST_ACCESS_MODE_DISABLE 0x00000000U -#define FSMC_BURST_ACCESS_MODE_ENABLE 0x00000100U -/** - * @} - */ - -/** @defgroup FSMC_Wait_Signal_Polarity FSMC Wait Signal Polarity - * @{ - */ -#define FSMC_WAIT_SIGNAL_POLARITY_LOW 0x00000000U -#define FSMC_WAIT_SIGNAL_POLARITY_HIGH 0x00000200U -/** - * @} - */ - -/** @defgroup FSMC_Wrap_Mode FSMC Wrap Mode - * @note These values are available only for the STM32F405/415/407/417xx devices. - * @{ - */ -#define FSMC_WRAP_MODE_DISABLE 0x00000000U -#define FSMC_WRAP_MODE_ENABLE 0x00000400U -/** - * @} - */ - -/** @defgroup FSMC_Wait_Timing FSMC Wait Timing - * @{ - */ -#define FSMC_WAIT_TIMING_BEFORE_WS 0x00000000U -#define FSMC_WAIT_TIMING_DURING_WS 0x00000800U -/** - * @} - */ - -/** @defgroup FSMC_Write_Operation FSMC Write Operation - * @{ - */ -#define FSMC_WRITE_OPERATION_DISABLE 0x00000000U -#define FSMC_WRITE_OPERATION_ENABLE 0x00001000U -/** - * @} - */ - -/** @defgroup FSMC_Wait_Signal FSMC Wait Signal - * @{ - */ -#define FSMC_WAIT_SIGNAL_DISABLE 0x00000000U -#define FSMC_WAIT_SIGNAL_ENABLE 0x00002000U -/** - * @} - */ - -/** @defgroup FSMC_Extended_Mode FSMC Extended Mode - * @{ - */ -#define FSMC_EXTENDED_MODE_DISABLE 0x00000000U -#define FSMC_EXTENDED_MODE_ENABLE 0x00004000U -/** - * @} - */ - -/** @defgroup FSMC_AsynchronousWait FSMC Asynchronous Wait - * @{ - */ -#define FSMC_ASYNCHRONOUS_WAIT_DISABLE 0x00000000U -#define FSMC_ASYNCHRONOUS_WAIT_ENABLE 0x00008000U -/** - * @} - */ - -/** @defgroup FSMC_Page_Size FSMC Page Size - * @{ - */ -#define FSMC_PAGE_SIZE_NONE 0x00000000U -#define FSMC_PAGE_SIZE_128 ((uint32_t)FSMC_BCR1_CPSIZE_0) -#define FSMC_PAGE_SIZE_256 ((uint32_t)FSMC_BCR1_CPSIZE_1) -#define FSMC_PAGE_SIZE_512 ((uint32_t)(FSMC_BCR1_CPSIZE_0 | FSMC_BCR1_CPSIZE_1)) -#define FSMC_PAGE_SIZE_1024 ((uint32_t)FSMC_BCR1_CPSIZE_2) -/** - * @} - */ - -/** @defgroup FSMC_Write_FIFO FSMC Write FIFO - * @note These values are available only for the STM32F412Vx/Zx/Rx devices. - * @{ - */ -#define FSMC_WRITE_FIFO_DISABLE ((uint32_t)FSMC_BCR1_WFDIS) -#define FSMC_WRITE_FIFO_ENABLE 0x00000000U -/** - * @} - */ - -/** @defgroup FSMC_Write_Burst FSMC Write Burst - * @{ - */ -#define FSMC_WRITE_BURST_DISABLE 0x00000000U -#define FSMC_WRITE_BURST_ENABLE 0x00080000U -/** - * @} - */ - -/** @defgroup FSMC_Continous_Clock FSMC Continous Clock - * @note These values are available only for the STM32F412Vx/Zx/Rx devices. - * @{ - */ -#define FSMC_CONTINUOUS_CLOCK_SYNC_ONLY 0x00000000U -#define FSMC_CONTINUOUS_CLOCK_SYNC_ASYNC 0x00100000U -/** - * @} - */ - -/** @defgroup FSMC_Access_Mode FSMC Access Mode - * @{ - */ -#define FSMC_ACCESS_MODE_A 0x00000000U -#define FSMC_ACCESS_MODE_B 0x10000000U -#define FSMC_ACCESS_MODE_C 0x20000000U -#define FSMC_ACCESS_MODE_D 0x30000000U -/** - * @} - */ -/** - * @} - */ - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) -/** @defgroup FSMC_LL_NAND_Controller FSMC NAND and PCCARD Controller - * @{ - */ -/** @defgroup FSMC_NAND_Bank FSMC NAND Bank - * @{ - */ -#define FSMC_NAND_BANK2 0x00000010U -#define FSMC_NAND_BANK3 0x00000100U -/** - * @} - */ - -/** @defgroup FSMC_Wait_feature FSMC Wait feature - * @{ - */ -#define FSMC_NAND_PCC_WAIT_FEATURE_DISABLE 0x00000000U -#define FSMC_NAND_PCC_WAIT_FEATURE_ENABLE 0x00000002U -/** - * @} - */ - -/** @defgroup FSMC_PCR_Memory_Type FSMC PCR Memory Type - * @{ - */ -#define FSMC_PCR_MEMORY_TYPE_PCCARD 0x00000000U -#define FSMC_PCR_MEMORY_TYPE_NAND 0x00000008U -/** - * @} - */ - -/** @defgroup FSMC_NAND_Data_Width FSMC NAND Data Width - * @{ - */ -#define FSMC_NAND_PCC_MEM_BUS_WIDTH_8 0x00000000U -#define FSMC_NAND_PCC_MEM_BUS_WIDTH_16 0x00000010U -/** - * @} - */ - -/** @defgroup FSMC_ECC FSMC ECC - * @{ - */ -#define FSMC_NAND_ECC_DISABLE 0x00000000U -#define FSMC_NAND_ECC_ENABLE 0x00000040U -/** - * @} - */ - -/** @defgroup FSMC_ECC_Page_Size FSMC ECC Page Size - * @{ - */ -#define FSMC_NAND_ECC_PAGE_SIZE_256BYTE 0x00000000U -#define FSMC_NAND_ECC_PAGE_SIZE_512BYTE 0x00020000U -#define FSMC_NAND_ECC_PAGE_SIZE_1024BYTE 0x00040000U -#define FSMC_NAND_ECC_PAGE_SIZE_2048BYTE 0x00060000U -#define FSMC_NAND_ECC_PAGE_SIZE_4096BYTE 0x00080000U -#define FSMC_NAND_ECC_PAGE_SIZE_8192BYTE 0x000A0000U -/** - * @} - */ -/** - * @} - */ -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ - -/** @defgroup FSMC_LL_Interrupt_definition FSMC Interrupt definition - * @{ - */ -#define FSMC_IT_RISING_EDGE 0x00000008U -#define FSMC_IT_LEVEL 0x00000010U -#define FSMC_IT_FALLING_EDGE 0x00000020U -#define FSMC_IT_REFRESH_ERROR 0x00004000U -/** - * @} - */ - -/** @defgroup FSMC_LL_Flag_definition FSMC Flag definition - * @{ - */ -#define FSMC_FLAG_RISING_EDGE 0x00000001U -#define FSMC_FLAG_LEVEL 0x00000002U -#define FSMC_FLAG_FALLING_EDGE 0x00000004U -#define FSMC_FLAG_FEMPT 0x00000040U -/** - * @} - */ - -/** @defgroup FSMC_LL_Alias_definition FSMC Alias definition - * @{ - */ -#define FSMC_NORSRAM_TypeDef FSMC_Bank1_TypeDef -#define FSMC_NORSRAM_EXTENDED_TypeDef FSMC_Bank1E_TypeDef -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) -#define FSMC_NAND_TypeDef FSMC_Bank2_3_TypeDef -#define FSMC_PCCARD_TypeDef FSMC_Bank4_TypeDef -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ - -#define FSMC_NORSRAM_DEVICE FSMC_Bank1 -#define FSMC_NORSRAM_EXTENDED_DEVICE FSMC_Bank1E -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) -#define FSMC_NAND_DEVICE FSMC_Bank2_3 -#define FSMC_PCCARD_DEVICE FSMC_Bank4 -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ - -#define FMC_NORSRAM_MEM_BUS_WIDTH_8 FSMC_NORSRAM_MEM_BUS_WIDTH_8 -#define FMC_NORSRAM_MEM_BUS_WIDTH_16 FSMC_NORSRAM_MEM_BUS_WIDTH_16 -#define FMC_NORSRAM_MEM_BUS_WIDTH_32 FSMC_NORSRAM_MEM_BUS_WIDTH_32 - -#define FMC_NORSRAM_TypeDef FSMC_NORSRAM_TypeDef -#define FMC_NORSRAM_EXTENDED_TypeDef FSMC_NORSRAM_EXTENDED_TypeDef -#define FMC_NORSRAM_InitTypeDef FSMC_NORSRAM_InitTypeDef -#define FMC_NORSRAM_TimingTypeDef FSMC_NORSRAM_TimingTypeDef - -#define FMC_NORSRAM_Init FSMC_NORSRAM_Init -#define FMC_NORSRAM_Timing_Init FSMC_NORSRAM_Timing_Init -#define FMC_NORSRAM_Extended_Timing_Init FSMC_NORSRAM_Extended_Timing_Init -#define FMC_NORSRAM_DeInit FSMC_NORSRAM_DeInit -#define FMC_NORSRAM_WriteOperation_Enable FSMC_NORSRAM_WriteOperation_Enable -#define FMC_NORSRAM_WriteOperation_Disable FSMC_NORSRAM_WriteOperation_Disable - -#define __FMC_NORSRAM_ENABLE __FSMC_NORSRAM_ENABLE -#define __FMC_NORSRAM_DISABLE __FSMC_NORSRAM_DISABLE - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) -#define FMC_NAND_InitTypeDef FSMC_NAND_InitTypeDef -#define FMC_PCCARD_InitTypeDef FSMC_PCCARD_InitTypeDef -#define FMC_NAND_PCC_TimingTypeDef FSMC_NAND_PCC_TimingTypeDef - -#define FMC_NAND_Init FSMC_NAND_Init -#define FMC_NAND_CommonSpace_Timing_Init FSMC_NAND_CommonSpace_Timing_Init -#define FMC_NAND_AttributeSpace_Timing_Init FSMC_NAND_AttributeSpace_Timing_Init -#define FMC_NAND_DeInit FSMC_NAND_DeInit -#define FMC_NAND_ECC_Enable FSMC_NAND_ECC_Enable -#define FMC_NAND_ECC_Disable FSMC_NAND_ECC_Disable -#define FMC_NAND_GetECC FSMC_NAND_GetECC -#define FMC_PCCARD_Init FSMC_PCCARD_Init -#define FMC_PCCARD_CommonSpace_Timing_Init FSMC_PCCARD_CommonSpace_Timing_Init -#define FMC_PCCARD_AttributeSpace_Timing_Init FSMC_PCCARD_AttributeSpace_Timing_Init -#define FMC_PCCARD_IOSpace_Timing_Init FSMC_PCCARD_IOSpace_Timing_Init -#define FMC_PCCARD_DeInit FSMC_PCCARD_DeInit - -#define __FMC_NAND_ENABLE __FSMC_NAND_ENABLE -#define __FMC_NAND_DISABLE __FSMC_NAND_DISABLE -#define __FMC_PCCARD_ENABLE __FSMC_PCCARD_ENABLE -#define __FMC_PCCARD_DISABLE __FSMC_PCCARD_DISABLE -#define __FMC_NAND_ENABLE_IT __FSMC_NAND_ENABLE_IT -#define __FMC_NAND_DISABLE_IT __FSMC_NAND_DISABLE_IT -#define __FMC_NAND_GET_FLAG __FSMC_NAND_GET_FLAG -#define __FMC_NAND_CLEAR_FLAG __FSMC_NAND_CLEAR_FLAG -#define __FMC_PCCARD_ENABLE_IT __FSMC_PCCARD_ENABLE_IT -#define __FMC_PCCARD_DISABLE_IT __FSMC_PCCARD_DISABLE_IT -#define __FMC_PCCARD_GET_FLAG __FSMC_PCCARD_GET_FLAG -#define __FMC_PCCARD_CLEAR_FLAG __FSMC_PCCARD_CLEAR_FLAG -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ - -#define FMC_NORSRAM_TypeDef FSMC_NORSRAM_TypeDef -#define FMC_NORSRAM_EXTENDED_TypeDef FSMC_NORSRAM_EXTENDED_TypeDef -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) -#define FMC_NAND_TypeDef FSMC_NAND_TypeDef -#define FMC_PCCARD_TypeDef FSMC_PCCARD_TypeDef -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ - -#define FMC_NORSRAM_DEVICE FSMC_NORSRAM_DEVICE -#define FMC_NORSRAM_EXTENDED_DEVICE FSMC_NORSRAM_EXTENDED_DEVICE -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) -#define FMC_NAND_DEVICE FSMC_NAND_DEVICE -#define FMC_PCCARD_DEVICE FSMC_PCCARD_DEVICE - -#define FMC_NAND_BANK2 FSMC_NAND_BANK2 -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ - -#define FMC_NORSRAM_BANK1 FSMC_NORSRAM_BANK1 -#define FMC_NORSRAM_BANK2 FSMC_NORSRAM_BANK2 -#define FMC_NORSRAM_BANK3 FSMC_NORSRAM_BANK3 - -#define FMC_IT_RISING_EDGE FSMC_IT_RISING_EDGE -#define FMC_IT_LEVEL FSMC_IT_LEVEL -#define FMC_IT_FALLING_EDGE FSMC_IT_FALLING_EDGE -#define FMC_IT_REFRESH_ERROR FSMC_IT_REFRESH_ERROR - -#define FMC_FLAG_RISING_EDGE FSMC_FLAG_RISING_EDGE -#define FMC_FLAG_LEVEL FSMC_FLAG_LEVEL -#define FMC_FLAG_FALLING_EDGE FSMC_FLAG_FALLING_EDGE -#define FMC_FLAG_FEMPT FSMC_FLAG_FEMPT -/** - * @} - */ - -/** - * @} - */ - -/* Private macro -------------------------------------------------------------*/ -/** @defgroup FSMC_LL_Private_Macros FSMC Private Macros - * @{ - */ - -/** @defgroup FSMC_LL_NOR_Macros FSMC NOR/SRAM Exported Macros - * @brief macros to handle NOR device enable/disable and read/write operations - * @{ - */ -/** - * @brief Enable the NORSRAM device access. - * @param __INSTANCE__ FSMC_NORSRAM Instance - * @param __BANK__ FSMC_NORSRAM Bank - * @retval none - */ -#define __FSMC_NORSRAM_ENABLE(__INSTANCE__, __BANK__) ((__INSTANCE__)->BTCR[(__BANK__)] |= FSMC_BCR1_MBKEN) - -/** - * @brief Disable the NORSRAM device access. - * @param __INSTANCE__ FSMC_NORSRAM Instance - * @param __BANK__ FSMC_NORSRAM Bank - * @retval none - */ -#define __FSMC_NORSRAM_DISABLE(__INSTANCE__, __BANK__) ((__INSTANCE__)->BTCR[(__BANK__)] &= ~FSMC_BCR1_MBKEN) -/** - * @} - */ - -/** @defgroup FSMC_LL_NAND_Macros FSMC NAND Macros - * @brief macros to handle NAND device enable/disable - * @{ - */ -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) -/** - * @brief Enable the NAND device access. - * @param __INSTANCE__ FSMC_NAND Instance - * @param __BANK__ FSMC_NAND Bank - * @retval none - */ -#define __FSMC_NAND_ENABLE(__INSTANCE__, __BANK__) (((__BANK__) == FSMC_NAND_BANK2)? ((__INSTANCE__)->PCR2 |= FSMC_PCR2_PBKEN): \ - ((__INSTANCE__)->PCR3 |= FSMC_PCR3_PBKEN)) - -/** - * @brief Disable the NAND device access. - * @param __INSTANCE__ FSMC_NAND Instance - * @param __BANK__ FSMC_NAND Bank - * @retval none - */ -#define __FSMC_NAND_DISABLE(__INSTANCE__, __BANK__) (((__BANK__) == FSMC_NAND_BANK2)? ((__INSTANCE__)->PCR2 &= ~FSMC_PCR2_PBKEN): \ - ((__INSTANCE__)->PCR3 &= ~FSMC_PCR3_PBKEN)) -/** - * @} - */ - -/** @defgroup FSMC_LL_PCCARD_Macros FSMC PCCARD Macros - * @brief macros to handle SRAM read/write operations - * @{ - */ -/** - * @brief Enable the PCCARD device access. - * @param __INSTANCE__ FSMC_PCCARD Instance - * @retval none - */ -#define __FSMC_PCCARD_ENABLE(__INSTANCE__) ((__INSTANCE__)->PCR4 |= FSMC_PCR4_PBKEN) - -/** - * @brief Disable the PCCARD device access. - * @param __INSTANCE__ FSMC_PCCARD Instance - * @retval none - */ -#define __FSMC_PCCARD_DISABLE(__INSTANCE__) ((__INSTANCE__)->PCR4 &= ~FSMC_PCR4_PBKEN) -/** - * @} - */ - -/** @defgroup FSMC_LL_Flag_Interrupt_Macros FSMC Flag&Interrupt Macros - * @brief macros to handle FSMC flags and interrupts - * @{ - */ -/** - * @brief Enable the NAND device interrupt. - * @param __INSTANCE__ FSMC_NAND Instance - * @param __BANK__ FSMC_NAND Bank - * @param __INTERRUPT__ FSMC_NAND interrupt - * This parameter can be any combination of the following values: - * @arg FSMC_IT_RISING_EDGE: Interrupt rising edge. - * @arg FSMC_IT_LEVEL: Interrupt level. - * @arg FSMC_IT_FALLING_EDGE: Interrupt falling edge. - * @retval None - */ -#define __FSMC_NAND_ENABLE_IT(__INSTANCE__, __BANK__, __INTERRUPT__) (((__BANK__) == FSMC_NAND_BANK2)? ((__INSTANCE__)->SR2 |= (__INTERRUPT__)): \ - ((__INSTANCE__)->SR3 |= (__INTERRUPT__))) - -/** - * @brief Disable the NAND device interrupt. - * @param __INSTANCE__ FSMC_NAND Instance - * @param __BANK__ FSMC_NAND Bank - * @param __INTERRUPT__ FSMC_NAND interrupt - * This parameter can be any combination of the following values: - * @arg FSMC_IT_RISING_EDGE: Interrupt rising edge. - * @arg FSMC_IT_LEVEL: Interrupt level. - * @arg FSMC_IT_FALLING_EDGE: Interrupt falling edge. - * @retval None - */ -#define __FSMC_NAND_DISABLE_IT(__INSTANCE__, __BANK__, __INTERRUPT__) (((__BANK__) == FSMC_NAND_BANK2)? ((__INSTANCE__)->SR2 &= ~(__INTERRUPT__)): \ - ((__INSTANCE__)->SR3 &= ~(__INTERRUPT__))) - -/** - * @brief Get flag status of the NAND device. - * @param __INSTANCE__ FSMC_NAND Instance - * @param __BANK__ FSMC_NAND Bank - * @param __FLAG__ FSMC_NAND flag - * This parameter can be any combination of the following values: - * @arg FSMC_FLAG_RISING_EDGE: Interrupt rising edge flag. - * @arg FSMC_FLAG_LEVEL: Interrupt level edge flag. - * @arg FSMC_FLAG_FALLING_EDGE: Interrupt falling edge flag. - * @arg FSMC_FLAG_FEMPT: FIFO empty flag. - * @retval The state of FLAG (SET or RESET). - */ -#define __FSMC_NAND_GET_FLAG(__INSTANCE__, __BANK__, __FLAG__) (((__BANK__) == FSMC_NAND_BANK2)? (((__INSTANCE__)->SR2 &(__FLAG__)) == (__FLAG__)): \ - (((__INSTANCE__)->SR3 &(__FLAG__)) == (__FLAG__))) - -/** - * @brief Clear flag status of the NAND device. - * @param __INSTANCE__ FSMC_NAND Instance - * @param __BANK__ FSMC_NAND Bank - * @param __FLAG__ FSMC_NAND flag - * This parameter can be any combination of the following values: - * @arg FSMC_FLAG_RISING_EDGE: Interrupt rising edge flag. - * @arg FSMC_FLAG_LEVEL: Interrupt level edge flag. - * @arg FSMC_FLAG_FALLING_EDGE: Interrupt falling edge flag. - * @arg FSMC_FLAG_FEMPT: FIFO empty flag. - * @retval None - */ -#define __FSMC_NAND_CLEAR_FLAG(__INSTANCE__, __BANK__, __FLAG__) (((__BANK__) == FSMC_NAND_BANK2)? ((__INSTANCE__)->SR2 &= ~(__FLAG__)): \ - ((__INSTANCE__)->SR3 &= ~(__FLAG__))) - -/** - * @brief Enable the PCCARD device interrupt. - * @param __INSTANCE__ FSMC_PCCARD Instance - * @param __INTERRUPT__ FSMC_PCCARD interrupt - * This parameter can be any combination of the following values: - * @arg FSMC_IT_RISING_EDGE: Interrupt rising edge. - * @arg FSMC_IT_LEVEL: Interrupt level. - * @arg FSMC_IT_FALLING_EDGE: Interrupt falling edge. - * @retval None - */ -#define __FSMC_PCCARD_ENABLE_IT(__INSTANCE__, __INTERRUPT__) ((__INSTANCE__)->SR4 |= (__INTERRUPT__)) - -/** - * @brief Disable the PCCARD device interrupt. - * @param __INSTANCE__ FSMC_PCCARD Instance - * @param __INTERRUPT__ FSMC_PCCARD interrupt - * This parameter can be any combination of the following values: - * @arg FSMC_IT_RISING_EDGE: Interrupt rising edge. - * @arg FSMC_IT_LEVEL: Interrupt level. - * @arg FSMC_IT_FALLING_EDGE: Interrupt falling edge. - * @retval None - */ -#define __FSMC_PCCARD_DISABLE_IT(__INSTANCE__, __INTERRUPT__) ((__INSTANCE__)->SR4 &= ~(__INTERRUPT__)) - -/** - * @brief Get flag status of the PCCARD device. - * @param __INSTANCE__ FSMC_PCCARD Instance - * @param __FLAG__ FSMC_PCCARD flag - * This parameter can be any combination of the following values: - * @arg FSMC_FLAG_RISING_EDGE: Interrupt rising edge flag. - * @arg FSMC_FLAG_LEVEL: Interrupt level edge flag. - * @arg FSMC_FLAG_FALLING_EDGE: Interrupt falling edge flag. - * @arg FSMC_FLAG_FEMPT: FIFO empty flag. - * @retval The state of FLAG (SET or RESET). - */ -#define __FSMC_PCCARD_GET_FLAG(__INSTANCE__, __FLAG__) (((__INSTANCE__)->SR4 &(__FLAG__)) == (__FLAG__)) - -/** - * @brief Clear flag status of the PCCARD device. - * @param __INSTANCE__ FSMC_PCCARD Instance - * @param __FLAG__ FSMC_PCCARD flag - * This parameter can be any combination of the following values: - * @arg FSMC_FLAG_RISING_EDGE: Interrupt rising edge flag. - * @arg FSMC_FLAG_LEVEL: Interrupt level edge flag. - * @arg FSMC_FLAG_FALLING_EDGE: Interrupt falling edge flag. - * @arg FSMC_FLAG_FEMPT: FIFO empty flag. - * @retval None - */ -#define __FSMC_PCCARD_CLEAR_FLAG(__INSTANCE__, __FLAG__) ((__INSTANCE__)->SR4 &= ~(__FLAG__)) -/** - * @} - */ -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ - -/** @defgroup FSMC_LL_Assert_Macros FSMC Assert Macros - * @{ - */ -#define IS_FSMC_NORSRAM_BANK(__BANK__) (((__BANK__) == FSMC_NORSRAM_BANK1) || \ - ((__BANK__) == FSMC_NORSRAM_BANK2) || \ - ((__BANK__) == FSMC_NORSRAM_BANK3) || \ - ((__BANK__) == FSMC_NORSRAM_BANK4)) - -#define IS_FSMC_MUX(__MUX__) (((__MUX__) == FSMC_DATA_ADDRESS_MUX_DISABLE) || \ - ((__MUX__) == FSMC_DATA_ADDRESS_MUX_ENABLE)) - -#define IS_FSMC_MEMORY(__MEMORY__) (((__MEMORY__) == FSMC_MEMORY_TYPE_SRAM) || \ - ((__MEMORY__) == FSMC_MEMORY_TYPE_PSRAM)|| \ - ((__MEMORY__) == FSMC_MEMORY_TYPE_NOR)) - -#define IS_FSMC_NORSRAM_MEMORY_WIDTH(__WIDTH__) (((__WIDTH__) == FSMC_NORSRAM_MEM_BUS_WIDTH_8) || \ - ((__WIDTH__) == FSMC_NORSRAM_MEM_BUS_WIDTH_16) || \ - ((__WIDTH__) == FSMC_NORSRAM_MEM_BUS_WIDTH_32)) - -#define IS_FSMC_ACCESS_MODE(__MODE__) (((__MODE__) == FSMC_ACCESS_MODE_A) || \ - ((__MODE__) == FSMC_ACCESS_MODE_B) || \ - ((__MODE__) == FSMC_ACCESS_MODE_C) || \ - ((__MODE__) == FSMC_ACCESS_MODE_D)) - -#define IS_FSMC_NAND_BANK(BANK) (((BANK) == FSMC_NAND_BANK2) || \ - ((BANK) == FSMC_NAND_BANK3)) - -#define IS_FSMC_WAIT_FEATURE(FEATURE) (((FEATURE) == FSMC_NAND_PCC_WAIT_FEATURE_DISABLE) || \ - ((FEATURE) == FSMC_NAND_PCC_WAIT_FEATURE_ENABLE)) - -#define IS_FSMC_NAND_MEMORY_WIDTH(WIDTH) (((WIDTH) == FSMC_NAND_PCC_MEM_BUS_WIDTH_8) || \ - ((WIDTH) == FSMC_NAND_PCC_MEM_BUS_WIDTH_16)) - -#define IS_FSMC_ECC_STATE(STATE) (((STATE) == FSMC_NAND_ECC_DISABLE) || \ - ((STATE) == FSMC_NAND_ECC_ENABLE)) - -#define IS_FSMC_ECCPAGE_SIZE(SIZE) (((SIZE) == FSMC_NAND_ECC_PAGE_SIZE_256BYTE) || \ - ((SIZE) == FSMC_NAND_ECC_PAGE_SIZE_512BYTE) || \ - ((SIZE) == FSMC_NAND_ECC_PAGE_SIZE_1024BYTE) || \ - ((SIZE) == FSMC_NAND_ECC_PAGE_SIZE_2048BYTE) || \ - ((SIZE) == FSMC_NAND_ECC_PAGE_SIZE_4096BYTE) || \ - ((SIZE) == FSMC_NAND_ECC_PAGE_SIZE_8192BYTE)) - -#define IS_FSMC_TCLR_TIME(TIME) ((TIME) <= 255U) - -#define IS_FSMC_TAR_TIME(TIME) ((TIME) <= 255U) - -#define IS_FSMC_SETUP_TIME(TIME) ((TIME) <= 255U) - -#define IS_FSMC_WAIT_TIME(TIME) ((TIME) <= 255U) - -#define IS_FSMC_HOLD_TIME(TIME) ((TIME) <= 255U) - -#define IS_FSMC_HIZ_TIME(TIME) ((TIME) <= 255U) - -#define IS_FSMC_NORSRAM_DEVICE(__INSTANCE__) ((__INSTANCE__) == FSMC_NORSRAM_DEVICE) - -#define IS_FSMC_NORSRAM_EXTENDED_DEVICE(__INSTANCE__) ((__INSTANCE__) == FSMC_NORSRAM_EXTENDED_DEVICE) - -#define IS_FSMC_NAND_DEVICE(INSTANCE) ((INSTANCE) == FSMC_NAND_DEVICE) - -#define IS_FSMC_PCCARD_DEVICE(INSTANCE) ((INSTANCE) == FSMC_PCCARD_DEVICE) - -#define IS_FSMC_BURSTMODE(__STATE__) (((__STATE__) == FSMC_BURST_ACCESS_MODE_DISABLE) || \ - ((__STATE__) == FSMC_BURST_ACCESS_MODE_ENABLE)) - -#define IS_FSMC_WAIT_POLARITY(__POLARITY__) (((__POLARITY__) == FSMC_WAIT_SIGNAL_POLARITY_LOW) || \ - ((__POLARITY__) == FSMC_WAIT_SIGNAL_POLARITY_HIGH)) - -#define IS_FSMC_WRAP_MODE(__MODE__) (((__MODE__) == FSMC_WRAP_MODE_DISABLE) || \ - ((__MODE__) == FSMC_WRAP_MODE_ENABLE)) - -#define IS_FSMC_WAIT_SIGNAL_ACTIVE(__ACTIVE__) (((__ACTIVE__) == FSMC_WAIT_TIMING_BEFORE_WS) || \ - ((__ACTIVE__) == FSMC_WAIT_TIMING_DURING_WS)) - -#define IS_FSMC_WRITE_OPERATION(__OPERATION__) (((__OPERATION__) == FSMC_WRITE_OPERATION_DISABLE) || \ - ((__OPERATION__) == FSMC_WRITE_OPERATION_ENABLE)) - -#define IS_FSMC_WAITE_SIGNAL(__SIGNAL__) (((__SIGNAL__) == FSMC_WAIT_SIGNAL_DISABLE) || \ - ((__SIGNAL__) == FSMC_WAIT_SIGNAL_ENABLE)) - -#define IS_FSMC_EXTENDED_MODE(__MODE__) (((__MODE__) == FSMC_EXTENDED_MODE_DISABLE) || \ - ((__MODE__) == FSMC_EXTENDED_MODE_ENABLE)) - -#define IS_FSMC_ASYNWAIT(__STATE__) (((__STATE__) == FSMC_ASYNCHRONOUS_WAIT_DISABLE) || \ - ((__STATE__) == FSMC_ASYNCHRONOUS_WAIT_ENABLE)) - -#define IS_FSMC_DATA_LATENCY(__LATENCY__) (((__LATENCY__) > 1U) && ((__LATENCY__) <= 17U)) - -#define IS_FSMC_WRITE_BURST(__BURST__) (((__BURST__) == FSMC_WRITE_BURST_DISABLE) || \ - ((__BURST__) == FSMC_WRITE_BURST_ENABLE)) - -#define IS_FSMC_ADDRESS_SETUP_TIME(__TIME__) ((__TIME__) <= 15U) - -#define IS_FSMC_ADDRESS_HOLD_TIME(__TIME__) (((__TIME__) > 0U) && ((__TIME__) <= 15U)) - -#define IS_FSMC_DATASETUP_TIME(__TIME__) (((__TIME__) > 0U) && ((__TIME__) <= 255U)) - -#define IS_FSMC_TURNAROUND_TIME(__TIME__) ((__TIME__) <= 15U) - -#define IS_FSMC_CONTINOUS_CLOCK(CCLOCK) (((CCLOCK) == FSMC_CONTINUOUS_CLOCK_SYNC_ONLY) || \ - ((CCLOCK) == FSMC_CONTINUOUS_CLOCK_SYNC_ASYNC)) - -#define IS_FSMC_CLK_DIV(DIV) (((DIV) > 1U) && ((DIV) <= 16U)) - -#define IS_FSMC_PAGESIZE(SIZE) (((SIZE) == FSMC_PAGE_SIZE_NONE) || \ - ((SIZE) == FSMC_PAGE_SIZE_128) || \ - ((SIZE) == FSMC_PAGE_SIZE_256) || \ - ((SIZE) == FSMC_PAGE_SIZE_512) || \ - ((SIZE) == FSMC_PAGE_SIZE_1024)) - -#define IS_FSMC_WRITE_FIFO(FIFO) (((FIFO) == FSMC_WRITE_FIFO_DISABLE) || \ - ((FIFO) == FSMC_WRITE_FIFO_ENABLE)) - -/** - * @} - */ -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup FSMC_LL_Private_Functions FSMC LL Private Functions - * @{ - */ - -/** @defgroup FSMC_LL_NORSRAM NOR SRAM - * @{ - */ - -/** @defgroup FSMC_LL_NORSRAM_Private_Functions_Group1 NOR SRAM Initialization/de-initialization functions - * @{ - */ -HAL_StatusTypeDef FSMC_NORSRAM_Init(FSMC_NORSRAM_TypeDef *Device, FSMC_NORSRAM_InitTypeDef *Init); -HAL_StatusTypeDef FSMC_NORSRAM_Timing_Init(FSMC_NORSRAM_TypeDef *Device, FSMC_NORSRAM_TimingTypeDef *Timing, uint32_t Bank); -HAL_StatusTypeDef FSMC_NORSRAM_Extended_Timing_Init(FSMC_NORSRAM_EXTENDED_TypeDef *Device, FSMC_NORSRAM_TimingTypeDef *Timing, uint32_t Bank, uint32_t ExtendedMode); -HAL_StatusTypeDef FSMC_NORSRAM_DeInit(FSMC_NORSRAM_TypeDef *Device, FSMC_NORSRAM_EXTENDED_TypeDef *ExDevice, uint32_t Bank); -/** - * @} - */ - -/** @defgroup FSMC_LL_NORSRAM_Private_Functions_Group2 NOR SRAM Control functions - * @{ - */ -HAL_StatusTypeDef FSMC_NORSRAM_WriteOperation_Enable(FSMC_NORSRAM_TypeDef *Device, uint32_t Bank); -HAL_StatusTypeDef FSMC_NORSRAM_WriteOperation_Disable(FSMC_NORSRAM_TypeDef *Device, uint32_t Bank); -/** - * @} - */ -/** - * @} - */ - -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) -/** @defgroup FSMC_LL_NAND NAND - * @{ - */ -/** @defgroup FSMC_LL_NAND_Private_Functions_Group1 NAND Initialization/de-initialization functions - * @{ - */ -HAL_StatusTypeDef FSMC_NAND_Init(FSMC_NAND_TypeDef *Device, FSMC_NAND_InitTypeDef *Init); -HAL_StatusTypeDef FSMC_NAND_CommonSpace_Timing_Init(FSMC_NAND_TypeDef *Device, FSMC_NAND_PCC_TimingTypeDef *Timing, uint32_t Bank); -HAL_StatusTypeDef FSMC_NAND_AttributeSpace_Timing_Init(FSMC_NAND_TypeDef *Device, FSMC_NAND_PCC_TimingTypeDef *Timing, uint32_t Bank); -HAL_StatusTypeDef FSMC_NAND_DeInit(FSMC_NAND_TypeDef *Device, uint32_t Bank); -/** - * @} - */ - -/** @defgroup FSMC_LL_NAND_Private_Functions_Group2 NAND Control functions - * @{ - */ -HAL_StatusTypeDef FSMC_NAND_ECC_Enable(FSMC_NAND_TypeDef *Device, uint32_t Bank); -HAL_StatusTypeDef FSMC_NAND_ECC_Disable(FSMC_NAND_TypeDef *Device, uint32_t Bank); -HAL_StatusTypeDef FSMC_NAND_GetECC(FSMC_NAND_TypeDef *Device, uint32_t *ECCval, uint32_t Bank, uint32_t Timeout); -/** - * @} - */ -/** - * @} - */ - -/** @defgroup FSMC_LL_PCCARD PCCARD - * @{ - */ -/** @defgroup FSMC_LL_PCCARD_Private_Functions_Group1 PCCARD Initialization/de-initialization functions - * @{ - */ -HAL_StatusTypeDef FSMC_PCCARD_Init(FSMC_PCCARD_TypeDef *Device, FSMC_PCCARD_InitTypeDef *Init); -HAL_StatusTypeDef FSMC_PCCARD_CommonSpace_Timing_Init(FSMC_PCCARD_TypeDef *Device, FSMC_NAND_PCC_TimingTypeDef *Timing); -HAL_StatusTypeDef FSMC_PCCARD_AttributeSpace_Timing_Init(FSMC_PCCARD_TypeDef *Device, FSMC_NAND_PCC_TimingTypeDef *Timing); -HAL_StatusTypeDef FSMC_PCCARD_IOSpace_Timing_Init(FSMC_PCCARD_TypeDef *Device, FSMC_NAND_PCC_TimingTypeDef *Timing); -HAL_StatusTypeDef FSMC_PCCARD_DeInit(FSMC_PCCARD_TypeDef *Device); -/** - * @} - */ -/** - * @} - */ -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ - -/** - * @} - */ -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_FSMC_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_gpio.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_gpio.h deleted file mode 100644 index 76e9170..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_gpio.h +++ /dev/null @@ -1,983 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_gpio.h - * @author MCD Application Team - * @brief Header file of GPIO LL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_LL_GPIO_H -#define __STM32F4xx_LL_GPIO_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (GPIOA) || defined (GPIOB) || defined (GPIOC) || defined (GPIOD) || defined (GPIOE) || defined (GPIOF) || defined (GPIOG) || defined (GPIOH) || defined (GPIOI) || defined (GPIOJ) || defined (GPIOK) - -/** @defgroup GPIO_LL GPIO - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup GPIO_LL_Private_Macros GPIO Private Macros - * @{ - */ - -/** - * @} - */ -#endif /*USE_FULL_LL_DRIVER*/ - -/* Exported types ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup GPIO_LL_ES_INIT GPIO Exported Init structures - * @{ - */ - -/** - * @brief LL GPIO Init Structure definition - */ -typedef struct -{ - uint32_t Pin; /*!< Specifies the GPIO pins to be configured. - This parameter can be any value of @ref GPIO_LL_EC_PIN */ - - uint32_t Mode; /*!< Specifies the operating mode for the selected pins. - This parameter can be a value of @ref GPIO_LL_EC_MODE. - - GPIO HW configuration can be modified afterwards using unitary function @ref LL_GPIO_SetPinMode().*/ - - uint32_t Speed; /*!< Specifies the speed for the selected pins. - This parameter can be a value of @ref GPIO_LL_EC_SPEED. - - GPIO HW configuration can be modified afterwards using unitary function @ref LL_GPIO_SetPinSpeed().*/ - - uint32_t OutputType; /*!< Specifies the operating output type for the selected pins. - This parameter can be a value of @ref GPIO_LL_EC_OUTPUT. - - GPIO HW configuration can be modified afterwards using unitary function @ref LL_GPIO_SetPinOutputType().*/ - - uint32_t Pull; /*!< Specifies the operating Pull-up/Pull down for the selected pins. - This parameter can be a value of @ref GPIO_LL_EC_PULL. - - GPIO HW configuration can be modified afterwards using unitary function @ref LL_GPIO_SetPinPull().*/ - - uint32_t Alternate; /*!< Specifies the Peripheral to be connected to the selected pins. - This parameter can be a value of @ref GPIO_LL_EC_AF. - - GPIO HW configuration can be modified afterwards using unitary function @ref LL_GPIO_SetAFPin_0_7() and LL_GPIO_SetAFPin_8_15().*/ -} LL_GPIO_InitTypeDef; - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup GPIO_LL_Exported_Constants GPIO Exported Constants - * @{ - */ - -/** @defgroup GPIO_LL_EC_PIN PIN - * @{ - */ -#define LL_GPIO_PIN_0 GPIO_BSRR_BS_0 /*!< Select pin 0 */ -#define LL_GPIO_PIN_1 GPIO_BSRR_BS_1 /*!< Select pin 1 */ -#define LL_GPIO_PIN_2 GPIO_BSRR_BS_2 /*!< Select pin 2 */ -#define LL_GPIO_PIN_3 GPIO_BSRR_BS_3 /*!< Select pin 3 */ -#define LL_GPIO_PIN_4 GPIO_BSRR_BS_4 /*!< Select pin 4 */ -#define LL_GPIO_PIN_5 GPIO_BSRR_BS_5 /*!< Select pin 5 */ -#define LL_GPIO_PIN_6 GPIO_BSRR_BS_6 /*!< Select pin 6 */ -#define LL_GPIO_PIN_7 GPIO_BSRR_BS_7 /*!< Select pin 7 */ -#define LL_GPIO_PIN_8 GPIO_BSRR_BS_8 /*!< Select pin 8 */ -#define LL_GPIO_PIN_9 GPIO_BSRR_BS_9 /*!< Select pin 9 */ -#define LL_GPIO_PIN_10 GPIO_BSRR_BS_10 /*!< Select pin 10 */ -#define LL_GPIO_PIN_11 GPIO_BSRR_BS_11 /*!< Select pin 11 */ -#define LL_GPIO_PIN_12 GPIO_BSRR_BS_12 /*!< Select pin 12 */ -#define LL_GPIO_PIN_13 GPIO_BSRR_BS_13 /*!< Select pin 13 */ -#define LL_GPIO_PIN_14 GPIO_BSRR_BS_14 /*!< Select pin 14 */ -#define LL_GPIO_PIN_15 GPIO_BSRR_BS_15 /*!< Select pin 15 */ -#define LL_GPIO_PIN_ALL (GPIO_BSRR_BS_0 | GPIO_BSRR_BS_1 | GPIO_BSRR_BS_2 | \ - GPIO_BSRR_BS_3 | GPIO_BSRR_BS_4 | GPIO_BSRR_BS_5 | \ - GPIO_BSRR_BS_6 | GPIO_BSRR_BS_7 | GPIO_BSRR_BS_8 | \ - GPIO_BSRR_BS_9 | GPIO_BSRR_BS_10 | GPIO_BSRR_BS_11 | \ - GPIO_BSRR_BS_12 | GPIO_BSRR_BS_13 | GPIO_BSRR_BS_14 | \ - GPIO_BSRR_BS_15) /*!< Select all pins */ -/** - * @} - */ - -/** @defgroup GPIO_LL_EC_MODE Mode - * @{ - */ -#define LL_GPIO_MODE_INPUT (0x00000000U) /*!< Select input mode */ -#define LL_GPIO_MODE_OUTPUT GPIO_MODER_MODER0_0 /*!< Select output mode */ -#define LL_GPIO_MODE_ALTERNATE GPIO_MODER_MODER0_1 /*!< Select alternate function mode */ -#define LL_GPIO_MODE_ANALOG GPIO_MODER_MODER0 /*!< Select analog mode */ -/** - * @} - */ - -/** @defgroup GPIO_LL_EC_OUTPUT Output Type - * @{ - */ -#define LL_GPIO_OUTPUT_PUSHPULL (0x00000000U) /*!< Select push-pull as output type */ -#define LL_GPIO_OUTPUT_OPENDRAIN GPIO_OTYPER_OT_0 /*!< Select open-drain as output type */ -/** - * @} - */ - -/** @defgroup GPIO_LL_EC_SPEED Output Speed - * @{ - */ -#define LL_GPIO_SPEED_FREQ_LOW (0x00000000U) /*!< Select I/O low output speed */ -#define LL_GPIO_SPEED_FREQ_MEDIUM GPIO_OSPEEDER_OSPEEDR0_0 /*!< Select I/O medium output speed */ -#define LL_GPIO_SPEED_FREQ_HIGH GPIO_OSPEEDER_OSPEEDR0_1 /*!< Select I/O fast output speed */ -#define LL_GPIO_SPEED_FREQ_VERY_HIGH GPIO_OSPEEDER_OSPEEDR0 /*!< Select I/O high output speed */ -/** - * @} - */ - -/** @defgroup GPIO_LL_EC_PULL Pull Up Pull Down - * @{ - */ -#define LL_GPIO_PULL_NO (0x00000000U) /*!< Select I/O no pull */ -#define LL_GPIO_PULL_UP GPIO_PUPDR_PUPDR0_0 /*!< Select I/O pull up */ -#define LL_GPIO_PULL_DOWN GPIO_PUPDR_PUPDR0_1 /*!< Select I/O pull down */ -/** - * @} - */ - -/** @defgroup GPIO_LL_EC_AF Alternate Function - * @{ - */ -#define LL_GPIO_AF_0 (0x0000000U) /*!< Select alternate function 0 */ -#define LL_GPIO_AF_1 (0x0000001U) /*!< Select alternate function 1 */ -#define LL_GPIO_AF_2 (0x0000002U) /*!< Select alternate function 2 */ -#define LL_GPIO_AF_3 (0x0000003U) /*!< Select alternate function 3 */ -#define LL_GPIO_AF_4 (0x0000004U) /*!< Select alternate function 4 */ -#define LL_GPIO_AF_5 (0x0000005U) /*!< Select alternate function 5 */ -#define LL_GPIO_AF_6 (0x0000006U) /*!< Select alternate function 6 */ -#define LL_GPIO_AF_7 (0x0000007U) /*!< Select alternate function 7 */ -#define LL_GPIO_AF_8 (0x0000008U) /*!< Select alternate function 8 */ -#define LL_GPIO_AF_9 (0x0000009U) /*!< Select alternate function 9 */ -#define LL_GPIO_AF_10 (0x000000AU) /*!< Select alternate function 10 */ -#define LL_GPIO_AF_11 (0x000000BU) /*!< Select alternate function 11 */ -#define LL_GPIO_AF_12 (0x000000CU) /*!< Select alternate function 12 */ -#define LL_GPIO_AF_13 (0x000000DU) /*!< Select alternate function 13 */ -#define LL_GPIO_AF_14 (0x000000EU) /*!< Select alternate function 14 */ -#define LL_GPIO_AF_15 (0x000000FU) /*!< Select alternate function 15 */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup GPIO_LL_Exported_Macros GPIO Exported Macros - * @{ - */ - -/** @defgroup GPIO_LL_EM_WRITE_READ Common Write and read registers Macros - * @{ - */ - -/** - * @brief Write a value in GPIO register - * @param __INSTANCE__ GPIO Instance - * @param __REG__ Register to be written - * @param __VALUE__ Value to be written in the register - * @retval None - */ -#define LL_GPIO_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__)) - -/** - * @brief Read a value in GPIO register - * @param __INSTANCE__ GPIO Instance - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_GPIO_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__) -/** - * @} - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup GPIO_LL_Exported_Functions GPIO Exported Functions - * @{ - */ - -/** @defgroup GPIO_LL_EF_Port_Configuration Port Configuration - * @{ - */ - -/** - * @brief Configure gpio mode for a dedicated pin on dedicated port. - * @note I/O mode can be Input mode, General purpose output, Alternate function mode or Analog. - * @note Warning: only one pin can be passed as parameter. - * @rmtoll MODER MODEy LL_GPIO_SetPinMode - * @param GPIOx GPIO Port - * @param Pin This parameter can be one of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @param Mode This parameter can be one of the following values: - * @arg @ref LL_GPIO_MODE_INPUT - * @arg @ref LL_GPIO_MODE_OUTPUT - * @arg @ref LL_GPIO_MODE_ALTERNATE - * @arg @ref LL_GPIO_MODE_ANALOG - * @retval None - */ -__STATIC_INLINE void LL_GPIO_SetPinMode(GPIO_TypeDef *GPIOx, uint32_t Pin, uint32_t Mode) -{ - MODIFY_REG(GPIOx->MODER, (GPIO_MODER_MODER0 << (POSITION_VAL(Pin) * 2U)), (Mode << (POSITION_VAL(Pin) * 2U))); -} - -/** - * @brief Return gpio mode for a dedicated pin on dedicated port. - * @note I/O mode can be Input mode, General purpose output, Alternate function mode or Analog. - * @note Warning: only one pin can be passed as parameter. - * @rmtoll MODER MODEy LL_GPIO_GetPinMode - * @param GPIOx GPIO Port - * @param Pin This parameter can be one of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @retval Returned value can be one of the following values: - * @arg @ref LL_GPIO_MODE_INPUT - * @arg @ref LL_GPIO_MODE_OUTPUT - * @arg @ref LL_GPIO_MODE_ALTERNATE - * @arg @ref LL_GPIO_MODE_ANALOG - */ -__STATIC_INLINE uint32_t LL_GPIO_GetPinMode(GPIO_TypeDef *GPIOx, uint32_t Pin) -{ - return (uint32_t)(READ_BIT(GPIOx->MODER, - (GPIO_MODER_MODER0 << (POSITION_VAL(Pin) * 2U))) >> (POSITION_VAL(Pin) * 2U)); -} - -/** - * @brief Configure gpio output type for several pins on dedicated port. - * @note Output type as to be set when gpio pin is in output or - * alternate modes. Possible type are Push-pull or Open-drain. - * @rmtoll OTYPER OTy LL_GPIO_SetPinOutputType - * @param GPIOx GPIO Port - * @param PinMask This parameter can be a combination of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @arg @ref LL_GPIO_PIN_ALL - * @param OutputType This parameter can be one of the following values: - * @arg @ref LL_GPIO_OUTPUT_PUSHPULL - * @arg @ref LL_GPIO_OUTPUT_OPENDRAIN - * @retval None - */ -__STATIC_INLINE void LL_GPIO_SetPinOutputType(GPIO_TypeDef *GPIOx, uint32_t PinMask, uint32_t OutputType) -{ - MODIFY_REG(GPIOx->OTYPER, PinMask, (PinMask * OutputType)); -} - -/** - * @brief Return gpio output type for several pins on dedicated port. - * @note Output type as to be set when gpio pin is in output or - * alternate modes. Possible type are Push-pull or Open-drain. - * @note Warning: only one pin can be passed as parameter. - * @rmtoll OTYPER OTy LL_GPIO_GetPinOutputType - * @param GPIOx GPIO Port - * @param Pin This parameter can be one of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @arg @ref LL_GPIO_PIN_ALL - * @retval Returned value can be one of the following values: - * @arg @ref LL_GPIO_OUTPUT_PUSHPULL - * @arg @ref LL_GPIO_OUTPUT_OPENDRAIN - */ -__STATIC_INLINE uint32_t LL_GPIO_GetPinOutputType(GPIO_TypeDef *GPIOx, uint32_t Pin) -{ - return (uint32_t)(READ_BIT(GPIOx->OTYPER, Pin) >> POSITION_VAL(Pin)); -} - -/** - * @brief Configure gpio speed for a dedicated pin on dedicated port. - * @note I/O speed can be Low, Medium, Fast or High speed. - * @note Warning: only one pin can be passed as parameter. - * @note Refer to datasheet for frequency specifications and the power - * supply and load conditions for each speed. - * @rmtoll OSPEEDR OSPEEDy LL_GPIO_SetPinSpeed - * @param GPIOx GPIO Port - * @param Pin This parameter can be one of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @param Speed This parameter can be one of the following values: - * @arg @ref LL_GPIO_SPEED_FREQ_LOW - * @arg @ref LL_GPIO_SPEED_FREQ_MEDIUM - * @arg @ref LL_GPIO_SPEED_FREQ_HIGH - * @arg @ref LL_GPIO_SPEED_FREQ_VERY_HIGH - * @retval None - */ -__STATIC_INLINE void LL_GPIO_SetPinSpeed(GPIO_TypeDef *GPIOx, uint32_t Pin, uint32_t Speed) -{ - MODIFY_REG(GPIOx->OSPEEDR, (GPIO_OSPEEDER_OSPEEDR0 << (POSITION_VAL(Pin) * 2U)), - (Speed << (POSITION_VAL(Pin) * 2U))); -} - -/** - * @brief Return gpio speed for a dedicated pin on dedicated port. - * @note I/O speed can be Low, Medium, Fast or High speed. - * @note Warning: only one pin can be passed as parameter. - * @note Refer to datasheet for frequency specifications and the power - * supply and load conditions for each speed. - * @rmtoll OSPEEDR OSPEEDy LL_GPIO_GetPinSpeed - * @param GPIOx GPIO Port - * @param Pin This parameter can be one of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @retval Returned value can be one of the following values: - * @arg @ref LL_GPIO_SPEED_FREQ_LOW - * @arg @ref LL_GPIO_SPEED_FREQ_MEDIUM - * @arg @ref LL_GPIO_SPEED_FREQ_HIGH - * @arg @ref LL_GPIO_SPEED_FREQ_VERY_HIGH - */ -__STATIC_INLINE uint32_t LL_GPIO_GetPinSpeed(GPIO_TypeDef *GPIOx, uint32_t Pin) -{ - return (uint32_t)(READ_BIT(GPIOx->OSPEEDR, - (GPIO_OSPEEDER_OSPEEDR0 << (POSITION_VAL(Pin) * 2U))) >> (POSITION_VAL(Pin) * 2U)); -} - -/** - * @brief Configure gpio pull-up or pull-down for a dedicated pin on a dedicated port. - * @note Warning: only one pin can be passed as parameter. - * @rmtoll PUPDR PUPDy LL_GPIO_SetPinPull - * @param GPIOx GPIO Port - * @param Pin This parameter can be one of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @param Pull This parameter can be one of the following values: - * @arg @ref LL_GPIO_PULL_NO - * @arg @ref LL_GPIO_PULL_UP - * @arg @ref LL_GPIO_PULL_DOWN - * @retval None - */ -__STATIC_INLINE void LL_GPIO_SetPinPull(GPIO_TypeDef *GPIOx, uint32_t Pin, uint32_t Pull) -{ - MODIFY_REG(GPIOx->PUPDR, (GPIO_PUPDR_PUPDR0 << (POSITION_VAL(Pin) * 2U)), (Pull << (POSITION_VAL(Pin) * 2U))); -} - -/** - * @brief Return gpio pull-up or pull-down for a dedicated pin on a dedicated port - * @note Warning: only one pin can be passed as parameter. - * @rmtoll PUPDR PUPDy LL_GPIO_GetPinPull - * @param GPIOx GPIO Port - * @param Pin This parameter can be one of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @retval Returned value can be one of the following values: - * @arg @ref LL_GPIO_PULL_NO - * @arg @ref LL_GPIO_PULL_UP - * @arg @ref LL_GPIO_PULL_DOWN - */ -__STATIC_INLINE uint32_t LL_GPIO_GetPinPull(GPIO_TypeDef *GPIOx, uint32_t Pin) -{ - return (uint32_t)(READ_BIT(GPIOx->PUPDR, - (GPIO_PUPDR_PUPDR0 << (POSITION_VAL(Pin) * 2U))) >> (POSITION_VAL(Pin) * 2U)); -} - -/** - * @brief Configure gpio alternate function of a dedicated pin from 0 to 7 for a dedicated port. - * @note Possible values are from AF0 to AF15 depending on target. - * @note Warning: only one pin can be passed as parameter. - * @rmtoll AFRL AFSELy LL_GPIO_SetAFPin_0_7 - * @param GPIOx GPIO Port - * @param Pin This parameter can be one of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @param Alternate This parameter can be one of the following values: - * @arg @ref LL_GPIO_AF_0 - * @arg @ref LL_GPIO_AF_1 - * @arg @ref LL_GPIO_AF_2 - * @arg @ref LL_GPIO_AF_3 - * @arg @ref LL_GPIO_AF_4 - * @arg @ref LL_GPIO_AF_5 - * @arg @ref LL_GPIO_AF_6 - * @arg @ref LL_GPIO_AF_7 - * @arg @ref LL_GPIO_AF_8 - * @arg @ref LL_GPIO_AF_9 - * @arg @ref LL_GPIO_AF_10 - * @arg @ref LL_GPIO_AF_11 - * @arg @ref LL_GPIO_AF_12 - * @arg @ref LL_GPIO_AF_13 - * @arg @ref LL_GPIO_AF_14 - * @arg @ref LL_GPIO_AF_15 - * @retval None - */ -__STATIC_INLINE void LL_GPIO_SetAFPin_0_7(GPIO_TypeDef *GPIOx, uint32_t Pin, uint32_t Alternate) -{ - MODIFY_REG(GPIOx->AFR[0], (GPIO_AFRL_AFSEL0 << (POSITION_VAL(Pin) * 4U)), - (Alternate << (POSITION_VAL(Pin) * 4U))); -} - -/** - * @brief Return gpio alternate function of a dedicated pin from 0 to 7 for a dedicated port. - * @rmtoll AFRL AFSELy LL_GPIO_GetAFPin_0_7 - * @param GPIOx GPIO Port - * @param Pin This parameter can be one of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @retval Returned value can be one of the following values: - * @arg @ref LL_GPIO_AF_0 - * @arg @ref LL_GPIO_AF_1 - * @arg @ref LL_GPIO_AF_2 - * @arg @ref LL_GPIO_AF_3 - * @arg @ref LL_GPIO_AF_4 - * @arg @ref LL_GPIO_AF_5 - * @arg @ref LL_GPIO_AF_6 - * @arg @ref LL_GPIO_AF_7 - * @arg @ref LL_GPIO_AF_8 - * @arg @ref LL_GPIO_AF_9 - * @arg @ref LL_GPIO_AF_10 - * @arg @ref LL_GPIO_AF_11 - * @arg @ref LL_GPIO_AF_12 - * @arg @ref LL_GPIO_AF_13 - * @arg @ref LL_GPIO_AF_14 - * @arg @ref LL_GPIO_AF_15 - */ -__STATIC_INLINE uint32_t LL_GPIO_GetAFPin_0_7(GPIO_TypeDef *GPIOx, uint32_t Pin) -{ - return (uint32_t)(READ_BIT(GPIOx->AFR[0], - (GPIO_AFRL_AFSEL0 << (POSITION_VAL(Pin) * 4U))) >> (POSITION_VAL(Pin) * 4U)); -} - -/** - * @brief Configure gpio alternate function of a dedicated pin from 8 to 15 for a dedicated port. - * @note Possible values are from AF0 to AF15 depending on target. - * @note Warning: only one pin can be passed as parameter. - * @rmtoll AFRH AFSELy LL_GPIO_SetAFPin_8_15 - * @param GPIOx GPIO Port - * @param Pin This parameter can be one of the following values: - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @param Alternate This parameter can be one of the following values: - * @arg @ref LL_GPIO_AF_0 - * @arg @ref LL_GPIO_AF_1 - * @arg @ref LL_GPIO_AF_2 - * @arg @ref LL_GPIO_AF_3 - * @arg @ref LL_GPIO_AF_4 - * @arg @ref LL_GPIO_AF_5 - * @arg @ref LL_GPIO_AF_6 - * @arg @ref LL_GPIO_AF_7 - * @arg @ref LL_GPIO_AF_8 - * @arg @ref LL_GPIO_AF_9 - * @arg @ref LL_GPIO_AF_10 - * @arg @ref LL_GPIO_AF_11 - * @arg @ref LL_GPIO_AF_12 - * @arg @ref LL_GPIO_AF_13 - * @arg @ref LL_GPIO_AF_14 - * @arg @ref LL_GPIO_AF_15 - * @retval None - */ -__STATIC_INLINE void LL_GPIO_SetAFPin_8_15(GPIO_TypeDef *GPIOx, uint32_t Pin, uint32_t Alternate) -{ - MODIFY_REG(GPIOx->AFR[1], (GPIO_AFRH_AFSEL8 << (POSITION_VAL(Pin >> 8U) * 4U)), - (Alternate << (POSITION_VAL(Pin >> 8U) * 4U))); -} - -/** - * @brief Return gpio alternate function of a dedicated pin from 8 to 15 for a dedicated port. - * @note Possible values are from AF0 to AF15 depending on target. - * @rmtoll AFRH AFSELy LL_GPIO_GetAFPin_8_15 - * @param GPIOx GPIO Port - * @param Pin This parameter can be one of the following values: - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @retval Returned value can be one of the following values: - * @arg @ref LL_GPIO_AF_0 - * @arg @ref LL_GPIO_AF_1 - * @arg @ref LL_GPIO_AF_2 - * @arg @ref LL_GPIO_AF_3 - * @arg @ref LL_GPIO_AF_4 - * @arg @ref LL_GPIO_AF_5 - * @arg @ref LL_GPIO_AF_6 - * @arg @ref LL_GPIO_AF_7 - * @arg @ref LL_GPIO_AF_8 - * @arg @ref LL_GPIO_AF_9 - * @arg @ref LL_GPIO_AF_10 - * @arg @ref LL_GPIO_AF_11 - * @arg @ref LL_GPIO_AF_12 - * @arg @ref LL_GPIO_AF_13 - * @arg @ref LL_GPIO_AF_14 - * @arg @ref LL_GPIO_AF_15 - */ -__STATIC_INLINE uint32_t LL_GPIO_GetAFPin_8_15(GPIO_TypeDef *GPIOx, uint32_t Pin) -{ - return (uint32_t)(READ_BIT(GPIOx->AFR[1], - (GPIO_AFRH_AFSEL8 << (POSITION_VAL(Pin >> 8U) * 4U))) >> (POSITION_VAL(Pin >> 8U) * 4U)); -} - - -/** - * @brief Lock configuration of several pins for a dedicated port. - * @note When the lock sequence has been applied on a port bit, the - * value of this port bit can no longer be modified until the - * next reset. - * @note Each lock bit freezes a specific configuration register - * (control and alternate function registers). - * @rmtoll LCKR LCKK LL_GPIO_LockPin - * @param GPIOx GPIO Port - * @param PinMask This parameter can be a combination of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @arg @ref LL_GPIO_PIN_ALL - * @retval None - */ -__STATIC_INLINE void LL_GPIO_LockPin(GPIO_TypeDef *GPIOx, uint32_t PinMask) -{ - __IO uint32_t temp; - WRITE_REG(GPIOx->LCKR, GPIO_LCKR_LCKK | PinMask); - WRITE_REG(GPIOx->LCKR, PinMask); - WRITE_REG(GPIOx->LCKR, GPIO_LCKR_LCKK | PinMask); - temp = READ_REG(GPIOx->LCKR); - (void) temp; -} - -/** - * @brief Return 1 if all pins passed as parameter, of a dedicated port, are locked. else Return 0. - * @rmtoll LCKR LCKy LL_GPIO_IsPinLocked - * @param GPIOx GPIO Port - * @param PinMask This parameter can be a combination of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @arg @ref LL_GPIO_PIN_ALL - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_GPIO_IsPinLocked(GPIO_TypeDef *GPIOx, uint32_t PinMask) -{ - return (READ_BIT(GPIOx->LCKR, PinMask) == (PinMask)); -} - -/** - * @brief Return 1 if one of the pin of a dedicated port is locked. else return 0. - * @rmtoll LCKR LCKK LL_GPIO_IsAnyPinLocked - * @param GPIOx GPIO Port - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_GPIO_IsAnyPinLocked(GPIO_TypeDef *GPIOx) -{ - return (READ_BIT(GPIOx->LCKR, GPIO_LCKR_LCKK) == (GPIO_LCKR_LCKK)); -} - -/** - * @} - */ - -/** @defgroup GPIO_LL_EF_Data_Access Data Access - * @{ - */ - -/** - * @brief Return full input data register value for a dedicated port. - * @rmtoll IDR IDy LL_GPIO_ReadInputPort - * @param GPIOx GPIO Port - * @retval Input data register value of port - */ -__STATIC_INLINE uint32_t LL_GPIO_ReadInputPort(GPIO_TypeDef *GPIOx) -{ - return (uint32_t)(READ_REG(GPIOx->IDR)); -} - -/** - * @brief Return if input data level for several pins of dedicated port is high or low. - * @rmtoll IDR IDy LL_GPIO_IsInputPinSet - * @param GPIOx GPIO Port - * @param PinMask This parameter can be a combination of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @arg @ref LL_GPIO_PIN_ALL - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_GPIO_IsInputPinSet(GPIO_TypeDef *GPIOx, uint32_t PinMask) -{ - return (READ_BIT(GPIOx->IDR, PinMask) == (PinMask)); -} - -/** - * @brief Write output data register for the port. - * @rmtoll ODR ODy LL_GPIO_WriteOutputPort - * @param GPIOx GPIO Port - * @param PortValue Level value for each pin of the port - * @retval None - */ -__STATIC_INLINE void LL_GPIO_WriteOutputPort(GPIO_TypeDef *GPIOx, uint32_t PortValue) -{ - WRITE_REG(GPIOx->ODR, PortValue); -} - -/** - * @brief Return full output data register value for a dedicated port. - * @rmtoll ODR ODy LL_GPIO_ReadOutputPort - * @param GPIOx GPIO Port - * @retval Output data register value of port - */ -__STATIC_INLINE uint32_t LL_GPIO_ReadOutputPort(GPIO_TypeDef *GPIOx) -{ - return (uint32_t)(READ_REG(GPIOx->ODR)); -} - -/** - * @brief Return if input data level for several pins of dedicated port is high or low. - * @rmtoll ODR ODy LL_GPIO_IsOutputPinSet - * @param GPIOx GPIO Port - * @param PinMask This parameter can be a combination of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @arg @ref LL_GPIO_PIN_ALL - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_GPIO_IsOutputPinSet(GPIO_TypeDef *GPIOx, uint32_t PinMask) -{ - return (READ_BIT(GPIOx->ODR, PinMask) == (PinMask)); -} - -/** - * @brief Set several pins to high level on dedicated gpio port. - * @rmtoll BSRR BSy LL_GPIO_SetOutputPin - * @param GPIOx GPIO Port - * @param PinMask This parameter can be a combination of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @arg @ref LL_GPIO_PIN_ALL - * @retval None - */ -__STATIC_INLINE void LL_GPIO_SetOutputPin(GPIO_TypeDef *GPIOx, uint32_t PinMask) -{ - WRITE_REG(GPIOx->BSRR, PinMask); -} - -/** - * @brief Set several pins to low level on dedicated gpio port. - * @rmtoll BSRR BRy LL_GPIO_ResetOutputPin - * @param GPIOx GPIO Port - * @param PinMask This parameter can be a combination of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @arg @ref LL_GPIO_PIN_ALL - * @retval None - */ -__STATIC_INLINE void LL_GPIO_ResetOutputPin(GPIO_TypeDef *GPIOx, uint32_t PinMask) -{ - WRITE_REG(GPIOx->BSRR, (PinMask << 16)); -} - -/** - * @brief Toggle data value for several pin of dedicated port. - * @rmtoll ODR ODy LL_GPIO_TogglePin - * @param GPIOx GPIO Port - * @param PinMask This parameter can be a combination of the following values: - * @arg @ref LL_GPIO_PIN_0 - * @arg @ref LL_GPIO_PIN_1 - * @arg @ref LL_GPIO_PIN_2 - * @arg @ref LL_GPIO_PIN_3 - * @arg @ref LL_GPIO_PIN_4 - * @arg @ref LL_GPIO_PIN_5 - * @arg @ref LL_GPIO_PIN_6 - * @arg @ref LL_GPIO_PIN_7 - * @arg @ref LL_GPIO_PIN_8 - * @arg @ref LL_GPIO_PIN_9 - * @arg @ref LL_GPIO_PIN_10 - * @arg @ref LL_GPIO_PIN_11 - * @arg @ref LL_GPIO_PIN_12 - * @arg @ref LL_GPIO_PIN_13 - * @arg @ref LL_GPIO_PIN_14 - * @arg @ref LL_GPIO_PIN_15 - * @arg @ref LL_GPIO_PIN_ALL - * @retval None - */ -__STATIC_INLINE void LL_GPIO_TogglePin(GPIO_TypeDef *GPIOx, uint32_t PinMask) -{ - uint32_t odr = READ_REG(GPIOx->ODR); - WRITE_REG(GPIOx->BSRR, ((odr & PinMask) << 16u) | (~odr & PinMask)); -} - -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup GPIO_LL_EF_Init Initialization and de-initialization functions - * @{ - */ - -ErrorStatus LL_GPIO_DeInit(GPIO_TypeDef *GPIOx); -ErrorStatus LL_GPIO_Init(GPIO_TypeDef *GPIOx, LL_GPIO_InitTypeDef *GPIO_InitStruct); -void LL_GPIO_StructInit(LL_GPIO_InitTypeDef *GPIO_InitStruct); - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* defined (GPIOA) || defined (GPIOB) || defined (GPIOC) || defined (GPIOD) || defined (GPIOE) || defined (GPIOF) || defined (GPIOG) || defined (GPIOH) || defined (GPIOI) || defined (GPIOJ) || defined (GPIOK) */ -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_GPIO_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_i2c.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_i2c.h deleted file mode 100644 index 5a46bab..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_i2c.h +++ /dev/null @@ -1,1892 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_i2c.h - * @author MCD Application Team - * @brief Header file of I2C LL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_LL_I2C_H -#define __STM32F4xx_LL_I2C_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (I2C1) || defined (I2C2) || defined (I2C3) - -/** @defgroup I2C_LL I2C - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup I2C_LL_Private_Constants I2C Private Constants - * @{ - */ - -/* Defines used to perform compute and check in the macros */ -#define LL_I2C_MAX_SPEED_STANDARD 100000U -#define LL_I2C_MAX_SPEED_FAST 400000U -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup I2C_LL_Private_Macros I2C Private Macros - * @{ - */ -/** - * @} - */ -#endif /*USE_FULL_LL_DRIVER*/ - -/* Exported types ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup I2C_LL_ES_INIT I2C Exported Init structure - * @{ - */ -typedef struct -{ - uint32_t PeripheralMode; /*!< Specifies the peripheral mode. - This parameter can be a value of @ref I2C_LL_EC_PERIPHERAL_MODE - - This feature can be modified afterwards using unitary function @ref LL_I2C_SetMode(). */ - - uint32_t ClockSpeed; /*!< Specifies the clock frequency. - This parameter must be set to a value lower than 400kHz (in Hz) - - This feature can be modified afterwards using unitary function @ref LL_I2C_SetClockPeriod() - or @ref LL_I2C_SetDutyCycle() or @ref LL_I2C_SetClockSpeedMode() or @ref LL_I2C_ConfigSpeed(). */ - - uint32_t DutyCycle; /*!< Specifies the I2C fast mode duty cycle. - This parameter can be a value of @ref I2C_LL_EC_DUTYCYCLE - - This feature can be modified afterwards using unitary function @ref LL_I2C_SetDutyCycle(). */ - -#if defined(I2C_FLTR_ANOFF)&&defined(I2C_FLTR_DNF) - uint32_t AnalogFilter; /*!< Enables or disables analog noise filter. - This parameter can be a value of @ref I2C_LL_EC_ANALOGFILTER_SELECTION - - This feature can be modified afterwards using unitary functions @ref LL_I2C_EnableAnalogFilter() or LL_I2C_DisableAnalogFilter(). */ - - uint32_t DigitalFilter; /*!< Configures the digital noise filter. - This parameter can be a number between Min_Data = 0x00 and Max_Data = 0x0F - - This feature can be modified afterwards using unitary function @ref LL_I2C_SetDigitalFilter(). */ - -#endif - uint32_t OwnAddress1; /*!< Specifies the device own address 1. - This parameter must be a value between Min_Data = 0x00 and Max_Data = 0x3FF - - This feature can be modified afterwards using unitary function @ref LL_I2C_SetOwnAddress1(). */ - - uint32_t TypeAcknowledge; /*!< Specifies the ACKnowledge or Non ACKnowledge condition after the address receive match code or next received byte. - This parameter can be a value of @ref I2C_LL_EC_I2C_ACKNOWLEDGE - - This feature can be modified afterwards using unitary function @ref LL_I2C_AcknowledgeNextData(). */ - - uint32_t OwnAddrSize; /*!< Specifies the device own address 1 size (7-bit or 10-bit). - This parameter can be a value of @ref I2C_LL_EC_OWNADDRESS1 - - This feature can be modified afterwards using unitary function @ref LL_I2C_SetOwnAddress1(). */ -} LL_I2C_InitTypeDef; -/** - * @} - */ -#endif /*USE_FULL_LL_DRIVER*/ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup I2C_LL_Exported_Constants I2C Exported Constants - * @{ - */ - -/** @defgroup I2C_LL_EC_GET_FLAG Get Flags Defines - * @brief Flags defines which can be used with LL_I2C_ReadReg function - * @{ - */ -#define LL_I2C_SR1_SB I2C_SR1_SB /*!< Start Bit (master mode) */ -#define LL_I2C_SR1_ADDR I2C_SR1_ADDR /*!< Address sent (master mode) or - Address matched flag (slave mode) */ -#define LL_I2C_SR1_BTF I2C_SR1_BTF /*!< Byte Transfer Finished flag */ -#define LL_I2C_SR1_ADD10 I2C_SR1_ADD10 /*!< 10-bit header sent (master mode) */ -#define LL_I2C_SR1_STOPF I2C_SR1_STOPF /*!< Stop detection flag (slave mode) */ -#define LL_I2C_SR1_RXNE I2C_SR1_RXNE /*!< Data register not empty (receivers) */ -#define LL_I2C_SR1_TXE I2C_SR1_TXE /*!< Data register empty (transmitters) */ -#define LL_I2C_SR1_BERR I2C_SR1_BERR /*!< Bus error */ -#define LL_I2C_SR1_ARLO I2C_SR1_ARLO /*!< Arbitration lost */ -#define LL_I2C_SR1_AF I2C_SR1_AF /*!< Acknowledge failure flag */ -#define LL_I2C_SR1_OVR I2C_SR1_OVR /*!< Overrun/Underrun */ -#define LL_I2C_SR1_PECERR I2C_ISR_PECERR /*!< PEC Error in reception (SMBus mode) */ -#define LL_I2C_SR1_TIMEOUT I2C_ISR_TIMEOUT /*!< Timeout detection flag (SMBus mode) */ -#define LL_I2C_SR1_SMALERT I2C_ISR_SMALERT /*!< SMBus alert (SMBus mode) */ -#define LL_I2C_SR2_MSL I2C_SR2_MSL /*!< Master/Slave flag */ -#define LL_I2C_SR2_BUSY I2C_SR2_BUSY /*!< Bus busy flag */ -#define LL_I2C_SR2_TRA I2C_SR2_TRA /*!< Transmitter/receiver direction */ -#define LL_I2C_SR2_GENCALL I2C_SR2_GENCALL /*!< General call address (Slave mode) */ -#define LL_I2C_SR2_SMBDEFAULT I2C_SR2_SMBDEFAULT /*!< SMBus Device default address (Slave mode) */ -#define LL_I2C_SR2_SMBHOST I2C_SR2_SMBHOST /*!< SMBus Host address (Slave mode) */ -#define LL_I2C_SR2_DUALF I2C_SR2_DUALF /*!< Dual flag (Slave mode) */ -/** - * @} - */ - -/** @defgroup I2C_LL_EC_IT IT Defines - * @brief IT defines which can be used with LL_I2C_ReadReg and LL_I2C_WriteReg functions - * @{ - */ -#define LL_I2C_CR2_ITEVTEN I2C_CR2_ITEVTEN /*!< Events interrupts enable */ -#define LL_I2C_CR2_ITBUFEN I2C_CR2_ITBUFEN /*!< Buffer interrupts enable */ -#define LL_I2C_CR2_ITERREN I2C_CR2_ITERREN /*!< Error interrupts enable */ -/** - * @} - */ - -#if defined(I2C_FLTR_ANOFF) -/** @defgroup I2C_LL_EC_ANALOGFILTER_SELECTION Analog Filter Selection - * @{ - */ -#define LL_I2C_ANALOGFILTER_ENABLE 0x00000000U /*!< Analog filter is enabled. */ -#define LL_I2C_ANALOGFILTER_DISABLE I2C_FLTR_ANOFF /*!< Analog filter is disabled.*/ -/** - * @} - */ - -#endif -/** @defgroup I2C_LL_EC_OWNADDRESS1 Own Address 1 Length - * @{ - */ -#define LL_I2C_OWNADDRESS1_7BIT 0x00004000U /*!< Own address 1 is a 7-bit address. */ -#define LL_I2C_OWNADDRESS1_10BIT (uint32_t)(I2C_OAR1_ADDMODE | 0x00004000U) /*!< Own address 1 is a 10-bit address. */ -/** - * @} - */ - -/** @defgroup I2C_LL_EC_DUTYCYCLE Fast Mode Duty Cycle - * @{ - */ -#define LL_I2C_DUTYCYCLE_2 0x00000000U /*!< I2C fast mode Tlow/Thigh = 2 */ -#define LL_I2C_DUTYCYCLE_16_9 I2C_CCR_DUTY /*!< I2C fast mode Tlow/Thigh = 16/9 */ -/** - * @} - */ - -/** @defgroup I2C_LL_EC_CLOCK_SPEED_MODE Master Clock Speed Mode - * @{ - */ -#define LL_I2C_CLOCK_SPEED_STANDARD_MODE 0x00000000U /*!< Master clock speed range is standard mode */ -#define LL_I2C_CLOCK_SPEED_FAST_MODE I2C_CCR_FS /*!< Master clock speed range is fast mode */ -/** - * @} - */ - -/** @defgroup I2C_LL_EC_PERIPHERAL_MODE Peripheral Mode - * @{ - */ -#define LL_I2C_MODE_I2C 0x00000000U /*!< I2C Master or Slave mode */ -#define LL_I2C_MODE_SMBUS_HOST (uint32_t)(I2C_CR1_SMBUS | I2C_CR1_SMBTYPE | I2C_CR1_ENARP) /*!< SMBus Host address acknowledge */ -#define LL_I2C_MODE_SMBUS_DEVICE I2C_CR1_SMBUS /*!< SMBus Device default mode (Default address not acknowledge) */ -#define LL_I2C_MODE_SMBUS_DEVICE_ARP (uint32_t)(I2C_CR1_SMBUS | I2C_CR1_ENARP) /*!< SMBus Device Default address acknowledge */ -/** - * @} - */ - -/** @defgroup I2C_LL_EC_I2C_ACKNOWLEDGE Acknowledge Generation - * @{ - */ -#define LL_I2C_ACK I2C_CR1_ACK /*!< ACK is sent after current received byte. */ -#define LL_I2C_NACK 0x00000000U /*!< NACK is sent after current received byte.*/ -/** - * @} - */ - -/** @defgroup I2C_LL_EC_DIRECTION Read Write Direction - * @{ - */ -#define LL_I2C_DIRECTION_WRITE I2C_SR2_TRA /*!< Bus is in write transfer */ -#define LL_I2C_DIRECTION_READ 0x00000000U /*!< Bus is in read transfer */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup I2C_LL_Exported_Macros I2C Exported Macros - * @{ - */ - -/** @defgroup I2C_LL_EM_WRITE_READ Common Write and read registers Macros - * @{ - */ - -/** - * @brief Write a value in I2C register - * @param __INSTANCE__ I2C Instance - * @param __REG__ Register to be written - * @param __VALUE__ Value to be written in the register - * @retval None - */ -#define LL_I2C_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__)) - -/** - * @brief Read a value in I2C register - * @param __INSTANCE__ I2C Instance - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_I2C_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__) -/** - * @} - */ - -/** @defgroup I2C_LL_EM_Exported_Macros_Helper Exported_Macros_Helper - * @{ - */ - -/** - * @brief Convert Peripheral Clock Frequency in Mhz. - * @param __PCLK__ This parameter must be a value of peripheral clock (in Hz). - * @retval Value of peripheral clock (in Mhz) - */ -#define __LL_I2C_FREQ_HZ_TO_MHZ(__PCLK__) (uint32_t)((__PCLK__)/1000000U) - -/** - * @brief Convert Peripheral Clock Frequency in Hz. - * @param __PCLK__ This parameter must be a value of peripheral clock (in Mhz). - * @retval Value of peripheral clock (in Hz) - */ -#define __LL_I2C_FREQ_MHZ_TO_HZ(__PCLK__) (uint32_t)((__PCLK__)*1000000U) - -/** - * @brief Compute I2C Clock rising time. - * @param __FREQRANGE__ This parameter must be a value of peripheral clock (in Mhz). - * @param __SPEED__ This parameter must be a value lower than 400kHz (in Hz). - * @retval Value between Min_Data=0x02 and Max_Data=0x3F - */ -#define __LL_I2C_RISE_TIME(__FREQRANGE__, __SPEED__) (uint32_t)(((__SPEED__) <= LL_I2C_MAX_SPEED_STANDARD) ? ((__FREQRANGE__) + 1U) : ((((__FREQRANGE__) * 300U) / 1000U) + 1U)) - -/** - * @brief Compute Speed clock range to a Clock Control Register (I2C_CCR_CCR) value. - * @param __PCLK__ This parameter must be a value of peripheral clock (in Hz). - * @param __SPEED__ This parameter must be a value lower than 400kHz (in Hz). - * @param __DUTYCYCLE__ This parameter can be one of the following values: - * @arg @ref LL_I2C_DUTYCYCLE_2 - * @arg @ref LL_I2C_DUTYCYCLE_16_9 - * @retval Value between Min_Data=0x004 and Max_Data=0xFFF, except in FAST DUTY mode where Min_Data=0x001. - */ -#define __LL_I2C_SPEED_TO_CCR(__PCLK__, __SPEED__, __DUTYCYCLE__) (uint32_t)(((__SPEED__) <= LL_I2C_MAX_SPEED_STANDARD)? \ - (__LL_I2C_SPEED_STANDARD_TO_CCR((__PCLK__), (__SPEED__))) : \ - (__LL_I2C_SPEED_FAST_TO_CCR((__PCLK__), (__SPEED__), (__DUTYCYCLE__)))) - -/** - * @brief Compute Speed Standard clock range to a Clock Control Register (I2C_CCR_CCR) value. - * @param __PCLK__ This parameter must be a value of peripheral clock (in Hz). - * @param __SPEED__ This parameter must be a value lower than 100kHz (in Hz). - * @retval Value between Min_Data=0x004 and Max_Data=0xFFF. - */ -#define __LL_I2C_SPEED_STANDARD_TO_CCR(__PCLK__, __SPEED__) (uint32_t)(((((__PCLK__)/((__SPEED__) << 1U)) & I2C_CCR_CCR) < 4U)? 4U:((__PCLK__) / ((__SPEED__) << 1U))) - -/** - * @brief Compute Speed Fast clock range to a Clock Control Register (I2C_CCR_CCR) value. - * @param __PCLK__ This parameter must be a value of peripheral clock (in Hz). - * @param __SPEED__ This parameter must be a value between Min_Data=100Khz and Max_Data=400Khz (in Hz). - * @param __DUTYCYCLE__ This parameter can be one of the following values: - * @arg @ref LL_I2C_DUTYCYCLE_2 - * @arg @ref LL_I2C_DUTYCYCLE_16_9 - * @retval Value between Min_Data=0x001 and Max_Data=0xFFF - */ -#define __LL_I2C_SPEED_FAST_TO_CCR(__PCLK__, __SPEED__, __DUTYCYCLE__) (uint32_t)(((__DUTYCYCLE__) == LL_I2C_DUTYCYCLE_2)? \ - (((((__PCLK__) / ((__SPEED__) * 3U)) & I2C_CCR_CCR) == 0U)? 1U:((__PCLK__) / ((__SPEED__) * 3U))) : \ - (((((__PCLK__) / ((__SPEED__) * 25U)) & I2C_CCR_CCR) == 0U)? 1U:((__PCLK__) / ((__SPEED__) * 25U)))) - -/** - * @brief Get the Least significant bits of a 10-Bits address. - * @param __ADDRESS__ This parameter must be a value of a 10-Bits slave address. - * @retval Value between Min_Data=0x00 and Max_Data=0xFF - */ -#define __LL_I2C_10BIT_ADDRESS(__ADDRESS__) ((uint8_t)((uint16_t)((__ADDRESS__) & (uint16_t)(0x00FF)))) - -/** - * @brief Convert a 10-Bits address to a 10-Bits header with Write direction. - * @param __ADDRESS__ This parameter must be a value of a 10-Bits slave address. - * @retval Value between Min_Data=0xF0 and Max_Data=0xF6 - */ -#define __LL_I2C_10BIT_HEADER_WRITE(__ADDRESS__) ((uint8_t)((uint16_t)((uint16_t)(((uint16_t)((__ADDRESS__) & (uint16_t)(0x0300))) >> 7) | (uint16_t)(0xF0)))) - -/** - * @brief Convert a 10-Bits address to a 10-Bits header with Read direction. - * @param __ADDRESS__ This parameter must be a value of a 10-Bits slave address. - * @retval Value between Min_Data=0xF1 and Max_Data=0xF7 - */ -#define __LL_I2C_10BIT_HEADER_READ(__ADDRESS__) ((uint8_t)((uint16_t)((uint16_t)(((uint16_t)((__ADDRESS__) & (uint16_t)(0x0300))) >> 7) | (uint16_t)(0xF1)))) - -/** - * @} - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ - -/** @defgroup I2C_LL_Exported_Functions I2C Exported Functions - * @{ - */ - -/** @defgroup I2C_LL_EF_Configuration Configuration - * @{ - */ - -/** - * @brief Enable I2C peripheral (PE = 1). - * @rmtoll CR1 PE LL_I2C_Enable - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_Enable(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR1, I2C_CR1_PE); -} - -/** - * @brief Disable I2C peripheral (PE = 0). - * @rmtoll CR1 PE LL_I2C_Disable - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_Disable(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR1, I2C_CR1_PE); -} - -/** - * @brief Check if the I2C peripheral is enabled or disabled. - * @rmtoll CR1 PE LL_I2C_IsEnabled - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabled(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR1, I2C_CR1_PE) == (I2C_CR1_PE)); -} - -#if defined(I2C_FLTR_ANOFF)&&defined(I2C_FLTR_DNF) -/** - * @brief Configure Noise Filters (Analog and Digital). - * @note If the analog filter is also enabled, the digital filter is added to analog filter. - * The filters can only be programmed when the I2C is disabled (PE = 0). - * @rmtoll FLTR ANOFF LL_I2C_ConfigFilters\n - * FLTR DNF LL_I2C_ConfigFilters - * @param I2Cx I2C Instance. - * @param AnalogFilter This parameter can be one of the following values: - * @arg @ref LL_I2C_ANALOGFILTER_ENABLE - * @arg @ref LL_I2C_ANALOGFILTER_DISABLE - * @param DigitalFilter This parameter must be a value between Min_Data=0x00 (Digital filter disabled) and Max_Data=0x0F (Digital filter enabled and filtering capability up to 15*TPCLK1) - * This parameter is used to configure the digital noise filter on SDA and SCL input. The digital filter will suppress the spikes with a length of up to DNF[3:0]*TPCLK1. - * @retval None - */ -__STATIC_INLINE void LL_I2C_ConfigFilters(I2C_TypeDef *I2Cx, uint32_t AnalogFilter, uint32_t DigitalFilter) -{ - MODIFY_REG(I2Cx->FLTR, I2C_FLTR_ANOFF | I2C_FLTR_DNF, AnalogFilter | DigitalFilter); -} -#endif -#if defined(I2C_FLTR_DNF) - -/** - * @brief Configure Digital Noise Filter. - * @note If the analog filter is also enabled, the digital filter is added to analog filter. - * This filter can only be programmed when the I2C is disabled (PE = 0). - * @rmtoll FLTR DNF LL_I2C_SetDigitalFilter - * @param I2Cx I2C Instance. - * @param DigitalFilter This parameter must be a value between Min_Data=0x00 (Digital filter disabled) and Max_Data=0x0F (Digital filter enabled and filtering capability up to 15*TPCLK1) - * This parameter is used to configure the digital noise filter on SDA and SCL input. The digital filter will suppress the spikes with a length of up to DNF[3:0]*TPCLK1. - * @retval None - */ -__STATIC_INLINE void LL_I2C_SetDigitalFilter(I2C_TypeDef *I2Cx, uint32_t DigitalFilter) -{ - MODIFY_REG(I2Cx->FLTR, I2C_FLTR_DNF, DigitalFilter); -} - -/** - * @brief Get the current Digital Noise Filter configuration. - * @rmtoll FLTR DNF LL_I2C_GetDigitalFilter - * @param I2Cx I2C Instance. - * @retval Value between Min_Data=0x0 and Max_Data=0xF - */ -__STATIC_INLINE uint32_t LL_I2C_GetDigitalFilter(I2C_TypeDef *I2Cx) -{ - return (uint32_t)(READ_BIT(I2Cx->FLTR, I2C_FLTR_DNF)); -} -#endif -#if defined(I2C_FLTR_ANOFF) - -/** - * @brief Enable Analog Noise Filter. - * @note This filter can only be programmed when the I2C is disabled (PE = 0). - * @rmtoll FLTR ANOFF LL_I2C_EnableAnalogFilter - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableAnalogFilter(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->FLTR, I2C_FLTR_ANOFF); -} - -/** - * @brief Disable Analog Noise Filter. - * @note This filter can only be programmed when the I2C is disabled (PE = 0). - * @rmtoll FLTR ANOFF LL_I2C_DisableAnalogFilter - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableAnalogFilter(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->FLTR, I2C_FLTR_ANOFF); -} - -/** - * @brief Check if Analog Noise Filter is enabled or disabled. - * @rmtoll FLTR ANOFF LL_I2C_IsEnabledAnalogFilter - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledAnalogFilter(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->FLTR, I2C_FLTR_ANOFF) == (I2C_FLTR_ANOFF)); -} -#endif - -/** - * @brief Enable DMA transmission requests. - * @rmtoll CR2 DMAEN LL_I2C_EnableDMAReq_TX - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableDMAReq_TX(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR2, I2C_CR2_DMAEN); -} - -/** - * @brief Disable DMA transmission requests. - * @rmtoll CR2 DMAEN LL_I2C_DisableDMAReq_TX - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableDMAReq_TX(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR2, I2C_CR2_DMAEN); -} - -/** - * @brief Check if DMA transmission requests are enabled or disabled. - * @rmtoll CR2 DMAEN LL_I2C_IsEnabledDMAReq_TX - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledDMAReq_TX(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR2, I2C_CR2_DMAEN) == (I2C_CR2_DMAEN)); -} - -/** - * @brief Enable DMA reception requests. - * @rmtoll CR2 DMAEN LL_I2C_EnableDMAReq_RX - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableDMAReq_RX(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR2, I2C_CR2_DMAEN); -} - -/** - * @brief Disable DMA reception requests. - * @rmtoll CR2 DMAEN LL_I2C_DisableDMAReq_RX - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableDMAReq_RX(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR2, I2C_CR2_DMAEN); -} - -/** - * @brief Check if DMA reception requests are enabled or disabled. - * @rmtoll CR2 DMAEN LL_I2C_IsEnabledDMAReq_RX - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledDMAReq_RX(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR2, I2C_CR2_DMAEN) == (I2C_CR2_DMAEN)); -} - -/** - * @brief Get the data register address used for DMA transfer. - * @rmtoll DR DR LL_I2C_DMA_GetRegAddr - * @param I2Cx I2C Instance. - * @retval Address of data register - */ -__STATIC_INLINE uint32_t LL_I2C_DMA_GetRegAddr(I2C_TypeDef *I2Cx) -{ - return (uint32_t) & (I2Cx->DR); -} - -/** - * @brief Enable Clock stretching. - * @note This bit can only be programmed when the I2C is disabled (PE = 0). - * @rmtoll CR1 NOSTRETCH LL_I2C_EnableClockStretching - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableClockStretching(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR1, I2C_CR1_NOSTRETCH); -} - -/** - * @brief Disable Clock stretching. - * @note This bit can only be programmed when the I2C is disabled (PE = 0). - * @rmtoll CR1 NOSTRETCH LL_I2C_DisableClockStretching - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableClockStretching(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR1, I2C_CR1_NOSTRETCH); -} - -/** - * @brief Check if Clock stretching is enabled or disabled. - * @rmtoll CR1 NOSTRETCH LL_I2C_IsEnabledClockStretching - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledClockStretching(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR1, I2C_CR1_NOSTRETCH) != (I2C_CR1_NOSTRETCH)); -} - -/** - * @brief Enable General Call. - * @note When enabled the Address 0x00 is ACKed. - * @rmtoll CR1 ENGC LL_I2C_EnableGeneralCall - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableGeneralCall(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR1, I2C_CR1_ENGC); -} - -/** - * @brief Disable General Call. - * @note When disabled the Address 0x00 is NACKed. - * @rmtoll CR1 ENGC LL_I2C_DisableGeneralCall - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableGeneralCall(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR1, I2C_CR1_ENGC); -} - -/** - * @brief Check if General Call is enabled or disabled. - * @rmtoll CR1 ENGC LL_I2C_IsEnabledGeneralCall - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledGeneralCall(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR1, I2C_CR1_ENGC) == (I2C_CR1_ENGC)); -} - -/** - * @brief Set the Own Address1. - * @rmtoll OAR1 ADD0 LL_I2C_SetOwnAddress1\n - * OAR1 ADD1_7 LL_I2C_SetOwnAddress1\n - * OAR1 ADD8_9 LL_I2C_SetOwnAddress1\n - * OAR1 ADDMODE LL_I2C_SetOwnAddress1 - * @param I2Cx I2C Instance. - * @param OwnAddress1 This parameter must be a value between Min_Data=0 and Max_Data=0x3FF. - * @param OwnAddrSize This parameter can be one of the following values: - * @arg @ref LL_I2C_OWNADDRESS1_7BIT - * @arg @ref LL_I2C_OWNADDRESS1_10BIT - * @retval None - */ -__STATIC_INLINE void LL_I2C_SetOwnAddress1(I2C_TypeDef *I2Cx, uint32_t OwnAddress1, uint32_t OwnAddrSize) -{ - MODIFY_REG(I2Cx->OAR1, I2C_OAR1_ADD0 | I2C_OAR1_ADD1_7 | I2C_OAR1_ADD8_9 | I2C_OAR1_ADDMODE, OwnAddress1 | OwnAddrSize); -} - -/** - * @brief Set the 7bits Own Address2. - * @note This action has no effect if own address2 is enabled. - * @rmtoll OAR2 ADD2 LL_I2C_SetOwnAddress2 - * @param I2Cx I2C Instance. - * @param OwnAddress2 This parameter must be a value between Min_Data=0 and Max_Data=0x7F. - * @retval None - */ -__STATIC_INLINE void LL_I2C_SetOwnAddress2(I2C_TypeDef *I2Cx, uint32_t OwnAddress2) -{ - MODIFY_REG(I2Cx->OAR2, I2C_OAR2_ADD2, OwnAddress2); -} - -/** - * @brief Enable acknowledge on Own Address2 match address. - * @rmtoll OAR2 ENDUAL LL_I2C_EnableOwnAddress2 - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableOwnAddress2(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->OAR2, I2C_OAR2_ENDUAL); -} - -/** - * @brief Disable acknowledge on Own Address2 match address. - * @rmtoll OAR2 ENDUAL LL_I2C_DisableOwnAddress2 - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableOwnAddress2(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->OAR2, I2C_OAR2_ENDUAL); -} - -/** - * @brief Check if Own Address1 acknowledge is enabled or disabled. - * @rmtoll OAR2 ENDUAL LL_I2C_IsEnabledOwnAddress2 - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledOwnAddress2(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->OAR2, I2C_OAR2_ENDUAL) == (I2C_OAR2_ENDUAL)); -} - -/** - * @brief Configure the Peripheral clock frequency. - * @rmtoll CR2 FREQ LL_I2C_SetPeriphClock - * @param I2Cx I2C Instance. - * @param PeriphClock Peripheral Clock (in Hz) - * @retval None - */ -__STATIC_INLINE void LL_I2C_SetPeriphClock(I2C_TypeDef *I2Cx, uint32_t PeriphClock) -{ - MODIFY_REG(I2Cx->CR2, I2C_CR2_FREQ, __LL_I2C_FREQ_HZ_TO_MHZ(PeriphClock)); -} - -/** - * @brief Get the Peripheral clock frequency. - * @rmtoll CR2 FREQ LL_I2C_GetPeriphClock - * @param I2Cx I2C Instance. - * @retval Value of Peripheral Clock (in Hz) - */ -__STATIC_INLINE uint32_t LL_I2C_GetPeriphClock(I2C_TypeDef *I2Cx) -{ - return (uint32_t)(__LL_I2C_FREQ_MHZ_TO_HZ(READ_BIT(I2Cx->CR2, I2C_CR2_FREQ))); -} - -/** - * @brief Configure the Duty cycle (Fast mode only). - * @rmtoll CCR DUTY LL_I2C_SetDutyCycle - * @param I2Cx I2C Instance. - * @param DutyCycle This parameter can be one of the following values: - * @arg @ref LL_I2C_DUTYCYCLE_2 - * @arg @ref LL_I2C_DUTYCYCLE_16_9 - * @retval None - */ -__STATIC_INLINE void LL_I2C_SetDutyCycle(I2C_TypeDef *I2Cx, uint32_t DutyCycle) -{ - MODIFY_REG(I2Cx->CCR, I2C_CCR_DUTY, DutyCycle); -} - -/** - * @brief Get the Duty cycle (Fast mode only). - * @rmtoll CCR DUTY LL_I2C_GetDutyCycle - * @param I2Cx I2C Instance. - * @retval Returned value can be one of the following values: - * @arg @ref LL_I2C_DUTYCYCLE_2 - * @arg @ref LL_I2C_DUTYCYCLE_16_9 - */ -__STATIC_INLINE uint32_t LL_I2C_GetDutyCycle(I2C_TypeDef *I2Cx) -{ - return (uint32_t)(READ_BIT(I2Cx->CCR, I2C_CCR_DUTY)); -} - -/** - * @brief Configure the I2C master clock speed mode. - * @rmtoll CCR FS LL_I2C_SetClockSpeedMode - * @param I2Cx I2C Instance. - * @param ClockSpeedMode This parameter can be one of the following values: - * @arg @ref LL_I2C_CLOCK_SPEED_STANDARD_MODE - * @arg @ref LL_I2C_CLOCK_SPEED_FAST_MODE - * @retval None - */ -__STATIC_INLINE void LL_I2C_SetClockSpeedMode(I2C_TypeDef *I2Cx, uint32_t ClockSpeedMode) -{ - MODIFY_REG(I2Cx->CCR, I2C_CCR_FS, ClockSpeedMode); -} - -/** - * @brief Get the the I2C master speed mode. - * @rmtoll CCR FS LL_I2C_GetClockSpeedMode - * @param I2Cx I2C Instance. - * @retval Returned value can be one of the following values: - * @arg @ref LL_I2C_CLOCK_SPEED_STANDARD_MODE - * @arg @ref LL_I2C_CLOCK_SPEED_FAST_MODE - */ -__STATIC_INLINE uint32_t LL_I2C_GetClockSpeedMode(I2C_TypeDef *I2Cx) -{ - return (uint32_t)(READ_BIT(I2Cx->CCR, I2C_CCR_FS)); -} - -/** - * @brief Configure the SCL, SDA rising time. - * @note This bit can only be programmed when the I2C is disabled (PE = 0). - * @rmtoll TRISE TRISE LL_I2C_SetRiseTime - * @param I2Cx I2C Instance. - * @param RiseTime This parameter must be a value between Min_Data=0x02 and Max_Data=0x3F. - * @retval None - */ -__STATIC_INLINE void LL_I2C_SetRiseTime(I2C_TypeDef *I2Cx, uint32_t RiseTime) -{ - MODIFY_REG(I2Cx->TRISE, I2C_TRISE_TRISE, RiseTime); -} - -/** - * @brief Get the SCL, SDA rising time. - * @rmtoll TRISE TRISE LL_I2C_GetRiseTime - * @param I2Cx I2C Instance. - * @retval Value between Min_Data=0x02 and Max_Data=0x3F - */ -__STATIC_INLINE uint32_t LL_I2C_GetRiseTime(I2C_TypeDef *I2Cx) -{ - return (uint32_t)(READ_BIT(I2Cx->TRISE, I2C_TRISE_TRISE)); -} - -/** - * @brief Configure the SCL high and low period. - * @note This bit can only be programmed when the I2C is disabled (PE = 0). - * @rmtoll CCR CCR LL_I2C_SetClockPeriod - * @param I2Cx I2C Instance. - * @param ClockPeriod This parameter must be a value between Min_Data=0x004 and Max_Data=0xFFF, except in FAST DUTY mode where Min_Data=0x001. - * @retval None - */ -__STATIC_INLINE void LL_I2C_SetClockPeriod(I2C_TypeDef *I2Cx, uint32_t ClockPeriod) -{ - MODIFY_REG(I2Cx->CCR, I2C_CCR_CCR, ClockPeriod); -} - -/** - * @brief Get the SCL high and low period. - * @rmtoll CCR CCR LL_I2C_GetClockPeriod - * @param I2Cx I2C Instance. - * @retval Value between Min_Data=0x004 and Max_Data=0xFFF, except in FAST DUTY mode where Min_Data=0x001. - */ -__STATIC_INLINE uint32_t LL_I2C_GetClockPeriod(I2C_TypeDef *I2Cx) -{ - return (uint32_t)(READ_BIT(I2Cx->CCR, I2C_CCR_CCR)); -} - -/** - * @brief Configure the SCL speed. - * @note This bit can only be programmed when the I2C is disabled (PE = 0). - * @rmtoll CR2 FREQ LL_I2C_ConfigSpeed\n - * TRISE TRISE LL_I2C_ConfigSpeed\n - * CCR FS LL_I2C_ConfigSpeed\n - * CCR DUTY LL_I2C_ConfigSpeed\n - * CCR CCR LL_I2C_ConfigSpeed - * @param I2Cx I2C Instance. - * @param PeriphClock Peripheral Clock (in Hz) - * @param ClockSpeed This parameter must be a value lower than 400kHz (in Hz). - * @param DutyCycle This parameter can be one of the following values: - * @arg @ref LL_I2C_DUTYCYCLE_2 - * @arg @ref LL_I2C_DUTYCYCLE_16_9 - * @retval None - */ -__STATIC_INLINE void LL_I2C_ConfigSpeed(I2C_TypeDef *I2Cx, uint32_t PeriphClock, uint32_t ClockSpeed, - uint32_t DutyCycle) -{ - uint32_t freqrange = 0x0U; - uint32_t clockconfig = 0x0U; - - /* Compute frequency range */ - freqrange = __LL_I2C_FREQ_HZ_TO_MHZ(PeriphClock); - - /* Configure I2Cx: Frequency range register */ - MODIFY_REG(I2Cx->CR2, I2C_CR2_FREQ, freqrange); - - /* Configure I2Cx: Rise Time register */ - MODIFY_REG(I2Cx->TRISE, I2C_TRISE_TRISE, __LL_I2C_RISE_TIME(freqrange, ClockSpeed)); - - /* Configure Speed mode, Duty Cycle and Clock control register value */ - if (ClockSpeed > LL_I2C_MAX_SPEED_STANDARD) - { - /* Set Speed mode at fast and duty cycle for Clock Speed request in fast clock range */ - clockconfig = LL_I2C_CLOCK_SPEED_FAST_MODE | \ - __LL_I2C_SPEED_FAST_TO_CCR(PeriphClock, ClockSpeed, DutyCycle) | \ - DutyCycle; - } - else - { - /* Set Speed mode at standard for Clock Speed request in standard clock range */ - clockconfig = LL_I2C_CLOCK_SPEED_STANDARD_MODE | \ - __LL_I2C_SPEED_STANDARD_TO_CCR(PeriphClock, ClockSpeed); - } - - /* Configure I2Cx: Clock control register */ - MODIFY_REG(I2Cx->CCR, (I2C_CCR_FS | I2C_CCR_DUTY | I2C_CCR_CCR), clockconfig); -} - -/** - * @brief Configure peripheral mode. - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @rmtoll CR1 SMBUS LL_I2C_SetMode\n - * CR1 SMBTYPE LL_I2C_SetMode\n - * CR1 ENARP LL_I2C_SetMode - * @param I2Cx I2C Instance. - * @param PeripheralMode This parameter can be one of the following values: - * @arg @ref LL_I2C_MODE_I2C - * @arg @ref LL_I2C_MODE_SMBUS_HOST - * @arg @ref LL_I2C_MODE_SMBUS_DEVICE - * @arg @ref LL_I2C_MODE_SMBUS_DEVICE_ARP - * @retval None - */ -__STATIC_INLINE void LL_I2C_SetMode(I2C_TypeDef *I2Cx, uint32_t PeripheralMode) -{ - MODIFY_REG(I2Cx->CR1, I2C_CR1_SMBUS | I2C_CR1_SMBTYPE | I2C_CR1_ENARP, PeripheralMode); -} - -/** - * @brief Get peripheral mode. - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @rmtoll CR1 SMBUS LL_I2C_GetMode\n - * CR1 SMBTYPE LL_I2C_GetMode\n - * CR1 ENARP LL_I2C_GetMode - * @param I2Cx I2C Instance. - * @retval Returned value can be one of the following values: - * @arg @ref LL_I2C_MODE_I2C - * @arg @ref LL_I2C_MODE_SMBUS_HOST - * @arg @ref LL_I2C_MODE_SMBUS_DEVICE - * @arg @ref LL_I2C_MODE_SMBUS_DEVICE_ARP - */ -__STATIC_INLINE uint32_t LL_I2C_GetMode(I2C_TypeDef *I2Cx) -{ - return (uint32_t)(READ_BIT(I2Cx->CR1, I2C_CR1_SMBUS | I2C_CR1_SMBTYPE | I2C_CR1_ENARP)); -} - -/** - * @brief Enable SMBus alert (Host or Device mode) - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @note SMBus Device mode: - * - SMBus Alert pin is drived low and - * Alert Response Address Header acknowledge is enabled. - * SMBus Host mode: - * - SMBus Alert pin management is supported. - * @rmtoll CR1 ALERT LL_I2C_EnableSMBusAlert - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableSMBusAlert(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR1, I2C_CR1_ALERT); -} - -/** - * @brief Disable SMBus alert (Host or Device mode) - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @note SMBus Device mode: - * - SMBus Alert pin is not drived (can be used as a standard GPIO) and - * Alert Response Address Header acknowledge is disabled. - * SMBus Host mode: - * - SMBus Alert pin management is not supported. - * @rmtoll CR1 ALERT LL_I2C_DisableSMBusAlert - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableSMBusAlert(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR1, I2C_CR1_ALERT); -} - -/** - * @brief Check if SMBus alert (Host or Device mode) is enabled or disabled. - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @rmtoll CR1 ALERT LL_I2C_IsEnabledSMBusAlert - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledSMBusAlert(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR1, I2C_CR1_ALERT) == (I2C_CR1_ALERT)); -} - -/** - * @brief Enable SMBus Packet Error Calculation (PEC). - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @rmtoll CR1 ENPEC LL_I2C_EnableSMBusPEC - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableSMBusPEC(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR1, I2C_CR1_ENPEC); -} - -/** - * @brief Disable SMBus Packet Error Calculation (PEC). - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @rmtoll CR1 ENPEC LL_I2C_DisableSMBusPEC - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableSMBusPEC(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR1, I2C_CR1_ENPEC); -} - -/** - * @brief Check if SMBus Packet Error Calculation (PEC) is enabled or disabled. - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @rmtoll CR1 ENPEC LL_I2C_IsEnabledSMBusPEC - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledSMBusPEC(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR1, I2C_CR1_ENPEC) == (I2C_CR1_ENPEC)); -} - -/** - * @} - */ - -/** @defgroup I2C_LL_EF_IT_Management IT_Management - * @{ - */ - -/** - * @brief Enable TXE interrupt. - * @rmtoll CR2 ITEVTEN LL_I2C_EnableIT_TX\n - * CR2 ITBUFEN LL_I2C_EnableIT_TX - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableIT_TX(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN); -} - -/** - * @brief Disable TXE interrupt. - * @rmtoll CR2 ITEVTEN LL_I2C_DisableIT_TX\n - * CR2 ITBUFEN LL_I2C_DisableIT_TX - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableIT_TX(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN); -} - -/** - * @brief Check if the TXE Interrupt is enabled or disabled. - * @rmtoll CR2 ITEVTEN LL_I2C_IsEnabledIT_TX\n - * CR2 ITBUFEN LL_I2C_IsEnabledIT_TX - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledIT_TX(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN) == (I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN)); -} - -/** - * @brief Enable RXNE interrupt. - * @rmtoll CR2 ITEVTEN LL_I2C_EnableIT_RX\n - * CR2 ITBUFEN LL_I2C_EnableIT_RX - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableIT_RX(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN); -} - -/** - * @brief Disable RXNE interrupt. - * @rmtoll CR2 ITEVTEN LL_I2C_DisableIT_RX\n - * CR2 ITBUFEN LL_I2C_DisableIT_RX - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableIT_RX(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN); -} - -/** - * @brief Check if the RXNE Interrupt is enabled or disabled. - * @rmtoll CR2 ITEVTEN LL_I2C_IsEnabledIT_RX\n - * CR2 ITBUFEN LL_I2C_IsEnabledIT_RX - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledIT_RX(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN) == (I2C_CR2_ITEVTEN | I2C_CR2_ITBUFEN)); -} - -/** - * @brief Enable Events interrupts. - * @note Any of these events will generate interrupt : - * Start Bit (SB) - * Address sent, Address matched (ADDR) - * 10-bit header sent (ADD10) - * Stop detection (STOPF) - * Byte transfer finished (BTF) - * - * @note Any of these events will generate interrupt if Buffer interrupts are enabled too(using unitary function @ref LL_I2C_EnableIT_BUF()) : - * Receive buffer not empty (RXNE) - * Transmit buffer empty (TXE) - * @rmtoll CR2 ITEVTEN LL_I2C_EnableIT_EVT - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableIT_EVT(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN); -} - -/** - * @brief Disable Events interrupts. - * @note Any of these events will generate interrupt : - * Start Bit (SB) - * Address sent, Address matched (ADDR) - * 10-bit header sent (ADD10) - * Stop detection (STOPF) - * Byte transfer finished (BTF) - * Receive buffer not empty (RXNE) - * Transmit buffer empty (TXE) - * @rmtoll CR2 ITEVTEN LL_I2C_DisableIT_EVT - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableIT_EVT(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN); -} - -/** - * @brief Check if Events interrupts are enabled or disabled. - * @rmtoll CR2 ITEVTEN LL_I2C_IsEnabledIT_EVT - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledIT_EVT(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR2, I2C_CR2_ITEVTEN) == (I2C_CR2_ITEVTEN)); -} - -/** - * @brief Enable Buffer interrupts. - * @note Any of these Buffer events will generate interrupt if Events interrupts are enabled too(using unitary function @ref LL_I2C_EnableIT_EVT()) : - * Receive buffer not empty (RXNE) - * Transmit buffer empty (TXE) - * @rmtoll CR2 ITBUFEN LL_I2C_EnableIT_BUF - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableIT_BUF(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR2, I2C_CR2_ITBUFEN); -} - -/** - * @brief Disable Buffer interrupts. - * @note Any of these Buffer events will generate interrupt : - * Receive buffer not empty (RXNE) - * Transmit buffer empty (TXE) - * @rmtoll CR2 ITBUFEN LL_I2C_DisableIT_BUF - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableIT_BUF(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR2, I2C_CR2_ITBUFEN); -} - -/** - * @brief Check if Buffer interrupts are enabled or disabled. - * @rmtoll CR2 ITBUFEN LL_I2C_IsEnabledIT_BUF - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledIT_BUF(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR2, I2C_CR2_ITBUFEN) == (I2C_CR2_ITBUFEN)); -} - -/** - * @brief Enable Error interrupts. - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @note Any of these errors will generate interrupt : - * Bus Error detection (BERR) - * Arbitration Loss (ARLO) - * Acknowledge Failure(AF) - * Overrun/Underrun (OVR) - * SMBus Timeout detection (TIMEOUT) - * SMBus PEC error detection (PECERR) - * SMBus Alert pin event detection (SMBALERT) - * @rmtoll CR2 ITERREN LL_I2C_EnableIT_ERR - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableIT_ERR(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR2, I2C_CR2_ITERREN); -} - -/** - * @brief Disable Error interrupts. - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @note Any of these errors will generate interrupt : - * Bus Error detection (BERR) - * Arbitration Loss (ARLO) - * Acknowledge Failure(AF) - * Overrun/Underrun (OVR) - * SMBus Timeout detection (TIMEOUT) - * SMBus PEC error detection (PECERR) - * SMBus Alert pin event detection (SMBALERT) - * @rmtoll CR2 ITERREN LL_I2C_DisableIT_ERR - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableIT_ERR(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR2, I2C_CR2_ITERREN); -} - -/** - * @brief Check if Error interrupts are enabled or disabled. - * @rmtoll CR2 ITERREN LL_I2C_IsEnabledIT_ERR - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledIT_ERR(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR2, I2C_CR2_ITERREN) == (I2C_CR2_ITERREN)); -} - -/** - * @} - */ - -/** @defgroup I2C_LL_EF_FLAG_management FLAG_management - * @{ - */ - -/** - * @brief Indicate the status of Transmit data register empty flag. - * @note RESET: When next data is written in Transmit data register. - * SET: When Transmit data register is empty. - * @rmtoll SR1 TXE LL_I2C_IsActiveFlag_TXE - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_TXE(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR1, I2C_SR1_TXE) == (I2C_SR1_TXE)); -} - -/** - * @brief Indicate the status of Byte Transfer Finished flag. - * RESET: When Data byte transfer not done. - * SET: When Data byte transfer succeeded. - * @rmtoll SR1 BTF LL_I2C_IsActiveFlag_BTF - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_BTF(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR1, I2C_SR1_BTF) == (I2C_SR1_BTF)); -} - -/** - * @brief Indicate the status of Receive data register not empty flag. - * @note RESET: When Receive data register is read. - * SET: When the received data is copied in Receive data register. - * @rmtoll SR1 RXNE LL_I2C_IsActiveFlag_RXNE - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_RXNE(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR1, I2C_SR1_RXNE) == (I2C_SR1_RXNE)); -} - -/** - * @brief Indicate the status of Start Bit (master mode). - * @note RESET: When No Start condition. - * SET: When Start condition is generated. - * @rmtoll SR1 SB LL_I2C_IsActiveFlag_SB - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_SB(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR1, I2C_SR1_SB) == (I2C_SR1_SB)); -} - -/** - * @brief Indicate the status of Address sent (master mode) or Address matched flag (slave mode). - * @note RESET: Clear default value. - * SET: When the address is fully sent (master mode) or when the received slave address matched with one of the enabled slave address (slave mode). - * @rmtoll SR1 ADDR LL_I2C_IsActiveFlag_ADDR - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_ADDR(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR1, I2C_SR1_ADDR) == (I2C_SR1_ADDR)); -} - -/** - * @brief Indicate the status of 10-bit header sent (master mode). - * @note RESET: When no ADD10 event occurred. - * SET: When the master has sent the first address byte (header). - * @rmtoll SR1 ADD10 LL_I2C_IsActiveFlag_ADD10 - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_ADD10(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR1, I2C_SR1_ADD10) == (I2C_SR1_ADD10)); -} - -/** - * @brief Indicate the status of Acknowledge failure flag. - * @note RESET: No acknowledge failure. - * SET: When an acknowledge failure is received after a byte transmission. - * @rmtoll SR1 AF LL_I2C_IsActiveFlag_AF - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_AF(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR1, I2C_SR1_AF) == (I2C_SR1_AF)); -} - -/** - * @brief Indicate the status of Stop detection flag (slave mode). - * @note RESET: Clear default value. - * SET: When a Stop condition is detected. - * @rmtoll SR1 STOPF LL_I2C_IsActiveFlag_STOP - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_STOP(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR1, I2C_SR1_STOPF) == (I2C_SR1_STOPF)); -} - -/** - * @brief Indicate the status of Bus error flag. - * @note RESET: Clear default value. - * SET: When a misplaced Start or Stop condition is detected. - * @rmtoll SR1 BERR LL_I2C_IsActiveFlag_BERR - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_BERR(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR1, I2C_SR1_BERR) == (I2C_SR1_BERR)); -} - -/** - * @brief Indicate the status of Arbitration lost flag. - * @note RESET: Clear default value. - * SET: When arbitration lost. - * @rmtoll SR1 ARLO LL_I2C_IsActiveFlag_ARLO - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_ARLO(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR1, I2C_SR1_ARLO) == (I2C_SR1_ARLO)); -} - -/** - * @brief Indicate the status of Overrun/Underrun flag. - * @note RESET: Clear default value. - * SET: When an overrun/underrun error occurs (Clock Stretching Disabled). - * @rmtoll SR1 OVR LL_I2C_IsActiveFlag_OVR - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_OVR(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR1, I2C_SR1_OVR) == (I2C_SR1_OVR)); -} - -/** - * @brief Indicate the status of SMBus PEC error flag in reception. - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @rmtoll SR1 PECERR LL_I2C_IsActiveSMBusFlag_PECERR - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveSMBusFlag_PECERR(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR1, I2C_SR1_PECERR) == (I2C_SR1_PECERR)); -} - -/** - * @brief Indicate the status of SMBus Timeout detection flag. - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @rmtoll SR1 TIMEOUT LL_I2C_IsActiveSMBusFlag_TIMEOUT - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveSMBusFlag_TIMEOUT(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR1, I2C_SR1_TIMEOUT) == (I2C_SR1_TIMEOUT)); -} - -/** - * @brief Indicate the status of SMBus alert flag. - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @rmtoll SR1 SMBALERT LL_I2C_IsActiveSMBusFlag_ALERT - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveSMBusFlag_ALERT(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR1, I2C_SR1_SMBALERT) == (I2C_SR1_SMBALERT)); -} - -/** - * @brief Indicate the status of Bus Busy flag. - * @note RESET: Clear default value. - * SET: When a Start condition is detected. - * @rmtoll SR2 BUSY LL_I2C_IsActiveFlag_BUSY - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_BUSY(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR2, I2C_SR2_BUSY) == (I2C_SR2_BUSY)); -} - -/** - * @brief Indicate the status of Dual flag. - * @note RESET: Received address matched with OAR1. - * SET: Received address matched with OAR2. - * @rmtoll SR2 DUALF LL_I2C_IsActiveFlag_DUAL - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_DUAL(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR2, I2C_SR2_DUALF) == (I2C_SR2_DUALF)); -} - -/** - * @brief Indicate the status of SMBus Host address reception (Slave mode). - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @note RESET: No SMBus Host address - * SET: SMBus Host address received. - * @note This status is cleared by hardware after a STOP condition or repeated START condition. - * @rmtoll SR2 SMBHOST LL_I2C_IsActiveSMBusFlag_SMBHOST - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveSMBusFlag_SMBHOST(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR2, I2C_SR2_SMBHOST) == (I2C_SR2_SMBHOST)); -} - -/** - * @brief Indicate the status of SMBus Device default address reception (Slave mode). - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @note RESET: No SMBus Device default address - * SET: SMBus Device default address received. - * @note This status is cleared by hardware after a STOP condition or repeated START condition. - * @rmtoll SR2 SMBDEFAULT LL_I2C_IsActiveSMBusFlag_SMBDEFAULT - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveSMBusFlag_SMBDEFAULT(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR2, I2C_SR2_SMBDEFAULT) == (I2C_SR2_SMBDEFAULT)); -} - -/** - * @brief Indicate the status of General call address reception (Slave mode). - * @note RESET: No General call address - * SET: General call address received. - * @note This status is cleared by hardware after a STOP condition or repeated START condition. - * @rmtoll SR2 GENCALL LL_I2C_IsActiveFlag_GENCALL - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_GENCALL(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR2, I2C_SR2_GENCALL) == (I2C_SR2_GENCALL)); -} - -/** - * @brief Indicate the status of Master/Slave flag. - * @note RESET: Slave Mode. - * SET: Master Mode. - * @rmtoll SR2 MSL LL_I2C_IsActiveFlag_MSL - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsActiveFlag_MSL(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->SR2, I2C_SR2_MSL) == (I2C_SR2_MSL)); -} - -/** - * @brief Clear Address Matched flag. - * @note Clearing this flag is done by a read access to the I2Cx_SR1 - * register followed by a read access to the I2Cx_SR2 register. - * @rmtoll SR1 ADDR LL_I2C_ClearFlag_ADDR - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_ClearFlag_ADDR(I2C_TypeDef *I2Cx) -{ - __IO uint32_t tmpreg; - tmpreg = I2Cx->SR1; - (void) tmpreg; - tmpreg = I2Cx->SR2; - (void) tmpreg; -} - -/** - * @brief Clear Acknowledge failure flag. - * @rmtoll SR1 AF LL_I2C_ClearFlag_AF - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_ClearFlag_AF(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->SR1, I2C_SR1_AF); -} - -/** - * @brief Clear Stop detection flag. - * @note Clearing this flag is done by a read access to the I2Cx_SR1 - * register followed by a write access to I2Cx_CR1 register. - * @rmtoll SR1 STOPF LL_I2C_ClearFlag_STOP\n - * CR1 PE LL_I2C_ClearFlag_STOP - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_ClearFlag_STOP(I2C_TypeDef *I2Cx) -{ - __IO uint32_t tmpreg; - tmpreg = I2Cx->SR1; - (void) tmpreg; - SET_BIT(I2Cx->CR1, I2C_CR1_PE); -} - -/** - * @brief Clear Bus error flag. - * @rmtoll SR1 BERR LL_I2C_ClearFlag_BERR - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_ClearFlag_BERR(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->SR1, I2C_SR1_BERR); -} - -/** - * @brief Clear Arbitration lost flag. - * @rmtoll SR1 ARLO LL_I2C_ClearFlag_ARLO - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_ClearFlag_ARLO(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->SR1, I2C_SR1_ARLO); -} - -/** - * @brief Clear Overrun/Underrun flag. - * @rmtoll SR1 OVR LL_I2C_ClearFlag_OVR - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_ClearFlag_OVR(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->SR1, I2C_SR1_OVR); -} - -/** - * @brief Clear SMBus PEC error flag. - * @rmtoll SR1 PECERR LL_I2C_ClearSMBusFlag_PECERR - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_ClearSMBusFlag_PECERR(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->SR1, I2C_SR1_PECERR); -} - -/** - * @brief Clear SMBus Timeout detection flag. - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @rmtoll SR1 TIMEOUT LL_I2C_ClearSMBusFlag_TIMEOUT - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_ClearSMBusFlag_TIMEOUT(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->SR1, I2C_SR1_TIMEOUT); -} - -/** - * @brief Clear SMBus Alert flag. - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @rmtoll SR1 SMBALERT LL_I2C_ClearSMBusFlag_ALERT - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_ClearSMBusFlag_ALERT(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->SR1, I2C_SR1_SMBALERT); -} - -/** - * @} - */ - -/** @defgroup I2C_LL_EF_Data_Management Data_Management - * @{ - */ - -/** - * @brief Enable Reset of I2C peripheral. - * @rmtoll CR1 SWRST LL_I2C_EnableReset - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableReset(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR1, I2C_CR1_SWRST); -} - -/** - * @brief Disable Reset of I2C peripheral. - * @rmtoll CR1 SWRST LL_I2C_DisableReset - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableReset(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR1, I2C_CR1_SWRST); -} - -/** - * @brief Check if the I2C peripheral is under reset state or not. - * @rmtoll CR1 SWRST LL_I2C_IsResetEnabled - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsResetEnabled(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR1, I2C_CR1_SWRST) == (I2C_CR1_SWRST)); -} - -/** - * @brief Prepare the generation of a ACKnowledge or Non ACKnowledge condition after the address receive match code or next received byte. - * @note Usage in Slave or Master mode. - * @rmtoll CR1 ACK LL_I2C_AcknowledgeNextData - * @param I2Cx I2C Instance. - * @param TypeAcknowledge This parameter can be one of the following values: - * @arg @ref LL_I2C_ACK - * @arg @ref LL_I2C_NACK - * @retval None - */ -__STATIC_INLINE void LL_I2C_AcknowledgeNextData(I2C_TypeDef *I2Cx, uint32_t TypeAcknowledge) -{ - MODIFY_REG(I2Cx->CR1, I2C_CR1_ACK, TypeAcknowledge); -} - -/** - * @brief Generate a START or RESTART condition - * @note The START bit can be set even if bus is BUSY or I2C is in slave mode. - * This action has no effect when RELOAD is set. - * @rmtoll CR1 START LL_I2C_GenerateStartCondition - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_GenerateStartCondition(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR1, I2C_CR1_START); -} - -/** - * @brief Generate a STOP condition after the current byte transfer (master mode). - * @rmtoll CR1 STOP LL_I2C_GenerateStopCondition - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_GenerateStopCondition(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR1, I2C_CR1_STOP); -} - -/** - * @brief Enable bit POS (master/host mode). - * @note In that case, the ACK bit controls the (N)ACK of the next byte received or the PEC bit indicates that the next byte in shift register is a PEC. - * @rmtoll CR1 POS LL_I2C_EnableBitPOS - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableBitPOS(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR1, I2C_CR1_POS); -} - -/** - * @brief Disable bit POS (master/host mode). - * @note In that case, the ACK bit controls the (N)ACK of the current byte received or the PEC bit indicates that the current byte in shift register is a PEC. - * @rmtoll CR1 POS LL_I2C_DisableBitPOS - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableBitPOS(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR1, I2C_CR1_POS); -} - -/** - * @brief Check if bit POS is enabled or disabled. - * @rmtoll CR1 POS LL_I2C_IsEnabledBitPOS - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledBitPOS(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR1, I2C_CR1_POS) == (I2C_CR1_POS)); -} - -/** - * @brief Indicate the value of transfer direction. - * @note RESET: Bus is in read transfer (peripheral point of view). - * SET: Bus is in write transfer (peripheral point of view). - * @rmtoll SR2 TRA LL_I2C_GetTransferDirection - * @param I2Cx I2C Instance. - * @retval Returned value can be one of the following values: - * @arg @ref LL_I2C_DIRECTION_WRITE - * @arg @ref LL_I2C_DIRECTION_READ - */ -__STATIC_INLINE uint32_t LL_I2C_GetTransferDirection(I2C_TypeDef *I2Cx) -{ - return (uint32_t)(READ_BIT(I2Cx->SR2, I2C_SR2_TRA)); -} - -/** - * @brief Enable DMA last transfer. - * @note This action mean that next DMA EOT is the last transfer. - * @rmtoll CR2 LAST LL_I2C_EnableLastDMA - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableLastDMA(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR2, I2C_CR2_LAST); -} - -/** - * @brief Disable DMA last transfer. - * @note This action mean that next DMA EOT is not the last transfer. - * @rmtoll CR2 LAST LL_I2C_DisableLastDMA - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableLastDMA(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR2, I2C_CR2_LAST); -} - -/** - * @brief Check if DMA last transfer is enabled or disabled. - * @rmtoll CR2 LAST LL_I2C_IsEnabledLastDMA - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledLastDMA(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR2, I2C_CR2_LAST) == (I2C_CR2_LAST)); -} - -/** - * @brief Enable transfer or internal comparison of the SMBus Packet Error byte (transmission or reception mode). - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @note This feature is cleared by hardware when the PEC byte is transferred or compared, - * or by a START or STOP condition, it is also cleared by software. - * @rmtoll CR1 PEC LL_I2C_EnableSMBusPECCompare - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_EnableSMBusPECCompare(I2C_TypeDef *I2Cx) -{ - SET_BIT(I2Cx->CR1, I2C_CR1_PEC); -} - -/** - * @brief Disable transfer or internal comparison of the SMBus Packet Error byte (transmission or reception mode). - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @rmtoll CR1 PEC LL_I2C_DisableSMBusPECCompare - * @param I2Cx I2C Instance. - * @retval None - */ -__STATIC_INLINE void LL_I2C_DisableSMBusPECCompare(I2C_TypeDef *I2Cx) -{ - CLEAR_BIT(I2Cx->CR1, I2C_CR1_PEC); -} - -/** - * @brief Check if the SMBus Packet Error byte transfer or internal comparison is requested or not. - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @rmtoll CR1 PEC LL_I2C_IsEnabledSMBusPECCompare - * @param I2Cx I2C Instance. - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2C_IsEnabledSMBusPECCompare(I2C_TypeDef *I2Cx) -{ - return (READ_BIT(I2Cx->CR1, I2C_CR1_PEC) == (I2C_CR1_PEC)); -} - -/** - * @brief Get the SMBus Packet Error byte calculated. - * @note Macro @ref IS_SMBUS_ALL_INSTANCE(I2Cx) can be used to check whether or not - * SMBus feature is supported by the I2Cx Instance. - * @rmtoll SR2 PEC LL_I2C_GetSMBusPEC - * @param I2Cx I2C Instance. - * @retval Value between Min_Data=0x00 and Max_Data=0xFF - */ -__STATIC_INLINE uint32_t LL_I2C_GetSMBusPEC(I2C_TypeDef *I2Cx) -{ - return (uint32_t)(READ_BIT(I2Cx->SR2, I2C_SR2_PEC) >> I2C_SR2_PEC_Pos); -} - -/** - * @brief Read Receive Data register. - * @rmtoll DR DR LL_I2C_ReceiveData8 - * @param I2Cx I2C Instance. - * @retval Value between Min_Data=0x0 and Max_Data=0xFF - */ -__STATIC_INLINE uint8_t LL_I2C_ReceiveData8(I2C_TypeDef *I2Cx) -{ - return (uint8_t)(READ_BIT(I2Cx->DR, I2C_DR_DR)); -} - -/** - * @brief Write in Transmit Data Register . - * @rmtoll DR DR LL_I2C_TransmitData8 - * @param I2Cx I2C Instance. - * @param Data Value between Min_Data=0x0 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_I2C_TransmitData8(I2C_TypeDef *I2Cx, uint8_t Data) -{ - MODIFY_REG(I2Cx->DR, I2C_DR_DR, Data); -} - -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup I2C_LL_EF_Init Initialization and de-initialization functions - * @{ - */ - -uint32_t LL_I2C_Init(I2C_TypeDef *I2Cx, LL_I2C_InitTypeDef *I2C_InitStruct); -uint32_t LL_I2C_DeInit(I2C_TypeDef *I2Cx); -void LL_I2C_StructInit(LL_I2C_InitTypeDef *I2C_InitStruct); - - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* I2C1 || I2C2 || I2C3 */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_I2C_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_iwdg.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_iwdg.h deleted file mode 100644 index 2f1b844..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_iwdg.h +++ /dev/null @@ -1,305 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_iwdg.h - * @author MCD Application Team - * @brief Header file of IWDG LL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_LL_IWDG_H -#define STM32F4xx_LL_IWDG_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined(IWDG) - -/** @defgroup IWDG_LL IWDG - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup IWDG_LL_Private_Constants IWDG Private Constants - * @{ - */ -#define LL_IWDG_KEY_RELOAD 0x0000AAAAU /*!< IWDG Reload Counter Enable */ -#define LL_IWDG_KEY_ENABLE 0x0000CCCCU /*!< IWDG Peripheral Enable */ -#define LL_IWDG_KEY_WR_ACCESS_ENABLE 0x00005555U /*!< IWDG KR Write Access Enable */ -#define LL_IWDG_KEY_WR_ACCESS_DISABLE 0x00000000U /*!< IWDG KR Write Access Disable */ -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/** @defgroup IWDG_LL_Exported_Constants IWDG Exported Constants - * @{ - */ - -/** @defgroup IWDG_LL_EC_GET_FLAG Get Flags Defines - * @brief Flags defines which can be used with LL_IWDG_ReadReg function - * @{ - */ -#define LL_IWDG_SR_PVU IWDG_SR_PVU /*!< Watchdog prescaler value update */ -#define LL_IWDG_SR_RVU IWDG_SR_RVU /*!< Watchdog counter reload value update */ -/** - * @} - */ - -/** @defgroup IWDG_LL_EC_PRESCALER Prescaler Divider - * @{ - */ -#define LL_IWDG_PRESCALER_4 0x00000000U /*!< Divider by 4 */ -#define LL_IWDG_PRESCALER_8 (IWDG_PR_PR_0) /*!< Divider by 8 */ -#define LL_IWDG_PRESCALER_16 (IWDG_PR_PR_1) /*!< Divider by 16 */ -#define LL_IWDG_PRESCALER_32 (IWDG_PR_PR_1 | IWDG_PR_PR_0) /*!< Divider by 32 */ -#define LL_IWDG_PRESCALER_64 (IWDG_PR_PR_2) /*!< Divider by 64 */ -#define LL_IWDG_PRESCALER_128 (IWDG_PR_PR_2 | IWDG_PR_PR_0) /*!< Divider by 128 */ -#define LL_IWDG_PRESCALER_256 (IWDG_PR_PR_2 | IWDG_PR_PR_1) /*!< Divider by 256 */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup IWDG_LL_Exported_Macros IWDG Exported Macros - * @{ - */ - -/** @defgroup IWDG_LL_EM_WRITE_READ Common Write and read registers Macros - * @{ - */ - -/** - * @brief Write a value in IWDG register - * @param __INSTANCE__ IWDG Instance - * @param __REG__ Register to be written - * @param __VALUE__ Value to be written in the register - * @retval None - */ -#define LL_IWDG_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__)) - -/** - * @brief Read a value in IWDG register - * @param __INSTANCE__ IWDG Instance - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_IWDG_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__) -/** - * @} - */ - -/** - * @} - */ - - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup IWDG_LL_Exported_Functions IWDG Exported Functions - * @{ - */ -/** @defgroup IWDG_LL_EF_Configuration Configuration - * @{ - */ - -/** - * @brief Start the Independent Watchdog - * @note Except if the hardware watchdog option is selected - * @rmtoll KR KEY LL_IWDG_Enable - * @param IWDGx IWDG Instance - * @retval None - */ -__STATIC_INLINE void LL_IWDG_Enable(IWDG_TypeDef *IWDGx) -{ - WRITE_REG(IWDGx->KR, LL_IWDG_KEY_ENABLE); -} - -/** - * @brief Reloads IWDG counter with value defined in the reload register - * @rmtoll KR KEY LL_IWDG_ReloadCounter - * @param IWDGx IWDG Instance - * @retval None - */ -__STATIC_INLINE void LL_IWDG_ReloadCounter(IWDG_TypeDef *IWDGx) -{ - WRITE_REG(IWDGx->KR, LL_IWDG_KEY_RELOAD); -} - -/** - * @brief Enable write access to IWDG_PR, IWDG_RLR and IWDG_WINR registers - * @rmtoll KR KEY LL_IWDG_EnableWriteAccess - * @param IWDGx IWDG Instance - * @retval None - */ -__STATIC_INLINE void LL_IWDG_EnableWriteAccess(IWDG_TypeDef *IWDGx) -{ - WRITE_REG(IWDGx->KR, LL_IWDG_KEY_WR_ACCESS_ENABLE); -} - -/** - * @brief Disable write access to IWDG_PR, IWDG_RLR and IWDG_WINR registers - * @rmtoll KR KEY LL_IWDG_DisableWriteAccess - * @param IWDGx IWDG Instance - * @retval None - */ -__STATIC_INLINE void LL_IWDG_DisableWriteAccess(IWDG_TypeDef *IWDGx) -{ - WRITE_REG(IWDGx->KR, LL_IWDG_KEY_WR_ACCESS_DISABLE); -} - -/** - * @brief Select the prescaler of the IWDG - * @rmtoll PR PR LL_IWDG_SetPrescaler - * @param IWDGx IWDG Instance - * @param Prescaler This parameter can be one of the following values: - * @arg @ref LL_IWDG_PRESCALER_4 - * @arg @ref LL_IWDG_PRESCALER_8 - * @arg @ref LL_IWDG_PRESCALER_16 - * @arg @ref LL_IWDG_PRESCALER_32 - * @arg @ref LL_IWDG_PRESCALER_64 - * @arg @ref LL_IWDG_PRESCALER_128 - * @arg @ref LL_IWDG_PRESCALER_256 - * @retval None - */ -__STATIC_INLINE void LL_IWDG_SetPrescaler(IWDG_TypeDef *IWDGx, uint32_t Prescaler) -{ - WRITE_REG(IWDGx->PR, IWDG_PR_PR & Prescaler); -} - -/** - * @brief Get the selected prescaler of the IWDG - * @rmtoll PR PR LL_IWDG_GetPrescaler - * @param IWDGx IWDG Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_IWDG_PRESCALER_4 - * @arg @ref LL_IWDG_PRESCALER_8 - * @arg @ref LL_IWDG_PRESCALER_16 - * @arg @ref LL_IWDG_PRESCALER_32 - * @arg @ref LL_IWDG_PRESCALER_64 - * @arg @ref LL_IWDG_PRESCALER_128 - * @arg @ref LL_IWDG_PRESCALER_256 - */ -__STATIC_INLINE uint32_t LL_IWDG_GetPrescaler(IWDG_TypeDef *IWDGx) -{ - return (READ_REG(IWDGx->PR)); -} - -/** - * @brief Specify the IWDG down-counter reload value - * @rmtoll RLR RL LL_IWDG_SetReloadCounter - * @param IWDGx IWDG Instance - * @param Counter Value between Min_Data=0 and Max_Data=0x0FFF - * @retval None - */ -__STATIC_INLINE void LL_IWDG_SetReloadCounter(IWDG_TypeDef *IWDGx, uint32_t Counter) -{ - WRITE_REG(IWDGx->RLR, IWDG_RLR_RL & Counter); -} - -/** - * @brief Get the specified IWDG down-counter reload value - * @rmtoll RLR RL LL_IWDG_GetReloadCounter - * @param IWDGx IWDG Instance - * @retval Value between Min_Data=0 and Max_Data=0x0FFF - */ -__STATIC_INLINE uint32_t LL_IWDG_GetReloadCounter(IWDG_TypeDef *IWDGx) -{ - return (READ_REG(IWDGx->RLR)); -} - -/** - * @} - */ - -/** @defgroup IWDG_LL_EF_FLAG_Management FLAG_Management - * @{ - */ - -/** - * @brief Check if flag Prescaler Value Update is set or not - * @rmtoll SR PVU LL_IWDG_IsActiveFlag_PVU - * @param IWDGx IWDG Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_IWDG_IsActiveFlag_PVU(IWDG_TypeDef *IWDGx) -{ - return ((READ_BIT(IWDGx->SR, IWDG_SR_PVU) == (IWDG_SR_PVU)) ? 1UL : 0UL); -} - -/** - * @brief Check if flag Reload Value Update is set or not - * @rmtoll SR RVU LL_IWDG_IsActiveFlag_RVU - * @param IWDGx IWDG Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_IWDG_IsActiveFlag_RVU(IWDG_TypeDef *IWDGx) -{ - return ((READ_BIT(IWDGx->SR, IWDG_SR_RVU) == (IWDG_SR_RVU)) ? 1UL : 0UL); -} - -/** - * @brief Check if flags Prescaler & Reload Value Update are reset or not - * @rmtoll SR PVU LL_IWDG_IsReady\n - * SR RVU LL_IWDG_IsReady - * @param IWDGx IWDG Instance - * @retval State of bits (1 or 0). - */ -__STATIC_INLINE uint32_t LL_IWDG_IsReady(IWDG_TypeDef *IWDGx) -{ - return ((READ_BIT(IWDGx->SR, IWDG_SR_PVU | IWDG_SR_RVU) == 0U) ? 1UL : 0UL); -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* IWDG */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_LL_IWDG_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_lptim.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_lptim.h deleted file mode 100644 index a91bf92..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_lptim.h +++ /dev/null @@ -1,1381 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_lptim.h - * @author MCD Application Team - * @brief Header file of LPTIM LL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_LL_LPTIM_H -#define STM32F4xx_LL_LPTIM_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (LPTIM1) - -/** @defgroup LPTIM_LL LPTIM - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ - -/* Private constants ---------------------------------------------------------*/ - -/* Private macros ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup LPTIM_LL_Private_Macros LPTIM Private Macros - * @{ - */ -/** - * @} - */ -#endif /*USE_FULL_LL_DRIVER*/ - -/* Exported types ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup LPTIM_LL_ES_INIT LPTIM Exported Init structure - * @{ - */ - -/** - * @brief LPTIM Init structure definition - */ -typedef struct -{ - uint32_t ClockSource; /*!< Specifies the source of the clock used by the LPTIM instance. - This parameter can be a value of @ref LPTIM_LL_EC_CLK_SOURCE. - - This feature can be modified afterwards using unitary - function @ref LL_LPTIM_SetClockSource().*/ - - uint32_t Prescaler; /*!< Specifies the prescaler division ratio. - This parameter can be a value of @ref LPTIM_LL_EC_PRESCALER. - - This feature can be modified afterwards using using unitary - function @ref LL_LPTIM_SetPrescaler().*/ - - uint32_t Waveform; /*!< Specifies the waveform shape. - This parameter can be a value of @ref LPTIM_LL_EC_OUTPUT_WAVEFORM. - - This feature can be modified afterwards using unitary - function @ref LL_LPTIM_ConfigOutput().*/ - - uint32_t Polarity; /*!< Specifies waveform polarity. - This parameter can be a value of @ref LPTIM_LL_EC_OUTPUT_POLARITY. - - This feature can be modified afterwards using unitary - function @ref LL_LPTIM_ConfigOutput().*/ -} LL_LPTIM_InitTypeDef; - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup LPTIM_LL_Exported_Constants LPTIM Exported Constants - * @{ - */ - -/** @defgroup LPTIM_LL_EC_GET_FLAG Get Flags Defines - * @brief Flags defines which can be used with LL_LPTIM_ReadReg function - * @{ - */ -#define LL_LPTIM_ISR_CMPM LPTIM_ISR_CMPM /*!< Compare match */ -#define LL_LPTIM_ISR_CMPOK LPTIM_ISR_CMPOK /*!< Compare register update OK */ -#define LL_LPTIM_ISR_ARRM LPTIM_ISR_ARRM /*!< Autoreload match */ -#define LL_LPTIM_ISR_EXTTRIG LPTIM_ISR_EXTTRIG /*!< External trigger edge event */ -#define LL_LPTIM_ISR_ARROK LPTIM_ISR_ARROK /*!< Autoreload register update OK */ -#define LL_LPTIM_ISR_UP LPTIM_ISR_UP /*!< Counter direction change down to up */ -#define LL_LPTIM_ISR_DOWN LPTIM_ISR_DOWN /*!< Counter direction change up to down */ -/** - * @} - */ - -/** @defgroup LPTIM_LL_EC_IT IT Defines - * @brief IT defines which can be used with LL_LPTIM_ReadReg and LL_LPTIM_WriteReg functions - * @{ - */ -#define LL_LPTIM_IER_CMPMIE LPTIM_IER_CMPMIE /*!< Compare match */ -#define LL_LPTIM_IER_CMPOKIE LPTIM_IER_CMPOKIE /*!< Compare register update OK */ -#define LL_LPTIM_IER_ARRMIE LPTIM_IER_ARRMIE /*!< Autoreload match */ -#define LL_LPTIM_IER_EXTTRIGIE LPTIM_IER_EXTTRIGIE /*!< External trigger edge event */ -#define LL_LPTIM_IER_ARROKIE LPTIM_IER_ARROKIE /*!< Autoreload register update OK */ -#define LL_LPTIM_IER_UPIE LPTIM_IER_UPIE /*!< Counter direction change down to up */ -#define LL_LPTIM_IER_DOWNIE LPTIM_IER_DOWNIE /*!< Counter direction change up to down */ -/** - * @} - */ - -/** @defgroup LPTIM_LL_EC_OPERATING_MODE Operating Mode - * @{ - */ -#define LL_LPTIM_OPERATING_MODE_CONTINUOUS LPTIM_CR_CNTSTRT /*!__REG__, (__VALUE__)) - -/** - * @brief Read a value in LPTIM register - * @param __INSTANCE__ LPTIM Instance - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_LPTIM_ReadReg(__INSTANCE__, __REG__) READ_REG((__INSTANCE__)->__REG__) -/** - * @} - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup LPTIM_LL_Exported_Functions LPTIM Exported Functions - * @{ - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup LPTIM_LL_EF_Init Initialisation and deinitialisation functions - * @{ - */ - -ErrorStatus LL_LPTIM_DeInit(LPTIM_TypeDef *LPTIMx); -void LL_LPTIM_StructInit(LL_LPTIM_InitTypeDef *LPTIM_InitStruct); -ErrorStatus LL_LPTIM_Init(LPTIM_TypeDef *LPTIMx, LL_LPTIM_InitTypeDef *LPTIM_InitStruct); -void LL_LPTIM_Disable(LPTIM_TypeDef *LPTIMx); -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** @defgroup LPTIM_LL_EF_LPTIM_Configuration LPTIM Configuration - * @{ - */ - -/** - * @brief Enable the LPTIM instance - * @note After setting the ENABLE bit, a delay of two counter clock is needed - * before the LPTIM instance is actually enabled. - * @rmtoll CR ENABLE LL_LPTIM_Enable - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_Enable(LPTIM_TypeDef *LPTIMx) -{ - SET_BIT(LPTIMx->CR, LPTIM_CR_ENABLE); -} - -/** - * @brief Indicates whether the LPTIM instance is enabled. - * @rmtoll CR ENABLE LL_LPTIM_IsEnabled - * @param LPTIMx Low-Power Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_LPTIM_IsEnabled(LPTIM_TypeDef *LPTIMx) -{ - return (((READ_BIT(LPTIMx->CR, LPTIM_CR_ENABLE) == LPTIM_CR_ENABLE) ? 1UL : 0UL)); -} - -/** - * @brief Starts the LPTIM counter in the desired mode. - * @note LPTIM instance must be enabled before starting the counter. - * @note It is possible to change on the fly from One Shot mode to - * Continuous mode. - * @rmtoll CR CNTSTRT LL_LPTIM_StartCounter\n - * CR SNGSTRT LL_LPTIM_StartCounter - * @param LPTIMx Low-Power Timer instance - * @param OperatingMode This parameter can be one of the following values: - * @arg @ref LL_LPTIM_OPERATING_MODE_CONTINUOUS - * @arg @ref LL_LPTIM_OPERATING_MODE_ONESHOT - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_StartCounter(LPTIM_TypeDef *LPTIMx, uint32_t OperatingMode) -{ - MODIFY_REG(LPTIMx->CR, LPTIM_CR_CNTSTRT | LPTIM_CR_SNGSTRT, OperatingMode); -} - -/** - * @brief Set the LPTIM registers update mode (enable/disable register preload) - * @note This function must be called when the LPTIM instance is disabled. - * @rmtoll CFGR PRELOAD LL_LPTIM_SetUpdateMode - * @param LPTIMx Low-Power Timer instance - * @param UpdateMode This parameter can be one of the following values: - * @arg @ref LL_LPTIM_UPDATE_MODE_IMMEDIATE - * @arg @ref LL_LPTIM_UPDATE_MODE_ENDOFPERIOD - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_SetUpdateMode(LPTIM_TypeDef *LPTIMx, uint32_t UpdateMode) -{ - MODIFY_REG(LPTIMx->CFGR, LPTIM_CFGR_PRELOAD, UpdateMode); -} - -/** - * @brief Get the LPTIM registers update mode - * @rmtoll CFGR PRELOAD LL_LPTIM_GetUpdateMode - * @param LPTIMx Low-Power Timer instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_LPTIM_UPDATE_MODE_IMMEDIATE - * @arg @ref LL_LPTIM_UPDATE_MODE_ENDOFPERIOD - */ -__STATIC_INLINE uint32_t LL_LPTIM_GetUpdateMode(LPTIM_TypeDef *LPTIMx) -{ - return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_PRELOAD)); -} - -/** - * @brief Set the auto reload value - * @note The LPTIMx_ARR register content must only be modified when the LPTIM is enabled - * @note After a write to the LPTIMx_ARR register a new write operation to the - * same register can only be performed when the previous write operation - * is completed. Any successive write before the ARROK flag is set, will - * lead to unpredictable results. - * @note autoreload value be strictly greater than the compare value. - * @rmtoll ARR ARR LL_LPTIM_SetAutoReload - * @param LPTIMx Low-Power Timer instance - * @param AutoReload Value between Min_Data=0x00 and Max_Data=0xFFFF - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_SetAutoReload(LPTIM_TypeDef *LPTIMx, uint32_t AutoReload) -{ - MODIFY_REG(LPTIMx->ARR, LPTIM_ARR_ARR, AutoReload); -} - -/** - * @brief Get actual auto reload value - * @rmtoll ARR ARR LL_LPTIM_GetAutoReload - * @param LPTIMx Low-Power Timer instance - * @retval AutoReload Value between Min_Data=0x00 and Max_Data=0xFFFF - */ -__STATIC_INLINE uint32_t LL_LPTIM_GetAutoReload(LPTIM_TypeDef *LPTIMx) -{ - return (uint32_t)(READ_BIT(LPTIMx->ARR, LPTIM_ARR_ARR)); -} - -/** - * @brief Set the compare value - * @note After a write to the LPTIMx_CMP register a new write operation to the - * same register can only be performed when the previous write operation - * is completed. Any successive write before the CMPOK flag is set, will - * lead to unpredictable results. - * @rmtoll CMP CMP LL_LPTIM_SetCompare - * @param LPTIMx Low-Power Timer instance - * @param CompareValue Value between Min_Data=0x00 and Max_Data=0xFFFF - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_SetCompare(LPTIM_TypeDef *LPTIMx, uint32_t CompareValue) -{ - MODIFY_REG(LPTIMx->CMP, LPTIM_CMP_CMP, CompareValue); -} - -/** - * @brief Get actual compare value - * @rmtoll CMP CMP LL_LPTIM_GetCompare - * @param LPTIMx Low-Power Timer instance - * @retval CompareValue Value between Min_Data=0x00 and Max_Data=0xFFFF - */ -__STATIC_INLINE uint32_t LL_LPTIM_GetCompare(LPTIM_TypeDef *LPTIMx) -{ - return (uint32_t)(READ_BIT(LPTIMx->CMP, LPTIM_CMP_CMP)); -} - -/** - * @brief Get actual counter value - * @note When the LPTIM instance is running with an asynchronous clock, reading - * the LPTIMx_CNT register may return unreliable values. So in this case - * it is necessary to perform two consecutive read accesses and verify - * that the two returned values are identical. - * @rmtoll CNT CNT LL_LPTIM_GetCounter - * @param LPTIMx Low-Power Timer instance - * @retval Counter value - */ -__STATIC_INLINE uint32_t LL_LPTIM_GetCounter(LPTIM_TypeDef *LPTIMx) -{ - return (uint32_t)(READ_BIT(LPTIMx->CNT, LPTIM_CNT_CNT)); -} - -/** - * @brief Set the counter mode (selection of the LPTIM counter clock source). - * @note The counter mode can be set only when the LPTIM instance is disabled. - * @rmtoll CFGR COUNTMODE LL_LPTIM_SetCounterMode - * @param LPTIMx Low-Power Timer instance - * @param CounterMode This parameter can be one of the following values: - * @arg @ref LL_LPTIM_COUNTER_MODE_INTERNAL - * @arg @ref LL_LPTIM_COUNTER_MODE_EXTERNAL - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_SetCounterMode(LPTIM_TypeDef *LPTIMx, uint32_t CounterMode) -{ - MODIFY_REG(LPTIMx->CFGR, LPTIM_CFGR_COUNTMODE, CounterMode); -} - -/** - * @brief Get the counter mode - * @rmtoll CFGR COUNTMODE LL_LPTIM_GetCounterMode - * @param LPTIMx Low-Power Timer instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_LPTIM_COUNTER_MODE_INTERNAL - * @arg @ref LL_LPTIM_COUNTER_MODE_EXTERNAL - */ -__STATIC_INLINE uint32_t LL_LPTIM_GetCounterMode(LPTIM_TypeDef *LPTIMx) -{ - return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_COUNTMODE)); -} - -/** - * @brief Configure the LPTIM instance output (LPTIMx_OUT) - * @note This function must be called when the LPTIM instance is disabled. - * @note Regarding the LPTIM output polarity the change takes effect - * immediately, so the output default value will change immediately after - * the polarity is re-configured, even before the timer is enabled. - * @rmtoll CFGR WAVE LL_LPTIM_ConfigOutput\n - * CFGR WAVPOL LL_LPTIM_ConfigOutput - * @param LPTIMx Low-Power Timer instance - * @param Waveform This parameter can be one of the following values: - * @arg @ref LL_LPTIM_OUTPUT_WAVEFORM_PWM - * @arg @ref LL_LPTIM_OUTPUT_WAVEFORM_SETONCE - * @param Polarity This parameter can be one of the following values: - * @arg @ref LL_LPTIM_OUTPUT_POLARITY_REGULAR - * @arg @ref LL_LPTIM_OUTPUT_POLARITY_INVERSE - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_ConfigOutput(LPTIM_TypeDef *LPTIMx, uint32_t Waveform, uint32_t Polarity) -{ - MODIFY_REG(LPTIMx->CFGR, LPTIM_CFGR_WAVE | LPTIM_CFGR_WAVPOL, Waveform | Polarity); -} - -/** - * @brief Set waveform shape - * @rmtoll CFGR WAVE LL_LPTIM_SetWaveform - * @param LPTIMx Low-Power Timer instance - * @param Waveform This parameter can be one of the following values: - * @arg @ref LL_LPTIM_OUTPUT_WAVEFORM_PWM - * @arg @ref LL_LPTIM_OUTPUT_WAVEFORM_SETONCE - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_SetWaveform(LPTIM_TypeDef *LPTIMx, uint32_t Waveform) -{ - MODIFY_REG(LPTIMx->CFGR, LPTIM_CFGR_WAVE, Waveform); -} - -/** - * @brief Get actual waveform shape - * @rmtoll CFGR WAVE LL_LPTIM_GetWaveform - * @param LPTIMx Low-Power Timer instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_LPTIM_OUTPUT_WAVEFORM_PWM - * @arg @ref LL_LPTIM_OUTPUT_WAVEFORM_SETONCE - */ -__STATIC_INLINE uint32_t LL_LPTIM_GetWaveform(LPTIM_TypeDef *LPTIMx) -{ - return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_WAVE)); -} - -/** - * @brief Set output polarity - * @rmtoll CFGR WAVPOL LL_LPTIM_SetPolarity - * @param LPTIMx Low-Power Timer instance - * @param Polarity This parameter can be one of the following values: - * @arg @ref LL_LPTIM_OUTPUT_POLARITY_REGULAR - * @arg @ref LL_LPTIM_OUTPUT_POLARITY_INVERSE - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_SetPolarity(LPTIM_TypeDef *LPTIMx, uint32_t Polarity) -{ - MODIFY_REG(LPTIMx->CFGR, LPTIM_CFGR_WAVPOL, Polarity); -} - -/** - * @brief Get actual output polarity - * @rmtoll CFGR WAVPOL LL_LPTIM_GetPolarity - * @param LPTIMx Low-Power Timer instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_LPTIM_OUTPUT_POLARITY_REGULAR - * @arg @ref LL_LPTIM_OUTPUT_POLARITY_INVERSE - */ -__STATIC_INLINE uint32_t LL_LPTIM_GetPolarity(LPTIM_TypeDef *LPTIMx) -{ - return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_WAVPOL)); -} - -/** - * @brief Set actual prescaler division ratio. - * @note This function must be called when the LPTIM instance is disabled. - * @note When the LPTIM is configured to be clocked by an internal clock source - * and the LPTIM counter is configured to be updated by active edges - * detected on the LPTIM external Input1, the internal clock provided to - * the LPTIM must be not be prescaled. - * @rmtoll CFGR PRESC LL_LPTIM_SetPrescaler - * @param LPTIMx Low-Power Timer instance - * @param Prescaler This parameter can be one of the following values: - * @arg @ref LL_LPTIM_PRESCALER_DIV1 - * @arg @ref LL_LPTIM_PRESCALER_DIV2 - * @arg @ref LL_LPTIM_PRESCALER_DIV4 - * @arg @ref LL_LPTIM_PRESCALER_DIV8 - * @arg @ref LL_LPTIM_PRESCALER_DIV16 - * @arg @ref LL_LPTIM_PRESCALER_DIV32 - * @arg @ref LL_LPTIM_PRESCALER_DIV64 - * @arg @ref LL_LPTIM_PRESCALER_DIV128 - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_SetPrescaler(LPTIM_TypeDef *LPTIMx, uint32_t Prescaler) -{ - MODIFY_REG(LPTIMx->CFGR, LPTIM_CFGR_PRESC, Prescaler); -} - -/** - * @brief Get actual prescaler division ratio. - * @rmtoll CFGR PRESC LL_LPTIM_GetPrescaler - * @param LPTIMx Low-Power Timer instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_LPTIM_PRESCALER_DIV1 - * @arg @ref LL_LPTIM_PRESCALER_DIV2 - * @arg @ref LL_LPTIM_PRESCALER_DIV4 - * @arg @ref LL_LPTIM_PRESCALER_DIV8 - * @arg @ref LL_LPTIM_PRESCALER_DIV16 - * @arg @ref LL_LPTIM_PRESCALER_DIV32 - * @arg @ref LL_LPTIM_PRESCALER_DIV64 - * @arg @ref LL_LPTIM_PRESCALER_DIV128 - */ -__STATIC_INLINE uint32_t LL_LPTIM_GetPrescaler(LPTIM_TypeDef *LPTIMx) -{ - return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_PRESC)); -} - -/** - * @brief Set LPTIM input 1 source (default GPIO). - * @rmtoll OR OR LL_LPTIM_SetInput1Src - * @param LPTIMx Low-Power Timer instance - * @param Src This parameter can be one of the following values: - * @arg @ref LL_LPTIM_INPUT1_SRC_PAD_AF - * @arg @ref LL_LPTIM_INPUT1_SRC_PAD_PA4 - * @arg @ref LL_LPTIM_INPUT1_SRC_PAD_PB9 - * @arg @ref LL_LPTIM_INPUT1_SRC_TIM_DAC - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_SetInput1Src(LPTIM_TypeDef *LPTIMx, uint32_t Src) -{ - MODIFY_REG(LPTIMx->OR, LPTIM_OR_OR, Src); -} - -/** - * @} - */ - -/** @defgroup LPTIM_LL_EF_Trigger_Configuration Trigger Configuration - * @{ - */ - -/** - * @brief Enable the timeout function - * @note This function must be called when the LPTIM instance is disabled. - * @note The first trigger event will start the timer, any successive trigger - * event will reset the counter and the timer will restart. - * @note The timeout value corresponds to the compare value; if no trigger - * occurs within the expected time frame, the MCU is waked-up by the - * compare match event. - * @rmtoll CFGR TIMOUT LL_LPTIM_EnableTimeout - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_EnableTimeout(LPTIM_TypeDef *LPTIMx) -{ - SET_BIT(LPTIMx->CFGR, LPTIM_CFGR_TIMOUT); -} - -/** - * @brief Disable the timeout function - * @note This function must be called when the LPTIM instance is disabled. - * @note A trigger event arriving when the timer is already started will be - * ignored. - * @rmtoll CFGR TIMOUT LL_LPTIM_DisableTimeout - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_DisableTimeout(LPTIM_TypeDef *LPTIMx) -{ - CLEAR_BIT(LPTIMx->CFGR, LPTIM_CFGR_TIMOUT); -} - -/** - * @brief Indicate whether the timeout function is enabled. - * @rmtoll CFGR TIMOUT LL_LPTIM_IsEnabledTimeout - * @param LPTIMx Low-Power Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_LPTIM_IsEnabledTimeout(LPTIM_TypeDef *LPTIMx) -{ - return (((READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_TIMOUT) == LPTIM_CFGR_TIMOUT) ? 1UL : 0UL)); -} - -/** - * @brief Start the LPTIM counter - * @note This function must be called when the LPTIM instance is disabled. - * @rmtoll CFGR TRIGEN LL_LPTIM_TrigSw - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_TrigSw(LPTIM_TypeDef *LPTIMx) -{ - CLEAR_BIT(LPTIMx->CFGR, LPTIM_CFGR_TRIGEN); -} - -/** - * @brief Configure the external trigger used as a trigger event for the LPTIM. - * @note This function must be called when the LPTIM instance is disabled. - * @note An internal clock source must be present when a digital filter is - * required for the trigger. - * @rmtoll CFGR TRIGSEL LL_LPTIM_ConfigTrigger\n - * CFGR TRGFLT LL_LPTIM_ConfigTrigger\n - * CFGR TRIGEN LL_LPTIM_ConfigTrigger - * @param LPTIMx Low-Power Timer instance - * @param Source This parameter can be one of the following values: - * @arg @ref LL_LPTIM_TRIG_SOURCE_GPIO - * @arg @ref LL_LPTIM_TRIG_SOURCE_RTCALARMA - * @arg @ref LL_LPTIM_TRIG_SOURCE_RTCALARMB - * @arg @ref LL_LPTIM_TRIG_SOURCE_RTCTAMP1 - * @arg @ref LL_LPTIM_TRIG_SOURCE_TIM1_TRGO - * @arg @ref LL_LPTIM_TRIG_SOURCE_TIM5_TRGO - * @param Filter This parameter can be one of the following values: - * @arg @ref LL_LPTIM_TRIG_FILTER_NONE - * @arg @ref LL_LPTIM_TRIG_FILTER_2 - * @arg @ref LL_LPTIM_TRIG_FILTER_4 - * @arg @ref LL_LPTIM_TRIG_FILTER_8 - * @param Polarity This parameter can be one of the following values: - * @arg @ref LL_LPTIM_TRIG_POLARITY_RISING - * @arg @ref LL_LPTIM_TRIG_POLARITY_FALLING - * @arg @ref LL_LPTIM_TRIG_POLARITY_RISING_FALLING - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_ConfigTrigger(LPTIM_TypeDef *LPTIMx, uint32_t Source, uint32_t Filter, uint32_t Polarity) -{ - MODIFY_REG(LPTIMx->CFGR, LPTIM_CFGR_TRIGSEL | LPTIM_CFGR_TRGFLT | LPTIM_CFGR_TRIGEN, Source | Filter | Polarity); -} - -/** - * @brief Get actual external trigger source. - * @rmtoll CFGR TRIGSEL LL_LPTIM_GetTriggerSource - * @param LPTIMx Low-Power Timer instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_LPTIM_TRIG_SOURCE_GPIO - * @arg @ref LL_LPTIM_TRIG_SOURCE_RTCALARMA - * @arg @ref LL_LPTIM_TRIG_SOURCE_RTCALARMB - * @arg @ref LL_LPTIM_TRIG_SOURCE_RTCTAMP1 - * @arg @ref LL_LPTIM_TRIG_SOURCE_TIM1_TRGO - * @arg @ref LL_LPTIM_TRIG_SOURCE_TIM5_TRGO - */ -__STATIC_INLINE uint32_t LL_LPTIM_GetTriggerSource(LPTIM_TypeDef *LPTIMx) -{ - return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_TRIGSEL)); -} - -/** - * @brief Get actual external trigger filter. - * @rmtoll CFGR TRGFLT LL_LPTIM_GetTriggerFilter - * @param LPTIMx Low-Power Timer instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_LPTIM_TRIG_FILTER_NONE - * @arg @ref LL_LPTIM_TRIG_FILTER_2 - * @arg @ref LL_LPTIM_TRIG_FILTER_4 - * @arg @ref LL_LPTIM_TRIG_FILTER_8 - */ -__STATIC_INLINE uint32_t LL_LPTIM_GetTriggerFilter(LPTIM_TypeDef *LPTIMx) -{ - return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_TRGFLT)); -} - -/** - * @brief Get actual external trigger polarity. - * @rmtoll CFGR TRIGEN LL_LPTIM_GetTriggerPolarity - * @param LPTIMx Low-Power Timer instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_LPTIM_TRIG_POLARITY_RISING - * @arg @ref LL_LPTIM_TRIG_POLARITY_FALLING - * @arg @ref LL_LPTIM_TRIG_POLARITY_RISING_FALLING - */ -__STATIC_INLINE uint32_t LL_LPTIM_GetTriggerPolarity(LPTIM_TypeDef *LPTIMx) -{ - return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_TRIGEN)); -} - -/** - * @} - */ - -/** @defgroup LPTIM_LL_EF_Clock_Configuration Clock Configuration - * @{ - */ - -/** - * @brief Set the source of the clock used by the LPTIM instance. - * @note This function must be called when the LPTIM instance is disabled. - * @rmtoll CFGR CKSEL LL_LPTIM_SetClockSource - * @param LPTIMx Low-Power Timer instance - * @param ClockSource This parameter can be one of the following values: - * @arg @ref LL_LPTIM_CLK_SOURCE_INTERNAL - * @arg @ref LL_LPTIM_CLK_SOURCE_EXTERNAL - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_SetClockSource(LPTIM_TypeDef *LPTIMx, uint32_t ClockSource) -{ - MODIFY_REG(LPTIMx->CFGR, LPTIM_CFGR_CKSEL, ClockSource); -} - -/** - * @brief Get actual LPTIM instance clock source. - * @rmtoll CFGR CKSEL LL_LPTIM_GetClockSource - * @param LPTIMx Low-Power Timer instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_LPTIM_CLK_SOURCE_INTERNAL - * @arg @ref LL_LPTIM_CLK_SOURCE_EXTERNAL - */ -__STATIC_INLINE uint32_t LL_LPTIM_GetClockSource(LPTIM_TypeDef *LPTIMx) -{ - return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_CKSEL)); -} - -/** - * @brief Configure the active edge or edges used by the counter when - the LPTIM is clocked by an external clock source. - * @note This function must be called when the LPTIM instance is disabled. - * @note When both external clock signal edges are considered active ones, - * the LPTIM must also be clocked by an internal clock source with a - * frequency equal to at least four times the external clock frequency. - * @note An internal clock source must be present when a digital filter is - * required for external clock. - * @rmtoll CFGR CKFLT LL_LPTIM_ConfigClock\n - * CFGR CKPOL LL_LPTIM_ConfigClock - * @param LPTIMx Low-Power Timer instance - * @param ClockFilter This parameter can be one of the following values: - * @arg @ref LL_LPTIM_CLK_FILTER_NONE - * @arg @ref LL_LPTIM_CLK_FILTER_2 - * @arg @ref LL_LPTIM_CLK_FILTER_4 - * @arg @ref LL_LPTIM_CLK_FILTER_8 - * @param ClockPolarity This parameter can be one of the following values: - * @arg @ref LL_LPTIM_CLK_POLARITY_RISING - * @arg @ref LL_LPTIM_CLK_POLARITY_FALLING - * @arg @ref LL_LPTIM_CLK_POLARITY_RISING_FALLING - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_ConfigClock(LPTIM_TypeDef *LPTIMx, uint32_t ClockFilter, uint32_t ClockPolarity) -{ - MODIFY_REG(LPTIMx->CFGR, LPTIM_CFGR_CKFLT | LPTIM_CFGR_CKPOL, ClockFilter | ClockPolarity); -} - -/** - * @brief Get actual clock polarity - * @rmtoll CFGR CKPOL LL_LPTIM_GetClockPolarity - * @param LPTIMx Low-Power Timer instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_LPTIM_CLK_POLARITY_RISING - * @arg @ref LL_LPTIM_CLK_POLARITY_FALLING - * @arg @ref LL_LPTIM_CLK_POLARITY_RISING_FALLING - */ -__STATIC_INLINE uint32_t LL_LPTIM_GetClockPolarity(LPTIM_TypeDef *LPTIMx) -{ - return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_CKPOL)); -} - -/** - * @brief Get actual clock digital filter - * @rmtoll CFGR CKFLT LL_LPTIM_GetClockFilter - * @param LPTIMx Low-Power Timer instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_LPTIM_CLK_FILTER_NONE - * @arg @ref LL_LPTIM_CLK_FILTER_2 - * @arg @ref LL_LPTIM_CLK_FILTER_4 - * @arg @ref LL_LPTIM_CLK_FILTER_8 - */ -__STATIC_INLINE uint32_t LL_LPTIM_GetClockFilter(LPTIM_TypeDef *LPTIMx) -{ - return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_CKFLT)); -} - -/** - * @} - */ - -/** @defgroup LPTIM_LL_EF_Encoder_Mode Encoder Mode - * @{ - */ - -/** - * @brief Configure the encoder mode. - * @note This function must be called when the LPTIM instance is disabled. - * @rmtoll CFGR CKPOL LL_LPTIM_SetEncoderMode - * @param LPTIMx Low-Power Timer instance - * @param EncoderMode This parameter can be one of the following values: - * @arg @ref LL_LPTIM_ENCODER_MODE_RISING - * @arg @ref LL_LPTIM_ENCODER_MODE_FALLING - * @arg @ref LL_LPTIM_ENCODER_MODE_RISING_FALLING - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_SetEncoderMode(LPTIM_TypeDef *LPTIMx, uint32_t EncoderMode) -{ - MODIFY_REG(LPTIMx->CFGR, LPTIM_CFGR_CKPOL, EncoderMode); -} - -/** - * @brief Get actual encoder mode. - * @rmtoll CFGR CKPOL LL_LPTIM_GetEncoderMode - * @param LPTIMx Low-Power Timer instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_LPTIM_ENCODER_MODE_RISING - * @arg @ref LL_LPTIM_ENCODER_MODE_FALLING - * @arg @ref LL_LPTIM_ENCODER_MODE_RISING_FALLING - */ -__STATIC_INLINE uint32_t LL_LPTIM_GetEncoderMode(LPTIM_TypeDef *LPTIMx) -{ - return (uint32_t)(READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_CKPOL)); -} - -/** - * @brief Enable the encoder mode - * @note This function must be called when the LPTIM instance is disabled. - * @note In this mode the LPTIM instance must be clocked by an internal clock - * source. Also, the prescaler division ratio must be equal to 1. - * @note LPTIM instance must be configured in continuous mode prior enabling - * the encoder mode. - * @rmtoll CFGR ENC LL_LPTIM_EnableEncoderMode - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_EnableEncoderMode(LPTIM_TypeDef *LPTIMx) -{ - SET_BIT(LPTIMx->CFGR, LPTIM_CFGR_ENC); -} - -/** - * @brief Disable the encoder mode - * @note This function must be called when the LPTIM instance is disabled. - * @rmtoll CFGR ENC LL_LPTIM_DisableEncoderMode - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_DisableEncoderMode(LPTIM_TypeDef *LPTIMx) -{ - CLEAR_BIT(LPTIMx->CFGR, LPTIM_CFGR_ENC); -} - -/** - * @brief Indicates whether the LPTIM operates in encoder mode. - * @rmtoll CFGR ENC LL_LPTIM_IsEnabledEncoderMode - * @param LPTIMx Low-Power Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_LPTIM_IsEnabledEncoderMode(LPTIM_TypeDef *LPTIMx) -{ - return (((READ_BIT(LPTIMx->CFGR, LPTIM_CFGR_ENC) == LPTIM_CFGR_ENC) ? 1UL : 0UL)); -} - -/** - * @} - */ - -/** @defgroup LPTIM_LL_EF_FLAG_Management FLAG Management - * @{ - */ - -/** - * @brief Clear the compare match flag (CMPMCF) - * @rmtoll ICR CMPMCF LL_LPTIM_ClearFLAG_CMPM - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_ClearFLAG_CMPM(LPTIM_TypeDef *LPTIMx) -{ - SET_BIT(LPTIMx->ICR, LPTIM_ICR_CMPMCF); -} - -/** - * @brief Inform application whether a compare match interrupt has occurred. - * @rmtoll ISR CMPM LL_LPTIM_IsActiveFlag_CMPM - * @param LPTIMx Low-Power Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_LPTIM_IsActiveFlag_CMPM(LPTIM_TypeDef *LPTIMx) -{ - return (((READ_BIT(LPTIMx->ISR, LPTIM_ISR_CMPM) == LPTIM_ISR_CMPM) ? 1UL : 0UL)); -} - -/** - * @brief Clear the autoreload match flag (ARRMCF) - * @rmtoll ICR ARRMCF LL_LPTIM_ClearFLAG_ARRM - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_ClearFLAG_ARRM(LPTIM_TypeDef *LPTIMx) -{ - SET_BIT(LPTIMx->ICR, LPTIM_ICR_ARRMCF); -} - -/** - * @brief Inform application whether a autoreload match interrupt has occurred. - * @rmtoll ISR ARRM LL_LPTIM_IsActiveFlag_ARRM - * @param LPTIMx Low-Power Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_LPTIM_IsActiveFlag_ARRM(LPTIM_TypeDef *LPTIMx) -{ - return (((READ_BIT(LPTIMx->ISR, LPTIM_ISR_ARRM) == LPTIM_ISR_ARRM) ? 1UL : 0UL)); -} - -/** - * @brief Clear the external trigger valid edge flag(EXTTRIGCF). - * @rmtoll ICR EXTTRIGCF LL_LPTIM_ClearFlag_EXTTRIG - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_ClearFlag_EXTTRIG(LPTIM_TypeDef *LPTIMx) -{ - SET_BIT(LPTIMx->ICR, LPTIM_ICR_EXTTRIGCF); -} - -/** - * @brief Inform application whether a valid edge on the selected external trigger input has occurred. - * @rmtoll ISR EXTTRIG LL_LPTIM_IsActiveFlag_EXTTRIG - * @param LPTIMx Low-Power Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_LPTIM_IsActiveFlag_EXTTRIG(LPTIM_TypeDef *LPTIMx) -{ - return (((READ_BIT(LPTIMx->ISR, LPTIM_ISR_EXTTRIG) == LPTIM_ISR_EXTTRIG) ? 1UL : 0UL)); -} - -/** - * @brief Clear the compare register update interrupt flag (CMPOKCF). - * @rmtoll ICR CMPOKCF LL_LPTIM_ClearFlag_CMPOK - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_ClearFlag_CMPOK(LPTIM_TypeDef *LPTIMx) -{ - SET_BIT(LPTIMx->ICR, LPTIM_ICR_CMPOKCF); -} - -/** - * @brief Informs application whether the APB bus write operation to the LPTIMx_CMP register has been successfully - completed. If so, a new one can be initiated. - * @rmtoll ISR CMPOK LL_LPTIM_IsActiveFlag_CMPOK - * @param LPTIMx Low-Power Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_LPTIM_IsActiveFlag_CMPOK(LPTIM_TypeDef *LPTIMx) -{ - return (((READ_BIT(LPTIMx->ISR, LPTIM_ISR_CMPOK) == LPTIM_ISR_CMPOK) ? 1UL : 0UL)); -} - -/** - * @brief Clear the autoreload register update interrupt flag (ARROKCF). - * @rmtoll ICR ARROKCF LL_LPTIM_ClearFlag_ARROK - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_ClearFlag_ARROK(LPTIM_TypeDef *LPTIMx) -{ - SET_BIT(LPTIMx->ICR, LPTIM_ICR_ARROKCF); -} - -/** - * @brief Informs application whether the APB bus write operation to the LPTIMx_ARR register has been successfully - completed. If so, a new one can be initiated. - * @rmtoll ISR ARROK LL_LPTIM_IsActiveFlag_ARROK - * @param LPTIMx Low-Power Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_LPTIM_IsActiveFlag_ARROK(LPTIM_TypeDef *LPTIMx) -{ - return (((READ_BIT(LPTIMx->ISR, LPTIM_ISR_ARROK) == LPTIM_ISR_ARROK) ? 1UL : 0UL)); -} - -/** - * @brief Clear the counter direction change to up interrupt flag (UPCF). - * @rmtoll ICR UPCF LL_LPTIM_ClearFlag_UP - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_ClearFlag_UP(LPTIM_TypeDef *LPTIMx) -{ - SET_BIT(LPTIMx->ICR, LPTIM_ICR_UPCF); -} - -/** - * @brief Informs the application whether the counter direction has changed from down to up (when the LPTIM instance - operates in encoder mode). - * @rmtoll ISR UP LL_LPTIM_IsActiveFlag_UP - * @param LPTIMx Low-Power Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_LPTIM_IsActiveFlag_UP(LPTIM_TypeDef *LPTIMx) -{ - return (((READ_BIT(LPTIMx->ISR, LPTIM_ISR_UP) == LPTIM_ISR_UP) ? 1UL : 0UL)); -} - -/** - * @brief Clear the counter direction change to down interrupt flag (DOWNCF). - * @rmtoll ICR DOWNCF LL_LPTIM_ClearFlag_DOWN - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_ClearFlag_DOWN(LPTIM_TypeDef *LPTIMx) -{ - SET_BIT(LPTIMx->ICR, LPTIM_ICR_DOWNCF); -} - -/** - * @brief Informs the application whether the counter direction has changed from up to down (when the LPTIM instance - operates in encoder mode). - * @rmtoll ISR DOWN LL_LPTIM_IsActiveFlag_DOWN - * @param LPTIMx Low-Power Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_LPTIM_IsActiveFlag_DOWN(LPTIM_TypeDef *LPTIMx) -{ - return (((READ_BIT(LPTIMx->ISR, LPTIM_ISR_DOWN) == LPTIM_ISR_DOWN) ? 1UL : 0UL)); -} - -/** - * @} - */ - -/** @defgroup LPTIM_LL_EF_IT_Management Interrupt Management - * @{ - */ - -/** - * @brief Enable compare match interrupt (CMPMIE). - * @rmtoll IER CMPMIE LL_LPTIM_EnableIT_CMPM - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_EnableIT_CMPM(LPTIM_TypeDef *LPTIMx) -{ - SET_BIT(LPTIMx->IER, LPTIM_IER_CMPMIE); -} - -/** - * @brief Disable compare match interrupt (CMPMIE). - * @rmtoll IER CMPMIE LL_LPTIM_DisableIT_CMPM - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_DisableIT_CMPM(LPTIM_TypeDef *LPTIMx) -{ - CLEAR_BIT(LPTIMx->IER, LPTIM_IER_CMPMIE); -} - -/** - * @brief Indicates whether the compare match interrupt (CMPMIE) is enabled. - * @rmtoll IER CMPMIE LL_LPTIM_IsEnabledIT_CMPM - * @param LPTIMx Low-Power Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_LPTIM_IsEnabledIT_CMPM(LPTIM_TypeDef *LPTIMx) -{ - return (((READ_BIT(LPTIMx->IER, LPTIM_IER_CMPMIE) == LPTIM_IER_CMPMIE) ? 1UL : 0UL)); -} - -/** - * @brief Enable autoreload match interrupt (ARRMIE). - * @rmtoll IER ARRMIE LL_LPTIM_EnableIT_ARRM - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_EnableIT_ARRM(LPTIM_TypeDef *LPTIMx) -{ - SET_BIT(LPTIMx->IER, LPTIM_IER_ARRMIE); -} - -/** - * @brief Disable autoreload match interrupt (ARRMIE). - * @rmtoll IER ARRMIE LL_LPTIM_DisableIT_ARRM - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_DisableIT_ARRM(LPTIM_TypeDef *LPTIMx) -{ - CLEAR_BIT(LPTIMx->IER, LPTIM_IER_ARRMIE); -} - -/** - * @brief Indicates whether the autoreload match interrupt (ARRMIE) is enabled. - * @rmtoll IER ARRMIE LL_LPTIM_IsEnabledIT_ARRM - * @param LPTIMx Low-Power Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_LPTIM_IsEnabledIT_ARRM(LPTIM_TypeDef *LPTIMx) -{ - return (((READ_BIT(LPTIMx->IER, LPTIM_IER_ARRMIE) == LPTIM_IER_ARRMIE) ? 1UL : 0UL)); -} - -/** - * @brief Enable external trigger valid edge interrupt (EXTTRIGIE). - * @rmtoll IER EXTTRIGIE LL_LPTIM_EnableIT_EXTTRIG - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_EnableIT_EXTTRIG(LPTIM_TypeDef *LPTIMx) -{ - SET_BIT(LPTIMx->IER, LPTIM_IER_EXTTRIGIE); -} - -/** - * @brief Disable external trigger valid edge interrupt (EXTTRIGIE). - * @rmtoll IER EXTTRIGIE LL_LPTIM_DisableIT_EXTTRIG - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_DisableIT_EXTTRIG(LPTIM_TypeDef *LPTIMx) -{ - CLEAR_BIT(LPTIMx->IER, LPTIM_IER_EXTTRIGIE); -} - -/** - * @brief Indicates external trigger valid edge interrupt (EXTTRIGIE) is enabled. - * @rmtoll IER EXTTRIGIE LL_LPTIM_IsEnabledIT_EXTTRIG - * @param LPTIMx Low-Power Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_LPTIM_IsEnabledIT_EXTTRIG(LPTIM_TypeDef *LPTIMx) -{ - return (((READ_BIT(LPTIMx->IER, LPTIM_IER_EXTTRIGIE) == LPTIM_IER_EXTTRIGIE) ? 1UL : 0UL)); -} - -/** - * @brief Enable compare register write completed interrupt (CMPOKIE). - * @rmtoll IER CMPOKIE LL_LPTIM_EnableIT_CMPOK - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_EnableIT_CMPOK(LPTIM_TypeDef *LPTIMx) -{ - SET_BIT(LPTIMx->IER, LPTIM_IER_CMPOKIE); -} - -/** - * @brief Disable compare register write completed interrupt (CMPOKIE). - * @rmtoll IER CMPOKIE LL_LPTIM_DisableIT_CMPOK - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_DisableIT_CMPOK(LPTIM_TypeDef *LPTIMx) -{ - CLEAR_BIT(LPTIMx->IER, LPTIM_IER_CMPOKIE); -} - -/** - * @brief Indicates whether the compare register write completed interrupt (CMPOKIE) is enabled. - * @rmtoll IER CMPOKIE LL_LPTIM_IsEnabledIT_CMPOK - * @param LPTIMx Low-Power Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_LPTIM_IsEnabledIT_CMPOK(LPTIM_TypeDef *LPTIMx) -{ - return (((READ_BIT(LPTIMx->IER, LPTIM_IER_CMPOKIE) == LPTIM_IER_CMPOKIE) ? 1UL : 0UL)); -} - -/** - * @brief Enable autoreload register write completed interrupt (ARROKIE). - * @rmtoll IER ARROKIE LL_LPTIM_EnableIT_ARROK - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_EnableIT_ARROK(LPTIM_TypeDef *LPTIMx) -{ - SET_BIT(LPTIMx->IER, LPTIM_IER_ARROKIE); -} - -/** - * @brief Disable autoreload register write completed interrupt (ARROKIE). - * @rmtoll IER ARROKIE LL_LPTIM_DisableIT_ARROK - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_DisableIT_ARROK(LPTIM_TypeDef *LPTIMx) -{ - CLEAR_BIT(LPTIMx->IER, LPTIM_IER_ARROKIE); -} - -/** - * @brief Indicates whether the autoreload register write completed interrupt (ARROKIE) is enabled. - * @rmtoll IER ARROKIE LL_LPTIM_IsEnabledIT_ARROK - * @param LPTIMx Low-Power Timer instance - * @retval State of bit(1 or 0). - */ -__STATIC_INLINE uint32_t LL_LPTIM_IsEnabledIT_ARROK(LPTIM_TypeDef *LPTIMx) -{ - return (((READ_BIT(LPTIMx->IER, LPTIM_IER_ARROKIE) == LPTIM_IER_ARROKIE) ? 1UL : 0UL)); -} - -/** - * @brief Enable direction change to up interrupt (UPIE). - * @rmtoll IER UPIE LL_LPTIM_EnableIT_UP - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_EnableIT_UP(LPTIM_TypeDef *LPTIMx) -{ - SET_BIT(LPTIMx->IER, LPTIM_IER_UPIE); -} - -/** - * @brief Disable direction change to up interrupt (UPIE). - * @rmtoll IER UPIE LL_LPTIM_DisableIT_UP - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_DisableIT_UP(LPTIM_TypeDef *LPTIMx) -{ - CLEAR_BIT(LPTIMx->IER, LPTIM_IER_UPIE); -} - -/** - * @brief Indicates whether the direction change to up interrupt (UPIE) is enabled. - * @rmtoll IER UPIE LL_LPTIM_IsEnabledIT_UP - * @param LPTIMx Low-Power Timer instance - * @retval State of bit(1 or 0). - */ -__STATIC_INLINE uint32_t LL_LPTIM_IsEnabledIT_UP(LPTIM_TypeDef *LPTIMx) -{ - return (((READ_BIT(LPTIMx->IER, LPTIM_IER_UPIE) == LPTIM_IER_UPIE) ? 1UL : 0UL)); -} - -/** - * @brief Enable direction change to down interrupt (DOWNIE). - * @rmtoll IER DOWNIE LL_LPTIM_EnableIT_DOWN - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_EnableIT_DOWN(LPTIM_TypeDef *LPTIMx) -{ - SET_BIT(LPTIMx->IER, LPTIM_IER_DOWNIE); -} - -/** - * @brief Disable direction change to down interrupt (DOWNIE). - * @rmtoll IER DOWNIE LL_LPTIM_DisableIT_DOWN - * @param LPTIMx Low-Power Timer instance - * @retval None - */ -__STATIC_INLINE void LL_LPTIM_DisableIT_DOWN(LPTIM_TypeDef *LPTIMx) -{ - CLEAR_BIT(LPTIMx->IER, LPTIM_IER_DOWNIE); -} - -/** - * @brief Indicates whether the direction change to down interrupt (DOWNIE) is enabled. - * @rmtoll IER DOWNIE LL_LPTIM_IsEnabledIT_DOWN - * @param LPTIMx Low-Power Timer instance - * @retval State of bit(1 or 0). - */ -__STATIC_INLINE uint32_t LL_LPTIM_IsEnabledIT_DOWN(LPTIM_TypeDef *LPTIMx) -{ - return ((READ_BIT(LPTIMx->IER, LPTIM_IER_DOWNIE) == LPTIM_IER_DOWNIE) ? 1UL : 0UL); -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* LPTIM1 */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_LL_LPTIM_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_pwr.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_pwr.h deleted file mode 100644 index 03b8706..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_pwr.h +++ /dev/null @@ -1,989 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_pwr.h - * @author MCD Application Team - * @brief Header file of PWR LL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_LL_PWR_H -#define __STM32F4xx_LL_PWR_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined(PWR) - -/** @defgroup PWR_LL PWR - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/** @defgroup PWR_LL_Exported_Constants PWR Exported Constants - * @{ - */ - -/** @defgroup PWR_LL_EC_CLEAR_FLAG Clear Flags Defines - * @brief Flags defines which can be used with LL_PWR_WriteReg function - * @{ - */ -#define LL_PWR_CR_CSBF PWR_CR_CSBF /*!< Clear standby flag */ -#define LL_PWR_CR_CWUF PWR_CR_CWUF /*!< Clear wakeup flag */ -/** - * @} - */ - -/** @defgroup PWR_LL_EC_GET_FLAG Get Flags Defines - * @brief Flags defines which can be used with LL_PWR_ReadReg function - * @{ - */ -#define LL_PWR_CSR_WUF PWR_CSR_WUF /*!< Wakeup flag */ -#define LL_PWR_CSR_SBF PWR_CSR_SBF /*!< Standby flag */ -#define LL_PWR_CSR_PVDO PWR_CSR_PVDO /*!< Power voltage detector output flag */ -#define LL_PWR_CSR_VOS PWR_CSR_VOSRDY /*!< Voltage scaling select flag */ -#if defined(PWR_CSR_EWUP) -#define LL_PWR_CSR_EWUP1 PWR_CSR_EWUP /*!< Enable WKUP pin */ -#elif defined(PWR_CSR_EWUP1) -#define LL_PWR_CSR_EWUP1 PWR_CSR_EWUP1 /*!< Enable WKUP pin 1 */ -#endif /* PWR_CSR_EWUP */ -#if defined(PWR_CSR_EWUP2) -#define LL_PWR_CSR_EWUP2 PWR_CSR_EWUP2 /*!< Enable WKUP pin 2 */ -#endif /* PWR_CSR_EWUP2 */ -#if defined(PWR_CSR_EWUP3) -#define LL_PWR_CSR_EWUP3 PWR_CSR_EWUP3 /*!< Enable WKUP pin 3 */ -#endif /* PWR_CSR_EWUP3 */ -/** - * @} - */ - -/** @defgroup PWR_LL_EC_REGU_VOLTAGE Regulator Voltage - * @{ - */ -#if defined(PWR_CR_VOS_0) -#define LL_PWR_REGU_VOLTAGE_SCALE3 (PWR_CR_VOS_0) -#define LL_PWR_REGU_VOLTAGE_SCALE2 (PWR_CR_VOS_1) -#define LL_PWR_REGU_VOLTAGE_SCALE1 (PWR_CR_VOS_0 | PWR_CR_VOS_1) /* The SCALE1 is not available for STM32F401xx devices */ -#else -#define LL_PWR_REGU_VOLTAGE_SCALE1 (PWR_CR_VOS) -#define LL_PWR_REGU_VOLTAGE_SCALE2 0x00000000U -#endif /* PWR_CR_VOS_0 */ -/** - * @} - */ - -/** @defgroup PWR_LL_EC_MODE_PWR Mode Power - * @{ - */ -#define LL_PWR_MODE_STOP_MAINREGU 0x00000000U /*!< Enter Stop mode when the CPU enters deepsleep */ -#define LL_PWR_MODE_STOP_LPREGU (PWR_CR_LPDS) /*!< Enter Stop mode (with low power Regulator ON) when the CPU enters deepsleep */ -#if defined(PWR_CR_MRUDS) && defined(PWR_CR_LPUDS) && defined(PWR_CR_FPDS) -#define LL_PWR_MODE_STOP_MAINREGU_UNDERDRIVE (PWR_CR_MRUDS | PWR_CR_FPDS) /*!< Enter Stop mode (with main Regulator in under-drive mode) when the CPU enters deepsleep */ -#define LL_PWR_MODE_STOP_LPREGU_UNDERDRIVE (PWR_CR_LPDS | PWR_CR_LPUDS | PWR_CR_FPDS) /*!< Enter Stop mode (with low power Regulator in under-drive mode) when the CPU enters deepsleep */ -#endif /* PWR_CR_MRUDS && PWR_CR_LPUDS && PWR_CR_FPDS */ -#if defined(PWR_CR_MRLVDS) && defined(PWR_CR_LPLVDS) && defined(PWR_CR_FPDS) -#define LL_PWR_MODE_STOP_MAINREGU_DEEPSLEEP (PWR_CR_MRLVDS | PWR_CR_FPDS) /*!< Enter Stop mode (with main Regulator in Deep Sleep mode) when the CPU enters deepsleep */ -#define LL_PWR_MODE_STOP_LPREGU_DEEPSLEEP (PWR_CR_LPDS | PWR_CR_LPLVDS | PWR_CR_FPDS) /*!< Enter Stop mode (with low power Regulator in Deep Sleep mode) when the CPU enters deepsleep */ -#endif /* PWR_CR_MRLVDS && PWR_CR_LPLVDS && PWR_CR_FPDS */ -#define LL_PWR_MODE_STANDBY (PWR_CR_PDDS) /*!< Enter Standby mode when the CPU enters deepsleep */ -/** - * @} - */ - -/** @defgroup PWR_LL_EC_REGU_MODE_DS_MODE Regulator Mode In Deep Sleep Mode - * @{ - */ -#define LL_PWR_REGU_DSMODE_MAIN 0x00000000U /*!< Voltage Regulator in main mode during deepsleep mode */ -#define LL_PWR_REGU_DSMODE_LOW_POWER (PWR_CR_LPDS) /*!< Voltage Regulator in low-power mode during deepsleep mode */ -/** - * @} - */ - -/** @defgroup PWR_LL_EC_PVDLEVEL Power Voltage Detector Level - * @{ - */ -#define LL_PWR_PVDLEVEL_0 (PWR_CR_PLS_LEV0) /*!< Voltage threshold detected by PVD 2.2 V */ -#define LL_PWR_PVDLEVEL_1 (PWR_CR_PLS_LEV1) /*!< Voltage threshold detected by PVD 2.3 V */ -#define LL_PWR_PVDLEVEL_2 (PWR_CR_PLS_LEV2) /*!< Voltage threshold detected by PVD 2.4 V */ -#define LL_PWR_PVDLEVEL_3 (PWR_CR_PLS_LEV3) /*!< Voltage threshold detected by PVD 2.5 V */ -#define LL_PWR_PVDLEVEL_4 (PWR_CR_PLS_LEV4) /*!< Voltage threshold detected by PVD 2.6 V */ -#define LL_PWR_PVDLEVEL_5 (PWR_CR_PLS_LEV5) /*!< Voltage threshold detected by PVD 2.7 V */ -#define LL_PWR_PVDLEVEL_6 (PWR_CR_PLS_LEV6) /*!< Voltage threshold detected by PVD 2.8 V */ -#define LL_PWR_PVDLEVEL_7 (PWR_CR_PLS_LEV7) /*!< Voltage threshold detected by PVD 2.9 V */ -/** - * @} - */ -/** @defgroup PWR_LL_EC_WAKEUP_PIN Wakeup Pins - * @{ - */ -#if defined(PWR_CSR_EWUP) -#define LL_PWR_WAKEUP_PIN1 (PWR_CSR_EWUP) /*!< WKUP pin : PA0 */ -#endif /* PWR_CSR_EWUP */ -#if defined(PWR_CSR_EWUP1) -#define LL_PWR_WAKEUP_PIN1 (PWR_CSR_EWUP1) /*!< WKUP pin 1 : PA0 */ -#endif /* PWR_CSR_EWUP1 */ -#if defined(PWR_CSR_EWUP2) -#define LL_PWR_WAKEUP_PIN2 (PWR_CSR_EWUP2) /*!< WKUP pin 2 : PC0 or PC13 according to device */ -#endif /* PWR_CSR_EWUP2 */ -#if defined(PWR_CSR_EWUP3) -#define LL_PWR_WAKEUP_PIN3 (PWR_CSR_EWUP3) /*!< WKUP pin 3 : PC1 */ -#endif /* PWR_CSR_EWUP3 */ -/** - * @} - */ - -/** - * @} - */ - - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup PWR_LL_Exported_Macros PWR Exported Macros - * @{ - */ - -/** @defgroup PWR_LL_EM_WRITE_READ Common write and read registers Macros - * @{ - */ - -/** - * @brief Write a value in PWR register - * @param __REG__ Register to be written - * @param __VALUE__ Value to be written in the register - * @retval None - */ -#define LL_PWR_WriteReg(__REG__, __VALUE__) WRITE_REG(PWR->__REG__, (__VALUE__)) - -/** - * @brief Read a value in PWR register - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_PWR_ReadReg(__REG__) READ_REG(PWR->__REG__) -/** - * @} - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup PWR_LL_Exported_Functions PWR Exported Functions - * @{ - */ - -/** @defgroup PWR_LL_EF_Configuration Configuration - * @{ - */ -#if defined(PWR_CR_FISSR) -/** - * @brief Enable FLASH interface STOP while system Run is ON - * @rmtoll CR FISSR LL_PWR_EnableFLASHInterfaceSTOP - * @note This mode is enabled only with STOP low power mode. - * @retval None - */ -__STATIC_INLINE void LL_PWR_EnableFLASHInterfaceSTOP(void) -{ - SET_BIT(PWR->CR, PWR_CR_FISSR); -} - -/** - * @brief Disable FLASH Interface STOP while system Run is ON - * @rmtoll CR FISSR LL_PWR_DisableFLASHInterfaceSTOP - * @retval None - */ -__STATIC_INLINE void LL_PWR_DisableFLASHInterfaceSTOP(void) -{ - CLEAR_BIT(PWR->CR, PWR_CR_FISSR); -} - -/** - * @brief Check if FLASH Interface STOP while system Run feature is enabled - * @rmtoll CR FISSR LL_PWR_IsEnabledFLASHInterfaceSTOP - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsEnabledFLASHInterfaceSTOP(void) -{ - return (READ_BIT(PWR->CR, PWR_CR_FISSR) == (PWR_CR_FISSR)); -} -#endif /* PWR_CR_FISSR */ - -#if defined(PWR_CR_FMSSR) -/** - * @brief Enable FLASH Memory STOP while system Run is ON - * @rmtoll CR FMSSR LL_PWR_EnableFLASHMemorySTOP - * @note This mode is enabled only with STOP low power mode. - * @retval None - */ -__STATIC_INLINE void LL_PWR_EnableFLASHMemorySTOP(void) -{ - SET_BIT(PWR->CR, PWR_CR_FMSSR); -} - -/** - * @brief Disable FLASH Memory STOP while system Run is ON - * @rmtoll CR FMSSR LL_PWR_DisableFLASHMemorySTOP - * @retval None - */ -__STATIC_INLINE void LL_PWR_DisableFLASHMemorySTOP(void) -{ - CLEAR_BIT(PWR->CR, PWR_CR_FMSSR); -} - -/** - * @brief Check if FLASH Memory STOP while system Run feature is enabled - * @rmtoll CR FMSSR LL_PWR_IsEnabledFLASHMemorySTOP - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsEnabledFLASHMemorySTOP(void) -{ - return (READ_BIT(PWR->CR, PWR_CR_FMSSR) == (PWR_CR_FMSSR)); -} -#endif /* PWR_CR_FMSSR */ -#if defined(PWR_CR_UDEN) -/** - * @brief Enable Under Drive Mode - * @rmtoll CR UDEN LL_PWR_EnableUnderDriveMode - * @note This mode is enabled only with STOP low power mode. - * In this mode, the 1.2V domain is preserved in reduced leakage mode. This - * mode is only available when the main Regulator or the low power Regulator - * is in low voltage mode. - * @note If the Under-drive mode was enabled, it is automatically disabled after - * exiting Stop mode. - * When the voltage Regulator operates in Under-drive mode, an additional - * startup delay is induced when waking up from Stop mode. - * @retval None - */ -__STATIC_INLINE void LL_PWR_EnableUnderDriveMode(void) -{ - SET_BIT(PWR->CR, PWR_CR_UDEN); -} - -/** - * @brief Disable Under Drive Mode - * @rmtoll CR UDEN LL_PWR_DisableUnderDriveMode - * @retval None - */ -__STATIC_INLINE void LL_PWR_DisableUnderDriveMode(void) -{ - CLEAR_BIT(PWR->CR, PWR_CR_UDEN); -} - -/** - * @brief Check if Under Drive Mode is enabled - * @rmtoll CR UDEN LL_PWR_IsEnabledUnderDriveMode - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsEnabledUnderDriveMode(void) -{ - return (READ_BIT(PWR->CR, PWR_CR_UDEN) == (PWR_CR_UDEN)); -} -#endif /* PWR_CR_UDEN */ - -#if defined(PWR_CR_ODSWEN) -/** - * @brief Enable Over drive switching - * @rmtoll CR ODSWEN LL_PWR_EnableOverDriveSwitching - * @retval None - */ -__STATIC_INLINE void LL_PWR_EnableOverDriveSwitching(void) -{ - SET_BIT(PWR->CR, PWR_CR_ODSWEN); -} - -/** - * @brief Disable Over drive switching - * @rmtoll CR ODSWEN LL_PWR_DisableOverDriveSwitching - * @retval None - */ -__STATIC_INLINE void LL_PWR_DisableOverDriveSwitching(void) -{ - CLEAR_BIT(PWR->CR, PWR_CR_ODSWEN); -} - -/** - * @brief Check if Over drive switching is enabled - * @rmtoll CR ODSWEN LL_PWR_IsEnabledOverDriveSwitching - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsEnabledOverDriveSwitching(void) -{ - return (READ_BIT(PWR->CR, PWR_CR_ODSWEN) == (PWR_CR_ODSWEN)); -} -#endif /* PWR_CR_ODSWEN */ -#if defined(PWR_CR_ODEN) -/** - * @brief Enable Over drive Mode - * @rmtoll CR ODEN LL_PWR_EnableOverDriveMode - * @retval None - */ -__STATIC_INLINE void LL_PWR_EnableOverDriveMode(void) -{ - SET_BIT(PWR->CR, PWR_CR_ODEN); -} - -/** - * @brief Disable Over drive Mode - * @rmtoll CR ODEN LL_PWR_DisableOverDriveMode - * @retval None - */ -__STATIC_INLINE void LL_PWR_DisableOverDriveMode(void) -{ - CLEAR_BIT(PWR->CR, PWR_CR_ODEN); -} - -/** - * @brief Check if Over drive switching is enabled - * @rmtoll CR ODEN LL_PWR_IsEnabledOverDriveMode - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsEnabledOverDriveMode(void) -{ - return (READ_BIT(PWR->CR, PWR_CR_ODEN) == (PWR_CR_ODEN)); -} -#endif /* PWR_CR_ODEN */ -#if defined(PWR_CR_MRUDS) -/** - * @brief Enable Main Regulator in deepsleep under-drive Mode - * @rmtoll CR MRUDS LL_PWR_EnableMainRegulatorDeepSleepUDMode - * @retval None - */ -__STATIC_INLINE void LL_PWR_EnableMainRegulatorDeepSleepUDMode(void) -{ - SET_BIT(PWR->CR, PWR_CR_MRUDS); -} - -/** - * @brief Disable Main Regulator in deepsleep under-drive Mode - * @rmtoll CR MRUDS LL_PWR_DisableMainRegulatorDeepSleepUDMode - * @retval None - */ -__STATIC_INLINE void LL_PWR_DisableMainRegulatorDeepSleepUDMode(void) -{ - CLEAR_BIT(PWR->CR, PWR_CR_MRUDS); -} - -/** - * @brief Check if Main Regulator in deepsleep under-drive Mode is enabled - * @rmtoll CR MRUDS LL_PWR_IsEnabledMainRegulatorDeepSleepUDMode - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsEnabledMainRegulatorDeepSleepUDMode(void) -{ - return (READ_BIT(PWR->CR, PWR_CR_MRUDS) == (PWR_CR_MRUDS)); -} -#endif /* PWR_CR_MRUDS */ - -#if defined(PWR_CR_LPUDS) -/** - * @brief Enable Low Power Regulator in deepsleep under-drive Mode - * @rmtoll CR LPUDS LL_PWR_EnableLowPowerRegulatorDeepSleepUDMode - * @retval None - */ -__STATIC_INLINE void LL_PWR_EnableLowPowerRegulatorDeepSleepUDMode(void) -{ - SET_BIT(PWR->CR, PWR_CR_LPUDS); -} - -/** - * @brief Disable Low Power Regulator in deepsleep under-drive Mode - * @rmtoll CR LPUDS LL_PWR_DisableLowPowerRegulatorDeepSleepUDMode - * @retval None - */ -__STATIC_INLINE void LL_PWR_DisableLowPowerRegulatorDeepSleepUDMode(void) -{ - CLEAR_BIT(PWR->CR, PWR_CR_LPUDS); -} - -/** - * @brief Check if Low Power Regulator in deepsleep under-drive Mode is enabled - * @rmtoll CR LPUDS LL_PWR_IsEnabledLowPowerRegulatorDeepSleepUDMode - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsEnabledLowPowerRegulatorDeepSleepUDMode(void) -{ - return (READ_BIT(PWR->CR, PWR_CR_LPUDS) == (PWR_CR_LPUDS)); -} -#endif /* PWR_CR_LPUDS */ - -#if defined(PWR_CR_MRLVDS) -/** - * @brief Enable Main Regulator low voltage Mode - * @rmtoll CR MRLVDS LL_PWR_EnableMainRegulatorLowVoltageMode - * @retval None - */ -__STATIC_INLINE void LL_PWR_EnableMainRegulatorLowVoltageMode(void) -{ - SET_BIT(PWR->CR, PWR_CR_MRLVDS); -} - -/** - * @brief Disable Main Regulator low voltage Mode - * @rmtoll CR MRLVDS LL_PWR_DisableMainRegulatorLowVoltageMode - * @retval None - */ -__STATIC_INLINE void LL_PWR_DisableMainRegulatorLowVoltageMode(void) -{ - CLEAR_BIT(PWR->CR, PWR_CR_MRLVDS); -} - -/** - * @brief Check if Main Regulator low voltage Mode is enabled - * @rmtoll CR MRLVDS LL_PWR_IsEnabledMainRegulatorLowVoltageMode - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsEnabledMainRegulatorLowVoltageMode(void) -{ - return (READ_BIT(PWR->CR, PWR_CR_MRLVDS) == (PWR_CR_MRLVDS)); -} -#endif /* PWR_CR_MRLVDS */ - -#if defined(PWR_CR_LPLVDS) -/** - * @brief Enable Low Power Regulator low voltage Mode - * @rmtoll CR LPLVDS LL_PWR_EnableLowPowerRegulatorLowVoltageMode - * @retval None - */ -__STATIC_INLINE void LL_PWR_EnableLowPowerRegulatorLowVoltageMode(void) -{ - SET_BIT(PWR->CR, PWR_CR_LPLVDS); -} - -/** - * @brief Disable Low Power Regulator low voltage Mode - * @rmtoll CR LPLVDS LL_PWR_DisableLowPowerRegulatorLowVoltageMode - * @retval None - */ -__STATIC_INLINE void LL_PWR_DisableLowPowerRegulatorLowVoltageMode(void) -{ - CLEAR_BIT(PWR->CR, PWR_CR_LPLVDS); -} - -/** - * @brief Check if Low Power Regulator low voltage Mode is enabled - * @rmtoll CR LPLVDS LL_PWR_IsEnabledLowPowerRegulatorLowVoltageMode - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsEnabledLowPowerRegulatorLowVoltageMode(void) -{ - return (READ_BIT(PWR->CR, PWR_CR_LPLVDS) == (PWR_CR_LPLVDS)); -} -#endif /* PWR_CR_LPLVDS */ -/** - * @brief Set the main internal Regulator output voltage - * @rmtoll CR VOS LL_PWR_SetRegulVoltageScaling - * @param VoltageScaling This parameter can be one of the following values: - * @arg @ref LL_PWR_REGU_VOLTAGE_SCALE1 (*) - * @arg @ref LL_PWR_REGU_VOLTAGE_SCALE2 - * @arg @ref LL_PWR_REGU_VOLTAGE_SCALE3 - * (*) LL_PWR_REGU_VOLTAGE_SCALE1 is not available for STM32F401xx devices - * @retval None - */ -__STATIC_INLINE void LL_PWR_SetRegulVoltageScaling(uint32_t VoltageScaling) -{ - MODIFY_REG(PWR->CR, PWR_CR_VOS, VoltageScaling); -} - -/** - * @brief Get the main internal Regulator output voltage - * @rmtoll CR VOS LL_PWR_GetRegulVoltageScaling - * @retval Returned value can be one of the following values: - * @arg @ref LL_PWR_REGU_VOLTAGE_SCALE1 (*) - * @arg @ref LL_PWR_REGU_VOLTAGE_SCALE2 - * @arg @ref LL_PWR_REGU_VOLTAGE_SCALE3 - * (*) LL_PWR_REGU_VOLTAGE_SCALE1 is not available for STM32F401xx devices - */ -__STATIC_INLINE uint32_t LL_PWR_GetRegulVoltageScaling(void) -{ - return (uint32_t)(READ_BIT(PWR->CR, PWR_CR_VOS)); -} -/** - * @brief Enable the Flash Power Down in Stop Mode - * @rmtoll CR FPDS LL_PWR_EnableFlashPowerDown - * @retval None - */ -__STATIC_INLINE void LL_PWR_EnableFlashPowerDown(void) -{ - SET_BIT(PWR->CR, PWR_CR_FPDS); -} - -/** - * @brief Disable the Flash Power Down in Stop Mode - * @rmtoll CR FPDS LL_PWR_DisableFlashPowerDown - * @retval None - */ -__STATIC_INLINE void LL_PWR_DisableFlashPowerDown(void) -{ - CLEAR_BIT(PWR->CR, PWR_CR_FPDS); -} - -/** - * @brief Check if the Flash Power Down in Stop Mode is enabled - * @rmtoll CR FPDS LL_PWR_IsEnabledFlashPowerDown - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsEnabledFlashPowerDown(void) -{ - return (READ_BIT(PWR->CR, PWR_CR_FPDS) == (PWR_CR_FPDS)); -} - -/** - * @brief Enable access to the backup domain - * @rmtoll CR DBP LL_PWR_EnableBkUpAccess - * @retval None - */ -__STATIC_INLINE void LL_PWR_EnableBkUpAccess(void) -{ - SET_BIT(PWR->CR, PWR_CR_DBP); -} - -/** - * @brief Disable access to the backup domain - * @rmtoll CR DBP LL_PWR_DisableBkUpAccess - * @retval None - */ -__STATIC_INLINE void LL_PWR_DisableBkUpAccess(void) -{ - CLEAR_BIT(PWR->CR, PWR_CR_DBP); -} - -/** - * @brief Check if the backup domain is enabled - * @rmtoll CR DBP LL_PWR_IsEnabledBkUpAccess - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsEnabledBkUpAccess(void) -{ - return (READ_BIT(PWR->CR, PWR_CR_DBP) == (PWR_CR_DBP)); -} -/** - * @brief Enable the backup Regulator - * @rmtoll CSR BRE LL_PWR_EnableBkUpRegulator - * @note The BRE bit of the PWR_CSR register is protected against parasitic write access. - * The LL_PWR_EnableBkUpAccess() must be called before using this API. - * @retval None - */ -__STATIC_INLINE void LL_PWR_EnableBkUpRegulator(void) -{ - SET_BIT(PWR->CSR, PWR_CSR_BRE); -} - -/** - * @brief Disable the backup Regulator - * @rmtoll CSR BRE LL_PWR_DisableBkUpRegulator - * @note The BRE bit of the PWR_CSR register is protected against parasitic write access. - * The LL_PWR_EnableBkUpAccess() must be called before using this API. - * @retval None - */ -__STATIC_INLINE void LL_PWR_DisableBkUpRegulator(void) -{ - CLEAR_BIT(PWR->CSR, PWR_CSR_BRE); -} - -/** - * @brief Check if the backup Regulator is enabled - * @rmtoll CSR BRE LL_PWR_IsEnabledBkUpRegulator - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsEnabledBkUpRegulator(void) -{ - return (READ_BIT(PWR->CSR, PWR_CSR_BRE) == (PWR_CSR_BRE)); -} - -/** - * @brief Set voltage Regulator mode during deep sleep mode - * @rmtoll CR LPDS LL_PWR_SetRegulModeDS - * @param RegulMode This parameter can be one of the following values: - * @arg @ref LL_PWR_REGU_DSMODE_MAIN - * @arg @ref LL_PWR_REGU_DSMODE_LOW_POWER - * @retval None - */ -__STATIC_INLINE void LL_PWR_SetRegulModeDS(uint32_t RegulMode) -{ - MODIFY_REG(PWR->CR, PWR_CR_LPDS, RegulMode); -} - -/** - * @brief Get voltage Regulator mode during deep sleep mode - * @rmtoll CR LPDS LL_PWR_GetRegulModeDS - * @retval Returned value can be one of the following values: - * @arg @ref LL_PWR_REGU_DSMODE_MAIN - * @arg @ref LL_PWR_REGU_DSMODE_LOW_POWER - */ -__STATIC_INLINE uint32_t LL_PWR_GetRegulModeDS(void) -{ - return (uint32_t)(READ_BIT(PWR->CR, PWR_CR_LPDS)); -} - -/** - * @brief Set Power Down mode when CPU enters deepsleep - * @rmtoll CR PDDS LL_PWR_SetPowerMode\n - * @rmtoll CR MRUDS LL_PWR_SetPowerMode\n - * @rmtoll CR LPUDS LL_PWR_SetPowerMode\n - * @rmtoll CR FPDS LL_PWR_SetPowerMode\n - * @rmtoll CR MRLVDS LL_PWR_SetPowerMode\n - * @rmtoll CR LPlVDS LL_PWR_SetPowerMode\n - * @rmtoll CR FPDS LL_PWR_SetPowerMode\n - * @rmtoll CR LPDS LL_PWR_SetPowerMode - * @param PDMode This parameter can be one of the following values: - * @arg @ref LL_PWR_MODE_STOP_MAINREGU - * @arg @ref LL_PWR_MODE_STOP_LPREGU - * @arg @ref LL_PWR_MODE_STOP_MAINREGU_UNDERDRIVE (*) - * @arg @ref LL_PWR_MODE_STOP_LPREGU_UNDERDRIVE (*) - * @arg @ref LL_PWR_MODE_STOP_MAINREGU_DEEPSLEEP (*) - * @arg @ref LL_PWR_MODE_STOP_LPREGU_DEEPSLEEP (*) - * - * (*) not available on all devices - * @arg @ref LL_PWR_MODE_STANDBY - * @retval None - */ -__STATIC_INLINE void LL_PWR_SetPowerMode(uint32_t PDMode) -{ -#if defined(PWR_CR_MRUDS) && defined(PWR_CR_LPUDS) && defined(PWR_CR_FPDS) - MODIFY_REG(PWR->CR, (PWR_CR_PDDS | PWR_CR_LPDS | PWR_CR_FPDS | PWR_CR_LPUDS | PWR_CR_MRUDS), PDMode); -#elif defined(PWR_CR_MRLVDS) && defined(PWR_CR_LPLVDS) && defined(PWR_CR_FPDS) - MODIFY_REG(PWR->CR, (PWR_CR_PDDS | PWR_CR_LPDS | PWR_CR_FPDS | PWR_CR_LPLVDS | PWR_CR_MRLVDS), PDMode); -#else - MODIFY_REG(PWR->CR, (PWR_CR_PDDS| PWR_CR_LPDS), PDMode); -#endif /* PWR_CR_MRUDS && PWR_CR_LPUDS && PWR_CR_FPDS */ -} - -/** - * @brief Get Power Down mode when CPU enters deepsleep - * @rmtoll CR PDDS LL_PWR_GetPowerMode\n - * @rmtoll CR MRUDS LL_PWR_GetPowerMode\n - * @rmtoll CR LPUDS LL_PWR_GetPowerMode\n - * @rmtoll CR FPDS LL_PWR_GetPowerMode\n - * @rmtoll CR MRLVDS LL_PWR_GetPowerMode\n - * @rmtoll CR LPLVDS LL_PWR_GetPowerMode\n - * @rmtoll CR FPDS LL_PWR_GetPowerMode\n - * @rmtoll CR LPDS LL_PWR_GetPowerMode - * @retval Returned value can be one of the following values: - * @arg @ref LL_PWR_MODE_STOP_MAINREGU - * @arg @ref LL_PWR_MODE_STOP_LPREGU - * @arg @ref LL_PWR_MODE_STOP_MAINREGU_UNDERDRIVE (*) - * @arg @ref LL_PWR_MODE_STOP_LPREGU_UNDERDRIVE (*) - * @arg @ref LL_PWR_MODE_STOP_MAINREGU_DEEPSLEEP (*) - * @arg @ref LL_PWR_MODE_STOP_LPREGU_DEEPSLEEP (*) - * - * (*) not available on all devices - * @arg @ref LL_PWR_MODE_STANDBY - */ -__STATIC_INLINE uint32_t LL_PWR_GetPowerMode(void) -{ -#if defined(PWR_CR_MRUDS) && defined(PWR_CR_LPUDS) && defined(PWR_CR_FPDS) - return (uint32_t)(READ_BIT(PWR->CR, (PWR_CR_PDDS | PWR_CR_LPDS | PWR_CR_FPDS | PWR_CR_LPUDS | PWR_CR_MRUDS))); -#elif defined(PWR_CR_MRLVDS) && defined(PWR_CR_LPLVDS) && defined(PWR_CR_FPDS) - return (uint32_t)(READ_BIT(PWR->CR, (PWR_CR_PDDS | PWR_CR_LPDS | PWR_CR_FPDS | PWR_CR_LPLVDS | PWR_CR_MRLVDS))); -#else - return (uint32_t)(READ_BIT(PWR->CR, (PWR_CR_PDDS| PWR_CR_LPDS))); -#endif /* PWR_CR_MRUDS && PWR_CR_LPUDS && PWR_CR_FPDS */ -} - -/** - * @brief Configure the voltage threshold detected by the Power Voltage Detector - * @rmtoll CR PLS LL_PWR_SetPVDLevel - * @param PVDLevel This parameter can be one of the following values: - * @arg @ref LL_PWR_PVDLEVEL_0 - * @arg @ref LL_PWR_PVDLEVEL_1 - * @arg @ref LL_PWR_PVDLEVEL_2 - * @arg @ref LL_PWR_PVDLEVEL_3 - * @arg @ref LL_PWR_PVDLEVEL_4 - * @arg @ref LL_PWR_PVDLEVEL_5 - * @arg @ref LL_PWR_PVDLEVEL_6 - * @arg @ref LL_PWR_PVDLEVEL_7 - * @retval None - */ -__STATIC_INLINE void LL_PWR_SetPVDLevel(uint32_t PVDLevel) -{ - MODIFY_REG(PWR->CR, PWR_CR_PLS, PVDLevel); -} - -/** - * @brief Get the voltage threshold detection - * @rmtoll CR PLS LL_PWR_GetPVDLevel - * @retval Returned value can be one of the following values: - * @arg @ref LL_PWR_PVDLEVEL_0 - * @arg @ref LL_PWR_PVDLEVEL_1 - * @arg @ref LL_PWR_PVDLEVEL_2 - * @arg @ref LL_PWR_PVDLEVEL_3 - * @arg @ref LL_PWR_PVDLEVEL_4 - * @arg @ref LL_PWR_PVDLEVEL_5 - * @arg @ref LL_PWR_PVDLEVEL_6 - * @arg @ref LL_PWR_PVDLEVEL_7 - */ -__STATIC_INLINE uint32_t LL_PWR_GetPVDLevel(void) -{ - return (uint32_t)(READ_BIT(PWR->CR, PWR_CR_PLS)); -} - -/** - * @brief Enable Power Voltage Detector - * @rmtoll CR PVDE LL_PWR_EnablePVD - * @retval None - */ -__STATIC_INLINE void LL_PWR_EnablePVD(void) -{ - SET_BIT(PWR->CR, PWR_CR_PVDE); -} - -/** - * @brief Disable Power Voltage Detector - * @rmtoll CR PVDE LL_PWR_DisablePVD - * @retval None - */ -__STATIC_INLINE void LL_PWR_DisablePVD(void) -{ - CLEAR_BIT(PWR->CR, PWR_CR_PVDE); -} - -/** - * @brief Check if Power Voltage Detector is enabled - * @rmtoll CR PVDE LL_PWR_IsEnabledPVD - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsEnabledPVD(void) -{ - return (READ_BIT(PWR->CR, PWR_CR_PVDE) == (PWR_CR_PVDE)); -} - -/** - * @brief Enable the WakeUp PINx functionality - * @rmtoll CSR EWUP LL_PWR_EnableWakeUpPin\n - * @rmtoll CSR EWUP1 LL_PWR_EnableWakeUpPin\n - * @rmtoll CSR EWUP2 LL_PWR_EnableWakeUpPin\n - * @rmtoll CSR EWUP3 LL_PWR_EnableWakeUpPin - * @param WakeUpPin This parameter can be one of the following values: - * @arg @ref LL_PWR_WAKEUP_PIN1 - * @arg @ref LL_PWR_WAKEUP_PIN2 (*) - * @arg @ref LL_PWR_WAKEUP_PIN3 (*) - * - * (*) not available on all devices - * @retval None - */ -__STATIC_INLINE void LL_PWR_EnableWakeUpPin(uint32_t WakeUpPin) -{ - SET_BIT(PWR->CSR, WakeUpPin); -} - -/** - * @brief Disable the WakeUp PINx functionality - * @rmtoll CSR EWUP LL_PWR_DisableWakeUpPin\n - * @rmtoll CSR EWUP1 LL_PWR_DisableWakeUpPin\n - * @rmtoll CSR EWUP2 LL_PWR_DisableWakeUpPin\n - * @rmtoll CSR EWUP3 LL_PWR_DisableWakeUpPin - * @param WakeUpPin This parameter can be one of the following values: - * @arg @ref LL_PWR_WAKEUP_PIN1 - * @arg @ref LL_PWR_WAKEUP_PIN2 (*) - * @arg @ref LL_PWR_WAKEUP_PIN3 (*) - * - * (*) not available on all devices - * @retval None - */ -__STATIC_INLINE void LL_PWR_DisableWakeUpPin(uint32_t WakeUpPin) -{ - CLEAR_BIT(PWR->CSR, WakeUpPin); -} - -/** - * @brief Check if the WakeUp PINx functionality is enabled - * @rmtoll CSR EWUP LL_PWR_IsEnabledWakeUpPin\n - * @rmtoll CSR EWUP1 LL_PWR_IsEnabledWakeUpPin\n - * @rmtoll CSR EWUP2 LL_PWR_IsEnabledWakeUpPin\n - * @rmtoll CSR EWUP3 LL_PWR_IsEnabledWakeUpPin - * @param WakeUpPin This parameter can be one of the following values: - * @arg @ref LL_PWR_WAKEUP_PIN1 - * @arg @ref LL_PWR_WAKEUP_PIN2 (*) - * @arg @ref LL_PWR_WAKEUP_PIN3 (*) - * - * (*) not available on all devices - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsEnabledWakeUpPin(uint32_t WakeUpPin) -{ - return (READ_BIT(PWR->CSR, WakeUpPin) == (WakeUpPin)); -} - - -/** - * @} - */ - -/** @defgroup PWR_LL_EF_FLAG_Management FLAG_Management - * @{ - */ - -/** - * @brief Get Wake-up Flag - * @rmtoll CSR WUF LL_PWR_IsActiveFlag_WU - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsActiveFlag_WU(void) -{ - return (READ_BIT(PWR->CSR, PWR_CSR_WUF) == (PWR_CSR_WUF)); -} - -/** - * @brief Get Standby Flag - * @rmtoll CSR SBF LL_PWR_IsActiveFlag_SB - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsActiveFlag_SB(void) -{ - return (READ_BIT(PWR->CSR, PWR_CSR_SBF) == (PWR_CSR_SBF)); -} - -/** - * @brief Get Backup Regulator ready Flag - * @rmtoll CSR BRR LL_PWR_IsActiveFlag_BRR - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsActiveFlag_BRR(void) -{ - return (READ_BIT(PWR->CSR, PWR_CSR_BRR) == (PWR_CSR_BRR)); -} -/** - * @brief Indicate whether VDD voltage is below the selected PVD threshold - * @rmtoll CSR PVDO LL_PWR_IsActiveFlag_PVDO - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsActiveFlag_PVDO(void) -{ - return (READ_BIT(PWR->CSR, PWR_CSR_PVDO) == (PWR_CSR_PVDO)); -} - -/** - * @brief Indicate whether the Regulator is ready in the selected voltage range or if its output voltage is still changing to the required voltage level - * @rmtoll CSR VOS LL_PWR_IsActiveFlag_VOS - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsActiveFlag_VOS(void) -{ - return (READ_BIT(PWR->CSR, LL_PWR_CSR_VOS) == (LL_PWR_CSR_VOS)); -} -#if defined(PWR_CR_ODEN) -/** - * @brief Indicate whether the Over-Drive mode is ready or not - * @rmtoll CSR ODRDY LL_PWR_IsActiveFlag_OD - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsActiveFlag_OD(void) -{ - return (READ_BIT(PWR->CSR, PWR_CSR_ODRDY) == (PWR_CSR_ODRDY)); -} -#endif /* PWR_CR_ODEN */ - -#if defined(PWR_CR_ODSWEN) -/** - * @brief Indicate whether the Over-Drive mode switching is ready or not - * @rmtoll CSR ODSWRDY LL_PWR_IsActiveFlag_ODSW - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsActiveFlag_ODSW(void) -{ - return (READ_BIT(PWR->CSR, PWR_CSR_ODSWRDY) == (PWR_CSR_ODSWRDY)); -} -#endif /* PWR_CR_ODSWEN */ - -#if defined(PWR_CR_UDEN) -/** - * @brief Indicate whether the Under-Drive mode is ready or not - * @rmtoll CSR UDRDY LL_PWR_IsActiveFlag_UD - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_PWR_IsActiveFlag_UD(void) -{ - return (READ_BIT(PWR->CSR, PWR_CSR_UDRDY) == (PWR_CSR_UDRDY)); -} -#endif /* PWR_CR_UDEN */ -/** - * @brief Clear Standby Flag - * @rmtoll CR CSBF LL_PWR_ClearFlag_SB - * @retval None - */ -__STATIC_INLINE void LL_PWR_ClearFlag_SB(void) -{ - SET_BIT(PWR->CR, PWR_CR_CSBF); -} - -/** - * @brief Clear Wake-up Flags - * @rmtoll CR CWUF LL_PWR_ClearFlag_WU - * @retval None - */ -__STATIC_INLINE void LL_PWR_ClearFlag_WU(void) -{ - SET_BIT(PWR->CR, PWR_CR_CWUF); -} -#if defined(PWR_CSR_UDRDY) -/** - * @brief Clear Under-Drive ready Flag - * @rmtoll CSR UDRDY LL_PWR_ClearFlag_UD - * @retval None - */ -__STATIC_INLINE void LL_PWR_ClearFlag_UD(void) -{ - WRITE_REG(PWR->CSR, PWR_CSR_UDRDY); -} -#endif /* PWR_CSR_UDRDY */ - -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup PWR_LL_EF_Init De-initialization function - * @{ - */ -ErrorStatus LL_PWR_DeInit(void); -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* defined(PWR) */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_PWR_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_rcc.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_rcc.h deleted file mode 100644 index d4c249f..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_rcc.h +++ /dev/null @@ -1,7099 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_rcc.h - * @author MCD Application Team - * @brief Header file of RCC LL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_LL_RCC_H -#define __STM32F4xx_LL_RCC_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined(RCC) - -/** @defgroup RCC_LL RCC - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/** @defgroup RCC_LL_Private_Variables RCC Private Variables - * @{ - */ - -#if defined(RCC_DCKCFGR_PLLSAIDIVR) -static const uint8_t aRCC_PLLSAIDIVRPrescTable[4] = {2, 4, 8, 16}; -#endif /* RCC_DCKCFGR_PLLSAIDIVR */ - -/** - * @} - */ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup RCC_LL_Private_Macros RCC Private Macros - * @{ - */ -/** - * @} - */ -#endif /*USE_FULL_LL_DRIVER*/ -/* Exported types ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup RCC_LL_Exported_Types RCC Exported Types - * @{ - */ - -/** @defgroup LL_ES_CLOCK_FREQ Clocks Frequency Structure - * @{ - */ - -/** - * @brief RCC Clocks Frequency Structure - */ -typedef struct -{ - uint32_t SYSCLK_Frequency; /*!< SYSCLK clock frequency */ - uint32_t HCLK_Frequency; /*!< HCLK clock frequency */ - uint32_t PCLK1_Frequency; /*!< PCLK1 clock frequency */ - uint32_t PCLK2_Frequency; /*!< PCLK2 clock frequency */ -} LL_RCC_ClocksTypeDef; - -/** - * @} - */ - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup RCC_LL_Exported_Constants RCC Exported Constants - * @{ - */ - -/** @defgroup RCC_LL_EC_OSC_VALUES Oscillator Values adaptation - * @brief Defines used to adapt values of different oscillators - * @note These values could be modified in the user environment according to - * HW set-up. - * @{ - */ -#if !defined (HSE_VALUE) -#define HSE_VALUE 25000000U /*!< Value of the HSE oscillator in Hz */ -#endif /* HSE_VALUE */ - -#if !defined (HSI_VALUE) -#define HSI_VALUE 16000000U /*!< Value of the HSI oscillator in Hz */ -#endif /* HSI_VALUE */ - -#if !defined (LSE_VALUE) -#define LSE_VALUE 32768U /*!< Value of the LSE oscillator in Hz */ -#endif /* LSE_VALUE */ - -#if !defined (LSI_VALUE) -#define LSI_VALUE 32000U /*!< Value of the LSI oscillator in Hz */ -#endif /* LSI_VALUE */ - -#if !defined (EXTERNAL_CLOCK_VALUE) -#define EXTERNAL_CLOCK_VALUE 12288000U /*!< Value of the I2S_CKIN external oscillator in Hz */ -#endif /* EXTERNAL_CLOCK_VALUE */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_CLEAR_FLAG Clear Flags Defines - * @brief Flags defines which can be used with LL_RCC_WriteReg function - * @{ - */ -#define LL_RCC_CIR_LSIRDYC RCC_CIR_LSIRDYC /*!< LSI Ready Interrupt Clear */ -#define LL_RCC_CIR_LSERDYC RCC_CIR_LSERDYC /*!< LSE Ready Interrupt Clear */ -#define LL_RCC_CIR_HSIRDYC RCC_CIR_HSIRDYC /*!< HSI Ready Interrupt Clear */ -#define LL_RCC_CIR_HSERDYC RCC_CIR_HSERDYC /*!< HSE Ready Interrupt Clear */ -#define LL_RCC_CIR_PLLRDYC RCC_CIR_PLLRDYC /*!< PLL Ready Interrupt Clear */ -#if defined(RCC_PLLI2S_SUPPORT) -#define LL_RCC_CIR_PLLI2SRDYC RCC_CIR_PLLI2SRDYC /*!< PLLI2S Ready Interrupt Clear */ -#endif /* RCC_PLLI2S_SUPPORT */ -#if defined(RCC_PLLSAI_SUPPORT) -#define LL_RCC_CIR_PLLSAIRDYC RCC_CIR_PLLSAIRDYC /*!< PLLSAI Ready Interrupt Clear */ -#endif /* RCC_PLLSAI_SUPPORT */ -#define LL_RCC_CIR_CSSC RCC_CIR_CSSC /*!< Clock Security System Interrupt Clear */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_GET_FLAG Get Flags Defines - * @brief Flags defines which can be used with LL_RCC_ReadReg function - * @{ - */ -#define LL_RCC_CIR_LSIRDYF RCC_CIR_LSIRDYF /*!< LSI Ready Interrupt flag */ -#define LL_RCC_CIR_LSERDYF RCC_CIR_LSERDYF /*!< LSE Ready Interrupt flag */ -#define LL_RCC_CIR_HSIRDYF RCC_CIR_HSIRDYF /*!< HSI Ready Interrupt flag */ -#define LL_RCC_CIR_HSERDYF RCC_CIR_HSERDYF /*!< HSE Ready Interrupt flag */ -#define LL_RCC_CIR_PLLRDYF RCC_CIR_PLLRDYF /*!< PLL Ready Interrupt flag */ -#if defined(RCC_PLLI2S_SUPPORT) -#define LL_RCC_CIR_PLLI2SRDYF RCC_CIR_PLLI2SRDYF /*!< PLLI2S Ready Interrupt flag */ -#endif /* RCC_PLLI2S_SUPPORT */ -#if defined(RCC_PLLSAI_SUPPORT) -#define LL_RCC_CIR_PLLSAIRDYF RCC_CIR_PLLSAIRDYF /*!< PLLSAI Ready Interrupt flag */ -#endif /* RCC_PLLSAI_SUPPORT */ -#define LL_RCC_CIR_CSSF RCC_CIR_CSSF /*!< Clock Security System Interrupt flag */ -#define LL_RCC_CSR_LPWRRSTF RCC_CSR_LPWRRSTF /*!< Low-Power reset flag */ -#define LL_RCC_CSR_PINRSTF RCC_CSR_PINRSTF /*!< PIN reset flag */ -#define LL_RCC_CSR_PORRSTF RCC_CSR_PORRSTF /*!< POR/PDR reset flag */ -#define LL_RCC_CSR_SFTRSTF RCC_CSR_SFTRSTF /*!< Software Reset flag */ -#define LL_RCC_CSR_IWDGRSTF RCC_CSR_IWDGRSTF /*!< Independent Watchdog reset flag */ -#define LL_RCC_CSR_WWDGRSTF RCC_CSR_WWDGRSTF /*!< Window watchdog reset flag */ -#if defined(RCC_CSR_BORRSTF) -#define LL_RCC_CSR_BORRSTF RCC_CSR_BORRSTF /*!< BOR reset flag */ -#endif /* RCC_CSR_BORRSTF */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_IT IT Defines - * @brief IT defines which can be used with LL_RCC_ReadReg and LL_RCC_WriteReg functions - * @{ - */ -#define LL_RCC_CIR_LSIRDYIE RCC_CIR_LSIRDYIE /*!< LSI Ready Interrupt Enable */ -#define LL_RCC_CIR_LSERDYIE RCC_CIR_LSERDYIE /*!< LSE Ready Interrupt Enable */ -#define LL_RCC_CIR_HSIRDYIE RCC_CIR_HSIRDYIE /*!< HSI Ready Interrupt Enable */ -#define LL_RCC_CIR_HSERDYIE RCC_CIR_HSERDYIE /*!< HSE Ready Interrupt Enable */ -#define LL_RCC_CIR_PLLRDYIE RCC_CIR_PLLRDYIE /*!< PLL Ready Interrupt Enable */ -#if defined(RCC_PLLI2S_SUPPORT) -#define LL_RCC_CIR_PLLI2SRDYIE RCC_CIR_PLLI2SRDYIE /*!< PLLI2S Ready Interrupt Enable */ -#endif /* RCC_PLLI2S_SUPPORT */ -#if defined(RCC_PLLSAI_SUPPORT) -#define LL_RCC_CIR_PLLSAIRDYIE RCC_CIR_PLLSAIRDYIE /*!< PLLSAI Ready Interrupt Enable */ -#endif /* RCC_PLLSAI_SUPPORT */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_SYS_CLKSOURCE System clock switch - * @{ - */ -#define LL_RCC_SYS_CLKSOURCE_HSI RCC_CFGR_SW_HSI /*!< HSI selection as system clock */ -#define LL_RCC_SYS_CLKSOURCE_HSE RCC_CFGR_SW_HSE /*!< HSE selection as system clock */ -#define LL_RCC_SYS_CLKSOURCE_PLL RCC_CFGR_SW_PLL /*!< PLL selection as system clock */ -#if defined(RCC_CFGR_SW_PLLR) -#define LL_RCC_SYS_CLKSOURCE_PLLR RCC_CFGR_SW_PLLR /*!< PLLR selection as system clock */ -#endif /* RCC_CFGR_SW_PLLR */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_SYS_CLKSOURCE_STATUS System clock switch status - * @{ - */ -#define LL_RCC_SYS_CLKSOURCE_STATUS_HSI RCC_CFGR_SWS_HSI /*!< HSI used as system clock */ -#define LL_RCC_SYS_CLKSOURCE_STATUS_HSE RCC_CFGR_SWS_HSE /*!< HSE used as system clock */ -#define LL_RCC_SYS_CLKSOURCE_STATUS_PLL RCC_CFGR_SWS_PLL /*!< PLL used as system clock */ -#if defined(RCC_PLLR_SYSCLK_SUPPORT) -#define LL_RCC_SYS_CLKSOURCE_STATUS_PLLR RCC_CFGR_SWS_PLLR /*!< PLLR used as system clock */ -#endif /* RCC_PLLR_SYSCLK_SUPPORT */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_SYSCLK_DIV AHB prescaler - * @{ - */ -#define LL_RCC_SYSCLK_DIV_1 RCC_CFGR_HPRE_DIV1 /*!< SYSCLK not divided */ -#define LL_RCC_SYSCLK_DIV_2 RCC_CFGR_HPRE_DIV2 /*!< SYSCLK divided by 2 */ -#define LL_RCC_SYSCLK_DIV_4 RCC_CFGR_HPRE_DIV4 /*!< SYSCLK divided by 4 */ -#define LL_RCC_SYSCLK_DIV_8 RCC_CFGR_HPRE_DIV8 /*!< SYSCLK divided by 8 */ -#define LL_RCC_SYSCLK_DIV_16 RCC_CFGR_HPRE_DIV16 /*!< SYSCLK divided by 16 */ -#define LL_RCC_SYSCLK_DIV_64 RCC_CFGR_HPRE_DIV64 /*!< SYSCLK divided by 64 */ -#define LL_RCC_SYSCLK_DIV_128 RCC_CFGR_HPRE_DIV128 /*!< SYSCLK divided by 128 */ -#define LL_RCC_SYSCLK_DIV_256 RCC_CFGR_HPRE_DIV256 /*!< SYSCLK divided by 256 */ -#define LL_RCC_SYSCLK_DIV_512 RCC_CFGR_HPRE_DIV512 /*!< SYSCLK divided by 512 */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_APB1_DIV APB low-speed prescaler (APB1) - * @{ - */ -#define LL_RCC_APB1_DIV_1 RCC_CFGR_PPRE1_DIV1 /*!< HCLK not divided */ -#define LL_RCC_APB1_DIV_2 RCC_CFGR_PPRE1_DIV2 /*!< HCLK divided by 2 */ -#define LL_RCC_APB1_DIV_4 RCC_CFGR_PPRE1_DIV4 /*!< HCLK divided by 4 */ -#define LL_RCC_APB1_DIV_8 RCC_CFGR_PPRE1_DIV8 /*!< HCLK divided by 8 */ -#define LL_RCC_APB1_DIV_16 RCC_CFGR_PPRE1_DIV16 /*!< HCLK divided by 16 */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_APB2_DIV APB high-speed prescaler (APB2) - * @{ - */ -#define LL_RCC_APB2_DIV_1 RCC_CFGR_PPRE2_DIV1 /*!< HCLK not divided */ -#define LL_RCC_APB2_DIV_2 RCC_CFGR_PPRE2_DIV2 /*!< HCLK divided by 2 */ -#define LL_RCC_APB2_DIV_4 RCC_CFGR_PPRE2_DIV4 /*!< HCLK divided by 4 */ -#define LL_RCC_APB2_DIV_8 RCC_CFGR_PPRE2_DIV8 /*!< HCLK divided by 8 */ -#define LL_RCC_APB2_DIV_16 RCC_CFGR_PPRE2_DIV16 /*!< HCLK divided by 16 */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_MCOxSOURCE MCO source selection - * @{ - */ -#define LL_RCC_MCO1SOURCE_HSI (uint32_t)(RCC_CFGR_MCO1|0x00000000U) /*!< HSI selection as MCO1 source */ -#define LL_RCC_MCO1SOURCE_LSE (uint32_t)(RCC_CFGR_MCO1|(RCC_CFGR_MCO1_0 >> 16U)) /*!< LSE selection as MCO1 source */ -#define LL_RCC_MCO1SOURCE_HSE (uint32_t)(RCC_CFGR_MCO1|(RCC_CFGR_MCO1_1 >> 16U)) /*!< HSE selection as MCO1 source */ -#define LL_RCC_MCO1SOURCE_PLLCLK (uint32_t)(RCC_CFGR_MCO1|((RCC_CFGR_MCO1_1|RCC_CFGR_MCO1_0) >> 16U)) /*!< PLLCLK selection as MCO1 source */ -#if defined(RCC_CFGR_MCO2) -#define LL_RCC_MCO2SOURCE_SYSCLK (uint32_t)(RCC_CFGR_MCO2|0x00000000U) /*!< SYSCLK selection as MCO2 source */ -#define LL_RCC_MCO2SOURCE_PLLI2S (uint32_t)(RCC_CFGR_MCO2|(RCC_CFGR_MCO2_0 >> 16U)) /*!< PLLI2S selection as MCO2 source */ -#define LL_RCC_MCO2SOURCE_HSE (uint32_t)(RCC_CFGR_MCO2|(RCC_CFGR_MCO2_1 >> 16U)) /*!< HSE selection as MCO2 source */ -#define LL_RCC_MCO2SOURCE_PLLCLK (uint32_t)(RCC_CFGR_MCO2|((RCC_CFGR_MCO2_1|RCC_CFGR_MCO2_0) >> 16U)) /*!< PLLCLK selection as MCO2 source */ -#endif /* RCC_CFGR_MCO2 */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_MCOx_DIV MCO prescaler - * @{ - */ -#define LL_RCC_MCO1_DIV_1 (uint32_t)(RCC_CFGR_MCO1PRE|0x00000000U) /*!< MCO1 not divided */ -#define LL_RCC_MCO1_DIV_2 (uint32_t)(RCC_CFGR_MCO1PRE|(RCC_CFGR_MCO1PRE_2 >> 16U)) /*!< MCO1 divided by 2 */ -#define LL_RCC_MCO1_DIV_3 (uint32_t)(RCC_CFGR_MCO1PRE|((RCC_CFGR_MCO1PRE_2|RCC_CFGR_MCO1PRE_0) >> 16U)) /*!< MCO1 divided by 3 */ -#define LL_RCC_MCO1_DIV_4 (uint32_t)(RCC_CFGR_MCO1PRE|((RCC_CFGR_MCO1PRE_2|RCC_CFGR_MCO1PRE_1) >> 16U)) /*!< MCO1 divided by 4 */ -#define LL_RCC_MCO1_DIV_5 (uint32_t)(RCC_CFGR_MCO1PRE|(RCC_CFGR_MCO1PRE >> 16U)) /*!< MCO1 divided by 5 */ -#if defined(RCC_CFGR_MCO2PRE) -#define LL_RCC_MCO2_DIV_1 (uint32_t)(RCC_CFGR_MCO2PRE|0x00000000U) /*!< MCO2 not divided */ -#define LL_RCC_MCO2_DIV_2 (uint32_t)(RCC_CFGR_MCO2PRE|(RCC_CFGR_MCO2PRE_2 >> 16U)) /*!< MCO2 divided by 2 */ -#define LL_RCC_MCO2_DIV_3 (uint32_t)(RCC_CFGR_MCO2PRE|((RCC_CFGR_MCO2PRE_2|RCC_CFGR_MCO2PRE_0) >> 16U)) /*!< MCO2 divided by 3 */ -#define LL_RCC_MCO2_DIV_4 (uint32_t)(RCC_CFGR_MCO2PRE|((RCC_CFGR_MCO2PRE_2|RCC_CFGR_MCO2PRE_1) >> 16U)) /*!< MCO2 divided by 4 */ -#define LL_RCC_MCO2_DIV_5 (uint32_t)(RCC_CFGR_MCO2PRE|(RCC_CFGR_MCO2PRE >> 16U)) /*!< MCO2 divided by 5 */ -#endif /* RCC_CFGR_MCO2PRE */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_RTC_HSEDIV HSE prescaler for RTC clock - * @{ - */ -#define LL_RCC_RTC_NOCLOCK 0x00000000U /*!< HSE not divided */ -#define LL_RCC_RTC_HSE_DIV_2 RCC_CFGR_RTCPRE_1 /*!< HSE clock divided by 2 */ -#define LL_RCC_RTC_HSE_DIV_3 (RCC_CFGR_RTCPRE_1|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 3 */ -#define LL_RCC_RTC_HSE_DIV_4 RCC_CFGR_RTCPRE_2 /*!< HSE clock divided by 4 */ -#define LL_RCC_RTC_HSE_DIV_5 (RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 5 */ -#define LL_RCC_RTC_HSE_DIV_6 (RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_1) /*!< HSE clock divided by 6 */ -#define LL_RCC_RTC_HSE_DIV_7 (RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_1|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 7 */ -#define LL_RCC_RTC_HSE_DIV_8 RCC_CFGR_RTCPRE_3 /*!< HSE clock divided by 8 */ -#define LL_RCC_RTC_HSE_DIV_9 (RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 9 */ -#define LL_RCC_RTC_HSE_DIV_10 (RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_1) /*!< HSE clock divided by 10 */ -#define LL_RCC_RTC_HSE_DIV_11 (RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_1|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 11 */ -#define LL_RCC_RTC_HSE_DIV_12 (RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_2) /*!< HSE clock divided by 12 */ -#define LL_RCC_RTC_HSE_DIV_13 (RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 13 */ -#define LL_RCC_RTC_HSE_DIV_14 (RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_1) /*!< HSE clock divided by 14 */ -#define LL_RCC_RTC_HSE_DIV_15 (RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_1|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 15 */ -#define LL_RCC_RTC_HSE_DIV_16 RCC_CFGR_RTCPRE_4 /*!< HSE clock divided by 16 */ -#define LL_RCC_RTC_HSE_DIV_17 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 17 */ -#define LL_RCC_RTC_HSE_DIV_18 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_1) /*!< HSE clock divided by 18 */ -#define LL_RCC_RTC_HSE_DIV_19 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_1|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 19 */ -#define LL_RCC_RTC_HSE_DIV_20 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_2) /*!< HSE clock divided by 20 */ -#define LL_RCC_RTC_HSE_DIV_21 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 21 */ -#define LL_RCC_RTC_HSE_DIV_22 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_1) /*!< HSE clock divided by 22 */ -#define LL_RCC_RTC_HSE_DIV_23 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_1|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 23 */ -#define LL_RCC_RTC_HSE_DIV_24 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_3) /*!< HSE clock divided by 24 */ -#define LL_RCC_RTC_HSE_DIV_25 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 25 */ -#define LL_RCC_RTC_HSE_DIV_26 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_1) /*!< HSE clock divided by 26 */ -#define LL_RCC_RTC_HSE_DIV_27 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_1|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 27 */ -#define LL_RCC_RTC_HSE_DIV_28 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_2) /*!< HSE clock divided by 28 */ -#define LL_RCC_RTC_HSE_DIV_29 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 29 */ -#define LL_RCC_RTC_HSE_DIV_30 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_1) /*!< HSE clock divided by 30 */ -#define LL_RCC_RTC_HSE_DIV_31 (RCC_CFGR_RTCPRE_4|RCC_CFGR_RTCPRE_3|RCC_CFGR_RTCPRE_2|RCC_CFGR_RTCPRE_1|RCC_CFGR_RTCPRE_0) /*!< HSE clock divided by 31 */ -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup RCC_LL_EC_PERIPH_FREQUENCY Peripheral clock frequency - * @{ - */ -#define LL_RCC_PERIPH_FREQUENCY_NO 0x00000000U /*!< No clock enabled for the peripheral */ -#define LL_RCC_PERIPH_FREQUENCY_NA 0xFFFFFFFFU /*!< Frequency cannot be provided as external clock */ -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -#if defined(FMPI2C1) -/** @defgroup RCC_LL_EC_FMPI2C1_CLKSOURCE Peripheral FMPI2C clock source selection - * @{ - */ -#define LL_RCC_FMPI2C1_CLKSOURCE_PCLK1 0x00000000U /*!< PCLK1 clock used as FMPI2C1 clock source */ -#define LL_RCC_FMPI2C1_CLKSOURCE_SYSCLK RCC_DCKCFGR2_FMPI2C1SEL_0 /*!< SYSCLK clock used as FMPI2C1 clock source */ -#define LL_RCC_FMPI2C1_CLKSOURCE_HSI RCC_DCKCFGR2_FMPI2C1SEL_1 /*!< HSI clock used as FMPI2C1 clock source */ -/** - * @} - */ -#endif /* FMPI2C1 */ - -#if defined(LPTIM1) -/** @defgroup RCC_LL_EC_LPTIM1_CLKSOURCE Peripheral LPTIM clock source selection - * @{ - */ -#define LL_RCC_LPTIM1_CLKSOURCE_PCLK1 0x00000000U /*!< PCLK1 clock used as LPTIM1 clock */ -#define LL_RCC_LPTIM1_CLKSOURCE_HSI RCC_DCKCFGR2_LPTIM1SEL_0 /*!< LSI oscillator clock used as LPTIM1 clock */ -#define LL_RCC_LPTIM1_CLKSOURCE_LSI RCC_DCKCFGR2_LPTIM1SEL_1 /*!< HSI oscillator clock used as LPTIM1 clock */ -#define LL_RCC_LPTIM1_CLKSOURCE_LSE (uint32_t)(RCC_DCKCFGR2_LPTIM1SEL_1 | RCC_DCKCFGR2_LPTIM1SEL_0) /*!< LSE oscillator clock used as LPTIM1 clock */ -/** - * @} - */ -#endif /* LPTIM1 */ - -#if defined(SAI1) -/** @defgroup RCC_LL_EC_SAIx_CLKSOURCE Peripheral SAI clock source selection - * @{ - */ -#if defined(RCC_DCKCFGR_SAI1SRC) -#define LL_RCC_SAI1_CLKSOURCE_PLLSAI (uint32_t)(RCC_DCKCFGR_SAI1SRC | 0x00000000U) /*!< PLLSAI clock used as SAI1 clock source */ -#define LL_RCC_SAI1_CLKSOURCE_PLLI2S (uint32_t)(RCC_DCKCFGR_SAI1SRC | (RCC_DCKCFGR_SAI1SRC_0 >> 16)) /*!< PLLI2S clock used as SAI1 clock source */ -#define LL_RCC_SAI1_CLKSOURCE_PLL (uint32_t)(RCC_DCKCFGR_SAI1SRC | (RCC_DCKCFGR_SAI1SRC_1 >> 16)) /*!< PLL clock used as SAI1 clock source */ -#define LL_RCC_SAI1_CLKSOURCE_PIN (uint32_t)(RCC_DCKCFGR_SAI1SRC | (RCC_DCKCFGR_SAI1SRC >> 16)) /*!< External pin clock used as SAI1 clock source */ -#endif /* RCC_DCKCFGR_SAI1SRC */ -#if defined(RCC_DCKCFGR_SAI2SRC) -#define LL_RCC_SAI2_CLKSOURCE_PLLSAI (uint32_t)(RCC_DCKCFGR_SAI2SRC | 0x00000000U) /*!< PLLSAI clock used as SAI2 clock source */ -#define LL_RCC_SAI2_CLKSOURCE_PLLI2S (uint32_t)(RCC_DCKCFGR_SAI2SRC | (RCC_DCKCFGR_SAI2SRC_0 >> 16)) /*!< PLLI2S clock used as SAI2 clock source */ -#define LL_RCC_SAI2_CLKSOURCE_PLL (uint32_t)(RCC_DCKCFGR_SAI2SRC | (RCC_DCKCFGR_SAI2SRC_1 >> 16)) /*!< PLL clock used as SAI2 clock source */ -#define LL_RCC_SAI2_CLKSOURCE_PLLSRC (uint32_t)(RCC_DCKCFGR_SAI2SRC | (RCC_DCKCFGR_SAI2SRC >> 16)) /*!< PLL Main clock used as SAI2 clock source */ -#endif /* RCC_DCKCFGR_SAI2SRC */ -#if defined(RCC_DCKCFGR_SAI1ASRC) -#if defined(RCC_SAI1A_PLLSOURCE_SUPPORT) -#define LL_RCC_SAI1_A_CLKSOURCE_PLLI2S (uint32_t)(RCC_DCKCFGR_SAI1ASRC | 0x00000000U) /*!< PLLI2S clock used as SAI1 block A clock source */ -#define LL_RCC_SAI1_A_CLKSOURCE_PIN (uint32_t)(RCC_DCKCFGR_SAI1ASRC | (RCC_DCKCFGR_SAI1ASRC_0 >> 16)) /*!< External pin used as SAI1 block A clock source */ -#define LL_RCC_SAI1_A_CLKSOURCE_PLL (uint32_t)(RCC_DCKCFGR_SAI1ASRC | (RCC_DCKCFGR_SAI1ASRC_1 >> 16)) /*!< PLL clock used as SAI1 block A clock source */ -#define LL_RCC_SAI1_A_CLKSOURCE_PLLSRC (uint32_t)(RCC_DCKCFGR_SAI1ASRC | (RCC_DCKCFGR_SAI1ASRC >> 16)) /*!< PLL Main clock used as SAI1 block A clock source */ -#else -#define LL_RCC_SAI1_A_CLKSOURCE_PLLSAI (uint32_t)(RCC_DCKCFGR_SAI1ASRC | 0x00000000U) /*!< PLLSAI clock used as SAI1 block A clock source */ -#define LL_RCC_SAI1_A_CLKSOURCE_PLLI2S (uint32_t)(RCC_DCKCFGR_SAI1ASRC | (RCC_DCKCFGR_SAI1ASRC_0 >> 16)) /*!< PLLI2S clock used as SAI1 block A clock source */ -#define LL_RCC_SAI1_A_CLKSOURCE_PIN (uint32_t)(RCC_DCKCFGR_SAI1ASRC | (RCC_DCKCFGR_SAI1ASRC_1 >> 16)) /*!< External pin clock used as SAI1 block A clock source */ -#endif /* RCC_SAI1A_PLLSOURCE_SUPPORT */ -#endif /* RCC_DCKCFGR_SAI1ASRC */ -#if defined(RCC_DCKCFGR_SAI1BSRC) -#if defined(RCC_SAI1B_PLLSOURCE_SUPPORT) -#define LL_RCC_SAI1_B_CLKSOURCE_PLLI2S (uint32_t)(RCC_DCKCFGR_SAI1BSRC | 0x00000000U) /*!< PLLI2S clock used as SAI1 block B clock source */ -#define LL_RCC_SAI1_B_CLKSOURCE_PIN (uint32_t)(RCC_DCKCFGR_SAI1BSRC | (RCC_DCKCFGR_SAI1BSRC_0 >> 16)) /*!< External pin used as SAI1 block B clock source */ -#define LL_RCC_SAI1_B_CLKSOURCE_PLL (uint32_t)(RCC_DCKCFGR_SAI1BSRC | (RCC_DCKCFGR_SAI1BSRC_1 >> 16)) /*!< PLL clock used as SAI1 block B clock source */ -#define LL_RCC_SAI1_B_CLKSOURCE_PLLSRC (uint32_t)(RCC_DCKCFGR_SAI1BSRC | (RCC_DCKCFGR_SAI1BSRC >> 16)) /*!< PLL Main clock used as SAI1 block B clock source */ -#else -#define LL_RCC_SAI1_B_CLKSOURCE_PLLSAI (uint32_t)(RCC_DCKCFGR_SAI1BSRC | 0x00000000U) /*!< PLLSAI clock used as SAI1 block B clock source */ -#define LL_RCC_SAI1_B_CLKSOURCE_PLLI2S (uint32_t)(RCC_DCKCFGR_SAI1BSRC | (RCC_DCKCFGR_SAI1BSRC_0 >> 16)) /*!< PLLI2S clock used as SAI1 block B clock source */ -#define LL_RCC_SAI1_B_CLKSOURCE_PIN (uint32_t)(RCC_DCKCFGR_SAI1BSRC | (RCC_DCKCFGR_SAI1BSRC_1 >> 16)) /*!< External pin clock used as SAI1 block B clock source */ -#endif /* RCC_SAI1B_PLLSOURCE_SUPPORT */ -#endif /* RCC_DCKCFGR_SAI1BSRC */ -/** - * @} - */ -#endif /* SAI1 */ - -#if defined(RCC_DCKCFGR_SDIOSEL) || defined(RCC_DCKCFGR2_SDIOSEL) -/** @defgroup RCC_LL_EC_SDIOx_CLKSOURCE Peripheral SDIO clock source selection - * @{ - */ -#define LL_RCC_SDIO_CLKSOURCE_PLL48CLK 0x00000000U /*!< PLL 48M domain clock used as SDIO clock */ -#if defined(RCC_DCKCFGR_SDIOSEL) -#define LL_RCC_SDIO_CLKSOURCE_SYSCLK RCC_DCKCFGR_SDIOSEL /*!< System clock clock used as SDIO clock */ -#else -#define LL_RCC_SDIO_CLKSOURCE_SYSCLK RCC_DCKCFGR2_SDIOSEL /*!< System clock clock used as SDIO clock */ -#endif /* RCC_DCKCFGR_SDIOSEL */ -/** - * @} - */ -#endif /* RCC_DCKCFGR_SDIOSEL || RCC_DCKCFGR2_SDIOSEL */ - -#if defined(DSI) -/** @defgroup RCC_LL_EC_DSI_CLKSOURCE Peripheral DSI clock source selection - * @{ - */ -#define LL_RCC_DSI_CLKSOURCE_PHY 0x00000000U /*!< DSI-PHY clock used as DSI byte lane clock source */ -#define LL_RCC_DSI_CLKSOURCE_PLL RCC_DCKCFGR_DSISEL /*!< PLL clock used as DSI byte lane clock source */ -/** - * @} - */ -#endif /* DSI */ - -#if defined(CEC) -/** @defgroup RCC_LL_EC_CEC_CLKSOURCE Peripheral CEC clock source selection - * @{ - */ -#define LL_RCC_CEC_CLKSOURCE_HSI_DIV488 0x00000000U /*!< HSI oscillator clock divided by 488 used as CEC clock */ -#define LL_RCC_CEC_CLKSOURCE_LSE RCC_DCKCFGR2_CECSEL /*!< LSE oscillator clock used as CEC clock */ -/** - * @} - */ -#endif /* CEC */ - -/** @defgroup RCC_LL_EC_I2S1_CLKSOURCE Peripheral I2S clock source selection - * @{ - */ -#if defined(RCC_CFGR_I2SSRC) -#define LL_RCC_I2S1_CLKSOURCE_PLLI2S 0x00000000U /*!< I2S oscillator clock used as I2S1 clock */ -#define LL_RCC_I2S1_CLKSOURCE_PIN RCC_CFGR_I2SSRC /*!< External pin clock used as I2S1 clock */ -#endif /* RCC_CFGR_I2SSRC */ -#if defined(RCC_DCKCFGR_I2SSRC) -#define LL_RCC_I2S1_CLKSOURCE_PLL (uint32_t)(RCC_DCKCFGR_I2SSRC | 0x00000000U) /*!< PLL clock used as I2S1 clock source */ -#define LL_RCC_I2S1_CLKSOURCE_PIN (uint32_t)(RCC_DCKCFGR_I2SSRC | (RCC_DCKCFGR_I2SSRC_0 >> 16)) /*!< External pin used as I2S1 clock source */ -#define LL_RCC_I2S1_CLKSOURCE_PLLSRC (uint32_t)(RCC_DCKCFGR_I2SSRC | (RCC_DCKCFGR_I2SSRC_1 >> 16)) /*!< PLL Main clock used as I2S1 clock source */ -#endif /* RCC_DCKCFGR_I2SSRC */ -#if defined(RCC_DCKCFGR_I2S1SRC) -#define LL_RCC_I2S1_CLKSOURCE_PLLI2S (uint32_t)(RCC_DCKCFGR_I2S1SRC | 0x00000000U) /*!< PLLI2S clock used as I2S1 clock source */ -#define LL_RCC_I2S1_CLKSOURCE_PIN (uint32_t)(RCC_DCKCFGR_I2S1SRC | (RCC_DCKCFGR_I2S1SRC_0 >> 16)) /*!< External pin used as I2S1 clock source */ -#define LL_RCC_I2S1_CLKSOURCE_PLL (uint32_t)(RCC_DCKCFGR_I2S1SRC | (RCC_DCKCFGR_I2S1SRC_1 >> 16)) /*!< PLL clock used as I2S1 clock source */ -#define LL_RCC_I2S1_CLKSOURCE_PLLSRC (uint32_t)(RCC_DCKCFGR_I2S1SRC | (RCC_DCKCFGR_I2S1SRC >> 16)) /*!< PLL Main clock used as I2S1 clock source */ -#endif /* RCC_DCKCFGR_I2S1SRC */ -#if defined(RCC_DCKCFGR_I2S2SRC) -#define LL_RCC_I2S2_CLKSOURCE_PLLI2S (uint32_t)(RCC_DCKCFGR_I2S2SRC | 0x00000000U) /*!< PLLI2S clock used as I2S2 clock source */ -#define LL_RCC_I2S2_CLKSOURCE_PIN (uint32_t)(RCC_DCKCFGR_I2S2SRC | (RCC_DCKCFGR_I2S2SRC_0 >> 16)) /*!< External pin used as I2S2 clock source */ -#define LL_RCC_I2S2_CLKSOURCE_PLL (uint32_t)(RCC_DCKCFGR_I2S2SRC | (RCC_DCKCFGR_I2S2SRC_1 >> 16)) /*!< PLL clock used as I2S2 clock source */ -#define LL_RCC_I2S2_CLKSOURCE_PLLSRC (uint32_t)(RCC_DCKCFGR_I2S2SRC | (RCC_DCKCFGR_I2S2SRC >> 16)) /*!< PLL Main clock used as I2S2 clock source */ -#endif /* RCC_DCKCFGR_I2S2SRC */ -/** - * @} - */ - -#if defined(RCC_DCKCFGR_CK48MSEL) || defined(RCC_DCKCFGR2_CK48MSEL) -/** @defgroup RCC_LL_EC_CK48M_CLKSOURCE Peripheral 48Mhz domain clock source selection - * @{ - */ -#if defined(RCC_DCKCFGR_CK48MSEL) -#define LL_RCC_CK48M_CLKSOURCE_PLL 0x00000000U /*!< PLL oscillator clock used as 48Mhz domain clock */ -#define LL_RCC_CK48M_CLKSOURCE_PLLSAI RCC_DCKCFGR_CK48MSEL /*!< PLLSAI oscillator clock used as 48Mhz domain clock */ -#endif /* RCC_DCKCFGR_CK48MSEL */ -#if defined(RCC_DCKCFGR2_CK48MSEL) -#define LL_RCC_CK48M_CLKSOURCE_PLL 0x00000000U /*!< PLL oscillator clock used as 48Mhz domain clock */ -#if defined(RCC_PLLSAI_SUPPORT) -#define LL_RCC_CK48M_CLKSOURCE_PLLSAI RCC_DCKCFGR2_CK48MSEL /*!< PLLSAI oscillator clock used as 48Mhz domain clock */ -#endif /* RCC_PLLSAI_SUPPORT */ -#if defined(RCC_PLLI2SCFGR_PLLI2SQ) && !defined(RCC_DCKCFGR_PLLI2SDIVQ) -#define LL_RCC_CK48M_CLKSOURCE_PLLI2S RCC_DCKCFGR2_CK48MSEL /*!< PLLI2S oscillator clock used as 48Mhz domain clock */ -#endif /* RCC_PLLI2SCFGR_PLLI2SQ && !RCC_DCKCFGR_PLLI2SDIVQ */ -#endif /* RCC_DCKCFGR2_CK48MSEL */ -/** - * @} - */ - -#if defined(RNG) -/** @defgroup RCC_LL_EC_RNG_CLKSOURCE Peripheral RNG clock source selection - * @{ - */ -#define LL_RCC_RNG_CLKSOURCE_PLL LL_RCC_CK48M_CLKSOURCE_PLL /*!< PLL clock used as RNG clock source */ -#if defined(RCC_PLLSAI_SUPPORT) -#define LL_RCC_RNG_CLKSOURCE_PLLSAI LL_RCC_CK48M_CLKSOURCE_PLLSAI /*!< PLLSAI clock used as RNG clock source */ -#endif /* RCC_PLLSAI_SUPPORT */ -#if defined(RCC_PLLI2SCFGR_PLLI2SQ) && !defined(RCC_DCKCFGR_PLLI2SDIVQ) -#define LL_RCC_RNG_CLKSOURCE_PLLI2S LL_RCC_CK48M_CLKSOURCE_PLLI2S /*!< PLLI2S clock used as RNG clock source */ -#endif /* RCC_PLLI2SCFGR_PLLI2SQ && !RCC_DCKCFGR_PLLI2SDIVQ */ -/** - * @} - */ -#endif /* RNG */ - -#if defined(USB_OTG_FS) || defined(USB_OTG_HS) -/** @defgroup RCC_LL_EC_USB_CLKSOURCE Peripheral USB clock source selection - * @{ - */ -#define LL_RCC_USB_CLKSOURCE_PLL LL_RCC_CK48M_CLKSOURCE_PLL /*!< PLL clock used as USB clock source */ -#if defined(RCC_PLLSAI_SUPPORT) -#define LL_RCC_USB_CLKSOURCE_PLLSAI LL_RCC_CK48M_CLKSOURCE_PLLSAI /*!< PLLSAI clock used as USB clock source */ -#endif /* RCC_PLLSAI_SUPPORT */ -#if defined(RCC_PLLI2SCFGR_PLLI2SQ) && !defined(RCC_DCKCFGR_PLLI2SDIVQ) -#define LL_RCC_USB_CLKSOURCE_PLLI2S LL_RCC_CK48M_CLKSOURCE_PLLI2S /*!< PLLI2S clock used as USB clock source */ -#endif /* RCC_PLLI2SCFGR_PLLI2SQ && !RCC_DCKCFGR_PLLI2SDIVQ */ -/** - * @} - */ -#endif /* USB_OTG_FS || USB_OTG_HS */ - -#endif /* RCC_DCKCFGR_CK48MSEL || RCC_DCKCFGR2_CK48MSEL */ - -#if defined(DFSDM1_Channel0) || defined(DFSDM2_Channel0) -/** @defgroup RCC_LL_EC_DFSDM1_AUDIO_CLKSOURCE Peripheral DFSDM Audio clock source selection - * @{ - */ -#define LL_RCC_DFSDM1_AUDIO_CLKSOURCE_I2S1 (uint32_t)(RCC_DCKCFGR_CKDFSDM1ASEL | 0x00000000U) /*!< I2S1 clock used as DFSDM1 Audio clock source */ -#define LL_RCC_DFSDM1_AUDIO_CLKSOURCE_I2S2 (uint32_t)(RCC_DCKCFGR_CKDFSDM1ASEL | (RCC_DCKCFGR_CKDFSDM1ASEL << 16)) /*!< I2S2 clock used as DFSDM1 Audio clock source */ -#if defined(DFSDM2_Channel0) -#define LL_RCC_DFSDM2_AUDIO_CLKSOURCE_I2S1 (uint32_t)(RCC_DCKCFGR_CKDFSDM2ASEL | 0x00000000U) /*!< I2S1 clock used as DFSDM2 Audio clock source */ -#define LL_RCC_DFSDM2_AUDIO_CLKSOURCE_I2S2 (uint32_t)(RCC_DCKCFGR_CKDFSDM2ASEL | (RCC_DCKCFGR_CKDFSDM2ASEL << 16)) /*!< I2S2 clock used as DFSDM2 Audio clock source */ -#endif /* DFSDM2_Channel0 */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_DFSDM1_CLKSOURCE Peripheral DFSDM clock source selection - * @{ - */ -#define LL_RCC_DFSDM1_CLKSOURCE_PCLK2 0x00000000U /*!< PCLK2 clock used as DFSDM1 clock */ -#define LL_RCC_DFSDM1_CLKSOURCE_SYSCLK RCC_DCKCFGR_CKDFSDM1SEL /*!< System clock used as DFSDM1 clock */ -#if defined(DFSDM2_Channel0) -#define LL_RCC_DFSDM2_CLKSOURCE_PCLK2 0x00000000U /*!< PCLK2 clock used as DFSDM2 clock */ -#define LL_RCC_DFSDM2_CLKSOURCE_SYSCLK RCC_DCKCFGR_CKDFSDM1SEL /*!< System clock used as DFSDM2 clock */ -#endif /* DFSDM2_Channel0 */ -/** - * @} - */ -#endif /* DFSDM1_Channel0 || DFSDM2_Channel0 */ - -#if defined(FMPI2C1) -/** @defgroup RCC_LL_EC_FMPI2C1 Peripheral FMPI2C get clock source - * @{ - */ -#define LL_RCC_FMPI2C1_CLKSOURCE RCC_DCKCFGR2_FMPI2C1SEL /*!< FMPI2C1 Clock source selection */ -/** - * @} - */ -#endif /* FMPI2C1 */ - -#if defined(SPDIFRX) -/** @defgroup RCC_LL_EC_SPDIFRX_CLKSOURCE Peripheral SPDIFRX clock source selection - * @{ - */ -#define LL_RCC_SPDIFRX1_CLKSOURCE_PLL 0x00000000U /*!< PLL clock used as SPDIFRX clock source */ -#define LL_RCC_SPDIFRX1_CLKSOURCE_PLLI2S RCC_DCKCFGR2_SPDIFRXSEL /*!< PLLI2S clock used as SPDIFRX clock source */ -/** - * @} - */ -#endif /* SPDIFRX */ - -#if defined(LPTIM1) -/** @defgroup RCC_LL_EC_LPTIM1 Peripheral LPTIM get clock source - * @{ - */ -#define LL_RCC_LPTIM1_CLKSOURCE RCC_DCKCFGR2_LPTIM1SEL /*!< LPTIM1 Clock source selection */ -/** - * @} - */ -#endif /* LPTIM1 */ - -#if defined(SAI1) -/** @defgroup RCC_LL_EC_SAIx Peripheral SAI get clock source - * @{ - */ -#if defined(RCC_DCKCFGR_SAI1ASRC) -#define LL_RCC_SAI1_A_CLKSOURCE RCC_DCKCFGR_SAI1ASRC /*!< SAI1 block A Clock source selection */ -#endif /* RCC_DCKCFGR_SAI1ASRC */ -#if defined(RCC_DCKCFGR_SAI1BSRC) -#define LL_RCC_SAI1_B_CLKSOURCE RCC_DCKCFGR_SAI1BSRC /*!< SAI1 block B Clock source selection */ -#endif /* RCC_DCKCFGR_SAI1BSRC */ -#if defined(RCC_DCKCFGR_SAI1SRC) -#define LL_RCC_SAI1_CLKSOURCE RCC_DCKCFGR_SAI1SRC /*!< SAI1 Clock source selection */ -#endif /* RCC_DCKCFGR_SAI1SRC */ -#if defined(RCC_DCKCFGR_SAI2SRC) -#define LL_RCC_SAI2_CLKSOURCE RCC_DCKCFGR_SAI2SRC /*!< SAI2 Clock source selection */ -#endif /* RCC_DCKCFGR_SAI2SRC */ -/** - * @} - */ -#endif /* SAI1 */ - -#if defined(SDIO) -/** @defgroup RCC_LL_EC_SDIOx Peripheral SDIO get clock source - * @{ - */ -#if defined(RCC_DCKCFGR_SDIOSEL) -#define LL_RCC_SDIO_CLKSOURCE RCC_DCKCFGR_SDIOSEL /*!< SDIO Clock source selection */ -#elif defined(RCC_DCKCFGR2_SDIOSEL) -#define LL_RCC_SDIO_CLKSOURCE RCC_DCKCFGR2_SDIOSEL /*!< SDIO Clock source selection */ -#else -#define LL_RCC_SDIO_CLKSOURCE RCC_PLLCFGR_PLLQ /*!< SDIO Clock source selection */ -#endif -/** - * @} - */ -#endif /* SDIO */ - -#if defined(RCC_DCKCFGR_CK48MSEL) || defined(RCC_DCKCFGR2_CK48MSEL) -/** @defgroup RCC_LL_EC_CK48M Peripheral CK48M get clock source - * @{ - */ -#if defined(RCC_DCKCFGR_CK48MSEL) -#define LL_RCC_CK48M_CLKSOURCE RCC_DCKCFGR_CK48MSEL /*!< CK48M Domain clock source selection */ -#endif /* RCC_DCKCFGR_CK48MSEL */ -#if defined(RCC_DCKCFGR2_CK48MSEL) -#define LL_RCC_CK48M_CLKSOURCE RCC_DCKCFGR2_CK48MSEL /*!< CK48M Domain clock source selection */ -#endif /* RCC_DCKCFGR_CK48MSEL */ -/** - * @} - */ -#endif /* RCC_DCKCFGR_CK48MSEL || RCC_DCKCFGR2_CK48MSEL */ - -#if defined(RNG) -/** @defgroup RCC_LL_EC_RNG Peripheral RNG get clock source - * @{ - */ -#if defined(RCC_DCKCFGR_CK48MSEL) || defined(RCC_DCKCFGR2_CK48MSEL) -#define LL_RCC_RNG_CLKSOURCE LL_RCC_CK48M_CLKSOURCE /*!< RNG Clock source selection */ -#else -#define LL_RCC_RNG_CLKSOURCE RCC_PLLCFGR_PLLQ /*!< RNG Clock source selection */ -#endif /* RCC_DCKCFGR_CK48MSEL || RCC_DCKCFGR2_CK48MSEL */ -/** - * @} - */ -#endif /* RNG */ - -#if defined(USB_OTG_FS) || defined(USB_OTG_HS) -/** @defgroup RCC_LL_EC_USB Peripheral USB get clock source - * @{ - */ -#if defined(RCC_DCKCFGR_CK48MSEL) || defined(RCC_DCKCFGR2_CK48MSEL) -#define LL_RCC_USB_CLKSOURCE LL_RCC_CK48M_CLKSOURCE /*!< USB Clock source selection */ -#else -#define LL_RCC_USB_CLKSOURCE RCC_PLLCFGR_PLLQ /*!< USB Clock source selection */ -#endif /* RCC_DCKCFGR_CK48MSEL || RCC_DCKCFGR2_CK48MSEL */ -/** - * @} - */ -#endif /* USB_OTG_FS || USB_OTG_HS */ - -#if defined(CEC) -/** @defgroup RCC_LL_EC_CEC Peripheral CEC get clock source - * @{ - */ -#define LL_RCC_CEC_CLKSOURCE RCC_DCKCFGR2_CECSEL /*!< CEC Clock source selection */ -/** - * @} - */ -#endif /* CEC */ - -/** @defgroup RCC_LL_EC_I2S1 Peripheral I2S get clock source - * @{ - */ -#if defined(RCC_CFGR_I2SSRC) -#define LL_RCC_I2S1_CLKSOURCE RCC_CFGR_I2SSRC /*!< I2S1 Clock source selection */ -#endif /* RCC_CFGR_I2SSRC */ -#if defined(RCC_DCKCFGR_I2SSRC) -#define LL_RCC_I2S1_CLKSOURCE RCC_DCKCFGR_I2SSRC /*!< I2S1 Clock source selection */ -#endif /* RCC_DCKCFGR_I2SSRC */ -#if defined(RCC_DCKCFGR_I2S1SRC) -#define LL_RCC_I2S1_CLKSOURCE RCC_DCKCFGR_I2S1SRC /*!< I2S1 Clock source selection */ -#endif /* RCC_DCKCFGR_I2S1SRC */ -#if defined(RCC_DCKCFGR_I2S2SRC) -#define LL_RCC_I2S2_CLKSOURCE RCC_DCKCFGR_I2S2SRC /*!< I2S2 Clock source selection */ -#endif /* RCC_DCKCFGR_I2S2SRC */ -/** - * @} - */ - -#if defined(DFSDM1_Channel0) || defined(DFSDM2_Channel0) -/** @defgroup RCC_LL_EC_DFSDM_AUDIO Peripheral DFSDM Audio get clock source - * @{ - */ -#define LL_RCC_DFSDM1_AUDIO_CLKSOURCE RCC_DCKCFGR_CKDFSDM1ASEL /*!< DFSDM1 Audio Clock source selection */ -#if defined(DFSDM2_Channel0) -#define LL_RCC_DFSDM2_AUDIO_CLKSOURCE RCC_DCKCFGR_CKDFSDM2ASEL /*!< DFSDM2 Audio Clock source selection */ -#endif /* DFSDM2_Channel0 */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_DFSDM Peripheral DFSDM get clock source - * @{ - */ -#define LL_RCC_DFSDM1_CLKSOURCE RCC_DCKCFGR_CKDFSDM1SEL /*!< DFSDM1 Clock source selection */ -#if defined(DFSDM2_Channel0) -#define LL_RCC_DFSDM2_CLKSOURCE RCC_DCKCFGR_CKDFSDM1SEL /*!< DFSDM2 Clock source selection */ -#endif /* DFSDM2_Channel0 */ -/** - * @} - */ -#endif /* DFSDM1_Channel0 || DFSDM2_Channel0 */ - -#if defined(SPDIFRX) -/** @defgroup RCC_LL_EC_SPDIFRX Peripheral SPDIFRX get clock source - * @{ - */ -#define LL_RCC_SPDIFRX1_CLKSOURCE RCC_DCKCFGR2_SPDIFRXSEL /*!< SPDIFRX Clock source selection */ -/** - * @} - */ -#endif /* SPDIFRX */ - -#if defined(DSI) -/** @defgroup RCC_LL_EC_DSI Peripheral DSI get clock source - * @{ - */ -#define LL_RCC_DSI_CLKSOURCE RCC_DCKCFGR_DSISEL /*!< DSI Clock source selection */ -/** - * @} - */ -#endif /* DSI */ - -#if defined(LTDC) -/** @defgroup RCC_LL_EC_LTDC Peripheral LTDC get clock source - * @{ - */ -#define LL_RCC_LTDC_CLKSOURCE RCC_DCKCFGR_PLLSAIDIVR /*!< LTDC Clock source selection */ -/** - * @} - */ -#endif /* LTDC */ - - -/** @defgroup RCC_LL_EC_RTC_CLKSOURCE RTC clock source selection - * @{ - */ -#define LL_RCC_RTC_CLKSOURCE_NONE 0x00000000U /*!< No clock used as RTC clock */ -#define LL_RCC_RTC_CLKSOURCE_LSE RCC_BDCR_RTCSEL_0 /*!< LSE oscillator clock used as RTC clock */ -#define LL_RCC_RTC_CLKSOURCE_LSI RCC_BDCR_RTCSEL_1 /*!< LSI oscillator clock used as RTC clock */ -#define LL_RCC_RTC_CLKSOURCE_HSE RCC_BDCR_RTCSEL /*!< HSE oscillator clock divided by HSE prescaler used as RTC clock */ -/** - * @} - */ - -#if defined(RCC_DCKCFGR_TIMPRE) -/** @defgroup RCC_LL_EC_TIM_CLKPRESCALER Timers clocks prescalers selection - * @{ - */ -#define LL_RCC_TIM_PRESCALER_TWICE 0x00000000U /*!< Timers clock to twice PCLK */ -#define LL_RCC_TIM_PRESCALER_FOUR_TIMES RCC_DCKCFGR_TIMPRE /*!< Timers clock to four time PCLK */ -/** - * @} - */ -#endif /* RCC_DCKCFGR_TIMPRE */ - -/** @defgroup RCC_LL_EC_PLLSOURCE PLL, PLLI2S and PLLSAI entry clock source - * @{ - */ -#define LL_RCC_PLLSOURCE_HSI RCC_PLLCFGR_PLLSRC_HSI /*!< HSI16 clock selected as PLL entry clock source */ -#define LL_RCC_PLLSOURCE_HSE RCC_PLLCFGR_PLLSRC_HSE /*!< HSE clock selected as PLL entry clock source */ -#if defined(RCC_PLLI2SCFGR_PLLI2SSRC) -#define LL_RCC_PLLI2SSOURCE_PIN (RCC_PLLI2SCFGR_PLLI2SSRC | 0x80U) /*!< I2S External pin input clock selected as PLLI2S entry clock source */ -#endif /* RCC_PLLI2SCFGR_PLLI2SSRC */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_PLLM_DIV PLL, PLLI2S and PLLSAI division factor - * @{ - */ -#define LL_RCC_PLLM_DIV_2 (RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 2 */ -#define LL_RCC_PLLM_DIV_3 (RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 3 */ -#define LL_RCC_PLLM_DIV_4 (RCC_PLLCFGR_PLLM_2) /*!< PLL, PLLI2S and PLLSAI division factor by 4 */ -#define LL_RCC_PLLM_DIV_5 (RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 5 */ -#define LL_RCC_PLLM_DIV_6 (RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 6 */ -#define LL_RCC_PLLM_DIV_7 (RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 7 */ -#define LL_RCC_PLLM_DIV_8 (RCC_PLLCFGR_PLLM_3) /*!< PLL, PLLI2S and PLLSAI division factor by 8 */ -#define LL_RCC_PLLM_DIV_9 (RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 9 */ -#define LL_RCC_PLLM_DIV_10 (RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 10 */ -#define LL_RCC_PLLM_DIV_11 (RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 11 */ -#define LL_RCC_PLLM_DIV_12 (RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2) /*!< PLL, PLLI2S and PLLSAI division factor by 12 */ -#define LL_RCC_PLLM_DIV_13 (RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 13 */ -#define LL_RCC_PLLM_DIV_14 (RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 14 */ -#define LL_RCC_PLLM_DIV_15 (RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 15 */ -#define LL_RCC_PLLM_DIV_16 (RCC_PLLCFGR_PLLM_4) /*!< PLL, PLLI2S and PLLSAI division factor by 16 */ -#define LL_RCC_PLLM_DIV_17 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 17 */ -#define LL_RCC_PLLM_DIV_18 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 18 */ -#define LL_RCC_PLLM_DIV_19 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 19 */ -#define LL_RCC_PLLM_DIV_20 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_2) /*!< PLL, PLLI2S and PLLSAI division factor by 20 */ -#define LL_RCC_PLLM_DIV_21 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 21 */ -#define LL_RCC_PLLM_DIV_22 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 22 */ -#define LL_RCC_PLLM_DIV_23 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 23 */ -#define LL_RCC_PLLM_DIV_24 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3) /*!< PLL, PLLI2S and PLLSAI division factor by 24 */ -#define LL_RCC_PLLM_DIV_25 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 25 */ -#define LL_RCC_PLLM_DIV_26 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 26 */ -#define LL_RCC_PLLM_DIV_27 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 27 */ -#define LL_RCC_PLLM_DIV_28 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2) /*!< PLL, PLLI2S and PLLSAI division factor by 28 */ -#define LL_RCC_PLLM_DIV_29 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 29 */ -#define LL_RCC_PLLM_DIV_30 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 30 */ -#define LL_RCC_PLLM_DIV_31 (RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 31 */ -#define LL_RCC_PLLM_DIV_32 (RCC_PLLCFGR_PLLM_5) /*!< PLL, PLLI2S and PLLSAI division factor by 32 */ -#define LL_RCC_PLLM_DIV_33 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 33 */ -#define LL_RCC_PLLM_DIV_34 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 34 */ -#define LL_RCC_PLLM_DIV_35 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 35 */ -#define LL_RCC_PLLM_DIV_36 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_2) /*!< PLL, PLLI2S and PLLSAI division factor by 36 */ -#define LL_RCC_PLLM_DIV_37 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 37 */ -#define LL_RCC_PLLM_DIV_38 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 38 */ -#define LL_RCC_PLLM_DIV_39 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 39 */ -#define LL_RCC_PLLM_DIV_40 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_3) /*!< PLL, PLLI2S and PLLSAI division factor by 40 */ -#define LL_RCC_PLLM_DIV_41 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 41 */ -#define LL_RCC_PLLM_DIV_42 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 42 */ -#define LL_RCC_PLLM_DIV_43 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 43 */ -#define LL_RCC_PLLM_DIV_44 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2) /*!< PLL, PLLI2S and PLLSAI division factor by 44 */ -#define LL_RCC_PLLM_DIV_45 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 45 */ -#define LL_RCC_PLLM_DIV_46 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 46 */ -#define LL_RCC_PLLM_DIV_47 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 47 */ -#define LL_RCC_PLLM_DIV_48 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4) /*!< PLL, PLLI2S and PLLSAI division factor by 48 */ -#define LL_RCC_PLLM_DIV_49 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 49 */ -#define LL_RCC_PLLM_DIV_50 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 50 */ -#define LL_RCC_PLLM_DIV_51 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 51 */ -#define LL_RCC_PLLM_DIV_52 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_2) /*!< PLL, PLLI2S and PLLSAI division factor by 52 */ -#define LL_RCC_PLLM_DIV_53 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 53 */ -#define LL_RCC_PLLM_DIV_54 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 54 */ -#define LL_RCC_PLLM_DIV_55 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 55 */ -#define LL_RCC_PLLM_DIV_56 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3) /*!< PLL, PLLI2S and PLLSAI division factor by 56 */ -#define LL_RCC_PLLM_DIV_57 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 57 */ -#define LL_RCC_PLLM_DIV_58 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 58 */ -#define LL_RCC_PLLM_DIV_59 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 59 */ -#define LL_RCC_PLLM_DIV_60 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2) /*!< PLL, PLLI2S and PLLSAI division factor by 60 */ -#define LL_RCC_PLLM_DIV_61 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 61 */ -#define LL_RCC_PLLM_DIV_62 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1) /*!< PLL, PLLI2S and PLLSAI division factor by 62 */ -#define LL_RCC_PLLM_DIV_63 (RCC_PLLCFGR_PLLM_5 | RCC_PLLCFGR_PLLM_4 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLM_2 | RCC_PLLCFGR_PLLM_1 | RCC_PLLCFGR_PLLM_0) /*!< PLL, PLLI2S and PLLSAI division factor by 63 */ -/** - * @} - */ - -#if defined(RCC_PLLCFGR_PLLR) -/** @defgroup RCC_LL_EC_PLLR_DIV PLL division factor (PLLR) - * @{ - */ -#define LL_RCC_PLLR_DIV_2 (RCC_PLLCFGR_PLLR_1) /*!< Main PLL division factor for PLLCLK (system clock) by 2 */ -#define LL_RCC_PLLR_DIV_3 (RCC_PLLCFGR_PLLR_1|RCC_PLLCFGR_PLLR_0) /*!< Main PLL division factor for PLLCLK (system clock) by 3 */ -#define LL_RCC_PLLR_DIV_4 (RCC_PLLCFGR_PLLR_2) /*!< Main PLL division factor for PLLCLK (system clock) by 4 */ -#define LL_RCC_PLLR_DIV_5 (RCC_PLLCFGR_PLLR_2|RCC_PLLCFGR_PLLR_0) /*!< Main PLL division factor for PLLCLK (system clock) by 5 */ -#define LL_RCC_PLLR_DIV_6 (RCC_PLLCFGR_PLLR_2|RCC_PLLCFGR_PLLR_1) /*!< Main PLL division factor for PLLCLK (system clock) by 6 */ -#define LL_RCC_PLLR_DIV_7 (RCC_PLLCFGR_PLLR) /*!< Main PLL division factor for PLLCLK (system clock) by 7 */ -/** - * @} - */ -#endif /* RCC_PLLCFGR_PLLR */ - -#if defined(RCC_DCKCFGR_PLLDIVR) -/** @defgroup RCC_LL_EC_PLLDIVR PLLDIVR division factor (PLLDIVR) - * @{ - */ -#define LL_RCC_PLLDIVR_DIV_1 (RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 1 */ -#define LL_RCC_PLLDIVR_DIV_2 (RCC_DCKCFGR_PLLDIVR_1) /*!< PLL division factor for PLLDIVR output by 2 */ -#define LL_RCC_PLLDIVR_DIV_3 (RCC_DCKCFGR_PLLDIVR_1 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 3 */ -#define LL_RCC_PLLDIVR_DIV_4 (RCC_DCKCFGR_PLLDIVR_2) /*!< PLL division factor for PLLDIVR output by 4 */ -#define LL_RCC_PLLDIVR_DIV_5 (RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 5 */ -#define LL_RCC_PLLDIVR_DIV_6 (RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_1) /*!< PLL division factor for PLLDIVR output by 6 */ -#define LL_RCC_PLLDIVR_DIV_7 (RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_1 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 7 */ -#define LL_RCC_PLLDIVR_DIV_8 (RCC_DCKCFGR_PLLDIVR_3) /*!< PLL division factor for PLLDIVR output by 8 */ -#define LL_RCC_PLLDIVR_DIV_9 (RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 9 */ -#define LL_RCC_PLLDIVR_DIV_10 (RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_1) /*!< PLL division factor for PLLDIVR output by 10 */ -#define LL_RCC_PLLDIVR_DIV_11 (RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_1 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 11 */ -#define LL_RCC_PLLDIVR_DIV_12 (RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_2) /*!< PLL division factor for PLLDIVR output by 12 */ -#define LL_RCC_PLLDIVR_DIV_13 (RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 13 */ -#define LL_RCC_PLLDIVR_DIV_14 (RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_1) /*!< PLL division factor for PLLDIVR output by 14 */ -#define LL_RCC_PLLDIVR_DIV_15 (RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_1 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 15 */ -#define LL_RCC_PLLDIVR_DIV_16 (RCC_DCKCFGR_PLLDIVR_4) /*!< PLL division factor for PLLDIVR output by 16 */ -#define LL_RCC_PLLDIVR_DIV_17 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 17 */ -#define LL_RCC_PLLDIVR_DIV_18 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_1) /*!< PLL division factor for PLLDIVR output by 18 */ -#define LL_RCC_PLLDIVR_DIV_19 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_1 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 19 */ -#define LL_RCC_PLLDIVR_DIV_20 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_2) /*!< PLL division factor for PLLDIVR output by 20 */ -#define LL_RCC_PLLDIVR_DIV_21 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 21 */ -#define LL_RCC_PLLDIVR_DIV_22 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_1) /*!< PLL division factor for PLLDIVR output by 22 */ -#define LL_RCC_PLLDIVR_DIV_23 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_1 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 23 */ -#define LL_RCC_PLLDIVR_DIV_24 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_3) /*!< PLL division factor for PLLDIVR output by 24 */ -#define LL_RCC_PLLDIVR_DIV_25 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 25 */ -#define LL_RCC_PLLDIVR_DIV_26 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_1) /*!< PLL division factor for PLLDIVR output by 26 */ -#define LL_RCC_PLLDIVR_DIV_27 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_1 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 27 */ -#define LL_RCC_PLLDIVR_DIV_28 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_2) /*!< PLL division factor for PLLDIVR output by 28 */ -#define LL_RCC_PLLDIVR_DIV_29 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 29 */ -#define LL_RCC_PLLDIVR_DIV_30 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_1) /*!< PLL division factor for PLLDIVR output by 30 */ -#define LL_RCC_PLLDIVR_DIV_31 (RCC_DCKCFGR_PLLDIVR_4 | RCC_DCKCFGR_PLLDIVR_3 | RCC_DCKCFGR_PLLDIVR_2 | RCC_DCKCFGR_PLLDIVR_1 | RCC_DCKCFGR_PLLDIVR_0) /*!< PLL division factor for PLLDIVR output by 31 */ -/** - * @} - */ -#endif /* RCC_DCKCFGR_PLLDIVR */ - -/** @defgroup RCC_LL_EC_PLLP_DIV PLL division factor (PLLP) - * @{ - */ -#define LL_RCC_PLLP_DIV_2 0x00000000U /*!< Main PLL division factor for PLLP output by 2 */ -#define LL_RCC_PLLP_DIV_4 RCC_PLLCFGR_PLLP_0 /*!< Main PLL division factor for PLLP output by 4 */ -#define LL_RCC_PLLP_DIV_6 RCC_PLLCFGR_PLLP_1 /*!< Main PLL division factor for PLLP output by 6 */ -#define LL_RCC_PLLP_DIV_8 (RCC_PLLCFGR_PLLP_1 | RCC_PLLCFGR_PLLP_0) /*!< Main PLL division factor for PLLP output by 8 */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_PLLQ_DIV PLL division factor (PLLQ) - * @{ - */ -#define LL_RCC_PLLQ_DIV_2 RCC_PLLCFGR_PLLQ_1 /*!< Main PLL division factor for PLLQ output by 2 */ -#define LL_RCC_PLLQ_DIV_3 (RCC_PLLCFGR_PLLQ_1|RCC_PLLCFGR_PLLQ_0) /*!< Main PLL division factor for PLLQ output by 3 */ -#define LL_RCC_PLLQ_DIV_4 RCC_PLLCFGR_PLLQ_2 /*!< Main PLL division factor for PLLQ output by 4 */ -#define LL_RCC_PLLQ_DIV_5 (RCC_PLLCFGR_PLLQ_2|RCC_PLLCFGR_PLLQ_0) /*!< Main PLL division factor for PLLQ output by 5 */ -#define LL_RCC_PLLQ_DIV_6 (RCC_PLLCFGR_PLLQ_2|RCC_PLLCFGR_PLLQ_1) /*!< Main PLL division factor for PLLQ output by 6 */ -#define LL_RCC_PLLQ_DIV_7 (RCC_PLLCFGR_PLLQ_2|RCC_PLLCFGR_PLLQ_1|RCC_PLLCFGR_PLLQ_0) /*!< Main PLL division factor for PLLQ output by 7 */ -#define LL_RCC_PLLQ_DIV_8 RCC_PLLCFGR_PLLQ_3 /*!< Main PLL division factor for PLLQ output by 8 */ -#define LL_RCC_PLLQ_DIV_9 (RCC_PLLCFGR_PLLQ_3|RCC_PLLCFGR_PLLQ_0) /*!< Main PLL division factor for PLLQ output by 9 */ -#define LL_RCC_PLLQ_DIV_10 (RCC_PLLCFGR_PLLQ_3|RCC_PLLCFGR_PLLQ_1) /*!< Main PLL division factor for PLLQ output by 10 */ -#define LL_RCC_PLLQ_DIV_11 (RCC_PLLCFGR_PLLQ_3|RCC_PLLCFGR_PLLQ_1|RCC_PLLCFGR_PLLQ_0) /*!< Main PLL division factor for PLLQ output by 11 */ -#define LL_RCC_PLLQ_DIV_12 (RCC_PLLCFGR_PLLQ_3|RCC_PLLCFGR_PLLQ_2) /*!< Main PLL division factor for PLLQ output by 12 */ -#define LL_RCC_PLLQ_DIV_13 (RCC_PLLCFGR_PLLQ_3|RCC_PLLCFGR_PLLQ_2|RCC_PLLCFGR_PLLQ_0) /*!< Main PLL division factor for PLLQ output by 13 */ -#define LL_RCC_PLLQ_DIV_14 (RCC_PLLCFGR_PLLQ_3|RCC_PLLCFGR_PLLQ_2|RCC_PLLCFGR_PLLQ_1) /*!< Main PLL division factor for PLLQ output by 14 */ -#define LL_RCC_PLLQ_DIV_15 (RCC_PLLCFGR_PLLQ_3|RCC_PLLCFGR_PLLQ_2|RCC_PLLCFGR_PLLQ_1|RCC_PLLCFGR_PLLQ_0) /*!< Main PLL division factor for PLLQ output by 15 */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_PLL_SPRE_SEL PLL Spread Spectrum Selection - * @{ - */ -#define LL_RCC_SPREAD_SELECT_CENTER 0x00000000U /*!< PLL center spread spectrum selection */ -#define LL_RCC_SPREAD_SELECT_DOWN RCC_SSCGR_SPREADSEL /*!< PLL down spread spectrum selection */ -/** - * @} - */ - -#if defined(RCC_PLLI2S_SUPPORT) -/** @defgroup RCC_LL_EC_PLLI2SM PLLI2SM division factor (PLLI2SM) - * @{ - */ -#if defined(RCC_PLLI2SCFGR_PLLI2SM) -#define LL_RCC_PLLI2SM_DIV_2 (RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 2 */ -#define LL_RCC_PLLI2SM_DIV_3 (RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 3 */ -#define LL_RCC_PLLI2SM_DIV_4 (RCC_PLLI2SCFGR_PLLI2SM_2) /*!< PLLI2S division factor for PLLI2SM output by 4 */ -#define LL_RCC_PLLI2SM_DIV_5 (RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 5 */ -#define LL_RCC_PLLI2SM_DIV_6 (RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 6 */ -#define LL_RCC_PLLI2SM_DIV_7 (RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 7 */ -#define LL_RCC_PLLI2SM_DIV_8 (RCC_PLLI2SCFGR_PLLI2SM_3) /*!< PLLI2S division factor for PLLI2SM output by 8 */ -#define LL_RCC_PLLI2SM_DIV_9 (RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 9 */ -#define LL_RCC_PLLI2SM_DIV_10 (RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 10 */ -#define LL_RCC_PLLI2SM_DIV_11 (RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 11 */ -#define LL_RCC_PLLI2SM_DIV_12 (RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2) /*!< PLLI2S division factor for PLLI2SM output by 12 */ -#define LL_RCC_PLLI2SM_DIV_13 (RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 13 */ -#define LL_RCC_PLLI2SM_DIV_14 (RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 14 */ -#define LL_RCC_PLLI2SM_DIV_15 (RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 15 */ -#define LL_RCC_PLLI2SM_DIV_16 (RCC_PLLI2SCFGR_PLLI2SM_4) /*!< PLLI2S division factor for PLLI2SM output by 16 */ -#define LL_RCC_PLLI2SM_DIV_17 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 17 */ -#define LL_RCC_PLLI2SM_DIV_18 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 18 */ -#define LL_RCC_PLLI2SM_DIV_19 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 19 */ -#define LL_RCC_PLLI2SM_DIV_20 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_2) /*!< PLLI2S division factor for PLLI2SM output by 20 */ -#define LL_RCC_PLLI2SM_DIV_21 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 21 */ -#define LL_RCC_PLLI2SM_DIV_22 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 22 */ -#define LL_RCC_PLLI2SM_DIV_23 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 23 */ -#define LL_RCC_PLLI2SM_DIV_24 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3) /*!< PLLI2S division factor for PLLI2SM output by 24 */ -#define LL_RCC_PLLI2SM_DIV_25 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 25 */ -#define LL_RCC_PLLI2SM_DIV_26 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 26 */ -#define LL_RCC_PLLI2SM_DIV_27 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 27 */ -#define LL_RCC_PLLI2SM_DIV_28 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2) /*!< PLLI2S division factor for PLLI2SM output by 28 */ -#define LL_RCC_PLLI2SM_DIV_29 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 29 */ -#define LL_RCC_PLLI2SM_DIV_30 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 30 */ -#define LL_RCC_PLLI2SM_DIV_31 (RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 31 */ -#define LL_RCC_PLLI2SM_DIV_32 (RCC_PLLI2SCFGR_PLLI2SM_5) /*!< PLLI2S division factor for PLLI2SM output by 32 */ -#define LL_RCC_PLLI2SM_DIV_33 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 33 */ -#define LL_RCC_PLLI2SM_DIV_34 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 34 */ -#define LL_RCC_PLLI2SM_DIV_35 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 35 */ -#define LL_RCC_PLLI2SM_DIV_36 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_2) /*!< PLLI2S division factor for PLLI2SM output by 36 */ -#define LL_RCC_PLLI2SM_DIV_37 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 37 */ -#define LL_RCC_PLLI2SM_DIV_38 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 38 */ -#define LL_RCC_PLLI2SM_DIV_39 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 39 */ -#define LL_RCC_PLLI2SM_DIV_40 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_3) /*!< PLLI2S division factor for PLLI2SM output by 40 */ -#define LL_RCC_PLLI2SM_DIV_41 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 41 */ -#define LL_RCC_PLLI2SM_DIV_42 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 42 */ -#define LL_RCC_PLLI2SM_DIV_43 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 43 */ -#define LL_RCC_PLLI2SM_DIV_44 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2) /*!< PLLI2S division factor for PLLI2SM output by 44 */ -#define LL_RCC_PLLI2SM_DIV_45 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 45 */ -#define LL_RCC_PLLI2SM_DIV_46 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 46 */ -#define LL_RCC_PLLI2SM_DIV_47 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 47 */ -#define LL_RCC_PLLI2SM_DIV_48 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4) /*!< PLLI2S division factor for PLLI2SM output by 48 */ -#define LL_RCC_PLLI2SM_DIV_49 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 49 */ -#define LL_RCC_PLLI2SM_DIV_50 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 50 */ -#define LL_RCC_PLLI2SM_DIV_51 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 51 */ -#define LL_RCC_PLLI2SM_DIV_52 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_2) /*!< PLLI2S division factor for PLLI2SM output by 52 */ -#define LL_RCC_PLLI2SM_DIV_53 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 53 */ -#define LL_RCC_PLLI2SM_DIV_54 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 54 */ -#define LL_RCC_PLLI2SM_DIV_55 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 55 */ -#define LL_RCC_PLLI2SM_DIV_56 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3) /*!< PLLI2S division factor for PLLI2SM output by 56 */ -#define LL_RCC_PLLI2SM_DIV_57 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 57 */ -#define LL_RCC_PLLI2SM_DIV_58 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 58 */ -#define LL_RCC_PLLI2SM_DIV_59 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 59 */ -#define LL_RCC_PLLI2SM_DIV_60 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2) /*!< PLLI2S division factor for PLLI2SM output by 60 */ -#define LL_RCC_PLLI2SM_DIV_61 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 61 */ -#define LL_RCC_PLLI2SM_DIV_62 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1) /*!< PLLI2S division factor for PLLI2SM output by 62 */ -#define LL_RCC_PLLI2SM_DIV_63 (RCC_PLLI2SCFGR_PLLI2SM_5 | RCC_PLLI2SCFGR_PLLI2SM_4 | RCC_PLLI2SCFGR_PLLI2SM_3 | RCC_PLLI2SCFGR_PLLI2SM_2 | RCC_PLLI2SCFGR_PLLI2SM_1 | RCC_PLLI2SCFGR_PLLI2SM_0) /*!< PLLI2S division factor for PLLI2SM output by 63 */ -#else -#define LL_RCC_PLLI2SM_DIV_2 LL_RCC_PLLM_DIV_2 /*!< PLLI2S division factor for PLLI2SM output by 2 */ -#define LL_RCC_PLLI2SM_DIV_3 LL_RCC_PLLM_DIV_3 /*!< PLLI2S division factor for PLLI2SM output by 3 */ -#define LL_RCC_PLLI2SM_DIV_4 LL_RCC_PLLM_DIV_4 /*!< PLLI2S division factor for PLLI2SM output by 4 */ -#define LL_RCC_PLLI2SM_DIV_5 LL_RCC_PLLM_DIV_5 /*!< PLLI2S division factor for PLLI2SM output by 5 */ -#define LL_RCC_PLLI2SM_DIV_6 LL_RCC_PLLM_DIV_6 /*!< PLLI2S division factor for PLLI2SM output by 6 */ -#define LL_RCC_PLLI2SM_DIV_7 LL_RCC_PLLM_DIV_7 /*!< PLLI2S division factor for PLLI2SM output by 7 */ -#define LL_RCC_PLLI2SM_DIV_8 LL_RCC_PLLM_DIV_8 /*!< PLLI2S division factor for PLLI2SM output by 8 */ -#define LL_RCC_PLLI2SM_DIV_9 LL_RCC_PLLM_DIV_9 /*!< PLLI2S division factor for PLLI2SM output by 9 */ -#define LL_RCC_PLLI2SM_DIV_10 LL_RCC_PLLM_DIV_10 /*!< PLLI2S division factor for PLLI2SM output by 10 */ -#define LL_RCC_PLLI2SM_DIV_11 LL_RCC_PLLM_DIV_11 /*!< PLLI2S division factor for PLLI2SM output by 11 */ -#define LL_RCC_PLLI2SM_DIV_12 LL_RCC_PLLM_DIV_12 /*!< PLLI2S division factor for PLLI2SM output by 12 */ -#define LL_RCC_PLLI2SM_DIV_13 LL_RCC_PLLM_DIV_13 /*!< PLLI2S division factor for PLLI2SM output by 13 */ -#define LL_RCC_PLLI2SM_DIV_14 LL_RCC_PLLM_DIV_14 /*!< PLLI2S division factor for PLLI2SM output by 14 */ -#define LL_RCC_PLLI2SM_DIV_15 LL_RCC_PLLM_DIV_15 /*!< PLLI2S division factor for PLLI2SM output by 15 */ -#define LL_RCC_PLLI2SM_DIV_16 LL_RCC_PLLM_DIV_16 /*!< PLLI2S division factor for PLLI2SM output by 16 */ -#define LL_RCC_PLLI2SM_DIV_17 LL_RCC_PLLM_DIV_17 /*!< PLLI2S division factor for PLLI2SM output by 17 */ -#define LL_RCC_PLLI2SM_DIV_18 LL_RCC_PLLM_DIV_18 /*!< PLLI2S division factor for PLLI2SM output by 18 */ -#define LL_RCC_PLLI2SM_DIV_19 LL_RCC_PLLM_DIV_19 /*!< PLLI2S division factor for PLLI2SM output by 19 */ -#define LL_RCC_PLLI2SM_DIV_20 LL_RCC_PLLM_DIV_20 /*!< PLLI2S division factor for PLLI2SM output by 20 */ -#define LL_RCC_PLLI2SM_DIV_21 LL_RCC_PLLM_DIV_21 /*!< PLLI2S division factor for PLLI2SM output by 21 */ -#define LL_RCC_PLLI2SM_DIV_22 LL_RCC_PLLM_DIV_22 /*!< PLLI2S division factor for PLLI2SM output by 22 */ -#define LL_RCC_PLLI2SM_DIV_23 LL_RCC_PLLM_DIV_23 /*!< PLLI2S division factor for PLLI2SM output by 23 */ -#define LL_RCC_PLLI2SM_DIV_24 LL_RCC_PLLM_DIV_24 /*!< PLLI2S division factor for PLLI2SM output by 24 */ -#define LL_RCC_PLLI2SM_DIV_25 LL_RCC_PLLM_DIV_25 /*!< PLLI2S division factor for PLLI2SM output by 25 */ -#define LL_RCC_PLLI2SM_DIV_26 LL_RCC_PLLM_DIV_26 /*!< PLLI2S division factor for PLLI2SM output by 26 */ -#define LL_RCC_PLLI2SM_DIV_27 LL_RCC_PLLM_DIV_27 /*!< PLLI2S division factor for PLLI2SM output by 27 */ -#define LL_RCC_PLLI2SM_DIV_28 LL_RCC_PLLM_DIV_28 /*!< PLLI2S division factor for PLLI2SM output by 28 */ -#define LL_RCC_PLLI2SM_DIV_29 LL_RCC_PLLM_DIV_29 /*!< PLLI2S division factor for PLLI2SM output by 29 */ -#define LL_RCC_PLLI2SM_DIV_30 LL_RCC_PLLM_DIV_30 /*!< PLLI2S division factor for PLLI2SM output by 30 */ -#define LL_RCC_PLLI2SM_DIV_31 LL_RCC_PLLM_DIV_31 /*!< PLLI2S division factor for PLLI2SM output by 31 */ -#define LL_RCC_PLLI2SM_DIV_32 LL_RCC_PLLM_DIV_32 /*!< PLLI2S division factor for PLLI2SM output by 32 */ -#define LL_RCC_PLLI2SM_DIV_33 LL_RCC_PLLM_DIV_33 /*!< PLLI2S division factor for PLLI2SM output by 33 */ -#define LL_RCC_PLLI2SM_DIV_34 LL_RCC_PLLM_DIV_34 /*!< PLLI2S division factor for PLLI2SM output by 34 */ -#define LL_RCC_PLLI2SM_DIV_35 LL_RCC_PLLM_DIV_35 /*!< PLLI2S division factor for PLLI2SM output by 35 */ -#define LL_RCC_PLLI2SM_DIV_36 LL_RCC_PLLM_DIV_36 /*!< PLLI2S division factor for PLLI2SM output by 36 */ -#define LL_RCC_PLLI2SM_DIV_37 LL_RCC_PLLM_DIV_37 /*!< PLLI2S division factor for PLLI2SM output by 37 */ -#define LL_RCC_PLLI2SM_DIV_38 LL_RCC_PLLM_DIV_38 /*!< PLLI2S division factor for PLLI2SM output by 38 */ -#define LL_RCC_PLLI2SM_DIV_39 LL_RCC_PLLM_DIV_39 /*!< PLLI2S division factor for PLLI2SM output by 39 */ -#define LL_RCC_PLLI2SM_DIV_40 LL_RCC_PLLM_DIV_40 /*!< PLLI2S division factor for PLLI2SM output by 40 */ -#define LL_RCC_PLLI2SM_DIV_41 LL_RCC_PLLM_DIV_41 /*!< PLLI2S division factor for PLLI2SM output by 41 */ -#define LL_RCC_PLLI2SM_DIV_42 LL_RCC_PLLM_DIV_42 /*!< PLLI2S division factor for PLLI2SM output by 42 */ -#define LL_RCC_PLLI2SM_DIV_43 LL_RCC_PLLM_DIV_43 /*!< PLLI2S division factor for PLLI2SM output by 43 */ -#define LL_RCC_PLLI2SM_DIV_44 LL_RCC_PLLM_DIV_44 /*!< PLLI2S division factor for PLLI2SM output by 44 */ -#define LL_RCC_PLLI2SM_DIV_45 LL_RCC_PLLM_DIV_45 /*!< PLLI2S division factor for PLLI2SM output by 45 */ -#define LL_RCC_PLLI2SM_DIV_46 LL_RCC_PLLM_DIV_46 /*!< PLLI2S division factor for PLLI2SM output by 46 */ -#define LL_RCC_PLLI2SM_DIV_47 LL_RCC_PLLM_DIV_47 /*!< PLLI2S division factor for PLLI2SM output by 47 */ -#define LL_RCC_PLLI2SM_DIV_48 LL_RCC_PLLM_DIV_48 /*!< PLLI2S division factor for PLLI2SM output by 48 */ -#define LL_RCC_PLLI2SM_DIV_49 LL_RCC_PLLM_DIV_49 /*!< PLLI2S division factor for PLLI2SM output by 49 */ -#define LL_RCC_PLLI2SM_DIV_50 LL_RCC_PLLM_DIV_50 /*!< PLLI2S division factor for PLLI2SM output by 50 */ -#define LL_RCC_PLLI2SM_DIV_51 LL_RCC_PLLM_DIV_51 /*!< PLLI2S division factor for PLLI2SM output by 51 */ -#define LL_RCC_PLLI2SM_DIV_52 LL_RCC_PLLM_DIV_52 /*!< PLLI2S division factor for PLLI2SM output by 52 */ -#define LL_RCC_PLLI2SM_DIV_53 LL_RCC_PLLM_DIV_53 /*!< PLLI2S division factor for PLLI2SM output by 53 */ -#define LL_RCC_PLLI2SM_DIV_54 LL_RCC_PLLM_DIV_54 /*!< PLLI2S division factor for PLLI2SM output by 54 */ -#define LL_RCC_PLLI2SM_DIV_55 LL_RCC_PLLM_DIV_55 /*!< PLLI2S division factor for PLLI2SM output by 55 */ -#define LL_RCC_PLLI2SM_DIV_56 LL_RCC_PLLM_DIV_56 /*!< PLLI2S division factor for PLLI2SM output by 56 */ -#define LL_RCC_PLLI2SM_DIV_57 LL_RCC_PLLM_DIV_57 /*!< PLLI2S division factor for PLLI2SM output by 57 */ -#define LL_RCC_PLLI2SM_DIV_58 LL_RCC_PLLM_DIV_58 /*!< PLLI2S division factor for PLLI2SM output by 58 */ -#define LL_RCC_PLLI2SM_DIV_59 LL_RCC_PLLM_DIV_59 /*!< PLLI2S division factor for PLLI2SM output by 59 */ -#define LL_RCC_PLLI2SM_DIV_60 LL_RCC_PLLM_DIV_60 /*!< PLLI2S division factor for PLLI2SM output by 60 */ -#define LL_RCC_PLLI2SM_DIV_61 LL_RCC_PLLM_DIV_61 /*!< PLLI2S division factor for PLLI2SM output by 61 */ -#define LL_RCC_PLLI2SM_DIV_62 LL_RCC_PLLM_DIV_62 /*!< PLLI2S division factor for PLLI2SM output by 62 */ -#define LL_RCC_PLLI2SM_DIV_63 LL_RCC_PLLM_DIV_63 /*!< PLLI2S division factor for PLLI2SM output by 63 */ -#endif /* RCC_PLLI2SCFGR_PLLI2SM */ -/** - * @} - */ - -#if defined(RCC_PLLI2SCFGR_PLLI2SQ) -/** @defgroup RCC_LL_EC_PLLI2SQ PLLI2SQ division factor (PLLI2SQ) - * @{ - */ -#define LL_RCC_PLLI2SQ_DIV_2 RCC_PLLI2SCFGR_PLLI2SQ_1 /*!< PLLI2S division factor for PLLI2SQ output by 2 */ -#define LL_RCC_PLLI2SQ_DIV_3 (RCC_PLLI2SCFGR_PLLI2SQ_1 | RCC_PLLI2SCFGR_PLLI2SQ_0) /*!< PLLI2S division factor for PLLI2SQ output by 3 */ -#define LL_RCC_PLLI2SQ_DIV_4 RCC_PLLI2SCFGR_PLLI2SQ_2 /*!< PLLI2S division factor for PLLI2SQ output by 4 */ -#define LL_RCC_PLLI2SQ_DIV_5 (RCC_PLLI2SCFGR_PLLI2SQ_2 | RCC_PLLI2SCFGR_PLLI2SQ_0) /*!< PLLI2S division factor for PLLI2SQ output by 5 */ -#define LL_RCC_PLLI2SQ_DIV_6 (RCC_PLLI2SCFGR_PLLI2SQ_2 | RCC_PLLI2SCFGR_PLLI2SQ_1) /*!< PLLI2S division factor for PLLI2SQ output by 6 */ -#define LL_RCC_PLLI2SQ_DIV_7 (RCC_PLLI2SCFGR_PLLI2SQ_2 | RCC_PLLI2SCFGR_PLLI2SQ_1 | RCC_PLLI2SCFGR_PLLI2SQ_0) /*!< PLLI2S division factor for PLLI2SQ output by 7 */ -#define LL_RCC_PLLI2SQ_DIV_8 RCC_PLLI2SCFGR_PLLI2SQ_3 /*!< PLLI2S division factor for PLLI2SQ output by 8 */ -#define LL_RCC_PLLI2SQ_DIV_9 (RCC_PLLI2SCFGR_PLLI2SQ_3 | RCC_PLLI2SCFGR_PLLI2SQ_0) /*!< PLLI2S division factor for PLLI2SQ output by 9 */ -#define LL_RCC_PLLI2SQ_DIV_10 (RCC_PLLI2SCFGR_PLLI2SQ_3 | RCC_PLLI2SCFGR_PLLI2SQ_1) /*!< PLLI2S division factor for PLLI2SQ output by 10 */ -#define LL_RCC_PLLI2SQ_DIV_11 (RCC_PLLI2SCFGR_PLLI2SQ_3 | RCC_PLLI2SCFGR_PLLI2SQ_1 | RCC_PLLI2SCFGR_PLLI2SQ_0) /*!< PLLI2S division factor for PLLI2SQ output by 11 */ -#define LL_RCC_PLLI2SQ_DIV_12 (RCC_PLLI2SCFGR_PLLI2SQ_3 | RCC_PLLI2SCFGR_PLLI2SQ_2) /*!< PLLI2S division factor for PLLI2SQ output by 12 */ -#define LL_RCC_PLLI2SQ_DIV_13 (RCC_PLLI2SCFGR_PLLI2SQ_3 | RCC_PLLI2SCFGR_PLLI2SQ_2 | RCC_PLLI2SCFGR_PLLI2SQ_0) /*!< PLLI2S division factor for PLLI2SQ output by 13 */ -#define LL_RCC_PLLI2SQ_DIV_14 (RCC_PLLI2SCFGR_PLLI2SQ_3 | RCC_PLLI2SCFGR_PLLI2SQ_2 | RCC_PLLI2SCFGR_PLLI2SQ_1) /*!< PLLI2S division factor for PLLI2SQ output by 14 */ -#define LL_RCC_PLLI2SQ_DIV_15 (RCC_PLLI2SCFGR_PLLI2SQ_3 | RCC_PLLI2SCFGR_PLLI2SQ_2 | RCC_PLLI2SCFGR_PLLI2SQ_1 | RCC_PLLI2SCFGR_PLLI2SQ_0) /*!< PLLI2S division factor for PLLI2SQ output by 15 */ -/** - * @} - */ -#endif /* RCC_PLLI2SCFGR_PLLI2SQ */ - -#if defined(RCC_DCKCFGR_PLLI2SDIVQ) -/** @defgroup RCC_LL_EC_PLLI2SDIVQ PLLI2SDIVQ division factor (PLLI2SDIVQ) - * @{ - */ -#define LL_RCC_PLLI2SDIVQ_DIV_1 0x00000000U /*!< PLLI2S division factor for PLLI2SDIVQ output by 1 */ -#define LL_RCC_PLLI2SDIVQ_DIV_2 RCC_DCKCFGR_PLLI2SDIVQ_0 /*!< PLLI2S division factor for PLLI2SDIVQ output by 2 */ -#define LL_RCC_PLLI2SDIVQ_DIV_3 RCC_DCKCFGR_PLLI2SDIVQ_1 /*!< PLLI2S division factor for PLLI2SDIVQ output by 3 */ -#define LL_RCC_PLLI2SDIVQ_DIV_4 (RCC_DCKCFGR_PLLI2SDIVQ_1 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 4 */ -#define LL_RCC_PLLI2SDIVQ_DIV_5 RCC_DCKCFGR_PLLI2SDIVQ_2 /*!< PLLI2S division factor for PLLI2SDIVQ output by 5 */ -#define LL_RCC_PLLI2SDIVQ_DIV_6 (RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 6 */ -#define LL_RCC_PLLI2SDIVQ_DIV_7 (RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_1) /*!< PLLI2S division factor for PLLI2SDIVQ output by 7 */ -#define LL_RCC_PLLI2SDIVQ_DIV_8 (RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_1 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 8 */ -#define LL_RCC_PLLI2SDIVQ_DIV_9 RCC_DCKCFGR_PLLI2SDIVQ_3 /*!< PLLI2S division factor for PLLI2SDIVQ output by 9 */ -#define LL_RCC_PLLI2SDIVQ_DIV_10 (RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 10 */ -#define LL_RCC_PLLI2SDIVQ_DIV_11 (RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_1) /*!< PLLI2S division factor for PLLI2SDIVQ output by 11 */ -#define LL_RCC_PLLI2SDIVQ_DIV_12 (RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_1 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 12 */ -#define LL_RCC_PLLI2SDIVQ_DIV_13 (RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_2) /*!< PLLI2S division factor for PLLI2SDIVQ output by 13 */ -#define LL_RCC_PLLI2SDIVQ_DIV_14 (RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 14 */ -#define LL_RCC_PLLI2SDIVQ_DIV_15 (RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_1) /*!< PLLI2S division factor for PLLI2SDIVQ output by 15 */ -#define LL_RCC_PLLI2SDIVQ_DIV_16 (RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_1 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 16 */ -#define LL_RCC_PLLI2SDIVQ_DIV_17 RCC_DCKCFGR_PLLI2SDIVQ_4 /*!< PLLI2S division factor for PLLI2SDIVQ output by 17 */ -#define LL_RCC_PLLI2SDIVQ_DIV_18 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 18 */ -#define LL_RCC_PLLI2SDIVQ_DIV_19 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_1) /*!< PLLI2S division factor for PLLI2SDIVQ output by 19 */ -#define LL_RCC_PLLI2SDIVQ_DIV_20 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_1 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 20 */ -#define LL_RCC_PLLI2SDIVQ_DIV_21 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_2) /*!< PLLI2S division factor for PLLI2SDIVQ output by 21 */ -#define LL_RCC_PLLI2SDIVQ_DIV_22 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 22 */ -#define LL_RCC_PLLI2SDIVQ_DIV_23 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_1) /*!< PLLI2S division factor for PLLI2SDIVQ output by 23 */ -#define LL_RCC_PLLI2SDIVQ_DIV_24 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_1 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 24 */ -#define LL_RCC_PLLI2SDIVQ_DIV_25 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_3) /*!< PLLI2S division factor for PLLI2SDIVQ output by 25 */ -#define LL_RCC_PLLI2SDIVQ_DIV_26 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 26 */ -#define LL_RCC_PLLI2SDIVQ_DIV_27 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_1) /*!< PLLI2S division factor for PLLI2SDIVQ output by 27 */ -#define LL_RCC_PLLI2SDIVQ_DIV_28 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_1 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 28 */ -#define LL_RCC_PLLI2SDIVQ_DIV_29 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_2) /*!< PLLI2S division factor for PLLI2SDIVQ output by 29 */ -#define LL_RCC_PLLI2SDIVQ_DIV_30 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 30 */ -#define LL_RCC_PLLI2SDIVQ_DIV_31 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_1) /*!< PLLI2S division factor for PLLI2SDIVQ output by 31 */ -#define LL_RCC_PLLI2SDIVQ_DIV_32 (RCC_DCKCFGR_PLLI2SDIVQ_4 | RCC_DCKCFGR_PLLI2SDIVQ_3 | RCC_DCKCFGR_PLLI2SDIVQ_2 | RCC_DCKCFGR_PLLI2SDIVQ_1 | RCC_DCKCFGR_PLLI2SDIVQ_0) /*!< PLLI2S division factor for PLLI2SDIVQ output by 32 */ -/** - * @} - */ -#endif /* RCC_DCKCFGR_PLLI2SDIVQ */ - -#if defined(RCC_DCKCFGR_PLLI2SDIVR) -/** @defgroup RCC_LL_EC_PLLI2SDIVR PLLI2SDIVR division factor (PLLI2SDIVR) - * @{ - */ -#define LL_RCC_PLLI2SDIVR_DIV_1 (RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 1 */ -#define LL_RCC_PLLI2SDIVR_DIV_2 (RCC_DCKCFGR_PLLI2SDIVR_1) /*!< PLLI2S division factor for PLLI2SDIVR output by 2 */ -#define LL_RCC_PLLI2SDIVR_DIV_3 (RCC_DCKCFGR_PLLI2SDIVR_1 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 3 */ -#define LL_RCC_PLLI2SDIVR_DIV_4 (RCC_DCKCFGR_PLLI2SDIVR_2) /*!< PLLI2S division factor for PLLI2SDIVR output by 4 */ -#define LL_RCC_PLLI2SDIVR_DIV_5 (RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 5 */ -#define LL_RCC_PLLI2SDIVR_DIV_6 (RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_1) /*!< PLLI2S division factor for PLLI2SDIVR output by 6 */ -#define LL_RCC_PLLI2SDIVR_DIV_7 (RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_1 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 7 */ -#define LL_RCC_PLLI2SDIVR_DIV_8 (RCC_DCKCFGR_PLLI2SDIVR_3) /*!< PLLI2S division factor for PLLI2SDIVR output by 8 */ -#define LL_RCC_PLLI2SDIVR_DIV_9 (RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 9 */ -#define LL_RCC_PLLI2SDIVR_DIV_10 (RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_1) /*!< PLLI2S division factor for PLLI2SDIVR output by 10 */ -#define LL_RCC_PLLI2SDIVR_DIV_11 (RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_1 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 11 */ -#define LL_RCC_PLLI2SDIVR_DIV_12 (RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_2) /*!< PLLI2S division factor for PLLI2SDIVR output by 12 */ -#define LL_RCC_PLLI2SDIVR_DIV_13 (RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 13 */ -#define LL_RCC_PLLI2SDIVR_DIV_14 (RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_1) /*!< PLLI2S division factor for PLLI2SDIVR output by 14 */ -#define LL_RCC_PLLI2SDIVR_DIV_15 (RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_1 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 15 */ -#define LL_RCC_PLLI2SDIVR_DIV_16 (RCC_DCKCFGR_PLLI2SDIVR_4) /*!< PLLI2S division factor for PLLI2SDIVR output by 16 */ -#define LL_RCC_PLLI2SDIVR_DIV_17 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 17 */ -#define LL_RCC_PLLI2SDIVR_DIV_18 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_1) /*!< PLLI2S division factor for PLLI2SDIVR output by 18 */ -#define LL_RCC_PLLI2SDIVR_DIV_19 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_1 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 19 */ -#define LL_RCC_PLLI2SDIVR_DIV_20 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_2) /*!< PLLI2S division factor for PLLI2SDIVR output by 20 */ -#define LL_RCC_PLLI2SDIVR_DIV_21 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 21 */ -#define LL_RCC_PLLI2SDIVR_DIV_22 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_1) /*!< PLLI2S division factor for PLLI2SDIVR output by 22 */ -#define LL_RCC_PLLI2SDIVR_DIV_23 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_1 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 23 */ -#define LL_RCC_PLLI2SDIVR_DIV_24 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_3) /*!< PLLI2S division factor for PLLI2SDIVR output by 24 */ -#define LL_RCC_PLLI2SDIVR_DIV_25 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 25 */ -#define LL_RCC_PLLI2SDIVR_DIV_26 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_1) /*!< PLLI2S division factor for PLLI2SDIVR output by 26 */ -#define LL_RCC_PLLI2SDIVR_DIV_27 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_1 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 27 */ -#define LL_RCC_PLLI2SDIVR_DIV_28 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_2) /*!< PLLI2S division factor for PLLI2SDIVR output by 28 */ -#define LL_RCC_PLLI2SDIVR_DIV_29 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 29 */ -#define LL_RCC_PLLI2SDIVR_DIV_30 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_1) /*!< PLLI2S division factor for PLLI2SDIVR output by 30 */ -#define LL_RCC_PLLI2SDIVR_DIV_31 (RCC_DCKCFGR_PLLI2SDIVR_4 | RCC_DCKCFGR_PLLI2SDIVR_3 | RCC_DCKCFGR_PLLI2SDIVR_2 | RCC_DCKCFGR_PLLI2SDIVR_1 | RCC_DCKCFGR_PLLI2SDIVR_0) /*!< PLLI2S division factor for PLLI2SDIVR output by 31 */ -/** - * @} - */ -#endif /* RCC_DCKCFGR_PLLI2SDIVR */ - -/** @defgroup RCC_LL_EC_PLLI2SR PLLI2SR division factor (PLLI2SR) - * @{ - */ -#define LL_RCC_PLLI2SR_DIV_2 RCC_PLLI2SCFGR_PLLI2SR_1 /*!< PLLI2S division factor for PLLI2SR output by 2 */ -#define LL_RCC_PLLI2SR_DIV_3 (RCC_PLLI2SCFGR_PLLI2SR_1 | RCC_PLLI2SCFGR_PLLI2SR_0) /*!< PLLI2S division factor for PLLI2SR output by 3 */ -#define LL_RCC_PLLI2SR_DIV_4 RCC_PLLI2SCFGR_PLLI2SR_2 /*!< PLLI2S division factor for PLLI2SR output by 4 */ -#define LL_RCC_PLLI2SR_DIV_5 (RCC_PLLI2SCFGR_PLLI2SR_2 | RCC_PLLI2SCFGR_PLLI2SR_0) /*!< PLLI2S division factor for PLLI2SR output by 5 */ -#define LL_RCC_PLLI2SR_DIV_6 (RCC_PLLI2SCFGR_PLLI2SR_2 | RCC_PLLI2SCFGR_PLLI2SR_1) /*!< PLLI2S division factor for PLLI2SR output by 6 */ -#define LL_RCC_PLLI2SR_DIV_7 (RCC_PLLI2SCFGR_PLLI2SR_2 | RCC_PLLI2SCFGR_PLLI2SR_1 | RCC_PLLI2SCFGR_PLLI2SR_0) /*!< PLLI2S division factor for PLLI2SR output by 7 */ -/** - * @} - */ - -#if defined(RCC_PLLI2SCFGR_PLLI2SP) -/** @defgroup RCC_LL_EC_PLLI2SP PLLI2SP division factor (PLLI2SP) - * @{ - */ -#define LL_RCC_PLLI2SP_DIV_2 0x00000000U /*!< PLLI2S division factor for PLLI2SP output by 2 */ -#define LL_RCC_PLLI2SP_DIV_4 RCC_PLLI2SCFGR_PLLI2SP_0 /*!< PLLI2S division factor for PLLI2SP output by 4 */ -#define LL_RCC_PLLI2SP_DIV_6 RCC_PLLI2SCFGR_PLLI2SP_1 /*!< PLLI2S division factor for PLLI2SP output by 6 */ -#define LL_RCC_PLLI2SP_DIV_8 (RCC_PLLI2SCFGR_PLLI2SP_1 | RCC_PLLI2SCFGR_PLLI2SP_0) /*!< PLLI2S division factor for PLLI2SP output by 8 */ -/** - * @} - */ -#endif /* RCC_PLLI2SCFGR_PLLI2SP */ -#endif /* RCC_PLLI2S_SUPPORT */ - -#if defined(RCC_PLLSAI_SUPPORT) -/** @defgroup RCC_LL_EC_PLLSAIM PLLSAIM division factor (PLLSAIM or PLLM) - * @{ - */ -#if defined(RCC_PLLSAICFGR_PLLSAIM) -#define LL_RCC_PLLSAIM_DIV_2 (RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 2 */ -#define LL_RCC_PLLSAIM_DIV_3 (RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 3 */ -#define LL_RCC_PLLSAIM_DIV_4 (RCC_PLLSAICFGR_PLLSAIM_2) /*!< PLLSAI division factor for PLLSAIM output by 4 */ -#define LL_RCC_PLLSAIM_DIV_5 (RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 5 */ -#define LL_RCC_PLLSAIM_DIV_6 (RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 6 */ -#define LL_RCC_PLLSAIM_DIV_7 (RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 7 */ -#define LL_RCC_PLLSAIM_DIV_8 (RCC_PLLSAICFGR_PLLSAIM_3) /*!< PLLSAI division factor for PLLSAIM output by 8 */ -#define LL_RCC_PLLSAIM_DIV_9 (RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 9 */ -#define LL_RCC_PLLSAIM_DIV_10 (RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 10 */ -#define LL_RCC_PLLSAIM_DIV_11 (RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 11 */ -#define LL_RCC_PLLSAIM_DIV_12 (RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2) /*!< PLLSAI division factor for PLLSAIM output by 12 */ -#define LL_RCC_PLLSAIM_DIV_13 (RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 13 */ -#define LL_RCC_PLLSAIM_DIV_14 (RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 14 */ -#define LL_RCC_PLLSAIM_DIV_15 (RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 15 */ -#define LL_RCC_PLLSAIM_DIV_16 (RCC_PLLSAICFGR_PLLSAIM_4) /*!< PLLSAI division factor for PLLSAIM output by 16 */ -#define LL_RCC_PLLSAIM_DIV_17 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 17 */ -#define LL_RCC_PLLSAIM_DIV_18 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 18 */ -#define LL_RCC_PLLSAIM_DIV_19 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 19 */ -#define LL_RCC_PLLSAIM_DIV_20 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_2) /*!< PLLSAI division factor for PLLSAIM output by 20 */ -#define LL_RCC_PLLSAIM_DIV_21 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 21 */ -#define LL_RCC_PLLSAIM_DIV_22 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 22 */ -#define LL_RCC_PLLSAIM_DIV_23 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 23 */ -#define LL_RCC_PLLSAIM_DIV_24 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3) /*!< PLLSAI division factor for PLLSAIM output by 24 */ -#define LL_RCC_PLLSAIM_DIV_25 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 25 */ -#define LL_RCC_PLLSAIM_DIV_26 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 26 */ -#define LL_RCC_PLLSAIM_DIV_27 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 27 */ -#define LL_RCC_PLLSAIM_DIV_28 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2) /*!< PLLSAI division factor for PLLSAIM output by 28 */ -#define LL_RCC_PLLSAIM_DIV_29 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 29 */ -#define LL_RCC_PLLSAIM_DIV_30 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 30 */ -#define LL_RCC_PLLSAIM_DIV_31 (RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 31 */ -#define LL_RCC_PLLSAIM_DIV_32 (RCC_PLLSAICFGR_PLLSAIM_5) /*!< PLLSAI division factor for PLLSAIM output by 32 */ -#define LL_RCC_PLLSAIM_DIV_33 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 33 */ -#define LL_RCC_PLLSAIM_DIV_34 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 34 */ -#define LL_RCC_PLLSAIM_DIV_35 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 35 */ -#define LL_RCC_PLLSAIM_DIV_36 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_2) /*!< PLLSAI division factor for PLLSAIM output by 36 */ -#define LL_RCC_PLLSAIM_DIV_37 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 37 */ -#define LL_RCC_PLLSAIM_DIV_38 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 38 */ -#define LL_RCC_PLLSAIM_DIV_39 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 39 */ -#define LL_RCC_PLLSAIM_DIV_40 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_3) /*!< PLLSAI division factor for PLLSAIM output by 40 */ -#define LL_RCC_PLLSAIM_DIV_41 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 41 */ -#define LL_RCC_PLLSAIM_DIV_42 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 42 */ -#define LL_RCC_PLLSAIM_DIV_43 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 43 */ -#define LL_RCC_PLLSAIM_DIV_44 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2) /*!< PLLSAI division factor for PLLSAIM output by 44 */ -#define LL_RCC_PLLSAIM_DIV_45 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 45 */ -#define LL_RCC_PLLSAIM_DIV_46 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 46 */ -#define LL_RCC_PLLSAIM_DIV_47 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 47 */ -#define LL_RCC_PLLSAIM_DIV_48 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4) /*!< PLLSAI division factor for PLLSAIM output by 48 */ -#define LL_RCC_PLLSAIM_DIV_49 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 49 */ -#define LL_RCC_PLLSAIM_DIV_50 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 50 */ -#define LL_RCC_PLLSAIM_DIV_51 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 51 */ -#define LL_RCC_PLLSAIM_DIV_52 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_2) /*!< PLLSAI division factor for PLLSAIM output by 52 */ -#define LL_RCC_PLLSAIM_DIV_53 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 53 */ -#define LL_RCC_PLLSAIM_DIV_54 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 54 */ -#define LL_RCC_PLLSAIM_DIV_55 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 55 */ -#define LL_RCC_PLLSAIM_DIV_56 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3) /*!< PLLSAI division factor for PLLSAIM output by 56 */ -#define LL_RCC_PLLSAIM_DIV_57 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 57 */ -#define LL_RCC_PLLSAIM_DIV_58 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 58 */ -#define LL_RCC_PLLSAIM_DIV_59 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 59 */ -#define LL_RCC_PLLSAIM_DIV_60 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2) /*!< PLLSAI division factor for PLLSAIM output by 60 */ -#define LL_RCC_PLLSAIM_DIV_61 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 61 */ -#define LL_RCC_PLLSAIM_DIV_62 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1) /*!< PLLSAI division factor for PLLSAIM output by 62 */ -#define LL_RCC_PLLSAIM_DIV_63 (RCC_PLLSAICFGR_PLLSAIM_5 | RCC_PLLSAICFGR_PLLSAIM_4 | RCC_PLLSAICFGR_PLLSAIM_3 | RCC_PLLSAICFGR_PLLSAIM_2 | RCC_PLLSAICFGR_PLLSAIM_1 | RCC_PLLSAICFGR_PLLSAIM_0) /*!< PLLSAI division factor for PLLSAIM output by 63 */ -#else -#define LL_RCC_PLLSAIM_DIV_2 LL_RCC_PLLM_DIV_2 /*!< PLLSAI division factor for PLLSAIM output by 2 */ -#define LL_RCC_PLLSAIM_DIV_3 LL_RCC_PLLM_DIV_3 /*!< PLLSAI division factor for PLLSAIM output by 3 */ -#define LL_RCC_PLLSAIM_DIV_4 LL_RCC_PLLM_DIV_4 /*!< PLLSAI division factor for PLLSAIM output by 4 */ -#define LL_RCC_PLLSAIM_DIV_5 LL_RCC_PLLM_DIV_5 /*!< PLLSAI division factor for PLLSAIM output by 5 */ -#define LL_RCC_PLLSAIM_DIV_6 LL_RCC_PLLM_DIV_6 /*!< PLLSAI division factor for PLLSAIM output by 6 */ -#define LL_RCC_PLLSAIM_DIV_7 LL_RCC_PLLM_DIV_7 /*!< PLLSAI division factor for PLLSAIM output by 7 */ -#define LL_RCC_PLLSAIM_DIV_8 LL_RCC_PLLM_DIV_8 /*!< PLLSAI division factor for PLLSAIM output by 8 */ -#define LL_RCC_PLLSAIM_DIV_9 LL_RCC_PLLM_DIV_9 /*!< PLLSAI division factor for PLLSAIM output by 9 */ -#define LL_RCC_PLLSAIM_DIV_10 LL_RCC_PLLM_DIV_10 /*!< PLLSAI division factor for PLLSAIM output by 10 */ -#define LL_RCC_PLLSAIM_DIV_11 LL_RCC_PLLM_DIV_11 /*!< PLLSAI division factor for PLLSAIM output by 11 */ -#define LL_RCC_PLLSAIM_DIV_12 LL_RCC_PLLM_DIV_12 /*!< PLLSAI division factor for PLLSAIM output by 12 */ -#define LL_RCC_PLLSAIM_DIV_13 LL_RCC_PLLM_DIV_13 /*!< PLLSAI division factor for PLLSAIM output by 13 */ -#define LL_RCC_PLLSAIM_DIV_14 LL_RCC_PLLM_DIV_14 /*!< PLLSAI division factor for PLLSAIM output by 14 */ -#define LL_RCC_PLLSAIM_DIV_15 LL_RCC_PLLM_DIV_15 /*!< PLLSAI division factor for PLLSAIM output by 15 */ -#define LL_RCC_PLLSAIM_DIV_16 LL_RCC_PLLM_DIV_16 /*!< PLLSAI division factor for PLLSAIM output by 16 */ -#define LL_RCC_PLLSAIM_DIV_17 LL_RCC_PLLM_DIV_17 /*!< PLLSAI division factor for PLLSAIM output by 17 */ -#define LL_RCC_PLLSAIM_DIV_18 LL_RCC_PLLM_DIV_18 /*!< PLLSAI division factor for PLLSAIM output by 18 */ -#define LL_RCC_PLLSAIM_DIV_19 LL_RCC_PLLM_DIV_19 /*!< PLLSAI division factor for PLLSAIM output by 19 */ -#define LL_RCC_PLLSAIM_DIV_20 LL_RCC_PLLM_DIV_20 /*!< PLLSAI division factor for PLLSAIM output by 20 */ -#define LL_RCC_PLLSAIM_DIV_21 LL_RCC_PLLM_DIV_21 /*!< PLLSAI division factor for PLLSAIM output by 21 */ -#define LL_RCC_PLLSAIM_DIV_22 LL_RCC_PLLM_DIV_22 /*!< PLLSAI division factor for PLLSAIM output by 22 */ -#define LL_RCC_PLLSAIM_DIV_23 LL_RCC_PLLM_DIV_23 /*!< PLLSAI division factor for PLLSAIM output by 23 */ -#define LL_RCC_PLLSAIM_DIV_24 LL_RCC_PLLM_DIV_24 /*!< PLLSAI division factor for PLLSAIM output by 24 */ -#define LL_RCC_PLLSAIM_DIV_25 LL_RCC_PLLM_DIV_25 /*!< PLLSAI division factor for PLLSAIM output by 25 */ -#define LL_RCC_PLLSAIM_DIV_26 LL_RCC_PLLM_DIV_26 /*!< PLLSAI division factor for PLLSAIM output by 26 */ -#define LL_RCC_PLLSAIM_DIV_27 LL_RCC_PLLM_DIV_27 /*!< PLLSAI division factor for PLLSAIM output by 27 */ -#define LL_RCC_PLLSAIM_DIV_28 LL_RCC_PLLM_DIV_28 /*!< PLLSAI division factor for PLLSAIM output by 28 */ -#define LL_RCC_PLLSAIM_DIV_29 LL_RCC_PLLM_DIV_29 /*!< PLLSAI division factor for PLLSAIM output by 29 */ -#define LL_RCC_PLLSAIM_DIV_30 LL_RCC_PLLM_DIV_30 /*!< PLLSAI division factor for PLLSAIM output by 30 */ -#define LL_RCC_PLLSAIM_DIV_31 LL_RCC_PLLM_DIV_31 /*!< PLLSAI division factor for PLLSAIM output by 31 */ -#define LL_RCC_PLLSAIM_DIV_32 LL_RCC_PLLM_DIV_32 /*!< PLLSAI division factor for PLLSAIM output by 32 */ -#define LL_RCC_PLLSAIM_DIV_33 LL_RCC_PLLM_DIV_33 /*!< PLLSAI division factor for PLLSAIM output by 33 */ -#define LL_RCC_PLLSAIM_DIV_34 LL_RCC_PLLM_DIV_34 /*!< PLLSAI division factor for PLLSAIM output by 34 */ -#define LL_RCC_PLLSAIM_DIV_35 LL_RCC_PLLM_DIV_35 /*!< PLLSAI division factor for PLLSAIM output by 35 */ -#define LL_RCC_PLLSAIM_DIV_36 LL_RCC_PLLM_DIV_36 /*!< PLLSAI division factor for PLLSAIM output by 36 */ -#define LL_RCC_PLLSAIM_DIV_37 LL_RCC_PLLM_DIV_37 /*!< PLLSAI division factor for PLLSAIM output by 37 */ -#define LL_RCC_PLLSAIM_DIV_38 LL_RCC_PLLM_DIV_38 /*!< PLLSAI division factor for PLLSAIM output by 38 */ -#define LL_RCC_PLLSAIM_DIV_39 LL_RCC_PLLM_DIV_39 /*!< PLLSAI division factor for PLLSAIM output by 39 */ -#define LL_RCC_PLLSAIM_DIV_40 LL_RCC_PLLM_DIV_40 /*!< PLLSAI division factor for PLLSAIM output by 40 */ -#define LL_RCC_PLLSAIM_DIV_41 LL_RCC_PLLM_DIV_41 /*!< PLLSAI division factor for PLLSAIM output by 41 */ -#define LL_RCC_PLLSAIM_DIV_42 LL_RCC_PLLM_DIV_42 /*!< PLLSAI division factor for PLLSAIM output by 42 */ -#define LL_RCC_PLLSAIM_DIV_43 LL_RCC_PLLM_DIV_43 /*!< PLLSAI division factor for PLLSAIM output by 43 */ -#define LL_RCC_PLLSAIM_DIV_44 LL_RCC_PLLM_DIV_44 /*!< PLLSAI division factor for PLLSAIM output by 44 */ -#define LL_RCC_PLLSAIM_DIV_45 LL_RCC_PLLM_DIV_45 /*!< PLLSAI division factor for PLLSAIM output by 45 */ -#define LL_RCC_PLLSAIM_DIV_46 LL_RCC_PLLM_DIV_46 /*!< PLLSAI division factor for PLLSAIM output by 46 */ -#define LL_RCC_PLLSAIM_DIV_47 LL_RCC_PLLM_DIV_47 /*!< PLLSAI division factor for PLLSAIM output by 47 */ -#define LL_RCC_PLLSAIM_DIV_48 LL_RCC_PLLM_DIV_48 /*!< PLLSAI division factor for PLLSAIM output by 48 */ -#define LL_RCC_PLLSAIM_DIV_49 LL_RCC_PLLM_DIV_49 /*!< PLLSAI division factor for PLLSAIM output by 49 */ -#define LL_RCC_PLLSAIM_DIV_50 LL_RCC_PLLM_DIV_50 /*!< PLLSAI division factor for PLLSAIM output by 50 */ -#define LL_RCC_PLLSAIM_DIV_51 LL_RCC_PLLM_DIV_51 /*!< PLLSAI division factor for PLLSAIM output by 51 */ -#define LL_RCC_PLLSAIM_DIV_52 LL_RCC_PLLM_DIV_52 /*!< PLLSAI division factor for PLLSAIM output by 52 */ -#define LL_RCC_PLLSAIM_DIV_53 LL_RCC_PLLM_DIV_53 /*!< PLLSAI division factor for PLLSAIM output by 53 */ -#define LL_RCC_PLLSAIM_DIV_54 LL_RCC_PLLM_DIV_54 /*!< PLLSAI division factor for PLLSAIM output by 54 */ -#define LL_RCC_PLLSAIM_DIV_55 LL_RCC_PLLM_DIV_55 /*!< PLLSAI division factor for PLLSAIM output by 55 */ -#define LL_RCC_PLLSAIM_DIV_56 LL_RCC_PLLM_DIV_56 /*!< PLLSAI division factor for PLLSAIM output by 56 */ -#define LL_RCC_PLLSAIM_DIV_57 LL_RCC_PLLM_DIV_57 /*!< PLLSAI division factor for PLLSAIM output by 57 */ -#define LL_RCC_PLLSAIM_DIV_58 LL_RCC_PLLM_DIV_58 /*!< PLLSAI division factor for PLLSAIM output by 58 */ -#define LL_RCC_PLLSAIM_DIV_59 LL_RCC_PLLM_DIV_59 /*!< PLLSAI division factor for PLLSAIM output by 59 */ -#define LL_RCC_PLLSAIM_DIV_60 LL_RCC_PLLM_DIV_60 /*!< PLLSAI division factor for PLLSAIM output by 60 */ -#define LL_RCC_PLLSAIM_DIV_61 LL_RCC_PLLM_DIV_61 /*!< PLLSAI division factor for PLLSAIM output by 61 */ -#define LL_RCC_PLLSAIM_DIV_62 LL_RCC_PLLM_DIV_62 /*!< PLLSAI division factor for PLLSAIM output by 62 */ -#define LL_RCC_PLLSAIM_DIV_63 LL_RCC_PLLM_DIV_63 /*!< PLLSAI division factor for PLLSAIM output by 63 */ -#endif /* RCC_PLLSAICFGR_PLLSAIM */ -/** - * @} - */ - -/** @defgroup RCC_LL_EC_PLLSAIQ PLLSAIQ division factor (PLLSAIQ) - * @{ - */ -#define LL_RCC_PLLSAIQ_DIV_2 RCC_PLLSAICFGR_PLLSAIQ_1 /*!< PLLSAI division factor for PLLSAIQ output by 2 */ -#define LL_RCC_PLLSAIQ_DIV_3 (RCC_PLLSAICFGR_PLLSAIQ_1 | RCC_PLLSAICFGR_PLLSAIQ_0) /*!< PLLSAI division factor for PLLSAIQ output by 3 */ -#define LL_RCC_PLLSAIQ_DIV_4 RCC_PLLSAICFGR_PLLSAIQ_2 /*!< PLLSAI division factor for PLLSAIQ output by 4 */ -#define LL_RCC_PLLSAIQ_DIV_5 (RCC_PLLSAICFGR_PLLSAIQ_2 | RCC_PLLSAICFGR_PLLSAIQ_0) /*!< PLLSAI division factor for PLLSAIQ output by 5 */ -#define LL_RCC_PLLSAIQ_DIV_6 (RCC_PLLSAICFGR_PLLSAIQ_2 | RCC_PLLSAICFGR_PLLSAIQ_1) /*!< PLLSAI division factor for PLLSAIQ output by 6 */ -#define LL_RCC_PLLSAIQ_DIV_7 (RCC_PLLSAICFGR_PLLSAIQ_2 | RCC_PLLSAICFGR_PLLSAIQ_1 | RCC_PLLSAICFGR_PLLSAIQ_0) /*!< PLLSAI division factor for PLLSAIQ output by 7 */ -#define LL_RCC_PLLSAIQ_DIV_8 RCC_PLLSAICFGR_PLLSAIQ_3 /*!< PLLSAI division factor for PLLSAIQ output by 8 */ -#define LL_RCC_PLLSAIQ_DIV_9 (RCC_PLLSAICFGR_PLLSAIQ_3 | RCC_PLLSAICFGR_PLLSAIQ_0) /*!< PLLSAI division factor for PLLSAIQ output by 9 */ -#define LL_RCC_PLLSAIQ_DIV_10 (RCC_PLLSAICFGR_PLLSAIQ_3 | RCC_PLLSAICFGR_PLLSAIQ_1) /*!< PLLSAI division factor for PLLSAIQ output by 10 */ -#define LL_RCC_PLLSAIQ_DIV_11 (RCC_PLLSAICFGR_PLLSAIQ_3 | RCC_PLLSAICFGR_PLLSAIQ_1 | RCC_PLLSAICFGR_PLLSAIQ_0) /*!< PLLSAI division factor for PLLSAIQ output by 11 */ -#define LL_RCC_PLLSAIQ_DIV_12 (RCC_PLLSAICFGR_PLLSAIQ_3 | RCC_PLLSAICFGR_PLLSAIQ_2) /*!< PLLSAI division factor for PLLSAIQ output by 12 */ -#define LL_RCC_PLLSAIQ_DIV_13 (RCC_PLLSAICFGR_PLLSAIQ_3 | RCC_PLLSAICFGR_PLLSAIQ_2 | RCC_PLLSAICFGR_PLLSAIQ_0) /*!< PLLSAI division factor for PLLSAIQ output by 13 */ -#define LL_RCC_PLLSAIQ_DIV_14 (RCC_PLLSAICFGR_PLLSAIQ_3 | RCC_PLLSAICFGR_PLLSAIQ_2 | RCC_PLLSAICFGR_PLLSAIQ_1) /*!< PLLSAI division factor for PLLSAIQ output by 14 */ -#define LL_RCC_PLLSAIQ_DIV_15 (RCC_PLLSAICFGR_PLLSAIQ_3 | RCC_PLLSAICFGR_PLLSAIQ_2 | RCC_PLLSAICFGR_PLLSAIQ_1 | RCC_PLLSAICFGR_PLLSAIQ_0) /*!< PLLSAI division factor for PLLSAIQ output by 15 */ -/** - * @} - */ - -#if defined(RCC_DCKCFGR_PLLSAIDIVQ) -/** @defgroup RCC_LL_EC_PLLSAIDIVQ PLLSAIDIVQ division factor (PLLSAIDIVQ) - * @{ - */ -#define LL_RCC_PLLSAIDIVQ_DIV_1 0x00000000U /*!< PLLSAI division factor for PLLSAIDIVQ output by 1 */ -#define LL_RCC_PLLSAIDIVQ_DIV_2 RCC_DCKCFGR_PLLSAIDIVQ_0 /*!< PLLSAI division factor for PLLSAIDIVQ output by 2 */ -#define LL_RCC_PLLSAIDIVQ_DIV_3 RCC_DCKCFGR_PLLSAIDIVQ_1 /*!< PLLSAI division factor for PLLSAIDIVQ output by 3 */ -#define LL_RCC_PLLSAIDIVQ_DIV_4 (RCC_DCKCFGR_PLLSAIDIVQ_1 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 4 */ -#define LL_RCC_PLLSAIDIVQ_DIV_5 RCC_DCKCFGR_PLLSAIDIVQ_2 /*!< PLLSAI division factor for PLLSAIDIVQ output by 5 */ -#define LL_RCC_PLLSAIDIVQ_DIV_6 (RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 6 */ -#define LL_RCC_PLLSAIDIVQ_DIV_7 (RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_1) /*!< PLLSAI division factor for PLLSAIDIVQ output by 7 */ -#define LL_RCC_PLLSAIDIVQ_DIV_8 (RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_1 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 8 */ -#define LL_RCC_PLLSAIDIVQ_DIV_9 RCC_DCKCFGR_PLLSAIDIVQ_3 /*!< PLLSAI division factor for PLLSAIDIVQ output by 9 */ -#define LL_RCC_PLLSAIDIVQ_DIV_10 (RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 10 */ -#define LL_RCC_PLLSAIDIVQ_DIV_11 (RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_1) /*!< PLLSAI division factor for PLLSAIDIVQ output by 11 */ -#define LL_RCC_PLLSAIDIVQ_DIV_12 (RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_1 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 12 */ -#define LL_RCC_PLLSAIDIVQ_DIV_13 (RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_2) /*!< PLLSAI division factor for PLLSAIDIVQ output by 13 */ -#define LL_RCC_PLLSAIDIVQ_DIV_14 (RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 14 */ -#define LL_RCC_PLLSAIDIVQ_DIV_15 (RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_1) /*!< PLLSAI division factor for PLLSAIDIVQ output by 15 */ -#define LL_RCC_PLLSAIDIVQ_DIV_16 (RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_1 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 16 */ -#define LL_RCC_PLLSAIDIVQ_DIV_17 RCC_DCKCFGR_PLLSAIDIVQ_4 /*!< PLLSAI division factor for PLLSAIDIVQ output by 17 */ -#define LL_RCC_PLLSAIDIVQ_DIV_18 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 18 */ -#define LL_RCC_PLLSAIDIVQ_DIV_19 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_1) /*!< PLLSAI division factor for PLLSAIDIVQ output by 19 */ -#define LL_RCC_PLLSAIDIVQ_DIV_20 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_1 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 20 */ -#define LL_RCC_PLLSAIDIVQ_DIV_21 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_2) /*!< PLLSAI division factor for PLLSAIDIVQ output by 21 */ -#define LL_RCC_PLLSAIDIVQ_DIV_22 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 22 */ -#define LL_RCC_PLLSAIDIVQ_DIV_23 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_1) /*!< PLLSAI division factor for PLLSAIDIVQ output by 23 */ -#define LL_RCC_PLLSAIDIVQ_DIV_24 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_1 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 24 */ -#define LL_RCC_PLLSAIDIVQ_DIV_25 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_3) /*!< PLLSAI division factor for PLLSAIDIVQ output by 25 */ -#define LL_RCC_PLLSAIDIVQ_DIV_26 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 26 */ -#define LL_RCC_PLLSAIDIVQ_DIV_27 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_1) /*!< PLLSAI division factor for PLLSAIDIVQ output by 27 */ -#define LL_RCC_PLLSAIDIVQ_DIV_28 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_1 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 28 */ -#define LL_RCC_PLLSAIDIVQ_DIV_29 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_2) /*!< PLLSAI division factor for PLLSAIDIVQ output by 29 */ -#define LL_RCC_PLLSAIDIVQ_DIV_30 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 30 */ -#define LL_RCC_PLLSAIDIVQ_DIV_31 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_1) /*!< PLLSAI division factor for PLLSAIDIVQ output by 31 */ -#define LL_RCC_PLLSAIDIVQ_DIV_32 (RCC_DCKCFGR_PLLSAIDIVQ_4 | RCC_DCKCFGR_PLLSAIDIVQ_3 | RCC_DCKCFGR_PLLSAIDIVQ_2 | RCC_DCKCFGR_PLLSAIDIVQ_1 | RCC_DCKCFGR_PLLSAIDIVQ_0) /*!< PLLSAI division factor for PLLSAIDIVQ output by 32 */ -/** - * @} - */ -#endif /* RCC_DCKCFGR_PLLSAIDIVQ */ - -#if defined(RCC_PLLSAICFGR_PLLSAIR) -/** @defgroup RCC_LL_EC_PLLSAIR PLLSAIR division factor (PLLSAIR) - * @{ - */ -#define LL_RCC_PLLSAIR_DIV_2 RCC_PLLSAICFGR_PLLSAIR_1 /*!< PLLSAI division factor for PLLSAIR output by 2 */ -#define LL_RCC_PLLSAIR_DIV_3 (RCC_PLLSAICFGR_PLLSAIR_1 | RCC_PLLSAICFGR_PLLSAIR_0) /*!< PLLSAI division factor for PLLSAIR output by 3 */ -#define LL_RCC_PLLSAIR_DIV_4 RCC_PLLSAICFGR_PLLSAIR_2 /*!< PLLSAI division factor for PLLSAIR output by 4 */ -#define LL_RCC_PLLSAIR_DIV_5 (RCC_PLLSAICFGR_PLLSAIR_2 | RCC_PLLSAICFGR_PLLSAIR_0) /*!< PLLSAI division factor for PLLSAIR output by 5 */ -#define LL_RCC_PLLSAIR_DIV_6 (RCC_PLLSAICFGR_PLLSAIR_2 | RCC_PLLSAICFGR_PLLSAIR_1) /*!< PLLSAI division factor for PLLSAIR output by 6 */ -#define LL_RCC_PLLSAIR_DIV_7 (RCC_PLLSAICFGR_PLLSAIR_2 | RCC_PLLSAICFGR_PLLSAIR_1 | RCC_PLLSAICFGR_PLLSAIR_0) /*!< PLLSAI division factor for PLLSAIR output by 7 */ -/** - * @} - */ -#endif /* RCC_PLLSAICFGR_PLLSAIR */ - -#if defined(RCC_DCKCFGR_PLLSAIDIVR) -/** @defgroup RCC_LL_EC_PLLSAIDIVR PLLSAIDIVR division factor (PLLSAIDIVR) - * @{ - */ -#define LL_RCC_PLLSAIDIVR_DIV_2 0x00000000U /*!< PLLSAI division factor for PLLSAIDIVR output by 2 */ -#define LL_RCC_PLLSAIDIVR_DIV_4 RCC_DCKCFGR_PLLSAIDIVR_0 /*!< PLLSAI division factor for PLLSAIDIVR output by 4 */ -#define LL_RCC_PLLSAIDIVR_DIV_8 RCC_DCKCFGR_PLLSAIDIVR_1 /*!< PLLSAI division factor for PLLSAIDIVR output by 8 */ -#define LL_RCC_PLLSAIDIVR_DIV_16 (RCC_DCKCFGR_PLLSAIDIVR_1 | RCC_DCKCFGR_PLLSAIDIVR_0) /*!< PLLSAI division factor for PLLSAIDIVR output by 16 */ -/** - * @} - */ -#endif /* RCC_DCKCFGR_PLLSAIDIVR */ - -#if defined(RCC_PLLSAICFGR_PLLSAIP) -/** @defgroup RCC_LL_EC_PLLSAIP PLLSAIP division factor (PLLSAIP) - * @{ - */ -#define LL_RCC_PLLSAIP_DIV_2 0x00000000U /*!< PLLSAI division factor for PLLSAIP output by 2 */ -#define LL_RCC_PLLSAIP_DIV_4 RCC_PLLSAICFGR_PLLSAIP_0 /*!< PLLSAI division factor for PLLSAIP output by 4 */ -#define LL_RCC_PLLSAIP_DIV_6 RCC_PLLSAICFGR_PLLSAIP_1 /*!< PLLSAI division factor for PLLSAIP output by 6 */ -#define LL_RCC_PLLSAIP_DIV_8 (RCC_PLLSAICFGR_PLLSAIP_1 | RCC_PLLSAICFGR_PLLSAIP_0) /*!< PLLSAI division factor for PLLSAIP output by 8 */ -/** - * @} - */ -#endif /* RCC_PLLSAICFGR_PLLSAIP */ -#endif /* RCC_PLLSAI_SUPPORT */ -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup RCC_LL_Exported_Macros RCC Exported Macros - * @{ - */ - -/** @defgroup RCC_LL_EM_WRITE_READ Common Write and read registers Macros - * @{ - */ - -/** - * @brief Write a value in RCC register - * @param __REG__ Register to be written - * @param __VALUE__ Value to be written in the register - * @retval None - */ -#define LL_RCC_WriteReg(__REG__, __VALUE__) WRITE_REG(RCC->__REG__, (__VALUE__)) - -/** - * @brief Read a value in RCC register - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_RCC_ReadReg(__REG__) READ_REG(RCC->__REG__) -/** - * @} - */ - -/** @defgroup RCC_LL_EM_CALC_FREQ Calculate frequencies - * @{ - */ - -/** - * @brief Helper macro to calculate the PLLCLK frequency on system domain - * @note ex: @ref __LL_RCC_CALC_PLLCLK_FREQ (HSE_VALUE,@ref LL_RCC_PLL_GetDivider (), - * @ref LL_RCC_PLL_GetN (), @ref LL_RCC_PLL_GetP ()); - * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) - * @param __PLLM__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLM_DIV_2 - * @arg @ref LL_RCC_PLLM_DIV_3 - * @arg @ref LL_RCC_PLLM_DIV_4 - * @arg @ref LL_RCC_PLLM_DIV_5 - * @arg @ref LL_RCC_PLLM_DIV_6 - * @arg @ref LL_RCC_PLLM_DIV_7 - * @arg @ref LL_RCC_PLLM_DIV_8 - * @arg @ref LL_RCC_PLLM_DIV_9 - * @arg @ref LL_RCC_PLLM_DIV_10 - * @arg @ref LL_RCC_PLLM_DIV_11 - * @arg @ref LL_RCC_PLLM_DIV_12 - * @arg @ref LL_RCC_PLLM_DIV_13 - * @arg @ref LL_RCC_PLLM_DIV_14 - * @arg @ref LL_RCC_PLLM_DIV_15 - * @arg @ref LL_RCC_PLLM_DIV_16 - * @arg @ref LL_RCC_PLLM_DIV_17 - * @arg @ref LL_RCC_PLLM_DIV_18 - * @arg @ref LL_RCC_PLLM_DIV_19 - * @arg @ref LL_RCC_PLLM_DIV_20 - * @arg @ref LL_RCC_PLLM_DIV_21 - * @arg @ref LL_RCC_PLLM_DIV_22 - * @arg @ref LL_RCC_PLLM_DIV_23 - * @arg @ref LL_RCC_PLLM_DIV_24 - * @arg @ref LL_RCC_PLLM_DIV_25 - * @arg @ref LL_RCC_PLLM_DIV_26 - * @arg @ref LL_RCC_PLLM_DIV_27 - * @arg @ref LL_RCC_PLLM_DIV_28 - * @arg @ref LL_RCC_PLLM_DIV_29 - * @arg @ref LL_RCC_PLLM_DIV_30 - * @arg @ref LL_RCC_PLLM_DIV_31 - * @arg @ref LL_RCC_PLLM_DIV_32 - * @arg @ref LL_RCC_PLLM_DIV_33 - * @arg @ref LL_RCC_PLLM_DIV_34 - * @arg @ref LL_RCC_PLLM_DIV_35 - * @arg @ref LL_RCC_PLLM_DIV_36 - * @arg @ref LL_RCC_PLLM_DIV_37 - * @arg @ref LL_RCC_PLLM_DIV_38 - * @arg @ref LL_RCC_PLLM_DIV_39 - * @arg @ref LL_RCC_PLLM_DIV_40 - * @arg @ref LL_RCC_PLLM_DIV_41 - * @arg @ref LL_RCC_PLLM_DIV_42 - * @arg @ref LL_RCC_PLLM_DIV_43 - * @arg @ref LL_RCC_PLLM_DIV_44 - * @arg @ref LL_RCC_PLLM_DIV_45 - * @arg @ref LL_RCC_PLLM_DIV_46 - * @arg @ref LL_RCC_PLLM_DIV_47 - * @arg @ref LL_RCC_PLLM_DIV_48 - * @arg @ref LL_RCC_PLLM_DIV_49 - * @arg @ref LL_RCC_PLLM_DIV_50 - * @arg @ref LL_RCC_PLLM_DIV_51 - * @arg @ref LL_RCC_PLLM_DIV_52 - * @arg @ref LL_RCC_PLLM_DIV_53 - * @arg @ref LL_RCC_PLLM_DIV_54 - * @arg @ref LL_RCC_PLLM_DIV_55 - * @arg @ref LL_RCC_PLLM_DIV_56 - * @arg @ref LL_RCC_PLLM_DIV_57 - * @arg @ref LL_RCC_PLLM_DIV_58 - * @arg @ref LL_RCC_PLLM_DIV_59 - * @arg @ref LL_RCC_PLLM_DIV_60 - * @arg @ref LL_RCC_PLLM_DIV_61 - * @arg @ref LL_RCC_PLLM_DIV_62 - * @arg @ref LL_RCC_PLLM_DIV_63 - * @param __PLLN__ Between 50/192(*) and 432 - * - * (*) value not defined in all devices. - * @param __PLLP__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLP_DIV_2 - * @arg @ref LL_RCC_PLLP_DIV_4 - * @arg @ref LL_RCC_PLLP_DIV_6 - * @arg @ref LL_RCC_PLLP_DIV_8 - * @retval PLL clock frequency (in Hz) - */ -#define __LL_RCC_CALC_PLLCLK_FREQ(__INPUTFREQ__, __PLLM__, __PLLN__, __PLLP__) ((__INPUTFREQ__) / (__PLLM__) * (__PLLN__) / \ - ((((__PLLP__) >> RCC_PLLCFGR_PLLP_Pos ) + 1U) * 2U)) - -#if defined(RCC_PLLR_SYSCLK_SUPPORT) -/** - * @brief Helper macro to calculate the PLLRCLK frequency on system domain - * @note ex: @ref __LL_RCC_CALC_PLLRCLK_FREQ (HSE_VALUE,@ref LL_RCC_PLL_GetDivider (), - * @ref LL_RCC_PLL_GetN (), @ref LL_RCC_PLL_GetR ()); - * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) - * @param __PLLM__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLM_DIV_2 - * @arg @ref LL_RCC_PLLM_DIV_3 - * @arg @ref LL_RCC_PLLM_DIV_4 - * @arg @ref LL_RCC_PLLM_DIV_5 - * @arg @ref LL_RCC_PLLM_DIV_6 - * @arg @ref LL_RCC_PLLM_DIV_7 - * @arg @ref LL_RCC_PLLM_DIV_8 - * @arg @ref LL_RCC_PLLM_DIV_9 - * @arg @ref LL_RCC_PLLM_DIV_10 - * @arg @ref LL_RCC_PLLM_DIV_11 - * @arg @ref LL_RCC_PLLM_DIV_12 - * @arg @ref LL_RCC_PLLM_DIV_13 - * @arg @ref LL_RCC_PLLM_DIV_14 - * @arg @ref LL_RCC_PLLM_DIV_15 - * @arg @ref LL_RCC_PLLM_DIV_16 - * @arg @ref LL_RCC_PLLM_DIV_17 - * @arg @ref LL_RCC_PLLM_DIV_18 - * @arg @ref LL_RCC_PLLM_DIV_19 - * @arg @ref LL_RCC_PLLM_DIV_20 - * @arg @ref LL_RCC_PLLM_DIV_21 - * @arg @ref LL_RCC_PLLM_DIV_22 - * @arg @ref LL_RCC_PLLM_DIV_23 - * @arg @ref LL_RCC_PLLM_DIV_24 - * @arg @ref LL_RCC_PLLM_DIV_25 - * @arg @ref LL_RCC_PLLM_DIV_26 - * @arg @ref LL_RCC_PLLM_DIV_27 - * @arg @ref LL_RCC_PLLM_DIV_28 - * @arg @ref LL_RCC_PLLM_DIV_29 - * @arg @ref LL_RCC_PLLM_DIV_30 - * @arg @ref LL_RCC_PLLM_DIV_31 - * @arg @ref LL_RCC_PLLM_DIV_32 - * @arg @ref LL_RCC_PLLM_DIV_33 - * @arg @ref LL_RCC_PLLM_DIV_34 - * @arg @ref LL_RCC_PLLM_DIV_35 - * @arg @ref LL_RCC_PLLM_DIV_36 - * @arg @ref LL_RCC_PLLM_DIV_37 - * @arg @ref LL_RCC_PLLM_DIV_38 - * @arg @ref LL_RCC_PLLM_DIV_39 - * @arg @ref LL_RCC_PLLM_DIV_40 - * @arg @ref LL_RCC_PLLM_DIV_41 - * @arg @ref LL_RCC_PLLM_DIV_42 - * @arg @ref LL_RCC_PLLM_DIV_43 - * @arg @ref LL_RCC_PLLM_DIV_44 - * @arg @ref LL_RCC_PLLM_DIV_45 - * @arg @ref LL_RCC_PLLM_DIV_46 - * @arg @ref LL_RCC_PLLM_DIV_47 - * @arg @ref LL_RCC_PLLM_DIV_48 - * @arg @ref LL_RCC_PLLM_DIV_49 - * @arg @ref LL_RCC_PLLM_DIV_50 - * @arg @ref LL_RCC_PLLM_DIV_51 - * @arg @ref LL_RCC_PLLM_DIV_52 - * @arg @ref LL_RCC_PLLM_DIV_53 - * @arg @ref LL_RCC_PLLM_DIV_54 - * @arg @ref LL_RCC_PLLM_DIV_55 - * @arg @ref LL_RCC_PLLM_DIV_56 - * @arg @ref LL_RCC_PLLM_DIV_57 - * @arg @ref LL_RCC_PLLM_DIV_58 - * @arg @ref LL_RCC_PLLM_DIV_59 - * @arg @ref LL_RCC_PLLM_DIV_60 - * @arg @ref LL_RCC_PLLM_DIV_61 - * @arg @ref LL_RCC_PLLM_DIV_62 - * @arg @ref LL_RCC_PLLM_DIV_63 - * @param __PLLN__ Between 50 and 432 - * @param __PLLR__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLR_DIV_2 - * @arg @ref LL_RCC_PLLR_DIV_3 - * @arg @ref LL_RCC_PLLR_DIV_4 - * @arg @ref LL_RCC_PLLR_DIV_5 - * @arg @ref LL_RCC_PLLR_DIV_6 - * @arg @ref LL_RCC_PLLR_DIV_7 - * @retval PLL clock frequency (in Hz) - */ -#define __LL_RCC_CALC_PLLRCLK_FREQ(__INPUTFREQ__, __PLLM__, __PLLN__, __PLLR__) ((__INPUTFREQ__) / (__PLLM__) * (__PLLN__) / \ - ((__PLLR__) >> RCC_PLLCFGR_PLLR_Pos )) - -#endif /* RCC_PLLR_SYSCLK_SUPPORT */ - -/** - * @brief Helper macro to calculate the PLLCLK frequency used on 48M domain - * @note ex: @ref __LL_RCC_CALC_PLLCLK_48M_FREQ (HSE_VALUE,@ref LL_RCC_PLL_GetDivider (), - * @ref LL_RCC_PLL_GetN (), @ref LL_RCC_PLL_GetQ ()); - * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) - * @param __PLLM__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLM_DIV_2 - * @arg @ref LL_RCC_PLLM_DIV_3 - * @arg @ref LL_RCC_PLLM_DIV_4 - * @arg @ref LL_RCC_PLLM_DIV_5 - * @arg @ref LL_RCC_PLLM_DIV_6 - * @arg @ref LL_RCC_PLLM_DIV_7 - * @arg @ref LL_RCC_PLLM_DIV_8 - * @arg @ref LL_RCC_PLLM_DIV_9 - * @arg @ref LL_RCC_PLLM_DIV_10 - * @arg @ref LL_RCC_PLLM_DIV_11 - * @arg @ref LL_RCC_PLLM_DIV_12 - * @arg @ref LL_RCC_PLLM_DIV_13 - * @arg @ref LL_RCC_PLLM_DIV_14 - * @arg @ref LL_RCC_PLLM_DIV_15 - * @arg @ref LL_RCC_PLLM_DIV_16 - * @arg @ref LL_RCC_PLLM_DIV_17 - * @arg @ref LL_RCC_PLLM_DIV_18 - * @arg @ref LL_RCC_PLLM_DIV_19 - * @arg @ref LL_RCC_PLLM_DIV_20 - * @arg @ref LL_RCC_PLLM_DIV_21 - * @arg @ref LL_RCC_PLLM_DIV_22 - * @arg @ref LL_RCC_PLLM_DIV_23 - * @arg @ref LL_RCC_PLLM_DIV_24 - * @arg @ref LL_RCC_PLLM_DIV_25 - * @arg @ref LL_RCC_PLLM_DIV_26 - * @arg @ref LL_RCC_PLLM_DIV_27 - * @arg @ref LL_RCC_PLLM_DIV_28 - * @arg @ref LL_RCC_PLLM_DIV_29 - * @arg @ref LL_RCC_PLLM_DIV_30 - * @arg @ref LL_RCC_PLLM_DIV_31 - * @arg @ref LL_RCC_PLLM_DIV_32 - * @arg @ref LL_RCC_PLLM_DIV_33 - * @arg @ref LL_RCC_PLLM_DIV_34 - * @arg @ref LL_RCC_PLLM_DIV_35 - * @arg @ref LL_RCC_PLLM_DIV_36 - * @arg @ref LL_RCC_PLLM_DIV_37 - * @arg @ref LL_RCC_PLLM_DIV_38 - * @arg @ref LL_RCC_PLLM_DIV_39 - * @arg @ref LL_RCC_PLLM_DIV_40 - * @arg @ref LL_RCC_PLLM_DIV_41 - * @arg @ref LL_RCC_PLLM_DIV_42 - * @arg @ref LL_RCC_PLLM_DIV_43 - * @arg @ref LL_RCC_PLLM_DIV_44 - * @arg @ref LL_RCC_PLLM_DIV_45 - * @arg @ref LL_RCC_PLLM_DIV_46 - * @arg @ref LL_RCC_PLLM_DIV_47 - * @arg @ref LL_RCC_PLLM_DIV_48 - * @arg @ref LL_RCC_PLLM_DIV_49 - * @arg @ref LL_RCC_PLLM_DIV_50 - * @arg @ref LL_RCC_PLLM_DIV_51 - * @arg @ref LL_RCC_PLLM_DIV_52 - * @arg @ref LL_RCC_PLLM_DIV_53 - * @arg @ref LL_RCC_PLLM_DIV_54 - * @arg @ref LL_RCC_PLLM_DIV_55 - * @arg @ref LL_RCC_PLLM_DIV_56 - * @arg @ref LL_RCC_PLLM_DIV_57 - * @arg @ref LL_RCC_PLLM_DIV_58 - * @arg @ref LL_RCC_PLLM_DIV_59 - * @arg @ref LL_RCC_PLLM_DIV_60 - * @arg @ref LL_RCC_PLLM_DIV_61 - * @arg @ref LL_RCC_PLLM_DIV_62 - * @arg @ref LL_RCC_PLLM_DIV_63 - * @param __PLLN__ Between 50/192(*) and 432 - * - * (*) value not defined in all devices. - * @param __PLLQ__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLQ_DIV_2 - * @arg @ref LL_RCC_PLLQ_DIV_3 - * @arg @ref LL_RCC_PLLQ_DIV_4 - * @arg @ref LL_RCC_PLLQ_DIV_5 - * @arg @ref LL_RCC_PLLQ_DIV_6 - * @arg @ref LL_RCC_PLLQ_DIV_7 - * @arg @ref LL_RCC_PLLQ_DIV_8 - * @arg @ref LL_RCC_PLLQ_DIV_9 - * @arg @ref LL_RCC_PLLQ_DIV_10 - * @arg @ref LL_RCC_PLLQ_DIV_11 - * @arg @ref LL_RCC_PLLQ_DIV_12 - * @arg @ref LL_RCC_PLLQ_DIV_13 - * @arg @ref LL_RCC_PLLQ_DIV_14 - * @arg @ref LL_RCC_PLLQ_DIV_15 - * @retval PLL clock frequency (in Hz) - */ -#define __LL_RCC_CALC_PLLCLK_48M_FREQ(__INPUTFREQ__, __PLLM__, __PLLN__, __PLLQ__) ((__INPUTFREQ__) / (__PLLM__) * (__PLLN__) / \ - ((__PLLQ__) >> RCC_PLLCFGR_PLLQ_Pos )) - -#if defined(DSI) -/** - * @brief Helper macro to calculate the PLLCLK frequency used on DSI - * @note ex: @ref __LL_RCC_CALC_PLLCLK_DSI_FREQ (HSE_VALUE, @ref LL_RCC_PLL_GetDivider (), - * @ref LL_RCC_PLL_GetN (), @ref LL_RCC_PLL_GetR ()); - * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) - * @param __PLLM__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLM_DIV_2 - * @arg @ref LL_RCC_PLLM_DIV_3 - * @arg @ref LL_RCC_PLLM_DIV_4 - * @arg @ref LL_RCC_PLLM_DIV_5 - * @arg @ref LL_RCC_PLLM_DIV_6 - * @arg @ref LL_RCC_PLLM_DIV_7 - * @arg @ref LL_RCC_PLLM_DIV_8 - * @arg @ref LL_RCC_PLLM_DIV_9 - * @arg @ref LL_RCC_PLLM_DIV_10 - * @arg @ref LL_RCC_PLLM_DIV_11 - * @arg @ref LL_RCC_PLLM_DIV_12 - * @arg @ref LL_RCC_PLLM_DIV_13 - * @arg @ref LL_RCC_PLLM_DIV_14 - * @arg @ref LL_RCC_PLLM_DIV_15 - * @arg @ref LL_RCC_PLLM_DIV_16 - * @arg @ref LL_RCC_PLLM_DIV_17 - * @arg @ref LL_RCC_PLLM_DIV_18 - * @arg @ref LL_RCC_PLLM_DIV_19 - * @arg @ref LL_RCC_PLLM_DIV_20 - * @arg @ref LL_RCC_PLLM_DIV_21 - * @arg @ref LL_RCC_PLLM_DIV_22 - * @arg @ref LL_RCC_PLLM_DIV_23 - * @arg @ref LL_RCC_PLLM_DIV_24 - * @arg @ref LL_RCC_PLLM_DIV_25 - * @arg @ref LL_RCC_PLLM_DIV_26 - * @arg @ref LL_RCC_PLLM_DIV_27 - * @arg @ref LL_RCC_PLLM_DIV_28 - * @arg @ref LL_RCC_PLLM_DIV_29 - * @arg @ref LL_RCC_PLLM_DIV_30 - * @arg @ref LL_RCC_PLLM_DIV_31 - * @arg @ref LL_RCC_PLLM_DIV_32 - * @arg @ref LL_RCC_PLLM_DIV_33 - * @arg @ref LL_RCC_PLLM_DIV_34 - * @arg @ref LL_RCC_PLLM_DIV_35 - * @arg @ref LL_RCC_PLLM_DIV_36 - * @arg @ref LL_RCC_PLLM_DIV_37 - * @arg @ref LL_RCC_PLLM_DIV_38 - * @arg @ref LL_RCC_PLLM_DIV_39 - * @arg @ref LL_RCC_PLLM_DIV_40 - * @arg @ref LL_RCC_PLLM_DIV_41 - * @arg @ref LL_RCC_PLLM_DIV_42 - * @arg @ref LL_RCC_PLLM_DIV_43 - * @arg @ref LL_RCC_PLLM_DIV_44 - * @arg @ref LL_RCC_PLLM_DIV_45 - * @arg @ref LL_RCC_PLLM_DIV_46 - * @arg @ref LL_RCC_PLLM_DIV_47 - * @arg @ref LL_RCC_PLLM_DIV_48 - * @arg @ref LL_RCC_PLLM_DIV_49 - * @arg @ref LL_RCC_PLLM_DIV_50 - * @arg @ref LL_RCC_PLLM_DIV_51 - * @arg @ref LL_RCC_PLLM_DIV_52 - * @arg @ref LL_RCC_PLLM_DIV_53 - * @arg @ref LL_RCC_PLLM_DIV_54 - * @arg @ref LL_RCC_PLLM_DIV_55 - * @arg @ref LL_RCC_PLLM_DIV_56 - * @arg @ref LL_RCC_PLLM_DIV_57 - * @arg @ref LL_RCC_PLLM_DIV_58 - * @arg @ref LL_RCC_PLLM_DIV_59 - * @arg @ref LL_RCC_PLLM_DIV_60 - * @arg @ref LL_RCC_PLLM_DIV_61 - * @arg @ref LL_RCC_PLLM_DIV_62 - * @arg @ref LL_RCC_PLLM_DIV_63 - * @param __PLLN__ Between 50 and 432 - * @param __PLLR__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLR_DIV_2 - * @arg @ref LL_RCC_PLLR_DIV_3 - * @arg @ref LL_RCC_PLLR_DIV_4 - * @arg @ref LL_RCC_PLLR_DIV_5 - * @arg @ref LL_RCC_PLLR_DIV_6 - * @arg @ref LL_RCC_PLLR_DIV_7 - * @retval PLL clock frequency (in Hz) - */ -#define __LL_RCC_CALC_PLLCLK_DSI_FREQ(__INPUTFREQ__, __PLLM__, __PLLN__, __PLLR__) ((__INPUTFREQ__) / (__PLLM__) * (__PLLN__) / \ - ((__PLLR__) >> RCC_PLLCFGR_PLLR_Pos )) -#endif /* DSI */ - -#if defined(RCC_PLLR_I2S_CLKSOURCE_SUPPORT) -/** - * @brief Helper macro to calculate the PLLCLK frequency used on I2S - * @note ex: @ref __LL_RCC_CALC_PLLCLK_I2S_FREQ (HSE_VALUE, @ref LL_RCC_PLL_GetDivider (), - * @ref LL_RCC_PLL_GetN (), @ref LL_RCC_PLL_GetR ()); - * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) - * @param __PLLM__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLM_DIV_2 - * @arg @ref LL_RCC_PLLM_DIV_3 - * @arg @ref LL_RCC_PLLM_DIV_4 - * @arg @ref LL_RCC_PLLM_DIV_5 - * @arg @ref LL_RCC_PLLM_DIV_6 - * @arg @ref LL_RCC_PLLM_DIV_7 - * @arg @ref LL_RCC_PLLM_DIV_8 - * @arg @ref LL_RCC_PLLM_DIV_9 - * @arg @ref LL_RCC_PLLM_DIV_10 - * @arg @ref LL_RCC_PLLM_DIV_11 - * @arg @ref LL_RCC_PLLM_DIV_12 - * @arg @ref LL_RCC_PLLM_DIV_13 - * @arg @ref LL_RCC_PLLM_DIV_14 - * @arg @ref LL_RCC_PLLM_DIV_15 - * @arg @ref LL_RCC_PLLM_DIV_16 - * @arg @ref LL_RCC_PLLM_DIV_17 - * @arg @ref LL_RCC_PLLM_DIV_18 - * @arg @ref LL_RCC_PLLM_DIV_19 - * @arg @ref LL_RCC_PLLM_DIV_20 - * @arg @ref LL_RCC_PLLM_DIV_21 - * @arg @ref LL_RCC_PLLM_DIV_22 - * @arg @ref LL_RCC_PLLM_DIV_23 - * @arg @ref LL_RCC_PLLM_DIV_24 - * @arg @ref LL_RCC_PLLM_DIV_25 - * @arg @ref LL_RCC_PLLM_DIV_26 - * @arg @ref LL_RCC_PLLM_DIV_27 - * @arg @ref LL_RCC_PLLM_DIV_28 - * @arg @ref LL_RCC_PLLM_DIV_29 - * @arg @ref LL_RCC_PLLM_DIV_30 - * @arg @ref LL_RCC_PLLM_DIV_31 - * @arg @ref LL_RCC_PLLM_DIV_32 - * @arg @ref LL_RCC_PLLM_DIV_33 - * @arg @ref LL_RCC_PLLM_DIV_34 - * @arg @ref LL_RCC_PLLM_DIV_35 - * @arg @ref LL_RCC_PLLM_DIV_36 - * @arg @ref LL_RCC_PLLM_DIV_37 - * @arg @ref LL_RCC_PLLM_DIV_38 - * @arg @ref LL_RCC_PLLM_DIV_39 - * @arg @ref LL_RCC_PLLM_DIV_40 - * @arg @ref LL_RCC_PLLM_DIV_41 - * @arg @ref LL_RCC_PLLM_DIV_42 - * @arg @ref LL_RCC_PLLM_DIV_43 - * @arg @ref LL_RCC_PLLM_DIV_44 - * @arg @ref LL_RCC_PLLM_DIV_45 - * @arg @ref LL_RCC_PLLM_DIV_46 - * @arg @ref LL_RCC_PLLM_DIV_47 - * @arg @ref LL_RCC_PLLM_DIV_48 - * @arg @ref LL_RCC_PLLM_DIV_49 - * @arg @ref LL_RCC_PLLM_DIV_50 - * @arg @ref LL_RCC_PLLM_DIV_51 - * @arg @ref LL_RCC_PLLM_DIV_52 - * @arg @ref LL_RCC_PLLM_DIV_53 - * @arg @ref LL_RCC_PLLM_DIV_54 - * @arg @ref LL_RCC_PLLM_DIV_55 - * @arg @ref LL_RCC_PLLM_DIV_56 - * @arg @ref LL_RCC_PLLM_DIV_57 - * @arg @ref LL_RCC_PLLM_DIV_58 - * @arg @ref LL_RCC_PLLM_DIV_59 - * @arg @ref LL_RCC_PLLM_DIV_60 - * @arg @ref LL_RCC_PLLM_DIV_61 - * @arg @ref LL_RCC_PLLM_DIV_62 - * @arg @ref LL_RCC_PLLM_DIV_63 - * @param __PLLN__ Between 50 and 432 - * @param __PLLR__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLR_DIV_2 - * @arg @ref LL_RCC_PLLR_DIV_3 - * @arg @ref LL_RCC_PLLR_DIV_4 - * @arg @ref LL_RCC_PLLR_DIV_5 - * @arg @ref LL_RCC_PLLR_DIV_6 - * @arg @ref LL_RCC_PLLR_DIV_7 - * @retval PLL clock frequency (in Hz) - */ -#define __LL_RCC_CALC_PLLCLK_I2S_FREQ(__INPUTFREQ__, __PLLM__, __PLLN__, __PLLR__) ((__INPUTFREQ__) / (__PLLM__) * (__PLLN__) / \ - ((__PLLR__) >> RCC_PLLCFGR_PLLR_Pos )) -#endif /* RCC_PLLR_I2S_CLKSOURCE_SUPPORT */ - -#if defined(SPDIFRX) -/** - * @brief Helper macro to calculate the PLLCLK frequency used on SPDIFRX - * @note ex: @ref __LL_RCC_CALC_PLLCLK_SPDIFRX_FREQ (HSE_VALUE, @ref LL_RCC_PLL_GetDivider (), - * @ref LL_RCC_PLL_GetN (), @ref LL_RCC_PLL_GetR ()); - * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) - * @param __PLLM__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLM_DIV_2 - * @arg @ref LL_RCC_PLLM_DIV_3 - * @arg @ref LL_RCC_PLLM_DIV_4 - * @arg @ref LL_RCC_PLLM_DIV_5 - * @arg @ref LL_RCC_PLLM_DIV_6 - * @arg @ref LL_RCC_PLLM_DIV_7 - * @arg @ref LL_RCC_PLLM_DIV_8 - * @arg @ref LL_RCC_PLLM_DIV_9 - * @arg @ref LL_RCC_PLLM_DIV_10 - * @arg @ref LL_RCC_PLLM_DIV_11 - * @arg @ref LL_RCC_PLLM_DIV_12 - * @arg @ref LL_RCC_PLLM_DIV_13 - * @arg @ref LL_RCC_PLLM_DIV_14 - * @arg @ref LL_RCC_PLLM_DIV_15 - * @arg @ref LL_RCC_PLLM_DIV_16 - * @arg @ref LL_RCC_PLLM_DIV_17 - * @arg @ref LL_RCC_PLLM_DIV_18 - * @arg @ref LL_RCC_PLLM_DIV_19 - * @arg @ref LL_RCC_PLLM_DIV_20 - * @arg @ref LL_RCC_PLLM_DIV_21 - * @arg @ref LL_RCC_PLLM_DIV_22 - * @arg @ref LL_RCC_PLLM_DIV_23 - * @arg @ref LL_RCC_PLLM_DIV_24 - * @arg @ref LL_RCC_PLLM_DIV_25 - * @arg @ref LL_RCC_PLLM_DIV_26 - * @arg @ref LL_RCC_PLLM_DIV_27 - * @arg @ref LL_RCC_PLLM_DIV_28 - * @arg @ref LL_RCC_PLLM_DIV_29 - * @arg @ref LL_RCC_PLLM_DIV_30 - * @arg @ref LL_RCC_PLLM_DIV_31 - * @arg @ref LL_RCC_PLLM_DIV_32 - * @arg @ref LL_RCC_PLLM_DIV_33 - * @arg @ref LL_RCC_PLLM_DIV_34 - * @arg @ref LL_RCC_PLLM_DIV_35 - * @arg @ref LL_RCC_PLLM_DIV_36 - * @arg @ref LL_RCC_PLLM_DIV_37 - * @arg @ref LL_RCC_PLLM_DIV_38 - * @arg @ref LL_RCC_PLLM_DIV_39 - * @arg @ref LL_RCC_PLLM_DIV_40 - * @arg @ref LL_RCC_PLLM_DIV_41 - * @arg @ref LL_RCC_PLLM_DIV_42 - * @arg @ref LL_RCC_PLLM_DIV_43 - * @arg @ref LL_RCC_PLLM_DIV_44 - * @arg @ref LL_RCC_PLLM_DIV_45 - * @arg @ref LL_RCC_PLLM_DIV_46 - * @arg @ref LL_RCC_PLLM_DIV_47 - * @arg @ref LL_RCC_PLLM_DIV_48 - * @arg @ref LL_RCC_PLLM_DIV_49 - * @arg @ref LL_RCC_PLLM_DIV_50 - * @arg @ref LL_RCC_PLLM_DIV_51 - * @arg @ref LL_RCC_PLLM_DIV_52 - * @arg @ref LL_RCC_PLLM_DIV_53 - * @arg @ref LL_RCC_PLLM_DIV_54 - * @arg @ref LL_RCC_PLLM_DIV_55 - * @arg @ref LL_RCC_PLLM_DIV_56 - * @arg @ref LL_RCC_PLLM_DIV_57 - * @arg @ref LL_RCC_PLLM_DIV_58 - * @arg @ref LL_RCC_PLLM_DIV_59 - * @arg @ref LL_RCC_PLLM_DIV_60 - * @arg @ref LL_RCC_PLLM_DIV_61 - * @arg @ref LL_RCC_PLLM_DIV_62 - * @arg @ref LL_RCC_PLLM_DIV_63 - * @param __PLLN__ Between 50 and 432 - * @param __PLLR__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLR_DIV_2 - * @arg @ref LL_RCC_PLLR_DIV_3 - * @arg @ref LL_RCC_PLLR_DIV_4 - * @arg @ref LL_RCC_PLLR_DIV_5 - * @arg @ref LL_RCC_PLLR_DIV_6 - * @arg @ref LL_RCC_PLLR_DIV_7 - * @retval PLL clock frequency (in Hz) - */ -#define __LL_RCC_CALC_PLLCLK_SPDIFRX_FREQ(__INPUTFREQ__, __PLLM__, __PLLN__, __PLLR__) ((__INPUTFREQ__) / (__PLLM__) * (__PLLN__) / \ - ((__PLLR__) >> RCC_PLLCFGR_PLLR_Pos )) -#endif /* SPDIFRX */ - -#if defined(RCC_PLLCFGR_PLLR) -#if defined(SAI1) -/** - * @brief Helper macro to calculate the PLLCLK frequency used on SAI - * @note ex: @ref __LL_RCC_CALC_PLLCLK_SAI_FREQ (HSE_VALUE, @ref LL_RCC_PLL_GetDivider (), - * @ref LL_RCC_PLL_GetN (), @ref LL_RCC_PLL_GetR (), @ref LL_RCC_PLL_GetDIVR ()); - * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) - * @param __PLLM__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLM_DIV_2 - * @arg @ref LL_RCC_PLLM_DIV_3 - * @arg @ref LL_RCC_PLLM_DIV_4 - * @arg @ref LL_RCC_PLLM_DIV_5 - * @arg @ref LL_RCC_PLLM_DIV_6 - * @arg @ref LL_RCC_PLLM_DIV_7 - * @arg @ref LL_RCC_PLLM_DIV_8 - * @arg @ref LL_RCC_PLLM_DIV_9 - * @arg @ref LL_RCC_PLLM_DIV_10 - * @arg @ref LL_RCC_PLLM_DIV_11 - * @arg @ref LL_RCC_PLLM_DIV_12 - * @arg @ref LL_RCC_PLLM_DIV_13 - * @arg @ref LL_RCC_PLLM_DIV_14 - * @arg @ref LL_RCC_PLLM_DIV_15 - * @arg @ref LL_RCC_PLLM_DIV_16 - * @arg @ref LL_RCC_PLLM_DIV_17 - * @arg @ref LL_RCC_PLLM_DIV_18 - * @arg @ref LL_RCC_PLLM_DIV_19 - * @arg @ref LL_RCC_PLLM_DIV_20 - * @arg @ref LL_RCC_PLLM_DIV_21 - * @arg @ref LL_RCC_PLLM_DIV_22 - * @arg @ref LL_RCC_PLLM_DIV_23 - * @arg @ref LL_RCC_PLLM_DIV_24 - * @arg @ref LL_RCC_PLLM_DIV_25 - * @arg @ref LL_RCC_PLLM_DIV_26 - * @arg @ref LL_RCC_PLLM_DIV_27 - * @arg @ref LL_RCC_PLLM_DIV_28 - * @arg @ref LL_RCC_PLLM_DIV_29 - * @arg @ref LL_RCC_PLLM_DIV_30 - * @arg @ref LL_RCC_PLLM_DIV_31 - * @arg @ref LL_RCC_PLLM_DIV_32 - * @arg @ref LL_RCC_PLLM_DIV_33 - * @arg @ref LL_RCC_PLLM_DIV_34 - * @arg @ref LL_RCC_PLLM_DIV_35 - * @arg @ref LL_RCC_PLLM_DIV_36 - * @arg @ref LL_RCC_PLLM_DIV_37 - * @arg @ref LL_RCC_PLLM_DIV_38 - * @arg @ref LL_RCC_PLLM_DIV_39 - * @arg @ref LL_RCC_PLLM_DIV_40 - * @arg @ref LL_RCC_PLLM_DIV_41 - * @arg @ref LL_RCC_PLLM_DIV_42 - * @arg @ref LL_RCC_PLLM_DIV_43 - * @arg @ref LL_RCC_PLLM_DIV_44 - * @arg @ref LL_RCC_PLLM_DIV_45 - * @arg @ref LL_RCC_PLLM_DIV_46 - * @arg @ref LL_RCC_PLLM_DIV_47 - * @arg @ref LL_RCC_PLLM_DIV_48 - * @arg @ref LL_RCC_PLLM_DIV_49 - * @arg @ref LL_RCC_PLLM_DIV_50 - * @arg @ref LL_RCC_PLLM_DIV_51 - * @arg @ref LL_RCC_PLLM_DIV_52 - * @arg @ref LL_RCC_PLLM_DIV_53 - * @arg @ref LL_RCC_PLLM_DIV_54 - * @arg @ref LL_RCC_PLLM_DIV_55 - * @arg @ref LL_RCC_PLLM_DIV_56 - * @arg @ref LL_RCC_PLLM_DIV_57 - * @arg @ref LL_RCC_PLLM_DIV_58 - * @arg @ref LL_RCC_PLLM_DIV_59 - * @arg @ref LL_RCC_PLLM_DIV_60 - * @arg @ref LL_RCC_PLLM_DIV_61 - * @arg @ref LL_RCC_PLLM_DIV_62 - * @arg @ref LL_RCC_PLLM_DIV_63 - * @param __PLLN__ Between 50 and 432 - * @param __PLLR__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLR_DIV_2 - * @arg @ref LL_RCC_PLLR_DIV_3 - * @arg @ref LL_RCC_PLLR_DIV_4 - * @arg @ref LL_RCC_PLLR_DIV_5 - * @arg @ref LL_RCC_PLLR_DIV_6 - * @arg @ref LL_RCC_PLLR_DIV_7 - * @param __PLLDIVR__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLDIVR_DIV_1 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_2 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_3 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_4 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_5 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_6 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_7 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_8 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_9 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_10 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_11 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_12 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_13 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_14 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_15 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_16 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_17 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_18 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_19 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_20 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_21 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_22 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_23 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_24 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_25 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_26 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_27 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_28 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_29 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_30 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_31 (*) - * - * (*) value not defined in all devices. - * @retval PLL clock frequency (in Hz) - */ -#if defined(RCC_DCKCFGR_PLLDIVR) -#define __LL_RCC_CALC_PLLCLK_SAI_FREQ(__INPUTFREQ__, __PLLM__, __PLLN__, __PLLR__, __PLLDIVR__) (((__INPUTFREQ__) / (__PLLM__) * (__PLLN__) / \ - ((__PLLR__) >> RCC_PLLCFGR_PLLR_Pos )) / ((__PLLDIVR__) >> RCC_DCKCFGR_PLLDIVR_Pos )) -#else -#define __LL_RCC_CALC_PLLCLK_SAI_FREQ(__INPUTFREQ__, __PLLM__, __PLLN__, __PLLR__) ((__INPUTFREQ__) / (__PLLM__) * (__PLLN__) / \ - ((__PLLR__) >> RCC_PLLCFGR_PLLR_Pos )) -#endif /* RCC_DCKCFGR_PLLDIVR */ -#endif /* SAI1 */ -#endif /* RCC_PLLCFGR_PLLR */ - -#if defined(RCC_PLLSAI_SUPPORT) -/** - * @brief Helper macro to calculate the PLLSAI frequency used for SAI domain - * @note ex: @ref __LL_RCC_CALC_PLLSAI_SAI_FREQ (HSE_VALUE,@ref LL_RCC_PLLSAI_GetDivider (), - * @ref LL_RCC_PLLSAI_GetN (), @ref LL_RCC_PLLSAI_GetQ (), @ref LL_RCC_PLLSAI_GetDIVQ ()); - * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) - * @param __PLLM__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIM_DIV_2 - * @arg @ref LL_RCC_PLLSAIM_DIV_3 - * @arg @ref LL_RCC_PLLSAIM_DIV_4 - * @arg @ref LL_RCC_PLLSAIM_DIV_5 - * @arg @ref LL_RCC_PLLSAIM_DIV_6 - * @arg @ref LL_RCC_PLLSAIM_DIV_7 - * @arg @ref LL_RCC_PLLSAIM_DIV_8 - * @arg @ref LL_RCC_PLLSAIM_DIV_9 - * @arg @ref LL_RCC_PLLSAIM_DIV_10 - * @arg @ref LL_RCC_PLLSAIM_DIV_11 - * @arg @ref LL_RCC_PLLSAIM_DIV_12 - * @arg @ref LL_RCC_PLLSAIM_DIV_13 - * @arg @ref LL_RCC_PLLSAIM_DIV_14 - * @arg @ref LL_RCC_PLLSAIM_DIV_15 - * @arg @ref LL_RCC_PLLSAIM_DIV_16 - * @arg @ref LL_RCC_PLLSAIM_DIV_17 - * @arg @ref LL_RCC_PLLSAIM_DIV_18 - * @arg @ref LL_RCC_PLLSAIM_DIV_19 - * @arg @ref LL_RCC_PLLSAIM_DIV_20 - * @arg @ref LL_RCC_PLLSAIM_DIV_21 - * @arg @ref LL_RCC_PLLSAIM_DIV_22 - * @arg @ref LL_RCC_PLLSAIM_DIV_23 - * @arg @ref LL_RCC_PLLSAIM_DIV_24 - * @arg @ref LL_RCC_PLLSAIM_DIV_25 - * @arg @ref LL_RCC_PLLSAIM_DIV_26 - * @arg @ref LL_RCC_PLLSAIM_DIV_27 - * @arg @ref LL_RCC_PLLSAIM_DIV_28 - * @arg @ref LL_RCC_PLLSAIM_DIV_29 - * @arg @ref LL_RCC_PLLSAIM_DIV_30 - * @arg @ref LL_RCC_PLLSAIM_DIV_31 - * @arg @ref LL_RCC_PLLSAIM_DIV_32 - * @arg @ref LL_RCC_PLLSAIM_DIV_33 - * @arg @ref LL_RCC_PLLSAIM_DIV_34 - * @arg @ref LL_RCC_PLLSAIM_DIV_35 - * @arg @ref LL_RCC_PLLSAIM_DIV_36 - * @arg @ref LL_RCC_PLLSAIM_DIV_37 - * @arg @ref LL_RCC_PLLSAIM_DIV_38 - * @arg @ref LL_RCC_PLLSAIM_DIV_39 - * @arg @ref LL_RCC_PLLSAIM_DIV_40 - * @arg @ref LL_RCC_PLLSAIM_DIV_41 - * @arg @ref LL_RCC_PLLSAIM_DIV_42 - * @arg @ref LL_RCC_PLLSAIM_DIV_43 - * @arg @ref LL_RCC_PLLSAIM_DIV_44 - * @arg @ref LL_RCC_PLLSAIM_DIV_45 - * @arg @ref LL_RCC_PLLSAIM_DIV_46 - * @arg @ref LL_RCC_PLLSAIM_DIV_47 - * @arg @ref LL_RCC_PLLSAIM_DIV_48 - * @arg @ref LL_RCC_PLLSAIM_DIV_49 - * @arg @ref LL_RCC_PLLSAIM_DIV_50 - * @arg @ref LL_RCC_PLLSAIM_DIV_51 - * @arg @ref LL_RCC_PLLSAIM_DIV_52 - * @arg @ref LL_RCC_PLLSAIM_DIV_53 - * @arg @ref LL_RCC_PLLSAIM_DIV_54 - * @arg @ref LL_RCC_PLLSAIM_DIV_55 - * @arg @ref LL_RCC_PLLSAIM_DIV_56 - * @arg @ref LL_RCC_PLLSAIM_DIV_57 - * @arg @ref LL_RCC_PLLSAIM_DIV_58 - * @arg @ref LL_RCC_PLLSAIM_DIV_59 - * @arg @ref LL_RCC_PLLSAIM_DIV_60 - * @arg @ref LL_RCC_PLLSAIM_DIV_61 - * @arg @ref LL_RCC_PLLSAIM_DIV_62 - * @arg @ref LL_RCC_PLLSAIM_DIV_63 - * @param __PLLSAIN__ Between 49/50(*) and 432 - * - * (*) value not defined in all devices. - * @param __PLLSAIQ__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIQ_DIV_2 - * @arg @ref LL_RCC_PLLSAIQ_DIV_3 - * @arg @ref LL_RCC_PLLSAIQ_DIV_4 - * @arg @ref LL_RCC_PLLSAIQ_DIV_5 - * @arg @ref LL_RCC_PLLSAIQ_DIV_6 - * @arg @ref LL_RCC_PLLSAIQ_DIV_7 - * @arg @ref LL_RCC_PLLSAIQ_DIV_8 - * @arg @ref LL_RCC_PLLSAIQ_DIV_9 - * @arg @ref LL_RCC_PLLSAIQ_DIV_10 - * @arg @ref LL_RCC_PLLSAIQ_DIV_11 - * @arg @ref LL_RCC_PLLSAIQ_DIV_12 - * @arg @ref LL_RCC_PLLSAIQ_DIV_13 - * @arg @ref LL_RCC_PLLSAIQ_DIV_14 - * @arg @ref LL_RCC_PLLSAIQ_DIV_15 - * @param __PLLSAIDIVQ__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_1 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_2 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_3 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_4 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_5 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_6 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_7 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_8 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_9 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_10 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_11 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_12 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_13 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_14 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_15 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_16 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_17 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_18 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_19 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_20 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_21 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_22 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_23 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_24 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_25 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_26 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_27 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_28 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_29 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_30 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_31 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_32 - * @retval PLLSAI clock frequency (in Hz) - */ -#define __LL_RCC_CALC_PLLSAI_SAI_FREQ(__INPUTFREQ__, __PLLM__, __PLLSAIN__, __PLLSAIQ__, __PLLSAIDIVQ__) (((__INPUTFREQ__) / (__PLLM__)) * (__PLLSAIN__) / \ - (((__PLLSAIQ__) >> RCC_PLLSAICFGR_PLLSAIQ_Pos) * (((__PLLSAIDIVQ__) >> RCC_DCKCFGR_PLLSAIDIVQ_Pos) + 1U))) - -#if defined(RCC_PLLSAICFGR_PLLSAIP) -/** - * @brief Helper macro to calculate the PLLSAI frequency used on 48Mhz domain - * @note ex: @ref __LL_RCC_CALC_PLLSAI_48M_FREQ (HSE_VALUE,@ref LL_RCC_PLLSAI_GetDivider (), - * @ref LL_RCC_PLLSAI_GetN (), @ref LL_RCC_PLLSAI_GetP ()); - * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) - * @param __PLLM__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIM_DIV_2 - * @arg @ref LL_RCC_PLLSAIM_DIV_3 - * @arg @ref LL_RCC_PLLSAIM_DIV_4 - * @arg @ref LL_RCC_PLLSAIM_DIV_5 - * @arg @ref LL_RCC_PLLSAIM_DIV_6 - * @arg @ref LL_RCC_PLLSAIM_DIV_7 - * @arg @ref LL_RCC_PLLSAIM_DIV_8 - * @arg @ref LL_RCC_PLLSAIM_DIV_9 - * @arg @ref LL_RCC_PLLSAIM_DIV_10 - * @arg @ref LL_RCC_PLLSAIM_DIV_11 - * @arg @ref LL_RCC_PLLSAIM_DIV_12 - * @arg @ref LL_RCC_PLLSAIM_DIV_13 - * @arg @ref LL_RCC_PLLSAIM_DIV_14 - * @arg @ref LL_RCC_PLLSAIM_DIV_15 - * @arg @ref LL_RCC_PLLSAIM_DIV_16 - * @arg @ref LL_RCC_PLLSAIM_DIV_17 - * @arg @ref LL_RCC_PLLSAIM_DIV_18 - * @arg @ref LL_RCC_PLLSAIM_DIV_19 - * @arg @ref LL_RCC_PLLSAIM_DIV_20 - * @arg @ref LL_RCC_PLLSAIM_DIV_21 - * @arg @ref LL_RCC_PLLSAIM_DIV_22 - * @arg @ref LL_RCC_PLLSAIM_DIV_23 - * @arg @ref LL_RCC_PLLSAIM_DIV_24 - * @arg @ref LL_RCC_PLLSAIM_DIV_25 - * @arg @ref LL_RCC_PLLSAIM_DIV_26 - * @arg @ref LL_RCC_PLLSAIM_DIV_27 - * @arg @ref LL_RCC_PLLSAIM_DIV_28 - * @arg @ref LL_RCC_PLLSAIM_DIV_29 - * @arg @ref LL_RCC_PLLSAIM_DIV_30 - * @arg @ref LL_RCC_PLLSAIM_DIV_31 - * @arg @ref LL_RCC_PLLSAIM_DIV_32 - * @arg @ref LL_RCC_PLLSAIM_DIV_33 - * @arg @ref LL_RCC_PLLSAIM_DIV_34 - * @arg @ref LL_RCC_PLLSAIM_DIV_35 - * @arg @ref LL_RCC_PLLSAIM_DIV_36 - * @arg @ref LL_RCC_PLLSAIM_DIV_37 - * @arg @ref LL_RCC_PLLSAIM_DIV_38 - * @arg @ref LL_RCC_PLLSAIM_DIV_39 - * @arg @ref LL_RCC_PLLSAIM_DIV_40 - * @arg @ref LL_RCC_PLLSAIM_DIV_41 - * @arg @ref LL_RCC_PLLSAIM_DIV_42 - * @arg @ref LL_RCC_PLLSAIM_DIV_43 - * @arg @ref LL_RCC_PLLSAIM_DIV_44 - * @arg @ref LL_RCC_PLLSAIM_DIV_45 - * @arg @ref LL_RCC_PLLSAIM_DIV_46 - * @arg @ref LL_RCC_PLLSAIM_DIV_47 - * @arg @ref LL_RCC_PLLSAIM_DIV_48 - * @arg @ref LL_RCC_PLLSAIM_DIV_49 - * @arg @ref LL_RCC_PLLSAIM_DIV_50 - * @arg @ref LL_RCC_PLLSAIM_DIV_51 - * @arg @ref LL_RCC_PLLSAIM_DIV_52 - * @arg @ref LL_RCC_PLLSAIM_DIV_53 - * @arg @ref LL_RCC_PLLSAIM_DIV_54 - * @arg @ref LL_RCC_PLLSAIM_DIV_55 - * @arg @ref LL_RCC_PLLSAIM_DIV_56 - * @arg @ref LL_RCC_PLLSAIM_DIV_57 - * @arg @ref LL_RCC_PLLSAIM_DIV_58 - * @arg @ref LL_RCC_PLLSAIM_DIV_59 - * @arg @ref LL_RCC_PLLSAIM_DIV_60 - * @arg @ref LL_RCC_PLLSAIM_DIV_61 - * @arg @ref LL_RCC_PLLSAIM_DIV_62 - * @arg @ref LL_RCC_PLLSAIM_DIV_63 - * @param __PLLSAIN__ Between 50 and 432 - * @param __PLLSAIP__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIP_DIV_2 - * @arg @ref LL_RCC_PLLSAIP_DIV_4 - * @arg @ref LL_RCC_PLLSAIP_DIV_6 - * @arg @ref LL_RCC_PLLSAIP_DIV_8 - * @retval PLLSAI clock frequency (in Hz) - */ -#define __LL_RCC_CALC_PLLSAI_48M_FREQ(__INPUTFREQ__, __PLLM__, __PLLSAIN__, __PLLSAIP__) (((__INPUTFREQ__) / (__PLLM__)) * (__PLLSAIN__) / \ - ((((__PLLSAIP__) >> RCC_PLLSAICFGR_PLLSAIP_Pos) + 1U) * 2U)) -#endif /* RCC_PLLSAICFGR_PLLSAIP */ - -#if defined(LTDC) -/** - * @brief Helper macro to calculate the PLLSAI frequency used for LTDC domain - * @note ex: @ref __LL_RCC_CALC_PLLSAI_LTDC_FREQ (HSE_VALUE,@ref LL_RCC_PLLSAI_GetDivider (), - * @ref LL_RCC_PLLSAI_GetN (), @ref LL_RCC_PLLSAI_GetR (), @ref LL_RCC_PLLSAI_GetDIVR ()); - * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) - * @param __PLLM__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIM_DIV_2 - * @arg @ref LL_RCC_PLLSAIM_DIV_3 - * @arg @ref LL_RCC_PLLSAIM_DIV_4 - * @arg @ref LL_RCC_PLLSAIM_DIV_5 - * @arg @ref LL_RCC_PLLSAIM_DIV_6 - * @arg @ref LL_RCC_PLLSAIM_DIV_7 - * @arg @ref LL_RCC_PLLSAIM_DIV_8 - * @arg @ref LL_RCC_PLLSAIM_DIV_9 - * @arg @ref LL_RCC_PLLSAIM_DIV_10 - * @arg @ref LL_RCC_PLLSAIM_DIV_11 - * @arg @ref LL_RCC_PLLSAIM_DIV_12 - * @arg @ref LL_RCC_PLLSAIM_DIV_13 - * @arg @ref LL_RCC_PLLSAIM_DIV_14 - * @arg @ref LL_RCC_PLLSAIM_DIV_15 - * @arg @ref LL_RCC_PLLSAIM_DIV_16 - * @arg @ref LL_RCC_PLLSAIM_DIV_17 - * @arg @ref LL_RCC_PLLSAIM_DIV_18 - * @arg @ref LL_RCC_PLLSAIM_DIV_19 - * @arg @ref LL_RCC_PLLSAIM_DIV_20 - * @arg @ref LL_RCC_PLLSAIM_DIV_21 - * @arg @ref LL_RCC_PLLSAIM_DIV_22 - * @arg @ref LL_RCC_PLLSAIM_DIV_23 - * @arg @ref LL_RCC_PLLSAIM_DIV_24 - * @arg @ref LL_RCC_PLLSAIM_DIV_25 - * @arg @ref LL_RCC_PLLSAIM_DIV_26 - * @arg @ref LL_RCC_PLLSAIM_DIV_27 - * @arg @ref LL_RCC_PLLSAIM_DIV_28 - * @arg @ref LL_RCC_PLLSAIM_DIV_29 - * @arg @ref LL_RCC_PLLSAIM_DIV_30 - * @arg @ref LL_RCC_PLLSAIM_DIV_31 - * @arg @ref LL_RCC_PLLSAIM_DIV_32 - * @arg @ref LL_RCC_PLLSAIM_DIV_33 - * @arg @ref LL_RCC_PLLSAIM_DIV_34 - * @arg @ref LL_RCC_PLLSAIM_DIV_35 - * @arg @ref LL_RCC_PLLSAIM_DIV_36 - * @arg @ref LL_RCC_PLLSAIM_DIV_37 - * @arg @ref LL_RCC_PLLSAIM_DIV_38 - * @arg @ref LL_RCC_PLLSAIM_DIV_39 - * @arg @ref LL_RCC_PLLSAIM_DIV_40 - * @arg @ref LL_RCC_PLLSAIM_DIV_41 - * @arg @ref LL_RCC_PLLSAIM_DIV_42 - * @arg @ref LL_RCC_PLLSAIM_DIV_43 - * @arg @ref LL_RCC_PLLSAIM_DIV_44 - * @arg @ref LL_RCC_PLLSAIM_DIV_45 - * @arg @ref LL_RCC_PLLSAIM_DIV_46 - * @arg @ref LL_RCC_PLLSAIM_DIV_47 - * @arg @ref LL_RCC_PLLSAIM_DIV_48 - * @arg @ref LL_RCC_PLLSAIM_DIV_49 - * @arg @ref LL_RCC_PLLSAIM_DIV_50 - * @arg @ref LL_RCC_PLLSAIM_DIV_51 - * @arg @ref LL_RCC_PLLSAIM_DIV_52 - * @arg @ref LL_RCC_PLLSAIM_DIV_53 - * @arg @ref LL_RCC_PLLSAIM_DIV_54 - * @arg @ref LL_RCC_PLLSAIM_DIV_55 - * @arg @ref LL_RCC_PLLSAIM_DIV_56 - * @arg @ref LL_RCC_PLLSAIM_DIV_57 - * @arg @ref LL_RCC_PLLSAIM_DIV_58 - * @arg @ref LL_RCC_PLLSAIM_DIV_59 - * @arg @ref LL_RCC_PLLSAIM_DIV_60 - * @arg @ref LL_RCC_PLLSAIM_DIV_61 - * @arg @ref LL_RCC_PLLSAIM_DIV_62 - * @arg @ref LL_RCC_PLLSAIM_DIV_63 - * @param __PLLSAIN__ Between 49/50(*) and 432 - * - * (*) value not defined in all devices. - * @param __PLLSAIR__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIR_DIV_2 - * @arg @ref LL_RCC_PLLSAIR_DIV_3 - * @arg @ref LL_RCC_PLLSAIR_DIV_4 - * @arg @ref LL_RCC_PLLSAIR_DIV_5 - * @arg @ref LL_RCC_PLLSAIR_DIV_6 - * @arg @ref LL_RCC_PLLSAIR_DIV_7 - * @param __PLLSAIDIVR__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIDIVR_DIV_2 - * @arg @ref LL_RCC_PLLSAIDIVR_DIV_4 - * @arg @ref LL_RCC_PLLSAIDIVR_DIV_8 - * @arg @ref LL_RCC_PLLSAIDIVR_DIV_16 - * @retval PLLSAI clock frequency (in Hz) - */ -#define __LL_RCC_CALC_PLLSAI_LTDC_FREQ(__INPUTFREQ__, __PLLM__, __PLLSAIN__, __PLLSAIR__, __PLLSAIDIVR__) (((__INPUTFREQ__) / (__PLLM__)) * (__PLLSAIN__) / \ - (((__PLLSAIR__) >> RCC_PLLSAICFGR_PLLSAIR_Pos) * (aRCC_PLLSAIDIVRPrescTable[(__PLLSAIDIVR__) >> RCC_DCKCFGR_PLLSAIDIVR_Pos]))) -#endif /* LTDC */ -#endif /* RCC_PLLSAI_SUPPORT */ - -#if defined(RCC_PLLI2S_SUPPORT) -#if defined(RCC_DCKCFGR_PLLI2SDIVQ) || defined(RCC_DCKCFGR_PLLI2SDIVR) -/** - * @brief Helper macro to calculate the PLLI2S frequency used for SAI domain - * @note ex: @ref __LL_RCC_CALC_PLLI2S_SAI_FREQ (HSE_VALUE,@ref LL_RCC_PLLI2S_GetDivider (), - * @ref LL_RCC_PLLI2S_GetN (), @ref LL_RCC_PLLI2S_GetQ (), @ref LL_RCC_PLLI2S_GetDIVQ ()); - * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) - * @param __PLLM__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SM_DIV_2 - * @arg @ref LL_RCC_PLLI2SM_DIV_3 - * @arg @ref LL_RCC_PLLI2SM_DIV_4 - * @arg @ref LL_RCC_PLLI2SM_DIV_5 - * @arg @ref LL_RCC_PLLI2SM_DIV_6 - * @arg @ref LL_RCC_PLLI2SM_DIV_7 - * @arg @ref LL_RCC_PLLI2SM_DIV_8 - * @arg @ref LL_RCC_PLLI2SM_DIV_9 - * @arg @ref LL_RCC_PLLI2SM_DIV_10 - * @arg @ref LL_RCC_PLLI2SM_DIV_11 - * @arg @ref LL_RCC_PLLI2SM_DIV_12 - * @arg @ref LL_RCC_PLLI2SM_DIV_13 - * @arg @ref LL_RCC_PLLI2SM_DIV_14 - * @arg @ref LL_RCC_PLLI2SM_DIV_15 - * @arg @ref LL_RCC_PLLI2SM_DIV_16 - * @arg @ref LL_RCC_PLLI2SM_DIV_17 - * @arg @ref LL_RCC_PLLI2SM_DIV_18 - * @arg @ref LL_RCC_PLLI2SM_DIV_19 - * @arg @ref LL_RCC_PLLI2SM_DIV_20 - * @arg @ref LL_RCC_PLLI2SM_DIV_21 - * @arg @ref LL_RCC_PLLI2SM_DIV_22 - * @arg @ref LL_RCC_PLLI2SM_DIV_23 - * @arg @ref LL_RCC_PLLI2SM_DIV_24 - * @arg @ref LL_RCC_PLLI2SM_DIV_25 - * @arg @ref LL_RCC_PLLI2SM_DIV_26 - * @arg @ref LL_RCC_PLLI2SM_DIV_27 - * @arg @ref LL_RCC_PLLI2SM_DIV_28 - * @arg @ref LL_RCC_PLLI2SM_DIV_29 - * @arg @ref LL_RCC_PLLI2SM_DIV_30 - * @arg @ref LL_RCC_PLLI2SM_DIV_31 - * @arg @ref LL_RCC_PLLI2SM_DIV_32 - * @arg @ref LL_RCC_PLLI2SM_DIV_33 - * @arg @ref LL_RCC_PLLI2SM_DIV_34 - * @arg @ref LL_RCC_PLLI2SM_DIV_35 - * @arg @ref LL_RCC_PLLI2SM_DIV_36 - * @arg @ref LL_RCC_PLLI2SM_DIV_37 - * @arg @ref LL_RCC_PLLI2SM_DIV_38 - * @arg @ref LL_RCC_PLLI2SM_DIV_39 - * @arg @ref LL_RCC_PLLI2SM_DIV_40 - * @arg @ref LL_RCC_PLLI2SM_DIV_41 - * @arg @ref LL_RCC_PLLI2SM_DIV_42 - * @arg @ref LL_RCC_PLLI2SM_DIV_43 - * @arg @ref LL_RCC_PLLI2SM_DIV_44 - * @arg @ref LL_RCC_PLLI2SM_DIV_45 - * @arg @ref LL_RCC_PLLI2SM_DIV_46 - * @arg @ref LL_RCC_PLLI2SM_DIV_47 - * @arg @ref LL_RCC_PLLI2SM_DIV_48 - * @arg @ref LL_RCC_PLLI2SM_DIV_49 - * @arg @ref LL_RCC_PLLI2SM_DIV_50 - * @arg @ref LL_RCC_PLLI2SM_DIV_51 - * @arg @ref LL_RCC_PLLI2SM_DIV_52 - * @arg @ref LL_RCC_PLLI2SM_DIV_53 - * @arg @ref LL_RCC_PLLI2SM_DIV_54 - * @arg @ref LL_RCC_PLLI2SM_DIV_55 - * @arg @ref LL_RCC_PLLI2SM_DIV_56 - * @arg @ref LL_RCC_PLLI2SM_DIV_57 - * @arg @ref LL_RCC_PLLI2SM_DIV_58 - * @arg @ref LL_RCC_PLLI2SM_DIV_59 - * @arg @ref LL_RCC_PLLI2SM_DIV_60 - * @arg @ref LL_RCC_PLLI2SM_DIV_61 - * @arg @ref LL_RCC_PLLI2SM_DIV_62 - * @arg @ref LL_RCC_PLLI2SM_DIV_63 - * @param __PLLI2SN__ Between 50/192(*) and 432 - * - * (*) value not defined in all devices. - * @param __PLLI2SQ_R__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SQ_DIV_2 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_3 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_4 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_5 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_6 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_7 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_8 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_9 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_10 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_11 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_12 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_13 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_14 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_15 (*) - * @arg @ref LL_RCC_PLLI2SR_DIV_2 (*) - * @arg @ref LL_RCC_PLLI2SR_DIV_3 (*) - * @arg @ref LL_RCC_PLLI2SR_DIV_4 (*) - * @arg @ref LL_RCC_PLLI2SR_DIV_5 (*) - * @arg @ref LL_RCC_PLLI2SR_DIV_6 (*) - * @arg @ref LL_RCC_PLLI2SR_DIV_7 (*) - * - * (*) value not defined in all devices. - * @param __PLLI2SDIVQ_R__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_1 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_2 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_3 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_4 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_5 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_6 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_7 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_8 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_9 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_10 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_11 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_12 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_13 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_14 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_15 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_16 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_17 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_18 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_19 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_20 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_21 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_22 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_23 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_24 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_25 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_26 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_27 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_28 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_29 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_30 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_31 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_32 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_1 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_2 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_3 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_4 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_5 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_6 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_7 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_8 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_9 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_10 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_11 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_12 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_13 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_14 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_15 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_16 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_17 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_18 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_19 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_20 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_21 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_22 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_23 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_24 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_25 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_26 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_27 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_28 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_29 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_30 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_31 (*) - * - * (*) value not defined in all devices. - * @retval PLLI2S clock frequency (in Hz) - */ -#if defined(RCC_DCKCFGR_PLLI2SDIVQ) -#define __LL_RCC_CALC_PLLI2S_SAI_FREQ(__INPUTFREQ__, __PLLM__, __PLLI2SN__, __PLLI2SQ_R__, __PLLI2SDIVQ_R__) (((__INPUTFREQ__) / (__PLLM__)) * (__PLLI2SN__) / \ - (((__PLLI2SQ_R__) >> RCC_PLLI2SCFGR_PLLI2SQ_Pos) * (((__PLLI2SDIVQ_R__) >> RCC_DCKCFGR_PLLI2SDIVQ_Pos) + 1U))) -#else -#define __LL_RCC_CALC_PLLI2S_SAI_FREQ(__INPUTFREQ__, __PLLM__, __PLLI2SN__, __PLLI2SQ_R__, __PLLI2SDIVQ_R__) (((__INPUTFREQ__) / (__PLLM__)) * (__PLLI2SN__) / \ - (((__PLLI2SQ_R__) >> RCC_PLLI2SCFGR_PLLI2SR_Pos) * ((__PLLI2SDIVQ_R__) >> RCC_DCKCFGR_PLLI2SDIVR_Pos))) - -#endif /* RCC_DCKCFGR_PLLI2SDIVQ */ -#endif /* RCC_DCKCFGR_PLLI2SDIVQ || RCC_DCKCFGR_PLLI2SDIVR */ - -#if defined(SPDIFRX) -/** - * @brief Helper macro to calculate the PLLI2S frequency used on SPDIFRX domain - * @note ex: @ref __LL_RCC_CALC_PLLI2S_SPDIFRX_FREQ (HSE_VALUE,@ref LL_RCC_PLLI2S_GetDivider (), - * @ref LL_RCC_PLLI2S_GetN (), @ref LL_RCC_PLLI2S_GetP ()); - * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) - * @param __PLLM__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SM_DIV_2 - * @arg @ref LL_RCC_PLLI2SM_DIV_3 - * @arg @ref LL_RCC_PLLI2SM_DIV_4 - * @arg @ref LL_RCC_PLLI2SM_DIV_5 - * @arg @ref LL_RCC_PLLI2SM_DIV_6 - * @arg @ref LL_RCC_PLLI2SM_DIV_7 - * @arg @ref LL_RCC_PLLI2SM_DIV_8 - * @arg @ref LL_RCC_PLLI2SM_DIV_9 - * @arg @ref LL_RCC_PLLI2SM_DIV_10 - * @arg @ref LL_RCC_PLLI2SM_DIV_11 - * @arg @ref LL_RCC_PLLI2SM_DIV_12 - * @arg @ref LL_RCC_PLLI2SM_DIV_13 - * @arg @ref LL_RCC_PLLI2SM_DIV_14 - * @arg @ref LL_RCC_PLLI2SM_DIV_15 - * @arg @ref LL_RCC_PLLI2SM_DIV_16 - * @arg @ref LL_RCC_PLLI2SM_DIV_17 - * @arg @ref LL_RCC_PLLI2SM_DIV_18 - * @arg @ref LL_RCC_PLLI2SM_DIV_19 - * @arg @ref LL_RCC_PLLI2SM_DIV_20 - * @arg @ref LL_RCC_PLLI2SM_DIV_21 - * @arg @ref LL_RCC_PLLI2SM_DIV_22 - * @arg @ref LL_RCC_PLLI2SM_DIV_23 - * @arg @ref LL_RCC_PLLI2SM_DIV_24 - * @arg @ref LL_RCC_PLLI2SM_DIV_25 - * @arg @ref LL_RCC_PLLI2SM_DIV_26 - * @arg @ref LL_RCC_PLLI2SM_DIV_27 - * @arg @ref LL_RCC_PLLI2SM_DIV_28 - * @arg @ref LL_RCC_PLLI2SM_DIV_29 - * @arg @ref LL_RCC_PLLI2SM_DIV_30 - * @arg @ref LL_RCC_PLLI2SM_DIV_31 - * @arg @ref LL_RCC_PLLI2SM_DIV_32 - * @arg @ref LL_RCC_PLLI2SM_DIV_33 - * @arg @ref LL_RCC_PLLI2SM_DIV_34 - * @arg @ref LL_RCC_PLLI2SM_DIV_35 - * @arg @ref LL_RCC_PLLI2SM_DIV_36 - * @arg @ref LL_RCC_PLLI2SM_DIV_37 - * @arg @ref LL_RCC_PLLI2SM_DIV_38 - * @arg @ref LL_RCC_PLLI2SM_DIV_39 - * @arg @ref LL_RCC_PLLI2SM_DIV_40 - * @arg @ref LL_RCC_PLLI2SM_DIV_41 - * @arg @ref LL_RCC_PLLI2SM_DIV_42 - * @arg @ref LL_RCC_PLLI2SM_DIV_43 - * @arg @ref LL_RCC_PLLI2SM_DIV_44 - * @arg @ref LL_RCC_PLLI2SM_DIV_45 - * @arg @ref LL_RCC_PLLI2SM_DIV_46 - * @arg @ref LL_RCC_PLLI2SM_DIV_47 - * @arg @ref LL_RCC_PLLI2SM_DIV_48 - * @arg @ref LL_RCC_PLLI2SM_DIV_49 - * @arg @ref LL_RCC_PLLI2SM_DIV_50 - * @arg @ref LL_RCC_PLLI2SM_DIV_51 - * @arg @ref LL_RCC_PLLI2SM_DIV_52 - * @arg @ref LL_RCC_PLLI2SM_DIV_53 - * @arg @ref LL_RCC_PLLI2SM_DIV_54 - * @arg @ref LL_RCC_PLLI2SM_DIV_55 - * @arg @ref LL_RCC_PLLI2SM_DIV_56 - * @arg @ref LL_RCC_PLLI2SM_DIV_57 - * @arg @ref LL_RCC_PLLI2SM_DIV_58 - * @arg @ref LL_RCC_PLLI2SM_DIV_59 - * @arg @ref LL_RCC_PLLI2SM_DIV_60 - * @arg @ref LL_RCC_PLLI2SM_DIV_61 - * @arg @ref LL_RCC_PLLI2SM_DIV_62 - * @arg @ref LL_RCC_PLLI2SM_DIV_63 - * @param __PLLI2SN__ Between 50 and 432 - * @param __PLLI2SP__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SP_DIV_2 - * @arg @ref LL_RCC_PLLI2SP_DIV_4 - * @arg @ref LL_RCC_PLLI2SP_DIV_6 - * @arg @ref LL_RCC_PLLI2SP_DIV_8 - * @retval PLLI2S clock frequency (in Hz) - */ -#define __LL_RCC_CALC_PLLI2S_SPDIFRX_FREQ(__INPUTFREQ__, __PLLM__, __PLLI2SN__, __PLLI2SP__) (((__INPUTFREQ__) / (__PLLM__)) * (__PLLI2SN__) / \ - ((((__PLLI2SP__) >> RCC_PLLI2SCFGR_PLLI2SP_Pos) + 1U) * 2U)) - -#endif /* SPDIFRX */ - -/** - * @brief Helper macro to calculate the PLLI2S frequency used for I2S domain - * @note ex: @ref __LL_RCC_CALC_PLLI2S_I2S_FREQ (HSE_VALUE,@ref LL_RCC_PLLI2S_GetDivider (), - * @ref LL_RCC_PLLI2S_GetN (), @ref LL_RCC_PLLI2S_GetR ()); - * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) - * @param __PLLM__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SM_DIV_2 - * @arg @ref LL_RCC_PLLI2SM_DIV_3 - * @arg @ref LL_RCC_PLLI2SM_DIV_4 - * @arg @ref LL_RCC_PLLI2SM_DIV_5 - * @arg @ref LL_RCC_PLLI2SM_DIV_6 - * @arg @ref LL_RCC_PLLI2SM_DIV_7 - * @arg @ref LL_RCC_PLLI2SM_DIV_8 - * @arg @ref LL_RCC_PLLI2SM_DIV_9 - * @arg @ref LL_RCC_PLLI2SM_DIV_10 - * @arg @ref LL_RCC_PLLI2SM_DIV_11 - * @arg @ref LL_RCC_PLLI2SM_DIV_12 - * @arg @ref LL_RCC_PLLI2SM_DIV_13 - * @arg @ref LL_RCC_PLLI2SM_DIV_14 - * @arg @ref LL_RCC_PLLI2SM_DIV_15 - * @arg @ref LL_RCC_PLLI2SM_DIV_16 - * @arg @ref LL_RCC_PLLI2SM_DIV_17 - * @arg @ref LL_RCC_PLLI2SM_DIV_18 - * @arg @ref LL_RCC_PLLI2SM_DIV_19 - * @arg @ref LL_RCC_PLLI2SM_DIV_20 - * @arg @ref LL_RCC_PLLI2SM_DIV_21 - * @arg @ref LL_RCC_PLLI2SM_DIV_22 - * @arg @ref LL_RCC_PLLI2SM_DIV_23 - * @arg @ref LL_RCC_PLLI2SM_DIV_24 - * @arg @ref LL_RCC_PLLI2SM_DIV_25 - * @arg @ref LL_RCC_PLLI2SM_DIV_26 - * @arg @ref LL_RCC_PLLI2SM_DIV_27 - * @arg @ref LL_RCC_PLLI2SM_DIV_28 - * @arg @ref LL_RCC_PLLI2SM_DIV_29 - * @arg @ref LL_RCC_PLLI2SM_DIV_30 - * @arg @ref LL_RCC_PLLI2SM_DIV_31 - * @arg @ref LL_RCC_PLLI2SM_DIV_32 - * @arg @ref LL_RCC_PLLI2SM_DIV_33 - * @arg @ref LL_RCC_PLLI2SM_DIV_34 - * @arg @ref LL_RCC_PLLI2SM_DIV_35 - * @arg @ref LL_RCC_PLLI2SM_DIV_36 - * @arg @ref LL_RCC_PLLI2SM_DIV_37 - * @arg @ref LL_RCC_PLLI2SM_DIV_38 - * @arg @ref LL_RCC_PLLI2SM_DIV_39 - * @arg @ref LL_RCC_PLLI2SM_DIV_40 - * @arg @ref LL_RCC_PLLI2SM_DIV_41 - * @arg @ref LL_RCC_PLLI2SM_DIV_42 - * @arg @ref LL_RCC_PLLI2SM_DIV_43 - * @arg @ref LL_RCC_PLLI2SM_DIV_44 - * @arg @ref LL_RCC_PLLI2SM_DIV_45 - * @arg @ref LL_RCC_PLLI2SM_DIV_46 - * @arg @ref LL_RCC_PLLI2SM_DIV_47 - * @arg @ref LL_RCC_PLLI2SM_DIV_48 - * @arg @ref LL_RCC_PLLI2SM_DIV_49 - * @arg @ref LL_RCC_PLLI2SM_DIV_50 - * @arg @ref LL_RCC_PLLI2SM_DIV_51 - * @arg @ref LL_RCC_PLLI2SM_DIV_52 - * @arg @ref LL_RCC_PLLI2SM_DIV_53 - * @arg @ref LL_RCC_PLLI2SM_DIV_54 - * @arg @ref LL_RCC_PLLI2SM_DIV_55 - * @arg @ref LL_RCC_PLLI2SM_DIV_56 - * @arg @ref LL_RCC_PLLI2SM_DIV_57 - * @arg @ref LL_RCC_PLLI2SM_DIV_58 - * @arg @ref LL_RCC_PLLI2SM_DIV_59 - * @arg @ref LL_RCC_PLLI2SM_DIV_60 - * @arg @ref LL_RCC_PLLI2SM_DIV_61 - * @arg @ref LL_RCC_PLLI2SM_DIV_62 - * @arg @ref LL_RCC_PLLI2SM_DIV_63 - * @param __PLLI2SN__ Between 50/192(*) and 432 - * - * (*) value not defined in all devices. - * @param __PLLI2SR__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SR_DIV_2 - * @arg @ref LL_RCC_PLLI2SR_DIV_3 - * @arg @ref LL_RCC_PLLI2SR_DIV_4 - * @arg @ref LL_RCC_PLLI2SR_DIV_5 - * @arg @ref LL_RCC_PLLI2SR_DIV_6 - * @arg @ref LL_RCC_PLLI2SR_DIV_7 - * @retval PLLI2S clock frequency (in Hz) - */ -#define __LL_RCC_CALC_PLLI2S_I2S_FREQ(__INPUTFREQ__, __PLLM__, __PLLI2SN__, __PLLI2SR__) (((__INPUTFREQ__) / (__PLLM__)) * (__PLLI2SN__) / \ - ((__PLLI2SR__) >> RCC_PLLI2SCFGR_PLLI2SR_Pos)) - -#if defined(RCC_PLLI2SCFGR_PLLI2SQ) && !defined(RCC_DCKCFGR_PLLI2SDIVQ) -/** - * @brief Helper macro to calculate the PLLI2S frequency used for 48Mhz domain - * @note ex: @ref __LL_RCC_CALC_PLLI2S_48M_FREQ (HSE_VALUE,@ref LL_RCC_PLLI2S_GetDivider (), - * @ref LL_RCC_PLLI2S_GetN (), @ref LL_RCC_PLLI2S_GetQ ()); - * @param __INPUTFREQ__ PLL Input frequency (based on HSE/HSI) - * @param __PLLM__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SM_DIV_2 - * @arg @ref LL_RCC_PLLI2SM_DIV_3 - * @arg @ref LL_RCC_PLLI2SM_DIV_4 - * @arg @ref LL_RCC_PLLI2SM_DIV_5 - * @arg @ref LL_RCC_PLLI2SM_DIV_6 - * @arg @ref LL_RCC_PLLI2SM_DIV_7 - * @arg @ref LL_RCC_PLLI2SM_DIV_8 - * @arg @ref LL_RCC_PLLI2SM_DIV_9 - * @arg @ref LL_RCC_PLLI2SM_DIV_10 - * @arg @ref LL_RCC_PLLI2SM_DIV_11 - * @arg @ref LL_RCC_PLLI2SM_DIV_12 - * @arg @ref LL_RCC_PLLI2SM_DIV_13 - * @arg @ref LL_RCC_PLLI2SM_DIV_14 - * @arg @ref LL_RCC_PLLI2SM_DIV_15 - * @arg @ref LL_RCC_PLLI2SM_DIV_16 - * @arg @ref LL_RCC_PLLI2SM_DIV_17 - * @arg @ref LL_RCC_PLLI2SM_DIV_18 - * @arg @ref LL_RCC_PLLI2SM_DIV_19 - * @arg @ref LL_RCC_PLLI2SM_DIV_20 - * @arg @ref LL_RCC_PLLI2SM_DIV_21 - * @arg @ref LL_RCC_PLLI2SM_DIV_22 - * @arg @ref LL_RCC_PLLI2SM_DIV_23 - * @arg @ref LL_RCC_PLLI2SM_DIV_24 - * @arg @ref LL_RCC_PLLI2SM_DIV_25 - * @arg @ref LL_RCC_PLLI2SM_DIV_26 - * @arg @ref LL_RCC_PLLI2SM_DIV_27 - * @arg @ref LL_RCC_PLLI2SM_DIV_28 - * @arg @ref LL_RCC_PLLI2SM_DIV_29 - * @arg @ref LL_RCC_PLLI2SM_DIV_30 - * @arg @ref LL_RCC_PLLI2SM_DIV_31 - * @arg @ref LL_RCC_PLLI2SM_DIV_32 - * @arg @ref LL_RCC_PLLI2SM_DIV_33 - * @arg @ref LL_RCC_PLLI2SM_DIV_34 - * @arg @ref LL_RCC_PLLI2SM_DIV_35 - * @arg @ref LL_RCC_PLLI2SM_DIV_36 - * @arg @ref LL_RCC_PLLI2SM_DIV_37 - * @arg @ref LL_RCC_PLLI2SM_DIV_38 - * @arg @ref LL_RCC_PLLI2SM_DIV_39 - * @arg @ref LL_RCC_PLLI2SM_DIV_40 - * @arg @ref LL_RCC_PLLI2SM_DIV_41 - * @arg @ref LL_RCC_PLLI2SM_DIV_42 - * @arg @ref LL_RCC_PLLI2SM_DIV_43 - * @arg @ref LL_RCC_PLLI2SM_DIV_44 - * @arg @ref LL_RCC_PLLI2SM_DIV_45 - * @arg @ref LL_RCC_PLLI2SM_DIV_46 - * @arg @ref LL_RCC_PLLI2SM_DIV_47 - * @arg @ref LL_RCC_PLLI2SM_DIV_48 - * @arg @ref LL_RCC_PLLI2SM_DIV_49 - * @arg @ref LL_RCC_PLLI2SM_DIV_50 - * @arg @ref LL_RCC_PLLI2SM_DIV_51 - * @arg @ref LL_RCC_PLLI2SM_DIV_52 - * @arg @ref LL_RCC_PLLI2SM_DIV_53 - * @arg @ref LL_RCC_PLLI2SM_DIV_54 - * @arg @ref LL_RCC_PLLI2SM_DIV_55 - * @arg @ref LL_RCC_PLLI2SM_DIV_56 - * @arg @ref LL_RCC_PLLI2SM_DIV_57 - * @arg @ref LL_RCC_PLLI2SM_DIV_58 - * @arg @ref LL_RCC_PLLI2SM_DIV_59 - * @arg @ref LL_RCC_PLLI2SM_DIV_60 - * @arg @ref LL_RCC_PLLI2SM_DIV_61 - * @arg @ref LL_RCC_PLLI2SM_DIV_62 - * @arg @ref LL_RCC_PLLI2SM_DIV_63 - * @param __PLLI2SN__ Between 50 and 432 - * @param __PLLI2SQ__ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SQ_DIV_2 - * @arg @ref LL_RCC_PLLI2SQ_DIV_3 - * @arg @ref LL_RCC_PLLI2SQ_DIV_4 - * @arg @ref LL_RCC_PLLI2SQ_DIV_5 - * @arg @ref LL_RCC_PLLI2SQ_DIV_6 - * @arg @ref LL_RCC_PLLI2SQ_DIV_7 - * @arg @ref LL_RCC_PLLI2SQ_DIV_8 - * @arg @ref LL_RCC_PLLI2SQ_DIV_9 - * @arg @ref LL_RCC_PLLI2SQ_DIV_10 - * @arg @ref LL_RCC_PLLI2SQ_DIV_11 - * @arg @ref LL_RCC_PLLI2SQ_DIV_12 - * @arg @ref LL_RCC_PLLI2SQ_DIV_13 - * @arg @ref LL_RCC_PLLI2SQ_DIV_14 - * @arg @ref LL_RCC_PLLI2SQ_DIV_15 - * @retval PLLI2S clock frequency (in Hz) - */ -#define __LL_RCC_CALC_PLLI2S_48M_FREQ(__INPUTFREQ__, __PLLM__, __PLLI2SN__, __PLLI2SQ__) (((__INPUTFREQ__) / (__PLLM__)) * (__PLLI2SN__) / \ - ((__PLLI2SQ__) >> RCC_PLLI2SCFGR_PLLI2SQ_Pos)) - -#endif /* RCC_PLLI2SCFGR_PLLI2SQ && !RCC_DCKCFGR_PLLI2SDIVQ */ -#endif /* RCC_PLLI2S_SUPPORT */ - -/** - * @brief Helper macro to calculate the HCLK frequency - * @param __SYSCLKFREQ__ SYSCLK frequency (based on HSE/HSI/PLLCLK) - * @param __AHBPRESCALER__ This parameter can be one of the following values: - * @arg @ref LL_RCC_SYSCLK_DIV_1 - * @arg @ref LL_RCC_SYSCLK_DIV_2 - * @arg @ref LL_RCC_SYSCLK_DIV_4 - * @arg @ref LL_RCC_SYSCLK_DIV_8 - * @arg @ref LL_RCC_SYSCLK_DIV_16 - * @arg @ref LL_RCC_SYSCLK_DIV_64 - * @arg @ref LL_RCC_SYSCLK_DIV_128 - * @arg @ref LL_RCC_SYSCLK_DIV_256 - * @arg @ref LL_RCC_SYSCLK_DIV_512 - * @retval HCLK clock frequency (in Hz) - */ -#define __LL_RCC_CALC_HCLK_FREQ(__SYSCLKFREQ__, __AHBPRESCALER__) ((__SYSCLKFREQ__) >> AHBPrescTable[((__AHBPRESCALER__) & RCC_CFGR_HPRE) >> RCC_CFGR_HPRE_Pos]) - -/** - * @brief Helper macro to calculate the PCLK1 frequency (ABP1) - * @param __HCLKFREQ__ HCLK frequency - * @param __APB1PRESCALER__ This parameter can be one of the following values: - * @arg @ref LL_RCC_APB1_DIV_1 - * @arg @ref LL_RCC_APB1_DIV_2 - * @arg @ref LL_RCC_APB1_DIV_4 - * @arg @ref LL_RCC_APB1_DIV_8 - * @arg @ref LL_RCC_APB1_DIV_16 - * @retval PCLK1 clock frequency (in Hz) - */ -#define __LL_RCC_CALC_PCLK1_FREQ(__HCLKFREQ__, __APB1PRESCALER__) ((__HCLKFREQ__) >> APBPrescTable[(__APB1PRESCALER__) >> RCC_CFGR_PPRE1_Pos]) - -/** - * @brief Helper macro to calculate the PCLK2 frequency (ABP2) - * @param __HCLKFREQ__ HCLK frequency - * @param __APB2PRESCALER__ This parameter can be one of the following values: - * @arg @ref LL_RCC_APB2_DIV_1 - * @arg @ref LL_RCC_APB2_DIV_2 - * @arg @ref LL_RCC_APB2_DIV_4 - * @arg @ref LL_RCC_APB2_DIV_8 - * @arg @ref LL_RCC_APB2_DIV_16 - * @retval PCLK2 clock frequency (in Hz) - */ -#define __LL_RCC_CALC_PCLK2_FREQ(__HCLKFREQ__, __APB2PRESCALER__) ((__HCLKFREQ__) >> APBPrescTable[(__APB2PRESCALER__) >> RCC_CFGR_PPRE2_Pos]) - -/** - * @} - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup RCC_LL_Exported_Functions RCC Exported Functions - * @{ - */ - -/** @defgroup RCC_LL_EF_HSE HSE - * @{ - */ - -/** - * @brief Enable the Clock Security System. - * @rmtoll CR CSSON LL_RCC_HSE_EnableCSS - * @retval None - */ -__STATIC_INLINE void LL_RCC_HSE_EnableCSS(void) -{ - SET_BIT(RCC->CR, RCC_CR_CSSON); -} - -/** - * @brief Enable HSE external oscillator (HSE Bypass) - * @rmtoll CR HSEBYP LL_RCC_HSE_EnableBypass - * @retval None - */ -__STATIC_INLINE void LL_RCC_HSE_EnableBypass(void) -{ - SET_BIT(RCC->CR, RCC_CR_HSEBYP); -} - -/** - * @brief Disable HSE external oscillator (HSE Bypass) - * @rmtoll CR HSEBYP LL_RCC_HSE_DisableBypass - * @retval None - */ -__STATIC_INLINE void LL_RCC_HSE_DisableBypass(void) -{ - CLEAR_BIT(RCC->CR, RCC_CR_HSEBYP); -} - -/** - * @brief Enable HSE crystal oscillator (HSE ON) - * @rmtoll CR HSEON LL_RCC_HSE_Enable - * @retval None - */ -__STATIC_INLINE void LL_RCC_HSE_Enable(void) -{ - SET_BIT(RCC->CR, RCC_CR_HSEON); -} - -/** - * @brief Disable HSE crystal oscillator (HSE ON) - * @rmtoll CR HSEON LL_RCC_HSE_Disable - * @retval None - */ -__STATIC_INLINE void LL_RCC_HSE_Disable(void) -{ - CLEAR_BIT(RCC->CR, RCC_CR_HSEON); -} - -/** - * @brief Check if HSE oscillator Ready - * @rmtoll CR HSERDY LL_RCC_HSE_IsReady - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_HSE_IsReady(void) -{ - return (READ_BIT(RCC->CR, RCC_CR_HSERDY) == (RCC_CR_HSERDY)); -} - -/** - * @} - */ - -/** @defgroup RCC_LL_EF_HSI HSI - * @{ - */ - -/** - * @brief Enable HSI oscillator - * @rmtoll CR HSION LL_RCC_HSI_Enable - * @retval None - */ -__STATIC_INLINE void LL_RCC_HSI_Enable(void) -{ - SET_BIT(RCC->CR, RCC_CR_HSION); -} - -/** - * @brief Disable HSI oscillator - * @rmtoll CR HSION LL_RCC_HSI_Disable - * @retval None - */ -__STATIC_INLINE void LL_RCC_HSI_Disable(void) -{ - CLEAR_BIT(RCC->CR, RCC_CR_HSION); -} - -/** - * @brief Check if HSI clock is ready - * @rmtoll CR HSIRDY LL_RCC_HSI_IsReady - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_HSI_IsReady(void) -{ - return (READ_BIT(RCC->CR, RCC_CR_HSIRDY) == (RCC_CR_HSIRDY)); -} - -/** - * @brief Get HSI Calibration value - * @note When HSITRIM is written, HSICAL is updated with the sum of - * HSITRIM and the factory trim value - * @rmtoll CR HSICAL LL_RCC_HSI_GetCalibration - * @retval Between Min_Data = 0x00 and Max_Data = 0xFF - */ -__STATIC_INLINE uint32_t LL_RCC_HSI_GetCalibration(void) -{ - return (uint32_t)(READ_BIT(RCC->CR, RCC_CR_HSICAL) >> RCC_CR_HSICAL_Pos); -} - -/** - * @brief Set HSI Calibration trimming - * @note user-programmable trimming value that is added to the HSICAL - * @note Default value is 16, which, when added to the HSICAL value, - * should trim the HSI to 16 MHz +/- 1 % - * @rmtoll CR HSITRIM LL_RCC_HSI_SetCalibTrimming - * @param Value Between Min_Data = 0 and Max_Data = 31 - * @retval None - */ -__STATIC_INLINE void LL_RCC_HSI_SetCalibTrimming(uint32_t Value) -{ - MODIFY_REG(RCC->CR, RCC_CR_HSITRIM, Value << RCC_CR_HSITRIM_Pos); -} - -/** - * @brief Get HSI Calibration trimming - * @rmtoll CR HSITRIM LL_RCC_HSI_GetCalibTrimming - * @retval Between Min_Data = 0 and Max_Data = 31 - */ -__STATIC_INLINE uint32_t LL_RCC_HSI_GetCalibTrimming(void) -{ - return (uint32_t)(READ_BIT(RCC->CR, RCC_CR_HSITRIM) >> RCC_CR_HSITRIM_Pos); -} - -/** - * @} - */ - -/** @defgroup RCC_LL_EF_LSE LSE - * @{ - */ - -/** - * @brief Enable Low Speed External (LSE) crystal. - * @rmtoll BDCR LSEON LL_RCC_LSE_Enable - * @retval None - */ -__STATIC_INLINE void LL_RCC_LSE_Enable(void) -{ - SET_BIT(RCC->BDCR, RCC_BDCR_LSEON); -} - -/** - * @brief Disable Low Speed External (LSE) crystal. - * @rmtoll BDCR LSEON LL_RCC_LSE_Disable - * @retval None - */ -__STATIC_INLINE void LL_RCC_LSE_Disable(void) -{ - CLEAR_BIT(RCC->BDCR, RCC_BDCR_LSEON); -} - -/** - * @brief Enable external clock source (LSE bypass). - * @rmtoll BDCR LSEBYP LL_RCC_LSE_EnableBypass - * @retval None - */ -__STATIC_INLINE void LL_RCC_LSE_EnableBypass(void) -{ - SET_BIT(RCC->BDCR, RCC_BDCR_LSEBYP); -} - -/** - * @brief Disable external clock source (LSE bypass). - * @rmtoll BDCR LSEBYP LL_RCC_LSE_DisableBypass - * @retval None - */ -__STATIC_INLINE void LL_RCC_LSE_DisableBypass(void) -{ - CLEAR_BIT(RCC->BDCR, RCC_BDCR_LSEBYP); -} - -/** - * @brief Check if LSE oscillator Ready - * @rmtoll BDCR LSERDY LL_RCC_LSE_IsReady - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_LSE_IsReady(void) -{ - return (READ_BIT(RCC->BDCR, RCC_BDCR_LSERDY) == (RCC_BDCR_LSERDY)); -} - -#if defined(RCC_BDCR_LSEMOD) -/** - * @brief Enable LSE high drive mode. - * @note LSE high drive mode can be enabled only when the LSE clock is disabled - * @rmtoll BDCR LSEMOD LL_RCC_LSE_EnableHighDriveMode - * @retval None - */ -__STATIC_INLINE void LL_RCC_LSE_EnableHighDriveMode(void) -{ - SET_BIT(RCC->BDCR, RCC_BDCR_LSEMOD); -} - -/** - * @brief Disable LSE high drive mode. - * @note LSE high drive mode can be disabled only when the LSE clock is disabled - * @rmtoll BDCR LSEMOD LL_RCC_LSE_DisableHighDriveMode - * @retval None - */ -__STATIC_INLINE void LL_RCC_LSE_DisableHighDriveMode(void) -{ - CLEAR_BIT(RCC->BDCR, RCC_BDCR_LSEMOD); -} -#endif /* RCC_BDCR_LSEMOD */ - -/** - * @} - */ - -/** @defgroup RCC_LL_EF_LSI LSI - * @{ - */ - -/** - * @brief Enable LSI Oscillator - * @rmtoll CSR LSION LL_RCC_LSI_Enable - * @retval None - */ -__STATIC_INLINE void LL_RCC_LSI_Enable(void) -{ - SET_BIT(RCC->CSR, RCC_CSR_LSION); -} - -/** - * @brief Disable LSI Oscillator - * @rmtoll CSR LSION LL_RCC_LSI_Disable - * @retval None - */ -__STATIC_INLINE void LL_RCC_LSI_Disable(void) -{ - CLEAR_BIT(RCC->CSR, RCC_CSR_LSION); -} - -/** - * @brief Check if LSI is Ready - * @rmtoll CSR LSIRDY LL_RCC_LSI_IsReady - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_LSI_IsReady(void) -{ - return (READ_BIT(RCC->CSR, RCC_CSR_LSIRDY) == (RCC_CSR_LSIRDY)); -} - -/** - * @} - */ - -/** @defgroup RCC_LL_EF_System System - * @{ - */ - -/** - * @brief Configure the system clock source - * @rmtoll CFGR SW LL_RCC_SetSysClkSource - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_SYS_CLKSOURCE_HSI - * @arg @ref LL_RCC_SYS_CLKSOURCE_HSE - * @arg @ref LL_RCC_SYS_CLKSOURCE_PLL - * @arg @ref LL_RCC_SYS_CLKSOURCE_PLLR (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetSysClkSource(uint32_t Source) -{ - MODIFY_REG(RCC->CFGR, RCC_CFGR_SW, Source); -} - -/** - * @brief Get the system clock source - * @rmtoll CFGR SWS LL_RCC_GetSysClkSource - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_SYS_CLKSOURCE_STATUS_HSI - * @arg @ref LL_RCC_SYS_CLKSOURCE_STATUS_HSE - * @arg @ref LL_RCC_SYS_CLKSOURCE_STATUS_PLL - * @arg @ref LL_RCC_SYS_CLKSOURCE_STATUS_PLLR (*) - * - * (*) value not defined in all devices. - */ -__STATIC_INLINE uint32_t LL_RCC_GetSysClkSource(void) -{ - return (uint32_t)(READ_BIT(RCC->CFGR, RCC_CFGR_SWS)); -} - -/** - * @brief Set AHB prescaler - * @rmtoll CFGR HPRE LL_RCC_SetAHBPrescaler - * @param Prescaler This parameter can be one of the following values: - * @arg @ref LL_RCC_SYSCLK_DIV_1 - * @arg @ref LL_RCC_SYSCLK_DIV_2 - * @arg @ref LL_RCC_SYSCLK_DIV_4 - * @arg @ref LL_RCC_SYSCLK_DIV_8 - * @arg @ref LL_RCC_SYSCLK_DIV_16 - * @arg @ref LL_RCC_SYSCLK_DIV_64 - * @arg @ref LL_RCC_SYSCLK_DIV_128 - * @arg @ref LL_RCC_SYSCLK_DIV_256 - * @arg @ref LL_RCC_SYSCLK_DIV_512 - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetAHBPrescaler(uint32_t Prescaler) -{ - MODIFY_REG(RCC->CFGR, RCC_CFGR_HPRE, Prescaler); -} - -/** - * @brief Set APB1 prescaler - * @rmtoll CFGR PPRE1 LL_RCC_SetAPB1Prescaler - * @param Prescaler This parameter can be one of the following values: - * @arg @ref LL_RCC_APB1_DIV_1 - * @arg @ref LL_RCC_APB1_DIV_2 - * @arg @ref LL_RCC_APB1_DIV_4 - * @arg @ref LL_RCC_APB1_DIV_8 - * @arg @ref LL_RCC_APB1_DIV_16 - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetAPB1Prescaler(uint32_t Prescaler) -{ - MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE1, Prescaler); -} - -/** - * @brief Set APB2 prescaler - * @rmtoll CFGR PPRE2 LL_RCC_SetAPB2Prescaler - * @param Prescaler This parameter can be one of the following values: - * @arg @ref LL_RCC_APB2_DIV_1 - * @arg @ref LL_RCC_APB2_DIV_2 - * @arg @ref LL_RCC_APB2_DIV_4 - * @arg @ref LL_RCC_APB2_DIV_8 - * @arg @ref LL_RCC_APB2_DIV_16 - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetAPB2Prescaler(uint32_t Prescaler) -{ - MODIFY_REG(RCC->CFGR, RCC_CFGR_PPRE2, Prescaler); -} - -/** - * @brief Get AHB prescaler - * @rmtoll CFGR HPRE LL_RCC_GetAHBPrescaler - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_SYSCLK_DIV_1 - * @arg @ref LL_RCC_SYSCLK_DIV_2 - * @arg @ref LL_RCC_SYSCLK_DIV_4 - * @arg @ref LL_RCC_SYSCLK_DIV_8 - * @arg @ref LL_RCC_SYSCLK_DIV_16 - * @arg @ref LL_RCC_SYSCLK_DIV_64 - * @arg @ref LL_RCC_SYSCLK_DIV_128 - * @arg @ref LL_RCC_SYSCLK_DIV_256 - * @arg @ref LL_RCC_SYSCLK_DIV_512 - */ -__STATIC_INLINE uint32_t LL_RCC_GetAHBPrescaler(void) -{ - return (uint32_t)(READ_BIT(RCC->CFGR, RCC_CFGR_HPRE)); -} - -/** - * @brief Get APB1 prescaler - * @rmtoll CFGR PPRE1 LL_RCC_GetAPB1Prescaler - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_APB1_DIV_1 - * @arg @ref LL_RCC_APB1_DIV_2 - * @arg @ref LL_RCC_APB1_DIV_4 - * @arg @ref LL_RCC_APB1_DIV_8 - * @arg @ref LL_RCC_APB1_DIV_16 - */ -__STATIC_INLINE uint32_t LL_RCC_GetAPB1Prescaler(void) -{ - return (uint32_t)(READ_BIT(RCC->CFGR, RCC_CFGR_PPRE1)); -} - -/** - * @brief Get APB2 prescaler - * @rmtoll CFGR PPRE2 LL_RCC_GetAPB2Prescaler - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_APB2_DIV_1 - * @arg @ref LL_RCC_APB2_DIV_2 - * @arg @ref LL_RCC_APB2_DIV_4 - * @arg @ref LL_RCC_APB2_DIV_8 - * @arg @ref LL_RCC_APB2_DIV_16 - */ -__STATIC_INLINE uint32_t LL_RCC_GetAPB2Prescaler(void) -{ - return (uint32_t)(READ_BIT(RCC->CFGR, RCC_CFGR_PPRE2)); -} - -/** - * @} - */ - -/** @defgroup RCC_LL_EF_MCO MCO - * @{ - */ - -#if defined(RCC_CFGR_MCO1EN) -/** - * @brief Enable MCO1 output - * @rmtoll CFGR RCC_CFGR_MCO1EN LL_RCC_MCO1_Enable - * @retval None - */ -__STATIC_INLINE void LL_RCC_MCO1_Enable(void) -{ - SET_BIT(RCC->CFGR, RCC_CFGR_MCO1EN); -} - -/** - * @brief Disable MCO1 output - * @rmtoll CFGR RCC_CFGR_MCO1EN LL_RCC_MCO1_Disable - * @retval None - */ -__STATIC_INLINE void LL_RCC_MCO1_Disable(void) -{ - CLEAR_BIT(RCC->CFGR, RCC_CFGR_MCO1EN); -} -#endif /* RCC_CFGR_MCO1EN */ - -#if defined(RCC_CFGR_MCO2EN) -/** - * @brief Enable MCO2 output - * @rmtoll CFGR RCC_CFGR_MCO2EN LL_RCC_MCO2_Enable - * @retval None - */ -__STATIC_INLINE void LL_RCC_MCO2_Enable(void) -{ - SET_BIT(RCC->CFGR, RCC_CFGR_MCO2EN); -} - -/** - * @brief Disable MCO2 output - * @rmtoll CFGR RCC_CFGR_MCO2EN LL_RCC_MCO2_Disable - * @retval None - */ -__STATIC_INLINE void LL_RCC_MCO2_Disable(void) -{ - CLEAR_BIT(RCC->CFGR, RCC_CFGR_MCO2EN); -} -#endif /* RCC_CFGR_MCO2EN */ - -/** - * @brief Configure MCOx - * @rmtoll CFGR MCO1 LL_RCC_ConfigMCO\n - * CFGR MCO1PRE LL_RCC_ConfigMCO\n - * CFGR MCO2 LL_RCC_ConfigMCO\n - * CFGR MCO2PRE LL_RCC_ConfigMCO - * @param MCOxSource This parameter can be one of the following values: - * @arg @ref LL_RCC_MCO1SOURCE_HSI - * @arg @ref LL_RCC_MCO1SOURCE_LSE - * @arg @ref LL_RCC_MCO1SOURCE_HSE - * @arg @ref LL_RCC_MCO1SOURCE_PLLCLK - * @arg @ref LL_RCC_MCO2SOURCE_SYSCLK - * @arg @ref LL_RCC_MCO2SOURCE_PLLI2S - * @arg @ref LL_RCC_MCO2SOURCE_HSE - * @arg @ref LL_RCC_MCO2SOURCE_PLLCLK - * @param MCOxPrescaler This parameter can be one of the following values: - * @arg @ref LL_RCC_MCO1_DIV_1 - * @arg @ref LL_RCC_MCO1_DIV_2 - * @arg @ref LL_RCC_MCO1_DIV_3 - * @arg @ref LL_RCC_MCO1_DIV_4 - * @arg @ref LL_RCC_MCO1_DIV_5 - * @arg @ref LL_RCC_MCO2_DIV_1 - * @arg @ref LL_RCC_MCO2_DIV_2 - * @arg @ref LL_RCC_MCO2_DIV_3 - * @arg @ref LL_RCC_MCO2_DIV_4 - * @arg @ref LL_RCC_MCO2_DIV_5 - * @retval None - */ -__STATIC_INLINE void LL_RCC_ConfigMCO(uint32_t MCOxSource, uint32_t MCOxPrescaler) -{ - MODIFY_REG(RCC->CFGR, (MCOxSource & 0xFFFF0000U) | (MCOxPrescaler & 0xFFFF0000U), (MCOxSource << 16U) | (MCOxPrescaler << 16U)); -} - -/** - * @} - */ - -/** @defgroup RCC_LL_EF_Peripheral_Clock_Source Peripheral Clock Source - * @{ - */ -#if defined(FMPI2C1) -/** - * @brief Configure FMPI2C clock source - * @rmtoll DCKCFGR2 FMPI2C1SEL LL_RCC_SetFMPI2CClockSource - * @param FMPI2CxSource This parameter can be one of the following values: - * @arg @ref LL_RCC_FMPI2C1_CLKSOURCE_PCLK1 - * @arg @ref LL_RCC_FMPI2C1_CLKSOURCE_SYSCLK - * @arg @ref LL_RCC_FMPI2C1_CLKSOURCE_HSI - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetFMPI2CClockSource(uint32_t FMPI2CxSource) -{ - MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_FMPI2C1SEL, FMPI2CxSource); -} -#endif /* FMPI2C1 */ - -#if defined(LPTIM1) -/** - * @brief Configure LPTIMx clock source - * @rmtoll DCKCFGR2 LPTIM1SEL LL_RCC_SetLPTIMClockSource - * @param LPTIMxSource This parameter can be one of the following values: - * @arg @ref LL_RCC_LPTIM1_CLKSOURCE_PCLK1 - * @arg @ref LL_RCC_LPTIM1_CLKSOURCE_HSI - * @arg @ref LL_RCC_LPTIM1_CLKSOURCE_LSI - * @arg @ref LL_RCC_LPTIM1_CLKSOURCE_LSE - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetLPTIMClockSource(uint32_t LPTIMxSource) -{ - MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_LPTIM1SEL, LPTIMxSource); -} -#endif /* LPTIM1 */ - -#if defined(SAI1) -/** - * @brief Configure SAIx clock source - * @rmtoll DCKCFGR SAI1SRC LL_RCC_SetSAIClockSource\n - * DCKCFGR SAI2SRC LL_RCC_SetSAIClockSource\n - * DCKCFGR SAI1ASRC LL_RCC_SetSAIClockSource\n - * DCKCFGR SAI1BSRC LL_RCC_SetSAIClockSource - * @param SAIxSource This parameter can be one of the following values: - * @arg @ref LL_RCC_SAI1_CLKSOURCE_PLLSAI (*) - * @arg @ref LL_RCC_SAI1_CLKSOURCE_PLLI2S (*) - * @arg @ref LL_RCC_SAI1_CLKSOURCE_PLL (*) - * @arg @ref LL_RCC_SAI1_CLKSOURCE_PIN (*) - * @arg @ref LL_RCC_SAI2_CLKSOURCE_PLLSAI (*) - * @arg @ref LL_RCC_SAI2_CLKSOURCE_PLLI2S (*) - * @arg @ref LL_RCC_SAI2_CLKSOURCE_PLL (*) - * @arg @ref LL_RCC_SAI2_CLKSOURCE_PLLSRC (*) - * @arg @ref LL_RCC_SAI1_A_CLKSOURCE_PLLSAI (*) - * @arg @ref LL_RCC_SAI1_A_CLKSOURCE_PLLI2S (*) - * @arg @ref LL_RCC_SAI1_A_CLKSOURCE_PIN (*) - * @arg @ref LL_RCC_SAI1_A_CLKSOURCE_PLL (*) - * @arg @ref LL_RCC_SAI1_A_CLKSOURCE_PLLSRC (*) - * @arg @ref LL_RCC_SAI1_B_CLKSOURCE_PLLSAI (*) - * @arg @ref LL_RCC_SAI1_B_CLKSOURCE_PLLI2S (*) - * @arg @ref LL_RCC_SAI1_B_CLKSOURCE_PIN (*) - * @arg @ref LL_RCC_SAI1_B_CLKSOURCE_PLL (*) - * @arg @ref LL_RCC_SAI1_B_CLKSOURCE_PLLSRC (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetSAIClockSource(uint32_t SAIxSource) -{ - MODIFY_REG(RCC->DCKCFGR, (SAIxSource & 0xFFFF0000U), (SAIxSource << 16U)); -} -#endif /* SAI1 */ - -#if defined(RCC_DCKCFGR_SDIOSEL) || defined(RCC_DCKCFGR2_SDIOSEL) -/** - * @brief Configure SDIO clock source - * @rmtoll DCKCFGR SDIOSEL LL_RCC_SetSDIOClockSource\n - * DCKCFGR2 SDIOSEL LL_RCC_SetSDIOClockSource - * @param SDIOxSource This parameter can be one of the following values: - * @arg @ref LL_RCC_SDIO_CLKSOURCE_PLL48CLK - * @arg @ref LL_RCC_SDIO_CLKSOURCE_SYSCLK - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetSDIOClockSource(uint32_t SDIOxSource) -{ -#if defined(RCC_DCKCFGR_SDIOSEL) - MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_SDIOSEL, SDIOxSource); -#else - MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_SDIOSEL, SDIOxSource); -#endif /* RCC_DCKCFGR_SDIOSEL */ -} -#endif /* RCC_DCKCFGR_SDIOSEL || RCC_DCKCFGR2_SDIOSEL */ - -#if defined(RCC_DCKCFGR_CK48MSEL) || defined(RCC_DCKCFGR2_CK48MSEL) -/** - * @brief Configure 48Mhz domain clock source - * @rmtoll DCKCFGR CK48MSEL LL_RCC_SetCK48MClockSource\n - * DCKCFGR2 CK48MSEL LL_RCC_SetCK48MClockSource - * @param CK48MxSource This parameter can be one of the following values: - * @arg @ref LL_RCC_CK48M_CLKSOURCE_PLL - * @arg @ref LL_RCC_CK48M_CLKSOURCE_PLLSAI (*) - * @arg @ref LL_RCC_CK48M_CLKSOURCE_PLLI2S (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetCK48MClockSource(uint32_t CK48MxSource) -{ -#if defined(RCC_DCKCFGR_CK48MSEL) - MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_CK48MSEL, CK48MxSource); -#else - MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_CK48MSEL, CK48MxSource); -#endif /* RCC_DCKCFGR_CK48MSEL */ -} - -#if defined(RNG) -/** - * @brief Configure RNG clock source - * @rmtoll DCKCFGR CK48MSEL LL_RCC_SetRNGClockSource\n - * DCKCFGR2 CK48MSEL LL_RCC_SetRNGClockSource - * @param RNGxSource This parameter can be one of the following values: - * @arg @ref LL_RCC_RNG_CLKSOURCE_PLL - * @arg @ref LL_RCC_RNG_CLKSOURCE_PLLSAI (*) - * @arg @ref LL_RCC_RNG_CLKSOURCE_PLLI2S (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetRNGClockSource(uint32_t RNGxSource) -{ -#if defined(RCC_DCKCFGR_CK48MSEL) - MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_CK48MSEL, RNGxSource); -#else - MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_CK48MSEL, RNGxSource); -#endif /* RCC_DCKCFGR_CK48MSEL */ -} -#endif /* RNG */ - -#if defined(USB_OTG_FS) || defined(USB_OTG_HS) -/** - * @brief Configure USB clock source - * @rmtoll DCKCFGR CK48MSEL LL_RCC_SetUSBClockSource\n - * DCKCFGR2 CK48MSEL LL_RCC_SetUSBClockSource - * @param USBxSource This parameter can be one of the following values: - * @arg @ref LL_RCC_USB_CLKSOURCE_PLL - * @arg @ref LL_RCC_USB_CLKSOURCE_PLLSAI (*) - * @arg @ref LL_RCC_USB_CLKSOURCE_PLLI2S (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetUSBClockSource(uint32_t USBxSource) -{ -#if defined(RCC_DCKCFGR_CK48MSEL) - MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_CK48MSEL, USBxSource); -#else - MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_CK48MSEL, USBxSource); -#endif /* RCC_DCKCFGR_CK48MSEL */ -} -#endif /* USB_OTG_FS || USB_OTG_HS */ -#endif /* RCC_DCKCFGR_CK48MSEL || RCC_DCKCFGR2_CK48MSEL */ - -#if defined(CEC) -/** - * @brief Configure CEC clock source - * @rmtoll DCKCFGR2 CECSEL LL_RCC_SetCECClockSource - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_CEC_CLKSOURCE_HSI_DIV488 - * @arg @ref LL_RCC_CEC_CLKSOURCE_LSE - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetCECClockSource(uint32_t Source) -{ - MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_CECSEL, Source); -} -#endif /* CEC */ - -/** - * @brief Configure I2S clock source - * @rmtoll CFGR I2SSRC LL_RCC_SetI2SClockSource\n - * DCKCFGR I2SSRC LL_RCC_SetI2SClockSource\n - * DCKCFGR I2S1SRC LL_RCC_SetI2SClockSource\n - * DCKCFGR I2S2SRC LL_RCC_SetI2SClockSource - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_I2S1_CLKSOURCE_PLLI2S (*) - * @arg @ref LL_RCC_I2S1_CLKSOURCE_PIN - * @arg @ref LL_RCC_I2S1_CLKSOURCE_PLL (*) - * @arg @ref LL_RCC_I2S1_CLKSOURCE_PLLSRC (*) - * @arg @ref LL_RCC_I2S2_CLKSOURCE_PLLI2S (*) - * @arg @ref LL_RCC_I2S2_CLKSOURCE_PIN (*) - * @arg @ref LL_RCC_I2S2_CLKSOURCE_PLL (*) - * @arg @ref LL_RCC_I2S2_CLKSOURCE_PLLSRC (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetI2SClockSource(uint32_t Source) -{ -#if defined(RCC_CFGR_I2SSRC) - MODIFY_REG(RCC->CFGR, RCC_CFGR_I2SSRC, Source); -#else - MODIFY_REG(RCC->DCKCFGR, (Source & 0xFFFF0000U), (Source << 16U)); -#endif /* RCC_CFGR_I2SSRC */ -} - -#if defined(DSI) -/** - * @brief Configure DSI clock source - * @rmtoll DCKCFGR DSISEL LL_RCC_SetDSIClockSource - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_DSI_CLKSOURCE_PHY - * @arg @ref LL_RCC_DSI_CLKSOURCE_PLL - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetDSIClockSource(uint32_t Source) -{ - MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_DSISEL, Source); -} -#endif /* DSI */ - -#if defined(DFSDM1_Channel0) -/** - * @brief Configure DFSDM Audio clock source - * @rmtoll DCKCFGR CKDFSDM1ASEL LL_RCC_SetDFSDMAudioClockSource\n - * DCKCFGR CKDFSDM2ASEL LL_RCC_SetDFSDMAudioClockSource - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_DFSDM1_AUDIO_CLKSOURCE_I2S1 - * @arg @ref LL_RCC_DFSDM1_AUDIO_CLKSOURCE_I2S2 - * @arg @ref LL_RCC_DFSDM2_AUDIO_CLKSOURCE_I2S1 (*) - * @arg @ref LL_RCC_DFSDM2_AUDIO_CLKSOURCE_I2S2 (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetDFSDMAudioClockSource(uint32_t Source) -{ - MODIFY_REG(RCC->DCKCFGR, (Source & 0x0000FFFFU), (Source >> 16U)); -} - -/** - * @brief Configure DFSDM Kernel clock source - * @rmtoll DCKCFGR CKDFSDM1SEL LL_RCC_SetDFSDMClockSource - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_DFSDM1_CLKSOURCE_PCLK2 - * @arg @ref LL_RCC_DFSDM1_CLKSOURCE_SYSCLK - * @arg @ref LL_RCC_DFSDM2_CLKSOURCE_PCLK2 (*) - * @arg @ref LL_RCC_DFSDM2_CLKSOURCE_SYSCLK (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetDFSDMClockSource(uint32_t Source) -{ - MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_CKDFSDM1SEL, Source); -} -#endif /* DFSDM1_Channel0 */ - -#if defined(SPDIFRX) -/** - * @brief Configure SPDIFRX clock source - * @rmtoll DCKCFGR2 SPDIFRXSEL LL_RCC_SetSPDIFRXClockSource - * @param SPDIFRXxSource This parameter can be one of the following values: - * @arg @ref LL_RCC_SPDIFRX1_CLKSOURCE_PLL - * @arg @ref LL_RCC_SPDIFRX1_CLKSOURCE_PLLI2S - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetSPDIFRXClockSource(uint32_t SPDIFRXxSource) -{ - MODIFY_REG(RCC->DCKCFGR2, RCC_DCKCFGR2_SPDIFRXSEL, SPDIFRXxSource); -} -#endif /* SPDIFRX */ - -#if defined(FMPI2C1) -/** - * @brief Get FMPI2C clock source - * @rmtoll DCKCFGR2 FMPI2C1SEL LL_RCC_GetFMPI2CClockSource - * @param FMPI2Cx This parameter can be one of the following values: - * @arg @ref LL_RCC_FMPI2C1_CLKSOURCE - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_FMPI2C1_CLKSOURCE_PCLK1 - * @arg @ref LL_RCC_FMPI2C1_CLKSOURCE_SYSCLK - * @arg @ref LL_RCC_FMPI2C1_CLKSOURCE_HSI - */ -__STATIC_INLINE uint32_t LL_RCC_GetFMPI2CClockSource(uint32_t FMPI2Cx) -{ - return (uint32_t)(READ_BIT(RCC->DCKCFGR2, FMPI2Cx)); -} -#endif /* FMPI2C1 */ - -#if defined(LPTIM1) -/** - * @brief Get LPTIMx clock source - * @rmtoll DCKCFGR2 LPTIM1SEL LL_RCC_GetLPTIMClockSource - * @param LPTIMx This parameter can be one of the following values: - * @arg @ref LL_RCC_LPTIM1_CLKSOURCE - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_LPTIM1_CLKSOURCE_PCLK1 - * @arg @ref LL_RCC_LPTIM1_CLKSOURCE_HSI - * @arg @ref LL_RCC_LPTIM1_CLKSOURCE_LSI - * @arg @ref LL_RCC_LPTIM1_CLKSOURCE_LSE - */ -__STATIC_INLINE uint32_t LL_RCC_GetLPTIMClockSource(uint32_t LPTIMx) -{ - return (uint32_t)(READ_BIT(RCC->DCKCFGR2, RCC_DCKCFGR2_LPTIM1SEL)); -} -#endif /* LPTIM1 */ - -#if defined(SAI1) -/** - * @brief Get SAIx clock source - * @rmtoll DCKCFGR SAI1SEL LL_RCC_GetSAIClockSource\n - * DCKCFGR SAI2SEL LL_RCC_GetSAIClockSource\n - * DCKCFGR SAI1ASRC LL_RCC_GetSAIClockSource\n - * DCKCFGR SAI1BSRC LL_RCC_GetSAIClockSource - * @param SAIx This parameter can be one of the following values: - * @arg @ref LL_RCC_SAI1_CLKSOURCE (*) - * @arg @ref LL_RCC_SAI2_CLKSOURCE (*) - * @arg @ref LL_RCC_SAI1_A_CLKSOURCE (*) - * @arg @ref LL_RCC_SAI1_B_CLKSOURCE (*) - * - * (*) value not defined in all devices. - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_SAI1_CLKSOURCE_PLLSAI (*) - * @arg @ref LL_RCC_SAI1_CLKSOURCE_PLLI2S (*) - * @arg @ref LL_RCC_SAI1_CLKSOURCE_PLL (*) - * @arg @ref LL_RCC_SAI1_CLKSOURCE_PIN (*) - * @arg @ref LL_RCC_SAI2_CLKSOURCE_PLLSAI (*) - * @arg @ref LL_RCC_SAI2_CLKSOURCE_PLLI2S (*) - * @arg @ref LL_RCC_SAI2_CLKSOURCE_PLL (*) - * @arg @ref LL_RCC_SAI2_CLKSOURCE_PLLSRC (*) - * @arg @ref LL_RCC_SAI1_A_CLKSOURCE_PLLSAI (*) - * @arg @ref LL_RCC_SAI1_A_CLKSOURCE_PLLI2S (*) - * @arg @ref LL_RCC_SAI1_A_CLKSOURCE_PIN (*) - * @arg @ref LL_RCC_SAI1_A_CLKSOURCE_PLL (*) - * @arg @ref LL_RCC_SAI1_A_CLKSOURCE_PLLSRC (*) - * @arg @ref LL_RCC_SAI1_B_CLKSOURCE_PLLSAI (*) - * @arg @ref LL_RCC_SAI1_B_CLKSOURCE_PLLI2S (*) - * @arg @ref LL_RCC_SAI1_B_CLKSOURCE_PIN (*) - * @arg @ref LL_RCC_SAI1_B_CLKSOURCE_PLL (*) - * @arg @ref LL_RCC_SAI1_B_CLKSOURCE_PLLSRC (*) - * - * (*) value not defined in all devices. - */ -__STATIC_INLINE uint32_t LL_RCC_GetSAIClockSource(uint32_t SAIx) -{ - return (uint32_t)(READ_BIT(RCC->DCKCFGR, SAIx) >> 16U | SAIx); -} -#endif /* SAI1 */ - -#if defined(RCC_DCKCFGR_SDIOSEL) || defined(RCC_DCKCFGR2_SDIOSEL) -/** - * @brief Get SDIOx clock source - * @rmtoll DCKCFGR SDIOSEL LL_RCC_GetSDIOClockSource\n - * DCKCFGR2 SDIOSEL LL_RCC_GetSDIOClockSource - * @param SDIOx This parameter can be one of the following values: - * @arg @ref LL_RCC_SDIO_CLKSOURCE - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_SDIO_CLKSOURCE_PLL48CLK - * @arg @ref LL_RCC_SDIO_CLKSOURCE_SYSCLK - */ -__STATIC_INLINE uint32_t LL_RCC_GetSDIOClockSource(uint32_t SDIOx) -{ -#if defined(RCC_DCKCFGR_SDIOSEL) - return (uint32_t)(READ_BIT(RCC->DCKCFGR, SDIOx)); -#else - return (uint32_t)(READ_BIT(RCC->DCKCFGR2, SDIOx)); -#endif /* RCC_DCKCFGR_SDIOSEL */ -} -#endif /* RCC_DCKCFGR_SDIOSEL || RCC_DCKCFGR2_SDIOSEL */ - -#if defined(RCC_DCKCFGR_CK48MSEL) || defined(RCC_DCKCFGR2_CK48MSEL) -/** - * @brief Get 48Mhz domain clock source - * @rmtoll DCKCFGR CK48MSEL LL_RCC_GetCK48MClockSource\n - * DCKCFGR2 CK48MSEL LL_RCC_GetCK48MClockSource - * @param CK48Mx This parameter can be one of the following values: - * @arg @ref LL_RCC_CK48M_CLKSOURCE - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_CK48M_CLKSOURCE_PLL - * @arg @ref LL_RCC_CK48M_CLKSOURCE_PLLSAI (*) - * @arg @ref LL_RCC_CK48M_CLKSOURCE_PLLI2S (*) - * - * (*) value not defined in all devices. - */ -__STATIC_INLINE uint32_t LL_RCC_GetCK48MClockSource(uint32_t CK48Mx) -{ -#if defined(RCC_DCKCFGR_CK48MSEL) - return (uint32_t)(READ_BIT(RCC->DCKCFGR, CK48Mx)); -#else - return (uint32_t)(READ_BIT(RCC->DCKCFGR2, CK48Mx)); -#endif /* RCC_DCKCFGR_CK48MSEL */ -} - -#if defined(RNG) -/** - * @brief Get RNGx clock source - * @rmtoll DCKCFGR CK48MSEL LL_RCC_GetRNGClockSource\n - * DCKCFGR2 CK48MSEL LL_RCC_GetRNGClockSource - * @param RNGx This parameter can be one of the following values: - * @arg @ref LL_RCC_RNG_CLKSOURCE - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_RNG_CLKSOURCE_PLL - * @arg @ref LL_RCC_RNG_CLKSOURCE_PLLSAI (*) - * @arg @ref LL_RCC_RNG_CLKSOURCE_PLLI2S (*) - * - * (*) value not defined in all devices. - */ -__STATIC_INLINE uint32_t LL_RCC_GetRNGClockSource(uint32_t RNGx) -{ -#if defined(RCC_DCKCFGR_CK48MSEL) - return (uint32_t)(READ_BIT(RCC->DCKCFGR, RNGx)); -#else - return (uint32_t)(READ_BIT(RCC->DCKCFGR2, RNGx)); -#endif /* RCC_DCKCFGR_CK48MSEL */ -} -#endif /* RNG */ - -#if defined(USB_OTG_FS) || defined(USB_OTG_HS) -/** - * @brief Get USBx clock source - * @rmtoll DCKCFGR CK48MSEL LL_RCC_GetUSBClockSource\n - * DCKCFGR2 CK48MSEL LL_RCC_GetUSBClockSource - * @param USBx This parameter can be one of the following values: - * @arg @ref LL_RCC_USB_CLKSOURCE - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_USB_CLKSOURCE_PLL - * @arg @ref LL_RCC_USB_CLKSOURCE_PLLSAI (*) - * @arg @ref LL_RCC_USB_CLKSOURCE_PLLI2S (*) - * - * (*) value not defined in all devices. - */ -__STATIC_INLINE uint32_t LL_RCC_GetUSBClockSource(uint32_t USBx) -{ -#if defined(RCC_DCKCFGR_CK48MSEL) - return (uint32_t)(READ_BIT(RCC->DCKCFGR, USBx)); -#else - return (uint32_t)(READ_BIT(RCC->DCKCFGR2, USBx)); -#endif /* RCC_DCKCFGR_CK48MSEL */ -} -#endif /* USB_OTG_FS || USB_OTG_HS */ -#endif /* RCC_DCKCFGR_CK48MSEL || RCC_DCKCFGR2_CK48MSEL */ - -#if defined(CEC) -/** - * @brief Get CEC Clock Source - * @rmtoll DCKCFGR2 CECSEL LL_RCC_GetCECClockSource - * @param CECx This parameter can be one of the following values: - * @arg @ref LL_RCC_CEC_CLKSOURCE - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_CEC_CLKSOURCE_HSI_DIV488 - * @arg @ref LL_RCC_CEC_CLKSOURCE_LSE - */ -__STATIC_INLINE uint32_t LL_RCC_GetCECClockSource(uint32_t CECx) -{ - return (uint32_t)(READ_BIT(RCC->DCKCFGR2, CECx)); -} -#endif /* CEC */ - -/** - * @brief Get I2S Clock Source - * @rmtoll CFGR I2SSRC LL_RCC_GetI2SClockSource\n - * DCKCFGR I2SSRC LL_RCC_GetI2SClockSource\n - * DCKCFGR I2S1SRC LL_RCC_GetI2SClockSource\n - * DCKCFGR I2S2SRC LL_RCC_GetI2SClockSource - * @param I2Sx This parameter can be one of the following values: - * @arg @ref LL_RCC_I2S1_CLKSOURCE - * @arg @ref LL_RCC_I2S2_CLKSOURCE (*) - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_I2S1_CLKSOURCE_PLLI2S (*) - * @arg @ref LL_RCC_I2S1_CLKSOURCE_PIN - * @arg @ref LL_RCC_I2S1_CLKSOURCE_PLL (*) - * @arg @ref LL_RCC_I2S1_CLKSOURCE_PLLSRC (*) - * @arg @ref LL_RCC_I2S2_CLKSOURCE_PLLI2S (*) - * @arg @ref LL_RCC_I2S2_CLKSOURCE_PIN (*) - * @arg @ref LL_RCC_I2S2_CLKSOURCE_PLL (*) - * @arg @ref LL_RCC_I2S2_CLKSOURCE_PLLSRC (*) - * - * (*) value not defined in all devices. - */ -__STATIC_INLINE uint32_t LL_RCC_GetI2SClockSource(uint32_t I2Sx) -{ -#if defined(RCC_CFGR_I2SSRC) - return (uint32_t)(READ_BIT(RCC->CFGR, I2Sx)); -#else - return (uint32_t)(READ_BIT(RCC->DCKCFGR, I2Sx) >> 16U | I2Sx); -#endif /* RCC_CFGR_I2SSRC */ -} - -#if defined(DFSDM1_Channel0) -/** - * @brief Get DFSDM Audio Clock Source - * @rmtoll DCKCFGR CKDFSDM1ASEL LL_RCC_GetDFSDMAudioClockSource\n - * DCKCFGR CKDFSDM2ASEL LL_RCC_GetDFSDMAudioClockSource - * @param DFSDMx This parameter can be one of the following values: - * @arg @ref LL_RCC_DFSDM1_AUDIO_CLKSOURCE - * @arg @ref LL_RCC_DFSDM2_AUDIO_CLKSOURCE (*) - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_DFSDM1_AUDIO_CLKSOURCE_I2S1 - * @arg @ref LL_RCC_DFSDM1_AUDIO_CLKSOURCE_I2S2 - * @arg @ref LL_RCC_DFSDM2_AUDIO_CLKSOURCE_I2S1 (*) - * @arg @ref LL_RCC_DFSDM2_AUDIO_CLKSOURCE_I2S2 (*) - * - * (*) value not defined in all devices. - */ -__STATIC_INLINE uint32_t LL_RCC_GetDFSDMAudioClockSource(uint32_t DFSDMx) -{ - return (uint32_t)(READ_BIT(RCC->DCKCFGR, DFSDMx) << 16U | DFSDMx); -} - -/** - * @brief Get DFSDM Audio Clock Source - * @rmtoll DCKCFGR CKDFSDM1SEL LL_RCC_GetDFSDMClockSource - * @param DFSDMx This parameter can be one of the following values: - * @arg @ref LL_RCC_DFSDM1_CLKSOURCE - * @arg @ref LL_RCC_DFSDM2_CLKSOURCE (*) - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_DFSDM1_CLKSOURCE_PCLK2 - * @arg @ref LL_RCC_DFSDM1_CLKSOURCE_SYSCLK - * @arg @ref LL_RCC_DFSDM2_CLKSOURCE_PCLK2 (*) - * @arg @ref LL_RCC_DFSDM2_CLKSOURCE_SYSCLK (*) - * - * (*) value not defined in all devices. - */ -__STATIC_INLINE uint32_t LL_RCC_GetDFSDMClockSource(uint32_t DFSDMx) -{ - return (uint32_t)(READ_BIT(RCC->DCKCFGR, DFSDMx)); -} -#endif /* DFSDM1_Channel0 */ - -#if defined(SPDIFRX) -/** - * @brief Get SPDIFRX clock source - * @rmtoll DCKCFGR2 SPDIFRXSEL LL_RCC_GetSPDIFRXClockSource - * @param SPDIFRXx This parameter can be one of the following values: - * @arg @ref LL_RCC_SPDIFRX1_CLKSOURCE - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_SPDIFRX1_CLKSOURCE_PLL - * @arg @ref LL_RCC_SPDIFRX1_CLKSOURCE_PLLI2S - * - * (*) value not defined in all devices. - */ -__STATIC_INLINE uint32_t LL_RCC_GetSPDIFRXClockSource(uint32_t SPDIFRXx) -{ - return (uint32_t)(READ_BIT(RCC->DCKCFGR2, SPDIFRXx)); -} -#endif /* SPDIFRX */ - -#if defined(DSI) -/** - * @brief Get DSI Clock Source - * @rmtoll DCKCFGR DSISEL LL_RCC_GetDSIClockSource - * @param DSIx This parameter can be one of the following values: - * @arg @ref LL_RCC_DSI_CLKSOURCE - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_DSI_CLKSOURCE_PHY - * @arg @ref LL_RCC_DSI_CLKSOURCE_PLL - */ -__STATIC_INLINE uint32_t LL_RCC_GetDSIClockSource(uint32_t DSIx) -{ - return (uint32_t)(READ_BIT(RCC->DCKCFGR, DSIx)); -} -#endif /* DSI */ - -/** - * @} - */ - -/** @defgroup RCC_LL_EF_RTC RTC - * @{ - */ - -/** - * @brief Set RTC Clock Source - * @note Once the RTC clock source has been selected, it cannot be changed anymore unless - * the Backup domain is reset, or unless a failure is detected on LSE (LSECSSD is - * set). The BDRST bit can be used to reset them. - * @rmtoll BDCR RTCSEL LL_RCC_SetRTCClockSource - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_RTC_CLKSOURCE_NONE - * @arg @ref LL_RCC_RTC_CLKSOURCE_LSE - * @arg @ref LL_RCC_RTC_CLKSOURCE_LSI - * @arg @ref LL_RCC_RTC_CLKSOURCE_HSE - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetRTCClockSource(uint32_t Source) -{ - MODIFY_REG(RCC->BDCR, RCC_BDCR_RTCSEL, Source); -} - -/** - * @brief Get RTC Clock Source - * @rmtoll BDCR RTCSEL LL_RCC_GetRTCClockSource - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_RTC_CLKSOURCE_NONE - * @arg @ref LL_RCC_RTC_CLKSOURCE_LSE - * @arg @ref LL_RCC_RTC_CLKSOURCE_LSI - * @arg @ref LL_RCC_RTC_CLKSOURCE_HSE - */ -__STATIC_INLINE uint32_t LL_RCC_GetRTCClockSource(void) -{ - return (uint32_t)(READ_BIT(RCC->BDCR, RCC_BDCR_RTCSEL)); -} - -/** - * @brief Enable RTC - * @rmtoll BDCR RTCEN LL_RCC_EnableRTC - * @retval None - */ -__STATIC_INLINE void LL_RCC_EnableRTC(void) -{ - SET_BIT(RCC->BDCR, RCC_BDCR_RTCEN); -} - -/** - * @brief Disable RTC - * @rmtoll BDCR RTCEN LL_RCC_DisableRTC - * @retval None - */ -__STATIC_INLINE void LL_RCC_DisableRTC(void) -{ - CLEAR_BIT(RCC->BDCR, RCC_BDCR_RTCEN); -} - -/** - * @brief Check if RTC has been enabled or not - * @rmtoll BDCR RTCEN LL_RCC_IsEnabledRTC - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsEnabledRTC(void) -{ - return (READ_BIT(RCC->BDCR, RCC_BDCR_RTCEN) == (RCC_BDCR_RTCEN)); -} - -/** - * @brief Force the Backup domain reset - * @rmtoll BDCR BDRST LL_RCC_ForceBackupDomainReset - * @retval None - */ -__STATIC_INLINE void LL_RCC_ForceBackupDomainReset(void) -{ - SET_BIT(RCC->BDCR, RCC_BDCR_BDRST); -} - -/** - * @brief Release the Backup domain reset - * @rmtoll BDCR BDRST LL_RCC_ReleaseBackupDomainReset - * @retval None - */ -__STATIC_INLINE void LL_RCC_ReleaseBackupDomainReset(void) -{ - CLEAR_BIT(RCC->BDCR, RCC_BDCR_BDRST); -} - -/** - * @brief Set HSE Prescalers for RTC Clock - * @rmtoll CFGR RTCPRE LL_RCC_SetRTC_HSEPrescaler - * @param Prescaler This parameter can be one of the following values: - * @arg @ref LL_RCC_RTC_NOCLOCK - * @arg @ref LL_RCC_RTC_HSE_DIV_2 - * @arg @ref LL_RCC_RTC_HSE_DIV_3 - * @arg @ref LL_RCC_RTC_HSE_DIV_4 - * @arg @ref LL_RCC_RTC_HSE_DIV_5 - * @arg @ref LL_RCC_RTC_HSE_DIV_6 - * @arg @ref LL_RCC_RTC_HSE_DIV_7 - * @arg @ref LL_RCC_RTC_HSE_DIV_8 - * @arg @ref LL_RCC_RTC_HSE_DIV_9 - * @arg @ref LL_RCC_RTC_HSE_DIV_10 - * @arg @ref LL_RCC_RTC_HSE_DIV_11 - * @arg @ref LL_RCC_RTC_HSE_DIV_12 - * @arg @ref LL_RCC_RTC_HSE_DIV_13 - * @arg @ref LL_RCC_RTC_HSE_DIV_14 - * @arg @ref LL_RCC_RTC_HSE_DIV_15 - * @arg @ref LL_RCC_RTC_HSE_DIV_16 - * @arg @ref LL_RCC_RTC_HSE_DIV_17 - * @arg @ref LL_RCC_RTC_HSE_DIV_18 - * @arg @ref LL_RCC_RTC_HSE_DIV_19 - * @arg @ref LL_RCC_RTC_HSE_DIV_20 - * @arg @ref LL_RCC_RTC_HSE_DIV_21 - * @arg @ref LL_RCC_RTC_HSE_DIV_22 - * @arg @ref LL_RCC_RTC_HSE_DIV_23 - * @arg @ref LL_RCC_RTC_HSE_DIV_24 - * @arg @ref LL_RCC_RTC_HSE_DIV_25 - * @arg @ref LL_RCC_RTC_HSE_DIV_26 - * @arg @ref LL_RCC_RTC_HSE_DIV_27 - * @arg @ref LL_RCC_RTC_HSE_DIV_28 - * @arg @ref LL_RCC_RTC_HSE_DIV_29 - * @arg @ref LL_RCC_RTC_HSE_DIV_30 - * @arg @ref LL_RCC_RTC_HSE_DIV_31 - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetRTC_HSEPrescaler(uint32_t Prescaler) -{ - MODIFY_REG(RCC->CFGR, RCC_CFGR_RTCPRE, Prescaler); -} - -/** - * @brief Get HSE Prescalers for RTC Clock - * @rmtoll CFGR RTCPRE LL_RCC_GetRTC_HSEPrescaler - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_RTC_NOCLOCK - * @arg @ref LL_RCC_RTC_HSE_DIV_2 - * @arg @ref LL_RCC_RTC_HSE_DIV_3 - * @arg @ref LL_RCC_RTC_HSE_DIV_4 - * @arg @ref LL_RCC_RTC_HSE_DIV_5 - * @arg @ref LL_RCC_RTC_HSE_DIV_6 - * @arg @ref LL_RCC_RTC_HSE_DIV_7 - * @arg @ref LL_RCC_RTC_HSE_DIV_8 - * @arg @ref LL_RCC_RTC_HSE_DIV_9 - * @arg @ref LL_RCC_RTC_HSE_DIV_10 - * @arg @ref LL_RCC_RTC_HSE_DIV_11 - * @arg @ref LL_RCC_RTC_HSE_DIV_12 - * @arg @ref LL_RCC_RTC_HSE_DIV_13 - * @arg @ref LL_RCC_RTC_HSE_DIV_14 - * @arg @ref LL_RCC_RTC_HSE_DIV_15 - * @arg @ref LL_RCC_RTC_HSE_DIV_16 - * @arg @ref LL_RCC_RTC_HSE_DIV_17 - * @arg @ref LL_RCC_RTC_HSE_DIV_18 - * @arg @ref LL_RCC_RTC_HSE_DIV_19 - * @arg @ref LL_RCC_RTC_HSE_DIV_20 - * @arg @ref LL_RCC_RTC_HSE_DIV_21 - * @arg @ref LL_RCC_RTC_HSE_DIV_22 - * @arg @ref LL_RCC_RTC_HSE_DIV_23 - * @arg @ref LL_RCC_RTC_HSE_DIV_24 - * @arg @ref LL_RCC_RTC_HSE_DIV_25 - * @arg @ref LL_RCC_RTC_HSE_DIV_26 - * @arg @ref LL_RCC_RTC_HSE_DIV_27 - * @arg @ref LL_RCC_RTC_HSE_DIV_28 - * @arg @ref LL_RCC_RTC_HSE_DIV_29 - * @arg @ref LL_RCC_RTC_HSE_DIV_30 - * @arg @ref LL_RCC_RTC_HSE_DIV_31 - */ -__STATIC_INLINE uint32_t LL_RCC_GetRTC_HSEPrescaler(void) -{ - return (uint32_t)(READ_BIT(RCC->CFGR, RCC_CFGR_RTCPRE)); -} - -/** - * @} - */ - -#if defined(RCC_DCKCFGR_TIMPRE) -/** @defgroup RCC_LL_EF_TIM_CLOCK_PRESCALER TIM - * @{ - */ - -/** - * @brief Set Timers Clock Prescalers - * @rmtoll DCKCFGR TIMPRE LL_RCC_SetTIMPrescaler - * @param Prescaler This parameter can be one of the following values: - * @arg @ref LL_RCC_TIM_PRESCALER_TWICE - * @arg @ref LL_RCC_TIM_PRESCALER_FOUR_TIMES - * @retval None - */ -__STATIC_INLINE void LL_RCC_SetTIMPrescaler(uint32_t Prescaler) -{ - MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_TIMPRE, Prescaler); -} - -/** - * @brief Get Timers Clock Prescalers - * @rmtoll DCKCFGR TIMPRE LL_RCC_GetTIMPrescaler - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_TIM_PRESCALER_TWICE - * @arg @ref LL_RCC_TIM_PRESCALER_FOUR_TIMES - */ -__STATIC_INLINE uint32_t LL_RCC_GetTIMPrescaler(void) -{ - return (uint32_t)(READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_TIMPRE)); -} - -/** - * @} - */ -#endif /* RCC_DCKCFGR_TIMPRE */ - -/** @defgroup RCC_LL_EF_PLL PLL - * @{ - */ - -/** - * @brief Enable PLL - * @rmtoll CR PLLON LL_RCC_PLL_Enable - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLL_Enable(void) -{ - SET_BIT(RCC->CR, RCC_CR_PLLON); -} - -/** - * @brief Disable PLL - * @note Cannot be disabled if the PLL clock is used as the system clock - * @rmtoll CR PLLON LL_RCC_PLL_Disable - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLL_Disable(void) -{ - CLEAR_BIT(RCC->CR, RCC_CR_PLLON); -} - -/** - * @brief Check if PLL Ready - * @rmtoll CR PLLRDY LL_RCC_PLL_IsReady - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_PLL_IsReady(void) -{ - return (READ_BIT(RCC->CR, RCC_CR_PLLRDY) == (RCC_CR_PLLRDY)); -} - -/** - * @brief Configure PLL used for SYSCLK Domain - * @note PLL Source and PLLM Divider can be written only when PLL, - * PLLI2S and PLLSAI(*) are disabled - * @note PLLN/PLLP can be written only when PLL is disabled - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLL_ConfigDomain_SYS\n - * PLLCFGR PLLM LL_RCC_PLL_ConfigDomain_SYS\n - * PLLCFGR PLLN LL_RCC_PLL_ConfigDomain_SYS\n - * PLLCFGR PLLR LL_RCC_PLL_ConfigDomain_SYS\n - * PLLCFGR PLLP LL_RCC_PLL_ConfigDomain_SYS - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @param PLLM This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLM_DIV_2 - * @arg @ref LL_RCC_PLLM_DIV_3 - * @arg @ref LL_RCC_PLLM_DIV_4 - * @arg @ref LL_RCC_PLLM_DIV_5 - * @arg @ref LL_RCC_PLLM_DIV_6 - * @arg @ref LL_RCC_PLLM_DIV_7 - * @arg @ref LL_RCC_PLLM_DIV_8 - * @arg @ref LL_RCC_PLLM_DIV_9 - * @arg @ref LL_RCC_PLLM_DIV_10 - * @arg @ref LL_RCC_PLLM_DIV_11 - * @arg @ref LL_RCC_PLLM_DIV_12 - * @arg @ref LL_RCC_PLLM_DIV_13 - * @arg @ref LL_RCC_PLLM_DIV_14 - * @arg @ref LL_RCC_PLLM_DIV_15 - * @arg @ref LL_RCC_PLLM_DIV_16 - * @arg @ref LL_RCC_PLLM_DIV_17 - * @arg @ref LL_RCC_PLLM_DIV_18 - * @arg @ref LL_RCC_PLLM_DIV_19 - * @arg @ref LL_RCC_PLLM_DIV_20 - * @arg @ref LL_RCC_PLLM_DIV_21 - * @arg @ref LL_RCC_PLLM_DIV_22 - * @arg @ref LL_RCC_PLLM_DIV_23 - * @arg @ref LL_RCC_PLLM_DIV_24 - * @arg @ref LL_RCC_PLLM_DIV_25 - * @arg @ref LL_RCC_PLLM_DIV_26 - * @arg @ref LL_RCC_PLLM_DIV_27 - * @arg @ref LL_RCC_PLLM_DIV_28 - * @arg @ref LL_RCC_PLLM_DIV_29 - * @arg @ref LL_RCC_PLLM_DIV_30 - * @arg @ref LL_RCC_PLLM_DIV_31 - * @arg @ref LL_RCC_PLLM_DIV_32 - * @arg @ref LL_RCC_PLLM_DIV_33 - * @arg @ref LL_RCC_PLLM_DIV_34 - * @arg @ref LL_RCC_PLLM_DIV_35 - * @arg @ref LL_RCC_PLLM_DIV_36 - * @arg @ref LL_RCC_PLLM_DIV_37 - * @arg @ref LL_RCC_PLLM_DIV_38 - * @arg @ref LL_RCC_PLLM_DIV_39 - * @arg @ref LL_RCC_PLLM_DIV_40 - * @arg @ref LL_RCC_PLLM_DIV_41 - * @arg @ref LL_RCC_PLLM_DIV_42 - * @arg @ref LL_RCC_PLLM_DIV_43 - * @arg @ref LL_RCC_PLLM_DIV_44 - * @arg @ref LL_RCC_PLLM_DIV_45 - * @arg @ref LL_RCC_PLLM_DIV_46 - * @arg @ref LL_RCC_PLLM_DIV_47 - * @arg @ref LL_RCC_PLLM_DIV_48 - * @arg @ref LL_RCC_PLLM_DIV_49 - * @arg @ref LL_RCC_PLLM_DIV_50 - * @arg @ref LL_RCC_PLLM_DIV_51 - * @arg @ref LL_RCC_PLLM_DIV_52 - * @arg @ref LL_RCC_PLLM_DIV_53 - * @arg @ref LL_RCC_PLLM_DIV_54 - * @arg @ref LL_RCC_PLLM_DIV_55 - * @arg @ref LL_RCC_PLLM_DIV_56 - * @arg @ref LL_RCC_PLLM_DIV_57 - * @arg @ref LL_RCC_PLLM_DIV_58 - * @arg @ref LL_RCC_PLLM_DIV_59 - * @arg @ref LL_RCC_PLLM_DIV_60 - * @arg @ref LL_RCC_PLLM_DIV_61 - * @arg @ref LL_RCC_PLLM_DIV_62 - * @arg @ref LL_RCC_PLLM_DIV_63 - * @param PLLN Between 50/192(*) and 432 - * - * (*) value not defined in all devices. - * @param PLLP_R This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLP_DIV_2 - * @arg @ref LL_RCC_PLLP_DIV_4 - * @arg @ref LL_RCC_PLLP_DIV_6 - * @arg @ref LL_RCC_PLLP_DIV_8 - * @arg @ref LL_RCC_PLLR_DIV_2 (*) - * @arg @ref LL_RCC_PLLR_DIV_3 (*) - * @arg @ref LL_RCC_PLLR_DIV_4 (*) - * @arg @ref LL_RCC_PLLR_DIV_5 (*) - * @arg @ref LL_RCC_PLLR_DIV_6 (*) - * @arg @ref LL_RCC_PLLR_DIV_7 (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLL_ConfigDomain_SYS(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLP_R) -{ - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC | RCC_PLLCFGR_PLLM | RCC_PLLCFGR_PLLN, - Source | PLLM | PLLN << RCC_PLLCFGR_PLLN_Pos); - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLP, PLLP_R); -#if defined(RCC_PLLR_SYSCLK_SUPPORT) - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLR, PLLP_R); -#endif /* RCC_PLLR_SYSCLK_SUPPORT */ -} - -/** - * @brief Configure PLL used for 48Mhz domain clock - * @note PLL Source and PLLM Divider can be written only when PLL, - * PLLI2S and PLLSAI(*) are disabled - * @note PLLN/PLLQ can be written only when PLL is disabled - * @note This can be selected for USB, RNG, SDIO - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLL_ConfigDomain_48M\n - * PLLCFGR PLLM LL_RCC_PLL_ConfigDomain_48M\n - * PLLCFGR PLLN LL_RCC_PLL_ConfigDomain_48M\n - * PLLCFGR PLLQ LL_RCC_PLL_ConfigDomain_48M - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @param PLLM This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLM_DIV_2 - * @arg @ref LL_RCC_PLLM_DIV_3 - * @arg @ref LL_RCC_PLLM_DIV_4 - * @arg @ref LL_RCC_PLLM_DIV_5 - * @arg @ref LL_RCC_PLLM_DIV_6 - * @arg @ref LL_RCC_PLLM_DIV_7 - * @arg @ref LL_RCC_PLLM_DIV_8 - * @arg @ref LL_RCC_PLLM_DIV_9 - * @arg @ref LL_RCC_PLLM_DIV_10 - * @arg @ref LL_RCC_PLLM_DIV_11 - * @arg @ref LL_RCC_PLLM_DIV_12 - * @arg @ref LL_RCC_PLLM_DIV_13 - * @arg @ref LL_RCC_PLLM_DIV_14 - * @arg @ref LL_RCC_PLLM_DIV_15 - * @arg @ref LL_RCC_PLLM_DIV_16 - * @arg @ref LL_RCC_PLLM_DIV_17 - * @arg @ref LL_RCC_PLLM_DIV_18 - * @arg @ref LL_RCC_PLLM_DIV_19 - * @arg @ref LL_RCC_PLLM_DIV_20 - * @arg @ref LL_RCC_PLLM_DIV_21 - * @arg @ref LL_RCC_PLLM_DIV_22 - * @arg @ref LL_RCC_PLLM_DIV_23 - * @arg @ref LL_RCC_PLLM_DIV_24 - * @arg @ref LL_RCC_PLLM_DIV_25 - * @arg @ref LL_RCC_PLLM_DIV_26 - * @arg @ref LL_RCC_PLLM_DIV_27 - * @arg @ref LL_RCC_PLLM_DIV_28 - * @arg @ref LL_RCC_PLLM_DIV_29 - * @arg @ref LL_RCC_PLLM_DIV_30 - * @arg @ref LL_RCC_PLLM_DIV_31 - * @arg @ref LL_RCC_PLLM_DIV_32 - * @arg @ref LL_RCC_PLLM_DIV_33 - * @arg @ref LL_RCC_PLLM_DIV_34 - * @arg @ref LL_RCC_PLLM_DIV_35 - * @arg @ref LL_RCC_PLLM_DIV_36 - * @arg @ref LL_RCC_PLLM_DIV_37 - * @arg @ref LL_RCC_PLLM_DIV_38 - * @arg @ref LL_RCC_PLLM_DIV_39 - * @arg @ref LL_RCC_PLLM_DIV_40 - * @arg @ref LL_RCC_PLLM_DIV_41 - * @arg @ref LL_RCC_PLLM_DIV_42 - * @arg @ref LL_RCC_PLLM_DIV_43 - * @arg @ref LL_RCC_PLLM_DIV_44 - * @arg @ref LL_RCC_PLLM_DIV_45 - * @arg @ref LL_RCC_PLLM_DIV_46 - * @arg @ref LL_RCC_PLLM_DIV_47 - * @arg @ref LL_RCC_PLLM_DIV_48 - * @arg @ref LL_RCC_PLLM_DIV_49 - * @arg @ref LL_RCC_PLLM_DIV_50 - * @arg @ref LL_RCC_PLLM_DIV_51 - * @arg @ref LL_RCC_PLLM_DIV_52 - * @arg @ref LL_RCC_PLLM_DIV_53 - * @arg @ref LL_RCC_PLLM_DIV_54 - * @arg @ref LL_RCC_PLLM_DIV_55 - * @arg @ref LL_RCC_PLLM_DIV_56 - * @arg @ref LL_RCC_PLLM_DIV_57 - * @arg @ref LL_RCC_PLLM_DIV_58 - * @arg @ref LL_RCC_PLLM_DIV_59 - * @arg @ref LL_RCC_PLLM_DIV_60 - * @arg @ref LL_RCC_PLLM_DIV_61 - * @arg @ref LL_RCC_PLLM_DIV_62 - * @arg @ref LL_RCC_PLLM_DIV_63 - * @param PLLN Between 50/192(*) and 432 - * - * (*) value not defined in all devices. - * @param PLLQ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLQ_DIV_2 - * @arg @ref LL_RCC_PLLQ_DIV_3 - * @arg @ref LL_RCC_PLLQ_DIV_4 - * @arg @ref LL_RCC_PLLQ_DIV_5 - * @arg @ref LL_RCC_PLLQ_DIV_6 - * @arg @ref LL_RCC_PLLQ_DIV_7 - * @arg @ref LL_RCC_PLLQ_DIV_8 - * @arg @ref LL_RCC_PLLQ_DIV_9 - * @arg @ref LL_RCC_PLLQ_DIV_10 - * @arg @ref LL_RCC_PLLQ_DIV_11 - * @arg @ref LL_RCC_PLLQ_DIV_12 - * @arg @ref LL_RCC_PLLQ_DIV_13 - * @arg @ref LL_RCC_PLLQ_DIV_14 - * @arg @ref LL_RCC_PLLQ_DIV_15 - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLL_ConfigDomain_48M(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLQ) -{ - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC | RCC_PLLCFGR_PLLM | RCC_PLLCFGR_PLLN | RCC_PLLCFGR_PLLQ, - Source | PLLM | PLLN << RCC_PLLCFGR_PLLN_Pos | PLLQ); -} - -#if defined(DSI) -/** - * @brief Configure PLL used for DSI clock - * @note PLL Source and PLLM Divider can be written only when PLL, - * PLLI2S and PLLSAI are disabled - * @note PLLN/PLLR can be written only when PLL is disabled - * @note This can be selected for DSI - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLL_ConfigDomain_DSI\n - * PLLCFGR PLLM LL_RCC_PLL_ConfigDomain_DSI\n - * PLLCFGR PLLN LL_RCC_PLL_ConfigDomain_DSI\n - * PLLCFGR PLLR LL_RCC_PLL_ConfigDomain_DSI - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @param PLLM This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLM_DIV_2 - * @arg @ref LL_RCC_PLLM_DIV_3 - * @arg @ref LL_RCC_PLLM_DIV_4 - * @arg @ref LL_RCC_PLLM_DIV_5 - * @arg @ref LL_RCC_PLLM_DIV_6 - * @arg @ref LL_RCC_PLLM_DIV_7 - * @arg @ref LL_RCC_PLLM_DIV_8 - * @arg @ref LL_RCC_PLLM_DIV_9 - * @arg @ref LL_RCC_PLLM_DIV_10 - * @arg @ref LL_RCC_PLLM_DIV_11 - * @arg @ref LL_RCC_PLLM_DIV_12 - * @arg @ref LL_RCC_PLLM_DIV_13 - * @arg @ref LL_RCC_PLLM_DIV_14 - * @arg @ref LL_RCC_PLLM_DIV_15 - * @arg @ref LL_RCC_PLLM_DIV_16 - * @arg @ref LL_RCC_PLLM_DIV_17 - * @arg @ref LL_RCC_PLLM_DIV_18 - * @arg @ref LL_RCC_PLLM_DIV_19 - * @arg @ref LL_RCC_PLLM_DIV_20 - * @arg @ref LL_RCC_PLLM_DIV_21 - * @arg @ref LL_RCC_PLLM_DIV_22 - * @arg @ref LL_RCC_PLLM_DIV_23 - * @arg @ref LL_RCC_PLLM_DIV_24 - * @arg @ref LL_RCC_PLLM_DIV_25 - * @arg @ref LL_RCC_PLLM_DIV_26 - * @arg @ref LL_RCC_PLLM_DIV_27 - * @arg @ref LL_RCC_PLLM_DIV_28 - * @arg @ref LL_RCC_PLLM_DIV_29 - * @arg @ref LL_RCC_PLLM_DIV_30 - * @arg @ref LL_RCC_PLLM_DIV_31 - * @arg @ref LL_RCC_PLLM_DIV_32 - * @arg @ref LL_RCC_PLLM_DIV_33 - * @arg @ref LL_RCC_PLLM_DIV_34 - * @arg @ref LL_RCC_PLLM_DIV_35 - * @arg @ref LL_RCC_PLLM_DIV_36 - * @arg @ref LL_RCC_PLLM_DIV_37 - * @arg @ref LL_RCC_PLLM_DIV_38 - * @arg @ref LL_RCC_PLLM_DIV_39 - * @arg @ref LL_RCC_PLLM_DIV_40 - * @arg @ref LL_RCC_PLLM_DIV_41 - * @arg @ref LL_RCC_PLLM_DIV_42 - * @arg @ref LL_RCC_PLLM_DIV_43 - * @arg @ref LL_RCC_PLLM_DIV_44 - * @arg @ref LL_RCC_PLLM_DIV_45 - * @arg @ref LL_RCC_PLLM_DIV_46 - * @arg @ref LL_RCC_PLLM_DIV_47 - * @arg @ref LL_RCC_PLLM_DIV_48 - * @arg @ref LL_RCC_PLLM_DIV_49 - * @arg @ref LL_RCC_PLLM_DIV_50 - * @arg @ref LL_RCC_PLLM_DIV_51 - * @arg @ref LL_RCC_PLLM_DIV_52 - * @arg @ref LL_RCC_PLLM_DIV_53 - * @arg @ref LL_RCC_PLLM_DIV_54 - * @arg @ref LL_RCC_PLLM_DIV_55 - * @arg @ref LL_RCC_PLLM_DIV_56 - * @arg @ref LL_RCC_PLLM_DIV_57 - * @arg @ref LL_RCC_PLLM_DIV_58 - * @arg @ref LL_RCC_PLLM_DIV_59 - * @arg @ref LL_RCC_PLLM_DIV_60 - * @arg @ref LL_RCC_PLLM_DIV_61 - * @arg @ref LL_RCC_PLLM_DIV_62 - * @arg @ref LL_RCC_PLLM_DIV_63 - * @param PLLN Between 50 and 432 - * @param PLLR This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLR_DIV_2 - * @arg @ref LL_RCC_PLLR_DIV_3 - * @arg @ref LL_RCC_PLLR_DIV_4 - * @arg @ref LL_RCC_PLLR_DIV_5 - * @arg @ref LL_RCC_PLLR_DIV_6 - * @arg @ref LL_RCC_PLLR_DIV_7 - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLL_ConfigDomain_DSI(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLR) -{ - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC | RCC_PLLCFGR_PLLM | RCC_PLLCFGR_PLLN | RCC_PLLCFGR_PLLR, - Source | PLLM | PLLN << RCC_PLLCFGR_PLLN_Pos | PLLR); -} -#endif /* DSI */ - -#if defined(RCC_PLLR_I2S_CLKSOURCE_SUPPORT) -/** - * @brief Configure PLL used for I2S clock - * @note PLL Source and PLLM Divider can be written only when PLL, - * PLLI2S and PLLSAI are disabled - * @note PLLN/PLLR can be written only when PLL is disabled - * @note This can be selected for I2S - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLL_ConfigDomain_I2S\n - * PLLCFGR PLLM LL_RCC_PLL_ConfigDomain_I2S\n - * PLLCFGR PLLN LL_RCC_PLL_ConfigDomain_I2S\n - * PLLCFGR PLLR LL_RCC_PLL_ConfigDomain_I2S - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @param PLLM This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLM_DIV_2 - * @arg @ref LL_RCC_PLLM_DIV_3 - * @arg @ref LL_RCC_PLLM_DIV_4 - * @arg @ref LL_RCC_PLLM_DIV_5 - * @arg @ref LL_RCC_PLLM_DIV_6 - * @arg @ref LL_RCC_PLLM_DIV_7 - * @arg @ref LL_RCC_PLLM_DIV_8 - * @arg @ref LL_RCC_PLLM_DIV_9 - * @arg @ref LL_RCC_PLLM_DIV_10 - * @arg @ref LL_RCC_PLLM_DIV_11 - * @arg @ref LL_RCC_PLLM_DIV_12 - * @arg @ref LL_RCC_PLLM_DIV_13 - * @arg @ref LL_RCC_PLLM_DIV_14 - * @arg @ref LL_RCC_PLLM_DIV_15 - * @arg @ref LL_RCC_PLLM_DIV_16 - * @arg @ref LL_RCC_PLLM_DIV_17 - * @arg @ref LL_RCC_PLLM_DIV_18 - * @arg @ref LL_RCC_PLLM_DIV_19 - * @arg @ref LL_RCC_PLLM_DIV_20 - * @arg @ref LL_RCC_PLLM_DIV_21 - * @arg @ref LL_RCC_PLLM_DIV_22 - * @arg @ref LL_RCC_PLLM_DIV_23 - * @arg @ref LL_RCC_PLLM_DIV_24 - * @arg @ref LL_RCC_PLLM_DIV_25 - * @arg @ref LL_RCC_PLLM_DIV_26 - * @arg @ref LL_RCC_PLLM_DIV_27 - * @arg @ref LL_RCC_PLLM_DIV_28 - * @arg @ref LL_RCC_PLLM_DIV_29 - * @arg @ref LL_RCC_PLLM_DIV_30 - * @arg @ref LL_RCC_PLLM_DIV_31 - * @arg @ref LL_RCC_PLLM_DIV_32 - * @arg @ref LL_RCC_PLLM_DIV_33 - * @arg @ref LL_RCC_PLLM_DIV_34 - * @arg @ref LL_RCC_PLLM_DIV_35 - * @arg @ref LL_RCC_PLLM_DIV_36 - * @arg @ref LL_RCC_PLLM_DIV_37 - * @arg @ref LL_RCC_PLLM_DIV_38 - * @arg @ref LL_RCC_PLLM_DIV_39 - * @arg @ref LL_RCC_PLLM_DIV_40 - * @arg @ref LL_RCC_PLLM_DIV_41 - * @arg @ref LL_RCC_PLLM_DIV_42 - * @arg @ref LL_RCC_PLLM_DIV_43 - * @arg @ref LL_RCC_PLLM_DIV_44 - * @arg @ref LL_RCC_PLLM_DIV_45 - * @arg @ref LL_RCC_PLLM_DIV_46 - * @arg @ref LL_RCC_PLLM_DIV_47 - * @arg @ref LL_RCC_PLLM_DIV_48 - * @arg @ref LL_RCC_PLLM_DIV_49 - * @arg @ref LL_RCC_PLLM_DIV_50 - * @arg @ref LL_RCC_PLLM_DIV_51 - * @arg @ref LL_RCC_PLLM_DIV_52 - * @arg @ref LL_RCC_PLLM_DIV_53 - * @arg @ref LL_RCC_PLLM_DIV_54 - * @arg @ref LL_RCC_PLLM_DIV_55 - * @arg @ref LL_RCC_PLLM_DIV_56 - * @arg @ref LL_RCC_PLLM_DIV_57 - * @arg @ref LL_RCC_PLLM_DIV_58 - * @arg @ref LL_RCC_PLLM_DIV_59 - * @arg @ref LL_RCC_PLLM_DIV_60 - * @arg @ref LL_RCC_PLLM_DIV_61 - * @arg @ref LL_RCC_PLLM_DIV_62 - * @arg @ref LL_RCC_PLLM_DIV_63 - * @param PLLN Between 50 and 432 - * @param PLLR This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLR_DIV_2 - * @arg @ref LL_RCC_PLLR_DIV_3 - * @arg @ref LL_RCC_PLLR_DIV_4 - * @arg @ref LL_RCC_PLLR_DIV_5 - * @arg @ref LL_RCC_PLLR_DIV_6 - * @arg @ref LL_RCC_PLLR_DIV_7 - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLL_ConfigDomain_I2S(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLR) -{ - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC | RCC_PLLCFGR_PLLM | RCC_PLLCFGR_PLLN | RCC_PLLCFGR_PLLR, - Source | PLLM | PLLN << RCC_PLLCFGR_PLLN_Pos | PLLR); -} -#endif /* RCC_PLLR_I2S_CLKSOURCE_SUPPORT */ - -#if defined(SPDIFRX) -/** - * @brief Configure PLL used for SPDIFRX clock - * @note PLL Source and PLLM Divider can be written only when PLL, - * PLLI2S and PLLSAI are disabled - * @note PLLN/PLLR can be written only when PLL is disabled - * @note This can be selected for SPDIFRX - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLL_ConfigDomain_SPDIFRX\n - * PLLCFGR PLLM LL_RCC_PLL_ConfigDomain_SPDIFRX\n - * PLLCFGR PLLN LL_RCC_PLL_ConfigDomain_SPDIFRX\n - * PLLCFGR PLLR LL_RCC_PLL_ConfigDomain_SPDIFRX - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @param PLLM This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLM_DIV_2 - * @arg @ref LL_RCC_PLLM_DIV_3 - * @arg @ref LL_RCC_PLLM_DIV_4 - * @arg @ref LL_RCC_PLLM_DIV_5 - * @arg @ref LL_RCC_PLLM_DIV_6 - * @arg @ref LL_RCC_PLLM_DIV_7 - * @arg @ref LL_RCC_PLLM_DIV_8 - * @arg @ref LL_RCC_PLLM_DIV_9 - * @arg @ref LL_RCC_PLLM_DIV_10 - * @arg @ref LL_RCC_PLLM_DIV_11 - * @arg @ref LL_RCC_PLLM_DIV_12 - * @arg @ref LL_RCC_PLLM_DIV_13 - * @arg @ref LL_RCC_PLLM_DIV_14 - * @arg @ref LL_RCC_PLLM_DIV_15 - * @arg @ref LL_RCC_PLLM_DIV_16 - * @arg @ref LL_RCC_PLLM_DIV_17 - * @arg @ref LL_RCC_PLLM_DIV_18 - * @arg @ref LL_RCC_PLLM_DIV_19 - * @arg @ref LL_RCC_PLLM_DIV_20 - * @arg @ref LL_RCC_PLLM_DIV_21 - * @arg @ref LL_RCC_PLLM_DIV_22 - * @arg @ref LL_RCC_PLLM_DIV_23 - * @arg @ref LL_RCC_PLLM_DIV_24 - * @arg @ref LL_RCC_PLLM_DIV_25 - * @arg @ref LL_RCC_PLLM_DIV_26 - * @arg @ref LL_RCC_PLLM_DIV_27 - * @arg @ref LL_RCC_PLLM_DIV_28 - * @arg @ref LL_RCC_PLLM_DIV_29 - * @arg @ref LL_RCC_PLLM_DIV_30 - * @arg @ref LL_RCC_PLLM_DIV_31 - * @arg @ref LL_RCC_PLLM_DIV_32 - * @arg @ref LL_RCC_PLLM_DIV_33 - * @arg @ref LL_RCC_PLLM_DIV_34 - * @arg @ref LL_RCC_PLLM_DIV_35 - * @arg @ref LL_RCC_PLLM_DIV_36 - * @arg @ref LL_RCC_PLLM_DIV_37 - * @arg @ref LL_RCC_PLLM_DIV_38 - * @arg @ref LL_RCC_PLLM_DIV_39 - * @arg @ref LL_RCC_PLLM_DIV_40 - * @arg @ref LL_RCC_PLLM_DIV_41 - * @arg @ref LL_RCC_PLLM_DIV_42 - * @arg @ref LL_RCC_PLLM_DIV_43 - * @arg @ref LL_RCC_PLLM_DIV_44 - * @arg @ref LL_RCC_PLLM_DIV_45 - * @arg @ref LL_RCC_PLLM_DIV_46 - * @arg @ref LL_RCC_PLLM_DIV_47 - * @arg @ref LL_RCC_PLLM_DIV_48 - * @arg @ref LL_RCC_PLLM_DIV_49 - * @arg @ref LL_RCC_PLLM_DIV_50 - * @arg @ref LL_RCC_PLLM_DIV_51 - * @arg @ref LL_RCC_PLLM_DIV_52 - * @arg @ref LL_RCC_PLLM_DIV_53 - * @arg @ref LL_RCC_PLLM_DIV_54 - * @arg @ref LL_RCC_PLLM_DIV_55 - * @arg @ref LL_RCC_PLLM_DIV_56 - * @arg @ref LL_RCC_PLLM_DIV_57 - * @arg @ref LL_RCC_PLLM_DIV_58 - * @arg @ref LL_RCC_PLLM_DIV_59 - * @arg @ref LL_RCC_PLLM_DIV_60 - * @arg @ref LL_RCC_PLLM_DIV_61 - * @arg @ref LL_RCC_PLLM_DIV_62 - * @arg @ref LL_RCC_PLLM_DIV_63 - * @param PLLN Between 50 and 432 - * @param PLLR This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLR_DIV_2 - * @arg @ref LL_RCC_PLLR_DIV_3 - * @arg @ref LL_RCC_PLLR_DIV_4 - * @arg @ref LL_RCC_PLLR_DIV_5 - * @arg @ref LL_RCC_PLLR_DIV_6 - * @arg @ref LL_RCC_PLLR_DIV_7 - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLL_ConfigDomain_SPDIFRX(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLR) -{ - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC | RCC_PLLCFGR_PLLM | RCC_PLLCFGR_PLLN | RCC_PLLCFGR_PLLR, - Source | PLLM | PLLN << RCC_PLLCFGR_PLLN_Pos | PLLR); -} -#endif /* SPDIFRX */ - -#if defined(RCC_PLLCFGR_PLLR) -#if defined(SAI1) -/** - * @brief Configure PLL used for SAI clock - * @note PLL Source and PLLM Divider can be written only when PLL, - * PLLI2S and PLLSAI are disabled - * @note PLLN/PLLR can be written only when PLL is disabled - * @note This can be selected for SAI - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLL_ConfigDomain_SAI\n - * PLLCFGR PLLM LL_RCC_PLL_ConfigDomain_SAI\n - * PLLCFGR PLLN LL_RCC_PLL_ConfigDomain_SAI\n - * PLLCFGR PLLR LL_RCC_PLL_ConfigDomain_SAI\n - * DCKCFGR PLLDIVR LL_RCC_PLL_ConfigDomain_SAI - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @param PLLM This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLM_DIV_2 - * @arg @ref LL_RCC_PLLM_DIV_3 - * @arg @ref LL_RCC_PLLM_DIV_4 - * @arg @ref LL_RCC_PLLM_DIV_5 - * @arg @ref LL_RCC_PLLM_DIV_6 - * @arg @ref LL_RCC_PLLM_DIV_7 - * @arg @ref LL_RCC_PLLM_DIV_8 - * @arg @ref LL_RCC_PLLM_DIV_9 - * @arg @ref LL_RCC_PLLM_DIV_10 - * @arg @ref LL_RCC_PLLM_DIV_11 - * @arg @ref LL_RCC_PLLM_DIV_12 - * @arg @ref LL_RCC_PLLM_DIV_13 - * @arg @ref LL_RCC_PLLM_DIV_14 - * @arg @ref LL_RCC_PLLM_DIV_15 - * @arg @ref LL_RCC_PLLM_DIV_16 - * @arg @ref LL_RCC_PLLM_DIV_17 - * @arg @ref LL_RCC_PLLM_DIV_18 - * @arg @ref LL_RCC_PLLM_DIV_19 - * @arg @ref LL_RCC_PLLM_DIV_20 - * @arg @ref LL_RCC_PLLM_DIV_21 - * @arg @ref LL_RCC_PLLM_DIV_22 - * @arg @ref LL_RCC_PLLM_DIV_23 - * @arg @ref LL_RCC_PLLM_DIV_24 - * @arg @ref LL_RCC_PLLM_DIV_25 - * @arg @ref LL_RCC_PLLM_DIV_26 - * @arg @ref LL_RCC_PLLM_DIV_27 - * @arg @ref LL_RCC_PLLM_DIV_28 - * @arg @ref LL_RCC_PLLM_DIV_29 - * @arg @ref LL_RCC_PLLM_DIV_30 - * @arg @ref LL_RCC_PLLM_DIV_31 - * @arg @ref LL_RCC_PLLM_DIV_32 - * @arg @ref LL_RCC_PLLM_DIV_33 - * @arg @ref LL_RCC_PLLM_DIV_34 - * @arg @ref LL_RCC_PLLM_DIV_35 - * @arg @ref LL_RCC_PLLM_DIV_36 - * @arg @ref LL_RCC_PLLM_DIV_37 - * @arg @ref LL_RCC_PLLM_DIV_38 - * @arg @ref LL_RCC_PLLM_DIV_39 - * @arg @ref LL_RCC_PLLM_DIV_40 - * @arg @ref LL_RCC_PLLM_DIV_41 - * @arg @ref LL_RCC_PLLM_DIV_42 - * @arg @ref LL_RCC_PLLM_DIV_43 - * @arg @ref LL_RCC_PLLM_DIV_44 - * @arg @ref LL_RCC_PLLM_DIV_45 - * @arg @ref LL_RCC_PLLM_DIV_46 - * @arg @ref LL_RCC_PLLM_DIV_47 - * @arg @ref LL_RCC_PLLM_DIV_48 - * @arg @ref LL_RCC_PLLM_DIV_49 - * @arg @ref LL_RCC_PLLM_DIV_50 - * @arg @ref LL_RCC_PLLM_DIV_51 - * @arg @ref LL_RCC_PLLM_DIV_52 - * @arg @ref LL_RCC_PLLM_DIV_53 - * @arg @ref LL_RCC_PLLM_DIV_54 - * @arg @ref LL_RCC_PLLM_DIV_55 - * @arg @ref LL_RCC_PLLM_DIV_56 - * @arg @ref LL_RCC_PLLM_DIV_57 - * @arg @ref LL_RCC_PLLM_DIV_58 - * @arg @ref LL_RCC_PLLM_DIV_59 - * @arg @ref LL_RCC_PLLM_DIV_60 - * @arg @ref LL_RCC_PLLM_DIV_61 - * @arg @ref LL_RCC_PLLM_DIV_62 - * @arg @ref LL_RCC_PLLM_DIV_63 - * @param PLLN Between 50 and 432 - * @param PLLR This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLR_DIV_2 - * @arg @ref LL_RCC_PLLR_DIV_3 - * @arg @ref LL_RCC_PLLR_DIV_4 - * @arg @ref LL_RCC_PLLR_DIV_5 - * @arg @ref LL_RCC_PLLR_DIV_6 - * @arg @ref LL_RCC_PLLR_DIV_7 - * @param PLLDIVR This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLDIVR_DIV_1 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_2 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_3 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_4 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_5 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_6 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_7 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_8 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_9 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_10 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_11 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_12 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_13 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_14 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_15 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_16 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_17 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_18 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_19 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_20 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_21 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_22 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_23 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_24 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_25 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_26 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_27 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_28 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_29 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_30 (*) - * @arg @ref LL_RCC_PLLDIVR_DIV_31 (*) - * - * (*) value not defined in all devices. - * @retval None - */ -#if defined(RCC_DCKCFGR_PLLDIVR) -__STATIC_INLINE void LL_RCC_PLL_ConfigDomain_SAI(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLR, uint32_t PLLDIVR) -#else -__STATIC_INLINE void LL_RCC_PLL_ConfigDomain_SAI(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLR) -#endif /* RCC_DCKCFGR_PLLDIVR */ -{ - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC | RCC_PLLCFGR_PLLM | RCC_PLLCFGR_PLLN | RCC_PLLCFGR_PLLR, - Source | PLLM | PLLN << RCC_PLLCFGR_PLLN_Pos | PLLR); -#if defined(RCC_DCKCFGR_PLLDIVR) - MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_PLLDIVR, PLLDIVR); -#endif /* RCC_DCKCFGR_PLLDIVR */ -} -#endif /* SAI1 */ -#endif /* RCC_PLLCFGR_PLLR */ - -/** - * @brief Configure PLL clock source - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLL_SetMainSource - * @param PLLSource This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLL_SetMainSource(uint32_t PLLSource) -{ - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC, PLLSource); -} - -/** - * @brief Get the oscillator used as PLL clock source. - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLL_GetMainSource - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - */ -__STATIC_INLINE uint32_t LL_RCC_PLL_GetMainSource(void) -{ - return (uint32_t)(READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC)); -} - -/** - * @brief Get Main PLL multiplication factor for VCO - * @rmtoll PLLCFGR PLLN LL_RCC_PLL_GetN - * @retval Between 50/192(*) and 432 - * - * (*) value not defined in all devices. - */ -__STATIC_INLINE uint32_t LL_RCC_PLL_GetN(void) -{ - return (uint32_t)(READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLN) >> RCC_PLLCFGR_PLLN_Pos); -} - -/** - * @brief Get Main PLL division factor for PLLP - * @rmtoll PLLCFGR PLLP LL_RCC_PLL_GetP - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLP_DIV_2 - * @arg @ref LL_RCC_PLLP_DIV_4 - * @arg @ref LL_RCC_PLLP_DIV_6 - * @arg @ref LL_RCC_PLLP_DIV_8 - */ -__STATIC_INLINE uint32_t LL_RCC_PLL_GetP(void) -{ - return (uint32_t)(READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLP)); -} - -/** - * @brief Get Main PLL division factor for PLLQ - * @note used for PLL48MCLK selected for USB, RNG, SDIO (48 MHz clock) - * @rmtoll PLLCFGR PLLQ LL_RCC_PLL_GetQ - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLQ_DIV_2 - * @arg @ref LL_RCC_PLLQ_DIV_3 - * @arg @ref LL_RCC_PLLQ_DIV_4 - * @arg @ref LL_RCC_PLLQ_DIV_5 - * @arg @ref LL_RCC_PLLQ_DIV_6 - * @arg @ref LL_RCC_PLLQ_DIV_7 - * @arg @ref LL_RCC_PLLQ_DIV_8 - * @arg @ref LL_RCC_PLLQ_DIV_9 - * @arg @ref LL_RCC_PLLQ_DIV_10 - * @arg @ref LL_RCC_PLLQ_DIV_11 - * @arg @ref LL_RCC_PLLQ_DIV_12 - * @arg @ref LL_RCC_PLLQ_DIV_13 - * @arg @ref LL_RCC_PLLQ_DIV_14 - * @arg @ref LL_RCC_PLLQ_DIV_15 - */ -__STATIC_INLINE uint32_t LL_RCC_PLL_GetQ(void) -{ - return (uint32_t)(READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLQ)); -} - -#if defined(RCC_PLLCFGR_PLLR) -/** - * @brief Get Main PLL division factor for PLLR - * @note used for PLLCLK (system clock) - * @rmtoll PLLCFGR PLLR LL_RCC_PLL_GetR - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLR_DIV_2 - * @arg @ref LL_RCC_PLLR_DIV_3 - * @arg @ref LL_RCC_PLLR_DIV_4 - * @arg @ref LL_RCC_PLLR_DIV_5 - * @arg @ref LL_RCC_PLLR_DIV_6 - * @arg @ref LL_RCC_PLLR_DIV_7 - */ -__STATIC_INLINE uint32_t LL_RCC_PLL_GetR(void) -{ - return (uint32_t)(READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLR)); -} -#endif /* RCC_PLLCFGR_PLLR */ - -#if defined(RCC_DCKCFGR_PLLDIVR) -/** - * @brief Get Main PLL division factor for PLLDIVR - * @note used for PLLSAICLK (SAI1 and SAI2 clock) - * @rmtoll DCKCFGR PLLDIVR LL_RCC_PLL_GetDIVR - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLDIVR_DIV_1 - * @arg @ref LL_RCC_PLLDIVR_DIV_2 - * @arg @ref LL_RCC_PLLDIVR_DIV_3 - * @arg @ref LL_RCC_PLLDIVR_DIV_4 - * @arg @ref LL_RCC_PLLDIVR_DIV_5 - * @arg @ref LL_RCC_PLLDIVR_DIV_6 - * @arg @ref LL_RCC_PLLDIVR_DIV_7 - * @arg @ref LL_RCC_PLLDIVR_DIV_8 - * @arg @ref LL_RCC_PLLDIVR_DIV_9 - * @arg @ref LL_RCC_PLLDIVR_DIV_10 - * @arg @ref LL_RCC_PLLDIVR_DIV_11 - * @arg @ref LL_RCC_PLLDIVR_DIV_12 - * @arg @ref LL_RCC_PLLDIVR_DIV_13 - * @arg @ref LL_RCC_PLLDIVR_DIV_14 - * @arg @ref LL_RCC_PLLDIVR_DIV_15 - * @arg @ref LL_RCC_PLLDIVR_DIV_16 - * @arg @ref LL_RCC_PLLDIVR_DIV_17 - * @arg @ref LL_RCC_PLLDIVR_DIV_18 - * @arg @ref LL_RCC_PLLDIVR_DIV_19 - * @arg @ref LL_RCC_PLLDIVR_DIV_20 - * @arg @ref LL_RCC_PLLDIVR_DIV_21 - * @arg @ref LL_RCC_PLLDIVR_DIV_22 - * @arg @ref LL_RCC_PLLDIVR_DIV_23 - * @arg @ref LL_RCC_PLLDIVR_DIV_24 - * @arg @ref LL_RCC_PLLDIVR_DIV_25 - * @arg @ref LL_RCC_PLLDIVR_DIV_26 - * @arg @ref LL_RCC_PLLDIVR_DIV_27 - * @arg @ref LL_RCC_PLLDIVR_DIV_28 - * @arg @ref LL_RCC_PLLDIVR_DIV_29 - * @arg @ref LL_RCC_PLLDIVR_DIV_30 - * @arg @ref LL_RCC_PLLDIVR_DIV_31 - */ -__STATIC_INLINE uint32_t LL_RCC_PLL_GetDIVR(void) -{ - return (uint32_t)(READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_PLLDIVR)); -} -#endif /* RCC_DCKCFGR_PLLDIVR */ - -/** - * @brief Get Division factor for the main PLL and other PLL - * @rmtoll PLLCFGR PLLM LL_RCC_PLL_GetDivider - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLM_DIV_2 - * @arg @ref LL_RCC_PLLM_DIV_3 - * @arg @ref LL_RCC_PLLM_DIV_4 - * @arg @ref LL_RCC_PLLM_DIV_5 - * @arg @ref LL_RCC_PLLM_DIV_6 - * @arg @ref LL_RCC_PLLM_DIV_7 - * @arg @ref LL_RCC_PLLM_DIV_8 - * @arg @ref LL_RCC_PLLM_DIV_9 - * @arg @ref LL_RCC_PLLM_DIV_10 - * @arg @ref LL_RCC_PLLM_DIV_11 - * @arg @ref LL_RCC_PLLM_DIV_12 - * @arg @ref LL_RCC_PLLM_DIV_13 - * @arg @ref LL_RCC_PLLM_DIV_14 - * @arg @ref LL_RCC_PLLM_DIV_15 - * @arg @ref LL_RCC_PLLM_DIV_16 - * @arg @ref LL_RCC_PLLM_DIV_17 - * @arg @ref LL_RCC_PLLM_DIV_18 - * @arg @ref LL_RCC_PLLM_DIV_19 - * @arg @ref LL_RCC_PLLM_DIV_20 - * @arg @ref LL_RCC_PLLM_DIV_21 - * @arg @ref LL_RCC_PLLM_DIV_22 - * @arg @ref LL_RCC_PLLM_DIV_23 - * @arg @ref LL_RCC_PLLM_DIV_24 - * @arg @ref LL_RCC_PLLM_DIV_25 - * @arg @ref LL_RCC_PLLM_DIV_26 - * @arg @ref LL_RCC_PLLM_DIV_27 - * @arg @ref LL_RCC_PLLM_DIV_28 - * @arg @ref LL_RCC_PLLM_DIV_29 - * @arg @ref LL_RCC_PLLM_DIV_30 - * @arg @ref LL_RCC_PLLM_DIV_31 - * @arg @ref LL_RCC_PLLM_DIV_32 - * @arg @ref LL_RCC_PLLM_DIV_33 - * @arg @ref LL_RCC_PLLM_DIV_34 - * @arg @ref LL_RCC_PLLM_DIV_35 - * @arg @ref LL_RCC_PLLM_DIV_36 - * @arg @ref LL_RCC_PLLM_DIV_37 - * @arg @ref LL_RCC_PLLM_DIV_38 - * @arg @ref LL_RCC_PLLM_DIV_39 - * @arg @ref LL_RCC_PLLM_DIV_40 - * @arg @ref LL_RCC_PLLM_DIV_41 - * @arg @ref LL_RCC_PLLM_DIV_42 - * @arg @ref LL_RCC_PLLM_DIV_43 - * @arg @ref LL_RCC_PLLM_DIV_44 - * @arg @ref LL_RCC_PLLM_DIV_45 - * @arg @ref LL_RCC_PLLM_DIV_46 - * @arg @ref LL_RCC_PLLM_DIV_47 - * @arg @ref LL_RCC_PLLM_DIV_48 - * @arg @ref LL_RCC_PLLM_DIV_49 - * @arg @ref LL_RCC_PLLM_DIV_50 - * @arg @ref LL_RCC_PLLM_DIV_51 - * @arg @ref LL_RCC_PLLM_DIV_52 - * @arg @ref LL_RCC_PLLM_DIV_53 - * @arg @ref LL_RCC_PLLM_DIV_54 - * @arg @ref LL_RCC_PLLM_DIV_55 - * @arg @ref LL_RCC_PLLM_DIV_56 - * @arg @ref LL_RCC_PLLM_DIV_57 - * @arg @ref LL_RCC_PLLM_DIV_58 - * @arg @ref LL_RCC_PLLM_DIV_59 - * @arg @ref LL_RCC_PLLM_DIV_60 - * @arg @ref LL_RCC_PLLM_DIV_61 - * @arg @ref LL_RCC_PLLM_DIV_62 - * @arg @ref LL_RCC_PLLM_DIV_63 - */ -__STATIC_INLINE uint32_t LL_RCC_PLL_GetDivider(void) -{ - return (uint32_t)(READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLM)); -} - -/** - * @brief Configure Spread Spectrum used for PLL - * @note These bits must be written before enabling PLL - * @rmtoll SSCGR MODPER LL_RCC_PLL_ConfigSpreadSpectrum\n - * SSCGR INCSTEP LL_RCC_PLL_ConfigSpreadSpectrum\n - * SSCGR SPREADSEL LL_RCC_PLL_ConfigSpreadSpectrum - * @param Mod Between Min_Data=0 and Max_Data=8191 - * @param Inc Between Min_Data=0 and Max_Data=32767 - * @param Sel This parameter can be one of the following values: - * @arg @ref LL_RCC_SPREAD_SELECT_CENTER - * @arg @ref LL_RCC_SPREAD_SELECT_DOWN - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLL_ConfigSpreadSpectrum(uint32_t Mod, uint32_t Inc, uint32_t Sel) -{ - MODIFY_REG(RCC->SSCGR, RCC_SSCGR_MODPER | RCC_SSCGR_INCSTEP | RCC_SSCGR_SPREADSEL, Mod | (Inc << RCC_SSCGR_INCSTEP_Pos) | Sel); -} - -/** - * @brief Get Spread Spectrum Modulation Period for PLL - * @rmtoll SSCGR MODPER LL_RCC_PLL_GetPeriodModulation - * @retval Between Min_Data=0 and Max_Data=8191 - */ -__STATIC_INLINE uint32_t LL_RCC_PLL_GetPeriodModulation(void) -{ - return (uint32_t)(READ_BIT(RCC->SSCGR, RCC_SSCGR_MODPER)); -} - -/** - * @brief Get Spread Spectrum Incrementation Step for PLL - * @note Must be written before enabling PLL - * @rmtoll SSCGR INCSTEP LL_RCC_PLL_GetStepIncrementation - * @retval Between Min_Data=0 and Max_Data=32767 - */ -__STATIC_INLINE uint32_t LL_RCC_PLL_GetStepIncrementation(void) -{ - return (uint32_t)(READ_BIT(RCC->SSCGR, RCC_SSCGR_INCSTEP) >> RCC_SSCGR_INCSTEP_Pos); -} - -/** - * @brief Get Spread Spectrum Selection for PLL - * @note Must be written before enabling PLL - * @rmtoll SSCGR SPREADSEL LL_RCC_PLL_GetSpreadSelection - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_SPREAD_SELECT_CENTER - * @arg @ref LL_RCC_SPREAD_SELECT_DOWN - */ -__STATIC_INLINE uint32_t LL_RCC_PLL_GetSpreadSelection(void) -{ - return (uint32_t)(READ_BIT(RCC->SSCGR, RCC_SSCGR_SPREADSEL)); -} - -/** - * @brief Enable Spread Spectrum for PLL. - * @rmtoll SSCGR SSCGEN LL_RCC_PLL_SpreadSpectrum_Enable - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLL_SpreadSpectrum_Enable(void) -{ - SET_BIT(RCC->SSCGR, RCC_SSCGR_SSCGEN); -} - -/** - * @brief Disable Spread Spectrum for PLL. - * @rmtoll SSCGR SSCGEN LL_RCC_PLL_SpreadSpectrum_Disable - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLL_SpreadSpectrum_Disable(void) -{ - CLEAR_BIT(RCC->SSCGR, RCC_SSCGR_SSCGEN); -} - -/** - * @} - */ - -#if defined(RCC_PLLI2S_SUPPORT) -/** @defgroup RCC_LL_EF_PLLI2S PLLI2S - * @{ - */ - -/** - * @brief Enable PLLI2S - * @rmtoll CR PLLI2SON LL_RCC_PLLI2S_Enable - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLLI2S_Enable(void) -{ - SET_BIT(RCC->CR, RCC_CR_PLLI2SON); -} - -/** - * @brief Disable PLLI2S - * @rmtoll CR PLLI2SON LL_RCC_PLLI2S_Disable - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLLI2S_Disable(void) -{ - CLEAR_BIT(RCC->CR, RCC_CR_PLLI2SON); -} - -/** - * @brief Check if PLLI2S Ready - * @rmtoll CR PLLI2SRDY LL_RCC_PLLI2S_IsReady - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_PLLI2S_IsReady(void) -{ - return (READ_BIT(RCC->CR, RCC_CR_PLLI2SRDY) == (RCC_CR_PLLI2SRDY)); -} - -#if (defined(RCC_DCKCFGR_PLLI2SDIVQ) || defined(RCC_DCKCFGR_PLLI2SDIVR)) -/** - * @brief Configure PLLI2S used for SAI domain clock - * @note PLL Source and PLLM Divider can be written only when PLL, - * PLLI2S and PLLSAI(*) are disabled - * @note PLLN/PLLQ/PLLR can be written only when PLLI2S is disabled - * @note This can be selected for SAI - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLLI2S_ConfigDomain_SAI\n - * PLLI2SCFGR PLLI2SSRC LL_RCC_PLLI2S_ConfigDomain_SAI\n - * PLLCFGR PLLM LL_RCC_PLLI2S_ConfigDomain_SAI\n - * PLLI2SCFGR PLLI2SM LL_RCC_PLLI2S_ConfigDomain_SAI\n - * PLLI2SCFGR PLLI2SN LL_RCC_PLLI2S_ConfigDomain_SAI\n - * PLLI2SCFGR PLLI2SQ LL_RCC_PLLI2S_ConfigDomain_SAI\n - * PLLI2SCFGR PLLI2SR LL_RCC_PLLI2S_ConfigDomain_SAI\n - * DCKCFGR PLLI2SDIVQ LL_RCC_PLLI2S_ConfigDomain_SAI\n - * DCKCFGR PLLI2SDIVR LL_RCC_PLLI2S_ConfigDomain_SAI - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @arg @ref LL_RCC_PLLI2SSOURCE_PIN (*) - * - * (*) value not defined in all devices. - * @param PLLM This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SM_DIV_2 - * @arg @ref LL_RCC_PLLI2SM_DIV_3 - * @arg @ref LL_RCC_PLLI2SM_DIV_4 - * @arg @ref LL_RCC_PLLI2SM_DIV_5 - * @arg @ref LL_RCC_PLLI2SM_DIV_6 - * @arg @ref LL_RCC_PLLI2SM_DIV_7 - * @arg @ref LL_RCC_PLLI2SM_DIV_8 - * @arg @ref LL_RCC_PLLI2SM_DIV_9 - * @arg @ref LL_RCC_PLLI2SM_DIV_10 - * @arg @ref LL_RCC_PLLI2SM_DIV_11 - * @arg @ref LL_RCC_PLLI2SM_DIV_12 - * @arg @ref LL_RCC_PLLI2SM_DIV_13 - * @arg @ref LL_RCC_PLLI2SM_DIV_14 - * @arg @ref LL_RCC_PLLI2SM_DIV_15 - * @arg @ref LL_RCC_PLLI2SM_DIV_16 - * @arg @ref LL_RCC_PLLI2SM_DIV_17 - * @arg @ref LL_RCC_PLLI2SM_DIV_18 - * @arg @ref LL_RCC_PLLI2SM_DIV_19 - * @arg @ref LL_RCC_PLLI2SM_DIV_20 - * @arg @ref LL_RCC_PLLI2SM_DIV_21 - * @arg @ref LL_RCC_PLLI2SM_DIV_22 - * @arg @ref LL_RCC_PLLI2SM_DIV_23 - * @arg @ref LL_RCC_PLLI2SM_DIV_24 - * @arg @ref LL_RCC_PLLI2SM_DIV_25 - * @arg @ref LL_RCC_PLLI2SM_DIV_26 - * @arg @ref LL_RCC_PLLI2SM_DIV_27 - * @arg @ref LL_RCC_PLLI2SM_DIV_28 - * @arg @ref LL_RCC_PLLI2SM_DIV_29 - * @arg @ref LL_RCC_PLLI2SM_DIV_30 - * @arg @ref LL_RCC_PLLI2SM_DIV_31 - * @arg @ref LL_RCC_PLLI2SM_DIV_32 - * @arg @ref LL_RCC_PLLI2SM_DIV_33 - * @arg @ref LL_RCC_PLLI2SM_DIV_34 - * @arg @ref LL_RCC_PLLI2SM_DIV_35 - * @arg @ref LL_RCC_PLLI2SM_DIV_36 - * @arg @ref LL_RCC_PLLI2SM_DIV_37 - * @arg @ref LL_RCC_PLLI2SM_DIV_38 - * @arg @ref LL_RCC_PLLI2SM_DIV_39 - * @arg @ref LL_RCC_PLLI2SM_DIV_40 - * @arg @ref LL_RCC_PLLI2SM_DIV_41 - * @arg @ref LL_RCC_PLLI2SM_DIV_42 - * @arg @ref LL_RCC_PLLI2SM_DIV_43 - * @arg @ref LL_RCC_PLLI2SM_DIV_44 - * @arg @ref LL_RCC_PLLI2SM_DIV_45 - * @arg @ref LL_RCC_PLLI2SM_DIV_46 - * @arg @ref LL_RCC_PLLI2SM_DIV_47 - * @arg @ref LL_RCC_PLLI2SM_DIV_48 - * @arg @ref LL_RCC_PLLI2SM_DIV_49 - * @arg @ref LL_RCC_PLLI2SM_DIV_50 - * @arg @ref LL_RCC_PLLI2SM_DIV_51 - * @arg @ref LL_RCC_PLLI2SM_DIV_52 - * @arg @ref LL_RCC_PLLI2SM_DIV_53 - * @arg @ref LL_RCC_PLLI2SM_DIV_54 - * @arg @ref LL_RCC_PLLI2SM_DIV_55 - * @arg @ref LL_RCC_PLLI2SM_DIV_56 - * @arg @ref LL_RCC_PLLI2SM_DIV_57 - * @arg @ref LL_RCC_PLLI2SM_DIV_58 - * @arg @ref LL_RCC_PLLI2SM_DIV_59 - * @arg @ref LL_RCC_PLLI2SM_DIV_60 - * @arg @ref LL_RCC_PLLI2SM_DIV_61 - * @arg @ref LL_RCC_PLLI2SM_DIV_62 - * @arg @ref LL_RCC_PLLI2SM_DIV_63 - * @param PLLN Between 50/192(*) and 432 - * - * (*) value not defined in all devices. - * @param PLLQ_R This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SQ_DIV_2 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_3 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_4 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_5 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_6 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_7 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_8 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_9 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_10 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_11 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_12 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_13 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_14 (*) - * @arg @ref LL_RCC_PLLI2SQ_DIV_15 (*) - * @arg @ref LL_RCC_PLLI2SR_DIV_2 (*) - * @arg @ref LL_RCC_PLLI2SR_DIV_3 (*) - * @arg @ref LL_RCC_PLLI2SR_DIV_4 (*) - * @arg @ref LL_RCC_PLLI2SR_DIV_5 (*) - * @arg @ref LL_RCC_PLLI2SR_DIV_6 (*) - * @arg @ref LL_RCC_PLLI2SR_DIV_7 (*) - * - * (*) value not defined in all devices. - * @param PLLDIVQ_R This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_1 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_2 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_3 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_4 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_5 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_6 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_7 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_8 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_9 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_10 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_11 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_12 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_13 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_14 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_15 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_16 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_17 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_18 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_19 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_20 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_21 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_22 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_23 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_24 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_25 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_26 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_27 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_28 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_29 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_30 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_31 (*) - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_32 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_1 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_2 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_3 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_4 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_5 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_6 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_7 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_8 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_9 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_10 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_11 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_12 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_13 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_14 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_15 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_16 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_17 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_18 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_19 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_20 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_21 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_22 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_23 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_24 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_25 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_26 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_27 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_28 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_29 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_30 (*) - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_31 (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLLI2S_ConfigDomain_SAI(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLQ_R, uint32_t PLLDIVQ_R) -{ - __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&RCC->PLLCFGR) + (Source & 0x80U))); - MODIFY_REG(*pReg, RCC_PLLCFGR_PLLSRC, (Source & (~0x80U))); -#if defined(RCC_PLLI2SCFGR_PLLI2SM) - MODIFY_REG(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SM, PLLM); -#else - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLM, PLLM); -#endif /* RCC_PLLI2SCFGR_PLLI2SM */ - MODIFY_REG(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SN, PLLN << RCC_PLLI2SCFGR_PLLI2SN_Pos); -#if defined(RCC_DCKCFGR_PLLI2SDIVQ) - MODIFY_REG(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SQ, PLLQ_R); - MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_PLLI2SDIVQ, PLLDIVQ_R); -#else - MODIFY_REG(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SR, PLLQ_R); - MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_PLLI2SDIVR, PLLDIVQ_R); -#endif /* RCC_DCKCFGR_PLLI2SDIVQ */ -} -#endif /* RCC_DCKCFGR_PLLI2SDIVQ && RCC_DCKCFGR_PLLI2SDIVR */ - -#if defined(RCC_PLLI2SCFGR_PLLI2SQ) && !defined(RCC_DCKCFGR_PLLI2SDIVQ) -/** - * @brief Configure PLLI2S used for 48Mhz domain clock - * @note PLL Source and PLLM Divider can be written only when PLL, - * PLLI2S and PLLSAI(*) are disabled - * @note PLLN/PLLQ can be written only when PLLI2S is disabled - * @note This can be selected for RNG, USB, SDIO - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLLI2S_ConfigDomain_48M\n - * PLLI2SCFGR PLLI2SSRC LL_RCC_PLLI2S_ConfigDomain_48M\n - * PLLCFGR PLLM LL_RCC_PLLI2S_ConfigDomain_48M\n - * PLLI2SCFGR PLLI2SM LL_RCC_PLLI2S_ConfigDomain_48M\n - * PLLI2SCFGR PLLI2SN LL_RCC_PLLI2S_ConfigDomain_48M\n - * PLLI2SCFGR PLLI2SQ LL_RCC_PLLI2S_ConfigDomain_48M - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @arg @ref LL_RCC_PLLI2SSOURCE_PIN (*) - * - * (*) value not defined in all devices. - * @param PLLM This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SM_DIV_2 - * @arg @ref LL_RCC_PLLI2SM_DIV_3 - * @arg @ref LL_RCC_PLLI2SM_DIV_4 - * @arg @ref LL_RCC_PLLI2SM_DIV_5 - * @arg @ref LL_RCC_PLLI2SM_DIV_6 - * @arg @ref LL_RCC_PLLI2SM_DIV_7 - * @arg @ref LL_RCC_PLLI2SM_DIV_8 - * @arg @ref LL_RCC_PLLI2SM_DIV_9 - * @arg @ref LL_RCC_PLLI2SM_DIV_10 - * @arg @ref LL_RCC_PLLI2SM_DIV_11 - * @arg @ref LL_RCC_PLLI2SM_DIV_12 - * @arg @ref LL_RCC_PLLI2SM_DIV_13 - * @arg @ref LL_RCC_PLLI2SM_DIV_14 - * @arg @ref LL_RCC_PLLI2SM_DIV_15 - * @arg @ref LL_RCC_PLLI2SM_DIV_16 - * @arg @ref LL_RCC_PLLI2SM_DIV_17 - * @arg @ref LL_RCC_PLLI2SM_DIV_18 - * @arg @ref LL_RCC_PLLI2SM_DIV_19 - * @arg @ref LL_RCC_PLLI2SM_DIV_20 - * @arg @ref LL_RCC_PLLI2SM_DIV_21 - * @arg @ref LL_RCC_PLLI2SM_DIV_22 - * @arg @ref LL_RCC_PLLI2SM_DIV_23 - * @arg @ref LL_RCC_PLLI2SM_DIV_24 - * @arg @ref LL_RCC_PLLI2SM_DIV_25 - * @arg @ref LL_RCC_PLLI2SM_DIV_26 - * @arg @ref LL_RCC_PLLI2SM_DIV_27 - * @arg @ref LL_RCC_PLLI2SM_DIV_28 - * @arg @ref LL_RCC_PLLI2SM_DIV_29 - * @arg @ref LL_RCC_PLLI2SM_DIV_30 - * @arg @ref LL_RCC_PLLI2SM_DIV_31 - * @arg @ref LL_RCC_PLLI2SM_DIV_32 - * @arg @ref LL_RCC_PLLI2SM_DIV_33 - * @arg @ref LL_RCC_PLLI2SM_DIV_34 - * @arg @ref LL_RCC_PLLI2SM_DIV_35 - * @arg @ref LL_RCC_PLLI2SM_DIV_36 - * @arg @ref LL_RCC_PLLI2SM_DIV_37 - * @arg @ref LL_RCC_PLLI2SM_DIV_38 - * @arg @ref LL_RCC_PLLI2SM_DIV_39 - * @arg @ref LL_RCC_PLLI2SM_DIV_40 - * @arg @ref LL_RCC_PLLI2SM_DIV_41 - * @arg @ref LL_RCC_PLLI2SM_DIV_42 - * @arg @ref LL_RCC_PLLI2SM_DIV_43 - * @arg @ref LL_RCC_PLLI2SM_DIV_44 - * @arg @ref LL_RCC_PLLI2SM_DIV_45 - * @arg @ref LL_RCC_PLLI2SM_DIV_46 - * @arg @ref LL_RCC_PLLI2SM_DIV_47 - * @arg @ref LL_RCC_PLLI2SM_DIV_48 - * @arg @ref LL_RCC_PLLI2SM_DIV_49 - * @arg @ref LL_RCC_PLLI2SM_DIV_50 - * @arg @ref LL_RCC_PLLI2SM_DIV_51 - * @arg @ref LL_RCC_PLLI2SM_DIV_52 - * @arg @ref LL_RCC_PLLI2SM_DIV_53 - * @arg @ref LL_RCC_PLLI2SM_DIV_54 - * @arg @ref LL_RCC_PLLI2SM_DIV_55 - * @arg @ref LL_RCC_PLLI2SM_DIV_56 - * @arg @ref LL_RCC_PLLI2SM_DIV_57 - * @arg @ref LL_RCC_PLLI2SM_DIV_58 - * @arg @ref LL_RCC_PLLI2SM_DIV_59 - * @arg @ref LL_RCC_PLLI2SM_DIV_60 - * @arg @ref LL_RCC_PLLI2SM_DIV_61 - * @arg @ref LL_RCC_PLLI2SM_DIV_62 - * @arg @ref LL_RCC_PLLI2SM_DIV_63 - * @param PLLN Between 50 and 432 - * @param PLLQ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SQ_DIV_2 - * @arg @ref LL_RCC_PLLI2SQ_DIV_3 - * @arg @ref LL_RCC_PLLI2SQ_DIV_4 - * @arg @ref LL_RCC_PLLI2SQ_DIV_5 - * @arg @ref LL_RCC_PLLI2SQ_DIV_6 - * @arg @ref LL_RCC_PLLI2SQ_DIV_7 - * @arg @ref LL_RCC_PLLI2SQ_DIV_8 - * @arg @ref LL_RCC_PLLI2SQ_DIV_9 - * @arg @ref LL_RCC_PLLI2SQ_DIV_10 - * @arg @ref LL_RCC_PLLI2SQ_DIV_11 - * @arg @ref LL_RCC_PLLI2SQ_DIV_12 - * @arg @ref LL_RCC_PLLI2SQ_DIV_13 - * @arg @ref LL_RCC_PLLI2SQ_DIV_14 - * @arg @ref LL_RCC_PLLI2SQ_DIV_15 - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLLI2S_ConfigDomain_48M(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLQ) -{ - __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&RCC->PLLCFGR) + (Source & 0x80U))); - MODIFY_REG(*pReg, RCC_PLLCFGR_PLLSRC, (Source & (~0x80U))); -#if defined(RCC_PLLI2SCFGR_PLLI2SM) - MODIFY_REG(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SM, PLLM); -#else - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLM, PLLM); -#endif /* RCC_PLLI2SCFGR_PLLI2SM */ - MODIFY_REG(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SN | RCC_PLLI2SCFGR_PLLI2SQ, PLLN << RCC_PLLI2SCFGR_PLLI2SN_Pos | PLLQ); -} -#endif /* RCC_PLLI2SCFGR_PLLI2SQ && !RCC_DCKCFGR_PLLI2SDIVQ */ - -#if defined(SPDIFRX) -/** - * @brief Configure PLLI2S used for SPDIFRX domain clock - * @note PLL Source and PLLM Divider can be written only when PLL, - * PLLI2S and PLLSAI(*) are disabled - * @note PLLN/PLLP can be written only when PLLI2S is disabled - * @note This can be selected for SPDIFRX - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLLI2S_ConfigDomain_SPDIFRX\n - * PLLCFGR PLLM LL_RCC_PLLI2S_ConfigDomain_SPDIFRX\n - * PLLI2SCFGR PLLI2SM LL_RCC_PLLI2S_ConfigDomain_SPDIFRX\n - * PLLI2SCFGR PLLI2SN LL_RCC_PLLI2S_ConfigDomain_SPDIFRX\n - * PLLI2SCFGR PLLI2SP LL_RCC_PLLI2S_ConfigDomain_SPDIFRX - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @param PLLM This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SM_DIV_2 - * @arg @ref LL_RCC_PLLI2SM_DIV_3 - * @arg @ref LL_RCC_PLLI2SM_DIV_4 - * @arg @ref LL_RCC_PLLI2SM_DIV_5 - * @arg @ref LL_RCC_PLLI2SM_DIV_6 - * @arg @ref LL_RCC_PLLI2SM_DIV_7 - * @arg @ref LL_RCC_PLLI2SM_DIV_8 - * @arg @ref LL_RCC_PLLI2SM_DIV_9 - * @arg @ref LL_RCC_PLLI2SM_DIV_10 - * @arg @ref LL_RCC_PLLI2SM_DIV_11 - * @arg @ref LL_RCC_PLLI2SM_DIV_12 - * @arg @ref LL_RCC_PLLI2SM_DIV_13 - * @arg @ref LL_RCC_PLLI2SM_DIV_14 - * @arg @ref LL_RCC_PLLI2SM_DIV_15 - * @arg @ref LL_RCC_PLLI2SM_DIV_16 - * @arg @ref LL_RCC_PLLI2SM_DIV_17 - * @arg @ref LL_RCC_PLLI2SM_DIV_18 - * @arg @ref LL_RCC_PLLI2SM_DIV_19 - * @arg @ref LL_RCC_PLLI2SM_DIV_20 - * @arg @ref LL_RCC_PLLI2SM_DIV_21 - * @arg @ref LL_RCC_PLLI2SM_DIV_22 - * @arg @ref LL_RCC_PLLI2SM_DIV_23 - * @arg @ref LL_RCC_PLLI2SM_DIV_24 - * @arg @ref LL_RCC_PLLI2SM_DIV_25 - * @arg @ref LL_RCC_PLLI2SM_DIV_26 - * @arg @ref LL_RCC_PLLI2SM_DIV_27 - * @arg @ref LL_RCC_PLLI2SM_DIV_28 - * @arg @ref LL_RCC_PLLI2SM_DIV_29 - * @arg @ref LL_RCC_PLLI2SM_DIV_30 - * @arg @ref LL_RCC_PLLI2SM_DIV_31 - * @arg @ref LL_RCC_PLLI2SM_DIV_32 - * @arg @ref LL_RCC_PLLI2SM_DIV_33 - * @arg @ref LL_RCC_PLLI2SM_DIV_34 - * @arg @ref LL_RCC_PLLI2SM_DIV_35 - * @arg @ref LL_RCC_PLLI2SM_DIV_36 - * @arg @ref LL_RCC_PLLI2SM_DIV_37 - * @arg @ref LL_RCC_PLLI2SM_DIV_38 - * @arg @ref LL_RCC_PLLI2SM_DIV_39 - * @arg @ref LL_RCC_PLLI2SM_DIV_40 - * @arg @ref LL_RCC_PLLI2SM_DIV_41 - * @arg @ref LL_RCC_PLLI2SM_DIV_42 - * @arg @ref LL_RCC_PLLI2SM_DIV_43 - * @arg @ref LL_RCC_PLLI2SM_DIV_44 - * @arg @ref LL_RCC_PLLI2SM_DIV_45 - * @arg @ref LL_RCC_PLLI2SM_DIV_46 - * @arg @ref LL_RCC_PLLI2SM_DIV_47 - * @arg @ref LL_RCC_PLLI2SM_DIV_48 - * @arg @ref LL_RCC_PLLI2SM_DIV_49 - * @arg @ref LL_RCC_PLLI2SM_DIV_50 - * @arg @ref LL_RCC_PLLI2SM_DIV_51 - * @arg @ref LL_RCC_PLLI2SM_DIV_52 - * @arg @ref LL_RCC_PLLI2SM_DIV_53 - * @arg @ref LL_RCC_PLLI2SM_DIV_54 - * @arg @ref LL_RCC_PLLI2SM_DIV_55 - * @arg @ref LL_RCC_PLLI2SM_DIV_56 - * @arg @ref LL_RCC_PLLI2SM_DIV_57 - * @arg @ref LL_RCC_PLLI2SM_DIV_58 - * @arg @ref LL_RCC_PLLI2SM_DIV_59 - * @arg @ref LL_RCC_PLLI2SM_DIV_60 - * @arg @ref LL_RCC_PLLI2SM_DIV_61 - * @arg @ref LL_RCC_PLLI2SM_DIV_62 - * @arg @ref LL_RCC_PLLI2SM_DIV_63 - * @param PLLN Between 50 and 432 - * @param PLLP This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SP_DIV_2 - * @arg @ref LL_RCC_PLLI2SP_DIV_4 - * @arg @ref LL_RCC_PLLI2SP_DIV_6 - * @arg @ref LL_RCC_PLLI2SP_DIV_8 - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLLI2S_ConfigDomain_SPDIFRX(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLP) -{ - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC, Source); -#if defined(RCC_PLLI2SCFGR_PLLI2SM) - MODIFY_REG(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SM, PLLM); -#else - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLM, PLLM); -#endif /* RCC_PLLI2SCFGR_PLLI2SM */ - MODIFY_REG(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SN | RCC_PLLI2SCFGR_PLLI2SP, PLLN << RCC_PLLI2SCFGR_PLLI2SN_Pos | PLLP); -} -#endif /* SPDIFRX */ - -/** - * @brief Configure PLLI2S used for I2S1 domain clock - * @note PLL Source and PLLM Divider can be written only when PLL, - * PLLI2S and PLLSAI(*) are disabled - * @note PLLN/PLLR can be written only when PLLI2S is disabled - * @note This can be selected for I2S - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLLI2S_ConfigDomain_I2S\n - * PLLCFGR PLLM LL_RCC_PLLI2S_ConfigDomain_I2S\n - * PLLI2SCFGR PLLI2SSRC LL_RCC_PLLI2S_ConfigDomain_I2S\n - * PLLI2SCFGR PLLI2SM LL_RCC_PLLI2S_ConfigDomain_I2S\n - * PLLI2SCFGR PLLI2SN LL_RCC_PLLI2S_ConfigDomain_I2S\n - * PLLI2SCFGR PLLI2SR LL_RCC_PLLI2S_ConfigDomain_I2S - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @arg @ref LL_RCC_PLLI2SSOURCE_PIN (*) - * - * (*) value not defined in all devices. - * @param PLLM This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SM_DIV_2 - * @arg @ref LL_RCC_PLLI2SM_DIV_3 - * @arg @ref LL_RCC_PLLI2SM_DIV_4 - * @arg @ref LL_RCC_PLLI2SM_DIV_5 - * @arg @ref LL_RCC_PLLI2SM_DIV_6 - * @arg @ref LL_RCC_PLLI2SM_DIV_7 - * @arg @ref LL_RCC_PLLI2SM_DIV_8 - * @arg @ref LL_RCC_PLLI2SM_DIV_9 - * @arg @ref LL_RCC_PLLI2SM_DIV_10 - * @arg @ref LL_RCC_PLLI2SM_DIV_11 - * @arg @ref LL_RCC_PLLI2SM_DIV_12 - * @arg @ref LL_RCC_PLLI2SM_DIV_13 - * @arg @ref LL_RCC_PLLI2SM_DIV_14 - * @arg @ref LL_RCC_PLLI2SM_DIV_15 - * @arg @ref LL_RCC_PLLI2SM_DIV_16 - * @arg @ref LL_RCC_PLLI2SM_DIV_17 - * @arg @ref LL_RCC_PLLI2SM_DIV_18 - * @arg @ref LL_RCC_PLLI2SM_DIV_19 - * @arg @ref LL_RCC_PLLI2SM_DIV_20 - * @arg @ref LL_RCC_PLLI2SM_DIV_21 - * @arg @ref LL_RCC_PLLI2SM_DIV_22 - * @arg @ref LL_RCC_PLLI2SM_DIV_23 - * @arg @ref LL_RCC_PLLI2SM_DIV_24 - * @arg @ref LL_RCC_PLLI2SM_DIV_25 - * @arg @ref LL_RCC_PLLI2SM_DIV_26 - * @arg @ref LL_RCC_PLLI2SM_DIV_27 - * @arg @ref LL_RCC_PLLI2SM_DIV_28 - * @arg @ref LL_RCC_PLLI2SM_DIV_29 - * @arg @ref LL_RCC_PLLI2SM_DIV_30 - * @arg @ref LL_RCC_PLLI2SM_DIV_31 - * @arg @ref LL_RCC_PLLI2SM_DIV_32 - * @arg @ref LL_RCC_PLLI2SM_DIV_33 - * @arg @ref LL_RCC_PLLI2SM_DIV_34 - * @arg @ref LL_RCC_PLLI2SM_DIV_35 - * @arg @ref LL_RCC_PLLI2SM_DIV_36 - * @arg @ref LL_RCC_PLLI2SM_DIV_37 - * @arg @ref LL_RCC_PLLI2SM_DIV_38 - * @arg @ref LL_RCC_PLLI2SM_DIV_39 - * @arg @ref LL_RCC_PLLI2SM_DIV_40 - * @arg @ref LL_RCC_PLLI2SM_DIV_41 - * @arg @ref LL_RCC_PLLI2SM_DIV_42 - * @arg @ref LL_RCC_PLLI2SM_DIV_43 - * @arg @ref LL_RCC_PLLI2SM_DIV_44 - * @arg @ref LL_RCC_PLLI2SM_DIV_45 - * @arg @ref LL_RCC_PLLI2SM_DIV_46 - * @arg @ref LL_RCC_PLLI2SM_DIV_47 - * @arg @ref LL_RCC_PLLI2SM_DIV_48 - * @arg @ref LL_RCC_PLLI2SM_DIV_49 - * @arg @ref LL_RCC_PLLI2SM_DIV_50 - * @arg @ref LL_RCC_PLLI2SM_DIV_51 - * @arg @ref LL_RCC_PLLI2SM_DIV_52 - * @arg @ref LL_RCC_PLLI2SM_DIV_53 - * @arg @ref LL_RCC_PLLI2SM_DIV_54 - * @arg @ref LL_RCC_PLLI2SM_DIV_55 - * @arg @ref LL_RCC_PLLI2SM_DIV_56 - * @arg @ref LL_RCC_PLLI2SM_DIV_57 - * @arg @ref LL_RCC_PLLI2SM_DIV_58 - * @arg @ref LL_RCC_PLLI2SM_DIV_59 - * @arg @ref LL_RCC_PLLI2SM_DIV_60 - * @arg @ref LL_RCC_PLLI2SM_DIV_61 - * @arg @ref LL_RCC_PLLI2SM_DIV_62 - * @arg @ref LL_RCC_PLLI2SM_DIV_63 - * @param PLLN Between 50/192(*) and 432 - * - * (*) value not defined in all devices. - * @param PLLR This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLI2SR_DIV_2 - * @arg @ref LL_RCC_PLLI2SR_DIV_3 - * @arg @ref LL_RCC_PLLI2SR_DIV_4 - * @arg @ref LL_RCC_PLLI2SR_DIV_5 - * @arg @ref LL_RCC_PLLI2SR_DIV_6 - * @arg @ref LL_RCC_PLLI2SR_DIV_7 - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLLI2S_ConfigDomain_I2S(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLR) -{ - __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&RCC->PLLCFGR) + (Source & 0x80U))); - MODIFY_REG(*pReg, RCC_PLLCFGR_PLLSRC, (Source & (~0x80U))); -#if defined(RCC_PLLI2SCFGR_PLLI2SM) - MODIFY_REG(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SM, PLLM); -#else - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLM, PLLM); -#endif /* RCC_PLLI2SCFGR_PLLI2SM */ - MODIFY_REG(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SN | RCC_PLLI2SCFGR_PLLI2SR, PLLN << RCC_PLLI2SCFGR_PLLI2SN_Pos | PLLR); -} - -/** - * @brief Get I2SPLL multiplication factor for VCO - * @rmtoll PLLI2SCFGR PLLI2SN LL_RCC_PLLI2S_GetN - * @retval Between 50/192(*) and 432 - * - * (*) value not defined in all devices. - */ -__STATIC_INLINE uint32_t LL_RCC_PLLI2S_GetN(void) -{ - return (uint32_t)(READ_BIT(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SN) >> RCC_PLLI2SCFGR_PLLI2SN_Pos); -} - -#if defined(RCC_PLLI2SCFGR_PLLI2SQ) -/** - * @brief Get I2SPLL division factor for PLLI2SQ - * @rmtoll PLLI2SCFGR PLLI2SQ LL_RCC_PLLI2S_GetQ - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLI2SQ_DIV_2 - * @arg @ref LL_RCC_PLLI2SQ_DIV_3 - * @arg @ref LL_RCC_PLLI2SQ_DIV_4 - * @arg @ref LL_RCC_PLLI2SQ_DIV_5 - * @arg @ref LL_RCC_PLLI2SQ_DIV_6 - * @arg @ref LL_RCC_PLLI2SQ_DIV_7 - * @arg @ref LL_RCC_PLLI2SQ_DIV_8 - * @arg @ref LL_RCC_PLLI2SQ_DIV_9 - * @arg @ref LL_RCC_PLLI2SQ_DIV_10 - * @arg @ref LL_RCC_PLLI2SQ_DIV_11 - * @arg @ref LL_RCC_PLLI2SQ_DIV_12 - * @arg @ref LL_RCC_PLLI2SQ_DIV_13 - * @arg @ref LL_RCC_PLLI2SQ_DIV_14 - * @arg @ref LL_RCC_PLLI2SQ_DIV_15 - */ -__STATIC_INLINE uint32_t LL_RCC_PLLI2S_GetQ(void) -{ - return (uint32_t)(READ_BIT(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SQ)); -} -#endif /* RCC_PLLI2SCFGR_PLLI2SQ */ - -/** - * @brief Get I2SPLL division factor for PLLI2SR - * @note used for PLLI2SCLK (I2S clock) - * @rmtoll PLLI2SCFGR PLLI2SR LL_RCC_PLLI2S_GetR - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLI2SR_DIV_2 - * @arg @ref LL_RCC_PLLI2SR_DIV_3 - * @arg @ref LL_RCC_PLLI2SR_DIV_4 - * @arg @ref LL_RCC_PLLI2SR_DIV_5 - * @arg @ref LL_RCC_PLLI2SR_DIV_6 - * @arg @ref LL_RCC_PLLI2SR_DIV_7 - */ -__STATIC_INLINE uint32_t LL_RCC_PLLI2S_GetR(void) -{ - return (uint32_t)(READ_BIT(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SR)); -} - -#if defined(RCC_PLLI2SCFGR_PLLI2SP) -/** - * @brief Get I2SPLL division factor for PLLI2SP - * @note used for PLLSPDIFRXCLK (SPDIFRX clock) - * @rmtoll PLLI2SCFGR PLLI2SP LL_RCC_PLLI2S_GetP - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLI2SP_DIV_2 - * @arg @ref LL_RCC_PLLI2SP_DIV_4 - * @arg @ref LL_RCC_PLLI2SP_DIV_6 - * @arg @ref LL_RCC_PLLI2SP_DIV_8 - */ -__STATIC_INLINE uint32_t LL_RCC_PLLI2S_GetP(void) -{ - return (uint32_t)(READ_BIT(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SP)); -} -#endif /* RCC_PLLI2SCFGR_PLLI2SP */ - -#if defined(RCC_DCKCFGR_PLLI2SDIVQ) -/** - * @brief Get I2SPLL division factor for PLLI2SDIVQ - * @note used PLLSAICLK selected (SAI clock) - * @rmtoll DCKCFGR PLLI2SDIVQ LL_RCC_PLLI2S_GetDIVQ - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_1 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_2 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_3 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_4 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_5 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_6 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_7 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_8 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_9 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_10 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_11 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_12 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_13 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_14 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_15 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_16 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_17 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_18 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_19 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_20 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_21 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_22 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_23 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_24 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_25 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_26 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_27 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_28 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_29 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_30 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_31 - * @arg @ref LL_RCC_PLLI2SDIVQ_DIV_32 - */ -__STATIC_INLINE uint32_t LL_RCC_PLLI2S_GetDIVQ(void) -{ - return (uint32_t)(READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_PLLI2SDIVQ)); -} -#endif /* RCC_DCKCFGR_PLLI2SDIVQ */ - -#if defined(RCC_DCKCFGR_PLLI2SDIVR) -/** - * @brief Get I2SPLL division factor for PLLI2SDIVR - * @note used PLLSAICLK selected (SAI clock) - * @rmtoll DCKCFGR PLLI2SDIVR LL_RCC_PLLI2S_GetDIVR - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_1 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_2 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_3 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_4 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_5 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_6 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_7 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_8 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_9 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_10 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_11 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_12 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_13 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_14 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_15 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_16 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_17 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_18 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_19 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_20 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_21 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_22 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_23 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_24 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_25 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_26 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_27 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_28 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_29 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_30 - * @arg @ref LL_RCC_PLLI2SDIVR_DIV_31 - */ -__STATIC_INLINE uint32_t LL_RCC_PLLI2S_GetDIVR(void) -{ - return (uint32_t)(READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_PLLI2SDIVR)); -} -#endif /* RCC_DCKCFGR_PLLI2SDIVR */ - -/** - * @brief Get division factor for PLLI2S input clock - * @rmtoll PLLCFGR PLLM LL_RCC_PLLI2S_GetDivider\n - * PLLI2SCFGR PLLI2SM LL_RCC_PLLI2S_GetDivider - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLI2SM_DIV_2 - * @arg @ref LL_RCC_PLLI2SM_DIV_3 - * @arg @ref LL_RCC_PLLI2SM_DIV_4 - * @arg @ref LL_RCC_PLLI2SM_DIV_5 - * @arg @ref LL_RCC_PLLI2SM_DIV_6 - * @arg @ref LL_RCC_PLLI2SM_DIV_7 - * @arg @ref LL_RCC_PLLI2SM_DIV_8 - * @arg @ref LL_RCC_PLLI2SM_DIV_9 - * @arg @ref LL_RCC_PLLI2SM_DIV_10 - * @arg @ref LL_RCC_PLLI2SM_DIV_11 - * @arg @ref LL_RCC_PLLI2SM_DIV_12 - * @arg @ref LL_RCC_PLLI2SM_DIV_13 - * @arg @ref LL_RCC_PLLI2SM_DIV_14 - * @arg @ref LL_RCC_PLLI2SM_DIV_15 - * @arg @ref LL_RCC_PLLI2SM_DIV_16 - * @arg @ref LL_RCC_PLLI2SM_DIV_17 - * @arg @ref LL_RCC_PLLI2SM_DIV_18 - * @arg @ref LL_RCC_PLLI2SM_DIV_19 - * @arg @ref LL_RCC_PLLI2SM_DIV_20 - * @arg @ref LL_RCC_PLLI2SM_DIV_21 - * @arg @ref LL_RCC_PLLI2SM_DIV_22 - * @arg @ref LL_RCC_PLLI2SM_DIV_23 - * @arg @ref LL_RCC_PLLI2SM_DIV_24 - * @arg @ref LL_RCC_PLLI2SM_DIV_25 - * @arg @ref LL_RCC_PLLI2SM_DIV_26 - * @arg @ref LL_RCC_PLLI2SM_DIV_27 - * @arg @ref LL_RCC_PLLI2SM_DIV_28 - * @arg @ref LL_RCC_PLLI2SM_DIV_29 - * @arg @ref LL_RCC_PLLI2SM_DIV_30 - * @arg @ref LL_RCC_PLLI2SM_DIV_31 - * @arg @ref LL_RCC_PLLI2SM_DIV_32 - * @arg @ref LL_RCC_PLLI2SM_DIV_33 - * @arg @ref LL_RCC_PLLI2SM_DIV_34 - * @arg @ref LL_RCC_PLLI2SM_DIV_35 - * @arg @ref LL_RCC_PLLI2SM_DIV_36 - * @arg @ref LL_RCC_PLLI2SM_DIV_37 - * @arg @ref LL_RCC_PLLI2SM_DIV_38 - * @arg @ref LL_RCC_PLLI2SM_DIV_39 - * @arg @ref LL_RCC_PLLI2SM_DIV_40 - * @arg @ref LL_RCC_PLLI2SM_DIV_41 - * @arg @ref LL_RCC_PLLI2SM_DIV_42 - * @arg @ref LL_RCC_PLLI2SM_DIV_43 - * @arg @ref LL_RCC_PLLI2SM_DIV_44 - * @arg @ref LL_RCC_PLLI2SM_DIV_45 - * @arg @ref LL_RCC_PLLI2SM_DIV_46 - * @arg @ref LL_RCC_PLLI2SM_DIV_47 - * @arg @ref LL_RCC_PLLI2SM_DIV_48 - * @arg @ref LL_RCC_PLLI2SM_DIV_49 - * @arg @ref LL_RCC_PLLI2SM_DIV_50 - * @arg @ref LL_RCC_PLLI2SM_DIV_51 - * @arg @ref LL_RCC_PLLI2SM_DIV_52 - * @arg @ref LL_RCC_PLLI2SM_DIV_53 - * @arg @ref LL_RCC_PLLI2SM_DIV_54 - * @arg @ref LL_RCC_PLLI2SM_DIV_55 - * @arg @ref LL_RCC_PLLI2SM_DIV_56 - * @arg @ref LL_RCC_PLLI2SM_DIV_57 - * @arg @ref LL_RCC_PLLI2SM_DIV_58 - * @arg @ref LL_RCC_PLLI2SM_DIV_59 - * @arg @ref LL_RCC_PLLI2SM_DIV_60 - * @arg @ref LL_RCC_PLLI2SM_DIV_61 - * @arg @ref LL_RCC_PLLI2SM_DIV_62 - * @arg @ref LL_RCC_PLLI2SM_DIV_63 - */ -__STATIC_INLINE uint32_t LL_RCC_PLLI2S_GetDivider(void) -{ -#if defined(RCC_PLLI2SCFGR_PLLI2SM) - return (uint32_t)(READ_BIT(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SM)); -#else - return (uint32_t)(READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLM)); -#endif /* RCC_PLLI2SCFGR_PLLI2SM */ -} - -/** - * @brief Get the oscillator used as PLL clock source. - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLLI2S_GetMainSource\n - * PLLI2SCFGR PLLI2SSRC LL_RCC_PLLI2S_GetMainSource - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @arg @ref LL_RCC_PLLI2SSOURCE_PIN (*) - * - * (*) value not defined in all devices. - */ -__STATIC_INLINE uint32_t LL_RCC_PLLI2S_GetMainSource(void) -{ -#if defined(RCC_PLLI2SCFGR_PLLI2SSRC) - uint32_t pllsrc = READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC); - uint32_t plli2sssrc0 = READ_BIT(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SSRC); - uint32_t plli2sssrc1 = READ_BIT(RCC->PLLI2SCFGR, RCC_PLLI2SCFGR_PLLI2SSRC) >> 15U; - return (uint32_t)(pllsrc | plli2sssrc0 | plli2sssrc1); -#else - return (uint32_t)(READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC)); -#endif /* RCC_PLLI2SCFGR_PLLI2SSRC */ -} - -/** - * @} - */ -#endif /* RCC_PLLI2S_SUPPORT */ - -#if defined(RCC_PLLSAI_SUPPORT) -/** @defgroup RCC_LL_EF_PLLSAI PLLSAI - * @{ - */ - -/** - * @brief Enable PLLSAI - * @rmtoll CR PLLSAION LL_RCC_PLLSAI_Enable - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLLSAI_Enable(void) -{ - SET_BIT(RCC->CR, RCC_CR_PLLSAION); -} - -/** - * @brief Disable PLLSAI - * @rmtoll CR PLLSAION LL_RCC_PLLSAI_Disable - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLLSAI_Disable(void) -{ - CLEAR_BIT(RCC->CR, RCC_CR_PLLSAION); -} - -/** - * @brief Check if PLLSAI Ready - * @rmtoll CR PLLSAIRDY LL_RCC_PLLSAI_IsReady - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_PLLSAI_IsReady(void) -{ - return (READ_BIT(RCC->CR, RCC_CR_PLLSAIRDY) == (RCC_CR_PLLSAIRDY)); -} - -/** - * @brief Configure PLLSAI used for SAI domain clock - * @note PLL Source and PLLM Divider can be written only when PLL, - * PLLI2S and PLLSAI(*) are disabled - * @note PLLN/PLLQ can be written only when PLLSAI is disabled - * @note This can be selected for SAI - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLLSAI_ConfigDomain_SAI\n - * PLLCFGR PLLM LL_RCC_PLLSAI_ConfigDomain_SAI\n - * PLLSAICFGR PLLSAIM LL_RCC_PLLSAI_ConfigDomain_SAI\n - * PLLSAICFGR PLLSAIN LL_RCC_PLLSAI_ConfigDomain_SAI\n - * PLLSAICFGR PLLSAIQ LL_RCC_PLLSAI_ConfigDomain_SAI\n - * DCKCFGR PLLSAIDIVQ LL_RCC_PLLSAI_ConfigDomain_SAI - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @param PLLM This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIM_DIV_2 - * @arg @ref LL_RCC_PLLSAIM_DIV_3 - * @arg @ref LL_RCC_PLLSAIM_DIV_4 - * @arg @ref LL_RCC_PLLSAIM_DIV_5 - * @arg @ref LL_RCC_PLLSAIM_DIV_6 - * @arg @ref LL_RCC_PLLSAIM_DIV_7 - * @arg @ref LL_RCC_PLLSAIM_DIV_8 - * @arg @ref LL_RCC_PLLSAIM_DIV_9 - * @arg @ref LL_RCC_PLLSAIM_DIV_10 - * @arg @ref LL_RCC_PLLSAIM_DIV_11 - * @arg @ref LL_RCC_PLLSAIM_DIV_12 - * @arg @ref LL_RCC_PLLSAIM_DIV_13 - * @arg @ref LL_RCC_PLLSAIM_DIV_14 - * @arg @ref LL_RCC_PLLSAIM_DIV_15 - * @arg @ref LL_RCC_PLLSAIM_DIV_16 - * @arg @ref LL_RCC_PLLSAIM_DIV_17 - * @arg @ref LL_RCC_PLLSAIM_DIV_18 - * @arg @ref LL_RCC_PLLSAIM_DIV_19 - * @arg @ref LL_RCC_PLLSAIM_DIV_20 - * @arg @ref LL_RCC_PLLSAIM_DIV_21 - * @arg @ref LL_RCC_PLLSAIM_DIV_22 - * @arg @ref LL_RCC_PLLSAIM_DIV_23 - * @arg @ref LL_RCC_PLLSAIM_DIV_24 - * @arg @ref LL_RCC_PLLSAIM_DIV_25 - * @arg @ref LL_RCC_PLLSAIM_DIV_26 - * @arg @ref LL_RCC_PLLSAIM_DIV_27 - * @arg @ref LL_RCC_PLLSAIM_DIV_28 - * @arg @ref LL_RCC_PLLSAIM_DIV_29 - * @arg @ref LL_RCC_PLLSAIM_DIV_30 - * @arg @ref LL_RCC_PLLSAIM_DIV_31 - * @arg @ref LL_RCC_PLLSAIM_DIV_32 - * @arg @ref LL_RCC_PLLSAIM_DIV_33 - * @arg @ref LL_RCC_PLLSAIM_DIV_34 - * @arg @ref LL_RCC_PLLSAIM_DIV_35 - * @arg @ref LL_RCC_PLLSAIM_DIV_36 - * @arg @ref LL_RCC_PLLSAIM_DIV_37 - * @arg @ref LL_RCC_PLLSAIM_DIV_38 - * @arg @ref LL_RCC_PLLSAIM_DIV_39 - * @arg @ref LL_RCC_PLLSAIM_DIV_40 - * @arg @ref LL_RCC_PLLSAIM_DIV_41 - * @arg @ref LL_RCC_PLLSAIM_DIV_42 - * @arg @ref LL_RCC_PLLSAIM_DIV_43 - * @arg @ref LL_RCC_PLLSAIM_DIV_44 - * @arg @ref LL_RCC_PLLSAIM_DIV_45 - * @arg @ref LL_RCC_PLLSAIM_DIV_46 - * @arg @ref LL_RCC_PLLSAIM_DIV_47 - * @arg @ref LL_RCC_PLLSAIM_DIV_48 - * @arg @ref LL_RCC_PLLSAIM_DIV_49 - * @arg @ref LL_RCC_PLLSAIM_DIV_50 - * @arg @ref LL_RCC_PLLSAIM_DIV_51 - * @arg @ref LL_RCC_PLLSAIM_DIV_52 - * @arg @ref LL_RCC_PLLSAIM_DIV_53 - * @arg @ref LL_RCC_PLLSAIM_DIV_54 - * @arg @ref LL_RCC_PLLSAIM_DIV_55 - * @arg @ref LL_RCC_PLLSAIM_DIV_56 - * @arg @ref LL_RCC_PLLSAIM_DIV_57 - * @arg @ref LL_RCC_PLLSAIM_DIV_58 - * @arg @ref LL_RCC_PLLSAIM_DIV_59 - * @arg @ref LL_RCC_PLLSAIM_DIV_60 - * @arg @ref LL_RCC_PLLSAIM_DIV_61 - * @arg @ref LL_RCC_PLLSAIM_DIV_62 - * @arg @ref LL_RCC_PLLSAIM_DIV_63 - * @param PLLN Between 49/50(*) and 432 - * - * (*) value not defined in all devices. - * @param PLLQ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIQ_DIV_2 - * @arg @ref LL_RCC_PLLSAIQ_DIV_3 - * @arg @ref LL_RCC_PLLSAIQ_DIV_4 - * @arg @ref LL_RCC_PLLSAIQ_DIV_5 - * @arg @ref LL_RCC_PLLSAIQ_DIV_6 - * @arg @ref LL_RCC_PLLSAIQ_DIV_7 - * @arg @ref LL_RCC_PLLSAIQ_DIV_8 - * @arg @ref LL_RCC_PLLSAIQ_DIV_9 - * @arg @ref LL_RCC_PLLSAIQ_DIV_10 - * @arg @ref LL_RCC_PLLSAIQ_DIV_11 - * @arg @ref LL_RCC_PLLSAIQ_DIV_12 - * @arg @ref LL_RCC_PLLSAIQ_DIV_13 - * @arg @ref LL_RCC_PLLSAIQ_DIV_14 - * @arg @ref LL_RCC_PLLSAIQ_DIV_15 - * @param PLLDIVQ This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_1 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_2 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_3 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_4 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_5 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_6 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_7 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_8 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_9 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_10 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_11 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_12 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_13 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_14 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_15 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_16 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_17 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_18 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_19 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_20 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_21 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_22 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_23 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_24 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_25 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_26 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_27 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_28 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_29 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_30 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_31 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_32 - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLLSAI_ConfigDomain_SAI(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLQ, uint32_t PLLDIVQ) -{ - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC, Source); -#if defined(RCC_PLLSAICFGR_PLLSAIM) - MODIFY_REG(RCC->PLLSAICFGR, RCC_PLLSAICFGR_PLLSAIM, PLLM); -#else - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLM, PLLM); -#endif /* RCC_PLLSAICFGR_PLLSAIM */ - MODIFY_REG(RCC->PLLSAICFGR, RCC_PLLSAICFGR_PLLSAIN | RCC_PLLSAICFGR_PLLSAIQ, PLLN << RCC_PLLSAICFGR_PLLSAIN_Pos | PLLQ); - MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_PLLSAIDIVQ, PLLDIVQ); -} - -#if defined(RCC_PLLSAICFGR_PLLSAIP) -/** - * @brief Configure PLLSAI used for 48Mhz domain clock - * @note PLL Source and PLLM Divider can be written only when PLL, - * PLLI2S and PLLSAI(*) are disabled - * @note PLLN/PLLP can be written only when PLLSAI is disabled - * @note This can be selected for USB, RNG, SDIO - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLLSAI_ConfigDomain_48M\n - * PLLCFGR PLLM LL_RCC_PLLSAI_ConfigDomain_48M\n - * PLLSAICFGR PLLSAIM LL_RCC_PLLSAI_ConfigDomain_48M\n - * PLLSAICFGR PLLSAIN LL_RCC_PLLSAI_ConfigDomain_48M\n - * PLLSAICFGR PLLSAIP LL_RCC_PLLSAI_ConfigDomain_48M - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @param PLLM This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIM_DIV_2 - * @arg @ref LL_RCC_PLLSAIM_DIV_3 - * @arg @ref LL_RCC_PLLSAIM_DIV_4 - * @arg @ref LL_RCC_PLLSAIM_DIV_5 - * @arg @ref LL_RCC_PLLSAIM_DIV_6 - * @arg @ref LL_RCC_PLLSAIM_DIV_7 - * @arg @ref LL_RCC_PLLSAIM_DIV_8 - * @arg @ref LL_RCC_PLLSAIM_DIV_9 - * @arg @ref LL_RCC_PLLSAIM_DIV_10 - * @arg @ref LL_RCC_PLLSAIM_DIV_11 - * @arg @ref LL_RCC_PLLSAIM_DIV_12 - * @arg @ref LL_RCC_PLLSAIM_DIV_13 - * @arg @ref LL_RCC_PLLSAIM_DIV_14 - * @arg @ref LL_RCC_PLLSAIM_DIV_15 - * @arg @ref LL_RCC_PLLSAIM_DIV_16 - * @arg @ref LL_RCC_PLLSAIM_DIV_17 - * @arg @ref LL_RCC_PLLSAIM_DIV_18 - * @arg @ref LL_RCC_PLLSAIM_DIV_19 - * @arg @ref LL_RCC_PLLSAIM_DIV_20 - * @arg @ref LL_RCC_PLLSAIM_DIV_21 - * @arg @ref LL_RCC_PLLSAIM_DIV_22 - * @arg @ref LL_RCC_PLLSAIM_DIV_23 - * @arg @ref LL_RCC_PLLSAIM_DIV_24 - * @arg @ref LL_RCC_PLLSAIM_DIV_25 - * @arg @ref LL_RCC_PLLSAIM_DIV_26 - * @arg @ref LL_RCC_PLLSAIM_DIV_27 - * @arg @ref LL_RCC_PLLSAIM_DIV_28 - * @arg @ref LL_RCC_PLLSAIM_DIV_29 - * @arg @ref LL_RCC_PLLSAIM_DIV_30 - * @arg @ref LL_RCC_PLLSAIM_DIV_31 - * @arg @ref LL_RCC_PLLSAIM_DIV_32 - * @arg @ref LL_RCC_PLLSAIM_DIV_33 - * @arg @ref LL_RCC_PLLSAIM_DIV_34 - * @arg @ref LL_RCC_PLLSAIM_DIV_35 - * @arg @ref LL_RCC_PLLSAIM_DIV_36 - * @arg @ref LL_RCC_PLLSAIM_DIV_37 - * @arg @ref LL_RCC_PLLSAIM_DIV_38 - * @arg @ref LL_RCC_PLLSAIM_DIV_39 - * @arg @ref LL_RCC_PLLSAIM_DIV_40 - * @arg @ref LL_RCC_PLLSAIM_DIV_41 - * @arg @ref LL_RCC_PLLSAIM_DIV_42 - * @arg @ref LL_RCC_PLLSAIM_DIV_43 - * @arg @ref LL_RCC_PLLSAIM_DIV_44 - * @arg @ref LL_RCC_PLLSAIM_DIV_45 - * @arg @ref LL_RCC_PLLSAIM_DIV_46 - * @arg @ref LL_RCC_PLLSAIM_DIV_47 - * @arg @ref LL_RCC_PLLSAIM_DIV_48 - * @arg @ref LL_RCC_PLLSAIM_DIV_49 - * @arg @ref LL_RCC_PLLSAIM_DIV_50 - * @arg @ref LL_RCC_PLLSAIM_DIV_51 - * @arg @ref LL_RCC_PLLSAIM_DIV_52 - * @arg @ref LL_RCC_PLLSAIM_DIV_53 - * @arg @ref LL_RCC_PLLSAIM_DIV_54 - * @arg @ref LL_RCC_PLLSAIM_DIV_55 - * @arg @ref LL_RCC_PLLSAIM_DIV_56 - * @arg @ref LL_RCC_PLLSAIM_DIV_57 - * @arg @ref LL_RCC_PLLSAIM_DIV_58 - * @arg @ref LL_RCC_PLLSAIM_DIV_59 - * @arg @ref LL_RCC_PLLSAIM_DIV_60 - * @arg @ref LL_RCC_PLLSAIM_DIV_61 - * @arg @ref LL_RCC_PLLSAIM_DIV_62 - * @arg @ref LL_RCC_PLLSAIM_DIV_63 - * @param PLLN Between 50 and 432 - * @param PLLP This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIP_DIV_2 - * @arg @ref LL_RCC_PLLSAIP_DIV_4 - * @arg @ref LL_RCC_PLLSAIP_DIV_6 - * @arg @ref LL_RCC_PLLSAIP_DIV_8 - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLLSAI_ConfigDomain_48M(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLP) -{ - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC, Source); -#if defined(RCC_PLLSAICFGR_PLLSAIM) - MODIFY_REG(RCC->PLLSAICFGR, RCC_PLLSAICFGR_PLLSAIM, PLLM); -#else - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLM, PLLM); -#endif /* RCC_PLLSAICFGR_PLLSAIM */ - MODIFY_REG(RCC->PLLSAICFGR, RCC_PLLSAICFGR_PLLSAIN | RCC_PLLSAICFGR_PLLSAIP, PLLN << RCC_PLLSAICFGR_PLLSAIN_Pos | PLLP); -} -#endif /* RCC_PLLSAICFGR_PLLSAIP */ - -#if defined(LTDC) -/** - * @brief Configure PLLSAI used for LTDC domain clock - * @note PLL Source and PLLM Divider can be written only when PLL, - * PLLI2S and PLLSAI(*) are disabled - * @note PLLN/PLLR can be written only when PLLSAI is disabled - * @note This can be selected for LTDC - * @rmtoll PLLCFGR PLLSRC LL_RCC_PLLSAI_ConfigDomain_LTDC\n - * PLLCFGR PLLM LL_RCC_PLLSAI_ConfigDomain_LTDC\n - * PLLSAICFGR PLLSAIN LL_RCC_PLLSAI_ConfigDomain_LTDC\n - * PLLSAICFGR PLLSAIR LL_RCC_PLLSAI_ConfigDomain_LTDC\n - * DCKCFGR PLLSAIDIVR LL_RCC_PLLSAI_ConfigDomain_LTDC - * @param Source This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSOURCE_HSI - * @arg @ref LL_RCC_PLLSOURCE_HSE - * @param PLLM This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIM_DIV_2 - * @arg @ref LL_RCC_PLLSAIM_DIV_3 - * @arg @ref LL_RCC_PLLSAIM_DIV_4 - * @arg @ref LL_RCC_PLLSAIM_DIV_5 - * @arg @ref LL_RCC_PLLSAIM_DIV_6 - * @arg @ref LL_RCC_PLLSAIM_DIV_7 - * @arg @ref LL_RCC_PLLSAIM_DIV_8 - * @arg @ref LL_RCC_PLLSAIM_DIV_9 - * @arg @ref LL_RCC_PLLSAIM_DIV_10 - * @arg @ref LL_RCC_PLLSAIM_DIV_11 - * @arg @ref LL_RCC_PLLSAIM_DIV_12 - * @arg @ref LL_RCC_PLLSAIM_DIV_13 - * @arg @ref LL_RCC_PLLSAIM_DIV_14 - * @arg @ref LL_RCC_PLLSAIM_DIV_15 - * @arg @ref LL_RCC_PLLSAIM_DIV_16 - * @arg @ref LL_RCC_PLLSAIM_DIV_17 - * @arg @ref LL_RCC_PLLSAIM_DIV_18 - * @arg @ref LL_RCC_PLLSAIM_DIV_19 - * @arg @ref LL_RCC_PLLSAIM_DIV_20 - * @arg @ref LL_RCC_PLLSAIM_DIV_21 - * @arg @ref LL_RCC_PLLSAIM_DIV_22 - * @arg @ref LL_RCC_PLLSAIM_DIV_23 - * @arg @ref LL_RCC_PLLSAIM_DIV_24 - * @arg @ref LL_RCC_PLLSAIM_DIV_25 - * @arg @ref LL_RCC_PLLSAIM_DIV_26 - * @arg @ref LL_RCC_PLLSAIM_DIV_27 - * @arg @ref LL_RCC_PLLSAIM_DIV_28 - * @arg @ref LL_RCC_PLLSAIM_DIV_29 - * @arg @ref LL_RCC_PLLSAIM_DIV_30 - * @arg @ref LL_RCC_PLLSAIM_DIV_31 - * @arg @ref LL_RCC_PLLSAIM_DIV_32 - * @arg @ref LL_RCC_PLLSAIM_DIV_33 - * @arg @ref LL_RCC_PLLSAIM_DIV_34 - * @arg @ref LL_RCC_PLLSAIM_DIV_35 - * @arg @ref LL_RCC_PLLSAIM_DIV_36 - * @arg @ref LL_RCC_PLLSAIM_DIV_37 - * @arg @ref LL_RCC_PLLSAIM_DIV_38 - * @arg @ref LL_RCC_PLLSAIM_DIV_39 - * @arg @ref LL_RCC_PLLSAIM_DIV_40 - * @arg @ref LL_RCC_PLLSAIM_DIV_41 - * @arg @ref LL_RCC_PLLSAIM_DIV_42 - * @arg @ref LL_RCC_PLLSAIM_DIV_43 - * @arg @ref LL_RCC_PLLSAIM_DIV_44 - * @arg @ref LL_RCC_PLLSAIM_DIV_45 - * @arg @ref LL_RCC_PLLSAIM_DIV_46 - * @arg @ref LL_RCC_PLLSAIM_DIV_47 - * @arg @ref LL_RCC_PLLSAIM_DIV_48 - * @arg @ref LL_RCC_PLLSAIM_DIV_49 - * @arg @ref LL_RCC_PLLSAIM_DIV_50 - * @arg @ref LL_RCC_PLLSAIM_DIV_51 - * @arg @ref LL_RCC_PLLSAIM_DIV_52 - * @arg @ref LL_RCC_PLLSAIM_DIV_53 - * @arg @ref LL_RCC_PLLSAIM_DIV_54 - * @arg @ref LL_RCC_PLLSAIM_DIV_55 - * @arg @ref LL_RCC_PLLSAIM_DIV_56 - * @arg @ref LL_RCC_PLLSAIM_DIV_57 - * @arg @ref LL_RCC_PLLSAIM_DIV_58 - * @arg @ref LL_RCC_PLLSAIM_DIV_59 - * @arg @ref LL_RCC_PLLSAIM_DIV_60 - * @arg @ref LL_RCC_PLLSAIM_DIV_61 - * @arg @ref LL_RCC_PLLSAIM_DIV_62 - * @arg @ref LL_RCC_PLLSAIM_DIV_63 - * @param PLLN Between 49/50(*) and 432 - * - * (*) value not defined in all devices. - * @param PLLR This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIR_DIV_2 - * @arg @ref LL_RCC_PLLSAIR_DIV_3 - * @arg @ref LL_RCC_PLLSAIR_DIV_4 - * @arg @ref LL_RCC_PLLSAIR_DIV_5 - * @arg @ref LL_RCC_PLLSAIR_DIV_6 - * @arg @ref LL_RCC_PLLSAIR_DIV_7 - * @param PLLDIVR This parameter can be one of the following values: - * @arg @ref LL_RCC_PLLSAIDIVR_DIV_2 - * @arg @ref LL_RCC_PLLSAIDIVR_DIV_4 - * @arg @ref LL_RCC_PLLSAIDIVR_DIV_8 - * @arg @ref LL_RCC_PLLSAIDIVR_DIV_16 - * @retval None - */ -__STATIC_INLINE void LL_RCC_PLLSAI_ConfigDomain_LTDC(uint32_t Source, uint32_t PLLM, uint32_t PLLN, uint32_t PLLR, uint32_t PLLDIVR) -{ - MODIFY_REG(RCC->PLLCFGR, RCC_PLLCFGR_PLLSRC | RCC_PLLCFGR_PLLM, Source | PLLM); - MODIFY_REG(RCC->PLLSAICFGR, RCC_PLLSAICFGR_PLLSAIN | RCC_PLLSAICFGR_PLLSAIR, PLLN << RCC_PLLSAICFGR_PLLSAIN_Pos | PLLR); - MODIFY_REG(RCC->DCKCFGR, RCC_DCKCFGR_PLLSAIDIVR, PLLDIVR); -} -#endif /* LTDC */ - -/** - * @brief Get division factor for PLLSAI input clock - * @rmtoll PLLCFGR PLLM LL_RCC_PLLSAI_GetDivider\n - * PLLSAICFGR PLLSAIM LL_RCC_PLLSAI_GetDivider - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLSAIM_DIV_2 - * @arg @ref LL_RCC_PLLSAIM_DIV_3 - * @arg @ref LL_RCC_PLLSAIM_DIV_4 - * @arg @ref LL_RCC_PLLSAIM_DIV_5 - * @arg @ref LL_RCC_PLLSAIM_DIV_6 - * @arg @ref LL_RCC_PLLSAIM_DIV_7 - * @arg @ref LL_RCC_PLLSAIM_DIV_8 - * @arg @ref LL_RCC_PLLSAIM_DIV_9 - * @arg @ref LL_RCC_PLLSAIM_DIV_10 - * @arg @ref LL_RCC_PLLSAIM_DIV_11 - * @arg @ref LL_RCC_PLLSAIM_DIV_12 - * @arg @ref LL_RCC_PLLSAIM_DIV_13 - * @arg @ref LL_RCC_PLLSAIM_DIV_14 - * @arg @ref LL_RCC_PLLSAIM_DIV_15 - * @arg @ref LL_RCC_PLLSAIM_DIV_16 - * @arg @ref LL_RCC_PLLSAIM_DIV_17 - * @arg @ref LL_RCC_PLLSAIM_DIV_18 - * @arg @ref LL_RCC_PLLSAIM_DIV_19 - * @arg @ref LL_RCC_PLLSAIM_DIV_20 - * @arg @ref LL_RCC_PLLSAIM_DIV_21 - * @arg @ref LL_RCC_PLLSAIM_DIV_22 - * @arg @ref LL_RCC_PLLSAIM_DIV_23 - * @arg @ref LL_RCC_PLLSAIM_DIV_24 - * @arg @ref LL_RCC_PLLSAIM_DIV_25 - * @arg @ref LL_RCC_PLLSAIM_DIV_26 - * @arg @ref LL_RCC_PLLSAIM_DIV_27 - * @arg @ref LL_RCC_PLLSAIM_DIV_28 - * @arg @ref LL_RCC_PLLSAIM_DIV_29 - * @arg @ref LL_RCC_PLLSAIM_DIV_30 - * @arg @ref LL_RCC_PLLSAIM_DIV_31 - * @arg @ref LL_RCC_PLLSAIM_DIV_32 - * @arg @ref LL_RCC_PLLSAIM_DIV_33 - * @arg @ref LL_RCC_PLLSAIM_DIV_34 - * @arg @ref LL_RCC_PLLSAIM_DIV_35 - * @arg @ref LL_RCC_PLLSAIM_DIV_36 - * @arg @ref LL_RCC_PLLSAIM_DIV_37 - * @arg @ref LL_RCC_PLLSAIM_DIV_38 - * @arg @ref LL_RCC_PLLSAIM_DIV_39 - * @arg @ref LL_RCC_PLLSAIM_DIV_40 - * @arg @ref LL_RCC_PLLSAIM_DIV_41 - * @arg @ref LL_RCC_PLLSAIM_DIV_42 - * @arg @ref LL_RCC_PLLSAIM_DIV_43 - * @arg @ref LL_RCC_PLLSAIM_DIV_44 - * @arg @ref LL_RCC_PLLSAIM_DIV_45 - * @arg @ref LL_RCC_PLLSAIM_DIV_46 - * @arg @ref LL_RCC_PLLSAIM_DIV_47 - * @arg @ref LL_RCC_PLLSAIM_DIV_48 - * @arg @ref LL_RCC_PLLSAIM_DIV_49 - * @arg @ref LL_RCC_PLLSAIM_DIV_50 - * @arg @ref LL_RCC_PLLSAIM_DIV_51 - * @arg @ref LL_RCC_PLLSAIM_DIV_52 - * @arg @ref LL_RCC_PLLSAIM_DIV_53 - * @arg @ref LL_RCC_PLLSAIM_DIV_54 - * @arg @ref LL_RCC_PLLSAIM_DIV_55 - * @arg @ref LL_RCC_PLLSAIM_DIV_56 - * @arg @ref LL_RCC_PLLSAIM_DIV_57 - * @arg @ref LL_RCC_PLLSAIM_DIV_58 - * @arg @ref LL_RCC_PLLSAIM_DIV_59 - * @arg @ref LL_RCC_PLLSAIM_DIV_60 - * @arg @ref LL_RCC_PLLSAIM_DIV_61 - * @arg @ref LL_RCC_PLLSAIM_DIV_62 - * @arg @ref LL_RCC_PLLSAIM_DIV_63 - */ -__STATIC_INLINE uint32_t LL_RCC_PLLSAI_GetDivider(void) -{ -#if defined(RCC_PLLSAICFGR_PLLSAIM) - return (uint32_t)(READ_BIT(RCC->PLLSAICFGR, RCC_PLLSAICFGR_PLLSAIM)); -#else - return (uint32_t)(READ_BIT(RCC->PLLCFGR, RCC_PLLCFGR_PLLM)); -#endif /* RCC_PLLSAICFGR_PLLSAIM */ -} - -/** - * @brief Get SAIPLL multiplication factor for VCO - * @rmtoll PLLSAICFGR PLLSAIN LL_RCC_PLLSAI_GetN - * @retval Between 49/50(*) and 432 - * - * (*) value not defined in all devices. - */ -__STATIC_INLINE uint32_t LL_RCC_PLLSAI_GetN(void) -{ - return (uint32_t)(READ_BIT(RCC->PLLSAICFGR, RCC_PLLSAICFGR_PLLSAIN) >> RCC_PLLSAICFGR_PLLSAIN_Pos); -} - -/** - * @brief Get SAIPLL division factor for PLLSAIQ - * @rmtoll PLLSAICFGR PLLSAIQ LL_RCC_PLLSAI_GetQ - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLSAIQ_DIV_2 - * @arg @ref LL_RCC_PLLSAIQ_DIV_3 - * @arg @ref LL_RCC_PLLSAIQ_DIV_4 - * @arg @ref LL_RCC_PLLSAIQ_DIV_5 - * @arg @ref LL_RCC_PLLSAIQ_DIV_6 - * @arg @ref LL_RCC_PLLSAIQ_DIV_7 - * @arg @ref LL_RCC_PLLSAIQ_DIV_8 - * @arg @ref LL_RCC_PLLSAIQ_DIV_9 - * @arg @ref LL_RCC_PLLSAIQ_DIV_10 - * @arg @ref LL_RCC_PLLSAIQ_DIV_11 - * @arg @ref LL_RCC_PLLSAIQ_DIV_12 - * @arg @ref LL_RCC_PLLSAIQ_DIV_13 - * @arg @ref LL_RCC_PLLSAIQ_DIV_14 - * @arg @ref LL_RCC_PLLSAIQ_DIV_15 - */ -__STATIC_INLINE uint32_t LL_RCC_PLLSAI_GetQ(void) -{ - return (uint32_t)(READ_BIT(RCC->PLLSAICFGR, RCC_PLLSAICFGR_PLLSAIQ)); -} - -#if defined(RCC_PLLSAICFGR_PLLSAIR) -/** - * @brief Get SAIPLL division factor for PLLSAIR - * @note used for PLLSAICLK (SAI clock) - * @rmtoll PLLSAICFGR PLLSAIR LL_RCC_PLLSAI_GetR - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLSAIR_DIV_2 - * @arg @ref LL_RCC_PLLSAIR_DIV_3 - * @arg @ref LL_RCC_PLLSAIR_DIV_4 - * @arg @ref LL_RCC_PLLSAIR_DIV_5 - * @arg @ref LL_RCC_PLLSAIR_DIV_6 - * @arg @ref LL_RCC_PLLSAIR_DIV_7 - */ -__STATIC_INLINE uint32_t LL_RCC_PLLSAI_GetR(void) -{ - return (uint32_t)(READ_BIT(RCC->PLLSAICFGR, RCC_PLLSAICFGR_PLLSAIR)); -} -#endif /* RCC_PLLSAICFGR_PLLSAIR */ - -#if defined(RCC_PLLSAICFGR_PLLSAIP) -/** - * @brief Get SAIPLL division factor for PLLSAIP - * @note used for PLL48MCLK (48M domain clock) - * @rmtoll PLLSAICFGR PLLSAIP LL_RCC_PLLSAI_GetP - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLSAIP_DIV_2 - * @arg @ref LL_RCC_PLLSAIP_DIV_4 - * @arg @ref LL_RCC_PLLSAIP_DIV_6 - * @arg @ref LL_RCC_PLLSAIP_DIV_8 - */ -__STATIC_INLINE uint32_t LL_RCC_PLLSAI_GetP(void) -{ - return (uint32_t)(READ_BIT(RCC->PLLSAICFGR, RCC_PLLSAICFGR_PLLSAIP)); -} -#endif /* RCC_PLLSAICFGR_PLLSAIP */ - -/** - * @brief Get SAIPLL division factor for PLLSAIDIVQ - * @note used PLLSAICLK selected (SAI clock) - * @rmtoll DCKCFGR PLLSAIDIVQ LL_RCC_PLLSAI_GetDIVQ - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_1 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_2 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_3 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_4 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_5 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_6 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_7 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_8 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_9 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_10 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_11 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_12 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_13 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_14 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_15 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_16 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_17 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_18 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_19 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_20 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_21 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_22 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_23 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_24 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_25 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_26 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_27 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_28 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_29 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_30 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_31 - * @arg @ref LL_RCC_PLLSAIDIVQ_DIV_32 - */ -__STATIC_INLINE uint32_t LL_RCC_PLLSAI_GetDIVQ(void) -{ - return (uint32_t)(READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_PLLSAIDIVQ)); -} - -#if defined(RCC_DCKCFGR_PLLSAIDIVR) -/** - * @brief Get SAIPLL division factor for PLLSAIDIVR - * @note used for LTDC domain clock - * @rmtoll DCKCFGR PLLSAIDIVR LL_RCC_PLLSAI_GetDIVR - * @retval Returned value can be one of the following values: - * @arg @ref LL_RCC_PLLSAIDIVR_DIV_2 - * @arg @ref LL_RCC_PLLSAIDIVR_DIV_4 - * @arg @ref LL_RCC_PLLSAIDIVR_DIV_8 - * @arg @ref LL_RCC_PLLSAIDIVR_DIV_16 - */ -__STATIC_INLINE uint32_t LL_RCC_PLLSAI_GetDIVR(void) -{ - return (uint32_t)(READ_BIT(RCC->DCKCFGR, RCC_DCKCFGR_PLLSAIDIVR)); -} -#endif /* RCC_DCKCFGR_PLLSAIDIVR */ - -/** - * @} - */ -#endif /* RCC_PLLSAI_SUPPORT */ - -/** @defgroup RCC_LL_EF_FLAG_Management FLAG Management - * @{ - */ - -/** - * @brief Clear LSI ready interrupt flag - * @rmtoll CIR LSIRDYC LL_RCC_ClearFlag_LSIRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_ClearFlag_LSIRDY(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_LSIRDYC); -} - -/** - * @brief Clear LSE ready interrupt flag - * @rmtoll CIR LSERDYC LL_RCC_ClearFlag_LSERDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_ClearFlag_LSERDY(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_LSERDYC); -} - -/** - * @brief Clear HSI ready interrupt flag - * @rmtoll CIR HSIRDYC LL_RCC_ClearFlag_HSIRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_ClearFlag_HSIRDY(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_HSIRDYC); -} - -/** - * @brief Clear HSE ready interrupt flag - * @rmtoll CIR HSERDYC LL_RCC_ClearFlag_HSERDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_ClearFlag_HSERDY(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_HSERDYC); -} - -/** - * @brief Clear PLL ready interrupt flag - * @rmtoll CIR PLLRDYC LL_RCC_ClearFlag_PLLRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_ClearFlag_PLLRDY(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_PLLRDYC); -} - -#if defined(RCC_PLLI2S_SUPPORT) -/** - * @brief Clear PLLI2S ready interrupt flag - * @rmtoll CIR PLLI2SRDYC LL_RCC_ClearFlag_PLLI2SRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_ClearFlag_PLLI2SRDY(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_PLLI2SRDYC); -} - -#endif /* RCC_PLLI2S_SUPPORT */ - -#if defined(RCC_PLLSAI_SUPPORT) -/** - * @brief Clear PLLSAI ready interrupt flag - * @rmtoll CIR PLLSAIRDYC LL_RCC_ClearFlag_PLLSAIRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_ClearFlag_PLLSAIRDY(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_PLLSAIRDYC); -} - -#endif /* RCC_PLLSAI_SUPPORT */ - -/** - * @brief Clear Clock security system interrupt flag - * @rmtoll CIR CSSC LL_RCC_ClearFlag_HSECSS - * @retval None - */ -__STATIC_INLINE void LL_RCC_ClearFlag_HSECSS(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_CSSC); -} - -/** - * @brief Check if LSI ready interrupt occurred or not - * @rmtoll CIR LSIRDYF LL_RCC_IsActiveFlag_LSIRDY - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_LSIRDY(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_LSIRDYF) == (RCC_CIR_LSIRDYF)); -} - -/** - * @brief Check if LSE ready interrupt occurred or not - * @rmtoll CIR LSERDYF LL_RCC_IsActiveFlag_LSERDY - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_LSERDY(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_LSERDYF) == (RCC_CIR_LSERDYF)); -} - -/** - * @brief Check if HSI ready interrupt occurred or not - * @rmtoll CIR HSIRDYF LL_RCC_IsActiveFlag_HSIRDY - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_HSIRDY(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_HSIRDYF) == (RCC_CIR_HSIRDYF)); -} - -/** - * @brief Check if HSE ready interrupt occurred or not - * @rmtoll CIR HSERDYF LL_RCC_IsActiveFlag_HSERDY - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_HSERDY(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_HSERDYF) == (RCC_CIR_HSERDYF)); -} - -/** - * @brief Check if PLL ready interrupt occurred or not - * @rmtoll CIR PLLRDYF LL_RCC_IsActiveFlag_PLLRDY - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_PLLRDY(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_PLLRDYF) == (RCC_CIR_PLLRDYF)); -} - -#if defined(RCC_PLLI2S_SUPPORT) -/** - * @brief Check if PLLI2S ready interrupt occurred or not - * @rmtoll CIR PLLI2SRDYF LL_RCC_IsActiveFlag_PLLI2SRDY - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_PLLI2SRDY(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_PLLI2SRDYF) == (RCC_CIR_PLLI2SRDYF)); -} -#endif /* RCC_PLLI2S_SUPPORT */ - -#if defined(RCC_PLLSAI_SUPPORT) -/** - * @brief Check if PLLSAI ready interrupt occurred or not - * @rmtoll CIR PLLSAIRDYF LL_RCC_IsActiveFlag_PLLSAIRDY - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_PLLSAIRDY(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_PLLSAIRDYF) == (RCC_CIR_PLLSAIRDYF)); -} -#endif /* RCC_PLLSAI_SUPPORT */ - -/** - * @brief Check if Clock security system interrupt occurred or not - * @rmtoll CIR CSSF LL_RCC_IsActiveFlag_HSECSS - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_HSECSS(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_CSSF) == (RCC_CIR_CSSF)); -} - -/** - * @brief Check if RCC flag Independent Watchdog reset is set or not. - * @rmtoll CSR IWDGRSTF LL_RCC_IsActiveFlag_IWDGRST - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_IWDGRST(void) -{ - return (READ_BIT(RCC->CSR, RCC_CSR_IWDGRSTF) == (RCC_CSR_IWDGRSTF)); -} - -/** - * @brief Check if RCC flag Low Power reset is set or not. - * @rmtoll CSR LPWRRSTF LL_RCC_IsActiveFlag_LPWRRST - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_LPWRRST(void) -{ - return (READ_BIT(RCC->CSR, RCC_CSR_LPWRRSTF) == (RCC_CSR_LPWRRSTF)); -} - -/** - * @brief Check if RCC flag Pin reset is set or not. - * @rmtoll CSR PINRSTF LL_RCC_IsActiveFlag_PINRST - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_PINRST(void) -{ - return (READ_BIT(RCC->CSR, RCC_CSR_PINRSTF) == (RCC_CSR_PINRSTF)); -} - -/** - * @brief Check if RCC flag POR/PDR reset is set or not. - * @rmtoll CSR PORRSTF LL_RCC_IsActiveFlag_PORRST - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_PORRST(void) -{ - return (READ_BIT(RCC->CSR, RCC_CSR_PORRSTF) == (RCC_CSR_PORRSTF)); -} - -/** - * @brief Check if RCC flag Software reset is set or not. - * @rmtoll CSR SFTRSTF LL_RCC_IsActiveFlag_SFTRST - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_SFTRST(void) -{ - return (READ_BIT(RCC->CSR, RCC_CSR_SFTRSTF) == (RCC_CSR_SFTRSTF)); -} - -/** - * @brief Check if RCC flag Window Watchdog reset is set or not. - * @rmtoll CSR WWDGRSTF LL_RCC_IsActiveFlag_WWDGRST - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_WWDGRST(void) -{ - return (READ_BIT(RCC->CSR, RCC_CSR_WWDGRSTF) == (RCC_CSR_WWDGRSTF)); -} - -#if defined(RCC_CSR_BORRSTF) -/** - * @brief Check if RCC flag BOR reset is set or not. - * @rmtoll CSR BORRSTF LL_RCC_IsActiveFlag_BORRST - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsActiveFlag_BORRST(void) -{ - return (READ_BIT(RCC->CSR, RCC_CSR_BORRSTF) == (RCC_CSR_BORRSTF)); -} -#endif /* RCC_CSR_BORRSTF */ - -/** - * @brief Set RMVF bit to clear the reset flags. - * @rmtoll CSR RMVF LL_RCC_ClearResetFlags - * @retval None - */ -__STATIC_INLINE void LL_RCC_ClearResetFlags(void) -{ - SET_BIT(RCC->CSR, RCC_CSR_RMVF); -} - -/** - * @} - */ - -/** @defgroup RCC_LL_EF_IT_Management IT Management - * @{ - */ - -/** - * @brief Enable LSI ready interrupt - * @rmtoll CIR LSIRDYIE LL_RCC_EnableIT_LSIRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_EnableIT_LSIRDY(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_LSIRDYIE); -} - -/** - * @brief Enable LSE ready interrupt - * @rmtoll CIR LSERDYIE LL_RCC_EnableIT_LSERDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_EnableIT_LSERDY(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_LSERDYIE); -} - -/** - * @brief Enable HSI ready interrupt - * @rmtoll CIR HSIRDYIE LL_RCC_EnableIT_HSIRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_EnableIT_HSIRDY(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_HSIRDYIE); -} - -/** - * @brief Enable HSE ready interrupt - * @rmtoll CIR HSERDYIE LL_RCC_EnableIT_HSERDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_EnableIT_HSERDY(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_HSERDYIE); -} - -/** - * @brief Enable PLL ready interrupt - * @rmtoll CIR PLLRDYIE LL_RCC_EnableIT_PLLRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_EnableIT_PLLRDY(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_PLLRDYIE); -} - -#if defined(RCC_PLLI2S_SUPPORT) -/** - * @brief Enable PLLI2S ready interrupt - * @rmtoll CIR PLLI2SRDYIE LL_RCC_EnableIT_PLLI2SRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_EnableIT_PLLI2SRDY(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_PLLI2SRDYIE); -} -#endif /* RCC_PLLI2S_SUPPORT */ - -#if defined(RCC_PLLSAI_SUPPORT) -/** - * @brief Enable PLLSAI ready interrupt - * @rmtoll CIR PLLSAIRDYIE LL_RCC_EnableIT_PLLSAIRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_EnableIT_PLLSAIRDY(void) -{ - SET_BIT(RCC->CIR, RCC_CIR_PLLSAIRDYIE); -} -#endif /* RCC_PLLSAI_SUPPORT */ - -/** - * @brief Disable LSI ready interrupt - * @rmtoll CIR LSIRDYIE LL_RCC_DisableIT_LSIRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_DisableIT_LSIRDY(void) -{ - CLEAR_BIT(RCC->CIR, RCC_CIR_LSIRDYIE); -} - -/** - * @brief Disable LSE ready interrupt - * @rmtoll CIR LSERDYIE LL_RCC_DisableIT_LSERDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_DisableIT_LSERDY(void) -{ - CLEAR_BIT(RCC->CIR, RCC_CIR_LSERDYIE); -} - -/** - * @brief Disable HSI ready interrupt - * @rmtoll CIR HSIRDYIE LL_RCC_DisableIT_HSIRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_DisableIT_HSIRDY(void) -{ - CLEAR_BIT(RCC->CIR, RCC_CIR_HSIRDYIE); -} - -/** - * @brief Disable HSE ready interrupt - * @rmtoll CIR HSERDYIE LL_RCC_DisableIT_HSERDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_DisableIT_HSERDY(void) -{ - CLEAR_BIT(RCC->CIR, RCC_CIR_HSERDYIE); -} - -/** - * @brief Disable PLL ready interrupt - * @rmtoll CIR PLLRDYIE LL_RCC_DisableIT_PLLRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_DisableIT_PLLRDY(void) -{ - CLEAR_BIT(RCC->CIR, RCC_CIR_PLLRDYIE); -} - -#if defined(RCC_PLLI2S_SUPPORT) -/** - * @brief Disable PLLI2S ready interrupt - * @rmtoll CIR PLLI2SRDYIE LL_RCC_DisableIT_PLLI2SRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_DisableIT_PLLI2SRDY(void) -{ - CLEAR_BIT(RCC->CIR, RCC_CIR_PLLI2SRDYIE); -} - -#endif /* RCC_PLLI2S_SUPPORT */ - -#if defined(RCC_PLLSAI_SUPPORT) -/** - * @brief Disable PLLSAI ready interrupt - * @rmtoll CIR PLLSAIRDYIE LL_RCC_DisableIT_PLLSAIRDY - * @retval None - */ -__STATIC_INLINE void LL_RCC_DisableIT_PLLSAIRDY(void) -{ - CLEAR_BIT(RCC->CIR, RCC_CIR_PLLSAIRDYIE); -} -#endif /* RCC_PLLSAI_SUPPORT */ - -/** - * @brief Checks if LSI ready interrupt source is enabled or disabled. - * @rmtoll CIR LSIRDYIE LL_RCC_IsEnabledIT_LSIRDY - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsEnabledIT_LSIRDY(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_LSIRDYIE) == (RCC_CIR_LSIRDYIE)); -} - -/** - * @brief Checks if LSE ready interrupt source is enabled or disabled. - * @rmtoll CIR LSERDYIE LL_RCC_IsEnabledIT_LSERDY - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsEnabledIT_LSERDY(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_LSERDYIE) == (RCC_CIR_LSERDYIE)); -} - -/** - * @brief Checks if HSI ready interrupt source is enabled or disabled. - * @rmtoll CIR HSIRDYIE LL_RCC_IsEnabledIT_HSIRDY - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsEnabledIT_HSIRDY(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_HSIRDYIE) == (RCC_CIR_HSIRDYIE)); -} - -/** - * @brief Checks if HSE ready interrupt source is enabled or disabled. - * @rmtoll CIR HSERDYIE LL_RCC_IsEnabledIT_HSERDY - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsEnabledIT_HSERDY(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_HSERDYIE) == (RCC_CIR_HSERDYIE)); -} - -/** - * @brief Checks if PLL ready interrupt source is enabled or disabled. - * @rmtoll CIR PLLRDYIE LL_RCC_IsEnabledIT_PLLRDY - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsEnabledIT_PLLRDY(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_PLLRDYIE) == (RCC_CIR_PLLRDYIE)); -} - -#if defined(RCC_PLLI2S_SUPPORT) -/** - * @brief Checks if PLLI2S ready interrupt source is enabled or disabled. - * @rmtoll CIR PLLI2SRDYIE LL_RCC_IsEnabledIT_PLLI2SRDY - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsEnabledIT_PLLI2SRDY(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_PLLI2SRDYIE) == (RCC_CIR_PLLI2SRDYIE)); -} - -#endif /* RCC_PLLI2S_SUPPORT */ - -#if defined(RCC_PLLSAI_SUPPORT) -/** - * @brief Checks if PLLSAI ready interrupt source is enabled or disabled. - * @rmtoll CIR PLLSAIRDYIE LL_RCC_IsEnabledIT_PLLSAIRDY - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RCC_IsEnabledIT_PLLSAIRDY(void) -{ - return (READ_BIT(RCC->CIR, RCC_CIR_PLLSAIRDYIE) == (RCC_CIR_PLLSAIRDYIE)); -} -#endif /* RCC_PLLSAI_SUPPORT */ - -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup RCC_LL_EF_Init De-initialization function - * @{ - */ -ErrorStatus LL_RCC_DeInit(void); -/** - * @} - */ - -/** @defgroup RCC_LL_EF_Get_Freq Get system and peripherals clocks frequency functions - * @{ - */ -void LL_RCC_GetSystemClocksFreq(LL_RCC_ClocksTypeDef *RCC_Clocks); -#if defined(FMPI2C1) -uint32_t LL_RCC_GetFMPI2CClockFreq(uint32_t FMPI2CxSource); -#endif /* FMPI2C1 */ -#if defined(LPTIM1) -uint32_t LL_RCC_GetLPTIMClockFreq(uint32_t LPTIMxSource); -#endif /* LPTIM1 */ -#if defined(SAI1) -uint32_t LL_RCC_GetSAIClockFreq(uint32_t SAIxSource); -#endif /* SAI1 */ -#if defined(SDIO) -uint32_t LL_RCC_GetSDIOClockFreq(uint32_t SDIOxSource); -#endif /* SDIO */ -#if defined(RNG) -uint32_t LL_RCC_GetRNGClockFreq(uint32_t RNGxSource); -#endif /* RNG */ -#if defined(USB_OTG_FS) || defined(USB_OTG_HS) -uint32_t LL_RCC_GetUSBClockFreq(uint32_t USBxSource); -#endif /* USB_OTG_FS || USB_OTG_HS */ -#if defined(DFSDM1_Channel0) -uint32_t LL_RCC_GetDFSDMClockFreq(uint32_t DFSDMxSource); -uint32_t LL_RCC_GetDFSDMAudioClockFreq(uint32_t DFSDMxSource); -#endif /* DFSDM1_Channel0 */ -uint32_t LL_RCC_GetI2SClockFreq(uint32_t I2SxSource); -#if defined(CEC) -uint32_t LL_RCC_GetCECClockFreq(uint32_t CECxSource); -#endif /* CEC */ -#if defined(LTDC) -uint32_t LL_RCC_GetLTDCClockFreq(uint32_t LTDCxSource); -#endif /* LTDC */ -#if defined(SPDIFRX) -uint32_t LL_RCC_GetSPDIFRXClockFreq(uint32_t SPDIFRXxSource); -#endif /* SPDIFRX */ -#if defined(DSI) -uint32_t LL_RCC_GetDSIClockFreq(uint32_t DSIxSource); -#endif /* DSI */ -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* defined(RCC) */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_RCC_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_rng.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_rng.h deleted file mode 100644 index c142717..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_rng.h +++ /dev/null @@ -1,337 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_rng.h - * @author MCD Application Team - * @brief Header file of RNG LL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_LL_RNG_H -#define STM32F4xx_LL_RNG_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (RNG) - -/** @defgroup RNG_LL RNG - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/** @defgroup RNG_LL_Exported_Constants RNG Exported Constants - * @{ - */ - - -/** @defgroup RNG_LL_EC_GET_FLAG Get Flags Defines - * @brief Flags defines which can be used with LL_RNG_ReadReg function - * @{ - */ -#define LL_RNG_SR_DRDY RNG_SR_DRDY /*!< Register contains valid random data */ -#define LL_RNG_SR_CECS RNG_SR_CECS /*!< Clock error current status */ -#define LL_RNG_SR_SECS RNG_SR_SECS /*!< Seed error current status */ -#define LL_RNG_SR_CEIS RNG_SR_CEIS /*!< Clock error interrupt status */ -#define LL_RNG_SR_SEIS RNG_SR_SEIS /*!< Seed error interrupt status */ -/** - * @} - */ - -/** @defgroup RNG_LL_EC_IT IT Defines - * @brief IT defines which can be used with LL_RNG_ReadReg and LL_RNG_WriteReg macros - * @{ - */ -#define LL_RNG_CR_IE RNG_CR_IE /*!< RNG Interrupt enable */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup RNG_LL_Exported_Macros RNG Exported Macros - * @{ - */ - -/** @defgroup RNG_LL_EM_WRITE_READ Common Write and read registers Macros - * @{ - */ - -/** - * @brief Write a value in RNG register - * @param __INSTANCE__ RNG Instance - * @param __REG__ Register to be written - * @param __VALUE__ Value to be written in the register - * @retval None - */ -#define LL_RNG_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__)) - -/** - * @brief Read a value in RNG register - * @param __INSTANCE__ RNG Instance - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_RNG_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__) -/** - * @} - */ - -/** - * @} - */ - - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup RNG_LL_Exported_Functions RNG Exported Functions - * @{ - */ -/** @defgroup RNG_LL_EF_Configuration RNG Configuration functions - * @{ - */ - -/** - * @brief Enable Random Number Generation - * @rmtoll CR RNGEN LL_RNG_Enable - * @param RNGx RNG Instance - * @retval None - */ -__STATIC_INLINE void LL_RNG_Enable(RNG_TypeDef *RNGx) -{ - SET_BIT(RNGx->CR, RNG_CR_RNGEN); -} - -/** - * @brief Disable Random Number Generation - * @rmtoll CR RNGEN LL_RNG_Disable - * @param RNGx RNG Instance - * @retval None - */ -__STATIC_INLINE void LL_RNG_Disable(RNG_TypeDef *RNGx) -{ - CLEAR_BIT(RNGx->CR, RNG_CR_RNGEN); -} - -/** - * @brief Check if Random Number Generator is enabled - * @rmtoll CR RNGEN LL_RNG_IsEnabled - * @param RNGx RNG Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RNG_IsEnabled(RNG_TypeDef *RNGx) -{ - return ((READ_BIT(RNGx->CR, RNG_CR_RNGEN) == (RNG_CR_RNGEN)) ? 1UL : 0UL); -} - -/** - * @} - */ - -/** @defgroup RNG_LL_EF_FLAG_Management FLAG Management - * @{ - */ - -/** - * @brief Indicate if the RNG Data ready Flag is set or not - * @rmtoll SR DRDY LL_RNG_IsActiveFlag_DRDY - * @param RNGx RNG Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RNG_IsActiveFlag_DRDY(RNG_TypeDef *RNGx) -{ - return ((READ_BIT(RNGx->SR, RNG_SR_DRDY) == (RNG_SR_DRDY)) ? 1UL : 0UL); -} - -/** - * @brief Indicate if the Clock Error Current Status Flag is set or not - * @rmtoll SR CECS LL_RNG_IsActiveFlag_CECS - * @param RNGx RNG Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RNG_IsActiveFlag_CECS(RNG_TypeDef *RNGx) -{ - return ((READ_BIT(RNGx->SR, RNG_SR_CECS) == (RNG_SR_CECS)) ? 1UL : 0UL); -} - -/** - * @brief Indicate if the Seed Error Current Status Flag is set or not - * @rmtoll SR SECS LL_RNG_IsActiveFlag_SECS - * @param RNGx RNG Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RNG_IsActiveFlag_SECS(RNG_TypeDef *RNGx) -{ - return ((READ_BIT(RNGx->SR, RNG_SR_SECS) == (RNG_SR_SECS)) ? 1UL : 0UL); -} - -/** - * @brief Indicate if the Clock Error Interrupt Status Flag is set or not - * @rmtoll SR CEIS LL_RNG_IsActiveFlag_CEIS - * @param RNGx RNG Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RNG_IsActiveFlag_CEIS(RNG_TypeDef *RNGx) -{ - return ((READ_BIT(RNGx->SR, RNG_SR_CEIS) == (RNG_SR_CEIS)) ? 1UL : 0UL); -} - -/** - * @brief Indicate if the Seed Error Interrupt Status Flag is set or not - * @rmtoll SR SEIS LL_RNG_IsActiveFlag_SEIS - * @param RNGx RNG Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RNG_IsActiveFlag_SEIS(RNG_TypeDef *RNGx) -{ - return ((READ_BIT(RNGx->SR, RNG_SR_SEIS) == (RNG_SR_SEIS)) ? 1UL : 0UL); -} - -/** - * @brief Clear Clock Error interrupt Status (CEIS) Flag - * @rmtoll SR CEIS LL_RNG_ClearFlag_CEIS - * @param RNGx RNG Instance - * @retval None - */ -__STATIC_INLINE void LL_RNG_ClearFlag_CEIS(RNG_TypeDef *RNGx) -{ - WRITE_REG(RNGx->SR, ~RNG_SR_CEIS); -} - -/** - * @brief Clear Seed Error interrupt Status (SEIS) Flag - * @rmtoll SR SEIS LL_RNG_ClearFlag_SEIS - * @param RNGx RNG Instance - * @retval None - */ -__STATIC_INLINE void LL_RNG_ClearFlag_SEIS(RNG_TypeDef *RNGx) -{ - WRITE_REG(RNGx->SR, ~RNG_SR_SEIS); -} - -/** - * @} - */ - -/** @defgroup RNG_LL_EF_IT_Management IT Management - * @{ - */ - -/** - * @brief Enable Random Number Generator Interrupt - * (applies for either Seed error, Clock Error or Data ready interrupts) - * @rmtoll CR IE LL_RNG_EnableIT - * @param RNGx RNG Instance - * @retval None - */ -__STATIC_INLINE void LL_RNG_EnableIT(RNG_TypeDef *RNGx) -{ - SET_BIT(RNGx->CR, RNG_CR_IE); -} - -/** - * @brief Disable Random Number Generator Interrupt - * (applies for either Seed error, Clock Error or Data ready interrupts) - * @rmtoll CR IE LL_RNG_DisableIT - * @param RNGx RNG Instance - * @retval None - */ -__STATIC_INLINE void LL_RNG_DisableIT(RNG_TypeDef *RNGx) -{ - CLEAR_BIT(RNGx->CR, RNG_CR_IE); -} - -/** - * @brief Check if Random Number Generator Interrupt is enabled - * (applies for either Seed error, Clock Error or Data ready interrupts) - * @rmtoll CR IE LL_RNG_IsEnabledIT - * @param RNGx RNG Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RNG_IsEnabledIT(RNG_TypeDef *RNGx) -{ - return ((READ_BIT(RNGx->CR, RNG_CR_IE) == (RNG_CR_IE)) ? 1UL : 0UL); -} - -/** - * @} - */ - -/** @defgroup RNG_LL_EF_Data_Management Data Management - * @{ - */ - -/** - * @brief Return32-bit Random Number value - * @rmtoll DR RNDATA LL_RNG_ReadRandData32 - * @param RNGx RNG Instance - * @retval Generated 32-bit random value - */ -__STATIC_INLINE uint32_t LL_RNG_ReadRandData32(RNG_TypeDef *RNGx) -{ - return (uint32_t)(READ_REG(RNGx->DR)); -} - -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup RNG_LL_EF_Init Initialization and de-initialization functions - * @{ - */ -ErrorStatus LL_RNG_DeInit(RNG_TypeDef *RNGx); - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* RNG */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_RNG_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_rtc.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_rtc.h deleted file mode 100644 index 1f57ce4..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_rtc.h +++ /dev/null @@ -1,3793 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_rtc.h - * @author MCD Application Team - * @brief Header file of RTC LL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_LL_RTC_H -#define __STM32F4xx_LL_RTC_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined(RTC) - -/** @defgroup RTC_LL RTC - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup RTC_LL_Private_Constants RTC Private Constants - * @{ - */ -/* Masks Definition */ -#define RTC_INIT_MASK 0xFFFFFFFFU -#define RTC_RSF_MASK 0xFFFFFF5FU - -/* Write protection defines */ -#define RTC_WRITE_PROTECTION_DISABLE ((uint8_t)0xFFU) -#define RTC_WRITE_PROTECTION_ENABLE_1 ((uint8_t)0xCAU) -#define RTC_WRITE_PROTECTION_ENABLE_2 ((uint8_t)0x53U) - -/* Defines used to combine date & time */ -#define RTC_OFFSET_WEEKDAY 24U -#define RTC_OFFSET_DAY 16U -#define RTC_OFFSET_MONTH 8U -#define RTC_OFFSET_HOUR 16U -#define RTC_OFFSET_MINUTE 8U - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup RTC_LL_Private_Macros RTC Private Macros - * @{ - */ -/** - * @} - */ -#endif /*USE_FULL_LL_DRIVER*/ - -/* Exported types ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup RTC_LL_ES_INIT RTC Exported Init structure - * @{ - */ - -/** - * @brief RTC Init structures definition - */ -typedef struct -{ - uint32_t HourFormat; /*!< Specifies the RTC Hours Format. - This parameter can be a value of @ref RTC_LL_EC_HOURFORMAT - - This feature can be modified afterwards using unitary function - @ref LL_RTC_SetHourFormat(). */ - - uint32_t AsynchPrescaler; /*!< Specifies the RTC Asynchronous Predivider value. - This parameter must be a number between Min_Data = 0x00 and Max_Data = 0x7F - - This feature can be modified afterwards using unitary function - @ref LL_RTC_SetAsynchPrescaler(). */ - - uint32_t SynchPrescaler; /*!< Specifies the RTC Synchronous Predivider value. - This parameter must be a number between Min_Data = 0x00 and Max_Data = 0x7FFF - - This feature can be modified afterwards using unitary function - @ref LL_RTC_SetSynchPrescaler(). */ -} LL_RTC_InitTypeDef; - -/** - * @brief RTC Time structure definition - */ -typedef struct -{ - uint32_t TimeFormat; /*!< Specifies the RTC AM/PM Time. - This parameter can be a value of @ref RTC_LL_EC_TIME_FORMAT - - This feature can be modified afterwards using unitary function @ref LL_RTC_TIME_SetFormat(). */ - - uint8_t Hours; /*!< Specifies the RTC Time Hours. - This parameter must be a number between Min_Data = 0 and Max_Data = 12 if the @ref LL_RTC_TIME_FORMAT_PM is selected. - This parameter must be a number between Min_Data = 0 and Max_Data = 23 if the @ref LL_RTC_TIME_FORMAT_AM_OR_24 is selected. - - This feature can be modified afterwards using unitary function @ref LL_RTC_TIME_SetHour(). */ - - uint8_t Minutes; /*!< Specifies the RTC Time Minutes. - This parameter must be a number between Min_Data = 0 and Max_Data = 59 - - This feature can be modified afterwards using unitary function @ref LL_RTC_TIME_SetMinute(). */ - - uint8_t Seconds; /*!< Specifies the RTC Time Seconds. - This parameter must be a number between Min_Data = 0 and Max_Data = 59 - - This feature can be modified afterwards using unitary function @ref LL_RTC_TIME_SetSecond(). */ -} LL_RTC_TimeTypeDef; - -/** - * @brief RTC Date structure definition - */ -typedef struct -{ - uint8_t WeekDay; /*!< Specifies the RTC Date WeekDay. - This parameter can be a value of @ref RTC_LL_EC_WEEKDAY - - This feature can be modified afterwards using unitary function @ref LL_RTC_DATE_SetWeekDay(). */ - - uint8_t Month; /*!< Specifies the RTC Date Month. - This parameter can be a value of @ref RTC_LL_EC_MONTH - - This feature can be modified afterwards using unitary function @ref LL_RTC_DATE_SetMonth(). */ - - uint8_t Day; /*!< Specifies the RTC Date Day. - This parameter must be a number between Min_Data = 1 and Max_Data = 31 - - This feature can be modified afterwards using unitary function @ref LL_RTC_DATE_SetDay(). */ - - uint8_t Year; /*!< Specifies the RTC Date Year. - This parameter must be a number between Min_Data = 0 and Max_Data = 99 - - This feature can be modified afterwards using unitary function @ref LL_RTC_DATE_SetYear(). */ -} LL_RTC_DateTypeDef; - -/** - * @brief RTC Alarm structure definition - */ -typedef struct -{ - LL_RTC_TimeTypeDef AlarmTime; /*!< Specifies the RTC Alarm Time members. */ - - uint32_t AlarmMask; /*!< Specifies the RTC Alarm Masks. - This parameter can be a value of @ref RTC_LL_EC_ALMA_MASK for ALARM A or @ref RTC_LL_EC_ALMB_MASK for ALARM B. - - This feature can be modified afterwards using unitary function @ref LL_RTC_ALMA_SetMask() for ALARM A - or @ref LL_RTC_ALMB_SetMask() for ALARM B - */ - - uint32_t AlarmDateWeekDaySel; /*!< Specifies the RTC Alarm is on day or WeekDay. - This parameter can be a value of @ref RTC_LL_EC_ALMA_WEEKDAY_SELECTION for ALARM A or @ref RTC_LL_EC_ALMB_WEEKDAY_SELECTION for ALARM B - - This feature can be modified afterwards using unitary function @ref LL_RTC_ALMA_EnableWeekday() or @ref LL_RTC_ALMA_DisableWeekday() - for ALARM A or @ref LL_RTC_ALMB_EnableWeekday() or @ref LL_RTC_ALMB_DisableWeekday() for ALARM B - */ - - uint8_t AlarmDateWeekDay; /*!< Specifies the RTC Alarm Day/WeekDay. - If AlarmDateWeekDaySel set to day, this parameter must be a number between Min_Data = 1 and Max_Data = 31. - - This feature can be modified afterwards using unitary function @ref LL_RTC_ALMA_SetDay() - for ALARM A or @ref LL_RTC_ALMB_SetDay() for ALARM B. - - If AlarmDateWeekDaySel set to Weekday, this parameter can be a value of @ref RTC_LL_EC_WEEKDAY. - - This feature can be modified afterwards using unitary function @ref LL_RTC_ALMA_SetWeekDay() - for ALARM A or @ref LL_RTC_ALMB_SetWeekDay() for ALARM B. - */ -} LL_RTC_AlarmTypeDef; - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup RTC_LL_Exported_Constants RTC Exported Constants - * @{ - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup RTC_LL_EC_FORMAT FORMAT - * @{ - */ -#define LL_RTC_FORMAT_BIN 0x000000000U /*!< Binary data format */ -#define LL_RTC_FORMAT_BCD 0x000000001U /*!< BCD data format */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_ALMA_WEEKDAY_SELECTION RTC Alarm A Date WeekDay - * @{ - */ -#define LL_RTC_ALMA_DATEWEEKDAYSEL_DATE 0x00000000U /*!< Alarm A Date is selected */ -#define LL_RTC_ALMA_DATEWEEKDAYSEL_WEEKDAY RTC_ALRMAR_WDSEL /*!< Alarm A WeekDay is selected */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_ALMB_WEEKDAY_SELECTION RTC Alarm B Date WeekDay - * @{ - */ -#define LL_RTC_ALMB_DATEWEEKDAYSEL_DATE 0x00000000U /*!< Alarm B Date is selected */ -#define LL_RTC_ALMB_DATEWEEKDAYSEL_WEEKDAY RTC_ALRMBR_WDSEL /*!< Alarm B WeekDay is selected */ -/** - * @} - */ - -#endif /* USE_FULL_LL_DRIVER */ - -/** @defgroup RTC_LL_EC_GET_FLAG Get Flags Defines - * @brief Flags defines which can be used with LL_RTC_ReadReg function - * @{ - */ -#define LL_RTC_ISR_RECALPF RTC_ISR_RECALPF -#define LL_RTC_ISR_TAMP3F RTC_ISR_TAMP3F -#define LL_RTC_ISR_TAMP2F RTC_ISR_TAMP2F -#define LL_RTC_ISR_TAMP1F RTC_ISR_TAMP1F -#define LL_RTC_ISR_TSOVF RTC_ISR_TSOVF -#define LL_RTC_ISR_TSF RTC_ISR_TSF -#define LL_RTC_ISR_WUTF RTC_ISR_WUTF -#define LL_RTC_ISR_ALRBF RTC_ISR_ALRBF -#define LL_RTC_ISR_ALRAF RTC_ISR_ALRAF -#define LL_RTC_ISR_INITF RTC_ISR_INITF -#define LL_RTC_ISR_RSF RTC_ISR_RSF -#define LL_RTC_ISR_INITS RTC_ISR_INITS -#define LL_RTC_ISR_SHPF RTC_ISR_SHPF -#define LL_RTC_ISR_WUTWF RTC_ISR_WUTWF -#define LL_RTC_ISR_ALRBWF RTC_ISR_ALRBWF -#define LL_RTC_ISR_ALRAWF RTC_ISR_ALRAWF -/** - * @} - */ - -/** @defgroup RTC_LL_EC_IT IT Defines - * @brief IT defines which can be used with LL_RTC_ReadReg and LL_RTC_WriteReg functions - * @{ - */ -#define LL_RTC_CR_TSIE RTC_CR_TSIE -#define LL_RTC_CR_WUTIE RTC_CR_WUTIE -#define LL_RTC_CR_ALRBIE RTC_CR_ALRBIE -#define LL_RTC_CR_ALRAIE RTC_CR_ALRAIE -#define LL_RTC_TAFCR_TAMPIE RTC_TAFCR_TAMPIE -/** - * @} - */ - -/** @defgroup RTC_LL_EC_WEEKDAY WEEK DAY - * @{ - */ -#define LL_RTC_WEEKDAY_MONDAY ((uint8_t)0x01U) /*!< Monday */ -#define LL_RTC_WEEKDAY_TUESDAY ((uint8_t)0x02U) /*!< Tuesday */ -#define LL_RTC_WEEKDAY_WEDNESDAY ((uint8_t)0x03U) /*!< Wednesday */ -#define LL_RTC_WEEKDAY_THURSDAY ((uint8_t)0x04U) /*!< Thrusday */ -#define LL_RTC_WEEKDAY_FRIDAY ((uint8_t)0x05U) /*!< Friday */ -#define LL_RTC_WEEKDAY_SATURDAY ((uint8_t)0x06U) /*!< Saturday */ -#define LL_RTC_WEEKDAY_SUNDAY ((uint8_t)0x07U) /*!< Sunday */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_MONTH MONTH - * @{ - */ -#define LL_RTC_MONTH_JANUARY ((uint8_t)0x01U) /*!< January */ -#define LL_RTC_MONTH_FEBRUARY ((uint8_t)0x02U) /*!< February */ -#define LL_RTC_MONTH_MARCH ((uint8_t)0x03U) /*!< March */ -#define LL_RTC_MONTH_APRIL ((uint8_t)0x04U) /*!< April */ -#define LL_RTC_MONTH_MAY ((uint8_t)0x05U) /*!< May */ -#define LL_RTC_MONTH_JUNE ((uint8_t)0x06U) /*!< June */ -#define LL_RTC_MONTH_JULY ((uint8_t)0x07U) /*!< July */ -#define LL_RTC_MONTH_AUGUST ((uint8_t)0x08U) /*!< August */ -#define LL_RTC_MONTH_SEPTEMBER ((uint8_t)0x09U) /*!< September */ -#define LL_RTC_MONTH_OCTOBER ((uint8_t)0x10U) /*!< October */ -#define LL_RTC_MONTH_NOVEMBER ((uint8_t)0x11U) /*!< November */ -#define LL_RTC_MONTH_DECEMBER ((uint8_t)0x12U) /*!< December */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_HOURFORMAT HOUR FORMAT - * @{ - */ -#define LL_RTC_HOURFORMAT_24HOUR 0x00000000U /*!< 24 hour/day format */ -#define LL_RTC_HOURFORMAT_AMPM RTC_CR_FMT /*!< AM/PM hour format */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_ALARMOUT ALARM OUTPUT - * @{ - */ -#define LL_RTC_ALARMOUT_DISABLE 0x00000000U /*!< Output disabled */ -#define LL_RTC_ALARMOUT_ALMA RTC_CR_OSEL_0 /*!< Alarm A output enabled */ -#define LL_RTC_ALARMOUT_ALMB RTC_CR_OSEL_1 /*!< Alarm B output enabled */ -#define LL_RTC_ALARMOUT_WAKEUP RTC_CR_OSEL /*!< Wakeup output enabled */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_ALARM_OUTPUTTYPE ALARM OUTPUT TYPE - * @{ - */ -#define LL_RTC_ALARM_OUTPUTTYPE_OPENDRAIN 0x00000000U /*!< RTC_ALARM, when mapped on PC13, is open-drain output */ -#define LL_RTC_ALARM_OUTPUTTYPE_PUSHPULL RTC_TAFCR_ALARMOUTTYPE /*!< RTC_ALARM, when mapped on PC13, is push-pull output */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_PIN PIN - * @{ - */ -#define LL_RTC_PIN_PC13 RTC_TAFCR_PC13MODE /*!< PC13 is forced to push-pull output if all RTC alternate functions are disabled */ -#define LL_RTC_PIN_PC14 RTC_TAFCR_PC14MODE /*!< PC14 is forced to push-pull output if LSE is disabled */ -#define LL_RTC_PIN_PC15 RTC_TAFCR_PC15MODE /*!< PC15 is forced to push-pull output if LSE is disabled */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_OUTPUTPOLARITY_PIN OUTPUT POLARITY PIN - * @{ - */ -#define LL_RTC_OUTPUTPOLARITY_PIN_HIGH 0x00000000U /*!< Pin is high when ALRAF/ALRBF/WUTF is asserted (depending on OSEL)*/ -#define LL_RTC_OUTPUTPOLARITY_PIN_LOW RTC_CR_POL /*!< Pin is low when ALRAF/ALRBF/WUTF is asserted (depending on OSEL) */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_TIME_FORMAT TIME FORMAT - * @{ - */ -#define LL_RTC_TIME_FORMAT_AM_OR_24 0x00000000U /*!< AM or 24-hour format */ -#define LL_RTC_TIME_FORMAT_PM RTC_TR_PM /*!< PM */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_SHIFT_SECOND SHIFT SECOND - * @{ - */ -#define LL_RTC_SHIFT_SECOND_DELAY 0x00000000U /* Delay (seconds) = SUBFS / (PREDIV_S + 1) */ -#define LL_RTC_SHIFT_SECOND_ADVANCE RTC_SHIFTR_ADD1S /* Advance (seconds) = (1 - (SUBFS / (PREDIV_S + 1))) */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_ALMA_MASK ALARMA MASK - * @{ - */ -#define LL_RTC_ALMA_MASK_NONE 0x00000000U /*!< No masks applied on Alarm A*/ -#define LL_RTC_ALMA_MASK_DATEWEEKDAY RTC_ALRMAR_MSK4 /*!< Date/day do not care in Alarm A comparison */ -#define LL_RTC_ALMA_MASK_HOURS RTC_ALRMAR_MSK3 /*!< Hours do not care in Alarm A comparison */ -#define LL_RTC_ALMA_MASK_MINUTES RTC_ALRMAR_MSK2 /*!< Minutes do not care in Alarm A comparison */ -#define LL_RTC_ALMA_MASK_SECONDS RTC_ALRMAR_MSK1 /*!< Seconds do not care in Alarm A comparison */ -#define LL_RTC_ALMA_MASK_ALL (RTC_ALRMAR_MSK4 | RTC_ALRMAR_MSK3 | RTC_ALRMAR_MSK2 | RTC_ALRMAR_MSK1) /*!< Masks all */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_ALMA_TIME_FORMAT ALARMA TIME FORMAT - * @{ - */ -#define LL_RTC_ALMA_TIME_FORMAT_AM 0x00000000U /*!< AM or 24-hour format */ -#define LL_RTC_ALMA_TIME_FORMAT_PM RTC_ALRMAR_PM /*!< PM */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_ALMB_MASK ALARMB MASK - * @{ - */ -#define LL_RTC_ALMB_MASK_NONE 0x00000000U /*!< No masks applied on Alarm B*/ -#define LL_RTC_ALMB_MASK_DATEWEEKDAY RTC_ALRMBR_MSK4 /*!< Date/day do not care in Alarm B comparison */ -#define LL_RTC_ALMB_MASK_HOURS RTC_ALRMBR_MSK3 /*!< Hours do not care in Alarm B comparison */ -#define LL_RTC_ALMB_MASK_MINUTES RTC_ALRMBR_MSK2 /*!< Minutes do not care in Alarm B comparison */ -#define LL_RTC_ALMB_MASK_SECONDS RTC_ALRMBR_MSK1 /*!< Seconds do not care in Alarm B comparison */ -#define LL_RTC_ALMB_MASK_ALL (RTC_ALRMBR_MSK4 | RTC_ALRMBR_MSK3 | RTC_ALRMBR_MSK2 | RTC_ALRMBR_MSK1) /*!< Masks all */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_ALMB_TIME_FORMAT ALARMB TIME FORMAT - * @{ - */ -#define LL_RTC_ALMB_TIME_FORMAT_AM 0x00000000U /*!< AM or 24-hour format */ -#define LL_RTC_ALMB_TIME_FORMAT_PM RTC_ALRMBR_PM /*!< PM */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_TIMESTAMP_EDGE TIMESTAMP EDGE - * @{ - */ -#define LL_RTC_TIMESTAMP_EDGE_RISING 0x00000000U /*!< RTC_TS input rising edge generates a time-stamp event */ -#define LL_RTC_TIMESTAMP_EDGE_FALLING RTC_CR_TSEDGE /*!< RTC_TS input falling edge generates a time-stamp even */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_TS_TIME_FORMAT TIMESTAMP TIME FORMAT - * @{ - */ -#define LL_RTC_TS_TIME_FORMAT_AM 0x00000000U /*!< AM or 24-hour format */ -#define LL_RTC_TS_TIME_FORMAT_PM RTC_TSTR_PM /*!< PM */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_TAMPER TAMPER - * @{ - */ -#define LL_RTC_TAMPER_1 RTC_TAFCR_TAMP1E /*!< RTC_TAMP1 input detection */ -#if defined(RTC_TAMPER2_SUPPORT) -#define LL_RTC_TAMPER_2 RTC_TAFCR_TAMP2E /*!< RTC_TAMP2 input detection */ -#endif /* RTC_TAMPER2_SUPPORT */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_TAMPER_MASK TAMPER MASK - * @{ - */ -#define LL_RTC_TAMPER_MASK_TAMPER1 RTC_TAFCR_TAMP1MF /*!< Tamper 1 event generates a trigger event. TAMP1F is masked and internally cleared by hardware.The backup registers are not erased */ -#if defined(RTC_TAMPER2_SUPPORT) -#define LL_RTC_TAMPER_MASK_TAMPER2 RTC_TAFCR_TAMP2MF /*!< Tamper 2 event generates a trigger event. TAMP2F is masked and internally cleared by hardware. The backup registers are not erased. */ -#endif /* RTC_TAMPER2_SUPPORT */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_TAMPER_NOERASE TAMPER NO ERASE - * @{ - */ -#define LL_RTC_TAMPER_NOERASE_TAMPER1 RTC_TAFCR_TAMP1NOERASE /*!< Tamper 1 event does not erase the backup registers. */ -#if defined(RTC_TAMPER2_SUPPORT) -#define LL_RTC_TAMPER_NOERASE_TAMPER2 RTC_TAFCR_TAMP2NOERASE /*!< Tamper 2 event does not erase the backup registers. */ -#endif /* RTC_TAMPER2_SUPPORT */ -/** - * @} - */ - -#if defined(RTC_TAFCR_TAMPPRCH) -/** @defgroup RTC_LL_EC_TAMPER_DURATION TAMPER DURATION - * @{ - */ -#define LL_RTC_TAMPER_DURATION_1RTCCLK 0x00000000U /*!< Tamper pins are pre-charged before sampling during 1 RTCCLK cycle */ -#define LL_RTC_TAMPER_DURATION_2RTCCLK RTC_TAFCR_TAMPPRCH_0 /*!< Tamper pins are pre-charged before sampling during 2 RTCCLK cycles */ -#define LL_RTC_TAMPER_DURATION_4RTCCLK RTC_TAFCR_TAMPPRCH_1 /*!< Tamper pins are pre-charged before sampling during 4 RTCCLK cycles */ -#define LL_RTC_TAMPER_DURATION_8RTCCLK RTC_TAFCR_TAMPPRCH /*!< Tamper pins are pre-charged before sampling during 8 RTCCLK cycles */ -/** - * @} - */ -#endif /* RTC_TAFCR_TAMPPRCH */ - -#if defined(RTC_TAFCR_TAMPFLT) -/** @defgroup RTC_LL_EC_TAMPER_FILTER TAMPER FILTER - * @{ - */ -#define LL_RTC_TAMPER_FILTER_DISABLE 0x00000000U /*!< Tamper filter is disabled */ -#define LL_RTC_TAMPER_FILTER_2SAMPLE RTC_TAFCR_TAMPFLT_0 /*!< Tamper is activated after 2 consecutive samples at the active level */ -#define LL_RTC_TAMPER_FILTER_4SAMPLE RTC_TAFCR_TAMPFLT_1 /*!< Tamper is activated after 4 consecutive samples at the active level */ -#define LL_RTC_TAMPER_FILTER_8SAMPLE RTC_TAFCR_TAMPFLT /*!< Tamper is activated after 8 consecutive samples at the active level. */ -/** - * @} - */ -#endif /* RTC_TAFCR_TAMPFLT */ - -#if defined(RTC_TAFCR_TAMPFREQ) -/** @defgroup RTC_LL_EC_TAMPER_SAMPLFREQDIV TAMPER SAMPLING FREQUENCY DIVIDER - * @{ - */ -#define LL_RTC_TAMPER_SAMPLFREQDIV_32768 0x00000000U /*!< Each of the tamper inputs are sampled with a frequency = RTCCLK / 32768 */ -#define LL_RTC_TAMPER_SAMPLFREQDIV_16384 RTC_TAFCR_TAMPFREQ_0 /*!< Each of the tamper inputs are sampled with a frequency = RTCCLK / 16384 */ -#define LL_RTC_TAMPER_SAMPLFREQDIV_8192 RTC_TAFCR_TAMPFREQ_1 /*!< Each of the tamper inputs are sampled with a frequency = RTCCLK / 8192 */ -#define LL_RTC_TAMPER_SAMPLFREQDIV_4096 (RTC_TAFCR_TAMPFREQ_1 | RTC_TAFCR_TAMPFREQ_0) /*!< Each of the tamper inputs are sampled with a frequency = RTCCLK / 4096 */ -#define LL_RTC_TAMPER_SAMPLFREQDIV_2048 RTC_TAFCR_TAMPFREQ_2 /*!< Each of the tamper inputs are sampled with a frequency = RTCCLK / 2048 */ -#define LL_RTC_TAMPER_SAMPLFREQDIV_1024 (RTC_TAFCR_TAMPFREQ_2 | RTC_TAFCR_TAMPFREQ_0) /*!< Each of the tamper inputs are sampled with a frequency = RTCCLK / 1024 */ -#define LL_RTC_TAMPER_SAMPLFREQDIV_512 (RTC_TAFCR_TAMPFREQ_2 | RTC_TAFCR_TAMPFREQ_1) /*!< Each of the tamper inputs are sampled with a frequency = RTCCLK / 512 */ -#define LL_RTC_TAMPER_SAMPLFREQDIV_256 RTC_TAFCR_TAMPFREQ /*!< Each of the tamper inputs are sampled with a frequency = RTCCLK / 256 */ -/** - * @} - */ -#endif /* RTC_TAFCR_TAMPFREQ */ - -/** @defgroup RTC_LL_EC_TAMPER_ACTIVELEVEL TAMPER ACTIVE LEVEL - * @{ - */ -#define LL_RTC_TAMPER_ACTIVELEVEL_TAMP1 RTC_TAFCR_TAMP1TRG /*!< RTC_TAMP1 input falling edge (if TAMPFLT = 00) or staying high (if TAMPFLT != 00) triggers a tamper detection event*/ -#if defined(RTC_TAMPER2_SUPPORT) -#define LL_RTC_TAMPER_ACTIVELEVEL_TAMP2 RTC_TAFCR_TAMP2TRG /*!< RTC_TAMP2 input falling edge (if TAMPFLT = 00) or staying high (if TAMPFLT != 00) triggers a tamper detection event*/ -#endif /* RTC_TAMPER2_SUPPORT */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_WAKEUPCLOCK_DIV WAKEUP CLOCK DIV - * @{ - */ -#define LL_RTC_WAKEUPCLOCK_DIV_16 0x00000000U /*!< RTC/16 clock is selected */ -#define LL_RTC_WAKEUPCLOCK_DIV_8 (RTC_CR_WUCKSEL_0) /*!< RTC/8 clock is selected */ -#define LL_RTC_WAKEUPCLOCK_DIV_4 (RTC_CR_WUCKSEL_1) /*!< RTC/4 clock is selected */ -#define LL_RTC_WAKEUPCLOCK_DIV_2 (RTC_CR_WUCKSEL_1 | RTC_CR_WUCKSEL_0) /*!< RTC/2 clock is selected */ -#define LL_RTC_WAKEUPCLOCK_CKSPRE (RTC_CR_WUCKSEL_2) /*!< ck_spre (usually 1 Hz) clock is selected */ -#define LL_RTC_WAKEUPCLOCK_CKSPRE_WUT (RTC_CR_WUCKSEL_2 | RTC_CR_WUCKSEL_1) /*!< ck_spre (usually 1 Hz) clock is selected and 2exp16 is added to the WUT counter value*/ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_BKP BACKUP - * @{ - */ -#define LL_RTC_BKP_DR0 0x00000000U -#define LL_RTC_BKP_DR1 0x00000001U -#define LL_RTC_BKP_DR2 0x00000002U -#define LL_RTC_BKP_DR3 0x00000003U -#define LL_RTC_BKP_DR4 0x00000004U -#if RTC_BKP_NUMBER > 5 -#define LL_RTC_BKP_DR5 0x00000005U -#define LL_RTC_BKP_DR6 0x00000006U -#define LL_RTC_BKP_DR7 0x00000007U -#define LL_RTC_BKP_DR8 0x00000008U -#define LL_RTC_BKP_DR9 0x00000009U -#define LL_RTC_BKP_DR10 0x0000000AU -#define LL_RTC_BKP_DR11 0x0000000BU -#define LL_RTC_BKP_DR12 0x0000000CU -#define LL_RTC_BKP_DR13 0x0000000DU -#define LL_RTC_BKP_DR14 0x0000000EU -#define LL_RTC_BKP_DR15 0x0000000FU -#endif /* RTC_BKP_NUMBER > 5 */ - -#if RTC_BKP_NUMBER > 16 -#define LL_RTC_BKP_DR16 0x00000010U -#define LL_RTC_BKP_DR17 0x00000011U -#define LL_RTC_BKP_DR18 0x00000012U -#define LL_RTC_BKP_DR19 0x00000013U -#endif /* RTC_BKP_NUMBER > 16 */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_CALIB_OUTPUT Calibration output - * @{ - */ -#define LL_RTC_CALIB_OUTPUT_NONE 0x00000000U /*!< Calibration output disabled */ -#define LL_RTC_CALIB_OUTPUT_1HZ (RTC_CR_COE | RTC_CR_COSEL) /*!< Calibration output is 1 Hz */ -#define LL_RTC_CALIB_OUTPUT_512HZ (RTC_CR_COE) /*!< Calibration output is 512 Hz */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_CALIB_SIGN Coarse digital calibration sign - * @{ - */ -#define LL_RTC_CALIB_SIGN_POSITIVE 0x00000000U /*!< Positive calibration: calendar update frequency is increased */ -#define LL_RTC_CALIB_SIGN_NEGATIVE RTC_CALIBR_DCS /*!< Negative calibration: calendar update frequency is decreased */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_CALIB_INSERTPULSE Calibration pulse insertion - * @{ - */ -#define LL_RTC_CALIB_INSERTPULSE_NONE 0x00000000U /*!< No RTCCLK pulses are added */ -#define LL_RTC_CALIB_INSERTPULSE_SET RTC_CALR_CALP /*!< One RTCCLK pulse is effectively inserted every 2exp11 pulses (frequency increased by 488.5 ppm) */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_CALIB_PERIOD Calibration period - * @{ - */ -#define LL_RTC_CALIB_PERIOD_32SEC 0x00000000U /*!< Use a 32-second calibration cycle period */ -#define LL_RTC_CALIB_PERIOD_16SEC RTC_CALR_CALW16 /*!< Use a 16-second calibration cycle period */ -#define LL_RTC_CALIB_PERIOD_8SEC RTC_CALR_CALW8 /*!< Use a 8-second calibration cycle period */ -/** - * @} - */ - -/** @defgroup RTC_LL_EC_TSINSEL TIMESTAMP mapping - * @{ - */ -#define LL_RTC_TimeStampPin_Default 0x00000000U /*!< Use RTC_AF1 as TIMESTAMP */ -#if defined(RTC_AF2_SUPPORT) -#define LL_RTC_TimeStampPin_Pos1 RTC_TAFCR_TSINSEL /*!< Use RTC_AF2 as TIMESTAMP */ -#endif -/** - * @} - */ - -/** @defgroup RTC_LL_EC_TAMP1INSEL TAMPER1 mapping - * @{ - */ -#define LL_RTC_TamperPin_Default 0x00000000U /*!< Use RTC_AF1 as TAMPER1 */ -#if defined(RTC_AF2_SUPPORT) -#define LL_RTC_TamperPin_Pos1 RTC_TAFCR_TAMP1INSEL /*!< Use RTC_AF2 as TAMPER1 */ -#endif -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup RTC_LL_Exported_Macros RTC Exported Macros - * @{ - */ - -/** @defgroup RTC_LL_EM_WRITE_READ Common Write and read registers Macros - * @{ - */ - -/** - * @brief Write a value in RTC register - * @param __INSTANCE__ RTC Instance - * @param __REG__ Register to be written - * @param __VALUE__ Value to be written in the register - * @retval None - */ -#define LL_RTC_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__)) - -/** - * @brief Read a value in RTC register - * @param __INSTANCE__ RTC Instance - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_RTC_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__) -/** - * @} - */ - -/** @defgroup RTC_LL_EM_Convert Convert helper Macros - * @{ - */ - -/** - * @brief Helper macro to convert a value from 2 digit decimal format to BCD format - * @param __VALUE__ Byte to be converted - * @retval Converted byte - */ -#define __LL_RTC_CONVERT_BIN2BCD(__VALUE__) (uint8_t)((((__VALUE__) / 10U) << 4U) | ((__VALUE__) % 10U)) - -/** - * @brief Helper macro to convert a value from BCD format to 2 digit decimal format - * @param __VALUE__ BCD value to be converted - * @retval Converted byte - */ -#define __LL_RTC_CONVERT_BCD2BIN(__VALUE__) (uint8_t)(((uint8_t)((__VALUE__) & (uint8_t)0xF0U) >> (uint8_t)0x4U) * 10U + ((__VALUE__) & (uint8_t)0x0FU)) - -/** - * @} - */ - -/** @defgroup RTC_LL_EM_Date Date helper Macros - * @{ - */ - -/** - * @brief Helper macro to retrieve weekday. - * @param __RTC_DATE__ Date returned by @ref LL_RTC_DATE_Get function. - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_WEEKDAY_MONDAY - * @arg @ref LL_RTC_WEEKDAY_TUESDAY - * @arg @ref LL_RTC_WEEKDAY_WEDNESDAY - * @arg @ref LL_RTC_WEEKDAY_THURSDAY - * @arg @ref LL_RTC_WEEKDAY_FRIDAY - * @arg @ref LL_RTC_WEEKDAY_SATURDAY - * @arg @ref LL_RTC_WEEKDAY_SUNDAY - */ -#define __LL_RTC_GET_WEEKDAY(__RTC_DATE__) (((__RTC_DATE__) >> RTC_OFFSET_WEEKDAY) & 0x000000FFU) - -/** - * @brief Helper macro to retrieve Year in BCD format - * @param __RTC_DATE__ Value returned by @ref LL_RTC_DATE_Get - * @retval Year in BCD format (0x00 . . . 0x99) - */ -#define __LL_RTC_GET_YEAR(__RTC_DATE__) ((__RTC_DATE__) & 0x000000FFU) - -/** - * @brief Helper macro to retrieve Month in BCD format - * @param __RTC_DATE__ Value returned by @ref LL_RTC_DATE_Get - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_MONTH_JANUARY - * @arg @ref LL_RTC_MONTH_FEBRUARY - * @arg @ref LL_RTC_MONTH_MARCH - * @arg @ref LL_RTC_MONTH_APRIL - * @arg @ref LL_RTC_MONTH_MAY - * @arg @ref LL_RTC_MONTH_JUNE - * @arg @ref LL_RTC_MONTH_JULY - * @arg @ref LL_RTC_MONTH_AUGUST - * @arg @ref LL_RTC_MONTH_SEPTEMBER - * @arg @ref LL_RTC_MONTH_OCTOBER - * @arg @ref LL_RTC_MONTH_NOVEMBER - * @arg @ref LL_RTC_MONTH_DECEMBER - */ -#define __LL_RTC_GET_MONTH(__RTC_DATE__) (((__RTC_DATE__) >>RTC_OFFSET_MONTH) & 0x000000FFU) - -/** - * @brief Helper macro to retrieve Day in BCD format - * @param __RTC_DATE__ Value returned by @ref LL_RTC_DATE_Get - * @retval Day in BCD format (0x01 . . . 0x31) - */ -#define __LL_RTC_GET_DAY(__RTC_DATE__) (((__RTC_DATE__) >>RTC_OFFSET_DAY) & 0x000000FFU) - -/** - * @} - */ - -/** @defgroup RTC_LL_EM_Time Time helper Macros - * @{ - */ - -/** - * @brief Helper macro to retrieve hour in BCD format - * @param __RTC_TIME__ RTC time returned by @ref LL_RTC_TIME_Get function - * @retval Hours in BCD format (0x01. . .0x12 or between Min_Data=0x00 and Max_Data=0x23) - */ -#define __LL_RTC_GET_HOUR(__RTC_TIME__) (((__RTC_TIME__) >> RTC_OFFSET_HOUR) & 0x000000FFU) - -/** - * @brief Helper macro to retrieve minute in BCD format - * @param __RTC_TIME__ RTC time returned by @ref LL_RTC_TIME_Get function - * @retval Minutes in BCD format (0x00. . .0x59) - */ -#define __LL_RTC_GET_MINUTE(__RTC_TIME__) (((__RTC_TIME__) >> RTC_OFFSET_MINUTE) & 0x000000FFU) - -/** - * @brief Helper macro to retrieve second in BCD format - * @param __RTC_TIME__ RTC time returned by @ref LL_RTC_TIME_Get function - * @retval Seconds in format (0x00. . .0x59) - */ -#define __LL_RTC_GET_SECOND(__RTC_TIME__) ((__RTC_TIME__) & 0x000000FFU) - -/** - * @} - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup RTC_LL_Exported_Functions RTC Exported Functions - * @{ - */ - -/** @defgroup RTC_LL_EF_Configuration Configuration - * @{ - */ - -/** - * @brief Set Hours format (24 hour/day or AM/PM hour format) - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @note It can be written in initialization mode only (@ref LL_RTC_EnableInitMode function) - * @rmtoll CR FMT LL_RTC_SetHourFormat - * @param RTCx RTC Instance - * @param HourFormat This parameter can be one of the following values: - * @arg @ref LL_RTC_HOURFORMAT_24HOUR - * @arg @ref LL_RTC_HOURFORMAT_AMPM - * @retval None - */ -__STATIC_INLINE void LL_RTC_SetHourFormat(RTC_TypeDef *RTCx, uint32_t HourFormat) -{ - MODIFY_REG(RTCx->CR, RTC_CR_FMT, HourFormat); -} - -/** - * @brief Get Hours format (24 hour/day or AM/PM hour format) - * @rmtoll CR FMT LL_RTC_GetHourFormat - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_HOURFORMAT_24HOUR - * @arg @ref LL_RTC_HOURFORMAT_AMPM - */ -__STATIC_INLINE uint32_t LL_RTC_GetHourFormat(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->CR, RTC_CR_FMT)); -} - -/** - * @brief Select the flag to be routed to RTC_ALARM output - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR OSEL LL_RTC_SetAlarmOutEvent - * @param RTCx RTC Instance - * @param AlarmOutput This parameter can be one of the following values: - * @arg @ref LL_RTC_ALARMOUT_DISABLE - * @arg @ref LL_RTC_ALARMOUT_ALMA - * @arg @ref LL_RTC_ALARMOUT_ALMB - * @arg @ref LL_RTC_ALARMOUT_WAKEUP - * @retval None - */ -__STATIC_INLINE void LL_RTC_SetAlarmOutEvent(RTC_TypeDef *RTCx, uint32_t AlarmOutput) -{ - MODIFY_REG(RTCx->CR, RTC_CR_OSEL, AlarmOutput); -} - -/** - * @brief Get the flag to be routed to RTC_ALARM output - * @rmtoll CR OSEL LL_RTC_GetAlarmOutEvent - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_ALARMOUT_DISABLE - * @arg @ref LL_RTC_ALARMOUT_ALMA - * @arg @ref LL_RTC_ALARMOUT_ALMB - * @arg @ref LL_RTC_ALARMOUT_WAKEUP - */ -__STATIC_INLINE uint32_t LL_RTC_GetAlarmOutEvent(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->CR, RTC_CR_OSEL)); -} - -/** - * @brief Set RTC_ALARM output type (ALARM in push-pull or open-drain output) - * @note Used only when RTC_ALARM is mapped on PC13 - * @note If all RTC alternate functions are disabled and PC13MODE = 1, PC13VALUE configures the - * PC13 output data - * @rmtoll TAFCR ALARMOUTTYPE LL_RTC_SetAlarmOutputType - * @param RTCx RTC Instance - * @param Output This parameter can be one of the following values: - * @arg @ref LL_RTC_ALARM_OUTPUTTYPE_OPENDRAIN - * @arg @ref LL_RTC_ALARM_OUTPUTTYPE_PUSHPULL - * @retval None - */ -__STATIC_INLINE void LL_RTC_SetAlarmOutputType(RTC_TypeDef *RTCx, uint32_t Output) -{ - MODIFY_REG(RTCx->TAFCR, RTC_TAFCR_ALARMOUTTYPE, Output); -} - -/** - * @brief Get RTC_ALARM output type (ALARM in push-pull or open-drain output) - * @note used only when RTC_ALARM is mapped on PC13 - * @note If all RTC alternate functions are disabled and PC13MODE = 1, PC13VALUE configures the - * PC13 output data - * @rmtoll TAFCR ALARMOUTTYPE LL_RTC_GetAlarmOutputType - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_ALARM_OUTPUTTYPE_OPENDRAIN - * @arg @ref LL_RTC_ALARM_OUTPUTTYPE_PUSHPULL - */ -__STATIC_INLINE uint32_t LL_RTC_GetAlarmOutputType(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->TAFCR, RTC_TAFCR_ALARMOUTTYPE)); -} - -/** - * @brief Enable push-pull output on PC13, PC14 and/or PC15 - * @note PC13 forced to push-pull output if all RTC alternate functions are disabled - * @note PC14 and PC15 forced to push-pull output if LSE is disabled - * @rmtoll TAFCR PC13MODE LL_RTC_EnablePushPullMode\n - * @rmtoll TAFCR PC14MODE LL_RTC_EnablePushPullMode\n - * @rmtoll TAFCR PC15MODE LL_RTC_EnablePushPullMode - * @param RTCx RTC Instance - * @param PinMask This parameter can be a combination of the following values: - * @arg @ref LL_RTC_PIN_PC13 - * @arg @ref LL_RTC_PIN_PC14 - * @arg @ref LL_RTC_PIN_PC15 - * @retval None - */ -__STATIC_INLINE void LL_RTC_EnablePushPullMode(RTC_TypeDef *RTCx, uint32_t PinMask) -{ - SET_BIT(RTCx->TAFCR, PinMask); -} - -/** - * @brief Disable push-pull output on PC13, PC14 and/or PC15 - * @note PC13, PC14 and/or PC15 are controlled by the GPIO configuration registers. - * Consequently PC13, PC14 and/or PC15 are floating in Standby mode. - * @rmtoll TAFCR PC13MODE LL_RTC_DisablePushPullMode\n - * TAFCR PC14MODE LL_RTC_DisablePushPullMode\n - * TAFCR PC15MODE LL_RTC_DisablePushPullMode - * @param RTCx RTC Instance - * @param PinMask This parameter can be a combination of the following values: - * @arg @ref LL_RTC_PIN_PC13 - * @arg @ref LL_RTC_PIN_PC14 - * @arg @ref LL_RTC_PIN_PC15 - * @retval None - */ -__STATIC_INLINE void LL_RTC_DisablePushPullMode(RTC_TypeDef* RTCx, uint32_t PinMask) -{ - CLEAR_BIT(RTCx->TAFCR, PinMask); -} - -/** - * @brief Set PC14 and/or PC15 to high level. - * @note Output data configuration is possible if the LSE is disabled and PushPull output is enabled (through @ref LL_RTC_EnablePushPullMode) - * @rmtoll TAFCR PC14VALUE LL_RTC_SetOutputPin\n - * TAFCR PC15VALUE LL_RTC_SetOutputPin - * @param RTCx RTC Instance - * @param PinMask This parameter can be a combination of the following values: - * @arg @ref LL_RTC_PIN_PC14 - * @arg @ref LL_RTC_PIN_PC15 - * @retval None - */ -__STATIC_INLINE void LL_RTC_SetOutputPin(RTC_TypeDef* RTCx, uint32_t PinMask) -{ - SET_BIT(RTCx->TAFCR, (PinMask >> 1)); -} - -/** - * @brief Set PC14 and/or PC15 to low level. - * @note Output data configuration is possible if the LSE is disabled and PushPull output is enabled (through @ref LL_RTC_EnablePushPullMode) - * @rmtoll TAFCR PC14VALUE LL_RTC_ResetOutputPin\n - * TAFCR PC15VALUE LL_RTC_ResetOutputPin - * @param RTCx RTC Instance - * @param PinMask This parameter can be a combination of the following values: - * @arg @ref LL_RTC_PIN_PC14 - * @arg @ref LL_RTC_PIN_PC15 - * @retval None - */ -__STATIC_INLINE void LL_RTC_ResetOutputPin(RTC_TypeDef* RTCx, uint32_t PinMask) -{ - CLEAR_BIT(RTCx->TAFCR, (PinMask >> 1)); -} - -/** - * @brief Enable initialization mode - * @note Initialization mode is used to program time and date register (RTC_TR and RTC_DR) - * and prescaler register (RTC_PRER). - * Counters are stopped and start counting from the new value when INIT is reset. - * @rmtoll ISR INIT LL_RTC_EnableInitMode - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_EnableInitMode(RTC_TypeDef *RTCx) -{ - /* Set the Initialization mode */ - WRITE_REG(RTCx->ISR, RTC_INIT_MASK); -} - -/** - * @brief Disable initialization mode (Free running mode) - * @rmtoll ISR INIT LL_RTC_DisableInitMode - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_DisableInitMode(RTC_TypeDef *RTCx) -{ - /* Exit Initialization mode */ - WRITE_REG(RTCx->ISR, (uint32_t)~RTC_ISR_INIT); -} - -/** - * @brief Set Output polarity (pin is low when ALRAF/ALRBF/WUTF is asserted) - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR POL LL_RTC_SetOutputPolarity - * @param RTCx RTC Instance - * @param Polarity This parameter can be one of the following values: - * @arg @ref LL_RTC_OUTPUTPOLARITY_PIN_HIGH - * @arg @ref LL_RTC_OUTPUTPOLARITY_PIN_LOW - * @retval None - */ -__STATIC_INLINE void LL_RTC_SetOutputPolarity(RTC_TypeDef *RTCx, uint32_t Polarity) -{ - MODIFY_REG(RTCx->CR, RTC_CR_POL, Polarity); -} - -/** - * @brief Get Output polarity - * @rmtoll CR POL LL_RTC_GetOutputPolarity - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_OUTPUTPOLARITY_PIN_HIGH - * @arg @ref LL_RTC_OUTPUTPOLARITY_PIN_LOW - */ -__STATIC_INLINE uint32_t LL_RTC_GetOutputPolarity(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->CR, RTC_CR_POL)); -} - -/** - * @brief Enable Bypass the shadow registers - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR BYPSHAD LL_RTC_EnableShadowRegBypass - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_EnableShadowRegBypass(RTC_TypeDef *RTCx) -{ - SET_BIT(RTCx->CR, RTC_CR_BYPSHAD); -} - -/** - * @brief Disable Bypass the shadow registers - * @rmtoll CR BYPSHAD LL_RTC_DisableShadowRegBypass - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_DisableShadowRegBypass(RTC_TypeDef *RTCx) -{ - CLEAR_BIT(RTCx->CR, RTC_CR_BYPSHAD); -} - -/** - * @brief Check if Shadow registers bypass is enabled or not. - * @rmtoll CR BYPSHAD LL_RTC_IsShadowRegBypassEnabled - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_IsShadowRegBypassEnabled(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->CR, RTC_CR_BYPSHAD) == (RTC_CR_BYPSHAD)); -} - -/** - * @brief Enable RTC_REFIN reference clock detection (50 or 60 Hz) - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @note It can be written in initialization mode only (@ref LL_RTC_EnableInitMode function) - * @rmtoll CR REFCKON LL_RTC_EnableRefClock - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_EnableRefClock(RTC_TypeDef *RTCx) -{ - SET_BIT(RTCx->CR, RTC_CR_REFCKON); -} - -/** - * @brief Disable RTC_REFIN reference clock detection (50 or 60 Hz) - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @note It can be written in initialization mode only (@ref LL_RTC_EnableInitMode function) - * @rmtoll CR REFCKON LL_RTC_DisableRefClock - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_DisableRefClock(RTC_TypeDef *RTCx) -{ - CLEAR_BIT(RTCx->CR, RTC_CR_REFCKON); -} - -/** - * @brief Set Asynchronous prescaler factor - * @rmtoll PRER PREDIV_A LL_RTC_SetAsynchPrescaler - * @param RTCx RTC Instance - * @param AsynchPrescaler Value between Min_Data = 0 and Max_Data = 0x7F - * @retval None - */ -__STATIC_INLINE void LL_RTC_SetAsynchPrescaler(RTC_TypeDef *RTCx, uint32_t AsynchPrescaler) -{ - MODIFY_REG(RTCx->PRER, RTC_PRER_PREDIV_A, AsynchPrescaler << RTC_PRER_PREDIV_A_Pos); -} - -/** - * @brief Set Synchronous prescaler factor - * @rmtoll PRER PREDIV_S LL_RTC_SetSynchPrescaler - * @param RTCx RTC Instance - * @param SynchPrescaler Value between Min_Data = 0 and Max_Data = 0x7FFF - * @retval None - */ -__STATIC_INLINE void LL_RTC_SetSynchPrescaler(RTC_TypeDef *RTCx, uint32_t SynchPrescaler) -{ - MODIFY_REG(RTCx->PRER, RTC_PRER_PREDIV_S, SynchPrescaler); -} - -/** - * @brief Get Asynchronous prescaler factor - * @rmtoll PRER PREDIV_A LL_RTC_GetAsynchPrescaler - * @param RTCx RTC Instance - * @retval Value between Min_Data = 0 and Max_Data = 0x7F - */ -__STATIC_INLINE uint32_t LL_RTC_GetAsynchPrescaler(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->PRER, RTC_PRER_PREDIV_A) >> RTC_PRER_PREDIV_A_Pos); -} - -/** - * @brief Get Synchronous prescaler factor - * @rmtoll PRER PREDIV_S LL_RTC_GetSynchPrescaler - * @param RTCx RTC Instance - * @retval Value between Min_Data = 0 and Max_Data = 0x7FFF - */ -__STATIC_INLINE uint32_t LL_RTC_GetSynchPrescaler(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->PRER, RTC_PRER_PREDIV_S)); -} - -/** - * @brief Enable the write protection for RTC registers. - * @rmtoll WPR KEY LL_RTC_EnableWriteProtection - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_EnableWriteProtection(RTC_TypeDef *RTCx) -{ - WRITE_REG(RTCx->WPR, RTC_WRITE_PROTECTION_DISABLE); -} - -/** - * @brief Disable the write protection for RTC registers. - * @rmtoll WPR KEY LL_RTC_DisableWriteProtection - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_DisableWriteProtection(RTC_TypeDef *RTCx) -{ - WRITE_REG(RTCx->WPR, RTC_WRITE_PROTECTION_ENABLE_1); - WRITE_REG(RTCx->WPR, RTC_WRITE_PROTECTION_ENABLE_2); -} - -/** - * @} - */ - -/** @defgroup RTC_LL_EF_Time Time - * @{ - */ - -/** - * @brief Set time format (AM/24-hour or PM notation) - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @note It can be written in initialization mode only (@ref LL_RTC_EnableInitMode function) - * @rmtoll TR PM LL_RTC_TIME_SetFormat - * @param RTCx RTC Instance - * @param TimeFormat This parameter can be one of the following values: - * @arg @ref LL_RTC_TIME_FORMAT_AM_OR_24 - * @arg @ref LL_RTC_TIME_FORMAT_PM - * @retval None - */ -__STATIC_INLINE void LL_RTC_TIME_SetFormat(RTC_TypeDef *RTCx, uint32_t TimeFormat) -{ - MODIFY_REG(RTCx->TR, RTC_TR_PM, TimeFormat); -} - -/** - * @brief Get time format (AM or PM notation) - * @note if shadow mode is disabled (BYPSHAD=0), need to check if RSF flag is set - * before reading this bit - * @note Read either RTC_SSR or RTC_TR locks the values in the higher-order calendar - * shadow registers until RTC_DR is read (LL_RTC_ReadReg(RTC, DR)). - * @rmtoll TR PM LL_RTC_TIME_GetFormat - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_TIME_FORMAT_AM_OR_24 - * @arg @ref LL_RTC_TIME_FORMAT_PM - */ -__STATIC_INLINE uint32_t LL_RTC_TIME_GetFormat(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->TR, RTC_TR_PM)); -} - -/** - * @brief Set Hours in BCD format - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @note It can be written in initialization mode only (@ref LL_RTC_EnableInitMode function) - * @note helper macro __LL_RTC_CONVERT_BIN2BCD is available to convert hour from binary to BCD format - * @rmtoll TR HT LL_RTC_TIME_SetHour\n - * TR HU LL_RTC_TIME_SetHour - * @param RTCx RTC Instance - * @param Hours Value between Min_Data=0x01 and Max_Data=0x12 or between Min_Data=0x00 and Max_Data=0x23 - * @retval None - */ -__STATIC_INLINE void LL_RTC_TIME_SetHour(RTC_TypeDef *RTCx, uint32_t Hours) -{ - MODIFY_REG(RTCx->TR, (RTC_TR_HT | RTC_TR_HU), - (((Hours & 0xF0U) << (RTC_TR_HT_Pos - 4U)) | ((Hours & 0x0FU) << RTC_TR_HU_Pos))); -} - -/** - * @brief Get Hours in BCD format - * @note if shadow mode is disabled (BYPSHAD=0), need to check if RSF flag is set - * before reading this bit - * @note Read either RTC_SSR or RTC_TR locks the values in the higher-order calendar - * shadow registers until RTC_DR is read (LL_RTC_ReadReg(RTC, DR)). - * @note helper macro __LL_RTC_CONVERT_BCD2BIN is available to convert hour from BCD to - * Binary format - * @rmtoll TR HT LL_RTC_TIME_GetHour\n - * TR HU LL_RTC_TIME_GetHour - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x01 and Max_Data=0x12 or between Min_Data=0x00 and Max_Data=0x23 - */ -__STATIC_INLINE uint32_t LL_RTC_TIME_GetHour(RTC_TypeDef *RTCx) -{ - return (uint32_t)((READ_BIT(RTCx->TR, (RTC_TR_HT | RTC_TR_HU))) >> RTC_TR_HU_Pos); -} - -/** - * @brief Set Minutes in BCD format - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @note It can be written in initialization mode only (@ref LL_RTC_EnableInitMode function) - * @note helper macro __LL_RTC_CONVERT_BIN2BCD is available to convert Minutes from binary to BCD format - * @rmtoll TR MNT LL_RTC_TIME_SetMinute\n - * TR MNU LL_RTC_TIME_SetMinute - * @param RTCx RTC Instance - * @param Minutes Value between Min_Data=0x00 and Max_Data=0x59 - * @retval None - */ -__STATIC_INLINE void LL_RTC_TIME_SetMinute(RTC_TypeDef *RTCx, uint32_t Minutes) -{ - MODIFY_REG(RTCx->TR, (RTC_TR_MNT | RTC_TR_MNU), - (((Minutes & 0xF0U) << (RTC_TR_MNT_Pos - 4U)) | ((Minutes & 0x0FU) << RTC_TR_MNU_Pos))); -} - -/** - * @brief Get Minutes in BCD format - * @note if shadow mode is disabled (BYPSHAD=0), need to check if RSF flag is set - * before reading this bit - * @note Read either RTC_SSR or RTC_TR locks the values in the higher-order calendar - * shadow registers until RTC_DR is read (LL_RTC_ReadReg(RTC, DR)). - * @note helper macro __LL_RTC_CONVERT_BCD2BIN is available to convert minute from BCD - * to Binary format - * @rmtoll TR MNT LL_RTC_TIME_GetMinute\n - * TR MNU LL_RTC_TIME_GetMinute - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x00 and Max_Data=0x59 - */ -__STATIC_INLINE uint32_t LL_RTC_TIME_GetMinute(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->TR, (RTC_TR_MNT | RTC_TR_MNU))>> RTC_TR_MNU_Pos); -} - -/** - * @brief Set Seconds in BCD format - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @note It can be written in initialization mode only (@ref LL_RTC_EnableInitMode function) - * @note helper macro __LL_RTC_CONVERT_BIN2BCD is available to convert Seconds from binary to BCD format - * @rmtoll TR ST LL_RTC_TIME_SetSecond\n - * TR SU LL_RTC_TIME_SetSecond - * @param RTCx RTC Instance - * @param Seconds Value between Min_Data=0x00 and Max_Data=0x59 - * @retval None - */ -__STATIC_INLINE void LL_RTC_TIME_SetSecond(RTC_TypeDef *RTCx, uint32_t Seconds) -{ - MODIFY_REG(RTCx->TR, (RTC_TR_ST | RTC_TR_SU), - (((Seconds & 0xF0U) << (RTC_TR_ST_Pos - 4U)) | ((Seconds & 0x0FU) << RTC_TR_SU_Pos))); -} - -/** - * @brief Get Seconds in BCD format - * @note if shadow mode is disabled (BYPSHAD=0), need to check if RSF flag is set - * before reading this bit - * @note Read either RTC_SSR or RTC_TR locks the values in the higher-order calendar - * shadow registers until RTC_DR is read (LL_RTC_ReadReg(RTC, DR)). - * @note helper macro __LL_RTC_CONVERT_BCD2BIN is available to convert Seconds from BCD - * to Binary format - * @rmtoll TR ST LL_RTC_TIME_GetSecond\n - * TR SU LL_RTC_TIME_GetSecond - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x00 and Max_Data=0x59 - */ -__STATIC_INLINE uint32_t LL_RTC_TIME_GetSecond(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->TR, (RTC_TR_ST | RTC_TR_SU)) >> RTC_TR_SU_Pos); -} - -/** - * @brief Set time (hour, minute and second) in BCD format - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @note It can be written in initialization mode only (@ref LL_RTC_EnableInitMode function) - * @note TimeFormat and Hours should follow the same format - * @rmtoll TR PM LL_RTC_TIME_Config\n - * TR HT LL_RTC_TIME_Config\n - * TR HU LL_RTC_TIME_Config\n - * TR MNT LL_RTC_TIME_Config\n - * TR MNU LL_RTC_TIME_Config\n - * TR ST LL_RTC_TIME_Config\n - * TR SU LL_RTC_TIME_Config - * @param RTCx RTC Instance - * @param Format12_24 This parameter can be one of the following values: - * @arg @ref LL_RTC_TIME_FORMAT_AM_OR_24 - * @arg @ref LL_RTC_TIME_FORMAT_PM - * @param Hours Value between Min_Data=0x01 and Max_Data=0x12 or between Min_Data=0x00 and Max_Data=0x23 - * @param Minutes Value between Min_Data=0x00 and Max_Data=0x59 - * @param Seconds Value between Min_Data=0x00 and Max_Data=0x59 - * @retval None - */ -__STATIC_INLINE void LL_RTC_TIME_Config(RTC_TypeDef *RTCx, uint32_t Format12_24, uint32_t Hours, uint32_t Minutes, uint32_t Seconds) -{ - register uint32_t temp = 0U; - - temp = Format12_24 | \ - (((Hours & 0xF0U) << (RTC_TR_HT_Pos - 4U)) | ((Hours & 0x0FU) << RTC_TR_HU_Pos)) | \ - (((Minutes & 0xF0U) << (RTC_TR_MNT_Pos - 4U)) | ((Minutes & 0x0FU) << RTC_TR_MNU_Pos)) | \ - (((Seconds & 0xF0U) << (RTC_TR_ST_Pos - 4U)) | ((Seconds & 0x0FU) << RTC_TR_SU_Pos)); - MODIFY_REG(RTCx->TR, (RTC_TR_PM | RTC_TR_HT | RTC_TR_HU | RTC_TR_MNT | RTC_TR_MNU | RTC_TR_ST | RTC_TR_SU), temp); -} - -/** - * @brief Get time (hour, minute and second) in BCD format - * @note if shadow mode is disabled (BYPSHAD=0), need to check if RSF flag is set - * before reading this bit - * @note Read either RTC_SSR or RTC_TR locks the values in the higher-order calendar - * shadow registers until RTC_DR is read (LL_RTC_ReadReg(RTC, DR)). - * @note helper macros __LL_RTC_GET_HOUR, __LL_RTC_GET_MINUTE and __LL_RTC_GET_SECOND - * are available to get independently each parameter. - * @rmtoll TR HT LL_RTC_TIME_Get\n - * TR HU LL_RTC_TIME_Get\n - * TR MNT LL_RTC_TIME_Get\n - * TR MNU LL_RTC_TIME_Get\n - * TR ST LL_RTC_TIME_Get\n - * TR SU LL_RTC_TIME_Get - * @param RTCx RTC Instance - * @retval Combination of hours, minutes and seconds (Format: 0x00HHMMSS). - */ -__STATIC_INLINE uint32_t LL_RTC_TIME_Get(RTC_TypeDef *RTCx) -{ - register uint32_t temp = 0U; - - temp = READ_BIT(RTCx->TR, (RTC_TR_HT | RTC_TR_HU | RTC_TR_MNT | RTC_TR_MNU | RTC_TR_ST | RTC_TR_SU)); - return (uint32_t)((((((temp & RTC_TR_HT) >> RTC_TR_HT_Pos) << 4U) | ((temp & RTC_TR_HU) >> RTC_TR_HU_Pos)) << RTC_OFFSET_HOUR) | \ - (((((temp & RTC_TR_MNT) >> RTC_TR_MNT_Pos) << 4U) | ((temp & RTC_TR_MNU) >> RTC_TR_MNU_Pos)) << RTC_OFFSET_MINUTE) | \ - ((((temp & RTC_TR_ST) >> RTC_TR_ST_Pos) << 4U) | ((temp & RTC_TR_SU) >> RTC_TR_SU_Pos))); -} - -/** - * @brief Memorize whether the daylight saving time change has been performed - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR BKP LL_RTC_TIME_EnableDayLightStore - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_TIME_EnableDayLightStore(RTC_TypeDef *RTCx) -{ - SET_BIT(RTCx->CR, RTC_CR_BKP); -} - -/** - * @brief Disable memorization whether the daylight saving time change has been performed. - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR BKP LL_RTC_TIME_DisableDayLightStore - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_TIME_DisableDayLightStore(RTC_TypeDef *RTCx) -{ - CLEAR_BIT(RTCx->CR, RTC_CR_BKP); -} - -/** - * @brief Check if RTC Day Light Saving stored operation has been enabled or not - * @rmtoll CR BKP LL_RTC_TIME_IsDayLightStoreEnabled - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_TIME_IsDayLightStoreEnabled(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->CR, RTC_CR_BKP) == (RTC_CR_BKP)); -} - -/** - * @brief Subtract 1 hour (winter time change) - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR SUB1H LL_RTC_TIME_DecHour - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_TIME_DecHour(RTC_TypeDef *RTCx) -{ - SET_BIT(RTCx->CR, RTC_CR_SUB1H); -} - -/** - * @brief Add 1 hour (summer time change) - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR ADD1H LL_RTC_TIME_IncHour - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_TIME_IncHour(RTC_TypeDef *RTCx) -{ - SET_BIT(RTCx->CR, RTC_CR_ADD1H); -} - -/** - * @brief Get Sub second value in the synchronous prescaler counter. - * @note You can use both SubSeconds value and SecondFraction (PREDIV_S through - * LL_RTC_GetSynchPrescaler function) terms returned to convert Calendar - * SubSeconds value in second fraction ratio with time unit following - * generic formula: - * ==> Seconds fraction ratio * time_unit= [(SecondFraction-SubSeconds)/(SecondFraction+1)] * time_unit - * This conversion can be performed only if no shift operation is pending - * (ie. SHFP=0) when PREDIV_S >= SS. - * @rmtoll SSR SS LL_RTC_TIME_GetSubSecond - * @param RTCx RTC Instance - * @retval Sub second value (number between 0 and 65535) - */ -__STATIC_INLINE uint32_t LL_RTC_TIME_GetSubSecond(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->SSR, RTC_SSR_SS)); -} - -/** - * @brief Synchronize to a remote clock with a high degree of precision. - * @note This operation effectively subtracts from (delays) or advance the clock of a fraction of a second. - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @note When REFCKON is set, firmware must not write to Shift control register. - * @rmtoll SHIFTR ADD1S LL_RTC_TIME_Synchronize\n - * SHIFTR SUBFS LL_RTC_TIME_Synchronize - * @param RTCx RTC Instance - * @param ShiftSecond This parameter can be one of the following values: - * @arg @ref LL_RTC_SHIFT_SECOND_DELAY - * @arg @ref LL_RTC_SHIFT_SECOND_ADVANCE - * @param Fraction Number of Seconds Fractions (any value from 0 to 0x7FFF) - * @retval None - */ -__STATIC_INLINE void LL_RTC_TIME_Synchronize(RTC_TypeDef *RTCx, uint32_t ShiftSecond, uint32_t Fraction) -{ - WRITE_REG(RTCx->SHIFTR, ShiftSecond | Fraction); -} - -/** - * @} - */ - -/** @defgroup RTC_LL_EF_Date Date - * @{ - */ - -/** - * @brief Set Year in BCD format - * @note helper macro __LL_RTC_CONVERT_BIN2BCD is available to convert Year from binary to BCD format - * @rmtoll DR YT LL_RTC_DATE_SetYear\n - * DR YU LL_RTC_DATE_SetYear - * @param RTCx RTC Instance - * @param Year Value between Min_Data=0x00 and Max_Data=0x99 - * @retval None - */ -__STATIC_INLINE void LL_RTC_DATE_SetYear(RTC_TypeDef *RTCx, uint32_t Year) -{ - MODIFY_REG(RTCx->DR, (RTC_DR_YT | RTC_DR_YU), - (((Year & 0xF0U) << (RTC_DR_YT_Pos - 4U)) | ((Year & 0x0FU) << RTC_DR_YU_Pos))); -} - -/** - * @brief Get Year in BCD format - * @note if shadow mode is disabled (BYPSHAD=0), need to check if RSF flag is set - * before reading this bit - * @note helper macro __LL_RTC_CONVERT_BCD2BIN is available to convert Year from BCD to Binary format - * @rmtoll DR YT LL_RTC_DATE_GetYear\n - * DR YU LL_RTC_DATE_GetYear - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x00 and Max_Data=0x99 - */ -__STATIC_INLINE uint32_t LL_RTC_DATE_GetYear(RTC_TypeDef *RTCx) -{ - return (uint32_t)((READ_BIT(RTCx->DR, (RTC_DR_YT | RTC_DR_YU))) >> RTC_DR_YU_Pos); -} - -/** - * @brief Set Week day - * @rmtoll DR WDU LL_RTC_DATE_SetWeekDay - * @param RTCx RTC Instance - * @param WeekDay This parameter can be one of the following values: - * @arg @ref LL_RTC_WEEKDAY_MONDAY - * @arg @ref LL_RTC_WEEKDAY_TUESDAY - * @arg @ref LL_RTC_WEEKDAY_WEDNESDAY - * @arg @ref LL_RTC_WEEKDAY_THURSDAY - * @arg @ref LL_RTC_WEEKDAY_FRIDAY - * @arg @ref LL_RTC_WEEKDAY_SATURDAY - * @arg @ref LL_RTC_WEEKDAY_SUNDAY - * @retval None - */ -__STATIC_INLINE void LL_RTC_DATE_SetWeekDay(RTC_TypeDef *RTCx, uint32_t WeekDay) -{ - MODIFY_REG(RTCx->DR, RTC_DR_WDU, WeekDay << RTC_DR_WDU_Pos); -} - -/** - * @brief Get Week day - * @note if shadow mode is disabled (BYPSHAD=0), need to check if RSF flag is set - * before reading this bit - * @rmtoll DR WDU LL_RTC_DATE_GetWeekDay - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_WEEKDAY_MONDAY - * @arg @ref LL_RTC_WEEKDAY_TUESDAY - * @arg @ref LL_RTC_WEEKDAY_WEDNESDAY - * @arg @ref LL_RTC_WEEKDAY_THURSDAY - * @arg @ref LL_RTC_WEEKDAY_FRIDAY - * @arg @ref LL_RTC_WEEKDAY_SATURDAY - * @arg @ref LL_RTC_WEEKDAY_SUNDAY - */ -__STATIC_INLINE uint32_t LL_RTC_DATE_GetWeekDay(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->DR, RTC_DR_WDU) >> RTC_DR_WDU_Pos); -} - -/** - * @brief Set Month in BCD format - * @note helper macro __LL_RTC_CONVERT_BIN2BCD is available to convert Month from binary to BCD format - * @rmtoll DR MT LL_RTC_DATE_SetMonth\n - * DR MU LL_RTC_DATE_SetMonth - * @param RTCx RTC Instance - * @param Month This parameter can be one of the following values: - * @arg @ref LL_RTC_MONTH_JANUARY - * @arg @ref LL_RTC_MONTH_FEBRUARY - * @arg @ref LL_RTC_MONTH_MARCH - * @arg @ref LL_RTC_MONTH_APRIL - * @arg @ref LL_RTC_MONTH_MAY - * @arg @ref LL_RTC_MONTH_JUNE - * @arg @ref LL_RTC_MONTH_JULY - * @arg @ref LL_RTC_MONTH_AUGUST - * @arg @ref LL_RTC_MONTH_SEPTEMBER - * @arg @ref LL_RTC_MONTH_OCTOBER - * @arg @ref LL_RTC_MONTH_NOVEMBER - * @arg @ref LL_RTC_MONTH_DECEMBER - * @retval None - */ -__STATIC_INLINE void LL_RTC_DATE_SetMonth(RTC_TypeDef *RTCx, uint32_t Month) -{ - MODIFY_REG(RTCx->DR, (RTC_DR_MT | RTC_DR_MU), - (((Month & 0xF0U) << (RTC_DR_MT_Pos - 4U)) | ((Month & 0x0FU) << RTC_DR_MU_Pos))); -} - -/** - * @brief Get Month in BCD format - * @note if shadow mode is disabled (BYPSHAD=0), need to check if RSF flag is set - * before reading this bit - * @note helper macro __LL_RTC_CONVERT_BCD2BIN is available to convert Month from BCD to Binary format - * @rmtoll DR MT LL_RTC_DATE_GetMonth\n - * DR MU LL_RTC_DATE_GetMonth - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_MONTH_JANUARY - * @arg @ref LL_RTC_MONTH_FEBRUARY - * @arg @ref LL_RTC_MONTH_MARCH - * @arg @ref LL_RTC_MONTH_APRIL - * @arg @ref LL_RTC_MONTH_MAY - * @arg @ref LL_RTC_MONTH_JUNE - * @arg @ref LL_RTC_MONTH_JULY - * @arg @ref LL_RTC_MONTH_AUGUST - * @arg @ref LL_RTC_MONTH_SEPTEMBER - * @arg @ref LL_RTC_MONTH_OCTOBER - * @arg @ref LL_RTC_MONTH_NOVEMBER - * @arg @ref LL_RTC_MONTH_DECEMBER - */ -__STATIC_INLINE uint32_t LL_RTC_DATE_GetMonth(RTC_TypeDef *RTCx) -{ - return (uint32_t)((READ_BIT(RTCx->DR, (RTC_DR_MT | RTC_DR_MU)))>> RTC_DR_MU_Pos); -} - -/** - * @brief Set Day in BCD format - * @note helper macro __LL_RTC_CONVERT_BIN2BCD is available to convert Day from binary to BCD format - * @rmtoll DR DT LL_RTC_DATE_SetDay\n - * DR DU LL_RTC_DATE_SetDay - * @param RTCx RTC Instance - * @param Day Value between Min_Data=0x01 and Max_Data=0x31 - * @retval None - */ -__STATIC_INLINE void LL_RTC_DATE_SetDay(RTC_TypeDef *RTCx, uint32_t Day) -{ - MODIFY_REG(RTCx->DR, (RTC_DR_DT | RTC_DR_DU), - (((Day & 0xF0U) << (RTC_DR_DT_Pos - 4U)) | ((Day & 0x0FU) << RTC_DR_DU_Pos))); -} - -/** - * @brief Get Day in BCD format - * @note if shadow mode is disabled (BYPSHAD=0), need to check if RSF flag is set - * before reading this bit - * @note helper macro __LL_RTC_CONVERT_BCD2BIN is available to convert Day from BCD to Binary format - * @rmtoll DR DT LL_RTC_DATE_GetDay\n - * DR DU LL_RTC_DATE_GetDay - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x01 and Max_Data=0x31 - */ -__STATIC_INLINE uint32_t LL_RTC_DATE_GetDay(RTC_TypeDef *RTCx) -{ - return (uint32_t)((READ_BIT(RTCx->DR, (RTC_DR_DT | RTC_DR_DU))) >> RTC_DR_DU_Pos); -} - -/** - * @brief Set date (WeekDay, Day, Month and Year) in BCD format - * @rmtoll DR WDU LL_RTC_DATE_Config\n - * DR MT LL_RTC_DATE_Config\n - * DR MU LL_RTC_DATE_Config\n - * DR DT LL_RTC_DATE_Config\n - * DR DU LL_RTC_DATE_Config\n - * DR YT LL_RTC_DATE_Config\n - * DR YU LL_RTC_DATE_Config - * @param RTCx RTC Instance - * @param WeekDay This parameter can be one of the following values: - * @arg @ref LL_RTC_WEEKDAY_MONDAY - * @arg @ref LL_RTC_WEEKDAY_TUESDAY - * @arg @ref LL_RTC_WEEKDAY_WEDNESDAY - * @arg @ref LL_RTC_WEEKDAY_THURSDAY - * @arg @ref LL_RTC_WEEKDAY_FRIDAY - * @arg @ref LL_RTC_WEEKDAY_SATURDAY - * @arg @ref LL_RTC_WEEKDAY_SUNDAY - * @param Day Value between Min_Data=0x01 and Max_Data=0x31 - * @param Month This parameter can be one of the following values: - * @arg @ref LL_RTC_MONTH_JANUARY - * @arg @ref LL_RTC_MONTH_FEBRUARY - * @arg @ref LL_RTC_MONTH_MARCH - * @arg @ref LL_RTC_MONTH_APRIL - * @arg @ref LL_RTC_MONTH_MAY - * @arg @ref LL_RTC_MONTH_JUNE - * @arg @ref LL_RTC_MONTH_JULY - * @arg @ref LL_RTC_MONTH_AUGUST - * @arg @ref LL_RTC_MONTH_SEPTEMBER - * @arg @ref LL_RTC_MONTH_OCTOBER - * @arg @ref LL_RTC_MONTH_NOVEMBER - * @arg @ref LL_RTC_MONTH_DECEMBER - * @param Year Value between Min_Data=0x00 and Max_Data=0x99 - * @retval None - */ -__STATIC_INLINE void LL_RTC_DATE_Config(RTC_TypeDef *RTCx, uint32_t WeekDay, uint32_t Day, uint32_t Month, uint32_t Year) -{ - register uint32_t temp = 0U; - - temp = (WeekDay << RTC_DR_WDU_Pos) | \ - (((Year & 0xF0U) << (RTC_DR_YT_Pos - 4U)) | ((Year & 0x0FU) << RTC_DR_YU_Pos)) | \ - (((Month & 0xF0U) << (RTC_DR_MT_Pos - 4U)) | ((Month & 0x0FU) << RTC_DR_MU_Pos)) | \ - (((Day & 0xF0U) << (RTC_DR_DT_Pos - 4U)) | ((Day & 0x0FU) << RTC_DR_DU_Pos)); - - MODIFY_REG(RTCx->DR, (RTC_DR_WDU | RTC_DR_MT | RTC_DR_MU | RTC_DR_DT | RTC_DR_DU | RTC_DR_YT | RTC_DR_YU), temp); -} - -/** - * @brief Get date (WeekDay, Day, Month and Year) in BCD format - * @note if shadow mode is disabled (BYPSHAD=0), need to check if RSF flag is set - * before reading this bit - * @note helper macros __LL_RTC_GET_WEEKDAY, __LL_RTC_GET_YEAR, __LL_RTC_GET_MONTH, - * and __LL_RTC_GET_DAY are available to get independently each parameter. - * @rmtoll DR WDU LL_RTC_DATE_Get\n - * DR MT LL_RTC_DATE_Get\n - * DR MU LL_RTC_DATE_Get\n - * DR DT LL_RTC_DATE_Get\n - * DR DU LL_RTC_DATE_Get\n - * DR YT LL_RTC_DATE_Get\n - * DR YU LL_RTC_DATE_Get - * @param RTCx RTC Instance - * @retval Combination of WeekDay, Day, Month and Year (Format: 0xWWDDMMYY). - */ -__STATIC_INLINE uint32_t LL_RTC_DATE_Get(RTC_TypeDef *RTCx) -{ - register uint32_t temp = 0U; - - temp = READ_BIT(RTCx->DR, (RTC_DR_WDU | RTC_DR_MT | RTC_DR_MU | RTC_DR_DT | RTC_DR_DU | RTC_DR_YT | RTC_DR_YU)); - return (uint32_t)((((temp & RTC_DR_WDU) >> RTC_DR_WDU_Pos) << RTC_OFFSET_WEEKDAY) | \ - (((((temp & RTC_DR_DT) >> RTC_DR_DT_Pos) << 4U) | ((temp & RTC_DR_DU) >> RTC_DR_DU_Pos)) << RTC_OFFSET_DAY) | \ - (((((temp & RTC_DR_MT) >> RTC_DR_MT_Pos) << 4U) | ((temp & RTC_DR_MU) >> RTC_DR_MU_Pos)) << RTC_OFFSET_MONTH) | \ - ((((temp & RTC_DR_YT) >> RTC_DR_YT_Pos) << 4U) | ((temp & RTC_DR_YU) >> RTC_DR_YU_Pos))); -} - -/** - * @} - */ - -/** @defgroup RTC_LL_EF_ALARMA ALARMA - * @{ - */ - -/** - * @brief Enable Alarm A - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR ALRAE LL_RTC_ALMA_Enable - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMA_Enable(RTC_TypeDef *RTCx) -{ - SET_BIT(RTCx->CR, RTC_CR_ALRAE); -} - -/** - * @brief Disable Alarm A - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR ALRAE LL_RTC_ALMA_Disable - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMA_Disable(RTC_TypeDef *RTCx) -{ - CLEAR_BIT(RTCx->CR, RTC_CR_ALRAE); -} - -/** - * @brief Specify the Alarm A masks. - * @rmtoll ALRMAR MSK4 LL_RTC_ALMA_SetMask\n - * ALRMAR MSK3 LL_RTC_ALMA_SetMask\n - * ALRMAR MSK2 LL_RTC_ALMA_SetMask\n - * ALRMAR MSK1 LL_RTC_ALMA_SetMask - * @param RTCx RTC Instance - * @param Mask This parameter can be a combination of the following values: - * @arg @ref LL_RTC_ALMA_MASK_NONE - * @arg @ref LL_RTC_ALMA_MASK_DATEWEEKDAY - * @arg @ref LL_RTC_ALMA_MASK_HOURS - * @arg @ref LL_RTC_ALMA_MASK_MINUTES - * @arg @ref LL_RTC_ALMA_MASK_SECONDS - * @arg @ref LL_RTC_ALMA_MASK_ALL - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMA_SetMask(RTC_TypeDef *RTCx, uint32_t Mask) -{ - MODIFY_REG(RTCx->ALRMAR, RTC_ALRMAR_MSK4 | RTC_ALRMAR_MSK3 | RTC_ALRMAR_MSK2 | RTC_ALRMAR_MSK1, Mask); -} - -/** - * @brief Get the Alarm A masks. - * @rmtoll ALRMAR MSK4 LL_RTC_ALMA_GetMask\n - * ALRMAR MSK3 LL_RTC_ALMA_GetMask\n - * ALRMAR MSK2 LL_RTC_ALMA_GetMask\n - * ALRMAR MSK1 LL_RTC_ALMA_GetMask - * @param RTCx RTC Instance - * @retval Returned value can be can be a combination of the following values: - * @arg @ref LL_RTC_ALMA_MASK_NONE - * @arg @ref LL_RTC_ALMA_MASK_DATEWEEKDAY - * @arg @ref LL_RTC_ALMA_MASK_HOURS - * @arg @ref LL_RTC_ALMA_MASK_MINUTES - * @arg @ref LL_RTC_ALMA_MASK_SECONDS - * @arg @ref LL_RTC_ALMA_MASK_ALL - */ -__STATIC_INLINE uint32_t LL_RTC_ALMA_GetMask(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->ALRMAR, RTC_ALRMAR_MSK4 | RTC_ALRMAR_MSK3 | RTC_ALRMAR_MSK2 | RTC_ALRMAR_MSK1)); -} - -/** - * @brief Enable AlarmA Week day selection (DU[3:0] represents the week day. DT[1:0] is do not care) - * @rmtoll ALRMAR WDSEL LL_RTC_ALMA_EnableWeekday - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMA_EnableWeekday(RTC_TypeDef *RTCx) -{ - SET_BIT(RTCx->ALRMAR, RTC_ALRMAR_WDSEL); -} - -/** - * @brief Disable AlarmA Week day selection (DU[3:0] represents the date ) - * @rmtoll ALRMAR WDSEL LL_RTC_ALMA_DisableWeekday - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMA_DisableWeekday(RTC_TypeDef *RTCx) -{ - CLEAR_BIT(RTCx->ALRMAR, RTC_ALRMAR_WDSEL); -} - -/** - * @brief Set ALARM A Day in BCD format - * @note helper macro __LL_RTC_CONVERT_BIN2BCD is available to convert Day from binary to BCD format - * @rmtoll ALRMAR DT LL_RTC_ALMA_SetDay\n - * ALRMAR DU LL_RTC_ALMA_SetDay - * @param RTCx RTC Instance - * @param Day Value between Min_Data=0x01 and Max_Data=0x31 - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMA_SetDay(RTC_TypeDef *RTCx, uint32_t Day) -{ - MODIFY_REG(RTCx->ALRMAR, (RTC_ALRMAR_DT | RTC_ALRMAR_DU), - (((Day & 0xF0U) << (RTC_ALRMAR_DT_Pos - 4U)) | ((Day & 0x0FU) << RTC_ALRMAR_DU_Pos))); -} - -/** - * @brief Get ALARM A Day in BCD format - * @note helper macro __LL_RTC_CONVERT_BCD2BIN is available to convert Day from BCD to Binary format - * @rmtoll ALRMAR DT LL_RTC_ALMA_GetDay\n - * ALRMAR DU LL_RTC_ALMA_GetDay - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x01 and Max_Data=0x31 - */ -__STATIC_INLINE uint32_t LL_RTC_ALMA_GetDay(RTC_TypeDef *RTCx) -{ - return (uint32_t)((READ_BIT(RTCx->ALRMAR, (RTC_ALRMAR_DT | RTC_ALRMAR_DU))) >> RTC_ALRMAR_DU_Pos); -} - -/** - * @brief Set ALARM A Weekday - * @rmtoll ALRMAR DU LL_RTC_ALMA_SetWeekDay - * @param RTCx RTC Instance - * @param WeekDay This parameter can be one of the following values: - * @arg @ref LL_RTC_WEEKDAY_MONDAY - * @arg @ref LL_RTC_WEEKDAY_TUESDAY - * @arg @ref LL_RTC_WEEKDAY_WEDNESDAY - * @arg @ref LL_RTC_WEEKDAY_THURSDAY - * @arg @ref LL_RTC_WEEKDAY_FRIDAY - * @arg @ref LL_RTC_WEEKDAY_SATURDAY - * @arg @ref LL_RTC_WEEKDAY_SUNDAY - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMA_SetWeekDay(RTC_TypeDef *RTCx, uint32_t WeekDay) -{ - MODIFY_REG(RTCx->ALRMAR, RTC_ALRMAR_DU, WeekDay << RTC_ALRMAR_DU_Pos); -} - -/** - * @brief Get ALARM A Weekday - * @rmtoll ALRMAR DU LL_RTC_ALMA_GetWeekDay - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_WEEKDAY_MONDAY - * @arg @ref LL_RTC_WEEKDAY_TUESDAY - * @arg @ref LL_RTC_WEEKDAY_WEDNESDAY - * @arg @ref LL_RTC_WEEKDAY_THURSDAY - * @arg @ref LL_RTC_WEEKDAY_FRIDAY - * @arg @ref LL_RTC_WEEKDAY_SATURDAY - * @arg @ref LL_RTC_WEEKDAY_SUNDAY - */ -__STATIC_INLINE uint32_t LL_RTC_ALMA_GetWeekDay(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->ALRMAR, RTC_ALRMAR_DU) >> RTC_ALRMAR_DU_Pos); -} - -/** - * @brief Set Alarm A time format (AM/24-hour or PM notation) - * @rmtoll ALRMAR PM LL_RTC_ALMA_SetTimeFormat - * @param RTCx RTC Instance - * @param TimeFormat This parameter can be one of the following values: - * @arg @ref LL_RTC_ALMA_TIME_FORMAT_AM - * @arg @ref LL_RTC_ALMA_TIME_FORMAT_PM - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMA_SetTimeFormat(RTC_TypeDef *RTCx, uint32_t TimeFormat) -{ - MODIFY_REG(RTCx->ALRMAR, RTC_ALRMAR_PM, TimeFormat); -} - -/** - * @brief Get Alarm A time format (AM or PM notation) - * @rmtoll ALRMAR PM LL_RTC_ALMA_GetTimeFormat - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_ALMA_TIME_FORMAT_AM - * @arg @ref LL_RTC_ALMA_TIME_FORMAT_PM - */ -__STATIC_INLINE uint32_t LL_RTC_ALMA_GetTimeFormat(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->ALRMAR, RTC_ALRMAR_PM)); -} - -/** - * @brief Set ALARM A Hours in BCD format - * @note helper macro __LL_RTC_CONVERT_BIN2BCD is available to convert Hours from binary to BCD format - * @rmtoll ALRMAR HT LL_RTC_ALMA_SetHour\n - * ALRMAR HU LL_RTC_ALMA_SetHour - * @param RTCx RTC Instance - * @param Hours Value between Min_Data=0x01 and Max_Data=0x12 or between Min_Data=0x00 and Max_Data=0x23 - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMA_SetHour(RTC_TypeDef *RTCx, uint32_t Hours) -{ - MODIFY_REG(RTCx->ALRMAR, (RTC_ALRMAR_HT | RTC_ALRMAR_HU), - (((Hours & 0xF0U) << (RTC_ALRMAR_HT_Pos - 4U)) | ((Hours & 0x0FU) << RTC_ALRMAR_HU_Pos))); -} - -/** - * @brief Get ALARM A Hours in BCD format - * @note helper macro __LL_RTC_CONVERT_BCD2BIN is available to convert Hours from BCD to Binary format - * @rmtoll ALRMAR HT LL_RTC_ALMA_GetHour\n - * ALRMAR HU LL_RTC_ALMA_GetHour - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x01 and Max_Data=0x12 or between Min_Data=0x00 and Max_Data=0x23 - */ -__STATIC_INLINE uint32_t LL_RTC_ALMA_GetHour(RTC_TypeDef *RTCx) -{ - return (uint32_t)(( READ_BIT(RTCx->ALRMAR, (RTC_ALRMAR_HT | RTC_ALRMAR_HU))) >> RTC_ALRMAR_HU_Pos); -} - -/** - * @brief Set ALARM A Minutes in BCD format - * @note helper macro __LL_RTC_CONVERT_BIN2BCD is available to convert Minutes from binary to BCD format - * @rmtoll ALRMAR MNT LL_RTC_ALMA_SetMinute\n - * ALRMAR MNU LL_RTC_ALMA_SetMinute - * @param RTCx RTC Instance - * @param Minutes Value between Min_Data=0x00 and Max_Data=0x59 - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMA_SetMinute(RTC_TypeDef *RTCx, uint32_t Minutes) -{ - MODIFY_REG(RTCx->ALRMAR, (RTC_ALRMAR_MNT | RTC_ALRMAR_MNU), - (((Minutes & 0xF0U) << (RTC_ALRMAR_MNT_Pos - 4U)) | ((Minutes & 0x0FU) << RTC_ALRMAR_MNU_Pos))); -} - -/** - * @brief Get ALARM A Minutes in BCD format - * @note helper macro __LL_RTC_CONVERT_BCD2BIN is available to convert Minutes from BCD to Binary format - * @rmtoll ALRMAR MNT LL_RTC_ALMA_GetMinute\n - * ALRMAR MNU LL_RTC_ALMA_GetMinute - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x00 and Max_Data=0x59 - */ -__STATIC_INLINE uint32_t LL_RTC_ALMA_GetMinute(RTC_TypeDef *RTCx) -{ - return (uint32_t)((READ_BIT(RTCx->ALRMAR, (RTC_ALRMAR_MNT | RTC_ALRMAR_MNU))) >> RTC_ALRMAR_MNU_Pos); -} - -/** - * @brief Set ALARM A Seconds in BCD format - * @note helper macro __LL_RTC_CONVERT_BIN2BCD is available to convert Seconds from binary to BCD format - * @rmtoll ALRMAR ST LL_RTC_ALMA_SetSecond\n - * ALRMAR SU LL_RTC_ALMA_SetSecond - * @param RTCx RTC Instance - * @param Seconds Value between Min_Data=0x00 and Max_Data=0x59 - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMA_SetSecond(RTC_TypeDef *RTCx, uint32_t Seconds) -{ - MODIFY_REG(RTCx->ALRMAR, (RTC_ALRMAR_ST | RTC_ALRMAR_SU), - (((Seconds & 0xF0U) << (RTC_ALRMAR_ST_Pos - 4U)) | ((Seconds & 0x0FU) << RTC_ALRMAR_SU_Pos))); -} - -/** - * @brief Get ALARM A Seconds in BCD format - * @note helper macro __LL_RTC_CONVERT_BCD2BIN is available to convert Seconds from BCD to Binary format - * @rmtoll ALRMAR ST LL_RTC_ALMA_GetSecond\n - * ALRMAR SU LL_RTC_ALMA_GetSecond - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x00 and Max_Data=0x59 - */ -__STATIC_INLINE uint32_t LL_RTC_ALMA_GetSecond(RTC_TypeDef *RTCx) -{ - return (uint32_t)((READ_BIT(RTCx->ALRMAR, (RTC_ALRMAR_ST | RTC_ALRMAR_SU))) >> RTC_ALRMAR_SU_Pos); -} - -/** - * @brief Set Alarm A Time (hour, minute and second) in BCD format - * @rmtoll ALRMAR PM LL_RTC_ALMA_ConfigTime\n - * ALRMAR HT LL_RTC_ALMA_ConfigTime\n - * ALRMAR HU LL_RTC_ALMA_ConfigTime\n - * ALRMAR MNT LL_RTC_ALMA_ConfigTime\n - * ALRMAR MNU LL_RTC_ALMA_ConfigTime\n - * ALRMAR ST LL_RTC_ALMA_ConfigTime\n - * ALRMAR SU LL_RTC_ALMA_ConfigTime - * @param RTCx RTC Instance - * @param Format12_24 This parameter can be one of the following values: - * @arg @ref LL_RTC_ALMA_TIME_FORMAT_AM - * @arg @ref LL_RTC_ALMA_TIME_FORMAT_PM - * @param Hours Value between Min_Data=0x01 and Max_Data=0x12 or between Min_Data=0x00 and Max_Data=0x23 - * @param Minutes Value between Min_Data=0x00 and Max_Data=0x59 - * @param Seconds Value between Min_Data=0x00 and Max_Data=0x59 - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMA_ConfigTime(RTC_TypeDef *RTCx, uint32_t Format12_24, uint32_t Hours, uint32_t Minutes, uint32_t Seconds) -{ - register uint32_t temp = 0U; - - temp = Format12_24 | (((Hours & 0xF0U) << (RTC_ALRMAR_HT_Pos - 4U)) | ((Hours & 0x0FU) << RTC_ALRMAR_HU_Pos)) | \ - (((Minutes & 0xF0U) << (RTC_ALRMAR_MNT_Pos - 4U)) | ((Minutes & 0x0FU) << RTC_ALRMAR_MNU_Pos)) | \ - (((Seconds & 0xF0U) << (RTC_ALRMAR_ST_Pos - 4U)) | ((Seconds & 0x0FU) << RTC_ALRMAR_SU_Pos)); - - MODIFY_REG(RTCx->ALRMAR, RTC_ALRMAR_PM | RTC_ALRMAR_HT | RTC_ALRMAR_HU | RTC_ALRMAR_MNT | RTC_ALRMAR_MNU | RTC_ALRMAR_ST | RTC_ALRMAR_SU, temp); -} - -/** - * @brief Get Alarm B Time (hour, minute and second) in BCD format - * @note helper macros __LL_RTC_GET_HOUR, __LL_RTC_GET_MINUTE and __LL_RTC_GET_SECOND - * are available to get independently each parameter. - * @rmtoll ALRMAR HT LL_RTC_ALMA_GetTime\n - * ALRMAR HU LL_RTC_ALMA_GetTime\n - * ALRMAR MNT LL_RTC_ALMA_GetTime\n - * ALRMAR MNU LL_RTC_ALMA_GetTime\n - * ALRMAR ST LL_RTC_ALMA_GetTime\n - * ALRMAR SU LL_RTC_ALMA_GetTime - * @param RTCx RTC Instance - * @retval Combination of hours, minutes and seconds. - */ -__STATIC_INLINE uint32_t LL_RTC_ALMA_GetTime(RTC_TypeDef *RTCx) -{ - return (uint32_t)((LL_RTC_ALMA_GetHour(RTCx) << RTC_OFFSET_HOUR) | (LL_RTC_ALMA_GetMinute(RTCx) << RTC_OFFSET_MINUTE) | LL_RTC_ALMA_GetSecond(RTCx)); -} - -/** - * @brief Set Alarm A Mask the most-significant bits starting at this bit - * @note This register can be written only when ALRAE is reset in RTC_CR register, - * or in initialization mode. - * @rmtoll ALRMASSR MASKSS LL_RTC_ALMA_SetSubSecondMask - * @param RTCx RTC Instance - * @param Mask Value between Min_Data=0x00 and Max_Data=0xF - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMA_SetSubSecondMask(RTC_TypeDef *RTCx, uint32_t Mask) -{ - MODIFY_REG(RTCx->ALRMASSR, RTC_ALRMASSR_MASKSS, Mask << RTC_ALRMASSR_MASKSS_Pos); -} - -/** - * @brief Get Alarm A Mask the most-significant bits starting at this bit - * @rmtoll ALRMASSR MASKSS LL_RTC_ALMA_GetSubSecondMask - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x00 and Max_Data=0xF - */ -__STATIC_INLINE uint32_t LL_RTC_ALMA_GetSubSecondMask(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->ALRMASSR, RTC_ALRMASSR_MASKSS) >> RTC_ALRMASSR_MASKSS_Pos); -} - -/** - * @brief Set Alarm A Sub seconds value - * @rmtoll ALRMASSR SS LL_RTC_ALMA_SetSubSecond - * @param RTCx RTC Instance - * @param Subsecond Value between Min_Data=0x00 and Max_Data=0x7FFF - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMA_SetSubSecond(RTC_TypeDef *RTCx, uint32_t Subsecond) -{ - MODIFY_REG(RTCx->ALRMASSR, RTC_ALRMASSR_SS, Subsecond); -} - -/** - * @brief Get Alarm A Sub seconds value - * @rmtoll ALRMASSR SS LL_RTC_ALMA_GetSubSecond - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x00 and Max_Data=0x7FFF - */ -__STATIC_INLINE uint32_t LL_RTC_ALMA_GetSubSecond(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->ALRMASSR, RTC_ALRMASSR_SS)); -} - -/** - * @} - */ - -/** @defgroup RTC_LL_EF_ALARMB ALARMB - * @{ - */ - -/** - * @brief Enable Alarm B - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR ALRBE LL_RTC_ALMB_Enable - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMB_Enable(RTC_TypeDef *RTCx) -{ - SET_BIT(RTCx->CR, RTC_CR_ALRBE); -} - -/** - * @brief Disable Alarm B - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR ALRBE LL_RTC_ALMB_Disable - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMB_Disable(RTC_TypeDef *RTCx) -{ - CLEAR_BIT(RTCx->CR, RTC_CR_ALRBE); -} - -/** - * @brief Specify the Alarm B masks. - * @rmtoll ALRMBR MSK4 LL_RTC_ALMB_SetMask\n - * ALRMBR MSK3 LL_RTC_ALMB_SetMask\n - * ALRMBR MSK2 LL_RTC_ALMB_SetMask\n - * ALRMBR MSK1 LL_RTC_ALMB_SetMask - * @param RTCx RTC Instance - * @param Mask This parameter can be a combination of the following values: - * @arg @ref LL_RTC_ALMB_MASK_NONE - * @arg @ref LL_RTC_ALMB_MASK_DATEWEEKDAY - * @arg @ref LL_RTC_ALMB_MASK_HOURS - * @arg @ref LL_RTC_ALMB_MASK_MINUTES - * @arg @ref LL_RTC_ALMB_MASK_SECONDS - * @arg @ref LL_RTC_ALMB_MASK_ALL - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMB_SetMask(RTC_TypeDef *RTCx, uint32_t Mask) -{ - MODIFY_REG(RTCx->ALRMBR, RTC_ALRMBR_MSK4 | RTC_ALRMBR_MSK3 | RTC_ALRMBR_MSK2 | RTC_ALRMBR_MSK1, Mask); -} - -/** - * @brief Get the Alarm B masks. - * @rmtoll ALRMBR MSK4 LL_RTC_ALMB_GetMask\n - * ALRMBR MSK3 LL_RTC_ALMB_GetMask\n - * ALRMBR MSK2 LL_RTC_ALMB_GetMask\n - * ALRMBR MSK1 LL_RTC_ALMB_GetMask - * @param RTCx RTC Instance - * @retval Returned value can be can be a combination of the following values: - * @arg @ref LL_RTC_ALMB_MASK_NONE - * @arg @ref LL_RTC_ALMB_MASK_DATEWEEKDAY - * @arg @ref LL_RTC_ALMB_MASK_HOURS - * @arg @ref LL_RTC_ALMB_MASK_MINUTES - * @arg @ref LL_RTC_ALMB_MASK_SECONDS - * @arg @ref LL_RTC_ALMB_MASK_ALL - */ -__STATIC_INLINE uint32_t LL_RTC_ALMB_GetMask(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->ALRMBR, RTC_ALRMBR_MSK4 | RTC_ALRMBR_MSK3 | RTC_ALRMBR_MSK2 | RTC_ALRMBR_MSK1)); -} - -/** - * @brief Enable AlarmB Week day selection (DU[3:0] represents the week day. DT[1:0] is do not care) - * @rmtoll ALRMBR WDSEL LL_RTC_ALMB_EnableWeekday - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMB_EnableWeekday(RTC_TypeDef *RTCx) -{ - SET_BIT(RTCx->ALRMBR, RTC_ALRMBR_WDSEL); -} - -/** - * @brief Disable AlarmB Week day selection (DU[3:0] represents the date ) - * @rmtoll ALRMBR WDSEL LL_RTC_ALMB_DisableWeekday - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMB_DisableWeekday(RTC_TypeDef *RTCx) -{ - CLEAR_BIT(RTCx->ALRMBR, RTC_ALRMBR_WDSEL); -} - -/** - * @brief Set ALARM B Day in BCD format - * @note helper macro __LL_RTC_CONVERT_BIN2BCD is available to convert Day from binary to BCD format - * @rmtoll ALRMBR DT LL_RTC_ALMB_SetDay\n - * ALRMBR DU LL_RTC_ALMB_SetDay - * @param RTCx RTC Instance - * @param Day Value between Min_Data=0x01 and Max_Data=0x31 - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMB_SetDay(RTC_TypeDef *RTCx, uint32_t Day) -{ - MODIFY_REG(RTC->ALRMBR, (RTC_ALRMBR_DT | RTC_ALRMBR_DU), - (((Day & 0xF0U) << (RTC_ALRMBR_DT_Pos - 4U)) | ((Day & 0x0FU) << RTC_ALRMBR_DU_Pos))); -} - -/** - * @brief Get ALARM B Day in BCD format - * @note helper macro __LL_RTC_CONVERT_BCD2BIN is available to convert Day from BCD to Binary format - * @rmtoll ALRMBR DT LL_RTC_ALMB_GetDay\n - * ALRMBR DU LL_RTC_ALMB_GetDay - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x01 and Max_Data=0x31 - */ -__STATIC_INLINE uint32_t LL_RTC_ALMB_GetDay(RTC_TypeDef *RTCx) -{ - return (uint32_t)(( READ_BIT(RTCx->ALRMBR, (RTC_ALRMBR_DT | RTC_ALRMBR_DU))) >> RTC_ALRMBR_DU_Pos); -} - -/** - * @brief Set ALARM B Weekday - * @rmtoll ALRMBR DU LL_RTC_ALMB_SetWeekDay - * @param RTCx RTC Instance - * @param WeekDay This parameter can be one of the following values: - * @arg @ref LL_RTC_WEEKDAY_MONDAY - * @arg @ref LL_RTC_WEEKDAY_TUESDAY - * @arg @ref LL_RTC_WEEKDAY_WEDNESDAY - * @arg @ref LL_RTC_WEEKDAY_THURSDAY - * @arg @ref LL_RTC_WEEKDAY_FRIDAY - * @arg @ref LL_RTC_WEEKDAY_SATURDAY - * @arg @ref LL_RTC_WEEKDAY_SUNDAY - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMB_SetWeekDay(RTC_TypeDef *RTCx, uint32_t WeekDay) -{ - MODIFY_REG(RTCx->ALRMBR, RTC_ALRMBR_DU, WeekDay << RTC_ALRMBR_DU_Pos); -} - -/** - * @brief Get ALARM B Weekday - * @rmtoll ALRMBR DU LL_RTC_ALMB_GetWeekDay - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_WEEKDAY_MONDAY - * @arg @ref LL_RTC_WEEKDAY_TUESDAY - * @arg @ref LL_RTC_WEEKDAY_WEDNESDAY - * @arg @ref LL_RTC_WEEKDAY_THURSDAY - * @arg @ref LL_RTC_WEEKDAY_FRIDAY - * @arg @ref LL_RTC_WEEKDAY_SATURDAY - * @arg @ref LL_RTC_WEEKDAY_SUNDAY - */ -__STATIC_INLINE uint32_t LL_RTC_ALMB_GetWeekDay(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->ALRMBR, RTC_ALRMBR_DU) >> RTC_ALRMBR_DU_Pos); -} - -/** - * @brief Set ALARM B time format (AM/24-hour or PM notation) - * @rmtoll ALRMBR PM LL_RTC_ALMB_SetTimeFormat - * @param RTCx RTC Instance - * @param TimeFormat This parameter can be one of the following values: - * @arg @ref LL_RTC_ALMB_TIME_FORMAT_AM - * @arg @ref LL_RTC_ALMB_TIME_FORMAT_PM - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMB_SetTimeFormat(RTC_TypeDef *RTCx, uint32_t TimeFormat) -{ - MODIFY_REG(RTCx->ALRMBR, RTC_ALRMBR_PM, TimeFormat); -} - -/** - * @brief Get ALARM B time format (AM or PM notation) - * @rmtoll ALRMBR PM LL_RTC_ALMB_GetTimeFormat - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_ALMB_TIME_FORMAT_AM - * @arg @ref LL_RTC_ALMB_TIME_FORMAT_PM - */ -__STATIC_INLINE uint32_t LL_RTC_ALMB_GetTimeFormat(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->ALRMBR, RTC_ALRMBR_PM)); -} - -/** - * @brief Set ALARM B Hours in BCD format - * @note helper macro __LL_RTC_CONVERT_BIN2BCD is available to convert Hours from binary to BCD format - * @rmtoll ALRMBR HT LL_RTC_ALMB_SetHour\n - * ALRMBR HU LL_RTC_ALMB_SetHour - * @param RTCx RTC Instance - * @param Hours Value between Min_Data=0x01 and Max_Data=0x12 or between Min_Data=0x00 and Max_Data=0x23 - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMB_SetHour(RTC_TypeDef *RTCx, uint32_t Hours) -{ - MODIFY_REG(RTCx->ALRMBR, (RTC_ALRMBR_HT | RTC_ALRMBR_HU), - (((Hours & 0xF0U) << (RTC_ALRMBR_HT_Pos - 4U)) | ((Hours & 0x0FU) << RTC_ALRMBR_HU_Pos))); -} - -/** - * @brief Get ALARM B Hours in BCD format - * @note helper macro __LL_RTC_CONVERT_BCD2BIN is available to convert Hours from BCD to Binary format - * @rmtoll ALRMBR HT LL_RTC_ALMB_GetHour\n - * ALRMBR HU LL_RTC_ALMB_GetHour - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x01 and Max_Data=0x12 or between Min_Data=0x00 and Max_Data=0x23 - */ -__STATIC_INLINE uint32_t LL_RTC_ALMB_GetHour(RTC_TypeDef *RTCx) -{ - return (uint32_t)((READ_BIT(RTCx->ALRMBR, (RTC_ALRMBR_HT | RTC_ALRMBR_HU))) >> RTC_ALRMBR_HU_Pos); -} - -/** - * @brief Set ALARM B Minutes in BCD format - * @note helper macro __LL_RTC_CONVERT_BIN2BCD is available to convert Minutes from binary to BCD format - * @rmtoll ALRMBR MNT LL_RTC_ALMB_SetMinute\n - * ALRMBR MNU LL_RTC_ALMB_SetMinute - * @param RTCx RTC Instance - * @param Minutes between Min_Data=0x00 and Max_Data=0x59 - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMB_SetMinute(RTC_TypeDef *RTCx, uint32_t Minutes) -{ - MODIFY_REG(RTCx->ALRMBR, (RTC_ALRMBR_MNT | RTC_ALRMBR_MNU), - (((Minutes & 0xF0U) << (RTC_ALRMBR_MNT_Pos - 4U)) | ((Minutes & 0x0FU) << RTC_ALRMBR_MNU_Pos))); -} - -/** - * @brief Get ALARM B Minutes in BCD format - * @note helper macro __LL_RTC_CONVERT_BCD2BIN is available to convert Minutes from BCD to Binary format - * @rmtoll ALRMBR MNT LL_RTC_ALMB_GetMinute\n - * ALRMBR MNU LL_RTC_ALMB_GetMinute - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x00 and Max_Data=0x59 - */ -__STATIC_INLINE uint32_t LL_RTC_ALMB_GetMinute(RTC_TypeDef *RTCx) -{ - return (uint32_t)((READ_BIT(RTCx->ALRMBR, (RTC_ALRMBR_MNT | RTC_ALRMBR_MNU))) >> RTC_ALRMBR_MNU_Pos); -} - -/** - * @brief Set ALARM B Seconds in BCD format - * @note helper macro __LL_RTC_CONVERT_BIN2BCD is available to convert Seconds from binary to BCD format - * @rmtoll ALRMBR ST LL_RTC_ALMB_SetSecond\n - * ALRMBR SU LL_RTC_ALMB_SetSecond - * @param RTCx RTC Instance - * @param Seconds Value between Min_Data=0x00 and Max_Data=0x59 - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMB_SetSecond(RTC_TypeDef *RTCx, uint32_t Seconds) -{ - MODIFY_REG(RTCx->ALRMBR, (RTC_ALRMBR_ST | RTC_ALRMBR_SU), - (((Seconds & 0xF0U) << (RTC_ALRMBR_ST_Pos - 4U)) | ((Seconds & 0x0FU) << RTC_ALRMBR_SU_Pos))); -} - -/** - * @brief Get ALARM B Seconds in BCD format - * @note helper macro __LL_RTC_CONVERT_BCD2BIN is available to convert Seconds from BCD to Binary format - * @rmtoll ALRMBR ST LL_RTC_ALMB_GetSecond\n - * ALRMBR SU LL_RTC_ALMB_GetSecond - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x00 and Max_Data=0x59 - */ -__STATIC_INLINE uint32_t LL_RTC_ALMB_GetSecond(RTC_TypeDef *RTCx) -{ - register uint32_t temp = 0U; - - temp = READ_BIT(RTCx->ALRMBR, (RTC_ALRMBR_ST | RTC_ALRMBR_SU)); - return (uint32_t)((((temp & RTC_ALRMBR_ST) >> RTC_ALRMBR_ST_Pos) << 4U) | ((temp & RTC_ALRMBR_SU) >> RTC_ALRMBR_SU_Pos)); -} - -/** - * @brief Set Alarm B Time (hour, minute and second) in BCD format - * @rmtoll ALRMBR PM LL_RTC_ALMB_ConfigTime\n - * ALRMBR HT LL_RTC_ALMB_ConfigTime\n - * ALRMBR HU LL_RTC_ALMB_ConfigTime\n - * ALRMBR MNT LL_RTC_ALMB_ConfigTime\n - * ALRMBR MNU LL_RTC_ALMB_ConfigTime\n - * ALRMBR ST LL_RTC_ALMB_ConfigTime\n - * ALRMBR SU LL_RTC_ALMB_ConfigTime - * @param RTCx RTC Instance - * @param Format12_24 This parameter can be one of the following values: - * @arg @ref LL_RTC_ALMB_TIME_FORMAT_AM - * @arg @ref LL_RTC_ALMB_TIME_FORMAT_PM - * @param Hours Value between Min_Data=0x01 and Max_Data=0x12 or between Min_Data=0x00 and Max_Data=0x23 - * @param Minutes Value between Min_Data=0x00 and Max_Data=0x59 - * @param Seconds Value between Min_Data=0x00 and Max_Data=0x59 - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMB_ConfigTime(RTC_TypeDef *RTCx, uint32_t Format12_24, uint32_t Hours, uint32_t Minutes, uint32_t Seconds) -{ - register uint32_t temp = 0U; - - temp = Format12_24 | (((Hours & 0xF0U) << (RTC_ALRMBR_HT_Pos - 4U)) | ((Hours & 0x0FU) << RTC_ALRMBR_HU_Pos)) | \ - (((Minutes & 0xF0U) << (RTC_ALRMBR_MNT_Pos - 4U)) | ((Minutes & 0x0FU) << RTC_ALRMBR_MNU_Pos)) | \ - (((Seconds & 0xF0U) << (RTC_ALRMBR_ST_Pos - 4U)) | ((Seconds & 0x0FU) << RTC_ALRMBR_SU_Pos)); - - MODIFY_REG(RTCx->ALRMBR, RTC_ALRMBR_PM| RTC_ALRMBR_HT | RTC_ALRMBR_HU | RTC_ALRMBR_MNT | RTC_ALRMBR_MNU | RTC_ALRMBR_ST | RTC_ALRMBR_SU, temp); -} - -/** - * @brief Get Alarm B Time (hour, minute and second) in BCD format - * @note helper macros __LL_RTC_GET_HOUR, __LL_RTC_GET_MINUTE and __LL_RTC_GET_SECOND - * are available to get independently each parameter. - * @rmtoll ALRMBR HT LL_RTC_ALMB_GetTime\n - * ALRMBR HU LL_RTC_ALMB_GetTime\n - * ALRMBR MNT LL_RTC_ALMB_GetTime\n - * ALRMBR MNU LL_RTC_ALMB_GetTime\n - * ALRMBR ST LL_RTC_ALMB_GetTime\n - * ALRMBR SU LL_RTC_ALMB_GetTime - * @param RTCx RTC Instance - * @retval Combination of hours, minutes and seconds. - */ -__STATIC_INLINE uint32_t LL_RTC_ALMB_GetTime(RTC_TypeDef *RTCx) -{ - return (uint32_t)((LL_RTC_ALMB_GetHour(RTCx) << RTC_OFFSET_HOUR) | (LL_RTC_ALMB_GetMinute(RTCx) << RTC_OFFSET_MINUTE) | LL_RTC_ALMB_GetSecond(RTCx)); -} - -/** - * @brief Set Alarm B Mask the most-significant bits starting at this bit - * @note This register can be written only when ALRBE is reset in RTC_CR register, - * or in initialization mode. - * @rmtoll ALRMBSSR MASKSS LL_RTC_ALMB_SetSubSecondMask - * @param RTCx RTC Instance - * @param Mask Value between Min_Data=0x00 and Max_Data=0xF - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMB_SetSubSecondMask(RTC_TypeDef *RTCx, uint32_t Mask) -{ - MODIFY_REG(RTCx->ALRMBSSR, RTC_ALRMBSSR_MASKSS, Mask << RTC_ALRMBSSR_MASKSS_Pos); -} - -/** - * @brief Get Alarm B Mask the most-significant bits starting at this bit - * @rmtoll ALRMBSSR MASKSS LL_RTC_ALMB_GetSubSecondMask - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x00 and Max_Data=0xF - */ -__STATIC_INLINE uint32_t LL_RTC_ALMB_GetSubSecondMask(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->ALRMBSSR, RTC_ALRMBSSR_MASKSS) >> RTC_ALRMBSSR_MASKSS_Pos); -} - -/** - * @brief Set Alarm B Sub seconds value - * @rmtoll ALRMBSSR SS LL_RTC_ALMB_SetSubSecond - * @param RTCx RTC Instance - * @param Subsecond Value between Min_Data=0x00 and Max_Data=0x7FFF - * @retval None - */ -__STATIC_INLINE void LL_RTC_ALMB_SetSubSecond(RTC_TypeDef *RTCx, uint32_t Subsecond) -{ - MODIFY_REG(RTCx->ALRMBSSR, RTC_ALRMBSSR_SS, Subsecond); -} - -/** - * @brief Get Alarm B Sub seconds value - * @rmtoll ALRMBSSR SS LL_RTC_ALMB_GetSubSecond - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x00 and Max_Data=0x7FFF - */ -__STATIC_INLINE uint32_t LL_RTC_ALMB_GetSubSecond(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->ALRMBSSR, RTC_ALRMBSSR_SS)); -} - -/** - * @} - */ - -/** @defgroup RTC_LL_EF_Timestamp Timestamp - * @{ - */ - -/** - * @brief Enable Timestamp - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR TSE LL_RTC_TS_Enable - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_TS_Enable(RTC_TypeDef *RTCx) -{ - SET_BIT(RTCx->CR, RTC_CR_TSE); -} - -/** - * @brief Disable Timestamp - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR TSE LL_RTC_TS_Disable - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_TS_Disable(RTC_TypeDef *RTCx) -{ - CLEAR_BIT(RTCx->CR, RTC_CR_TSE); -} - -/** - * @brief Set Time-stamp event active edge - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @note TSE must be reset when TSEDGE is changed to avoid unwanted TSF setting - * @rmtoll CR TSEDGE LL_RTC_TS_SetActiveEdge - * @param RTCx RTC Instance - * @param Edge This parameter can be one of the following values: - * @arg @ref LL_RTC_TIMESTAMP_EDGE_RISING - * @arg @ref LL_RTC_TIMESTAMP_EDGE_FALLING - * @retval None - */ -__STATIC_INLINE void LL_RTC_TS_SetActiveEdge(RTC_TypeDef *RTCx, uint32_t Edge) -{ - MODIFY_REG(RTCx->CR, RTC_CR_TSEDGE, Edge); -} - -/** - * @brief Get Time-stamp event active edge - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR TSEDGE LL_RTC_TS_GetActiveEdge - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_TIMESTAMP_EDGE_RISING - * @arg @ref LL_RTC_TIMESTAMP_EDGE_FALLING - */ -__STATIC_INLINE uint32_t LL_RTC_TS_GetActiveEdge(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->CR, RTC_CR_TSEDGE)); -} - -/** - * @brief Get Timestamp AM/PM notation (AM or 24-hour format) - * @rmtoll TSTR PM LL_RTC_TS_GetTimeFormat - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_TS_TIME_FORMAT_AM - * @arg @ref LL_RTC_TS_TIME_FORMAT_PM - */ -__STATIC_INLINE uint32_t LL_RTC_TS_GetTimeFormat(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->TSTR, RTC_TSTR_PM)); -} - -/** - * @brief Get Timestamp Hours in BCD format - * @note helper macro __LL_RTC_CONVERT_BCD2BIN is available to convert Hours from BCD to Binary format - * @rmtoll TSTR HT LL_RTC_TS_GetHour\n - * TSTR HU LL_RTC_TS_GetHour - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x01 and Max_Data=0x12 or between Min_Data=0x00 and Max_Data=0x23 - */ -__STATIC_INLINE uint32_t LL_RTC_TS_GetHour(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->TSTR, RTC_TSTR_HT | RTC_TSTR_HU) >> RTC_TSTR_HU_Pos); -} - -/** - * @brief Get Timestamp Minutes in BCD format - * @note helper macro __LL_RTC_CONVERT_BCD2BIN is available to convert Minutes from BCD to Binary format - * @rmtoll TSTR MNT LL_RTC_TS_GetMinute\n - * TSTR MNU LL_RTC_TS_GetMinute - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x00 and Max_Data=0x59 - */ -__STATIC_INLINE uint32_t LL_RTC_TS_GetMinute(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->TSTR, RTC_TSTR_MNT | RTC_TSTR_MNU) >> RTC_TSTR_MNU_Pos); -} - -/** - * @brief Get Timestamp Seconds in BCD format - * @note helper macro __LL_RTC_CONVERT_BCD2BIN is available to convert Seconds from BCD to Binary format - * @rmtoll TSTR ST LL_RTC_TS_GetSecond\n - * TSTR SU LL_RTC_TS_GetSecond - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x00 and Max_Data=0x59 - */ -__STATIC_INLINE uint32_t LL_RTC_TS_GetSecond(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->TSTR, RTC_TSTR_ST | RTC_TSTR_SU)); -} - -/** - * @brief Get Timestamp time (hour, minute and second) in BCD format - * @note helper macros __LL_RTC_GET_HOUR, __LL_RTC_GET_MINUTE and __LL_RTC_GET_SECOND - * are available to get independently each parameter. - * @rmtoll TSTR HT LL_RTC_TS_GetTime\n - * TSTR HU LL_RTC_TS_GetTime\n - * TSTR MNT LL_RTC_TS_GetTime\n - * TSTR MNU LL_RTC_TS_GetTime\n - * TSTR ST LL_RTC_TS_GetTime\n - * TSTR SU LL_RTC_TS_GetTime - * @param RTCx RTC Instance - * @retval Combination of hours, minutes and seconds. - */ -__STATIC_INLINE uint32_t LL_RTC_TS_GetTime(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->TSTR, - RTC_TSTR_HT | RTC_TSTR_HU | RTC_TSTR_MNT | RTC_TSTR_MNU | RTC_TSTR_ST | RTC_TSTR_SU)); -} - -/** - * @brief Get Timestamp Week day - * @rmtoll TSDR WDU LL_RTC_TS_GetWeekDay - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_WEEKDAY_MONDAY - * @arg @ref LL_RTC_WEEKDAY_TUESDAY - * @arg @ref LL_RTC_WEEKDAY_WEDNESDAY - * @arg @ref LL_RTC_WEEKDAY_THURSDAY - * @arg @ref LL_RTC_WEEKDAY_FRIDAY - * @arg @ref LL_RTC_WEEKDAY_SATURDAY - * @arg @ref LL_RTC_WEEKDAY_SUNDAY - */ -__STATIC_INLINE uint32_t LL_RTC_TS_GetWeekDay(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->TSDR, RTC_TSDR_WDU) >> RTC_TSDR_WDU_Pos); -} - -/** - * @brief Get Timestamp Month in BCD format - * @note helper macro __LL_RTC_CONVERT_BCD2BIN is available to convert Month from BCD to Binary format - * @rmtoll TSDR MT LL_RTC_TS_GetMonth\n - * TSDR MU LL_RTC_TS_GetMonth - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_MONTH_JANUARY - * @arg @ref LL_RTC_MONTH_FEBRUARY - * @arg @ref LL_RTC_MONTH_MARCH - * @arg @ref LL_RTC_MONTH_APRIL - * @arg @ref LL_RTC_MONTH_MAY - * @arg @ref LL_RTC_MONTH_JUNE - * @arg @ref LL_RTC_MONTH_JULY - * @arg @ref LL_RTC_MONTH_AUGUST - * @arg @ref LL_RTC_MONTH_SEPTEMBER - * @arg @ref LL_RTC_MONTH_OCTOBER - * @arg @ref LL_RTC_MONTH_NOVEMBER - * @arg @ref LL_RTC_MONTH_DECEMBER - */ -__STATIC_INLINE uint32_t LL_RTC_TS_GetMonth(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->TSDR, RTC_TSDR_MT | RTC_TSDR_MU) >> RTC_TSDR_MU_Pos); -} - -/** - * @brief Get Timestamp Day in BCD format - * @note helper macro __LL_RTC_CONVERT_BCD2BIN is available to convert Day from BCD to Binary format - * @rmtoll TSDR DT LL_RTC_TS_GetDay\n - * TSDR DU LL_RTC_TS_GetDay - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x01 and Max_Data=0x31 - */ -__STATIC_INLINE uint32_t LL_RTC_TS_GetDay(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->TSDR, RTC_TSDR_DT | RTC_TSDR_DU)); -} - -/** - * @brief Get Timestamp date (WeekDay, Day and Month) in BCD format - * @note helper macros __LL_RTC_GET_WEEKDAY, __LL_RTC_GET_MONTH, - * and __LL_RTC_GET_DAY are available to get independently each parameter. - * @rmtoll TSDR WDU LL_RTC_TS_GetDate\n - * TSDR MT LL_RTC_TS_GetDate\n - * TSDR MU LL_RTC_TS_GetDate\n - * TSDR DT LL_RTC_TS_GetDate\n - * TSDR DU LL_RTC_TS_GetDate - * @param RTCx RTC Instance - * @retval Combination of Weekday, Day and Month - */ -__STATIC_INLINE uint32_t LL_RTC_TS_GetDate(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->TSDR, RTC_TSDR_WDU | RTC_TSDR_MT | RTC_TSDR_MU | RTC_TSDR_DT | RTC_TSDR_DU)); -} - -/** - * @brief Get time-stamp sub second value - * @rmtoll TSSSR SS LL_RTC_TS_GetSubSecond - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x00 and Max_Data=0xFFFF - */ -__STATIC_INLINE uint32_t LL_RTC_TS_GetSubSecond(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->TSSSR, RTC_TSSSR_SS)); -} - -#if defined(RTC_TAFCR_TAMPTS) -/** - * @brief Activate timestamp on tamper detection event - * @rmtoll TAFCR TAMPTS LL_RTC_TS_EnableOnTamper - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_TS_EnableOnTamper(RTC_TypeDef *RTCx) -{ - SET_BIT(RTCx->TAFCR, RTC_TAFCR_TAMPTS); -} - -/** - * @brief Disable timestamp on tamper detection event - * @rmtoll TAFCR TAMPTS LL_RTC_TS_DisableOnTamper - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_TS_DisableOnTamper(RTC_TypeDef *RTCx) -{ - CLEAR_BIT(RTCx->TAFCR, RTC_TAFCR_TAMPTS); -} -#endif /* RTC_TAFCR_TAMPTS */ - -/** - * @brief Set timestamp Pin - * @rmtoll TAFCR TSINSEL LL_RTC_TS_SetPin - * @param RTCx RTC Instance - * @param TSPin specifies the RTC TimeStamp Pin. - * This parameter can be one of the following values: - * @arg LL_RTC_TimeStampPin_Default: RTC_AF1 is used as RTC TimeStamp. - * @arg LL_RTC_TimeStampPin_Pos1: RTC_AF2 is selected as RTC TimeStamp. (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RTC_TS_SetPin(RTC_TypeDef *RTCx, uint32_t TSPin) -{ - MODIFY_REG(RTCx->TAFCR, RTC_TAFCR_TSINSEL , TSPin); -} - -/** - * @brief Get timestamp Pin - * @rmtoll TAFCR TSINSEL LL_RTC_TS_GetPin - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg LL_RTC_TimeStampPin_Default: RTC_AF1 is used as RTC TimeStamp Pin. - * @arg LL_RTC_TimeStampPin_Pos1: RTC_AF2 is selected as RTC TimeStamp Pin. (*) - * - * (*) value not defined in all devices. - * @retval None - */ - -__STATIC_INLINE uint32_t LL_RTC_TS_GetPin(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->TAFCR, RTC_TAFCR_TSINSEL)); -} - -/** - * @} - */ - -/** @defgroup RTC_LL_EF_Tamper Tamper - * @{ - */ - -/** - * @brief Enable RTC_TAMPx input detection - * @rmtoll TAFCR TAMP1E LL_RTC_TAMPER_Enable\n - * TAFCR TAMP2E LL_RTC_TAMPER_Enable\n - * @param RTCx RTC Instance - * @param Tamper This parameter can be a combination of the following values: - * @arg @ref LL_RTC_TAMPER_1 - * @arg @ref LL_RTC_TAMPER_2 (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RTC_TAMPER_Enable(RTC_TypeDef *RTCx, uint32_t Tamper) -{ - SET_BIT(RTCx->TAFCR, Tamper); -} - -/** - * @brief Clear RTC_TAMPx input detection - * @rmtoll TAFCR TAMP1E LL_RTC_TAMPER_Disable\n - * TAFCR TAMP2E LL_RTC_TAMPER_Disable\n - * @param RTCx RTC Instance - * @param Tamper This parameter can be a combination of the following values: - * @arg @ref LL_RTC_TAMPER_1 - * @arg @ref LL_RTC_TAMPER_2 (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RTC_TAMPER_Disable(RTC_TypeDef *RTCx, uint32_t Tamper) -{ - CLEAR_BIT(RTCx->TAFCR, Tamper); -} - -#if defined(RTC_TAFCR_TAMPPUDIS) -/** - * @brief Disable RTC_TAMPx pull-up disable (Disable precharge of RTC_TAMPx pins) - * @rmtoll TAFCR TAMPPUDIS LL_RTC_TAMPER_DisablePullUp - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_TAMPER_DisablePullUp(RTC_TypeDef *RTCx) -{ - SET_BIT(RTCx->TAFCR, RTC_TAFCR_TAMPPUDIS); -} - -/** - * @brief Enable RTC_TAMPx pull-up disable ( Precharge RTC_TAMPx pins before sampling) - * @rmtoll TAFCR TAMPPUDIS LL_RTC_TAMPER_EnablePullUp - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_TAMPER_EnablePullUp(RTC_TypeDef *RTCx) -{ - CLEAR_BIT(RTCx->TAFCR, RTC_TAFCR_TAMPPUDIS); -} -#endif /* RTC_TAFCR_TAMPPUDIS */ - -#if defined(RTC_TAFCR_TAMPPRCH) -/** - * @brief Set RTC_TAMPx precharge duration - * @rmtoll TAFCR TAMPPRCH LL_RTC_TAMPER_SetPrecharge - * @param RTCx RTC Instance - * @param Duration This parameter can be one of the following values: - * @arg @ref LL_RTC_TAMPER_DURATION_1RTCCLK - * @arg @ref LL_RTC_TAMPER_DURATION_2RTCCLK - * @arg @ref LL_RTC_TAMPER_DURATION_4RTCCLK - * @arg @ref LL_RTC_TAMPER_DURATION_8RTCCLK - * @retval None - */ -__STATIC_INLINE void LL_RTC_TAMPER_SetPrecharge(RTC_TypeDef *RTCx, uint32_t Duration) -{ - MODIFY_REG(RTCx->TAFCR, RTC_TAFCR_TAMPPRCH, Duration); -} - -/** - * @brief Get RTC_TAMPx precharge duration - * @rmtoll TAFCR TAMPPRCH LL_RTC_TAMPER_GetPrecharge - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_TAMPER_DURATION_1RTCCLK - * @arg @ref LL_RTC_TAMPER_DURATION_2RTCCLK - * @arg @ref LL_RTC_TAMPER_DURATION_4RTCCLK - * @arg @ref LL_RTC_TAMPER_DURATION_8RTCCLK - */ -__STATIC_INLINE uint32_t LL_RTC_TAMPER_GetPrecharge(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->TAFCR, RTC_TAFCR_TAMPPRCH)); -} -#endif /* RTC_TAFCR_TAMPPRCH */ - -#if defined(RTC_TAFCR_TAMPFLT) -/** - * @brief Set RTC_TAMPx filter count - * @rmtoll TAFCR TAMPFLT LL_RTC_TAMPER_SetFilterCount - * @param RTCx RTC Instance - * @param FilterCount This parameter can be one of the following values: - * @arg @ref LL_RTC_TAMPER_FILTER_DISABLE - * @arg @ref LL_RTC_TAMPER_FILTER_2SAMPLE - * @arg @ref LL_RTC_TAMPER_FILTER_4SAMPLE - * @arg @ref LL_RTC_TAMPER_FILTER_8SAMPLE - * @retval None - */ -__STATIC_INLINE void LL_RTC_TAMPER_SetFilterCount(RTC_TypeDef *RTCx, uint32_t FilterCount) -{ - MODIFY_REG(RTCx->TAFCR, RTC_TAFCR_TAMPFLT, FilterCount); -} - -/** - * @brief Get RTC_TAMPx filter count - * @rmtoll TAFCR TAMPFLT LL_RTC_TAMPER_GetFilterCount - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_TAMPER_FILTER_DISABLE - * @arg @ref LL_RTC_TAMPER_FILTER_2SAMPLE - * @arg @ref LL_RTC_TAMPER_FILTER_4SAMPLE - * @arg @ref LL_RTC_TAMPER_FILTER_8SAMPLE - */ -__STATIC_INLINE uint32_t LL_RTC_TAMPER_GetFilterCount(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->TAFCR, RTC_TAFCR_TAMPFLT)); -} -#endif /* RTC_TAFCR_TAMPFLT */ - -#if defined(RTC_TAFCR_TAMPFREQ) -/** - * @brief Set Tamper sampling frequency - * @rmtoll TAFCR TAMPFREQ LL_RTC_TAMPER_SetSamplingFreq - * @param RTCx RTC Instance - * @param SamplingFreq This parameter can be one of the following values: - * @arg @ref LL_RTC_TAMPER_SAMPLFREQDIV_32768 - * @arg @ref LL_RTC_TAMPER_SAMPLFREQDIV_16384 - * @arg @ref LL_RTC_TAMPER_SAMPLFREQDIV_8192 - * @arg @ref LL_RTC_TAMPER_SAMPLFREQDIV_4096 - * @arg @ref LL_RTC_TAMPER_SAMPLFREQDIV_2048 - * @arg @ref LL_RTC_TAMPER_SAMPLFREQDIV_1024 - * @arg @ref LL_RTC_TAMPER_SAMPLFREQDIV_512 - * @arg @ref LL_RTC_TAMPER_SAMPLFREQDIV_256 - * @retval None - */ -__STATIC_INLINE void LL_RTC_TAMPER_SetSamplingFreq(RTC_TypeDef *RTCx, uint32_t SamplingFreq) -{ - MODIFY_REG(RTCx->TAFCR, RTC_TAFCR_TAMPFREQ, SamplingFreq); -} - -/** - * @brief Get Tamper sampling frequency - * @rmtoll TAFCR TAMPFREQ LL_RTC_TAMPER_GetSamplingFreq - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_TAMPER_SAMPLFREQDIV_32768 - * @arg @ref LL_RTC_TAMPER_SAMPLFREQDIV_16384 - * @arg @ref LL_RTC_TAMPER_SAMPLFREQDIV_8192 - * @arg @ref LL_RTC_TAMPER_SAMPLFREQDIV_4096 - * @arg @ref LL_RTC_TAMPER_SAMPLFREQDIV_2048 - * @arg @ref LL_RTC_TAMPER_SAMPLFREQDIV_1024 - * @arg @ref LL_RTC_TAMPER_SAMPLFREQDIV_512 - * @arg @ref LL_RTC_TAMPER_SAMPLFREQDIV_256 - */ -__STATIC_INLINE uint32_t LL_RTC_TAMPER_GetSamplingFreq(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->TAFCR, RTC_TAFCR_TAMPFREQ)); -} -#endif /* RTC_TAFCR_TAMPFREQ */ - -/** - * @brief Enable Active level for Tamper input - * @rmtoll TAFCR TAMP1TRG LL_RTC_TAMPER_EnableActiveLevel\n - * TAFCR TAMP2TRG LL_RTC_TAMPER_EnableActiveLevel\n - * @param RTCx RTC Instance - * @param Tamper This parameter can be a combination of the following values: - * @arg @ref LL_RTC_TAMPER_ACTIVELEVEL_TAMP1 - * @arg @ref LL_RTC_TAMPER_ACTIVELEVEL_TAMP2 (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RTC_TAMPER_EnableActiveLevel(RTC_TypeDef *RTCx, uint32_t Tamper) -{ - SET_BIT(RTCx->TAFCR, Tamper); -} - -/** - * @brief Disable Active level for Tamper input - * @rmtoll TAFCR TAMP1TRG LL_RTC_TAMPER_DisableActiveLevel\n - * TAFCR TAMP2TRG LL_RTC_TAMPER_DisableActiveLevel\n - * @param RTCx RTC Instance - * @param Tamper This parameter can be a combination of the following values: - * @arg @ref LL_RTC_TAMPER_ACTIVELEVEL_TAMP1 - * @arg @ref LL_RTC_TAMPER_ACTIVELEVEL_TAMP2 (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RTC_TAMPER_DisableActiveLevel(RTC_TypeDef *RTCx, uint32_t Tamper) -{ - CLEAR_BIT(RTCx->TAFCR, Tamper); -} - -/** - * @brief Set Tamper Pin - * @rmtoll TAFCR TAMP1INSEL LL_RTC_TAMPER_SetPin - * @param RTCx RTC Instance - * @param TamperPin specifies the RTC Tamper Pin. - * This parameter can be one of the following values: - * @arg LL_RTC_TamperPin_Default: RTC_AF1 is used as RTC Tamper. - * @arg LL_RTC_TamperPin_Pos1: RTC_AF2 is selected as RTC Tamper. (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_RTC_TAMPER_SetPin(RTC_TypeDef *RTCx, uint32_t TamperPin) -{ - MODIFY_REG(RTCx->TAFCR, RTC_TAFCR_TAMP1INSEL , TamperPin); -} - -/** - * @brief Get Tamper Pin - * @rmtoll TAFCR TAMP1INSEL LL_RTC_TAMPER_GetPin - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg LL_RTC_TamperPin_Default: RTC_AF1 is used as RTC Tamper Pin. - * @arg LL_RTC_TamperPin_Pos1: RTC_AF2 is selected as RTC Tamper Pin. (*) - * - * (*) value not defined in all devices. - * @retval None - */ - -__STATIC_INLINE uint32_t LL_RTC_TAMPER_GetPin(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->TAFCR, RTC_TAFCR_TAMP1INSEL)); -} - -/** - * @} - */ - -/** @defgroup RTC_LL_EF_Wakeup Wakeup - * @{ - */ - -/** - * @brief Enable Wakeup timer - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR WUTE LL_RTC_WAKEUP_Enable - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_WAKEUP_Enable(RTC_TypeDef *RTCx) -{ - SET_BIT(RTCx->CR, RTC_CR_WUTE); -} - -/** - * @brief Disable Wakeup timer - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR WUTE LL_RTC_WAKEUP_Disable - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_WAKEUP_Disable(RTC_TypeDef *RTCx) -{ - CLEAR_BIT(RTCx->CR, RTC_CR_WUTE); -} - -/** - * @brief Check if Wakeup timer is enabled or not - * @rmtoll CR WUTE LL_RTC_WAKEUP_IsEnabled - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_WAKEUP_IsEnabled(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->CR, RTC_CR_WUTE) == (RTC_CR_WUTE)); -} - -/** - * @brief Select Wakeup clock - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @note Bit can be written only when RTC_CR WUTE bit = 0 and RTC_ISR WUTWF bit = 1 - * @rmtoll CR WUCKSEL LL_RTC_WAKEUP_SetClock - * @param RTCx RTC Instance - * @param WakeupClock This parameter can be one of the following values: - * @arg @ref LL_RTC_WAKEUPCLOCK_DIV_16 - * @arg @ref LL_RTC_WAKEUPCLOCK_DIV_8 - * @arg @ref LL_RTC_WAKEUPCLOCK_DIV_4 - * @arg @ref LL_RTC_WAKEUPCLOCK_DIV_2 - * @arg @ref LL_RTC_WAKEUPCLOCK_CKSPRE - * @arg @ref LL_RTC_WAKEUPCLOCK_CKSPRE_WUT - * @retval None - */ -__STATIC_INLINE void LL_RTC_WAKEUP_SetClock(RTC_TypeDef *RTCx, uint32_t WakeupClock) -{ - MODIFY_REG(RTCx->CR, RTC_CR_WUCKSEL, WakeupClock); -} - -/** - * @brief Get Wakeup clock - * @rmtoll CR WUCKSEL LL_RTC_WAKEUP_GetClock - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_WAKEUPCLOCK_DIV_16 - * @arg @ref LL_RTC_WAKEUPCLOCK_DIV_8 - * @arg @ref LL_RTC_WAKEUPCLOCK_DIV_4 - * @arg @ref LL_RTC_WAKEUPCLOCK_DIV_2 - * @arg @ref LL_RTC_WAKEUPCLOCK_CKSPRE - * @arg @ref LL_RTC_WAKEUPCLOCK_CKSPRE_WUT - */ -__STATIC_INLINE uint32_t LL_RTC_WAKEUP_GetClock(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->CR, RTC_CR_WUCKSEL)); -} - -/** - * @brief Set Wakeup auto-reload value - * @note Bit can be written only when WUTWF is set to 1 in RTC_ISR - * @rmtoll WUTR WUT LL_RTC_WAKEUP_SetAutoReload - * @param RTCx RTC Instance - * @param Value Value between Min_Data=0x00 and Max_Data=0xFFFF - * @retval None - */ -__STATIC_INLINE void LL_RTC_WAKEUP_SetAutoReload(RTC_TypeDef *RTCx, uint32_t Value) -{ - MODIFY_REG(RTCx->WUTR, RTC_WUTR_WUT, Value); -} - -/** - * @brief Get Wakeup auto-reload value - * @rmtoll WUTR WUT LL_RTC_WAKEUP_GetAutoReload - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x00 and Max_Data=0xFFFF - */ -__STATIC_INLINE uint32_t LL_RTC_WAKEUP_GetAutoReload(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->WUTR, RTC_WUTR_WUT)); -} - -/** - * @} - */ - -/** @defgroup RTC_LL_EF_Backup_Registers Backup_Registers - * @{ - */ - -/** - * @brief Writes a data in a specified RTC Backup data register. - * @rmtoll BKPxR BKP LL_RTC_BAK_SetRegister - * @param RTCx RTC Instance - * @param BackupRegister This parameter can be one of the following values: - * @arg @ref LL_RTC_BKP_DR0 - * @arg @ref LL_RTC_BKP_DR1 - * @arg @ref LL_RTC_BKP_DR2 - * @arg @ref LL_RTC_BKP_DR3 - * @arg @ref LL_RTC_BKP_DR4 - * @arg @ref LL_RTC_BKP_DR5 - * @arg @ref LL_RTC_BKP_DR6 - * @arg @ref LL_RTC_BKP_DR7 - * @arg @ref LL_RTC_BKP_DR8 - * @arg @ref LL_RTC_BKP_DR9 - * @arg @ref LL_RTC_BKP_DR10 - * @arg @ref LL_RTC_BKP_DR11 - * @arg @ref LL_RTC_BKP_DR12 - * @arg @ref LL_RTC_BKP_DR13 - * @arg @ref LL_RTC_BKP_DR14 - * @arg @ref LL_RTC_BKP_DR15 - * @arg @ref LL_RTC_BKP_DR16 - * @arg @ref LL_RTC_BKP_DR17 - * @arg @ref LL_RTC_BKP_DR18 - * @arg @ref LL_RTC_BKP_DR19 - * @param Data Value between Min_Data=0x00 and Max_Data=0xFFFFFFFF - * @retval None - */ -__STATIC_INLINE void LL_RTC_BAK_SetRegister(RTC_TypeDef *RTCx, uint32_t BackupRegister, uint32_t Data) -{ - register uint32_t tmp = 0U; - - tmp = (uint32_t)(&(RTCx->BKP0R)); - tmp += (BackupRegister * 4U); - - /* Write the specified register */ - *(__IO uint32_t *)tmp = (uint32_t)Data; -} - -/** - * @brief Reads data from the specified RTC Backup data Register. - * @rmtoll BKPxR BKP LL_RTC_BAK_GetRegister - * @param RTCx RTC Instance - * @param BackupRegister This parameter can be one of the following values: - * @arg @ref LL_RTC_BKP_DR0 - * @arg @ref LL_RTC_BKP_DR1 - * @arg @ref LL_RTC_BKP_DR2 - * @arg @ref LL_RTC_BKP_DR3 - * @arg @ref LL_RTC_BKP_DR4 - * @arg @ref LL_RTC_BKP_DR5 - * @arg @ref LL_RTC_BKP_DR6 - * @arg @ref LL_RTC_BKP_DR7 - * @arg @ref LL_RTC_BKP_DR8 - * @arg @ref LL_RTC_BKP_DR9 - * @arg @ref LL_RTC_BKP_DR10 - * @arg @ref LL_RTC_BKP_DR11 - * @arg @ref LL_RTC_BKP_DR12 - * @arg @ref LL_RTC_BKP_DR13 - * @arg @ref LL_RTC_BKP_DR14 - * @arg @ref LL_RTC_BKP_DR15 - * @arg @ref LL_RTC_BKP_DR16 - * @arg @ref LL_RTC_BKP_DR17 - * @arg @ref LL_RTC_BKP_DR18 - * @arg @ref LL_RTC_BKP_DR19 - * @retval Value between Min_Data=0x00 and Max_Data=0xFFFFFFFF - */ -__STATIC_INLINE uint32_t LL_RTC_BAK_GetRegister(RTC_TypeDef *RTCx, uint32_t BackupRegister) -{ - register uint32_t tmp = 0U; - - tmp = (uint32_t)(&(RTCx->BKP0R)); - tmp += (BackupRegister * 4U); - - /* Read the specified register */ - return (*(__IO uint32_t *)tmp); -} - -/** - * @} - */ - -/** @defgroup RTC_LL_EF_Calibration Calibration - * @{ - */ - -/** - * @brief Set Calibration output frequency (1 Hz or 512 Hz) - * @note Bits are write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR COE LL_RTC_CAL_SetOutputFreq\n - * CR COSEL LL_RTC_CAL_SetOutputFreq - * @param RTCx RTC Instance - * @param Frequency This parameter can be one of the following values: - * @arg @ref LL_RTC_CALIB_OUTPUT_NONE - * @arg @ref LL_RTC_CALIB_OUTPUT_1HZ - * @arg @ref LL_RTC_CALIB_OUTPUT_512HZ - * @retval None - */ -__STATIC_INLINE void LL_RTC_CAL_SetOutputFreq(RTC_TypeDef *RTCx, uint32_t Frequency) -{ - MODIFY_REG(RTCx->CR, RTC_CR_COE | RTC_CR_COSEL, Frequency); -} - -/** - * @brief Get Calibration output frequency (1 Hz or 512 Hz) - * @rmtoll CR COE LL_RTC_CAL_GetOutputFreq\n - * CR COSEL LL_RTC_CAL_GetOutputFreq - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_CALIB_OUTPUT_NONE - * @arg @ref LL_RTC_CALIB_OUTPUT_1HZ - * @arg @ref LL_RTC_CALIB_OUTPUT_512HZ - */ -__STATIC_INLINE uint32_t LL_RTC_CAL_GetOutputFreq(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->CR, RTC_CR_COE | RTC_CR_COSEL)); -} - -/** - * @brief Enable Coarse digital calibration - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @note It can be written in initialization mode only (@ref LL_RTC_EnableInitMode function) - * @rmtoll CR DCE LL_RTC_CAL_EnableCoarseDigital - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_CAL_EnableCoarseDigital(RTC_TypeDef *RTCx) -{ - SET_BIT(RTCx->CR, RTC_CR_DCE); -} - -/** - * @brief Disable Coarse digital calibration - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @note It can be written in initialization mode only (@ref LL_RTC_EnableInitMode function) - * @rmtoll CR DCE LL_RTC_CAL_DisableCoarseDigital - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_CAL_DisableCoarseDigital(RTC_TypeDef *RTCx) -{ - CLEAR_BIT(RTCx->CR, RTC_CR_DCE); -} - -/** - * @brief Set the coarse digital calibration - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @note It can be written in initialization mode only (@ref LL_RTC_EnableInitMode function) - * @rmtoll CALIBR DCS LL_RTC_CAL_ConfigCoarseDigital\n - * CALIBR DC LL_RTC_CAL_ConfigCoarseDigital - * @param RTCx RTC Instance - * @param Sign This parameter can be one of the following values: - * @arg @ref LL_RTC_CALIB_SIGN_POSITIVE - * @arg @ref LL_RTC_CALIB_SIGN_NEGATIVE - * @param Value value of coarse calibration expressed in ppm (coded on 5 bits) - * @note This Calibration value should be between 0 and 63 when using negative sign with a 2-ppm step. - * @note This Calibration value should be between 0 and 126 when using positive sign with a 4-ppm step. - * @retval None - */ -__STATIC_INLINE void LL_RTC_CAL_ConfigCoarseDigital(RTC_TypeDef* RTCx, uint32_t Sign, uint32_t Value) -{ - MODIFY_REG(RTCx->CALIBR, RTC_CALIBR_DCS | RTC_CALIBR_DC, Sign | Value); -} - -/** - * @brief Get the coarse digital calibration value - * @rmtoll CALIBR DC LL_RTC_CAL_GetCoarseDigitalValue - * @param RTCx RTC Instance - * @retval value of coarse calibration expressed in ppm (coded on 5 bits) - */ -__STATIC_INLINE uint32_t LL_RTC_CAL_GetCoarseDigitalValue(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->CALIBR, RTC_CALIBR_DC)); -} - -/** - * @brief Get the coarse digital calibration sign - * @rmtoll CALIBR DCS LL_RTC_CAL_GetCoarseDigitalSign - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_CALIB_SIGN_POSITIVE - * @arg @ref LL_RTC_CALIB_SIGN_NEGATIVE - */ -__STATIC_INLINE uint32_t LL_RTC_CAL_GetCoarseDigitalSign(RTC_TypeDef* RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->CALIBR, RTC_CALIBR_DCS)); -} - -/** - * @brief Insert or not One RTCCLK pulse every 2exp11 pulses (frequency increased by 488.5 ppm) - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @note Bit can be written only when RECALPF is set to 0 in RTC_ISR - * @rmtoll CALR CALP LL_RTC_CAL_SetPulse - * @param RTCx RTC Instance - * @param Pulse This parameter can be one of the following values: - * @arg @ref LL_RTC_CALIB_INSERTPULSE_NONE - * @arg @ref LL_RTC_CALIB_INSERTPULSE_SET - * @retval None - */ -__STATIC_INLINE void LL_RTC_CAL_SetPulse(RTC_TypeDef *RTCx, uint32_t Pulse) -{ - MODIFY_REG(RTCx->CALR, RTC_CALR_CALP, Pulse); -} - -/** - * @brief Check if one RTCCLK has been inserted or not every 2exp11 pulses (frequency increased by 488.5 ppm) - * @rmtoll CALR CALP LL_RTC_CAL_IsPulseInserted - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_CAL_IsPulseInserted(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->CALR, RTC_CALR_CALP) == (RTC_CALR_CALP)); -} - -/** - * @brief Set the calibration cycle period - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @note Bit can be written only when RECALPF is set to 0 in RTC_ISR - * @rmtoll CALR CALW8 LL_RTC_CAL_SetPeriod\n - * CALR CALW16 LL_RTC_CAL_SetPeriod - * @param RTCx RTC Instance - * @param Period This parameter can be one of the following values: - * @arg @ref LL_RTC_CALIB_PERIOD_32SEC - * @arg @ref LL_RTC_CALIB_PERIOD_16SEC - * @arg @ref LL_RTC_CALIB_PERIOD_8SEC - * @retval None - */ -__STATIC_INLINE void LL_RTC_CAL_SetPeriod(RTC_TypeDef *RTCx, uint32_t Period) -{ - MODIFY_REG(RTCx->CALR, RTC_CALR_CALW8 | RTC_CALR_CALW16, Period); -} - -/** - * @brief Get the calibration cycle period - * @rmtoll CALR CALW8 LL_RTC_CAL_GetPeriod\n - * CALR CALW16 LL_RTC_CAL_GetPeriod - * @param RTCx RTC Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_RTC_CALIB_PERIOD_32SEC - * @arg @ref LL_RTC_CALIB_PERIOD_16SEC - * @arg @ref LL_RTC_CALIB_PERIOD_8SEC - */ -__STATIC_INLINE uint32_t LL_RTC_CAL_GetPeriod(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->CALR, RTC_CALR_CALW8 | RTC_CALR_CALW16)); -} - -/** - * @brief Set Calibration minus - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @note Bit can be written only when RECALPF is set to 0 in RTC_ISR - * @rmtoll CALR CALM LL_RTC_CAL_SetMinus - * @param RTCx RTC Instance - * @param CalibMinus Value between Min_Data=0x00 and Max_Data=0x1FF - * @retval None - */ -__STATIC_INLINE void LL_RTC_CAL_SetMinus(RTC_TypeDef *RTCx, uint32_t CalibMinus) -{ - MODIFY_REG(RTCx->CALR, RTC_CALR_CALM, CalibMinus); -} - -/** - * @brief Get Calibration minus - * @rmtoll CALR CALM LL_RTC_CAL_GetMinus - * @param RTCx RTC Instance - * @retval Value between Min_Data=0x00 and Max_Data= 0x1FF - */ -__STATIC_INLINE uint32_t LL_RTC_CAL_GetMinus(RTC_TypeDef *RTCx) -{ - return (uint32_t)(READ_BIT(RTCx->CALR, RTC_CALR_CALM)); -} - -/** - * @} - */ - -/** @defgroup RTC_LL_EF_FLAG_Management FLAG_Management - * @{ - */ - -/** - * @brief Get Recalibration pending Flag - * @rmtoll ISR RECALPF LL_RTC_IsActiveFlag_RECALP - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_IsActiveFlag_RECALP(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->ISR, RTC_ISR_RECALPF) == (RTC_ISR_RECALPF)); -} - - -#if defined(RTC_TAMPER2_SUPPORT) -/** - * @brief Get RTC_TAMP2 detection flag - * @rmtoll ISR TAMP2F LL_RTC_IsActiveFlag_TAMP2 - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_IsActiveFlag_TAMP2(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->ISR, RTC_ISR_TAMP2F) == (RTC_ISR_TAMP2F)); -} -#endif /* RTC_TAMPER2_SUPPORT */ - -/** - * @brief Get RTC_TAMP1 detection flag - * @rmtoll ISR TAMP1F LL_RTC_IsActiveFlag_TAMP1 - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_IsActiveFlag_TAMP1(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->ISR, RTC_ISR_TAMP1F) == (RTC_ISR_TAMP1F)); -} - -/** - * @brief Get Time-stamp overflow flag - * @rmtoll ISR TSOVF LL_RTC_IsActiveFlag_TSOV - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_IsActiveFlag_TSOV(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->ISR, RTC_ISR_TSOVF) == (RTC_ISR_TSOVF)); -} - -/** - * @brief Get Time-stamp flag - * @rmtoll ISR TSF LL_RTC_IsActiveFlag_TS - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_IsActiveFlag_TS(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->ISR, RTC_ISR_TSF) == (RTC_ISR_TSF)); -} - -/** - * @brief Get Wakeup timer flag - * @rmtoll ISR WUTF LL_RTC_IsActiveFlag_WUT - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_IsActiveFlag_WUT(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->ISR, RTC_ISR_WUTF) == (RTC_ISR_WUTF)); -} - -/** - * @brief Get Alarm B flag - * @rmtoll ISR ALRBF LL_RTC_IsActiveFlag_ALRB - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_IsActiveFlag_ALRB(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->ISR, RTC_ISR_ALRBF) == (RTC_ISR_ALRBF)); -} - -/** - * @brief Get Alarm A flag - * @rmtoll ISR ALRAF LL_RTC_IsActiveFlag_ALRA - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_IsActiveFlag_ALRA(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->ISR, RTC_ISR_ALRAF) == (RTC_ISR_ALRAF)); -} - - -#if defined(RTC_TAMPER2_SUPPORT) -/** - * @brief Clear RTC_TAMP2 detection flag - * @rmtoll ISR TAMP2F LL_RTC_ClearFlag_TAMP2 - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_ClearFlag_TAMP2(RTC_TypeDef *RTCx) -{ - WRITE_REG(RTCx->ISR, (~((RTC_ISR_TAMP2F | RTC_ISR_INIT) & 0x0000FFFFU) | (RTCx->ISR & RTC_ISR_INIT))); -} -#endif /* RTC_TAMPER2_SUPPORT */ - -/** - * @brief Clear RTC_TAMP1 detection flag - * @rmtoll ISR TAMP1F LL_RTC_ClearFlag_TAMP1 - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_ClearFlag_TAMP1(RTC_TypeDef *RTCx) -{ - WRITE_REG(RTCx->ISR, (~((RTC_ISR_TAMP1F | RTC_ISR_INIT) & 0x0000FFFFU) | (RTCx->ISR & RTC_ISR_INIT))); -} - -/** - * @brief Clear Time-stamp overflow flag - * @rmtoll ISR TSOVF LL_RTC_ClearFlag_TSOV - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_ClearFlag_TSOV(RTC_TypeDef *RTCx) -{ - WRITE_REG(RTCx->ISR, (~((RTC_ISR_TSOVF | RTC_ISR_INIT) & 0x0000FFFFU) | (RTCx->ISR & RTC_ISR_INIT))); -} - -/** - * @brief Clear Time-stamp flag - * @rmtoll ISR TSF LL_RTC_ClearFlag_TS - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_ClearFlag_TS(RTC_TypeDef *RTCx) -{ - WRITE_REG(RTCx->ISR, (~((RTC_ISR_TSF | RTC_ISR_INIT) & 0x0000FFFFU) | (RTCx->ISR & RTC_ISR_INIT))); -} - -/** - * @brief Clear Wakeup timer flag - * @rmtoll ISR WUTF LL_RTC_ClearFlag_WUT - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_ClearFlag_WUT(RTC_TypeDef *RTCx) -{ - WRITE_REG(RTCx->ISR, (~((RTC_ISR_WUTF | RTC_ISR_INIT) & 0x0000FFFFU) | (RTCx->ISR & RTC_ISR_INIT))); -} - -/** - * @brief Clear Alarm B flag - * @rmtoll ISR ALRBF LL_RTC_ClearFlag_ALRB - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_ClearFlag_ALRB(RTC_TypeDef *RTCx) -{ - WRITE_REG(RTCx->ISR, (~((RTC_ISR_ALRBF | RTC_ISR_INIT) & 0x0000FFFFU) | (RTCx->ISR & RTC_ISR_INIT))); -} - -/** - * @brief Clear Alarm A flag - * @rmtoll ISR ALRAF LL_RTC_ClearFlag_ALRA - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_ClearFlag_ALRA(RTC_TypeDef *RTCx) -{ - WRITE_REG(RTCx->ISR, (~((RTC_ISR_ALRAF | RTC_ISR_INIT) & 0x0000FFFFU) | (RTCx->ISR & RTC_ISR_INIT))); -} - -/** - * @brief Get Initialization flag - * @rmtoll ISR INITF LL_RTC_IsActiveFlag_INIT - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_IsActiveFlag_INIT(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->ISR, RTC_ISR_INITF) == (RTC_ISR_INITF)); -} - -/** - * @brief Get Registers synchronization flag - * @rmtoll ISR RSF LL_RTC_IsActiveFlag_RS - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_IsActiveFlag_RS(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->ISR, RTC_ISR_RSF) == (RTC_ISR_RSF)); -} - -/** - * @brief Clear Registers synchronization flag - * @rmtoll ISR RSF LL_RTC_ClearFlag_RS - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_ClearFlag_RS(RTC_TypeDef *RTCx) -{ - WRITE_REG(RTCx->ISR, (~((RTC_ISR_RSF | RTC_ISR_INIT) & 0x0000FFFFU) | (RTCx->ISR & RTC_ISR_INIT))); -} - -/** - * @brief Get Initialization status flag - * @rmtoll ISR INITS LL_RTC_IsActiveFlag_INITS - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_IsActiveFlag_INITS(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->ISR, RTC_ISR_INITS) == (RTC_ISR_INITS)); -} - -/** - * @brief Get Shift operation pending flag - * @rmtoll ISR SHPF LL_RTC_IsActiveFlag_SHP - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_IsActiveFlag_SHP(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->ISR, RTC_ISR_SHPF) == (RTC_ISR_SHPF)); -} - -/** - * @brief Get Wakeup timer write flag - * @rmtoll ISR WUTWF LL_RTC_IsActiveFlag_WUTW - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_IsActiveFlag_WUTW(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->ISR, RTC_ISR_WUTWF) == (RTC_ISR_WUTWF)); -} - -/** - * @brief Get Alarm B write flag - * @rmtoll ISR ALRBWF LL_RTC_IsActiveFlag_ALRBW - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_IsActiveFlag_ALRBW(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->ISR, RTC_ISR_ALRBWF) == (RTC_ISR_ALRBWF)); -} - -/** - * @brief Get Alarm A write flag - * @rmtoll ISR ALRAWF LL_RTC_IsActiveFlag_ALRAW - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_IsActiveFlag_ALRAW(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->ISR, RTC_ISR_ALRAWF) == (RTC_ISR_ALRAWF)); -} - -/** - * @} - */ - -/** @defgroup RTC_LL_EF_IT_Management IT_Management - * @{ - */ - -/** - * @brief Enable Time-stamp interrupt - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR TSIE LL_RTC_EnableIT_TS - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_EnableIT_TS(RTC_TypeDef *RTCx) -{ - SET_BIT(RTCx->CR, RTC_CR_TSIE); -} - -/** - * @brief Disable Time-stamp interrupt - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR TSIE LL_RTC_DisableIT_TS - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_DisableIT_TS(RTC_TypeDef *RTCx) -{ - CLEAR_BIT(RTCx->CR, RTC_CR_TSIE); -} - -/** - * @brief Enable Wakeup timer interrupt - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR WUTIE LL_RTC_EnableIT_WUT - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_EnableIT_WUT(RTC_TypeDef *RTCx) -{ - SET_BIT(RTCx->CR, RTC_CR_WUTIE); -} - -/** - * @brief Disable Wakeup timer interrupt - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR WUTIE LL_RTC_DisableIT_WUT - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_DisableIT_WUT(RTC_TypeDef *RTCx) -{ - CLEAR_BIT(RTCx->CR, RTC_CR_WUTIE); -} - -/** - * @brief Enable Alarm B interrupt - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR ALRBIE LL_RTC_EnableIT_ALRB - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_EnableIT_ALRB(RTC_TypeDef *RTCx) -{ - SET_BIT(RTCx->CR, RTC_CR_ALRBIE); -} - -/** - * @brief Disable Alarm B interrupt - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR ALRBIE LL_RTC_DisableIT_ALRB - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_DisableIT_ALRB(RTC_TypeDef *RTCx) -{ - CLEAR_BIT(RTCx->CR, RTC_CR_ALRBIE); -} - -/** - * @brief Enable Alarm A interrupt - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR ALRAIE LL_RTC_EnableIT_ALRA - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_EnableIT_ALRA(RTC_TypeDef *RTCx) -{ - SET_BIT(RTCx->CR, RTC_CR_ALRAIE); -} - -/** - * @brief Disable Alarm A interrupt - * @note Bit is write-protected. @ref LL_RTC_DisableWriteProtection function should be called before. - * @rmtoll CR ALRAIE LL_RTC_DisableIT_ALRA - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_DisableIT_ALRA(RTC_TypeDef *RTCx) -{ - CLEAR_BIT(RTCx->CR, RTC_CR_ALRAIE); -} - -/** - * @brief Enable all Tamper Interrupt - * @rmtoll TAFCR TAMPIE LL_RTC_EnableIT_TAMP - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_EnableIT_TAMP(RTC_TypeDef *RTCx) -{ - SET_BIT(RTCx->TAFCR, RTC_TAFCR_TAMPIE); -} - -/** - * @brief Disable all Tamper Interrupt - * @rmtoll TAFCR TAMPIE LL_RTC_DisableIT_TAMP - * @param RTCx RTC Instance - * @retval None - */ -__STATIC_INLINE void LL_RTC_DisableIT_TAMP(RTC_TypeDef *RTCx) -{ - CLEAR_BIT(RTCx->TAFCR, RTC_TAFCR_TAMPIE); -} - -/** - * @brief Check if Time-stamp interrupt is enabled or not - * @rmtoll CR TSIE LL_RTC_IsEnabledIT_TS - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_IsEnabledIT_TS(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->CR, RTC_CR_TSIE) == (RTC_CR_TSIE)); -} - -/** - * @brief Check if Wakeup timer interrupt is enabled or not - * @rmtoll CR WUTIE LL_RTC_IsEnabledIT_WUT - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_IsEnabledIT_WUT(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->CR, RTC_CR_WUTIE) == (RTC_CR_WUTIE)); -} - -/** - * @brief Check if Alarm B interrupt is enabled or not - * @rmtoll CR ALRBIE LL_RTC_IsEnabledIT_ALRB - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_IsEnabledIT_ALRB(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->CR, RTC_CR_ALRBIE) == (RTC_CR_ALRBIE)); -} - -/** - * @brief Check if Alarm A interrupt is enabled or not - * @rmtoll CR ALRAIE LL_RTC_IsEnabledIT_ALRA - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_IsEnabledIT_ALRA(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->CR, RTC_CR_ALRAIE) == (RTC_CR_ALRAIE)); -} - -/** - * @brief Check if all the TAMPER interrupts are enabled or not - * @rmtoll TAFCR TAMPIE LL_RTC_IsEnabledIT_TAMP - * @param RTCx RTC Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_RTC_IsEnabledIT_TAMP(RTC_TypeDef *RTCx) -{ - return (READ_BIT(RTCx->TAFCR, - RTC_TAFCR_TAMPIE) == (RTC_TAFCR_TAMPIE)); -} - -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup RTC_LL_EF_Init Initialization and de-initialization functions - * @{ - */ - -ErrorStatus LL_RTC_DeInit(RTC_TypeDef *RTCx); -ErrorStatus LL_RTC_Init(RTC_TypeDef *RTCx, LL_RTC_InitTypeDef *RTC_InitStruct); -void LL_RTC_StructInit(LL_RTC_InitTypeDef *RTC_InitStruct); -ErrorStatus LL_RTC_TIME_Init(RTC_TypeDef *RTCx, uint32_t RTC_Format, LL_RTC_TimeTypeDef *RTC_TimeStruct); -void LL_RTC_TIME_StructInit(LL_RTC_TimeTypeDef *RTC_TimeStruct); -ErrorStatus LL_RTC_DATE_Init(RTC_TypeDef *RTCx, uint32_t RTC_Format, LL_RTC_DateTypeDef *RTC_DateStruct); -void LL_RTC_DATE_StructInit(LL_RTC_DateTypeDef *RTC_DateStruct); -ErrorStatus LL_RTC_ALMA_Init(RTC_TypeDef *RTCx, uint32_t RTC_Format, LL_RTC_AlarmTypeDef *RTC_AlarmStruct); -ErrorStatus LL_RTC_ALMB_Init(RTC_TypeDef *RTCx, uint32_t RTC_Format, LL_RTC_AlarmTypeDef *RTC_AlarmStruct); -void LL_RTC_ALMA_StructInit(LL_RTC_AlarmTypeDef *RTC_AlarmStruct); -void LL_RTC_ALMB_StructInit(LL_RTC_AlarmTypeDef *RTC_AlarmStruct); -ErrorStatus LL_RTC_EnterInitMode(RTC_TypeDef *RTCx); -ErrorStatus LL_RTC_ExitInitMode(RTC_TypeDef *RTCx); -ErrorStatus LL_RTC_WaitForSynchro(RTC_TypeDef *RTCx); - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* defined(RTC) */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_RTC_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_sdmmc.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_sdmmc.h deleted file mode 100644 index 540a0e1..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_sdmmc.h +++ /dev/null @@ -1,1125 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_sdmmc.h - * @author MCD Application Team - * @brief Header file of SDMMC HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_LL_SDMMC_H -#define STM32F4xx_LL_SDMMC_H - -#ifdef __cplusplus - extern "C" { -#endif - -#if defined(SDIO) - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_Driver - * @{ - */ - -/** @addtogroup SDMMC_LL - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/** @defgroup SDMMC_LL_Exported_Types SDMMC_LL Exported Types - * @{ - */ - -/** - * @brief SDMMC Configuration Structure definition - */ -typedef struct -{ - uint32_t ClockEdge; /*!< Specifies the clock transition on which the bit capture is made. - This parameter can be a value of @ref SDMMC_LL_Clock_Edge */ - - uint32_t ClockBypass; /*!< Specifies whether the SDMMC Clock divider bypass is - enabled or disabled. - This parameter can be a value of @ref SDMMC_LL_Clock_Bypass */ - - uint32_t ClockPowerSave; /*!< Specifies whether SDMMC Clock output is enabled or - disabled when the bus is idle. - This parameter can be a value of @ref SDMMC_LL_Clock_Power_Save */ - - uint32_t BusWide; /*!< Specifies the SDMMC bus width. - This parameter can be a value of @ref SDMMC_LL_Bus_Wide */ - - uint32_t HardwareFlowControl; /*!< Specifies whether the SDMMC hardware flow control is enabled or disabled. - This parameter can be a value of @ref SDMMC_LL_Hardware_Flow_Control */ - - uint32_t ClockDiv; /*!< Specifies the clock frequency of the SDMMC controller. - This parameter can be a value between Min_Data = 0 and Max_Data = 255 */ - -}SDIO_InitTypeDef; - - -/** - * @brief SDMMC Command Control structure - */ -typedef struct -{ - uint32_t Argument; /*!< Specifies the SDMMC command argument which is sent - to a card as part of a command message. If a command - contains an argument, it must be loaded into this register - before writing the command to the command register. */ - - uint32_t CmdIndex; /*!< Specifies the SDMMC command index. It must be Min_Data = 0 and - Max_Data = 64 */ - - uint32_t Response; /*!< Specifies the SDMMC response type. - This parameter can be a value of @ref SDMMC_LL_Response_Type */ - - uint32_t WaitForInterrupt; /*!< Specifies whether SDMMC wait for interrupt request is - enabled or disabled. - This parameter can be a value of @ref SDMMC_LL_Wait_Interrupt_State */ - - uint32_t CPSM; /*!< Specifies whether SDMMC Command path state machine (CPSM) - is enabled or disabled. - This parameter can be a value of @ref SDMMC_LL_CPSM_State */ -}SDIO_CmdInitTypeDef; - - -/** - * @brief SDMMC Data Control structure - */ -typedef struct -{ - uint32_t DataTimeOut; /*!< Specifies the data timeout period in card bus clock periods. */ - - uint32_t DataLength; /*!< Specifies the number of data bytes to be transferred. */ - - uint32_t DataBlockSize; /*!< Specifies the data block size for block transfer. - This parameter can be a value of @ref SDMMC_LL_Data_Block_Size */ - - uint32_t TransferDir; /*!< Specifies the data transfer direction, whether the transfer - is a read or write. - This parameter can be a value of @ref SDMMC_LL_Transfer_Direction */ - - uint32_t TransferMode; /*!< Specifies whether data transfer is in stream or block mode. - This parameter can be a value of @ref SDMMC_LL_Transfer_Type */ - - uint32_t DPSM; /*!< Specifies whether SDMMC Data path state machine (DPSM) - is enabled or disabled. - This parameter can be a value of @ref SDMMC_LL_DPSM_State */ -}SDIO_DataInitTypeDef; - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup SDMMC_LL_Exported_Constants SDMMC_LL Exported Constants - * @{ - */ -#define SDMMC_ERROR_NONE 0x00000000U /*!< No error */ -#define SDMMC_ERROR_CMD_CRC_FAIL 0x00000001U /*!< Command response received (but CRC check failed) */ -#define SDMMC_ERROR_DATA_CRC_FAIL 0x00000002U /*!< Data block sent/received (CRC check failed) */ -#define SDMMC_ERROR_CMD_RSP_TIMEOUT 0x00000004U /*!< Command response timeout */ -#define SDMMC_ERROR_DATA_TIMEOUT 0x00000008U /*!< Data timeout */ -#define SDMMC_ERROR_TX_UNDERRUN 0x00000010U /*!< Transmit FIFO underrun */ -#define SDMMC_ERROR_RX_OVERRUN 0x00000020U /*!< Receive FIFO overrun */ -#define SDMMC_ERROR_ADDR_MISALIGNED 0x00000040U /*!< Misaligned address */ -#define SDMMC_ERROR_BLOCK_LEN_ERR 0x00000080U /*!< Transferred block length is not allowed for the card or the - number of transferred bytes does not match the block length */ -#define SDMMC_ERROR_ERASE_SEQ_ERR 0x00000100U /*!< An error in the sequence of erase command occurs */ -#define SDMMC_ERROR_BAD_ERASE_PARAM 0x00000200U /*!< An invalid selection for erase groups */ -#define SDMMC_ERROR_WRITE_PROT_VIOLATION 0x00000400U /*!< Attempt to program a write protect block */ -#define SDMMC_ERROR_LOCK_UNLOCK_FAILED 0x00000800U /*!< Sequence or password error has been detected in unlock - command or if there was an attempt to access a locked card */ -#define SDMMC_ERROR_COM_CRC_FAILED 0x00001000U /*!< CRC check of the previous command failed */ -#define SDMMC_ERROR_ILLEGAL_CMD 0x00002000U /*!< Command is not legal for the card state */ -#define SDMMC_ERROR_CARD_ECC_FAILED 0x00004000U /*!< Card internal ECC was applied but failed to correct the data */ -#define SDMMC_ERROR_CC_ERR 0x00008000U /*!< Internal card controller error */ -#define SDMMC_ERROR_GENERAL_UNKNOWN_ERR 0x00010000U /*!< General or unknown error */ -#define SDMMC_ERROR_STREAM_READ_UNDERRUN 0x00020000U /*!< The card could not sustain data reading in stream rmode */ -#define SDMMC_ERROR_STREAM_WRITE_OVERRUN 0x00040000U /*!< The card could not sustain data programming in stream mode */ -#define SDMMC_ERROR_CID_CSD_OVERWRITE 0x00080000U /*!< CID/CSD overwrite error */ -#define SDMMC_ERROR_WP_ERASE_SKIP 0x00100000U /*!< Only partial address space was erased */ -#define SDMMC_ERROR_CARD_ECC_DISABLED 0x00200000U /*!< Command has been executed without using internal ECC */ -#define SDMMC_ERROR_ERASE_RESET 0x00400000U /*!< Erase sequence was cleared before executing because an out - of erase sequence command was received */ -#define SDMMC_ERROR_AKE_SEQ_ERR 0x00800000U /*!< Error in sequence of authentication */ -#define SDMMC_ERROR_INVALID_VOLTRANGE 0x01000000U /*!< Error in case of invalid voltage range */ -#define SDMMC_ERROR_ADDR_OUT_OF_RANGE 0x02000000U /*!< Error when addressed block is out of range */ -#define SDMMC_ERROR_REQUEST_NOT_APPLICABLE 0x04000000U /*!< Error when command request is not applicable */ -#define SDMMC_ERROR_INVALID_PARAMETER 0x08000000U /*!< the used parameter is not valid */ -#define SDMMC_ERROR_UNSUPPORTED_FEATURE 0x10000000U /*!< Error when feature is not insupported */ -#define SDMMC_ERROR_BUSY 0x20000000U /*!< Error when transfer process is busy */ -#define SDMMC_ERROR_DMA 0x40000000U /*!< Error while DMA transfer */ -#define SDMMC_ERROR_TIMEOUT 0x80000000U /*!< Timeout error */ - -/** - * @brief SDMMC Commands Index - */ -#define SDMMC_CMD_GO_IDLE_STATE 0U /*!< Resets the SD memory card. */ -#define SDMMC_CMD_SEND_OP_COND 1U /*!< Sends host capacity support information and activates the card's initialization process. */ -#define SDMMC_CMD_ALL_SEND_CID 2U /*!< Asks any card connected to the host to send the CID numbers on the CMD line. */ -#define SDMMC_CMD_SET_REL_ADDR 3U /*!< Asks the card to publish a new relative address (RCA). */ -#define SDMMC_CMD_SET_DSR 4U /*!< Programs the DSR of all cards. */ -#define SDMMC_CMD_SDMMC_SEN_OP_COND 5U /*!< Sends host capacity support information (HCS) and asks the accessed card to send its - operating condition register (OCR) content in the response on the CMD line. */ -#define SDMMC_CMD_HS_SWITCH 6U /*!< Checks switchable function (mode 0) and switch card function (mode 1). */ -#define SDMMC_CMD_SEL_DESEL_CARD 7U /*!< Selects the card by its own relative address and gets deselected by any other address */ -#define SDMMC_CMD_HS_SEND_EXT_CSD 8U /*!< Sends SD Memory Card interface condition, which includes host supply voltage information - and asks the card whether card supports voltage. */ -#define SDMMC_CMD_SEND_CSD 9U /*!< Addressed card sends its card specific data (CSD) on the CMD line. */ -#define SDMMC_CMD_SEND_CID 10U /*!< Addressed card sends its card identification (CID) on the CMD line. */ -#define SDMMC_CMD_READ_DAT_UNTIL_STOP 11U /*!< SD card doesn't support it. */ -#define SDMMC_CMD_STOP_TRANSMISSION 12U /*!< Forces the card to stop transmission. */ -#define SDMMC_CMD_SEND_STATUS 13U /*!< Addressed card sends its status register. */ -#define SDMMC_CMD_HS_BUSTEST_READ 14U /*!< Reserved */ -#define SDMMC_CMD_GO_INACTIVE_STATE 15U /*!< Sends an addressed card into the inactive state. */ -#define SDMMC_CMD_SET_BLOCKLEN 16U /*!< Sets the block length (in bytes for SDSC) for all following block commands - (read, write, lock). Default block length is fixed to 512 Bytes. Not effective - for SDHS and SDXC. */ -#define SDMMC_CMD_READ_SINGLE_BLOCK 17U /*!< Reads single block of size selected by SET_BLOCKLEN in case of SDSC, and a block of - fixed 512 bytes in case of SDHC and SDXC. */ -#define SDMMC_CMD_READ_MULT_BLOCK 18U /*!< Continuously transfers data blocks from card to host until interrupted by - STOP_TRANSMISSION command. */ -#define SDMMC_CMD_HS_BUSTEST_WRITE 19U /*!< 64 bytes tuning pattern is sent for SDR50 and SDR104. */ -#define SDMMC_CMD_WRITE_DAT_UNTIL_STOP 20U /*!< Speed class control command. */ -#define SDMMC_CMD_SET_BLOCK_COUNT 23U /*!< Specify block count for CMD18 and CMD25. */ -#define SDMMC_CMD_WRITE_SINGLE_BLOCK 24U /*!< Writes single block of size selected by SET_BLOCKLEN in case of SDSC, and a block of - fixed 512 bytes in case of SDHC and SDXC. */ -#define SDMMC_CMD_WRITE_MULT_BLOCK 25U /*!< Continuously writes blocks of data until a STOP_TRANSMISSION follows. */ -#define SDMMC_CMD_PROG_CID 26U /*!< Reserved for manufacturers. */ -#define SDMMC_CMD_PROG_CSD 27U /*!< Programming of the programmable bits of the CSD. */ -#define SDMMC_CMD_SET_WRITE_PROT 28U /*!< Sets the write protection bit of the addressed group. */ -#define SDMMC_CMD_CLR_WRITE_PROT 29U /*!< Clears the write protection bit of the addressed group. */ -#define SDMMC_CMD_SEND_WRITE_PROT 30U /*!< Asks the card to send the status of the write protection bits. */ -#define SDMMC_CMD_SD_ERASE_GRP_START 32U /*!< Sets the address of the first write block to be erased. (For SD card only). */ -#define SDMMC_CMD_SD_ERASE_GRP_END 33U /*!< Sets the address of the last write block of the continuous range to be erased. */ -#define SDMMC_CMD_ERASE_GRP_START 35U /*!< Sets the address of the first write block to be erased. Reserved for each command - system set by switch function command (CMD6). */ -#define SDMMC_CMD_ERASE_GRP_END 36U /*!< Sets the address of the last write block of the continuous range to be erased. - Reserved for each command system set by switch function command (CMD6). */ -#define SDMMC_CMD_ERASE 38U /*!< Reserved for SD security applications. */ -#define SDMMC_CMD_FAST_IO 39U /*!< SD card doesn't support it (Reserved). */ -#define SDMMC_CMD_GO_IRQ_STATE 40U /*!< SD card doesn't support it (Reserved). */ -#define SDMMC_CMD_LOCK_UNLOCK 42U /*!< Sets/resets the password or lock/unlock the card. The size of the data block is set by - the SET_BLOCK_LEN command. */ -#define SDMMC_CMD_APP_CMD 55U /*!< Indicates to the card that the next command is an application specific command rather - than a standard command. */ -#define SDMMC_CMD_GEN_CMD 56U /*!< Used either to transfer a data block to the card or to get a data block from the card - for general purpose/application specific commands. */ -#define SDMMC_CMD_NO_CMD 64U /*!< No command */ - -/** - * @brief Following commands are SD Card Specific commands. - * SDMMC_APP_CMD should be sent before sending these commands. - */ -#define SDMMC_CMD_APP_SD_SET_BUSWIDTH 6U /*!< (ACMD6) Defines the data bus width to be used for data transfer. The allowed data bus - widths are given in SCR register. */ -#define SDMMC_CMD_SD_APP_STATUS 13U /*!< (ACMD13) Sends the SD status. */ -#define SDMMC_CMD_SD_APP_SEND_NUM_WRITE_BLOCKS 22U /*!< (ACMD22) Sends the number of the written (without errors) write blocks. Responds with - 32bit+CRC data block. */ -#define SDMMC_CMD_SD_APP_OP_COND 41U /*!< (ACMD41) Sends host capacity support information (HCS) and asks the accessed card to - send its operating condition register (OCR) content in the response on the CMD line. */ -#define SDMMC_CMD_SD_APP_SET_CLR_CARD_DETECT 42U /*!< (ACMD42) Connect/Disconnect the 50 KOhm pull-up resistor on CD/DAT3 (pin 1) of the card */ -#define SDMMC_CMD_SD_APP_SEND_SCR 51U /*!< Reads the SD Configuration Register (SCR). */ -#define SDMMC_CMD_SDMMC_RW_DIRECT 52U /*!< For SD I/O card only, reserved for security specification. */ -#define SDMMC_CMD_SDMMC_RW_EXTENDED 53U /*!< For SD I/O card only, reserved for security specification. */ - -/** - * @brief Following commands are SD Card Specific security commands. - * SDMMC_CMD_APP_CMD should be sent before sending these commands. - */ -#define SDMMC_CMD_SD_APP_GET_MKB 43U -#define SDMMC_CMD_SD_APP_GET_MID 44U -#define SDMMC_CMD_SD_APP_SET_CER_RN1 45U -#define SDMMC_CMD_SD_APP_GET_CER_RN2 46U -#define SDMMC_CMD_SD_APP_SET_CER_RES2 47U -#define SDMMC_CMD_SD_APP_GET_CER_RES1 48U -#define SDMMC_CMD_SD_APP_SECURE_READ_MULTIPLE_BLOCK 18U -#define SDMMC_CMD_SD_APP_SECURE_WRITE_MULTIPLE_BLOCK 25U -#define SDMMC_CMD_SD_APP_SECURE_ERASE 38U -#define SDMMC_CMD_SD_APP_CHANGE_SECURE_AREA 49U -#define SDMMC_CMD_SD_APP_SECURE_WRITE_MKB 48U - -/** - * @brief Masks for errors Card Status R1 (OCR Register) - */ -#define SDMMC_OCR_ADDR_OUT_OF_RANGE 0x80000000U -#define SDMMC_OCR_ADDR_MISALIGNED 0x40000000U -#define SDMMC_OCR_BLOCK_LEN_ERR 0x20000000U -#define SDMMC_OCR_ERASE_SEQ_ERR 0x10000000U -#define SDMMC_OCR_BAD_ERASE_PARAM 0x08000000U -#define SDMMC_OCR_WRITE_PROT_VIOLATION 0x04000000U -#define SDMMC_OCR_LOCK_UNLOCK_FAILED 0x01000000U -#define SDMMC_OCR_COM_CRC_FAILED 0x00800000U -#define SDMMC_OCR_ILLEGAL_CMD 0x00400000U -#define SDMMC_OCR_CARD_ECC_FAILED 0x00200000U -#define SDMMC_OCR_CC_ERROR 0x00100000U -#define SDMMC_OCR_GENERAL_UNKNOWN_ERROR 0x00080000U -#define SDMMC_OCR_STREAM_READ_UNDERRUN 0x00040000U -#define SDMMC_OCR_STREAM_WRITE_OVERRUN 0x00020000U -#define SDMMC_OCR_CID_CSD_OVERWRITE 0x00010000U -#define SDMMC_OCR_WP_ERASE_SKIP 0x00008000U -#define SDMMC_OCR_CARD_ECC_DISABLED 0x00004000U -#define SDMMC_OCR_ERASE_RESET 0x00002000U -#define SDMMC_OCR_AKE_SEQ_ERROR 0x00000008U -#define SDMMC_OCR_ERRORBITS 0xFDFFE008U - -/** - * @brief Masks for R6 Response - */ -#define SDMMC_R6_GENERAL_UNKNOWN_ERROR 0x00002000U -#define SDMMC_R6_ILLEGAL_CMD 0x00004000U -#define SDMMC_R6_COM_CRC_FAILED 0x00008000U - -#define SDMMC_VOLTAGE_WINDOW_SD 0x80100000U -#define SDMMC_HIGH_CAPACITY 0x40000000U -#define SDMMC_STD_CAPACITY 0x00000000U -#define SDMMC_CHECK_PATTERN 0x000001AAU -#define SD_SWITCH_1_8V_CAPACITY 0x01000000U - -#define SDMMC_MAX_VOLT_TRIAL 0x0000FFFFU - -#define SDMMC_MAX_TRIAL 0x0000FFFFU - -#define SDMMC_ALLZERO 0x00000000U - -#define SDMMC_WIDE_BUS_SUPPORT 0x00040000U -#define SDMMC_SINGLE_BUS_SUPPORT 0x00010000U -#define SDMMC_CARD_LOCKED 0x02000000U - -#ifndef SDMMC_DATATIMEOUT -#define SDMMC_DATATIMEOUT 0xFFFFFFFFU -#endif /* SDMMC_DATATIMEOUT */ - -#define SDMMC_0TO7BITS 0x000000FFU -#define SDMMC_8TO15BITS 0x0000FF00U -#define SDMMC_16TO23BITS 0x00FF0000U -#define SDMMC_24TO31BITS 0xFF000000U -#define SDMMC_MAX_DATA_LENGTH 0x01FFFFFFU - -#define SDMMC_HALFFIFO 0x00000008U -#define SDMMC_HALFFIFOBYTES 0x00000020U - -/** - * @brief Command Class supported - */ -#define SDIO_CCCC_ERASE 0x00000020U - -#define SDIO_CMDTIMEOUT 5000U /* Command send and response timeout */ -#define SDIO_MAXERASETIMEOUT 63000U /* Max erase Timeout 63 s */ -#define SDIO_STOPTRANSFERTIMEOUT 100000000U /* Timeout for STOP TRANSMISSION command */ - -/** @defgroup SDIO_LL_Clock_Edge Clock Edge - * @{ - */ -#define SDIO_CLOCK_EDGE_RISING 0x00000000U -#define SDIO_CLOCK_EDGE_FALLING SDIO_CLKCR_NEGEDGE - -#define IS_SDIO_CLOCK_EDGE(EDGE) (((EDGE) == SDIO_CLOCK_EDGE_RISING) || \ - ((EDGE) == SDIO_CLOCK_EDGE_FALLING)) -/** - * @} - */ - -/** @defgroup SDIO_LL_Clock_Bypass Clock Bypass - * @{ - */ -#define SDIO_CLOCK_BYPASS_DISABLE 0x00000000U -#define SDIO_CLOCK_BYPASS_ENABLE SDIO_CLKCR_BYPASS - -#define IS_SDIO_CLOCK_BYPASS(BYPASS) (((BYPASS) == SDIO_CLOCK_BYPASS_DISABLE) || \ - ((BYPASS) == SDIO_CLOCK_BYPASS_ENABLE)) -/** - * @} - */ - -/** @defgroup SDIO_LL_Clock_Power_Save Clock Power Saving - * @{ - */ -#define SDIO_CLOCK_POWER_SAVE_DISABLE 0x00000000U -#define SDIO_CLOCK_POWER_SAVE_ENABLE SDIO_CLKCR_PWRSAV - -#define IS_SDIO_CLOCK_POWER_SAVE(SAVE) (((SAVE) == SDIO_CLOCK_POWER_SAVE_DISABLE) || \ - ((SAVE) == SDIO_CLOCK_POWER_SAVE_ENABLE)) -/** - * @} - */ - -/** @defgroup SDIO_LL_Bus_Wide Bus Width - * @{ - */ -#define SDIO_BUS_WIDE_1B 0x00000000U -#define SDIO_BUS_WIDE_4B SDIO_CLKCR_WIDBUS_0 -#define SDIO_BUS_WIDE_8B SDIO_CLKCR_WIDBUS_1 - -#define IS_SDIO_BUS_WIDE(WIDE) (((WIDE) == SDIO_BUS_WIDE_1B) || \ - ((WIDE) == SDIO_BUS_WIDE_4B) || \ - ((WIDE) == SDIO_BUS_WIDE_8B)) -/** - * @} - */ - -/** @defgroup SDIO_LL_Hardware_Flow_Control Hardware Flow Control - * @{ - */ -#define SDIO_HARDWARE_FLOW_CONTROL_DISABLE 0x00000000U -#define SDIO_HARDWARE_FLOW_CONTROL_ENABLE SDIO_CLKCR_HWFC_EN - -#define IS_SDIO_HARDWARE_FLOW_CONTROL(CONTROL) (((CONTROL) == SDIO_HARDWARE_FLOW_CONTROL_DISABLE) || \ - ((CONTROL) == SDIO_HARDWARE_FLOW_CONTROL_ENABLE)) -/** - * @} - */ - -/** @defgroup SDIO_LL_Clock_Division Clock Division - * @{ - */ -#define IS_SDIO_CLKDIV(DIV) ((DIV) <= 0xFFU) -/** - * @} - */ - -/** @defgroup SDIO_LL_Command_Index Command Index - * @{ - */ -#define IS_SDIO_CMD_INDEX(INDEX) ((INDEX) < 0x40U) -/** - * @} - */ - -/** @defgroup SDIO_LL_Response_Type Response Type - * @{ - */ -#define SDIO_RESPONSE_NO 0x00000000U -#define SDIO_RESPONSE_SHORT SDIO_CMD_WAITRESP_0 -#define SDIO_RESPONSE_LONG SDIO_CMD_WAITRESP - -#define IS_SDIO_RESPONSE(RESPONSE) (((RESPONSE) == SDIO_RESPONSE_NO) || \ - ((RESPONSE) == SDIO_RESPONSE_SHORT) || \ - ((RESPONSE) == SDIO_RESPONSE_LONG)) -/** - * @} - */ - -/** @defgroup SDIO_LL_Wait_Interrupt_State Wait Interrupt - * @{ - */ -#define SDIO_WAIT_NO 0x00000000U -#define SDIO_WAIT_IT SDIO_CMD_WAITINT -#define SDIO_WAIT_PEND SDIO_CMD_WAITPEND - -#define IS_SDIO_WAIT(WAIT) (((WAIT) == SDIO_WAIT_NO) || \ - ((WAIT) == SDIO_WAIT_IT) || \ - ((WAIT) == SDIO_WAIT_PEND)) -/** - * @} - */ - -/** @defgroup SDIO_LL_CPSM_State CPSM State - * @{ - */ -#define SDIO_CPSM_DISABLE 0x00000000U -#define SDIO_CPSM_ENABLE SDIO_CMD_CPSMEN - -#define IS_SDIO_CPSM(CPSM) (((CPSM) == SDIO_CPSM_DISABLE) || \ - ((CPSM) == SDIO_CPSM_ENABLE)) -/** - * @} - */ - -/** @defgroup SDIO_LL_Response_Registers Response Register - * @{ - */ -#define SDIO_RESP1 0x00000000U -#define SDIO_RESP2 0x00000004U -#define SDIO_RESP3 0x00000008U -#define SDIO_RESP4 0x0000000CU - -#define IS_SDIO_RESP(RESP) (((RESP) == SDIO_RESP1) || \ - ((RESP) == SDIO_RESP2) || \ - ((RESP) == SDIO_RESP3) || \ - ((RESP) == SDIO_RESP4)) -/** - * @} - */ - -/** @defgroup SDIO_LL_Data_Length Data Length - * @{ - */ -#define IS_SDIO_DATA_LENGTH(LENGTH) ((LENGTH) <= 0x01FFFFFFU) -/** - * @} - */ - -/** @defgroup SDIO_LL_Data_Block_Size Data Block Size - * @{ - */ -#define SDIO_DATABLOCK_SIZE_1B 0x00000000U -#define SDIO_DATABLOCK_SIZE_2B SDIO_DCTRL_DBLOCKSIZE_0 -#define SDIO_DATABLOCK_SIZE_4B SDIO_DCTRL_DBLOCKSIZE_1 -#define SDIO_DATABLOCK_SIZE_8B (SDIO_DCTRL_DBLOCKSIZE_0|SDIO_DCTRL_DBLOCKSIZE_1) -#define SDIO_DATABLOCK_SIZE_16B SDIO_DCTRL_DBLOCKSIZE_2 -#define SDIO_DATABLOCK_SIZE_32B (SDIO_DCTRL_DBLOCKSIZE_0|SDIO_DCTRL_DBLOCKSIZE_2) -#define SDIO_DATABLOCK_SIZE_64B (SDIO_DCTRL_DBLOCKSIZE_1|SDIO_DCTRL_DBLOCKSIZE_2) -#define SDIO_DATABLOCK_SIZE_128B (SDIO_DCTRL_DBLOCKSIZE_0|SDIO_DCTRL_DBLOCKSIZE_1|SDIO_DCTRL_DBLOCKSIZE_2) -#define SDIO_DATABLOCK_SIZE_256B SDIO_DCTRL_DBLOCKSIZE_3 -#define SDIO_DATABLOCK_SIZE_512B (SDIO_DCTRL_DBLOCKSIZE_0|SDIO_DCTRL_DBLOCKSIZE_3) -#define SDIO_DATABLOCK_SIZE_1024B (SDIO_DCTRL_DBLOCKSIZE_1|SDIO_DCTRL_DBLOCKSIZE_3) -#define SDIO_DATABLOCK_SIZE_2048B (SDIO_DCTRL_DBLOCKSIZE_0|SDIO_DCTRL_DBLOCKSIZE_1|SDIO_DCTRL_DBLOCKSIZE_3) -#define SDIO_DATABLOCK_SIZE_4096B (SDIO_DCTRL_DBLOCKSIZE_2|SDIO_DCTRL_DBLOCKSIZE_3) -#define SDIO_DATABLOCK_SIZE_8192B (SDIO_DCTRL_DBLOCKSIZE_0|SDIO_DCTRL_DBLOCKSIZE_2|SDIO_DCTRL_DBLOCKSIZE_3) -#define SDIO_DATABLOCK_SIZE_16384B (SDIO_DCTRL_DBLOCKSIZE_1|SDIO_DCTRL_DBLOCKSIZE_2|SDIO_DCTRL_DBLOCKSIZE_3) - -#define IS_SDIO_BLOCK_SIZE(SIZE) (((SIZE) == SDIO_DATABLOCK_SIZE_1B) || \ - ((SIZE) == SDIO_DATABLOCK_SIZE_2B) || \ - ((SIZE) == SDIO_DATABLOCK_SIZE_4B) || \ - ((SIZE) == SDIO_DATABLOCK_SIZE_8B) || \ - ((SIZE) == SDIO_DATABLOCK_SIZE_16B) || \ - ((SIZE) == SDIO_DATABLOCK_SIZE_32B) || \ - ((SIZE) == SDIO_DATABLOCK_SIZE_64B) || \ - ((SIZE) == SDIO_DATABLOCK_SIZE_128B) || \ - ((SIZE) == SDIO_DATABLOCK_SIZE_256B) || \ - ((SIZE) == SDIO_DATABLOCK_SIZE_512B) || \ - ((SIZE) == SDIO_DATABLOCK_SIZE_1024B) || \ - ((SIZE) == SDIO_DATABLOCK_SIZE_2048B) || \ - ((SIZE) == SDIO_DATABLOCK_SIZE_4096B) || \ - ((SIZE) == SDIO_DATABLOCK_SIZE_8192B) || \ - ((SIZE) == SDIO_DATABLOCK_SIZE_16384B)) -/** - * @} - */ - -/** @defgroup SDIO_LL_Transfer_Direction Transfer Direction - * @{ - */ -#define SDIO_TRANSFER_DIR_TO_CARD 0x00000000U -#define SDIO_TRANSFER_DIR_TO_SDIO SDIO_DCTRL_DTDIR - -#define IS_SDIO_TRANSFER_DIR(DIR) (((DIR) == SDIO_TRANSFER_DIR_TO_CARD) || \ - ((DIR) == SDIO_TRANSFER_DIR_TO_SDIO)) -/** - * @} - */ - -/** @defgroup SDIO_LL_Transfer_Type Transfer Type - * @{ - */ -#define SDIO_TRANSFER_MODE_BLOCK 0x00000000U -#define SDIO_TRANSFER_MODE_STREAM SDIO_DCTRL_DTMODE - -#define IS_SDIO_TRANSFER_MODE(MODE) (((MODE) == SDIO_TRANSFER_MODE_BLOCK) || \ - ((MODE) == SDIO_TRANSFER_MODE_STREAM)) -/** - * @} - */ - -/** @defgroup SDIO_LL_DPSM_State DPSM State - * @{ - */ -#define SDIO_DPSM_DISABLE 0x00000000U -#define SDIO_DPSM_ENABLE SDIO_DCTRL_DTEN - -#define IS_SDIO_DPSM(DPSM) (((DPSM) == SDIO_DPSM_DISABLE) ||\ - ((DPSM) == SDIO_DPSM_ENABLE)) -/** - * @} - */ - -/** @defgroup SDIO_LL_Read_Wait_Mode Read Wait Mode - * @{ - */ -#define SDIO_READ_WAIT_MODE_DATA2 0x00000000U -#define SDIO_READ_WAIT_MODE_CLK (SDIO_DCTRL_RWMOD) - -#define IS_SDIO_READWAIT_MODE(MODE) (((MODE) == SDIO_READ_WAIT_MODE_CLK) || \ - ((MODE) == SDIO_READ_WAIT_MODE_DATA2)) -/** - * @} - */ - -/** @defgroup SDIO_LL_Interrupt_sources Interrupt Sources - * @{ - */ -#define SDIO_IT_CCRCFAIL SDIO_MASK_CCRCFAILIE -#define SDIO_IT_DCRCFAIL SDIO_MASK_DCRCFAILIE -#define SDIO_IT_CTIMEOUT SDIO_MASK_CTIMEOUTIE -#define SDIO_IT_DTIMEOUT SDIO_MASK_DTIMEOUTIE -#define SDIO_IT_TXUNDERR SDIO_MASK_TXUNDERRIE -#define SDIO_IT_RXOVERR SDIO_MASK_RXOVERRIE -#define SDIO_IT_CMDREND SDIO_MASK_CMDRENDIE -#define SDIO_IT_CMDSENT SDIO_MASK_CMDSENTIE -#define SDIO_IT_DATAEND SDIO_MASK_DATAENDIE -#if defined(SDIO_STA_STBITERR) -#define SDIO_IT_STBITERR SDIO_MASK_STBITERRIE -#endif -#define SDIO_IT_DBCKEND SDIO_MASK_DBCKENDIE -#define SDIO_IT_CMDACT SDIO_MASK_CMDACTIE -#define SDIO_IT_TXACT SDIO_MASK_TXACTIE -#define SDIO_IT_RXACT SDIO_MASK_RXACTIE -#define SDIO_IT_TXFIFOHE SDIO_MASK_TXFIFOHEIE -#define SDIO_IT_RXFIFOHF SDIO_MASK_RXFIFOHFIE -#define SDIO_IT_TXFIFOF SDIO_MASK_TXFIFOFIE -#define SDIO_IT_RXFIFOF SDIO_MASK_RXFIFOFIE -#define SDIO_IT_TXFIFOE SDIO_MASK_TXFIFOEIE -#define SDIO_IT_RXFIFOE SDIO_MASK_RXFIFOEIE -#define SDIO_IT_TXDAVL SDIO_MASK_TXDAVLIE -#define SDIO_IT_RXDAVL SDIO_MASK_RXDAVLIE -#define SDIO_IT_SDIOIT SDIO_MASK_SDIOITIE -#if defined(SDIO_CMD_CEATACMD) -#define SDIO_IT_CEATAEND SDIO_MASK_CEATAENDIE -#endif -/** - * @} - */ - -/** @defgroup SDIO_LL_Flags Flags - * @{ - */ -#define SDIO_FLAG_CCRCFAIL SDIO_STA_CCRCFAIL -#define SDIO_FLAG_DCRCFAIL SDIO_STA_DCRCFAIL -#define SDIO_FLAG_CTIMEOUT SDIO_STA_CTIMEOUT -#define SDIO_FLAG_DTIMEOUT SDIO_STA_DTIMEOUT -#define SDIO_FLAG_TXUNDERR SDIO_STA_TXUNDERR -#define SDIO_FLAG_RXOVERR SDIO_STA_RXOVERR -#define SDIO_FLAG_CMDREND SDIO_STA_CMDREND -#define SDIO_FLAG_CMDSENT SDIO_STA_CMDSENT -#define SDIO_FLAG_DATAEND SDIO_STA_DATAEND -#if defined(SDIO_STA_STBITERR) -#define SDIO_FLAG_STBITERR SDIO_STA_STBITERR -#endif -#define SDIO_FLAG_DBCKEND SDIO_STA_DBCKEND -#define SDIO_FLAG_CMDACT SDIO_STA_CMDACT -#define SDIO_FLAG_TXACT SDIO_STA_TXACT -#define SDIO_FLAG_RXACT SDIO_STA_RXACT -#define SDIO_FLAG_TXFIFOHE SDIO_STA_TXFIFOHE -#define SDIO_FLAG_RXFIFOHF SDIO_STA_RXFIFOHF -#define SDIO_FLAG_TXFIFOF SDIO_STA_TXFIFOF -#define SDIO_FLAG_RXFIFOF SDIO_STA_RXFIFOF -#define SDIO_FLAG_TXFIFOE SDIO_STA_TXFIFOE -#define SDIO_FLAG_RXFIFOE SDIO_STA_RXFIFOE -#define SDIO_FLAG_TXDAVL SDIO_STA_TXDAVL -#define SDIO_FLAG_RXDAVL SDIO_STA_RXDAVL -#define SDIO_FLAG_SDIOIT SDIO_STA_SDIOIT -#if defined(SDIO_CMD_CEATACMD) -#define SDIO_FLAG_CEATAEND SDIO_STA_CEATAEND -#endif -#define SDIO_STATIC_FLAGS ((uint32_t)(SDIO_FLAG_CCRCFAIL | SDIO_FLAG_DCRCFAIL | SDIO_FLAG_CTIMEOUT |\ - SDIO_FLAG_DTIMEOUT | SDIO_FLAG_TXUNDERR | SDIO_FLAG_RXOVERR |\ - SDIO_FLAG_CMDREND | SDIO_FLAG_CMDSENT | SDIO_FLAG_DATAEND |\ - SDIO_FLAG_DBCKEND | SDIO_FLAG_SDIOIT)) - -#define SDIO_STATIC_CMD_FLAGS ((uint32_t)(SDIO_FLAG_CCRCFAIL | SDIO_FLAG_CTIMEOUT | SDIO_FLAG_CMDREND |\ - SDIO_FLAG_CMDSENT)) - -#define SDIO_STATIC_DATA_FLAGS ((uint32_t)(SDIO_FLAG_DCRCFAIL | SDIO_FLAG_DTIMEOUT | SDIO_FLAG_TXUNDERR |\ - SDIO_FLAG_RXOVERR | SDIO_FLAG_DATAEND | SDIO_FLAG_DBCKEND)) -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup SDIO_LL_Exported_macros SDIO_LL Exported Macros - * @{ - */ - -/** @defgroup SDMMC_LL_Alias_Region Bit Address in the alias region - * @{ - */ -/* ------------ SDIO registers bit address in the alias region -------------- */ -#define SDIO_OFFSET (SDIO_BASE - PERIPH_BASE) - -/* --- CLKCR Register ---*/ -/* Alias word address of CLKEN bit */ -#define CLKCR_OFFSET (SDIO_OFFSET + 0x04U) -#define CLKEN_BITNUMBER 0x08U -#define CLKCR_CLKEN_BB (PERIPH_BB_BASE + (CLKCR_OFFSET * 32U) + (CLKEN_BITNUMBER * 4U)) - -/* --- CMD Register ---*/ -/* Alias word address of SDIOSUSPEND bit */ -#define CMD_OFFSET (SDIO_OFFSET + 0x0CU) -#define SDIOSUSPEND_BITNUMBER 0x0BU -#define CMD_SDIOSUSPEND_BB (PERIPH_BB_BASE + (CMD_OFFSET * 32U) + (SDIOSUSPEND_BITNUMBER * 4U)) - -/* Alias word address of ENCMDCOMPL bit */ -#define ENCMDCOMPL_BITNUMBER 0x0CU -#define CMD_ENCMDCOMPL_BB (PERIPH_BB_BASE + (CMD_OFFSET * 32U) + (ENCMDCOMPL_BITNUMBER * 4U)) - -/* Alias word address of NIEN bit */ -#define NIEN_BITNUMBER 0x0DU -#define CMD_NIEN_BB (PERIPH_BB_BASE + (CMD_OFFSET * 32U) + (NIEN_BITNUMBER * 4U)) - -/* Alias word address of ATACMD bit */ -#define ATACMD_BITNUMBER 0x0EU -#define CMD_ATACMD_BB (PERIPH_BB_BASE + (CMD_OFFSET * 32U) + (ATACMD_BITNUMBER * 4U)) - -/* --- DCTRL Register ---*/ -/* Alias word address of DMAEN bit */ -#define DCTRL_OFFSET (SDIO_OFFSET + 0x2CU) -#define DMAEN_BITNUMBER 0x03U -#define DCTRL_DMAEN_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32U) + (DMAEN_BITNUMBER * 4U)) - -/* Alias word address of RWSTART bit */ -#define RWSTART_BITNUMBER 0x08U -#define DCTRL_RWSTART_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32U) + (RWSTART_BITNUMBER * 4U)) - -/* Alias word address of RWSTOP bit */ -#define RWSTOP_BITNUMBER 0x09U -#define DCTRL_RWSTOP_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32U) + (RWSTOP_BITNUMBER * 4U)) - -/* Alias word address of RWMOD bit */ -#define RWMOD_BITNUMBER 0x0AU -#define DCTRL_RWMOD_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32U) + (RWMOD_BITNUMBER * 4U)) - -/* Alias word address of SDIOEN bit */ -#define SDIOEN_BITNUMBER 0x0BU -#define DCTRL_SDIOEN_BB (PERIPH_BB_BASE + (DCTRL_OFFSET * 32U) + (SDIOEN_BITNUMBER * 4U)) -/** - * @} - */ - -/** @defgroup SDIO_LL_Register Bits And Addresses Definitions - * @brief SDIO_LL registers bit address in the alias region - * @{ - */ -/* ---------------------- SDIO registers bit mask --------------------------- */ -/* --- CLKCR Register ---*/ -/* CLKCR register clear mask */ -#define CLKCR_CLEAR_MASK ((uint32_t)(SDIO_CLKCR_CLKDIV | SDIO_CLKCR_PWRSAV |\ - SDIO_CLKCR_BYPASS | SDIO_CLKCR_WIDBUS |\ - SDIO_CLKCR_NEGEDGE | SDIO_CLKCR_HWFC_EN)) - -/* --- DCTRL Register ---*/ -/* SDIO DCTRL Clear Mask */ -#define DCTRL_CLEAR_MASK ((uint32_t)(SDIO_DCTRL_DTEN | SDIO_DCTRL_DTDIR |\ - SDIO_DCTRL_DTMODE | SDIO_DCTRL_DBLOCKSIZE)) - -/* --- CMD Register ---*/ -/* CMD Register clear mask */ -#define CMD_CLEAR_MASK ((uint32_t)(SDIO_CMD_CMDINDEX | SDIO_CMD_WAITRESP |\ - SDIO_CMD_WAITINT | SDIO_CMD_WAITPEND |\ - SDIO_CMD_CPSMEN | SDIO_CMD_SDIOSUSPEND)) - -/* SDIO Initialization Frequency (400KHz max) */ -#define SDIO_INIT_CLK_DIV ((uint8_t)0x76) /* 48MHz / (SDMMC_INIT_CLK_DIV + 2) < 400KHz */ - -/* SDIO Data Transfer Frequency (25MHz max) */ -#define SDIO_TRANSFER_CLK_DIV ((uint8_t)0x0) /* 48MHz / (SDMMC_TRANSFER_CLK_DIV + 2) < 25MHz */ -/** - * @} - */ - -/** @defgroup SDIO_LL_Interrupt_Clock Interrupt And Clock Configuration - * @brief macros to handle interrupts and specific clock configurations - * @{ - */ - -/** - * @brief Enable the SDIO device. - * @param __INSTANCE__: SDIO Instance - * @retval None - */ -#define __SDIO_ENABLE(__INSTANCE__) (*(__IO uint32_t *)CLKCR_CLKEN_BB = ENABLE) - -/** - * @brief Disable the SDIO device. - * @param __INSTANCE__: SDIO Instance - * @retval None - */ -#define __SDIO_DISABLE(__INSTANCE__) (*(__IO uint32_t *)CLKCR_CLKEN_BB = DISABLE) - -/** - * @brief Enable the SDIO DMA transfer. - * @param __INSTANCE__: SDIO Instance - * @retval None - */ -#define __SDIO_DMA_ENABLE(__INSTANCE__) (*(__IO uint32_t *)DCTRL_DMAEN_BB = ENABLE) - -/** - * @brief Disable the SDIO DMA transfer. - * @param __INSTANCE__: SDIO Instance - * @retval None - */ -#define __SDIO_DMA_DISABLE(__INSTANCE__) (*(__IO uint32_t *)DCTRL_DMAEN_BB = DISABLE) - -/** - * @brief Enable the SDIO device interrupt. - * @param __INSTANCE__ : Pointer to SDIO register base - * @param __INTERRUPT__ : specifies the SDIO interrupt sources to be enabled. - * This parameter can be one or a combination of the following values: - * @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt - * @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt - * @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt - * @arg SDIO_IT_DTIMEOUT: Data timeout interrupt - * @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt - * @arg SDIO_IT_RXOVERR: Received FIFO overrun error interrupt - * @arg SDIO_IT_CMDREND: Command response received (CRC check passed) interrupt - * @arg SDIO_IT_CMDSENT: Command sent (no response required) interrupt - * @arg SDIO_IT_DATAEND: Data end (data counter, DATACOUNT, is zero) interrupt - * @arg SDIO_IT_DBCKEND: Data block sent/received (CRC check passed) interrupt - * @arg SDIO_IT_CMDACT: Command transfer in progress interrupt - * @arg SDIO_IT_TXACT: Data transmit in progress interrupt - * @arg SDIO_IT_RXACT: Data receive in progress interrupt - * @arg SDIO_IT_TXFIFOHE: Transmit FIFO Half Empty interrupt - * @arg SDIO_IT_RXFIFOHF: Receive FIFO Half Full interrupt - * @arg SDIO_IT_TXFIFOF: Transmit FIFO full interrupt - * @arg SDIO_IT_RXFIFOF: Receive FIFO full interrupt - * @arg SDIO_IT_TXFIFOE: Transmit FIFO empty interrupt - * @arg SDIO_IT_RXFIFOE: Receive FIFO empty interrupt - * @arg SDIO_IT_TXDAVL: Data available in transmit FIFO interrupt - * @arg SDIO_IT_RXDAVL: Data available in receive FIFO interrupt - * @arg SDIO_IT_SDIOIT: SDIO interrupt received interrupt - * @retval None - */ -#define __SDIO_ENABLE_IT(__INSTANCE__, __INTERRUPT__) ((__INSTANCE__)->MASK |= (__INTERRUPT__)) - -/** - * @brief Disable the SDIO device interrupt. - * @param __INSTANCE__ : Pointer to SDIO register base - * @param __INTERRUPT__ : specifies the SDIO interrupt sources to be disabled. - * This parameter can be one or a combination of the following values: - * @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt - * @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt - * @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt - * @arg SDIO_IT_DTIMEOUT: Data timeout interrupt - * @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt - * @arg SDIO_IT_RXOVERR: Received FIFO overrun error interrupt - * @arg SDIO_IT_CMDREND: Command response received (CRC check passed) interrupt - * @arg SDIO_IT_CMDSENT: Command sent (no response required) interrupt - * @arg SDIO_IT_DATAEND: Data end (data counter, DATACOUNT, is zero) interrupt - * @arg SDIO_IT_DBCKEND: Data block sent/received (CRC check passed) interrupt - * @arg SDIO_IT_CMDACT: Command transfer in progress interrupt - * @arg SDIO_IT_TXACT: Data transmit in progress interrupt - * @arg SDIO_IT_RXACT: Data receive in progress interrupt - * @arg SDIO_IT_TXFIFOHE: Transmit FIFO Half Empty interrupt - * @arg SDIO_IT_RXFIFOHF: Receive FIFO Half Full interrupt - * @arg SDIO_IT_TXFIFOF: Transmit FIFO full interrupt - * @arg SDIO_IT_RXFIFOF: Receive FIFO full interrupt - * @arg SDIO_IT_TXFIFOE: Transmit FIFO empty interrupt - * @arg SDIO_IT_RXFIFOE: Receive FIFO empty interrupt - * @arg SDIO_IT_TXDAVL: Data available in transmit FIFO interrupt - * @arg SDIO_IT_RXDAVL: Data available in receive FIFO interrupt - * @arg SDIO_IT_SDIOIT: SDIO interrupt received interrupt - * @retval None - */ -#define __SDIO_DISABLE_IT(__INSTANCE__, __INTERRUPT__) ((__INSTANCE__)->MASK &= ~(__INTERRUPT__)) - -/** - * @brief Checks whether the specified SDIO flag is set or not. - * @param __INSTANCE__ : Pointer to SDIO register base - * @param __FLAG__: specifies the flag to check. - * This parameter can be one of the following values: - * @arg SDIO_FLAG_CCRCFAIL: Command response received (CRC check failed) - * @arg SDIO_FLAG_DCRCFAIL: Data block sent/received (CRC check failed) - * @arg SDIO_FLAG_CTIMEOUT: Command response timeout - * @arg SDIO_FLAG_DTIMEOUT: Data timeout - * @arg SDIO_FLAG_TXUNDERR: Transmit FIFO underrun error - * @arg SDIO_FLAG_RXOVERR: Received FIFO overrun error - * @arg SDIO_FLAG_CMDREND: Command response received (CRC check passed) - * @arg SDIO_FLAG_CMDSENT: Command sent (no response required) - * @arg SDIO_FLAG_DATAEND: Data end (data counter, DATACOUNT, is zero) - * @arg SDIO_FLAG_DBCKEND: Data block sent/received (CRC check passed) - * @arg SDIO_FLAG_CMDACT: Command transfer in progress - * @arg SDIO_FLAG_TXACT: Data transmit in progress - * @arg SDIO_FLAG_RXACT: Data receive in progress - * @arg SDIO_FLAG_TXFIFOHE: Transmit FIFO Half Empty - * @arg SDIO_FLAG_RXFIFOHF: Receive FIFO Half Full - * @arg SDIO_FLAG_TXFIFOF: Transmit FIFO full - * @arg SDIO_FLAG_RXFIFOF: Receive FIFO full - * @arg SDIO_FLAG_TXFIFOE: Transmit FIFO empty - * @arg SDIO_FLAG_RXFIFOE: Receive FIFO empty - * @arg SDIO_FLAG_TXDAVL: Data available in transmit FIFO - * @arg SDIO_FLAG_RXDAVL: Data available in receive FIFO - * @arg SDIO_FLAG_SDIOIT: SDIO interrupt received - * @retval The new state of SDIO_FLAG (SET or RESET). - */ -#define __SDIO_GET_FLAG(__INSTANCE__, __FLAG__) (((__INSTANCE__)->STA &(__FLAG__)) != 0U) - - -/** - * @brief Clears the SDIO pending flags. - * @param __INSTANCE__ : Pointer to SDIO register base - * @param __FLAG__: specifies the flag to clear. - * This parameter can be one or a combination of the following values: - * @arg SDIO_FLAG_CCRCFAIL: Command response received (CRC check failed) - * @arg SDIO_FLAG_DCRCFAIL: Data block sent/received (CRC check failed) - * @arg SDIO_FLAG_CTIMEOUT: Command response timeout - * @arg SDIO_FLAG_DTIMEOUT: Data timeout - * @arg SDIO_FLAG_TXUNDERR: Transmit FIFO underrun error - * @arg SDIO_FLAG_RXOVERR: Received FIFO overrun error - * @arg SDIO_FLAG_CMDREND: Command response received (CRC check passed) - * @arg SDIO_FLAG_CMDSENT: Command sent (no response required) - * @arg SDIO_FLAG_DATAEND: Data end (data counter, DATACOUNT, is zero) - * @arg SDIO_FLAG_DBCKEND: Data block sent/received (CRC check passed) - * @arg SDIO_FLAG_SDIOIT: SDIO interrupt received - * @retval None - */ -#define __SDIO_CLEAR_FLAG(__INSTANCE__, __FLAG__) ((__INSTANCE__)->ICR = (__FLAG__)) - -/** - * @brief Checks whether the specified SDIO interrupt has occurred or not. - * @param __INSTANCE__ : Pointer to SDIO register base - * @param __INTERRUPT__: specifies the SDIO interrupt source to check. - * This parameter can be one of the following values: - * @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt - * @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt - * @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt - * @arg SDIO_IT_DTIMEOUT: Data timeout interrupt - * @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt - * @arg SDIO_IT_RXOVERR: Received FIFO overrun error interrupt - * @arg SDIO_IT_CMDREND: Command response received (CRC check passed) interrupt - * @arg SDIO_IT_CMDSENT: Command sent (no response required) interrupt - * @arg SDIO_IT_DATAEND: Data end (data counter, DATACOUNT, is zero) interrupt - * @arg SDIO_IT_DBCKEND: Data block sent/received (CRC check passed) interrupt - * @arg SDIO_IT_CMDACT: Command transfer in progress interrupt - * @arg SDIO_IT_TXACT: Data transmit in progress interrupt - * @arg SDIO_IT_RXACT: Data receive in progress interrupt - * @arg SDIO_IT_TXFIFOHE: Transmit FIFO Half Empty interrupt - * @arg SDIO_IT_RXFIFOHF: Receive FIFO Half Full interrupt - * @arg SDIO_IT_TXFIFOF: Transmit FIFO full interrupt - * @arg SDIO_IT_RXFIFOF: Receive FIFO full interrupt - * @arg SDIO_IT_TXFIFOE: Transmit FIFO empty interrupt - * @arg SDIO_IT_RXFIFOE: Receive FIFO empty interrupt - * @arg SDIO_IT_TXDAVL: Data available in transmit FIFO interrupt - * @arg SDIO_IT_RXDAVL: Data available in receive FIFO interrupt - * @arg SDIO_IT_SDIOIT: SDIO interrupt received interrupt - * @retval The new state of SDIO_IT (SET or RESET). - */ -#define __SDIO_GET_IT (__INSTANCE__, __INTERRUPT__) (((__INSTANCE__)->STA &(__INTERRUPT__)) == (__INTERRUPT__)) - -/** - * @brief Clears the SDIO's interrupt pending bits. - * @param __INSTANCE__ : Pointer to SDIO register base - * @param __INTERRUPT__: specifies the interrupt pending bit to clear. - * This parameter can be one or a combination of the following values: - * @arg SDIO_IT_CCRCFAIL: Command response received (CRC check failed) interrupt - * @arg SDIO_IT_DCRCFAIL: Data block sent/received (CRC check failed) interrupt - * @arg SDIO_IT_CTIMEOUT: Command response timeout interrupt - * @arg SDIO_IT_DTIMEOUT: Data timeout interrupt - * @arg SDIO_IT_TXUNDERR: Transmit FIFO underrun error interrupt - * @arg SDIO_IT_RXOVERR: Received FIFO overrun error interrupt - * @arg SDIO_IT_CMDREND: Command response received (CRC check passed) interrupt - * @arg SDIO_IT_CMDSENT: Command sent (no response required) interrupt - * @arg SDIO_IT_DATAEND: Data end (data counter, DATACOUNT, is zero) interrupt - * @arg SDIO_IT_SDIOIT: SDIO interrupt received interrupt - * @retval None - */ -#define __SDIO_CLEAR_IT(__INSTANCE__, __INTERRUPT__) ((__INSTANCE__)->ICR = (__INTERRUPT__)) - -/** - * @brief Enable Start the SD I/O Read Wait operation. - * @param __INSTANCE__ : Pointer to SDIO register base - * @retval None - */ -#define __SDIO_START_READWAIT_ENABLE(__INSTANCE__) (*(__IO uint32_t *) DCTRL_RWSTART_BB = ENABLE) - -/** - * @brief Disable Start the SD I/O Read Wait operations. - * @param __INSTANCE__ : Pointer to SDIO register base - * @retval None - */ -#define __SDIO_START_READWAIT_DISABLE(__INSTANCE__) (*(__IO uint32_t *) DCTRL_RWSTART_BB = DISABLE) - -/** - * @brief Enable Start the SD I/O Read Wait operation. - * @param __INSTANCE__ : Pointer to SDIO register base - * @retval None - */ -#define __SDIO_STOP_READWAIT_ENABLE(__INSTANCE__) (*(__IO uint32_t *) DCTRL_RWSTOP_BB = ENABLE) - -/** - * @brief Disable Stop the SD I/O Read Wait operations. - * @param __INSTANCE__ : Pointer to SDIO register base - * @retval None - */ -#define __SDIO_STOP_READWAIT_DISABLE(__INSTANCE__) (*(__IO uint32_t *) DCTRL_RWSTOP_BB = DISABLE) - -/** - * @brief Enable the SD I/O Mode Operation. - * @param __INSTANCE__ : Pointer to SDIO register base - * @retval None - */ -#define __SDIO_OPERATION_ENABLE(__INSTANCE__) (*(__IO uint32_t *) DCTRL_SDIOEN_BB = ENABLE) - -/** - * @brief Disable the SD I/O Mode Operation. - * @param __INSTANCE__ : Pointer to SDIO register base - * @retval None - */ -#define __SDIO_OPERATION_DISABLE(__INSTANCE__) (*(__IO uint32_t *) DCTRL_SDIOEN_BB = DISABLE) - -/** - * @brief Enable the SD I/O Suspend command sending. - * @param __INSTANCE__ : Pointer to SDIO register base - * @retval None - */ -#define __SDIO_SUSPEND_CMD_ENABLE(__INSTANCE__) (*(__IO uint32_t *) CMD_SDIOSUSPEND_BB = ENABLE) - -/** - * @brief Disable the SD I/O Suspend command sending. - * @param __INSTANCE__ : Pointer to SDIO register base - * @retval None - */ -#define __SDIO_SUSPEND_CMD_DISABLE(__INSTANCE__) (*(__IO uint32_t *) CMD_SDIOSUSPEND_BB = DISABLE) - -#if defined(SDIO_CMD_CEATACMD) -/** - * @brief Enable the command completion signal. - * @retval None - */ -#define __SDIO_CEATA_CMD_COMPLETION_ENABLE() (*(__IO uint32_t *) CMD_ENCMDCOMPL_BB = ENABLE) - -/** - * @brief Disable the command completion signal. - * @retval None - */ -#define __SDIO_CEATA_CMD_COMPLETION_DISABLE() (*(__IO uint32_t *) CMD_ENCMDCOMPL_BB = DISABLE) - -/** - * @brief Enable the CE-ATA interrupt. - * @retval None - */ -#define __SDIO_CEATA_ENABLE_IT() (*(__IO uint32_t *) CMD_NIEN_BB = (uint32_t)0U) - -/** - * @brief Disable the CE-ATA interrupt. - * @retval None - */ -#define __SDIO_CEATA_DISABLE_IT() (*(__IO uint32_t *) CMD_NIEN_BB = (uint32_t)1U) - -/** - * @brief Enable send CE-ATA command (CMD61). - * @retval None - */ -#define __SDIO_CEATA_SENDCMD_ENABLE() (*(__IO uint32_t *) CMD_ATACMD_BB = ENABLE) - -/** - * @brief Disable send CE-ATA command (CMD61). - * @retval None - */ -#define __SDIO_CEATA_SENDCMD_DISABLE() (*(__IO uint32_t *) CMD_ATACMD_BB = DISABLE) - -#endif -/** - * @} - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup SDMMC_LL_Exported_Functions - * @{ - */ - -/* Initialization/de-initialization functions **********************************/ -/** @addtogroup HAL_SDMMC_LL_Group1 - * @{ - */ -HAL_StatusTypeDef SDIO_Init(SDIO_TypeDef *SDIOx, SDIO_InitTypeDef Init); -/** - * @} - */ - -/* I/O operation functions *****************************************************/ -/** @addtogroup HAL_SDMMC_LL_Group2 - * @{ - */ -uint32_t SDIO_ReadFIFO(SDIO_TypeDef *SDIOx); -HAL_StatusTypeDef SDIO_WriteFIFO(SDIO_TypeDef *SDIOx, uint32_t *pWriteData); -/** - * @} - */ - -/* Peripheral Control functions ************************************************/ -/** @addtogroup HAL_SDMMC_LL_Group3 - * @{ - */ -HAL_StatusTypeDef SDIO_PowerState_ON(SDIO_TypeDef *SDIOx); -HAL_StatusTypeDef SDIO_PowerState_OFF(SDIO_TypeDef *SDIOx); -uint32_t SDIO_GetPowerState(SDIO_TypeDef *SDIOx); - -/* Command path state machine (CPSM) management functions */ -HAL_StatusTypeDef SDIO_SendCommand(SDIO_TypeDef *SDIOx, SDIO_CmdInitTypeDef *Command); -uint8_t SDIO_GetCommandResponse(SDIO_TypeDef *SDIOx); -uint32_t SDIO_GetResponse(SDIO_TypeDef *SDIOx, uint32_t Response); - -/* Data path state machine (DPSM) management functions */ -HAL_StatusTypeDef SDIO_ConfigData(SDIO_TypeDef *SDIOx, SDIO_DataInitTypeDef* Data); -uint32_t SDIO_GetDataCounter(SDIO_TypeDef *SDIOx); -uint32_t SDIO_GetFIFOCount(SDIO_TypeDef *SDIOx); - -/* SDMMC Cards mode management functions */ -HAL_StatusTypeDef SDIO_SetSDMMCReadWaitMode(SDIO_TypeDef *SDIOx, uint32_t SDIO_ReadWaitMode); - -/* SDMMC Commands management functions */ -uint32_t SDMMC_CmdBlockLength(SDIO_TypeDef *SDIOx, uint32_t BlockSize); -uint32_t SDMMC_CmdReadSingleBlock(SDIO_TypeDef *SDIOx, uint32_t ReadAdd); -uint32_t SDMMC_CmdReadMultiBlock(SDIO_TypeDef *SDIOx, uint32_t ReadAdd); -uint32_t SDMMC_CmdWriteSingleBlock(SDIO_TypeDef *SDIOx, uint32_t WriteAdd); -uint32_t SDMMC_CmdWriteMultiBlock(SDIO_TypeDef *SDIOx, uint32_t WriteAdd); -uint32_t SDMMC_CmdEraseStartAdd(SDIO_TypeDef *SDIOx, uint32_t StartAdd); -uint32_t SDMMC_CmdSDEraseStartAdd(SDIO_TypeDef *SDIOx, uint32_t StartAdd); -uint32_t SDMMC_CmdEraseEndAdd(SDIO_TypeDef *SDIOx, uint32_t EndAdd); -uint32_t SDMMC_CmdSDEraseEndAdd(SDIO_TypeDef *SDIOx, uint32_t EndAdd); -uint32_t SDMMC_CmdErase(SDIO_TypeDef *SDIOx); -uint32_t SDMMC_CmdStopTransfer(SDIO_TypeDef *SDIOx); -uint32_t SDMMC_CmdSelDesel(SDIO_TypeDef *SDIOx, uint64_t Addr); -uint32_t SDMMC_CmdGoIdleState(SDIO_TypeDef *SDIOx); -uint32_t SDMMC_CmdOperCond(SDIO_TypeDef *SDIOx); -uint32_t SDMMC_CmdAppCommand(SDIO_TypeDef *SDIOx, uint32_t Argument); -uint32_t SDMMC_CmdAppOperCommand(SDIO_TypeDef *SDIOx, uint32_t Argument); -uint32_t SDMMC_CmdBusWidth(SDIO_TypeDef *SDIOx, uint32_t BusWidth); -uint32_t SDMMC_CmdSendSCR(SDIO_TypeDef *SDIOx); -uint32_t SDMMC_CmdSendCID(SDIO_TypeDef *SDIOx); -uint32_t SDMMC_CmdSendCSD(SDIO_TypeDef *SDIOx, uint32_t Argument); -uint32_t SDMMC_CmdSendEXTCSD(SDIO_TypeDef *SDIOx, uint32_t Argument); -uint32_t SDMMC_CmdSetRelAdd(SDIO_TypeDef *SDIOx, uint16_t *pRCA); -uint32_t SDMMC_CmdSendStatus(SDIO_TypeDef *SDIOx, uint32_t Argument); -uint32_t SDMMC_CmdStatusRegister(SDIO_TypeDef *SDIOx); -uint32_t SDMMC_CmdOpCondition(SDIO_TypeDef *SDIOx, uint32_t Argument); -uint32_t SDMMC_CmdSwitch(SDIO_TypeDef *SDIOx, uint32_t Argument); - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* SDIO */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_LL_SDMMC_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_spi.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_spi.h deleted file mode 100644 index d7ef2f6..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_spi.h +++ /dev/null @@ -1,2029 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_spi.h - * @author MCD Application Team - * @brief Header file of SPI LL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_LL_SPI_H -#define STM32F4xx_LL_SPI_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (SPI1) || defined (SPI2) || defined (SPI3) || defined (SPI4) || defined (SPI5) || defined(SPI6) - -/** @defgroup SPI_LL SPI - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ - -/* Exported types ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup SPI_LL_ES_INIT SPI Exported Init structure - * @{ - */ - -/** - * @brief SPI Init structures definition - */ -typedef struct -{ - uint32_t TransferDirection; /*!< Specifies the SPI unidirectional or bidirectional data mode. - This parameter can be a value of @ref SPI_LL_EC_TRANSFER_MODE. - - This feature can be modified afterwards using unitary function @ref LL_SPI_SetTransferDirection().*/ - - uint32_t Mode; /*!< Specifies the SPI mode (Master/Slave). - This parameter can be a value of @ref SPI_LL_EC_MODE. - - This feature can be modified afterwards using unitary function @ref LL_SPI_SetMode().*/ - - uint32_t DataWidth; /*!< Specifies the SPI data width. - This parameter can be a value of @ref SPI_LL_EC_DATAWIDTH. - - This feature can be modified afterwards using unitary function @ref LL_SPI_SetDataWidth().*/ - - uint32_t ClockPolarity; /*!< Specifies the serial clock steady state. - This parameter can be a value of @ref SPI_LL_EC_POLARITY. - - This feature can be modified afterwards using unitary function @ref LL_SPI_SetClockPolarity().*/ - - uint32_t ClockPhase; /*!< Specifies the clock active edge for the bit capture. - This parameter can be a value of @ref SPI_LL_EC_PHASE. - - This feature can be modified afterwards using unitary function @ref LL_SPI_SetClockPhase().*/ - - uint32_t NSS; /*!< Specifies whether the NSS signal is managed by hardware (NSS pin) or by software using the SSI bit. - This parameter can be a value of @ref SPI_LL_EC_NSS_MODE. - - This feature can be modified afterwards using unitary function @ref LL_SPI_SetNSSMode().*/ - - uint32_t BaudRate; /*!< Specifies the BaudRate prescaler value which will be used to configure the transmit and receive SCK clock. - This parameter can be a value of @ref SPI_LL_EC_BAUDRATEPRESCALER. - @note The communication clock is derived from the master clock. The slave clock does not need to be set. - - This feature can be modified afterwards using unitary function @ref LL_SPI_SetBaudRatePrescaler().*/ - - uint32_t BitOrder; /*!< Specifies whether data transfers start from MSB or LSB bit. - This parameter can be a value of @ref SPI_LL_EC_BIT_ORDER. - - This feature can be modified afterwards using unitary function @ref LL_SPI_SetTransferBitOrder().*/ - - uint32_t CRCCalculation; /*!< Specifies if the CRC calculation is enabled or not. - This parameter can be a value of @ref SPI_LL_EC_CRC_CALCULATION. - - This feature can be modified afterwards using unitary functions @ref LL_SPI_EnableCRC() and @ref LL_SPI_DisableCRC().*/ - - uint32_t CRCPoly; /*!< Specifies the polynomial used for the CRC calculation. - This parameter must be a number between Min_Data = 0x00 and Max_Data = 0xFFFF. - - This feature can be modified afterwards using unitary function @ref LL_SPI_SetCRCPolynomial().*/ - -} LL_SPI_InitTypeDef; - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup SPI_LL_Exported_Constants SPI Exported Constants - * @{ - */ - -/** @defgroup SPI_LL_EC_GET_FLAG Get Flags Defines - * @brief Flags defines which can be used with LL_SPI_ReadReg function - * @{ - */ -#define LL_SPI_SR_RXNE SPI_SR_RXNE /*!< Rx buffer not empty flag */ -#define LL_SPI_SR_TXE SPI_SR_TXE /*!< Tx buffer empty flag */ -#define LL_SPI_SR_BSY SPI_SR_BSY /*!< Busy flag */ -#define LL_SPI_SR_CRCERR SPI_SR_CRCERR /*!< CRC error flag */ -#define LL_SPI_SR_MODF SPI_SR_MODF /*!< Mode fault flag */ -#define LL_SPI_SR_OVR SPI_SR_OVR /*!< Overrun flag */ -#define LL_SPI_SR_FRE SPI_SR_FRE /*!< TI mode frame format error flag */ -/** - * @} - */ - -/** @defgroup SPI_LL_EC_IT IT Defines - * @brief IT defines which can be used with LL_SPI_ReadReg and LL_SPI_WriteReg functions - * @{ - */ -#define LL_SPI_CR2_RXNEIE SPI_CR2_RXNEIE /*!< Rx buffer not empty interrupt enable */ -#define LL_SPI_CR2_TXEIE SPI_CR2_TXEIE /*!< Tx buffer empty interrupt enable */ -#define LL_SPI_CR2_ERRIE SPI_CR2_ERRIE /*!< Error interrupt enable */ -/** - * @} - */ - -/** @defgroup SPI_LL_EC_MODE Operation Mode - * @{ - */ -#define LL_SPI_MODE_MASTER (SPI_CR1_MSTR | SPI_CR1_SSI) /*!< Master configuration */ -#define LL_SPI_MODE_SLAVE 0x00000000U /*!< Slave configuration */ -/** - * @} - */ - -/** @defgroup SPI_LL_EC_PROTOCOL Serial Protocol - * @{ - */ -#define LL_SPI_PROTOCOL_MOTOROLA 0x00000000U /*!< Motorola mode. Used as default value */ -#define LL_SPI_PROTOCOL_TI (SPI_CR2_FRF) /*!< TI mode */ -/** - * @} - */ - -/** @defgroup SPI_LL_EC_PHASE Clock Phase - * @{ - */ -#define LL_SPI_PHASE_1EDGE 0x00000000U /*!< First clock transition is the first data capture edge */ -#define LL_SPI_PHASE_2EDGE (SPI_CR1_CPHA) /*!< Second clock transition is the first data capture edge */ -/** - * @} - */ - -/** @defgroup SPI_LL_EC_POLARITY Clock Polarity - * @{ - */ -#define LL_SPI_POLARITY_LOW 0x00000000U /*!< Clock to 0 when idle */ -#define LL_SPI_POLARITY_HIGH (SPI_CR1_CPOL) /*!< Clock to 1 when idle */ -/** - * @} - */ - -/** @defgroup SPI_LL_EC_BAUDRATEPRESCALER Baud Rate Prescaler - * @{ - */ -#define LL_SPI_BAUDRATEPRESCALER_DIV2 0x00000000U /*!< BaudRate control equal to fPCLK/2 */ -#define LL_SPI_BAUDRATEPRESCALER_DIV4 (SPI_CR1_BR_0) /*!< BaudRate control equal to fPCLK/4 */ -#define LL_SPI_BAUDRATEPRESCALER_DIV8 (SPI_CR1_BR_1) /*!< BaudRate control equal to fPCLK/8 */ -#define LL_SPI_BAUDRATEPRESCALER_DIV16 (SPI_CR1_BR_1 | SPI_CR1_BR_0) /*!< BaudRate control equal to fPCLK/16 */ -#define LL_SPI_BAUDRATEPRESCALER_DIV32 (SPI_CR1_BR_2) /*!< BaudRate control equal to fPCLK/32 */ -#define LL_SPI_BAUDRATEPRESCALER_DIV64 (SPI_CR1_BR_2 | SPI_CR1_BR_0) /*!< BaudRate control equal to fPCLK/64 */ -#define LL_SPI_BAUDRATEPRESCALER_DIV128 (SPI_CR1_BR_2 | SPI_CR1_BR_1) /*!< BaudRate control equal to fPCLK/128 */ -#define LL_SPI_BAUDRATEPRESCALER_DIV256 (SPI_CR1_BR_2 | SPI_CR1_BR_1 | SPI_CR1_BR_0) /*!< BaudRate control equal to fPCLK/256 */ -/** - * @} - */ - -/** @defgroup SPI_LL_EC_BIT_ORDER Transmission Bit Order - * @{ - */ -#define LL_SPI_LSB_FIRST (SPI_CR1_LSBFIRST) /*!< Data is transmitted/received with the LSB first */ -#define LL_SPI_MSB_FIRST 0x00000000U /*!< Data is transmitted/received with the MSB first */ -/** - * @} - */ - -/** @defgroup SPI_LL_EC_TRANSFER_MODE Transfer Mode - * @{ - */ -#define LL_SPI_FULL_DUPLEX 0x00000000U /*!< Full-Duplex mode. Rx and Tx transfer on 2 lines */ -#define LL_SPI_SIMPLEX_RX (SPI_CR1_RXONLY) /*!< Simplex Rx mode. Rx transfer only on 1 line */ -#define LL_SPI_HALF_DUPLEX_RX (SPI_CR1_BIDIMODE) /*!< Half-Duplex Rx mode. Rx transfer on 1 line */ -#define LL_SPI_HALF_DUPLEX_TX (SPI_CR1_BIDIMODE | SPI_CR1_BIDIOE) /*!< Half-Duplex Tx mode. Tx transfer on 1 line */ -/** - * @} - */ - -/** @defgroup SPI_LL_EC_NSS_MODE Slave Select Pin Mode - * @{ - */ -#define LL_SPI_NSS_SOFT (SPI_CR1_SSM) /*!< NSS managed internally. NSS pin not used and free */ -#define LL_SPI_NSS_HARD_INPUT 0x00000000U /*!< NSS pin used in Input. Only used in Master mode */ -#define LL_SPI_NSS_HARD_OUTPUT (((uint32_t)SPI_CR2_SSOE << 16U)) /*!< NSS pin used in Output. Only used in Slave mode as chip select */ -/** - * @} - */ - -/** @defgroup SPI_LL_EC_DATAWIDTH Datawidth - * @{ - */ -#define LL_SPI_DATAWIDTH_8BIT 0x00000000U /*!< Data length for SPI transfer: 8 bits */ -#define LL_SPI_DATAWIDTH_16BIT (SPI_CR1_DFF) /*!< Data length for SPI transfer: 16 bits */ -/** - * @} - */ -#if defined(USE_FULL_LL_DRIVER) - -/** @defgroup SPI_LL_EC_CRC_CALCULATION CRC Calculation - * @{ - */ -#define LL_SPI_CRCCALCULATION_DISABLE 0x00000000U /*!< CRC calculation disabled */ -#define LL_SPI_CRCCALCULATION_ENABLE (SPI_CR1_CRCEN) /*!< CRC calculation enabled */ -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup SPI_LL_Exported_Macros SPI Exported Macros - * @{ - */ - -/** @defgroup SPI_LL_EM_WRITE_READ Common Write and read registers Macros - * @{ - */ - -/** - * @brief Write a value in SPI register - * @param __INSTANCE__ SPI Instance - * @param __REG__ Register to be written - * @param __VALUE__ Value to be written in the register - * @retval None - */ -#define LL_SPI_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__)) - -/** - * @brief Read a value in SPI register - * @param __INSTANCE__ SPI Instance - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_SPI_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__) -/** - * @} - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup SPI_LL_Exported_Functions SPI Exported Functions - * @{ - */ - -/** @defgroup SPI_LL_EF_Configuration Configuration - * @{ - */ - -/** - * @brief Enable SPI peripheral - * @rmtoll CR1 SPE LL_SPI_Enable - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_SPI_Enable(SPI_TypeDef *SPIx) -{ - SET_BIT(SPIx->CR1, SPI_CR1_SPE); -} - -/** - * @brief Disable SPI peripheral - * @note When disabling the SPI, follow the procedure described in the Reference Manual. - * @rmtoll CR1 SPE LL_SPI_Disable - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_SPI_Disable(SPI_TypeDef *SPIx) -{ - CLEAR_BIT(SPIx->CR1, SPI_CR1_SPE); -} - -/** - * @brief Check if SPI peripheral is enabled - * @rmtoll CR1 SPE LL_SPI_IsEnabled - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_SPI_IsEnabled(SPI_TypeDef *SPIx) -{ - return ((READ_BIT(SPIx->CR1, SPI_CR1_SPE) == (SPI_CR1_SPE)) ? 1UL : 0UL); -} - -/** - * @brief Set SPI operation mode to Master or Slave - * @note This bit should not be changed when communication is ongoing. - * @rmtoll CR1 MSTR LL_SPI_SetMode\n - * CR1 SSI LL_SPI_SetMode - * @param SPIx SPI Instance - * @param Mode This parameter can be one of the following values: - * @arg @ref LL_SPI_MODE_MASTER - * @arg @ref LL_SPI_MODE_SLAVE - * @retval None - */ -__STATIC_INLINE void LL_SPI_SetMode(SPI_TypeDef *SPIx, uint32_t Mode) -{ - MODIFY_REG(SPIx->CR1, SPI_CR1_MSTR | SPI_CR1_SSI, Mode); -} - -/** - * @brief Get SPI operation mode (Master or Slave) - * @rmtoll CR1 MSTR LL_SPI_GetMode\n - * CR1 SSI LL_SPI_GetMode - * @param SPIx SPI Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_SPI_MODE_MASTER - * @arg @ref LL_SPI_MODE_SLAVE - */ -__STATIC_INLINE uint32_t LL_SPI_GetMode(SPI_TypeDef *SPIx) -{ - return (uint32_t)(READ_BIT(SPIx->CR1, SPI_CR1_MSTR | SPI_CR1_SSI)); -} - -/** - * @brief Set serial protocol used - * @note This bit should be written only when SPI is disabled (SPE = 0) for correct operation. - * @rmtoll CR2 FRF LL_SPI_SetStandard - * @param SPIx SPI Instance - * @param Standard This parameter can be one of the following values: - * @arg @ref LL_SPI_PROTOCOL_MOTOROLA - * @arg @ref LL_SPI_PROTOCOL_TI - * @retval None - */ -__STATIC_INLINE void LL_SPI_SetStandard(SPI_TypeDef *SPIx, uint32_t Standard) -{ - MODIFY_REG(SPIx->CR2, SPI_CR2_FRF, Standard); -} - -/** - * @brief Get serial protocol used - * @rmtoll CR2 FRF LL_SPI_GetStandard - * @param SPIx SPI Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_SPI_PROTOCOL_MOTOROLA - * @arg @ref LL_SPI_PROTOCOL_TI - */ -__STATIC_INLINE uint32_t LL_SPI_GetStandard(SPI_TypeDef *SPIx) -{ - return (uint32_t)(READ_BIT(SPIx->CR2, SPI_CR2_FRF)); -} - -/** - * @brief Set clock phase - * @note This bit should not be changed when communication is ongoing. - * This bit is not used in SPI TI mode. - * @rmtoll CR1 CPHA LL_SPI_SetClockPhase - * @param SPIx SPI Instance - * @param ClockPhase This parameter can be one of the following values: - * @arg @ref LL_SPI_PHASE_1EDGE - * @arg @ref LL_SPI_PHASE_2EDGE - * @retval None - */ -__STATIC_INLINE void LL_SPI_SetClockPhase(SPI_TypeDef *SPIx, uint32_t ClockPhase) -{ - MODIFY_REG(SPIx->CR1, SPI_CR1_CPHA, ClockPhase); -} - -/** - * @brief Get clock phase - * @rmtoll CR1 CPHA LL_SPI_GetClockPhase - * @param SPIx SPI Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_SPI_PHASE_1EDGE - * @arg @ref LL_SPI_PHASE_2EDGE - */ -__STATIC_INLINE uint32_t LL_SPI_GetClockPhase(SPI_TypeDef *SPIx) -{ - return (uint32_t)(READ_BIT(SPIx->CR1, SPI_CR1_CPHA)); -} - -/** - * @brief Set clock polarity - * @note This bit should not be changed when communication is ongoing. - * This bit is not used in SPI TI mode. - * @rmtoll CR1 CPOL LL_SPI_SetClockPolarity - * @param SPIx SPI Instance - * @param ClockPolarity This parameter can be one of the following values: - * @arg @ref LL_SPI_POLARITY_LOW - * @arg @ref LL_SPI_POLARITY_HIGH - * @retval None - */ -__STATIC_INLINE void LL_SPI_SetClockPolarity(SPI_TypeDef *SPIx, uint32_t ClockPolarity) -{ - MODIFY_REG(SPIx->CR1, SPI_CR1_CPOL, ClockPolarity); -} - -/** - * @brief Get clock polarity - * @rmtoll CR1 CPOL LL_SPI_GetClockPolarity - * @param SPIx SPI Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_SPI_POLARITY_LOW - * @arg @ref LL_SPI_POLARITY_HIGH - */ -__STATIC_INLINE uint32_t LL_SPI_GetClockPolarity(SPI_TypeDef *SPIx) -{ - return (uint32_t)(READ_BIT(SPIx->CR1, SPI_CR1_CPOL)); -} - -/** - * @brief Set baud rate prescaler - * @note These bits should not be changed when communication is ongoing. SPI BaudRate = fPCLK/Prescaler. - * @rmtoll CR1 BR LL_SPI_SetBaudRatePrescaler - * @param SPIx SPI Instance - * @param BaudRate This parameter can be one of the following values: - * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV2 - * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV4 - * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV8 - * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV16 - * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV32 - * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV64 - * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV128 - * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV256 - * @retval None - */ -__STATIC_INLINE void LL_SPI_SetBaudRatePrescaler(SPI_TypeDef *SPIx, uint32_t BaudRate) -{ - MODIFY_REG(SPIx->CR1, SPI_CR1_BR, BaudRate); -} - -/** - * @brief Get baud rate prescaler - * @rmtoll CR1 BR LL_SPI_GetBaudRatePrescaler - * @param SPIx SPI Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV2 - * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV4 - * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV8 - * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV16 - * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV32 - * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV64 - * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV128 - * @arg @ref LL_SPI_BAUDRATEPRESCALER_DIV256 - */ -__STATIC_INLINE uint32_t LL_SPI_GetBaudRatePrescaler(SPI_TypeDef *SPIx) -{ - return (uint32_t)(READ_BIT(SPIx->CR1, SPI_CR1_BR)); -} - -/** - * @brief Set transfer bit order - * @note This bit should not be changed when communication is ongoing. This bit is not used in SPI TI mode. - * @rmtoll CR1 LSBFIRST LL_SPI_SetTransferBitOrder - * @param SPIx SPI Instance - * @param BitOrder This parameter can be one of the following values: - * @arg @ref LL_SPI_LSB_FIRST - * @arg @ref LL_SPI_MSB_FIRST - * @retval None - */ -__STATIC_INLINE void LL_SPI_SetTransferBitOrder(SPI_TypeDef *SPIx, uint32_t BitOrder) -{ - MODIFY_REG(SPIx->CR1, SPI_CR1_LSBFIRST, BitOrder); -} - -/** - * @brief Get transfer bit order - * @rmtoll CR1 LSBFIRST LL_SPI_GetTransferBitOrder - * @param SPIx SPI Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_SPI_LSB_FIRST - * @arg @ref LL_SPI_MSB_FIRST - */ -__STATIC_INLINE uint32_t LL_SPI_GetTransferBitOrder(SPI_TypeDef *SPIx) -{ - return (uint32_t)(READ_BIT(SPIx->CR1, SPI_CR1_LSBFIRST)); -} - -/** - * @brief Set transfer direction mode - * @note For Half-Duplex mode, Rx Direction is set by default. - * In master mode, the MOSI pin is used and in slave mode, the MISO pin is used for Half-Duplex. - * @rmtoll CR1 RXONLY LL_SPI_SetTransferDirection\n - * CR1 BIDIMODE LL_SPI_SetTransferDirection\n - * CR1 BIDIOE LL_SPI_SetTransferDirection - * @param SPIx SPI Instance - * @param TransferDirection This parameter can be one of the following values: - * @arg @ref LL_SPI_FULL_DUPLEX - * @arg @ref LL_SPI_SIMPLEX_RX - * @arg @ref LL_SPI_HALF_DUPLEX_RX - * @arg @ref LL_SPI_HALF_DUPLEX_TX - * @retval None - */ -__STATIC_INLINE void LL_SPI_SetTransferDirection(SPI_TypeDef *SPIx, uint32_t TransferDirection) -{ - MODIFY_REG(SPIx->CR1, SPI_CR1_RXONLY | SPI_CR1_BIDIMODE | SPI_CR1_BIDIOE, TransferDirection); -} - -/** - * @brief Get transfer direction mode - * @rmtoll CR1 RXONLY LL_SPI_GetTransferDirection\n - * CR1 BIDIMODE LL_SPI_GetTransferDirection\n - * CR1 BIDIOE LL_SPI_GetTransferDirection - * @param SPIx SPI Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_SPI_FULL_DUPLEX - * @arg @ref LL_SPI_SIMPLEX_RX - * @arg @ref LL_SPI_HALF_DUPLEX_RX - * @arg @ref LL_SPI_HALF_DUPLEX_TX - */ -__STATIC_INLINE uint32_t LL_SPI_GetTransferDirection(SPI_TypeDef *SPIx) -{ - return (uint32_t)(READ_BIT(SPIx->CR1, SPI_CR1_RXONLY | SPI_CR1_BIDIMODE | SPI_CR1_BIDIOE)); -} - -/** - * @brief Set frame data width - * @rmtoll CR1 DFF LL_SPI_SetDataWidth - * @param SPIx SPI Instance - * @param DataWidth This parameter can be one of the following values: - * @arg @ref LL_SPI_DATAWIDTH_8BIT - * @arg @ref LL_SPI_DATAWIDTH_16BIT - * @retval None - */ -__STATIC_INLINE void LL_SPI_SetDataWidth(SPI_TypeDef *SPIx, uint32_t DataWidth) -{ - MODIFY_REG(SPIx->CR1, SPI_CR1_DFF, DataWidth); -} - -/** - * @brief Get frame data width - * @rmtoll CR1 DFF LL_SPI_GetDataWidth - * @param SPIx SPI Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_SPI_DATAWIDTH_8BIT - * @arg @ref LL_SPI_DATAWIDTH_16BIT - */ -__STATIC_INLINE uint32_t LL_SPI_GetDataWidth(SPI_TypeDef *SPIx) -{ - return (uint32_t)(READ_BIT(SPIx->CR1, SPI_CR1_DFF)); -} - -/** - * @} - */ - -/** @defgroup SPI_LL_EF_CRC_Management CRC Management - * @{ - */ - -/** - * @brief Enable CRC - * @note This bit should be written only when SPI is disabled (SPE = 0) for correct operation. - * @rmtoll CR1 CRCEN LL_SPI_EnableCRC - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_SPI_EnableCRC(SPI_TypeDef *SPIx) -{ - SET_BIT(SPIx->CR1, SPI_CR1_CRCEN); -} - -/** - * @brief Disable CRC - * @note This bit should be written only when SPI is disabled (SPE = 0) for correct operation. - * @rmtoll CR1 CRCEN LL_SPI_DisableCRC - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_SPI_DisableCRC(SPI_TypeDef *SPIx) -{ - CLEAR_BIT(SPIx->CR1, SPI_CR1_CRCEN); -} - -/** - * @brief Check if CRC is enabled - * @note This bit should be written only when SPI is disabled (SPE = 0) for correct operation. - * @rmtoll CR1 CRCEN LL_SPI_IsEnabledCRC - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_SPI_IsEnabledCRC(SPI_TypeDef *SPIx) -{ - return ((READ_BIT(SPIx->CR1, SPI_CR1_CRCEN) == (SPI_CR1_CRCEN)) ? 1UL : 0UL); -} - -/** - * @brief Set CRCNext to transfer CRC on the line - * @note This bit has to be written as soon as the last data is written in the SPIx_DR register. - * @rmtoll CR1 CRCNEXT LL_SPI_SetCRCNext - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_SPI_SetCRCNext(SPI_TypeDef *SPIx) -{ - SET_BIT(SPIx->CR1, SPI_CR1_CRCNEXT); -} - -/** - * @brief Set polynomial for CRC calculation - * @rmtoll CRCPR CRCPOLY LL_SPI_SetCRCPolynomial - * @param SPIx SPI Instance - * @param CRCPoly This parameter must be a number between Min_Data = 0x00 and Max_Data = 0xFFFF - * @retval None - */ -__STATIC_INLINE void LL_SPI_SetCRCPolynomial(SPI_TypeDef *SPIx, uint32_t CRCPoly) -{ - WRITE_REG(SPIx->CRCPR, (uint16_t)CRCPoly); -} - -/** - * @brief Get polynomial for CRC calculation - * @rmtoll CRCPR CRCPOLY LL_SPI_GetCRCPolynomial - * @param SPIx SPI Instance - * @retval Returned value is a number between Min_Data = 0x00 and Max_Data = 0xFFFF - */ -__STATIC_INLINE uint32_t LL_SPI_GetCRCPolynomial(SPI_TypeDef *SPIx) -{ - return (uint32_t)(READ_REG(SPIx->CRCPR)); -} - -/** - * @brief Get Rx CRC - * @rmtoll RXCRCR RXCRC LL_SPI_GetRxCRC - * @param SPIx SPI Instance - * @retval Returned value is a number between Min_Data = 0x00 and Max_Data = 0xFFFF - */ -__STATIC_INLINE uint32_t LL_SPI_GetRxCRC(SPI_TypeDef *SPIx) -{ - return (uint32_t)(READ_REG(SPIx->RXCRCR)); -} - -/** - * @brief Get Tx CRC - * @rmtoll TXCRCR TXCRC LL_SPI_GetTxCRC - * @param SPIx SPI Instance - * @retval Returned value is a number between Min_Data = 0x00 and Max_Data = 0xFFFF - */ -__STATIC_INLINE uint32_t LL_SPI_GetTxCRC(SPI_TypeDef *SPIx) -{ - return (uint32_t)(READ_REG(SPIx->TXCRCR)); -} - -/** - * @} - */ - -/** @defgroup SPI_LL_EF_NSS_Management Slave Select Pin Management - * @{ - */ - -/** - * @brief Set NSS mode - * @note LL_SPI_NSS_SOFT Mode is not used in SPI TI mode. - * @rmtoll CR1 SSM LL_SPI_SetNSSMode\n - * @rmtoll CR2 SSOE LL_SPI_SetNSSMode - * @param SPIx SPI Instance - * @param NSS This parameter can be one of the following values: - * @arg @ref LL_SPI_NSS_SOFT - * @arg @ref LL_SPI_NSS_HARD_INPUT - * @arg @ref LL_SPI_NSS_HARD_OUTPUT - * @retval None - */ -__STATIC_INLINE void LL_SPI_SetNSSMode(SPI_TypeDef *SPIx, uint32_t NSS) -{ - MODIFY_REG(SPIx->CR1, SPI_CR1_SSM, NSS); - MODIFY_REG(SPIx->CR2, SPI_CR2_SSOE, ((uint32_t)(NSS >> 16U))); -} - -/** - * @brief Get NSS mode - * @rmtoll CR1 SSM LL_SPI_GetNSSMode\n - * @rmtoll CR2 SSOE LL_SPI_GetNSSMode - * @param SPIx SPI Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_SPI_NSS_SOFT - * @arg @ref LL_SPI_NSS_HARD_INPUT - * @arg @ref LL_SPI_NSS_HARD_OUTPUT - */ -__STATIC_INLINE uint32_t LL_SPI_GetNSSMode(SPI_TypeDef *SPIx) -{ - uint32_t Ssm = (READ_BIT(SPIx->CR1, SPI_CR1_SSM)); - uint32_t Ssoe = (READ_BIT(SPIx->CR2, SPI_CR2_SSOE) << 16U); - return (Ssm | Ssoe); -} - -/** - * @} - */ - -/** @defgroup SPI_LL_EF_FLAG_Management FLAG Management - * @{ - */ - -/** - * @brief Check if Rx buffer is not empty - * @rmtoll SR RXNE LL_SPI_IsActiveFlag_RXNE - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_SPI_IsActiveFlag_RXNE(SPI_TypeDef *SPIx) -{ - return ((READ_BIT(SPIx->SR, SPI_SR_RXNE) == (SPI_SR_RXNE)) ? 1UL : 0UL); -} - -/** - * @brief Check if Tx buffer is empty - * @rmtoll SR TXE LL_SPI_IsActiveFlag_TXE - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_SPI_IsActiveFlag_TXE(SPI_TypeDef *SPIx) -{ - return ((READ_BIT(SPIx->SR, SPI_SR_TXE) == (SPI_SR_TXE)) ? 1UL : 0UL); -} - -/** - * @brief Get CRC error flag - * @rmtoll SR CRCERR LL_SPI_IsActiveFlag_CRCERR - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_SPI_IsActiveFlag_CRCERR(SPI_TypeDef *SPIx) -{ - return ((READ_BIT(SPIx->SR, SPI_SR_CRCERR) == (SPI_SR_CRCERR)) ? 1UL : 0UL); -} - -/** - * @brief Get mode fault error flag - * @rmtoll SR MODF LL_SPI_IsActiveFlag_MODF - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_SPI_IsActiveFlag_MODF(SPI_TypeDef *SPIx) -{ - return ((READ_BIT(SPIx->SR, SPI_SR_MODF) == (SPI_SR_MODF)) ? 1UL : 0UL); -} - -/** - * @brief Get overrun error flag - * @rmtoll SR OVR LL_SPI_IsActiveFlag_OVR - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_SPI_IsActiveFlag_OVR(SPI_TypeDef *SPIx) -{ - return ((READ_BIT(SPIx->SR, SPI_SR_OVR) == (SPI_SR_OVR)) ? 1UL : 0UL); -} - -/** - * @brief Get busy flag - * @note The BSY flag is cleared under any one of the following conditions: - * -When the SPI is correctly disabled - * -When a fault is detected in Master mode (MODF bit set to 1) - * -In Master mode, when it finishes a data transmission and no new data is ready to be - * sent - * -In Slave mode, when the BSY flag is set to '0' for at least one SPI clock cycle between - * each data transfer. - * @rmtoll SR BSY LL_SPI_IsActiveFlag_BSY - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_SPI_IsActiveFlag_BSY(SPI_TypeDef *SPIx) -{ - return ((READ_BIT(SPIx->SR, SPI_SR_BSY) == (SPI_SR_BSY)) ? 1UL : 0UL); -} - -/** - * @brief Get frame format error flag - * @rmtoll SR FRE LL_SPI_IsActiveFlag_FRE - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_SPI_IsActiveFlag_FRE(SPI_TypeDef *SPIx) -{ - return ((READ_BIT(SPIx->SR, SPI_SR_FRE) == (SPI_SR_FRE)) ? 1UL : 0UL); -} - -/** - * @brief Clear CRC error flag - * @rmtoll SR CRCERR LL_SPI_ClearFlag_CRCERR - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_SPI_ClearFlag_CRCERR(SPI_TypeDef *SPIx) -{ - CLEAR_BIT(SPIx->SR, SPI_SR_CRCERR); -} - -/** - * @brief Clear mode fault error flag - * @note Clearing this flag is done by a read access to the SPIx_SR - * register followed by a write access to the SPIx_CR1 register - * @rmtoll SR MODF LL_SPI_ClearFlag_MODF - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_SPI_ClearFlag_MODF(SPI_TypeDef *SPIx) -{ - __IO uint32_t tmpreg_sr; - tmpreg_sr = SPIx->SR; - (void) tmpreg_sr; - CLEAR_BIT(SPIx->CR1, SPI_CR1_SPE); -} - -/** - * @brief Clear overrun error flag - * @note Clearing this flag is done by a read access to the SPIx_DR - * register followed by a read access to the SPIx_SR register - * @rmtoll SR OVR LL_SPI_ClearFlag_OVR - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_SPI_ClearFlag_OVR(SPI_TypeDef *SPIx) -{ - __IO uint32_t tmpreg; - tmpreg = SPIx->DR; - (void) tmpreg; - tmpreg = SPIx->SR; - (void) tmpreg; -} - -/** - * @brief Clear frame format error flag - * @note Clearing this flag is done by reading SPIx_SR register - * @rmtoll SR FRE LL_SPI_ClearFlag_FRE - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_SPI_ClearFlag_FRE(SPI_TypeDef *SPIx) -{ - __IO uint32_t tmpreg; - tmpreg = SPIx->SR; - (void) tmpreg; -} - -/** - * @} - */ - -/** @defgroup SPI_LL_EF_IT_Management Interrupt Management - * @{ - */ - -/** - * @brief Enable error interrupt - * @note This bit controls the generation of an interrupt when an error condition occurs (CRCERR, OVR, MODF in SPI mode, FRE at TI mode). - * @rmtoll CR2 ERRIE LL_SPI_EnableIT_ERR - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_SPI_EnableIT_ERR(SPI_TypeDef *SPIx) -{ - SET_BIT(SPIx->CR2, SPI_CR2_ERRIE); -} - -/** - * @brief Enable Rx buffer not empty interrupt - * @rmtoll CR2 RXNEIE LL_SPI_EnableIT_RXNE - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_SPI_EnableIT_RXNE(SPI_TypeDef *SPIx) -{ - SET_BIT(SPIx->CR2, SPI_CR2_RXNEIE); -} - -/** - * @brief Enable Tx buffer empty interrupt - * @rmtoll CR2 TXEIE LL_SPI_EnableIT_TXE - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_SPI_EnableIT_TXE(SPI_TypeDef *SPIx) -{ - SET_BIT(SPIx->CR2, SPI_CR2_TXEIE); -} - -/** - * @brief Disable error interrupt - * @note This bit controls the generation of an interrupt when an error condition occurs (CRCERR, OVR, MODF in SPI mode, FRE at TI mode). - * @rmtoll CR2 ERRIE LL_SPI_DisableIT_ERR - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_SPI_DisableIT_ERR(SPI_TypeDef *SPIx) -{ - CLEAR_BIT(SPIx->CR2, SPI_CR2_ERRIE); -} - -/** - * @brief Disable Rx buffer not empty interrupt - * @rmtoll CR2 RXNEIE LL_SPI_DisableIT_RXNE - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_SPI_DisableIT_RXNE(SPI_TypeDef *SPIx) -{ - CLEAR_BIT(SPIx->CR2, SPI_CR2_RXNEIE); -} - -/** - * @brief Disable Tx buffer empty interrupt - * @rmtoll CR2 TXEIE LL_SPI_DisableIT_TXE - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_SPI_DisableIT_TXE(SPI_TypeDef *SPIx) -{ - CLEAR_BIT(SPIx->CR2, SPI_CR2_TXEIE); -} - -/** - * @brief Check if error interrupt is enabled - * @rmtoll CR2 ERRIE LL_SPI_IsEnabledIT_ERR - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_SPI_IsEnabledIT_ERR(SPI_TypeDef *SPIx) -{ - return ((READ_BIT(SPIx->CR2, SPI_CR2_ERRIE) == (SPI_CR2_ERRIE)) ? 1UL : 0UL); -} - -/** - * @brief Check if Rx buffer not empty interrupt is enabled - * @rmtoll CR2 RXNEIE LL_SPI_IsEnabledIT_RXNE - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_SPI_IsEnabledIT_RXNE(SPI_TypeDef *SPIx) -{ - return ((READ_BIT(SPIx->CR2, SPI_CR2_RXNEIE) == (SPI_CR2_RXNEIE)) ? 1UL : 0UL); -} - -/** - * @brief Check if Tx buffer empty interrupt - * @rmtoll CR2 TXEIE LL_SPI_IsEnabledIT_TXE - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_SPI_IsEnabledIT_TXE(SPI_TypeDef *SPIx) -{ - return ((READ_BIT(SPIx->CR2, SPI_CR2_TXEIE) == (SPI_CR2_TXEIE)) ? 1UL : 0UL); -} - -/** - * @} - */ - -/** @defgroup SPI_LL_EF_DMA_Management DMA Management - * @{ - */ - -/** - * @brief Enable DMA Rx - * @rmtoll CR2 RXDMAEN LL_SPI_EnableDMAReq_RX - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_SPI_EnableDMAReq_RX(SPI_TypeDef *SPIx) -{ - SET_BIT(SPIx->CR2, SPI_CR2_RXDMAEN); -} - -/** - * @brief Disable DMA Rx - * @rmtoll CR2 RXDMAEN LL_SPI_DisableDMAReq_RX - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_SPI_DisableDMAReq_RX(SPI_TypeDef *SPIx) -{ - CLEAR_BIT(SPIx->CR2, SPI_CR2_RXDMAEN); -} - -/** - * @brief Check if DMA Rx is enabled - * @rmtoll CR2 RXDMAEN LL_SPI_IsEnabledDMAReq_RX - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_SPI_IsEnabledDMAReq_RX(SPI_TypeDef *SPIx) -{ - return ((READ_BIT(SPIx->CR2, SPI_CR2_RXDMAEN) == (SPI_CR2_RXDMAEN)) ? 1UL : 0UL); -} - -/** - * @brief Enable DMA Tx - * @rmtoll CR2 TXDMAEN LL_SPI_EnableDMAReq_TX - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_SPI_EnableDMAReq_TX(SPI_TypeDef *SPIx) -{ - SET_BIT(SPIx->CR2, SPI_CR2_TXDMAEN); -} - -/** - * @brief Disable DMA Tx - * @rmtoll CR2 TXDMAEN LL_SPI_DisableDMAReq_TX - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_SPI_DisableDMAReq_TX(SPI_TypeDef *SPIx) -{ - CLEAR_BIT(SPIx->CR2, SPI_CR2_TXDMAEN); -} - -/** - * @brief Check if DMA Tx is enabled - * @rmtoll CR2 TXDMAEN LL_SPI_IsEnabledDMAReq_TX - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_SPI_IsEnabledDMAReq_TX(SPI_TypeDef *SPIx) -{ - return ((READ_BIT(SPIx->CR2, SPI_CR2_TXDMAEN) == (SPI_CR2_TXDMAEN)) ? 1UL : 0UL); -} - -/** - * @brief Get the data register address used for DMA transfer - * @rmtoll DR DR LL_SPI_DMA_GetRegAddr - * @param SPIx SPI Instance - * @retval Address of data register - */ -__STATIC_INLINE uint32_t LL_SPI_DMA_GetRegAddr(SPI_TypeDef *SPIx) -{ - return (uint32_t) &(SPIx->DR); -} - -/** - * @} - */ - -/** @defgroup SPI_LL_EF_DATA_Management DATA Management - * @{ - */ - -/** - * @brief Read 8-Bits in the data register - * @rmtoll DR DR LL_SPI_ReceiveData8 - * @param SPIx SPI Instance - * @retval RxData Value between Min_Data=0x00 and Max_Data=0xFF - */ -__STATIC_INLINE uint8_t LL_SPI_ReceiveData8(SPI_TypeDef *SPIx) -{ - return (*((__IO uint8_t *)&SPIx->DR)); -} - -/** - * @brief Read 16-Bits in the data register - * @rmtoll DR DR LL_SPI_ReceiveData16 - * @param SPIx SPI Instance - * @retval RxData Value between Min_Data=0x00 and Max_Data=0xFFFF - */ -__STATIC_INLINE uint16_t LL_SPI_ReceiveData16(SPI_TypeDef *SPIx) -{ - return (uint16_t)(READ_REG(SPIx->DR)); -} - -/** - * @brief Write 8-Bits in the data register - * @rmtoll DR DR LL_SPI_TransmitData8 - * @param SPIx SPI Instance - * @param TxData Value between Min_Data=0x00 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_SPI_TransmitData8(SPI_TypeDef *SPIx, uint8_t TxData) -{ -#if defined (__GNUC__) - __IO uint8_t *spidr = ((__IO uint8_t *)&SPIx->DR); - *spidr = TxData; -#else - *((__IO uint8_t *)&SPIx->DR) = TxData; -#endif /* __GNUC__ */ -} - -/** - * @brief Write 16-Bits in the data register - * @rmtoll DR DR LL_SPI_TransmitData16 - * @param SPIx SPI Instance - * @param TxData Value between Min_Data=0x00 and Max_Data=0xFFFF - * @retval None - */ -__STATIC_INLINE void LL_SPI_TransmitData16(SPI_TypeDef *SPIx, uint16_t TxData) -{ -#if defined (__GNUC__) - __IO uint16_t *spidr = ((__IO uint16_t *)&SPIx->DR); - *spidr = TxData; -#else - SPIx->DR = TxData; -#endif /* __GNUC__ */ -} - -/** - * @} - */ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup SPI_LL_EF_Init Initialization and de-initialization functions - * @{ - */ - -ErrorStatus LL_SPI_DeInit(SPI_TypeDef *SPIx); -ErrorStatus LL_SPI_Init(SPI_TypeDef *SPIx, LL_SPI_InitTypeDef *SPI_InitStruct); -void LL_SPI_StructInit(LL_SPI_InitTypeDef *SPI_InitStruct); - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ -/** - * @} - */ - -/** - * @} - */ - -/** @defgroup I2S_LL I2S - * @{ - */ - -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ - -/* Exported types ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup I2S_LL_ES_INIT I2S Exported Init structure - * @{ - */ - -/** - * @brief I2S Init structure definition - */ - -typedef struct -{ - uint32_t Mode; /*!< Specifies the I2S operating mode. - This parameter can be a value of @ref I2S_LL_EC_MODE - - This feature can be modified afterwards using unitary function @ref LL_I2S_SetTransferMode().*/ - - uint32_t Standard; /*!< Specifies the standard used for the I2S communication. - This parameter can be a value of @ref I2S_LL_EC_STANDARD - - This feature can be modified afterwards using unitary function @ref LL_I2S_SetStandard().*/ - - - uint32_t DataFormat; /*!< Specifies the data format for the I2S communication. - This parameter can be a value of @ref I2S_LL_EC_DATA_FORMAT - - This feature can be modified afterwards using unitary function @ref LL_I2S_SetDataFormat().*/ - - - uint32_t MCLKOutput; /*!< Specifies whether the I2S MCLK output is enabled or not. - This parameter can be a value of @ref I2S_LL_EC_MCLK_OUTPUT - - This feature can be modified afterwards using unitary functions @ref LL_I2S_EnableMasterClock() or @ref LL_I2S_DisableMasterClock.*/ - - - uint32_t AudioFreq; /*!< Specifies the frequency selected for the I2S communication. - This parameter can be a value of @ref I2S_LL_EC_AUDIO_FREQ - - Audio Frequency can be modified afterwards using Reference manual formulas to calculate Prescaler Linear, Parity - and unitary functions @ref LL_I2S_SetPrescalerLinear() and @ref LL_I2S_SetPrescalerParity() to set it.*/ - - - uint32_t ClockPolarity; /*!< Specifies the idle state of the I2S clock. - This parameter can be a value of @ref I2S_LL_EC_POLARITY - - This feature can be modified afterwards using unitary function @ref LL_I2S_SetClockPolarity().*/ - -} LL_I2S_InitTypeDef; - -/** - * @} - */ -#endif /*USE_FULL_LL_DRIVER*/ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup I2S_LL_Exported_Constants I2S Exported Constants - * @{ - */ - -/** @defgroup I2S_LL_EC_GET_FLAG Get Flags Defines - * @brief Flags defines which can be used with LL_I2S_ReadReg function - * @{ - */ -#define LL_I2S_SR_RXNE LL_SPI_SR_RXNE /*!< Rx buffer not empty flag */ -#define LL_I2S_SR_TXE LL_SPI_SR_TXE /*!< Tx buffer empty flag */ -#define LL_I2S_SR_BSY LL_SPI_SR_BSY /*!< Busy flag */ -#define LL_I2S_SR_UDR SPI_SR_UDR /*!< Underrun flag */ -#define LL_I2S_SR_OVR LL_SPI_SR_OVR /*!< Overrun flag */ -#define LL_I2S_SR_FRE LL_SPI_SR_FRE /*!< TI mode frame format error flag */ -/** - * @} - */ - -/** @defgroup SPI_LL_EC_IT IT Defines - * @brief IT defines which can be used with LL_SPI_ReadReg and LL_SPI_WriteReg functions - * @{ - */ -#define LL_I2S_CR2_RXNEIE LL_SPI_CR2_RXNEIE /*!< Rx buffer not empty interrupt enable */ -#define LL_I2S_CR2_TXEIE LL_SPI_CR2_TXEIE /*!< Tx buffer empty interrupt enable */ -#define LL_I2S_CR2_ERRIE LL_SPI_CR2_ERRIE /*!< Error interrupt enable */ -/** - * @} - */ - -/** @defgroup I2S_LL_EC_DATA_FORMAT Data format - * @{ - */ -#define LL_I2S_DATAFORMAT_16B 0x00000000U /*!< Data length 16 bits, Channel length 16bit */ -#define LL_I2S_DATAFORMAT_16B_EXTENDED (SPI_I2SCFGR_CHLEN) /*!< Data length 16 bits, Channel length 32bit */ -#define LL_I2S_DATAFORMAT_24B (SPI_I2SCFGR_CHLEN | SPI_I2SCFGR_DATLEN_0) /*!< Data length 24 bits, Channel length 32bit */ -#define LL_I2S_DATAFORMAT_32B (SPI_I2SCFGR_CHLEN | SPI_I2SCFGR_DATLEN_1) /*!< Data length 16 bits, Channel length 32bit */ -/** - * @} - */ - -/** @defgroup I2S_LL_EC_POLARITY Clock Polarity - * @{ - */ -#define LL_I2S_POLARITY_LOW 0x00000000U /*!< Clock steady state is low level */ -#define LL_I2S_POLARITY_HIGH (SPI_I2SCFGR_CKPOL) /*!< Clock steady state is high level */ -/** - * @} - */ - -/** @defgroup I2S_LL_EC_STANDARD I2s Standard - * @{ - */ -#define LL_I2S_STANDARD_PHILIPS 0x00000000U /*!< I2S standard philips */ -#define LL_I2S_STANDARD_MSB (SPI_I2SCFGR_I2SSTD_0) /*!< MSB justified standard (left justified) */ -#define LL_I2S_STANDARD_LSB (SPI_I2SCFGR_I2SSTD_1) /*!< LSB justified standard (right justified) */ -#define LL_I2S_STANDARD_PCM_SHORT (SPI_I2SCFGR_I2SSTD_0 | SPI_I2SCFGR_I2SSTD_1) /*!< PCM standard, short frame synchronization */ -#define LL_I2S_STANDARD_PCM_LONG (SPI_I2SCFGR_I2SSTD_0 | SPI_I2SCFGR_I2SSTD_1 | SPI_I2SCFGR_PCMSYNC) /*!< PCM standard, long frame synchronization */ -/** - * @} - */ - -/** @defgroup I2S_LL_EC_MODE Operation Mode - * @{ - */ -#define LL_I2S_MODE_SLAVE_TX 0x00000000U /*!< Slave Tx configuration */ -#define LL_I2S_MODE_SLAVE_RX (SPI_I2SCFGR_I2SCFG_0) /*!< Slave Rx configuration */ -#define LL_I2S_MODE_MASTER_TX (SPI_I2SCFGR_I2SCFG_1) /*!< Master Tx configuration */ -#define LL_I2S_MODE_MASTER_RX (SPI_I2SCFGR_I2SCFG_0 | SPI_I2SCFGR_I2SCFG_1) /*!< Master Rx configuration */ -/** - * @} - */ - -/** @defgroup I2S_LL_EC_PRESCALER_FACTOR Prescaler Factor - * @{ - */ -#define LL_I2S_PRESCALER_PARITY_EVEN 0x00000000U /*!< Odd factor: Real divider value is = I2SDIV * 2 */ -#define LL_I2S_PRESCALER_PARITY_ODD (SPI_I2SPR_ODD >> 8U) /*!< Odd factor: Real divider value is = (I2SDIV * 2)+1 */ -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) - -/** @defgroup I2S_LL_EC_MCLK_OUTPUT MCLK Output - * @{ - */ -#define LL_I2S_MCLK_OUTPUT_DISABLE 0x00000000U /*!< Master clock output is disabled */ -#define LL_I2S_MCLK_OUTPUT_ENABLE (SPI_I2SPR_MCKOE) /*!< Master clock output is enabled */ -/** - * @} - */ - -/** @defgroup I2S_LL_EC_AUDIO_FREQ Audio Frequency - * @{ - */ - -#define LL_I2S_AUDIOFREQ_192K 192000U /*!< Audio Frequency configuration 192000 Hz */ -#define LL_I2S_AUDIOFREQ_96K 96000U /*!< Audio Frequency configuration 96000 Hz */ -#define LL_I2S_AUDIOFREQ_48K 48000U /*!< Audio Frequency configuration 48000 Hz */ -#define LL_I2S_AUDIOFREQ_44K 44100U /*!< Audio Frequency configuration 44100 Hz */ -#define LL_I2S_AUDIOFREQ_32K 32000U /*!< Audio Frequency configuration 32000 Hz */ -#define LL_I2S_AUDIOFREQ_22K 22050U /*!< Audio Frequency configuration 22050 Hz */ -#define LL_I2S_AUDIOFREQ_16K 16000U /*!< Audio Frequency configuration 16000 Hz */ -#define LL_I2S_AUDIOFREQ_11K 11025U /*!< Audio Frequency configuration 11025 Hz */ -#define LL_I2S_AUDIOFREQ_8K 8000U /*!< Audio Frequency configuration 8000 Hz */ -#define LL_I2S_AUDIOFREQ_DEFAULT 2U /*!< Audio Freq not specified. Register I2SDIV = 2 */ -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup I2S_LL_Exported_Macros I2S Exported Macros - * @{ - */ - -/** @defgroup I2S_LL_EM_WRITE_READ Common Write and read registers Macros - * @{ - */ - -/** - * @brief Write a value in I2S register - * @param __INSTANCE__ I2S Instance - * @param __REG__ Register to be written - * @param __VALUE__ Value to be written in the register - * @retval None - */ -#define LL_I2S_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__)) - -/** - * @brief Read a value in I2S register - * @param __INSTANCE__ I2S Instance - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_I2S_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__) -/** - * @} - */ - -/** - * @} - */ - - -/* Exported functions --------------------------------------------------------*/ - -/** @defgroup I2S_LL_Exported_Functions I2S Exported Functions - * @{ - */ - -/** @defgroup I2S_LL_EF_Configuration Configuration - * @{ - */ - -/** - * @brief Select I2S mode and Enable I2S peripheral - * @rmtoll I2SCFGR I2SMOD LL_I2S_Enable\n - * I2SCFGR I2SE LL_I2S_Enable - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_I2S_Enable(SPI_TypeDef *SPIx) -{ - SET_BIT(SPIx->I2SCFGR, SPI_I2SCFGR_I2SMOD | SPI_I2SCFGR_I2SE); -} - -/** - * @brief Disable I2S peripheral - * @rmtoll I2SCFGR I2SE LL_I2S_Disable - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_I2S_Disable(SPI_TypeDef *SPIx) -{ - CLEAR_BIT(SPIx->I2SCFGR, SPI_I2SCFGR_I2SMOD | SPI_I2SCFGR_I2SE); -} - -/** - * @brief Check if I2S peripheral is enabled - * @rmtoll I2SCFGR I2SE LL_I2S_IsEnabled - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2S_IsEnabled(SPI_TypeDef *SPIx) -{ - return ((READ_BIT(SPIx->I2SCFGR, SPI_I2SCFGR_I2SE) == (SPI_I2SCFGR_I2SE)) ? 1UL : 0UL); -} - -/** - * @brief Set I2S data frame length - * @rmtoll I2SCFGR DATLEN LL_I2S_SetDataFormat\n - * I2SCFGR CHLEN LL_I2S_SetDataFormat - * @param SPIx SPI Instance - * @param DataFormat This parameter can be one of the following values: - * @arg @ref LL_I2S_DATAFORMAT_16B - * @arg @ref LL_I2S_DATAFORMAT_16B_EXTENDED - * @arg @ref LL_I2S_DATAFORMAT_24B - * @arg @ref LL_I2S_DATAFORMAT_32B - * @retval None - */ -__STATIC_INLINE void LL_I2S_SetDataFormat(SPI_TypeDef *SPIx, uint32_t DataFormat) -{ - MODIFY_REG(SPIx->I2SCFGR, SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN, DataFormat); -} - -/** - * @brief Get I2S data frame length - * @rmtoll I2SCFGR DATLEN LL_I2S_GetDataFormat\n - * I2SCFGR CHLEN LL_I2S_GetDataFormat - * @param SPIx SPI Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_I2S_DATAFORMAT_16B - * @arg @ref LL_I2S_DATAFORMAT_16B_EXTENDED - * @arg @ref LL_I2S_DATAFORMAT_24B - * @arg @ref LL_I2S_DATAFORMAT_32B - */ -__STATIC_INLINE uint32_t LL_I2S_GetDataFormat(SPI_TypeDef *SPIx) -{ - return (uint32_t)(READ_BIT(SPIx->I2SCFGR, SPI_I2SCFGR_DATLEN | SPI_I2SCFGR_CHLEN)); -} - -/** - * @brief Set I2S clock polarity - * @rmtoll I2SCFGR CKPOL LL_I2S_SetClockPolarity - * @param SPIx SPI Instance - * @param ClockPolarity This parameter can be one of the following values: - * @arg @ref LL_I2S_POLARITY_LOW - * @arg @ref LL_I2S_POLARITY_HIGH - * @retval None - */ -__STATIC_INLINE void LL_I2S_SetClockPolarity(SPI_TypeDef *SPIx, uint32_t ClockPolarity) -{ - SET_BIT(SPIx->I2SCFGR, ClockPolarity); -} - -/** - * @brief Get I2S clock polarity - * @rmtoll I2SCFGR CKPOL LL_I2S_GetClockPolarity - * @param SPIx SPI Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_I2S_POLARITY_LOW - * @arg @ref LL_I2S_POLARITY_HIGH - */ -__STATIC_INLINE uint32_t LL_I2S_GetClockPolarity(SPI_TypeDef *SPIx) -{ - return (uint32_t)(READ_BIT(SPIx->I2SCFGR, SPI_I2SCFGR_CKPOL)); -} - -/** - * @brief Set I2S standard protocol - * @rmtoll I2SCFGR I2SSTD LL_I2S_SetStandard\n - * I2SCFGR PCMSYNC LL_I2S_SetStandard - * @param SPIx SPI Instance - * @param Standard This parameter can be one of the following values: - * @arg @ref LL_I2S_STANDARD_PHILIPS - * @arg @ref LL_I2S_STANDARD_MSB - * @arg @ref LL_I2S_STANDARD_LSB - * @arg @ref LL_I2S_STANDARD_PCM_SHORT - * @arg @ref LL_I2S_STANDARD_PCM_LONG - * @retval None - */ -__STATIC_INLINE void LL_I2S_SetStandard(SPI_TypeDef *SPIx, uint32_t Standard) -{ - MODIFY_REG(SPIx->I2SCFGR, SPI_I2SCFGR_I2SSTD | SPI_I2SCFGR_PCMSYNC, Standard); -} - -/** - * @brief Get I2S standard protocol - * @rmtoll I2SCFGR I2SSTD LL_I2S_GetStandard\n - * I2SCFGR PCMSYNC LL_I2S_GetStandard - * @param SPIx SPI Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_I2S_STANDARD_PHILIPS - * @arg @ref LL_I2S_STANDARD_MSB - * @arg @ref LL_I2S_STANDARD_LSB - * @arg @ref LL_I2S_STANDARD_PCM_SHORT - * @arg @ref LL_I2S_STANDARD_PCM_LONG - */ -__STATIC_INLINE uint32_t LL_I2S_GetStandard(SPI_TypeDef *SPIx) -{ - return (uint32_t)(READ_BIT(SPIx->I2SCFGR, SPI_I2SCFGR_I2SSTD | SPI_I2SCFGR_PCMSYNC)); -} - -/** - * @brief Set I2S transfer mode - * @rmtoll I2SCFGR I2SCFG LL_I2S_SetTransferMode - * @param SPIx SPI Instance - * @param Mode This parameter can be one of the following values: - * @arg @ref LL_I2S_MODE_SLAVE_TX - * @arg @ref LL_I2S_MODE_SLAVE_RX - * @arg @ref LL_I2S_MODE_MASTER_TX - * @arg @ref LL_I2S_MODE_MASTER_RX - * @retval None - */ -__STATIC_INLINE void LL_I2S_SetTransferMode(SPI_TypeDef *SPIx, uint32_t Mode) -{ - MODIFY_REG(SPIx->I2SCFGR, SPI_I2SCFGR_I2SCFG, Mode); -} - -/** - * @brief Get I2S transfer mode - * @rmtoll I2SCFGR I2SCFG LL_I2S_GetTransferMode - * @param SPIx SPI Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_I2S_MODE_SLAVE_TX - * @arg @ref LL_I2S_MODE_SLAVE_RX - * @arg @ref LL_I2S_MODE_MASTER_TX - * @arg @ref LL_I2S_MODE_MASTER_RX - */ -__STATIC_INLINE uint32_t LL_I2S_GetTransferMode(SPI_TypeDef *SPIx) -{ - return (uint32_t)(READ_BIT(SPIx->I2SCFGR, SPI_I2SCFGR_I2SCFG)); -} - -/** - * @brief Set I2S linear prescaler - * @rmtoll I2SPR I2SDIV LL_I2S_SetPrescalerLinear - * @param SPIx SPI Instance - * @param PrescalerLinear Value between Min_Data=0x02 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_I2S_SetPrescalerLinear(SPI_TypeDef *SPIx, uint8_t PrescalerLinear) -{ - MODIFY_REG(SPIx->I2SPR, SPI_I2SPR_I2SDIV, PrescalerLinear); -} - -/** - * @brief Get I2S linear prescaler - * @rmtoll I2SPR I2SDIV LL_I2S_GetPrescalerLinear - * @param SPIx SPI Instance - * @retval PrescalerLinear Value between Min_Data=0x02 and Max_Data=0xFF - */ -__STATIC_INLINE uint32_t LL_I2S_GetPrescalerLinear(SPI_TypeDef *SPIx) -{ - return (uint32_t)(READ_BIT(SPIx->I2SPR, SPI_I2SPR_I2SDIV)); -} - -/** - * @brief Set I2S parity prescaler - * @rmtoll I2SPR ODD LL_I2S_SetPrescalerParity - * @param SPIx SPI Instance - * @param PrescalerParity This parameter can be one of the following values: - * @arg @ref LL_I2S_PRESCALER_PARITY_EVEN - * @arg @ref LL_I2S_PRESCALER_PARITY_ODD - * @retval None - */ -__STATIC_INLINE void LL_I2S_SetPrescalerParity(SPI_TypeDef *SPIx, uint32_t PrescalerParity) -{ - MODIFY_REG(SPIx->I2SPR, SPI_I2SPR_ODD, PrescalerParity << 8U); -} - -/** - * @brief Get I2S parity prescaler - * @rmtoll I2SPR ODD LL_I2S_GetPrescalerParity - * @param SPIx SPI Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_I2S_PRESCALER_PARITY_EVEN - * @arg @ref LL_I2S_PRESCALER_PARITY_ODD - */ -__STATIC_INLINE uint32_t LL_I2S_GetPrescalerParity(SPI_TypeDef *SPIx) -{ - return (uint32_t)(READ_BIT(SPIx->I2SPR, SPI_I2SPR_ODD) >> 8U); -} - -/** - * @brief Enable the master clock output (Pin MCK) - * @rmtoll I2SPR MCKOE LL_I2S_EnableMasterClock - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_I2S_EnableMasterClock(SPI_TypeDef *SPIx) -{ - SET_BIT(SPIx->I2SPR, SPI_I2SPR_MCKOE); -} - -/** - * @brief Disable the master clock output (Pin MCK) - * @rmtoll I2SPR MCKOE LL_I2S_DisableMasterClock - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_I2S_DisableMasterClock(SPI_TypeDef *SPIx) -{ - CLEAR_BIT(SPIx->I2SPR, SPI_I2SPR_MCKOE); -} - -/** - * @brief Check if the master clock output (Pin MCK) is enabled - * @rmtoll I2SPR MCKOE LL_I2S_IsEnabledMasterClock - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2S_IsEnabledMasterClock(SPI_TypeDef *SPIx) -{ - return ((READ_BIT(SPIx->I2SPR, SPI_I2SPR_MCKOE) == (SPI_I2SPR_MCKOE)) ? 1UL : 0UL); -} - -#if defined(SPI_I2SCFGR_ASTRTEN) -/** - * @brief Enable asynchronous start - * @rmtoll I2SCFGR ASTRTEN LL_I2S_EnableAsyncStart - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_I2S_EnableAsyncStart(SPI_TypeDef *SPIx) -{ - SET_BIT(SPIx->I2SCFGR, SPI_I2SCFGR_ASTRTEN); -} - -/** - * @brief Disable asynchronous start - * @rmtoll I2SCFGR ASTRTEN LL_I2S_DisableAsyncStart - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_I2S_DisableAsyncStart(SPI_TypeDef *SPIx) -{ - CLEAR_BIT(SPIx->I2SCFGR, SPI_I2SCFGR_ASTRTEN); -} - -/** - * @brief Check if asynchronous start is enabled - * @rmtoll I2SCFGR ASTRTEN LL_I2S_IsEnabledAsyncStart - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2S_IsEnabledAsyncStart(SPI_TypeDef *SPIx) -{ - return ((READ_BIT(SPIx->I2SCFGR, SPI_I2SCFGR_ASTRTEN) == (SPI_I2SCFGR_ASTRTEN)) ? 1UL : 0UL); -} -#endif /* SPI_I2SCFGR_ASTRTEN */ - -/** - * @} - */ - -/** @defgroup I2S_LL_EF_FLAG FLAG Management - * @{ - */ - -/** - * @brief Check if Rx buffer is not empty - * @rmtoll SR RXNE LL_I2S_IsActiveFlag_RXNE - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2S_IsActiveFlag_RXNE(SPI_TypeDef *SPIx) -{ - return LL_SPI_IsActiveFlag_RXNE(SPIx); -} - -/** - * @brief Check if Tx buffer is empty - * @rmtoll SR TXE LL_I2S_IsActiveFlag_TXE - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2S_IsActiveFlag_TXE(SPI_TypeDef *SPIx) -{ - return LL_SPI_IsActiveFlag_TXE(SPIx); -} - -/** - * @brief Get busy flag - * @rmtoll SR BSY LL_I2S_IsActiveFlag_BSY - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2S_IsActiveFlag_BSY(SPI_TypeDef *SPIx) -{ - return LL_SPI_IsActiveFlag_BSY(SPIx); -} - -/** - * @brief Get overrun error flag - * @rmtoll SR OVR LL_I2S_IsActiveFlag_OVR - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2S_IsActiveFlag_OVR(SPI_TypeDef *SPIx) -{ - return LL_SPI_IsActiveFlag_OVR(SPIx); -} - -/** - * @brief Get underrun error flag - * @rmtoll SR UDR LL_I2S_IsActiveFlag_UDR - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2S_IsActiveFlag_UDR(SPI_TypeDef *SPIx) -{ - return ((READ_BIT(SPIx->SR, SPI_SR_UDR) == (SPI_SR_UDR)) ? 1UL : 0UL); -} - -/** - * @brief Get frame format error flag - * @rmtoll SR FRE LL_I2S_IsActiveFlag_FRE - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2S_IsActiveFlag_FRE(SPI_TypeDef *SPIx) -{ - return LL_SPI_IsActiveFlag_FRE(SPIx); -} - -/** - * @brief Get channel side flag. - * @note 0: Channel Left has to be transmitted or has been received\n - * 1: Channel Right has to be transmitted or has been received\n - * It has no significance in PCM mode. - * @rmtoll SR CHSIDE LL_I2S_IsActiveFlag_CHSIDE - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2S_IsActiveFlag_CHSIDE(SPI_TypeDef *SPIx) -{ - return ((READ_BIT(SPIx->SR, SPI_SR_CHSIDE) == (SPI_SR_CHSIDE)) ? 1UL : 0UL); -} - -/** - * @brief Clear overrun error flag - * @rmtoll SR OVR LL_I2S_ClearFlag_OVR - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_I2S_ClearFlag_OVR(SPI_TypeDef *SPIx) -{ - LL_SPI_ClearFlag_OVR(SPIx); -} - -/** - * @brief Clear underrun error flag - * @rmtoll SR UDR LL_I2S_ClearFlag_UDR - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_I2S_ClearFlag_UDR(SPI_TypeDef *SPIx) -{ - __IO uint32_t tmpreg; - tmpreg = SPIx->SR; - (void)tmpreg; -} - -/** - * @brief Clear frame format error flag - * @rmtoll SR FRE LL_I2S_ClearFlag_FRE - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_I2S_ClearFlag_FRE(SPI_TypeDef *SPIx) -{ - LL_SPI_ClearFlag_FRE(SPIx); -} - -/** - * @} - */ - -/** @defgroup I2S_LL_EF_IT Interrupt Management - * @{ - */ - -/** - * @brief Enable error IT - * @note This bit controls the generation of an interrupt when an error condition occurs (OVR, UDR and FRE in I2S mode). - * @rmtoll CR2 ERRIE LL_I2S_EnableIT_ERR - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_I2S_EnableIT_ERR(SPI_TypeDef *SPIx) -{ - LL_SPI_EnableIT_ERR(SPIx); -} - -/** - * @brief Enable Rx buffer not empty IT - * @rmtoll CR2 RXNEIE LL_I2S_EnableIT_RXNE - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_I2S_EnableIT_RXNE(SPI_TypeDef *SPIx) -{ - LL_SPI_EnableIT_RXNE(SPIx); -} - -/** - * @brief Enable Tx buffer empty IT - * @rmtoll CR2 TXEIE LL_I2S_EnableIT_TXE - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_I2S_EnableIT_TXE(SPI_TypeDef *SPIx) -{ - LL_SPI_EnableIT_TXE(SPIx); -} - -/** - * @brief Disable error IT - * @note This bit controls the generation of an interrupt when an error condition occurs (OVR, UDR and FRE in I2S mode). - * @rmtoll CR2 ERRIE LL_I2S_DisableIT_ERR - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_I2S_DisableIT_ERR(SPI_TypeDef *SPIx) -{ - LL_SPI_DisableIT_ERR(SPIx); -} - -/** - * @brief Disable Rx buffer not empty IT - * @rmtoll CR2 RXNEIE LL_I2S_DisableIT_RXNE - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_I2S_DisableIT_RXNE(SPI_TypeDef *SPIx) -{ - LL_SPI_DisableIT_RXNE(SPIx); -} - -/** - * @brief Disable Tx buffer empty IT - * @rmtoll CR2 TXEIE LL_I2S_DisableIT_TXE - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_I2S_DisableIT_TXE(SPI_TypeDef *SPIx) -{ - LL_SPI_DisableIT_TXE(SPIx); -} - -/** - * @brief Check if ERR IT is enabled - * @rmtoll CR2 ERRIE LL_I2S_IsEnabledIT_ERR - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2S_IsEnabledIT_ERR(SPI_TypeDef *SPIx) -{ - return LL_SPI_IsEnabledIT_ERR(SPIx); -} - -/** - * @brief Check if RXNE IT is enabled - * @rmtoll CR2 RXNEIE LL_I2S_IsEnabledIT_RXNE - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2S_IsEnabledIT_RXNE(SPI_TypeDef *SPIx) -{ - return LL_SPI_IsEnabledIT_RXNE(SPIx); -} - -/** - * @brief Check if TXE IT is enabled - * @rmtoll CR2 TXEIE LL_I2S_IsEnabledIT_TXE - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2S_IsEnabledIT_TXE(SPI_TypeDef *SPIx) -{ - return LL_SPI_IsEnabledIT_TXE(SPIx); -} - -/** - * @} - */ - -/** @defgroup I2S_LL_EF_DMA DMA Management - * @{ - */ - -/** - * @brief Enable DMA Rx - * @rmtoll CR2 RXDMAEN LL_I2S_EnableDMAReq_RX - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_I2S_EnableDMAReq_RX(SPI_TypeDef *SPIx) -{ - LL_SPI_EnableDMAReq_RX(SPIx); -} - -/** - * @brief Disable DMA Rx - * @rmtoll CR2 RXDMAEN LL_I2S_DisableDMAReq_RX - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_I2S_DisableDMAReq_RX(SPI_TypeDef *SPIx) -{ - LL_SPI_DisableDMAReq_RX(SPIx); -} - -/** - * @brief Check if DMA Rx is enabled - * @rmtoll CR2 RXDMAEN LL_I2S_IsEnabledDMAReq_RX - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2S_IsEnabledDMAReq_RX(SPI_TypeDef *SPIx) -{ - return LL_SPI_IsEnabledDMAReq_RX(SPIx); -} - -/** - * @brief Enable DMA Tx - * @rmtoll CR2 TXDMAEN LL_I2S_EnableDMAReq_TX - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_I2S_EnableDMAReq_TX(SPI_TypeDef *SPIx) -{ - LL_SPI_EnableDMAReq_TX(SPIx); -} - -/** - * @brief Disable DMA Tx - * @rmtoll CR2 TXDMAEN LL_I2S_DisableDMAReq_TX - * @param SPIx SPI Instance - * @retval None - */ -__STATIC_INLINE void LL_I2S_DisableDMAReq_TX(SPI_TypeDef *SPIx) -{ - LL_SPI_DisableDMAReq_TX(SPIx); -} - -/** - * @brief Check if DMA Tx is enabled - * @rmtoll CR2 TXDMAEN LL_I2S_IsEnabledDMAReq_TX - * @param SPIx SPI Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_I2S_IsEnabledDMAReq_TX(SPI_TypeDef *SPIx) -{ - return LL_SPI_IsEnabledDMAReq_TX(SPIx); -} - -/** - * @} - */ - -/** @defgroup I2S_LL_EF_DATA DATA Management - * @{ - */ - -/** - * @brief Read 16-Bits in data register - * @rmtoll DR DR LL_I2S_ReceiveData16 - * @param SPIx SPI Instance - * @retval RxData Value between Min_Data=0x0000 and Max_Data=0xFFFF - */ -__STATIC_INLINE uint16_t LL_I2S_ReceiveData16(SPI_TypeDef *SPIx) -{ - return LL_SPI_ReceiveData16(SPIx); -} - -/** - * @brief Write 16-Bits in data register - * @rmtoll DR DR LL_I2S_TransmitData16 - * @param SPIx SPI Instance - * @param TxData Value between Min_Data=0x0000 and Max_Data=0xFFFF - * @retval None - */ -__STATIC_INLINE void LL_I2S_TransmitData16(SPI_TypeDef *SPIx, uint16_t TxData) -{ - LL_SPI_TransmitData16(SPIx, TxData); -} - -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup I2S_LL_EF_Init Initialization and de-initialization functions - * @{ - */ - -ErrorStatus LL_I2S_DeInit(SPI_TypeDef *SPIx); -ErrorStatus LL_I2S_Init(SPI_TypeDef *SPIx, LL_I2S_InitTypeDef *I2S_InitStruct); -void LL_I2S_StructInit(LL_I2S_InitTypeDef *I2S_InitStruct); -void LL_I2S_ConfigPrescaler(SPI_TypeDef *SPIx, uint32_t PrescalerLinear, uint32_t PrescalerParity); -#if defined (SPI_I2S_FULLDUPLEX_SUPPORT) -ErrorStatus LL_I2S_InitFullDuplex(SPI_TypeDef *I2Sxext, LL_I2S_InitTypeDef *I2S_InitStruct); -#endif /* SPI_I2S_FULLDUPLEX_SUPPORT */ - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* defined (SPI1) || defined (SPI2) || defined (SPI3) || defined (SPI4) || defined (SPI5) || defined(SPI6) */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_LL_SPI_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_system.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_system.h deleted file mode 100644 index cc7635e..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_system.h +++ /dev/null @@ -1,1710 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_system.h - * @author MCD Application Team - * @brief Header file of SYSTEM LL module. - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - The LL SYSTEM driver contains a set of generic APIs that can be - used by user: - (+) Some of the FLASH features need to be handled in the SYSTEM file. - (+) Access to DBGCMU registers - (+) Access to SYSCFG registers - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_LL_SYSTEM_H -#define __STM32F4xx_LL_SYSTEM_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (FLASH) || defined (SYSCFG) || defined (DBGMCU) - -/** @defgroup SYSTEM_LL SYSTEM - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup SYSTEM_LL_Private_Constants SYSTEM Private Constants - * @{ - */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/** @defgroup SYSTEM_LL_Exported_Constants SYSTEM Exported Constants - * @{ - */ - -/** @defgroup SYSTEM_LL_EC_REMAP SYSCFG REMAP -* @{ -*/ -#define LL_SYSCFG_REMAP_FLASH (uint32_t)0x00000000 /*!< Main Flash memory mapped at 0x00000000 */ -#define LL_SYSCFG_REMAP_SYSTEMFLASH SYSCFG_MEMRMP_MEM_MODE_0 /*!< System Flash memory mapped at 0x00000000 */ -#if defined(FSMC_Bank1) -#define LL_SYSCFG_REMAP_FSMC SYSCFG_MEMRMP_MEM_MODE_1 /*!< FSMC(NOR/PSRAM 1 and 2) mapped at 0x00000000 */ -#endif /* FSMC_Bank1 */ -#if defined(FMC_Bank1) -#define LL_SYSCFG_REMAP_FMC SYSCFG_MEMRMP_MEM_MODE_1 /*!< FMC(NOR/PSRAM 1 and 2) mapped at 0x00000000 */ -#define LL_SYSCFG_REMAP_SDRAM SYSCFG_MEMRMP_MEM_MODE_2 /*!< FMC/SDRAM mapped at 0x00000000 */ -#endif /* FMC_Bank1 */ -#define LL_SYSCFG_REMAP_SRAM (SYSCFG_MEMRMP_MEM_MODE_1 | SYSCFG_MEMRMP_MEM_MODE_0) /*!< SRAM1 mapped at 0x00000000 */ - -/** - * @} - */ - -#if defined(SYSCFG_PMC_MII_RMII_SEL) - /** @defgroup SYSTEM_LL_EC_PMC SYSCFG PMC -* @{ -*/ -#define LL_SYSCFG_PMC_ETHMII (uint32_t)0x00000000 /*!< ETH Media MII interface */ -#define LL_SYSCFG_PMC_ETHRMII (uint32_t)SYSCFG_PMC_MII_RMII_SEL /*!< ETH Media RMII interface */ - -/** - * @} - */ -#endif /* SYSCFG_PMC_MII_RMII_SEL */ - - - -#if defined(SYSCFG_MEMRMP_UFB_MODE) -/** @defgroup SYSTEM_LL_EC_BANKMODE SYSCFG BANK MODE - * @{ - */ -#define LL_SYSCFG_BANKMODE_BANK1 (uint32_t)0x00000000 /*!< Flash Bank 1 base address mapped at 0x0800 0000 (AXI) and 0x0020 0000 (TCM) - and Flash Bank 2 base address mapped at 0x0810 0000 (AXI) and 0x0030 0000 (TCM)*/ -#define LL_SYSCFG_BANKMODE_BANK2 SYSCFG_MEMRMP_UFB_MODE /*!< Flash Bank 2 base address mapped at 0x0800 0000 (AXI) and 0x0020 0000(TCM) - and Flash Bank 1 base address mapped at 0x0810 0000 (AXI) and 0x0030 0000(TCM) */ -/** - * @} - */ -#endif /* SYSCFG_MEMRMP_UFB_MODE */ -/** @defgroup SYSTEM_LL_EC_I2C_FASTMODEPLUS SYSCFG I2C FASTMODEPLUS - * @{ - */ -#if defined(SYSCFG_CFGR_FMPI2C1_SCL) -#define LL_SYSCFG_I2C_FASTMODEPLUS_SCL SYSCFG_CFGR_FMPI2C1_SCL /*!< Enable Fast Mode Plus on FMPI2C_SCL pin */ -#define LL_SYSCFG_I2C_FASTMODEPLUS_SDA SYSCFG_CFGR_FMPI2C1_SDA /*!< Enable Fast Mode Plus on FMPI2C_SDA pin*/ -#endif /* SYSCFG_CFGR_FMPI2C1_SCL */ -/** - * @} - */ - -/** @defgroup SYSTEM_LL_EC_EXTI_PORT SYSCFG EXTI PORT - * @{ - */ -#define LL_SYSCFG_EXTI_PORTA (uint32_t)0 /*!< EXTI PORT A */ -#define LL_SYSCFG_EXTI_PORTB (uint32_t)1 /*!< EXTI PORT B */ -#define LL_SYSCFG_EXTI_PORTC (uint32_t)2 /*!< EXTI PORT C */ -#define LL_SYSCFG_EXTI_PORTD (uint32_t)3 /*!< EXTI PORT D */ -#define LL_SYSCFG_EXTI_PORTE (uint32_t)4 /*!< EXTI PORT E */ -#if defined(GPIOF) -#define LL_SYSCFG_EXTI_PORTF (uint32_t)5 /*!< EXTI PORT F */ -#endif /* GPIOF */ -#if defined(GPIOG) -#define LL_SYSCFG_EXTI_PORTG (uint32_t)6 /*!< EXTI PORT G */ -#endif /* GPIOG */ -#define LL_SYSCFG_EXTI_PORTH (uint32_t)7 /*!< EXTI PORT H */ -#if defined(GPIOI) -#define LL_SYSCFG_EXTI_PORTI (uint32_t)8 /*!< EXTI PORT I */ -#endif /* GPIOI */ -#if defined(GPIOJ) -#define LL_SYSCFG_EXTI_PORTJ (uint32_t)9 /*!< EXTI PORT J */ -#endif /* GPIOJ */ -#if defined(GPIOK) -#define LL_SYSCFG_EXTI_PORTK (uint32_t)10 /*!< EXTI PORT k */ -#endif /* GPIOK */ -/** - * @} - */ - -/** @defgroup SYSTEM_LL_EC_EXTI_LINE SYSCFG EXTI LINE - * @{ - */ -#define LL_SYSCFG_EXTI_LINE0 (uint32_t)(0x000FU << 16 | 0) /*!< EXTI_POSITION_0 | EXTICR[0] */ -#define LL_SYSCFG_EXTI_LINE1 (uint32_t)(0x00F0U << 16 | 0) /*!< EXTI_POSITION_4 | EXTICR[0] */ -#define LL_SYSCFG_EXTI_LINE2 (uint32_t)(0x0F00U << 16 | 0) /*!< EXTI_POSITION_8 | EXTICR[0] */ -#define LL_SYSCFG_EXTI_LINE3 (uint32_t)(0xF000U << 16 | 0) /*!< EXTI_POSITION_12 | EXTICR[0] */ -#define LL_SYSCFG_EXTI_LINE4 (uint32_t)(0x000FU << 16 | 1) /*!< EXTI_POSITION_0 | EXTICR[1] */ -#define LL_SYSCFG_EXTI_LINE5 (uint32_t)(0x00F0U << 16 | 1) /*!< EXTI_POSITION_4 | EXTICR[1] */ -#define LL_SYSCFG_EXTI_LINE6 (uint32_t)(0x0F00U << 16 | 1) /*!< EXTI_POSITION_8 | EXTICR[1] */ -#define LL_SYSCFG_EXTI_LINE7 (uint32_t)(0xF000U << 16 | 1) /*!< EXTI_POSITION_12 | EXTICR[1] */ -#define LL_SYSCFG_EXTI_LINE8 (uint32_t)(0x000FU << 16 | 2) /*!< EXTI_POSITION_0 | EXTICR[2] */ -#define LL_SYSCFG_EXTI_LINE9 (uint32_t)(0x00F0U << 16 | 2) /*!< EXTI_POSITION_4 | EXTICR[2] */ -#define LL_SYSCFG_EXTI_LINE10 (uint32_t)(0x0F00U << 16 | 2) /*!< EXTI_POSITION_8 | EXTICR[2] */ -#define LL_SYSCFG_EXTI_LINE11 (uint32_t)(0xF000U << 16 | 2) /*!< EXTI_POSITION_12 | EXTICR[2] */ -#define LL_SYSCFG_EXTI_LINE12 (uint32_t)(0x000FU << 16 | 3) /*!< EXTI_POSITION_0 | EXTICR[3] */ -#define LL_SYSCFG_EXTI_LINE13 (uint32_t)(0x00F0U << 16 | 3) /*!< EXTI_POSITION_4 | EXTICR[3] */ -#define LL_SYSCFG_EXTI_LINE14 (uint32_t)(0x0F00U << 16 | 3) /*!< EXTI_POSITION_8 | EXTICR[3] */ -#define LL_SYSCFG_EXTI_LINE15 (uint32_t)(0xF000U << 16 | 3) /*!< EXTI_POSITION_12 | EXTICR[3] */ -/** - * @} - */ - -/** @defgroup SYSTEM_LL_EC_TIMBREAK SYSCFG TIMER BREAK - * @{ - */ -#if defined(SYSCFG_CFGR2_LOCKUP_LOCK) -#define LL_SYSCFG_TIMBREAK_LOCKUP SYSCFG_CFGR2_LOCKUP_LOCK /*!< Enables and locks the LOCKUP output of CortexM4 - with Break Input of TIM1/8 */ -#define LL_SYSCFG_TIMBREAK_PVD SYSCFG_CFGR2_PVD_LOCK /*!< Enables and locks the PVD connection with TIM1/8 Break Input - and also the PVDE and PLS bits of the Power Control Interface */ -#endif /* SYSCFG_CFGR2_CLL */ -/** - * @} - */ - -#if defined(SYSCFG_MCHDLYCR_BSCKSEL) -/** @defgroup SYSTEM_LL_DFSDM_BitStream_ClockSource SYSCFG MCHDLY BCKKSEL - * @{ - */ -#define LL_SYSCFG_BITSTREAM_CLOCK_TIM2OC1 (uint32_t)0x00000000 -#define LL_SYSCFG_BITSTREAM_CLOCK_DFSDM2 SYSCFG_MCHDLYCR_BSCKSEL -/** - * @} - */ -/** @defgroup SYSTEM_LL_DFSDM_MCHDLYEN SYSCFG MCHDLY MCHDLYEN - * @{ - */ -#define LL_SYSCFG_DFSDM1_MCHDLYEN SYSCFG_MCHDLYCR_MCHDLY1EN -#define LL_SYSCFG_DFSDM2_MCHDLYEN SYSCFG_MCHDLYCR_MCHDLY2EN -/** - * @} - */ -/** @defgroup SYSTEM_LL_DFSDM_DataIn0_Source SYSCFG MCHDLY DFSDMD0SEL - * @{ - */ -#define LL_SYSCFG_DFSDM1_DataIn0 SYSCFG_MCHDLYCR_DFSDM1D0SEL -#define LL_SYSCFG_DFSDM2_DataIn0 SYSCFG_MCHDLYCR_DFSDM2D0SEL - -#define LL_SYSCFG_DFSDM1_DataIn0_PAD (uint32_t)((SYSCFG_MCHDLYCR_DFSDM1D0SEL << 16) | 0x00000000) -#define LL_SYSCFG_DFSDM1_DataIn0_DM (uint32_t)((SYSCFG_MCHDLYCR_DFSDM1D0SEL << 16) | SYSCFG_MCHDLYCR_DFSDM1D0SEL) -#define LL_SYSCFG_DFSDM2_DataIn0_PAD (uint32_t)((SYSCFG_MCHDLYCR_DFSDM2D0SEL << 16) | 0x00000000) -#define LL_SYSCFG_DFSDM2_DataIn0_DM (uint32_t)((SYSCFG_MCHDLYCR_DFSDM2D0SEL << 16) | SYSCFG_MCHDLYCR_DFSDM2D0SEL) -/** - * @} - */ -/** @defgroup SYSTEM_LL_DFSDM_DataIn2_Source SYSCFG MCHDLY DFSDMD2SEL - * @{ - */ -#define LL_SYSCFG_DFSDM1_DataIn2 SYSCFG_MCHDLYCR_DFSDM1D2SEL -#define LL_SYSCFG_DFSDM2_DataIn2 SYSCFG_MCHDLYCR_DFSDM2D2SEL - -#define LL_SYSCFG_DFSDM1_DataIn2_PAD (uint32_t)((SYSCFG_MCHDLYCR_DFSDM1D2SEL << 16) | 0x00000000) -#define LL_SYSCFG_DFSDM1_DataIn2_DM (uint32_t)((SYSCFG_MCHDLYCR_DFSDM1D2SEL << 16) | SYSCFG_MCHDLYCR_DFSDM1D2SEL) -#define LL_SYSCFG_DFSDM2_DataIn2_PAD (uint32_t)((SYSCFG_MCHDLYCR_DFSDM2D2SEL << 16) | 0x00000000) -#define LL_SYSCFG_DFSDM2_DataIn2_DM (uint32_t)((SYSCFG_MCHDLYCR_DFSDM2D2SEL << 16) | SYSCFG_MCHDLYCR_DFSDM2D2SEL) -/** - * @} - */ -/** @defgroup SYSTEM_LL_DFSDM1_TIM4OC2_BitstreamDistribution SYSCFG MCHDLY DFSDM1CK02SEL - * @{ - */ -#define LL_SYSCFG_DFSDM1_TIM4OC2_CLKIN0 (uint32_t)0x00000000 -#define LL_SYSCFG_DFSDM1_TIM4OC2_CLKIN2 SYSCFG_MCHDLYCR_DFSDM1CK02SEL -/** - * @} - */ -/** @defgroup SYSTEM_LL_DFSDM1_TIM4OC1_BitstreamDistribution SYSCFG MCHDLY DFSDM1CK13SEL - * @{ - */ -#define LL_SYSCFG_DFSDM1_TIM4OC1_CLKIN1 (uint32_t)0x00000000 -#define LL_SYSCFG_DFSDM1_TIM4OC1_CLKIN3 SYSCFG_MCHDLYCR_DFSDM1CK13SEL -/** - * @} - */ -/** @defgroup SYSTEM_LL_DFSDM1_CLKIN_SourceSelection SYSCFG MCHDLY DFSDMCFG - * @{ - */ -#define LL_SYSCFG_DFSDM1_CKIN_PAD (uint32_t)0x00000000 -#define LL_SYSCFG_DFSDM1_CKIN_DM SYSCFG_MCHDLYCR_DFSDM1CFG -/** - * @} - */ -/** @defgroup SYSTEM_LL_DFSDM1_CLKOUT_SourceSelection SYSCFG MCHDLY DFSDM1CKOSEL - * @{ - */ -#define LL_SYSCFG_DFSDM1_CKOUT (uint32_t)0x00000000 -#define LL_SYSCFG_DFSDM1_CKOUT_M27 SYSCFG_MCHDLYCR_DFSDM1CKOSEL -/** - * @} - */ - -/** @defgroup SYSTEM_LL_DFSDM2_DataIn4_SourceSelection SYSCFG MCHDLY DFSDM2D4SEL - * @{ - */ -#define LL_SYSCFG_DFSDM2_DataIn4_PAD (uint32_t)0x00000000 -#define LL_SYSCFG_DFSDM2_DataIn4_DM SYSCFG_MCHDLYCR_DFSDM2D4SEL -/** - * @} - */ -/** @defgroup SYSTEM_LL_DFSDM2_DataIn6_SourceSelection SYSCFG MCHDLY DFSDM2D6SEL - * @{ - */ -#define LL_SYSCFG_DFSDM2_DataIn6_PAD (uint32_t)0x00000000 -#define LL_SYSCFG_DFSDM2_DataIn6_DM SYSCFG_MCHDLYCR_DFSDM2D6SEL -/** - * @} - */ -/** @defgroup SYSTEM_LL_DFSDM2_TIM3OC4_BitstreamDistribution SYSCFG MCHDLY DFSDM2CK04SEL - * @{ - */ -#define LL_SYSCFG_DFSDM2_TIM3OC4_CLKIN0 (uint32_t)0x00000000 -#define LL_SYSCFG_DFSDM2_TIM3OC4_CLKIN4 SYSCFG_MCHDLYCR_DFSDM2CK04SEL -/** - * @} - */ -/** @defgroup SYSTEM_LL_DFSDM2_TIM3OC3_BitstreamDistribution SYSCFG MCHDLY DFSDM2CK15SEL - * @{ - */ -#define LL_SYSCFG_DFSDM2_TIM3OC3_CLKIN1 (uint32_t)0x00000000 -#define LL_SYSCFG_DFSDM2_TIM3OC3_CLKIN5 SYSCFG_MCHDLYCR_DFSDM2CK15SEL -/** - * @} - */ -/** @defgroup SYSTEM_LL_DFSDM2_TIM3OC2_BitstreamDistribution SYSCFG MCHDLY DFSDM2CK26SEL - * @{ - */ -#define LL_SYSCFG_DFSDM2_TIM3OC2_CLKIN2 (uint32_t)0x00000000 -#define LL_SYSCFG_DFSDM2_TIM3OC2_CLKIN6 SYSCFG_MCHDLYCR_DFSDM2CK26SEL -/** - * @} - */ -/** @defgroup SYSTEM_LL_DFSDM2_TIM3OC1_BitstreamDistribution SYSCFG MCHDLY DFSDM2CK37SEL - * @{ - */ -#define LL_SYSCFG_DFSDM2_TIM3OC1_CLKIN3 (uint32_t)0x00000000 -#define LL_SYSCFG_DFSDM2_TIM3OC1_CLKIN7 SYSCFG_MCHDLYCR_DFSDM2CK37SEL -/** - * @} - */ -/** @defgroup SYSTEM_LL_DFSDM2_CLKIN_SourceSelection SYSCFG MCHDLY DFSDM2CFG - * @{ - */ -#define LL_SYSCFG_DFSDM2_CKIN_PAD (uint32_t)0x00000000 -#define LL_SYSCFG_DFSDM2_CKIN_DM SYSCFG_MCHDLYCR_DFSDM2CFG -/** - * @} - */ -/** @defgroup SYSTEM_LL_DFSDM2_CLKOUT_SourceSelection SYSCFG MCHDLY DFSDM2CKOSEL - * @{ - */ -#define LL_SYSCFG_DFSDM2_CKOUT (uint32_t)0x00000000 -#define LL_SYSCFG_DFSDM2_CKOUT_M27 SYSCFG_MCHDLYCR_DFSDM2CKOSEL -/** - * @} - */ -#endif /* SYSCFG_MCHDLYCR_BSCKSEL */ - -/** @defgroup SYSTEM_LL_EC_TRACE DBGMCU TRACE Pin Assignment - * @{ - */ -#define LL_DBGMCU_TRACE_NONE 0x00000000U /*!< TRACE pins not assigned (default state) */ -#define LL_DBGMCU_TRACE_ASYNCH DBGMCU_CR_TRACE_IOEN /*!< TRACE pin assignment for Asynchronous Mode */ -#define LL_DBGMCU_TRACE_SYNCH_SIZE1 (DBGMCU_CR_TRACE_IOEN | DBGMCU_CR_TRACE_MODE_0) /*!< TRACE pin assignment for Synchronous Mode with a TRACEDATA size of 1 */ -#define LL_DBGMCU_TRACE_SYNCH_SIZE2 (DBGMCU_CR_TRACE_IOEN | DBGMCU_CR_TRACE_MODE_1) /*!< TRACE pin assignment for Synchronous Mode with a TRACEDATA size of 2 */ -#define LL_DBGMCU_TRACE_SYNCH_SIZE4 (DBGMCU_CR_TRACE_IOEN | DBGMCU_CR_TRACE_MODE) /*!< TRACE pin assignment for Synchronous Mode with a TRACEDATA size of 4 */ -/** - * @} - */ - -/** @defgroup SYSTEM_LL_EC_APB1_GRP1_STOP_IP DBGMCU APB1 GRP1 STOP IP - * @{ - */ -#if defined(DBGMCU_APB1_FZ_DBG_TIM2_STOP) -#define LL_DBGMCU_APB1_GRP1_TIM2_STOP DBGMCU_APB1_FZ_DBG_TIM2_STOP /*!< TIM2 counter stopped when core is halted */ -#endif /* DBGMCU_APB1_FZ_DBG_TIM2_STOP */ -#if defined(DBGMCU_APB1_FZ_DBG_TIM3_STOP) -#define LL_DBGMCU_APB1_GRP1_TIM3_STOP DBGMCU_APB1_FZ_DBG_TIM3_STOP /*!< TIM3 counter stopped when core is halted */ -#endif /* DBGMCU_APB1_FZ_DBG_TIM3_STOP */ -#if defined(DBGMCU_APB1_FZ_DBG_TIM4_STOP) -#define LL_DBGMCU_APB1_GRP1_TIM4_STOP DBGMCU_APB1_FZ_DBG_TIM4_STOP /*!< TIM4 counter stopped when core is halted */ -#endif /* DBGMCU_APB1_FZ_DBG_TIM4_STOP */ -#define LL_DBGMCU_APB1_GRP1_TIM5_STOP DBGMCU_APB1_FZ_DBG_TIM5_STOP /*!< TIM5 counter stopped when core is halted */ -#if defined(DBGMCU_APB1_FZ_DBG_TIM6_STOP) -#define LL_DBGMCU_APB1_GRP1_TIM6_STOP DBGMCU_APB1_FZ_DBG_TIM6_STOP /*!< TIM6 counter stopped when core is halted */ -#endif /* DBGMCU_APB1_FZ_DBG_TIM6_STOP */ -#if defined(DBGMCU_APB1_FZ_DBG_TIM7_STOP) -#define LL_DBGMCU_APB1_GRP1_TIM7_STOP DBGMCU_APB1_FZ_DBG_TIM7_STOP /*!< TIM7 counter stopped when core is halted */ -#endif /* DBGMCU_APB1_FZ_DBG_TIM7_STOP */ -#if defined(DBGMCU_APB1_FZ_DBG_TIM12_STOP) -#define LL_DBGMCU_APB1_GRP1_TIM12_STOP DBGMCU_APB1_FZ_DBG_TIM12_STOP /*!< TIM12 counter stopped when core is halted */ -#endif /* DBGMCU_APB1_FZ_DBG_TIM12_STOP */ -#if defined(DBGMCU_APB1_FZ_DBG_TIM13_STOP) -#define LL_DBGMCU_APB1_GRP1_TIM13_STOP DBGMCU_APB1_FZ_DBG_TIM13_STOP /*!< TIM13 counter stopped when core is halted */ -#endif /* DBGMCU_APB1_FZ_DBG_TIM13_STOP */ -#if defined(DBGMCU_APB1_FZ_DBG_TIM14_STOP) -#define LL_DBGMCU_APB1_GRP1_TIM14_STOP DBGMCU_APB1_FZ_DBG_TIM14_STOP /*!< TIM14 counter stopped when core is halted */ -#endif /* DBGMCU_APB1_FZ_DBG_TIM14_STOP */ -#if defined(DBGMCU_APB1_FZ_DBG_LPTIM_STOP) -#define LL_DBGMCU_APB1_GRP1_LPTIM_STOP DBGMCU_APB1_FZ_DBG_LPTIM_STOP /*!< LPTIM counter stopped when core is halted */ -#endif /* DBGMCU_APB1_FZ_DBG_LPTIM_STOP */ -#define LL_DBGMCU_APB1_GRP1_RTC_STOP DBGMCU_APB1_FZ_DBG_RTC_STOP /*!< RTC counter stopped when core is halted */ -#define LL_DBGMCU_APB1_GRP1_WWDG_STOP DBGMCU_APB1_FZ_DBG_WWDG_STOP /*!< Debug Window Watchdog stopped when Core is halted */ -#define LL_DBGMCU_APB1_GRP1_IWDG_STOP DBGMCU_APB1_FZ_DBG_IWDG_STOP /*!< Debug Independent Watchdog stopped when Core is halted */ -#define LL_DBGMCU_APB1_GRP1_I2C1_STOP DBGMCU_APB1_FZ_DBG_I2C1_SMBUS_TIMEOUT /*!< I2C1 SMBUS timeout mode stopped when Core is halted */ -#define LL_DBGMCU_APB1_GRP1_I2C2_STOP DBGMCU_APB1_FZ_DBG_I2C2_SMBUS_TIMEOUT /*!< I2C2 SMBUS timeout mode stopped when Core is halted */ -#if defined(DBGMCU_APB1_FZ_DBG_I2C3_SMBUS_TIMEOUT) -#define LL_DBGMCU_APB1_GRP1_I2C3_STOP DBGMCU_APB1_FZ_DBG_I2C3_SMBUS_TIMEOUT /*!< I2C3 SMBUS timeout mode stopped when Core is halted */ -#endif /* DBGMCU_APB1_FZ_DBG_I2C3_SMBUS_TIMEOUT */ -#if defined(DBGMCU_APB1_FZ_DBG_I2C4_SMBUS_TIMEOUT) -#define LL_DBGMCU_APB1_GRP1_I2C4_STOP DBGMCU_APB1_FZ_DBG_I2C4_SMBUS_TIMEOUT /*!< I2C4 SMBUS timeout mode stopped when Core is halted */ -#endif /* DBGMCU_APB1_FZ_DBG_I2C4_SMBUS_TIMEOUT */ -#if defined(DBGMCU_APB1_FZ_DBG_CAN1_STOP) -#define LL_DBGMCU_APB1_GRP1_CAN1_STOP DBGMCU_APB1_FZ_DBG_CAN1_STOP /*!< CAN1 debug stopped when Core is halted */ -#endif /* DBGMCU_APB1_FZ_DBG_CAN1_STOP */ -#if defined(DBGMCU_APB1_FZ_DBG_CAN2_STOP) -#define LL_DBGMCU_APB1_GRP1_CAN2_STOP DBGMCU_APB1_FZ_DBG_CAN2_STOP /*!< CAN2 debug stopped when Core is halted */ -#endif /* DBGMCU_APB1_FZ_DBG_CAN2_STOP */ -#if defined(DBGMCU_APB1_FZ_DBG_CAN3_STOP) -#define LL_DBGMCU_APB1_GRP1_CAN3_STOP DBGMCU_APB1_FZ_DBG_CAN3_STOP /*!< CAN3 debug stopped when Core is halted */ -#endif /* DBGMCU_APB1_FZ_DBG_CAN3_STOP */ -/** - * @} - */ - -/** @defgroup SYSTEM_LL_EC_APB2_GRP1_STOP_IP DBGMCU APB2 GRP1 STOP IP - * @{ - */ -#define LL_DBGMCU_APB2_GRP1_TIM1_STOP DBGMCU_APB2_FZ_DBG_TIM1_STOP /*!< TIM1 counter stopped when core is halted */ -#if defined(DBGMCU_APB2_FZ_DBG_TIM8_STOP) -#define LL_DBGMCU_APB2_GRP1_TIM8_STOP DBGMCU_APB2_FZ_DBG_TIM8_STOP /*!< TIM8 counter stopped when core is halted */ -#endif /* DBGMCU_APB2_FZ_DBG_TIM8_STOP */ -#define LL_DBGMCU_APB2_GRP1_TIM9_STOP DBGMCU_APB2_FZ_DBG_TIM9_STOP /*!< TIM9 counter stopped when core is halted */ -#if defined(DBGMCU_APB2_FZ_DBG_TIM10_STOP) -#define LL_DBGMCU_APB2_GRP1_TIM10_STOP DBGMCU_APB2_FZ_DBG_TIM10_STOP /*!< TIM10 counter stopped when core is halted */ -#endif /* DBGMCU_APB2_FZ_DBG_TIM10_STOP */ -#define LL_DBGMCU_APB2_GRP1_TIM11_STOP DBGMCU_APB2_FZ_DBG_TIM11_STOP /*!< TIM11 counter stopped when core is halted */ -/** - * @} - */ - -/** @defgroup SYSTEM_LL_EC_LATENCY FLASH LATENCY - * @{ - */ -#define LL_FLASH_LATENCY_0 FLASH_ACR_LATENCY_0WS /*!< FLASH Zero wait state */ -#define LL_FLASH_LATENCY_1 FLASH_ACR_LATENCY_1WS /*!< FLASH One wait state */ -#define LL_FLASH_LATENCY_2 FLASH_ACR_LATENCY_2WS /*!< FLASH Two wait states */ -#define LL_FLASH_LATENCY_3 FLASH_ACR_LATENCY_3WS /*!< FLASH Three wait states */ -#define LL_FLASH_LATENCY_4 FLASH_ACR_LATENCY_4WS /*!< FLASH Four wait states */ -#define LL_FLASH_LATENCY_5 FLASH_ACR_LATENCY_5WS /*!< FLASH five wait state */ -#define LL_FLASH_LATENCY_6 FLASH_ACR_LATENCY_6WS /*!< FLASH six wait state */ -#define LL_FLASH_LATENCY_7 FLASH_ACR_LATENCY_7WS /*!< FLASH seven wait states */ -#define LL_FLASH_LATENCY_8 FLASH_ACR_LATENCY_8WS /*!< FLASH eight wait states */ -#define LL_FLASH_LATENCY_9 FLASH_ACR_LATENCY_9WS /*!< FLASH nine wait states */ -#define LL_FLASH_LATENCY_10 FLASH_ACR_LATENCY_10WS /*!< FLASH ten wait states */ -#define LL_FLASH_LATENCY_11 FLASH_ACR_LATENCY_11WS /*!< FLASH eleven wait states */ -#define LL_FLASH_LATENCY_12 FLASH_ACR_LATENCY_12WS /*!< FLASH twelve wait states */ -#define LL_FLASH_LATENCY_13 FLASH_ACR_LATENCY_13WS /*!< FLASH thirteen wait states */ -#define LL_FLASH_LATENCY_14 FLASH_ACR_LATENCY_14WS /*!< FLASH fourteen wait states */ -#define LL_FLASH_LATENCY_15 FLASH_ACR_LATENCY_15WS /*!< FLASH fifteen wait states */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup SYSTEM_LL_Exported_Functions SYSTEM Exported Functions - * @{ - */ - -/** @defgroup SYSTEM_LL_EF_SYSCFG SYSCFG - * @{ - */ -/** - * @brief Set memory mapping at address 0x00000000 - * @rmtoll SYSCFG_MEMRMP MEM_MODE LL_SYSCFG_SetRemapMemory - * @param Memory This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_REMAP_FLASH - * @arg @ref LL_SYSCFG_REMAP_SYSTEMFLASH - * @arg @ref LL_SYSCFG_REMAP_SRAM - * @arg @ref LL_SYSCFG_REMAP_FSMC (*) - * @arg @ref LL_SYSCFG_REMAP_FMC (*) - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_SetRemapMemory(uint32_t Memory) -{ - MODIFY_REG(SYSCFG->MEMRMP, SYSCFG_MEMRMP_MEM_MODE, Memory); -} - -/** - * @brief Get memory mapping at address 0x00000000 - * @rmtoll SYSCFG_MEMRMP MEM_MODE LL_SYSCFG_GetRemapMemory - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_REMAP_FLASH - * @arg @ref LL_SYSCFG_REMAP_SYSTEMFLASH - * @arg @ref LL_SYSCFG_REMAP_SRAM - * @arg @ref LL_SYSCFG_REMAP_FSMC (*) - * @arg @ref LL_SYSCFG_REMAP_FMC (*) - */ -__STATIC_INLINE uint32_t LL_SYSCFG_GetRemapMemory(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MEMRMP, SYSCFG_MEMRMP_MEM_MODE)); -} - -#if defined(SYSCFG_MEMRMP_SWP_FMC) -/** - * @brief Enables the FMC Memory Mapping Swapping - * @rmtoll SYSCFG_MEMRMP SWP_FMC LL_SYSCFG_EnableFMCMemorySwapping - * @note SDRAM is accessible at 0x60000000 and NOR/RAM - * is accessible at 0xC0000000 - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_EnableFMCMemorySwapping(void) -{ - SET_BIT(SYSCFG->MEMRMP, SYSCFG_MEMRMP_SWP_FMC_0); -} - -/** - * @brief Disables the FMC Memory Mapping Swapping - * @rmtoll SYSCFG_MEMRMP SWP_FMC LL_SYSCFG_DisableFMCMemorySwapping - * @note SDRAM is accessible at 0xC0000000 (default mapping) - * and NOR/RAM is accessible at 0x60000000 (default mapping) - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DisableFMCMemorySwapping(void) -{ - CLEAR_BIT(SYSCFG->MEMRMP, SYSCFG_MEMRMP_SWP_FMC); -} - -#endif /* SYSCFG_MEMRMP_SWP_FMC */ -/** - * @brief Enables the Compensation cell Power Down - * @rmtoll SYSCFG_CMPCR CMP_PD LL_SYSCFG_EnableCompensationCell - * @note The I/O compensation cell can be used only when the device supply - * voltage ranges from 2.4 to 3.6 V - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_EnableCompensationCell(void) -{ - SET_BIT(SYSCFG->CMPCR, SYSCFG_CMPCR_CMP_PD); -} - -/** - * @brief Disables the Compensation cell Power Down - * @rmtoll SYSCFG_CMPCR CMP_PD LL_SYSCFG_DisableCompensationCell - * @note The I/O compensation cell can be used only when the device supply - * voltage ranges from 2.4 to 3.6 V - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DisableCompensationCell(void) -{ - CLEAR_BIT(SYSCFG->CMPCR, SYSCFG_CMPCR_CMP_PD); -} - -/** - * @brief Get Compensation Cell ready Flag - * @rmtoll SYSCFG_CMPCR READY LL_SYSCFG_IsActiveFlag_CMPCR - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_SYSCFG_IsActiveFlag_CMPCR(void) -{ - return (READ_BIT(SYSCFG->CMPCR, SYSCFG_CMPCR_READY) == (SYSCFG_CMPCR_READY)); -} - -#if defined(SYSCFG_PMC_MII_RMII_SEL) -/** - * @brief Select Ethernet PHY interface - * @rmtoll SYSCFG_PMC MII_RMII_SEL LL_SYSCFG_SetPHYInterface - * @param Interface This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_PMC_ETHMII - * @arg @ref LL_SYSCFG_PMC_ETHRMII - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_SetPHYInterface(uint32_t Interface) -{ - MODIFY_REG(SYSCFG->PMC, SYSCFG_PMC_MII_RMII_SEL, Interface); -} - -/** - * @brief Get Ethernet PHY interface - * @rmtoll SYSCFG_PMC MII_RMII_SEL LL_SYSCFG_GetPHYInterface - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_PMC_ETHMII - * @arg @ref LL_SYSCFG_PMC_ETHRMII - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_GetPHYInterface(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->PMC, SYSCFG_PMC_MII_RMII_SEL)); -} -#endif /* SYSCFG_PMC_MII_RMII_SEL */ - - - -#if defined(SYSCFG_MEMRMP_UFB_MODE) -/** - * @brief Select Flash bank mode (Bank flashed at 0x08000000) - * @rmtoll SYSCFG_MEMRMP UFB_MODE LL_SYSCFG_SetFlashBankMode - * @param Bank This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_BANKMODE_BANK1 - * @arg @ref LL_SYSCFG_BANKMODE_BANK2 - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_SetFlashBankMode(uint32_t Bank) -{ - MODIFY_REG(SYSCFG->MEMRMP, SYSCFG_MEMRMP_UFB_MODE, Bank); -} - -/** - * @brief Get Flash bank mode (Bank flashed at 0x08000000) - * @rmtoll SYSCFG_MEMRMP UFB_MODE LL_SYSCFG_GetFlashBankMode - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_BANKMODE_BANK1 - * @arg @ref LL_SYSCFG_BANKMODE_BANK2 - */ -__STATIC_INLINE uint32_t LL_SYSCFG_GetFlashBankMode(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MEMRMP, SYSCFG_MEMRMP_UFB_MODE)); -} -#endif /* SYSCFG_MEMRMP_UFB_MODE */ - -#if defined(SYSCFG_CFGR_FMPI2C1_SCL) -/** - * @brief Enable the I2C fast mode plus driving capability. - * @rmtoll SYSCFG_CFGR FMPI2C1_SCL LL_SYSCFG_EnableFastModePlus\n - * SYSCFG_CFGR FMPI2C1_SDA LL_SYSCFG_EnableFastModePlus - * @param ConfigFastModePlus This parameter can be a combination of the following values: - * @arg @ref LL_SYSCFG_I2C_FASTMODEPLUS_SCL - * @arg @ref LL_SYSCFG_I2C_FASTMODEPLUS_SDA - * (*) value not defined in all devices - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_EnableFastModePlus(uint32_t ConfigFastModePlus) -{ - SET_BIT(SYSCFG->CFGR, ConfigFastModePlus); -} - -/** - * @brief Disable the I2C fast mode plus driving capability. - * @rmtoll SYSCFG_CFGR FMPI2C1_SCL LL_SYSCFG_DisableFastModePlus\n - * SYSCFG_CFGR FMPI2C1_SDA LL_SYSCFG_DisableFastModePlus\n - * @param ConfigFastModePlus This parameter can be a combination of the following values: - * @arg @ref LL_SYSCFG_I2C_FASTMODEPLUS_SCL - * @arg @ref LL_SYSCFG_I2C_FASTMODEPLUS_SDA - * (*) value not defined in all devices - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DisableFastModePlus(uint32_t ConfigFastModePlus) -{ - CLEAR_BIT(SYSCFG->CFGR, ConfigFastModePlus); -} -#endif /* SYSCFG_CFGR_FMPI2C1_SCL */ - -/** - * @brief Configure source input for the EXTI external interrupt. - * @rmtoll SYSCFG_EXTICR1 EXTIx LL_SYSCFG_SetEXTISource\n - * SYSCFG_EXTICR2 EXTIx LL_SYSCFG_SetEXTISource\n - * SYSCFG_EXTICR3 EXTIx LL_SYSCFG_SetEXTISource\n - * SYSCFG_EXTICR4 EXTIx LL_SYSCFG_SetEXTISource - * @param Port This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_EXTI_PORTA - * @arg @ref LL_SYSCFG_EXTI_PORTB - * @arg @ref LL_SYSCFG_EXTI_PORTC - * @arg @ref LL_SYSCFG_EXTI_PORTD - * @arg @ref LL_SYSCFG_EXTI_PORTE - * @arg @ref LL_SYSCFG_EXTI_PORTF (*) - * @arg @ref LL_SYSCFG_EXTI_PORTG (*) - * @arg @ref LL_SYSCFG_EXTI_PORTH - * - * (*) value not defined in all devices - * @param Line This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_EXTI_LINE0 - * @arg @ref LL_SYSCFG_EXTI_LINE1 - * @arg @ref LL_SYSCFG_EXTI_LINE2 - * @arg @ref LL_SYSCFG_EXTI_LINE3 - * @arg @ref LL_SYSCFG_EXTI_LINE4 - * @arg @ref LL_SYSCFG_EXTI_LINE5 - * @arg @ref LL_SYSCFG_EXTI_LINE6 - * @arg @ref LL_SYSCFG_EXTI_LINE7 - * @arg @ref LL_SYSCFG_EXTI_LINE8 - * @arg @ref LL_SYSCFG_EXTI_LINE9 - * @arg @ref LL_SYSCFG_EXTI_LINE10 - * @arg @ref LL_SYSCFG_EXTI_LINE11 - * @arg @ref LL_SYSCFG_EXTI_LINE12 - * @arg @ref LL_SYSCFG_EXTI_LINE13 - * @arg @ref LL_SYSCFG_EXTI_LINE14 - * @arg @ref LL_SYSCFG_EXTI_LINE15 - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_SetEXTISource(uint32_t Port, uint32_t Line) -{ - MODIFY_REG(SYSCFG->EXTICR[Line & 0xFF], (Line >> 16), Port << POSITION_VAL((Line >> 16))); -} - -/** - * @brief Get the configured defined for specific EXTI Line - * @rmtoll SYSCFG_EXTICR1 EXTIx LL_SYSCFG_GetEXTISource\n - * SYSCFG_EXTICR2 EXTIx LL_SYSCFG_GetEXTISource\n - * SYSCFG_EXTICR3 EXTIx LL_SYSCFG_GetEXTISource\n - * SYSCFG_EXTICR4 EXTIx LL_SYSCFG_GetEXTISource - * @param Line This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_EXTI_LINE0 - * @arg @ref LL_SYSCFG_EXTI_LINE1 - * @arg @ref LL_SYSCFG_EXTI_LINE2 - * @arg @ref LL_SYSCFG_EXTI_LINE3 - * @arg @ref LL_SYSCFG_EXTI_LINE4 - * @arg @ref LL_SYSCFG_EXTI_LINE5 - * @arg @ref LL_SYSCFG_EXTI_LINE6 - * @arg @ref LL_SYSCFG_EXTI_LINE7 - * @arg @ref LL_SYSCFG_EXTI_LINE8 - * @arg @ref LL_SYSCFG_EXTI_LINE9 - * @arg @ref LL_SYSCFG_EXTI_LINE10 - * @arg @ref LL_SYSCFG_EXTI_LINE11 - * @arg @ref LL_SYSCFG_EXTI_LINE12 - * @arg @ref LL_SYSCFG_EXTI_LINE13 - * @arg @ref LL_SYSCFG_EXTI_LINE14 - * @arg @ref LL_SYSCFG_EXTI_LINE15 - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_EXTI_PORTA - * @arg @ref LL_SYSCFG_EXTI_PORTB - * @arg @ref LL_SYSCFG_EXTI_PORTC - * @arg @ref LL_SYSCFG_EXTI_PORTD - * @arg @ref LL_SYSCFG_EXTI_PORTE - * @arg @ref LL_SYSCFG_EXTI_PORTF (*) - * @arg @ref LL_SYSCFG_EXTI_PORTG (*) - * @arg @ref LL_SYSCFG_EXTI_PORTH - * (*) value not defined in all devices - */ -__STATIC_INLINE uint32_t LL_SYSCFG_GetEXTISource(uint32_t Line) -{ - return (uint32_t)(READ_BIT(SYSCFG->EXTICR[Line & 0xFF], (Line >> 16)) >> POSITION_VAL(Line >> 16)); -} - -#if defined(SYSCFG_CFGR2_LOCKUP_LOCK) -/** - * @brief Set connections to TIM1/8 break inputs - * @rmtoll SYSCFG_CFGR2 LockUp Lock LL_SYSCFG_SetTIMBreakInputs \n - * SYSCFG_CFGR2 PVD Lock LL_SYSCFG_SetTIMBreakInputs - * @param Break This parameter can be a combination of the following values: - * @arg @ref LL_SYSCFG_TIMBREAK_LOCKUP - * @arg @ref LL_SYSCFG_TIMBREAK_PVD - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_SetTIMBreakInputs(uint32_t Break) -{ - MODIFY_REG(SYSCFG->CFGR2, SYSCFG_CFGR2_LOCKUP_LOCK | SYSCFG_CFGR2_PVD_LOCK, Break); -} - -/** - * @brief Get connections to TIM1/8 Break inputs - * @rmtoll SYSCFG_CFGR2 LockUp Lock LL_SYSCFG_SetTIMBreakInputs \n - * SYSCFG_CFGR2 PVD Lock LL_SYSCFG_SetTIMBreakInputs - * @retval Returned value can be can be a combination of the following values: - * @arg @ref LL_SYSCFG_TIMBREAK_LOCKUP - * @arg @ref LL_SYSCFG_TIMBREAK_PVD - */ -__STATIC_INLINE uint32_t LL_SYSCFG_GetTIMBreakInputs(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->CFGR2, SYSCFG_CFGR2_LOCKUP_LOCK | SYSCFG_CFGR2_PVD_LOCK)); -} -#endif /* SYSCFG_CFGR2_LOCKUP_LOCK */ -#if defined(SYSCFG_MCHDLYCR_BSCKSEL) -/** - * @brief Select the DFSDM2 or TIM2_OC1 as clock source for the bitstream clock. - * @rmtoll SYSCFG_MCHDLYCR BSCKSEL LL_SYSCFG_DFSDM_SetBitstreamClockSourceSelection - * @param ClockSource This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_BITSTREAM_CLOCK_DFSDM2 - * @arg @ref LL_SYSCFG_BITSTREAM_CLOCK_TIM2OC1 - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM_SetBitstreamClockSourceSelection(uint32_t ClockSource) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_BSCKSEL, ClockSource); -} -/** - * @brief Get the DFSDM2 or TIM2_OC1 as clock source for the bitstream clock. - * @rmtoll SYSCFG_MCHDLYCR BSCKSEL LL_SYSCFG_DFSDM_GetBitstreamClockSourceSelection - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_BITSTREAM_CLOCK_DFSDM2 - * @arg @ref LL_SYSCFG_BITSTREAM_CLOCK_TIM2OC1 - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM_GetBitstreamClockSourceSelection(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_BSCKSEL)); -} -/** - * @brief Enables the DFSDM1 or DFSDM2 Delay clock - * @rmtoll SYSCFG_MCHDLYCR MCHDLYEN LL_SYSCFG_DFSDM_EnableDelayClock - * @param MCHDLY This paramater can be one of the following values - * @arg @ref LL_SYSCFG_DFSDM1_MCHDLYEN - * @arg @ref LL_SYSCFG_DFSDM2_MCHDLYEN - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM_EnableDelayClock(uint32_t MCHDLY) -{ - SET_BIT(SYSCFG->MCHDLYCR, MCHDLY); -} - -/** - * @brief Disables the DFSDM1 or the DFSDM2 Delay clock - * @rmtoll SYSCFG_MCHDLYCR MCHDLY1EN LL_SYSCFG_DFSDM1_DisableDelayClock - * @param MCHDLY This paramater can be one of the following values - * @arg @ref LL_SYSCFG_DFSDM1_MCHDLYEN - * @arg @ref LL_SYSCFG_DFSDM2_MCHDLYEN - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM_DisableDelayClock(uint32_t MCHDLY) -{ - CLEAR_BIT(SYSCFG->MCHDLYCR, MCHDLY); -} - -/** - * @brief Select the source for DFSDM1 or DFSDM2 DatIn0 - * @rmtoll SYSCFG_MCHDLYCR DFSDMD0SEL LL_SYSCFG_DFSDM_SetDataIn0Source - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM1_DataIn0_PAD - * @arg @ref LL_SYSCFG_DFSDM1_DataIn0_DM - * @arg @ref LL_SYSCFG_DFSDM2_DataIn0_PAD - * @arg @ref LL_SYSCFG_DFSDM2_DataIn0_DM - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM_SetDataIn0Source(uint32_t Source) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, (Source >> 16), (Source & 0x0000FFFF)); -} -/** - * @brief Get the source for DFSDM1 or DFSDM2 DatIn0. - * @rmtoll SYSCFG_MCHDLYCR DFSDMD0SEL LL_SYSCFG_DFSDM_GetDataIn0Source - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM1_DataIn0 - * @arg @ref LL_SYSCFG_DFSDM2_DataIn0 - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM1_DataIn0_PAD - * @arg @ref LL_SYSCFG_DFSDM1_DataIn0_DM - * @arg @ref LL_SYSCFG_DFSDM2_DataIn0_PAD - * @arg @ref LL_SYSCFG_DFSDM2_DataIn0_DM - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM_GetDataIn0Source(uint32_t Source) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, Source)); -} -/** - * @brief Select the source for DFSDM1 or DFSDM2 DatIn2 - * @rmtoll SYSCFG_MCHDLYCR DFSDMD2SEL LL_SYSCFG_DFSDM_SetDataIn2Source - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM1_DataIn2_PAD - * @arg @ref LL_SYSCFG_DFSDM1_DataIn2_DM - * @arg @ref LL_SYSCFG_DFSDM2_DataIn2_PAD - * @arg @ref LL_SYSCFG_DFSDM2_DataIn2_DM - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM_SetDataIn2Source(uint32_t Source) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, (Source >> 16), (Source & 0x0000FFFF)); -} -/** - * @brief Get the source for DFSDM1 or DFSDM2 DatIn2. - * @rmtoll SYSCFG_MCHDLYCR DFSDMD2SEL LL_SYSCFG_DFSDM_GetDataIn2Source - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM1_DataIn2 - * @arg @ref LL_SYSCFG_DFSDM2_DataIn2 - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM1_DataIn2_PAD - * @arg @ref LL_SYSCFG_DFSDM1_DataIn2_DM - * @arg @ref LL_SYSCFG_DFSDM2_DataIn2_PAD - * @arg @ref LL_SYSCFG_DFSDM2_DataIn2_DM - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM_GetDataIn2Source(uint32_t Source) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, Source)); -} - -/** - * @brief Select the distribution of the bitsream lock gated by TIM4 OC2 - * @rmtoll SYSCFG_MCHDLYCR DFSDM1CK02SEL LL_SYSCFG_DFSDM1_SetTIM4OC2BitStreamDistribution - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM1_TIM4OC2_CLKIN0 - * @arg @ref LL_SYSCFG_DFSDM1_TIM4OC2_CLKIN2 - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM1_SetTIM4OC2BitStreamDistribution(uint32_t Source) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM1CK02SEL, Source); -} -/** - * @brief Get the distribution of the bitsream lock gated by TIM4 OC2 - * @rmtoll SYSCFG_MCHDLYCR DFSDM1D2SEL LL_SYSCFG_DFSDM1_GetTIM4OC2BitStreamDistribution - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM1_TIM4OC2_CLKIN0 - * @arg @ref LL_SYSCFG_DFSDM1_TIM4OC2_CLKIN2 - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM1_GetTIM4OC2BitStreamDistribution(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM1CK02SEL)); -} - -/** - * @brief Select the distribution of the bitsream lock gated by TIM4 OC1 - * @rmtoll SYSCFG_MCHDLYCR DFSDM1CK13SEL LL_SYSCFG_DFSDM1_SetTIM4OC1BitStreamDistribution - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM1_TIM4OC1_CLKIN1 - * @arg @ref LL_SYSCFG_DFSDM1_TIM4OC1_CLKIN3 - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM1_SetTIM4OC1BitStreamDistribution(uint32_t Source) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM1CK13SEL, Source); -} -/** - * @brief Get the distribution of the bitsream lock gated by TIM4 OC1 - * @rmtoll SYSCFG_MCHDLYCR DFSDM1D2SEL LL_SYSCFG_DFSDM1_GetTIM4OC1BitStreamDistribution - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM1_TIM4OC1_CLKIN1 - * @arg @ref LL_SYSCFG_DFSDM1_TIM4OC1_CLKIN3 - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM1_GetTIM4OC1BitStreamDistribution(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM1CK13SEL)); -} - -/** - * @brief Select the DFSDM1 Clock In - * @rmtoll SYSCFG_MCHDLYCR DFSDM1CFG LL_SYSCFG_DFSDM1_SetClockInSourceSelection - * @param ClockSource This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM1_CKIN_PAD - * @arg @ref LL_SYSCFG_DFSDM1_CKIN_DM - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM1_SetClockInSourceSelection(uint32_t ClockSource) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM1CFG, ClockSource); -} -/** - * @brief GET the DFSDM1 Clock In - * @rmtoll SYSCFG_MCHDLYCR DFSDM1CFG LL_SYSCFG_DFSDM1_GetClockInSourceSelection - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM1_CKIN_PAD - * @arg @ref LL_SYSCFG_DFSDM1_CKIN_DM - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM1_GetClockInSourceSelection(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM1CFG)); -} - -/** - * @brief Select the DFSDM1 Clock Out - * @rmtoll SYSCFG_MCHDLYCR DFSDM1CKOSEL LL_SYSCFG_DFSDM1_SetClockOutSourceSelection - * @param ClockSource This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM1_CKOUT - * @arg @ref LL_SYSCFG_DFSDM1_CKOUT_M27 - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM1_SetClockOutSourceSelection(uint32_t ClockSource) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM1CKOSEL, ClockSource); -} -/** - * @brief GET the DFSDM1 Clock Out - * @rmtoll SYSCFG_MCHDLYCR DFSDM1CKOSEL LL_SYSCFG_DFSDM1_GetClockOutSourceSelection - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM1_CKOUT - * @arg @ref LL_SYSCFG_DFSDM1_CKOUT_M27 - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM1_GetClockOutSourceSelection(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM1CKOSEL)); -} - -/** - * @brief Enables the DFSDM2 Delay clock - * @rmtoll SYSCFG_MCHDLYCR MCHDLY2EN LL_SYSCFG_DFSDM2_EnableDelayClock - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM2_EnableDelayClock(void) -{ - SET_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_MCHDLY2EN); -} - -/** - * @brief Disables the DFSDM2 Delay clock - * @rmtoll SYSCFG_MCHDLYCR MCHDLY2EN LL_SYSCFG_DFSDM2_DisableDelayClock - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM2_DisableDelayClock(void) -{ - CLEAR_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_MCHDLY2EN); -} -/** - * @brief Select the source for DFSDM2 DatIn0 - * @rmtoll SYSCFG_MCHDLYCR DFSDM2D0SEL LL_SYSCFG_DFSDM2_SetDataIn0Source - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_DataIn0_PAD - * @arg @ref LL_SYSCFG_DFSDM2_DataIn0_DM - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM2_SetDataIn0Source(uint32_t Source) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2D0SEL, Source); -} -/** - * @brief Get the source for DFSDM2 DatIn0. - * @rmtoll SYSCFG_MCHDLYCR DFSDM2D0SEL LL_SYSCFG_DFSDM2_GetDataIn0Source - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_DataIn0_PAD - * @arg @ref LL_SYSCFG_DFSDM2_DataIn0_DM - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM2_GetDataIn0Source(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2D0SEL)); -} - -/** - * @brief Select the source for DFSDM2 DatIn2 - * @rmtoll SYSCFG_MCHDLYCR DFSDM2D2SEL LL_SYSCFG_DFSDM2_SetDataIn2Source - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_DataIn2_PAD - * @arg @ref LL_SYSCFG_DFSDM2_DataIn2_DM - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM2_SetDataIn2Source(uint32_t Source) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2D2SEL, Source); -} -/** - * @brief Get the source for DFSDM2 DatIn2. - * @rmtoll SYSCFG_MCHDLYCR DFSDM2D2SEL LL_SYSCFG_DFSDM2_GetDataIn2Source - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_DataIn2_PAD - * @arg @ref LL_SYSCFG_DFSDM2_DataIn2_DM - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM2_GetDataIn2Source(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2D2SEL)); -} - -/** - * @brief Select the source for DFSDM2 DatIn4 - * @rmtoll SYSCFG_MCHDLYCR DFSDM2D4SEL LL_SYSCFG_DFSDM2_SetDataIn4Source - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_DataIn4_PAD - * @arg @ref LL_SYSCFG_DFSDM2_DataIn4_DM - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM2_SetDataIn4Source(uint32_t Source) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2D4SEL, Source); -} -/** - * @brief Get the source for DFSDM2 DatIn4. - * @rmtoll SYSCFG_MCHDLYCR DFSDM2D4SEL LL_SYSCFG_DFSDM2_GetDataIn4Source - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_DataIn4_PAD - * @arg @ref LL_SYSCFG_DFSDM2_DataIn4_DM - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM2_GetDataIn4Source(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2D4SEL)); -} - -/** - * @brief Select the source for DFSDM2 DatIn6 - * @rmtoll SYSCFG_MCHDLYCR DFSDM2D6SEL LL_SYSCFG_DFSDM2_SetDataIn6Source - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_DataIn6_PAD - * @arg @ref LL_SYSCFG_DFSDM2_DataIn6_DM - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM2_SetDataIn6Source(uint32_t Source) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2D6SEL, Source); -} -/** - * @brief Get the source for DFSDM2 DatIn6. - * @rmtoll SYSCFG_MCHDLYCR DFSDM2D6SEL LL_SYSCFG_DFSDM2_GetDataIn6Source - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_DataIn6_PAD - * @arg @ref LL_SYSCFG_DFSDM2_DataIn6_DM - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM2_GetDataIn6Source(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2D6SEL)); -} - -/** - * @brief Select the distribution of the bitsream lock gated by TIM3 OC4 - * @rmtoll SYSCFG_MCHDLYCR DFSDM2CK04SEL LL_SYSCFG_DFSDM2_SetTIM3OC4BitStreamDistribution - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC4_CLKIN0 - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC4_CLKIN4 - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM2_SetTIM3OC4BitStreamDistribution(uint32_t Source) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CK04SEL, Source); -} -/** - * @brief Get the distribution of the bitsream lock gated by TIM3 OC4 - * @rmtoll SYSCFG_MCHDLYCR DFSDM2CK04SEL LL_SYSCFG_DFSDM2_GetTIM3OC4BitStreamDistribution - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC4_CLKIN0 - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC4_CLKIN4 - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM2_GetTIM3OC4BitStreamDistribution(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CK04SEL)); -} - -/** - * @brief Select the distribution of the bitsream lock gated by TIM3 OC3 - * @rmtoll SYSCFG_MCHDLYCR DFSDM2CK15SEL LL_SYSCFG_DFSDM2_SetTIM3OC3BitStreamDistribution - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC3_CLKIN1 - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC3_CLKIN5 - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM2_SetTIM3OC3BitStreamDistribution(uint32_t Source) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CK15SEL, Source); -} -/** - * @brief Get the distribution of the bitsream lock gated by TIM3 OC4 - * @rmtoll SYSCFG_MCHDLYCR DFSDM2CK04SEL LL_SYSCFG_DFSDM2_GetTIM3OC3BitStreamDistribution - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC3_CLKIN1 - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC3_CLKIN5 - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM2_GetTIM3OC3BitStreamDistribution(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CK15SEL)); -} - -/** - * @brief Select the distribution of the bitsream lock gated by TIM3 OC2 - * @rmtoll SYSCFG_MCHDLYCR DFSDM2CK26SEL LL_SYSCFG_DFSDM2_SetTIM3OC2BitStreamDistribution - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC2_CLKIN2 - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC2_CLKIN6 - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM2_SetTIM3OC2BitStreamDistribution(uint32_t Source) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CK26SEL, Source); -} -/** - * @brief Get the distribution of the bitsream lock gated by TIM3 OC2 - * @rmtoll SYSCFG_MCHDLYCR DFSDM2CK04SEL LL_SYSCFG_DFSDM2_GetTIM3OC2BitStreamDistribution - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC2_CLKIN2 - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC2_CLKIN6 - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM2_GetTIM3OC2BitStreamDistribution(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CK26SEL)); -} - -/** - * @brief Select the distribution of the bitsream lock gated by TIM3 OC1 - * @rmtoll SYSCFG_MCHDLYCR DFSDM2CK37SEL LL_SYSCFG_DFSDM2_SetTIM3OC1BitStreamDistribution - * @param Source This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC1_CLKIN3 - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC1_CLKIN7 - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM2_SetTIM3OC1BitStreamDistribution(uint32_t Source) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CK37SEL, Source); -} -/** - * @brief Get the distribution of the bitsream lock gated by TIM3 OC1 - * @rmtoll SYSCFG_MCHDLYCR DFSDM2CK37SEL LL_SYSCFG_DFSDM2_GetTIM3OC1BitStreamDistribution - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC1_CLKIN3 - * @arg @ref LL_SYSCFG_DFSDM2_TIM3OC1_CLKIN7 - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM2_GetTIM3OC1BitStreamDistribution(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CK37SEL)); -} - -/** - * @brief Select the DFSDM2 Clock In - * @rmtoll SYSCFG_MCHDLYCR DFSDM2CFG LL_SYSCFG_DFSDM2_SetClockInSourceSelection - * @param ClockSource This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_CKIN_PAD - * @arg @ref LL_SYSCFG_DFSDM2_CKIN_DM - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM2_SetClockInSourceSelection(uint32_t ClockSource) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CFG, ClockSource); -} -/** - * @brief GET the DFSDM2 Clock In - * @rmtoll SYSCFG_MCHDLYCR DFSDM2CFG LL_SYSCFG_DFSDM2_GetClockInSourceSelection - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_CKIN_PAD - * @arg @ref LL_SYSCFG_DFSDM2_CKIN_DM - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM2_GetClockInSourceSelection(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CFG)); -} - -/** - * @brief Select the DFSDM2 Clock Out - * @rmtoll SYSCFG_MCHDLYCR DFSDM2CKOSEL LL_SYSCFG_DFSDM2_SetClockOutSourceSelection - * @param ClockSource This parameter can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_CKOUT - * @arg @ref LL_SYSCFG_DFSDM2_CKOUT_M27 - * @retval None - */ -__STATIC_INLINE void LL_SYSCFG_DFSDM2_SetClockOutSourceSelection(uint32_t ClockSource) -{ - MODIFY_REG(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CKOSEL, ClockSource); -} -/** - * @brief GET the DFSDM2 Clock Out - * @rmtoll SYSCFG_MCHDLYCR DFSDM2CKOSEL LL_SYSCFG_DFSDM2_GetClockOutSourceSelection - * @retval Returned value can be one of the following values: - * @arg @ref LL_SYSCFG_DFSDM2_CKOUT - * @arg @ref LL_SYSCFG_DFSDM2_CKOUT_M27 - * @retval None - */ -__STATIC_INLINE uint32_t LL_SYSCFG_DFSDM2_GetClockOutSourceSelection(void) -{ - return (uint32_t)(READ_BIT(SYSCFG->MCHDLYCR, SYSCFG_MCHDLYCR_DFSDM2CKOSEL)); -} - -#endif /* SYSCFG_MCHDLYCR_BSCKSEL */ -/** - * @} - */ - - -/** @defgroup SYSTEM_LL_EF_DBGMCU DBGMCU - * @{ - */ - -/** - * @brief Return the device identifier - * @note For STM32F405/407xx and STM32F415/417xx devices, the device ID is 0x413 - * @note For STM32F42xxx and STM32F43xxx devices, the device ID is 0x419 - * @note For STM32F401xx devices, the device ID is 0x423 - * @note For STM32F401xx devices, the device ID is 0x433 - * @note For STM32F411xx devices, the device ID is 0x431 - * @note For STM32F410xx devices, the device ID is 0x458 - * @note For STM32F412xx devices, the device ID is 0x441 - * @note For STM32F413xx and STM32423xx devices, the device ID is 0x463 - * @note For STM32F446xx devices, the device ID is 0x421 - * @note For STM32F469xx and STM32F479xx devices, the device ID is 0x434 - * @rmtoll DBGMCU_IDCODE DEV_ID LL_DBGMCU_GetDeviceID - * @retval Values between Min_Data=0x00 and Max_Data=0xFFF - */ -__STATIC_INLINE uint32_t LL_DBGMCU_GetDeviceID(void) -{ - return (uint32_t)(READ_BIT(DBGMCU->IDCODE, DBGMCU_IDCODE_DEV_ID)); -} - -/** - * @brief Return the device revision identifier - * @note This field indicates the revision of the device. - For example, it is read as RevA -> 0x1000, Cat 2 revZ -> 0x1001, rev1 -> 0x1003, rev2 ->0x1007, revY -> 0x100F for STM32F405/407xx and STM32F415/417xx devices - For example, it is read as RevA -> 0x1000, Cat 2 revY -> 0x1003, rev1 -> 0x1007, rev3 ->0x2001 for STM32F42xxx and STM32F43xxx devices - For example, it is read as RevZ -> 0x1000, Cat 2 revA -> 0x1001 for STM32F401xB/C devices - For example, it is read as RevA -> 0x1000, Cat 2 revZ -> 0x1001 for STM32F401xD/E devices - For example, it is read as RevA -> 0x1000 for STM32F411xx,STM32F413/423xx,STM32F469/423xx, STM32F446xx and STM32F410xx devices - For example, it is read as RevZ -> 0x1001, Cat 2 revB -> 0x2000, revC -> 0x3000 for STM32F412xx devices - * @rmtoll DBGMCU_IDCODE REV_ID LL_DBGMCU_GetRevisionID - * @retval Values between Min_Data=0x00 and Max_Data=0xFFFF - */ -__STATIC_INLINE uint32_t LL_DBGMCU_GetRevisionID(void) -{ - return (uint32_t)(READ_BIT(DBGMCU->IDCODE, DBGMCU_IDCODE_REV_ID) >> DBGMCU_IDCODE_REV_ID_Pos); -} - -/** - * @brief Enable the Debug Module during SLEEP mode - * @rmtoll DBGMCU_CR DBG_SLEEP LL_DBGMCU_EnableDBGSleepMode - * @retval None - */ -__STATIC_INLINE void LL_DBGMCU_EnableDBGSleepMode(void) -{ - SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_SLEEP); -} - -/** - * @brief Disable the Debug Module during SLEEP mode - * @rmtoll DBGMCU_CR DBG_SLEEP LL_DBGMCU_DisableDBGSleepMode - * @retval None - */ -__STATIC_INLINE void LL_DBGMCU_DisableDBGSleepMode(void) -{ - CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_SLEEP); -} - -/** - * @brief Enable the Debug Module during STOP mode - * @rmtoll DBGMCU_CR DBG_STOP LL_DBGMCU_EnableDBGStopMode - * @retval None - */ -__STATIC_INLINE void LL_DBGMCU_EnableDBGStopMode(void) -{ - SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_STOP); -} - -/** - * @brief Disable the Debug Module during STOP mode - * @rmtoll DBGMCU_CR DBG_STOP LL_DBGMCU_DisableDBGStopMode - * @retval None - */ -__STATIC_INLINE void LL_DBGMCU_DisableDBGStopMode(void) -{ - CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_STOP); -} - -/** - * @brief Enable the Debug Module during STANDBY mode - * @rmtoll DBGMCU_CR DBG_STANDBY LL_DBGMCU_EnableDBGStandbyMode - * @retval None - */ -__STATIC_INLINE void LL_DBGMCU_EnableDBGStandbyMode(void) -{ - SET_BIT(DBGMCU->CR, DBGMCU_CR_DBG_STANDBY); -} - -/** - * @brief Disable the Debug Module during STANDBY mode - * @rmtoll DBGMCU_CR DBG_STANDBY LL_DBGMCU_DisableDBGStandbyMode - * @retval None - */ -__STATIC_INLINE void LL_DBGMCU_DisableDBGStandbyMode(void) -{ - CLEAR_BIT(DBGMCU->CR, DBGMCU_CR_DBG_STANDBY); -} - -/** - * @brief Set Trace pin assignment control - * @rmtoll DBGMCU_CR TRACE_IOEN LL_DBGMCU_SetTracePinAssignment\n - * DBGMCU_CR TRACE_MODE LL_DBGMCU_SetTracePinAssignment - * @param PinAssignment This parameter can be one of the following values: - * @arg @ref LL_DBGMCU_TRACE_NONE - * @arg @ref LL_DBGMCU_TRACE_ASYNCH - * @arg @ref LL_DBGMCU_TRACE_SYNCH_SIZE1 - * @arg @ref LL_DBGMCU_TRACE_SYNCH_SIZE2 - * @arg @ref LL_DBGMCU_TRACE_SYNCH_SIZE4 - * @retval None - */ -__STATIC_INLINE void LL_DBGMCU_SetTracePinAssignment(uint32_t PinAssignment) -{ - MODIFY_REG(DBGMCU->CR, DBGMCU_CR_TRACE_IOEN | DBGMCU_CR_TRACE_MODE, PinAssignment); -} - -/** - * @brief Get Trace pin assignment control - * @rmtoll DBGMCU_CR TRACE_IOEN LL_DBGMCU_GetTracePinAssignment\n - * DBGMCU_CR TRACE_MODE LL_DBGMCU_GetTracePinAssignment - * @retval Returned value can be one of the following values: - * @arg @ref LL_DBGMCU_TRACE_NONE - * @arg @ref LL_DBGMCU_TRACE_ASYNCH - * @arg @ref LL_DBGMCU_TRACE_SYNCH_SIZE1 - * @arg @ref LL_DBGMCU_TRACE_SYNCH_SIZE2 - * @arg @ref LL_DBGMCU_TRACE_SYNCH_SIZE4 - */ -__STATIC_INLINE uint32_t LL_DBGMCU_GetTracePinAssignment(void) -{ - return (uint32_t)(READ_BIT(DBGMCU->CR, DBGMCU_CR_TRACE_IOEN | DBGMCU_CR_TRACE_MODE)); -} - -/** - * @brief Freeze APB1 peripherals (group1 peripherals) - * @rmtoll DBGMCU_APB1_FZ DBG_TIM2_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM3_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM4_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM5_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM6_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM7_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM12_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM13_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM14_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_LPTIM_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_RTC_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_WWDG_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_IWDG_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_I2C1_SMBUS_TIMEOUT LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_I2C2_SMBUS_TIMEOUT LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_I2C3_SMBUS_TIMEOUT LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_I2C4_SMBUS_TIMEOUT LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_CAN1_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_CAN2_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph\n - * DBGMCU_APB1_FZ DBG_CAN3_STOP LL_DBGMCU_APB1_GRP1_FreezePeriph - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM2_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM3_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM4_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM5_STOP - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM6_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM7_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM12_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM13_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM14_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_LPTIM_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_RTC_STOP - * @arg @ref LL_DBGMCU_APB1_GRP1_WWDG_STOP - * @arg @ref LL_DBGMCU_APB1_GRP1_IWDG_STOP - * @arg @ref LL_DBGMCU_APB1_GRP1_I2C1_STOP - * @arg @ref LL_DBGMCU_APB1_GRP1_I2C2_STOP - * @arg @ref LL_DBGMCU_APB1_GRP1_I2C3_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_I2C4_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_CAN1_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_CAN2_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_CAN3_STOP (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_DBGMCU_APB1_GRP1_FreezePeriph(uint32_t Periphs) -{ - SET_BIT(DBGMCU->APB1FZ, Periphs); -} - -/** - * @brief Unfreeze APB1 peripherals (group1 peripherals) - * @rmtoll DBGMCU_APB1_FZ DBG_TIM2_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM3_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM4_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM5_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM6_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM7_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM12_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM13_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_TIM14_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_LPTIM_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_RTC_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_WWDG_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_IWDG_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_I2C1_SMBUS_TIMEOUT LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_I2C2_SMBUS_TIMEOUT LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_I2C3_SMBUS_TIMEOUT LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_I2C4_SMBUS_TIMEOUT LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_CAN1_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_CAN2_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph\n - * DBGMCU_APB1_FZ DBG_CAN3_STOP LL_DBGMCU_APB1_GRP1_UnFreezePeriph - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM2_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM3_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM4_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM5_STOP - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM6_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM7_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM12_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM13_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_TIM14_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_LPTIM_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_RTC_STOP - * @arg @ref LL_DBGMCU_APB1_GRP1_WWDG_STOP - * @arg @ref LL_DBGMCU_APB1_GRP1_IWDG_STOP - * @arg @ref LL_DBGMCU_APB1_GRP1_I2C1_STOP - * @arg @ref LL_DBGMCU_APB1_GRP1_I2C2_STOP - * @arg @ref LL_DBGMCU_APB1_GRP1_I2C3_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_I2C4_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_CAN1_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_CAN2_STOP (*) - * @arg @ref LL_DBGMCU_APB1_GRP1_CAN3_STOP (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_DBGMCU_APB1_GRP1_UnFreezePeriph(uint32_t Periphs) -{ - CLEAR_BIT(DBGMCU->APB1FZ, Periphs); -} - -/** - * @brief Freeze APB2 peripherals - * @rmtoll DBGMCU_APB2_FZ DBG_TIM1_STOP LL_DBGMCU_APB2_GRP1_FreezePeriph\n - * DBGMCU_APB2_FZ DBG_TIM8_STOP LL_DBGMCU_APB2_GRP1_FreezePeriph\n - * DBGMCU_APB2_FZ DBG_TIM9_STOP LL_DBGMCU_APB2_GRP1_FreezePeriph\n - * DBGMCU_APB2_FZ DBG_TIM10_STOP LL_DBGMCU_APB2_GRP1_FreezePeriph\n - * DBGMCU_APB2_FZ DBG_TIM11_STOP LL_DBGMCU_APB2_GRP1_FreezePeriph - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_DBGMCU_APB2_GRP1_TIM1_STOP - * @arg @ref LL_DBGMCU_APB2_GRP1_TIM8_STOP (*) - * @arg @ref LL_DBGMCU_APB2_GRP1_TIM9_STOP (*) - * @arg @ref LL_DBGMCU_APB2_GRP1_TIM10_STOP (*) - * @arg @ref LL_DBGMCU_APB2_GRP1_TIM11_STOP (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_DBGMCU_APB2_GRP1_FreezePeriph(uint32_t Periphs) -{ - SET_BIT(DBGMCU->APB2FZ, Periphs); -} - -/** - * @brief Unfreeze APB2 peripherals - * @rmtoll DBGMCU_APB2_FZ DBG_TIM1_STOP LL_DBGMCU_APB2_GRP1_UnFreezePeriph\n - * DBGMCU_APB2_FZ DBG_TIM8_STOP LL_DBGMCU_APB2_GRP1_UnFreezePeriph\n - * DBGMCU_APB2_FZ DBG_TIM9_STOP LL_DBGMCU_APB2_GRP1_UnFreezePeriph\n - * DBGMCU_APB2_FZ DBG_TIM10_STOP LL_DBGMCU_APB2_GRP1_UnFreezePeriph\n - * DBGMCU_APB2_FZ DBG_TIM11_STOP LL_DBGMCU_APB2_GRP1_UnFreezePeriph - * @param Periphs This parameter can be a combination of the following values: - * @arg @ref LL_DBGMCU_APB2_GRP1_TIM1_STOP - * @arg @ref LL_DBGMCU_APB2_GRP1_TIM8_STOP (*) - * @arg @ref LL_DBGMCU_APB2_GRP1_TIM9_STOP (*) - * @arg @ref LL_DBGMCU_APB2_GRP1_TIM10_STOP (*) - * @arg @ref LL_DBGMCU_APB2_GRP1_TIM11_STOP (*) - * - * (*) value not defined in all devices. - * @retval None - */ -__STATIC_INLINE void LL_DBGMCU_APB2_GRP1_UnFreezePeriph(uint32_t Periphs) -{ - CLEAR_BIT(DBGMCU->APB2FZ, Periphs); -} -/** - * @} - */ - -/** @defgroup SYSTEM_LL_EF_FLASH FLASH - * @{ - */ - -/** - * @brief Set FLASH Latency - * @rmtoll FLASH_ACR LATENCY LL_FLASH_SetLatency - * @param Latency This parameter can be one of the following values: - * @arg @ref LL_FLASH_LATENCY_0 - * @arg @ref LL_FLASH_LATENCY_1 - * @arg @ref LL_FLASH_LATENCY_2 - * @arg @ref LL_FLASH_LATENCY_3 - * @arg @ref LL_FLASH_LATENCY_4 - * @arg @ref LL_FLASH_LATENCY_5 - * @arg @ref LL_FLASH_LATENCY_6 - * @arg @ref LL_FLASH_LATENCY_7 - * @arg @ref LL_FLASH_LATENCY_8 - * @arg @ref LL_FLASH_LATENCY_9 - * @arg @ref LL_FLASH_LATENCY_10 - * @arg @ref LL_FLASH_LATENCY_11 - * @arg @ref LL_FLASH_LATENCY_12 - * @arg @ref LL_FLASH_LATENCY_13 - * @arg @ref LL_FLASH_LATENCY_14 - * @arg @ref LL_FLASH_LATENCY_15 - * @retval None - */ -__STATIC_INLINE void LL_FLASH_SetLatency(uint32_t Latency) -{ - MODIFY_REG(FLASH->ACR, FLASH_ACR_LATENCY, Latency); -} - -/** - * @brief Get FLASH Latency - * @rmtoll FLASH_ACR LATENCY LL_FLASH_GetLatency - * @retval Returned value can be one of the following values: - * @arg @ref LL_FLASH_LATENCY_0 - * @arg @ref LL_FLASH_LATENCY_1 - * @arg @ref LL_FLASH_LATENCY_2 - * @arg @ref LL_FLASH_LATENCY_3 - * @arg @ref LL_FLASH_LATENCY_4 - * @arg @ref LL_FLASH_LATENCY_5 - * @arg @ref LL_FLASH_LATENCY_6 - * @arg @ref LL_FLASH_LATENCY_7 - * @arg @ref LL_FLASH_LATENCY_8 - * @arg @ref LL_FLASH_LATENCY_9 - * @arg @ref LL_FLASH_LATENCY_10 - * @arg @ref LL_FLASH_LATENCY_11 - * @arg @ref LL_FLASH_LATENCY_12 - * @arg @ref LL_FLASH_LATENCY_13 - * @arg @ref LL_FLASH_LATENCY_14 - * @arg @ref LL_FLASH_LATENCY_15 - */ -__STATIC_INLINE uint32_t LL_FLASH_GetLatency(void) -{ - return (uint32_t)(READ_BIT(FLASH->ACR, FLASH_ACR_LATENCY)); -} - -/** - * @brief Enable Prefetch - * @rmtoll FLASH_ACR PRFTEN LL_FLASH_EnablePrefetch - * @retval None - */ -__STATIC_INLINE void LL_FLASH_EnablePrefetch(void) -{ - SET_BIT(FLASH->ACR, FLASH_ACR_PRFTEN); -} - -/** - * @brief Disable Prefetch - * @rmtoll FLASH_ACR PRFTEN LL_FLASH_DisablePrefetch - * @retval None - */ -__STATIC_INLINE void LL_FLASH_DisablePrefetch(void) -{ - CLEAR_BIT(FLASH->ACR, FLASH_ACR_PRFTEN); -} - -/** - * @brief Check if Prefetch buffer is enabled - * @rmtoll FLASH_ACR PRFTEN LL_FLASH_IsPrefetchEnabled - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_FLASH_IsPrefetchEnabled(void) -{ - return (READ_BIT(FLASH->ACR, FLASH_ACR_PRFTEN) == (FLASH_ACR_PRFTEN)); -} - -/** - * @brief Enable Instruction cache - * @rmtoll FLASH_ACR ICEN LL_FLASH_EnableInstCache - * @retval None - */ -__STATIC_INLINE void LL_FLASH_EnableInstCache(void) -{ - SET_BIT(FLASH->ACR, FLASH_ACR_ICEN); -} - -/** - * @brief Disable Instruction cache - * @rmtoll FLASH_ACR ICEN LL_FLASH_DisableInstCache - * @retval None - */ -__STATIC_INLINE void LL_FLASH_DisableInstCache(void) -{ - CLEAR_BIT(FLASH->ACR, FLASH_ACR_ICEN); -} - -/** - * @brief Enable Data cache - * @rmtoll FLASH_ACR DCEN LL_FLASH_EnableDataCache - * @retval None - */ -__STATIC_INLINE void LL_FLASH_EnableDataCache(void) -{ - SET_BIT(FLASH->ACR, FLASH_ACR_DCEN); -} - -/** - * @brief Disable Data cache - * @rmtoll FLASH_ACR DCEN LL_FLASH_DisableDataCache - * @retval None - */ -__STATIC_INLINE void LL_FLASH_DisableDataCache(void) -{ - CLEAR_BIT(FLASH->ACR, FLASH_ACR_DCEN); -} - -/** - * @brief Enable Instruction cache reset - * @note bit can be written only when the instruction cache is disabled - * @rmtoll FLASH_ACR ICRST LL_FLASH_EnableInstCacheReset - * @retval None - */ -__STATIC_INLINE void LL_FLASH_EnableInstCacheReset(void) -{ - SET_BIT(FLASH->ACR, FLASH_ACR_ICRST); -} - -/** - * @brief Disable Instruction cache reset - * @rmtoll FLASH_ACR ICRST LL_FLASH_DisableInstCacheReset - * @retval None - */ -__STATIC_INLINE void LL_FLASH_DisableInstCacheReset(void) -{ - CLEAR_BIT(FLASH->ACR, FLASH_ACR_ICRST); -} - -/** - * @brief Enable Data cache reset - * @note bit can be written only when the data cache is disabled - * @rmtoll FLASH_ACR DCRST LL_FLASH_EnableDataCacheReset - * @retval None - */ -__STATIC_INLINE void LL_FLASH_EnableDataCacheReset(void) -{ - SET_BIT(FLASH->ACR, FLASH_ACR_DCRST); -} - -/** - * @brief Disable Data cache reset - * @rmtoll FLASH_ACR DCRST LL_FLASH_DisableDataCacheReset - * @retval None - */ -__STATIC_INLINE void LL_FLASH_DisableDataCacheReset(void) -{ - CLEAR_BIT(FLASH->ACR, FLASH_ACR_DCRST); -} - - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* defined (FLASH) || defined (SYSCFG) || defined (DBGMCU) */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_SYSTEM_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_tim.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_tim.h deleted file mode 100644 index 3f83c98..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_tim.h +++ /dev/null @@ -1,4095 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_tim.h - * @author MCD Application Team - * @brief Header file of TIM LL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_LL_TIM_H -#define __STM32F4xx_LL_TIM_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (TIM1) || defined (TIM2) || defined (TIM3) || defined (TIM4) || defined (TIM5) || defined (TIM6) || defined (TIM7) || defined (TIM8) || defined (TIM9) || defined (TIM10) || defined (TIM11) || defined (TIM12) || defined (TIM13) || defined (TIM14) - -/** @defgroup TIM_LL TIM - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/** @defgroup TIM_LL_Private_Variables TIM Private Variables - * @{ - */ -static const uint8_t OFFSET_TAB_CCMRx[] = -{ - 0x00U, /* 0: TIMx_CH1 */ - 0x00U, /* 1: TIMx_CH1N */ - 0x00U, /* 2: TIMx_CH2 */ - 0x00U, /* 3: TIMx_CH2N */ - 0x04U, /* 4: TIMx_CH3 */ - 0x04U, /* 5: TIMx_CH3N */ - 0x04U /* 6: TIMx_CH4 */ -}; - -static const uint8_t SHIFT_TAB_OCxx[] = -{ - 0U, /* 0: OC1M, OC1FE, OC1PE */ - 0U, /* 1: - NA */ - 8U, /* 2: OC2M, OC2FE, OC2PE */ - 0U, /* 3: - NA */ - 0U, /* 4: OC3M, OC3FE, OC3PE */ - 0U, /* 5: - NA */ - 8U /* 6: OC4M, OC4FE, OC4PE */ -}; - -static const uint8_t SHIFT_TAB_ICxx[] = -{ - 0U, /* 0: CC1S, IC1PSC, IC1F */ - 0U, /* 1: - NA */ - 8U, /* 2: CC2S, IC2PSC, IC2F */ - 0U, /* 3: - NA */ - 0U, /* 4: CC3S, IC3PSC, IC3F */ - 0U, /* 5: - NA */ - 8U /* 6: CC4S, IC4PSC, IC4F */ -}; - -static const uint8_t SHIFT_TAB_CCxP[] = -{ - 0U, /* 0: CC1P */ - 2U, /* 1: CC1NP */ - 4U, /* 2: CC2P */ - 6U, /* 3: CC2NP */ - 8U, /* 4: CC3P */ - 10U, /* 5: CC3NP */ - 12U /* 6: CC4P */ -}; - -static const uint8_t SHIFT_TAB_OISx[] = -{ - 0U, /* 0: OIS1 */ - 1U, /* 1: OIS1N */ - 2U, /* 2: OIS2 */ - 3U, /* 3: OIS2N */ - 4U, /* 4: OIS3 */ - 5U, /* 5: OIS3N */ - 6U /* 6: OIS4 */ -}; -/** - * @} - */ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup TIM_LL_Private_Constants TIM Private Constants - * @{ - */ - - -/* Remap mask definitions */ -#define TIMx_OR_RMP_SHIFT 16U -#define TIMx_OR_RMP_MASK 0x0000FFFFU -#define TIM2_OR_RMP_MASK (TIM_OR_ITR1_RMP << TIMx_OR_RMP_SHIFT) -#define TIM5_OR_RMP_MASK (TIM_OR_TI4_RMP << TIMx_OR_RMP_SHIFT) -#define TIM11_OR_RMP_MASK (TIM_OR_TI1_RMP << TIMx_OR_RMP_SHIFT) - -/* Mask used to set the TDG[x:0] of the DTG bits of the TIMx_BDTR register */ -#define DT_DELAY_1 ((uint8_t)0x7F) -#define DT_DELAY_2 ((uint8_t)0x3F) -#define DT_DELAY_3 ((uint8_t)0x1F) -#define DT_DELAY_4 ((uint8_t)0x1F) - -/* Mask used to set the DTG[7:5] bits of the DTG bits of the TIMx_BDTR register */ -#define DT_RANGE_1 ((uint8_t)0x00) -#define DT_RANGE_2 ((uint8_t)0x80) -#define DT_RANGE_3 ((uint8_t)0xC0) -#define DT_RANGE_4 ((uint8_t)0xE0) - - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup TIM_LL_Private_Macros TIM Private Macros - * @{ - */ -/** @brief Convert channel id into channel index. - * @param __CHANNEL__ This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH1N - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH2N - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH3N - * @arg @ref LL_TIM_CHANNEL_CH4 - * @retval none - */ -#define TIM_GET_CHANNEL_INDEX( __CHANNEL__) \ - (((__CHANNEL__) == LL_TIM_CHANNEL_CH1) ? 0U :\ - ((__CHANNEL__) == LL_TIM_CHANNEL_CH1N) ? 1U :\ - ((__CHANNEL__) == LL_TIM_CHANNEL_CH2) ? 2U :\ - ((__CHANNEL__) == LL_TIM_CHANNEL_CH2N) ? 3U :\ - ((__CHANNEL__) == LL_TIM_CHANNEL_CH3) ? 4U :\ - ((__CHANNEL__) == LL_TIM_CHANNEL_CH3N) ? 5U : 6U) - -/** @brief Calculate the deadtime sampling period(in ps). - * @param __TIMCLK__ timer input clock frequency (in Hz). - * @param __CKD__ This parameter can be one of the following values: - * @arg @ref LL_TIM_CLOCKDIVISION_DIV1 - * @arg @ref LL_TIM_CLOCKDIVISION_DIV2 - * @arg @ref LL_TIM_CLOCKDIVISION_DIV4 - * @retval none - */ -#define TIM_CALC_DTS(__TIMCLK__, __CKD__) \ - (((__CKD__) == LL_TIM_CLOCKDIVISION_DIV1) ? ((uint64_t)1000000000000U/(__TIMCLK__)) : \ - ((__CKD__) == LL_TIM_CLOCKDIVISION_DIV2) ? ((uint64_t)1000000000000U/((__TIMCLK__) >> 1U)) : \ - ((uint64_t)1000000000000U/((__TIMCLK__) >> 2U))) -/** - * @} - */ - - -/* Exported types ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup TIM_LL_ES_INIT TIM Exported Init structure - * @{ - */ - -/** - * @brief TIM Time Base configuration structure definition. - */ -typedef struct -{ - uint16_t Prescaler; /*!< Specifies the prescaler value used to divide the TIM clock. - This parameter can be a number between Min_Data=0x0000 and Max_Data=0xFFFF. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_SetPrescaler().*/ - - uint32_t CounterMode; /*!< Specifies the counter mode. - This parameter can be a value of @ref TIM_LL_EC_COUNTERMODE. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_SetCounterMode().*/ - - uint32_t Autoreload; /*!< Specifies the auto reload value to be loaded into the active - Auto-Reload Register at the next update event. - This parameter must be a number between Min_Data=0x0000 and Max_Data=0xFFFF. - Some timer instances may support 32 bits counters. In that case this parameter must - be a number between 0x0000 and 0xFFFFFFFF. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_SetAutoReload().*/ - - uint32_t ClockDivision; /*!< Specifies the clock division. - This parameter can be a value of @ref TIM_LL_EC_CLOCKDIVISION. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_SetClockDivision().*/ - - uint32_t RepetitionCounter; /*!< Specifies the repetition counter value. Each time the RCR downcounter - reaches zero, an update event is generated and counting restarts - from the RCR value (N). - This means in PWM mode that (N+1) corresponds to: - - the number of PWM periods in edge-aligned mode - - the number of half PWM period in center-aligned mode - GP timers: this parameter must be a number between Min_Data = 0x00 and - Max_Data = 0xFF. - Advanced timers: this parameter must be a number between Min_Data = 0x0000 and - Max_Data = 0xFFFF. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_SetRepetitionCounter().*/ -} LL_TIM_InitTypeDef; - -/** - * @brief TIM Output Compare configuration structure definition. - */ -typedef struct -{ - uint32_t OCMode; /*!< Specifies the output mode. - This parameter can be a value of @ref TIM_LL_EC_OCMODE. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_OC_SetMode().*/ - - uint32_t OCState; /*!< Specifies the TIM Output Compare state. - This parameter can be a value of @ref TIM_LL_EC_OCSTATE. - - This feature can be modified afterwards using unitary functions - @ref LL_TIM_CC_EnableChannel() or @ref LL_TIM_CC_DisableChannel().*/ - - uint32_t OCNState; /*!< Specifies the TIM complementary Output Compare state. - This parameter can be a value of @ref TIM_LL_EC_OCSTATE. - - This feature can be modified afterwards using unitary functions - @ref LL_TIM_CC_EnableChannel() or @ref LL_TIM_CC_DisableChannel().*/ - - uint32_t CompareValue; /*!< Specifies the Compare value to be loaded into the Capture Compare Register. - This parameter can be a number between Min_Data=0x0000 and Max_Data=0xFFFF. - - This feature can be modified afterwards using unitary function - LL_TIM_OC_SetCompareCHx (x=1..6).*/ - - uint32_t OCPolarity; /*!< Specifies the output polarity. - This parameter can be a value of @ref TIM_LL_EC_OCPOLARITY. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_OC_SetPolarity().*/ - - uint32_t OCNPolarity; /*!< Specifies the complementary output polarity. - This parameter can be a value of @ref TIM_LL_EC_OCPOLARITY. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_OC_SetPolarity().*/ - - - uint32_t OCIdleState; /*!< Specifies the TIM Output Compare pin state during Idle state. - This parameter can be a value of @ref TIM_LL_EC_OCIDLESTATE. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_OC_SetIdleState().*/ - - uint32_t OCNIdleState; /*!< Specifies the TIM Output Compare pin state during Idle state. - This parameter can be a value of @ref TIM_LL_EC_OCIDLESTATE. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_OC_SetIdleState().*/ -} LL_TIM_OC_InitTypeDef; - -/** - * @brief TIM Input Capture configuration structure definition. - */ - -typedef struct -{ - - uint32_t ICPolarity; /*!< Specifies the active edge of the input signal. - This parameter can be a value of @ref TIM_LL_EC_IC_POLARITY. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_IC_SetPolarity().*/ - - uint32_t ICActiveInput; /*!< Specifies the input. - This parameter can be a value of @ref TIM_LL_EC_ACTIVEINPUT. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_IC_SetActiveInput().*/ - - uint32_t ICPrescaler; /*!< Specifies the Input Capture Prescaler. - This parameter can be a value of @ref TIM_LL_EC_ICPSC. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_IC_SetPrescaler().*/ - - uint32_t ICFilter; /*!< Specifies the input capture filter. - This parameter can be a value of @ref TIM_LL_EC_IC_FILTER. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_IC_SetFilter().*/ -} LL_TIM_IC_InitTypeDef; - - -/** - * @brief TIM Encoder interface configuration structure definition. - */ -typedef struct -{ - uint32_t EncoderMode; /*!< Specifies the encoder resolution (x2 or x4). - This parameter can be a value of @ref TIM_LL_EC_ENCODERMODE. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_SetEncoderMode().*/ - - uint32_t IC1Polarity; /*!< Specifies the active edge of TI1 input. - This parameter can be a value of @ref TIM_LL_EC_IC_POLARITY. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_IC_SetPolarity().*/ - - uint32_t IC1ActiveInput; /*!< Specifies the TI1 input source - This parameter can be a value of @ref TIM_LL_EC_ACTIVEINPUT. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_IC_SetActiveInput().*/ - - uint32_t IC1Prescaler; /*!< Specifies the TI1 input prescaler value. - This parameter can be a value of @ref TIM_LL_EC_ICPSC. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_IC_SetPrescaler().*/ - - uint32_t IC1Filter; /*!< Specifies the TI1 input filter. - This parameter can be a value of @ref TIM_LL_EC_IC_FILTER. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_IC_SetFilter().*/ - - uint32_t IC2Polarity; /*!< Specifies the active edge of TI2 input. - This parameter can be a value of @ref TIM_LL_EC_IC_POLARITY. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_IC_SetPolarity().*/ - - uint32_t IC2ActiveInput; /*!< Specifies the TI2 input source - This parameter can be a value of @ref TIM_LL_EC_ACTIVEINPUT. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_IC_SetActiveInput().*/ - - uint32_t IC2Prescaler; /*!< Specifies the TI2 input prescaler value. - This parameter can be a value of @ref TIM_LL_EC_ICPSC. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_IC_SetPrescaler().*/ - - uint32_t IC2Filter; /*!< Specifies the TI2 input filter. - This parameter can be a value of @ref TIM_LL_EC_IC_FILTER. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_IC_SetFilter().*/ - -} LL_TIM_ENCODER_InitTypeDef; - -/** - * @brief TIM Hall sensor interface configuration structure definition. - */ -typedef struct -{ - - uint32_t IC1Polarity; /*!< Specifies the active edge of TI1 input. - This parameter can be a value of @ref TIM_LL_EC_IC_POLARITY. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_IC_SetPolarity().*/ - - uint32_t IC1Prescaler; /*!< Specifies the TI1 input prescaler value. - Prescaler must be set to get a maximum counter period longer than the - time interval between 2 consecutive changes on the Hall inputs. - This parameter can be a value of @ref TIM_LL_EC_ICPSC. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_IC_SetPrescaler().*/ - - uint32_t IC1Filter; /*!< Specifies the TI1 input filter. - This parameter can be a value of - @ref TIM_LL_EC_IC_FILTER. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_IC_SetFilter().*/ - - uint32_t CommutationDelay; /*!< Specifies the compare value to be loaded into the Capture Compare Register. - A positive pulse (TRGO event) is generated with a programmable delay every time - a change occurs on the Hall inputs. - This parameter can be a number between Min_Data = 0x0000 and Max_Data = 0xFFFF. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_OC_SetCompareCH2().*/ -} LL_TIM_HALLSENSOR_InitTypeDef; - -/** - * @brief BDTR (Break and Dead Time) structure definition - */ -typedef struct -{ - uint32_t OSSRState; /*!< Specifies the Off-State selection used in Run mode. - This parameter can be a value of @ref TIM_LL_EC_OSSR - - This feature can be modified afterwards using unitary function - @ref LL_TIM_SetOffStates() - - @note This bit-field cannot be modified as long as LOCK level 2 has been - programmed. */ - - uint32_t OSSIState; /*!< Specifies the Off-State used in Idle state. - This parameter can be a value of @ref TIM_LL_EC_OSSI - - This feature can be modified afterwards using unitary function - @ref LL_TIM_SetOffStates() - - @note This bit-field cannot be modified as long as LOCK level 2 has been - programmed. */ - - uint32_t LockLevel; /*!< Specifies the LOCK level parameters. - This parameter can be a value of @ref TIM_LL_EC_LOCKLEVEL - - @note The LOCK bits can be written only once after the reset. Once the TIMx_BDTR - register has been written, their content is frozen until the next reset.*/ - - uint8_t DeadTime; /*!< Specifies the delay time between the switching-off and the - switching-on of the outputs. - This parameter can be a number between Min_Data = 0x00 and Max_Data = 0xFF. - - This feature can be modified afterwards using unitary function - @ref LL_TIM_OC_SetDeadTime() - - @note This bit-field can not be modified as long as LOCK level 1, 2 or 3 has been - programmed. */ - - uint16_t BreakState; /*!< Specifies whether the TIM Break input is enabled or not. - This parameter can be a value of @ref TIM_LL_EC_BREAK_ENABLE - - This feature can be modified afterwards using unitary functions - @ref LL_TIM_EnableBRK() or @ref LL_TIM_DisableBRK() - - @note This bit-field can not be modified as long as LOCK level 1 has been - programmed. */ - - uint32_t BreakPolarity; /*!< Specifies the TIM Break Input pin polarity. - This parameter can be a value of @ref TIM_LL_EC_BREAK_POLARITY - - This feature can be modified afterwards using unitary function - @ref LL_TIM_ConfigBRK() - - @note This bit-field can not be modified as long as LOCK level 1 has been - programmed. */ - - uint32_t AutomaticOutput; /*!< Specifies whether the TIM Automatic Output feature is enabled or not. - This parameter can be a value of @ref TIM_LL_EC_AUTOMATICOUTPUT_ENABLE - - This feature can be modified afterwards using unitary functions - @ref LL_TIM_EnableAutomaticOutput() or @ref LL_TIM_DisableAutomaticOutput() - - @note This bit-field can not be modified as long as LOCK level 1 has been - programmed. */ -} LL_TIM_BDTR_InitTypeDef; - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup TIM_LL_Exported_Constants TIM Exported Constants - * @{ - */ - -/** @defgroup TIM_LL_EC_GET_FLAG Get Flags Defines - * @brief Flags defines which can be used with LL_TIM_ReadReg function. - * @{ - */ -#define LL_TIM_SR_UIF TIM_SR_UIF /*!< Update interrupt flag */ -#define LL_TIM_SR_CC1IF TIM_SR_CC1IF /*!< Capture/compare 1 interrupt flag */ -#define LL_TIM_SR_CC2IF TIM_SR_CC2IF /*!< Capture/compare 2 interrupt flag */ -#define LL_TIM_SR_CC3IF TIM_SR_CC3IF /*!< Capture/compare 3 interrupt flag */ -#define LL_TIM_SR_CC4IF TIM_SR_CC4IF /*!< Capture/compare 4 interrupt flag */ -#define LL_TIM_SR_COMIF TIM_SR_COMIF /*!< COM interrupt flag */ -#define LL_TIM_SR_TIF TIM_SR_TIF /*!< Trigger interrupt flag */ -#define LL_TIM_SR_BIF TIM_SR_BIF /*!< Break interrupt flag */ -#define LL_TIM_SR_CC1OF TIM_SR_CC1OF /*!< Capture/Compare 1 overcapture flag */ -#define LL_TIM_SR_CC2OF TIM_SR_CC2OF /*!< Capture/Compare 2 overcapture flag */ -#define LL_TIM_SR_CC3OF TIM_SR_CC3OF /*!< Capture/Compare 3 overcapture flag */ -#define LL_TIM_SR_CC4OF TIM_SR_CC4OF /*!< Capture/Compare 4 overcapture flag */ -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup TIM_LL_EC_BREAK_ENABLE Break Enable - * @{ - */ -#define LL_TIM_BREAK_DISABLE 0x00000000U /*!< Break function disabled */ -#define LL_TIM_BREAK_ENABLE TIM_BDTR_BKE /*!< Break function enabled */ -/** - * @} - */ - -/** @defgroup TIM_LL_EC_AUTOMATICOUTPUT_ENABLE Automatic output enable - * @{ - */ -#define LL_TIM_AUTOMATICOUTPUT_DISABLE 0x00000000U /*!< MOE can be set only by software */ -#define LL_TIM_AUTOMATICOUTPUT_ENABLE TIM_BDTR_AOE /*!< MOE can be set by software or automatically at the next update event */ -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** @defgroup TIM_LL_EC_IT IT Defines - * @brief IT defines which can be used with LL_TIM_ReadReg and LL_TIM_WriteReg functions. - * @{ - */ -#define LL_TIM_DIER_UIE TIM_DIER_UIE /*!< Update interrupt enable */ -#define LL_TIM_DIER_CC1IE TIM_DIER_CC1IE /*!< Capture/compare 1 interrupt enable */ -#define LL_TIM_DIER_CC2IE TIM_DIER_CC2IE /*!< Capture/compare 2 interrupt enable */ -#define LL_TIM_DIER_CC3IE TIM_DIER_CC3IE /*!< Capture/compare 3 interrupt enable */ -#define LL_TIM_DIER_CC4IE TIM_DIER_CC4IE /*!< Capture/compare 4 interrupt enable */ -#define LL_TIM_DIER_COMIE TIM_DIER_COMIE /*!< COM interrupt enable */ -#define LL_TIM_DIER_TIE TIM_DIER_TIE /*!< Trigger interrupt enable */ -#define LL_TIM_DIER_BIE TIM_DIER_BIE /*!< Break interrupt enable */ -/** - * @} - */ - -/** @defgroup TIM_LL_EC_UPDATESOURCE Update Source - * @{ - */ -#define LL_TIM_UPDATESOURCE_REGULAR 0x00000000U /*!< Counter overflow/underflow, Setting the UG bit or Update generation through the slave mode controller generates an update request */ -#define LL_TIM_UPDATESOURCE_COUNTER TIM_CR1_URS /*!< Only counter overflow/underflow generates an update request */ -/** - * @} - */ - -/** @defgroup TIM_LL_EC_ONEPULSEMODE One Pulse Mode - * @{ - */ -#define LL_TIM_ONEPULSEMODE_SINGLE TIM_CR1_OPM /*!< Counter stops counting at the next update event */ -#define LL_TIM_ONEPULSEMODE_REPETITIVE 0x00000000U /*!< Counter is not stopped at update event */ -/** - * @} - */ - -/** @defgroup TIM_LL_EC_COUNTERMODE Counter Mode - * @{ - */ -#define LL_TIM_COUNTERMODE_UP 0x00000000U /*!TIMx_CCRy else active.*/ -#define LL_TIM_OCMODE_PWM2 (TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1M_1 | TIM_CCMR1_OC1M_0) /*!TIMx_CCRy else inactive*/ -/** - * @} - */ - -/** @defgroup TIM_LL_EC_OCPOLARITY Output Configuration Polarity - * @{ - */ -#define LL_TIM_OCPOLARITY_HIGH 0x00000000U /*!< OCxactive high*/ -#define LL_TIM_OCPOLARITY_LOW TIM_CCER_CC1P /*!< OCxactive low*/ -/** - * @} - */ - -/** @defgroup TIM_LL_EC_OCIDLESTATE Output Configuration Idle State - * @{ - */ -#define LL_TIM_OCIDLESTATE_LOW 0x00000000U /*!__REG__, (__VALUE__)) - -/** - * @brief Read a value in TIM register. - * @param __INSTANCE__ TIM Instance - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_TIM_ReadReg(__INSTANCE__, __REG__) READ_REG((__INSTANCE__)->__REG__) -/** - * @} - */ - -/** @defgroup TIM_LL_EM_Exported_Macros Exported_Macros - * @{ - */ - -/** - * @brief HELPER macro calculating DTG[0:7] in the TIMx_BDTR register to achieve the requested dead time duration. - * @note ex: @ref __LL_TIM_CALC_DEADTIME (80000000, @ref LL_TIM_GetClockDivision (), 120); - * @param __TIMCLK__ timer input clock frequency (in Hz) - * @param __CKD__ This parameter can be one of the following values: - * @arg @ref LL_TIM_CLOCKDIVISION_DIV1 - * @arg @ref LL_TIM_CLOCKDIVISION_DIV2 - * @arg @ref LL_TIM_CLOCKDIVISION_DIV4 - * @param __DT__ deadtime duration (in ns) - * @retval DTG[0:7] - */ -#define __LL_TIM_CALC_DEADTIME(__TIMCLK__, __CKD__, __DT__) \ - ( (((uint64_t)((__DT__)*1000U)) < ((DT_DELAY_1+1U) * TIM_CALC_DTS((__TIMCLK__), (__CKD__)))) ? \ - (uint8_t)(((uint64_t)((__DT__)*1000U) / TIM_CALC_DTS((__TIMCLK__), (__CKD__))) & DT_DELAY_1) : \ - (((uint64_t)((__DT__)*1000U)) < ((64U + (DT_DELAY_2+1U)) * 2U * TIM_CALC_DTS((__TIMCLK__), (__CKD__)))) ? \ - (uint8_t)(DT_RANGE_2 | ((uint8_t)((uint8_t)((((uint64_t)((__DT__)*1000U))/ TIM_CALC_DTS((__TIMCLK__), \ - (__CKD__))) >> 1U) - (uint8_t) 64) & DT_DELAY_2)) :\ - (((uint64_t)((__DT__)*1000U)) < ((32U + (DT_DELAY_3+1U)) * 8U * TIM_CALC_DTS((__TIMCLK__), (__CKD__)))) ? \ - (uint8_t)(DT_RANGE_3 | ((uint8_t)((uint8_t)(((((uint64_t)(__DT__)*1000U))/ TIM_CALC_DTS((__TIMCLK__), \ - (__CKD__))) >> 3U) - (uint8_t) 32) & DT_DELAY_3)) :\ - (((uint64_t)((__DT__)*1000U)) < ((32U + (DT_DELAY_4+1U)) * 16U * TIM_CALC_DTS((__TIMCLK__), (__CKD__)))) ? \ - (uint8_t)(DT_RANGE_4 | ((uint8_t)((uint8_t)(((((uint64_t)(__DT__)*1000U))/ TIM_CALC_DTS((__TIMCLK__), \ - (__CKD__))) >> 4U) - (uint8_t) 32) & DT_DELAY_4)) :\ - 0U) - -/** - * @brief HELPER macro calculating the prescaler value to achieve the required counter clock frequency. - * @note ex: @ref __LL_TIM_CALC_PSC (80000000, 1000000); - * @param __TIMCLK__ timer input clock frequency (in Hz) - * @param __CNTCLK__ counter clock frequency (in Hz) - * @retval Prescaler value (between Min_Data=0 and Max_Data=65535) - */ -#define __LL_TIM_CALC_PSC(__TIMCLK__, __CNTCLK__) \ - (((__TIMCLK__) >= (__CNTCLK__)) ? (uint32_t)(((__TIMCLK__)/(__CNTCLK__)) - 1U) : 0U) - -/** - * @brief HELPER macro calculating the auto-reload value to achieve the required output signal frequency. - * @note ex: @ref __LL_TIM_CALC_ARR (1000000, @ref LL_TIM_GetPrescaler (), 10000); - * @param __TIMCLK__ timer input clock frequency (in Hz) - * @param __PSC__ prescaler - * @param __FREQ__ output signal frequency (in Hz) - * @retval Auto-reload value (between Min_Data=0 and Max_Data=65535) - */ -#define __LL_TIM_CALC_ARR(__TIMCLK__, __PSC__, __FREQ__) \ - ((((__TIMCLK__)/((__PSC__) + 1U)) >= (__FREQ__)) ? (((__TIMCLK__)/((__FREQ__) * ((__PSC__) + 1U))) - 1U) : 0U) - -/** - * @brief HELPER macro calculating the compare value required to achieve the required timer output compare - * active/inactive delay. - * @note ex: @ref __LL_TIM_CALC_DELAY (1000000, @ref LL_TIM_GetPrescaler (), 10); - * @param __TIMCLK__ timer input clock frequency (in Hz) - * @param __PSC__ prescaler - * @param __DELAY__ timer output compare active/inactive delay (in us) - * @retval Compare value (between Min_Data=0 and Max_Data=65535) - */ -#define __LL_TIM_CALC_DELAY(__TIMCLK__, __PSC__, __DELAY__) \ - ((uint32_t)(((uint64_t)(__TIMCLK__) * (uint64_t)(__DELAY__)) \ - / ((uint64_t)1000000U * (uint64_t)((__PSC__) + 1U)))) - -/** - * @brief HELPER macro calculating the auto-reload value to achieve the required pulse duration - * (when the timer operates in one pulse mode). - * @note ex: @ref __LL_TIM_CALC_PULSE (1000000, @ref LL_TIM_GetPrescaler (), 10, 20); - * @param __TIMCLK__ timer input clock frequency (in Hz) - * @param __PSC__ prescaler - * @param __DELAY__ timer output compare active/inactive delay (in us) - * @param __PULSE__ pulse duration (in us) - * @retval Auto-reload value (between Min_Data=0 and Max_Data=65535) - */ -#define __LL_TIM_CALC_PULSE(__TIMCLK__, __PSC__, __DELAY__, __PULSE__) \ - ((uint32_t)(__LL_TIM_CALC_DELAY((__TIMCLK__), (__PSC__), (__PULSE__)) \ - + __LL_TIM_CALC_DELAY((__TIMCLK__), (__PSC__), (__DELAY__)))) - -/** - * @brief HELPER macro retrieving the ratio of the input capture prescaler - * @note ex: @ref __LL_TIM_GET_ICPSC_RATIO (@ref LL_TIM_IC_GetPrescaler ()); - * @param __ICPSC__ This parameter can be one of the following values: - * @arg @ref LL_TIM_ICPSC_DIV1 - * @arg @ref LL_TIM_ICPSC_DIV2 - * @arg @ref LL_TIM_ICPSC_DIV4 - * @arg @ref LL_TIM_ICPSC_DIV8 - * @retval Input capture prescaler ratio (1, 2, 4 or 8) - */ -#define __LL_TIM_GET_ICPSC_RATIO(__ICPSC__) \ - ((uint32_t)(0x01U << (((__ICPSC__) >> 16U) >> TIM_CCMR1_IC1PSC_Pos))) - - -/** - * @} - */ - - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup TIM_LL_Exported_Functions TIM Exported Functions - * @{ - */ - -/** @defgroup TIM_LL_EF_Time_Base Time Base configuration - * @{ - */ -/** - * @brief Enable timer counter. - * @rmtoll CR1 CEN LL_TIM_EnableCounter - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableCounter(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->CR1, TIM_CR1_CEN); -} - -/** - * @brief Disable timer counter. - * @rmtoll CR1 CEN LL_TIM_DisableCounter - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableCounter(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->CR1, TIM_CR1_CEN); -} - -/** - * @brief Indicates whether the timer counter is enabled. - * @rmtoll CR1 CEN LL_TIM_IsEnabledCounter - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsEnabledCounter(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->CR1, TIM_CR1_CEN) == (TIM_CR1_CEN)) ? 1UL : 0UL); -} - -/** - * @brief Enable update event generation. - * @rmtoll CR1 UDIS LL_TIM_EnableUpdateEvent - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableUpdateEvent(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->CR1, TIM_CR1_UDIS); -} - -/** - * @brief Disable update event generation. - * @rmtoll CR1 UDIS LL_TIM_DisableUpdateEvent - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableUpdateEvent(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->CR1, TIM_CR1_UDIS); -} - -/** - * @brief Indicates whether update event generation is enabled. - * @rmtoll CR1 UDIS LL_TIM_IsEnabledUpdateEvent - * @param TIMx Timer instance - * @retval Inverted state of bit (0 or 1). - */ -__STATIC_INLINE uint32_t LL_TIM_IsEnabledUpdateEvent(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->CR1, TIM_CR1_UDIS) == (uint32_t)RESET) ? 1UL : 0UL); -} - -/** - * @brief Set update event source - * @note Update event source set to LL_TIM_UPDATESOURCE_REGULAR: any of the following events - * generate an update interrupt or DMA request if enabled: - * - Counter overflow/underflow - * - Setting the UG bit - * - Update generation through the slave mode controller - * @note Update event source set to LL_TIM_UPDATESOURCE_COUNTER: only counter - * overflow/underflow generates an update interrupt or DMA request if enabled. - * @rmtoll CR1 URS LL_TIM_SetUpdateSource - * @param TIMx Timer instance - * @param UpdateSource This parameter can be one of the following values: - * @arg @ref LL_TIM_UPDATESOURCE_REGULAR - * @arg @ref LL_TIM_UPDATESOURCE_COUNTER - * @retval None - */ -__STATIC_INLINE void LL_TIM_SetUpdateSource(TIM_TypeDef *TIMx, uint32_t UpdateSource) -{ - MODIFY_REG(TIMx->CR1, TIM_CR1_URS, UpdateSource); -} - -/** - * @brief Get actual event update source - * @rmtoll CR1 URS LL_TIM_GetUpdateSource - * @param TIMx Timer instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_TIM_UPDATESOURCE_REGULAR - * @arg @ref LL_TIM_UPDATESOURCE_COUNTER - */ -__STATIC_INLINE uint32_t LL_TIM_GetUpdateSource(TIM_TypeDef *TIMx) -{ - return (uint32_t)(READ_BIT(TIMx->CR1, TIM_CR1_URS)); -} - -/** - * @brief Set one pulse mode (one shot v.s. repetitive). - * @rmtoll CR1 OPM LL_TIM_SetOnePulseMode - * @param TIMx Timer instance - * @param OnePulseMode This parameter can be one of the following values: - * @arg @ref LL_TIM_ONEPULSEMODE_SINGLE - * @arg @ref LL_TIM_ONEPULSEMODE_REPETITIVE - * @retval None - */ -__STATIC_INLINE void LL_TIM_SetOnePulseMode(TIM_TypeDef *TIMx, uint32_t OnePulseMode) -{ - MODIFY_REG(TIMx->CR1, TIM_CR1_OPM, OnePulseMode); -} - -/** - * @brief Get actual one pulse mode. - * @rmtoll CR1 OPM LL_TIM_GetOnePulseMode - * @param TIMx Timer instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_TIM_ONEPULSEMODE_SINGLE - * @arg @ref LL_TIM_ONEPULSEMODE_REPETITIVE - */ -__STATIC_INLINE uint32_t LL_TIM_GetOnePulseMode(TIM_TypeDef *TIMx) -{ - return (uint32_t)(READ_BIT(TIMx->CR1, TIM_CR1_OPM)); -} - -/** - * @brief Set the timer counter counting mode. - * @note Macro IS_TIM_COUNTER_MODE_SELECT_INSTANCE(TIMx) can be used to - * check whether or not the counter mode selection feature is supported - * by a timer instance. - * @note Switching from Center Aligned counter mode to Edge counter mode (or reverse) - * requires a timer reset to avoid unexpected direction - * due to DIR bit readonly in center aligned mode. - * @rmtoll CR1 DIR LL_TIM_SetCounterMode\n - * CR1 CMS LL_TIM_SetCounterMode - * @param TIMx Timer instance - * @param CounterMode This parameter can be one of the following values: - * @arg @ref LL_TIM_COUNTERMODE_UP - * @arg @ref LL_TIM_COUNTERMODE_DOWN - * @arg @ref LL_TIM_COUNTERMODE_CENTER_UP - * @arg @ref LL_TIM_COUNTERMODE_CENTER_DOWN - * @arg @ref LL_TIM_COUNTERMODE_CENTER_UP_DOWN - * @retval None - */ -__STATIC_INLINE void LL_TIM_SetCounterMode(TIM_TypeDef *TIMx, uint32_t CounterMode) -{ - MODIFY_REG(TIMx->CR1, (TIM_CR1_DIR | TIM_CR1_CMS), CounterMode); -} - -/** - * @brief Get actual counter mode. - * @note Macro IS_TIM_COUNTER_MODE_SELECT_INSTANCE(TIMx) can be used to - * check whether or not the counter mode selection feature is supported - * by a timer instance. - * @rmtoll CR1 DIR LL_TIM_GetCounterMode\n - * CR1 CMS LL_TIM_GetCounterMode - * @param TIMx Timer instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_TIM_COUNTERMODE_UP - * @arg @ref LL_TIM_COUNTERMODE_DOWN - * @arg @ref LL_TIM_COUNTERMODE_CENTER_UP - * @arg @ref LL_TIM_COUNTERMODE_CENTER_DOWN - * @arg @ref LL_TIM_COUNTERMODE_CENTER_UP_DOWN - */ -__STATIC_INLINE uint32_t LL_TIM_GetCounterMode(TIM_TypeDef *TIMx) -{ - uint32_t counter_mode; - - counter_mode = (uint32_t)(READ_BIT(TIMx->CR1, TIM_CR1_CMS)); - - if (counter_mode == 0U) - { - counter_mode = (uint32_t)(READ_BIT(TIMx->CR1, TIM_CR1_DIR)); - } - - return counter_mode; -} - -/** - * @brief Enable auto-reload (ARR) preload. - * @rmtoll CR1 ARPE LL_TIM_EnableARRPreload - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableARRPreload(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->CR1, TIM_CR1_ARPE); -} - -/** - * @brief Disable auto-reload (ARR) preload. - * @rmtoll CR1 ARPE LL_TIM_DisableARRPreload - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableARRPreload(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->CR1, TIM_CR1_ARPE); -} - -/** - * @brief Indicates whether auto-reload (ARR) preload is enabled. - * @rmtoll CR1 ARPE LL_TIM_IsEnabledARRPreload - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsEnabledARRPreload(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->CR1, TIM_CR1_ARPE) == (TIM_CR1_ARPE)) ? 1UL : 0UL); -} - -/** - * @brief Set the division ratio between the timer clock and the sampling clock used by the dead-time generators - * (when supported) and the digital filters. - * @note Macro IS_TIM_CLOCK_DIVISION_INSTANCE(TIMx) can be used to check - * whether or not the clock division feature is supported by the timer - * instance. - * @rmtoll CR1 CKD LL_TIM_SetClockDivision - * @param TIMx Timer instance - * @param ClockDivision This parameter can be one of the following values: - * @arg @ref LL_TIM_CLOCKDIVISION_DIV1 - * @arg @ref LL_TIM_CLOCKDIVISION_DIV2 - * @arg @ref LL_TIM_CLOCKDIVISION_DIV4 - * @retval None - */ -__STATIC_INLINE void LL_TIM_SetClockDivision(TIM_TypeDef *TIMx, uint32_t ClockDivision) -{ - MODIFY_REG(TIMx->CR1, TIM_CR1_CKD, ClockDivision); -} - -/** - * @brief Get the actual division ratio between the timer clock and the sampling clock used by the dead-time - * generators (when supported) and the digital filters. - * @note Macro IS_TIM_CLOCK_DIVISION_INSTANCE(TIMx) can be used to check - * whether or not the clock division feature is supported by the timer - * instance. - * @rmtoll CR1 CKD LL_TIM_GetClockDivision - * @param TIMx Timer instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_TIM_CLOCKDIVISION_DIV1 - * @arg @ref LL_TIM_CLOCKDIVISION_DIV2 - * @arg @ref LL_TIM_CLOCKDIVISION_DIV4 - */ -__STATIC_INLINE uint32_t LL_TIM_GetClockDivision(TIM_TypeDef *TIMx) -{ - return (uint32_t)(READ_BIT(TIMx->CR1, TIM_CR1_CKD)); -} - -/** - * @brief Set the counter value. - * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports a 32 bits counter. - * @rmtoll CNT CNT LL_TIM_SetCounter - * @param TIMx Timer instance - * @param Counter Counter value (between Min_Data=0 and Max_Data=0xFFFF or 0xFFFFFFFF) - * @retval None - */ -__STATIC_INLINE void LL_TIM_SetCounter(TIM_TypeDef *TIMx, uint32_t Counter) -{ - WRITE_REG(TIMx->CNT, Counter); -} - -/** - * @brief Get the counter value. - * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports a 32 bits counter. - * @rmtoll CNT CNT LL_TIM_GetCounter - * @param TIMx Timer instance - * @retval Counter value (between Min_Data=0 and Max_Data=0xFFFF or 0xFFFFFFFF) - */ -__STATIC_INLINE uint32_t LL_TIM_GetCounter(TIM_TypeDef *TIMx) -{ - return (uint32_t)(READ_REG(TIMx->CNT)); -} - -/** - * @brief Get the current direction of the counter - * @rmtoll CR1 DIR LL_TIM_GetDirection - * @param TIMx Timer instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_TIM_COUNTERDIRECTION_UP - * @arg @ref LL_TIM_COUNTERDIRECTION_DOWN - */ -__STATIC_INLINE uint32_t LL_TIM_GetDirection(TIM_TypeDef *TIMx) -{ - return (uint32_t)(READ_BIT(TIMx->CR1, TIM_CR1_DIR)); -} - -/** - * @brief Set the prescaler value. - * @note The counter clock frequency CK_CNT is equal to fCK_PSC / (PSC[15:0] + 1). - * @note The prescaler can be changed on the fly as this control register is buffered. The new - * prescaler ratio is taken into account at the next update event. - * @note Helper macro @ref __LL_TIM_CALC_PSC can be used to calculate the Prescaler parameter - * @rmtoll PSC PSC LL_TIM_SetPrescaler - * @param TIMx Timer instance - * @param Prescaler between Min_Data=0 and Max_Data=65535 - * @retval None - */ -__STATIC_INLINE void LL_TIM_SetPrescaler(TIM_TypeDef *TIMx, uint32_t Prescaler) -{ - WRITE_REG(TIMx->PSC, Prescaler); -} - -/** - * @brief Get the prescaler value. - * @rmtoll PSC PSC LL_TIM_GetPrescaler - * @param TIMx Timer instance - * @retval Prescaler value between Min_Data=0 and Max_Data=65535 - */ -__STATIC_INLINE uint32_t LL_TIM_GetPrescaler(TIM_TypeDef *TIMx) -{ - return (uint32_t)(READ_REG(TIMx->PSC)); -} - -/** - * @brief Set the auto-reload value. - * @note The counter is blocked while the auto-reload value is null. - * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports a 32 bits counter. - * @note Helper macro @ref __LL_TIM_CALC_ARR can be used to calculate the AutoReload parameter - * @rmtoll ARR ARR LL_TIM_SetAutoReload - * @param TIMx Timer instance - * @param AutoReload between Min_Data=0 and Max_Data=65535 - * @retval None - */ -__STATIC_INLINE void LL_TIM_SetAutoReload(TIM_TypeDef *TIMx, uint32_t AutoReload) -{ - WRITE_REG(TIMx->ARR, AutoReload); -} - -/** - * @brief Get the auto-reload value. - * @rmtoll ARR ARR LL_TIM_GetAutoReload - * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports a 32 bits counter. - * @param TIMx Timer instance - * @retval Auto-reload value - */ -__STATIC_INLINE uint32_t LL_TIM_GetAutoReload(TIM_TypeDef *TIMx) -{ - return (uint32_t)(READ_REG(TIMx->ARR)); -} - -/** - * @brief Set the repetition counter value. - * @note Macro IS_TIM_REPETITION_COUNTER_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports a repetition counter. - * @rmtoll RCR REP LL_TIM_SetRepetitionCounter - * @param TIMx Timer instance - * @param RepetitionCounter between Min_Data=0 and Max_Data=255 or 65535 for advanced timer. - * @retval None - */ -__STATIC_INLINE void LL_TIM_SetRepetitionCounter(TIM_TypeDef *TIMx, uint32_t RepetitionCounter) -{ - WRITE_REG(TIMx->RCR, RepetitionCounter); -} - -/** - * @brief Get the repetition counter value. - * @note Macro IS_TIM_REPETITION_COUNTER_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports a repetition counter. - * @rmtoll RCR REP LL_TIM_GetRepetitionCounter - * @param TIMx Timer instance - * @retval Repetition counter value - */ -__STATIC_INLINE uint32_t LL_TIM_GetRepetitionCounter(TIM_TypeDef *TIMx) -{ - return (uint32_t)(READ_REG(TIMx->RCR)); -} - -/** - * @} - */ - -/** @defgroup TIM_LL_EF_Capture_Compare Capture Compare configuration - * @{ - */ -/** - * @brief Enable the capture/compare control bits (CCxE, CCxNE and OCxM) preload. - * @note CCxE, CCxNE and OCxM bits are preloaded, after having been written, - * they are updated only when a commutation event (COM) occurs. - * @note Only on channels that have a complementary output. - * @note Macro IS_TIM_COMMUTATION_EVENT_INSTANCE(TIMx) can be used to check - * whether or not a timer instance is able to generate a commutation event. - * @rmtoll CR2 CCPC LL_TIM_CC_EnablePreload - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_CC_EnablePreload(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->CR2, TIM_CR2_CCPC); -} - -/** - * @brief Disable the capture/compare control bits (CCxE, CCxNE and OCxM) preload. - * @note Macro IS_TIM_COMMUTATION_EVENT_INSTANCE(TIMx) can be used to check - * whether or not a timer instance is able to generate a commutation event. - * @rmtoll CR2 CCPC LL_TIM_CC_DisablePreload - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_CC_DisablePreload(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->CR2, TIM_CR2_CCPC); -} - -/** - * @brief Set the updated source of the capture/compare control bits (CCxE, CCxNE and OCxM). - * @note Macro IS_TIM_COMMUTATION_EVENT_INSTANCE(TIMx) can be used to check - * whether or not a timer instance is able to generate a commutation event. - * @rmtoll CR2 CCUS LL_TIM_CC_SetUpdate - * @param TIMx Timer instance - * @param CCUpdateSource This parameter can be one of the following values: - * @arg @ref LL_TIM_CCUPDATESOURCE_COMG_ONLY - * @arg @ref LL_TIM_CCUPDATESOURCE_COMG_AND_TRGI - * @retval None - */ -__STATIC_INLINE void LL_TIM_CC_SetUpdate(TIM_TypeDef *TIMx, uint32_t CCUpdateSource) -{ - MODIFY_REG(TIMx->CR2, TIM_CR2_CCUS, CCUpdateSource); -} - -/** - * @brief Set the trigger of the capture/compare DMA request. - * @rmtoll CR2 CCDS LL_TIM_CC_SetDMAReqTrigger - * @param TIMx Timer instance - * @param DMAReqTrigger This parameter can be one of the following values: - * @arg @ref LL_TIM_CCDMAREQUEST_CC - * @arg @ref LL_TIM_CCDMAREQUEST_UPDATE - * @retval None - */ -__STATIC_INLINE void LL_TIM_CC_SetDMAReqTrigger(TIM_TypeDef *TIMx, uint32_t DMAReqTrigger) -{ - MODIFY_REG(TIMx->CR2, TIM_CR2_CCDS, DMAReqTrigger); -} - -/** - * @brief Get actual trigger of the capture/compare DMA request. - * @rmtoll CR2 CCDS LL_TIM_CC_GetDMAReqTrigger - * @param TIMx Timer instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_TIM_CCDMAREQUEST_CC - * @arg @ref LL_TIM_CCDMAREQUEST_UPDATE - */ -__STATIC_INLINE uint32_t LL_TIM_CC_GetDMAReqTrigger(TIM_TypeDef *TIMx) -{ - return (uint32_t)(READ_BIT(TIMx->CR2, TIM_CR2_CCDS)); -} - -/** - * @brief Set the lock level to freeze the - * configuration of several capture/compare parameters. - * @note Macro IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not - * the lock mechanism is supported by a timer instance. - * @rmtoll BDTR LOCK LL_TIM_CC_SetLockLevel - * @param TIMx Timer instance - * @param LockLevel This parameter can be one of the following values: - * @arg @ref LL_TIM_LOCKLEVEL_OFF - * @arg @ref LL_TIM_LOCKLEVEL_1 - * @arg @ref LL_TIM_LOCKLEVEL_2 - * @arg @ref LL_TIM_LOCKLEVEL_3 - * @retval None - */ -__STATIC_INLINE void LL_TIM_CC_SetLockLevel(TIM_TypeDef *TIMx, uint32_t LockLevel) -{ - MODIFY_REG(TIMx->BDTR, TIM_BDTR_LOCK, LockLevel); -} - -/** - * @brief Enable capture/compare channels. - * @rmtoll CCER CC1E LL_TIM_CC_EnableChannel\n - * CCER CC1NE LL_TIM_CC_EnableChannel\n - * CCER CC2E LL_TIM_CC_EnableChannel\n - * CCER CC2NE LL_TIM_CC_EnableChannel\n - * CCER CC3E LL_TIM_CC_EnableChannel\n - * CCER CC3NE LL_TIM_CC_EnableChannel\n - * CCER CC4E LL_TIM_CC_EnableChannel - * @param TIMx Timer instance - * @param Channels This parameter can be a combination of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH1N - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH2N - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH3N - * @arg @ref LL_TIM_CHANNEL_CH4 - * @retval None - */ -__STATIC_INLINE void LL_TIM_CC_EnableChannel(TIM_TypeDef *TIMx, uint32_t Channels) -{ - SET_BIT(TIMx->CCER, Channels); -} - -/** - * @brief Disable capture/compare channels. - * @rmtoll CCER CC1E LL_TIM_CC_DisableChannel\n - * CCER CC1NE LL_TIM_CC_DisableChannel\n - * CCER CC2E LL_TIM_CC_DisableChannel\n - * CCER CC2NE LL_TIM_CC_DisableChannel\n - * CCER CC3E LL_TIM_CC_DisableChannel\n - * CCER CC3NE LL_TIM_CC_DisableChannel\n - * CCER CC4E LL_TIM_CC_DisableChannel - * @param TIMx Timer instance - * @param Channels This parameter can be a combination of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH1N - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH2N - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH3N - * @arg @ref LL_TIM_CHANNEL_CH4 - * @retval None - */ -__STATIC_INLINE void LL_TIM_CC_DisableChannel(TIM_TypeDef *TIMx, uint32_t Channels) -{ - CLEAR_BIT(TIMx->CCER, Channels); -} - -/** - * @brief Indicate whether channel(s) is(are) enabled. - * @rmtoll CCER CC1E LL_TIM_CC_IsEnabledChannel\n - * CCER CC1NE LL_TIM_CC_IsEnabledChannel\n - * CCER CC2E LL_TIM_CC_IsEnabledChannel\n - * CCER CC2NE LL_TIM_CC_IsEnabledChannel\n - * CCER CC3E LL_TIM_CC_IsEnabledChannel\n - * CCER CC3NE LL_TIM_CC_IsEnabledChannel\n - * CCER CC4E LL_TIM_CC_IsEnabledChannel - * @param TIMx Timer instance - * @param Channels This parameter can be a combination of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH1N - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH2N - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH3N - * @arg @ref LL_TIM_CHANNEL_CH4 - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_CC_IsEnabledChannel(TIM_TypeDef *TIMx, uint32_t Channels) -{ - return ((READ_BIT(TIMx->CCER, Channels) == (Channels)) ? 1UL : 0UL); -} - -/** - * @} - */ - -/** @defgroup TIM_LL_EF_Output_Channel Output channel configuration - * @{ - */ -/** - * @brief Configure an output channel. - * @rmtoll CCMR1 CC1S LL_TIM_OC_ConfigOutput\n - * CCMR1 CC2S LL_TIM_OC_ConfigOutput\n - * CCMR2 CC3S LL_TIM_OC_ConfigOutput\n - * CCMR2 CC4S LL_TIM_OC_ConfigOutput\n - * CCER CC1P LL_TIM_OC_ConfigOutput\n - * CCER CC2P LL_TIM_OC_ConfigOutput\n - * CCER CC3P LL_TIM_OC_ConfigOutput\n - * CCER CC4P LL_TIM_OC_ConfigOutput\n - * CR2 OIS1 LL_TIM_OC_ConfigOutput\n - * CR2 OIS2 LL_TIM_OC_ConfigOutput\n - * CR2 OIS3 LL_TIM_OC_ConfigOutput\n - * CR2 OIS4 LL_TIM_OC_ConfigOutput - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH4 - * @param Configuration This parameter must be a combination of all the following values: - * @arg @ref LL_TIM_OCPOLARITY_HIGH or @ref LL_TIM_OCPOLARITY_LOW - * @arg @ref LL_TIM_OCIDLESTATE_LOW or @ref LL_TIM_OCIDLESTATE_HIGH - * @retval None - */ -__STATIC_INLINE void LL_TIM_OC_ConfigOutput(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t Configuration) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); - CLEAR_BIT(*pReg, (TIM_CCMR1_CC1S << SHIFT_TAB_OCxx[iChannel])); - MODIFY_REG(TIMx->CCER, (TIM_CCER_CC1P << SHIFT_TAB_CCxP[iChannel]), - (Configuration & TIM_CCER_CC1P) << SHIFT_TAB_CCxP[iChannel]); - MODIFY_REG(TIMx->CR2, (TIM_CR2_OIS1 << SHIFT_TAB_OISx[iChannel]), - (Configuration & TIM_CR2_OIS1) << SHIFT_TAB_OISx[iChannel]); -} - -/** - * @brief Define the behavior of the output reference signal OCxREF from which - * OCx and OCxN (when relevant) are derived. - * @rmtoll CCMR1 OC1M LL_TIM_OC_SetMode\n - * CCMR1 OC2M LL_TIM_OC_SetMode\n - * CCMR2 OC3M LL_TIM_OC_SetMode\n - * CCMR2 OC4M LL_TIM_OC_SetMode - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH4 - * @param Mode This parameter can be one of the following values: - * @arg @ref LL_TIM_OCMODE_FROZEN - * @arg @ref LL_TIM_OCMODE_ACTIVE - * @arg @ref LL_TIM_OCMODE_INACTIVE - * @arg @ref LL_TIM_OCMODE_TOGGLE - * @arg @ref LL_TIM_OCMODE_FORCED_INACTIVE - * @arg @ref LL_TIM_OCMODE_FORCED_ACTIVE - * @arg @ref LL_TIM_OCMODE_PWM1 - * @arg @ref LL_TIM_OCMODE_PWM2 - * @retval None - */ -__STATIC_INLINE void LL_TIM_OC_SetMode(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t Mode) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); - MODIFY_REG(*pReg, ((TIM_CCMR1_OC1M | TIM_CCMR1_CC1S) << SHIFT_TAB_OCxx[iChannel]), Mode << SHIFT_TAB_OCxx[iChannel]); -} - -/** - * @brief Get the output compare mode of an output channel. - * @rmtoll CCMR1 OC1M LL_TIM_OC_GetMode\n - * CCMR1 OC2M LL_TIM_OC_GetMode\n - * CCMR2 OC3M LL_TIM_OC_GetMode\n - * CCMR2 OC4M LL_TIM_OC_GetMode - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH4 - * @retval Returned value can be one of the following values: - * @arg @ref LL_TIM_OCMODE_FROZEN - * @arg @ref LL_TIM_OCMODE_ACTIVE - * @arg @ref LL_TIM_OCMODE_INACTIVE - * @arg @ref LL_TIM_OCMODE_TOGGLE - * @arg @ref LL_TIM_OCMODE_FORCED_INACTIVE - * @arg @ref LL_TIM_OCMODE_FORCED_ACTIVE - * @arg @ref LL_TIM_OCMODE_PWM1 - * @arg @ref LL_TIM_OCMODE_PWM2 - */ -__STATIC_INLINE uint32_t LL_TIM_OC_GetMode(TIM_TypeDef *TIMx, uint32_t Channel) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - const __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); - return (READ_BIT(*pReg, ((TIM_CCMR1_OC1M | TIM_CCMR1_CC1S) << SHIFT_TAB_OCxx[iChannel])) >> SHIFT_TAB_OCxx[iChannel]); -} - -/** - * @brief Set the polarity of an output channel. - * @rmtoll CCER CC1P LL_TIM_OC_SetPolarity\n - * CCER CC1NP LL_TIM_OC_SetPolarity\n - * CCER CC2P LL_TIM_OC_SetPolarity\n - * CCER CC2NP LL_TIM_OC_SetPolarity\n - * CCER CC3P LL_TIM_OC_SetPolarity\n - * CCER CC3NP LL_TIM_OC_SetPolarity\n - * CCER CC4P LL_TIM_OC_SetPolarity - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH1N - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH2N - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH3N - * @arg @ref LL_TIM_CHANNEL_CH4 - * @param Polarity This parameter can be one of the following values: - * @arg @ref LL_TIM_OCPOLARITY_HIGH - * @arg @ref LL_TIM_OCPOLARITY_LOW - * @retval None - */ -__STATIC_INLINE void LL_TIM_OC_SetPolarity(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t Polarity) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - MODIFY_REG(TIMx->CCER, (TIM_CCER_CC1P << SHIFT_TAB_CCxP[iChannel]), Polarity << SHIFT_TAB_CCxP[iChannel]); -} - -/** - * @brief Get the polarity of an output channel. - * @rmtoll CCER CC1P LL_TIM_OC_GetPolarity\n - * CCER CC1NP LL_TIM_OC_GetPolarity\n - * CCER CC2P LL_TIM_OC_GetPolarity\n - * CCER CC2NP LL_TIM_OC_GetPolarity\n - * CCER CC3P LL_TIM_OC_GetPolarity\n - * CCER CC3NP LL_TIM_OC_GetPolarity\n - * CCER CC4P LL_TIM_OC_GetPolarity - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH1N - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH2N - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH3N - * @arg @ref LL_TIM_CHANNEL_CH4 - * @retval Returned value can be one of the following values: - * @arg @ref LL_TIM_OCPOLARITY_HIGH - * @arg @ref LL_TIM_OCPOLARITY_LOW - */ -__STATIC_INLINE uint32_t LL_TIM_OC_GetPolarity(TIM_TypeDef *TIMx, uint32_t Channel) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - return (READ_BIT(TIMx->CCER, (TIM_CCER_CC1P << SHIFT_TAB_CCxP[iChannel])) >> SHIFT_TAB_CCxP[iChannel]); -} - -/** - * @brief Set the IDLE state of an output channel - * @note This function is significant only for the timer instances - * supporting the break feature. Macro IS_TIM_BREAK_INSTANCE(TIMx) - * can be used to check whether or not a timer instance provides - * a break input. - * @rmtoll CR2 OIS1 LL_TIM_OC_SetIdleState\n - * CR2 OIS1N LL_TIM_OC_SetIdleState\n - * CR2 OIS2 LL_TIM_OC_SetIdleState\n - * CR2 OIS2N LL_TIM_OC_SetIdleState\n - * CR2 OIS3 LL_TIM_OC_SetIdleState\n - * CR2 OIS3N LL_TIM_OC_SetIdleState\n - * CR2 OIS4 LL_TIM_OC_SetIdleState - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH1N - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH2N - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH3N - * @arg @ref LL_TIM_CHANNEL_CH4 - * @param IdleState This parameter can be one of the following values: - * @arg @ref LL_TIM_OCIDLESTATE_LOW - * @arg @ref LL_TIM_OCIDLESTATE_HIGH - * @retval None - */ -__STATIC_INLINE void LL_TIM_OC_SetIdleState(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t IdleState) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - MODIFY_REG(TIMx->CR2, (TIM_CR2_OIS1 << SHIFT_TAB_OISx[iChannel]), IdleState << SHIFT_TAB_OISx[iChannel]); -} - -/** - * @brief Get the IDLE state of an output channel - * @rmtoll CR2 OIS1 LL_TIM_OC_GetIdleState\n - * CR2 OIS1N LL_TIM_OC_GetIdleState\n - * CR2 OIS2 LL_TIM_OC_GetIdleState\n - * CR2 OIS2N LL_TIM_OC_GetIdleState\n - * CR2 OIS3 LL_TIM_OC_GetIdleState\n - * CR2 OIS3N LL_TIM_OC_GetIdleState\n - * CR2 OIS4 LL_TIM_OC_GetIdleState - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH1N - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH2N - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH3N - * @arg @ref LL_TIM_CHANNEL_CH4 - * @retval Returned value can be one of the following values: - * @arg @ref LL_TIM_OCIDLESTATE_LOW - * @arg @ref LL_TIM_OCIDLESTATE_HIGH - */ -__STATIC_INLINE uint32_t LL_TIM_OC_GetIdleState(TIM_TypeDef *TIMx, uint32_t Channel) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - return (READ_BIT(TIMx->CR2, (TIM_CR2_OIS1 << SHIFT_TAB_OISx[iChannel])) >> SHIFT_TAB_OISx[iChannel]); -} - -/** - * @brief Enable fast mode for the output channel. - * @note Acts only if the channel is configured in PWM1 or PWM2 mode. - * @rmtoll CCMR1 OC1FE LL_TIM_OC_EnableFast\n - * CCMR1 OC2FE LL_TIM_OC_EnableFast\n - * CCMR2 OC3FE LL_TIM_OC_EnableFast\n - * CCMR2 OC4FE LL_TIM_OC_EnableFast - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH4 - * @retval None - */ -__STATIC_INLINE void LL_TIM_OC_EnableFast(TIM_TypeDef *TIMx, uint32_t Channel) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); - SET_BIT(*pReg, (TIM_CCMR1_OC1FE << SHIFT_TAB_OCxx[iChannel])); - -} - -/** - * @brief Disable fast mode for the output channel. - * @rmtoll CCMR1 OC1FE LL_TIM_OC_DisableFast\n - * CCMR1 OC2FE LL_TIM_OC_DisableFast\n - * CCMR2 OC3FE LL_TIM_OC_DisableFast\n - * CCMR2 OC4FE LL_TIM_OC_DisableFast - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH4 - * @retval None - */ -__STATIC_INLINE void LL_TIM_OC_DisableFast(TIM_TypeDef *TIMx, uint32_t Channel) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); - CLEAR_BIT(*pReg, (TIM_CCMR1_OC1FE << SHIFT_TAB_OCxx[iChannel])); - -} - -/** - * @brief Indicates whether fast mode is enabled for the output channel. - * @rmtoll CCMR1 OC1FE LL_TIM_OC_IsEnabledFast\n - * CCMR1 OC2FE LL_TIM_OC_IsEnabledFast\n - * CCMR2 OC3FE LL_TIM_OC_IsEnabledFast\n - * CCMR2 OC4FE LL_TIM_OC_IsEnabledFast\n - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH4 - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_OC_IsEnabledFast(TIM_TypeDef *TIMx, uint32_t Channel) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - const __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); - uint32_t bitfield = TIM_CCMR1_OC1FE << SHIFT_TAB_OCxx[iChannel]; - return ((READ_BIT(*pReg, bitfield) == bitfield) ? 1UL : 0UL); -} - -/** - * @brief Enable compare register (TIMx_CCRx) preload for the output channel. - * @rmtoll CCMR1 OC1PE LL_TIM_OC_EnablePreload\n - * CCMR1 OC2PE LL_TIM_OC_EnablePreload\n - * CCMR2 OC3PE LL_TIM_OC_EnablePreload\n - * CCMR2 OC4PE LL_TIM_OC_EnablePreload - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH4 - * @retval None - */ -__STATIC_INLINE void LL_TIM_OC_EnablePreload(TIM_TypeDef *TIMx, uint32_t Channel) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); - SET_BIT(*pReg, (TIM_CCMR1_OC1PE << SHIFT_TAB_OCxx[iChannel])); -} - -/** - * @brief Disable compare register (TIMx_CCRx) preload for the output channel. - * @rmtoll CCMR1 OC1PE LL_TIM_OC_DisablePreload\n - * CCMR1 OC2PE LL_TIM_OC_DisablePreload\n - * CCMR2 OC3PE LL_TIM_OC_DisablePreload\n - * CCMR2 OC4PE LL_TIM_OC_DisablePreload - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH4 - * @retval None - */ -__STATIC_INLINE void LL_TIM_OC_DisablePreload(TIM_TypeDef *TIMx, uint32_t Channel) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); - CLEAR_BIT(*pReg, (TIM_CCMR1_OC1PE << SHIFT_TAB_OCxx[iChannel])); -} - -/** - * @brief Indicates whether compare register (TIMx_CCRx) preload is enabled for the output channel. - * @rmtoll CCMR1 OC1PE LL_TIM_OC_IsEnabledPreload\n - * CCMR1 OC2PE LL_TIM_OC_IsEnabledPreload\n - * CCMR2 OC3PE LL_TIM_OC_IsEnabledPreload\n - * CCMR2 OC4PE LL_TIM_OC_IsEnabledPreload\n - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH4 - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_OC_IsEnabledPreload(TIM_TypeDef *TIMx, uint32_t Channel) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - const __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); - uint32_t bitfield = TIM_CCMR1_OC1PE << SHIFT_TAB_OCxx[iChannel]; - return ((READ_BIT(*pReg, bitfield) == bitfield) ? 1UL : 0UL); -} - -/** - * @brief Enable clearing the output channel on an external event. - * @note This function can only be used in Output compare and PWM modes. It does not work in Forced mode. - * @note Macro IS_TIM_OCXREF_CLEAR_INSTANCE(TIMx) can be used to check whether - * or not a timer instance can clear the OCxREF signal on an external event. - * @rmtoll CCMR1 OC1CE LL_TIM_OC_EnableClear\n - * CCMR1 OC2CE LL_TIM_OC_EnableClear\n - * CCMR2 OC3CE LL_TIM_OC_EnableClear\n - * CCMR2 OC4CE LL_TIM_OC_EnableClear - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH4 - * @retval None - */ -__STATIC_INLINE void LL_TIM_OC_EnableClear(TIM_TypeDef *TIMx, uint32_t Channel) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); - SET_BIT(*pReg, (TIM_CCMR1_OC1CE << SHIFT_TAB_OCxx[iChannel])); -} - -/** - * @brief Disable clearing the output channel on an external event. - * @note Macro IS_TIM_OCXREF_CLEAR_INSTANCE(TIMx) can be used to check whether - * or not a timer instance can clear the OCxREF signal on an external event. - * @rmtoll CCMR1 OC1CE LL_TIM_OC_DisableClear\n - * CCMR1 OC2CE LL_TIM_OC_DisableClear\n - * CCMR2 OC3CE LL_TIM_OC_DisableClear\n - * CCMR2 OC4CE LL_TIM_OC_DisableClear - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH4 - * @retval None - */ -__STATIC_INLINE void LL_TIM_OC_DisableClear(TIM_TypeDef *TIMx, uint32_t Channel) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); - CLEAR_BIT(*pReg, (TIM_CCMR1_OC1CE << SHIFT_TAB_OCxx[iChannel])); -} - -/** - * @brief Indicates clearing the output channel on an external event is enabled for the output channel. - * @note This function enables clearing the output channel on an external event. - * @note This function can only be used in Output compare and PWM modes. It does not work in Forced mode. - * @note Macro IS_TIM_OCXREF_CLEAR_INSTANCE(TIMx) can be used to check whether - * or not a timer instance can clear the OCxREF signal on an external event. - * @rmtoll CCMR1 OC1CE LL_TIM_OC_IsEnabledClear\n - * CCMR1 OC2CE LL_TIM_OC_IsEnabledClear\n - * CCMR2 OC3CE LL_TIM_OC_IsEnabledClear\n - * CCMR2 OC4CE LL_TIM_OC_IsEnabledClear\n - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH4 - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_OC_IsEnabledClear(TIM_TypeDef *TIMx, uint32_t Channel) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - const __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); - uint32_t bitfield = TIM_CCMR1_OC1CE << SHIFT_TAB_OCxx[iChannel]; - return ((READ_BIT(*pReg, bitfield) == bitfield) ? 1UL : 0UL); -} - -/** - * @brief Set the dead-time delay (delay inserted between the rising edge of the OCxREF signal and the rising edge of - * the Ocx and OCxN signals). - * @note Macro IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not - * dead-time insertion feature is supported by a timer instance. - * @note Helper macro @ref __LL_TIM_CALC_DEADTIME can be used to calculate the DeadTime parameter - * @rmtoll BDTR DTG LL_TIM_OC_SetDeadTime - * @param TIMx Timer instance - * @param DeadTime between Min_Data=0 and Max_Data=255 - * @retval None - */ -__STATIC_INLINE void LL_TIM_OC_SetDeadTime(TIM_TypeDef *TIMx, uint32_t DeadTime) -{ - MODIFY_REG(TIMx->BDTR, TIM_BDTR_DTG, DeadTime); -} - -/** - * @brief Set compare value for output channel 1 (TIMx_CCR1). - * @note In 32-bit timer implementations compare value can be between 0x00000000 and 0xFFFFFFFF. - * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports a 32 bits counter. - * @note Macro IS_TIM_CC1_INSTANCE(TIMx) can be used to check whether or not - * output channel 1 is supported by a timer instance. - * @rmtoll CCR1 CCR1 LL_TIM_OC_SetCompareCH1 - * @param TIMx Timer instance - * @param CompareValue between Min_Data=0 and Max_Data=65535 - * @retval None - */ -__STATIC_INLINE void LL_TIM_OC_SetCompareCH1(TIM_TypeDef *TIMx, uint32_t CompareValue) -{ - WRITE_REG(TIMx->CCR1, CompareValue); -} - -/** - * @brief Set compare value for output channel 2 (TIMx_CCR2). - * @note In 32-bit timer implementations compare value can be between 0x00000000 and 0xFFFFFFFF. - * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports a 32 bits counter. - * @note Macro IS_TIM_CC2_INSTANCE(TIMx) can be used to check whether or not - * output channel 2 is supported by a timer instance. - * @rmtoll CCR2 CCR2 LL_TIM_OC_SetCompareCH2 - * @param TIMx Timer instance - * @param CompareValue between Min_Data=0 and Max_Data=65535 - * @retval None - */ -__STATIC_INLINE void LL_TIM_OC_SetCompareCH2(TIM_TypeDef *TIMx, uint32_t CompareValue) -{ - WRITE_REG(TIMx->CCR2, CompareValue); -} - -/** - * @brief Set compare value for output channel 3 (TIMx_CCR3). - * @note In 32-bit timer implementations compare value can be between 0x00000000 and 0xFFFFFFFF. - * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports a 32 bits counter. - * @note Macro IS_TIM_CC3_INSTANCE(TIMx) can be used to check whether or not - * output channel is supported by a timer instance. - * @rmtoll CCR3 CCR3 LL_TIM_OC_SetCompareCH3 - * @param TIMx Timer instance - * @param CompareValue between Min_Data=0 and Max_Data=65535 - * @retval None - */ -__STATIC_INLINE void LL_TIM_OC_SetCompareCH3(TIM_TypeDef *TIMx, uint32_t CompareValue) -{ - WRITE_REG(TIMx->CCR3, CompareValue); -} - -/** - * @brief Set compare value for output channel 4 (TIMx_CCR4). - * @note In 32-bit timer implementations compare value can be between 0x00000000 and 0xFFFFFFFF. - * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports a 32 bits counter. - * @note Macro IS_TIM_CC4_INSTANCE(TIMx) can be used to check whether or not - * output channel 4 is supported by a timer instance. - * @rmtoll CCR4 CCR4 LL_TIM_OC_SetCompareCH4 - * @param TIMx Timer instance - * @param CompareValue between Min_Data=0 and Max_Data=65535 - * @retval None - */ -__STATIC_INLINE void LL_TIM_OC_SetCompareCH4(TIM_TypeDef *TIMx, uint32_t CompareValue) -{ - WRITE_REG(TIMx->CCR4, CompareValue); -} - -/** - * @brief Get compare value (TIMx_CCR1) set for output channel 1. - * @note In 32-bit timer implementations returned compare value can be between 0x00000000 and 0xFFFFFFFF. - * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports a 32 bits counter. - * @note Macro IS_TIM_CC1_INSTANCE(TIMx) can be used to check whether or not - * output channel 1 is supported by a timer instance. - * @rmtoll CCR1 CCR1 LL_TIM_OC_GetCompareCH1 - * @param TIMx Timer instance - * @retval CompareValue (between Min_Data=0 and Max_Data=65535) - */ -__STATIC_INLINE uint32_t LL_TIM_OC_GetCompareCH1(TIM_TypeDef *TIMx) -{ - return (uint32_t)(READ_REG(TIMx->CCR1)); -} - -/** - * @brief Get compare value (TIMx_CCR2) set for output channel 2. - * @note In 32-bit timer implementations returned compare value can be between 0x00000000 and 0xFFFFFFFF. - * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports a 32 bits counter. - * @note Macro IS_TIM_CC2_INSTANCE(TIMx) can be used to check whether or not - * output channel 2 is supported by a timer instance. - * @rmtoll CCR2 CCR2 LL_TIM_OC_GetCompareCH2 - * @param TIMx Timer instance - * @retval CompareValue (between Min_Data=0 and Max_Data=65535) - */ -__STATIC_INLINE uint32_t LL_TIM_OC_GetCompareCH2(TIM_TypeDef *TIMx) -{ - return (uint32_t)(READ_REG(TIMx->CCR2)); -} - -/** - * @brief Get compare value (TIMx_CCR3) set for output channel 3. - * @note In 32-bit timer implementations returned compare value can be between 0x00000000 and 0xFFFFFFFF. - * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports a 32 bits counter. - * @note Macro IS_TIM_CC3_INSTANCE(TIMx) can be used to check whether or not - * output channel 3 is supported by a timer instance. - * @rmtoll CCR3 CCR3 LL_TIM_OC_GetCompareCH3 - * @param TIMx Timer instance - * @retval CompareValue (between Min_Data=0 and Max_Data=65535) - */ -__STATIC_INLINE uint32_t LL_TIM_OC_GetCompareCH3(TIM_TypeDef *TIMx) -{ - return (uint32_t)(READ_REG(TIMx->CCR3)); -} - -/** - * @brief Get compare value (TIMx_CCR4) set for output channel 4. - * @note In 32-bit timer implementations returned compare value can be between 0x00000000 and 0xFFFFFFFF. - * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports a 32 bits counter. - * @note Macro IS_TIM_CC4_INSTANCE(TIMx) can be used to check whether or not - * output channel 4 is supported by a timer instance. - * @rmtoll CCR4 CCR4 LL_TIM_OC_GetCompareCH4 - * @param TIMx Timer instance - * @retval CompareValue (between Min_Data=0 and Max_Data=65535) - */ -__STATIC_INLINE uint32_t LL_TIM_OC_GetCompareCH4(TIM_TypeDef *TIMx) -{ - return (uint32_t)(READ_REG(TIMx->CCR4)); -} - -/** - * @} - */ - -/** @defgroup TIM_LL_EF_Input_Channel Input channel configuration - * @{ - */ -/** - * @brief Configure input channel. - * @rmtoll CCMR1 CC1S LL_TIM_IC_Config\n - * CCMR1 IC1PSC LL_TIM_IC_Config\n - * CCMR1 IC1F LL_TIM_IC_Config\n - * CCMR1 CC2S LL_TIM_IC_Config\n - * CCMR1 IC2PSC LL_TIM_IC_Config\n - * CCMR1 IC2F LL_TIM_IC_Config\n - * CCMR2 CC3S LL_TIM_IC_Config\n - * CCMR2 IC3PSC LL_TIM_IC_Config\n - * CCMR2 IC3F LL_TIM_IC_Config\n - * CCMR2 CC4S LL_TIM_IC_Config\n - * CCMR2 IC4PSC LL_TIM_IC_Config\n - * CCMR2 IC4F LL_TIM_IC_Config\n - * CCER CC1P LL_TIM_IC_Config\n - * CCER CC1NP LL_TIM_IC_Config\n - * CCER CC2P LL_TIM_IC_Config\n - * CCER CC2NP LL_TIM_IC_Config\n - * CCER CC3P LL_TIM_IC_Config\n - * CCER CC3NP LL_TIM_IC_Config\n - * CCER CC4P LL_TIM_IC_Config\n - * CCER CC4NP LL_TIM_IC_Config - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH4 - * @param Configuration This parameter must be a combination of all the following values: - * @arg @ref LL_TIM_ACTIVEINPUT_DIRECTTI or @ref LL_TIM_ACTIVEINPUT_INDIRECTTI or @ref LL_TIM_ACTIVEINPUT_TRC - * @arg @ref LL_TIM_ICPSC_DIV1 or ... or @ref LL_TIM_ICPSC_DIV8 - * @arg @ref LL_TIM_IC_FILTER_FDIV1 or ... or @ref LL_TIM_IC_FILTER_FDIV32_N8 - * @arg @ref LL_TIM_IC_POLARITY_RISING or @ref LL_TIM_IC_POLARITY_FALLING or @ref LL_TIM_IC_POLARITY_BOTHEDGE - * @retval None - */ -__STATIC_INLINE void LL_TIM_IC_Config(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t Configuration) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); - MODIFY_REG(*pReg, ((TIM_CCMR1_IC1F | TIM_CCMR1_IC1PSC | TIM_CCMR1_CC1S) << SHIFT_TAB_ICxx[iChannel]), - ((Configuration >> 16U) & (TIM_CCMR1_IC1F | TIM_CCMR1_IC1PSC | TIM_CCMR1_CC1S)) \ - << SHIFT_TAB_ICxx[iChannel]); - MODIFY_REG(TIMx->CCER, ((TIM_CCER_CC1NP | TIM_CCER_CC1P) << SHIFT_TAB_CCxP[iChannel]), - (Configuration & (TIM_CCER_CC1NP | TIM_CCER_CC1P)) << SHIFT_TAB_CCxP[iChannel]); -} - -/** - * @brief Set the active input. - * @rmtoll CCMR1 CC1S LL_TIM_IC_SetActiveInput\n - * CCMR1 CC2S LL_TIM_IC_SetActiveInput\n - * CCMR2 CC3S LL_TIM_IC_SetActiveInput\n - * CCMR2 CC4S LL_TIM_IC_SetActiveInput - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH4 - * @param ICActiveInput This parameter can be one of the following values: - * @arg @ref LL_TIM_ACTIVEINPUT_DIRECTTI - * @arg @ref LL_TIM_ACTIVEINPUT_INDIRECTTI - * @arg @ref LL_TIM_ACTIVEINPUT_TRC - * @retval None - */ -__STATIC_INLINE void LL_TIM_IC_SetActiveInput(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t ICActiveInput) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); - MODIFY_REG(*pReg, ((TIM_CCMR1_CC1S) << SHIFT_TAB_ICxx[iChannel]), (ICActiveInput >> 16U) << SHIFT_TAB_ICxx[iChannel]); -} - -/** - * @brief Get the current active input. - * @rmtoll CCMR1 CC1S LL_TIM_IC_GetActiveInput\n - * CCMR1 CC2S LL_TIM_IC_GetActiveInput\n - * CCMR2 CC3S LL_TIM_IC_GetActiveInput\n - * CCMR2 CC4S LL_TIM_IC_GetActiveInput - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH4 - * @retval Returned value can be one of the following values: - * @arg @ref LL_TIM_ACTIVEINPUT_DIRECTTI - * @arg @ref LL_TIM_ACTIVEINPUT_INDIRECTTI - * @arg @ref LL_TIM_ACTIVEINPUT_TRC - */ -__STATIC_INLINE uint32_t LL_TIM_IC_GetActiveInput(TIM_TypeDef *TIMx, uint32_t Channel) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - const __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); - return ((READ_BIT(*pReg, ((TIM_CCMR1_CC1S) << SHIFT_TAB_ICxx[iChannel])) >> SHIFT_TAB_ICxx[iChannel]) << 16U); -} - -/** - * @brief Set the prescaler of input channel. - * @rmtoll CCMR1 IC1PSC LL_TIM_IC_SetPrescaler\n - * CCMR1 IC2PSC LL_TIM_IC_SetPrescaler\n - * CCMR2 IC3PSC LL_TIM_IC_SetPrescaler\n - * CCMR2 IC4PSC LL_TIM_IC_SetPrescaler - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH4 - * @param ICPrescaler This parameter can be one of the following values: - * @arg @ref LL_TIM_ICPSC_DIV1 - * @arg @ref LL_TIM_ICPSC_DIV2 - * @arg @ref LL_TIM_ICPSC_DIV4 - * @arg @ref LL_TIM_ICPSC_DIV8 - * @retval None - */ -__STATIC_INLINE void LL_TIM_IC_SetPrescaler(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t ICPrescaler) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); - MODIFY_REG(*pReg, ((TIM_CCMR1_IC1PSC) << SHIFT_TAB_ICxx[iChannel]), (ICPrescaler >> 16U) << SHIFT_TAB_ICxx[iChannel]); -} - -/** - * @brief Get the current prescaler value acting on an input channel. - * @rmtoll CCMR1 IC1PSC LL_TIM_IC_GetPrescaler\n - * CCMR1 IC2PSC LL_TIM_IC_GetPrescaler\n - * CCMR2 IC3PSC LL_TIM_IC_GetPrescaler\n - * CCMR2 IC4PSC LL_TIM_IC_GetPrescaler - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH4 - * @retval Returned value can be one of the following values: - * @arg @ref LL_TIM_ICPSC_DIV1 - * @arg @ref LL_TIM_ICPSC_DIV2 - * @arg @ref LL_TIM_ICPSC_DIV4 - * @arg @ref LL_TIM_ICPSC_DIV8 - */ -__STATIC_INLINE uint32_t LL_TIM_IC_GetPrescaler(TIM_TypeDef *TIMx, uint32_t Channel) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - const __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); - return ((READ_BIT(*pReg, ((TIM_CCMR1_IC1PSC) << SHIFT_TAB_ICxx[iChannel])) >> SHIFT_TAB_ICxx[iChannel]) << 16U); -} - -/** - * @brief Set the input filter duration. - * @rmtoll CCMR1 IC1F LL_TIM_IC_SetFilter\n - * CCMR1 IC2F LL_TIM_IC_SetFilter\n - * CCMR2 IC3F LL_TIM_IC_SetFilter\n - * CCMR2 IC4F LL_TIM_IC_SetFilter - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH4 - * @param ICFilter This parameter can be one of the following values: - * @arg @ref LL_TIM_IC_FILTER_FDIV1 - * @arg @ref LL_TIM_IC_FILTER_FDIV1_N2 - * @arg @ref LL_TIM_IC_FILTER_FDIV1_N4 - * @arg @ref LL_TIM_IC_FILTER_FDIV1_N8 - * @arg @ref LL_TIM_IC_FILTER_FDIV2_N6 - * @arg @ref LL_TIM_IC_FILTER_FDIV2_N8 - * @arg @ref LL_TIM_IC_FILTER_FDIV4_N6 - * @arg @ref LL_TIM_IC_FILTER_FDIV4_N8 - * @arg @ref LL_TIM_IC_FILTER_FDIV8_N6 - * @arg @ref LL_TIM_IC_FILTER_FDIV8_N8 - * @arg @ref LL_TIM_IC_FILTER_FDIV16_N5 - * @arg @ref LL_TIM_IC_FILTER_FDIV16_N6 - * @arg @ref LL_TIM_IC_FILTER_FDIV16_N8 - * @arg @ref LL_TIM_IC_FILTER_FDIV32_N5 - * @arg @ref LL_TIM_IC_FILTER_FDIV32_N6 - * @arg @ref LL_TIM_IC_FILTER_FDIV32_N8 - * @retval None - */ -__STATIC_INLINE void LL_TIM_IC_SetFilter(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t ICFilter) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); - MODIFY_REG(*pReg, ((TIM_CCMR1_IC1F) << SHIFT_TAB_ICxx[iChannel]), (ICFilter >> 16U) << SHIFT_TAB_ICxx[iChannel]); -} - -/** - * @brief Get the input filter duration. - * @rmtoll CCMR1 IC1F LL_TIM_IC_GetFilter\n - * CCMR1 IC2F LL_TIM_IC_GetFilter\n - * CCMR2 IC3F LL_TIM_IC_GetFilter\n - * CCMR2 IC4F LL_TIM_IC_GetFilter - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH4 - * @retval Returned value can be one of the following values: - * @arg @ref LL_TIM_IC_FILTER_FDIV1 - * @arg @ref LL_TIM_IC_FILTER_FDIV1_N2 - * @arg @ref LL_TIM_IC_FILTER_FDIV1_N4 - * @arg @ref LL_TIM_IC_FILTER_FDIV1_N8 - * @arg @ref LL_TIM_IC_FILTER_FDIV2_N6 - * @arg @ref LL_TIM_IC_FILTER_FDIV2_N8 - * @arg @ref LL_TIM_IC_FILTER_FDIV4_N6 - * @arg @ref LL_TIM_IC_FILTER_FDIV4_N8 - * @arg @ref LL_TIM_IC_FILTER_FDIV8_N6 - * @arg @ref LL_TIM_IC_FILTER_FDIV8_N8 - * @arg @ref LL_TIM_IC_FILTER_FDIV16_N5 - * @arg @ref LL_TIM_IC_FILTER_FDIV16_N6 - * @arg @ref LL_TIM_IC_FILTER_FDIV16_N8 - * @arg @ref LL_TIM_IC_FILTER_FDIV32_N5 - * @arg @ref LL_TIM_IC_FILTER_FDIV32_N6 - * @arg @ref LL_TIM_IC_FILTER_FDIV32_N8 - */ -__STATIC_INLINE uint32_t LL_TIM_IC_GetFilter(TIM_TypeDef *TIMx, uint32_t Channel) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - const __IO uint32_t *pReg = (__IO uint32_t *)((uint32_t)((uint32_t)(&TIMx->CCMR1) + OFFSET_TAB_CCMRx[iChannel])); - return ((READ_BIT(*pReg, ((TIM_CCMR1_IC1F) << SHIFT_TAB_ICxx[iChannel])) >> SHIFT_TAB_ICxx[iChannel]) << 16U); -} - -/** - * @brief Set the input channel polarity. - * @rmtoll CCER CC1P LL_TIM_IC_SetPolarity\n - * CCER CC1NP LL_TIM_IC_SetPolarity\n - * CCER CC2P LL_TIM_IC_SetPolarity\n - * CCER CC2NP LL_TIM_IC_SetPolarity\n - * CCER CC3P LL_TIM_IC_SetPolarity\n - * CCER CC3NP LL_TIM_IC_SetPolarity\n - * CCER CC4P LL_TIM_IC_SetPolarity\n - * CCER CC4NP LL_TIM_IC_SetPolarity - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH4 - * @param ICPolarity This parameter can be one of the following values: - * @arg @ref LL_TIM_IC_POLARITY_RISING - * @arg @ref LL_TIM_IC_POLARITY_FALLING - * @arg @ref LL_TIM_IC_POLARITY_BOTHEDGE - * @retval None - */ -__STATIC_INLINE void LL_TIM_IC_SetPolarity(TIM_TypeDef *TIMx, uint32_t Channel, uint32_t ICPolarity) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - MODIFY_REG(TIMx->CCER, ((TIM_CCER_CC1NP | TIM_CCER_CC1P) << SHIFT_TAB_CCxP[iChannel]), - ICPolarity << SHIFT_TAB_CCxP[iChannel]); -} - -/** - * @brief Get the current input channel polarity. - * @rmtoll CCER CC1P LL_TIM_IC_GetPolarity\n - * CCER CC1NP LL_TIM_IC_GetPolarity\n - * CCER CC2P LL_TIM_IC_GetPolarity\n - * CCER CC2NP LL_TIM_IC_GetPolarity\n - * CCER CC3P LL_TIM_IC_GetPolarity\n - * CCER CC3NP LL_TIM_IC_GetPolarity\n - * CCER CC4P LL_TIM_IC_GetPolarity\n - * CCER CC4NP LL_TIM_IC_GetPolarity - * @param TIMx Timer instance - * @param Channel This parameter can be one of the following values: - * @arg @ref LL_TIM_CHANNEL_CH1 - * @arg @ref LL_TIM_CHANNEL_CH2 - * @arg @ref LL_TIM_CHANNEL_CH3 - * @arg @ref LL_TIM_CHANNEL_CH4 - * @retval Returned value can be one of the following values: - * @arg @ref LL_TIM_IC_POLARITY_RISING - * @arg @ref LL_TIM_IC_POLARITY_FALLING - * @arg @ref LL_TIM_IC_POLARITY_BOTHEDGE - */ -__STATIC_INLINE uint32_t LL_TIM_IC_GetPolarity(TIM_TypeDef *TIMx, uint32_t Channel) -{ - uint8_t iChannel = TIM_GET_CHANNEL_INDEX(Channel); - return (READ_BIT(TIMx->CCER, ((TIM_CCER_CC1NP | TIM_CCER_CC1P) << SHIFT_TAB_CCxP[iChannel])) >> - SHIFT_TAB_CCxP[iChannel]); -} - -/** - * @brief Connect the TIMx_CH1, CH2 and CH3 pins to the TI1 input (XOR combination). - * @note Macro IS_TIM_XOR_INSTANCE(TIMx) can be used to check whether or not - * a timer instance provides an XOR input. - * @rmtoll CR2 TI1S LL_TIM_IC_EnableXORCombination - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_IC_EnableXORCombination(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->CR2, TIM_CR2_TI1S); -} - -/** - * @brief Disconnect the TIMx_CH1, CH2 and CH3 pins from the TI1 input. - * @note Macro IS_TIM_XOR_INSTANCE(TIMx) can be used to check whether or not - * a timer instance provides an XOR input. - * @rmtoll CR2 TI1S LL_TIM_IC_DisableXORCombination - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_IC_DisableXORCombination(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->CR2, TIM_CR2_TI1S); -} - -/** - * @brief Indicates whether the TIMx_CH1, CH2 and CH3 pins are connectected to the TI1 input. - * @note Macro IS_TIM_XOR_INSTANCE(TIMx) can be used to check whether or not - * a timer instance provides an XOR input. - * @rmtoll CR2 TI1S LL_TIM_IC_IsEnabledXORCombination - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IC_IsEnabledXORCombination(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->CR2, TIM_CR2_TI1S) == (TIM_CR2_TI1S)) ? 1UL : 0UL); -} - -/** - * @brief Get captured value for input channel 1. - * @note In 32-bit timer implementations returned captured value can be between 0x00000000 and 0xFFFFFFFF. - * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports a 32 bits counter. - * @note Macro IS_TIM_CC1_INSTANCE(TIMx) can be used to check whether or not - * input channel 1 is supported by a timer instance. - * @rmtoll CCR1 CCR1 LL_TIM_IC_GetCaptureCH1 - * @param TIMx Timer instance - * @retval CapturedValue (between Min_Data=0 and Max_Data=65535) - */ -__STATIC_INLINE uint32_t LL_TIM_IC_GetCaptureCH1(TIM_TypeDef *TIMx) -{ - return (uint32_t)(READ_REG(TIMx->CCR1)); -} - -/** - * @brief Get captured value for input channel 2. - * @note In 32-bit timer implementations returned captured value can be between 0x00000000 and 0xFFFFFFFF. - * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports a 32 bits counter. - * @note Macro IS_TIM_CC2_INSTANCE(TIMx) can be used to check whether or not - * input channel 2 is supported by a timer instance. - * @rmtoll CCR2 CCR2 LL_TIM_IC_GetCaptureCH2 - * @param TIMx Timer instance - * @retval CapturedValue (between Min_Data=0 and Max_Data=65535) - */ -__STATIC_INLINE uint32_t LL_TIM_IC_GetCaptureCH2(TIM_TypeDef *TIMx) -{ - return (uint32_t)(READ_REG(TIMx->CCR2)); -} - -/** - * @brief Get captured value for input channel 3. - * @note In 32-bit timer implementations returned captured value can be between 0x00000000 and 0xFFFFFFFF. - * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports a 32 bits counter. - * @note Macro IS_TIM_CC3_INSTANCE(TIMx) can be used to check whether or not - * input channel 3 is supported by a timer instance. - * @rmtoll CCR3 CCR3 LL_TIM_IC_GetCaptureCH3 - * @param TIMx Timer instance - * @retval CapturedValue (between Min_Data=0 and Max_Data=65535) - */ -__STATIC_INLINE uint32_t LL_TIM_IC_GetCaptureCH3(TIM_TypeDef *TIMx) -{ - return (uint32_t)(READ_REG(TIMx->CCR3)); -} - -/** - * @brief Get captured value for input channel 4. - * @note In 32-bit timer implementations returned captured value can be between 0x00000000 and 0xFFFFFFFF. - * @note Macro IS_TIM_32B_COUNTER_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports a 32 bits counter. - * @note Macro IS_TIM_CC4_INSTANCE(TIMx) can be used to check whether or not - * input channel 4 is supported by a timer instance. - * @rmtoll CCR4 CCR4 LL_TIM_IC_GetCaptureCH4 - * @param TIMx Timer instance - * @retval CapturedValue (between Min_Data=0 and Max_Data=65535) - */ -__STATIC_INLINE uint32_t LL_TIM_IC_GetCaptureCH4(TIM_TypeDef *TIMx) -{ - return (uint32_t)(READ_REG(TIMx->CCR4)); -} - -/** - * @} - */ - -/** @defgroup TIM_LL_EF_Clock_Selection Counter clock selection - * @{ - */ -/** - * @brief Enable external clock mode 2. - * @note When external clock mode 2 is enabled the counter is clocked by any active edge on the ETRF signal. - * @note Macro IS_TIM_CLOCKSOURCE_ETRMODE2_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports external clock mode2. - * @rmtoll SMCR ECE LL_TIM_EnableExternalClock - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableExternalClock(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->SMCR, TIM_SMCR_ECE); -} - -/** - * @brief Disable external clock mode 2. - * @note Macro IS_TIM_CLOCKSOURCE_ETRMODE2_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports external clock mode2. - * @rmtoll SMCR ECE LL_TIM_DisableExternalClock - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableExternalClock(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->SMCR, TIM_SMCR_ECE); -} - -/** - * @brief Indicate whether external clock mode 2 is enabled. - * @note Macro IS_TIM_CLOCKSOURCE_ETRMODE2_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports external clock mode2. - * @rmtoll SMCR ECE LL_TIM_IsEnabledExternalClock - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsEnabledExternalClock(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->SMCR, TIM_SMCR_ECE) == (TIM_SMCR_ECE)) ? 1UL : 0UL); -} - -/** - * @brief Set the clock source of the counter clock. - * @note when selected clock source is external clock mode 1, the timer input - * the external clock is applied is selected by calling the @ref LL_TIM_SetTriggerInput() - * function. This timer input must be configured by calling - * the @ref LL_TIM_IC_Config() function. - * @note Macro IS_TIM_CLOCKSOURCE_ETRMODE1_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports external clock mode1. - * @note Macro IS_TIM_CLOCKSOURCE_ETRMODE2_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports external clock mode2. - * @rmtoll SMCR SMS LL_TIM_SetClockSource\n - * SMCR ECE LL_TIM_SetClockSource - * @param TIMx Timer instance - * @param ClockSource This parameter can be one of the following values: - * @arg @ref LL_TIM_CLOCKSOURCE_INTERNAL - * @arg @ref LL_TIM_CLOCKSOURCE_EXT_MODE1 - * @arg @ref LL_TIM_CLOCKSOURCE_EXT_MODE2 - * @retval None - */ -__STATIC_INLINE void LL_TIM_SetClockSource(TIM_TypeDef *TIMx, uint32_t ClockSource) -{ - MODIFY_REG(TIMx->SMCR, TIM_SMCR_SMS | TIM_SMCR_ECE, ClockSource); -} - -/** - * @brief Set the encoder interface mode. - * @note Macro IS_TIM_ENCODER_INTERFACE_INSTANCE(TIMx) can be used to check - * whether or not a timer instance supports the encoder mode. - * @rmtoll SMCR SMS LL_TIM_SetEncoderMode - * @param TIMx Timer instance - * @param EncoderMode This parameter can be one of the following values: - * @arg @ref LL_TIM_ENCODERMODE_X2_TI1 - * @arg @ref LL_TIM_ENCODERMODE_X2_TI2 - * @arg @ref LL_TIM_ENCODERMODE_X4_TI12 - * @retval None - */ -__STATIC_INLINE void LL_TIM_SetEncoderMode(TIM_TypeDef *TIMx, uint32_t EncoderMode) -{ - MODIFY_REG(TIMx->SMCR, TIM_SMCR_SMS, EncoderMode); -} - -/** - * @} - */ - -/** @defgroup TIM_LL_EF_Timer_Synchronization Timer synchronisation configuration - * @{ - */ -/** - * @brief Set the trigger output (TRGO) used for timer synchronization . - * @note Macro IS_TIM_MASTER_INSTANCE(TIMx) can be used to check - * whether or not a timer instance can operate as a master timer. - * @rmtoll CR2 MMS LL_TIM_SetTriggerOutput - * @param TIMx Timer instance - * @param TimerSynchronization This parameter can be one of the following values: - * @arg @ref LL_TIM_TRGO_RESET - * @arg @ref LL_TIM_TRGO_ENABLE - * @arg @ref LL_TIM_TRGO_UPDATE - * @arg @ref LL_TIM_TRGO_CC1IF - * @arg @ref LL_TIM_TRGO_OC1REF - * @arg @ref LL_TIM_TRGO_OC2REF - * @arg @ref LL_TIM_TRGO_OC3REF - * @arg @ref LL_TIM_TRGO_OC4REF - * @retval None - */ -__STATIC_INLINE void LL_TIM_SetTriggerOutput(TIM_TypeDef *TIMx, uint32_t TimerSynchronization) -{ - MODIFY_REG(TIMx->CR2, TIM_CR2_MMS, TimerSynchronization); -} - -/** - * @brief Set the synchronization mode of a slave timer. - * @note Macro IS_TIM_SLAVE_INSTANCE(TIMx) can be used to check whether or not - * a timer instance can operate as a slave timer. - * @rmtoll SMCR SMS LL_TIM_SetSlaveMode - * @param TIMx Timer instance - * @param SlaveMode This parameter can be one of the following values: - * @arg @ref LL_TIM_SLAVEMODE_DISABLED - * @arg @ref LL_TIM_SLAVEMODE_RESET - * @arg @ref LL_TIM_SLAVEMODE_GATED - * @arg @ref LL_TIM_SLAVEMODE_TRIGGER - * @retval None - */ -__STATIC_INLINE void LL_TIM_SetSlaveMode(TIM_TypeDef *TIMx, uint32_t SlaveMode) -{ - MODIFY_REG(TIMx->SMCR, TIM_SMCR_SMS, SlaveMode); -} - -/** - * @brief Set the selects the trigger input to be used to synchronize the counter. - * @note Macro IS_TIM_SLAVE_INSTANCE(TIMx) can be used to check whether or not - * a timer instance can operate as a slave timer. - * @rmtoll SMCR TS LL_TIM_SetTriggerInput - * @param TIMx Timer instance - * @param TriggerInput This parameter can be one of the following values: - * @arg @ref LL_TIM_TS_ITR0 - * @arg @ref LL_TIM_TS_ITR1 - * @arg @ref LL_TIM_TS_ITR2 - * @arg @ref LL_TIM_TS_ITR3 - * @arg @ref LL_TIM_TS_TI1F_ED - * @arg @ref LL_TIM_TS_TI1FP1 - * @arg @ref LL_TIM_TS_TI2FP2 - * @arg @ref LL_TIM_TS_ETRF - * @retval None - */ -__STATIC_INLINE void LL_TIM_SetTriggerInput(TIM_TypeDef *TIMx, uint32_t TriggerInput) -{ - MODIFY_REG(TIMx->SMCR, TIM_SMCR_TS, TriggerInput); -} - -/** - * @brief Enable the Master/Slave mode. - * @note Macro IS_TIM_SLAVE_INSTANCE(TIMx) can be used to check whether or not - * a timer instance can operate as a slave timer. - * @rmtoll SMCR MSM LL_TIM_EnableMasterSlaveMode - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableMasterSlaveMode(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->SMCR, TIM_SMCR_MSM); -} - -/** - * @brief Disable the Master/Slave mode. - * @note Macro IS_TIM_SLAVE_INSTANCE(TIMx) can be used to check whether or not - * a timer instance can operate as a slave timer. - * @rmtoll SMCR MSM LL_TIM_DisableMasterSlaveMode - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableMasterSlaveMode(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->SMCR, TIM_SMCR_MSM); -} - -/** - * @brief Indicates whether the Master/Slave mode is enabled. - * @note Macro IS_TIM_SLAVE_INSTANCE(TIMx) can be used to check whether or not - * a timer instance can operate as a slave timer. - * @rmtoll SMCR MSM LL_TIM_IsEnabledMasterSlaveMode - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsEnabledMasterSlaveMode(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->SMCR, TIM_SMCR_MSM) == (TIM_SMCR_MSM)) ? 1UL : 0UL); -} - -/** - * @brief Configure the external trigger (ETR) input. - * @note Macro IS_TIM_ETR_INSTANCE(TIMx) can be used to check whether or not - * a timer instance provides an external trigger input. - * @rmtoll SMCR ETP LL_TIM_ConfigETR\n - * SMCR ETPS LL_TIM_ConfigETR\n - * SMCR ETF LL_TIM_ConfigETR - * @param TIMx Timer instance - * @param ETRPolarity This parameter can be one of the following values: - * @arg @ref LL_TIM_ETR_POLARITY_NONINVERTED - * @arg @ref LL_TIM_ETR_POLARITY_INVERTED - * @param ETRPrescaler This parameter can be one of the following values: - * @arg @ref LL_TIM_ETR_PRESCALER_DIV1 - * @arg @ref LL_TIM_ETR_PRESCALER_DIV2 - * @arg @ref LL_TIM_ETR_PRESCALER_DIV4 - * @arg @ref LL_TIM_ETR_PRESCALER_DIV8 - * @param ETRFilter This parameter can be one of the following values: - * @arg @ref LL_TIM_ETR_FILTER_FDIV1 - * @arg @ref LL_TIM_ETR_FILTER_FDIV1_N2 - * @arg @ref LL_TIM_ETR_FILTER_FDIV1_N4 - * @arg @ref LL_TIM_ETR_FILTER_FDIV1_N8 - * @arg @ref LL_TIM_ETR_FILTER_FDIV2_N6 - * @arg @ref LL_TIM_ETR_FILTER_FDIV2_N8 - * @arg @ref LL_TIM_ETR_FILTER_FDIV4_N6 - * @arg @ref LL_TIM_ETR_FILTER_FDIV4_N8 - * @arg @ref LL_TIM_ETR_FILTER_FDIV8_N6 - * @arg @ref LL_TIM_ETR_FILTER_FDIV8_N8 - * @arg @ref LL_TIM_ETR_FILTER_FDIV16_N5 - * @arg @ref LL_TIM_ETR_FILTER_FDIV16_N6 - * @arg @ref LL_TIM_ETR_FILTER_FDIV16_N8 - * @arg @ref LL_TIM_ETR_FILTER_FDIV32_N5 - * @arg @ref LL_TIM_ETR_FILTER_FDIV32_N6 - * @arg @ref LL_TIM_ETR_FILTER_FDIV32_N8 - * @retval None - */ -__STATIC_INLINE void LL_TIM_ConfigETR(TIM_TypeDef *TIMx, uint32_t ETRPolarity, uint32_t ETRPrescaler, - uint32_t ETRFilter) -{ - MODIFY_REG(TIMx->SMCR, TIM_SMCR_ETP | TIM_SMCR_ETPS | TIM_SMCR_ETF, ETRPolarity | ETRPrescaler | ETRFilter); -} - -/** - * @} - */ - -/** @defgroup TIM_LL_EF_Break_Function Break function configuration - * @{ - */ -/** - * @brief Enable the break function. - * @note Macro IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not - * a timer instance provides a break input. - * @rmtoll BDTR BKE LL_TIM_EnableBRK - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableBRK(TIM_TypeDef *TIMx) -{ - __IO uint32_t tmpreg; - SET_BIT(TIMx->BDTR, TIM_BDTR_BKE); - /* Note: Any write operation to this bit takes a delay of 1 APB clock cycle to become effective. */ - tmpreg = READ_REG(TIMx->BDTR); - (void)(tmpreg); -} - -/** - * @brief Disable the break function. - * @rmtoll BDTR BKE LL_TIM_DisableBRK - * @param TIMx Timer instance - * @note Macro IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not - * a timer instance provides a break input. - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableBRK(TIM_TypeDef *TIMx) -{ - __IO uint32_t tmpreg; - CLEAR_BIT(TIMx->BDTR, TIM_BDTR_BKE); - /* Note: Any write operation to this bit takes a delay of 1 APB clock cycle to become effective. */ - tmpreg = READ_REG(TIMx->BDTR); - (void)(tmpreg); -} - -/** - * @brief Configure the break input. - * @note Macro IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not - * a timer instance provides a break input. - * @rmtoll BDTR BKP LL_TIM_ConfigBRK - * @param TIMx Timer instance - * @param BreakPolarity This parameter can be one of the following values: - * @arg @ref LL_TIM_BREAK_POLARITY_LOW - * @arg @ref LL_TIM_BREAK_POLARITY_HIGH - * @retval None - */ -__STATIC_INLINE void LL_TIM_ConfigBRK(TIM_TypeDef *TIMx, uint32_t BreakPolarity) -{ - __IO uint32_t tmpreg; - MODIFY_REG(TIMx->BDTR, TIM_BDTR_BKP, BreakPolarity); - /* Note: Any write operation to BKP bit takes a delay of 1 APB clock cycle to become effective. */ - tmpreg = READ_REG(TIMx->BDTR); - (void)(tmpreg); -} - -/** - * @brief Select the outputs off state (enabled v.s. disabled) in Idle and Run modes. - * @note Macro IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not - * a timer instance provides a break input. - * @rmtoll BDTR OSSI LL_TIM_SetOffStates\n - * BDTR OSSR LL_TIM_SetOffStates - * @param TIMx Timer instance - * @param OffStateIdle This parameter can be one of the following values: - * @arg @ref LL_TIM_OSSI_DISABLE - * @arg @ref LL_TIM_OSSI_ENABLE - * @param OffStateRun This parameter can be one of the following values: - * @arg @ref LL_TIM_OSSR_DISABLE - * @arg @ref LL_TIM_OSSR_ENABLE - * @retval None - */ -__STATIC_INLINE void LL_TIM_SetOffStates(TIM_TypeDef *TIMx, uint32_t OffStateIdle, uint32_t OffStateRun) -{ - MODIFY_REG(TIMx->BDTR, TIM_BDTR_OSSI | TIM_BDTR_OSSR, OffStateIdle | OffStateRun); -} - -/** - * @brief Enable automatic output (MOE can be set by software or automatically when a break input is active). - * @note Macro IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not - * a timer instance provides a break input. - * @rmtoll BDTR AOE LL_TIM_EnableAutomaticOutput - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableAutomaticOutput(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->BDTR, TIM_BDTR_AOE); -} - -/** - * @brief Disable automatic output (MOE can be set only by software). - * @note Macro IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not - * a timer instance provides a break input. - * @rmtoll BDTR AOE LL_TIM_DisableAutomaticOutput - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableAutomaticOutput(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->BDTR, TIM_BDTR_AOE); -} - -/** - * @brief Indicate whether automatic output is enabled. - * @note Macro IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not - * a timer instance provides a break input. - * @rmtoll BDTR AOE LL_TIM_IsEnabledAutomaticOutput - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsEnabledAutomaticOutput(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->BDTR, TIM_BDTR_AOE) == (TIM_BDTR_AOE)) ? 1UL : 0UL); -} - -/** - * @brief Enable the outputs (set the MOE bit in TIMx_BDTR register). - * @note The MOE bit in TIMx_BDTR register allows to enable /disable the outputs by - * software and is reset in case of break or break2 event - * @note Macro IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not - * a timer instance provides a break input. - * @rmtoll BDTR MOE LL_TIM_EnableAllOutputs - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableAllOutputs(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->BDTR, TIM_BDTR_MOE); -} - -/** - * @brief Disable the outputs (reset the MOE bit in TIMx_BDTR register). - * @note The MOE bit in TIMx_BDTR register allows to enable /disable the outputs by - * software and is reset in case of break or break2 event. - * @note Macro IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not - * a timer instance provides a break input. - * @rmtoll BDTR MOE LL_TIM_DisableAllOutputs - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableAllOutputs(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->BDTR, TIM_BDTR_MOE); -} - -/** - * @brief Indicates whether outputs are enabled. - * @note Macro IS_TIM_BREAK_INSTANCE(TIMx) can be used to check whether or not - * a timer instance provides a break input. - * @rmtoll BDTR MOE LL_TIM_IsEnabledAllOutputs - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsEnabledAllOutputs(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->BDTR, TIM_BDTR_MOE) == (TIM_BDTR_MOE)) ? 1UL : 0UL); -} - -/** - * @} - */ - -/** @defgroup TIM_LL_EF_DMA_Burst_Mode DMA burst mode configuration - * @{ - */ -/** - * @brief Configures the timer DMA burst feature. - * @note Macro IS_TIM_DMABURST_INSTANCE(TIMx) can be used to check whether or - * not a timer instance supports the DMA burst mode. - * @rmtoll DCR DBL LL_TIM_ConfigDMABurst\n - * DCR DBA LL_TIM_ConfigDMABurst - * @param TIMx Timer instance - * @param DMABurstBaseAddress This parameter can be one of the following values: - * @arg @ref LL_TIM_DMABURST_BASEADDR_CR1 - * @arg @ref LL_TIM_DMABURST_BASEADDR_CR2 - * @arg @ref LL_TIM_DMABURST_BASEADDR_SMCR - * @arg @ref LL_TIM_DMABURST_BASEADDR_DIER - * @arg @ref LL_TIM_DMABURST_BASEADDR_SR - * @arg @ref LL_TIM_DMABURST_BASEADDR_EGR - * @arg @ref LL_TIM_DMABURST_BASEADDR_CCMR1 - * @arg @ref LL_TIM_DMABURST_BASEADDR_CCMR2 - * @arg @ref LL_TIM_DMABURST_BASEADDR_CCER - * @arg @ref LL_TIM_DMABURST_BASEADDR_CNT - * @arg @ref LL_TIM_DMABURST_BASEADDR_PSC - * @arg @ref LL_TIM_DMABURST_BASEADDR_ARR - * @arg @ref LL_TIM_DMABURST_BASEADDR_RCR - * @arg @ref LL_TIM_DMABURST_BASEADDR_CCR1 - * @arg @ref LL_TIM_DMABURST_BASEADDR_CCR2 - * @arg @ref LL_TIM_DMABURST_BASEADDR_CCR3 - * @arg @ref LL_TIM_DMABURST_BASEADDR_CCR4 - * @arg @ref LL_TIM_DMABURST_BASEADDR_BDTR - * @param DMABurstLength This parameter can be one of the following values: - * @arg @ref LL_TIM_DMABURST_LENGTH_1TRANSFER - * @arg @ref LL_TIM_DMABURST_LENGTH_2TRANSFERS - * @arg @ref LL_TIM_DMABURST_LENGTH_3TRANSFERS - * @arg @ref LL_TIM_DMABURST_LENGTH_4TRANSFERS - * @arg @ref LL_TIM_DMABURST_LENGTH_5TRANSFERS - * @arg @ref LL_TIM_DMABURST_LENGTH_6TRANSFERS - * @arg @ref LL_TIM_DMABURST_LENGTH_7TRANSFERS - * @arg @ref LL_TIM_DMABURST_LENGTH_8TRANSFERS - * @arg @ref LL_TIM_DMABURST_LENGTH_9TRANSFERS - * @arg @ref LL_TIM_DMABURST_LENGTH_10TRANSFERS - * @arg @ref LL_TIM_DMABURST_LENGTH_11TRANSFERS - * @arg @ref LL_TIM_DMABURST_LENGTH_12TRANSFERS - * @arg @ref LL_TIM_DMABURST_LENGTH_13TRANSFERS - * @arg @ref LL_TIM_DMABURST_LENGTH_14TRANSFERS - * @arg @ref LL_TIM_DMABURST_LENGTH_15TRANSFERS - * @arg @ref LL_TIM_DMABURST_LENGTH_16TRANSFERS - * @arg @ref LL_TIM_DMABURST_LENGTH_17TRANSFERS - * @arg @ref LL_TIM_DMABURST_LENGTH_18TRANSFERS - * @retval None - */ -__STATIC_INLINE void LL_TIM_ConfigDMABurst(TIM_TypeDef *TIMx, uint32_t DMABurstBaseAddress, uint32_t DMABurstLength) -{ - MODIFY_REG(TIMx->DCR, (TIM_DCR_DBL | TIM_DCR_DBA), (DMABurstBaseAddress | DMABurstLength)); -} - -/** - * @} - */ - -/** @defgroup TIM_LL_EF_Timer_Inputs_Remapping Timer input remapping - * @{ - */ -/** - * @brief Remap TIM inputs (input channel, internal/external triggers). - * @note Macro IS_TIM_REMAP_INSTANCE(TIMx) can be used to check whether or not - * a some timer inputs can be remapped. - * @rmtoll TIM1_OR ITR2_RMP LL_TIM_SetRemap\n - * TIM2_OR ITR1_RMP LL_TIM_SetRemap\n - * TIM5_OR ITR1_RMP LL_TIM_SetRemap\n - * TIM5_OR TI4_RMP LL_TIM_SetRemap\n - * TIM9_OR ITR1_RMP LL_TIM_SetRemap\n - * TIM11_OR TI1_RMP LL_TIM_SetRemap\n - * LPTIM1_OR OR LL_TIM_SetRemap - * @param TIMx Timer instance - * @param Remap Remap param depends on the TIMx. Description available only - * in CHM version of the User Manual (not in .pdf). - * Otherwise see Reference Manual description of OR registers. - * - * Below description summarizes "Timer Instance" and "Remap" param combinations: - * - * TIM1: one of the following values - * - * ITR2_RMP can be one of the following values - * @arg @ref LL_TIM_TIM1_ITR2_RMP_TIM3_TRGO (*) - * @arg @ref LL_TIM_TIM1_ITR2_RMP_LPTIM (*) - * - * TIM2: one of the following values - * - * ITR1_RMP can be one of the following values - * @arg @ref LL_TIM_TIM2_ITR1_RMP_TIM8_TRGO - * @arg @ref LL_TIM_TIM2_ITR1_RMP_OTG_FS_SOF - * @arg @ref LL_TIM_TIM2_ITR1_RMP_OTG_HS_SOF - * - * TIM5: one of the following values - * - * @arg @ref LL_TIM_TIM5_TI4_RMP_GPIO - * @arg @ref LL_TIM_TIM5_TI4_RMP_LSI - * @arg @ref LL_TIM_TIM5_TI4_RMP_LSE - * @arg @ref LL_TIM_TIM5_TI4_RMP_RTC - * @arg @ref LL_TIM_TIM5_ITR1_RMP_TIM3_TRGO (*) - * @arg @ref LL_TIM_TIM5_ITR1_RMP_LPTIM (*) - * - * TIM9: one of the following values - * - * ITR1_RMP can be one of the following values - * @arg @ref LL_TIM_TIM9_ITR1_RMP_TIM3_TRGO (*) - * @arg @ref LL_TIM_TIM9_ITR1_RMP_LPTIM (*) - * - * TIM11: one of the following values - * - * @arg @ref LL_TIM_TIM11_TI1_RMP_GPIO - * @arg @ref LL_TIM_TIM11_TI1_RMP_GPIO1 (*) - * @arg @ref LL_TIM_TIM11_TI1_RMP_HSE_RTC - * @arg @ref LL_TIM_TIM11_TI1_RMP_GPIO2 - * @arg @ref LL_TIM_TIM11_TI1_RMP_SPDIFRX (*) - * - * (*) Value not defined in all devices. \n - * - * @retval None - */ -__STATIC_INLINE void LL_TIM_SetRemap(TIM_TypeDef *TIMx, uint32_t Remap) -{ -#if defined(LPTIM_OR_TIM1_ITR2_RMP) && defined(LPTIM_OR_TIM5_ITR1_RMP) && defined(LPTIM_OR_TIM9_ITR1_RMP) - if ((Remap & LL_TIM_LPTIM_REMAP_MASK) == LL_TIM_LPTIM_REMAP_MASK) - { - /* Connect TIMx internal trigger to LPTIM1 output */ - SET_BIT(RCC->APB1ENR, RCC_APB1ENR_LPTIM1EN); - MODIFY_REG(LPTIM1->OR, - (LPTIM_OR_TIM1_ITR2_RMP | LPTIM_OR_TIM5_ITR1_RMP | LPTIM_OR_TIM9_ITR1_RMP), - Remap & ~(LL_TIM_LPTIM_REMAP_MASK)); - } - else - { - MODIFY_REG(TIMx->OR, (Remap >> TIMx_OR_RMP_SHIFT), (Remap & TIMx_OR_RMP_MASK)); - } -#else - MODIFY_REG(TIMx->OR, (Remap >> TIMx_OR_RMP_SHIFT), (Remap & TIMx_OR_RMP_MASK)); -#endif /* LPTIM_OR_TIM1_ITR2_RMP && LPTIM_OR_TIM5_ITR1_RMP && LPTIM_OR_TIM9_ITR1_RMP */ -} - -/** - * @} - */ - -/** @defgroup TIM_LL_EF_FLAG_Management FLAG-Management - * @{ - */ -/** - * @brief Clear the update interrupt flag (UIF). - * @rmtoll SR UIF LL_TIM_ClearFlag_UPDATE - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_ClearFlag_UPDATE(TIM_TypeDef *TIMx) -{ - WRITE_REG(TIMx->SR, ~(TIM_SR_UIF)); -} - -/** - * @brief Indicate whether update interrupt flag (UIF) is set (update interrupt is pending). - * @rmtoll SR UIF LL_TIM_IsActiveFlag_UPDATE - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsActiveFlag_UPDATE(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->SR, TIM_SR_UIF) == (TIM_SR_UIF)) ? 1UL : 0UL); -} - -/** - * @brief Clear the Capture/Compare 1 interrupt flag (CC1F). - * @rmtoll SR CC1IF LL_TIM_ClearFlag_CC1 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_ClearFlag_CC1(TIM_TypeDef *TIMx) -{ - WRITE_REG(TIMx->SR, ~(TIM_SR_CC1IF)); -} - -/** - * @brief Indicate whether Capture/Compare 1 interrupt flag (CC1F) is set (Capture/Compare 1 interrupt is pending). - * @rmtoll SR CC1IF LL_TIM_IsActiveFlag_CC1 - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsActiveFlag_CC1(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->SR, TIM_SR_CC1IF) == (TIM_SR_CC1IF)) ? 1UL : 0UL); -} - -/** - * @brief Clear the Capture/Compare 2 interrupt flag (CC2F). - * @rmtoll SR CC2IF LL_TIM_ClearFlag_CC2 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_ClearFlag_CC2(TIM_TypeDef *TIMx) -{ - WRITE_REG(TIMx->SR, ~(TIM_SR_CC2IF)); -} - -/** - * @brief Indicate whether Capture/Compare 2 interrupt flag (CC2F) is set (Capture/Compare 2 interrupt is pending). - * @rmtoll SR CC2IF LL_TIM_IsActiveFlag_CC2 - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsActiveFlag_CC2(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->SR, TIM_SR_CC2IF) == (TIM_SR_CC2IF)) ? 1UL : 0UL); -} - -/** - * @brief Clear the Capture/Compare 3 interrupt flag (CC3F). - * @rmtoll SR CC3IF LL_TIM_ClearFlag_CC3 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_ClearFlag_CC3(TIM_TypeDef *TIMx) -{ - WRITE_REG(TIMx->SR, ~(TIM_SR_CC3IF)); -} - -/** - * @brief Indicate whether Capture/Compare 3 interrupt flag (CC3F) is set (Capture/Compare 3 interrupt is pending). - * @rmtoll SR CC3IF LL_TIM_IsActiveFlag_CC3 - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsActiveFlag_CC3(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->SR, TIM_SR_CC3IF) == (TIM_SR_CC3IF)) ? 1UL : 0UL); -} - -/** - * @brief Clear the Capture/Compare 4 interrupt flag (CC4F). - * @rmtoll SR CC4IF LL_TIM_ClearFlag_CC4 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_ClearFlag_CC4(TIM_TypeDef *TIMx) -{ - WRITE_REG(TIMx->SR, ~(TIM_SR_CC4IF)); -} - -/** - * @brief Indicate whether Capture/Compare 4 interrupt flag (CC4F) is set (Capture/Compare 4 interrupt is pending). - * @rmtoll SR CC4IF LL_TIM_IsActiveFlag_CC4 - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsActiveFlag_CC4(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->SR, TIM_SR_CC4IF) == (TIM_SR_CC4IF)) ? 1UL : 0UL); -} - -/** - * @brief Clear the commutation interrupt flag (COMIF). - * @rmtoll SR COMIF LL_TIM_ClearFlag_COM - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_ClearFlag_COM(TIM_TypeDef *TIMx) -{ - WRITE_REG(TIMx->SR, ~(TIM_SR_COMIF)); -} - -/** - * @brief Indicate whether commutation interrupt flag (COMIF) is set (commutation interrupt is pending). - * @rmtoll SR COMIF LL_TIM_IsActiveFlag_COM - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsActiveFlag_COM(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->SR, TIM_SR_COMIF) == (TIM_SR_COMIF)) ? 1UL : 0UL); -} - -/** - * @brief Clear the trigger interrupt flag (TIF). - * @rmtoll SR TIF LL_TIM_ClearFlag_TRIG - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_ClearFlag_TRIG(TIM_TypeDef *TIMx) -{ - WRITE_REG(TIMx->SR, ~(TIM_SR_TIF)); -} - -/** - * @brief Indicate whether trigger interrupt flag (TIF) is set (trigger interrupt is pending). - * @rmtoll SR TIF LL_TIM_IsActiveFlag_TRIG - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsActiveFlag_TRIG(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->SR, TIM_SR_TIF) == (TIM_SR_TIF)) ? 1UL : 0UL); -} - -/** - * @brief Clear the break interrupt flag (BIF). - * @rmtoll SR BIF LL_TIM_ClearFlag_BRK - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_ClearFlag_BRK(TIM_TypeDef *TIMx) -{ - WRITE_REG(TIMx->SR, ~(TIM_SR_BIF)); -} - -/** - * @brief Indicate whether break interrupt flag (BIF) is set (break interrupt is pending). - * @rmtoll SR BIF LL_TIM_IsActiveFlag_BRK - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsActiveFlag_BRK(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->SR, TIM_SR_BIF) == (TIM_SR_BIF)) ? 1UL : 0UL); -} - -/** - * @brief Clear the Capture/Compare 1 over-capture interrupt flag (CC1OF). - * @rmtoll SR CC1OF LL_TIM_ClearFlag_CC1OVR - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_ClearFlag_CC1OVR(TIM_TypeDef *TIMx) -{ - WRITE_REG(TIMx->SR, ~(TIM_SR_CC1OF)); -} - -/** - * @brief Indicate whether Capture/Compare 1 over-capture interrupt flag (CC1OF) is set - * (Capture/Compare 1 interrupt is pending). - * @rmtoll SR CC1OF LL_TIM_IsActiveFlag_CC1OVR - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsActiveFlag_CC1OVR(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->SR, TIM_SR_CC1OF) == (TIM_SR_CC1OF)) ? 1UL : 0UL); -} - -/** - * @brief Clear the Capture/Compare 2 over-capture interrupt flag (CC2OF). - * @rmtoll SR CC2OF LL_TIM_ClearFlag_CC2OVR - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_ClearFlag_CC2OVR(TIM_TypeDef *TIMx) -{ - WRITE_REG(TIMx->SR, ~(TIM_SR_CC2OF)); -} - -/** - * @brief Indicate whether Capture/Compare 2 over-capture interrupt flag (CC2OF) is set - * (Capture/Compare 2 over-capture interrupt is pending). - * @rmtoll SR CC2OF LL_TIM_IsActiveFlag_CC2OVR - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsActiveFlag_CC2OVR(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->SR, TIM_SR_CC2OF) == (TIM_SR_CC2OF)) ? 1UL : 0UL); -} - -/** - * @brief Clear the Capture/Compare 3 over-capture interrupt flag (CC3OF). - * @rmtoll SR CC3OF LL_TIM_ClearFlag_CC3OVR - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_ClearFlag_CC3OVR(TIM_TypeDef *TIMx) -{ - WRITE_REG(TIMx->SR, ~(TIM_SR_CC3OF)); -} - -/** - * @brief Indicate whether Capture/Compare 3 over-capture interrupt flag (CC3OF) is set - * (Capture/Compare 3 over-capture interrupt is pending). - * @rmtoll SR CC3OF LL_TIM_IsActiveFlag_CC3OVR - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsActiveFlag_CC3OVR(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->SR, TIM_SR_CC3OF) == (TIM_SR_CC3OF)) ? 1UL : 0UL); -} - -/** - * @brief Clear the Capture/Compare 4 over-capture interrupt flag (CC4OF). - * @rmtoll SR CC4OF LL_TIM_ClearFlag_CC4OVR - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_ClearFlag_CC4OVR(TIM_TypeDef *TIMx) -{ - WRITE_REG(TIMx->SR, ~(TIM_SR_CC4OF)); -} - -/** - * @brief Indicate whether Capture/Compare 4 over-capture interrupt flag (CC4OF) is set - * (Capture/Compare 4 over-capture interrupt is pending). - * @rmtoll SR CC4OF LL_TIM_IsActiveFlag_CC4OVR - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsActiveFlag_CC4OVR(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->SR, TIM_SR_CC4OF) == (TIM_SR_CC4OF)) ? 1UL : 0UL); -} - -/** - * @} - */ - -/** @defgroup TIM_LL_EF_IT_Management IT-Management - * @{ - */ -/** - * @brief Enable update interrupt (UIE). - * @rmtoll DIER UIE LL_TIM_EnableIT_UPDATE - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableIT_UPDATE(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->DIER, TIM_DIER_UIE); -} - -/** - * @brief Disable update interrupt (UIE). - * @rmtoll DIER UIE LL_TIM_DisableIT_UPDATE - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableIT_UPDATE(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->DIER, TIM_DIER_UIE); -} - -/** - * @brief Indicates whether the update interrupt (UIE) is enabled. - * @rmtoll DIER UIE LL_TIM_IsEnabledIT_UPDATE - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsEnabledIT_UPDATE(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->DIER, TIM_DIER_UIE) == (TIM_DIER_UIE)) ? 1UL : 0UL); -} - -/** - * @brief Enable capture/compare 1 interrupt (CC1IE). - * @rmtoll DIER CC1IE LL_TIM_EnableIT_CC1 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableIT_CC1(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->DIER, TIM_DIER_CC1IE); -} - -/** - * @brief Disable capture/compare 1 interrupt (CC1IE). - * @rmtoll DIER CC1IE LL_TIM_DisableIT_CC1 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableIT_CC1(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->DIER, TIM_DIER_CC1IE); -} - -/** - * @brief Indicates whether the capture/compare 1 interrupt (CC1IE) is enabled. - * @rmtoll DIER CC1IE LL_TIM_IsEnabledIT_CC1 - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsEnabledIT_CC1(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->DIER, TIM_DIER_CC1IE) == (TIM_DIER_CC1IE)) ? 1UL : 0UL); -} - -/** - * @brief Enable capture/compare 2 interrupt (CC2IE). - * @rmtoll DIER CC2IE LL_TIM_EnableIT_CC2 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableIT_CC2(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->DIER, TIM_DIER_CC2IE); -} - -/** - * @brief Disable capture/compare 2 interrupt (CC2IE). - * @rmtoll DIER CC2IE LL_TIM_DisableIT_CC2 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableIT_CC2(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->DIER, TIM_DIER_CC2IE); -} - -/** - * @brief Indicates whether the capture/compare 2 interrupt (CC2IE) is enabled. - * @rmtoll DIER CC2IE LL_TIM_IsEnabledIT_CC2 - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsEnabledIT_CC2(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->DIER, TIM_DIER_CC2IE) == (TIM_DIER_CC2IE)) ? 1UL : 0UL); -} - -/** - * @brief Enable capture/compare 3 interrupt (CC3IE). - * @rmtoll DIER CC3IE LL_TIM_EnableIT_CC3 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableIT_CC3(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->DIER, TIM_DIER_CC3IE); -} - -/** - * @brief Disable capture/compare 3 interrupt (CC3IE). - * @rmtoll DIER CC3IE LL_TIM_DisableIT_CC3 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableIT_CC3(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->DIER, TIM_DIER_CC3IE); -} - -/** - * @brief Indicates whether the capture/compare 3 interrupt (CC3IE) is enabled. - * @rmtoll DIER CC3IE LL_TIM_IsEnabledIT_CC3 - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsEnabledIT_CC3(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->DIER, TIM_DIER_CC3IE) == (TIM_DIER_CC3IE)) ? 1UL : 0UL); -} - -/** - * @brief Enable capture/compare 4 interrupt (CC4IE). - * @rmtoll DIER CC4IE LL_TIM_EnableIT_CC4 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableIT_CC4(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->DIER, TIM_DIER_CC4IE); -} - -/** - * @brief Disable capture/compare 4 interrupt (CC4IE). - * @rmtoll DIER CC4IE LL_TIM_DisableIT_CC4 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableIT_CC4(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->DIER, TIM_DIER_CC4IE); -} - -/** - * @brief Indicates whether the capture/compare 4 interrupt (CC4IE) is enabled. - * @rmtoll DIER CC4IE LL_TIM_IsEnabledIT_CC4 - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsEnabledIT_CC4(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->DIER, TIM_DIER_CC4IE) == (TIM_DIER_CC4IE)) ? 1UL : 0UL); -} - -/** - * @brief Enable commutation interrupt (COMIE). - * @rmtoll DIER COMIE LL_TIM_EnableIT_COM - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableIT_COM(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->DIER, TIM_DIER_COMIE); -} - -/** - * @brief Disable commutation interrupt (COMIE). - * @rmtoll DIER COMIE LL_TIM_DisableIT_COM - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableIT_COM(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->DIER, TIM_DIER_COMIE); -} - -/** - * @brief Indicates whether the commutation interrupt (COMIE) is enabled. - * @rmtoll DIER COMIE LL_TIM_IsEnabledIT_COM - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsEnabledIT_COM(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->DIER, TIM_DIER_COMIE) == (TIM_DIER_COMIE)) ? 1UL : 0UL); -} - -/** - * @brief Enable trigger interrupt (TIE). - * @rmtoll DIER TIE LL_TIM_EnableIT_TRIG - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableIT_TRIG(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->DIER, TIM_DIER_TIE); -} - -/** - * @brief Disable trigger interrupt (TIE). - * @rmtoll DIER TIE LL_TIM_DisableIT_TRIG - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableIT_TRIG(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->DIER, TIM_DIER_TIE); -} - -/** - * @brief Indicates whether the trigger interrupt (TIE) is enabled. - * @rmtoll DIER TIE LL_TIM_IsEnabledIT_TRIG - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsEnabledIT_TRIG(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->DIER, TIM_DIER_TIE) == (TIM_DIER_TIE)) ? 1UL : 0UL); -} - -/** - * @brief Enable break interrupt (BIE). - * @rmtoll DIER BIE LL_TIM_EnableIT_BRK - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableIT_BRK(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->DIER, TIM_DIER_BIE); -} - -/** - * @brief Disable break interrupt (BIE). - * @rmtoll DIER BIE LL_TIM_DisableIT_BRK - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableIT_BRK(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->DIER, TIM_DIER_BIE); -} - -/** - * @brief Indicates whether the break interrupt (BIE) is enabled. - * @rmtoll DIER BIE LL_TIM_IsEnabledIT_BRK - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsEnabledIT_BRK(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->DIER, TIM_DIER_BIE) == (TIM_DIER_BIE)) ? 1UL : 0UL); -} - -/** - * @} - */ - -/** @defgroup TIM_LL_EF_DMA_Management DMA Management - * @{ - */ -/** - * @brief Enable update DMA request (UDE). - * @rmtoll DIER UDE LL_TIM_EnableDMAReq_UPDATE - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableDMAReq_UPDATE(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->DIER, TIM_DIER_UDE); -} - -/** - * @brief Disable update DMA request (UDE). - * @rmtoll DIER UDE LL_TIM_DisableDMAReq_UPDATE - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableDMAReq_UPDATE(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->DIER, TIM_DIER_UDE); -} - -/** - * @brief Indicates whether the update DMA request (UDE) is enabled. - * @rmtoll DIER UDE LL_TIM_IsEnabledDMAReq_UPDATE - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsEnabledDMAReq_UPDATE(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->DIER, TIM_DIER_UDE) == (TIM_DIER_UDE)) ? 1UL : 0UL); -} - -/** - * @brief Enable capture/compare 1 DMA request (CC1DE). - * @rmtoll DIER CC1DE LL_TIM_EnableDMAReq_CC1 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableDMAReq_CC1(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->DIER, TIM_DIER_CC1DE); -} - -/** - * @brief Disable capture/compare 1 DMA request (CC1DE). - * @rmtoll DIER CC1DE LL_TIM_DisableDMAReq_CC1 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableDMAReq_CC1(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->DIER, TIM_DIER_CC1DE); -} - -/** - * @brief Indicates whether the capture/compare 1 DMA request (CC1DE) is enabled. - * @rmtoll DIER CC1DE LL_TIM_IsEnabledDMAReq_CC1 - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsEnabledDMAReq_CC1(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->DIER, TIM_DIER_CC1DE) == (TIM_DIER_CC1DE)) ? 1UL : 0UL); -} - -/** - * @brief Enable capture/compare 2 DMA request (CC2DE). - * @rmtoll DIER CC2DE LL_TIM_EnableDMAReq_CC2 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableDMAReq_CC2(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->DIER, TIM_DIER_CC2DE); -} - -/** - * @brief Disable capture/compare 2 DMA request (CC2DE). - * @rmtoll DIER CC2DE LL_TIM_DisableDMAReq_CC2 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableDMAReq_CC2(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->DIER, TIM_DIER_CC2DE); -} - -/** - * @brief Indicates whether the capture/compare 2 DMA request (CC2DE) is enabled. - * @rmtoll DIER CC2DE LL_TIM_IsEnabledDMAReq_CC2 - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsEnabledDMAReq_CC2(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->DIER, TIM_DIER_CC2DE) == (TIM_DIER_CC2DE)) ? 1UL : 0UL); -} - -/** - * @brief Enable capture/compare 3 DMA request (CC3DE). - * @rmtoll DIER CC3DE LL_TIM_EnableDMAReq_CC3 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableDMAReq_CC3(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->DIER, TIM_DIER_CC3DE); -} - -/** - * @brief Disable capture/compare 3 DMA request (CC3DE). - * @rmtoll DIER CC3DE LL_TIM_DisableDMAReq_CC3 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableDMAReq_CC3(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->DIER, TIM_DIER_CC3DE); -} - -/** - * @brief Indicates whether the capture/compare 3 DMA request (CC3DE) is enabled. - * @rmtoll DIER CC3DE LL_TIM_IsEnabledDMAReq_CC3 - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsEnabledDMAReq_CC3(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->DIER, TIM_DIER_CC3DE) == (TIM_DIER_CC3DE)) ? 1UL : 0UL); -} - -/** - * @brief Enable capture/compare 4 DMA request (CC4DE). - * @rmtoll DIER CC4DE LL_TIM_EnableDMAReq_CC4 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableDMAReq_CC4(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->DIER, TIM_DIER_CC4DE); -} - -/** - * @brief Disable capture/compare 4 DMA request (CC4DE). - * @rmtoll DIER CC4DE LL_TIM_DisableDMAReq_CC4 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableDMAReq_CC4(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->DIER, TIM_DIER_CC4DE); -} - -/** - * @brief Indicates whether the capture/compare 4 DMA request (CC4DE) is enabled. - * @rmtoll DIER CC4DE LL_TIM_IsEnabledDMAReq_CC4 - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsEnabledDMAReq_CC4(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->DIER, TIM_DIER_CC4DE) == (TIM_DIER_CC4DE)) ? 1UL : 0UL); -} - -/** - * @brief Enable commutation DMA request (COMDE). - * @rmtoll DIER COMDE LL_TIM_EnableDMAReq_COM - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableDMAReq_COM(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->DIER, TIM_DIER_COMDE); -} - -/** - * @brief Disable commutation DMA request (COMDE). - * @rmtoll DIER COMDE LL_TIM_DisableDMAReq_COM - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableDMAReq_COM(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->DIER, TIM_DIER_COMDE); -} - -/** - * @brief Indicates whether the commutation DMA request (COMDE) is enabled. - * @rmtoll DIER COMDE LL_TIM_IsEnabledDMAReq_COM - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsEnabledDMAReq_COM(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->DIER, TIM_DIER_COMDE) == (TIM_DIER_COMDE)) ? 1UL : 0UL); -} - -/** - * @brief Enable trigger interrupt (TDE). - * @rmtoll DIER TDE LL_TIM_EnableDMAReq_TRIG - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_EnableDMAReq_TRIG(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->DIER, TIM_DIER_TDE); -} - -/** - * @brief Disable trigger interrupt (TDE). - * @rmtoll DIER TDE LL_TIM_DisableDMAReq_TRIG - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_DisableDMAReq_TRIG(TIM_TypeDef *TIMx) -{ - CLEAR_BIT(TIMx->DIER, TIM_DIER_TDE); -} - -/** - * @brief Indicates whether the trigger interrupt (TDE) is enabled. - * @rmtoll DIER TDE LL_TIM_IsEnabledDMAReq_TRIG - * @param TIMx Timer instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_TIM_IsEnabledDMAReq_TRIG(TIM_TypeDef *TIMx) -{ - return ((READ_BIT(TIMx->DIER, TIM_DIER_TDE) == (TIM_DIER_TDE)) ? 1UL : 0UL); -} - -/** - * @} - */ - -/** @defgroup TIM_LL_EF_EVENT_Management EVENT-Management - * @{ - */ -/** - * @brief Generate an update event. - * @rmtoll EGR UG LL_TIM_GenerateEvent_UPDATE - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_GenerateEvent_UPDATE(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->EGR, TIM_EGR_UG); -} - -/** - * @brief Generate Capture/Compare 1 event. - * @rmtoll EGR CC1G LL_TIM_GenerateEvent_CC1 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_GenerateEvent_CC1(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->EGR, TIM_EGR_CC1G); -} - -/** - * @brief Generate Capture/Compare 2 event. - * @rmtoll EGR CC2G LL_TIM_GenerateEvent_CC2 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_GenerateEvent_CC2(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->EGR, TIM_EGR_CC2G); -} - -/** - * @brief Generate Capture/Compare 3 event. - * @rmtoll EGR CC3G LL_TIM_GenerateEvent_CC3 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_GenerateEvent_CC3(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->EGR, TIM_EGR_CC3G); -} - -/** - * @brief Generate Capture/Compare 4 event. - * @rmtoll EGR CC4G LL_TIM_GenerateEvent_CC4 - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_GenerateEvent_CC4(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->EGR, TIM_EGR_CC4G); -} - -/** - * @brief Generate commutation event. - * @rmtoll EGR COMG LL_TIM_GenerateEvent_COM - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_GenerateEvent_COM(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->EGR, TIM_EGR_COMG); -} - -/** - * @brief Generate trigger event. - * @rmtoll EGR TG LL_TIM_GenerateEvent_TRIG - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_GenerateEvent_TRIG(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->EGR, TIM_EGR_TG); -} - -/** - * @brief Generate break event. - * @rmtoll EGR BG LL_TIM_GenerateEvent_BRK - * @param TIMx Timer instance - * @retval None - */ -__STATIC_INLINE void LL_TIM_GenerateEvent_BRK(TIM_TypeDef *TIMx) -{ - SET_BIT(TIMx->EGR, TIM_EGR_BG); -} - -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup TIM_LL_EF_Init Initialisation and deinitialisation functions - * @{ - */ - -ErrorStatus LL_TIM_DeInit(TIM_TypeDef *TIMx); -void LL_TIM_StructInit(LL_TIM_InitTypeDef *TIM_InitStruct); -ErrorStatus LL_TIM_Init(TIM_TypeDef *TIMx, LL_TIM_InitTypeDef *TIM_InitStruct); -void LL_TIM_OC_StructInit(LL_TIM_OC_InitTypeDef *TIM_OC_InitStruct); -ErrorStatus LL_TIM_OC_Init(TIM_TypeDef *TIMx, uint32_t Channel, LL_TIM_OC_InitTypeDef *TIM_OC_InitStruct); -void LL_TIM_IC_StructInit(LL_TIM_IC_InitTypeDef *TIM_ICInitStruct); -ErrorStatus LL_TIM_IC_Init(TIM_TypeDef *TIMx, uint32_t Channel, LL_TIM_IC_InitTypeDef *TIM_IC_InitStruct); -void LL_TIM_ENCODER_StructInit(LL_TIM_ENCODER_InitTypeDef *TIM_EncoderInitStruct); -ErrorStatus LL_TIM_ENCODER_Init(TIM_TypeDef *TIMx, LL_TIM_ENCODER_InitTypeDef *TIM_EncoderInitStruct); -void LL_TIM_HALLSENSOR_StructInit(LL_TIM_HALLSENSOR_InitTypeDef *TIM_HallSensorInitStruct); -ErrorStatus LL_TIM_HALLSENSOR_Init(TIM_TypeDef *TIMx, LL_TIM_HALLSENSOR_InitTypeDef *TIM_HallSensorInitStruct); -void LL_TIM_BDTR_StructInit(LL_TIM_BDTR_InitTypeDef *TIM_BDTRInitStruct); -ErrorStatus LL_TIM_BDTR_Init(TIM_TypeDef *TIMx, LL_TIM_BDTR_InitTypeDef *TIM_BDTRInitStruct); -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* TIM1 || TIM2 || TIM3 || TIM4 || TIM5 || TIM6 || TIM7 || TIM8 || TIM9 || TIM10 || TIM11 || TIM12 || TIM13 || TIM14 */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_TIM_H */ -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_usart.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_usart.h deleted file mode 100644 index 86ee731..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_usart.h +++ /dev/null @@ -1,2523 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_usart.h - * @author MCD Application Team - * @brief Header file of USART LL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_LL_USART_H -#define __STM32F4xx_LL_USART_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (USART1) || defined (USART2) || defined (USART3) || defined (USART6) || defined (UART4) || defined (UART5) || defined (UART7) || defined (UART8) || defined (UART9) || defined (UART10) - -/** @defgroup USART_LL USART - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup USART_LL_Private_Constants USART Private Constants - * @{ - */ - -/* Defines used for the bit position in the register and perform offsets*/ -#define USART_POSITION_GTPR_GT USART_GTPR_GT_Pos -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup USART_LL_Private_Macros USART Private Macros - * @{ - */ -/** - * @} - */ -#endif /*USE_FULL_LL_DRIVER*/ - -/* Exported types ------------------------------------------------------------*/ -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup USART_LL_ES_INIT USART Exported Init structures - * @{ - */ - -/** - * @brief LL USART Init Structure definition - */ -typedef struct -{ - uint32_t BaudRate; /*!< This field defines expected Usart communication baud rate. - - This feature can be modified afterwards using unitary function @ref LL_USART_SetBaudRate().*/ - - uint32_t DataWidth; /*!< Specifies the number of data bits transmitted or received in a frame. - This parameter can be a value of @ref USART_LL_EC_DATAWIDTH. - - This feature can be modified afterwards using unitary function @ref LL_USART_SetDataWidth().*/ - - uint32_t StopBits; /*!< Specifies the number of stop bits transmitted. - This parameter can be a value of @ref USART_LL_EC_STOPBITS. - - This feature can be modified afterwards using unitary function @ref LL_USART_SetStopBitsLength().*/ - - uint32_t Parity; /*!< Specifies the parity mode. - This parameter can be a value of @ref USART_LL_EC_PARITY. - - This feature can be modified afterwards using unitary function @ref LL_USART_SetParity().*/ - - uint32_t TransferDirection; /*!< Specifies whether the Receive and/or Transmit mode is enabled or disabled. - This parameter can be a value of @ref USART_LL_EC_DIRECTION. - - This feature can be modified afterwards using unitary function @ref LL_USART_SetTransferDirection().*/ - - uint32_t HardwareFlowControl; /*!< Specifies whether the hardware flow control mode is enabled or disabled. - This parameter can be a value of @ref USART_LL_EC_HWCONTROL. - - This feature can be modified afterwards using unitary function @ref LL_USART_SetHWFlowCtrl().*/ - - uint32_t OverSampling; /*!< Specifies whether USART oversampling mode is 16 or 8. - This parameter can be a value of @ref USART_LL_EC_OVERSAMPLING. - - This feature can be modified afterwards using unitary function @ref LL_USART_SetOverSampling().*/ - -} LL_USART_InitTypeDef; - -/** - * @brief LL USART Clock Init Structure definition - */ -typedef struct -{ - uint32_t ClockOutput; /*!< Specifies whether the USART clock is enabled or disabled. - This parameter can be a value of @ref USART_LL_EC_CLOCK. - - USART HW configuration can be modified afterwards using unitary functions - @ref LL_USART_EnableSCLKOutput() or @ref LL_USART_DisableSCLKOutput(). - For more details, refer to description of this function. */ - - uint32_t ClockPolarity; /*!< Specifies the steady state of the serial clock. - This parameter can be a value of @ref USART_LL_EC_POLARITY. - - USART HW configuration can be modified afterwards using unitary functions @ref LL_USART_SetClockPolarity(). - For more details, refer to description of this function. */ - - uint32_t ClockPhase; /*!< Specifies the clock transition on which the bit capture is made. - This parameter can be a value of @ref USART_LL_EC_PHASE. - - USART HW configuration can be modified afterwards using unitary functions @ref LL_USART_SetClockPhase(). - For more details, refer to description of this function. */ - - uint32_t LastBitClockPulse; /*!< Specifies whether the clock pulse corresponding to the last transmitted - data bit (MSB) has to be output on the SCLK pin in synchronous mode. - This parameter can be a value of @ref USART_LL_EC_LASTCLKPULSE. - - USART HW configuration can be modified afterwards using unitary functions @ref LL_USART_SetLastClkPulseOutput(). - For more details, refer to description of this function. */ - -} LL_USART_ClockInitTypeDef; - -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup USART_LL_Exported_Constants USART Exported Constants - * @{ - */ - -/** @defgroup USART_LL_EC_GET_FLAG Get Flags Defines - * @brief Flags defines which can be used with LL_USART_ReadReg function - * @{ - */ -#define LL_USART_SR_PE USART_SR_PE /*!< Parity error flag */ -#define LL_USART_SR_FE USART_SR_FE /*!< Framing error flag */ -#define LL_USART_SR_NE USART_SR_NE /*!< Noise detected flag */ -#define LL_USART_SR_ORE USART_SR_ORE /*!< Overrun error flag */ -#define LL_USART_SR_IDLE USART_SR_IDLE /*!< Idle line detected flag */ -#define LL_USART_SR_RXNE USART_SR_RXNE /*!< Read data register not empty flag */ -#define LL_USART_SR_TC USART_SR_TC /*!< Transmission complete flag */ -#define LL_USART_SR_TXE USART_SR_TXE /*!< Transmit data register empty flag */ -#define LL_USART_SR_LBD USART_SR_LBD /*!< LIN break detection flag */ -#define LL_USART_SR_CTS USART_SR_CTS /*!< CTS flag */ -/** - * @} - */ - -/** @defgroup USART_LL_EC_IT IT Defines - * @brief IT defines which can be used with LL_USART_ReadReg and LL_USART_WriteReg functions - * @{ - */ -#define LL_USART_CR1_IDLEIE USART_CR1_IDLEIE /*!< IDLE interrupt enable */ -#define LL_USART_CR1_RXNEIE USART_CR1_RXNEIE /*!< Read data register not empty interrupt enable */ -#define LL_USART_CR1_TCIE USART_CR1_TCIE /*!< Transmission complete interrupt enable */ -#define LL_USART_CR1_TXEIE USART_CR1_TXEIE /*!< Transmit data register empty interrupt enable */ -#define LL_USART_CR1_PEIE USART_CR1_PEIE /*!< Parity error */ -#define LL_USART_CR2_LBDIE USART_CR2_LBDIE /*!< LIN break detection interrupt enable */ -#define LL_USART_CR3_EIE USART_CR3_EIE /*!< Error interrupt enable */ -#define LL_USART_CR3_CTSIE USART_CR3_CTSIE /*!< CTS interrupt enable */ -/** - * @} - */ - -/** @defgroup USART_LL_EC_DIRECTION Communication Direction - * @{ - */ -#define LL_USART_DIRECTION_NONE 0x00000000U /*!< Transmitter and Receiver are disabled */ -#define LL_USART_DIRECTION_RX USART_CR1_RE /*!< Transmitter is disabled and Receiver is enabled */ -#define LL_USART_DIRECTION_TX USART_CR1_TE /*!< Transmitter is enabled and Receiver is disabled */ -#define LL_USART_DIRECTION_TX_RX (USART_CR1_TE |USART_CR1_RE) /*!< Transmitter and Receiver are enabled */ -/** - * @} - */ - -/** @defgroup USART_LL_EC_PARITY Parity Control - * @{ - */ -#define LL_USART_PARITY_NONE 0x00000000U /*!< Parity control disabled */ -#define LL_USART_PARITY_EVEN USART_CR1_PCE /*!< Parity control enabled and Even Parity is selected */ -#define LL_USART_PARITY_ODD (USART_CR1_PCE | USART_CR1_PS) /*!< Parity control enabled and Odd Parity is selected */ -/** - * @} - */ - -/** @defgroup USART_LL_EC_WAKEUP Wakeup - * @{ - */ -#define LL_USART_WAKEUP_IDLELINE 0x00000000U /*!< USART wake up from Mute mode on Idle Line */ -#define LL_USART_WAKEUP_ADDRESSMARK USART_CR1_WAKE /*!< USART wake up from Mute mode on Address Mark */ -/** - * @} - */ - -/** @defgroup USART_LL_EC_DATAWIDTH Datawidth - * @{ - */ -#define LL_USART_DATAWIDTH_8B 0x00000000U /*!< 8 bits word length : Start bit, 8 data bits, n stop bits */ -#define LL_USART_DATAWIDTH_9B USART_CR1_M /*!< 9 bits word length : Start bit, 9 data bits, n stop bits */ -/** - * @} - */ - -/** @defgroup USART_LL_EC_OVERSAMPLING Oversampling - * @{ - */ -#define LL_USART_OVERSAMPLING_16 0x00000000U /*!< Oversampling by 16 */ -#define LL_USART_OVERSAMPLING_8 USART_CR1_OVER8 /*!< Oversampling by 8 */ -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup USART_LL_EC_CLOCK Clock Signal - * @{ - */ - -#define LL_USART_CLOCK_DISABLE 0x00000000U /*!< Clock signal not provided */ -#define LL_USART_CLOCK_ENABLE USART_CR2_CLKEN /*!< Clock signal provided */ -/** - * @} - */ -#endif /*USE_FULL_LL_DRIVER*/ - -/** @defgroup USART_LL_EC_LASTCLKPULSE Last Clock Pulse - * @{ - */ -#define LL_USART_LASTCLKPULSE_NO_OUTPUT 0x00000000U /*!< The clock pulse of the last data bit is not output to the SCLK pin */ -#define LL_USART_LASTCLKPULSE_OUTPUT USART_CR2_LBCL /*!< The clock pulse of the last data bit is output to the SCLK pin */ -/** - * @} - */ - -/** @defgroup USART_LL_EC_PHASE Clock Phase - * @{ - */ -#define LL_USART_PHASE_1EDGE 0x00000000U /*!< The first clock transition is the first data capture edge */ -#define LL_USART_PHASE_2EDGE USART_CR2_CPHA /*!< The second clock transition is the first data capture edge */ -/** - * @} - */ - -/** @defgroup USART_LL_EC_POLARITY Clock Polarity - * @{ - */ -#define LL_USART_POLARITY_LOW 0x00000000U /*!< Steady low value on SCLK pin outside transmission window*/ -#define LL_USART_POLARITY_HIGH USART_CR2_CPOL /*!< Steady high value on SCLK pin outside transmission window */ -/** - * @} - */ - -/** @defgroup USART_LL_EC_STOPBITS Stop Bits - * @{ - */ -#define LL_USART_STOPBITS_0_5 USART_CR2_STOP_0 /*!< 0.5 stop bit */ -#define LL_USART_STOPBITS_1 0x00000000U /*!< 1 stop bit */ -#define LL_USART_STOPBITS_1_5 (USART_CR2_STOP_0 | USART_CR2_STOP_1) /*!< 1.5 stop bits */ -#define LL_USART_STOPBITS_2 USART_CR2_STOP_1 /*!< 2 stop bits */ -/** - * @} - */ - -/** @defgroup USART_LL_EC_HWCONTROL Hardware Control - * @{ - */ -#define LL_USART_HWCONTROL_NONE 0x00000000U /*!< CTS and RTS hardware flow control disabled */ -#define LL_USART_HWCONTROL_RTS USART_CR3_RTSE /*!< RTS output enabled, data is only requested when there is space in the receive buffer */ -#define LL_USART_HWCONTROL_CTS USART_CR3_CTSE /*!< CTS mode enabled, data is only transmitted when the nCTS input is asserted (tied to 0) */ -#define LL_USART_HWCONTROL_RTS_CTS (USART_CR3_RTSE | USART_CR3_CTSE) /*!< CTS and RTS hardware flow control enabled */ -/** - * @} - */ - -/** @defgroup USART_LL_EC_IRDA_POWER IrDA Power - * @{ - */ -#define LL_USART_IRDA_POWER_NORMAL 0x00000000U /*!< IrDA normal power mode */ -#define LL_USART_IRDA_POWER_LOW USART_CR3_IRLP /*!< IrDA low power mode */ -/** - * @} - */ - -/** @defgroup USART_LL_EC_LINBREAK_DETECT LIN Break Detection Length - * @{ - */ -#define LL_USART_LINBREAK_DETECT_10B 0x00000000U /*!< 10-bit break detection method selected */ -#define LL_USART_LINBREAK_DETECT_11B USART_CR2_LBDL /*!< 11-bit break detection method selected */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup USART_LL_Exported_Macros USART Exported Macros - * @{ - */ - -/** @defgroup USART_LL_EM_WRITE_READ Common Write and read registers Macros - * @{ - */ - -/** - * @brief Write a value in USART register - * @param __INSTANCE__ USART Instance - * @param __REG__ Register to be written - * @param __VALUE__ Value to be written in the register - * @retval None - */ -#define LL_USART_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__)) - -/** - * @brief Read a value in USART register - * @param __INSTANCE__ USART Instance - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_USART_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__) -/** - * @} - */ - -/** @defgroup USART_LL_EM_Exported_Macros_Helper Exported_Macros_Helper - * @{ - */ - -/** - * @brief Compute USARTDIV value according to Peripheral Clock and - * expected Baud Rate in 8 bits sampling mode (32 bits value of USARTDIV is returned) - * @param __PERIPHCLK__ Peripheral Clock frequency used for USART instance - * @param __BAUDRATE__ Baud rate value to achieve - * @retval USARTDIV value to be used for BRR register filling in OverSampling_8 case - */ -#define __LL_USART_DIV_SAMPLING8_100(__PERIPHCLK__, __BAUDRATE__) ((uint32_t)((((uint64_t)(__PERIPHCLK__))*25)/(2*((uint64_t)(__BAUDRATE__))))) -#define __LL_USART_DIVMANT_SAMPLING8(__PERIPHCLK__, __BAUDRATE__) (__LL_USART_DIV_SAMPLING8_100((__PERIPHCLK__), (__BAUDRATE__))/100) -#define __LL_USART_DIVFRAQ_SAMPLING8(__PERIPHCLK__, __BAUDRATE__) ((((__LL_USART_DIV_SAMPLING8_100((__PERIPHCLK__), (__BAUDRATE__)) - (__LL_USART_DIVMANT_SAMPLING8((__PERIPHCLK__), (__BAUDRATE__)) * 100)) * 8)\ - + 50) / 100) -/* UART BRR = mantissa + overflow + fraction - = (UART DIVMANT << 4) + ((UART DIVFRAQ & 0xF8) << 1) + (UART DIVFRAQ & 0x07) */ -#define __LL_USART_DIV_SAMPLING8(__PERIPHCLK__, __BAUDRATE__) (((__LL_USART_DIVMANT_SAMPLING8((__PERIPHCLK__), (__BAUDRATE__)) << 4) + \ - ((__LL_USART_DIVFRAQ_SAMPLING8((__PERIPHCLK__), (__BAUDRATE__)) & 0xF8) << 1)) + \ - (__LL_USART_DIVFRAQ_SAMPLING8((__PERIPHCLK__), (__BAUDRATE__)) & 0x07)) - -/** - * @brief Compute USARTDIV value according to Peripheral Clock and - * expected Baud Rate in 16 bits sampling mode (32 bits value of USARTDIV is returned) - * @param __PERIPHCLK__ Peripheral Clock frequency used for USART instance - * @param __BAUDRATE__ Baud rate value to achieve - * @retval USARTDIV value to be used for BRR register filling in OverSampling_16 case - */ -#define __LL_USART_DIV_SAMPLING16_100(__PERIPHCLK__, __BAUDRATE__) ((uint32_t)((((uint64_t)(__PERIPHCLK__))*25)/(4*((uint64_t)(__BAUDRATE__))))) -#define __LL_USART_DIVMANT_SAMPLING16(__PERIPHCLK__, __BAUDRATE__) (__LL_USART_DIV_SAMPLING16_100((__PERIPHCLK__), (__BAUDRATE__))/100) -#define __LL_USART_DIVFRAQ_SAMPLING16(__PERIPHCLK__, __BAUDRATE__) ((((__LL_USART_DIV_SAMPLING16_100((__PERIPHCLK__), (__BAUDRATE__)) - (__LL_USART_DIVMANT_SAMPLING16((__PERIPHCLK__), (__BAUDRATE__)) * 100)) * 16)\ - + 50) / 100) -/* USART BRR = mantissa + overflow + fraction - = (USART DIVMANT << 4) + (USART DIVFRAQ & 0xF0) + (USART DIVFRAQ & 0x0F) */ -#define __LL_USART_DIV_SAMPLING16(__PERIPHCLK__, __BAUDRATE__) (((__LL_USART_DIVMANT_SAMPLING16((__PERIPHCLK__), (__BAUDRATE__)) << 4) + \ - (__LL_USART_DIVFRAQ_SAMPLING16((__PERIPHCLK__), (__BAUDRATE__)) & 0xF0)) + \ - (__LL_USART_DIVFRAQ_SAMPLING16((__PERIPHCLK__), (__BAUDRATE__)) & 0x0F)) - -/** - * @} - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ - -/** @defgroup USART_LL_Exported_Functions USART Exported Functions - * @{ - */ - -/** @defgroup USART_LL_EF_Configuration Configuration functions - * @{ - */ - -/** - * @brief USART Enable - * @rmtoll CR1 UE LL_USART_Enable - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_Enable(USART_TypeDef *USARTx) -{ - SET_BIT(USARTx->CR1, USART_CR1_UE); -} - -/** - * @brief USART Disable (all USART prescalers and outputs are disabled) - * @note When USART is disabled, USART prescalers and outputs are stopped immediately, - * and current operations are discarded. The configuration of the USART is kept, but all the status - * flags, in the USARTx_SR are set to their default values. - * @rmtoll CR1 UE LL_USART_Disable - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_Disable(USART_TypeDef *USARTx) -{ - CLEAR_BIT(USARTx->CR1, USART_CR1_UE); -} - -/** - * @brief Indicate if USART is enabled - * @rmtoll CR1 UE LL_USART_IsEnabled - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabled(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR1, USART_CR1_UE) == (USART_CR1_UE)); -} - -/** - * @brief Receiver Enable (Receiver is enabled and begins searching for a start bit) - * @rmtoll CR1 RE LL_USART_EnableDirectionRx - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableDirectionRx(USART_TypeDef *USARTx) -{ - ATOMIC_SET_BIT(USARTx->CR1, USART_CR1_RE); -} - -/** - * @brief Receiver Disable - * @rmtoll CR1 RE LL_USART_DisableDirectionRx - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableDirectionRx(USART_TypeDef *USARTx) -{ - ATOMIC_CLEAR_BIT(USARTx->CR1, USART_CR1_RE); -} - -/** - * @brief Transmitter Enable - * @rmtoll CR1 TE LL_USART_EnableDirectionTx - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableDirectionTx(USART_TypeDef *USARTx) -{ - ATOMIC_SET_BIT(USARTx->CR1, USART_CR1_TE); -} - -/** - * @brief Transmitter Disable - * @rmtoll CR1 TE LL_USART_DisableDirectionTx - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableDirectionTx(USART_TypeDef *USARTx) -{ - ATOMIC_CLEAR_BIT(USARTx->CR1, USART_CR1_TE); -} - -/** - * @brief Configure simultaneously enabled/disabled states - * of Transmitter and Receiver - * @rmtoll CR1 RE LL_USART_SetTransferDirection\n - * CR1 TE LL_USART_SetTransferDirection - * @param USARTx USART Instance - * @param TransferDirection This parameter can be one of the following values: - * @arg @ref LL_USART_DIRECTION_NONE - * @arg @ref LL_USART_DIRECTION_RX - * @arg @ref LL_USART_DIRECTION_TX - * @arg @ref LL_USART_DIRECTION_TX_RX - * @retval None - */ -__STATIC_INLINE void LL_USART_SetTransferDirection(USART_TypeDef *USARTx, uint32_t TransferDirection) -{ - ATOMIC_MODIFY_REG(USARTx->CR1, USART_CR1_RE | USART_CR1_TE, TransferDirection); -} - -/** - * @brief Return enabled/disabled states of Transmitter and Receiver - * @rmtoll CR1 RE LL_USART_GetTransferDirection\n - * CR1 TE LL_USART_GetTransferDirection - * @param USARTx USART Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_USART_DIRECTION_NONE - * @arg @ref LL_USART_DIRECTION_RX - * @arg @ref LL_USART_DIRECTION_TX - * @arg @ref LL_USART_DIRECTION_TX_RX - */ -__STATIC_INLINE uint32_t LL_USART_GetTransferDirection(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->CR1, USART_CR1_RE | USART_CR1_TE)); -} - -/** - * @brief Configure Parity (enabled/disabled and parity mode if enabled). - * @note This function selects if hardware parity control (generation and detection) is enabled or disabled. - * When the parity control is enabled (Odd or Even), computed parity bit is inserted at the MSB position - * (9th or 8th bit depending on data width) and parity is checked on the received data. - * @rmtoll CR1 PS LL_USART_SetParity\n - * CR1 PCE LL_USART_SetParity - * @param USARTx USART Instance - * @param Parity This parameter can be one of the following values: - * @arg @ref LL_USART_PARITY_NONE - * @arg @ref LL_USART_PARITY_EVEN - * @arg @ref LL_USART_PARITY_ODD - * @retval None - */ -__STATIC_INLINE void LL_USART_SetParity(USART_TypeDef *USARTx, uint32_t Parity) -{ - MODIFY_REG(USARTx->CR1, USART_CR1_PS | USART_CR1_PCE, Parity); -} - -/** - * @brief Return Parity configuration (enabled/disabled and parity mode if enabled) - * @rmtoll CR1 PS LL_USART_GetParity\n - * CR1 PCE LL_USART_GetParity - * @param USARTx USART Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_USART_PARITY_NONE - * @arg @ref LL_USART_PARITY_EVEN - * @arg @ref LL_USART_PARITY_ODD - */ -__STATIC_INLINE uint32_t LL_USART_GetParity(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->CR1, USART_CR1_PS | USART_CR1_PCE)); -} - -/** - * @brief Set Receiver Wake Up method from Mute mode. - * @rmtoll CR1 WAKE LL_USART_SetWakeUpMethod - * @param USARTx USART Instance - * @param Method This parameter can be one of the following values: - * @arg @ref LL_USART_WAKEUP_IDLELINE - * @arg @ref LL_USART_WAKEUP_ADDRESSMARK - * @retval None - */ -__STATIC_INLINE void LL_USART_SetWakeUpMethod(USART_TypeDef *USARTx, uint32_t Method) -{ - MODIFY_REG(USARTx->CR1, USART_CR1_WAKE, Method); -} - -/** - * @brief Return Receiver Wake Up method from Mute mode - * @rmtoll CR1 WAKE LL_USART_GetWakeUpMethod - * @param USARTx USART Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_USART_WAKEUP_IDLELINE - * @arg @ref LL_USART_WAKEUP_ADDRESSMARK - */ -__STATIC_INLINE uint32_t LL_USART_GetWakeUpMethod(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->CR1, USART_CR1_WAKE)); -} - -/** - * @brief Set Word length (i.e. nb of data bits, excluding start and stop bits) - * @rmtoll CR1 M LL_USART_SetDataWidth - * @param USARTx USART Instance - * @param DataWidth This parameter can be one of the following values: - * @arg @ref LL_USART_DATAWIDTH_8B - * @arg @ref LL_USART_DATAWIDTH_9B - * @retval None - */ -__STATIC_INLINE void LL_USART_SetDataWidth(USART_TypeDef *USARTx, uint32_t DataWidth) -{ - MODIFY_REG(USARTx->CR1, USART_CR1_M, DataWidth); -} - -/** - * @brief Return Word length (i.e. nb of data bits, excluding start and stop bits) - * @rmtoll CR1 M LL_USART_GetDataWidth - * @param USARTx USART Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_USART_DATAWIDTH_8B - * @arg @ref LL_USART_DATAWIDTH_9B - */ -__STATIC_INLINE uint32_t LL_USART_GetDataWidth(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->CR1, USART_CR1_M)); -} - -/** - * @brief Set Oversampling to 8-bit or 16-bit mode - * @rmtoll CR1 OVER8 LL_USART_SetOverSampling - * @param USARTx USART Instance - * @param OverSampling This parameter can be one of the following values: - * @arg @ref LL_USART_OVERSAMPLING_16 - * @arg @ref LL_USART_OVERSAMPLING_8 - * @retval None - */ -__STATIC_INLINE void LL_USART_SetOverSampling(USART_TypeDef *USARTx, uint32_t OverSampling) -{ - MODIFY_REG(USARTx->CR1, USART_CR1_OVER8, OverSampling); -} - -/** - * @brief Return Oversampling mode - * @rmtoll CR1 OVER8 LL_USART_GetOverSampling - * @param USARTx USART Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_USART_OVERSAMPLING_16 - * @arg @ref LL_USART_OVERSAMPLING_8 - */ -__STATIC_INLINE uint32_t LL_USART_GetOverSampling(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->CR1, USART_CR1_OVER8)); -} - -/** - * @brief Configure if Clock pulse of the last data bit is output to the SCLK pin or not - * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not - * Synchronous mode is supported by the USARTx instance. - * @rmtoll CR2 LBCL LL_USART_SetLastClkPulseOutput - * @param USARTx USART Instance - * @param LastBitClockPulse This parameter can be one of the following values: - * @arg @ref LL_USART_LASTCLKPULSE_NO_OUTPUT - * @arg @ref LL_USART_LASTCLKPULSE_OUTPUT - * @retval None - */ -__STATIC_INLINE void LL_USART_SetLastClkPulseOutput(USART_TypeDef *USARTx, uint32_t LastBitClockPulse) -{ - MODIFY_REG(USARTx->CR2, USART_CR2_LBCL, LastBitClockPulse); -} - -/** - * @brief Retrieve Clock pulse of the last data bit output configuration - * (Last bit Clock pulse output to the SCLK pin or not) - * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not - * Synchronous mode is supported by the USARTx instance. - * @rmtoll CR2 LBCL LL_USART_GetLastClkPulseOutput - * @param USARTx USART Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_USART_LASTCLKPULSE_NO_OUTPUT - * @arg @ref LL_USART_LASTCLKPULSE_OUTPUT - */ -__STATIC_INLINE uint32_t LL_USART_GetLastClkPulseOutput(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_LBCL)); -} - -/** - * @brief Select the phase of the clock output on the SCLK pin in synchronous mode - * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not - * Synchronous mode is supported by the USARTx instance. - * @rmtoll CR2 CPHA LL_USART_SetClockPhase - * @param USARTx USART Instance - * @param ClockPhase This parameter can be one of the following values: - * @arg @ref LL_USART_PHASE_1EDGE - * @arg @ref LL_USART_PHASE_2EDGE - * @retval None - */ -__STATIC_INLINE void LL_USART_SetClockPhase(USART_TypeDef *USARTx, uint32_t ClockPhase) -{ - MODIFY_REG(USARTx->CR2, USART_CR2_CPHA, ClockPhase); -} - -/** - * @brief Return phase of the clock output on the SCLK pin in synchronous mode - * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not - * Synchronous mode is supported by the USARTx instance. - * @rmtoll CR2 CPHA LL_USART_GetClockPhase - * @param USARTx USART Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_USART_PHASE_1EDGE - * @arg @ref LL_USART_PHASE_2EDGE - */ -__STATIC_INLINE uint32_t LL_USART_GetClockPhase(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_CPHA)); -} - -/** - * @brief Select the polarity of the clock output on the SCLK pin in synchronous mode - * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not - * Synchronous mode is supported by the USARTx instance. - * @rmtoll CR2 CPOL LL_USART_SetClockPolarity - * @param USARTx USART Instance - * @param ClockPolarity This parameter can be one of the following values: - * @arg @ref LL_USART_POLARITY_LOW - * @arg @ref LL_USART_POLARITY_HIGH - * @retval None - */ -__STATIC_INLINE void LL_USART_SetClockPolarity(USART_TypeDef *USARTx, uint32_t ClockPolarity) -{ - MODIFY_REG(USARTx->CR2, USART_CR2_CPOL, ClockPolarity); -} - -/** - * @brief Return polarity of the clock output on the SCLK pin in synchronous mode - * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not - * Synchronous mode is supported by the USARTx instance. - * @rmtoll CR2 CPOL LL_USART_GetClockPolarity - * @param USARTx USART Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_USART_POLARITY_LOW - * @arg @ref LL_USART_POLARITY_HIGH - */ -__STATIC_INLINE uint32_t LL_USART_GetClockPolarity(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_CPOL)); -} - -/** - * @brief Configure Clock signal format (Phase Polarity and choice about output of last bit clock pulse) - * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not - * Synchronous mode is supported by the USARTx instance. - * @note Call of this function is equivalent to following function call sequence : - * - Clock Phase configuration using @ref LL_USART_SetClockPhase() function - * - Clock Polarity configuration using @ref LL_USART_SetClockPolarity() function - * - Output of Last bit Clock pulse configuration using @ref LL_USART_SetLastClkPulseOutput() function - * @rmtoll CR2 CPHA LL_USART_ConfigClock\n - * CR2 CPOL LL_USART_ConfigClock\n - * CR2 LBCL LL_USART_ConfigClock - * @param USARTx USART Instance - * @param Phase This parameter can be one of the following values: - * @arg @ref LL_USART_PHASE_1EDGE - * @arg @ref LL_USART_PHASE_2EDGE - * @param Polarity This parameter can be one of the following values: - * @arg @ref LL_USART_POLARITY_LOW - * @arg @ref LL_USART_POLARITY_HIGH - * @param LBCPOutput This parameter can be one of the following values: - * @arg @ref LL_USART_LASTCLKPULSE_NO_OUTPUT - * @arg @ref LL_USART_LASTCLKPULSE_OUTPUT - * @retval None - */ -__STATIC_INLINE void LL_USART_ConfigClock(USART_TypeDef *USARTx, uint32_t Phase, uint32_t Polarity, uint32_t LBCPOutput) -{ - MODIFY_REG(USARTx->CR2, USART_CR2_CPHA | USART_CR2_CPOL | USART_CR2_LBCL, Phase | Polarity | LBCPOutput); -} - -/** - * @brief Enable Clock output on SCLK pin - * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not - * Synchronous mode is supported by the USARTx instance. - * @rmtoll CR2 CLKEN LL_USART_EnableSCLKOutput - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableSCLKOutput(USART_TypeDef *USARTx) -{ - SET_BIT(USARTx->CR2, USART_CR2_CLKEN); -} - -/** - * @brief Disable Clock output on SCLK pin - * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not - * Synchronous mode is supported by the USARTx instance. - * @rmtoll CR2 CLKEN LL_USART_DisableSCLKOutput - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableSCLKOutput(USART_TypeDef *USARTx) -{ - CLEAR_BIT(USARTx->CR2, USART_CR2_CLKEN); -} - -/** - * @brief Indicate if Clock output on SCLK pin is enabled - * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not - * Synchronous mode is supported by the USARTx instance. - * @rmtoll CR2 CLKEN LL_USART_IsEnabledSCLKOutput - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledSCLKOutput(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR2, USART_CR2_CLKEN) == (USART_CR2_CLKEN)); -} - -/** - * @brief Set the length of the stop bits - * @rmtoll CR2 STOP LL_USART_SetStopBitsLength - * @param USARTx USART Instance - * @param StopBits This parameter can be one of the following values: - * @arg @ref LL_USART_STOPBITS_0_5 - * @arg @ref LL_USART_STOPBITS_1 - * @arg @ref LL_USART_STOPBITS_1_5 - * @arg @ref LL_USART_STOPBITS_2 - * @retval None - */ -__STATIC_INLINE void LL_USART_SetStopBitsLength(USART_TypeDef *USARTx, uint32_t StopBits) -{ - MODIFY_REG(USARTx->CR2, USART_CR2_STOP, StopBits); -} - -/** - * @brief Retrieve the length of the stop bits - * @rmtoll CR2 STOP LL_USART_GetStopBitsLength - * @param USARTx USART Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_USART_STOPBITS_0_5 - * @arg @ref LL_USART_STOPBITS_1 - * @arg @ref LL_USART_STOPBITS_1_5 - * @arg @ref LL_USART_STOPBITS_2 - */ -__STATIC_INLINE uint32_t LL_USART_GetStopBitsLength(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_STOP)); -} - -/** - * @brief Configure Character frame format (Datawidth, Parity control, Stop Bits) - * @note Call of this function is equivalent to following function call sequence : - * - Data Width configuration using @ref LL_USART_SetDataWidth() function - * - Parity Control and mode configuration using @ref LL_USART_SetParity() function - * - Stop bits configuration using @ref LL_USART_SetStopBitsLength() function - * @rmtoll CR1 PS LL_USART_ConfigCharacter\n - * CR1 PCE LL_USART_ConfigCharacter\n - * CR1 M LL_USART_ConfigCharacter\n - * CR2 STOP LL_USART_ConfigCharacter - * @param USARTx USART Instance - * @param DataWidth This parameter can be one of the following values: - * @arg @ref LL_USART_DATAWIDTH_8B - * @arg @ref LL_USART_DATAWIDTH_9B - * @param Parity This parameter can be one of the following values: - * @arg @ref LL_USART_PARITY_NONE - * @arg @ref LL_USART_PARITY_EVEN - * @arg @ref LL_USART_PARITY_ODD - * @param StopBits This parameter can be one of the following values: - * @arg @ref LL_USART_STOPBITS_0_5 - * @arg @ref LL_USART_STOPBITS_1 - * @arg @ref LL_USART_STOPBITS_1_5 - * @arg @ref LL_USART_STOPBITS_2 - * @retval None - */ -__STATIC_INLINE void LL_USART_ConfigCharacter(USART_TypeDef *USARTx, uint32_t DataWidth, uint32_t Parity, - uint32_t StopBits) -{ - MODIFY_REG(USARTx->CR1, USART_CR1_PS | USART_CR1_PCE | USART_CR1_M, Parity | DataWidth); - MODIFY_REG(USARTx->CR2, USART_CR2_STOP, StopBits); -} - -/** - * @brief Set Address of the USART node. - * @note This is used in multiprocessor communication during Mute mode or Stop mode, - * for wake up with address mark detection. - * @rmtoll CR2 ADD LL_USART_SetNodeAddress - * @param USARTx USART Instance - * @param NodeAddress 4 bit Address of the USART node. - * @retval None - */ -__STATIC_INLINE void LL_USART_SetNodeAddress(USART_TypeDef *USARTx, uint32_t NodeAddress) -{ - MODIFY_REG(USARTx->CR2, USART_CR2_ADD, (NodeAddress & USART_CR2_ADD)); -} - -/** - * @brief Return 4 bit Address of the USART node as set in ADD field of CR2. - * @note only 4bits (b3-b0) of returned value are relevant (b31-b4 are not relevant) - * @rmtoll CR2 ADD LL_USART_GetNodeAddress - * @param USARTx USART Instance - * @retval Address of the USART node (Value between Min_Data=0 and Max_Data=255) - */ -__STATIC_INLINE uint32_t LL_USART_GetNodeAddress(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_ADD)); -} - -/** - * @brief Enable RTS HW Flow Control - * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not - * Hardware Flow control feature is supported by the USARTx instance. - * @rmtoll CR3 RTSE LL_USART_EnableRTSHWFlowCtrl - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableRTSHWFlowCtrl(USART_TypeDef *USARTx) -{ - SET_BIT(USARTx->CR3, USART_CR3_RTSE); -} - -/** - * @brief Disable RTS HW Flow Control - * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not - * Hardware Flow control feature is supported by the USARTx instance. - * @rmtoll CR3 RTSE LL_USART_DisableRTSHWFlowCtrl - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableRTSHWFlowCtrl(USART_TypeDef *USARTx) -{ - CLEAR_BIT(USARTx->CR3, USART_CR3_RTSE); -} - -/** - * @brief Enable CTS HW Flow Control - * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not - * Hardware Flow control feature is supported by the USARTx instance. - * @rmtoll CR3 CTSE LL_USART_EnableCTSHWFlowCtrl - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableCTSHWFlowCtrl(USART_TypeDef *USARTx) -{ - SET_BIT(USARTx->CR3, USART_CR3_CTSE); -} - -/** - * @brief Disable CTS HW Flow Control - * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not - * Hardware Flow control feature is supported by the USARTx instance. - * @rmtoll CR3 CTSE LL_USART_DisableCTSHWFlowCtrl - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableCTSHWFlowCtrl(USART_TypeDef *USARTx) -{ - CLEAR_BIT(USARTx->CR3, USART_CR3_CTSE); -} - -/** - * @brief Configure HW Flow Control mode (both CTS and RTS) - * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not - * Hardware Flow control feature is supported by the USARTx instance. - * @rmtoll CR3 RTSE LL_USART_SetHWFlowCtrl\n - * CR3 CTSE LL_USART_SetHWFlowCtrl - * @param USARTx USART Instance - * @param HardwareFlowControl This parameter can be one of the following values: - * @arg @ref LL_USART_HWCONTROL_NONE - * @arg @ref LL_USART_HWCONTROL_RTS - * @arg @ref LL_USART_HWCONTROL_CTS - * @arg @ref LL_USART_HWCONTROL_RTS_CTS - * @retval None - */ -__STATIC_INLINE void LL_USART_SetHWFlowCtrl(USART_TypeDef *USARTx, uint32_t HardwareFlowControl) -{ - MODIFY_REG(USARTx->CR3, USART_CR3_RTSE | USART_CR3_CTSE, HardwareFlowControl); -} - -/** - * @brief Return HW Flow Control configuration (both CTS and RTS) - * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not - * Hardware Flow control feature is supported by the USARTx instance. - * @rmtoll CR3 RTSE LL_USART_GetHWFlowCtrl\n - * CR3 CTSE LL_USART_GetHWFlowCtrl - * @param USARTx USART Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_USART_HWCONTROL_NONE - * @arg @ref LL_USART_HWCONTROL_RTS - * @arg @ref LL_USART_HWCONTROL_CTS - * @arg @ref LL_USART_HWCONTROL_RTS_CTS - */ -__STATIC_INLINE uint32_t LL_USART_GetHWFlowCtrl(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->CR3, USART_CR3_RTSE | USART_CR3_CTSE)); -} - -/** - * @brief Enable One bit sampling method - * @rmtoll CR3 ONEBIT LL_USART_EnableOneBitSamp - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableOneBitSamp(USART_TypeDef *USARTx) -{ - SET_BIT(USARTx->CR3, USART_CR3_ONEBIT); -} - -/** - * @brief Disable One bit sampling method - * @rmtoll CR3 ONEBIT LL_USART_DisableOneBitSamp - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableOneBitSamp(USART_TypeDef *USARTx) -{ - CLEAR_BIT(USARTx->CR3, USART_CR3_ONEBIT); -} - -/** - * @brief Indicate if One bit sampling method is enabled - * @rmtoll CR3 ONEBIT LL_USART_IsEnabledOneBitSamp - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledOneBitSamp(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR3, USART_CR3_ONEBIT) == (USART_CR3_ONEBIT)); -} - -/** - * @brief Configure USART BRR register for achieving expected Baud Rate value. - * @note Compute and set USARTDIV value in BRR Register (full BRR content) - * according to used Peripheral Clock, Oversampling mode, and expected Baud Rate values - * @note Peripheral clock and Baud rate values provided as function parameters should be valid - * (Baud rate value != 0) - * @rmtoll BRR BRR LL_USART_SetBaudRate - * @param USARTx USART Instance - * @param PeriphClk Peripheral Clock - * @param OverSampling This parameter can be one of the following values: - * @arg @ref LL_USART_OVERSAMPLING_16 - * @arg @ref LL_USART_OVERSAMPLING_8 - * @param BaudRate Baud Rate - * @retval None - */ -__STATIC_INLINE void LL_USART_SetBaudRate(USART_TypeDef *USARTx, uint32_t PeriphClk, uint32_t OverSampling, - uint32_t BaudRate) -{ - if (OverSampling == LL_USART_OVERSAMPLING_8) - { - USARTx->BRR = (uint16_t)(__LL_USART_DIV_SAMPLING8(PeriphClk, BaudRate)); - } - else - { - USARTx->BRR = (uint16_t)(__LL_USART_DIV_SAMPLING16(PeriphClk, BaudRate)); - } -} - -/** - * @brief Return current Baud Rate value, according to USARTDIV present in BRR register - * (full BRR content), and to used Peripheral Clock and Oversampling mode values - * @note In case of non-initialized or invalid value stored in BRR register, value 0 will be returned. - * @rmtoll BRR BRR LL_USART_GetBaudRate - * @param USARTx USART Instance - * @param PeriphClk Peripheral Clock - * @param OverSampling This parameter can be one of the following values: - * @arg @ref LL_USART_OVERSAMPLING_16 - * @arg @ref LL_USART_OVERSAMPLING_8 - * @retval Baud Rate - */ -__STATIC_INLINE uint32_t LL_USART_GetBaudRate(USART_TypeDef *USARTx, uint32_t PeriphClk, uint32_t OverSampling) -{ - uint32_t usartdiv = 0x0U; - uint32_t brrresult = 0x0U; - - usartdiv = USARTx->BRR; - - if (OverSampling == LL_USART_OVERSAMPLING_8) - { - if ((usartdiv & 0xFFF7U) != 0U) - { - usartdiv = (uint16_t)((usartdiv & 0xFFF0U) | ((usartdiv & 0x0007U) << 1U)) ; - brrresult = (PeriphClk * 2U) / usartdiv; - } - } - else - { - if ((usartdiv & 0xFFFFU) != 0U) - { - brrresult = PeriphClk / usartdiv; - } - } - return (brrresult); -} - -/** - * @} - */ - -/** @defgroup USART_LL_EF_Configuration_IRDA Configuration functions related to Irda feature - * @{ - */ - -/** - * @brief Enable IrDA mode - * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not - * IrDA feature is supported by the USARTx instance. - * @rmtoll CR3 IREN LL_USART_EnableIrda - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableIrda(USART_TypeDef *USARTx) -{ - SET_BIT(USARTx->CR3, USART_CR3_IREN); -} - -/** - * @brief Disable IrDA mode - * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not - * IrDA feature is supported by the USARTx instance. - * @rmtoll CR3 IREN LL_USART_DisableIrda - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableIrda(USART_TypeDef *USARTx) -{ - CLEAR_BIT(USARTx->CR3, USART_CR3_IREN); -} - -/** - * @brief Indicate if IrDA mode is enabled - * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not - * IrDA feature is supported by the USARTx instance. - * @rmtoll CR3 IREN LL_USART_IsEnabledIrda - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledIrda(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR3, USART_CR3_IREN) == (USART_CR3_IREN)); -} - -/** - * @brief Configure IrDA Power Mode (Normal or Low Power) - * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not - * IrDA feature is supported by the USARTx instance. - * @rmtoll CR3 IRLP LL_USART_SetIrdaPowerMode - * @param USARTx USART Instance - * @param PowerMode This parameter can be one of the following values: - * @arg @ref LL_USART_IRDA_POWER_NORMAL - * @arg @ref LL_USART_IRDA_POWER_LOW - * @retval None - */ -__STATIC_INLINE void LL_USART_SetIrdaPowerMode(USART_TypeDef *USARTx, uint32_t PowerMode) -{ - MODIFY_REG(USARTx->CR3, USART_CR3_IRLP, PowerMode); -} - -/** - * @brief Retrieve IrDA Power Mode configuration (Normal or Low Power) - * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not - * IrDA feature is supported by the USARTx instance. - * @rmtoll CR3 IRLP LL_USART_GetIrdaPowerMode - * @param USARTx USART Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_USART_IRDA_POWER_NORMAL - * @arg @ref LL_USART_PHASE_2EDGE - */ -__STATIC_INLINE uint32_t LL_USART_GetIrdaPowerMode(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->CR3, USART_CR3_IRLP)); -} - -/** - * @brief Set Irda prescaler value, used for dividing the USART clock source - * to achieve the Irda Low Power frequency (8 bits value) - * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not - * IrDA feature is supported by the USARTx instance. - * @rmtoll GTPR PSC LL_USART_SetIrdaPrescaler - * @param USARTx USART Instance - * @param PrescalerValue Value between Min_Data=0x00 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_USART_SetIrdaPrescaler(USART_TypeDef *USARTx, uint32_t PrescalerValue) -{ - MODIFY_REG(USARTx->GTPR, USART_GTPR_PSC, PrescalerValue); -} - -/** - * @brief Return Irda prescaler value, used for dividing the USART clock source - * to achieve the Irda Low Power frequency (8 bits value) - * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not - * IrDA feature is supported by the USARTx instance. - * @rmtoll GTPR PSC LL_USART_GetIrdaPrescaler - * @param USARTx USART Instance - * @retval Irda prescaler value (Value between Min_Data=0x00 and Max_Data=0xFF) - */ -__STATIC_INLINE uint32_t LL_USART_GetIrdaPrescaler(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->GTPR, USART_GTPR_PSC)); -} - -/** - * @} - */ - -/** @defgroup USART_LL_EF_Configuration_Smartcard Configuration functions related to Smartcard feature - * @{ - */ - -/** - * @brief Enable Smartcard NACK transmission - * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not - * Smartcard feature is supported by the USARTx instance. - * @rmtoll CR3 NACK LL_USART_EnableSmartcardNACK - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableSmartcardNACK(USART_TypeDef *USARTx) -{ - SET_BIT(USARTx->CR3, USART_CR3_NACK); -} - -/** - * @brief Disable Smartcard NACK transmission - * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not - * Smartcard feature is supported by the USARTx instance. - * @rmtoll CR3 NACK LL_USART_DisableSmartcardNACK - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableSmartcardNACK(USART_TypeDef *USARTx) -{ - CLEAR_BIT(USARTx->CR3, USART_CR3_NACK); -} - -/** - * @brief Indicate if Smartcard NACK transmission is enabled - * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not - * Smartcard feature is supported by the USARTx instance. - * @rmtoll CR3 NACK LL_USART_IsEnabledSmartcardNACK - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledSmartcardNACK(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR3, USART_CR3_NACK) == (USART_CR3_NACK)); -} - -/** - * @brief Enable Smartcard mode - * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not - * Smartcard feature is supported by the USARTx instance. - * @rmtoll CR3 SCEN LL_USART_EnableSmartcard - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableSmartcard(USART_TypeDef *USARTx) -{ - SET_BIT(USARTx->CR3, USART_CR3_SCEN); -} - -/** - * @brief Disable Smartcard mode - * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not - * Smartcard feature is supported by the USARTx instance. - * @rmtoll CR3 SCEN LL_USART_DisableSmartcard - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableSmartcard(USART_TypeDef *USARTx) -{ - CLEAR_BIT(USARTx->CR3, USART_CR3_SCEN); -} - -/** - * @brief Indicate if Smartcard mode is enabled - * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not - * Smartcard feature is supported by the USARTx instance. - * @rmtoll CR3 SCEN LL_USART_IsEnabledSmartcard - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledSmartcard(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR3, USART_CR3_SCEN) == (USART_CR3_SCEN)); -} - -/** - * @brief Set Smartcard prescaler value, used for dividing the USART clock - * source to provide the SMARTCARD Clock (5 bits value) - * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not - * Smartcard feature is supported by the USARTx instance. - * @rmtoll GTPR PSC LL_USART_SetSmartcardPrescaler - * @param USARTx USART Instance - * @param PrescalerValue Value between Min_Data=0 and Max_Data=31 - * @retval None - */ -__STATIC_INLINE void LL_USART_SetSmartcardPrescaler(USART_TypeDef *USARTx, uint32_t PrescalerValue) -{ - MODIFY_REG(USARTx->GTPR, USART_GTPR_PSC, PrescalerValue); -} - -/** - * @brief Return Smartcard prescaler value, used for dividing the USART clock - * source to provide the SMARTCARD Clock (5 bits value) - * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not - * Smartcard feature is supported by the USARTx instance. - * @rmtoll GTPR PSC LL_USART_GetSmartcardPrescaler - * @param USARTx USART Instance - * @retval Smartcard prescaler value (Value between Min_Data=0 and Max_Data=31) - */ -__STATIC_INLINE uint32_t LL_USART_GetSmartcardPrescaler(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->GTPR, USART_GTPR_PSC)); -} - -/** - * @brief Set Smartcard Guard time value, expressed in nb of baud clocks periods - * (GT[7:0] bits : Guard time value) - * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not - * Smartcard feature is supported by the USARTx instance. - * @rmtoll GTPR GT LL_USART_SetSmartcardGuardTime - * @param USARTx USART Instance - * @param GuardTime Value between Min_Data=0x00 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_USART_SetSmartcardGuardTime(USART_TypeDef *USARTx, uint32_t GuardTime) -{ - MODIFY_REG(USARTx->GTPR, USART_GTPR_GT, GuardTime << USART_POSITION_GTPR_GT); -} - -/** - * @brief Return Smartcard Guard time value, expressed in nb of baud clocks periods - * (GT[7:0] bits : Guard time value) - * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not - * Smartcard feature is supported by the USARTx instance. - * @rmtoll GTPR GT LL_USART_GetSmartcardGuardTime - * @param USARTx USART Instance - * @retval Smartcard Guard time value (Value between Min_Data=0x00 and Max_Data=0xFF) - */ -__STATIC_INLINE uint32_t LL_USART_GetSmartcardGuardTime(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->GTPR, USART_GTPR_GT) >> USART_POSITION_GTPR_GT); -} - -/** - * @} - */ - -/** @defgroup USART_LL_EF_Configuration_HalfDuplex Configuration functions related to Half Duplex feature - * @{ - */ - -/** - * @brief Enable Single Wire Half-Duplex mode - * @note Macro @ref IS_UART_HALFDUPLEX_INSTANCE(USARTx) can be used to check whether or not - * Half-Duplex mode is supported by the USARTx instance. - * @rmtoll CR3 HDSEL LL_USART_EnableHalfDuplex - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableHalfDuplex(USART_TypeDef *USARTx) -{ - SET_BIT(USARTx->CR3, USART_CR3_HDSEL); -} - -/** - * @brief Disable Single Wire Half-Duplex mode - * @note Macro @ref IS_UART_HALFDUPLEX_INSTANCE(USARTx) can be used to check whether or not - * Half-Duplex mode is supported by the USARTx instance. - * @rmtoll CR3 HDSEL LL_USART_DisableHalfDuplex - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableHalfDuplex(USART_TypeDef *USARTx) -{ - CLEAR_BIT(USARTx->CR3, USART_CR3_HDSEL); -} - -/** - * @brief Indicate if Single Wire Half-Duplex mode is enabled - * @note Macro @ref IS_UART_HALFDUPLEX_INSTANCE(USARTx) can be used to check whether or not - * Half-Duplex mode is supported by the USARTx instance. - * @rmtoll CR3 HDSEL LL_USART_IsEnabledHalfDuplex - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledHalfDuplex(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR3, USART_CR3_HDSEL) == (USART_CR3_HDSEL)); -} - -/** - * @} - */ - -/** @defgroup USART_LL_EF_Configuration_LIN Configuration functions related to LIN feature - * @{ - */ - -/** - * @brief Set LIN Break Detection Length - * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not - * LIN feature is supported by the USARTx instance. - * @rmtoll CR2 LBDL LL_USART_SetLINBrkDetectionLen - * @param USARTx USART Instance - * @param LINBDLength This parameter can be one of the following values: - * @arg @ref LL_USART_LINBREAK_DETECT_10B - * @arg @ref LL_USART_LINBREAK_DETECT_11B - * @retval None - */ -__STATIC_INLINE void LL_USART_SetLINBrkDetectionLen(USART_TypeDef *USARTx, uint32_t LINBDLength) -{ - MODIFY_REG(USARTx->CR2, USART_CR2_LBDL, LINBDLength); -} - -/** - * @brief Return LIN Break Detection Length - * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not - * LIN feature is supported by the USARTx instance. - * @rmtoll CR2 LBDL LL_USART_GetLINBrkDetectionLen - * @param USARTx USART Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_USART_LINBREAK_DETECT_10B - * @arg @ref LL_USART_LINBREAK_DETECT_11B - */ -__STATIC_INLINE uint32_t LL_USART_GetLINBrkDetectionLen(USART_TypeDef *USARTx) -{ - return (uint32_t)(READ_BIT(USARTx->CR2, USART_CR2_LBDL)); -} - -/** - * @brief Enable LIN mode - * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not - * LIN feature is supported by the USARTx instance. - * @rmtoll CR2 LINEN LL_USART_EnableLIN - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableLIN(USART_TypeDef *USARTx) -{ - SET_BIT(USARTx->CR2, USART_CR2_LINEN); -} - -/** - * @brief Disable LIN mode - * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not - * LIN feature is supported by the USARTx instance. - * @rmtoll CR2 LINEN LL_USART_DisableLIN - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableLIN(USART_TypeDef *USARTx) -{ - CLEAR_BIT(USARTx->CR2, USART_CR2_LINEN); -} - -/** - * @brief Indicate if LIN mode is enabled - * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not - * LIN feature is supported by the USARTx instance. - * @rmtoll CR2 LINEN LL_USART_IsEnabledLIN - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledLIN(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR2, USART_CR2_LINEN) == (USART_CR2_LINEN)); -} - -/** - * @} - */ - -/** @defgroup USART_LL_EF_AdvancedConfiguration Advanced Configurations services - * @{ - */ - -/** - * @brief Perform basic configuration of USART for enabling use in Asynchronous Mode (UART) - * @note In UART mode, the following bits must be kept cleared: - * - LINEN bit in the USART_CR2 register, - * - CLKEN bit in the USART_CR2 register, - * - SCEN bit in the USART_CR3 register, - * - IREN bit in the USART_CR3 register, - * - HDSEL bit in the USART_CR3 register. - * @note Call of this function is equivalent to following function call sequence : - * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function - * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function - * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function - * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function - * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function - * @note Other remaining configurations items related to Asynchronous Mode - * (as Baud Rate, Word length, Parity, ...) should be set using - * dedicated functions - * @rmtoll CR2 LINEN LL_USART_ConfigAsyncMode\n - * CR2 CLKEN LL_USART_ConfigAsyncMode\n - * CR3 SCEN LL_USART_ConfigAsyncMode\n - * CR3 IREN LL_USART_ConfigAsyncMode\n - * CR3 HDSEL LL_USART_ConfigAsyncMode - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ConfigAsyncMode(USART_TypeDef *USARTx) -{ - /* In Asynchronous mode, the following bits must be kept cleared: - - LINEN, CLKEN bits in the USART_CR2 register, - - SCEN, IREN and HDSEL bits in the USART_CR3 register.*/ - CLEAR_BIT(USARTx->CR2, (USART_CR2_LINEN | USART_CR2_CLKEN)); - CLEAR_BIT(USARTx->CR3, (USART_CR3_SCEN | USART_CR3_IREN | USART_CR3_HDSEL)); -} - -/** - * @brief Perform basic configuration of USART for enabling use in Synchronous Mode - * @note In Synchronous mode, the following bits must be kept cleared: - * - LINEN bit in the USART_CR2 register, - * - SCEN bit in the USART_CR3 register, - * - IREN bit in the USART_CR3 register, - * - HDSEL bit in the USART_CR3 register. - * This function also sets the USART in Synchronous mode. - * @note Macro @ref IS_USART_INSTANCE(USARTx) can be used to check whether or not - * Synchronous mode is supported by the USARTx instance. - * @note Call of this function is equivalent to following function call sequence : - * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function - * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function - * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function - * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function - * - Set CLKEN in CR2 using @ref LL_USART_EnableSCLKOutput() function - * @note Other remaining configurations items related to Synchronous Mode - * (as Baud Rate, Word length, Parity, Clock Polarity, ...) should be set using - * dedicated functions - * @rmtoll CR2 LINEN LL_USART_ConfigSyncMode\n - * CR2 CLKEN LL_USART_ConfigSyncMode\n - * CR3 SCEN LL_USART_ConfigSyncMode\n - * CR3 IREN LL_USART_ConfigSyncMode\n - * CR3 HDSEL LL_USART_ConfigSyncMode - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ConfigSyncMode(USART_TypeDef *USARTx) -{ - /* In Synchronous mode, the following bits must be kept cleared: - - LINEN bit in the USART_CR2 register, - - SCEN, IREN and HDSEL bits in the USART_CR3 register.*/ - CLEAR_BIT(USARTx->CR2, (USART_CR2_LINEN)); - CLEAR_BIT(USARTx->CR3, (USART_CR3_SCEN | USART_CR3_IREN | USART_CR3_HDSEL)); - /* set the UART/USART in Synchronous mode */ - SET_BIT(USARTx->CR2, USART_CR2_CLKEN); -} - -/** - * @brief Perform basic configuration of USART for enabling use in LIN Mode - * @note In LIN mode, the following bits must be kept cleared: - * - STOP and CLKEN bits in the USART_CR2 register, - * - SCEN bit in the USART_CR3 register, - * - IREN bit in the USART_CR3 register, - * - HDSEL bit in the USART_CR3 register. - * This function also set the UART/USART in LIN mode. - * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not - * LIN feature is supported by the USARTx instance. - * @note Call of this function is equivalent to following function call sequence : - * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function - * - Clear STOP in CR2 using @ref LL_USART_SetStopBitsLength() function - * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function - * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function - * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function - * - Set LINEN in CR2 using @ref LL_USART_EnableLIN() function - * @note Other remaining configurations items related to LIN Mode - * (as Baud Rate, Word length, LIN Break Detection Length, ...) should be set using - * dedicated functions - * @rmtoll CR2 CLKEN LL_USART_ConfigLINMode\n - * CR2 STOP LL_USART_ConfigLINMode\n - * CR2 LINEN LL_USART_ConfigLINMode\n - * CR3 IREN LL_USART_ConfigLINMode\n - * CR3 SCEN LL_USART_ConfigLINMode\n - * CR3 HDSEL LL_USART_ConfigLINMode - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ConfigLINMode(USART_TypeDef *USARTx) -{ - /* In LIN mode, the following bits must be kept cleared: - - STOP and CLKEN bits in the USART_CR2 register, - - IREN, SCEN and HDSEL bits in the USART_CR3 register.*/ - CLEAR_BIT(USARTx->CR2, (USART_CR2_CLKEN | USART_CR2_STOP)); - CLEAR_BIT(USARTx->CR3, (USART_CR3_IREN | USART_CR3_SCEN | USART_CR3_HDSEL)); - /* Set the UART/USART in LIN mode */ - SET_BIT(USARTx->CR2, USART_CR2_LINEN); -} - -/** - * @brief Perform basic configuration of USART for enabling use in Half Duplex Mode - * @note In Half Duplex mode, the following bits must be kept cleared: - * - LINEN bit in the USART_CR2 register, - * - CLKEN bit in the USART_CR2 register, - * - SCEN bit in the USART_CR3 register, - * - IREN bit in the USART_CR3 register, - * This function also sets the UART/USART in Half Duplex mode. - * @note Macro @ref IS_UART_HALFDUPLEX_INSTANCE(USARTx) can be used to check whether or not - * Half-Duplex mode is supported by the USARTx instance. - * @note Call of this function is equivalent to following function call sequence : - * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function - * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function - * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function - * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function - * - Set HDSEL in CR3 using @ref LL_USART_EnableHalfDuplex() function - * @note Other remaining configurations items related to Half Duplex Mode - * (as Baud Rate, Word length, Parity, ...) should be set using - * dedicated functions - * @rmtoll CR2 LINEN LL_USART_ConfigHalfDuplexMode\n - * CR2 CLKEN LL_USART_ConfigHalfDuplexMode\n - * CR3 HDSEL LL_USART_ConfigHalfDuplexMode\n - * CR3 SCEN LL_USART_ConfigHalfDuplexMode\n - * CR3 IREN LL_USART_ConfigHalfDuplexMode - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ConfigHalfDuplexMode(USART_TypeDef *USARTx) -{ - /* In Half Duplex mode, the following bits must be kept cleared: - - LINEN and CLKEN bits in the USART_CR2 register, - - SCEN and IREN bits in the USART_CR3 register.*/ - CLEAR_BIT(USARTx->CR2, (USART_CR2_LINEN | USART_CR2_CLKEN)); - CLEAR_BIT(USARTx->CR3, (USART_CR3_SCEN | USART_CR3_IREN)); - /* set the UART/USART in Half Duplex mode */ - SET_BIT(USARTx->CR3, USART_CR3_HDSEL); -} - -/** - * @brief Perform basic configuration of USART for enabling use in Smartcard Mode - * @note In Smartcard mode, the following bits must be kept cleared: - * - LINEN bit in the USART_CR2 register, - * - IREN bit in the USART_CR3 register, - * - HDSEL bit in the USART_CR3 register. - * This function also configures Stop bits to 1.5 bits and - * sets the USART in Smartcard mode (SCEN bit). - * Clock Output is also enabled (CLKEN). - * @note Macro @ref IS_SMARTCARD_INSTANCE(USARTx) can be used to check whether or not - * Smartcard feature is supported by the USARTx instance. - * @note Call of this function is equivalent to following function call sequence : - * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function - * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function - * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function - * - Configure STOP in CR2 using @ref LL_USART_SetStopBitsLength() function - * - Set CLKEN in CR2 using @ref LL_USART_EnableSCLKOutput() function - * - Set SCEN in CR3 using @ref LL_USART_EnableSmartcard() function - * @note Other remaining configurations items related to Smartcard Mode - * (as Baud Rate, Word length, Parity, ...) should be set using - * dedicated functions - * @rmtoll CR2 LINEN LL_USART_ConfigSmartcardMode\n - * CR2 STOP LL_USART_ConfigSmartcardMode\n - * CR2 CLKEN LL_USART_ConfigSmartcardMode\n - * CR3 HDSEL LL_USART_ConfigSmartcardMode\n - * CR3 SCEN LL_USART_ConfigSmartcardMode - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ConfigSmartcardMode(USART_TypeDef *USARTx) -{ - /* In Smartcard mode, the following bits must be kept cleared: - - LINEN bit in the USART_CR2 register, - - IREN and HDSEL bits in the USART_CR3 register.*/ - CLEAR_BIT(USARTx->CR2, (USART_CR2_LINEN)); - CLEAR_BIT(USARTx->CR3, (USART_CR3_IREN | USART_CR3_HDSEL)); - /* Configure Stop bits to 1.5 bits */ - /* Synchronous mode is activated by default */ - SET_BIT(USARTx->CR2, (USART_CR2_STOP_0 | USART_CR2_STOP_1 | USART_CR2_CLKEN)); - /* set the UART/USART in Smartcard mode */ - SET_BIT(USARTx->CR3, USART_CR3_SCEN); -} - -/** - * @brief Perform basic configuration of USART for enabling use in Irda Mode - * @note In IRDA mode, the following bits must be kept cleared: - * - LINEN bit in the USART_CR2 register, - * - STOP and CLKEN bits in the USART_CR2 register, - * - SCEN bit in the USART_CR3 register, - * - HDSEL bit in the USART_CR3 register. - * This function also sets the UART/USART in IRDA mode (IREN bit). - * @note Macro @ref IS_IRDA_INSTANCE(USARTx) can be used to check whether or not - * IrDA feature is supported by the USARTx instance. - * @note Call of this function is equivalent to following function call sequence : - * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function - * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function - * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function - * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function - * - Configure STOP in CR2 using @ref LL_USART_SetStopBitsLength() function - * - Set IREN in CR3 using @ref LL_USART_EnableIrda() function - * @note Other remaining configurations items related to Irda Mode - * (as Baud Rate, Word length, Power mode, ...) should be set using - * dedicated functions - * @rmtoll CR2 LINEN LL_USART_ConfigIrdaMode\n - * CR2 CLKEN LL_USART_ConfigIrdaMode\n - * CR2 STOP LL_USART_ConfigIrdaMode\n - * CR3 SCEN LL_USART_ConfigIrdaMode\n - * CR3 HDSEL LL_USART_ConfigIrdaMode\n - * CR3 IREN LL_USART_ConfigIrdaMode - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ConfigIrdaMode(USART_TypeDef *USARTx) -{ - /* In IRDA mode, the following bits must be kept cleared: - - LINEN, STOP and CLKEN bits in the USART_CR2 register, - - SCEN and HDSEL bits in the USART_CR3 register.*/ - CLEAR_BIT(USARTx->CR2, (USART_CR2_LINEN | USART_CR2_CLKEN | USART_CR2_STOP)); - CLEAR_BIT(USARTx->CR3, (USART_CR3_SCEN | USART_CR3_HDSEL)); - /* set the UART/USART in IRDA mode */ - SET_BIT(USARTx->CR3, USART_CR3_IREN); -} - -/** - * @brief Perform basic configuration of USART for enabling use in Multi processor Mode - * (several USARTs connected in a network, one of the USARTs can be the master, - * its TX output connected to the RX inputs of the other slaves USARTs). - * @note In MultiProcessor mode, the following bits must be kept cleared: - * - LINEN bit in the USART_CR2 register, - * - CLKEN bit in the USART_CR2 register, - * - SCEN bit in the USART_CR3 register, - * - IREN bit in the USART_CR3 register, - * - HDSEL bit in the USART_CR3 register. - * @note Call of this function is equivalent to following function call sequence : - * - Clear LINEN in CR2 using @ref LL_USART_DisableLIN() function - * - Clear CLKEN in CR2 using @ref LL_USART_DisableSCLKOutput() function - * - Clear SCEN in CR3 using @ref LL_USART_DisableSmartcard() function - * - Clear IREN in CR3 using @ref LL_USART_DisableIrda() function - * - Clear HDSEL in CR3 using @ref LL_USART_DisableHalfDuplex() function - * @note Other remaining configurations items related to Multi processor Mode - * (as Baud Rate, Wake Up Method, Node address, ...) should be set using - * dedicated functions - * @rmtoll CR2 LINEN LL_USART_ConfigMultiProcessMode\n - * CR2 CLKEN LL_USART_ConfigMultiProcessMode\n - * CR3 SCEN LL_USART_ConfigMultiProcessMode\n - * CR3 HDSEL LL_USART_ConfigMultiProcessMode\n - * CR3 IREN LL_USART_ConfigMultiProcessMode - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ConfigMultiProcessMode(USART_TypeDef *USARTx) -{ - /* In Multi Processor mode, the following bits must be kept cleared: - - LINEN and CLKEN bits in the USART_CR2 register, - - IREN, SCEN and HDSEL bits in the USART_CR3 register.*/ - CLEAR_BIT(USARTx->CR2, (USART_CR2_LINEN | USART_CR2_CLKEN)); - CLEAR_BIT(USARTx->CR3, (USART_CR3_SCEN | USART_CR3_HDSEL | USART_CR3_IREN)); -} - -/** - * @} - */ - -/** @defgroup USART_LL_EF_FLAG_Management FLAG_Management - * @{ - */ - -/** - * @brief Check if the USART Parity Error Flag is set or not - * @rmtoll SR PE LL_USART_IsActiveFlag_PE - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_PE(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->SR, USART_SR_PE) == (USART_SR_PE)); -} - -/** - * @brief Check if the USART Framing Error Flag is set or not - * @rmtoll SR FE LL_USART_IsActiveFlag_FE - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_FE(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->SR, USART_SR_FE) == (USART_SR_FE)); -} - -/** - * @brief Check if the USART Noise error detected Flag is set or not - * @rmtoll SR NF LL_USART_IsActiveFlag_NE - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_NE(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->SR, USART_SR_NE) == (USART_SR_NE)); -} - -/** - * @brief Check if the USART OverRun Error Flag is set or not - * @rmtoll SR ORE LL_USART_IsActiveFlag_ORE - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_ORE(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->SR, USART_SR_ORE) == (USART_SR_ORE)); -} - -/** - * @brief Check if the USART IDLE line detected Flag is set or not - * @rmtoll SR IDLE LL_USART_IsActiveFlag_IDLE - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_IDLE(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->SR, USART_SR_IDLE) == (USART_SR_IDLE)); -} - -/** - * @brief Check if the USART Read Data Register Not Empty Flag is set or not - * @rmtoll SR RXNE LL_USART_IsActiveFlag_RXNE - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_RXNE(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->SR, USART_SR_RXNE) == (USART_SR_RXNE)); -} - -/** - * @brief Check if the USART Transmission Complete Flag is set or not - * @rmtoll SR TC LL_USART_IsActiveFlag_TC - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_TC(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->SR, USART_SR_TC) == (USART_SR_TC)); -} - -/** - * @brief Check if the USART Transmit Data Register Empty Flag is set or not - * @rmtoll SR TXE LL_USART_IsActiveFlag_TXE - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_TXE(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->SR, USART_SR_TXE) == (USART_SR_TXE)); -} - -/** - * @brief Check if the USART LIN Break Detection Flag is set or not - * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not - * LIN feature is supported by the USARTx instance. - * @rmtoll SR LBD LL_USART_IsActiveFlag_LBD - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_LBD(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->SR, USART_SR_LBD) == (USART_SR_LBD)); -} - -/** - * @brief Check if the USART CTS Flag is set or not - * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not - * Hardware Flow control feature is supported by the USARTx instance. - * @rmtoll SR CTS LL_USART_IsActiveFlag_nCTS - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_nCTS(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->SR, USART_SR_CTS) == (USART_SR_CTS)); -} - -/** - * @brief Check if the USART Send Break Flag is set or not - * @rmtoll CR1 SBK LL_USART_IsActiveFlag_SBK - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_SBK(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR1, USART_CR1_SBK) == (USART_CR1_SBK)); -} - -/** - * @brief Check if the USART Receive Wake Up from mute mode Flag is set or not - * @rmtoll CR1 RWU LL_USART_IsActiveFlag_RWU - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsActiveFlag_RWU(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR1, USART_CR1_RWU) == (USART_CR1_RWU)); -} - -/** - * @brief Clear Parity Error Flag - * @note Clearing this flag is done by a read access to the USARTx_SR - * register followed by a read access to the USARTx_DR register. - * @note Please also consider that when clearing this flag, other flags as - * NE, FE, ORE, IDLE would also be cleared. - * @rmtoll SR PE LL_USART_ClearFlag_PE - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ClearFlag_PE(USART_TypeDef *USARTx) -{ - __IO uint32_t tmpreg; - tmpreg = USARTx->SR; - (void) tmpreg; - tmpreg = USARTx->DR; - (void) tmpreg; -} - -/** - * @brief Clear Framing Error Flag - * @note Clearing this flag is done by a read access to the USARTx_SR - * register followed by a read access to the USARTx_DR register. - * @note Please also consider that when clearing this flag, other flags as - * PE, NE, ORE, IDLE would also be cleared. - * @rmtoll SR FE LL_USART_ClearFlag_FE - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ClearFlag_FE(USART_TypeDef *USARTx) -{ - __IO uint32_t tmpreg; - tmpreg = USARTx->SR; - (void) tmpreg; - tmpreg = USARTx->DR; - (void) tmpreg; -} - -/** - * @brief Clear Noise detected Flag - * @note Clearing this flag is done by a read access to the USARTx_SR - * register followed by a read access to the USARTx_DR register. - * @note Please also consider that when clearing this flag, other flags as - * PE, FE, ORE, IDLE would also be cleared. - * @rmtoll SR NF LL_USART_ClearFlag_NE - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ClearFlag_NE(USART_TypeDef *USARTx) -{ - __IO uint32_t tmpreg; - tmpreg = USARTx->SR; - (void) tmpreg; - tmpreg = USARTx->DR; - (void) tmpreg; -} - -/** - * @brief Clear OverRun Error Flag - * @note Clearing this flag is done by a read access to the USARTx_SR - * register followed by a read access to the USARTx_DR register. - * @note Please also consider that when clearing this flag, other flags as - * PE, NE, FE, IDLE would also be cleared. - * @rmtoll SR ORE LL_USART_ClearFlag_ORE - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ClearFlag_ORE(USART_TypeDef *USARTx) -{ - __IO uint32_t tmpreg; - tmpreg = USARTx->SR; - (void) tmpreg; - tmpreg = USARTx->DR; - (void) tmpreg; -} - -/** - * @brief Clear IDLE line detected Flag - * @note Clearing this flag is done by a read access to the USARTx_SR - * register followed by a read access to the USARTx_DR register. - * @note Please also consider that when clearing this flag, other flags as - * PE, NE, FE, ORE would also be cleared. - * @rmtoll SR IDLE LL_USART_ClearFlag_IDLE - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ClearFlag_IDLE(USART_TypeDef *USARTx) -{ - __IO uint32_t tmpreg; - tmpreg = USARTx->SR; - (void) tmpreg; - tmpreg = USARTx->DR; - (void) tmpreg; -} - -/** - * @brief Clear Transmission Complete Flag - * @rmtoll SR TC LL_USART_ClearFlag_TC - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ClearFlag_TC(USART_TypeDef *USARTx) -{ - WRITE_REG(USARTx->SR, ~(USART_SR_TC)); -} - -/** - * @brief Clear RX Not Empty Flag - * @rmtoll SR RXNE LL_USART_ClearFlag_RXNE - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ClearFlag_RXNE(USART_TypeDef *USARTx) -{ - WRITE_REG(USARTx->SR, ~(USART_SR_RXNE)); -} - -/** - * @brief Clear LIN Break Detection Flag - * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not - * LIN feature is supported by the USARTx instance. - * @rmtoll SR LBD LL_USART_ClearFlag_LBD - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ClearFlag_LBD(USART_TypeDef *USARTx) -{ - WRITE_REG(USARTx->SR, ~(USART_SR_LBD)); -} - -/** - * @brief Clear CTS Interrupt Flag - * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not - * Hardware Flow control feature is supported by the USARTx instance. - * @rmtoll SR CTS LL_USART_ClearFlag_nCTS - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_ClearFlag_nCTS(USART_TypeDef *USARTx) -{ - WRITE_REG(USARTx->SR, ~(USART_SR_CTS)); -} - -/** - * @} - */ - -/** @defgroup USART_LL_EF_IT_Management IT_Management - * @{ - */ - -/** - * @brief Enable IDLE Interrupt - * @rmtoll CR1 IDLEIE LL_USART_EnableIT_IDLE - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableIT_IDLE(USART_TypeDef *USARTx) -{ - ATOMIC_SET_BIT(USARTx->CR1, USART_CR1_IDLEIE); -} - -/** - * @brief Enable RX Not Empty Interrupt - * @rmtoll CR1 RXNEIE LL_USART_EnableIT_RXNE - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableIT_RXNE(USART_TypeDef *USARTx) -{ - ATOMIC_SET_BIT(USARTx->CR1, USART_CR1_RXNEIE); -} - -/** - * @brief Enable Transmission Complete Interrupt - * @rmtoll CR1 TCIE LL_USART_EnableIT_TC - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableIT_TC(USART_TypeDef *USARTx) -{ - ATOMIC_SET_BIT(USARTx->CR1, USART_CR1_TCIE); -} - -/** - * @brief Enable TX Empty Interrupt - * @rmtoll CR1 TXEIE LL_USART_EnableIT_TXE - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableIT_TXE(USART_TypeDef *USARTx) -{ - ATOMIC_SET_BIT(USARTx->CR1, USART_CR1_TXEIE); -} - -/** - * @brief Enable Parity Error Interrupt - * @rmtoll CR1 PEIE LL_USART_EnableIT_PE - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableIT_PE(USART_TypeDef *USARTx) -{ - ATOMIC_SET_BIT(USARTx->CR1, USART_CR1_PEIE); -} - -/** - * @brief Enable LIN Break Detection Interrupt - * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not - * LIN feature is supported by the USARTx instance. - * @rmtoll CR2 LBDIE LL_USART_EnableIT_LBD - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableIT_LBD(USART_TypeDef *USARTx) -{ - SET_BIT(USARTx->CR2, USART_CR2_LBDIE); -} - -/** - * @brief Enable Error Interrupt - * @note When set, Error Interrupt Enable Bit is enabling interrupt generation in case of a framing - * error, overrun error or noise flag (FE=1 or ORE=1 or NF=1 in the USARTx_SR register). - * 0: Interrupt is inhibited - * 1: An interrupt is generated when FE=1 or ORE=1 or NF=1 in the USARTx_SR register. - * @rmtoll CR3 EIE LL_USART_EnableIT_ERROR - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableIT_ERROR(USART_TypeDef *USARTx) -{ - ATOMIC_SET_BIT(USARTx->CR3, USART_CR3_EIE); -} - -/** - * @brief Enable CTS Interrupt - * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not - * Hardware Flow control feature is supported by the USARTx instance. - * @rmtoll CR3 CTSIE LL_USART_EnableIT_CTS - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableIT_CTS(USART_TypeDef *USARTx) -{ - ATOMIC_SET_BIT(USARTx->CR3, USART_CR3_CTSIE); -} - -/** - * @brief Disable IDLE Interrupt - * @rmtoll CR1 IDLEIE LL_USART_DisableIT_IDLE - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableIT_IDLE(USART_TypeDef *USARTx) -{ - ATOMIC_CLEAR_BIT(USARTx->CR1, USART_CR1_IDLEIE); -} - -/** - * @brief Disable RX Not Empty Interrupt - * @rmtoll CR1 RXNEIE LL_USART_DisableIT_RXNE - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableIT_RXNE(USART_TypeDef *USARTx) -{ - ATOMIC_CLEAR_BIT(USARTx->CR1, USART_CR1_RXNEIE); -} - -/** - * @brief Disable Transmission Complete Interrupt - * @rmtoll CR1 TCIE LL_USART_DisableIT_TC - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableIT_TC(USART_TypeDef *USARTx) -{ - ATOMIC_CLEAR_BIT(USARTx->CR1, USART_CR1_TCIE); -} - -/** - * @brief Disable TX Empty Interrupt - * @rmtoll CR1 TXEIE LL_USART_DisableIT_TXE - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableIT_TXE(USART_TypeDef *USARTx) -{ - ATOMIC_CLEAR_BIT(USARTx->CR1, USART_CR1_TXEIE); -} - -/** - * @brief Disable Parity Error Interrupt - * @rmtoll CR1 PEIE LL_USART_DisableIT_PE - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableIT_PE(USART_TypeDef *USARTx) -{ - ATOMIC_CLEAR_BIT(USARTx->CR1, USART_CR1_PEIE); -} - -/** - * @brief Disable LIN Break Detection Interrupt - * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not - * LIN feature is supported by the USARTx instance. - * @rmtoll CR2 LBDIE LL_USART_DisableIT_LBD - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableIT_LBD(USART_TypeDef *USARTx) -{ - CLEAR_BIT(USARTx->CR2, USART_CR2_LBDIE); -} - -/** - * @brief Disable Error Interrupt - * @note When set, Error Interrupt Enable Bit is enabling interrupt generation in case of a framing - * error, overrun error or noise flag (FE=1 or ORE=1 or NF=1 in the USARTx_SR register). - * 0: Interrupt is inhibited - * 1: An interrupt is generated when FE=1 or ORE=1 or NF=1 in the USARTx_SR register. - * @rmtoll CR3 EIE LL_USART_DisableIT_ERROR - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableIT_ERROR(USART_TypeDef *USARTx) -{ - ATOMIC_CLEAR_BIT(USARTx->CR3, USART_CR3_EIE); -} - -/** - * @brief Disable CTS Interrupt - * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not - * Hardware Flow control feature is supported by the USARTx instance. - * @rmtoll CR3 CTSIE LL_USART_DisableIT_CTS - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableIT_CTS(USART_TypeDef *USARTx) -{ - ATOMIC_CLEAR_BIT(USARTx->CR3, USART_CR3_CTSIE); -} - -/** - * @brief Check if the USART IDLE Interrupt source is enabled or disabled. - * @rmtoll CR1 IDLEIE LL_USART_IsEnabledIT_IDLE - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledIT_IDLE(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR1, USART_CR1_IDLEIE) == (USART_CR1_IDLEIE)); -} - -/** - * @brief Check if the USART RX Not Empty Interrupt is enabled or disabled. - * @rmtoll CR1 RXNEIE LL_USART_IsEnabledIT_RXNE - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledIT_RXNE(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR1, USART_CR1_RXNEIE) == (USART_CR1_RXNEIE)); -} - -/** - * @brief Check if the USART Transmission Complete Interrupt is enabled or disabled. - * @rmtoll CR1 TCIE LL_USART_IsEnabledIT_TC - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledIT_TC(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR1, USART_CR1_TCIE) == (USART_CR1_TCIE)); -} - -/** - * @brief Check if the USART TX Empty Interrupt is enabled or disabled. - * @rmtoll CR1 TXEIE LL_USART_IsEnabledIT_TXE - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledIT_TXE(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR1, USART_CR1_TXEIE) == (USART_CR1_TXEIE)); -} - -/** - * @brief Check if the USART Parity Error Interrupt is enabled or disabled. - * @rmtoll CR1 PEIE LL_USART_IsEnabledIT_PE - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledIT_PE(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR1, USART_CR1_PEIE) == (USART_CR1_PEIE)); -} - -/** - * @brief Check if the USART LIN Break Detection Interrupt is enabled or disabled. - * @note Macro @ref IS_UART_LIN_INSTANCE(USARTx) can be used to check whether or not - * LIN feature is supported by the USARTx instance. - * @rmtoll CR2 LBDIE LL_USART_IsEnabledIT_LBD - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledIT_LBD(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR2, USART_CR2_LBDIE) == (USART_CR2_LBDIE)); -} - -/** - * @brief Check if the USART Error Interrupt is enabled or disabled. - * @rmtoll CR3 EIE LL_USART_IsEnabledIT_ERROR - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledIT_ERROR(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR3, USART_CR3_EIE) == (USART_CR3_EIE)); -} - -/** - * @brief Check if the USART CTS Interrupt is enabled or disabled. - * @note Macro @ref IS_UART_HWFLOW_INSTANCE(USARTx) can be used to check whether or not - * Hardware Flow control feature is supported by the USARTx instance. - * @rmtoll CR3 CTSIE LL_USART_IsEnabledIT_CTS - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledIT_CTS(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR3, USART_CR3_CTSIE) == (USART_CR3_CTSIE)); -} - -/** - * @} - */ - -/** @defgroup USART_LL_EF_DMA_Management DMA_Management - * @{ - */ - -/** - * @brief Enable DMA Mode for reception - * @rmtoll CR3 DMAR LL_USART_EnableDMAReq_RX - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableDMAReq_RX(USART_TypeDef *USARTx) -{ - ATOMIC_SET_BIT(USARTx->CR3, USART_CR3_DMAR); -} - -/** - * @brief Disable DMA Mode for reception - * @rmtoll CR3 DMAR LL_USART_DisableDMAReq_RX - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableDMAReq_RX(USART_TypeDef *USARTx) -{ - ATOMIC_CLEAR_BIT(USARTx->CR3, USART_CR3_DMAR); -} - -/** - * @brief Check if DMA Mode is enabled for reception - * @rmtoll CR3 DMAR LL_USART_IsEnabledDMAReq_RX - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledDMAReq_RX(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR3, USART_CR3_DMAR) == (USART_CR3_DMAR)); -} - -/** - * @brief Enable DMA Mode for transmission - * @rmtoll CR3 DMAT LL_USART_EnableDMAReq_TX - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_EnableDMAReq_TX(USART_TypeDef *USARTx) -{ - ATOMIC_SET_BIT(USARTx->CR3, USART_CR3_DMAT); -} - -/** - * @brief Disable DMA Mode for transmission - * @rmtoll CR3 DMAT LL_USART_DisableDMAReq_TX - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_DisableDMAReq_TX(USART_TypeDef *USARTx) -{ - ATOMIC_CLEAR_BIT(USARTx->CR3, USART_CR3_DMAT); -} - -/** - * @brief Check if DMA Mode is enabled for transmission - * @rmtoll CR3 DMAT LL_USART_IsEnabledDMAReq_TX - * @param USARTx USART Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_USART_IsEnabledDMAReq_TX(USART_TypeDef *USARTx) -{ - return (READ_BIT(USARTx->CR3, USART_CR3_DMAT) == (USART_CR3_DMAT)); -} - -/** - * @brief Get the data register address used for DMA transfer - * @rmtoll DR DR LL_USART_DMA_GetRegAddr - * @note Address of Data Register is valid for both Transmit and Receive transfers. - * @param USARTx USART Instance - * @retval Address of data register - */ -__STATIC_INLINE uint32_t LL_USART_DMA_GetRegAddr(USART_TypeDef *USARTx) -{ - /* return address of DR register */ - return ((uint32_t) &(USARTx->DR)); -} - -/** - * @} - */ - -/** @defgroup USART_LL_EF_Data_Management Data_Management - * @{ - */ - -/** - * @brief Read Receiver Data register (Receive Data value, 8 bits) - * @rmtoll DR DR LL_USART_ReceiveData8 - * @param USARTx USART Instance - * @retval Value between Min_Data=0x00 and Max_Data=0xFF - */ -__STATIC_INLINE uint8_t LL_USART_ReceiveData8(USART_TypeDef *USARTx) -{ - return (uint8_t)(READ_BIT(USARTx->DR, USART_DR_DR)); -} - -/** - * @brief Read Receiver Data register (Receive Data value, 9 bits) - * @rmtoll DR DR LL_USART_ReceiveData9 - * @param USARTx USART Instance - * @retval Value between Min_Data=0x00 and Max_Data=0x1FF - */ -__STATIC_INLINE uint16_t LL_USART_ReceiveData9(USART_TypeDef *USARTx) -{ - return (uint16_t)(READ_BIT(USARTx->DR, USART_DR_DR)); -} - -/** - * @brief Write in Transmitter Data Register (Transmit Data value, 8 bits) - * @rmtoll DR DR LL_USART_TransmitData8 - * @param USARTx USART Instance - * @param Value between Min_Data=0x00 and Max_Data=0xFF - * @retval None - */ -__STATIC_INLINE void LL_USART_TransmitData8(USART_TypeDef *USARTx, uint8_t Value) -{ - USARTx->DR = Value; -} - -/** - * @brief Write in Transmitter Data Register (Transmit Data value, 9 bits) - * @rmtoll DR DR LL_USART_TransmitData9 - * @param USARTx USART Instance - * @param Value between Min_Data=0x00 and Max_Data=0x1FF - * @retval None - */ -__STATIC_INLINE void LL_USART_TransmitData9(USART_TypeDef *USARTx, uint16_t Value) -{ - USARTx->DR = Value & 0x1FFU; -} - -/** - * @} - */ - -/** @defgroup USART_LL_EF_Execution Execution - * @{ - */ - -/** - * @brief Request Break sending - * @rmtoll CR1 SBK LL_USART_RequestBreakSending - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_RequestBreakSending(USART_TypeDef *USARTx) -{ - SET_BIT(USARTx->CR1, USART_CR1_SBK); -} - -/** - * @brief Put USART in Mute mode - * @rmtoll CR1 RWU LL_USART_RequestEnterMuteMode - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_RequestEnterMuteMode(USART_TypeDef *USARTx) -{ - SET_BIT(USARTx->CR1, USART_CR1_RWU); -} - -/** - * @brief Put USART in Active mode - * @rmtoll CR1 RWU LL_USART_RequestExitMuteMode - * @param USARTx USART Instance - * @retval None - */ -__STATIC_INLINE void LL_USART_RequestExitMuteMode(USART_TypeDef *USARTx) -{ - CLEAR_BIT(USARTx->CR1, USART_CR1_RWU); -} - -/** - * @} - */ - -#if defined(USE_FULL_LL_DRIVER) -/** @defgroup USART_LL_EF_Init Initialization and de-initialization functions - * @{ - */ -ErrorStatus LL_USART_DeInit(USART_TypeDef *USARTx); -ErrorStatus LL_USART_Init(USART_TypeDef *USARTx, LL_USART_InitTypeDef *USART_InitStruct); -void LL_USART_StructInit(LL_USART_InitTypeDef *USART_InitStruct); -ErrorStatus LL_USART_ClockInit(USART_TypeDef *USARTx, LL_USART_ClockInitTypeDef *USART_ClockInitStruct); -void LL_USART_ClockStructInit(LL_USART_ClockInitTypeDef *USART_ClockInitStruct); -/** - * @} - */ -#endif /* USE_FULL_LL_DRIVER */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* USART1 || USART2 || USART3 || USART6 || UART4 || UART5 || UART7 || UART8 || UART9 || UART10 */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_USART_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_usb.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_usb.h deleted file mode 100644 index ca78e2a..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_usb.h +++ /dev/null @@ -1,522 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_usb.h - * @author MCD Application Team - * @brief Header file of USB Low Layer HAL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_LL_USB_H -#define STM32F4xx_LL_USB_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @addtogroup USB_LL - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ - -/** - * @brief USB Mode definition - */ -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) - -typedef enum -{ - USB_DEVICE_MODE = 0, - USB_HOST_MODE = 1, - USB_DRD_MODE = 2 -} USB_OTG_ModeTypeDef; - -/** - * @brief URB States definition - */ -typedef enum -{ - URB_IDLE = 0, - URB_DONE, - URB_NOTREADY, - URB_NYET, - URB_ERROR, - URB_STALL -} USB_OTG_URBStateTypeDef; - -/** - * @brief Host channel States definition - */ -typedef enum -{ - HC_IDLE = 0, - HC_XFRC, - HC_HALTED, - HC_NAK, - HC_NYET, - HC_STALL, - HC_XACTERR, - HC_BBLERR, - HC_DATATGLERR -} USB_OTG_HCStateTypeDef; - -/** - * @brief USB Instance Initialization Structure definition - */ -typedef struct -{ - uint32_t dev_endpoints; /*!< Device Endpoints number. - This parameter depends on the used USB core. - This parameter must be a number between Min_Data = 1 and Max_Data = 15 */ - - uint32_t Host_channels; /*!< Host Channels number. - This parameter Depends on the used USB core. - This parameter must be a number between Min_Data = 1 and Max_Data = 15 */ - - uint32_t speed; /*!< USB Core speed. - This parameter can be any value of @ref PCD_Speed/HCD_Speed - (HCD_SPEED_xxx, HCD_SPEED_xxx) */ - - uint32_t dma_enable; /*!< Enable or disable of the USB embedded DMA used only for OTG HS. */ - - uint32_t ep0_mps; /*!< Set the Endpoint 0 Max Packet size. */ - - uint32_t phy_itface; /*!< Select the used PHY interface. - This parameter can be any value of @ref PCD_PHY_Module/HCD_PHY_Module */ - - uint32_t Sof_enable; /*!< Enable or disable the output of the SOF signal. */ - - uint32_t low_power_enable; /*!< Enable or disable the low power mode. */ - - uint32_t lpm_enable; /*!< Enable or disable Link Power Management. */ - - uint32_t battery_charging_enable; /*!< Enable or disable Battery charging. */ - - uint32_t vbus_sensing_enable; /*!< Enable or disable the VBUS Sensing feature. */ - - uint32_t use_dedicated_ep1; /*!< Enable or disable the use of the dedicated EP1 interrupt. */ - - uint32_t use_external_vbus; /*!< Enable or disable the use of the external VBUS. */ - -} USB_OTG_CfgTypeDef; - -typedef struct -{ - uint8_t num; /*!< Endpoint number - This parameter must be a number between Min_Data = 1 and Max_Data = 15 */ - - uint8_t is_in; /*!< Endpoint direction - This parameter must be a number between Min_Data = 0 and Max_Data = 1 */ - - uint8_t is_stall; /*!< Endpoint stall condition - This parameter must be a number between Min_Data = 0 and Max_Data = 1 */ - - uint8_t type; /*!< Endpoint type - This parameter can be any value of @ref USB_LL_EP_Type */ - - uint8_t data_pid_start; /*!< Initial data PID - This parameter must be a number between Min_Data = 0 and Max_Data = 1 */ - - uint8_t even_odd_frame; /*!< IFrame parity - This parameter must be a number between Min_Data = 0 and Max_Data = 1 */ - - uint16_t tx_fifo_num; /*!< Transmission FIFO number - This parameter must be a number between Min_Data = 1 and Max_Data = 15 */ - - uint32_t maxpacket; /*!< Endpoint Max packet size - This parameter must be a number between Min_Data = 0 and Max_Data = 64KB */ - - uint8_t *xfer_buff; /*!< Pointer to transfer buffer */ - - uint32_t dma_addr; /*!< 32 bits aligned transfer buffer address */ - - uint32_t xfer_len; /*!< Current transfer length */ - - uint32_t xfer_count; /*!< Partial transfer length in case of multi packet transfer */ -} USB_OTG_EPTypeDef; - -typedef struct -{ - uint8_t dev_addr; /*!< USB device address. - This parameter must be a number between Min_Data = 1 and Max_Data = 255 */ - - uint8_t ch_num; /*!< Host channel number. - This parameter must be a number between Min_Data = 1 and Max_Data = 15 */ - - uint8_t ep_num; /*!< Endpoint number. - This parameter must be a number between Min_Data = 1 and Max_Data = 15 */ - - uint8_t ep_is_in; /*!< Endpoint direction - This parameter must be a number between Min_Data = 0 and Max_Data = 1 */ - - uint8_t speed; /*!< USB Host Channel speed. - This parameter can be any value of @ref HCD_Device_Speed: - (HCD_DEVICE_SPEED_xxx) */ - - uint8_t do_ping; /*!< Enable or disable the use of the PING protocol for HS mode. */ - - uint8_t process_ping; /*!< Execute the PING protocol for HS mode. */ - - uint8_t ep_type; /*!< Endpoint Type. - This parameter can be any value of @ref USB_LL_EP_Type */ - - uint16_t max_packet; /*!< Endpoint Max packet size. - This parameter must be a number between Min_Data = 0 and Max_Data = 64KB */ - - uint8_t data_pid; /*!< Initial data PID. - This parameter must be a number between Min_Data = 0 and Max_Data = 1 */ - - uint8_t *xfer_buff; /*!< Pointer to transfer buffer. */ - - uint32_t XferSize; /*!< OTG Channel transfer size. */ - - uint32_t xfer_len; /*!< Current transfer length. */ - - uint32_t xfer_count; /*!< Partial transfer length in case of multi packet transfer. */ - - uint8_t toggle_in; /*!< IN transfer current toggle flag. - This parameter must be a number between Min_Data = 0 and Max_Data = 1 */ - - uint8_t toggle_out; /*!< OUT transfer current toggle flag - This parameter must be a number between Min_Data = 0 and Max_Data = 1 */ - - uint32_t dma_addr; /*!< 32 bits aligned transfer buffer address. */ - - uint32_t ErrCnt; /*!< Host channel error count. */ - - USB_OTG_URBStateTypeDef urb_state; /*!< URB state. - This parameter can be any value of @ref USB_OTG_URBStateTypeDef */ - - USB_OTG_HCStateTypeDef state; /*!< Host Channel state. - This parameter can be any value of @ref USB_OTG_HCStateTypeDef */ -} USB_OTG_HCTypeDef; -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ - - -/* Exported constants --------------------------------------------------------*/ - -/** @defgroup PCD_Exported_Constants PCD Exported Constants - * @{ - */ - -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -/** @defgroup USB_OTG_CORE VERSION ID - * @{ - */ -#define USB_OTG_CORE_ID_300A 0x4F54300AU -#define USB_OTG_CORE_ID_310A 0x4F54310AU -/** - * @} - */ - -/** @defgroup USB_Core_Mode_ USB Core Mode - * @{ - */ -#define USB_OTG_MODE_DEVICE 0U -#define USB_OTG_MODE_HOST 1U -#define USB_OTG_MODE_DRD 2U -/** - * @} - */ - -/** @defgroup USB_LL Device Speed - * @{ - */ -#define USBD_HS_SPEED 0U -#define USBD_HSINFS_SPEED 1U -#define USBH_HS_SPEED 0U -#define USBD_FS_SPEED 2U -#define USBH_FSLS_SPEED 1U -/** - * @} - */ - -/** @defgroup USB_LL_Core_Speed USB Low Layer Core Speed - * @{ - */ -#define USB_OTG_SPEED_HIGH 0U -#define USB_OTG_SPEED_HIGH_IN_FULL 1U -#define USB_OTG_SPEED_FULL 3U -/** - * @} - */ - -/** @defgroup USB_LL_Core_PHY USB Low Layer Core PHY - * @{ - */ -#define USB_OTG_ULPI_PHY 1U -#define USB_OTG_EMBEDDED_PHY 2U -/** - * @} - */ - -/** @defgroup USB_LL_Turnaround_Timeout Turnaround Timeout Value - * @{ - */ -#ifndef USBD_HS_TRDT_VALUE -#define USBD_HS_TRDT_VALUE 9U -#endif /* USBD_HS_TRDT_VALUE */ -#ifndef USBD_FS_TRDT_VALUE -#define USBD_FS_TRDT_VALUE 5U -#define USBD_DEFAULT_TRDT_VALUE 9U -#endif /* USBD_HS_TRDT_VALUE */ -/** - * @} - */ - -/** @defgroup USB_LL_Core_MPS USB Low Layer Core MPS - * @{ - */ -#define USB_OTG_HS_MAX_PACKET_SIZE 512U -#define USB_OTG_FS_MAX_PACKET_SIZE 64U -#define USB_OTG_MAX_EP0_SIZE 64U -/** - * @} - */ - -/** @defgroup USB_LL_Core_PHY_Frequency USB Low Layer Core PHY Frequency - * @{ - */ -#define DSTS_ENUMSPD_HS_PHY_30MHZ_OR_60MHZ (0U << 1) -#define DSTS_ENUMSPD_FS_PHY_30MHZ_OR_60MHZ (1U << 1) -#define DSTS_ENUMSPD_FS_PHY_48MHZ (3U << 1) -/** - * @} - */ - -/** @defgroup USB_LL_CORE_Frame_Interval USB Low Layer Core Frame Interval - * @{ - */ -#define DCFG_FRAME_INTERVAL_80 0U -#define DCFG_FRAME_INTERVAL_85 1U -#define DCFG_FRAME_INTERVAL_90 2U -#define DCFG_FRAME_INTERVAL_95 3U -/** - * @} - */ - -/** @defgroup USB_LL_EP0_MPS USB Low Layer EP0 MPS - * @{ - */ -#define EP_MPS_64 0U -#define EP_MPS_32 1U -#define EP_MPS_16 2U -#define EP_MPS_8 3U -/** - * @} - */ - -/** @defgroup USB_LL_EP_Speed USB Low Layer EP Speed - * @{ - */ -#define EP_SPEED_LOW 0U -#define EP_SPEED_FULL 1U -#define EP_SPEED_HIGH 2U -/** - * @} - */ - -/** @defgroup USB_LL_EP_Type USB Low Layer EP Type - * @{ - */ -#define EP_TYPE_CTRL 0U -#define EP_TYPE_ISOC 1U -#define EP_TYPE_BULK 2U -#define EP_TYPE_INTR 3U -#define EP_TYPE_MSK 3U -/** - * @} - */ - -/** @defgroup USB_LL_STS_Defines USB Low Layer STS Defines - * @{ - */ -#define STS_GOUT_NAK 1U -#define STS_DATA_UPDT 2U -#define STS_XFER_COMP 3U -#define STS_SETUP_COMP 4U -#define STS_SETUP_UPDT 6U -/** - * @} - */ - -/** @defgroup USB_LL_HCFG_SPEED_Defines USB Low Layer HCFG Speed Defines - * @{ - */ -#define HCFG_30_60_MHZ 0U -#define HCFG_48_MHZ 1U -#define HCFG_6_MHZ 2U -/** - * @} - */ - -/** @defgroup USB_LL_HPRT0_PRTSPD_SPEED_Defines USB Low Layer HPRT0 PRTSPD Speed Defines - * @{ - */ -#define HPRT0_PRTSPD_HIGH_SPEED 0U -#define HPRT0_PRTSPD_FULL_SPEED 1U -#define HPRT0_PRTSPD_LOW_SPEED 2U -/** - * @} - */ - -#define HCCHAR_CTRL 0U -#define HCCHAR_ISOC 1U -#define HCCHAR_BULK 2U -#define HCCHAR_INTR 3U - -#define HC_PID_DATA0 0U -#define HC_PID_DATA2 1U -#define HC_PID_DATA1 2U -#define HC_PID_SETUP 3U - -#define GRXSTS_PKTSTS_IN 2U -#define GRXSTS_PKTSTS_IN_XFER_COMP 3U -#define GRXSTS_PKTSTS_DATA_TOGGLE_ERR 5U -#define GRXSTS_PKTSTS_CH_HALTED 7U - -#define USBx_PCGCCTL *(__IO uint32_t *)((uint32_t)USBx_BASE + USB_OTG_PCGCCTL_BASE) -#define USBx_HPRT0 *(__IO uint32_t *)((uint32_t)USBx_BASE + USB_OTG_HOST_PORT_BASE) - -#define USBx_DEVICE ((USB_OTG_DeviceTypeDef *)(USBx_BASE + USB_OTG_DEVICE_BASE)) -#define USBx_INEP(i) ((USB_OTG_INEndpointTypeDef *)(USBx_BASE\ - + USB_OTG_IN_ENDPOINT_BASE + ((i) * USB_OTG_EP_REG_SIZE))) - -#define USBx_OUTEP(i) ((USB_OTG_OUTEndpointTypeDef *)(USBx_BASE\ - + USB_OTG_OUT_ENDPOINT_BASE + ((i) * USB_OTG_EP_REG_SIZE))) - -#define USBx_DFIFO(i) *(__IO uint32_t *)(USBx_BASE + USB_OTG_FIFO_BASE + ((i) * USB_OTG_FIFO_SIZE)) - -#define USBx_HOST ((USB_OTG_HostTypeDef *)(USBx_BASE + USB_OTG_HOST_BASE)) -#define USBx_HC(i) ((USB_OTG_HostChannelTypeDef *)(USBx_BASE\ - + USB_OTG_HOST_CHANNEL_BASE\ - + ((i) * USB_OTG_HOST_CHANNEL_SIZE))) - -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ - -#define EP_ADDR_MSK 0xFU -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup USB_LL_Exported_Macros USB Low Layer Exported Macros - * @{ - */ -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -#define USB_MASK_INTERRUPT(__INSTANCE__, __INTERRUPT__) ((__INSTANCE__)->GINTMSK &= ~(__INTERRUPT__)) -#define USB_UNMASK_INTERRUPT(__INSTANCE__, __INTERRUPT__) ((__INSTANCE__)->GINTMSK |= (__INTERRUPT__)) - -#define CLEAR_IN_EP_INTR(__EPNUM__, __INTERRUPT__) (USBx_INEP(__EPNUM__)->DIEPINT = (__INTERRUPT__)) -#define CLEAR_OUT_EP_INTR(__EPNUM__, __INTERRUPT__) (USBx_OUTEP(__EPNUM__)->DOEPINT = (__INTERRUPT__)) -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @addtogroup USB_LL_Exported_Functions USB Low Layer Exported Functions - * @{ - */ -#if defined (USB_OTG_FS) || defined (USB_OTG_HS) -HAL_StatusTypeDef USB_CoreInit(USB_OTG_GlobalTypeDef *USBx, USB_OTG_CfgTypeDef cfg); -HAL_StatusTypeDef USB_DevInit(USB_OTG_GlobalTypeDef *USBx, USB_OTG_CfgTypeDef cfg); -HAL_StatusTypeDef USB_EnableGlobalInt(USB_OTG_GlobalTypeDef *USBx); -HAL_StatusTypeDef USB_DisableGlobalInt(USB_OTG_GlobalTypeDef *USBx); -HAL_StatusTypeDef USB_SetTurnaroundTime(USB_OTG_GlobalTypeDef *USBx, uint32_t hclk, uint8_t speed); -HAL_StatusTypeDef USB_SetCurrentMode(USB_OTG_GlobalTypeDef *USBx, USB_OTG_ModeTypeDef mode); -HAL_StatusTypeDef USB_SetDevSpeed(USB_OTG_GlobalTypeDef *USBx, uint8_t speed); -HAL_StatusTypeDef USB_FlushRxFifo(USB_OTG_GlobalTypeDef *USBx); -HAL_StatusTypeDef USB_FlushTxFifo(USB_OTG_GlobalTypeDef *USBx, uint32_t num); -HAL_StatusTypeDef USB_ActivateEndpoint(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep); -HAL_StatusTypeDef USB_DeactivateEndpoint(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep); -HAL_StatusTypeDef USB_ActivateDedicatedEndpoint(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep); -HAL_StatusTypeDef USB_DeactivateDedicatedEndpoint(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep); -HAL_StatusTypeDef USB_EPStartXfer(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep, uint8_t dma); -HAL_StatusTypeDef USB_EP0StartXfer(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep, uint8_t dma); -HAL_StatusTypeDef USB_WritePacket(USB_OTG_GlobalTypeDef *USBx, uint8_t *src, - uint8_t ch_ep_num, uint16_t len, uint8_t dma); - -void *USB_ReadPacket(USB_OTG_GlobalTypeDef *USBx, uint8_t *dest, uint16_t len); -HAL_StatusTypeDef USB_EPSetStall(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep); -HAL_StatusTypeDef USB_EPClearStall(USB_OTG_GlobalTypeDef *USBx, USB_OTG_EPTypeDef *ep); -HAL_StatusTypeDef USB_SetDevAddress(USB_OTG_GlobalTypeDef *USBx, uint8_t address); -HAL_StatusTypeDef USB_DevConnect(USB_OTG_GlobalTypeDef *USBx); -HAL_StatusTypeDef USB_DevDisconnect(USB_OTG_GlobalTypeDef *USBx); -HAL_StatusTypeDef USB_StopDevice(USB_OTG_GlobalTypeDef *USBx); -HAL_StatusTypeDef USB_ActivateSetup(USB_OTG_GlobalTypeDef *USBx); -HAL_StatusTypeDef USB_EP0_OutStart(USB_OTG_GlobalTypeDef *USBx, uint8_t dma, uint8_t *psetup); -uint8_t USB_GetDevSpeed(USB_OTG_GlobalTypeDef *USBx); -uint32_t USB_GetMode(USB_OTG_GlobalTypeDef *USBx); -uint32_t USB_ReadInterrupts(USB_OTG_GlobalTypeDef *USBx); -uint32_t USB_ReadDevAllOutEpInterrupt(USB_OTG_GlobalTypeDef *USBx); -uint32_t USB_ReadDevOutEPInterrupt(USB_OTG_GlobalTypeDef *USBx, uint8_t epnum); -uint32_t USB_ReadDevAllInEpInterrupt(USB_OTG_GlobalTypeDef *USBx); -uint32_t USB_ReadDevInEPInterrupt(USB_OTG_GlobalTypeDef *USBx, uint8_t epnum); -void USB_ClearInterrupts(USB_OTG_GlobalTypeDef *USBx, uint32_t interrupt); - -HAL_StatusTypeDef USB_HostInit(USB_OTG_GlobalTypeDef *USBx, USB_OTG_CfgTypeDef cfg); -HAL_StatusTypeDef USB_InitFSLSPClkSel(USB_OTG_GlobalTypeDef *USBx, uint8_t freq); -HAL_StatusTypeDef USB_ResetPort(USB_OTG_GlobalTypeDef *USBx); -HAL_StatusTypeDef USB_DriveVbus(USB_OTG_GlobalTypeDef *USBx, uint8_t state); -uint32_t USB_GetHostSpeed(USB_OTG_GlobalTypeDef *USBx); -uint32_t USB_GetCurrentFrame(USB_OTG_GlobalTypeDef *USBx); -HAL_StatusTypeDef USB_HC_Init(USB_OTG_GlobalTypeDef *USBx, uint8_t ch_num, - uint8_t epnum, uint8_t dev_address, uint8_t speed, - uint8_t ep_type, uint16_t mps); -HAL_StatusTypeDef USB_HC_StartXfer(USB_OTG_GlobalTypeDef *USBx, - USB_OTG_HCTypeDef *hc, uint8_t dma); - -uint32_t USB_HC_ReadInterrupt(USB_OTG_GlobalTypeDef *USBx); -HAL_StatusTypeDef USB_HC_Halt(USB_OTG_GlobalTypeDef *USBx, uint8_t hc_num); -HAL_StatusTypeDef USB_DoPing(USB_OTG_GlobalTypeDef *USBx, uint8_t ch_num); -HAL_StatusTypeDef USB_StopHost(USB_OTG_GlobalTypeDef *USBx); -HAL_StatusTypeDef USB_ActivateRemoteWakeup(USB_OTG_GlobalTypeDef *USBx); -HAL_StatusTypeDef USB_DeActivateRemoteWakeup(USB_OTG_GlobalTypeDef *USBx); -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ -#endif /* defined (USB_OTG_FS) || defined (USB_OTG_HS) */ - -#ifdef __cplusplus -} -#endif - - -#endif /* STM32F4xx_LL_USB_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_utils.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_utils.h deleted file mode 100644 index 3bac30c..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_utils.h +++ /dev/null @@ -1,310 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_utils.h - * @author MCD Application Team - * @brief Header file of UTILS LL module. - @verbatim - ============================================================================== - ##### How to use this driver ##### - ============================================================================== - [..] - The LL UTILS driver contains a set of generic APIs that can be - used by user: - (+) Device electronic signature - (+) Timing functions - (+) PLL configuration functions - - @endverbatim - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_LL_UTILS_H -#define __STM32F4xx_LL_UTILS_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -/** @defgroup UTILS_LL UTILS - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ - -/* Private constants ---------------------------------------------------------*/ -/** @defgroup UTILS_LL_Private_Constants UTILS Private Constants - * @{ - */ - -/* Max delay can be used in LL_mDelay */ -#define LL_MAX_DELAY 0xFFFFFFFFU - -/** - * @brief Unique device ID register base address - */ -#define UID_BASE_ADDRESS UID_BASE - -/** - * @brief Flash size data register base address - */ -#define FLASHSIZE_BASE_ADDRESS FLASHSIZE_BASE - -/** - * @brief Package data register base address - */ -#define PACKAGE_BASE_ADDRESS PACKAGE_BASE - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup UTILS_LL_Private_Macros UTILS Private Macros - * @{ - */ -/** - * @} - */ -/* Exported types ------------------------------------------------------------*/ -/** @defgroup UTILS_LL_ES_INIT UTILS Exported structures - * @{ - */ -/** - * @brief UTILS PLL structure definition - */ -typedef struct -{ - uint32_t PLLM; /*!< Division factor for PLL VCO input clock. - This parameter can be a value of @ref RCC_LL_EC_PLLM_DIV - - This feature can be modified afterwards using unitary function - @ref LL_RCC_PLL_ConfigDomain_SYS(). */ - - uint32_t PLLN; /*!< Multiplication factor for PLL VCO output clock. - This parameter must be a number between Min_Data = @ref RCC_PLLN_MIN_VALUE - and Max_Data = @ref RCC_PLLN_MIN_VALUE - - This feature can be modified afterwards using unitary function - @ref LL_RCC_PLL_ConfigDomain_SYS(). */ - - uint32_t PLLP; /*!< Division for the main system clock. - This parameter can be a value of @ref RCC_LL_EC_PLLP_DIV - - This feature can be modified afterwards using unitary function - @ref LL_RCC_PLL_ConfigDomain_SYS(). */ -} LL_UTILS_PLLInitTypeDef; - -/** - * @brief UTILS System, AHB and APB buses clock configuration structure definition - */ -typedef struct -{ - uint32_t AHBCLKDivider; /*!< The AHB clock (HCLK) divider. This clock is derived from the system clock (SYSCLK). - This parameter can be a value of @ref RCC_LL_EC_SYSCLK_DIV - - This feature can be modified afterwards using unitary function - @ref LL_RCC_SetAHBPrescaler(). */ - - uint32_t APB1CLKDivider; /*!< The APB1 clock (PCLK1) divider. This clock is derived from the AHB clock (HCLK). - This parameter can be a value of @ref RCC_LL_EC_APB1_DIV - - This feature can be modified afterwards using unitary function - @ref LL_RCC_SetAPB1Prescaler(). */ - - uint32_t APB2CLKDivider; /*!< The APB2 clock (PCLK2) divider. This clock is derived from the AHB clock (HCLK). - This parameter can be a value of @ref RCC_LL_EC_APB2_DIV - - This feature can be modified afterwards using unitary function - @ref LL_RCC_SetAPB2Prescaler(). */ - -} LL_UTILS_ClkInitTypeDef; - -/** - * @} - */ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup UTILS_LL_Exported_Constants UTILS Exported Constants - * @{ - */ - -/** @defgroup UTILS_EC_HSE_BYPASS HSE Bypass activation - * @{ - */ -#define LL_UTILS_HSEBYPASS_OFF 0x00000000U /*!< HSE Bypass is not enabled */ -#define LL_UTILS_HSEBYPASS_ON 0x00000001U /*!< HSE Bypass is enabled */ -/** - * @} - */ - -/** @defgroup UTILS_EC_PACKAGETYPE PACKAGE TYPE - * @{ - */ -#define LL_UTILS_PACKAGETYPE_WLCSP36_UFQFPN48_LQFP64 0x00000000U /*!< WLCSP36 or UFQFPN48 or LQFP64 package type */ -#define LL_UTILS_PACKAGETYPE_WLCSP168_FBGA169_LQFP100_LQFP64_UFQFPN48 0x00000100U /*!< WLCSP168 or FBGA169 or LQFP100 or LQFP64 or UFQFPN48 package type */ -#define LL_UTILS_PACKAGETYPE_WLCSP64_WLCSP81_LQFP176_UFBGA176 0x00000200U /*!< WLCSP64 or WLCSP81 or LQFP176 or UFBGA176 package type */ -#define LL_UTILS_PACKAGETYPE_LQFP144_UFBGA144_UFBGA144_UFBGA100 0x00000300U /*!< LQFP144 or UFBGA144 or UFBGA144 or UFBGA100 package type */ -#define LL_UTILS_PACKAGETYPE_LQFP100_LQFP208_TFBGA216 0x00000400U /*!< LQFP100 or LQFP208 or TFBGA216 package type */ -#define LL_UTILS_PACKAGETYPE_LQFP208_TFBGA216 0x00000500U /*!< LQFP208 or TFBGA216 package type */ -#define LL_UTILS_PACKAGETYPE_TQFP64_UFBGA144_LQFP144 0x00000700U /*!< TQFP64 or UFBGA144 or LQFP144 package type */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup UTILS_LL_Exported_Functions UTILS Exported Functions - * @{ - */ - -/** @defgroup UTILS_EF_DEVICE_ELECTRONIC_SIGNATURE DEVICE ELECTRONIC SIGNATURE - * @{ - */ - -/** - * @brief Get Word0 of the unique device identifier (UID based on 96 bits) - * @retval UID[31:0] - */ -__STATIC_INLINE uint32_t LL_GetUID_Word0(void) -{ - return (uint32_t)(READ_REG(*((uint32_t *)UID_BASE_ADDRESS))); -} - -/** - * @brief Get Word1 of the unique device identifier (UID based on 96 bits) - * @retval UID[63:32] - */ -__STATIC_INLINE uint32_t LL_GetUID_Word1(void) -{ - return (uint32_t)(READ_REG(*((uint32_t *)(UID_BASE_ADDRESS + 4U)))); -} - -/** - * @brief Get Word2 of the unique device identifier (UID based on 96 bits) - * @retval UID[95:64] - */ -__STATIC_INLINE uint32_t LL_GetUID_Word2(void) -{ - return (uint32_t)(READ_REG(*((uint32_t *)(UID_BASE_ADDRESS + 8U)))); -} - -/** - * @brief Get Flash memory size - * @note This bitfield indicates the size of the device Flash memory expressed in - * Kbytes. As an example, 0x040 corresponds to 64 Kbytes. - * @retval FLASH_SIZE[15:0]: Flash memory size - */ -__STATIC_INLINE uint32_t LL_GetFlashSize(void) -{ - return (uint32_t)(READ_REG(*((uint32_t *)FLASHSIZE_BASE_ADDRESS)) & 0xFFFF); -} - -/** - * @brief Get Package type - * @retval Returned value can be one of the following values: - * @arg @ref LL_UTILS_PACKAGETYPE_WLCSP36_UFQFPN48_LQFP64 (*) - * @arg @ref LL_UTILS_PACKAGETYPE_WLCSP168_FBGA169_LQFP100_LQFP64_UFQFPN48 (*) - * @arg @ref LL_UTILS_PACKAGETYPE_WLCSP64_WLCSP81_LQFP176_UFBGA176 (*) - * @arg @ref LL_UTILS_PACKAGETYPE_LQFP144_UFBGA144_UFBGA144_UFBGA100 (*) - * @arg @ref LL_UTILS_PACKAGETYPE_LQFP100_LQFP208_TFBGA216 (*) - * @arg @ref LL_UTILS_PACKAGETYPE_LQFP208_TFBGA216 (*) - * @arg @ref LL_UTILS_PACKAGETYPE_TQFP64_UFBGA144_LQFP144 (*) - * - * (*) value not defined in all devices. - */ -__STATIC_INLINE uint32_t LL_GetPackageType(void) -{ - return (uint32_t)(READ_REG(*((uint32_t *)PACKAGE_BASE_ADDRESS)) & 0x0700U); -} - -/** - * @} - */ - -/** @defgroup UTILS_LL_EF_DELAY DELAY - * @{ - */ - -/** - * @brief This function configures the Cortex-M SysTick source of the time base. - * @param HCLKFrequency HCLK frequency in Hz (can be calculated thanks to RCC helper macro) - * @note When a RTOS is used, it is recommended to avoid changing the SysTick - * configuration by calling this function, for a delay use rather osDelay RTOS service. - * @param Ticks Number of ticks - * @retval None - */ -__STATIC_INLINE void LL_InitTick(uint32_t HCLKFrequency, uint32_t Ticks) -{ - /* Configure the SysTick to have interrupt in 1ms time base */ - SysTick->LOAD = (uint32_t)((HCLKFrequency / Ticks) - 1UL); /* set reload register */ - SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ - SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | - SysTick_CTRL_ENABLE_Msk; /* Enable the Systick Timer */ -} - -void LL_Init1msTick(uint32_t HCLKFrequency); -void LL_mDelay(uint32_t Delay); - -/** - * @} - */ - -/** @defgroup UTILS_EF_SYSTEM SYSTEM - * @{ - */ - -void LL_SetSystemCoreClock(uint32_t HCLKFrequency); -ErrorStatus LL_SetFlashLatency(uint32_t HCLK_Frequency); -ErrorStatus LL_PLL_ConfigSystemClock_HSI(LL_UTILS_PLLInitTypeDef *UTILS_PLLInitStruct, - LL_UTILS_ClkInitTypeDef *UTILS_ClkInitStruct); -ErrorStatus LL_PLL_ConfigSystemClock_HSE(uint32_t HSEFrequency, uint32_t HSEBypass, - LL_UTILS_PLLInitTypeDef *UTILS_PLLInitStruct, LL_UTILS_ClkInitTypeDef *UTILS_ClkInitStruct); - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_LL_UTILS_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_wwdg.h b/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_wwdg.h deleted file mode 100644 index f20b82d..0000000 --- a/body/board/inc/STM32F4xx_HAL_Driver/Inc/stm32f4xx_ll_wwdg.h +++ /dev/null @@ -1,319 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_ll_wwdg.h - * @author MCD Application Team - * @brief Header file of WWDG LL module. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2016 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32F4xx_LL_WWDG_H -#define STM32F4xx_LL_WWDG_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - -/** @addtogroup STM32F4xx_LL_Driver - * @{ - */ - -#if defined (WWDG) - -/** @defgroup WWDG_LL WWDG - * @{ - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/* Private macros ------------------------------------------------------------*/ -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/** @defgroup WWDG_LL_Exported_Constants WWDG Exported Constants - * @{ - */ - -/** @defgroup WWDG_LL_EC_IT IT Defines - * @brief IT defines which can be used with LL_WWDG_ReadReg and LL_WWDG_WriteReg functions - * @{ - */ -#define LL_WWDG_CFR_EWI WWDG_CFR_EWI -/** - * @} - */ - -/** @defgroup WWDG_LL_EC_PRESCALER PRESCALER - * @{ - */ -#define LL_WWDG_PRESCALER_1 0x00000000u /*!< WWDG counter clock = (PCLK1/4096)/1 */ -#define LL_WWDG_PRESCALER_2 WWDG_CFR_WDGTB_0 /*!< WWDG counter clock = (PCLK1/4096)/2 */ -#define LL_WWDG_PRESCALER_4 WWDG_CFR_WDGTB_1 /*!< WWDG counter clock = (PCLK1/4096)/4 */ -#define LL_WWDG_PRESCALER_8 (WWDG_CFR_WDGTB_0 | WWDG_CFR_WDGTB_1) /*!< WWDG counter clock = (PCLK1/4096)/8 */ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup WWDG_LL_Exported_Macros WWDG Exported Macros - * @{ - */ -/** @defgroup WWDG_LL_EM_WRITE_READ Common Write and read registers macros - * @{ - */ -/** - * @brief Write a value in WWDG register - * @param __INSTANCE__ WWDG Instance - * @param __REG__ Register to be written - * @param __VALUE__ Value to be written in the register - * @retval None - */ -#define LL_WWDG_WriteReg(__INSTANCE__, __REG__, __VALUE__) WRITE_REG(__INSTANCE__->__REG__, (__VALUE__)) - -/** - * @brief Read a value in WWDG register - * @param __INSTANCE__ WWDG Instance - * @param __REG__ Register to be read - * @retval Register value - */ -#define LL_WWDG_ReadReg(__INSTANCE__, __REG__) READ_REG(__INSTANCE__->__REG__) -/** - * @} - */ - -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup WWDG_LL_Exported_Functions WWDG Exported Functions - * @{ - */ - -/** @defgroup WWDG_LL_EF_Configuration Configuration - * @{ - */ -/** - * @brief Enable Window Watchdog. The watchdog is always disabled after a reset. - * @note It is enabled by setting the WDGA bit in the WWDG_CR register, - * then it cannot be disabled again except by a reset. - * This bit is set by software and only cleared by hardware after a reset. - * When WDGA = 1, the watchdog can generate a reset. - * @rmtoll CR WDGA LL_WWDG_Enable - * @param WWDGx WWDG Instance - * @retval None - */ -__STATIC_INLINE void LL_WWDG_Enable(WWDG_TypeDef *WWDGx) -{ - SET_BIT(WWDGx->CR, WWDG_CR_WDGA); -} - -/** - * @brief Checks if Window Watchdog is enabled - * @rmtoll CR WDGA LL_WWDG_IsEnabled - * @param WWDGx WWDG Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_WWDG_IsEnabled(WWDG_TypeDef *WWDGx) -{ - return ((READ_BIT(WWDGx->CR, WWDG_CR_WDGA) == (WWDG_CR_WDGA)) ? 1UL : 0UL); -} - -/** - * @brief Set the Watchdog counter value to provided value (7-bits T[6:0]) - * @note When writing to the WWDG_CR register, always write 1 in the MSB b6 to avoid generating an immediate reset - * This counter is decremented every (4096 x 2expWDGTB) PCLK cycles - * A reset is produced when it rolls over from 0x40 to 0x3F (bit T6 becomes cleared) - * Setting the counter lower then 0x40 causes an immediate reset (if WWDG enabled) - * @rmtoll CR T LL_WWDG_SetCounter - * @param WWDGx WWDG Instance - * @param Counter 0..0x7F (7 bit counter value) - * @retval None - */ -__STATIC_INLINE void LL_WWDG_SetCounter(WWDG_TypeDef *WWDGx, uint32_t Counter) -{ - MODIFY_REG(WWDGx->CR, WWDG_CR_T, Counter); -} - -/** - * @brief Return current Watchdog Counter Value (7 bits counter value) - * @rmtoll CR T LL_WWDG_GetCounter - * @param WWDGx WWDG Instance - * @retval 7 bit Watchdog Counter value - */ -__STATIC_INLINE uint32_t LL_WWDG_GetCounter(WWDG_TypeDef *WWDGx) -{ - return (READ_BIT(WWDGx->CR, WWDG_CR_T)); -} - -/** - * @brief Set the time base of the prescaler (WDGTB). - * @note Prescaler is used to apply ratio on PCLK clock, so that Watchdog counter - * is decremented every (4096 x 2expWDGTB) PCLK cycles - * @rmtoll CFR WDGTB LL_WWDG_SetPrescaler - * @param WWDGx WWDG Instance - * @param Prescaler This parameter can be one of the following values: - * @arg @ref LL_WWDG_PRESCALER_1 - * @arg @ref LL_WWDG_PRESCALER_2 - * @arg @ref LL_WWDG_PRESCALER_4 - * @arg @ref LL_WWDG_PRESCALER_8 - * @retval None - */ -__STATIC_INLINE void LL_WWDG_SetPrescaler(WWDG_TypeDef *WWDGx, uint32_t Prescaler) -{ - MODIFY_REG(WWDGx->CFR, WWDG_CFR_WDGTB, Prescaler); -} - -/** - * @brief Return current Watchdog Prescaler Value - * @rmtoll CFR WDGTB LL_WWDG_GetPrescaler - * @param WWDGx WWDG Instance - * @retval Returned value can be one of the following values: - * @arg @ref LL_WWDG_PRESCALER_1 - * @arg @ref LL_WWDG_PRESCALER_2 - * @arg @ref LL_WWDG_PRESCALER_4 - * @arg @ref LL_WWDG_PRESCALER_8 - */ -__STATIC_INLINE uint32_t LL_WWDG_GetPrescaler(WWDG_TypeDef *WWDGx) -{ - return (READ_BIT(WWDGx->CFR, WWDG_CFR_WDGTB)); -} - -/** - * @brief Set the Watchdog Window value to be compared to the downcounter (7-bits W[6:0]). - * @note This window value defines when write in the WWDG_CR register - * to program Watchdog counter is allowed. - * Watchdog counter value update must occur only when the counter value - * is lower than the Watchdog window register value. - * Otherwise, a MCU reset is generated if the 7-bit Watchdog counter value - * (in the control register) is refreshed before the downcounter has reached - * the watchdog window register value. - * Physically is possible to set the Window lower then 0x40 but it is not recommended. - * To generate an immediate reset, it is possible to set the Counter lower than 0x40. - * @rmtoll CFR W LL_WWDG_SetWindow - * @param WWDGx WWDG Instance - * @param Window 0x00..0x7F (7 bit Window value) - * @retval None - */ -__STATIC_INLINE void LL_WWDG_SetWindow(WWDG_TypeDef *WWDGx, uint32_t Window) -{ - MODIFY_REG(WWDGx->CFR, WWDG_CFR_W, Window); -} - -/** - * @brief Return current Watchdog Window Value (7 bits value) - * @rmtoll CFR W LL_WWDG_GetWindow - * @param WWDGx WWDG Instance - * @retval 7 bit Watchdog Window value - */ -__STATIC_INLINE uint32_t LL_WWDG_GetWindow(WWDG_TypeDef *WWDGx) -{ - return (READ_BIT(WWDGx->CFR, WWDG_CFR_W)); -} - -/** - * @} - */ - -/** @defgroup WWDG_LL_EF_FLAG_Management FLAG_Management - * @{ - */ -/** - * @brief Indicates if the WWDG Early Wakeup Interrupt Flag is set or not. - * @note This bit is set by hardware when the counter has reached the value 0x40. - * It must be cleared by software by writing 0. - * A write of 1 has no effect. This bit is also set if the interrupt is not enabled. - * @rmtoll SR EWIF LL_WWDG_IsActiveFlag_EWKUP - * @param WWDGx WWDG Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_WWDG_IsActiveFlag_EWKUP(WWDG_TypeDef *WWDGx) -{ - return ((READ_BIT(WWDGx->SR, WWDG_SR_EWIF) == (WWDG_SR_EWIF)) ? 1UL : 0UL); -} - -/** - * @brief Clear WWDG Early Wakeup Interrupt Flag (EWIF) - * @rmtoll SR EWIF LL_WWDG_ClearFlag_EWKUP - * @param WWDGx WWDG Instance - * @retval None - */ -__STATIC_INLINE void LL_WWDG_ClearFlag_EWKUP(WWDG_TypeDef *WWDGx) -{ - WRITE_REG(WWDGx->SR, ~WWDG_SR_EWIF); -} - -/** - * @} - */ - -/** @defgroup WWDG_LL_EF_IT_Management IT_Management - * @{ - */ -/** - * @brief Enable the Early Wakeup Interrupt. - * @note When set, an interrupt occurs whenever the counter reaches value 0x40. - * This interrupt is only cleared by hardware after a reset - * @rmtoll CFR EWI LL_WWDG_EnableIT_EWKUP - * @param WWDGx WWDG Instance - * @retval None - */ -__STATIC_INLINE void LL_WWDG_EnableIT_EWKUP(WWDG_TypeDef *WWDGx) -{ - SET_BIT(WWDGx->CFR, WWDG_CFR_EWI); -} - -/** - * @brief Check if Early Wakeup Interrupt is enabled - * @rmtoll CFR EWI LL_WWDG_IsEnabledIT_EWKUP - * @param WWDGx WWDG Instance - * @retval State of bit (1 or 0). - */ -__STATIC_INLINE uint32_t LL_WWDG_IsEnabledIT_EWKUP(WWDG_TypeDef *WWDGx) -{ - return ((READ_BIT(WWDGx->CFR, WWDG_CFR_EWI) == (WWDG_CFR_EWI)) ? 1UL : 0UL); -} - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#endif /* WWDG */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32F4xx_LL_WWDG_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/arm_common_tables.h b/body/board/inc/arm_common_tables.h deleted file mode 100644 index 8742a56..0000000 --- a/body/board/inc/arm_common_tables.h +++ /dev/null @@ -1,136 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010-2014 ARM Limited. All rights reserved. -* -* $Date: 19. October 2015 -* $Revision: V.1.4.5 a -* -* Project: CMSIS DSP Library -* Title: arm_common_tables.h -* -* Description: This file has extern declaration for common tables like Bitreverse, reciprocal etc which are used across different functions -* -* Target Processor: Cortex-M4/Cortex-M3 -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions -* are met: -* - Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* - Redistributions in binary form must reproduce the above copyright -* notice, this list of conditions and the following disclaimer in -* the documentation and/or other materials provided with the -* distribution. -* - Neither the name of ARM LIMITED nor the names of its contributors -* may be used to endorse or promote products derived from this -* software without specific prior written permission. -* -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER -* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -* POSSIBILITY OF SUCH DAMAGE. -* -------------------------------------------------------------------- */ - -#ifndef _ARM_COMMON_TABLES_H -#define _ARM_COMMON_TABLES_H - -#include "arm_math.h" - -extern const uint16_t armBitRevTable[1024]; -extern const q15_t armRecipTableQ15[64]; -extern const q31_t armRecipTableQ31[64]; -/* extern const q31_t realCoefAQ31[1024]; */ -/* extern const q31_t realCoefBQ31[1024]; */ -extern const float32_t twiddleCoef_16[32]; -extern const float32_t twiddleCoef_32[64]; -extern const float32_t twiddleCoef_64[128]; -extern const float32_t twiddleCoef_128[256]; -extern const float32_t twiddleCoef_256[512]; -extern const float32_t twiddleCoef_512[1024]; -extern const float32_t twiddleCoef_1024[2048]; -extern const float32_t twiddleCoef_2048[4096]; -extern const float32_t twiddleCoef_4096[8192]; -#define twiddleCoef twiddleCoef_4096 -extern const q31_t twiddleCoef_16_q31[24]; -extern const q31_t twiddleCoef_32_q31[48]; -extern const q31_t twiddleCoef_64_q31[96]; -extern const q31_t twiddleCoef_128_q31[192]; -extern const q31_t twiddleCoef_256_q31[384]; -extern const q31_t twiddleCoef_512_q31[768]; -extern const q31_t twiddleCoef_1024_q31[1536]; -extern const q31_t twiddleCoef_2048_q31[3072]; -extern const q31_t twiddleCoef_4096_q31[6144]; -extern const q15_t twiddleCoef_16_q15[24]; -extern const q15_t twiddleCoef_32_q15[48]; -extern const q15_t twiddleCoef_64_q15[96]; -extern const q15_t twiddleCoef_128_q15[192]; -extern const q15_t twiddleCoef_256_q15[384]; -extern const q15_t twiddleCoef_512_q15[768]; -extern const q15_t twiddleCoef_1024_q15[1536]; -extern const q15_t twiddleCoef_2048_q15[3072]; -extern const q15_t twiddleCoef_4096_q15[6144]; -extern const float32_t twiddleCoef_rfft_32[32]; -extern const float32_t twiddleCoef_rfft_64[64]; -extern const float32_t twiddleCoef_rfft_128[128]; -extern const float32_t twiddleCoef_rfft_256[256]; -extern const float32_t twiddleCoef_rfft_512[512]; -extern const float32_t twiddleCoef_rfft_1024[1024]; -extern const float32_t twiddleCoef_rfft_2048[2048]; -extern const float32_t twiddleCoef_rfft_4096[4096]; - - -/* floating-point bit reversal tables */ -#define ARMBITREVINDEXTABLE__16_TABLE_LENGTH ((uint16_t)20 ) -#define ARMBITREVINDEXTABLE__32_TABLE_LENGTH ((uint16_t)48 ) -#define ARMBITREVINDEXTABLE__64_TABLE_LENGTH ((uint16_t)56 ) -#define ARMBITREVINDEXTABLE_128_TABLE_LENGTH ((uint16_t)208 ) -#define ARMBITREVINDEXTABLE_256_TABLE_LENGTH ((uint16_t)440 ) -#define ARMBITREVINDEXTABLE_512_TABLE_LENGTH ((uint16_t)448 ) -#define ARMBITREVINDEXTABLE1024_TABLE_LENGTH ((uint16_t)1800) -#define ARMBITREVINDEXTABLE2048_TABLE_LENGTH ((uint16_t)3808) -#define ARMBITREVINDEXTABLE4096_TABLE_LENGTH ((uint16_t)4032) - -extern const uint16_t armBitRevIndexTable16[ARMBITREVINDEXTABLE__16_TABLE_LENGTH]; -extern const uint16_t armBitRevIndexTable32[ARMBITREVINDEXTABLE__32_TABLE_LENGTH]; -extern const uint16_t armBitRevIndexTable64[ARMBITREVINDEXTABLE__64_TABLE_LENGTH]; -extern const uint16_t armBitRevIndexTable128[ARMBITREVINDEXTABLE_128_TABLE_LENGTH]; -extern const uint16_t armBitRevIndexTable256[ARMBITREVINDEXTABLE_256_TABLE_LENGTH]; -extern const uint16_t armBitRevIndexTable512[ARMBITREVINDEXTABLE_512_TABLE_LENGTH]; -extern const uint16_t armBitRevIndexTable1024[ARMBITREVINDEXTABLE1024_TABLE_LENGTH]; -extern const uint16_t armBitRevIndexTable2048[ARMBITREVINDEXTABLE2048_TABLE_LENGTH]; -extern const uint16_t armBitRevIndexTable4096[ARMBITREVINDEXTABLE4096_TABLE_LENGTH]; - -/* fixed-point bit reversal tables */ -#define ARMBITREVINDEXTABLE_FIXED___16_TABLE_LENGTH ((uint16_t)12 ) -#define ARMBITREVINDEXTABLE_FIXED___32_TABLE_LENGTH ((uint16_t)24 ) -#define ARMBITREVINDEXTABLE_FIXED___64_TABLE_LENGTH ((uint16_t)56 ) -#define ARMBITREVINDEXTABLE_FIXED__128_TABLE_LENGTH ((uint16_t)112 ) -#define ARMBITREVINDEXTABLE_FIXED__256_TABLE_LENGTH ((uint16_t)240 ) -#define ARMBITREVINDEXTABLE_FIXED__512_TABLE_LENGTH ((uint16_t)480 ) -#define ARMBITREVINDEXTABLE_FIXED_1024_TABLE_LENGTH ((uint16_t)992 ) -#define ARMBITREVINDEXTABLE_FIXED_2048_TABLE_LENGTH ((uint16_t)1984) -#define ARMBITREVINDEXTABLE_FIXED_4096_TABLE_LENGTH ((uint16_t)4032) - -extern const uint16_t armBitRevIndexTable_fixed_16[ARMBITREVINDEXTABLE_FIXED___16_TABLE_LENGTH]; -extern const uint16_t armBitRevIndexTable_fixed_32[ARMBITREVINDEXTABLE_FIXED___32_TABLE_LENGTH]; -extern const uint16_t armBitRevIndexTable_fixed_64[ARMBITREVINDEXTABLE_FIXED___64_TABLE_LENGTH]; -extern const uint16_t armBitRevIndexTable_fixed_128[ARMBITREVINDEXTABLE_FIXED__128_TABLE_LENGTH]; -extern const uint16_t armBitRevIndexTable_fixed_256[ARMBITREVINDEXTABLE_FIXED__256_TABLE_LENGTH]; -extern const uint16_t armBitRevIndexTable_fixed_512[ARMBITREVINDEXTABLE_FIXED__512_TABLE_LENGTH]; -extern const uint16_t armBitRevIndexTable_fixed_1024[ARMBITREVINDEXTABLE_FIXED_1024_TABLE_LENGTH]; -extern const uint16_t armBitRevIndexTable_fixed_2048[ARMBITREVINDEXTABLE_FIXED_2048_TABLE_LENGTH]; -extern const uint16_t armBitRevIndexTable_fixed_4096[ARMBITREVINDEXTABLE_FIXED_4096_TABLE_LENGTH]; - -/* Tables for Fast Math Sine and Cosine */ -extern const float32_t sinTable_f32[FAST_MATH_TABLE_SIZE + 1]; -extern const q31_t sinTable_q31[FAST_MATH_TABLE_SIZE + 1]; -extern const q15_t sinTable_q15[FAST_MATH_TABLE_SIZE + 1]; - -#endif /* ARM_COMMON_TABLES_H */ diff --git a/body/board/inc/arm_const_structs.h b/body/board/inc/arm_const_structs.h deleted file mode 100644 index 726d06e..0000000 --- a/body/board/inc/arm_const_structs.h +++ /dev/null @@ -1,79 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010-2014 ARM Limited. All rights reserved. -* -* $Date: 19. March 2015 -* $Revision: V.1.4.5 -* -* Project: CMSIS DSP Library -* Title: arm_const_structs.h -* -* Description: This file has constant structs that are initialized for -* user convenience. For example, some can be given as -* arguments to the arm_cfft_f32() function. -* -* Target Processor: Cortex-M4/Cortex-M3 -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions -* are met: -* - Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* - Redistributions in binary form must reproduce the above copyright -* notice, this list of conditions and the following disclaimer in -* the documentation and/or other materials provided with the -* distribution. -* - Neither the name of ARM LIMITED nor the names of its contributors -* may be used to endorse or promote products derived from this -* software without specific prior written permission. -* -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER -* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -* POSSIBILITY OF SUCH DAMAGE. -* -------------------------------------------------------------------- */ - -#ifndef _ARM_CONST_STRUCTS_H -#define _ARM_CONST_STRUCTS_H - -#include "arm_math.h" -#include "arm_common_tables.h" - - extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len16; - extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len32; - extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len64; - extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len128; - extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len256; - extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len512; - extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len1024; - extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len2048; - extern const arm_cfft_instance_f32 arm_cfft_sR_f32_len4096; - - extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len16; - extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len32; - extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len64; - extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len128; - extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len256; - extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len512; - extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len1024; - extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len2048; - extern const arm_cfft_instance_q31 arm_cfft_sR_q31_len4096; - - extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len16; - extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len32; - extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len64; - extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len128; - extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len256; - extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len512; - extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len1024; - extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len2048; - extern const arm_cfft_instance_q15 arm_cfft_sR_q15_len4096; - -#endif diff --git a/body/board/inc/arm_math.h b/body/board/inc/arm_math.h deleted file mode 100644 index d33f8a9..0000000 --- a/body/board/inc/arm_math.h +++ /dev/null @@ -1,7154 +0,0 @@ -/* ---------------------------------------------------------------------- -* Copyright (C) 2010-2015 ARM Limited. All rights reserved. -* -* $Date: 20. October 2015 -* $Revision: V1.4.5 b -* -* Project: CMSIS DSP Library -* Title: arm_math.h -* -* Description: Public header file for CMSIS DSP Library -* -* Target Processor: Cortex-M7/Cortex-M4/Cortex-M3/Cortex-M0 -* -* Redistribution and use in source and binary forms, with or without -* modification, are permitted provided that the following conditions -* are met: -* - Redistributions of source code must retain the above copyright -* notice, this list of conditions and the following disclaimer. -* - Redistributions in binary form must reproduce the above copyright -* notice, this list of conditions and the following disclaimer in -* the documentation and/or other materials provided with the -* distribution. -* - Neither the name of ARM LIMITED nor the names of its contributors -* may be used to endorse or promote products derived from this -* software without specific prior written permission. -* -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER -* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -* POSSIBILITY OF SUCH DAMAGE. - * -------------------------------------------------------------------- */ - -/** - \mainpage CMSIS DSP Software Library - * - * Introduction - * ------------ - * - * This user manual describes the CMSIS DSP software library, - * a suite of common signal processing functions for use on Cortex-M processor based devices. - * - * The library is divided into a number of functions each covering a specific category: - * - Basic math functions - * - Fast math functions - * - Complex math functions - * - Filters - * - Matrix functions - * - Transforms - * - Motor control functions - * - Statistical functions - * - Support functions - * - Interpolation functions - * - * The library has separate functions for operating on 8-bit integers, 16-bit integers, - * 32-bit integer and 32-bit floating-point values. - * - * Using the Library - * ------------ - * - * The library installer contains prebuilt versions of the libraries in the Lib folder. - * - arm_cortexM7lfdp_math.lib (Little endian and Double Precision Floating Point Unit on Cortex-M7) - * - arm_cortexM7bfdp_math.lib (Big endian and Double Precision Floating Point Unit on Cortex-M7) - * - arm_cortexM7lfsp_math.lib (Little endian and Single Precision Floating Point Unit on Cortex-M7) - * - arm_cortexM7bfsp_math.lib (Big endian and Single Precision Floating Point Unit on Cortex-M7) - * - arm_cortexM7l_math.lib (Little endian on Cortex-M7) - * - arm_cortexM7b_math.lib (Big endian on Cortex-M7) - * - arm_cortexM4lf_math.lib (Little endian and Floating Point Unit on Cortex-M4) - * - arm_cortexM4bf_math.lib (Big endian and Floating Point Unit on Cortex-M4) - * - arm_cortexM4l_math.lib (Little endian on Cortex-M4) - * - arm_cortexM4b_math.lib (Big endian on Cortex-M4) - * - arm_cortexM3l_math.lib (Little endian on Cortex-M3) - * - arm_cortexM3b_math.lib (Big endian on Cortex-M3) - * - arm_cortexM0l_math.lib (Little endian on Cortex-M0 / CortexM0+) - * - arm_cortexM0b_math.lib (Big endian on Cortex-M0 / CortexM0+) - * - * The library functions are declared in the public file arm_math.h which is placed in the Include folder. - * Simply include this file and link the appropriate library in the application and begin calling the library functions. The Library supports single - * public header file arm_math.h for Cortex-M7/M4/M3/M0/M0+ with little endian and big endian. Same header file will be used for floating point unit(FPU) variants. - * Define the appropriate pre processor MACRO ARM_MATH_CM7 or ARM_MATH_CM4 or ARM_MATH_CM3 or - * ARM_MATH_CM0 or ARM_MATH_CM0PLUS depending on the target processor in the application. - * - * Examples - * -------- - * - * The library ships with a number of examples which demonstrate how to use the library functions. - * - * Toolchain Support - * ------------ - * - * The library has been developed and tested with MDK-ARM version 5.14.0.0 - * The library is being tested in GCC and IAR toolchains and updates on this activity will be made available shortly. - * - * Building the Library - * ------------ - * - * The library installer contains a project file to re build libraries on MDK-ARM Tool chain in the CMSIS\\DSP_Lib\\Source\\ARM folder. - * - arm_cortexM_math.uvprojx - * - * - * The libraries can be built by opening the arm_cortexM_math.uvprojx project in MDK-ARM, selecting a specific target, and defining the optional pre processor MACROs detailed above. - * - * Pre-processor Macros - * ------------ - * - * Each library project have differant pre-processor macros. - * - * - UNALIGNED_SUPPORT_DISABLE: - * - * Define macro UNALIGNED_SUPPORT_DISABLE, If the silicon does not support unaligned memory access - * - * - ARM_MATH_BIG_ENDIAN: - * - * Define macro ARM_MATH_BIG_ENDIAN to build the library for big endian targets. By default library builds for little endian targets. - * - * - ARM_MATH_MATRIX_CHECK: - * - * Define macro ARM_MATH_MATRIX_CHECK for checking on the input and output sizes of matrices - * - * - ARM_MATH_ROUNDING: - * - * Define macro ARM_MATH_ROUNDING for rounding on support functions - * - * - ARM_MATH_CMx: - * - * Define macro ARM_MATH_CM4 for building the library on Cortex-M4 target, ARM_MATH_CM3 for building library on Cortex-M3 target - * and ARM_MATH_CM0 for building library on Cortex-M0 target, ARM_MATH_CM0PLUS for building library on Cortex-M0+ target, and - * ARM_MATH_CM7 for building the library on cortex-M7. - * - * - __FPU_PRESENT: - * - * Initialize macro __FPU_PRESENT = 1 when building on FPU supported Targets. Enable this macro for M4bf and M4lf libraries - * - *
- * CMSIS-DSP in ARM::CMSIS Pack - * ----------------------------- - * - * The following files relevant to CMSIS-DSP are present in the ARM::CMSIS Pack directories: - * |File/Folder |Content | - * |------------------------------|------------------------------------------------------------------------| - * |\b CMSIS\\Documentation\\DSP | This documentation | - * |\b CMSIS\\DSP_Lib | Software license agreement (license.txt) | - * |\b CMSIS\\DSP_Lib\\Examples | Example projects demonstrating the usage of the library functions | - * |\b CMSIS\\DSP_Lib\\Source | Source files for rebuilding the library | - * - *
- * Revision History of CMSIS-DSP - * ------------ - * Please refer to \ref ChangeLog_pg. - * - * Copyright Notice - * ------------ - * - * Copyright (C) 2010-2015 ARM Limited. All rights reserved. - */ - - -/** - * @defgroup groupMath Basic Math Functions - */ - -/** - * @defgroup groupFastMath Fast Math Functions - * This set of functions provides a fast approximation to sine, cosine, and square root. - * As compared to most of the other functions in the CMSIS math library, the fast math functions - * operate on individual values and not arrays. - * There are separate functions for Q15, Q31, and floating-point data. - * - */ - -/** - * @defgroup groupCmplxMath Complex Math Functions - * This set of functions operates on complex data vectors. - * The data in the complex arrays is stored in an interleaved fashion - * (real, imag, real, imag, ...). - * In the API functions, the number of samples in a complex array refers - * to the number of complex values; the array contains twice this number of - * real values. - */ - -/** - * @defgroup groupFilters Filtering Functions - */ - -/** - * @defgroup groupMatrix Matrix Functions - * - * This set of functions provides basic matrix math operations. - * The functions operate on matrix data structures. For example, - * the type - * definition for the floating-point matrix structure is shown - * below: - *
- *     typedef struct
- *     {
- *       uint16_t numRows;     // number of rows of the matrix.
- *       uint16_t numCols;     // number of columns of the matrix.
- *       float32_t *pData;     // points to the data of the matrix.
- *     } arm_matrix_instance_f32;
- * 
- * There are similar definitions for Q15 and Q31 data types. - * - * The structure specifies the size of the matrix and then points to - * an array of data. The array is of size numRows X numCols - * and the values are arranged in row order. That is, the - * matrix element (i, j) is stored at: - *
- *     pData[i*numCols + j]
- * 
- * - * \par Init Functions - * There is an associated initialization function for each type of matrix - * data structure. - * The initialization function sets the values of the internal structure fields. - * Refer to the function arm_mat_init_f32(), arm_mat_init_q31() - * and arm_mat_init_q15() for floating-point, Q31 and Q15 types, respectively. - * - * \par - * Use of the initialization function is optional. However, if initialization function is used - * then the instance structure cannot be placed into a const data section. - * To place the instance structure in a const data - * section, manually initialize the data structure. For example: - *
- * arm_matrix_instance_f32 S = {nRows, nColumns, pData};
- * arm_matrix_instance_q31 S = {nRows, nColumns, pData};
- * arm_matrix_instance_q15 S = {nRows, nColumns, pData};
- * 
- * where nRows specifies the number of rows, nColumns - * specifies the number of columns, and pData points to the - * data array. - * - * \par Size Checking - * By default all of the matrix functions perform size checking on the input and - * output matrices. For example, the matrix addition function verifies that the - * two input matrices and the output matrix all have the same number of rows and - * columns. If the size check fails the functions return: - *
- *     ARM_MATH_SIZE_MISMATCH
- * 
- * Otherwise the functions return - *
- *     ARM_MATH_SUCCESS
- * 
- * There is some overhead associated with this matrix size checking. - * The matrix size checking is enabled via the \#define - *
- *     ARM_MATH_MATRIX_CHECK
- * 
- * within the library project settings. By default this macro is defined - * and size checking is enabled. By changing the project settings and - * undefining this macro size checking is eliminated and the functions - * run a bit faster. With size checking disabled the functions always - * return ARM_MATH_SUCCESS. - */ - -/** - * @defgroup groupTransforms Transform Functions - */ - -/** - * @defgroup groupController Controller Functions - */ - -/** - * @defgroup groupStats Statistics Functions - */ -/** - * @defgroup groupSupport Support Functions - */ - -/** - * @defgroup groupInterpolation Interpolation Functions - * These functions perform 1- and 2-dimensional interpolation of data. - * Linear interpolation is used for 1-dimensional data and - * bilinear interpolation is used for 2-dimensional data. - */ - -/** - * @defgroup groupExamples Examples - */ -#ifndef _ARM_MATH_H -#define _ARM_MATH_H - -/* ignore some GCC warnings */ -#if defined ( __GNUC__ ) -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wsign-conversion" -#pragma GCC diagnostic ignored "-Wconversion" -#pragma GCC diagnostic ignored "-Wunused-parameter" -#endif - -#define __CMSIS_GENERIC /* disable NVIC and Systick functions */ - -#if defined(ARM_MATH_CM7) - #include "core_cm7.h" -#elif defined (ARM_MATH_CM4) - #include "core_cm4.h" -#elif defined (ARM_MATH_CM3) - #include "core_cm3.h" -#elif defined (ARM_MATH_CM0) - #include "core_cm0.h" - #define ARM_MATH_CM0_FAMILY -#elif defined (ARM_MATH_CM0PLUS) - #include "core_cm0plus.h" - #define ARM_MATH_CM0_FAMILY -#else - #error "Define according the used Cortex core ARM_MATH_CM7, ARM_MATH_CM4, ARM_MATH_CM3, ARM_MATH_CM0PLUS or ARM_MATH_CM0" -#endif - -#undef __CMSIS_GENERIC /* enable NVIC and Systick functions */ -#include "string.h" -#include "math.h" -#ifdef __cplusplus -extern "C" -{ -#endif - - - /** - * @brief Macros required for reciprocal calculation in Normalized LMS - */ - -#define DELTA_Q31 (0x100) -#define DELTA_Q15 0x5 -#define INDEX_MASK 0x0000003F -#ifndef PI -#define PI 3.14159265358979f -#endif - - /** - * @brief Macros required for SINE and COSINE Fast math approximations - */ - -#define FAST_MATH_TABLE_SIZE 512 -#define FAST_MATH_Q31_SHIFT (32 - 10) -#define FAST_MATH_Q15_SHIFT (16 - 10) -#define CONTROLLER_Q31_SHIFT (32 - 9) -#define TABLE_SIZE 256 -#define TABLE_SPACING_Q31 0x400000 -#define TABLE_SPACING_Q15 0x80 - - /** - * @brief Macros required for SINE and COSINE Controller functions - */ - /* 1.31(q31) Fixed value of 2/360 */ - /* -1 to +1 is divided into 360 values so total spacing is (2/360) */ -#define INPUT_SPACING 0xB60B61 - - /** - * @brief Macro for Unaligned Support - */ -#ifndef UNALIGNED_SUPPORT_DISABLE - #define ALIGN4 -#else - #if defined (__GNUC__) - #define ALIGN4 __attribute__((aligned(4))) - #else - #define ALIGN4 __align(4) - #endif -#endif /* #ifndef UNALIGNED_SUPPORT_DISABLE */ - - /** - * @brief Error status returned by some functions in the library. - */ - - typedef enum - { - ARM_MATH_SUCCESS = 0, /**< No error */ - ARM_MATH_ARGUMENT_ERROR = -1, /**< One or more arguments are incorrect */ - ARM_MATH_LENGTH_ERROR = -2, /**< Length of data buffer is incorrect */ - ARM_MATH_SIZE_MISMATCH = -3, /**< Size of matrices is not compatible with the operation. */ - ARM_MATH_NANINF = -4, /**< Not-a-number (NaN) or infinity is generated */ - ARM_MATH_SINGULAR = -5, /**< Generated by matrix inversion if the input matrix is singular and cannot be inverted. */ - ARM_MATH_TEST_FAILURE = -6 /**< Test Failed */ - } arm_status; - - /** - * @brief 8-bit fractional data type in 1.7 format. - */ - typedef int8_t q7_t; - - /** - * @brief 16-bit fractional data type in 1.15 format. - */ - typedef int16_t q15_t; - - /** - * @brief 32-bit fractional data type in 1.31 format. - */ - typedef int32_t q31_t; - - /** - * @brief 64-bit fractional data type in 1.63 format. - */ - typedef int64_t q63_t; - - /** - * @brief 32-bit floating-point type definition. - */ - typedef float float32_t; - - /** - * @brief 64-bit floating-point type definition. - */ - typedef double float64_t; - - /** - * @brief definition to read/write two 16 bit values. - */ -#if defined __CC_ARM - #define __SIMD32_TYPE int32_t __packed - #define CMSIS_UNUSED __attribute__((unused)) - -#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #define __SIMD32_TYPE int32_t - #define CMSIS_UNUSED __attribute__((unused)) - -#elif defined __GNUC__ - #define __SIMD32_TYPE int32_t - #define CMSIS_UNUSED __attribute__((unused)) - -#elif defined __ICCARM__ - #define __SIMD32_TYPE int32_t __packed - #define CMSIS_UNUSED - -#elif defined __CSMC__ - #define __SIMD32_TYPE int32_t - #define CMSIS_UNUSED - -#elif defined __TASKING__ - #define __SIMD32_TYPE __unaligned int32_t - #define CMSIS_UNUSED - -#else - #error Unknown compiler -#endif - -#define __SIMD32(addr) (*(__SIMD32_TYPE **) & (addr)) -#define __SIMD32_CONST(addr) ((__SIMD32_TYPE *)(addr)) -#define _SIMD32_OFFSET(addr) (*(__SIMD32_TYPE *) (addr)) -#define __SIMD64(addr) (*(int64_t **) & (addr)) - -#if defined (ARM_MATH_CM3) || defined (ARM_MATH_CM0_FAMILY) - /** - * @brief definition to pack two 16 bit values. - */ -#define __PKHBT(ARG1, ARG2, ARG3) ( (((int32_t)(ARG1) << 0) & (int32_t)0x0000FFFF) | \ - (((int32_t)(ARG2) << ARG3) & (int32_t)0xFFFF0000) ) -#define __PKHTB(ARG1, ARG2, ARG3) ( (((int32_t)(ARG1) << 0) & (int32_t)0xFFFF0000) | \ - (((int32_t)(ARG2) >> ARG3) & (int32_t)0x0000FFFF) ) - -#endif - - - /** - * @brief definition to pack four 8 bit values. - */ -#ifndef ARM_MATH_BIG_ENDIAN - -#define __PACKq7(v0,v1,v2,v3) ( (((int32_t)(v0) << 0) & (int32_t)0x000000FF) | \ - (((int32_t)(v1) << 8) & (int32_t)0x0000FF00) | \ - (((int32_t)(v2) << 16) & (int32_t)0x00FF0000) | \ - (((int32_t)(v3) << 24) & (int32_t)0xFF000000) ) -#else - -#define __PACKq7(v0,v1,v2,v3) ( (((int32_t)(v3) << 0) & (int32_t)0x000000FF) | \ - (((int32_t)(v2) << 8) & (int32_t)0x0000FF00) | \ - (((int32_t)(v1) << 16) & (int32_t)0x00FF0000) | \ - (((int32_t)(v0) << 24) & (int32_t)0xFF000000) ) - -#endif - - - /** - * @brief Clips Q63 to Q31 values. - */ - static __INLINE q31_t clip_q63_to_q31( - q63_t x) - { - return ((q31_t) (x >> 32) != ((q31_t) x >> 31)) ? - ((0x7FFFFFFF ^ ((q31_t) (x >> 63)))) : (q31_t) x; - } - - /** - * @brief Clips Q63 to Q15 values. - */ - static __INLINE q15_t clip_q63_to_q15( - q63_t x) - { - return ((q31_t) (x >> 32) != ((q31_t) x >> 31)) ? - ((0x7FFF ^ ((q15_t) (x >> 63)))) : (q15_t) (x >> 15); - } - - /** - * @brief Clips Q31 to Q7 values. - */ - static __INLINE q7_t clip_q31_to_q7( - q31_t x) - { - return ((q31_t) (x >> 24) != ((q31_t) x >> 23)) ? - ((0x7F ^ ((q7_t) (x >> 31)))) : (q7_t) x; - } - - /** - * @brief Clips Q31 to Q15 values. - */ - static __INLINE q15_t clip_q31_to_q15( - q31_t x) - { - return ((q31_t) (x >> 16) != ((q31_t) x >> 15)) ? - ((0x7FFF ^ ((q15_t) (x >> 31)))) : (q15_t) x; - } - - /** - * @brief Multiplies 32 X 64 and returns 32 bit result in 2.30 format. - */ - - static __INLINE q63_t mult32x64( - q63_t x, - q31_t y) - { - return ((((q63_t) (x & 0x00000000FFFFFFFF) * y) >> 32) + - (((q63_t) (x >> 32) * y))); - } - -/* - #if defined (ARM_MATH_CM0_FAMILY) && defined ( __CC_ARM ) - #define __CLZ __clz - #endif - */ -/* note: function can be removed when all toolchain support __CLZ for Cortex-M0 */ -#if defined (ARM_MATH_CM0_FAMILY) && ((defined (__ICCARM__)) ) - static __INLINE uint32_t __CLZ( - q31_t data); - - static __INLINE uint32_t __CLZ( - q31_t data) - { - uint32_t count = 0; - uint32_t mask = 0x80000000; - - while((data & mask) == 0) - { - count += 1u; - mask = mask >> 1u; - } - - return (count); - } -#endif - - /** - * @brief Function to Calculates 1/in (reciprocal) value of Q31 Data type. - */ - - static __INLINE uint32_t arm_recip_q31( - q31_t in, - q31_t * dst, - q31_t * pRecipTable) - { - q31_t out; - uint32_t tempVal; - uint32_t index, i; - uint32_t signBits; - - if(in > 0) - { - signBits = ((uint32_t) (__CLZ( in) - 1)); - } - else - { - signBits = ((uint32_t) (__CLZ(-in) - 1)); - } - - /* Convert input sample to 1.31 format */ - in = (in << signBits); - - /* calculation of index for initial approximated Val */ - index = (uint32_t)(in >> 24); - index = (index & INDEX_MASK); - - /* 1.31 with exp 1 */ - out = pRecipTable[index]; - - /* calculation of reciprocal value */ - /* running approximation for two iterations */ - for (i = 0u; i < 2u; i++) - { - tempVal = (uint32_t) (((q63_t) in * out) >> 31); - tempVal = 0x7FFFFFFFu - tempVal; - /* 1.31 with exp 1 */ - /* out = (q31_t) (((q63_t) out * tempVal) >> 30); */ - out = clip_q63_to_q31(((q63_t) out * tempVal) >> 30); - } - - /* write output */ - *dst = out; - - /* return num of signbits of out = 1/in value */ - return (signBits + 1u); - } - - - /** - * @brief Function to Calculates 1/in (reciprocal) value of Q15 Data type. - */ - static __INLINE uint32_t arm_recip_q15( - q15_t in, - q15_t * dst, - q15_t * pRecipTable) - { - q15_t out = 0; - uint32_t tempVal = 0; - uint32_t index = 0, i = 0; - uint32_t signBits = 0; - - if(in > 0) - { - signBits = ((uint32_t)(__CLZ( in) - 17)); - } - else - { - signBits = ((uint32_t)(__CLZ(-in) - 17)); - } - - /* Convert input sample to 1.15 format */ - in = (in << signBits); - - /* calculation of index for initial approximated Val */ - index = (uint32_t)(in >> 8); - index = (index & INDEX_MASK); - - /* 1.15 with exp 1 */ - out = pRecipTable[index]; - - /* calculation of reciprocal value */ - /* running approximation for two iterations */ - for (i = 0u; i < 2u; i++) - { - tempVal = (uint32_t) (((q31_t) in * out) >> 15); - tempVal = 0x7FFFu - tempVal; - /* 1.15 with exp 1 */ - out = (q15_t) (((q31_t) out * tempVal) >> 14); - /* out = clip_q31_to_q15(((q31_t) out * tempVal) >> 14); */ - } - - /* write output */ - *dst = out; - - /* return num of signbits of out = 1/in value */ - return (signBits + 1); - } - - - /* - * @brief C custom defined intrinisic function for only M0 processors - */ -#if defined(ARM_MATH_CM0_FAMILY) - static __INLINE q31_t __SSAT( - q31_t x, - uint32_t y) - { - int32_t posMax, negMin; - uint32_t i; - - posMax = 1; - for (i = 0; i < (y - 1); i++) - { - posMax = posMax * 2; - } - - if(x > 0) - { - posMax = (posMax - 1); - - if(x > posMax) - { - x = posMax; - } - } - else - { - negMin = -posMax; - - if(x < negMin) - { - x = negMin; - } - } - return (x); - } -#endif /* end of ARM_MATH_CM0_FAMILY */ - - - /* - * @brief C custom defined intrinsic function for M3 and M0 processors - */ -#if defined (ARM_MATH_CM3) || defined (ARM_MATH_CM0_FAMILY) - - /* - * @brief C custom defined QADD8 for M3 and M0 processors - */ - static __INLINE uint32_t __QADD8( - uint32_t x, - uint32_t y) - { - q31_t r, s, t, u; - - r = __SSAT(((((q31_t)x << 24) >> 24) + (((q31_t)y << 24) >> 24)), 8) & (int32_t)0x000000FF; - s = __SSAT(((((q31_t)x << 16) >> 24) + (((q31_t)y << 16) >> 24)), 8) & (int32_t)0x000000FF; - t = __SSAT(((((q31_t)x << 8) >> 24) + (((q31_t)y << 8) >> 24)), 8) & (int32_t)0x000000FF; - u = __SSAT(((((q31_t)x ) >> 24) + (((q31_t)y ) >> 24)), 8) & (int32_t)0x000000FF; - - return ((uint32_t)((u << 24) | (t << 16) | (s << 8) | (r ))); - } - - - /* - * @brief C custom defined QSUB8 for M3 and M0 processors - */ - static __INLINE uint32_t __QSUB8( - uint32_t x, - uint32_t y) - { - q31_t r, s, t, u; - - r = __SSAT(((((q31_t)x << 24) >> 24) - (((q31_t)y << 24) >> 24)), 8) & (int32_t)0x000000FF; - s = __SSAT(((((q31_t)x << 16) >> 24) - (((q31_t)y << 16) >> 24)), 8) & (int32_t)0x000000FF; - t = __SSAT(((((q31_t)x << 8) >> 24) - (((q31_t)y << 8) >> 24)), 8) & (int32_t)0x000000FF; - u = __SSAT(((((q31_t)x ) >> 24) - (((q31_t)y ) >> 24)), 8) & (int32_t)0x000000FF; - - return ((uint32_t)((u << 24) | (t << 16) | (s << 8) | (r ))); - } - - - /* - * @brief C custom defined QADD16 for M3 and M0 processors - */ - static __INLINE uint32_t __QADD16( - uint32_t x, - uint32_t y) - { -/* q31_t r, s; without initialisation 'arm_offset_q15 test' fails but 'intrinsic' tests pass! for armCC */ - q31_t r = 0, s = 0; - - r = __SSAT(((((q31_t)x << 16) >> 16) + (((q31_t)y << 16) >> 16)), 16) & (int32_t)0x0000FFFF; - s = __SSAT(((((q31_t)x ) >> 16) + (((q31_t)y ) >> 16)), 16) & (int32_t)0x0000FFFF; - - return ((uint32_t)((s << 16) | (r ))); - } - - - /* - * @brief C custom defined SHADD16 for M3 and M0 processors - */ - static __INLINE uint32_t __SHADD16( - uint32_t x, - uint32_t y) - { - q31_t r, s; - - r = (((((q31_t)x << 16) >> 16) + (((q31_t)y << 16) >> 16)) >> 1) & (int32_t)0x0000FFFF; - s = (((((q31_t)x ) >> 16) + (((q31_t)y ) >> 16)) >> 1) & (int32_t)0x0000FFFF; - - return ((uint32_t)((s << 16) | (r ))); - } - - - /* - * @brief C custom defined QSUB16 for M3 and M0 processors - */ - static __INLINE uint32_t __QSUB16( - uint32_t x, - uint32_t y) - { - q31_t r, s; - - r = __SSAT(((((q31_t)x << 16) >> 16) - (((q31_t)y << 16) >> 16)), 16) & (int32_t)0x0000FFFF; - s = __SSAT(((((q31_t)x ) >> 16) - (((q31_t)y ) >> 16)), 16) & (int32_t)0x0000FFFF; - - return ((uint32_t)((s << 16) | (r ))); - } - - - /* - * @brief C custom defined SHSUB16 for M3 and M0 processors - */ - static __INLINE uint32_t __SHSUB16( - uint32_t x, - uint32_t y) - { - q31_t r, s; - - r = (((((q31_t)x << 16) >> 16) - (((q31_t)y << 16) >> 16)) >> 1) & (int32_t)0x0000FFFF; - s = (((((q31_t)x ) >> 16) - (((q31_t)y ) >> 16)) >> 1) & (int32_t)0x0000FFFF; - - return ((uint32_t)((s << 16) | (r ))); - } - - - /* - * @brief C custom defined QASX for M3 and M0 processors - */ - static __INLINE uint32_t __QASX( - uint32_t x, - uint32_t y) - { - q31_t r, s; - - r = __SSAT(((((q31_t)x << 16) >> 16) - (((q31_t)y ) >> 16)), 16) & (int32_t)0x0000FFFF; - s = __SSAT(((((q31_t)x ) >> 16) + (((q31_t)y << 16) >> 16)), 16) & (int32_t)0x0000FFFF; - - return ((uint32_t)((s << 16) | (r ))); - } - - - /* - * @brief C custom defined SHASX for M3 and M0 processors - */ - static __INLINE uint32_t __SHASX( - uint32_t x, - uint32_t y) - { - q31_t r, s; - - r = (((((q31_t)x << 16) >> 16) - (((q31_t)y ) >> 16)) >> 1) & (int32_t)0x0000FFFF; - s = (((((q31_t)x ) >> 16) + (((q31_t)y << 16) >> 16)) >> 1) & (int32_t)0x0000FFFF; - - return ((uint32_t)((s << 16) | (r ))); - } - - - /* - * @brief C custom defined QSAX for M3 and M0 processors - */ - static __INLINE uint32_t __QSAX( - uint32_t x, - uint32_t y) - { - q31_t r, s; - - r = __SSAT(((((q31_t)x << 16) >> 16) + (((q31_t)y ) >> 16)), 16) & (int32_t)0x0000FFFF; - s = __SSAT(((((q31_t)x ) >> 16) - (((q31_t)y << 16) >> 16)), 16) & (int32_t)0x0000FFFF; - - return ((uint32_t)((s << 16) | (r ))); - } - - - /* - * @brief C custom defined SHSAX for M3 and M0 processors - */ - static __INLINE uint32_t __SHSAX( - uint32_t x, - uint32_t y) - { - q31_t r, s; - - r = (((((q31_t)x << 16) >> 16) + (((q31_t)y ) >> 16)) >> 1) & (int32_t)0x0000FFFF; - s = (((((q31_t)x ) >> 16) - (((q31_t)y << 16) >> 16)) >> 1) & (int32_t)0x0000FFFF; - - return ((uint32_t)((s << 16) | (r ))); - } - - - /* - * @brief C custom defined SMUSDX for M3 and M0 processors - */ - static __INLINE uint32_t __SMUSDX( - uint32_t x, - uint32_t y) - { - return ((uint32_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y ) >> 16)) - - ((((q31_t)x ) >> 16) * (((q31_t)y << 16) >> 16)) )); - } - - /* - * @brief C custom defined SMUADX for M3 and M0 processors - */ - static __INLINE uint32_t __SMUADX( - uint32_t x, - uint32_t y) - { - return ((uint32_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y ) >> 16)) + - ((((q31_t)x ) >> 16) * (((q31_t)y << 16) >> 16)) )); - } - - - /* - * @brief C custom defined QADD for M3 and M0 processors - */ - static __INLINE int32_t __QADD( - int32_t x, - int32_t y) - { - return ((int32_t)(clip_q63_to_q31((q63_t)x + (q31_t)y))); - } - - - /* - * @brief C custom defined QSUB for M3 and M0 processors - */ - static __INLINE int32_t __QSUB( - int32_t x, - int32_t y) - { - return ((int32_t)(clip_q63_to_q31((q63_t)x - (q31_t)y))); - } - - - /* - * @brief C custom defined SMLAD for M3 and M0 processors - */ - static __INLINE uint32_t __SMLAD( - uint32_t x, - uint32_t y, - uint32_t sum) - { - return ((uint32_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y << 16) >> 16)) + - ((((q31_t)x ) >> 16) * (((q31_t)y ) >> 16)) + - ( ((q31_t)sum ) ) )); - } - - - /* - * @brief C custom defined SMLADX for M3 and M0 processors - */ - static __INLINE uint32_t __SMLADX( - uint32_t x, - uint32_t y, - uint32_t sum) - { - return ((uint32_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y ) >> 16)) + - ((((q31_t)x ) >> 16) * (((q31_t)y << 16) >> 16)) + - ( ((q31_t)sum ) ) )); - } - - - /* - * @brief C custom defined SMLSDX for M3 and M0 processors - */ - static __INLINE uint32_t __SMLSDX( - uint32_t x, - uint32_t y, - uint32_t sum) - { - return ((uint32_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y ) >> 16)) - - ((((q31_t)x ) >> 16) * (((q31_t)y << 16) >> 16)) + - ( ((q31_t)sum ) ) )); - } - - - /* - * @brief C custom defined SMLALD for M3 and M0 processors - */ - static __INLINE uint64_t __SMLALD( - uint32_t x, - uint32_t y, - uint64_t sum) - { -/* return (sum + ((q15_t) (x >> 16) * (q15_t) (y >> 16)) + ((q15_t) x * (q15_t) y)); */ - return ((uint64_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y << 16) >> 16)) + - ((((q31_t)x ) >> 16) * (((q31_t)y ) >> 16)) + - ( ((q63_t)sum ) ) )); - } - - - /* - * @brief C custom defined SMLALDX for M3 and M0 processors - */ - static __INLINE uint64_t __SMLALDX( - uint32_t x, - uint32_t y, - uint64_t sum) - { -/* return (sum + ((q15_t) (x >> 16) * (q15_t) y)) + ((q15_t) x * (q15_t) (y >> 16)); */ - return ((uint64_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y ) >> 16)) + - ((((q31_t)x ) >> 16) * (((q31_t)y << 16) >> 16)) + - ( ((q63_t)sum ) ) )); - } - - - /* - * @brief C custom defined SMUAD for M3 and M0 processors - */ - static __INLINE uint32_t __SMUAD( - uint32_t x, - uint32_t y) - { - return ((uint32_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y << 16) >> 16)) + - ((((q31_t)x ) >> 16) * (((q31_t)y ) >> 16)) )); - } - - - /* - * @brief C custom defined SMUSD for M3 and M0 processors - */ - static __INLINE uint32_t __SMUSD( - uint32_t x, - uint32_t y) - { - return ((uint32_t)(((((q31_t)x << 16) >> 16) * (((q31_t)y << 16) >> 16)) - - ((((q31_t)x ) >> 16) * (((q31_t)y ) >> 16)) )); - } - - - /* - * @brief C custom defined SXTB16 for M3 and M0 processors - */ - static __INLINE uint32_t __SXTB16( - uint32_t x) - { - return ((uint32_t)(((((q31_t)x << 24) >> 24) & (q31_t)0x0000FFFF) | - ((((q31_t)x << 8) >> 8) & (q31_t)0xFFFF0000) )); - } - -#endif /* defined (ARM_MATH_CM3) || defined (ARM_MATH_CM0_FAMILY) */ - - - /** - * @brief Instance structure for the Q7 FIR filter. - */ - typedef struct - { - uint16_t numTaps; /**< number of filter coefficients in the filter. */ - q7_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ - q7_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ - } arm_fir_instance_q7; - - /** - * @brief Instance structure for the Q15 FIR filter. - */ - typedef struct - { - uint16_t numTaps; /**< number of filter coefficients in the filter. */ - q15_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ - q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ - } arm_fir_instance_q15; - - /** - * @brief Instance structure for the Q31 FIR filter. - */ - typedef struct - { - uint16_t numTaps; /**< number of filter coefficients in the filter. */ - q31_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ - q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */ - } arm_fir_instance_q31; - - /** - * @brief Instance structure for the floating-point FIR filter. - */ - typedef struct - { - uint16_t numTaps; /**< number of filter coefficients in the filter. */ - float32_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ - float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */ - } arm_fir_instance_f32; - - - /** - * @brief Processing function for the Q7 FIR filter. - * @param[in] S points to an instance of the Q7 FIR filter structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data. - * @param[in] blockSize number of samples to process. - */ - void arm_fir_q7( - const arm_fir_instance_q7 * S, - q7_t * pSrc, - q7_t * pDst, - uint32_t blockSize); - - - /** - * @brief Initialization function for the Q7 FIR filter. - * @param[in,out] S points to an instance of the Q7 FIR structure. - * @param[in] numTaps Number of filter coefficients in the filter. - * @param[in] pCoeffs points to the filter coefficients. - * @param[in] pState points to the state buffer. - * @param[in] blockSize number of samples that are processed. - */ - void arm_fir_init_q7( - arm_fir_instance_q7 * S, - uint16_t numTaps, - q7_t * pCoeffs, - q7_t * pState, - uint32_t blockSize); - - - /** - * @brief Processing function for the Q15 FIR filter. - * @param[in] S points to an instance of the Q15 FIR structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data. - * @param[in] blockSize number of samples to process. - */ - void arm_fir_q15( - const arm_fir_instance_q15 * S, - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize); - - - /** - * @brief Processing function for the fast Q15 FIR filter for Cortex-M3 and Cortex-M4. - * @param[in] S points to an instance of the Q15 FIR filter structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data. - * @param[in] blockSize number of samples to process. - */ - void arm_fir_fast_q15( - const arm_fir_instance_q15 * S, - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize); - - - /** - * @brief Initialization function for the Q15 FIR filter. - * @param[in,out] S points to an instance of the Q15 FIR filter structure. - * @param[in] numTaps Number of filter coefficients in the filter. Must be even and greater than or equal to 4. - * @param[in] pCoeffs points to the filter coefficients. - * @param[in] pState points to the state buffer. - * @param[in] blockSize number of samples that are processed at a time. - * @return The function returns ARM_MATH_SUCCESS if initialization was successful or ARM_MATH_ARGUMENT_ERROR if - * numTaps is not a supported value. - */ - arm_status arm_fir_init_q15( - arm_fir_instance_q15 * S, - uint16_t numTaps, - q15_t * pCoeffs, - q15_t * pState, - uint32_t blockSize); - - - /** - * @brief Processing function for the Q31 FIR filter. - * @param[in] S points to an instance of the Q31 FIR filter structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data. - * @param[in] blockSize number of samples to process. - */ - void arm_fir_q31( - const arm_fir_instance_q31 * S, - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize); - - - /** - * @brief Processing function for the fast Q31 FIR filter for Cortex-M3 and Cortex-M4. - * @param[in] S points to an instance of the Q31 FIR structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data. - * @param[in] blockSize number of samples to process. - */ - void arm_fir_fast_q31( - const arm_fir_instance_q31 * S, - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize); - - - /** - * @brief Initialization function for the Q31 FIR filter. - * @param[in,out] S points to an instance of the Q31 FIR structure. - * @param[in] numTaps Number of filter coefficients in the filter. - * @param[in] pCoeffs points to the filter coefficients. - * @param[in] pState points to the state buffer. - * @param[in] blockSize number of samples that are processed at a time. - */ - void arm_fir_init_q31( - arm_fir_instance_q31 * S, - uint16_t numTaps, - q31_t * pCoeffs, - q31_t * pState, - uint32_t blockSize); - - - /** - * @brief Processing function for the floating-point FIR filter. - * @param[in] S points to an instance of the floating-point FIR structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data. - * @param[in] blockSize number of samples to process. - */ - void arm_fir_f32( - const arm_fir_instance_f32 * S, - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize); - - - /** - * @brief Initialization function for the floating-point FIR filter. - * @param[in,out] S points to an instance of the floating-point FIR filter structure. - * @param[in] numTaps Number of filter coefficients in the filter. - * @param[in] pCoeffs points to the filter coefficients. - * @param[in] pState points to the state buffer. - * @param[in] blockSize number of samples that are processed at a time. - */ - void arm_fir_init_f32( - arm_fir_instance_f32 * S, - uint16_t numTaps, - float32_t * pCoeffs, - float32_t * pState, - uint32_t blockSize); - - - /** - * @brief Instance structure for the Q15 Biquad cascade filter. - */ - typedef struct - { - int8_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */ - q15_t *pState; /**< Points to the array of state coefficients. The array is of length 4*numStages. */ - q15_t *pCoeffs; /**< Points to the array of coefficients. The array is of length 5*numStages. */ - int8_t postShift; /**< Additional shift, in bits, applied to each output sample. */ - } arm_biquad_casd_df1_inst_q15; - - /** - * @brief Instance structure for the Q31 Biquad cascade filter. - */ - typedef struct - { - uint32_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */ - q31_t *pState; /**< Points to the array of state coefficients. The array is of length 4*numStages. */ - q31_t *pCoeffs; /**< Points to the array of coefficients. The array is of length 5*numStages. */ - uint8_t postShift; /**< Additional shift, in bits, applied to each output sample. */ - } arm_biquad_casd_df1_inst_q31; - - /** - * @brief Instance structure for the floating-point Biquad cascade filter. - */ - typedef struct - { - uint32_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */ - float32_t *pState; /**< Points to the array of state coefficients. The array is of length 4*numStages. */ - float32_t *pCoeffs; /**< Points to the array of coefficients. The array is of length 5*numStages. */ - } arm_biquad_casd_df1_inst_f32; - - - /** - * @brief Processing function for the Q15 Biquad cascade filter. - * @param[in] S points to an instance of the Q15 Biquad cascade structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data. - * @param[in] blockSize number of samples to process. - */ - void arm_biquad_cascade_df1_q15( - const arm_biquad_casd_df1_inst_q15 * S, - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize); - - - /** - * @brief Initialization function for the Q15 Biquad cascade filter. - * @param[in,out] S points to an instance of the Q15 Biquad cascade structure. - * @param[in] numStages number of 2nd order stages in the filter. - * @param[in] pCoeffs points to the filter coefficients. - * @param[in] pState points to the state buffer. - * @param[in] postShift Shift to be applied to the output. Varies according to the coefficients format - */ - void arm_biquad_cascade_df1_init_q15( - arm_biquad_casd_df1_inst_q15 * S, - uint8_t numStages, - q15_t * pCoeffs, - q15_t * pState, - int8_t postShift); - - - /** - * @brief Fast but less precise processing function for the Q15 Biquad cascade filter for Cortex-M3 and Cortex-M4. - * @param[in] S points to an instance of the Q15 Biquad cascade structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data. - * @param[in] blockSize number of samples to process. - */ - void arm_biquad_cascade_df1_fast_q15( - const arm_biquad_casd_df1_inst_q15 * S, - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize); - - - /** - * @brief Processing function for the Q31 Biquad cascade filter - * @param[in] S points to an instance of the Q31 Biquad cascade structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data. - * @param[in] blockSize number of samples to process. - */ - void arm_biquad_cascade_df1_q31( - const arm_biquad_casd_df1_inst_q31 * S, - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize); - - - /** - * @brief Fast but less precise processing function for the Q31 Biquad cascade filter for Cortex-M3 and Cortex-M4. - * @param[in] S points to an instance of the Q31 Biquad cascade structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data. - * @param[in] blockSize number of samples to process. - */ - void arm_biquad_cascade_df1_fast_q31( - const arm_biquad_casd_df1_inst_q31 * S, - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize); - - - /** - * @brief Initialization function for the Q31 Biquad cascade filter. - * @param[in,out] S points to an instance of the Q31 Biquad cascade structure. - * @param[in] numStages number of 2nd order stages in the filter. - * @param[in] pCoeffs points to the filter coefficients. - * @param[in] pState points to the state buffer. - * @param[in] postShift Shift to be applied to the output. Varies according to the coefficients format - */ - void arm_biquad_cascade_df1_init_q31( - arm_biquad_casd_df1_inst_q31 * S, - uint8_t numStages, - q31_t * pCoeffs, - q31_t * pState, - int8_t postShift); - - - /** - * @brief Processing function for the floating-point Biquad cascade filter. - * @param[in] S points to an instance of the floating-point Biquad cascade structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data. - * @param[in] blockSize number of samples to process. - */ - void arm_biquad_cascade_df1_f32( - const arm_biquad_casd_df1_inst_f32 * S, - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize); - - - /** - * @brief Initialization function for the floating-point Biquad cascade filter. - * @param[in,out] S points to an instance of the floating-point Biquad cascade structure. - * @param[in] numStages number of 2nd order stages in the filter. - * @param[in] pCoeffs points to the filter coefficients. - * @param[in] pState points to the state buffer. - */ - void arm_biquad_cascade_df1_init_f32( - arm_biquad_casd_df1_inst_f32 * S, - uint8_t numStages, - float32_t * pCoeffs, - float32_t * pState); - - - /** - * @brief Instance structure for the floating-point matrix structure. - */ - typedef struct - { - uint16_t numRows; /**< number of rows of the matrix. */ - uint16_t numCols; /**< number of columns of the matrix. */ - float32_t *pData; /**< points to the data of the matrix. */ - } arm_matrix_instance_f32; - - - /** - * @brief Instance structure for the floating-point matrix structure. - */ - typedef struct - { - uint16_t numRows; /**< number of rows of the matrix. */ - uint16_t numCols; /**< number of columns of the matrix. */ - float64_t *pData; /**< points to the data of the matrix. */ - } arm_matrix_instance_f64; - - /** - * @brief Instance structure for the Q15 matrix structure. - */ - typedef struct - { - uint16_t numRows; /**< number of rows of the matrix. */ - uint16_t numCols; /**< number of columns of the matrix. */ - q15_t *pData; /**< points to the data of the matrix. */ - } arm_matrix_instance_q15; - - /** - * @brief Instance structure for the Q31 matrix structure. - */ - typedef struct - { - uint16_t numRows; /**< number of rows of the matrix. */ - uint16_t numCols; /**< number of columns of the matrix. */ - q31_t *pData; /**< points to the data of the matrix. */ - } arm_matrix_instance_q31; - - - /** - * @brief Floating-point matrix addition. - * @param[in] pSrcA points to the first input matrix structure - * @param[in] pSrcB points to the second input matrix structure - * @param[out] pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - arm_status arm_mat_add_f32( - const arm_matrix_instance_f32 * pSrcA, - const arm_matrix_instance_f32 * pSrcB, - arm_matrix_instance_f32 * pDst); - - - /** - * @brief Q15 matrix addition. - * @param[in] pSrcA points to the first input matrix structure - * @param[in] pSrcB points to the second input matrix structure - * @param[out] pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - arm_status arm_mat_add_q15( - const arm_matrix_instance_q15 * pSrcA, - const arm_matrix_instance_q15 * pSrcB, - arm_matrix_instance_q15 * pDst); - - - /** - * @brief Q31 matrix addition. - * @param[in] pSrcA points to the first input matrix structure - * @param[in] pSrcB points to the second input matrix structure - * @param[out] pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - arm_status arm_mat_add_q31( - const arm_matrix_instance_q31 * pSrcA, - const arm_matrix_instance_q31 * pSrcB, - arm_matrix_instance_q31 * pDst); - - - /** - * @brief Floating-point, complex, matrix multiplication. - * @param[in] pSrcA points to the first input matrix structure - * @param[in] pSrcB points to the second input matrix structure - * @param[out] pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - arm_status arm_mat_cmplx_mult_f32( - const arm_matrix_instance_f32 * pSrcA, - const arm_matrix_instance_f32 * pSrcB, - arm_matrix_instance_f32 * pDst); - - - /** - * @brief Q15, complex, matrix multiplication. - * @param[in] pSrcA points to the first input matrix structure - * @param[in] pSrcB points to the second input matrix structure - * @param[out] pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - arm_status arm_mat_cmplx_mult_q15( - const arm_matrix_instance_q15 * pSrcA, - const arm_matrix_instance_q15 * pSrcB, - arm_matrix_instance_q15 * pDst, - q15_t * pScratch); - - - /** - * @brief Q31, complex, matrix multiplication. - * @param[in] pSrcA points to the first input matrix structure - * @param[in] pSrcB points to the second input matrix structure - * @param[out] pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - arm_status arm_mat_cmplx_mult_q31( - const arm_matrix_instance_q31 * pSrcA, - const arm_matrix_instance_q31 * pSrcB, - arm_matrix_instance_q31 * pDst); - - - /** - * @brief Floating-point matrix transpose. - * @param[in] pSrc points to the input matrix - * @param[out] pDst points to the output matrix - * @return The function returns either ARM_MATH_SIZE_MISMATCH - * or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - arm_status arm_mat_trans_f32( - const arm_matrix_instance_f32 * pSrc, - arm_matrix_instance_f32 * pDst); - - - /** - * @brief Q15 matrix transpose. - * @param[in] pSrc points to the input matrix - * @param[out] pDst points to the output matrix - * @return The function returns either ARM_MATH_SIZE_MISMATCH - * or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - arm_status arm_mat_trans_q15( - const arm_matrix_instance_q15 * pSrc, - arm_matrix_instance_q15 * pDst); - - - /** - * @brief Q31 matrix transpose. - * @param[in] pSrc points to the input matrix - * @param[out] pDst points to the output matrix - * @return The function returns either ARM_MATH_SIZE_MISMATCH - * or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - arm_status arm_mat_trans_q31( - const arm_matrix_instance_q31 * pSrc, - arm_matrix_instance_q31 * pDst); - - - /** - * @brief Floating-point matrix multiplication - * @param[in] pSrcA points to the first input matrix structure - * @param[in] pSrcB points to the second input matrix structure - * @param[out] pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - arm_status arm_mat_mult_f32( - const arm_matrix_instance_f32 * pSrcA, - const arm_matrix_instance_f32 * pSrcB, - arm_matrix_instance_f32 * pDst); - - - /** - * @brief Q15 matrix multiplication - * @param[in] pSrcA points to the first input matrix structure - * @param[in] pSrcB points to the second input matrix structure - * @param[out] pDst points to output matrix structure - * @param[in] pState points to the array for storing intermediate results - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - arm_status arm_mat_mult_q15( - const arm_matrix_instance_q15 * pSrcA, - const arm_matrix_instance_q15 * pSrcB, - arm_matrix_instance_q15 * pDst, - q15_t * pState); - - - /** - * @brief Q15 matrix multiplication (fast variant) for Cortex-M3 and Cortex-M4 - * @param[in] pSrcA points to the first input matrix structure - * @param[in] pSrcB points to the second input matrix structure - * @param[out] pDst points to output matrix structure - * @param[in] pState points to the array for storing intermediate results - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - arm_status arm_mat_mult_fast_q15( - const arm_matrix_instance_q15 * pSrcA, - const arm_matrix_instance_q15 * pSrcB, - arm_matrix_instance_q15 * pDst, - q15_t * pState); - - - /** - * @brief Q31 matrix multiplication - * @param[in] pSrcA points to the first input matrix structure - * @param[in] pSrcB points to the second input matrix structure - * @param[out] pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - arm_status arm_mat_mult_q31( - const arm_matrix_instance_q31 * pSrcA, - const arm_matrix_instance_q31 * pSrcB, - arm_matrix_instance_q31 * pDst); - - - /** - * @brief Q31 matrix multiplication (fast variant) for Cortex-M3 and Cortex-M4 - * @param[in] pSrcA points to the first input matrix structure - * @param[in] pSrcB points to the second input matrix structure - * @param[out] pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - arm_status arm_mat_mult_fast_q31( - const arm_matrix_instance_q31 * pSrcA, - const arm_matrix_instance_q31 * pSrcB, - arm_matrix_instance_q31 * pDst); - - - /** - * @brief Floating-point matrix subtraction - * @param[in] pSrcA points to the first input matrix structure - * @param[in] pSrcB points to the second input matrix structure - * @param[out] pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - arm_status arm_mat_sub_f32( - const arm_matrix_instance_f32 * pSrcA, - const arm_matrix_instance_f32 * pSrcB, - arm_matrix_instance_f32 * pDst); - - - /** - * @brief Q15 matrix subtraction - * @param[in] pSrcA points to the first input matrix structure - * @param[in] pSrcB points to the second input matrix structure - * @param[out] pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - arm_status arm_mat_sub_q15( - const arm_matrix_instance_q15 * pSrcA, - const arm_matrix_instance_q15 * pSrcB, - arm_matrix_instance_q15 * pDst); - - - /** - * @brief Q31 matrix subtraction - * @param[in] pSrcA points to the first input matrix structure - * @param[in] pSrcB points to the second input matrix structure - * @param[out] pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - arm_status arm_mat_sub_q31( - const arm_matrix_instance_q31 * pSrcA, - const arm_matrix_instance_q31 * pSrcB, - arm_matrix_instance_q31 * pDst); - - - /** - * @brief Floating-point matrix scaling. - * @param[in] pSrc points to the input matrix - * @param[in] scale scale factor - * @param[out] pDst points to the output matrix - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - arm_status arm_mat_scale_f32( - const arm_matrix_instance_f32 * pSrc, - float32_t scale, - arm_matrix_instance_f32 * pDst); - - - /** - * @brief Q15 matrix scaling. - * @param[in] pSrc points to input matrix - * @param[in] scaleFract fractional portion of the scale factor - * @param[in] shift number of bits to shift the result by - * @param[out] pDst points to output matrix - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - arm_status arm_mat_scale_q15( - const arm_matrix_instance_q15 * pSrc, - q15_t scaleFract, - int32_t shift, - arm_matrix_instance_q15 * pDst); - - - /** - * @brief Q31 matrix scaling. - * @param[in] pSrc points to input matrix - * @param[in] scaleFract fractional portion of the scale factor - * @param[in] shift number of bits to shift the result by - * @param[out] pDst points to output matrix structure - * @return The function returns either - * ARM_MATH_SIZE_MISMATCH or ARM_MATH_SUCCESS based on the outcome of size checking. - */ - arm_status arm_mat_scale_q31( - const arm_matrix_instance_q31 * pSrc, - q31_t scaleFract, - int32_t shift, - arm_matrix_instance_q31 * pDst); - - - /** - * @brief Q31 matrix initialization. - * @param[in,out] S points to an instance of the floating-point matrix structure. - * @param[in] nRows number of rows in the matrix. - * @param[in] nColumns number of columns in the matrix. - * @param[in] pData points to the matrix data array. - */ - void arm_mat_init_q31( - arm_matrix_instance_q31 * S, - uint16_t nRows, - uint16_t nColumns, - q31_t * pData); - - - /** - * @brief Q15 matrix initialization. - * @param[in,out] S points to an instance of the floating-point matrix structure. - * @param[in] nRows number of rows in the matrix. - * @param[in] nColumns number of columns in the matrix. - * @param[in] pData points to the matrix data array. - */ - void arm_mat_init_q15( - arm_matrix_instance_q15 * S, - uint16_t nRows, - uint16_t nColumns, - q15_t * pData); - - - /** - * @brief Floating-point matrix initialization. - * @param[in,out] S points to an instance of the floating-point matrix structure. - * @param[in] nRows number of rows in the matrix. - * @param[in] nColumns number of columns in the matrix. - * @param[in] pData points to the matrix data array. - */ - void arm_mat_init_f32( - arm_matrix_instance_f32 * S, - uint16_t nRows, - uint16_t nColumns, - float32_t * pData); - - - - /** - * @brief Instance structure for the Q15 PID Control. - */ - typedef struct - { - q15_t A0; /**< The derived gain, A0 = Kp + Ki + Kd . */ -#ifdef ARM_MATH_CM0_FAMILY - q15_t A1; - q15_t A2; -#else - q31_t A1; /**< The derived gain A1 = -Kp - 2Kd | Kd.*/ -#endif - q15_t state[3]; /**< The state array of length 3. */ - q15_t Kp; /**< The proportional gain. */ - q15_t Ki; /**< The integral gain. */ - q15_t Kd; /**< The derivative gain. */ - } arm_pid_instance_q15; - - /** - * @brief Instance structure for the Q31 PID Control. - */ - typedef struct - { - q31_t A0; /**< The derived gain, A0 = Kp + Ki + Kd . */ - q31_t A1; /**< The derived gain, A1 = -Kp - 2Kd. */ - q31_t A2; /**< The derived gain, A2 = Kd . */ - q31_t state[3]; /**< The state array of length 3. */ - q31_t Kp; /**< The proportional gain. */ - q31_t Ki; /**< The integral gain. */ - q31_t Kd; /**< The derivative gain. */ - } arm_pid_instance_q31; - - /** - * @brief Instance structure for the floating-point PID Control. - */ - typedef struct - { - float32_t A0; /**< The derived gain, A0 = Kp + Ki + Kd . */ - float32_t A1; /**< The derived gain, A1 = -Kp - 2Kd. */ - float32_t A2; /**< The derived gain, A2 = Kd . */ - float32_t state[3]; /**< The state array of length 3. */ - float32_t Kp; /**< The proportional gain. */ - float32_t Ki; /**< The integral gain. */ - float32_t Kd; /**< The derivative gain. */ - } arm_pid_instance_f32; - - - - /** - * @brief Initialization function for the floating-point PID Control. - * @param[in,out] S points to an instance of the PID structure. - * @param[in] resetStateFlag flag to reset the state. 0 = no change in state 1 = reset the state. - */ - void arm_pid_init_f32( - arm_pid_instance_f32 * S, - int32_t resetStateFlag); - - - /** - * @brief Reset function for the floating-point PID Control. - * @param[in,out] S is an instance of the floating-point PID Control structure - */ - void arm_pid_reset_f32( - arm_pid_instance_f32 * S); - - - /** - * @brief Initialization function for the Q31 PID Control. - * @param[in,out] S points to an instance of the Q15 PID structure. - * @param[in] resetStateFlag flag to reset the state. 0 = no change in state 1 = reset the state. - */ - void arm_pid_init_q31( - arm_pid_instance_q31 * S, - int32_t resetStateFlag); - - - /** - * @brief Reset function for the Q31 PID Control. - * @param[in,out] S points to an instance of the Q31 PID Control structure - */ - - void arm_pid_reset_q31( - arm_pid_instance_q31 * S); - - - /** - * @brief Initialization function for the Q15 PID Control. - * @param[in,out] S points to an instance of the Q15 PID structure. - * @param[in] resetStateFlag flag to reset the state. 0 = no change in state 1 = reset the state. - */ - void arm_pid_init_q15( - arm_pid_instance_q15 * S, - int32_t resetStateFlag); - - - /** - * @brief Reset function for the Q15 PID Control. - * @param[in,out] S points to an instance of the q15 PID Control structure - */ - void arm_pid_reset_q15( - arm_pid_instance_q15 * S); - - - /** - * @brief Instance structure for the floating-point Linear Interpolate function. - */ - typedef struct - { - uint32_t nValues; /**< nValues */ - float32_t x1; /**< x1 */ - float32_t xSpacing; /**< xSpacing */ - float32_t *pYData; /**< pointer to the table of Y values */ - } arm_linear_interp_instance_f32; - - /** - * @brief Instance structure for the floating-point bilinear interpolation function. - */ - typedef struct - { - uint16_t numRows; /**< number of rows in the data table. */ - uint16_t numCols; /**< number of columns in the data table. */ - float32_t *pData; /**< points to the data table. */ - } arm_bilinear_interp_instance_f32; - - /** - * @brief Instance structure for the Q31 bilinear interpolation function. - */ - typedef struct - { - uint16_t numRows; /**< number of rows in the data table. */ - uint16_t numCols; /**< number of columns in the data table. */ - q31_t *pData; /**< points to the data table. */ - } arm_bilinear_interp_instance_q31; - - /** - * @brief Instance structure for the Q15 bilinear interpolation function. - */ - typedef struct - { - uint16_t numRows; /**< number of rows in the data table. */ - uint16_t numCols; /**< number of columns in the data table. */ - q15_t *pData; /**< points to the data table. */ - } arm_bilinear_interp_instance_q15; - - /** - * @brief Instance structure for the Q15 bilinear interpolation function. - */ - typedef struct - { - uint16_t numRows; /**< number of rows in the data table. */ - uint16_t numCols; /**< number of columns in the data table. */ - q7_t *pData; /**< points to the data table. */ - } arm_bilinear_interp_instance_q7; - - - /** - * @brief Q7 vector multiplication. - * @param[in] pSrcA points to the first input vector - * @param[in] pSrcB points to the second input vector - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in each vector - */ - void arm_mult_q7( - q7_t * pSrcA, - q7_t * pSrcB, - q7_t * pDst, - uint32_t blockSize); - - - /** - * @brief Q15 vector multiplication. - * @param[in] pSrcA points to the first input vector - * @param[in] pSrcB points to the second input vector - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in each vector - */ - void arm_mult_q15( - q15_t * pSrcA, - q15_t * pSrcB, - q15_t * pDst, - uint32_t blockSize); - - - /** - * @brief Q31 vector multiplication. - * @param[in] pSrcA points to the first input vector - * @param[in] pSrcB points to the second input vector - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in each vector - */ - void arm_mult_q31( - q31_t * pSrcA, - q31_t * pSrcB, - q31_t * pDst, - uint32_t blockSize); - - - /** - * @brief Floating-point vector multiplication. - * @param[in] pSrcA points to the first input vector - * @param[in] pSrcB points to the second input vector - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in each vector - */ - void arm_mult_f32( - float32_t * pSrcA, - float32_t * pSrcB, - float32_t * pDst, - uint32_t blockSize); - - - /** - * @brief Instance structure for the Q15 CFFT/CIFFT function. - */ - typedef struct - { - uint16_t fftLen; /**< length of the FFT. */ - uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */ - uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */ - q15_t *pTwiddle; /**< points to the Sin twiddle factor table. */ - uint16_t *pBitRevTable; /**< points to the bit reversal table. */ - uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ - uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */ - } arm_cfft_radix2_instance_q15; - -/* Deprecated */ - arm_status arm_cfft_radix2_init_q15( - arm_cfft_radix2_instance_q15 * S, - uint16_t fftLen, - uint8_t ifftFlag, - uint8_t bitReverseFlag); - -/* Deprecated */ - void arm_cfft_radix2_q15( - const arm_cfft_radix2_instance_q15 * S, - q15_t * pSrc); - - - /** - * @brief Instance structure for the Q15 CFFT/CIFFT function. - */ - typedef struct - { - uint16_t fftLen; /**< length of the FFT. */ - uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */ - uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */ - q15_t *pTwiddle; /**< points to the twiddle factor table. */ - uint16_t *pBitRevTable; /**< points to the bit reversal table. */ - uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ - uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */ - } arm_cfft_radix4_instance_q15; - -/* Deprecated */ - arm_status arm_cfft_radix4_init_q15( - arm_cfft_radix4_instance_q15 * S, - uint16_t fftLen, - uint8_t ifftFlag, - uint8_t bitReverseFlag); - -/* Deprecated */ - void arm_cfft_radix4_q15( - const arm_cfft_radix4_instance_q15 * S, - q15_t * pSrc); - - /** - * @brief Instance structure for the Radix-2 Q31 CFFT/CIFFT function. - */ - typedef struct - { - uint16_t fftLen; /**< length of the FFT. */ - uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */ - uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */ - q31_t *pTwiddle; /**< points to the Twiddle factor table. */ - uint16_t *pBitRevTable; /**< points to the bit reversal table. */ - uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ - uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */ - } arm_cfft_radix2_instance_q31; - -/* Deprecated */ - arm_status arm_cfft_radix2_init_q31( - arm_cfft_radix2_instance_q31 * S, - uint16_t fftLen, - uint8_t ifftFlag, - uint8_t bitReverseFlag); - -/* Deprecated */ - void arm_cfft_radix2_q31( - const arm_cfft_radix2_instance_q31 * S, - q31_t * pSrc); - - /** - * @brief Instance structure for the Q31 CFFT/CIFFT function. - */ - typedef struct - { - uint16_t fftLen; /**< length of the FFT. */ - uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */ - uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */ - q31_t *pTwiddle; /**< points to the twiddle factor table. */ - uint16_t *pBitRevTable; /**< points to the bit reversal table. */ - uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ - uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */ - } arm_cfft_radix4_instance_q31; - -/* Deprecated */ - void arm_cfft_radix4_q31( - const arm_cfft_radix4_instance_q31 * S, - q31_t * pSrc); - -/* Deprecated */ - arm_status arm_cfft_radix4_init_q31( - arm_cfft_radix4_instance_q31 * S, - uint16_t fftLen, - uint8_t ifftFlag, - uint8_t bitReverseFlag); - - /** - * @brief Instance structure for the floating-point CFFT/CIFFT function. - */ - typedef struct - { - uint16_t fftLen; /**< length of the FFT. */ - uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */ - uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */ - float32_t *pTwiddle; /**< points to the Twiddle factor table. */ - uint16_t *pBitRevTable; /**< points to the bit reversal table. */ - uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ - uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */ - float32_t onebyfftLen; /**< value of 1/fftLen. */ - } arm_cfft_radix2_instance_f32; - -/* Deprecated */ - arm_status arm_cfft_radix2_init_f32( - arm_cfft_radix2_instance_f32 * S, - uint16_t fftLen, - uint8_t ifftFlag, - uint8_t bitReverseFlag); - -/* Deprecated */ - void arm_cfft_radix2_f32( - const arm_cfft_radix2_instance_f32 * S, - float32_t * pSrc); - - /** - * @brief Instance structure for the floating-point CFFT/CIFFT function. - */ - typedef struct - { - uint16_t fftLen; /**< length of the FFT. */ - uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */ - uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */ - float32_t *pTwiddle; /**< points to the Twiddle factor table. */ - uint16_t *pBitRevTable; /**< points to the bit reversal table. */ - uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ - uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */ - float32_t onebyfftLen; /**< value of 1/fftLen. */ - } arm_cfft_radix4_instance_f32; - -/* Deprecated */ - arm_status arm_cfft_radix4_init_f32( - arm_cfft_radix4_instance_f32 * S, - uint16_t fftLen, - uint8_t ifftFlag, - uint8_t bitReverseFlag); - -/* Deprecated */ - void arm_cfft_radix4_f32( - const arm_cfft_radix4_instance_f32 * S, - float32_t * pSrc); - - /** - * @brief Instance structure for the fixed-point CFFT/CIFFT function. - */ - typedef struct - { - uint16_t fftLen; /**< length of the FFT. */ - const q15_t *pTwiddle; /**< points to the Twiddle factor table. */ - const uint16_t *pBitRevTable; /**< points to the bit reversal table. */ - uint16_t bitRevLength; /**< bit reversal table length. */ - } arm_cfft_instance_q15; - -void arm_cfft_q15( - const arm_cfft_instance_q15 * S, - q15_t * p1, - uint8_t ifftFlag, - uint8_t bitReverseFlag); - - /** - * @brief Instance structure for the fixed-point CFFT/CIFFT function. - */ - typedef struct - { - uint16_t fftLen; /**< length of the FFT. */ - const q31_t *pTwiddle; /**< points to the Twiddle factor table. */ - const uint16_t *pBitRevTable; /**< points to the bit reversal table. */ - uint16_t bitRevLength; /**< bit reversal table length. */ - } arm_cfft_instance_q31; - -void arm_cfft_q31( - const arm_cfft_instance_q31 * S, - q31_t * p1, - uint8_t ifftFlag, - uint8_t bitReverseFlag); - - /** - * @brief Instance structure for the floating-point CFFT/CIFFT function. - */ - typedef struct - { - uint16_t fftLen; /**< length of the FFT. */ - const float32_t *pTwiddle; /**< points to the Twiddle factor table. */ - const uint16_t *pBitRevTable; /**< points to the bit reversal table. */ - uint16_t bitRevLength; /**< bit reversal table length. */ - } arm_cfft_instance_f32; - - void arm_cfft_f32( - const arm_cfft_instance_f32 * S, - float32_t * p1, - uint8_t ifftFlag, - uint8_t bitReverseFlag); - - /** - * @brief Instance structure for the Q15 RFFT/RIFFT function. - */ - typedef struct - { - uint32_t fftLenReal; /**< length of the real FFT. */ - uint8_t ifftFlagR; /**< flag that selects forward (ifftFlagR=0) or inverse (ifftFlagR=1) transform. */ - uint8_t bitReverseFlagR; /**< flag that enables (bitReverseFlagR=1) or disables (bitReverseFlagR=0) bit reversal of output. */ - uint32_t twidCoefRModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ - q15_t *pTwiddleAReal; /**< points to the real twiddle factor table. */ - q15_t *pTwiddleBReal; /**< points to the imag twiddle factor table. */ - const arm_cfft_instance_q15 *pCfft; /**< points to the complex FFT instance. */ - } arm_rfft_instance_q15; - - arm_status arm_rfft_init_q15( - arm_rfft_instance_q15 * S, - uint32_t fftLenReal, - uint32_t ifftFlagR, - uint32_t bitReverseFlag); - - void arm_rfft_q15( - const arm_rfft_instance_q15 * S, - q15_t * pSrc, - q15_t * pDst); - - /** - * @brief Instance structure for the Q31 RFFT/RIFFT function. - */ - typedef struct - { - uint32_t fftLenReal; /**< length of the real FFT. */ - uint8_t ifftFlagR; /**< flag that selects forward (ifftFlagR=0) or inverse (ifftFlagR=1) transform. */ - uint8_t bitReverseFlagR; /**< flag that enables (bitReverseFlagR=1) or disables (bitReverseFlagR=0) bit reversal of output. */ - uint32_t twidCoefRModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ - q31_t *pTwiddleAReal; /**< points to the real twiddle factor table. */ - q31_t *pTwiddleBReal; /**< points to the imag twiddle factor table. */ - const arm_cfft_instance_q31 *pCfft; /**< points to the complex FFT instance. */ - } arm_rfft_instance_q31; - - arm_status arm_rfft_init_q31( - arm_rfft_instance_q31 * S, - uint32_t fftLenReal, - uint32_t ifftFlagR, - uint32_t bitReverseFlag); - - void arm_rfft_q31( - const arm_rfft_instance_q31 * S, - q31_t * pSrc, - q31_t * pDst); - - /** - * @brief Instance structure for the floating-point RFFT/RIFFT function. - */ - typedef struct - { - uint32_t fftLenReal; /**< length of the real FFT. */ - uint16_t fftLenBy2; /**< length of the complex FFT. */ - uint8_t ifftFlagR; /**< flag that selects forward (ifftFlagR=0) or inverse (ifftFlagR=1) transform. */ - uint8_t bitReverseFlagR; /**< flag that enables (bitReverseFlagR=1) or disables (bitReverseFlagR=0) bit reversal of output. */ - uint32_t twidCoefRModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */ - float32_t *pTwiddleAReal; /**< points to the real twiddle factor table. */ - float32_t *pTwiddleBReal; /**< points to the imag twiddle factor table. */ - arm_cfft_radix4_instance_f32 *pCfft; /**< points to the complex FFT instance. */ - } arm_rfft_instance_f32; - - arm_status arm_rfft_init_f32( - arm_rfft_instance_f32 * S, - arm_cfft_radix4_instance_f32 * S_CFFT, - uint32_t fftLenReal, - uint32_t ifftFlagR, - uint32_t bitReverseFlag); - - void arm_rfft_f32( - const arm_rfft_instance_f32 * S, - float32_t * pSrc, - float32_t * pDst); - - /** - * @brief Instance structure for the floating-point RFFT/RIFFT function. - */ -typedef struct - { - arm_cfft_instance_f32 Sint; /**< Internal CFFT structure. */ - uint16_t fftLenRFFT; /**< length of the real sequence */ - float32_t * pTwiddleRFFT; /**< Twiddle factors real stage */ - } arm_rfft_fast_instance_f32 ; - -arm_status arm_rfft_fast_init_f32 ( - arm_rfft_fast_instance_f32 * S, - uint16_t fftLen); - -void arm_rfft_fast_f32( - arm_rfft_fast_instance_f32 * S, - float32_t * p, float32_t * pOut, - uint8_t ifftFlag); - - /** - * @brief Instance structure for the floating-point DCT4/IDCT4 function. - */ - typedef struct - { - uint16_t N; /**< length of the DCT4. */ - uint16_t Nby2; /**< half of the length of the DCT4. */ - float32_t normalize; /**< normalizing factor. */ - float32_t *pTwiddle; /**< points to the twiddle factor table. */ - float32_t *pCosFactor; /**< points to the cosFactor table. */ - arm_rfft_instance_f32 *pRfft; /**< points to the real FFT instance. */ - arm_cfft_radix4_instance_f32 *pCfft; /**< points to the complex FFT instance. */ - } arm_dct4_instance_f32; - - - /** - * @brief Initialization function for the floating-point DCT4/IDCT4. - * @param[in,out] S points to an instance of floating-point DCT4/IDCT4 structure. - * @param[in] S_RFFT points to an instance of floating-point RFFT/RIFFT structure. - * @param[in] S_CFFT points to an instance of floating-point CFFT/CIFFT structure. - * @param[in] N length of the DCT4. - * @param[in] Nby2 half of the length of the DCT4. - * @param[in] normalize normalizing factor. - * @return arm_status function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if fftLenReal is not a supported transform length. - */ - arm_status arm_dct4_init_f32( - arm_dct4_instance_f32 * S, - arm_rfft_instance_f32 * S_RFFT, - arm_cfft_radix4_instance_f32 * S_CFFT, - uint16_t N, - uint16_t Nby2, - float32_t normalize); - - - /** - * @brief Processing function for the floating-point DCT4/IDCT4. - * @param[in] S points to an instance of the floating-point DCT4/IDCT4 structure. - * @param[in] pState points to state buffer. - * @param[in,out] pInlineBuffer points to the in-place input and output buffer. - */ - void arm_dct4_f32( - const arm_dct4_instance_f32 * S, - float32_t * pState, - float32_t * pInlineBuffer); - - - /** - * @brief Instance structure for the Q31 DCT4/IDCT4 function. - */ - typedef struct - { - uint16_t N; /**< length of the DCT4. */ - uint16_t Nby2; /**< half of the length of the DCT4. */ - q31_t normalize; /**< normalizing factor. */ - q31_t *pTwiddle; /**< points to the twiddle factor table. */ - q31_t *pCosFactor; /**< points to the cosFactor table. */ - arm_rfft_instance_q31 *pRfft; /**< points to the real FFT instance. */ - arm_cfft_radix4_instance_q31 *pCfft; /**< points to the complex FFT instance. */ - } arm_dct4_instance_q31; - - - /** - * @brief Initialization function for the Q31 DCT4/IDCT4. - * @param[in,out] S points to an instance of Q31 DCT4/IDCT4 structure. - * @param[in] S_RFFT points to an instance of Q31 RFFT/RIFFT structure - * @param[in] S_CFFT points to an instance of Q31 CFFT/CIFFT structure - * @param[in] N length of the DCT4. - * @param[in] Nby2 half of the length of the DCT4. - * @param[in] normalize normalizing factor. - * @return arm_status function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if N is not a supported transform length. - */ - arm_status arm_dct4_init_q31( - arm_dct4_instance_q31 * S, - arm_rfft_instance_q31 * S_RFFT, - arm_cfft_radix4_instance_q31 * S_CFFT, - uint16_t N, - uint16_t Nby2, - q31_t normalize); - - - /** - * @brief Processing function for the Q31 DCT4/IDCT4. - * @param[in] S points to an instance of the Q31 DCT4 structure. - * @param[in] pState points to state buffer. - * @param[in,out] pInlineBuffer points to the in-place input and output buffer. - */ - void arm_dct4_q31( - const arm_dct4_instance_q31 * S, - q31_t * pState, - q31_t * pInlineBuffer); - - - /** - * @brief Instance structure for the Q15 DCT4/IDCT4 function. - */ - typedef struct - { - uint16_t N; /**< length of the DCT4. */ - uint16_t Nby2; /**< half of the length of the DCT4. */ - q15_t normalize; /**< normalizing factor. */ - q15_t *pTwiddle; /**< points to the twiddle factor table. */ - q15_t *pCosFactor; /**< points to the cosFactor table. */ - arm_rfft_instance_q15 *pRfft; /**< points to the real FFT instance. */ - arm_cfft_radix4_instance_q15 *pCfft; /**< points to the complex FFT instance. */ - } arm_dct4_instance_q15; - - - /** - * @brief Initialization function for the Q15 DCT4/IDCT4. - * @param[in,out] S points to an instance of Q15 DCT4/IDCT4 structure. - * @param[in] S_RFFT points to an instance of Q15 RFFT/RIFFT structure. - * @param[in] S_CFFT points to an instance of Q15 CFFT/CIFFT structure. - * @param[in] N length of the DCT4. - * @param[in] Nby2 half of the length of the DCT4. - * @param[in] normalize normalizing factor. - * @return arm_status function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if N is not a supported transform length. - */ - arm_status arm_dct4_init_q15( - arm_dct4_instance_q15 * S, - arm_rfft_instance_q15 * S_RFFT, - arm_cfft_radix4_instance_q15 * S_CFFT, - uint16_t N, - uint16_t Nby2, - q15_t normalize); - - - /** - * @brief Processing function for the Q15 DCT4/IDCT4. - * @param[in] S points to an instance of the Q15 DCT4 structure. - * @param[in] pState points to state buffer. - * @param[in,out] pInlineBuffer points to the in-place input and output buffer. - */ - void arm_dct4_q15( - const arm_dct4_instance_q15 * S, - q15_t * pState, - q15_t * pInlineBuffer); - - - /** - * @brief Floating-point vector addition. - * @param[in] pSrcA points to the first input vector - * @param[in] pSrcB points to the second input vector - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in each vector - */ - void arm_add_f32( - float32_t * pSrcA, - float32_t * pSrcB, - float32_t * pDst, - uint32_t blockSize); - - - /** - * @brief Q7 vector addition. - * @param[in] pSrcA points to the first input vector - * @param[in] pSrcB points to the second input vector - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in each vector - */ - void arm_add_q7( - q7_t * pSrcA, - q7_t * pSrcB, - q7_t * pDst, - uint32_t blockSize); - - - /** - * @brief Q15 vector addition. - * @param[in] pSrcA points to the first input vector - * @param[in] pSrcB points to the second input vector - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in each vector - */ - void arm_add_q15( - q15_t * pSrcA, - q15_t * pSrcB, - q15_t * pDst, - uint32_t blockSize); - - - /** - * @brief Q31 vector addition. - * @param[in] pSrcA points to the first input vector - * @param[in] pSrcB points to the second input vector - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in each vector - */ - void arm_add_q31( - q31_t * pSrcA, - q31_t * pSrcB, - q31_t * pDst, - uint32_t blockSize); - - - /** - * @brief Floating-point vector subtraction. - * @param[in] pSrcA points to the first input vector - * @param[in] pSrcB points to the second input vector - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in each vector - */ - void arm_sub_f32( - float32_t * pSrcA, - float32_t * pSrcB, - float32_t * pDst, - uint32_t blockSize); - - - /** - * @brief Q7 vector subtraction. - * @param[in] pSrcA points to the first input vector - * @param[in] pSrcB points to the second input vector - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in each vector - */ - void arm_sub_q7( - q7_t * pSrcA, - q7_t * pSrcB, - q7_t * pDst, - uint32_t blockSize); - - - /** - * @brief Q15 vector subtraction. - * @param[in] pSrcA points to the first input vector - * @param[in] pSrcB points to the second input vector - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in each vector - */ - void arm_sub_q15( - q15_t * pSrcA, - q15_t * pSrcB, - q15_t * pDst, - uint32_t blockSize); - - - /** - * @brief Q31 vector subtraction. - * @param[in] pSrcA points to the first input vector - * @param[in] pSrcB points to the second input vector - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in each vector - */ - void arm_sub_q31( - q31_t * pSrcA, - q31_t * pSrcB, - q31_t * pDst, - uint32_t blockSize); - - - /** - * @brief Multiplies a floating-point vector by a scalar. - * @param[in] pSrc points to the input vector - * @param[in] scale scale factor to be applied - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in the vector - */ - void arm_scale_f32( - float32_t * pSrc, - float32_t scale, - float32_t * pDst, - uint32_t blockSize); - - - /** - * @brief Multiplies a Q7 vector by a scalar. - * @param[in] pSrc points to the input vector - * @param[in] scaleFract fractional portion of the scale value - * @param[in] shift number of bits to shift the result by - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in the vector - */ - void arm_scale_q7( - q7_t * pSrc, - q7_t scaleFract, - int8_t shift, - q7_t * pDst, - uint32_t blockSize); - - - /** - * @brief Multiplies a Q15 vector by a scalar. - * @param[in] pSrc points to the input vector - * @param[in] scaleFract fractional portion of the scale value - * @param[in] shift number of bits to shift the result by - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in the vector - */ - void arm_scale_q15( - q15_t * pSrc, - q15_t scaleFract, - int8_t shift, - q15_t * pDst, - uint32_t blockSize); - - - /** - * @brief Multiplies a Q31 vector by a scalar. - * @param[in] pSrc points to the input vector - * @param[in] scaleFract fractional portion of the scale value - * @param[in] shift number of bits to shift the result by - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in the vector - */ - void arm_scale_q31( - q31_t * pSrc, - q31_t scaleFract, - int8_t shift, - q31_t * pDst, - uint32_t blockSize); - - - /** - * @brief Q7 vector absolute value. - * @param[in] pSrc points to the input buffer - * @param[out] pDst points to the output buffer - * @param[in] blockSize number of samples in each vector - */ - void arm_abs_q7( - q7_t * pSrc, - q7_t * pDst, - uint32_t blockSize); - - - /** - * @brief Floating-point vector absolute value. - * @param[in] pSrc points to the input buffer - * @param[out] pDst points to the output buffer - * @param[in] blockSize number of samples in each vector - */ - void arm_abs_f32( - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize); - - - /** - * @brief Q15 vector absolute value. - * @param[in] pSrc points to the input buffer - * @param[out] pDst points to the output buffer - * @param[in] blockSize number of samples in each vector - */ - void arm_abs_q15( - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize); - - - /** - * @brief Q31 vector absolute value. - * @param[in] pSrc points to the input buffer - * @param[out] pDst points to the output buffer - * @param[in] blockSize number of samples in each vector - */ - void arm_abs_q31( - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize); - - - /** - * @brief Dot product of floating-point vectors. - * @param[in] pSrcA points to the first input vector - * @param[in] pSrcB points to the second input vector - * @param[in] blockSize number of samples in each vector - * @param[out] result output result returned here - */ - void arm_dot_prod_f32( - float32_t * pSrcA, - float32_t * pSrcB, - uint32_t blockSize, - float32_t * result); - - - /** - * @brief Dot product of Q7 vectors. - * @param[in] pSrcA points to the first input vector - * @param[in] pSrcB points to the second input vector - * @param[in] blockSize number of samples in each vector - * @param[out] result output result returned here - */ - void arm_dot_prod_q7( - q7_t * pSrcA, - q7_t * pSrcB, - uint32_t blockSize, - q31_t * result); - - - /** - * @brief Dot product of Q15 vectors. - * @param[in] pSrcA points to the first input vector - * @param[in] pSrcB points to the second input vector - * @param[in] blockSize number of samples in each vector - * @param[out] result output result returned here - */ - void arm_dot_prod_q15( - q15_t * pSrcA, - q15_t * pSrcB, - uint32_t blockSize, - q63_t * result); - - - /** - * @brief Dot product of Q31 vectors. - * @param[in] pSrcA points to the first input vector - * @param[in] pSrcB points to the second input vector - * @param[in] blockSize number of samples in each vector - * @param[out] result output result returned here - */ - void arm_dot_prod_q31( - q31_t * pSrcA, - q31_t * pSrcB, - uint32_t blockSize, - q63_t * result); - - - /** - * @brief Shifts the elements of a Q7 vector a specified number of bits. - * @param[in] pSrc points to the input vector - * @param[in] shiftBits number of bits to shift. A positive value shifts left; a negative value shifts right. - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in the vector - */ - void arm_shift_q7( - q7_t * pSrc, - int8_t shiftBits, - q7_t * pDst, - uint32_t blockSize); - - - /** - * @brief Shifts the elements of a Q15 vector a specified number of bits. - * @param[in] pSrc points to the input vector - * @param[in] shiftBits number of bits to shift. A positive value shifts left; a negative value shifts right. - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in the vector - */ - void arm_shift_q15( - q15_t * pSrc, - int8_t shiftBits, - q15_t * pDst, - uint32_t blockSize); - - - /** - * @brief Shifts the elements of a Q31 vector a specified number of bits. - * @param[in] pSrc points to the input vector - * @param[in] shiftBits number of bits to shift. A positive value shifts left; a negative value shifts right. - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in the vector - */ - void arm_shift_q31( - q31_t * pSrc, - int8_t shiftBits, - q31_t * pDst, - uint32_t blockSize); - - - /** - * @brief Adds a constant offset to a floating-point vector. - * @param[in] pSrc points to the input vector - * @param[in] offset is the offset to be added - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in the vector - */ - void arm_offset_f32( - float32_t * pSrc, - float32_t offset, - float32_t * pDst, - uint32_t blockSize); - - - /** - * @brief Adds a constant offset to a Q7 vector. - * @param[in] pSrc points to the input vector - * @param[in] offset is the offset to be added - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in the vector - */ - void arm_offset_q7( - q7_t * pSrc, - q7_t offset, - q7_t * pDst, - uint32_t blockSize); - - - /** - * @brief Adds a constant offset to a Q15 vector. - * @param[in] pSrc points to the input vector - * @param[in] offset is the offset to be added - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in the vector - */ - void arm_offset_q15( - q15_t * pSrc, - q15_t offset, - q15_t * pDst, - uint32_t blockSize); - - - /** - * @brief Adds a constant offset to a Q31 vector. - * @param[in] pSrc points to the input vector - * @param[in] offset is the offset to be added - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in the vector - */ - void arm_offset_q31( - q31_t * pSrc, - q31_t offset, - q31_t * pDst, - uint32_t blockSize); - - - /** - * @brief Negates the elements of a floating-point vector. - * @param[in] pSrc points to the input vector - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in the vector - */ - void arm_negate_f32( - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize); - - - /** - * @brief Negates the elements of a Q7 vector. - * @param[in] pSrc points to the input vector - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in the vector - */ - void arm_negate_q7( - q7_t * pSrc, - q7_t * pDst, - uint32_t blockSize); - - - /** - * @brief Negates the elements of a Q15 vector. - * @param[in] pSrc points to the input vector - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in the vector - */ - void arm_negate_q15( - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize); - - - /** - * @brief Negates the elements of a Q31 vector. - * @param[in] pSrc points to the input vector - * @param[out] pDst points to the output vector - * @param[in] blockSize number of samples in the vector - */ - void arm_negate_q31( - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize); - - - /** - * @brief Copies the elements of a floating-point vector. - * @param[in] pSrc input pointer - * @param[out] pDst output pointer - * @param[in] blockSize number of samples to process - */ - void arm_copy_f32( - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize); - - - /** - * @brief Copies the elements of a Q7 vector. - * @param[in] pSrc input pointer - * @param[out] pDst output pointer - * @param[in] blockSize number of samples to process - */ - void arm_copy_q7( - q7_t * pSrc, - q7_t * pDst, - uint32_t blockSize); - - - /** - * @brief Copies the elements of a Q15 vector. - * @param[in] pSrc input pointer - * @param[out] pDst output pointer - * @param[in] blockSize number of samples to process - */ - void arm_copy_q15( - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize); - - - /** - * @brief Copies the elements of a Q31 vector. - * @param[in] pSrc input pointer - * @param[out] pDst output pointer - * @param[in] blockSize number of samples to process - */ - void arm_copy_q31( - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize); - - - /** - * @brief Fills a constant value into a floating-point vector. - * @param[in] value input value to be filled - * @param[out] pDst output pointer - * @param[in] blockSize number of samples to process - */ - void arm_fill_f32( - float32_t value, - float32_t * pDst, - uint32_t blockSize); - - - /** - * @brief Fills a constant value into a Q7 vector. - * @param[in] value input value to be filled - * @param[out] pDst output pointer - * @param[in] blockSize number of samples to process - */ - void arm_fill_q7( - q7_t value, - q7_t * pDst, - uint32_t blockSize); - - - /** - * @brief Fills a constant value into a Q15 vector. - * @param[in] value input value to be filled - * @param[out] pDst output pointer - * @param[in] blockSize number of samples to process - */ - void arm_fill_q15( - q15_t value, - q15_t * pDst, - uint32_t blockSize); - - - /** - * @brief Fills a constant value into a Q31 vector. - * @param[in] value input value to be filled - * @param[out] pDst output pointer - * @param[in] blockSize number of samples to process - */ - void arm_fill_q31( - q31_t value, - q31_t * pDst, - uint32_t blockSize); - - -/** - * @brief Convolution of floating-point sequences. - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the location where the output result is written. Length srcALen+srcBLen-1. - */ - void arm_conv_f32( - float32_t * pSrcA, - uint32_t srcALen, - float32_t * pSrcB, - uint32_t srcBLen, - float32_t * pDst); - - - /** - * @brief Convolution of Q15 sequences. - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data Length srcALen+srcBLen-1. - * @param[in] pScratch1 points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. - * @param[in] pScratch2 points to scratch buffer of size min(srcALen, srcBLen). - */ - void arm_conv_opt_q15( - q15_t * pSrcA, - uint32_t srcALen, - q15_t * pSrcB, - uint32_t srcBLen, - q15_t * pDst, - q15_t * pScratch1, - q15_t * pScratch2); - - -/** - * @brief Convolution of Q15 sequences. - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the location where the output result is written. Length srcALen+srcBLen-1. - */ - void arm_conv_q15( - q15_t * pSrcA, - uint32_t srcALen, - q15_t * pSrcB, - uint32_t srcBLen, - q15_t * pDst); - - - /** - * @brief Convolution of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4 - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data Length srcALen+srcBLen-1. - */ - void arm_conv_fast_q15( - q15_t * pSrcA, - uint32_t srcALen, - q15_t * pSrcB, - uint32_t srcBLen, - q15_t * pDst); - - - /** - * @brief Convolution of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4 - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data Length srcALen+srcBLen-1. - * @param[in] pScratch1 points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. - * @param[in] pScratch2 points to scratch buffer of size min(srcALen, srcBLen). - */ - void arm_conv_fast_opt_q15( - q15_t * pSrcA, - uint32_t srcALen, - q15_t * pSrcB, - uint32_t srcBLen, - q15_t * pDst, - q15_t * pScratch1, - q15_t * pScratch2); - - - /** - * @brief Convolution of Q31 sequences. - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data Length srcALen+srcBLen-1. - */ - void arm_conv_q31( - q31_t * pSrcA, - uint32_t srcALen, - q31_t * pSrcB, - uint32_t srcBLen, - q31_t * pDst); - - - /** - * @brief Convolution of Q31 sequences (fast version) for Cortex-M3 and Cortex-M4 - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data Length srcALen+srcBLen-1. - */ - void arm_conv_fast_q31( - q31_t * pSrcA, - uint32_t srcALen, - q31_t * pSrcB, - uint32_t srcBLen, - q31_t * pDst); - - - /** - * @brief Convolution of Q7 sequences. - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data Length srcALen+srcBLen-1. - * @param[in] pScratch1 points to scratch buffer(of type q15_t) of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. - * @param[in] pScratch2 points to scratch buffer (of type q15_t) of size min(srcALen, srcBLen). - */ - void arm_conv_opt_q7( - q7_t * pSrcA, - uint32_t srcALen, - q7_t * pSrcB, - uint32_t srcBLen, - q7_t * pDst, - q15_t * pScratch1, - q15_t * pScratch2); - - - /** - * @brief Convolution of Q7 sequences. - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data Length srcALen+srcBLen-1. - */ - void arm_conv_q7( - q7_t * pSrcA, - uint32_t srcALen, - q7_t * pSrcB, - uint32_t srcBLen, - q7_t * pDst); - - - /** - * @brief Partial convolution of floating-point sequences. - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data - * @param[in] firstIndex is the first output sample to start with. - * @param[in] numPoints is the number of output points to be computed. - * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. - */ - arm_status arm_conv_partial_f32( - float32_t * pSrcA, - uint32_t srcALen, - float32_t * pSrcB, - uint32_t srcBLen, - float32_t * pDst, - uint32_t firstIndex, - uint32_t numPoints); - - - /** - * @brief Partial convolution of Q15 sequences. - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data - * @param[in] firstIndex is the first output sample to start with. - * @param[in] numPoints is the number of output points to be computed. - * @param[in] pScratch1 points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. - * @param[in] pScratch2 points to scratch buffer of size min(srcALen, srcBLen). - * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. - */ - arm_status arm_conv_partial_opt_q15( - q15_t * pSrcA, - uint32_t srcALen, - q15_t * pSrcB, - uint32_t srcBLen, - q15_t * pDst, - uint32_t firstIndex, - uint32_t numPoints, - q15_t * pScratch1, - q15_t * pScratch2); - - - /** - * @brief Partial convolution of Q15 sequences. - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data - * @param[in] firstIndex is the first output sample to start with. - * @param[in] numPoints is the number of output points to be computed. - * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. - */ - arm_status arm_conv_partial_q15( - q15_t * pSrcA, - uint32_t srcALen, - q15_t * pSrcB, - uint32_t srcBLen, - q15_t * pDst, - uint32_t firstIndex, - uint32_t numPoints); - - - /** - * @brief Partial convolution of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4 - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data - * @param[in] firstIndex is the first output sample to start with. - * @param[in] numPoints is the number of output points to be computed. - * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. - */ - arm_status arm_conv_partial_fast_q15( - q15_t * pSrcA, - uint32_t srcALen, - q15_t * pSrcB, - uint32_t srcBLen, - q15_t * pDst, - uint32_t firstIndex, - uint32_t numPoints); - - - /** - * @brief Partial convolution of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4 - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data - * @param[in] firstIndex is the first output sample to start with. - * @param[in] numPoints is the number of output points to be computed. - * @param[in] pScratch1 points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. - * @param[in] pScratch2 points to scratch buffer of size min(srcALen, srcBLen). - * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. - */ - arm_status arm_conv_partial_fast_opt_q15( - q15_t * pSrcA, - uint32_t srcALen, - q15_t * pSrcB, - uint32_t srcBLen, - q15_t * pDst, - uint32_t firstIndex, - uint32_t numPoints, - q15_t * pScratch1, - q15_t * pScratch2); - - - /** - * @brief Partial convolution of Q31 sequences. - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data - * @param[in] firstIndex is the first output sample to start with. - * @param[in] numPoints is the number of output points to be computed. - * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. - */ - arm_status arm_conv_partial_q31( - q31_t * pSrcA, - uint32_t srcALen, - q31_t * pSrcB, - uint32_t srcBLen, - q31_t * pDst, - uint32_t firstIndex, - uint32_t numPoints); - - - /** - * @brief Partial convolution of Q31 sequences (fast version) for Cortex-M3 and Cortex-M4 - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data - * @param[in] firstIndex is the first output sample to start with. - * @param[in] numPoints is the number of output points to be computed. - * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. - */ - arm_status arm_conv_partial_fast_q31( - q31_t * pSrcA, - uint32_t srcALen, - q31_t * pSrcB, - uint32_t srcBLen, - q31_t * pDst, - uint32_t firstIndex, - uint32_t numPoints); - - - /** - * @brief Partial convolution of Q7 sequences - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data - * @param[in] firstIndex is the first output sample to start with. - * @param[in] numPoints is the number of output points to be computed. - * @param[in] pScratch1 points to scratch buffer(of type q15_t) of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. - * @param[in] pScratch2 points to scratch buffer (of type q15_t) of size min(srcALen, srcBLen). - * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. - */ - arm_status arm_conv_partial_opt_q7( - q7_t * pSrcA, - uint32_t srcALen, - q7_t * pSrcB, - uint32_t srcBLen, - q7_t * pDst, - uint32_t firstIndex, - uint32_t numPoints, - q15_t * pScratch1, - q15_t * pScratch2); - - -/** - * @brief Partial convolution of Q7 sequences. - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data - * @param[in] firstIndex is the first output sample to start with. - * @param[in] numPoints is the number of output points to be computed. - * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2]. - */ - arm_status arm_conv_partial_q7( - q7_t * pSrcA, - uint32_t srcALen, - q7_t * pSrcB, - uint32_t srcBLen, - q7_t * pDst, - uint32_t firstIndex, - uint32_t numPoints); - - - /** - * @brief Instance structure for the Q15 FIR decimator. - */ - typedef struct - { - uint8_t M; /**< decimation factor. */ - uint16_t numTaps; /**< number of coefficients in the filter. */ - q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ - q15_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ - } arm_fir_decimate_instance_q15; - - /** - * @brief Instance structure for the Q31 FIR decimator. - */ - typedef struct - { - uint8_t M; /**< decimation factor. */ - uint16_t numTaps; /**< number of coefficients in the filter. */ - q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ - q31_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ - } arm_fir_decimate_instance_q31; - - /** - * @brief Instance structure for the floating-point FIR decimator. - */ - typedef struct - { - uint8_t M; /**< decimation factor. */ - uint16_t numTaps; /**< number of coefficients in the filter. */ - float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ - float32_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ - } arm_fir_decimate_instance_f32; - - - /** - * @brief Processing function for the floating-point FIR decimator. - * @param[in] S points to an instance of the floating-point FIR decimator structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data - * @param[in] blockSize number of input samples to process per call. - */ - void arm_fir_decimate_f32( - const arm_fir_decimate_instance_f32 * S, - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize); - - - /** - * @brief Initialization function for the floating-point FIR decimator. - * @param[in,out] S points to an instance of the floating-point FIR decimator structure. - * @param[in] numTaps number of coefficients in the filter. - * @param[in] M decimation factor. - * @param[in] pCoeffs points to the filter coefficients. - * @param[in] pState points to the state buffer. - * @param[in] blockSize number of input samples to process per call. - * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if - * blockSize is not a multiple of M. - */ - arm_status arm_fir_decimate_init_f32( - arm_fir_decimate_instance_f32 * S, - uint16_t numTaps, - uint8_t M, - float32_t * pCoeffs, - float32_t * pState, - uint32_t blockSize); - - - /** - * @brief Processing function for the Q15 FIR decimator. - * @param[in] S points to an instance of the Q15 FIR decimator structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data - * @param[in] blockSize number of input samples to process per call. - */ - void arm_fir_decimate_q15( - const arm_fir_decimate_instance_q15 * S, - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize); - - - /** - * @brief Processing function for the Q15 FIR decimator (fast variant) for Cortex-M3 and Cortex-M4. - * @param[in] S points to an instance of the Q15 FIR decimator structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data - * @param[in] blockSize number of input samples to process per call. - */ - void arm_fir_decimate_fast_q15( - const arm_fir_decimate_instance_q15 * S, - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize); - - - /** - * @brief Initialization function for the Q15 FIR decimator. - * @param[in,out] S points to an instance of the Q15 FIR decimator structure. - * @param[in] numTaps number of coefficients in the filter. - * @param[in] M decimation factor. - * @param[in] pCoeffs points to the filter coefficients. - * @param[in] pState points to the state buffer. - * @param[in] blockSize number of input samples to process per call. - * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if - * blockSize is not a multiple of M. - */ - arm_status arm_fir_decimate_init_q15( - arm_fir_decimate_instance_q15 * S, - uint16_t numTaps, - uint8_t M, - q15_t * pCoeffs, - q15_t * pState, - uint32_t blockSize); - - - /** - * @brief Processing function for the Q31 FIR decimator. - * @param[in] S points to an instance of the Q31 FIR decimator structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data - * @param[in] blockSize number of input samples to process per call. - */ - void arm_fir_decimate_q31( - const arm_fir_decimate_instance_q31 * S, - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize); - - /** - * @brief Processing function for the Q31 FIR decimator (fast variant) for Cortex-M3 and Cortex-M4. - * @param[in] S points to an instance of the Q31 FIR decimator structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data - * @param[in] blockSize number of input samples to process per call. - */ - void arm_fir_decimate_fast_q31( - arm_fir_decimate_instance_q31 * S, - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize); - - - /** - * @brief Initialization function for the Q31 FIR decimator. - * @param[in,out] S points to an instance of the Q31 FIR decimator structure. - * @param[in] numTaps number of coefficients in the filter. - * @param[in] M decimation factor. - * @param[in] pCoeffs points to the filter coefficients. - * @param[in] pState points to the state buffer. - * @param[in] blockSize number of input samples to process per call. - * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if - * blockSize is not a multiple of M. - */ - arm_status arm_fir_decimate_init_q31( - arm_fir_decimate_instance_q31 * S, - uint16_t numTaps, - uint8_t M, - q31_t * pCoeffs, - q31_t * pState, - uint32_t blockSize); - - - /** - * @brief Instance structure for the Q15 FIR interpolator. - */ - typedef struct - { - uint8_t L; /**< upsample factor. */ - uint16_t phaseLength; /**< length of each polyphase filter component. */ - q15_t *pCoeffs; /**< points to the coefficient array. The array is of length L*phaseLength. */ - q15_t *pState; /**< points to the state variable array. The array is of length blockSize+phaseLength-1. */ - } arm_fir_interpolate_instance_q15; - - /** - * @brief Instance structure for the Q31 FIR interpolator. - */ - typedef struct - { - uint8_t L; /**< upsample factor. */ - uint16_t phaseLength; /**< length of each polyphase filter component. */ - q31_t *pCoeffs; /**< points to the coefficient array. The array is of length L*phaseLength. */ - q31_t *pState; /**< points to the state variable array. The array is of length blockSize+phaseLength-1. */ - } arm_fir_interpolate_instance_q31; - - /** - * @brief Instance structure for the floating-point FIR interpolator. - */ - typedef struct - { - uint8_t L; /**< upsample factor. */ - uint16_t phaseLength; /**< length of each polyphase filter component. */ - float32_t *pCoeffs; /**< points to the coefficient array. The array is of length L*phaseLength. */ - float32_t *pState; /**< points to the state variable array. The array is of length phaseLength+numTaps-1. */ - } arm_fir_interpolate_instance_f32; - - - /** - * @brief Processing function for the Q15 FIR interpolator. - * @param[in] S points to an instance of the Q15 FIR interpolator structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data. - * @param[in] blockSize number of input samples to process per call. - */ - void arm_fir_interpolate_q15( - const arm_fir_interpolate_instance_q15 * S, - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize); - - - /** - * @brief Initialization function for the Q15 FIR interpolator. - * @param[in,out] S points to an instance of the Q15 FIR interpolator structure. - * @param[in] L upsample factor. - * @param[in] numTaps number of filter coefficients in the filter. - * @param[in] pCoeffs points to the filter coefficient buffer. - * @param[in] pState points to the state buffer. - * @param[in] blockSize number of input samples to process per call. - * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if - * the filter length numTaps is not a multiple of the interpolation factor L. - */ - arm_status arm_fir_interpolate_init_q15( - arm_fir_interpolate_instance_q15 * S, - uint8_t L, - uint16_t numTaps, - q15_t * pCoeffs, - q15_t * pState, - uint32_t blockSize); - - - /** - * @brief Processing function for the Q31 FIR interpolator. - * @param[in] S points to an instance of the Q15 FIR interpolator structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data. - * @param[in] blockSize number of input samples to process per call. - */ - void arm_fir_interpolate_q31( - const arm_fir_interpolate_instance_q31 * S, - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize); - - - /** - * @brief Initialization function for the Q31 FIR interpolator. - * @param[in,out] S points to an instance of the Q31 FIR interpolator structure. - * @param[in] L upsample factor. - * @param[in] numTaps number of filter coefficients in the filter. - * @param[in] pCoeffs points to the filter coefficient buffer. - * @param[in] pState points to the state buffer. - * @param[in] blockSize number of input samples to process per call. - * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if - * the filter length numTaps is not a multiple of the interpolation factor L. - */ - arm_status arm_fir_interpolate_init_q31( - arm_fir_interpolate_instance_q31 * S, - uint8_t L, - uint16_t numTaps, - q31_t * pCoeffs, - q31_t * pState, - uint32_t blockSize); - - - /** - * @brief Processing function for the floating-point FIR interpolator. - * @param[in] S points to an instance of the floating-point FIR interpolator structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data. - * @param[in] blockSize number of input samples to process per call. - */ - void arm_fir_interpolate_f32( - const arm_fir_interpolate_instance_f32 * S, - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize); - - - /** - * @brief Initialization function for the floating-point FIR interpolator. - * @param[in,out] S points to an instance of the floating-point FIR interpolator structure. - * @param[in] L upsample factor. - * @param[in] numTaps number of filter coefficients in the filter. - * @param[in] pCoeffs points to the filter coefficient buffer. - * @param[in] pState points to the state buffer. - * @param[in] blockSize number of input samples to process per call. - * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if - * the filter length numTaps is not a multiple of the interpolation factor L. - */ - arm_status arm_fir_interpolate_init_f32( - arm_fir_interpolate_instance_f32 * S, - uint8_t L, - uint16_t numTaps, - float32_t * pCoeffs, - float32_t * pState, - uint32_t blockSize); - - - /** - * @brief Instance structure for the high precision Q31 Biquad cascade filter. - */ - typedef struct - { - uint8_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */ - q63_t *pState; /**< points to the array of state coefficients. The array is of length 4*numStages. */ - q31_t *pCoeffs; /**< points to the array of coefficients. The array is of length 5*numStages. */ - uint8_t postShift; /**< additional shift, in bits, applied to each output sample. */ - } arm_biquad_cas_df1_32x64_ins_q31; - - - /** - * @param[in] S points to an instance of the high precision Q31 Biquad cascade filter structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data - * @param[in] blockSize number of samples to process. - */ - void arm_biquad_cas_df1_32x64_q31( - const arm_biquad_cas_df1_32x64_ins_q31 * S, - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize); - - - /** - * @param[in,out] S points to an instance of the high precision Q31 Biquad cascade filter structure. - * @param[in] numStages number of 2nd order stages in the filter. - * @param[in] pCoeffs points to the filter coefficients. - * @param[in] pState points to the state buffer. - * @param[in] postShift shift to be applied to the output. Varies according to the coefficients format - */ - void arm_biquad_cas_df1_32x64_init_q31( - arm_biquad_cas_df1_32x64_ins_q31 * S, - uint8_t numStages, - q31_t * pCoeffs, - q63_t * pState, - uint8_t postShift); - - - /** - * @brief Instance structure for the floating-point transposed direct form II Biquad cascade filter. - */ - typedef struct - { - uint8_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */ - float32_t *pState; /**< points to the array of state coefficients. The array is of length 2*numStages. */ - float32_t *pCoeffs; /**< points to the array of coefficients. The array is of length 5*numStages. */ - } arm_biquad_cascade_df2T_instance_f32; - - /** - * @brief Instance structure for the floating-point transposed direct form II Biquad cascade filter. - */ - typedef struct - { - uint8_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */ - float32_t *pState; /**< points to the array of state coefficients. The array is of length 4*numStages. */ - float32_t *pCoeffs; /**< points to the array of coefficients. The array is of length 5*numStages. */ - } arm_biquad_cascade_stereo_df2T_instance_f32; - - /** - * @brief Instance structure for the floating-point transposed direct form II Biquad cascade filter. - */ - typedef struct - { - uint8_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */ - float64_t *pState; /**< points to the array of state coefficients. The array is of length 2*numStages. */ - float64_t *pCoeffs; /**< points to the array of coefficients. The array is of length 5*numStages. */ - } arm_biquad_cascade_df2T_instance_f64; - - - /** - * @brief Processing function for the floating-point transposed direct form II Biquad cascade filter. - * @param[in] S points to an instance of the filter data structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data - * @param[in] blockSize number of samples to process. - */ - void arm_biquad_cascade_df2T_f32( - const arm_biquad_cascade_df2T_instance_f32 * S, - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize); - - - /** - * @brief Processing function for the floating-point transposed direct form II Biquad cascade filter. 2 channels - * @param[in] S points to an instance of the filter data structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data - * @param[in] blockSize number of samples to process. - */ - void arm_biquad_cascade_stereo_df2T_f32( - const arm_biquad_cascade_stereo_df2T_instance_f32 * S, - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize); - - - /** - * @brief Processing function for the floating-point transposed direct form II Biquad cascade filter. - * @param[in] S points to an instance of the filter data structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data - * @param[in] blockSize number of samples to process. - */ - void arm_biquad_cascade_df2T_f64( - const arm_biquad_cascade_df2T_instance_f64 * S, - float64_t * pSrc, - float64_t * pDst, - uint32_t blockSize); - - - /** - * @brief Initialization function for the floating-point transposed direct form II Biquad cascade filter. - * @param[in,out] S points to an instance of the filter data structure. - * @param[in] numStages number of 2nd order stages in the filter. - * @param[in] pCoeffs points to the filter coefficients. - * @param[in] pState points to the state buffer. - */ - void arm_biquad_cascade_df2T_init_f32( - arm_biquad_cascade_df2T_instance_f32 * S, - uint8_t numStages, - float32_t * pCoeffs, - float32_t * pState); - - - /** - * @brief Initialization function for the floating-point transposed direct form II Biquad cascade filter. - * @param[in,out] S points to an instance of the filter data structure. - * @param[in] numStages number of 2nd order stages in the filter. - * @param[in] pCoeffs points to the filter coefficients. - * @param[in] pState points to the state buffer. - */ - void arm_biquad_cascade_stereo_df2T_init_f32( - arm_biquad_cascade_stereo_df2T_instance_f32 * S, - uint8_t numStages, - float32_t * pCoeffs, - float32_t * pState); - - - /** - * @brief Initialization function for the floating-point transposed direct form II Biquad cascade filter. - * @param[in,out] S points to an instance of the filter data structure. - * @param[in] numStages number of 2nd order stages in the filter. - * @param[in] pCoeffs points to the filter coefficients. - * @param[in] pState points to the state buffer. - */ - void arm_biquad_cascade_df2T_init_f64( - arm_biquad_cascade_df2T_instance_f64 * S, - uint8_t numStages, - float64_t * pCoeffs, - float64_t * pState); - - - /** - * @brief Instance structure for the Q15 FIR lattice filter. - */ - typedef struct - { - uint16_t numStages; /**< number of filter stages. */ - q15_t *pState; /**< points to the state variable array. The array is of length numStages. */ - q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numStages. */ - } arm_fir_lattice_instance_q15; - - /** - * @brief Instance structure for the Q31 FIR lattice filter. - */ - typedef struct - { - uint16_t numStages; /**< number of filter stages. */ - q31_t *pState; /**< points to the state variable array. The array is of length numStages. */ - q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numStages. */ - } arm_fir_lattice_instance_q31; - - /** - * @brief Instance structure for the floating-point FIR lattice filter. - */ - typedef struct - { - uint16_t numStages; /**< number of filter stages. */ - float32_t *pState; /**< points to the state variable array. The array is of length numStages. */ - float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numStages. */ - } arm_fir_lattice_instance_f32; - - - /** - * @brief Initialization function for the Q15 FIR lattice filter. - * @param[in] S points to an instance of the Q15 FIR lattice structure. - * @param[in] numStages number of filter stages. - * @param[in] pCoeffs points to the coefficient buffer. The array is of length numStages. - * @param[in] pState points to the state buffer. The array is of length numStages. - */ - void arm_fir_lattice_init_q15( - arm_fir_lattice_instance_q15 * S, - uint16_t numStages, - q15_t * pCoeffs, - q15_t * pState); - - - /** - * @brief Processing function for the Q15 FIR lattice filter. - * @param[in] S points to an instance of the Q15 FIR lattice structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data. - * @param[in] blockSize number of samples to process. - */ - void arm_fir_lattice_q15( - const arm_fir_lattice_instance_q15 * S, - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize); - - - /** - * @brief Initialization function for the Q31 FIR lattice filter. - * @param[in] S points to an instance of the Q31 FIR lattice structure. - * @param[in] numStages number of filter stages. - * @param[in] pCoeffs points to the coefficient buffer. The array is of length numStages. - * @param[in] pState points to the state buffer. The array is of length numStages. - */ - void arm_fir_lattice_init_q31( - arm_fir_lattice_instance_q31 * S, - uint16_t numStages, - q31_t * pCoeffs, - q31_t * pState); - - - /** - * @brief Processing function for the Q31 FIR lattice filter. - * @param[in] S points to an instance of the Q31 FIR lattice structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data - * @param[in] blockSize number of samples to process. - */ - void arm_fir_lattice_q31( - const arm_fir_lattice_instance_q31 * S, - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize); - - -/** - * @brief Initialization function for the floating-point FIR lattice filter. - * @param[in] S points to an instance of the floating-point FIR lattice structure. - * @param[in] numStages number of filter stages. - * @param[in] pCoeffs points to the coefficient buffer. The array is of length numStages. - * @param[in] pState points to the state buffer. The array is of length numStages. - */ - void arm_fir_lattice_init_f32( - arm_fir_lattice_instance_f32 * S, - uint16_t numStages, - float32_t * pCoeffs, - float32_t * pState); - - - /** - * @brief Processing function for the floating-point FIR lattice filter. - * @param[in] S points to an instance of the floating-point FIR lattice structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data - * @param[in] blockSize number of samples to process. - */ - void arm_fir_lattice_f32( - const arm_fir_lattice_instance_f32 * S, - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize); - - - /** - * @brief Instance structure for the Q15 IIR lattice filter. - */ - typedef struct - { - uint16_t numStages; /**< number of stages in the filter. */ - q15_t *pState; /**< points to the state variable array. The array is of length numStages+blockSize. */ - q15_t *pkCoeffs; /**< points to the reflection coefficient array. The array is of length numStages. */ - q15_t *pvCoeffs; /**< points to the ladder coefficient array. The array is of length numStages+1. */ - } arm_iir_lattice_instance_q15; - - /** - * @brief Instance structure for the Q31 IIR lattice filter. - */ - typedef struct - { - uint16_t numStages; /**< number of stages in the filter. */ - q31_t *pState; /**< points to the state variable array. The array is of length numStages+blockSize. */ - q31_t *pkCoeffs; /**< points to the reflection coefficient array. The array is of length numStages. */ - q31_t *pvCoeffs; /**< points to the ladder coefficient array. The array is of length numStages+1. */ - } arm_iir_lattice_instance_q31; - - /** - * @brief Instance structure for the floating-point IIR lattice filter. - */ - typedef struct - { - uint16_t numStages; /**< number of stages in the filter. */ - float32_t *pState; /**< points to the state variable array. The array is of length numStages+blockSize. */ - float32_t *pkCoeffs; /**< points to the reflection coefficient array. The array is of length numStages. */ - float32_t *pvCoeffs; /**< points to the ladder coefficient array. The array is of length numStages+1. */ - } arm_iir_lattice_instance_f32; - - - /** - * @brief Processing function for the floating-point IIR lattice filter. - * @param[in] S points to an instance of the floating-point IIR lattice structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data. - * @param[in] blockSize number of samples to process. - */ - void arm_iir_lattice_f32( - const arm_iir_lattice_instance_f32 * S, - float32_t * pSrc, - float32_t * pDst, - uint32_t blockSize); - - - /** - * @brief Initialization function for the floating-point IIR lattice filter. - * @param[in] S points to an instance of the floating-point IIR lattice structure. - * @param[in] numStages number of stages in the filter. - * @param[in] pkCoeffs points to the reflection coefficient buffer. The array is of length numStages. - * @param[in] pvCoeffs points to the ladder coefficient buffer. The array is of length numStages+1. - * @param[in] pState points to the state buffer. The array is of length numStages+blockSize-1. - * @param[in] blockSize number of samples to process. - */ - void arm_iir_lattice_init_f32( - arm_iir_lattice_instance_f32 * S, - uint16_t numStages, - float32_t * pkCoeffs, - float32_t * pvCoeffs, - float32_t * pState, - uint32_t blockSize); - - - /** - * @brief Processing function for the Q31 IIR lattice filter. - * @param[in] S points to an instance of the Q31 IIR lattice structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data. - * @param[in] blockSize number of samples to process. - */ - void arm_iir_lattice_q31( - const arm_iir_lattice_instance_q31 * S, - q31_t * pSrc, - q31_t * pDst, - uint32_t blockSize); - - - /** - * @brief Initialization function for the Q31 IIR lattice filter. - * @param[in] S points to an instance of the Q31 IIR lattice structure. - * @param[in] numStages number of stages in the filter. - * @param[in] pkCoeffs points to the reflection coefficient buffer. The array is of length numStages. - * @param[in] pvCoeffs points to the ladder coefficient buffer. The array is of length numStages+1. - * @param[in] pState points to the state buffer. The array is of length numStages+blockSize. - * @param[in] blockSize number of samples to process. - */ - void arm_iir_lattice_init_q31( - arm_iir_lattice_instance_q31 * S, - uint16_t numStages, - q31_t * pkCoeffs, - q31_t * pvCoeffs, - q31_t * pState, - uint32_t blockSize); - - - /** - * @brief Processing function for the Q15 IIR lattice filter. - * @param[in] S points to an instance of the Q15 IIR lattice structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data. - * @param[in] blockSize number of samples to process. - */ - void arm_iir_lattice_q15( - const arm_iir_lattice_instance_q15 * S, - q15_t * pSrc, - q15_t * pDst, - uint32_t blockSize); - - -/** - * @brief Initialization function for the Q15 IIR lattice filter. - * @param[in] S points to an instance of the fixed-point Q15 IIR lattice structure. - * @param[in] numStages number of stages in the filter. - * @param[in] pkCoeffs points to reflection coefficient buffer. The array is of length numStages. - * @param[in] pvCoeffs points to ladder coefficient buffer. The array is of length numStages+1. - * @param[in] pState points to state buffer. The array is of length numStages+blockSize. - * @param[in] blockSize number of samples to process per call. - */ - void arm_iir_lattice_init_q15( - arm_iir_lattice_instance_q15 * S, - uint16_t numStages, - q15_t * pkCoeffs, - q15_t * pvCoeffs, - q15_t * pState, - uint32_t blockSize); - - - /** - * @brief Instance structure for the floating-point LMS filter. - */ - typedef struct - { - uint16_t numTaps; /**< number of coefficients in the filter. */ - float32_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ - float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */ - float32_t mu; /**< step size that controls filter coefficient updates. */ - } arm_lms_instance_f32; - - - /** - * @brief Processing function for floating-point LMS filter. - * @param[in] S points to an instance of the floating-point LMS filter structure. - * @param[in] pSrc points to the block of input data. - * @param[in] pRef points to the block of reference data. - * @param[out] pOut points to the block of output data. - * @param[out] pErr points to the block of error data. - * @param[in] blockSize number of samples to process. - */ - void arm_lms_f32( - const arm_lms_instance_f32 * S, - float32_t * pSrc, - float32_t * pRef, - float32_t * pOut, - float32_t * pErr, - uint32_t blockSize); - - - /** - * @brief Initialization function for floating-point LMS filter. - * @param[in] S points to an instance of the floating-point LMS filter structure. - * @param[in] numTaps number of filter coefficients. - * @param[in] pCoeffs points to the coefficient buffer. - * @param[in] pState points to state buffer. - * @param[in] mu step size that controls filter coefficient updates. - * @param[in] blockSize number of samples to process. - */ - void arm_lms_init_f32( - arm_lms_instance_f32 * S, - uint16_t numTaps, - float32_t * pCoeffs, - float32_t * pState, - float32_t mu, - uint32_t blockSize); - - - /** - * @brief Instance structure for the Q15 LMS filter. - */ - typedef struct - { - uint16_t numTaps; /**< number of coefficients in the filter. */ - q15_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ - q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */ - q15_t mu; /**< step size that controls filter coefficient updates. */ - uint32_t postShift; /**< bit shift applied to coefficients. */ - } arm_lms_instance_q15; - - - /** - * @brief Initialization function for the Q15 LMS filter. - * @param[in] S points to an instance of the Q15 LMS filter structure. - * @param[in] numTaps number of filter coefficients. - * @param[in] pCoeffs points to the coefficient buffer. - * @param[in] pState points to the state buffer. - * @param[in] mu step size that controls filter coefficient updates. - * @param[in] blockSize number of samples to process. - * @param[in] postShift bit shift applied to coefficients. - */ - void arm_lms_init_q15( - arm_lms_instance_q15 * S, - uint16_t numTaps, - q15_t * pCoeffs, - q15_t * pState, - q15_t mu, - uint32_t blockSize, - uint32_t postShift); - - - /** - * @brief Processing function for Q15 LMS filter. - * @param[in] S points to an instance of the Q15 LMS filter structure. - * @param[in] pSrc points to the block of input data. - * @param[in] pRef points to the block of reference data. - * @param[out] pOut points to the block of output data. - * @param[out] pErr points to the block of error data. - * @param[in] blockSize number of samples to process. - */ - void arm_lms_q15( - const arm_lms_instance_q15 * S, - q15_t * pSrc, - q15_t * pRef, - q15_t * pOut, - q15_t * pErr, - uint32_t blockSize); - - - /** - * @brief Instance structure for the Q31 LMS filter. - */ - typedef struct - { - uint16_t numTaps; /**< number of coefficients in the filter. */ - q31_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ - q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */ - q31_t mu; /**< step size that controls filter coefficient updates. */ - uint32_t postShift; /**< bit shift applied to coefficients. */ - } arm_lms_instance_q31; - - - /** - * @brief Processing function for Q31 LMS filter. - * @param[in] S points to an instance of the Q15 LMS filter structure. - * @param[in] pSrc points to the block of input data. - * @param[in] pRef points to the block of reference data. - * @param[out] pOut points to the block of output data. - * @param[out] pErr points to the block of error data. - * @param[in] blockSize number of samples to process. - */ - void arm_lms_q31( - const arm_lms_instance_q31 * S, - q31_t * pSrc, - q31_t * pRef, - q31_t * pOut, - q31_t * pErr, - uint32_t blockSize); - - - /** - * @brief Initialization function for Q31 LMS filter. - * @param[in] S points to an instance of the Q31 LMS filter structure. - * @param[in] numTaps number of filter coefficients. - * @param[in] pCoeffs points to coefficient buffer. - * @param[in] pState points to state buffer. - * @param[in] mu step size that controls filter coefficient updates. - * @param[in] blockSize number of samples to process. - * @param[in] postShift bit shift applied to coefficients. - */ - void arm_lms_init_q31( - arm_lms_instance_q31 * S, - uint16_t numTaps, - q31_t * pCoeffs, - q31_t * pState, - q31_t mu, - uint32_t blockSize, - uint32_t postShift); - - - /** - * @brief Instance structure for the floating-point normalized LMS filter. - */ - typedef struct - { - uint16_t numTaps; /**< number of coefficients in the filter. */ - float32_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ - float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */ - float32_t mu; /**< step size that control filter coefficient updates. */ - float32_t energy; /**< saves previous frame energy. */ - float32_t x0; /**< saves previous input sample. */ - } arm_lms_norm_instance_f32; - - - /** - * @brief Processing function for floating-point normalized LMS filter. - * @param[in] S points to an instance of the floating-point normalized LMS filter structure. - * @param[in] pSrc points to the block of input data. - * @param[in] pRef points to the block of reference data. - * @param[out] pOut points to the block of output data. - * @param[out] pErr points to the block of error data. - * @param[in] blockSize number of samples to process. - */ - void arm_lms_norm_f32( - arm_lms_norm_instance_f32 * S, - float32_t * pSrc, - float32_t * pRef, - float32_t * pOut, - float32_t * pErr, - uint32_t blockSize); - - - /** - * @brief Initialization function for floating-point normalized LMS filter. - * @param[in] S points to an instance of the floating-point LMS filter structure. - * @param[in] numTaps number of filter coefficients. - * @param[in] pCoeffs points to coefficient buffer. - * @param[in] pState points to state buffer. - * @param[in] mu step size that controls filter coefficient updates. - * @param[in] blockSize number of samples to process. - */ - void arm_lms_norm_init_f32( - arm_lms_norm_instance_f32 * S, - uint16_t numTaps, - float32_t * pCoeffs, - float32_t * pState, - float32_t mu, - uint32_t blockSize); - - - /** - * @brief Instance structure for the Q31 normalized LMS filter. - */ - typedef struct - { - uint16_t numTaps; /**< number of coefficients in the filter. */ - q31_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ - q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */ - q31_t mu; /**< step size that controls filter coefficient updates. */ - uint8_t postShift; /**< bit shift applied to coefficients. */ - q31_t *recipTable; /**< points to the reciprocal initial value table. */ - q31_t energy; /**< saves previous frame energy. */ - q31_t x0; /**< saves previous input sample. */ - } arm_lms_norm_instance_q31; - - - /** - * @brief Processing function for Q31 normalized LMS filter. - * @param[in] S points to an instance of the Q31 normalized LMS filter structure. - * @param[in] pSrc points to the block of input data. - * @param[in] pRef points to the block of reference data. - * @param[out] pOut points to the block of output data. - * @param[out] pErr points to the block of error data. - * @param[in] blockSize number of samples to process. - */ - void arm_lms_norm_q31( - arm_lms_norm_instance_q31 * S, - q31_t * pSrc, - q31_t * pRef, - q31_t * pOut, - q31_t * pErr, - uint32_t blockSize); - - - /** - * @brief Initialization function for Q31 normalized LMS filter. - * @param[in] S points to an instance of the Q31 normalized LMS filter structure. - * @param[in] numTaps number of filter coefficients. - * @param[in] pCoeffs points to coefficient buffer. - * @param[in] pState points to state buffer. - * @param[in] mu step size that controls filter coefficient updates. - * @param[in] blockSize number of samples to process. - * @param[in] postShift bit shift applied to coefficients. - */ - void arm_lms_norm_init_q31( - arm_lms_norm_instance_q31 * S, - uint16_t numTaps, - q31_t * pCoeffs, - q31_t * pState, - q31_t mu, - uint32_t blockSize, - uint8_t postShift); - - - /** - * @brief Instance structure for the Q15 normalized LMS filter. - */ - typedef struct - { - uint16_t numTaps; /**< Number of coefficients in the filter. */ - q15_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */ - q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */ - q15_t mu; /**< step size that controls filter coefficient updates. */ - uint8_t postShift; /**< bit shift applied to coefficients. */ - q15_t *recipTable; /**< Points to the reciprocal initial value table. */ - q15_t energy; /**< saves previous frame energy. */ - q15_t x0; /**< saves previous input sample. */ - } arm_lms_norm_instance_q15; - - - /** - * @brief Processing function for Q15 normalized LMS filter. - * @param[in] S points to an instance of the Q15 normalized LMS filter structure. - * @param[in] pSrc points to the block of input data. - * @param[in] pRef points to the block of reference data. - * @param[out] pOut points to the block of output data. - * @param[out] pErr points to the block of error data. - * @param[in] blockSize number of samples to process. - */ - void arm_lms_norm_q15( - arm_lms_norm_instance_q15 * S, - q15_t * pSrc, - q15_t * pRef, - q15_t * pOut, - q15_t * pErr, - uint32_t blockSize); - - - /** - * @brief Initialization function for Q15 normalized LMS filter. - * @param[in] S points to an instance of the Q15 normalized LMS filter structure. - * @param[in] numTaps number of filter coefficients. - * @param[in] pCoeffs points to coefficient buffer. - * @param[in] pState points to state buffer. - * @param[in] mu step size that controls filter coefficient updates. - * @param[in] blockSize number of samples to process. - * @param[in] postShift bit shift applied to coefficients. - */ - void arm_lms_norm_init_q15( - arm_lms_norm_instance_q15 * S, - uint16_t numTaps, - q15_t * pCoeffs, - q15_t * pState, - q15_t mu, - uint32_t blockSize, - uint8_t postShift); - - - /** - * @brief Correlation of floating-point sequences. - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. - */ - void arm_correlate_f32( - float32_t * pSrcA, - uint32_t srcALen, - float32_t * pSrcB, - uint32_t srcBLen, - float32_t * pDst); - - - /** - * @brief Correlation of Q15 sequences - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. - * @param[in] pScratch points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. - */ - void arm_correlate_opt_q15( - q15_t * pSrcA, - uint32_t srcALen, - q15_t * pSrcB, - uint32_t srcBLen, - q15_t * pDst, - q15_t * pScratch); - - - /** - * @brief Correlation of Q15 sequences. - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. - */ - - void arm_correlate_q15( - q15_t * pSrcA, - uint32_t srcALen, - q15_t * pSrcB, - uint32_t srcBLen, - q15_t * pDst); - - - /** - * @brief Correlation of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4. - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. - */ - - void arm_correlate_fast_q15( - q15_t * pSrcA, - uint32_t srcALen, - q15_t * pSrcB, - uint32_t srcBLen, - q15_t * pDst); - - - /** - * @brief Correlation of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4. - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. - * @param[in] pScratch points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. - */ - void arm_correlate_fast_opt_q15( - q15_t * pSrcA, - uint32_t srcALen, - q15_t * pSrcB, - uint32_t srcBLen, - q15_t * pDst, - q15_t * pScratch); - - - /** - * @brief Correlation of Q31 sequences. - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. - */ - void arm_correlate_q31( - q31_t * pSrcA, - uint32_t srcALen, - q31_t * pSrcB, - uint32_t srcBLen, - q31_t * pDst); - - - /** - * @brief Correlation of Q31 sequences (fast version) for Cortex-M3 and Cortex-M4 - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. - */ - void arm_correlate_fast_q31( - q31_t * pSrcA, - uint32_t srcALen, - q31_t * pSrcB, - uint32_t srcBLen, - q31_t * pDst); - - - /** - * @brief Correlation of Q7 sequences. - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. - * @param[in] pScratch1 points to scratch buffer(of type q15_t) of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2. - * @param[in] pScratch2 points to scratch buffer (of type q15_t) of size min(srcALen, srcBLen). - */ - void arm_correlate_opt_q7( - q7_t * pSrcA, - uint32_t srcALen, - q7_t * pSrcB, - uint32_t srcBLen, - q7_t * pDst, - q15_t * pScratch1, - q15_t * pScratch2); - - - /** - * @brief Correlation of Q7 sequences. - * @param[in] pSrcA points to the first input sequence. - * @param[in] srcALen length of the first input sequence. - * @param[in] pSrcB points to the second input sequence. - * @param[in] srcBLen length of the second input sequence. - * @param[out] pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1. - */ - void arm_correlate_q7( - q7_t * pSrcA, - uint32_t srcALen, - q7_t * pSrcB, - uint32_t srcBLen, - q7_t * pDst); - - - /** - * @brief Instance structure for the floating-point sparse FIR filter. - */ - typedef struct - { - uint16_t numTaps; /**< number of coefficients in the filter. */ - uint16_t stateIndex; /**< state buffer index. Points to the oldest sample in the state buffer. */ - float32_t *pState; /**< points to the state buffer array. The array is of length maxDelay+blockSize-1. */ - float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ - uint16_t maxDelay; /**< maximum offset specified by the pTapDelay array. */ - int32_t *pTapDelay; /**< points to the array of delay values. The array is of length numTaps. */ - } arm_fir_sparse_instance_f32; - - /** - * @brief Instance structure for the Q31 sparse FIR filter. - */ - typedef struct - { - uint16_t numTaps; /**< number of coefficients in the filter. */ - uint16_t stateIndex; /**< state buffer index. Points to the oldest sample in the state buffer. */ - q31_t *pState; /**< points to the state buffer array. The array is of length maxDelay+blockSize-1. */ - q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ - uint16_t maxDelay; /**< maximum offset specified by the pTapDelay array. */ - int32_t *pTapDelay; /**< points to the array of delay values. The array is of length numTaps. */ - } arm_fir_sparse_instance_q31; - - /** - * @brief Instance structure for the Q15 sparse FIR filter. - */ - typedef struct - { - uint16_t numTaps; /**< number of coefficients in the filter. */ - uint16_t stateIndex; /**< state buffer index. Points to the oldest sample in the state buffer. */ - q15_t *pState; /**< points to the state buffer array. The array is of length maxDelay+blockSize-1. */ - q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ - uint16_t maxDelay; /**< maximum offset specified by the pTapDelay array. */ - int32_t *pTapDelay; /**< points to the array of delay values. The array is of length numTaps. */ - } arm_fir_sparse_instance_q15; - - /** - * @brief Instance structure for the Q7 sparse FIR filter. - */ - typedef struct - { - uint16_t numTaps; /**< number of coefficients in the filter. */ - uint16_t stateIndex; /**< state buffer index. Points to the oldest sample in the state buffer. */ - q7_t *pState; /**< points to the state buffer array. The array is of length maxDelay+blockSize-1. */ - q7_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/ - uint16_t maxDelay; /**< maximum offset specified by the pTapDelay array. */ - int32_t *pTapDelay; /**< points to the array of delay values. The array is of length numTaps. */ - } arm_fir_sparse_instance_q7; - - - /** - * @brief Processing function for the floating-point sparse FIR filter. - * @param[in] S points to an instance of the floating-point sparse FIR structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data - * @param[in] pScratchIn points to a temporary buffer of size blockSize. - * @param[in] blockSize number of input samples to process per call. - */ - void arm_fir_sparse_f32( - arm_fir_sparse_instance_f32 * S, - float32_t * pSrc, - float32_t * pDst, - float32_t * pScratchIn, - uint32_t blockSize); - - - /** - * @brief Initialization function for the floating-point sparse FIR filter. - * @param[in,out] S points to an instance of the floating-point sparse FIR structure. - * @param[in] numTaps number of nonzero coefficients in the filter. - * @param[in] pCoeffs points to the array of filter coefficients. - * @param[in] pState points to the state buffer. - * @param[in] pTapDelay points to the array of offset times. - * @param[in] maxDelay maximum offset time supported. - * @param[in] blockSize number of samples that will be processed per block. - */ - void arm_fir_sparse_init_f32( - arm_fir_sparse_instance_f32 * S, - uint16_t numTaps, - float32_t * pCoeffs, - float32_t * pState, - int32_t * pTapDelay, - uint16_t maxDelay, - uint32_t blockSize); - - - /** - * @brief Processing function for the Q31 sparse FIR filter. - * @param[in] S points to an instance of the Q31 sparse FIR structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data - * @param[in] pScratchIn points to a temporary buffer of size blockSize. - * @param[in] blockSize number of input samples to process per call. - */ - void arm_fir_sparse_q31( - arm_fir_sparse_instance_q31 * S, - q31_t * pSrc, - q31_t * pDst, - q31_t * pScratchIn, - uint32_t blockSize); - - - /** - * @brief Initialization function for the Q31 sparse FIR filter. - * @param[in,out] S points to an instance of the Q31 sparse FIR structure. - * @param[in] numTaps number of nonzero coefficients in the filter. - * @param[in] pCoeffs points to the array of filter coefficients. - * @param[in] pState points to the state buffer. - * @param[in] pTapDelay points to the array of offset times. - * @param[in] maxDelay maximum offset time supported. - * @param[in] blockSize number of samples that will be processed per block. - */ - void arm_fir_sparse_init_q31( - arm_fir_sparse_instance_q31 * S, - uint16_t numTaps, - q31_t * pCoeffs, - q31_t * pState, - int32_t * pTapDelay, - uint16_t maxDelay, - uint32_t blockSize); - - - /** - * @brief Processing function for the Q15 sparse FIR filter. - * @param[in] S points to an instance of the Q15 sparse FIR structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data - * @param[in] pScratchIn points to a temporary buffer of size blockSize. - * @param[in] pScratchOut points to a temporary buffer of size blockSize. - * @param[in] blockSize number of input samples to process per call. - */ - void arm_fir_sparse_q15( - arm_fir_sparse_instance_q15 * S, - q15_t * pSrc, - q15_t * pDst, - q15_t * pScratchIn, - q31_t * pScratchOut, - uint32_t blockSize); - - - /** - * @brief Initialization function for the Q15 sparse FIR filter. - * @param[in,out] S points to an instance of the Q15 sparse FIR structure. - * @param[in] numTaps number of nonzero coefficients in the filter. - * @param[in] pCoeffs points to the array of filter coefficients. - * @param[in] pState points to the state buffer. - * @param[in] pTapDelay points to the array of offset times. - * @param[in] maxDelay maximum offset time supported. - * @param[in] blockSize number of samples that will be processed per block. - */ - void arm_fir_sparse_init_q15( - arm_fir_sparse_instance_q15 * S, - uint16_t numTaps, - q15_t * pCoeffs, - q15_t * pState, - int32_t * pTapDelay, - uint16_t maxDelay, - uint32_t blockSize); - - - /** - * @brief Processing function for the Q7 sparse FIR filter. - * @param[in] S points to an instance of the Q7 sparse FIR structure. - * @param[in] pSrc points to the block of input data. - * @param[out] pDst points to the block of output data - * @param[in] pScratchIn points to a temporary buffer of size blockSize. - * @param[in] pScratchOut points to a temporary buffer of size blockSize. - * @param[in] blockSize number of input samples to process per call. - */ - void arm_fir_sparse_q7( - arm_fir_sparse_instance_q7 * S, - q7_t * pSrc, - q7_t * pDst, - q7_t * pScratchIn, - q31_t * pScratchOut, - uint32_t blockSize); - - - /** - * @brief Initialization function for the Q7 sparse FIR filter. - * @param[in,out] S points to an instance of the Q7 sparse FIR structure. - * @param[in] numTaps number of nonzero coefficients in the filter. - * @param[in] pCoeffs points to the array of filter coefficients. - * @param[in] pState points to the state buffer. - * @param[in] pTapDelay points to the array of offset times. - * @param[in] maxDelay maximum offset time supported. - * @param[in] blockSize number of samples that will be processed per block. - */ - void arm_fir_sparse_init_q7( - arm_fir_sparse_instance_q7 * S, - uint16_t numTaps, - q7_t * pCoeffs, - q7_t * pState, - int32_t * pTapDelay, - uint16_t maxDelay, - uint32_t blockSize); - - - /** - * @brief Floating-point sin_cos function. - * @param[in] theta input value in degrees - * @param[out] pSinVal points to the processed sine output. - * @param[out] pCosVal points to the processed cos output. - */ - void arm_sin_cos_f32( - float32_t theta, - float32_t * pSinVal, - float32_t * pCosVal); - - - /** - * @brief Q31 sin_cos function. - * @param[in] theta scaled input value in degrees - * @param[out] pSinVal points to the processed sine output. - * @param[out] pCosVal points to the processed cosine output. - */ - void arm_sin_cos_q31( - q31_t theta, - q31_t * pSinVal, - q31_t * pCosVal); - - - /** - * @brief Floating-point complex conjugate. - * @param[in] pSrc points to the input vector - * @param[out] pDst points to the output vector - * @param[in] numSamples number of complex samples in each vector - */ - void arm_cmplx_conj_f32( - float32_t * pSrc, - float32_t * pDst, - uint32_t numSamples); - - /** - * @brief Q31 complex conjugate. - * @param[in] pSrc points to the input vector - * @param[out] pDst points to the output vector - * @param[in] numSamples number of complex samples in each vector - */ - void arm_cmplx_conj_q31( - q31_t * pSrc, - q31_t * pDst, - uint32_t numSamples); - - - /** - * @brief Q15 complex conjugate. - * @param[in] pSrc points to the input vector - * @param[out] pDst points to the output vector - * @param[in] numSamples number of complex samples in each vector - */ - void arm_cmplx_conj_q15( - q15_t * pSrc, - q15_t * pDst, - uint32_t numSamples); - - - /** - * @brief Floating-point complex magnitude squared - * @param[in] pSrc points to the complex input vector - * @param[out] pDst points to the real output vector - * @param[in] numSamples number of complex samples in the input vector - */ - void arm_cmplx_mag_squared_f32( - float32_t * pSrc, - float32_t * pDst, - uint32_t numSamples); - - - /** - * @brief Q31 complex magnitude squared - * @param[in] pSrc points to the complex input vector - * @param[out] pDst points to the real output vector - * @param[in] numSamples number of complex samples in the input vector - */ - void arm_cmplx_mag_squared_q31( - q31_t * pSrc, - q31_t * pDst, - uint32_t numSamples); - - - /** - * @brief Q15 complex magnitude squared - * @param[in] pSrc points to the complex input vector - * @param[out] pDst points to the real output vector - * @param[in] numSamples number of complex samples in the input vector - */ - void arm_cmplx_mag_squared_q15( - q15_t * pSrc, - q15_t * pDst, - uint32_t numSamples); - - - /** - * @ingroup groupController - */ - - /** - * @defgroup PID PID Motor Control - * - * A Proportional Integral Derivative (PID) controller is a generic feedback control - * loop mechanism widely used in industrial control systems. - * A PID controller is the most commonly used type of feedback controller. - * - * This set of functions implements (PID) controllers - * for Q15, Q31, and floating-point data types. The functions operate on a single sample - * of data and each call to the function returns a single processed value. - * S points to an instance of the PID control data structure. in - * is the input sample value. The functions return the output value. - * - * \par Algorithm: - *
-   *    y[n] = y[n-1] + A0 * x[n] + A1 * x[n-1] + A2 * x[n-2]
-   *    A0 = Kp + Ki + Kd
-   *    A1 = (-Kp ) - (2 * Kd )
-   *    A2 = Kd  
- * - * \par - * where \c Kp is proportional constant, \c Ki is Integral constant and \c Kd is Derivative constant - * - * \par - * \image html PID.gif "Proportional Integral Derivative Controller" - * - * \par - * The PID controller calculates an "error" value as the difference between - * the measured output and the reference input. - * The controller attempts to minimize the error by adjusting the process control inputs. - * The proportional value determines the reaction to the current error, - * the integral value determines the reaction based on the sum of recent errors, - * and the derivative value determines the reaction based on the rate at which the error has been changing. - * - * \par Instance Structure - * The Gains A0, A1, A2 and state variables for a PID controller are stored together in an instance data structure. - * A separate instance structure must be defined for each PID Controller. - * There are separate instance structure declarations for each of the 3 supported data types. - * - * \par Reset Functions - * There is also an associated reset function for each data type which clears the state array. - * - * \par Initialization Functions - * There is also an associated initialization function for each data type. - * The initialization function performs the following operations: - * - Initializes the Gains A0, A1, A2 from Kp,Ki, Kd gains. - * - Zeros out the values in the state buffer. - * - * \par - * Instance structure cannot be placed into a const data section and it is recommended to use the initialization function. - * - * \par Fixed-Point Behavior - * Care must be taken when using the fixed-point versions of the PID Controller functions. - * In particular, the overflow and saturation behavior of the accumulator used in each function must be considered. - * Refer to the function specific documentation below for usage guidelines. - */ - - /** - * @addtogroup PID - * @{ - */ - - /** - * @brief Process function for the floating-point PID Control. - * @param[in,out] S is an instance of the floating-point PID Control structure - * @param[in] in input sample to process - * @return out processed output sample. - */ - static __INLINE float32_t arm_pid_f32( - arm_pid_instance_f32 * S, - float32_t in) - { - float32_t out; - - /* y[n] = y[n-1] + A0 * x[n] + A1 * x[n-1] + A2 * x[n-2] */ - out = (S->A0 * in) + - (S->A1 * S->state[0]) + (S->A2 * S->state[1]) + (S->state[2]); - - /* Update state */ - S->state[1] = S->state[0]; - S->state[0] = in; - S->state[2] = out; - - /* return to application */ - return (out); - - } - - /** - * @brief Process function for the Q31 PID Control. - * @param[in,out] S points to an instance of the Q31 PID Control structure - * @param[in] in input sample to process - * @return out processed output sample. - * - * Scaling and Overflow Behavior: - * \par - * The function is implemented using an internal 64-bit accumulator. - * The accumulator has a 2.62 format and maintains full precision of the intermediate multiplication results but provides only a single guard bit. - * Thus, if the accumulator result overflows it wraps around rather than clip. - * In order to avoid overflows completely the input signal must be scaled down by 2 bits as there are four additions. - * After all multiply-accumulates are performed, the 2.62 accumulator is truncated to 1.32 format and then saturated to 1.31 format. - */ - static __INLINE q31_t arm_pid_q31( - arm_pid_instance_q31 * S, - q31_t in) - { - q63_t acc; - q31_t out; - - /* acc = A0 * x[n] */ - acc = (q63_t) S->A0 * in; - - /* acc += A1 * x[n-1] */ - acc += (q63_t) S->A1 * S->state[0]; - - /* acc += A2 * x[n-2] */ - acc += (q63_t) S->A2 * S->state[1]; - - /* convert output to 1.31 format to add y[n-1] */ - out = (q31_t) (acc >> 31u); - - /* out += y[n-1] */ - out += S->state[2]; - - /* Update state */ - S->state[1] = S->state[0]; - S->state[0] = in; - S->state[2] = out; - - /* return to application */ - return (out); - } - - - /** - * @brief Process function for the Q15 PID Control. - * @param[in,out] S points to an instance of the Q15 PID Control structure - * @param[in] in input sample to process - * @return out processed output sample. - * - * Scaling and Overflow Behavior: - * \par - * The function is implemented using a 64-bit internal accumulator. - * Both Gains and state variables are represented in 1.15 format and multiplications yield a 2.30 result. - * The 2.30 intermediate results are accumulated in a 64-bit accumulator in 34.30 format. - * There is no risk of internal overflow with this approach and the full precision of intermediate multiplications is preserved. - * After all additions have been performed, the accumulator is truncated to 34.15 format by discarding low 15 bits. - * Lastly, the accumulator is saturated to yield a result in 1.15 format. - */ - static __INLINE q15_t arm_pid_q15( - arm_pid_instance_q15 * S, - q15_t in) - { - q63_t acc; - q15_t out; - -#ifndef ARM_MATH_CM0_FAMILY - __SIMD32_TYPE *vstate; - - /* Implementation of PID controller */ - - /* acc = A0 * x[n] */ - acc = (q31_t) __SMUAD((uint32_t)S->A0, (uint32_t)in); - - /* acc += A1 * x[n-1] + A2 * x[n-2] */ - vstate = __SIMD32_CONST(S->state); - acc = (q63_t)__SMLALD((uint32_t)S->A1, (uint32_t)*vstate, (uint64_t)acc); -#else - /* acc = A0 * x[n] */ - acc = ((q31_t) S->A0) * in; - - /* acc += A1 * x[n-1] + A2 * x[n-2] */ - acc += (q31_t) S->A1 * S->state[0]; - acc += (q31_t) S->A2 * S->state[1]; -#endif - - /* acc += y[n-1] */ - acc += (q31_t) S->state[2] << 15; - - /* saturate the output */ - out = (q15_t) (__SSAT((acc >> 15), 16)); - - /* Update state */ - S->state[1] = S->state[0]; - S->state[0] = in; - S->state[2] = out; - - /* return to application */ - return (out); - } - - /** - * @} end of PID group - */ - - - /** - * @brief Floating-point matrix inverse. - * @param[in] src points to the instance of the input floating-point matrix structure. - * @param[out] dst points to the instance of the output floating-point matrix structure. - * @return The function returns ARM_MATH_SIZE_MISMATCH, if the dimensions do not match. - * If the input matrix is singular (does not have an inverse), then the algorithm terminates and returns error status ARM_MATH_SINGULAR. - */ - arm_status arm_mat_inverse_f32( - const arm_matrix_instance_f32 * src, - arm_matrix_instance_f32 * dst); - - - /** - * @brief Floating-point matrix inverse. - * @param[in] src points to the instance of the input floating-point matrix structure. - * @param[out] dst points to the instance of the output floating-point matrix structure. - * @return The function returns ARM_MATH_SIZE_MISMATCH, if the dimensions do not match. - * If the input matrix is singular (does not have an inverse), then the algorithm terminates and returns error status ARM_MATH_SINGULAR. - */ - arm_status arm_mat_inverse_f64( - const arm_matrix_instance_f64 * src, - arm_matrix_instance_f64 * dst); - - - - /** - * @ingroup groupController - */ - - /** - * @defgroup clarke Vector Clarke Transform - * Forward Clarke transform converts the instantaneous stator phases into a two-coordinate time invariant vector. - * Generally the Clarke transform uses three-phase currents Ia, Ib and Ic to calculate currents - * in the two-phase orthogonal stator axis Ialpha and Ibeta. - * When Ialpha is superposed with Ia as shown in the figure below - * \image html clarke.gif Stator current space vector and its components in (a,b). - * and Ia + Ib + Ic = 0, in this condition Ialpha and Ibeta - * can be calculated using only Ia and Ib. - * - * The function operates on a single sample of data and each call to the function returns the processed output. - * The library provides separate functions for Q31 and floating-point data types. - * \par Algorithm - * \image html clarkeFormula.gif - * where Ia and Ib are the instantaneous stator phases and - * pIalpha and pIbeta are the two coordinates of time invariant vector. - * \par Fixed-Point Behavior - * Care must be taken when using the Q31 version of the Clarke transform. - * In particular, the overflow and saturation behavior of the accumulator used must be considered. - * Refer to the function specific documentation below for usage guidelines. - */ - - /** - * @addtogroup clarke - * @{ - */ - - /** - * - * @brief Floating-point Clarke transform - * @param[in] Ia input three-phase coordinate a - * @param[in] Ib input three-phase coordinate b - * @param[out] pIalpha points to output two-phase orthogonal vector axis alpha - * @param[out] pIbeta points to output two-phase orthogonal vector axis beta - */ - static __INLINE void arm_clarke_f32( - float32_t Ia, - float32_t Ib, - float32_t * pIalpha, - float32_t * pIbeta) - { - /* Calculate pIalpha using the equation, pIalpha = Ia */ - *pIalpha = Ia; - - /* Calculate pIbeta using the equation, pIbeta = (1/sqrt(3)) * Ia + (2/sqrt(3)) * Ib */ - *pIbeta = ((float32_t) 0.57735026919 * Ia + (float32_t) 1.15470053838 * Ib); - } - - - /** - * @brief Clarke transform for Q31 version - * @param[in] Ia input three-phase coordinate a - * @param[in] Ib input three-phase coordinate b - * @param[out] pIalpha points to output two-phase orthogonal vector axis alpha - * @param[out] pIbeta points to output two-phase orthogonal vector axis beta - * - * Scaling and Overflow Behavior: - * \par - * The function is implemented using an internal 32-bit accumulator. - * The accumulator maintains 1.31 format by truncating lower 31 bits of the intermediate multiplication in 2.62 format. - * There is saturation on the addition, hence there is no risk of overflow. - */ - static __INLINE void arm_clarke_q31( - q31_t Ia, - q31_t Ib, - q31_t * pIalpha, - q31_t * pIbeta) - { - q31_t product1, product2; /* Temporary variables used to store intermediate results */ - - /* Calculating pIalpha from Ia by equation pIalpha = Ia */ - *pIalpha = Ia; - - /* Intermediate product is calculated by (1/(sqrt(3)) * Ia) */ - product1 = (q31_t) (((q63_t) Ia * 0x24F34E8B) >> 30); - - /* Intermediate product is calculated by (2/sqrt(3) * Ib) */ - product2 = (q31_t) (((q63_t) Ib * 0x49E69D16) >> 30); - - /* pIbeta is calculated by adding the intermediate products */ - *pIbeta = __QADD(product1, product2); - } - - /** - * @} end of clarke group - */ - - /** - * @brief Converts the elements of the Q7 vector to Q31 vector. - * @param[in] pSrc input pointer - * @param[out] pDst output pointer - * @param[in] blockSize number of samples to process - */ - void arm_q7_to_q31( - q7_t * pSrc, - q31_t * pDst, - uint32_t blockSize); - - - - /** - * @ingroup groupController - */ - - /** - * @defgroup inv_clarke Vector Inverse Clarke Transform - * Inverse Clarke transform converts the two-coordinate time invariant vector into instantaneous stator phases. - * - * The function operates on a single sample of data and each call to the function returns the processed output. - * The library provides separate functions for Q31 and floating-point data types. - * \par Algorithm - * \image html clarkeInvFormula.gif - * where pIa and pIb are the instantaneous stator phases and - * Ialpha and Ibeta are the two coordinates of time invariant vector. - * \par Fixed-Point Behavior - * Care must be taken when using the Q31 version of the Clarke transform. - * In particular, the overflow and saturation behavior of the accumulator used must be considered. - * Refer to the function specific documentation below for usage guidelines. - */ - - /** - * @addtogroup inv_clarke - * @{ - */ - - /** - * @brief Floating-point Inverse Clarke transform - * @param[in] Ialpha input two-phase orthogonal vector axis alpha - * @param[in] Ibeta input two-phase orthogonal vector axis beta - * @param[out] pIa points to output three-phase coordinate a - * @param[out] pIb points to output three-phase coordinate b - */ - static __INLINE void arm_inv_clarke_f32( - float32_t Ialpha, - float32_t Ibeta, - float32_t * pIa, - float32_t * pIb) - { - /* Calculating pIa from Ialpha by equation pIa = Ialpha */ - *pIa = Ialpha; - - /* Calculating pIb from Ialpha and Ibeta by equation pIb = -(1/2) * Ialpha + (sqrt(3)/2) * Ibeta */ - *pIb = -0.5f * Ialpha + 0.8660254039f * Ibeta; - } - - - /** - * @brief Inverse Clarke transform for Q31 version - * @param[in] Ialpha input two-phase orthogonal vector axis alpha - * @param[in] Ibeta input two-phase orthogonal vector axis beta - * @param[out] pIa points to output three-phase coordinate a - * @param[out] pIb points to output three-phase coordinate b - * - * Scaling and Overflow Behavior: - * \par - * The function is implemented using an internal 32-bit accumulator. - * The accumulator maintains 1.31 format by truncating lower 31 bits of the intermediate multiplication in 2.62 format. - * There is saturation on the subtraction, hence there is no risk of overflow. - */ - static __INLINE void arm_inv_clarke_q31( - q31_t Ialpha, - q31_t Ibeta, - q31_t * pIa, - q31_t * pIb) - { - q31_t product1, product2; /* Temporary variables used to store intermediate results */ - - /* Calculating pIa from Ialpha by equation pIa = Ialpha */ - *pIa = Ialpha; - - /* Intermediate product is calculated by (1/(2*sqrt(3)) * Ia) */ - product1 = (q31_t) (((q63_t) (Ialpha) * (0x40000000)) >> 31); - - /* Intermediate product is calculated by (1/sqrt(3) * pIb) */ - product2 = (q31_t) (((q63_t) (Ibeta) * (0x6ED9EBA1)) >> 31); - - /* pIb is calculated by subtracting the products */ - *pIb = __QSUB(product2, product1); - } - - /** - * @} end of inv_clarke group - */ - - /** - * @brief Converts the elements of the Q7 vector to Q15 vector. - * @param[in] pSrc input pointer - * @param[out] pDst output pointer - * @param[in] blockSize number of samples to process - */ - void arm_q7_to_q15( - q7_t * pSrc, - q15_t * pDst, - uint32_t blockSize); - - - - /** - * @ingroup groupController - */ - - /** - * @defgroup park Vector Park Transform - * - * Forward Park transform converts the input two-coordinate vector to flux and torque components. - * The Park transform can be used to realize the transformation of the Ialpha and the Ibeta currents - * from the stationary to the moving reference frame and control the spatial relationship between - * the stator vector current and rotor flux vector. - * If we consider the d axis aligned with the rotor flux, the diagram below shows the - * current vector and the relationship from the two reference frames: - * \image html park.gif "Stator current space vector and its component in (a,b) and in the d,q rotating reference frame" - * - * The function operates on a single sample of data and each call to the function returns the processed output. - * The library provides separate functions for Q31 and floating-point data types. - * \par Algorithm - * \image html parkFormula.gif - * where Ialpha and Ibeta are the stator vector components, - * pId and pIq are rotor vector components and cosVal and sinVal are the - * cosine and sine values of theta (rotor flux position). - * \par Fixed-Point Behavior - * Care must be taken when using the Q31 version of the Park transform. - * In particular, the overflow and saturation behavior of the accumulator used must be considered. - * Refer to the function specific documentation below for usage guidelines. - */ - - /** - * @addtogroup park - * @{ - */ - - /** - * @brief Floating-point Park transform - * @param[in] Ialpha input two-phase vector coordinate alpha - * @param[in] Ibeta input two-phase vector coordinate beta - * @param[out] pId points to output rotor reference frame d - * @param[out] pIq points to output rotor reference frame q - * @param[in] sinVal sine value of rotation angle theta - * @param[in] cosVal cosine value of rotation angle theta - * - * The function implements the forward Park transform. - * - */ - static __INLINE void arm_park_f32( - float32_t Ialpha, - float32_t Ibeta, - float32_t * pId, - float32_t * pIq, - float32_t sinVal, - float32_t cosVal) - { - /* Calculate pId using the equation, pId = Ialpha * cosVal + Ibeta * sinVal */ - *pId = Ialpha * cosVal + Ibeta * sinVal; - - /* Calculate pIq using the equation, pIq = - Ialpha * sinVal + Ibeta * cosVal */ - *pIq = -Ialpha * sinVal + Ibeta * cosVal; - } - - - /** - * @brief Park transform for Q31 version - * @param[in] Ialpha input two-phase vector coordinate alpha - * @param[in] Ibeta input two-phase vector coordinate beta - * @param[out] pId points to output rotor reference frame d - * @param[out] pIq points to output rotor reference frame q - * @param[in] sinVal sine value of rotation angle theta - * @param[in] cosVal cosine value of rotation angle theta - * - * Scaling and Overflow Behavior: - * \par - * The function is implemented using an internal 32-bit accumulator. - * The accumulator maintains 1.31 format by truncating lower 31 bits of the intermediate multiplication in 2.62 format. - * There is saturation on the addition and subtraction, hence there is no risk of overflow. - */ - static __INLINE void arm_park_q31( - q31_t Ialpha, - q31_t Ibeta, - q31_t * pId, - q31_t * pIq, - q31_t sinVal, - q31_t cosVal) - { - q31_t product1, product2; /* Temporary variables used to store intermediate results */ - q31_t product3, product4; /* Temporary variables used to store intermediate results */ - - /* Intermediate product is calculated by (Ialpha * cosVal) */ - product1 = (q31_t) (((q63_t) (Ialpha) * (cosVal)) >> 31); - - /* Intermediate product is calculated by (Ibeta * sinVal) */ - product2 = (q31_t) (((q63_t) (Ibeta) * (sinVal)) >> 31); - - - /* Intermediate product is calculated by (Ialpha * sinVal) */ - product3 = (q31_t) (((q63_t) (Ialpha) * (sinVal)) >> 31); - - /* Intermediate product is calculated by (Ibeta * cosVal) */ - product4 = (q31_t) (((q63_t) (Ibeta) * (cosVal)) >> 31); - - /* Calculate pId by adding the two intermediate products 1 and 2 */ - *pId = __QADD(product1, product2); - - /* Calculate pIq by subtracting the two intermediate products 3 from 4 */ - *pIq = __QSUB(product4, product3); - } - - /** - * @} end of park group - */ - - /** - * @brief Converts the elements of the Q7 vector to floating-point vector. - * @param[in] pSrc is input pointer - * @param[out] pDst is output pointer - * @param[in] blockSize is the number of samples to process - */ - void arm_q7_to_float( - q7_t * pSrc, - float32_t * pDst, - uint32_t blockSize); - - - /** - * @ingroup groupController - */ - - /** - * @defgroup inv_park Vector Inverse Park transform - * Inverse Park transform converts the input flux and torque components to two-coordinate vector. - * - * The function operates on a single sample of data and each call to the function returns the processed output. - * The library provides separate functions for Q31 and floating-point data types. - * \par Algorithm - * \image html parkInvFormula.gif - * where pIalpha and pIbeta are the stator vector components, - * Id and Iq are rotor vector components and cosVal and sinVal are the - * cosine and sine values of theta (rotor flux position). - * \par Fixed-Point Behavior - * Care must be taken when using the Q31 version of the Park transform. - * In particular, the overflow and saturation behavior of the accumulator used must be considered. - * Refer to the function specific documentation below for usage guidelines. - */ - - /** - * @addtogroup inv_park - * @{ - */ - - /** - * @brief Floating-point Inverse Park transform - * @param[in] Id input coordinate of rotor reference frame d - * @param[in] Iq input coordinate of rotor reference frame q - * @param[out] pIalpha points to output two-phase orthogonal vector axis alpha - * @param[out] pIbeta points to output two-phase orthogonal vector axis beta - * @param[in] sinVal sine value of rotation angle theta - * @param[in] cosVal cosine value of rotation angle theta - */ - static __INLINE void arm_inv_park_f32( - float32_t Id, - float32_t Iq, - float32_t * pIalpha, - float32_t * pIbeta, - float32_t sinVal, - float32_t cosVal) - { - /* Calculate pIalpha using the equation, pIalpha = Id * cosVal - Iq * sinVal */ - *pIalpha = Id * cosVal - Iq * sinVal; - - /* Calculate pIbeta using the equation, pIbeta = Id * sinVal + Iq * cosVal */ - *pIbeta = Id * sinVal + Iq * cosVal; - } - - - /** - * @brief Inverse Park transform for Q31 version - * @param[in] Id input coordinate of rotor reference frame d - * @param[in] Iq input coordinate of rotor reference frame q - * @param[out] pIalpha points to output two-phase orthogonal vector axis alpha - * @param[out] pIbeta points to output two-phase orthogonal vector axis beta - * @param[in] sinVal sine value of rotation angle theta - * @param[in] cosVal cosine value of rotation angle theta - * - * Scaling and Overflow Behavior: - * \par - * The function is implemented using an internal 32-bit accumulator. - * The accumulator maintains 1.31 format by truncating lower 31 bits of the intermediate multiplication in 2.62 format. - * There is saturation on the addition, hence there is no risk of overflow. - */ - static __INLINE void arm_inv_park_q31( - q31_t Id, - q31_t Iq, - q31_t * pIalpha, - q31_t * pIbeta, - q31_t sinVal, - q31_t cosVal) - { - q31_t product1, product2; /* Temporary variables used to store intermediate results */ - q31_t product3, product4; /* Temporary variables used to store intermediate results */ - - /* Intermediate product is calculated by (Id * cosVal) */ - product1 = (q31_t) (((q63_t) (Id) * (cosVal)) >> 31); - - /* Intermediate product is calculated by (Iq * sinVal) */ - product2 = (q31_t) (((q63_t) (Iq) * (sinVal)) >> 31); - - - /* Intermediate product is calculated by (Id * sinVal) */ - product3 = (q31_t) (((q63_t) (Id) * (sinVal)) >> 31); - - /* Intermediate product is calculated by (Iq * cosVal) */ - product4 = (q31_t) (((q63_t) (Iq) * (cosVal)) >> 31); - - /* Calculate pIalpha by using the two intermediate products 1 and 2 */ - *pIalpha = __QSUB(product1, product2); - - /* Calculate pIbeta by using the two intermediate products 3 and 4 */ - *pIbeta = __QADD(product4, product3); - } - - /** - * @} end of Inverse park group - */ - - - /** - * @brief Converts the elements of the Q31 vector to floating-point vector. - * @param[in] pSrc is input pointer - * @param[out] pDst is output pointer - * @param[in] blockSize is the number of samples to process - */ - void arm_q31_to_float( - q31_t * pSrc, - float32_t * pDst, - uint32_t blockSize); - - /** - * @ingroup groupInterpolation - */ - - /** - * @defgroup LinearInterpolate Linear Interpolation - * - * Linear interpolation is a method of curve fitting using linear polynomials. - * Linear interpolation works by effectively drawing a straight line between two neighboring samples and returning the appropriate point along that line - * - * \par - * \image html LinearInterp.gif "Linear interpolation" - * - * \par - * A Linear Interpolate function calculates an output value(y), for the input(x) - * using linear interpolation of the input values x0, x1( nearest input values) and the output values y0 and y1(nearest output values) - * - * \par Algorithm: - *
-   *       y = y0 + (x - x0) * ((y1 - y0)/(x1-x0))
-   *       where x0, x1 are nearest values of input x
-   *             y0, y1 are nearest values to output y
-   * 
- * - * \par - * This set of functions implements Linear interpolation process - * for Q7, Q15, Q31, and floating-point data types. The functions operate on a single - * sample of data and each call to the function returns a single processed value. - * S points to an instance of the Linear Interpolate function data structure. - * x is the input sample value. The functions returns the output value. - * - * \par - * if x is outside of the table boundary, Linear interpolation returns first value of the table - * if x is below input range and returns last value of table if x is above range. - */ - - /** - * @addtogroup LinearInterpolate - * @{ - */ - - /** - * @brief Process function for the floating-point Linear Interpolation Function. - * @param[in,out] S is an instance of the floating-point Linear Interpolation structure - * @param[in] x input sample to process - * @return y processed output sample. - * - */ - static __INLINE float32_t arm_linear_interp_f32( - arm_linear_interp_instance_f32 * S, - float32_t x) - { - float32_t y; - float32_t x0, x1; /* Nearest input values */ - float32_t y0, y1; /* Nearest output values */ - float32_t xSpacing = S->xSpacing; /* spacing between input values */ - int32_t i; /* Index variable */ - float32_t *pYData = S->pYData; /* pointer to output table */ - - /* Calculation of index */ - i = (int32_t) ((x - S->x1) / xSpacing); - - if(i < 0) - { - /* Iniatilize output for below specified range as least output value of table */ - y = pYData[0]; - } - else if((uint32_t)i >= S->nValues) - { - /* Iniatilize output for above specified range as last output value of table */ - y = pYData[S->nValues - 1]; - } - else - { - /* Calculation of nearest input values */ - x0 = S->x1 + i * xSpacing; - x1 = S->x1 + (i + 1) * xSpacing; - - /* Read of nearest output values */ - y0 = pYData[i]; - y1 = pYData[i + 1]; - - /* Calculation of output */ - y = y0 + (x - x0) * ((y1 - y0) / (x1 - x0)); - - } - - /* returns output value */ - return (y); - } - - - /** - * - * @brief Process function for the Q31 Linear Interpolation Function. - * @param[in] pYData pointer to Q31 Linear Interpolation table - * @param[in] x input sample to process - * @param[in] nValues number of table values - * @return y processed output sample. - * - * \par - * Input sample x is in 12.20 format which contains 12 bits for table index and 20 bits for fractional part. - * This function can support maximum of table size 2^12. - * - */ - static __INLINE q31_t arm_linear_interp_q31( - q31_t * pYData, - q31_t x, - uint32_t nValues) - { - q31_t y; /* output */ - q31_t y0, y1; /* Nearest output values */ - q31_t fract; /* fractional part */ - int32_t index; /* Index to read nearest output values */ - - /* Input is in 12.20 format */ - /* 12 bits for the table index */ - /* Index value calculation */ - index = ((x & (q31_t)0xFFF00000) >> 20); - - if(index >= (int32_t)(nValues - 1)) - { - return (pYData[nValues - 1]); - } - else if(index < 0) - { - return (pYData[0]); - } - else - { - /* 20 bits for the fractional part */ - /* shift left by 11 to keep fract in 1.31 format */ - fract = (x & 0x000FFFFF) << 11; - - /* Read two nearest output values from the index in 1.31(q31) format */ - y0 = pYData[index]; - y1 = pYData[index + 1]; - - /* Calculation of y0 * (1-fract) and y is in 2.30 format */ - y = ((q31_t) ((q63_t) y0 * (0x7FFFFFFF - fract) >> 32)); - - /* Calculation of y0 * (1-fract) + y1 *fract and y is in 2.30 format */ - y += ((q31_t) (((q63_t) y1 * fract) >> 32)); - - /* Convert y to 1.31 format */ - return (y << 1u); - } - } - - - /** - * - * @brief Process function for the Q15 Linear Interpolation Function. - * @param[in] pYData pointer to Q15 Linear Interpolation table - * @param[in] x input sample to process - * @param[in] nValues number of table values - * @return y processed output sample. - * - * \par - * Input sample x is in 12.20 format which contains 12 bits for table index and 20 bits for fractional part. - * This function can support maximum of table size 2^12. - * - */ - static __INLINE q15_t arm_linear_interp_q15( - q15_t * pYData, - q31_t x, - uint32_t nValues) - { - q63_t y; /* output */ - q15_t y0, y1; /* Nearest output values */ - q31_t fract; /* fractional part */ - int32_t index; /* Index to read nearest output values */ - - /* Input is in 12.20 format */ - /* 12 bits for the table index */ - /* Index value calculation */ - index = ((x & (int32_t)0xFFF00000) >> 20); - - if(index >= (int32_t)(nValues - 1)) - { - return (pYData[nValues - 1]); - } - else if(index < 0) - { - return (pYData[0]); - } - else - { - /* 20 bits for the fractional part */ - /* fract is in 12.20 format */ - fract = (x & 0x000FFFFF); - - /* Read two nearest output values from the index */ - y0 = pYData[index]; - y1 = pYData[index + 1]; - - /* Calculation of y0 * (1-fract) and y is in 13.35 format */ - y = ((q63_t) y0 * (0xFFFFF - fract)); - - /* Calculation of (y0 * (1-fract) + y1 * fract) and y is in 13.35 format */ - y += ((q63_t) y1 * (fract)); - - /* convert y to 1.15 format */ - return (q15_t) (y >> 20); - } - } - - - /** - * - * @brief Process function for the Q7 Linear Interpolation Function. - * @param[in] pYData pointer to Q7 Linear Interpolation table - * @param[in] x input sample to process - * @param[in] nValues number of table values - * @return y processed output sample. - * - * \par - * Input sample x is in 12.20 format which contains 12 bits for table index and 20 bits for fractional part. - * This function can support maximum of table size 2^12. - */ - static __INLINE q7_t arm_linear_interp_q7( - q7_t * pYData, - q31_t x, - uint32_t nValues) - { - q31_t y; /* output */ - q7_t y0, y1; /* Nearest output values */ - q31_t fract; /* fractional part */ - uint32_t index; /* Index to read nearest output values */ - - /* Input is in 12.20 format */ - /* 12 bits for the table index */ - /* Index value calculation */ - if (x < 0) - { - return (pYData[0]); - } - index = (x >> 20) & 0xfff; - - if(index >= (nValues - 1)) - { - return (pYData[nValues - 1]); - } - else - { - /* 20 bits for the fractional part */ - /* fract is in 12.20 format */ - fract = (x & 0x000FFFFF); - - /* Read two nearest output values from the index and are in 1.7(q7) format */ - y0 = pYData[index]; - y1 = pYData[index + 1]; - - /* Calculation of y0 * (1-fract ) and y is in 13.27(q27) format */ - y = ((y0 * (0xFFFFF - fract))); - - /* Calculation of y1 * fract + y0 * (1-fract) and y is in 13.27(q27) format */ - y += (y1 * fract); - - /* convert y to 1.7(q7) format */ - return (q7_t) (y >> 20); - } - } - - /** - * @} end of LinearInterpolate group - */ - - /** - * @brief Fast approximation to the trigonometric sine function for floating-point data. - * @param[in] x input value in radians. - * @return sin(x). - */ - float32_t arm_sin_f32( - float32_t x); - - - /** - * @brief Fast approximation to the trigonometric sine function for Q31 data. - * @param[in] x Scaled input value in radians. - * @return sin(x). - */ - q31_t arm_sin_q31( - q31_t x); - - - /** - * @brief Fast approximation to the trigonometric sine function for Q15 data. - * @param[in] x Scaled input value in radians. - * @return sin(x). - */ - q15_t arm_sin_q15( - q15_t x); - - - /** - * @brief Fast approximation to the trigonometric cosine function for floating-point data. - * @param[in] x input value in radians. - * @return cos(x). - */ - float32_t arm_cos_f32( - float32_t x); - - - /** - * @brief Fast approximation to the trigonometric cosine function for Q31 data. - * @param[in] x Scaled input value in radians. - * @return cos(x). - */ - q31_t arm_cos_q31( - q31_t x); - - - /** - * @brief Fast approximation to the trigonometric cosine function for Q15 data. - * @param[in] x Scaled input value in radians. - * @return cos(x). - */ - q15_t arm_cos_q15( - q15_t x); - - - /** - * @ingroup groupFastMath - */ - - - /** - * @defgroup SQRT Square Root - * - * Computes the square root of a number. - * There are separate functions for Q15, Q31, and floating-point data types. - * The square root function is computed using the Newton-Raphson algorithm. - * This is an iterative algorithm of the form: - *
-   *      x1 = x0 - f(x0)/f'(x0)
-   * 
- * where x1 is the current estimate, - * x0 is the previous estimate, and - * f'(x0) is the derivative of f() evaluated at x0. - * For the square root function, the algorithm reduces to: - *
-   *     x0 = in/2                         [initial guess]
-   *     x1 = 1/2 * ( x0 + in / x0)        [each iteration]
-   * 
- */ - - - /** - * @addtogroup SQRT - * @{ - */ - - /** - * @brief Floating-point square root function. - * @param[in] in input value. - * @param[out] pOut square root of input value. - * @return The function returns ARM_MATH_SUCCESS if input value is positive value or ARM_MATH_ARGUMENT_ERROR if - * in is negative value and returns zero output for negative values. - */ - static __INLINE arm_status arm_sqrt_f32( - float32_t in, - float32_t * pOut) - { - if(in >= 0.0f) - { - -#if (__FPU_USED == 1) && defined ( __CC_ARM ) - *pOut = __sqrtf(in); -#elif (__FPU_USED == 1) && (defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)) - *pOut = __builtin_sqrtf(in); -#elif (__FPU_USED == 1) && defined(__GNUC__) - *pOut = __builtin_sqrtf(in); -#elif (__FPU_USED == 1) && defined ( __ICCARM__ ) && (__VER__ >= 6040000) - __ASM("VSQRT.F32 %0,%1" : "=t"(*pOut) : "t"(in)); -#else - *pOut = sqrtf(in); -#endif - - return (ARM_MATH_SUCCESS); - } - else - { - *pOut = 0.0f; - return (ARM_MATH_ARGUMENT_ERROR); - } - } - - - /** - * @brief Q31 square root function. - * @param[in] in input value. The range of the input value is [0 +1) or 0x00000000 to 0x7FFFFFFF. - * @param[out] pOut square root of input value. - * @return The function returns ARM_MATH_SUCCESS if input value is positive value or ARM_MATH_ARGUMENT_ERROR if - * in is negative value and returns zero output for negative values. - */ - arm_status arm_sqrt_q31( - q31_t in, - q31_t * pOut); - - - /** - * @brief Q15 square root function. - * @param[in] in input value. The range of the input value is [0 +1) or 0x0000 to 0x7FFF. - * @param[out] pOut square root of input value. - * @return The function returns ARM_MATH_SUCCESS if input value is positive value or ARM_MATH_ARGUMENT_ERROR if - * in is negative value and returns zero output for negative values. - */ - arm_status arm_sqrt_q15( - q15_t in, - q15_t * pOut); - - /** - * @} end of SQRT group - */ - - - /** - * @brief floating-point Circular write function. - */ - static __INLINE void arm_circularWrite_f32( - int32_t * circBuffer, - int32_t L, - uint16_t * writeOffset, - int32_t bufferInc, - const int32_t * src, - int32_t srcInc, - uint32_t blockSize) - { - uint32_t i = 0u; - int32_t wOffset; - - /* Copy the value of Index pointer that points - * to the current location where the input samples to be copied */ - wOffset = *writeOffset; - - /* Loop over the blockSize */ - i = blockSize; - - while(i > 0u) - { - /* copy the input sample to the circular buffer */ - circBuffer[wOffset] = *src; - - /* Update the input pointer */ - src += srcInc; - - /* Circularly update wOffset. Watch out for positive and negative value */ - wOffset += bufferInc; - if(wOffset >= L) - wOffset -= L; - - /* Decrement the loop counter */ - i--; - } - - /* Update the index pointer */ - *writeOffset = (uint16_t)wOffset; - } - - - - /** - * @brief floating-point Circular Read function. - */ - static __INLINE void arm_circularRead_f32( - int32_t * circBuffer, - int32_t L, - int32_t * readOffset, - int32_t bufferInc, - int32_t * dst, - int32_t * dst_base, - int32_t dst_length, - int32_t dstInc, - uint32_t blockSize) - { - uint32_t i = 0u; - int32_t rOffset, dst_end; - - /* Copy the value of Index pointer that points - * to the current location from where the input samples to be read */ - rOffset = *readOffset; - dst_end = (int32_t) (dst_base + dst_length); - - /* Loop over the blockSize */ - i = blockSize; - - while(i > 0u) - { - /* copy the sample from the circular buffer to the destination buffer */ - *dst = circBuffer[rOffset]; - - /* Update the input pointer */ - dst += dstInc; - - if(dst == (int32_t *) dst_end) - { - dst = dst_base; - } - - /* Circularly update rOffset. Watch out for positive and negative value */ - rOffset += bufferInc; - - if(rOffset >= L) - { - rOffset -= L; - } - - /* Decrement the loop counter */ - i--; - } - - /* Update the index pointer */ - *readOffset = rOffset; - } - - - /** - * @brief Q15 Circular write function. - */ - static __INLINE void arm_circularWrite_q15( - q15_t * circBuffer, - int32_t L, - uint16_t * writeOffset, - int32_t bufferInc, - const q15_t * src, - int32_t srcInc, - uint32_t blockSize) - { - uint32_t i = 0u; - int32_t wOffset; - - /* Copy the value of Index pointer that points - * to the current location where the input samples to be copied */ - wOffset = *writeOffset; - - /* Loop over the blockSize */ - i = blockSize; - - while(i > 0u) - { - /* copy the input sample to the circular buffer */ - circBuffer[wOffset] = *src; - - /* Update the input pointer */ - src += srcInc; - - /* Circularly update wOffset. Watch out for positive and negative value */ - wOffset += bufferInc; - if(wOffset >= L) - wOffset -= L; - - /* Decrement the loop counter */ - i--; - } - - /* Update the index pointer */ - *writeOffset = (uint16_t)wOffset; - } - - - /** - * @brief Q15 Circular Read function. - */ - static __INLINE void arm_circularRead_q15( - q15_t * circBuffer, - int32_t L, - int32_t * readOffset, - int32_t bufferInc, - q15_t * dst, - q15_t * dst_base, - int32_t dst_length, - int32_t dstInc, - uint32_t blockSize) - { - uint32_t i = 0; - int32_t rOffset, dst_end; - - /* Copy the value of Index pointer that points - * to the current location from where the input samples to be read */ - rOffset = *readOffset; - - dst_end = (int32_t) (dst_base + dst_length); - - /* Loop over the blockSize */ - i = blockSize; - - while(i > 0u) - { - /* copy the sample from the circular buffer to the destination buffer */ - *dst = circBuffer[rOffset]; - - /* Update the input pointer */ - dst += dstInc; - - if(dst == (q15_t *) dst_end) - { - dst = dst_base; - } - - /* Circularly update wOffset. Watch out for positive and negative value */ - rOffset += bufferInc; - - if(rOffset >= L) - { - rOffset -= L; - } - - /* Decrement the loop counter */ - i--; - } - - /* Update the index pointer */ - *readOffset = rOffset; - } - - - /** - * @brief Q7 Circular write function. - */ - static __INLINE void arm_circularWrite_q7( - q7_t * circBuffer, - int32_t L, - uint16_t * writeOffset, - int32_t bufferInc, - const q7_t * src, - int32_t srcInc, - uint32_t blockSize) - { - uint32_t i = 0u; - int32_t wOffset; - - /* Copy the value of Index pointer that points - * to the current location where the input samples to be copied */ - wOffset = *writeOffset; - - /* Loop over the blockSize */ - i = blockSize; - - while(i > 0u) - { - /* copy the input sample to the circular buffer */ - circBuffer[wOffset] = *src; - - /* Update the input pointer */ - src += srcInc; - - /* Circularly update wOffset. Watch out for positive and negative value */ - wOffset += bufferInc; - if(wOffset >= L) - wOffset -= L; - - /* Decrement the loop counter */ - i--; - } - - /* Update the index pointer */ - *writeOffset = (uint16_t)wOffset; - } - - - /** - * @brief Q7 Circular Read function. - */ - static __INLINE void arm_circularRead_q7( - q7_t * circBuffer, - int32_t L, - int32_t * readOffset, - int32_t bufferInc, - q7_t * dst, - q7_t * dst_base, - int32_t dst_length, - int32_t dstInc, - uint32_t blockSize) - { - uint32_t i = 0; - int32_t rOffset, dst_end; - - /* Copy the value of Index pointer that points - * to the current location from where the input samples to be read */ - rOffset = *readOffset; - - dst_end = (int32_t) (dst_base + dst_length); - - /* Loop over the blockSize */ - i = blockSize; - - while(i > 0u) - { - /* copy the sample from the circular buffer to the destination buffer */ - *dst = circBuffer[rOffset]; - - /* Update the input pointer */ - dst += dstInc; - - if(dst == (q7_t *) dst_end) - { - dst = dst_base; - } - - /* Circularly update rOffset. Watch out for positive and negative value */ - rOffset += bufferInc; - - if(rOffset >= L) - { - rOffset -= L; - } - - /* Decrement the loop counter */ - i--; - } - - /* Update the index pointer */ - *readOffset = rOffset; - } - - - /** - * @brief Sum of the squares of the elements of a Q31 vector. - * @param[in] pSrc is input pointer - * @param[in] blockSize is the number of samples to process - * @param[out] pResult is output value. - */ - void arm_power_q31( - q31_t * pSrc, - uint32_t blockSize, - q63_t * pResult); - - - /** - * @brief Sum of the squares of the elements of a floating-point vector. - * @param[in] pSrc is input pointer - * @param[in] blockSize is the number of samples to process - * @param[out] pResult is output value. - */ - void arm_power_f32( - float32_t * pSrc, - uint32_t blockSize, - float32_t * pResult); - - - /** - * @brief Sum of the squares of the elements of a Q15 vector. - * @param[in] pSrc is input pointer - * @param[in] blockSize is the number of samples to process - * @param[out] pResult is output value. - */ - void arm_power_q15( - q15_t * pSrc, - uint32_t blockSize, - q63_t * pResult); - - - /** - * @brief Sum of the squares of the elements of a Q7 vector. - * @param[in] pSrc is input pointer - * @param[in] blockSize is the number of samples to process - * @param[out] pResult is output value. - */ - void arm_power_q7( - q7_t * pSrc, - uint32_t blockSize, - q31_t * pResult); - - - /** - * @brief Mean value of a Q7 vector. - * @param[in] pSrc is input pointer - * @param[in] blockSize is the number of samples to process - * @param[out] pResult is output value. - */ - void arm_mean_q7( - q7_t * pSrc, - uint32_t blockSize, - q7_t * pResult); - - - /** - * @brief Mean value of a Q15 vector. - * @param[in] pSrc is input pointer - * @param[in] blockSize is the number of samples to process - * @param[out] pResult is output value. - */ - void arm_mean_q15( - q15_t * pSrc, - uint32_t blockSize, - q15_t * pResult); - - - /** - * @brief Mean value of a Q31 vector. - * @param[in] pSrc is input pointer - * @param[in] blockSize is the number of samples to process - * @param[out] pResult is output value. - */ - void arm_mean_q31( - q31_t * pSrc, - uint32_t blockSize, - q31_t * pResult); - - - /** - * @brief Mean value of a floating-point vector. - * @param[in] pSrc is input pointer - * @param[in] blockSize is the number of samples to process - * @param[out] pResult is output value. - */ - void arm_mean_f32( - float32_t * pSrc, - uint32_t blockSize, - float32_t * pResult); - - - /** - * @brief Variance of the elements of a floating-point vector. - * @param[in] pSrc is input pointer - * @param[in] blockSize is the number of samples to process - * @param[out] pResult is output value. - */ - void arm_var_f32( - float32_t * pSrc, - uint32_t blockSize, - float32_t * pResult); - - - /** - * @brief Variance of the elements of a Q31 vector. - * @param[in] pSrc is input pointer - * @param[in] blockSize is the number of samples to process - * @param[out] pResult is output value. - */ - void arm_var_q31( - q31_t * pSrc, - uint32_t blockSize, - q31_t * pResult); - - - /** - * @brief Variance of the elements of a Q15 vector. - * @param[in] pSrc is input pointer - * @param[in] blockSize is the number of samples to process - * @param[out] pResult is output value. - */ - void arm_var_q15( - q15_t * pSrc, - uint32_t blockSize, - q15_t * pResult); - - - /** - * @brief Root Mean Square of the elements of a floating-point vector. - * @param[in] pSrc is input pointer - * @param[in] blockSize is the number of samples to process - * @param[out] pResult is output value. - */ - void arm_rms_f32( - float32_t * pSrc, - uint32_t blockSize, - float32_t * pResult); - - - /** - * @brief Root Mean Square of the elements of a Q31 vector. - * @param[in] pSrc is input pointer - * @param[in] blockSize is the number of samples to process - * @param[out] pResult is output value. - */ - void arm_rms_q31( - q31_t * pSrc, - uint32_t blockSize, - q31_t * pResult); - - - /** - * @brief Root Mean Square of the elements of a Q15 vector. - * @param[in] pSrc is input pointer - * @param[in] blockSize is the number of samples to process - * @param[out] pResult is output value. - */ - void arm_rms_q15( - q15_t * pSrc, - uint32_t blockSize, - q15_t * pResult); - - - /** - * @brief Standard deviation of the elements of a floating-point vector. - * @param[in] pSrc is input pointer - * @param[in] blockSize is the number of samples to process - * @param[out] pResult is output value. - */ - void arm_std_f32( - float32_t * pSrc, - uint32_t blockSize, - float32_t * pResult); - - - /** - * @brief Standard deviation of the elements of a Q31 vector. - * @param[in] pSrc is input pointer - * @param[in] blockSize is the number of samples to process - * @param[out] pResult is output value. - */ - void arm_std_q31( - q31_t * pSrc, - uint32_t blockSize, - q31_t * pResult); - - - /** - * @brief Standard deviation of the elements of a Q15 vector. - * @param[in] pSrc is input pointer - * @param[in] blockSize is the number of samples to process - * @param[out] pResult is output value. - */ - void arm_std_q15( - q15_t * pSrc, - uint32_t blockSize, - q15_t * pResult); - - - /** - * @brief Floating-point complex magnitude - * @param[in] pSrc points to the complex input vector - * @param[out] pDst points to the real output vector - * @param[in] numSamples number of complex samples in the input vector - */ - void arm_cmplx_mag_f32( - float32_t * pSrc, - float32_t * pDst, - uint32_t numSamples); - - - /** - * @brief Q31 complex magnitude - * @param[in] pSrc points to the complex input vector - * @param[out] pDst points to the real output vector - * @param[in] numSamples number of complex samples in the input vector - */ - void arm_cmplx_mag_q31( - q31_t * pSrc, - q31_t * pDst, - uint32_t numSamples); - - - /** - * @brief Q15 complex magnitude - * @param[in] pSrc points to the complex input vector - * @param[out] pDst points to the real output vector - * @param[in] numSamples number of complex samples in the input vector - */ - void arm_cmplx_mag_q15( - q15_t * pSrc, - q15_t * pDst, - uint32_t numSamples); - - - /** - * @brief Q15 complex dot product - * @param[in] pSrcA points to the first input vector - * @param[in] pSrcB points to the second input vector - * @param[in] numSamples number of complex samples in each vector - * @param[out] realResult real part of the result returned here - * @param[out] imagResult imaginary part of the result returned here - */ - void arm_cmplx_dot_prod_q15( - q15_t * pSrcA, - q15_t * pSrcB, - uint32_t numSamples, - q31_t * realResult, - q31_t * imagResult); - - - /** - * @brief Q31 complex dot product - * @param[in] pSrcA points to the first input vector - * @param[in] pSrcB points to the second input vector - * @param[in] numSamples number of complex samples in each vector - * @param[out] realResult real part of the result returned here - * @param[out] imagResult imaginary part of the result returned here - */ - void arm_cmplx_dot_prod_q31( - q31_t * pSrcA, - q31_t * pSrcB, - uint32_t numSamples, - q63_t * realResult, - q63_t * imagResult); - - - /** - * @brief Floating-point complex dot product - * @param[in] pSrcA points to the first input vector - * @param[in] pSrcB points to the second input vector - * @param[in] numSamples number of complex samples in each vector - * @param[out] realResult real part of the result returned here - * @param[out] imagResult imaginary part of the result returned here - */ - void arm_cmplx_dot_prod_f32( - float32_t * pSrcA, - float32_t * pSrcB, - uint32_t numSamples, - float32_t * realResult, - float32_t * imagResult); - - - /** - * @brief Q15 complex-by-real multiplication - * @param[in] pSrcCmplx points to the complex input vector - * @param[in] pSrcReal points to the real input vector - * @param[out] pCmplxDst points to the complex output vector - * @param[in] numSamples number of samples in each vector - */ - void arm_cmplx_mult_real_q15( - q15_t * pSrcCmplx, - q15_t * pSrcReal, - q15_t * pCmplxDst, - uint32_t numSamples); - - - /** - * @brief Q31 complex-by-real multiplication - * @param[in] pSrcCmplx points to the complex input vector - * @param[in] pSrcReal points to the real input vector - * @param[out] pCmplxDst points to the complex output vector - * @param[in] numSamples number of samples in each vector - */ - void arm_cmplx_mult_real_q31( - q31_t * pSrcCmplx, - q31_t * pSrcReal, - q31_t * pCmplxDst, - uint32_t numSamples); - - - /** - * @brief Floating-point complex-by-real multiplication - * @param[in] pSrcCmplx points to the complex input vector - * @param[in] pSrcReal points to the real input vector - * @param[out] pCmplxDst points to the complex output vector - * @param[in] numSamples number of samples in each vector - */ - void arm_cmplx_mult_real_f32( - float32_t * pSrcCmplx, - float32_t * pSrcReal, - float32_t * pCmplxDst, - uint32_t numSamples); - - - /** - * @brief Minimum value of a Q7 vector. - * @param[in] pSrc is input pointer - * @param[in] blockSize is the number of samples to process - * @param[out] result is output pointer - * @param[in] index is the array index of the minimum value in the input buffer. - */ - void arm_min_q7( - q7_t * pSrc, - uint32_t blockSize, - q7_t * result, - uint32_t * index); - - - /** - * @brief Minimum value of a Q15 vector. - * @param[in] pSrc is input pointer - * @param[in] blockSize is the number of samples to process - * @param[out] pResult is output pointer - * @param[in] pIndex is the array index of the minimum value in the input buffer. - */ - void arm_min_q15( - q15_t * pSrc, - uint32_t blockSize, - q15_t * pResult, - uint32_t * pIndex); - - - /** - * @brief Minimum value of a Q31 vector. - * @param[in] pSrc is input pointer - * @param[in] blockSize is the number of samples to process - * @param[out] pResult is output pointer - * @param[out] pIndex is the array index of the minimum value in the input buffer. - */ - void arm_min_q31( - q31_t * pSrc, - uint32_t blockSize, - q31_t * pResult, - uint32_t * pIndex); - - - /** - * @brief Minimum value of a floating-point vector. - * @param[in] pSrc is input pointer - * @param[in] blockSize is the number of samples to process - * @param[out] pResult is output pointer - * @param[out] pIndex is the array index of the minimum value in the input buffer. - */ - void arm_min_f32( - float32_t * pSrc, - uint32_t blockSize, - float32_t * pResult, - uint32_t * pIndex); - - -/** - * @brief Maximum value of a Q7 vector. - * @param[in] pSrc points to the input buffer - * @param[in] blockSize length of the input vector - * @param[out] pResult maximum value returned here - * @param[out] pIndex index of maximum value returned here - */ - void arm_max_q7( - q7_t * pSrc, - uint32_t blockSize, - q7_t * pResult, - uint32_t * pIndex); - - -/** - * @brief Maximum value of a Q15 vector. - * @param[in] pSrc points to the input buffer - * @param[in] blockSize length of the input vector - * @param[out] pResult maximum value returned here - * @param[out] pIndex index of maximum value returned here - */ - void arm_max_q15( - q15_t * pSrc, - uint32_t blockSize, - q15_t * pResult, - uint32_t * pIndex); - - -/** - * @brief Maximum value of a Q31 vector. - * @param[in] pSrc points to the input buffer - * @param[in] blockSize length of the input vector - * @param[out] pResult maximum value returned here - * @param[out] pIndex index of maximum value returned here - */ - void arm_max_q31( - q31_t * pSrc, - uint32_t blockSize, - q31_t * pResult, - uint32_t * pIndex); - - -/** - * @brief Maximum value of a floating-point vector. - * @param[in] pSrc points to the input buffer - * @param[in] blockSize length of the input vector - * @param[out] pResult maximum value returned here - * @param[out] pIndex index of maximum value returned here - */ - void arm_max_f32( - float32_t * pSrc, - uint32_t blockSize, - float32_t * pResult, - uint32_t * pIndex); - - - /** - * @brief Q15 complex-by-complex multiplication - * @param[in] pSrcA points to the first input vector - * @param[in] pSrcB points to the second input vector - * @param[out] pDst points to the output vector - * @param[in] numSamples number of complex samples in each vector - */ - void arm_cmplx_mult_cmplx_q15( - q15_t * pSrcA, - q15_t * pSrcB, - q15_t * pDst, - uint32_t numSamples); - - - /** - * @brief Q31 complex-by-complex multiplication - * @param[in] pSrcA points to the first input vector - * @param[in] pSrcB points to the second input vector - * @param[out] pDst points to the output vector - * @param[in] numSamples number of complex samples in each vector - */ - void arm_cmplx_mult_cmplx_q31( - q31_t * pSrcA, - q31_t * pSrcB, - q31_t * pDst, - uint32_t numSamples); - - - /** - * @brief Floating-point complex-by-complex multiplication - * @param[in] pSrcA points to the first input vector - * @param[in] pSrcB points to the second input vector - * @param[out] pDst points to the output vector - * @param[in] numSamples number of complex samples in each vector - */ - void arm_cmplx_mult_cmplx_f32( - float32_t * pSrcA, - float32_t * pSrcB, - float32_t * pDst, - uint32_t numSamples); - - - /** - * @brief Converts the elements of the floating-point vector to Q31 vector. - * @param[in] pSrc points to the floating-point input vector - * @param[out] pDst points to the Q31 output vector - * @param[in] blockSize length of the input vector - */ - void arm_float_to_q31( - float32_t * pSrc, - q31_t * pDst, - uint32_t blockSize); - - - /** - * @brief Converts the elements of the floating-point vector to Q15 vector. - * @param[in] pSrc points to the floating-point input vector - * @param[out] pDst points to the Q15 output vector - * @param[in] blockSize length of the input vector - */ - void arm_float_to_q15( - float32_t * pSrc, - q15_t * pDst, - uint32_t blockSize); - - - /** - * @brief Converts the elements of the floating-point vector to Q7 vector. - * @param[in] pSrc points to the floating-point input vector - * @param[out] pDst points to the Q7 output vector - * @param[in] blockSize length of the input vector - */ - void arm_float_to_q7( - float32_t * pSrc, - q7_t * pDst, - uint32_t blockSize); - - - /** - * @brief Converts the elements of the Q31 vector to Q15 vector. - * @param[in] pSrc is input pointer - * @param[out] pDst is output pointer - * @param[in] blockSize is the number of samples to process - */ - void arm_q31_to_q15( - q31_t * pSrc, - q15_t * pDst, - uint32_t blockSize); - - - /** - * @brief Converts the elements of the Q31 vector to Q7 vector. - * @param[in] pSrc is input pointer - * @param[out] pDst is output pointer - * @param[in] blockSize is the number of samples to process - */ - void arm_q31_to_q7( - q31_t * pSrc, - q7_t * pDst, - uint32_t blockSize); - - - /** - * @brief Converts the elements of the Q15 vector to floating-point vector. - * @param[in] pSrc is input pointer - * @param[out] pDst is output pointer - * @param[in] blockSize is the number of samples to process - */ - void arm_q15_to_float( - q15_t * pSrc, - float32_t * pDst, - uint32_t blockSize); - - - /** - * @brief Converts the elements of the Q15 vector to Q31 vector. - * @param[in] pSrc is input pointer - * @param[out] pDst is output pointer - * @param[in] blockSize is the number of samples to process - */ - void arm_q15_to_q31( - q15_t * pSrc, - q31_t * pDst, - uint32_t blockSize); - - - /** - * @brief Converts the elements of the Q15 vector to Q7 vector. - * @param[in] pSrc is input pointer - * @param[out] pDst is output pointer - * @param[in] blockSize is the number of samples to process - */ - void arm_q15_to_q7( - q15_t * pSrc, - q7_t * pDst, - uint32_t blockSize); - - - /** - * @ingroup groupInterpolation - */ - - /** - * @defgroup BilinearInterpolate Bilinear Interpolation - * - * Bilinear interpolation is an extension of linear interpolation applied to a two dimensional grid. - * The underlying function f(x, y) is sampled on a regular grid and the interpolation process - * determines values between the grid points. - * Bilinear interpolation is equivalent to two step linear interpolation, first in the x-dimension and then in the y-dimension. - * Bilinear interpolation is often used in image processing to rescale images. - * The CMSIS DSP library provides bilinear interpolation functions for Q7, Q15, Q31, and floating-point data types. - * - * Algorithm - * \par - * The instance structure used by the bilinear interpolation functions describes a two dimensional data table. - * For floating-point, the instance structure is defined as: - *
-   *   typedef struct
-   *   {
-   *     uint16_t numRows;
-   *     uint16_t numCols;
-   *     float32_t *pData;
-   * } arm_bilinear_interp_instance_f32;
-   * 
- * - * \par - * where numRows specifies the number of rows in the table; - * numCols specifies the number of columns in the table; - * and pData points to an array of size numRows*numCols values. - * The data table pTable is organized in row order and the supplied data values fall on integer indexes. - * That is, table element (x,y) is located at pTable[x + y*numCols] where x and y are integers. - * - * \par - * Let (x, y) specify the desired interpolation point. Then define: - *
-   *     XF = floor(x)
-   *     YF = floor(y)
-   * 
- * \par - * The interpolated output point is computed as: - *
-   *  f(x, y) = f(XF, YF) * (1-(x-XF)) * (1-(y-YF))
-   *           + f(XF+1, YF) * (x-XF)*(1-(y-YF))
-   *           + f(XF, YF+1) * (1-(x-XF))*(y-YF)
-   *           + f(XF+1, YF+1) * (x-XF)*(y-YF)
-   * 
- * Note that the coordinates (x, y) contain integer and fractional components. - * The integer components specify which portion of the table to use while the - * fractional components control the interpolation processor. - * - * \par - * if (x,y) are outside of the table boundary, Bilinear interpolation returns zero output. - */ - - /** - * @addtogroup BilinearInterpolate - * @{ - */ - - - /** - * - * @brief Floating-point bilinear interpolation. - * @param[in,out] S points to an instance of the interpolation structure. - * @param[in] X interpolation coordinate. - * @param[in] Y interpolation coordinate. - * @return out interpolated value. - */ - static __INLINE float32_t arm_bilinear_interp_f32( - const arm_bilinear_interp_instance_f32 * S, - float32_t X, - float32_t Y) - { - float32_t out; - float32_t f00, f01, f10, f11; - float32_t *pData = S->pData; - int32_t xIndex, yIndex, index; - float32_t xdiff, ydiff; - float32_t b1, b2, b3, b4; - - xIndex = (int32_t) X; - yIndex = (int32_t) Y; - - /* Care taken for table outside boundary */ - /* Returns zero output when values are outside table boundary */ - if(xIndex < 0 || xIndex > (S->numRows - 1) || yIndex < 0 || yIndex > (S->numCols - 1)) - { - return (0); - } - - /* Calculation of index for two nearest points in X-direction */ - index = (xIndex - 1) + (yIndex - 1) * S->numCols; - - - /* Read two nearest points in X-direction */ - f00 = pData[index]; - f01 = pData[index + 1]; - - /* Calculation of index for two nearest points in Y-direction */ - index = (xIndex - 1) + (yIndex) * S->numCols; - - - /* Read two nearest points in Y-direction */ - f10 = pData[index]; - f11 = pData[index + 1]; - - /* Calculation of intermediate values */ - b1 = f00; - b2 = f01 - f00; - b3 = f10 - f00; - b4 = f00 - f01 - f10 + f11; - - /* Calculation of fractional part in X */ - xdiff = X - xIndex; - - /* Calculation of fractional part in Y */ - ydiff = Y - yIndex; - - /* Calculation of bi-linear interpolated output */ - out = b1 + b2 * xdiff + b3 * ydiff + b4 * xdiff * ydiff; - - /* return to application */ - return (out); - } - - - /** - * - * @brief Q31 bilinear interpolation. - * @param[in,out] S points to an instance of the interpolation structure. - * @param[in] X interpolation coordinate in 12.20 format. - * @param[in] Y interpolation coordinate in 12.20 format. - * @return out interpolated value. - */ - static __INLINE q31_t arm_bilinear_interp_q31( - arm_bilinear_interp_instance_q31 * S, - q31_t X, - q31_t Y) - { - q31_t out; /* Temporary output */ - q31_t acc = 0; /* output */ - q31_t xfract, yfract; /* X, Y fractional parts */ - q31_t x1, x2, y1, y2; /* Nearest output values */ - int32_t rI, cI; /* Row and column indices */ - q31_t *pYData = S->pData; /* pointer to output table values */ - uint32_t nCols = S->numCols; /* num of rows */ - - /* Input is in 12.20 format */ - /* 12 bits for the table index */ - /* Index value calculation */ - rI = ((X & (q31_t)0xFFF00000) >> 20); - - /* Input is in 12.20 format */ - /* 12 bits for the table index */ - /* Index value calculation */ - cI = ((Y & (q31_t)0xFFF00000) >> 20); - - /* Care taken for table outside boundary */ - /* Returns zero output when values are outside table boundary */ - if(rI < 0 || rI > (S->numRows - 1) || cI < 0 || cI > (S->numCols - 1)) - { - return (0); - } - - /* 20 bits for the fractional part */ - /* shift left xfract by 11 to keep 1.31 format */ - xfract = (X & 0x000FFFFF) << 11u; - - /* Read two nearest output values from the index */ - x1 = pYData[(rI) + (int32_t)nCols * (cI) ]; - x2 = pYData[(rI) + (int32_t)nCols * (cI) + 1]; - - /* 20 bits for the fractional part */ - /* shift left yfract by 11 to keep 1.31 format */ - yfract = (Y & 0x000FFFFF) << 11u; - - /* Read two nearest output values from the index */ - y1 = pYData[(rI) + (int32_t)nCols * (cI + 1) ]; - y2 = pYData[(rI) + (int32_t)nCols * (cI + 1) + 1]; - - /* Calculation of x1 * (1-xfract ) * (1-yfract) and acc is in 3.29(q29) format */ - out = ((q31_t) (((q63_t) x1 * (0x7FFFFFFF - xfract)) >> 32)); - acc = ((q31_t) (((q63_t) out * (0x7FFFFFFF - yfract)) >> 32)); - - /* x2 * (xfract) * (1-yfract) in 3.29(q29) and adding to acc */ - out = ((q31_t) ((q63_t) x2 * (0x7FFFFFFF - yfract) >> 32)); - acc += ((q31_t) ((q63_t) out * (xfract) >> 32)); - - /* y1 * (1 - xfract) * (yfract) in 3.29(q29) and adding to acc */ - out = ((q31_t) ((q63_t) y1 * (0x7FFFFFFF - xfract) >> 32)); - acc += ((q31_t) ((q63_t) out * (yfract) >> 32)); - - /* y2 * (xfract) * (yfract) in 3.29(q29) and adding to acc */ - out = ((q31_t) ((q63_t) y2 * (xfract) >> 32)); - acc += ((q31_t) ((q63_t) out * (yfract) >> 32)); - - /* Convert acc to 1.31(q31) format */ - return ((q31_t)(acc << 2)); - } - - - /** - * @brief Q15 bilinear interpolation. - * @param[in,out] S points to an instance of the interpolation structure. - * @param[in] X interpolation coordinate in 12.20 format. - * @param[in] Y interpolation coordinate in 12.20 format. - * @return out interpolated value. - */ - static __INLINE q15_t arm_bilinear_interp_q15( - arm_bilinear_interp_instance_q15 * S, - q31_t X, - q31_t Y) - { - q63_t acc = 0; /* output */ - q31_t out; /* Temporary output */ - q15_t x1, x2, y1, y2; /* Nearest output values */ - q31_t xfract, yfract; /* X, Y fractional parts */ - int32_t rI, cI; /* Row and column indices */ - q15_t *pYData = S->pData; /* pointer to output table values */ - uint32_t nCols = S->numCols; /* num of rows */ - - /* Input is in 12.20 format */ - /* 12 bits for the table index */ - /* Index value calculation */ - rI = ((X & (q31_t)0xFFF00000) >> 20); - - /* Input is in 12.20 format */ - /* 12 bits for the table index */ - /* Index value calculation */ - cI = ((Y & (q31_t)0xFFF00000) >> 20); - - /* Care taken for table outside boundary */ - /* Returns zero output when values are outside table boundary */ - if(rI < 0 || rI > (S->numRows - 1) || cI < 0 || cI > (S->numCols - 1)) - { - return (0); - } - - /* 20 bits for the fractional part */ - /* xfract should be in 12.20 format */ - xfract = (X & 0x000FFFFF); - - /* Read two nearest output values from the index */ - x1 = pYData[((uint32_t)rI) + nCols * ((uint32_t)cI) ]; - x2 = pYData[((uint32_t)rI) + nCols * ((uint32_t)cI) + 1]; - - /* 20 bits for the fractional part */ - /* yfract should be in 12.20 format */ - yfract = (Y & 0x000FFFFF); - - /* Read two nearest output values from the index */ - y1 = pYData[((uint32_t)rI) + nCols * ((uint32_t)cI + 1) ]; - y2 = pYData[((uint32_t)rI) + nCols * ((uint32_t)cI + 1) + 1]; - - /* Calculation of x1 * (1-xfract ) * (1-yfract) and acc is in 13.51 format */ - - /* x1 is in 1.15(q15), xfract in 12.20 format and out is in 13.35 format */ - /* convert 13.35 to 13.31 by right shifting and out is in 1.31 */ - out = (q31_t) (((q63_t) x1 * (0xFFFFF - xfract)) >> 4u); - acc = ((q63_t) out * (0xFFFFF - yfract)); - - /* x2 * (xfract) * (1-yfract) in 1.51 and adding to acc */ - out = (q31_t) (((q63_t) x2 * (0xFFFFF - yfract)) >> 4u); - acc += ((q63_t) out * (xfract)); - - /* y1 * (1 - xfract) * (yfract) in 1.51 and adding to acc */ - out = (q31_t) (((q63_t) y1 * (0xFFFFF - xfract)) >> 4u); - acc += ((q63_t) out * (yfract)); - - /* y2 * (xfract) * (yfract) in 1.51 and adding to acc */ - out = (q31_t) (((q63_t) y2 * (xfract)) >> 4u); - acc += ((q63_t) out * (yfract)); - - /* acc is in 13.51 format and down shift acc by 36 times */ - /* Convert out to 1.15 format */ - return ((q15_t)(acc >> 36)); - } - - - /** - * @brief Q7 bilinear interpolation. - * @param[in,out] S points to an instance of the interpolation structure. - * @param[in] X interpolation coordinate in 12.20 format. - * @param[in] Y interpolation coordinate in 12.20 format. - * @return out interpolated value. - */ - static __INLINE q7_t arm_bilinear_interp_q7( - arm_bilinear_interp_instance_q7 * S, - q31_t X, - q31_t Y) - { - q63_t acc = 0; /* output */ - q31_t out; /* Temporary output */ - q31_t xfract, yfract; /* X, Y fractional parts */ - q7_t x1, x2, y1, y2; /* Nearest output values */ - int32_t rI, cI; /* Row and column indices */ - q7_t *pYData = S->pData; /* pointer to output table values */ - uint32_t nCols = S->numCols; /* num of rows */ - - /* Input is in 12.20 format */ - /* 12 bits for the table index */ - /* Index value calculation */ - rI = ((X & (q31_t)0xFFF00000) >> 20); - - /* Input is in 12.20 format */ - /* 12 bits for the table index */ - /* Index value calculation */ - cI = ((Y & (q31_t)0xFFF00000) >> 20); - - /* Care taken for table outside boundary */ - /* Returns zero output when values are outside table boundary */ - if(rI < 0 || rI > (S->numRows - 1) || cI < 0 || cI > (S->numCols - 1)) - { - return (0); - } - - /* 20 bits for the fractional part */ - /* xfract should be in 12.20 format */ - xfract = (X & (q31_t)0x000FFFFF); - - /* Read two nearest output values from the index */ - x1 = pYData[((uint32_t)rI) + nCols * ((uint32_t)cI) ]; - x2 = pYData[((uint32_t)rI) + nCols * ((uint32_t)cI) + 1]; - - /* 20 bits for the fractional part */ - /* yfract should be in 12.20 format */ - yfract = (Y & (q31_t)0x000FFFFF); - - /* Read two nearest output values from the index */ - y1 = pYData[((uint32_t)rI) + nCols * ((uint32_t)cI + 1) ]; - y2 = pYData[((uint32_t)rI) + nCols * ((uint32_t)cI + 1) + 1]; - - /* Calculation of x1 * (1-xfract ) * (1-yfract) and acc is in 16.47 format */ - out = ((x1 * (0xFFFFF - xfract))); - acc = (((q63_t) out * (0xFFFFF - yfract))); - - /* x2 * (xfract) * (1-yfract) in 2.22 and adding to acc */ - out = ((x2 * (0xFFFFF - yfract))); - acc += (((q63_t) out * (xfract))); - - /* y1 * (1 - xfract) * (yfract) in 2.22 and adding to acc */ - out = ((y1 * (0xFFFFF - xfract))); - acc += (((q63_t) out * (yfract))); - - /* y2 * (xfract) * (yfract) in 2.22 and adding to acc */ - out = ((y2 * (yfract))); - acc += (((q63_t) out * (xfract))); - - /* acc in 16.47 format and down shift by 40 to convert to 1.7 format */ - return ((q7_t)(acc >> 40)); - } - - /** - * @} end of BilinearInterpolate group - */ - - -/* SMMLAR */ -#define multAcc_32x32_keep32_R(a, x, y) \ - a = (q31_t) (((((q63_t) a) << 32) + ((q63_t) x * y) + 0x80000000LL ) >> 32) - -/* SMMLSR */ -#define multSub_32x32_keep32_R(a, x, y) \ - a = (q31_t) (((((q63_t) a) << 32) - ((q63_t) x * y) + 0x80000000LL ) >> 32) - -/* SMMULR */ -#define mult_32x32_keep32_R(a, x, y) \ - a = (q31_t) (((q63_t) x * y + 0x80000000LL ) >> 32) - -/* SMMLA */ -#define multAcc_32x32_keep32(a, x, y) \ - a += (q31_t) (((q63_t) x * y) >> 32) - -/* SMMLS */ -#define multSub_32x32_keep32(a, x, y) \ - a -= (q31_t) (((q63_t) x * y) >> 32) - -/* SMMUL */ -#define mult_32x32_keep32(a, x, y) \ - a = (q31_t) (((q63_t) x * y ) >> 32) - - -#if defined ( __CC_ARM ) - /* Enter low optimization region - place directly above function definition */ - #if defined( ARM_MATH_CM4 ) || defined( ARM_MATH_CM7) - #define LOW_OPTIMIZATION_ENTER \ - _Pragma ("push") \ - _Pragma ("O1") - #else - #define LOW_OPTIMIZATION_ENTER - #endif - - /* Exit low optimization region - place directly after end of function definition */ - #if defined( ARM_MATH_CM4 ) || defined( ARM_MATH_CM7) - #define LOW_OPTIMIZATION_EXIT \ - _Pragma ("pop") - #else - #define LOW_OPTIMIZATION_EXIT - #endif - - /* Enter low optimization region - place directly above function definition */ - #define IAR_ONLY_LOW_OPTIMIZATION_ENTER - - /* Exit low optimization region - place directly after end of function definition */ - #define IAR_ONLY_LOW_OPTIMIZATION_EXIT - -#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #define LOW_OPTIMIZATION_ENTER - #define LOW_OPTIMIZATION_EXIT - #define IAR_ONLY_LOW_OPTIMIZATION_ENTER - #define IAR_ONLY_LOW_OPTIMIZATION_EXIT - -#elif defined(__GNUC__) - #define LOW_OPTIMIZATION_ENTER __attribute__(( optimize("-O1") )) - #define LOW_OPTIMIZATION_EXIT - #define IAR_ONLY_LOW_OPTIMIZATION_ENTER - #define IAR_ONLY_LOW_OPTIMIZATION_EXIT - -#elif defined(__ICCARM__) - /* Enter low optimization region - place directly above function definition */ - #if defined( ARM_MATH_CM4 ) || defined( ARM_MATH_CM7) - #define LOW_OPTIMIZATION_ENTER \ - _Pragma ("optimize=low") - #else - #define LOW_OPTIMIZATION_ENTER - #endif - - /* Exit low optimization region - place directly after end of function definition */ - #define LOW_OPTIMIZATION_EXIT - - /* Enter low optimization region - place directly above function definition */ - #if defined( ARM_MATH_CM4 ) || defined( ARM_MATH_CM7) - #define IAR_ONLY_LOW_OPTIMIZATION_ENTER \ - _Pragma ("optimize=low") - #else - #define IAR_ONLY_LOW_OPTIMIZATION_ENTER - #endif - - /* Exit low optimization region - place directly after end of function definition */ - #define IAR_ONLY_LOW_OPTIMIZATION_EXIT - -#elif defined(__CSMC__) - #define LOW_OPTIMIZATION_ENTER - #define LOW_OPTIMIZATION_EXIT - #define IAR_ONLY_LOW_OPTIMIZATION_ENTER - #define IAR_ONLY_LOW_OPTIMIZATION_EXIT - -#elif defined(__TASKING__) - #define LOW_OPTIMIZATION_ENTER - #define LOW_OPTIMIZATION_EXIT - #define IAR_ONLY_LOW_OPTIMIZATION_ENTER - #define IAR_ONLY_LOW_OPTIMIZATION_EXIT - -#endif - - -#ifdef __cplusplus -} -#endif - - -#if defined ( __GNUC__ ) -#pragma GCC diagnostic pop -#endif - -#endif /* _ARM_MATH_H */ - -/** - * - * End of file. - */ diff --git a/body/board/inc/cmsis_armcc.h b/body/board/inc/cmsis_armcc.h deleted file mode 100644 index 4d9d064..0000000 --- a/body/board/inc/cmsis_armcc.h +++ /dev/null @@ -1,865 +0,0 @@ -/**************************************************************************//** - * @file cmsis_armcc.h - * @brief CMSIS compiler ARMCC (Arm Compiler 5) header file - * @version V5.0.4 - * @date 10. January 2018 - ******************************************************************************/ -/* - * Copyright (c) 2009-2018 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#ifndef __CMSIS_ARMCC_H -#define __CMSIS_ARMCC_H - - -#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 400677) - #error "Please use Arm Compiler Toolchain V4.0.677 or later!" -#endif - -/* CMSIS compiler control architecture macros */ -#if ((defined (__TARGET_ARCH_6_M ) && (__TARGET_ARCH_6_M == 1)) || \ - (defined (__TARGET_ARCH_6S_M ) && (__TARGET_ARCH_6S_M == 1)) ) - #define __ARM_ARCH_6M__ 1 -#endif - -#if (defined (__TARGET_ARCH_7_M ) && (__TARGET_ARCH_7_M == 1)) - #define __ARM_ARCH_7M__ 1 -#endif - -#if (defined (__TARGET_ARCH_7E_M) && (__TARGET_ARCH_7E_M == 1)) - #define __ARM_ARCH_7EM__ 1 -#endif - - /* __ARM_ARCH_8M_BASE__ not applicable */ - /* __ARM_ARCH_8M_MAIN__ not applicable */ - - -/* CMSIS compiler specific defines */ -#ifndef __ASM - #define __ASM __asm -#endif -#ifndef __INLINE - #define __INLINE __inline -#endif -#ifndef __STATIC_INLINE - #define __STATIC_INLINE static __inline -#endif -#ifndef __STATIC_FORCEINLINE - #define __STATIC_FORCEINLINE static __forceinline -#endif -#ifndef __NO_RETURN - #define __NO_RETURN __declspec(noreturn) -#endif -#ifndef __USED - #define __USED __attribute__((used)) -#endif -#ifndef __WEAK - #define __WEAK __attribute__((weak)) -#endif -#ifndef __PACKED - #define __PACKED __attribute__((packed)) -#endif -#ifndef __PACKED_STRUCT - #define __PACKED_STRUCT __packed struct -#endif -#ifndef __PACKED_UNION - #define __PACKED_UNION __packed union -#endif -#ifndef __UNALIGNED_UINT32 /* deprecated */ - #define __UNALIGNED_UINT32(x) (*((__packed uint32_t *)(x))) -#endif -#ifndef __UNALIGNED_UINT16_WRITE - #define __UNALIGNED_UINT16_WRITE(addr, val) ((*((__packed uint16_t *)(addr))) = (val)) -#endif -#ifndef __UNALIGNED_UINT16_READ - #define __UNALIGNED_UINT16_READ(addr) (*((const __packed uint16_t *)(addr))) -#endif -#ifndef __UNALIGNED_UINT32_WRITE - #define __UNALIGNED_UINT32_WRITE(addr, val) ((*((__packed uint32_t *)(addr))) = (val)) -#endif -#ifndef __UNALIGNED_UINT32_READ - #define __UNALIGNED_UINT32_READ(addr) (*((const __packed uint32_t *)(addr))) -#endif -#ifndef __ALIGNED - #define __ALIGNED(x) __attribute__((aligned(x))) -#endif -#ifndef __RESTRICT - #define __RESTRICT __restrict -#endif - -/* ########################### Core Function Access ########################### */ -/** \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions - @{ - */ - -/** - \brief Enable IRQ Interrupts - \details Enables IRQ interrupts by clearing the I-bit in the CPSR. - Can only be executed in Privileged modes. - */ -/* intrinsic void __enable_irq(); */ - - -/** - \brief Disable IRQ Interrupts - \details Disables IRQ interrupts by setting the I-bit in the CPSR. - Can only be executed in Privileged modes. - */ -/* intrinsic void __disable_irq(); */ - -/** - \brief Get Control Register - \details Returns the content of the Control Register. - \return Control Register value - */ -__STATIC_INLINE uint32_t __get_CONTROL(void) -{ - register uint32_t __regControl __ASM("control"); - return(__regControl); -} - - -/** - \brief Set Control Register - \details Writes the given value to the Control Register. - \param [in] control Control Register value to set - */ -__STATIC_INLINE void __set_CONTROL(uint32_t control) -{ - register uint32_t __regControl __ASM("control"); - __regControl = control; -} - - -/** - \brief Get IPSR Register - \details Returns the content of the IPSR Register. - \return IPSR Register value - */ -__STATIC_INLINE uint32_t __get_IPSR(void) -{ - register uint32_t __regIPSR __ASM("ipsr"); - return(__regIPSR); -} - - -/** - \brief Get APSR Register - \details Returns the content of the APSR Register. - \return APSR Register value - */ -__STATIC_INLINE uint32_t __get_APSR(void) -{ - register uint32_t __regAPSR __ASM("apsr"); - return(__regAPSR); -} - - -/** - \brief Get xPSR Register - \details Returns the content of the xPSR Register. - \return xPSR Register value - */ -__STATIC_INLINE uint32_t __get_xPSR(void) -{ - register uint32_t __regXPSR __ASM("xpsr"); - return(__regXPSR); -} - - -/** - \brief Get Process Stack Pointer - \details Returns the current value of the Process Stack Pointer (PSP). - \return PSP Register value - */ -__STATIC_INLINE uint32_t __get_PSP(void) -{ - register uint32_t __regProcessStackPointer __ASM("psp"); - return(__regProcessStackPointer); -} - - -/** - \brief Set Process Stack Pointer - \details Assigns the given value to the Process Stack Pointer (PSP). - \param [in] topOfProcStack Process Stack Pointer value to set - */ -__STATIC_INLINE void __set_PSP(uint32_t topOfProcStack) -{ - register uint32_t __regProcessStackPointer __ASM("psp"); - __regProcessStackPointer = topOfProcStack; -} - - -/** - \brief Get Main Stack Pointer - \details Returns the current value of the Main Stack Pointer (MSP). - \return MSP Register value - */ -__STATIC_INLINE uint32_t __get_MSP(void) -{ - register uint32_t __regMainStackPointer __ASM("msp"); - return(__regMainStackPointer); -} - - -/** - \brief Set Main Stack Pointer - \details Assigns the given value to the Main Stack Pointer (MSP). - \param [in] topOfMainStack Main Stack Pointer value to set - */ -__STATIC_INLINE void __set_MSP(uint32_t topOfMainStack) -{ - register uint32_t __regMainStackPointer __ASM("msp"); - __regMainStackPointer = topOfMainStack; -} - - -/** - \brief Get Priority Mask - \details Returns the current state of the priority mask bit from the Priority Mask Register. - \return Priority Mask value - */ -__STATIC_INLINE uint32_t __get_PRIMASK(void) -{ - register uint32_t __regPriMask __ASM("primask"); - return(__regPriMask); -} - - -/** - \brief Set Priority Mask - \details Assigns the given value to the Priority Mask Register. - \param [in] priMask Priority Mask - */ -__STATIC_INLINE void __set_PRIMASK(uint32_t priMask) -{ - register uint32_t __regPriMask __ASM("primask"); - __regPriMask = (priMask); -} - - -#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) - -/** - \brief Enable FIQ - \details Enables FIQ interrupts by clearing the F-bit in the CPSR. - Can only be executed in Privileged modes. - */ -#define __enable_fault_irq __enable_fiq - - -/** - \brief Disable FIQ - \details Disables FIQ interrupts by setting the F-bit in the CPSR. - Can only be executed in Privileged modes. - */ -#define __disable_fault_irq __disable_fiq - - -/** - \brief Get Base Priority - \details Returns the current value of the Base Priority register. - \return Base Priority register value - */ -__STATIC_INLINE uint32_t __get_BASEPRI(void) -{ - register uint32_t __regBasePri __ASM("basepri"); - return(__regBasePri); -} - - -/** - \brief Set Base Priority - \details Assigns the given value to the Base Priority register. - \param [in] basePri Base Priority value to set - */ -__STATIC_INLINE void __set_BASEPRI(uint32_t basePri) -{ - register uint32_t __regBasePri __ASM("basepri"); - __regBasePri = (basePri & 0xFFU); -} - - -/** - \brief Set Base Priority with condition - \details Assigns the given value to the Base Priority register only if BASEPRI masking is disabled, - or the new value increases the BASEPRI priority level. - \param [in] basePri Base Priority value to set - */ -__STATIC_INLINE void __set_BASEPRI_MAX(uint32_t basePri) -{ - register uint32_t __regBasePriMax __ASM("basepri_max"); - __regBasePriMax = (basePri & 0xFFU); -} - - -/** - \brief Get Fault Mask - \details Returns the current value of the Fault Mask register. - \return Fault Mask register value - */ -__STATIC_INLINE uint32_t __get_FAULTMASK(void) -{ - register uint32_t __regFaultMask __ASM("faultmask"); - return(__regFaultMask); -} - - -/** - \brief Set Fault Mask - \details Assigns the given value to the Fault Mask register. - \param [in] faultMask Fault Mask value to set - */ -__STATIC_INLINE void __set_FAULTMASK(uint32_t faultMask) -{ - register uint32_t __regFaultMask __ASM("faultmask"); - __regFaultMask = (faultMask & (uint32_t)1U); -} - -#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) */ - - -/** - \brief Get FPSCR - \details Returns the current value of the Floating Point Status/Control register. - \return Floating Point Status/Control register value - */ -__STATIC_INLINE uint32_t __get_FPSCR(void) -{ -#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ - (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) - register uint32_t __regfpscr __ASM("fpscr"); - return(__regfpscr); -#else - return(0U); -#endif -} - - -/** - \brief Set FPSCR - \details Assigns the given value to the Floating Point Status/Control register. - \param [in] fpscr Floating Point Status/Control value to set - */ -__STATIC_INLINE void __set_FPSCR(uint32_t fpscr) -{ -#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ - (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) - register uint32_t __regfpscr __ASM("fpscr"); - __regfpscr = (fpscr); -#else - (void)fpscr; -#endif -} - - -/*@} end of CMSIS_Core_RegAccFunctions */ - - -/* ########################## Core Instruction Access ######################### */ -/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface - Access to dedicated instructions - @{ -*/ - -/** - \brief No Operation - \details No Operation does nothing. This instruction can be used for code alignment purposes. - */ -#define __NOP __nop - - -/** - \brief Wait For Interrupt - \details Wait For Interrupt is a hint instruction that suspends execution until one of a number of events occurs. - */ -#define __WFI __wfi - - -/** - \brief Wait For Event - \details Wait For Event is a hint instruction that permits the processor to enter - a low-power state until one of a number of events occurs. - */ -#define __WFE __wfe - - -/** - \brief Send Event - \details Send Event is a hint instruction. It causes an event to be signaled to the CPU. - */ -#define __SEV __sev - - -/** - \brief Instruction Synchronization Barrier - \details Instruction Synchronization Barrier flushes the pipeline in the processor, - so that all instructions following the ISB are fetched from cache or memory, - after the instruction has been completed. - */ -#define __ISB() do {\ - __schedule_barrier();\ - __isb(0xF);\ - __schedule_barrier();\ - } while (0U) - -/** - \brief Data Synchronization Barrier - \details Acts as a special kind of Data Memory Barrier. - It completes when all explicit memory accesses before this instruction complete. - */ -#define __DSB() do {\ - __schedule_barrier();\ - __dsb(0xF);\ - __schedule_barrier();\ - } while (0U) - -/** - \brief Data Memory Barrier - \details Ensures the apparent order of the explicit memory operations before - and after the instruction, without ensuring their completion. - */ -#define __DMB() do {\ - __schedule_barrier();\ - __dmb(0xF);\ - __schedule_barrier();\ - } while (0U) - - -/** - \brief Reverse byte order (32 bit) - \details Reverses the byte order in unsigned integer value. For example, 0x12345678 becomes 0x78563412. - \param [in] value Value to reverse - \return Reversed value - */ -#define __REV __rev - - -/** - \brief Reverse byte order (16 bit) - \details Reverses the byte order within each halfword of a word. For example, 0x12345678 becomes 0x34127856. - \param [in] value Value to reverse - \return Reversed value - */ -#ifndef __NO_EMBEDDED_ASM -__attribute__((section(".rev16_text"))) __STATIC_INLINE __ASM uint32_t __REV16(uint32_t value) -{ - rev16 r0, r0 - bx lr -} -#endif - - -/** - \brief Reverse byte order (16 bit) - \details Reverses the byte order in a 16-bit value and returns the signed 16-bit result. For example, 0x0080 becomes 0x8000. - \param [in] value Value to reverse - \return Reversed value - */ -#ifndef __NO_EMBEDDED_ASM -__attribute__((section(".revsh_text"))) __STATIC_INLINE __ASM int16_t __REVSH(int16_t value) -{ - revsh r0, r0 - bx lr -} -#endif - - -/** - \brief Rotate Right in unsigned value (32 bit) - \details Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits. - \param [in] op1 Value to rotate - \param [in] op2 Number of Bits to rotate - \return Rotated value - */ -#define __ROR __ror - - -/** - \brief Breakpoint - \details Causes the processor to enter Debug state. - Debug tools can use this to investigate system state when the instruction at a particular address is reached. - \param [in] value is ignored by the processor. - If required, a debugger can use it to store additional information about the breakpoint. - */ -#define __BKPT(value) __breakpoint(value) - - -/** - \brief Reverse bit order of value - \details Reverses the bit order of the given value. - \param [in] value Value to reverse - \return Reversed value - */ -#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) - #define __RBIT __rbit -#else -__attribute__((always_inline)) __STATIC_INLINE uint32_t __RBIT(uint32_t value) -{ - uint32_t result; - uint32_t s = (4U /*sizeof(v)*/ * 8U) - 1U; /* extra shift needed at end */ - - result = value; /* r will be reversed bits of v; first get LSB of v */ - for (value >>= 1U; value != 0U; value >>= 1U) - { - result <<= 1U; - result |= value & 1U; - s--; - } - result <<= s; /* shift when v's highest bits are zero */ - return result; -} -#endif - - -/** - \brief Count leading zeros - \details Counts the number of leading zeros of a data value. - \param [in] value Value to count the leading zeros - \return number of leading zeros in value - */ -#define __CLZ __clz - - -#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) - -/** - \brief LDR Exclusive (8 bit) - \details Executes a exclusive LDR instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020) - #define __LDREXB(ptr) ((uint8_t ) __ldrex(ptr)) -#else - #define __LDREXB(ptr) _Pragma("push") _Pragma("diag_suppress 3731") ((uint8_t ) __ldrex(ptr)) _Pragma("pop") -#endif - - -/** - \brief LDR Exclusive (16 bit) - \details Executes a exclusive LDR instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020) - #define __LDREXH(ptr) ((uint16_t) __ldrex(ptr)) -#else - #define __LDREXH(ptr) _Pragma("push") _Pragma("diag_suppress 3731") ((uint16_t) __ldrex(ptr)) _Pragma("pop") -#endif - - -/** - \brief LDR Exclusive (32 bit) - \details Executes a exclusive LDR instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020) - #define __LDREXW(ptr) ((uint32_t ) __ldrex(ptr)) -#else - #define __LDREXW(ptr) _Pragma("push") _Pragma("diag_suppress 3731") ((uint32_t ) __ldrex(ptr)) _Pragma("pop") -#endif - - -/** - \brief STR Exclusive (8 bit) - \details Executes a exclusive STR instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020) - #define __STREXB(value, ptr) __strex(value, ptr) -#else - #define __STREXB(value, ptr) _Pragma("push") _Pragma("diag_suppress 3731") __strex(value, ptr) _Pragma("pop") -#endif - - -/** - \brief STR Exclusive (16 bit) - \details Executes a exclusive STR instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020) - #define __STREXH(value, ptr) __strex(value, ptr) -#else - #define __STREXH(value, ptr) _Pragma("push") _Pragma("diag_suppress 3731") __strex(value, ptr) _Pragma("pop") -#endif - - -/** - \brief STR Exclusive (32 bit) - \details Executes a exclusive STR instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#if defined(__ARMCC_VERSION) && (__ARMCC_VERSION < 5060020) - #define __STREXW(value, ptr) __strex(value, ptr) -#else - #define __STREXW(value, ptr) _Pragma("push") _Pragma("diag_suppress 3731") __strex(value, ptr) _Pragma("pop") -#endif - - -/** - \brief Remove the exclusive lock - \details Removes the exclusive lock which is created by LDREX. - */ -#define __CLREX __clrex - - -/** - \brief Signed Saturate - \details Saturates a signed value. - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (1..32) - \return Saturated value - */ -#define __SSAT __ssat - - -/** - \brief Unsigned Saturate - \details Saturates an unsigned value. - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (0..31) - \return Saturated value - */ -#define __USAT __usat - - -/** - \brief Rotate Right with Extend (32 bit) - \details Moves each bit of a bitstring right by one bit. - The carry input is shifted in at the left end of the bitstring. - \param [in] value Value to rotate - \return Rotated value - */ -#ifndef __NO_EMBEDDED_ASM -__attribute__((section(".rrx_text"))) __STATIC_INLINE __ASM uint32_t __RRX(uint32_t value) -{ - rrx r0, r0 - bx lr -} -#endif - - -/** - \brief LDRT Unprivileged (8 bit) - \details Executes a Unprivileged LDRT instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -#define __LDRBT(ptr) ((uint8_t ) __ldrt(ptr)) - - -/** - \brief LDRT Unprivileged (16 bit) - \details Executes a Unprivileged LDRT instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -#define __LDRHT(ptr) ((uint16_t) __ldrt(ptr)) - - -/** - \brief LDRT Unprivileged (32 bit) - \details Executes a Unprivileged LDRT instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -#define __LDRT(ptr) ((uint32_t ) __ldrt(ptr)) - - -/** - \brief STRT Unprivileged (8 bit) - \details Executes a Unprivileged STRT instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -#define __STRBT(value, ptr) __strt(value, ptr) - - -/** - \brief STRT Unprivileged (16 bit) - \details Executes a Unprivileged STRT instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -#define __STRHT(value, ptr) __strt(value, ptr) - - -/** - \brief STRT Unprivileged (32 bit) - \details Executes a Unprivileged STRT instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -#define __STRT(value, ptr) __strt(value, ptr) - -#else /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) */ - -/** - \brief Signed Saturate - \details Saturates a signed value. - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (1..32) - \return Saturated value - */ -__attribute__((always_inline)) __STATIC_INLINE int32_t __SSAT(int32_t val, uint32_t sat) -{ - if ((sat >= 1U) && (sat <= 32U)) - { - const int32_t max = (int32_t)((1U << (sat - 1U)) - 1U); - const int32_t min = -1 - max ; - if (val > max) - { - return max; - } - else if (val < min) - { - return min; - } - } - return val; -} - -/** - \brief Unsigned Saturate - \details Saturates an unsigned value. - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (0..31) - \return Saturated value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __USAT(int32_t val, uint32_t sat) -{ - if (sat <= 31U) - { - const uint32_t max = ((1U << sat) - 1U); - if (val > (int32_t)max) - { - return max; - } - else if (val < 0) - { - return 0U; - } - } - return (uint32_t)val; -} - -#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) */ - -/*@}*/ /* end of group CMSIS_Core_InstructionInterface */ - - -/* ################### Compiler specific Intrinsics ########################### */ -/** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics - Access to dedicated SIMD instructions - @{ -*/ - -#if ((defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) - -#define __SADD8 __sadd8 -#define __QADD8 __qadd8 -#define __SHADD8 __shadd8 -#define __UADD8 __uadd8 -#define __UQADD8 __uqadd8 -#define __UHADD8 __uhadd8 -#define __SSUB8 __ssub8 -#define __QSUB8 __qsub8 -#define __SHSUB8 __shsub8 -#define __USUB8 __usub8 -#define __UQSUB8 __uqsub8 -#define __UHSUB8 __uhsub8 -#define __SADD16 __sadd16 -#define __QADD16 __qadd16 -#define __SHADD16 __shadd16 -#define __UADD16 __uadd16 -#define __UQADD16 __uqadd16 -#define __UHADD16 __uhadd16 -#define __SSUB16 __ssub16 -#define __QSUB16 __qsub16 -#define __SHSUB16 __shsub16 -#define __USUB16 __usub16 -#define __UQSUB16 __uqsub16 -#define __UHSUB16 __uhsub16 -#define __SASX __sasx -#define __QASX __qasx -#define __SHASX __shasx -#define __UASX __uasx -#define __UQASX __uqasx -#define __UHASX __uhasx -#define __SSAX __ssax -#define __QSAX __qsax -#define __SHSAX __shsax -#define __USAX __usax -#define __UQSAX __uqsax -#define __UHSAX __uhsax -#define __USAD8 __usad8 -#define __USADA8 __usada8 -#define __SSAT16 __ssat16 -#define __USAT16 __usat16 -#define __UXTB16 __uxtb16 -#define __UXTAB16 __uxtab16 -#define __SXTB16 __sxtb16 -#define __SXTAB16 __sxtab16 -#define __SMUAD __smuad -#define __SMUADX __smuadx -#define __SMLAD __smlad -#define __SMLADX __smladx -#define __SMLALD __smlald -#define __SMLALDX __smlaldx -#define __SMUSD __smusd -#define __SMUSDX __smusdx -#define __SMLSD __smlsd -#define __SMLSDX __smlsdx -#define __SMLSLD __smlsld -#define __SMLSLDX __smlsldx -#define __SEL __sel -#define __QADD __qadd -#define __QSUB __qsub - -#define __PKHBT(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0x0000FFFFUL) | \ - ((((uint32_t)(ARG2)) << (ARG3)) & 0xFFFF0000UL) ) - -#define __PKHTB(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0xFFFF0000UL) | \ - ((((uint32_t)(ARG2)) >> (ARG3)) & 0x0000FFFFUL) ) - -#define __SMMLA(ARG1,ARG2,ARG3) ( (int32_t)((((int64_t)(ARG1) * (ARG2)) + \ - ((int64_t)(ARG3) << 32U) ) >> 32U)) - -#endif /* ((defined (__ARM_ARCH_7EM__) && (__ARM_ARCH_7EM__ == 1)) ) */ -/*@} end of group CMSIS_SIMD_intrinsics */ - - -#endif /* __CMSIS_ARMCC_H */ diff --git a/body/board/inc/cmsis_armcc_V6.h b/body/board/inc/cmsis_armcc_V6.h deleted file mode 100644 index cd13240..0000000 --- a/body/board/inc/cmsis_armcc_V6.h +++ /dev/null @@ -1,1800 +0,0 @@ -/**************************************************************************//** - * @file cmsis_armcc_V6.h - * @brief CMSIS Cortex-M Core Function/Instruction Header File - * @version V4.30 - * @date 20. October 2015 - ******************************************************************************/ -/* Copyright (c) 2009 - 2015 ARM LIMITED - - All rights reserved. - Redistribution and use in source and binary forms, with or without - modification, are permitted provided that the following conditions are met: - - Redistributions of source code must retain the above copyright - notice, this list of conditions and the following disclaimer. - - Redistributions in binary form must reproduce the above copyright - notice, this list of conditions and the following disclaimer in the - documentation and/or other materials provided with the distribution. - - Neither the name of ARM nor the names of its contributors may be used - to endorse or promote products derived from this software without - specific prior written permission. - * - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE - LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - POSSIBILITY OF SUCH DAMAGE. - ---------------------------------------------------------------------------*/ - - -#ifndef __CMSIS_ARMCC_V6_H -#define __CMSIS_ARMCC_V6_H - - -/* ########################### Core Function Access ########################### */ -/** \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions - @{ - */ - -/** - \brief Enable IRQ Interrupts - \details Enables IRQ interrupts by clearing the I-bit in the CPSR. - Can only be executed in Privileged modes. - */ -__attribute__((always_inline)) __STATIC_INLINE void __enable_irq(void) -{ - __ASM volatile ("cpsie i" : : : "memory"); -} - - -/** - \brief Disable IRQ Interrupts - \details Disables IRQ interrupts by setting the I-bit in the CPSR. - Can only be executed in Privileged modes. - */ -__attribute__((always_inline)) __STATIC_INLINE void __disable_irq(void) -{ - __ASM volatile ("cpsid i" : : : "memory"); -} - - -/** - \brief Get Control Register - \details Returns the content of the Control Register. - \return Control Register value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __get_CONTROL(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, control" : "=r" (result) ); - return(result); -} - - -#if (__ARM_FEATURE_CMSE == 3U) -/** - \brief Get Control Register (non-secure) - \details Returns the content of the non-secure Control Register when in secure mode. - \return non-secure Control Register value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __TZ_get_CONTROL_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, control_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Control Register - \details Writes the given value to the Control Register. - \param [in] control Control Register value to set - */ -__attribute__((always_inline)) __STATIC_INLINE void __set_CONTROL(uint32_t control) -{ - __ASM volatile ("MSR control, %0" : : "r" (control) : "memory"); -} - - -#if (__ARM_FEATURE_CMSE == 3U) -/** - \brief Set Control Register (non-secure) - \details Writes the given value to the non-secure Control Register when in secure state. - \param [in] control Control Register value to set - */ -__attribute__((always_inline)) __STATIC_INLINE void __TZ_set_CONTROL_NS(uint32_t control) -{ - __ASM volatile ("MSR control_ns, %0" : : "r" (control) : "memory"); -} -#endif - - -/** - \brief Get IPSR Register - \details Returns the content of the IPSR Register. - \return IPSR Register value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __get_IPSR(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, ipsr" : "=r" (result) ); - return(result); -} - - -#if (__ARM_FEATURE_CMSE == 3U) -/** - \brief Get IPSR Register (non-secure) - \details Returns the content of the non-secure IPSR Register when in secure state. - \return IPSR Register value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __TZ_get_IPSR_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, ipsr_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Get APSR Register - \details Returns the content of the APSR Register. - \return APSR Register value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __get_APSR(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, apsr" : "=r" (result) ); - return(result); -} - - -#if (__ARM_FEATURE_CMSE == 3U) -/** - \brief Get APSR Register (non-secure) - \details Returns the content of the non-secure APSR Register when in secure state. - \return APSR Register value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __TZ_get_APSR_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, apsr_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Get xPSR Register - \details Returns the content of the xPSR Register. - \return xPSR Register value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __get_xPSR(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, xpsr" : "=r" (result) ); - return(result); -} - - -#if (__ARM_FEATURE_CMSE == 3U) -/** - \brief Get xPSR Register (non-secure) - \details Returns the content of the non-secure xPSR Register when in secure state. - \return xPSR Register value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __TZ_get_xPSR_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, xpsr_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Get Process Stack Pointer - \details Returns the current value of the Process Stack Pointer (PSP). - \return PSP Register value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __get_PSP(void) -{ - register uint32_t result; - - __ASM volatile ("MRS %0, psp" : "=r" (result) ); - return(result); -} - - -#if (__ARM_FEATURE_CMSE == 3U) -/** - \brief Get Process Stack Pointer (non-secure) - \details Returns the current value of the non-secure Process Stack Pointer (PSP) when in secure state. - \return PSP Register value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __TZ_get_PSP_NS(void) -{ - register uint32_t result; - - __ASM volatile ("MRS %0, psp_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Process Stack Pointer - \details Assigns the given value to the Process Stack Pointer (PSP). - \param [in] topOfProcStack Process Stack Pointer value to set - */ -__attribute__((always_inline)) __STATIC_INLINE void __set_PSP(uint32_t topOfProcStack) -{ - __ASM volatile ("MSR psp, %0" : : "r" (topOfProcStack) : "sp"); -} - - -#if (__ARM_FEATURE_CMSE == 3U) -/** - \brief Set Process Stack Pointer (non-secure) - \details Assigns the given value to the non-secure Process Stack Pointer (PSP) when in secure state. - \param [in] topOfProcStack Process Stack Pointer value to set - */ -__attribute__((always_inline)) __STATIC_INLINE void __TZ_set_PSP_NS(uint32_t topOfProcStack) -{ - __ASM volatile ("MSR psp_ns, %0" : : "r" (topOfProcStack) : "sp"); -} -#endif - - -/** - \brief Get Main Stack Pointer - \details Returns the current value of the Main Stack Pointer (MSP). - \return MSP Register value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __get_MSP(void) -{ - register uint32_t result; - - __ASM volatile ("MRS %0, msp" : "=r" (result) ); - return(result); -} - - -#if (__ARM_FEATURE_CMSE == 3U) -/** - \brief Get Main Stack Pointer (non-secure) - \details Returns the current value of the non-secure Main Stack Pointer (MSP) when in secure state. - \return MSP Register value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __TZ_get_MSP_NS(void) -{ - register uint32_t result; - - __ASM volatile ("MRS %0, msp_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Main Stack Pointer - \details Assigns the given value to the Main Stack Pointer (MSP). - \param [in] topOfMainStack Main Stack Pointer value to set - */ -__attribute__((always_inline)) __STATIC_INLINE void __set_MSP(uint32_t topOfMainStack) -{ - __ASM volatile ("MSR msp, %0" : : "r" (topOfMainStack) : "sp"); -} - - -#if (__ARM_FEATURE_CMSE == 3U) -/** - \brief Set Main Stack Pointer (non-secure) - \details Assigns the given value to the non-secure Main Stack Pointer (MSP) when in secure state. - \param [in] topOfMainStack Main Stack Pointer value to set - */ -__attribute__((always_inline)) __STATIC_INLINE void __TZ_set_MSP_NS(uint32_t topOfMainStack) -{ - __ASM volatile ("MSR msp_ns, %0" : : "r" (topOfMainStack) : "sp"); -} -#endif - - -/** - \brief Get Priority Mask - \details Returns the current state of the priority mask bit from the Priority Mask Register. - \return Priority Mask value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __get_PRIMASK(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, primask" : "=r" (result) ); - return(result); -} - - -#if (__ARM_FEATURE_CMSE == 3U) -/** - \brief Get Priority Mask (non-secure) - \details Returns the current state of the non-secure priority mask bit from the Priority Mask Register when in secure state. - \return Priority Mask value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __TZ_get_PRIMASK_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, primask_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Priority Mask - \details Assigns the given value to the Priority Mask Register. - \param [in] priMask Priority Mask - */ -__attribute__((always_inline)) __STATIC_INLINE void __set_PRIMASK(uint32_t priMask) -{ - __ASM volatile ("MSR primask, %0" : : "r" (priMask) : "memory"); -} - - -#if (__ARM_FEATURE_CMSE == 3U) -/** - \brief Set Priority Mask (non-secure) - \details Assigns the given value to the non-secure Priority Mask Register when in secure state. - \param [in] priMask Priority Mask - */ -__attribute__((always_inline)) __STATIC_INLINE void __TZ_set_PRIMASK_NS(uint32_t priMask) -{ - __ASM volatile ("MSR primask_ns, %0" : : "r" (priMask) : "memory"); -} -#endif - - -#if ((__ARM_ARCH_7M__ == 1U) || (__ARM_ARCH_7EM__ == 1U) || (__ARM_ARCH_8M__ == 1U)) /* ToDo: ARMCC_V6: check if this is ok for cortex >=3 */ - -/** - \brief Enable FIQ - \details Enables FIQ interrupts by clearing the F-bit in the CPSR. - Can only be executed in Privileged modes. - */ -__attribute__((always_inline)) __STATIC_INLINE void __enable_fault_irq(void) -{ - __ASM volatile ("cpsie f" : : : "memory"); -} - - -/** - \brief Disable FIQ - \details Disables FIQ interrupts by setting the F-bit in the CPSR. - Can only be executed in Privileged modes. - */ -__attribute__((always_inline)) __STATIC_INLINE void __disable_fault_irq(void) -{ - __ASM volatile ("cpsid f" : : : "memory"); -} - - -/** - \brief Get Base Priority - \details Returns the current value of the Base Priority register. - \return Base Priority register value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __get_BASEPRI(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, basepri" : "=r" (result) ); - return(result); -} - - -#if (__ARM_FEATURE_CMSE == 3U) -/** - \brief Get Base Priority (non-secure) - \details Returns the current value of the non-secure Base Priority register when in secure state. - \return Base Priority register value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __TZ_get_BASEPRI_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, basepri_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Base Priority - \details Assigns the given value to the Base Priority register. - \param [in] basePri Base Priority value to set - */ -__attribute__((always_inline)) __STATIC_INLINE void __set_BASEPRI(uint32_t value) -{ - __ASM volatile ("MSR basepri, %0" : : "r" (value) : "memory"); -} - - -#if (__ARM_FEATURE_CMSE == 3U) -/** - \brief Set Base Priority (non-secure) - \details Assigns the given value to the non-secure Base Priority register when in secure state. - \param [in] basePri Base Priority value to set - */ -__attribute__((always_inline)) __STATIC_INLINE void __TZ_set_BASEPRI_NS(uint32_t value) -{ - __ASM volatile ("MSR basepri_ns, %0" : : "r" (value) : "memory"); -} -#endif - - -/** - \brief Set Base Priority with condition - \details Assigns the given value to the Base Priority register only if BASEPRI masking is disabled, - or the new value increases the BASEPRI priority level. - \param [in] basePri Base Priority value to set - */ -__attribute__((always_inline)) __STATIC_INLINE void __set_BASEPRI_MAX(uint32_t value) -{ - __ASM volatile ("MSR basepri_max, %0" : : "r" (value) : "memory"); -} - - -#if (__ARM_FEATURE_CMSE == 3U) -/** - \brief Set Base Priority with condition (non_secure) - \details Assigns the given value to the non-secure Base Priority register when in secure state only if BASEPRI masking is disabled, - or the new value increases the BASEPRI priority level. - \param [in] basePri Base Priority value to set - */ -__attribute__((always_inline)) __STATIC_INLINE void __TZ_set_BASEPRI_MAX_NS(uint32_t value) -{ - __ASM volatile ("MSR basepri_max_ns, %0" : : "r" (value) : "memory"); -} -#endif - - -/** - \brief Get Fault Mask - \details Returns the current value of the Fault Mask register. - \return Fault Mask register value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __get_FAULTMASK(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, faultmask" : "=r" (result) ); - return(result); -} - - -#if (__ARM_FEATURE_CMSE == 3U) -/** - \brief Get Fault Mask (non-secure) - \details Returns the current value of the non-secure Fault Mask register when in secure state. - \return Fault Mask register value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __TZ_get_FAULTMASK_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, faultmask_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Fault Mask - \details Assigns the given value to the Fault Mask register. - \param [in] faultMask Fault Mask value to set - */ -__attribute__((always_inline)) __STATIC_INLINE void __set_FAULTMASK(uint32_t faultMask) -{ - __ASM volatile ("MSR faultmask, %0" : : "r" (faultMask) : "memory"); -} - - -#if (__ARM_FEATURE_CMSE == 3U) -/** - \brief Set Fault Mask (non-secure) - \details Assigns the given value to the non-secure Fault Mask register when in secure state. - \param [in] faultMask Fault Mask value to set - */ -__attribute__((always_inline)) __STATIC_INLINE void __TZ_set_FAULTMASK_NS(uint32_t faultMask) -{ - __ASM volatile ("MSR faultmask_ns, %0" : : "r" (faultMask) : "memory"); -} -#endif - - -#endif /* ((__ARM_ARCH_7M__ == 1U) || (__ARM_ARCH_8M__ == 1U)) */ - - -#if (__ARM_ARCH_8M__ == 1U) - -/** - \brief Get Process Stack Pointer Limit - \details Returns the current value of the Process Stack Pointer Limit (PSPLIM). - \return PSPLIM Register value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __get_PSPLIM(void) -{ - register uint32_t result; - - __ASM volatile ("MRS %0, psplim" : "=r" (result) ); - return(result); -} - - -#if (__ARM_FEATURE_CMSE == 3U) && (__ARM_ARCH_PROFILE == 'M') /* ToDo: ARMCC_V6: check predefined macro for mainline */ -/** - \brief Get Process Stack Pointer Limit (non-secure) - \details Returns the current value of the non-secure Process Stack Pointer Limit (PSPLIM) when in secure state. - \return PSPLIM Register value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __TZ_get_PSPLIM_NS(void) -{ - register uint32_t result; - - __ASM volatile ("MRS %0, psplim_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Process Stack Pointer Limit - \details Assigns the given value to the Process Stack Pointer Limit (PSPLIM). - \param [in] ProcStackPtrLimit Process Stack Pointer Limit value to set - */ -__attribute__((always_inline)) __STATIC_INLINE void __set_PSPLIM(uint32_t ProcStackPtrLimit) -{ - __ASM volatile ("MSR psplim, %0" : : "r" (ProcStackPtrLimit)); -} - - -#if (__ARM_FEATURE_CMSE == 3U) && (__ARM_ARCH_PROFILE == 'M') /* ToDo: ARMCC_V6: check predefined macro for mainline */ -/** - \brief Set Process Stack Pointer (non-secure) - \details Assigns the given value to the non-secure Process Stack Pointer Limit (PSPLIM) when in secure state. - \param [in] ProcStackPtrLimit Process Stack Pointer Limit value to set - */ -__attribute__((always_inline)) __STATIC_INLINE void __TZ_set_PSPLIM_NS(uint32_t ProcStackPtrLimit) -{ - __ASM volatile ("MSR psplim_ns, %0\n" : : "r" (ProcStackPtrLimit)); -} -#endif - - -/** - \brief Get Main Stack Pointer Limit - \details Returns the current value of the Main Stack Pointer Limit (MSPLIM). - \return MSPLIM Register value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __get_MSPLIM(void) -{ - register uint32_t result; - - __ASM volatile ("MRS %0, msplim" : "=r" (result) ); - - return(result); -} - - -#if (__ARM_FEATURE_CMSE == 3U) && (__ARM_ARCH_PROFILE == 'M') /* ToDo: ARMCC_V6: check predefined macro for mainline */ -/** - \brief Get Main Stack Pointer Limit (non-secure) - \details Returns the current value of the non-secure Main Stack Pointer Limit(MSPLIM) when in secure state. - \return MSPLIM Register value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __TZ_get_MSPLIM_NS(void) -{ - register uint32_t result; - - __ASM volatile ("MRS %0, msplim_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Main Stack Pointer Limit - \details Assigns the given value to the Main Stack Pointer Limit (MSPLIM). - \param [in] MainStackPtrLimit Main Stack Pointer Limit value to set - */ -__attribute__((always_inline)) __STATIC_INLINE void __set_MSPLIM(uint32_t MainStackPtrLimit) -{ - __ASM volatile ("MSR msplim, %0" : : "r" (MainStackPtrLimit)); -} - - -#if (__ARM_FEATURE_CMSE == 3U) && (__ARM_ARCH_PROFILE == 'M') /* ToDo: ARMCC_V6: check predefined macro for mainline */ -/** - \brief Set Main Stack Pointer Limit (non-secure) - \details Assigns the given value to the non-secure Main Stack Pointer Limit (MSPLIM) when in secure state. - \param [in] MainStackPtrLimit Main Stack Pointer value to set - */ -__attribute__((always_inline)) __STATIC_INLINE void __TZ_set_MSPLIM_NS(uint32_t MainStackPtrLimit) -{ - __ASM volatile ("MSR msplim_ns, %0" : : "r" (MainStackPtrLimit)); -} -#endif - -#endif /* (__ARM_ARCH_8M__ == 1U) */ - - -#if ((__ARM_ARCH_7EM__ == 1U) || (__ARM_ARCH_8M__ == 1U)) /* ToDo: ARMCC_V6: check if this is ok for cortex >=4 */ - -/** - \brief Get FPSCR - \details eturns the current value of the Floating Point Status/Control register. - \return Floating Point Status/Control register value - */ -#define __get_FPSCR __builtin_arm_get_fpscr -#if 0 -__attribute__((always_inline)) __STATIC_INLINE uint32_t __get_FPSCR(void) -{ -#if (__FPU_PRESENT == 1U) && (__FPU_USED == 1U) - uint32_t result; - - __ASM volatile (""); /* Empty asm statement works as a scheduling barrier */ - __ASM volatile ("VMRS %0, fpscr" : "=r" (result) ); - __ASM volatile (""); - return(result); -#else - return(0); -#endif -} -#endif - -#if (__ARM_FEATURE_CMSE == 3U) -/** - \brief Get FPSCR (non-secure) - \details Returns the current value of the non-secure Floating Point Status/Control register when in secure state. - \return Floating Point Status/Control register value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __TZ_get_FPSCR_NS(void) -{ -#if (__FPU_PRESENT == 1U) && (__FPU_USED == 1U) - uint32_t result; - - __ASM volatile (""); /* Empty asm statement works as a scheduling barrier */ - __ASM volatile ("VMRS %0, fpscr_ns" : "=r" (result) ); - __ASM volatile (""); - return(result); -#else - return(0); -#endif -} -#endif - - -/** - \brief Set FPSCR - \details Assigns the given value to the Floating Point Status/Control register. - \param [in] fpscr Floating Point Status/Control value to set - */ -#define __set_FPSCR __builtin_arm_set_fpscr -#if 0 -__attribute__((always_inline)) __STATIC_INLINE void __set_FPSCR(uint32_t fpscr) -{ -#if (__FPU_PRESENT == 1U) && (__FPU_USED == 1U) - __ASM volatile (""); /* Empty asm statement works as a scheduling barrier */ - __ASM volatile ("VMSR fpscr, %0" : : "r" (fpscr) : "vfpcc"); - __ASM volatile (""); -#endif -} -#endif - -#if (__ARM_FEATURE_CMSE == 3U) -/** - \brief Set FPSCR (non-secure) - \details Assigns the given value to the non-secure Floating Point Status/Control register when in secure state. - \param [in] fpscr Floating Point Status/Control value to set - */ -__attribute__((always_inline)) __STATIC_INLINE void __TZ_set_FPSCR_NS(uint32_t fpscr) -{ -#if (__FPU_PRESENT == 1U) && (__FPU_USED == 1U) - __ASM volatile (""); /* Empty asm statement works as a scheduling barrier */ - __ASM volatile ("VMSR fpscr_ns, %0" : : "r" (fpscr) : "vfpcc"); - __ASM volatile (""); -#endif -} -#endif - -#endif /* ((__ARM_ARCH_7EM__ == 1U) || (__ARM_ARCH_8M__ == 1U)) */ - - - -/*@} end of CMSIS_Core_RegAccFunctions */ - - -/* ########################## Core Instruction Access ######################### */ -/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface - Access to dedicated instructions - @{ -*/ - -/* Define macros for porting to both thumb1 and thumb2. - * For thumb1, use low register (r0-r7), specified by constraint "l" - * Otherwise, use general registers, specified by constraint "r" */ -#if defined (__thumb__) && !defined (__thumb2__) -#define __CMSIS_GCC_OUT_REG(r) "=l" (r) -#define __CMSIS_GCC_USE_REG(r) "l" (r) -#else -#define __CMSIS_GCC_OUT_REG(r) "=r" (r) -#define __CMSIS_GCC_USE_REG(r) "r" (r) -#endif - -/** - \brief No Operation - \details No Operation does nothing. This instruction can be used for code alignment purposes. - */ -#define __NOP __builtin_arm_nop - -/** - \brief Wait For Interrupt - \details Wait For Interrupt is a hint instruction that suspends execution until one of a number of events occurs. - */ -#define __WFI __builtin_arm_wfi - - -/** - \brief Wait For Event - \details Wait For Event is a hint instruction that permits the processor to enter - a low-power state until one of a number of events occurs. - */ -#define __WFE __builtin_arm_wfe - - -/** - \brief Send Event - \details Send Event is a hint instruction. It causes an event to be signaled to the CPU. - */ -#define __SEV __builtin_arm_sev - - -/** - \brief Instruction Synchronization Barrier - \details Instruction Synchronization Barrier flushes the pipeline in the processor, - so that all instructions following the ISB are fetched from cache or memory, - after the instruction has been completed. - */ -#define __ISB() __builtin_arm_isb(0xF); - -/** - \brief Data Synchronization Barrier - \details Acts as a special kind of Data Memory Barrier. - It completes when all explicit memory accesses before this instruction complete. - */ -#define __DSB() __builtin_arm_dsb(0xF); - - -/** - \brief Data Memory Barrier - \details Ensures the apparent order of the explicit memory operations before - and after the instruction, without ensuring their completion. - */ -#define __DMB() __builtin_arm_dmb(0xF); - - -/** - \brief Reverse byte order (32 bit) - \details Reverses the byte order in integer value. - \param [in] value Value to reverse - \return Reversed value - */ -#define __REV __builtin_bswap32 - - -/** - \brief Reverse byte order (16 bit) - \details Reverses the byte order in two unsigned short values. - \param [in] value Value to reverse - \return Reversed value - */ -#define __REV16 __builtin_bswap16 /* ToDo: ARMCC_V6: check if __builtin_bswap16 could be used */ -#if 0 -__attribute__((always_inline)) __STATIC_INLINE uint32_t __REV16(uint32_t value) -{ - uint32_t result; - - __ASM volatile ("rev16 %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return(result); -} -#endif - - -/** - \brief Reverse byte order in signed short value - \details Reverses the byte order in a signed short value with sign extension to integer. - \param [in] value Value to reverse - \return Reversed value - */ - /* ToDo: ARMCC_V6: check if __builtin_bswap16 could be used */ -__attribute__((always_inline)) __STATIC_INLINE int32_t __REVSH(int32_t value) -{ - int32_t result; - - __ASM volatile ("revsh %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return(result); -} - - -/** - \brief Rotate Right in unsigned value (32 bit) - \details Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits. - \param [in] op1 Value to rotate - \param [in] op2 Number of Bits to rotate - \return Rotated value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __ROR(uint32_t op1, uint32_t op2) -{ - return (op1 >> op2) | (op1 << (32U - op2)); -} - - -/** - \brief Breakpoint - \details Causes the processor to enter Debug state. - Debug tools can use this to investigate system state when the instruction at a particular address is reached. - \param [in] value is ignored by the processor. - If required, a debugger can use it to store additional information about the breakpoint. - */ -#define __BKPT(value) __ASM volatile ("bkpt "#value) - - -/** - \brief Reverse bit order of value - \details Reverses the bit order of the given value. - \param [in] value Value to reverse - \return Reversed value - */ - /* ToDo: ARMCC_V6: check if __builtin_arm_rbit is supported */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __RBIT(uint32_t value) -{ - uint32_t result; - -#if ((__ARM_ARCH_7M__ == 1U) || (__ARM_ARCH_7EM__ == 1U) || (__ARM_ARCH_8M__ == 1U)) /* ToDo: ARMCC_V6: check if this is ok for cortex >=3 */ - __ASM volatile ("rbit %0, %1" : "=r" (result) : "r" (value) ); -#else - int32_t s = 4 /*sizeof(v)*/ * 8 - 1; /* extra shift needed at end */ - - result = value; /* r will be reversed bits of v; first get LSB of v */ - for (value >>= 1U; value; value >>= 1U) - { - result <<= 1U; - result |= value & 1U; - s--; - } - result <<= s; /* shift when v's highest bits are zero */ -#endif - return(result); -} - - -/** - \brief Count leading zeros - \details Counts the number of leading zeros of a data value. - \param [in] value Value to count the leading zeros - \return number of leading zeros in value - */ -#define __CLZ __builtin_clz - - -#if ((__ARM_ARCH_7M__ == 1U) || (__ARM_ARCH_7EM__ == 1U) || (__ARM_ARCH_8M__ == 1U)) /* ToDo: ARMCC_V6: check if this is ok for cortex >=3 */ - -/** - \brief LDR Exclusive (8 bit) - \details Executes a exclusive LDR instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -#define __LDREXB (uint8_t)__builtin_arm_ldrex - - -/** - \brief LDR Exclusive (16 bit) - \details Executes a exclusive LDR instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -#define __LDREXH (uint16_t)__builtin_arm_ldrex - - -/** - \brief LDR Exclusive (32 bit) - \details Executes a exclusive LDR instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -#define __LDREXW (uint32_t)__builtin_arm_ldrex - - -/** - \brief STR Exclusive (8 bit) - \details Executes a exclusive STR instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#define __STREXB (uint32_t)__builtin_arm_strex - - -/** - \brief STR Exclusive (16 bit) - \details Executes a exclusive STR instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#define __STREXH (uint32_t)__builtin_arm_strex - - -/** - \brief STR Exclusive (32 bit) - \details Executes a exclusive STR instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#define __STREXW (uint32_t)__builtin_arm_strex - - -/** - \brief Remove the exclusive lock - \details Removes the exclusive lock which is created by LDREX. - */ -#define __CLREX __builtin_arm_clrex - - -/** - \brief Signed Saturate - \details Saturates a signed value. - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (1..32) - \return Saturated value - */ -/*#define __SSAT __builtin_arm_ssat*/ -#define __SSAT(ARG1,ARG2) \ -({ \ - int32_t __RES, __ARG1 = (ARG1); \ - __ASM ("ssat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) - - -/** - \brief Unsigned Saturate - \details Saturates an unsigned value. - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (0..31) - \return Saturated value - */ -#define __USAT __builtin_arm_usat -#if 0 -#define __USAT(ARG1,ARG2) \ -({ \ - uint32_t __RES, __ARG1 = (ARG1); \ - __ASM ("usat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) -#endif - - -/** - \brief Rotate Right with Extend (32 bit) - \details Moves each bit of a bitstring right by one bit. - The carry input is shifted in at the left end of the bitstring. - \param [in] value Value to rotate - \return Rotated value - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __RRX(uint32_t value) -{ - uint32_t result; - - __ASM volatile ("rrx %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return(result); -} - - -/** - \brief LDRT Unprivileged (8 bit) - \details Executes a Unprivileged LDRT instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -__attribute__((always_inline)) __STATIC_INLINE uint8_t __LDRBT(volatile uint8_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldrbt %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint8_t) result); /* Add explicit type cast here */ -} - - -/** - \brief LDRT Unprivileged (16 bit) - \details Executes a Unprivileged LDRT instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -__attribute__((always_inline)) __STATIC_INLINE uint16_t __LDRHT(volatile uint16_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldrht %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint16_t) result); /* Add explicit type cast here */ -} - - -/** - \brief LDRT Unprivileged (32 bit) - \details Executes a Unprivileged LDRT instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __LDRT(volatile uint32_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldrt %0, %1" : "=r" (result) : "Q" (*ptr) ); - return(result); -} - - -/** - \brief STRT Unprivileged (8 bit) - \details Executes a Unprivileged STRT instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__attribute__((always_inline)) __STATIC_INLINE void __STRBT(uint8_t value, volatile uint8_t *ptr) -{ - __ASM volatile ("strbt %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief STRT Unprivileged (16 bit) - \details Executes a Unprivileged STRT instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__attribute__((always_inline)) __STATIC_INLINE void __STRHT(uint16_t value, volatile uint16_t *ptr) -{ - __ASM volatile ("strht %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief STRT Unprivileged (32 bit) - \details Executes a Unprivileged STRT instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__attribute__((always_inline)) __STATIC_INLINE void __STRT(uint32_t value, volatile uint32_t *ptr) -{ - __ASM volatile ("strt %1, %0" : "=Q" (*ptr) : "r" (value) ); -} - -#endif /* ((__ARM_ARCH_7M__ == 1U) || (__ARM_ARCH_7EM__ == 1U) || (__ARM_ARCH_8M__ == 1U)) */ - - -#if (__ARM_ARCH_8M__ == 1U) - -/** - \brief Load-Acquire (8 bit) - \details Executes a LDAB instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -__attribute__((always_inline)) __STATIC_INLINE uint8_t __LDAB(volatile uint8_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldab %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint8_t) result); -} - - -/** - \brief Load-Acquire (16 bit) - \details Executes a LDAH instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -__attribute__((always_inline)) __STATIC_INLINE uint16_t __LDAH(volatile uint16_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldah %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint16_t) result); -} - - -/** - \brief Load-Acquire (32 bit) - \details Executes a LDA instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -__attribute__((always_inline)) __STATIC_INLINE uint32_t __LDA(volatile uint32_t *ptr) -{ - uint32_t result; - - __ASM volatile ("lda %0, %1" : "=r" (result) : "Q" (*ptr) ); - return(result); -} - - -/** - \brief Store-Release (8 bit) - \details Executes a STLB instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__attribute__((always_inline)) __STATIC_INLINE void __STLB(uint8_t value, volatile uint8_t *ptr) -{ - __ASM volatile ("stlb %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief Store-Release (16 bit) - \details Executes a STLH instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__attribute__((always_inline)) __STATIC_INLINE void __STLH(uint16_t value, volatile uint16_t *ptr) -{ - __ASM volatile ("stlh %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief Store-Release (32 bit) - \details Executes a STL instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__attribute__((always_inline)) __STATIC_INLINE void __STL(uint32_t value, volatile uint32_t *ptr) -{ - __ASM volatile ("stl %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief Load-Acquire Exclusive (8 bit) - \details Executes a LDAB exclusive instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -#define __LDAEXB (uint8_t)__builtin_arm_ldaex - - -/** - \brief Load-Acquire Exclusive (16 bit) - \details Executes a LDAH exclusive instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -#define __LDAEXH (uint16_t)__builtin_arm_ldaex - - -/** - \brief Load-Acquire Exclusive (32 bit) - \details Executes a LDA exclusive instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -#define __LDAEX (uint32_t)__builtin_arm_ldaex - - -/** - \brief Store-Release Exclusive (8 bit) - \details Executes a STLB exclusive instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#define __STLEXB (uint32_t)__builtin_arm_stlex - - -/** - \brief Store-Release Exclusive (16 bit) - \details Executes a STLH exclusive instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#define __STLEXH (uint32_t)__builtin_arm_stlex - - -/** - \brief Store-Release Exclusive (32 bit) - \details Executes a STL exclusive instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#define __STLEX (uint32_t)__builtin_arm_stlex - -#endif /* (__ARM_ARCH_8M__ == 1U) */ - -/*@}*/ /* end of group CMSIS_Core_InstructionInterface */ - - -/* ################### Compiler specific Intrinsics ########################### */ -/** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics - Access to dedicated SIMD instructions - @{ -*/ - -#if (__ARM_FEATURE_DSP == 1U) /* ToDo: ARMCC_V6: This should be ARCH >= ARMv7-M + SIMD */ - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __QADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SHADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __UADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __UQADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __UHADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("ssub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __QSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SHSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __USUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __UQSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __UHSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __QADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SHADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __UADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __UQADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __UHADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("ssub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __QSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SHSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __USUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __UQSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __UHSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __QASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SHASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __UASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __UQASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __UHASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("ssax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __QSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SHSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __USAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __UQSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __UHSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __USAD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usad8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __USADA8(uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("usada8 %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -#define __SSAT16(ARG1,ARG2) \ -({ \ - uint32_t __RES, __ARG1 = (ARG1); \ - __ASM ("ssat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) - -#define __USAT16(ARG1,ARG2) \ -({ \ - uint32_t __RES, __ARG1 = (ARG1); \ - __ASM ("usat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __UXTB16(uint32_t op1) -{ - uint32_t result; - - __ASM volatile ("uxtb16 %0, %1" : "=r" (result) : "r" (op1)); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __UXTAB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SXTB16(uint32_t op1) -{ - uint32_t result; - - __ASM volatile ("sxtb16 %0, %1" : "=r" (result) : "r" (op1)); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SXTAB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SMUAD (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smuad %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SMUADX (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smuadx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SMLAD (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smlad %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SMLADX (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smladx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint64_t __SMLALD (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__attribute__((always_inline)) __STATIC_INLINE uint64_t __SMLALDX (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SMUSD (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smusd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SMUSDX (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smusdx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SMLSD (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smlsd %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SMLSDX (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smlsdx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE uint64_t __SMLSLD (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__attribute__((always_inline)) __STATIC_INLINE uint64_t __SMLSLDX (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SEL (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sel %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE int32_t __QADD( int32_t op1, int32_t op2) -{ - int32_t result; - - __ASM volatile ("qadd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__attribute__((always_inline)) __STATIC_INLINE int32_t __QSUB( int32_t op1, int32_t op2) -{ - int32_t result; - - __ASM volatile ("qsub %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -#define __PKHBT(ARG1,ARG2,ARG3) \ -({ \ - uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \ - __ASM ("pkhbt %0, %1, %2, lsl %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \ - __RES; \ - }) - -#define __PKHTB(ARG1,ARG2,ARG3) \ -({ \ - uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \ - if (ARG3 == 0) \ - __ASM ("pkhtb %0, %1, %2" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2) ); \ - else \ - __ASM ("pkhtb %0, %1, %2, asr %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \ - __RES; \ - }) - -__attribute__((always_inline)) __STATIC_INLINE uint32_t __SMMLA (int32_t op1, int32_t op2, int32_t op3) -{ - int32_t result; - - __ASM volatile ("smmla %0, %1, %2, %3" : "=r" (result): "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -#endif /* (__ARM_FEATURE_DSP == 1U) */ -/*@} end of group CMSIS_SIMD_intrinsics */ - - -#endif /* __CMSIS_ARMCC_V6_H */ diff --git a/body/board/inc/cmsis_armclang.h b/body/board/inc/cmsis_armclang.h deleted file mode 100644 index 162a400..0000000 --- a/body/board/inc/cmsis_armclang.h +++ /dev/null @@ -1,1869 +0,0 @@ -/**************************************************************************//** - * @file cmsis_armclang.h - * @brief CMSIS compiler armclang (Arm Compiler 6) header file - * @version V5.0.4 - * @date 10. January 2018 - ******************************************************************************/ -/* - * Copyright (c) 2009-2018 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -/*lint -esym(9058, IRQn)*/ /* disable MISRA 2012 Rule 2.4 for IRQn */ - -#ifndef __CMSIS_ARMCLANG_H -#define __CMSIS_ARMCLANG_H - -#pragma clang system_header /* treat file as system include file */ - -#ifndef __ARM_COMPAT_H -#include /* Compatibility header for Arm Compiler 5 intrinsics */ -#endif - -/* CMSIS compiler specific defines */ -#ifndef __ASM - #define __ASM __asm -#endif -#ifndef __INLINE - #define __INLINE __inline -#endif -#ifndef __STATIC_INLINE - #define __STATIC_INLINE static __inline -#endif -#ifndef __STATIC_FORCEINLINE - #define __STATIC_FORCEINLINE __attribute__((always_inline)) static __inline -#endif -#ifndef __NO_RETURN - #define __NO_RETURN __attribute__((__noreturn__)) -#endif -#ifndef __USED - #define __USED __attribute__((used)) -#endif -#ifndef __WEAK - #define __WEAK __attribute__((weak)) -#endif -#ifndef __PACKED - #define __PACKED __attribute__((packed, aligned(1))) -#endif -#ifndef __PACKED_STRUCT - #define __PACKED_STRUCT struct __attribute__((packed, aligned(1))) -#endif -#ifndef __PACKED_UNION - #define __PACKED_UNION union __attribute__((packed, aligned(1))) -#endif -#ifndef __UNALIGNED_UINT32 /* deprecated */ - #pragma clang diagnostic push - #pragma clang diagnostic ignored "-Wpacked" -/*lint -esym(9058, T_UINT32)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT32 */ - struct __attribute__((packed)) T_UINT32 { uint32_t v; }; - #pragma clang diagnostic pop - #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) -#endif -#ifndef __UNALIGNED_UINT16_WRITE - #pragma clang diagnostic push - #pragma clang diagnostic ignored "-Wpacked" -/*lint -esym(9058, T_UINT16_WRITE)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT16_WRITE */ - __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; - #pragma clang diagnostic pop - #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val)) -#endif -#ifndef __UNALIGNED_UINT16_READ - #pragma clang diagnostic push - #pragma clang diagnostic ignored "-Wpacked" -/*lint -esym(9058, T_UINT16_READ)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT16_READ */ - __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; - #pragma clang diagnostic pop - #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) -#endif -#ifndef __UNALIGNED_UINT32_WRITE - #pragma clang diagnostic push - #pragma clang diagnostic ignored "-Wpacked" -/*lint -esym(9058, T_UINT32_WRITE)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT32_WRITE */ - __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; - #pragma clang diagnostic pop - #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) -#endif -#ifndef __UNALIGNED_UINT32_READ - #pragma clang diagnostic push - #pragma clang diagnostic ignored "-Wpacked" -/*lint -esym(9058, T_UINT32_READ)*/ /* disable MISRA 2012 Rule 2.4 for T_UINT32_READ */ - __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; - #pragma clang diagnostic pop - #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) -#endif -#ifndef __ALIGNED - #define __ALIGNED(x) __attribute__((aligned(x))) -#endif -#ifndef __RESTRICT - #define __RESTRICT __restrict -#endif - - -/* ########################### Core Function Access ########################### */ -/** \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions - @{ - */ - -/** - \brief Enable IRQ Interrupts - \details Enables IRQ interrupts by clearing the I-bit in the CPSR. - Can only be executed in Privileged modes. - */ -/* intrinsic void __enable_irq(); see arm_compat.h */ - - -/** - \brief Disable IRQ Interrupts - \details Disables IRQ interrupts by setting the I-bit in the CPSR. - Can only be executed in Privileged modes. - */ -/* intrinsic void __disable_irq(); see arm_compat.h */ - - -/** - \brief Get Control Register - \details Returns the content of the Control Register. - \return Control Register value - */ -__STATIC_FORCEINLINE uint32_t __get_CONTROL(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, control" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Control Register (non-secure) - \details Returns the content of the non-secure Control Register when in secure mode. - \return non-secure Control Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_CONTROL_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, control_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Control Register - \details Writes the given value to the Control Register. - \param [in] control Control Register value to set - */ -__STATIC_FORCEINLINE void __set_CONTROL(uint32_t control) -{ - __ASM volatile ("MSR control, %0" : : "r" (control) : "memory"); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Control Register (non-secure) - \details Writes the given value to the non-secure Control Register when in secure state. - \param [in] control Control Register value to set - */ -__STATIC_FORCEINLINE void __TZ_set_CONTROL_NS(uint32_t control) -{ - __ASM volatile ("MSR control_ns, %0" : : "r" (control) : "memory"); -} -#endif - - -/** - \brief Get IPSR Register - \details Returns the content of the IPSR Register. - \return IPSR Register value - */ -__STATIC_FORCEINLINE uint32_t __get_IPSR(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, ipsr" : "=r" (result) ); - return(result); -} - - -/** - \brief Get APSR Register - \details Returns the content of the APSR Register. - \return APSR Register value - */ -__STATIC_FORCEINLINE uint32_t __get_APSR(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, apsr" : "=r" (result) ); - return(result); -} - - -/** - \brief Get xPSR Register - \details Returns the content of the xPSR Register. - \return xPSR Register value - */ -__STATIC_FORCEINLINE uint32_t __get_xPSR(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, xpsr" : "=r" (result) ); - return(result); -} - - -/** - \brief Get Process Stack Pointer - \details Returns the current value of the Process Stack Pointer (PSP). - \return PSP Register value - */ -__STATIC_FORCEINLINE uint32_t __get_PSP(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, psp" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Process Stack Pointer (non-secure) - \details Returns the current value of the non-secure Process Stack Pointer (PSP) when in secure state. - \return PSP Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_PSP_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, psp_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Process Stack Pointer - \details Assigns the given value to the Process Stack Pointer (PSP). - \param [in] topOfProcStack Process Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __set_PSP(uint32_t topOfProcStack) -{ - __ASM volatile ("MSR psp, %0" : : "r" (topOfProcStack) : ); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Process Stack Pointer (non-secure) - \details Assigns the given value to the non-secure Process Stack Pointer (PSP) when in secure state. - \param [in] topOfProcStack Process Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __TZ_set_PSP_NS(uint32_t topOfProcStack) -{ - __ASM volatile ("MSR psp_ns, %0" : : "r" (topOfProcStack) : ); -} -#endif - - -/** - \brief Get Main Stack Pointer - \details Returns the current value of the Main Stack Pointer (MSP). - \return MSP Register value - */ -__STATIC_FORCEINLINE uint32_t __get_MSP(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, msp" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Main Stack Pointer (non-secure) - \details Returns the current value of the non-secure Main Stack Pointer (MSP) when in secure state. - \return MSP Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_MSP_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, msp_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Main Stack Pointer - \details Assigns the given value to the Main Stack Pointer (MSP). - \param [in] topOfMainStack Main Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __set_MSP(uint32_t topOfMainStack) -{ - __ASM volatile ("MSR msp, %0" : : "r" (topOfMainStack) : ); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Main Stack Pointer (non-secure) - \details Assigns the given value to the non-secure Main Stack Pointer (MSP) when in secure state. - \param [in] topOfMainStack Main Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __TZ_set_MSP_NS(uint32_t topOfMainStack) -{ - __ASM volatile ("MSR msp_ns, %0" : : "r" (topOfMainStack) : ); -} -#endif - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Stack Pointer (non-secure) - \details Returns the current value of the non-secure Stack Pointer (SP) when in secure state. - \return SP Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_SP_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, sp_ns" : "=r" (result) ); - return(result); -} - - -/** - \brief Set Stack Pointer (non-secure) - \details Assigns the given value to the non-secure Stack Pointer (SP) when in secure state. - \param [in] topOfStack Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __TZ_set_SP_NS(uint32_t topOfStack) -{ - __ASM volatile ("MSR sp_ns, %0" : : "r" (topOfStack) : ); -} -#endif - - -/** - \brief Get Priority Mask - \details Returns the current state of the priority mask bit from the Priority Mask Register. - \return Priority Mask value - */ -__STATIC_FORCEINLINE uint32_t __get_PRIMASK(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, primask" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Priority Mask (non-secure) - \details Returns the current state of the non-secure priority mask bit from the Priority Mask Register when in secure state. - \return Priority Mask value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_PRIMASK_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, primask_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Priority Mask - \details Assigns the given value to the Priority Mask Register. - \param [in] priMask Priority Mask - */ -__STATIC_FORCEINLINE void __set_PRIMASK(uint32_t priMask) -{ - __ASM volatile ("MSR primask, %0" : : "r" (priMask) : "memory"); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Priority Mask (non-secure) - \details Assigns the given value to the non-secure Priority Mask Register when in secure state. - \param [in] priMask Priority Mask - */ -__STATIC_FORCEINLINE void __TZ_set_PRIMASK_NS(uint32_t priMask) -{ - __ASM volatile ("MSR primask_ns, %0" : : "r" (priMask) : "memory"); -} -#endif - - -#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) -/** - \brief Enable FIQ - \details Enables FIQ interrupts by clearing the F-bit in the CPSR. - Can only be executed in Privileged modes. - */ -#define __enable_fault_irq __enable_fiq /* see arm_compat.h */ - - -/** - \brief Disable FIQ - \details Disables FIQ interrupts by setting the F-bit in the CPSR. - Can only be executed in Privileged modes. - */ -#define __disable_fault_irq __disable_fiq /* see arm_compat.h */ - - -/** - \brief Get Base Priority - \details Returns the current value of the Base Priority register. - \return Base Priority register value - */ -__STATIC_FORCEINLINE uint32_t __get_BASEPRI(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, basepri" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Base Priority (non-secure) - \details Returns the current value of the non-secure Base Priority register when in secure state. - \return Base Priority register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_BASEPRI_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, basepri_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Base Priority - \details Assigns the given value to the Base Priority register. - \param [in] basePri Base Priority value to set - */ -__STATIC_FORCEINLINE void __set_BASEPRI(uint32_t basePri) -{ - __ASM volatile ("MSR basepri, %0" : : "r" (basePri) : "memory"); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Base Priority (non-secure) - \details Assigns the given value to the non-secure Base Priority register when in secure state. - \param [in] basePri Base Priority value to set - */ -__STATIC_FORCEINLINE void __TZ_set_BASEPRI_NS(uint32_t basePri) -{ - __ASM volatile ("MSR basepri_ns, %0" : : "r" (basePri) : "memory"); -} -#endif - - -/** - \brief Set Base Priority with condition - \details Assigns the given value to the Base Priority register only if BASEPRI masking is disabled, - or the new value increases the BASEPRI priority level. - \param [in] basePri Base Priority value to set - */ -__STATIC_FORCEINLINE void __set_BASEPRI_MAX(uint32_t basePri) -{ - __ASM volatile ("MSR basepri_max, %0" : : "r" (basePri) : "memory"); -} - - -/** - \brief Get Fault Mask - \details Returns the current value of the Fault Mask register. - \return Fault Mask register value - */ -__STATIC_FORCEINLINE uint32_t __get_FAULTMASK(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, faultmask" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Fault Mask (non-secure) - \details Returns the current value of the non-secure Fault Mask register when in secure state. - \return Fault Mask register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_FAULTMASK_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, faultmask_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Fault Mask - \details Assigns the given value to the Fault Mask register. - \param [in] faultMask Fault Mask value to set - */ -__STATIC_FORCEINLINE void __set_FAULTMASK(uint32_t faultMask) -{ - __ASM volatile ("MSR faultmask, %0" : : "r" (faultMask) : "memory"); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Fault Mask (non-secure) - \details Assigns the given value to the non-secure Fault Mask register when in secure state. - \param [in] faultMask Fault Mask value to set - */ -__STATIC_FORCEINLINE void __TZ_set_FAULTMASK_NS(uint32_t faultMask) -{ - __ASM volatile ("MSR faultmask_ns, %0" : : "r" (faultMask) : "memory"); -} -#endif - -#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ - - -#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) - -/** - \brief Get Process Stack Pointer Limit - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence zero is returned always in non-secure - mode. - - \details Returns the current value of the Process Stack Pointer Limit (PSPLIM). - \return PSPLIM Register value - */ -__STATIC_FORCEINLINE uint32_t __get_PSPLIM(void) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - return 0U; -#else - uint32_t result; - __ASM volatile ("MRS %0, psplim" : "=r" (result) ); - return result; -#endif -} - -#if (defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Process Stack Pointer Limit (non-secure) - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence zero is returned always in non-secure - mode. - - \details Returns the current value of the non-secure Process Stack Pointer Limit (PSPLIM) when in secure state. - \return PSPLIM Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_PSPLIM_NS(void) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - return 0U; -#else - uint32_t result; - __ASM volatile ("MRS %0, psplim_ns" : "=r" (result) ); - return result; -#endif -} -#endif - - -/** - \brief Set Process Stack Pointer Limit - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence the write is silently ignored in non-secure - mode. - - \details Assigns the given value to the Process Stack Pointer Limit (PSPLIM). - \param [in] ProcStackPtrLimit Process Stack Pointer Limit value to set - */ -__STATIC_FORCEINLINE void __set_PSPLIM(uint32_t ProcStackPtrLimit) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - (void)ProcStackPtrLimit; -#else - __ASM volatile ("MSR psplim, %0" : : "r" (ProcStackPtrLimit)); -#endif -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Process Stack Pointer (non-secure) - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence the write is silently ignored in non-secure - mode. - - \details Assigns the given value to the non-secure Process Stack Pointer Limit (PSPLIM) when in secure state. - \param [in] ProcStackPtrLimit Process Stack Pointer Limit value to set - */ -__STATIC_FORCEINLINE void __TZ_set_PSPLIM_NS(uint32_t ProcStackPtrLimit) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - (void)ProcStackPtrLimit; -#else - __ASM volatile ("MSR psplim_ns, %0\n" : : "r" (ProcStackPtrLimit)); -#endif -} -#endif - - -/** - \brief Get Main Stack Pointer Limit - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence zero is returned always. - - \details Returns the current value of the Main Stack Pointer Limit (MSPLIM). - \return MSPLIM Register value - */ -__STATIC_FORCEINLINE uint32_t __get_MSPLIM(void) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - return 0U; -#else - uint32_t result; - __ASM volatile ("MRS %0, msplim" : "=r" (result) ); - return result; -#endif -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Main Stack Pointer Limit (non-secure) - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence zero is returned always. - - \details Returns the current value of the non-secure Main Stack Pointer Limit(MSPLIM) when in secure state. - \return MSPLIM Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_MSPLIM_NS(void) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - return 0U; -#else - uint32_t result; - __ASM volatile ("MRS %0, msplim_ns" : "=r" (result) ); - return result; -#endif -} -#endif - - -/** - \brief Set Main Stack Pointer Limit - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence the write is silently ignored. - - \details Assigns the given value to the Main Stack Pointer Limit (MSPLIM). - \param [in] MainStackPtrLimit Main Stack Pointer Limit value to set - */ -__STATIC_FORCEINLINE void __set_MSPLIM(uint32_t MainStackPtrLimit) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - (void)MainStackPtrLimit; -#else - __ASM volatile ("MSR msplim, %0" : : "r" (MainStackPtrLimit)); -#endif -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Main Stack Pointer Limit (non-secure) - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence the write is silently ignored. - - \details Assigns the given value to the non-secure Main Stack Pointer Limit (MSPLIM) when in secure state. - \param [in] MainStackPtrLimit Main Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __TZ_set_MSPLIM_NS(uint32_t MainStackPtrLimit) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - (void)MainStackPtrLimit; -#else - __ASM volatile ("MSR msplim_ns, %0" : : "r" (MainStackPtrLimit)); -#endif -} -#endif - -#endif /* ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ - -/** - \brief Get FPSCR - \details Returns the current value of the Floating Point Status/Control register. - \return Floating Point Status/Control register value - */ -#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ - (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) -#define __get_FPSCR (uint32_t)__builtin_arm_get_fpscr -#else -#define __get_FPSCR() ((uint32_t)0U) -#endif - -/** - \brief Set FPSCR - \details Assigns the given value to the Floating Point Status/Control register. - \param [in] fpscr Floating Point Status/Control value to set - */ -#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ - (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) -#define __set_FPSCR __builtin_arm_set_fpscr -#else -#define __set_FPSCR(x) ((void)(x)) -#endif - - -/*@} end of CMSIS_Core_RegAccFunctions */ - - -/* ########################## Core Instruction Access ######################### */ -/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface - Access to dedicated instructions - @{ -*/ - -/* Define macros for porting to both thumb1 and thumb2. - * For thumb1, use low register (r0-r7), specified by constraint "l" - * Otherwise, use general registers, specified by constraint "r" */ -#if defined (__thumb__) && !defined (__thumb2__) -#define __CMSIS_GCC_OUT_REG(r) "=l" (r) -#define __CMSIS_GCC_USE_REG(r) "l" (r) -#else -#define __CMSIS_GCC_OUT_REG(r) "=r" (r) -#define __CMSIS_GCC_USE_REG(r) "r" (r) -#endif - -/** - \brief No Operation - \details No Operation does nothing. This instruction can be used for code alignment purposes. - */ -#define __NOP __builtin_arm_nop - -/** - \brief Wait For Interrupt - \details Wait For Interrupt is a hint instruction that suspends execution until one of a number of events occurs. - */ -#define __WFI __builtin_arm_wfi - - -/** - \brief Wait For Event - \details Wait For Event is a hint instruction that permits the processor to enter - a low-power state until one of a number of events occurs. - */ -#define __WFE __builtin_arm_wfe - - -/** - \brief Send Event - \details Send Event is a hint instruction. It causes an event to be signaled to the CPU. - */ -#define __SEV __builtin_arm_sev - - -/** - \brief Instruction Synchronization Barrier - \details Instruction Synchronization Barrier flushes the pipeline in the processor, - so that all instructions following the ISB are fetched from cache or memory, - after the instruction has been completed. - */ -#define __ISB() __builtin_arm_isb(0xF); - -/** - \brief Data Synchronization Barrier - \details Acts as a special kind of Data Memory Barrier. - It completes when all explicit memory accesses before this instruction complete. - */ -#define __DSB() __builtin_arm_dsb(0xF); - - -/** - \brief Data Memory Barrier - \details Ensures the apparent order of the explicit memory operations before - and after the instruction, without ensuring their completion. - */ -#define __DMB() __builtin_arm_dmb(0xF); - - -/** - \brief Reverse byte order (32 bit) - \details Reverses the byte order in unsigned integer value. For example, 0x12345678 becomes 0x78563412. - \param [in] value Value to reverse - \return Reversed value - */ -#define __REV(value) __builtin_bswap32(value) - - -/** - \brief Reverse byte order (16 bit) - \details Reverses the byte order within each halfword of a word. For example, 0x12345678 becomes 0x34127856. - \param [in] value Value to reverse - \return Reversed value - */ -#define __REV16(value) __ROR(__REV(value), 16) - - -/** - \brief Reverse byte order (16 bit) - \details Reverses the byte order in a 16-bit value and returns the signed 16-bit result. For example, 0x0080 becomes 0x8000. - \param [in] value Value to reverse - \return Reversed value - */ -#define __REVSH(value) (int16_t)__builtin_bswap16(value) - - -/** - \brief Rotate Right in unsigned value (32 bit) - \details Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits. - \param [in] op1 Value to rotate - \param [in] op2 Number of Bits to rotate - \return Rotated value - */ -__STATIC_FORCEINLINE uint32_t __ROR(uint32_t op1, uint32_t op2) -{ - op2 %= 32U; - if (op2 == 0U) - { - return op1; - } - return (op1 >> op2) | (op1 << (32U - op2)); -} - - -/** - \brief Breakpoint - \details Causes the processor to enter Debug state. - Debug tools can use this to investigate system state when the instruction at a particular address is reached. - \param [in] value is ignored by the processor. - If required, a debugger can use it to store additional information about the breakpoint. - */ -#define __BKPT(value) __ASM volatile ("bkpt "#value) - - -/** - \brief Reverse bit order of value - \details Reverses the bit order of the given value. - \param [in] value Value to reverse - \return Reversed value - */ -#define __RBIT __builtin_arm_rbit - -/** - \brief Count leading zeros - \details Counts the number of leading zeros of a data value. - \param [in] value Value to count the leading zeros - \return number of leading zeros in value - */ -#define __CLZ (uint8_t)__builtin_clz - - -#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) -/** - \brief LDR Exclusive (8 bit) - \details Executes a exclusive LDR instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -#define __LDREXB (uint8_t)__builtin_arm_ldrex - - -/** - \brief LDR Exclusive (16 bit) - \details Executes a exclusive LDR instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -#define __LDREXH (uint16_t)__builtin_arm_ldrex - - -/** - \brief LDR Exclusive (32 bit) - \details Executes a exclusive LDR instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -#define __LDREXW (uint32_t)__builtin_arm_ldrex - - -/** - \brief STR Exclusive (8 bit) - \details Executes a exclusive STR instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#define __STREXB (uint32_t)__builtin_arm_strex - - -/** - \brief STR Exclusive (16 bit) - \details Executes a exclusive STR instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#define __STREXH (uint32_t)__builtin_arm_strex - - -/** - \brief STR Exclusive (32 bit) - \details Executes a exclusive STR instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#define __STREXW (uint32_t)__builtin_arm_strex - - -/** - \brief Remove the exclusive lock - \details Removes the exclusive lock which is created by LDREX. - */ -#define __CLREX __builtin_arm_clrex - -#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ - - -#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) - -/** - \brief Signed Saturate - \details Saturates a signed value. - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (1..32) - \return Saturated value - */ -#define __SSAT __builtin_arm_ssat - - -/** - \brief Unsigned Saturate - \details Saturates an unsigned value. - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (0..31) - \return Saturated value - */ -#define __USAT __builtin_arm_usat - - -/** - \brief Rotate Right with Extend (32 bit) - \details Moves each bit of a bitstring right by one bit. - The carry input is shifted in at the left end of the bitstring. - \param [in] value Value to rotate - \return Rotated value - */ -__STATIC_FORCEINLINE uint32_t __RRX(uint32_t value) -{ - uint32_t result; - - __ASM volatile ("rrx %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return(result); -} - - -/** - \brief LDRT Unprivileged (8 bit) - \details Executes a Unprivileged LDRT instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -__STATIC_FORCEINLINE uint8_t __LDRBT(volatile uint8_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldrbt %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint8_t) result); /* Add explicit type cast here */ -} - - -/** - \brief LDRT Unprivileged (16 bit) - \details Executes a Unprivileged LDRT instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -__STATIC_FORCEINLINE uint16_t __LDRHT(volatile uint16_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldrht %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint16_t) result); /* Add explicit type cast here */ -} - - -/** - \brief LDRT Unprivileged (32 bit) - \details Executes a Unprivileged LDRT instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -__STATIC_FORCEINLINE uint32_t __LDRT(volatile uint32_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldrt %0, %1" : "=r" (result) : "Q" (*ptr) ); - return(result); -} - - -/** - \brief STRT Unprivileged (8 bit) - \details Executes a Unprivileged STRT instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STRBT(uint8_t value, volatile uint8_t *ptr) -{ - __ASM volatile ("strbt %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief STRT Unprivileged (16 bit) - \details Executes a Unprivileged STRT instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STRHT(uint16_t value, volatile uint16_t *ptr) -{ - __ASM volatile ("strht %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief STRT Unprivileged (32 bit) - \details Executes a Unprivileged STRT instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STRT(uint32_t value, volatile uint32_t *ptr) -{ - __ASM volatile ("strt %1, %0" : "=Q" (*ptr) : "r" (value) ); -} - -#else /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ - -/** - \brief Signed Saturate - \details Saturates a signed value. - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (1..32) - \return Saturated value - */ -__STATIC_FORCEINLINE int32_t __SSAT(int32_t val, uint32_t sat) -{ - if ((sat >= 1U) && (sat <= 32U)) - { - const int32_t max = (int32_t)((1U << (sat - 1U)) - 1U); - const int32_t min = -1 - max ; - if (val > max) - { - return max; - } - else if (val < min) - { - return min; - } - } - return val; -} - -/** - \brief Unsigned Saturate - \details Saturates an unsigned value. - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (0..31) - \return Saturated value - */ -__STATIC_FORCEINLINE uint32_t __USAT(int32_t val, uint32_t sat) -{ - if (sat <= 31U) - { - const uint32_t max = ((1U << sat) - 1U); - if (val > (int32_t)max) - { - return max; - } - else if (val < 0) - { - return 0U; - } - } - return (uint32_t)val; -} - -#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ - - -#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) -/** - \brief Load-Acquire (8 bit) - \details Executes a LDAB instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -__STATIC_FORCEINLINE uint8_t __LDAB(volatile uint8_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldab %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint8_t) result); -} - - -/** - \brief Load-Acquire (16 bit) - \details Executes a LDAH instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -__STATIC_FORCEINLINE uint16_t __LDAH(volatile uint16_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldah %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint16_t) result); -} - - -/** - \brief Load-Acquire (32 bit) - \details Executes a LDA instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -__STATIC_FORCEINLINE uint32_t __LDA(volatile uint32_t *ptr) -{ - uint32_t result; - - __ASM volatile ("lda %0, %1" : "=r" (result) : "Q" (*ptr) ); - return(result); -} - - -/** - \brief Store-Release (8 bit) - \details Executes a STLB instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STLB(uint8_t value, volatile uint8_t *ptr) -{ - __ASM volatile ("stlb %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief Store-Release (16 bit) - \details Executes a STLH instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STLH(uint16_t value, volatile uint16_t *ptr) -{ - __ASM volatile ("stlh %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief Store-Release (32 bit) - \details Executes a STL instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STL(uint32_t value, volatile uint32_t *ptr) -{ - __ASM volatile ("stl %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief Load-Acquire Exclusive (8 bit) - \details Executes a LDAB exclusive instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -#define __LDAEXB (uint8_t)__builtin_arm_ldaex - - -/** - \brief Load-Acquire Exclusive (16 bit) - \details Executes a LDAH exclusive instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -#define __LDAEXH (uint16_t)__builtin_arm_ldaex - - -/** - \brief Load-Acquire Exclusive (32 bit) - \details Executes a LDA exclusive instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -#define __LDAEX (uint32_t)__builtin_arm_ldaex - - -/** - \brief Store-Release Exclusive (8 bit) - \details Executes a STLB exclusive instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#define __STLEXB (uint32_t)__builtin_arm_stlex - - -/** - \brief Store-Release Exclusive (16 bit) - \details Executes a STLH exclusive instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#define __STLEXH (uint32_t)__builtin_arm_stlex - - -/** - \brief Store-Release Exclusive (32 bit) - \details Executes a STL exclusive instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -#define __STLEX (uint32_t)__builtin_arm_stlex - -#endif /* ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ - -/*@}*/ /* end of group CMSIS_Core_InstructionInterface */ - - -/* ################### Compiler specific Intrinsics ########################### */ -/** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics - Access to dedicated SIMD instructions - @{ -*/ - -#if (defined (__ARM_FEATURE_DSP) && (__ARM_FEATURE_DSP == 1)) - -__STATIC_FORCEINLINE uint32_t __SADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - - -__STATIC_FORCEINLINE uint32_t __SSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("ssub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - - -__STATIC_FORCEINLINE uint32_t __SADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("ssub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("ssax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USAD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usad8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USADA8(uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("usada8 %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -#define __SSAT16(ARG1,ARG2) \ -({ \ - int32_t __RES, __ARG1 = (ARG1); \ - __ASM ("ssat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) - -#define __USAT16(ARG1,ARG2) \ -({ \ - uint32_t __RES, __ARG1 = (ARG1); \ - __ASM ("usat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) - -__STATIC_FORCEINLINE uint32_t __UXTB16(uint32_t op1) -{ - uint32_t result; - - __ASM volatile ("uxtb16 %0, %1" : "=r" (result) : "r" (op1)); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UXTAB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SXTB16(uint32_t op1) -{ - uint32_t result; - - __ASM volatile ("sxtb16 %0, %1" : "=r" (result) : "r" (op1)); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SXTAB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMUAD (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smuad %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMUADX (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smuadx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMLAD (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smlad %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMLADX (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smladx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__STATIC_FORCEINLINE uint64_t __SMLALD (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__STATIC_FORCEINLINE uint64_t __SMLALDX (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__STATIC_FORCEINLINE uint32_t __SMUSD (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smusd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMUSDX (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smusdx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMLSD (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smlsd %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMLSDX (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smlsdx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__STATIC_FORCEINLINE uint64_t __SMLSLD (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__STATIC_FORCEINLINE uint64_t __SMLSLDX (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__STATIC_FORCEINLINE uint32_t __SEL (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sel %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE int32_t __QADD( int32_t op1, int32_t op2) -{ - int32_t result; - - __ASM volatile ("qadd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE int32_t __QSUB( int32_t op1, int32_t op2) -{ - int32_t result; - - __ASM volatile ("qsub %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -#if 0 -#define __PKHBT(ARG1,ARG2,ARG3) \ -({ \ - uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \ - __ASM ("pkhbt %0, %1, %2, lsl %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \ - __RES; \ - }) - -#define __PKHTB(ARG1,ARG2,ARG3) \ -({ \ - uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \ - if (ARG3 == 0) \ - __ASM ("pkhtb %0, %1, %2" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2) ); \ - else \ - __ASM ("pkhtb %0, %1, %2, asr %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \ - __RES; \ - }) -#endif - -#define __PKHBT(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0x0000FFFFUL) | \ - ((((uint32_t)(ARG2)) << (ARG3)) & 0xFFFF0000UL) ) - -#define __PKHTB(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0xFFFF0000UL) | \ - ((((uint32_t)(ARG2)) >> (ARG3)) & 0x0000FFFFUL) ) - -__STATIC_FORCEINLINE int32_t __SMMLA (int32_t op1, int32_t op2, int32_t op3) -{ - int32_t result; - - __ASM volatile ("smmla %0, %1, %2, %3" : "=r" (result): "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -#endif /* (__ARM_FEATURE_DSP == 1) */ -/*@} end of group CMSIS_SIMD_intrinsics */ - - -#endif /* __CMSIS_ARMCLANG_H */ diff --git a/body/board/inc/cmsis_compiler.h b/body/board/inc/cmsis_compiler.h deleted file mode 100644 index 94212eb..0000000 --- a/body/board/inc/cmsis_compiler.h +++ /dev/null @@ -1,266 +0,0 @@ -/**************************************************************************//** - * @file cmsis_compiler.h - * @brief CMSIS compiler generic header file - * @version V5.0.4 - * @date 10. January 2018 - ******************************************************************************/ -/* - * Copyright (c) 2009-2018 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#ifndef __CMSIS_COMPILER_H -#define __CMSIS_COMPILER_H - -#include - -/* - * Arm Compiler 4/5 - */ -#if defined ( __CC_ARM ) - #include "cmsis_armcc.h" - - -/* - * Arm Compiler 6 (armclang) - */ -#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #include "cmsis_armclang.h" - - -/* - * GNU Compiler - */ -#elif defined ( __GNUC__ ) - #include "cmsis_gcc.h" - - -/* - * IAR Compiler - */ -#elif defined ( __ICCARM__ ) - #include - - -/* - * TI Arm Compiler - */ -#elif defined ( __TI_ARM__ ) - #include - - #ifndef __ASM - #define __ASM __asm - #endif - #ifndef __INLINE - #define __INLINE inline - #endif - #ifndef __STATIC_INLINE - #define __STATIC_INLINE static inline - #endif - #ifndef __STATIC_FORCEINLINE - #define __STATIC_FORCEINLINE __STATIC_INLINE - #endif - #ifndef __NO_RETURN - #define __NO_RETURN __attribute__((noreturn)) - #endif - #ifndef __USED - #define __USED __attribute__((used)) - #endif - #ifndef __WEAK - #define __WEAK __attribute__((weak)) - #endif - #ifndef __PACKED - #define __PACKED __attribute__((packed)) - #endif - #ifndef __PACKED_STRUCT - #define __PACKED_STRUCT struct __attribute__((packed)) - #endif - #ifndef __PACKED_UNION - #define __PACKED_UNION union __attribute__((packed)) - #endif - #ifndef __UNALIGNED_UINT32 /* deprecated */ - struct __attribute__((packed)) T_UINT32 { uint32_t v; }; - #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) - #endif - #ifndef __UNALIGNED_UINT16_WRITE - __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; - #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void*)(addr))->v) = (val)) - #endif - #ifndef __UNALIGNED_UINT16_READ - __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; - #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) - #endif - #ifndef __UNALIGNED_UINT32_WRITE - __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; - #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) - #endif - #ifndef __UNALIGNED_UINT32_READ - __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; - #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) - #endif - #ifndef __ALIGNED - #define __ALIGNED(x) __attribute__((aligned(x))) - #endif - #ifndef __RESTRICT - #warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored. - #define __RESTRICT - #endif - - -/* - * TASKING Compiler - */ -#elif defined ( __TASKING__ ) - /* - * The CMSIS functions have been implemented as intrinsics in the compiler. - * Please use "carm -?i" to get an up to date list of all intrinsics, - * Including the CMSIS ones. - */ - - #ifndef __ASM - #define __ASM __asm - #endif - #ifndef __INLINE - #define __INLINE inline - #endif - #ifndef __STATIC_INLINE - #define __STATIC_INLINE static inline - #endif - #ifndef __STATIC_FORCEINLINE - #define __STATIC_FORCEINLINE __STATIC_INLINE - #endif - #ifndef __NO_RETURN - #define __NO_RETURN __attribute__((noreturn)) - #endif - #ifndef __USED - #define __USED __attribute__((used)) - #endif - #ifndef __WEAK - #define __WEAK __attribute__((weak)) - #endif - #ifndef __PACKED - #define __PACKED __packed__ - #endif - #ifndef __PACKED_STRUCT - #define __PACKED_STRUCT struct __packed__ - #endif - #ifndef __PACKED_UNION - #define __PACKED_UNION union __packed__ - #endif - #ifndef __UNALIGNED_UINT32 /* deprecated */ - struct __packed__ T_UINT32 { uint32_t v; }; - #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) - #endif - #ifndef __UNALIGNED_UINT16_WRITE - __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; - #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val)) - #endif - #ifndef __UNALIGNED_UINT16_READ - __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; - #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) - #endif - #ifndef __UNALIGNED_UINT32_WRITE - __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; - #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) - #endif - #ifndef __UNALIGNED_UINT32_READ - __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; - #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) - #endif - #ifndef __ALIGNED - #define __ALIGNED(x) __align(x) - #endif - #ifndef __RESTRICT - #warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored. - #define __RESTRICT - #endif - - -/* - * COSMIC Compiler - */ -#elif defined ( __CSMC__ ) - #include - - #ifndef __ASM - #define __ASM _asm - #endif - #ifndef __INLINE - #define __INLINE inline - #endif - #ifndef __STATIC_INLINE - #define __STATIC_INLINE static inline - #endif - #ifndef __STATIC_FORCEINLINE - #define __STATIC_FORCEINLINE __STATIC_INLINE - #endif - #ifndef __NO_RETURN - // NO RETURN is automatically detected hence no warning here - #define __NO_RETURN - #endif - #ifndef __USED - #warning No compiler specific solution for __USED. __USED is ignored. - #define __USED - #endif - #ifndef __WEAK - #define __WEAK __weak - #endif - #ifndef __PACKED - #define __PACKED @packed - #endif - #ifndef __PACKED_STRUCT - #define __PACKED_STRUCT @packed struct - #endif - #ifndef __PACKED_UNION - #define __PACKED_UNION @packed union - #endif - #ifndef __UNALIGNED_UINT32 /* deprecated */ - @packed struct T_UINT32 { uint32_t v; }; - #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) - #endif - #ifndef __UNALIGNED_UINT16_WRITE - __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; - #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val)) - #endif - #ifndef __UNALIGNED_UINT16_READ - __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; - #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) - #endif - #ifndef __UNALIGNED_UINT32_WRITE - __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; - #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) - #endif - #ifndef __UNALIGNED_UINT32_READ - __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; - #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) - #endif - #ifndef __ALIGNED - #warning No compiler specific solution for __ALIGNED. __ALIGNED is ignored. - #define __ALIGNED(x) - #endif - #ifndef __RESTRICT - #warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored. - #define __RESTRICT - #endif - - -#else - #error Unknown compiler. -#endif - - -#endif /* __CMSIS_COMPILER_H */ - diff --git a/body/board/inc/cmsis_gcc.h b/body/board/inc/cmsis_gcc.h deleted file mode 100644 index 2d9db15..0000000 --- a/body/board/inc/cmsis_gcc.h +++ /dev/null @@ -1,2085 +0,0 @@ -/**************************************************************************//** - * @file cmsis_gcc.h - * @brief CMSIS compiler GCC header file - * @version V5.0.4 - * @date 09. April 2018 - ******************************************************************************/ -/* - * Copyright (c) 2009-2018 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#ifndef __CMSIS_GCC_H -#define __CMSIS_GCC_H - -/* ignore some GCC warnings */ -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wsign-conversion" -#pragma GCC diagnostic ignored "-Wconversion" -#pragma GCC diagnostic ignored "-Wunused-parameter" - -/* Fallback for __has_builtin */ -#ifndef __has_builtin - #define __has_builtin(x) (0) -#endif - -/* CMSIS compiler specific defines */ -#ifndef __ASM - #define __ASM __asm -#endif -#ifndef __INLINE - #define __INLINE inline -#endif -#ifndef __STATIC_INLINE - #define __STATIC_INLINE static inline -#endif -#ifndef __STATIC_FORCEINLINE - #define __STATIC_FORCEINLINE __attribute__((always_inline)) static inline -#endif -#ifndef __NO_RETURN - #define __NO_RETURN __attribute__((__noreturn__)) -#endif -#ifndef __USED - #define __USED __attribute__((used)) -#endif -#ifndef __WEAK - #define __WEAK __attribute__((weak)) -#endif -#ifndef __PACKED - #define __PACKED __attribute__((packed, aligned(1))) -#endif -#ifndef __PACKED_STRUCT - #define __PACKED_STRUCT struct __attribute__((packed, aligned(1))) -#endif -#ifndef __PACKED_UNION - #define __PACKED_UNION union __attribute__((packed, aligned(1))) -#endif -#ifndef __UNALIGNED_UINT32 /* deprecated */ - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wpacked" - #pragma GCC diagnostic ignored "-Wattributes" - struct __attribute__((packed)) T_UINT32 { uint32_t v; }; - #pragma GCC diagnostic pop - #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) -#endif -#ifndef __UNALIGNED_UINT16_WRITE - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wpacked" - #pragma GCC diagnostic ignored "-Wattributes" - __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; - #pragma GCC diagnostic pop - #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val)) -#endif -#ifndef __UNALIGNED_UINT16_READ - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wpacked" - #pragma GCC diagnostic ignored "-Wattributes" - __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; - #pragma GCC diagnostic pop - #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) -#endif -#ifndef __UNALIGNED_UINT32_WRITE - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wpacked" - #pragma GCC diagnostic ignored "-Wattributes" - __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; - #pragma GCC diagnostic pop - #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) -#endif -#ifndef __UNALIGNED_UINT32_READ - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wpacked" - #pragma GCC diagnostic ignored "-Wattributes" - __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; - #pragma GCC diagnostic pop - #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) -#endif -#ifndef __ALIGNED - #define __ALIGNED(x) __attribute__((aligned(x))) -#endif -#ifndef __RESTRICT - #define __RESTRICT __restrict -#endif - - -/* ########################### Core Function Access ########################### */ -/** \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions - @{ - */ - -/** - \brief Enable IRQ Interrupts - \details Enables IRQ interrupts by clearing the I-bit in the CPSR. - Can only be executed in Privileged modes. - */ -__STATIC_FORCEINLINE void __enable_irq(void) -{ - __ASM volatile ("cpsie i" : : : "memory"); -} - - -/** - \brief Disable IRQ Interrupts - \details Disables IRQ interrupts by setting the I-bit in the CPSR. - Can only be executed in Privileged modes. - */ -__STATIC_FORCEINLINE void __disable_irq(void) -{ - __ASM volatile ("cpsid i" : : : "memory"); -} - - -/** - \brief Get Control Register - \details Returns the content of the Control Register. - \return Control Register value - */ -__STATIC_FORCEINLINE uint32_t __get_CONTROL(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, control" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Control Register (non-secure) - \details Returns the content of the non-secure Control Register when in secure mode. - \return non-secure Control Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_CONTROL_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, control_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Control Register - \details Writes the given value to the Control Register. - \param [in] control Control Register value to set - */ -__STATIC_FORCEINLINE void __set_CONTROL(uint32_t control) -{ - __ASM volatile ("MSR control, %0" : : "r" (control) : "memory"); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Control Register (non-secure) - \details Writes the given value to the non-secure Control Register when in secure state. - \param [in] control Control Register value to set - */ -__STATIC_FORCEINLINE void __TZ_set_CONTROL_NS(uint32_t control) -{ - __ASM volatile ("MSR control_ns, %0" : : "r" (control) : "memory"); -} -#endif - - -/** - \brief Get IPSR Register - \details Returns the content of the IPSR Register. - \return IPSR Register value - */ -__STATIC_FORCEINLINE uint32_t __get_IPSR(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, ipsr" : "=r" (result) ); - return(result); -} - - -/** - \brief Get APSR Register - \details Returns the content of the APSR Register. - \return APSR Register value - */ -__STATIC_FORCEINLINE uint32_t __get_APSR(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, apsr" : "=r" (result) ); - return(result); -} - - -/** - \brief Get xPSR Register - \details Returns the content of the xPSR Register. - \return xPSR Register value - */ -__STATIC_FORCEINLINE uint32_t __get_xPSR(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, xpsr" : "=r" (result) ); - return(result); -} - - -/** - \brief Get Process Stack Pointer - \details Returns the current value of the Process Stack Pointer (PSP). - \return PSP Register value - */ -__STATIC_FORCEINLINE uint32_t __get_PSP(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, psp" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Process Stack Pointer (non-secure) - \details Returns the current value of the non-secure Process Stack Pointer (PSP) when in secure state. - \return PSP Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_PSP_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, psp_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Process Stack Pointer - \details Assigns the given value to the Process Stack Pointer (PSP). - \param [in] topOfProcStack Process Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __set_PSP(uint32_t topOfProcStack) -{ - __ASM volatile ("MSR psp, %0" : : "r" (topOfProcStack) : ); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Process Stack Pointer (non-secure) - \details Assigns the given value to the non-secure Process Stack Pointer (PSP) when in secure state. - \param [in] topOfProcStack Process Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __TZ_set_PSP_NS(uint32_t topOfProcStack) -{ - __ASM volatile ("MSR psp_ns, %0" : : "r" (topOfProcStack) : ); -} -#endif - - -/** - \brief Get Main Stack Pointer - \details Returns the current value of the Main Stack Pointer (MSP). - \return MSP Register value - */ -__STATIC_FORCEINLINE uint32_t __get_MSP(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, msp" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Main Stack Pointer (non-secure) - \details Returns the current value of the non-secure Main Stack Pointer (MSP) when in secure state. - \return MSP Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_MSP_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, msp_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Main Stack Pointer - \details Assigns the given value to the Main Stack Pointer (MSP). - \param [in] topOfMainStack Main Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __set_MSP(uint32_t topOfMainStack) -{ - __ASM volatile ("MSR msp, %0" : : "r" (topOfMainStack) : ); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Main Stack Pointer (non-secure) - \details Assigns the given value to the non-secure Main Stack Pointer (MSP) when in secure state. - \param [in] topOfMainStack Main Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __TZ_set_MSP_NS(uint32_t topOfMainStack) -{ - __ASM volatile ("MSR msp_ns, %0" : : "r" (topOfMainStack) : ); -} -#endif - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Stack Pointer (non-secure) - \details Returns the current value of the non-secure Stack Pointer (SP) when in secure state. - \return SP Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_SP_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, sp_ns" : "=r" (result) ); - return(result); -} - - -/** - \brief Set Stack Pointer (non-secure) - \details Assigns the given value to the non-secure Stack Pointer (SP) when in secure state. - \param [in] topOfStack Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __TZ_set_SP_NS(uint32_t topOfStack) -{ - __ASM volatile ("MSR sp_ns, %0" : : "r" (topOfStack) : ); -} -#endif - - -/** - \brief Get Priority Mask - \details Returns the current state of the priority mask bit from the Priority Mask Register. - \return Priority Mask value - */ -__STATIC_FORCEINLINE uint32_t __get_PRIMASK(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, primask" : "=r" (result) :: "memory"); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Priority Mask (non-secure) - \details Returns the current state of the non-secure priority mask bit from the Priority Mask Register when in secure state. - \return Priority Mask value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_PRIMASK_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, primask_ns" : "=r" (result) :: "memory"); - return(result); -} -#endif - - -/** - \brief Set Priority Mask - \details Assigns the given value to the Priority Mask Register. - \param [in] priMask Priority Mask - */ -__STATIC_FORCEINLINE void __set_PRIMASK(uint32_t priMask) -{ - __ASM volatile ("MSR primask, %0" : : "r" (priMask) : "memory"); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Priority Mask (non-secure) - \details Assigns the given value to the non-secure Priority Mask Register when in secure state. - \param [in] priMask Priority Mask - */ -__STATIC_FORCEINLINE void __TZ_set_PRIMASK_NS(uint32_t priMask) -{ - __ASM volatile ("MSR primask_ns, %0" : : "r" (priMask) : "memory"); -} -#endif - - -#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) -/** - \brief Enable FIQ - \details Enables FIQ interrupts by clearing the F-bit in the CPSR. - Can only be executed in Privileged modes. - */ -__STATIC_FORCEINLINE void __enable_fault_irq(void) -{ - __ASM volatile ("cpsie f" : : : "memory"); -} - - -/** - \brief Disable FIQ - \details Disables FIQ interrupts by setting the F-bit in the CPSR. - Can only be executed in Privileged modes. - */ -__STATIC_FORCEINLINE void __disable_fault_irq(void) -{ - __ASM volatile ("cpsid f" : : : "memory"); -} - - -/** - \brief Get Base Priority - \details Returns the current value of the Base Priority register. - \return Base Priority register value - */ -__STATIC_FORCEINLINE uint32_t __get_BASEPRI(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, basepri" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Base Priority (non-secure) - \details Returns the current value of the non-secure Base Priority register when in secure state. - \return Base Priority register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_BASEPRI_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, basepri_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Base Priority - \details Assigns the given value to the Base Priority register. - \param [in] basePri Base Priority value to set - */ -__STATIC_FORCEINLINE void __set_BASEPRI(uint32_t basePri) -{ - __ASM volatile ("MSR basepri, %0" : : "r" (basePri) : "memory"); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Base Priority (non-secure) - \details Assigns the given value to the non-secure Base Priority register when in secure state. - \param [in] basePri Base Priority value to set - */ -__STATIC_FORCEINLINE void __TZ_set_BASEPRI_NS(uint32_t basePri) -{ - __ASM volatile ("MSR basepri_ns, %0" : : "r" (basePri) : "memory"); -} -#endif - - -/** - \brief Set Base Priority with condition - \details Assigns the given value to the Base Priority register only if BASEPRI masking is disabled, - or the new value increases the BASEPRI priority level. - \param [in] basePri Base Priority value to set - */ -__STATIC_FORCEINLINE void __set_BASEPRI_MAX(uint32_t basePri) -{ - __ASM volatile ("MSR basepri_max, %0" : : "r" (basePri) : "memory"); -} - - -/** - \brief Get Fault Mask - \details Returns the current value of the Fault Mask register. - \return Fault Mask register value - */ -__STATIC_FORCEINLINE uint32_t __get_FAULTMASK(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, faultmask" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Fault Mask (non-secure) - \details Returns the current value of the non-secure Fault Mask register when in secure state. - \return Fault Mask register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_FAULTMASK_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, faultmask_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Fault Mask - \details Assigns the given value to the Fault Mask register. - \param [in] faultMask Fault Mask value to set - */ -__STATIC_FORCEINLINE void __set_FAULTMASK(uint32_t faultMask) -{ - __ASM volatile ("MSR faultmask, %0" : : "r" (faultMask) : "memory"); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Fault Mask (non-secure) - \details Assigns the given value to the non-secure Fault Mask register when in secure state. - \param [in] faultMask Fault Mask value to set - */ -__STATIC_FORCEINLINE void __TZ_set_FAULTMASK_NS(uint32_t faultMask) -{ - __ASM volatile ("MSR faultmask_ns, %0" : : "r" (faultMask) : "memory"); -} -#endif - -#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ - - -#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) - -/** - \brief Get Process Stack Pointer Limit - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence zero is returned always in non-secure - mode. - - \details Returns the current value of the Process Stack Pointer Limit (PSPLIM). - \return PSPLIM Register value - */ -__STATIC_FORCEINLINE uint32_t __get_PSPLIM(void) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - return 0U; -#else - uint32_t result; - __ASM volatile ("MRS %0, psplim" : "=r" (result) ); - return result; -#endif -} - -#if (defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Process Stack Pointer Limit (non-secure) - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence zero is returned always. - - \details Returns the current value of the non-secure Process Stack Pointer Limit (PSPLIM) when in secure state. - \return PSPLIM Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_PSPLIM_NS(void) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - return 0U; -#else - uint32_t result; - __ASM volatile ("MRS %0, psplim_ns" : "=r" (result) ); - return result; -#endif -} -#endif - - -/** - \brief Set Process Stack Pointer Limit - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence the write is silently ignored in non-secure - mode. - - \details Assigns the given value to the Process Stack Pointer Limit (PSPLIM). - \param [in] ProcStackPtrLimit Process Stack Pointer Limit value to set - */ -__STATIC_FORCEINLINE void __set_PSPLIM(uint32_t ProcStackPtrLimit) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - (void)ProcStackPtrLimit; -#else - __ASM volatile ("MSR psplim, %0" : : "r" (ProcStackPtrLimit)); -#endif -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Process Stack Pointer (non-secure) - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence the write is silently ignored. - - \details Assigns the given value to the non-secure Process Stack Pointer Limit (PSPLIM) when in secure state. - \param [in] ProcStackPtrLimit Process Stack Pointer Limit value to set - */ -__STATIC_FORCEINLINE void __TZ_set_PSPLIM_NS(uint32_t ProcStackPtrLimit) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - (void)ProcStackPtrLimit; -#else - __ASM volatile ("MSR psplim_ns, %0\n" : : "r" (ProcStackPtrLimit)); -#endif -} -#endif - - -/** - \brief Get Main Stack Pointer Limit - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence zero is returned always in non-secure - mode. - - \details Returns the current value of the Main Stack Pointer Limit (MSPLIM). - \return MSPLIM Register value - */ -__STATIC_FORCEINLINE uint32_t __get_MSPLIM(void) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - return 0U; -#else - uint32_t result; - __ASM volatile ("MRS %0, msplim" : "=r" (result) ); - return result; -#endif -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Main Stack Pointer Limit (non-secure) - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence zero is returned always. - - \details Returns the current value of the non-secure Main Stack Pointer Limit(MSPLIM) when in secure state. - \return MSPLIM Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_MSPLIM_NS(void) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - return 0U; -#else - uint32_t result; - __ASM volatile ("MRS %0, msplim_ns" : "=r" (result) ); - return result; -#endif -} -#endif - - -/** - \brief Set Main Stack Pointer Limit - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence the write is silently ignored in non-secure - mode. - - \details Assigns the given value to the Main Stack Pointer Limit (MSPLIM). - \param [in] MainStackPtrLimit Main Stack Pointer Limit value to set - */ -__STATIC_FORCEINLINE void __set_MSPLIM(uint32_t MainStackPtrLimit) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - (void)MainStackPtrLimit; -#else - __ASM volatile ("MSR msplim, %0" : : "r" (MainStackPtrLimit)); -#endif -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Main Stack Pointer Limit (non-secure) - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence the write is silently ignored. - - \details Assigns the given value to the non-secure Main Stack Pointer Limit (MSPLIM) when in secure state. - \param [in] MainStackPtrLimit Main Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __TZ_set_MSPLIM_NS(uint32_t MainStackPtrLimit) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - (void)MainStackPtrLimit; -#else - __ASM volatile ("MSR msplim_ns, %0" : : "r" (MainStackPtrLimit)); -#endif -} -#endif - -#endif /* ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ - - -/** - \brief Get FPSCR - \details Returns the current value of the Floating Point Status/Control register. - \return Floating Point Status/Control register value - */ -__STATIC_FORCEINLINE uint32_t __get_FPSCR(void) -{ -#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ - (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) -#if __has_builtin(__builtin_arm_get_fpscr) -// Re-enable using built-in when GCC has been fixed -// || (__GNUC__ > 7) || (__GNUC__ == 7 && __GNUC_MINOR__ >= 2) - /* see https://gcc.gnu.org/ml/gcc-patches/2017-04/msg00443.html */ - return __builtin_arm_get_fpscr(); -#else - uint32_t result; - - __ASM volatile ("VMRS %0, fpscr" : "=r" (result) ); - return(result); -#endif -#else - return(0U); -#endif -} - - -/** - \brief Set FPSCR - \details Assigns the given value to the Floating Point Status/Control register. - \param [in] fpscr Floating Point Status/Control value to set - */ -__STATIC_FORCEINLINE void __set_FPSCR(uint32_t fpscr) -{ -#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ - (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) -#if __has_builtin(__builtin_arm_set_fpscr) -// Re-enable using built-in when GCC has been fixed -// || (__GNUC__ > 7) || (__GNUC__ == 7 && __GNUC_MINOR__ >= 2) - /* see https://gcc.gnu.org/ml/gcc-patches/2017-04/msg00443.html */ - __builtin_arm_set_fpscr(fpscr); -#else - __ASM volatile ("VMSR fpscr, %0" : : "r" (fpscr) : "vfpcc", "memory"); -#endif -#else - (void)fpscr; -#endif -} - - -/*@} end of CMSIS_Core_RegAccFunctions */ - - -/* ########################## Core Instruction Access ######################### */ -/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface - Access to dedicated instructions - @{ -*/ - -/* Define macros for porting to both thumb1 and thumb2. - * For thumb1, use low register (r0-r7), specified by constraint "l" - * Otherwise, use general registers, specified by constraint "r" */ -#if defined (__thumb__) && !defined (__thumb2__) -#define __CMSIS_GCC_OUT_REG(r) "=l" (r) -#define __CMSIS_GCC_RW_REG(r) "+l" (r) -#define __CMSIS_GCC_USE_REG(r) "l" (r) -#else -#define __CMSIS_GCC_OUT_REG(r) "=r" (r) -#define __CMSIS_GCC_RW_REG(r) "+r" (r) -#define __CMSIS_GCC_USE_REG(r) "r" (r) -#endif - -/** - \brief No Operation - \details No Operation does nothing. This instruction can be used for code alignment purposes. - */ -#define __NOP() __ASM volatile ("nop") - -/** - \brief Wait For Interrupt - \details Wait For Interrupt is a hint instruction that suspends execution until one of a number of events occurs. - */ -#define __WFI() __ASM volatile ("wfi") - - -/** - \brief Wait For Event - \details Wait For Event is a hint instruction that permits the processor to enter - a low-power state until one of a number of events occurs. - */ -#define __WFE() __ASM volatile ("wfe") - - -/** - \brief Send Event - \details Send Event is a hint instruction. It causes an event to be signaled to the CPU. - */ -#define __SEV() __ASM volatile ("sev") - - -/** - \brief Instruction Synchronization Barrier - \details Instruction Synchronization Barrier flushes the pipeline in the processor, - so that all instructions following the ISB are fetched from cache or memory, - after the instruction has been completed. - */ -__STATIC_FORCEINLINE void __ISB(void) -{ - __ASM volatile ("isb 0xF":::"memory"); -} - - -/** - \brief Data Synchronization Barrier - \details Acts as a special kind of Data Memory Barrier. - It completes when all explicit memory accesses before this instruction complete. - */ -__STATIC_FORCEINLINE void __DSB(void) -{ - __ASM volatile ("dsb 0xF":::"memory"); -} - - -/** - \brief Data Memory Barrier - \details Ensures the apparent order of the explicit memory operations before - and after the instruction, without ensuring their completion. - */ -__STATIC_FORCEINLINE void __DMB(void) -{ - __ASM volatile ("dmb 0xF":::"memory"); -} - - -/** - \brief Reverse byte order (32 bit) - \details Reverses the byte order in unsigned integer value. For example, 0x12345678 becomes 0x78563412. - \param [in] value Value to reverse - \return Reversed value - */ -__STATIC_FORCEINLINE uint32_t __REV(uint32_t value) -{ -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 5) - return __builtin_bswap32(value); -#else - uint32_t result; - - __ASM volatile ("rev %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return result; -#endif -} - - -/** - \brief Reverse byte order (16 bit) - \details Reverses the byte order within each halfword of a word. For example, 0x12345678 becomes 0x34127856. - \param [in] value Value to reverse - \return Reversed value - */ -__STATIC_FORCEINLINE uint32_t __REV16(uint32_t value) -{ - uint32_t result; - - __ASM volatile ("rev16 %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return result; -} - - -/** - \brief Reverse byte order (16 bit) - \details Reverses the byte order in a 16-bit value and returns the signed 16-bit result. For example, 0x0080 becomes 0x8000. - \param [in] value Value to reverse - \return Reversed value - */ -__STATIC_FORCEINLINE int16_t __REVSH(int16_t value) -{ -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - return (int16_t)__builtin_bswap16(value); -#else - int16_t result; - - __ASM volatile ("revsh %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return result; -#endif -} - - -/** - \brief Rotate Right in unsigned value (32 bit) - \details Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits. - \param [in] op1 Value to rotate - \param [in] op2 Number of Bits to rotate - \return Rotated value - */ -__STATIC_FORCEINLINE uint32_t __ROR(uint32_t op1, uint32_t op2) -{ - op2 %= 32U; - if (op2 == 0U) - { - return op1; - } - return (op1 >> op2) | (op1 << (32U - op2)); -} - - -/** - \brief Breakpoint - \details Causes the processor to enter Debug state. - Debug tools can use this to investigate system state when the instruction at a particular address is reached. - \param [in] value is ignored by the processor. - If required, a debugger can use it to store additional information about the breakpoint. - */ -#define __BKPT(value) __ASM volatile ("bkpt "#value) - - -/** - \brief Reverse bit order of value - \details Reverses the bit order of the given value. - \param [in] value Value to reverse - \return Reversed value - */ -__STATIC_FORCEINLINE uint32_t __RBIT(uint32_t value) -{ - uint32_t result; - -#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) - __ASM volatile ("rbit %0, %1" : "=r" (result) : "r" (value) ); -#else - uint32_t s = (4U /*sizeof(v)*/ * 8U) - 1U; /* extra shift needed at end */ - - result = value; /* r will be reversed bits of v; first get LSB of v */ - for (value >>= 1U; value != 0U; value >>= 1U) - { - result <<= 1U; - result |= value & 1U; - s--; - } - result <<= s; /* shift when v's highest bits are zero */ -#endif - return result; -} - - -/** - \brief Count leading zeros - \details Counts the number of leading zeros of a data value. - \param [in] value Value to count the leading zeros - \return number of leading zeros in value - */ -#define __CLZ (uint8_t)__builtin_clz - - -#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) -/** - \brief LDR Exclusive (8 bit) - \details Executes a exclusive LDR instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -__STATIC_FORCEINLINE uint8_t __LDREXB(volatile uint8_t *addr) -{ - uint32_t result; - -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - __ASM volatile ("ldrexb %0, %1" : "=r" (result) : "Q" (*addr) ); -#else - /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not - accepted by assembler. So has to use following less efficient pattern. - */ - __ASM volatile ("ldrexb %0, [%1]" : "=r" (result) : "r" (addr) : "memory" ); -#endif - return ((uint8_t) result); /* Add explicit type cast here */ -} - - -/** - \brief LDR Exclusive (16 bit) - \details Executes a exclusive LDR instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -__STATIC_FORCEINLINE uint16_t __LDREXH(volatile uint16_t *addr) -{ - uint32_t result; - -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - __ASM volatile ("ldrexh %0, %1" : "=r" (result) : "Q" (*addr) ); -#else - /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not - accepted by assembler. So has to use following less efficient pattern. - */ - __ASM volatile ("ldrexh %0, [%1]" : "=r" (result) : "r" (addr) : "memory" ); -#endif - return ((uint16_t) result); /* Add explicit type cast here */ -} - - -/** - \brief LDR Exclusive (32 bit) - \details Executes a exclusive LDR instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -__STATIC_FORCEINLINE uint32_t __LDREXW(volatile uint32_t *addr) -{ - uint32_t result; - - __ASM volatile ("ldrex %0, %1" : "=r" (result) : "Q" (*addr) ); - return(result); -} - - -/** - \brief STR Exclusive (8 bit) - \details Executes a exclusive STR instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__STATIC_FORCEINLINE uint32_t __STREXB(uint8_t value, volatile uint8_t *addr) -{ - uint32_t result; - - __ASM volatile ("strexb %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" ((uint32_t)value) ); - return(result); -} - - -/** - \brief STR Exclusive (16 bit) - \details Executes a exclusive STR instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__STATIC_FORCEINLINE uint32_t __STREXH(uint16_t value, volatile uint16_t *addr) -{ - uint32_t result; - - __ASM volatile ("strexh %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" ((uint32_t)value) ); - return(result); -} - - -/** - \brief STR Exclusive (32 bit) - \details Executes a exclusive STR instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__STATIC_FORCEINLINE uint32_t __STREXW(uint32_t value, volatile uint32_t *addr) -{ - uint32_t result; - - __ASM volatile ("strex %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" (value) ); - return(result); -} - - -/** - \brief Remove the exclusive lock - \details Removes the exclusive lock which is created by LDREX. - */ -__STATIC_FORCEINLINE void __CLREX(void) -{ - __ASM volatile ("clrex" ::: "memory"); -} - -#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ - - -#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) -/** - \brief Signed Saturate - \details Saturates a signed value. - \param [in] ARG1 Value to be saturated - \param [in] ARG2 Bit position to saturate to (1..32) - \return Saturated value - */ -#define __SSAT(ARG1,ARG2) \ -__extension__ \ -({ \ - int32_t __RES, __ARG1 = (ARG1); \ - __ASM ("ssat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) - - -/** - \brief Unsigned Saturate - \details Saturates an unsigned value. - \param [in] ARG1 Value to be saturated - \param [in] ARG2 Bit position to saturate to (0..31) - \return Saturated value - */ -#define __USAT(ARG1,ARG2) \ - __extension__ \ -({ \ - uint32_t __RES, __ARG1 = (ARG1); \ - __ASM ("usat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) - - -/** - \brief Rotate Right with Extend (32 bit) - \details Moves each bit of a bitstring right by one bit. - The carry input is shifted in at the left end of the bitstring. - \param [in] value Value to rotate - \return Rotated value - */ -__STATIC_FORCEINLINE uint32_t __RRX(uint32_t value) -{ - uint32_t result; - - __ASM volatile ("rrx %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return(result); -} - - -/** - \brief LDRT Unprivileged (8 bit) - \details Executes a Unprivileged LDRT instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -__STATIC_FORCEINLINE uint8_t __LDRBT(volatile uint8_t *ptr) -{ - uint32_t result; - -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - __ASM volatile ("ldrbt %0, %1" : "=r" (result) : "Q" (*ptr) ); -#else - /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not - accepted by assembler. So has to use following less efficient pattern. - */ - __ASM volatile ("ldrbt %0, [%1]" : "=r" (result) : "r" (ptr) : "memory" ); -#endif - return ((uint8_t) result); /* Add explicit type cast here */ -} - - -/** - \brief LDRT Unprivileged (16 bit) - \details Executes a Unprivileged LDRT instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -__STATIC_FORCEINLINE uint16_t __LDRHT(volatile uint16_t *ptr) -{ - uint32_t result; - -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - __ASM volatile ("ldrht %0, %1" : "=r" (result) : "Q" (*ptr) ); -#else - /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not - accepted by assembler. So has to use following less efficient pattern. - */ - __ASM volatile ("ldrht %0, [%1]" : "=r" (result) : "r" (ptr) : "memory" ); -#endif - return ((uint16_t) result); /* Add explicit type cast here */ -} - - -/** - \brief LDRT Unprivileged (32 bit) - \details Executes a Unprivileged LDRT instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -__STATIC_FORCEINLINE uint32_t __LDRT(volatile uint32_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldrt %0, %1" : "=r" (result) : "Q" (*ptr) ); - return(result); -} - - -/** - \brief STRT Unprivileged (8 bit) - \details Executes a Unprivileged STRT instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STRBT(uint8_t value, volatile uint8_t *ptr) -{ - __ASM volatile ("strbt %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief STRT Unprivileged (16 bit) - \details Executes a Unprivileged STRT instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STRHT(uint16_t value, volatile uint16_t *ptr) -{ - __ASM volatile ("strht %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief STRT Unprivileged (32 bit) - \details Executes a Unprivileged STRT instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STRT(uint32_t value, volatile uint32_t *ptr) -{ - __ASM volatile ("strt %1, %0" : "=Q" (*ptr) : "r" (value) ); -} - -#else /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ - -/** - \brief Signed Saturate - \details Saturates a signed value. - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (1..32) - \return Saturated value - */ -__STATIC_FORCEINLINE int32_t __SSAT(int32_t val, uint32_t sat) -{ - if ((sat >= 1U) && (sat <= 32U)) - { - const int32_t max = (int32_t)((1U << (sat - 1U)) - 1U); - const int32_t min = -1 - max ; - if (val > max) - { - return max; - } - else if (val < min) - { - return min; - } - } - return val; -} - -/** - \brief Unsigned Saturate - \details Saturates an unsigned value. - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (0..31) - \return Saturated value - */ -__STATIC_FORCEINLINE uint32_t __USAT(int32_t val, uint32_t sat) -{ - if (sat <= 31U) - { - const uint32_t max = ((1U << sat) - 1U); - if (val > (int32_t)max) - { - return max; - } - else if (val < 0) - { - return 0U; - } - } - return (uint32_t)val; -} - -#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ - - -#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) -/** - \brief Load-Acquire (8 bit) - \details Executes a LDAB instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -__STATIC_FORCEINLINE uint8_t __LDAB(volatile uint8_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldab %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint8_t) result); -} - - -/** - \brief Load-Acquire (16 bit) - \details Executes a LDAH instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -__STATIC_FORCEINLINE uint16_t __LDAH(volatile uint16_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldah %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint16_t) result); -} - - -/** - \brief Load-Acquire (32 bit) - \details Executes a LDA instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -__STATIC_FORCEINLINE uint32_t __LDA(volatile uint32_t *ptr) -{ - uint32_t result; - - __ASM volatile ("lda %0, %1" : "=r" (result) : "Q" (*ptr) ); - return(result); -} - - -/** - \brief Store-Release (8 bit) - \details Executes a STLB instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STLB(uint8_t value, volatile uint8_t *ptr) -{ - __ASM volatile ("stlb %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief Store-Release (16 bit) - \details Executes a STLH instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STLH(uint16_t value, volatile uint16_t *ptr) -{ - __ASM volatile ("stlh %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief Store-Release (32 bit) - \details Executes a STL instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STL(uint32_t value, volatile uint32_t *ptr) -{ - __ASM volatile ("stl %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief Load-Acquire Exclusive (8 bit) - \details Executes a LDAB exclusive instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -__STATIC_FORCEINLINE uint8_t __LDAEXB(volatile uint8_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldaexb %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint8_t) result); -} - - -/** - \brief Load-Acquire Exclusive (16 bit) - \details Executes a LDAH exclusive instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -__STATIC_FORCEINLINE uint16_t __LDAEXH(volatile uint16_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldaexh %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint16_t) result); -} - - -/** - \brief Load-Acquire Exclusive (32 bit) - \details Executes a LDA exclusive instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -__STATIC_FORCEINLINE uint32_t __LDAEX(volatile uint32_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldaex %0, %1" : "=r" (result) : "Q" (*ptr) ); - return(result); -} - - -/** - \brief Store-Release Exclusive (8 bit) - \details Executes a STLB exclusive instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__STATIC_FORCEINLINE uint32_t __STLEXB(uint8_t value, volatile uint8_t *ptr) -{ - uint32_t result; - - __ASM volatile ("stlexb %0, %2, %1" : "=&r" (result), "=Q" (*ptr) : "r" ((uint32_t)value) ); - return(result); -} - - -/** - \brief Store-Release Exclusive (16 bit) - \details Executes a STLH exclusive instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__STATIC_FORCEINLINE uint32_t __STLEXH(uint16_t value, volatile uint16_t *ptr) -{ - uint32_t result; - - __ASM volatile ("stlexh %0, %2, %1" : "=&r" (result), "=Q" (*ptr) : "r" ((uint32_t)value) ); - return(result); -} - - -/** - \brief Store-Release Exclusive (32 bit) - \details Executes a STL exclusive instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__STATIC_FORCEINLINE uint32_t __STLEX(uint32_t value, volatile uint32_t *ptr) -{ - uint32_t result; - - __ASM volatile ("stlex %0, %2, %1" : "=&r" (result), "=Q" (*ptr) : "r" ((uint32_t)value) ); - return(result); -} - -#endif /* ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ - -/*@}*/ /* end of group CMSIS_Core_InstructionInterface */ - - -/* ################### Compiler specific Intrinsics ########################### */ -/** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics - Access to dedicated SIMD instructions - @{ -*/ - -#if (defined (__ARM_FEATURE_DSP) && (__ARM_FEATURE_DSP == 1)) - -__STATIC_FORCEINLINE uint32_t __SADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - - -__STATIC_FORCEINLINE uint32_t __SSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("ssub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - - -__STATIC_FORCEINLINE uint32_t __SADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("ssub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("ssax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USAD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usad8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USADA8(uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("usada8 %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -#define __SSAT16(ARG1,ARG2) \ -({ \ - int32_t __RES, __ARG1 = (ARG1); \ - __ASM ("ssat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) - -#define __USAT16(ARG1,ARG2) \ -({ \ - uint32_t __RES, __ARG1 = (ARG1); \ - __ASM ("usat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) - -__STATIC_FORCEINLINE uint32_t __UXTB16(uint32_t op1) -{ - uint32_t result; - - __ASM volatile ("uxtb16 %0, %1" : "=r" (result) : "r" (op1)); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UXTAB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SXTB16(uint32_t op1) -{ - uint32_t result; - - __ASM volatile ("sxtb16 %0, %1" : "=r" (result) : "r" (op1)); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SXTAB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMUAD (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smuad %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMUADX (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smuadx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMLAD (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smlad %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMLADX (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smladx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__STATIC_FORCEINLINE uint64_t __SMLALD (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__STATIC_FORCEINLINE uint64_t __SMLALDX (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__STATIC_FORCEINLINE uint32_t __SMUSD (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smusd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMUSDX (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smusdx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMLSD (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smlsd %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMLSDX (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smlsdx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__STATIC_FORCEINLINE uint64_t __SMLSLD (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__STATIC_FORCEINLINE uint64_t __SMLSLDX (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__STATIC_FORCEINLINE uint32_t __SEL (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sel %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE int32_t __QADD( int32_t op1, int32_t op2) -{ - int32_t result; - - __ASM volatile ("qadd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE int32_t __QSUB( int32_t op1, int32_t op2) -{ - int32_t result; - - __ASM volatile ("qsub %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -#if 0 -#define __PKHBT(ARG1,ARG2,ARG3) \ -({ \ - uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \ - __ASM ("pkhbt %0, %1, %2, lsl %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \ - __RES; \ - }) - -#define __PKHTB(ARG1,ARG2,ARG3) \ -({ \ - uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \ - if (ARG3 == 0) \ - __ASM ("pkhtb %0, %1, %2" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2) ); \ - else \ - __ASM ("pkhtb %0, %1, %2, asr %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \ - __RES; \ - }) -#endif - -#define __PKHBT(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0x0000FFFFUL) | \ - ((((uint32_t)(ARG2)) << (ARG3)) & 0xFFFF0000UL) ) - -#define __PKHTB(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0xFFFF0000UL) | \ - ((((uint32_t)(ARG2)) >> (ARG3)) & 0x0000FFFFUL) ) - -__STATIC_FORCEINLINE int32_t __SMMLA (int32_t op1, int32_t op2, int32_t op3) -{ - int32_t result; - - __ASM volatile ("smmla %0, %1, %2, %3" : "=r" (result): "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -#endif /* (__ARM_FEATURE_DSP == 1) */ -/*@} end of group CMSIS_SIMD_intrinsics */ - - -#pragma GCC diagnostic pop - -#endif /* __CMSIS_GCC_H */ diff --git a/body/board/inc/cmsis_iccarm.h b/body/board/inc/cmsis_iccarm.h deleted file mode 100644 index 11c4af0..0000000 --- a/body/board/inc/cmsis_iccarm.h +++ /dev/null @@ -1,935 +0,0 @@ -/**************************************************************************//** - * @file cmsis_iccarm.h - * @brief CMSIS compiler ICCARM (IAR Compiler for Arm) header file - * @version V5.0.7 - * @date 19. June 2018 - ******************************************************************************/ - -//------------------------------------------------------------------------------ -// -// Copyright (c) 2017-2018 IAR Systems -// -// Licensed under the Apache License, Version 2.0 (the "License") -// you may not use this file except in compliance with the License. -// You may obtain a copy of the License at -// http://www.apache.org/licenses/LICENSE-2.0 -// -// Unless required by applicable law or agreed to in writing, software -// distributed under the License is distributed on an "AS IS" BASIS, -// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -// See the License for the specific language governing permissions and -// limitations under the License. -// -//------------------------------------------------------------------------------ - - -#ifndef __CMSIS_ICCARM_H__ -#define __CMSIS_ICCARM_H__ - -#ifndef __ICCARM__ - #error This file should only be compiled by ICCARM -#endif - -#pragma system_include - -#define __IAR_FT _Pragma("inline=forced") __intrinsic - -#if (__VER__ >= 8000000) - #define __ICCARM_V8 1 -#else - #define __ICCARM_V8 0 -#endif - -#ifndef __ALIGNED - #if __ICCARM_V8 - #define __ALIGNED(x) __attribute__((aligned(x))) - #elif (__VER__ >= 7080000) - /* Needs IAR language extensions */ - #define __ALIGNED(x) __attribute__((aligned(x))) - #else - #warning No compiler specific solution for __ALIGNED.__ALIGNED is ignored. - #define __ALIGNED(x) - #endif -#endif - - -/* Define compiler macros for CPU architecture, used in CMSIS 5. - */ -#if __ARM_ARCH_6M__ || __ARM_ARCH_7M__ || __ARM_ARCH_7EM__ || __ARM_ARCH_8M_BASE__ || __ARM_ARCH_8M_MAIN__ -/* Macros already defined */ -#else - #if defined(__ARM8M_MAINLINE__) || defined(__ARM8EM_MAINLINE__) - #define __ARM_ARCH_8M_MAIN__ 1 - #elif defined(__ARM8M_BASELINE__) - #define __ARM_ARCH_8M_BASE__ 1 - #elif defined(__ARM_ARCH_PROFILE) && __ARM_ARCH_PROFILE == 'M' - #if __ARM_ARCH == 6 - #define __ARM_ARCH_6M__ 1 - #elif __ARM_ARCH == 7 - #if __ARM_FEATURE_DSP - #define __ARM_ARCH_7EM__ 1 - #else - #define __ARM_ARCH_7M__ 1 - #endif - #endif /* __ARM_ARCH */ - #endif /* __ARM_ARCH_PROFILE == 'M' */ -#endif - -/* Alternativ core deduction for older ICCARM's */ -#if !defined(__ARM_ARCH_6M__) && !defined(__ARM_ARCH_7M__) && !defined(__ARM_ARCH_7EM__) && \ - !defined(__ARM_ARCH_8M_BASE__) && !defined(__ARM_ARCH_8M_MAIN__) - #if defined(__ARM6M__) && (__CORE__ == __ARM6M__) - #define __ARM_ARCH_6M__ 1 - #elif defined(__ARM7M__) && (__CORE__ == __ARM7M__) - #define __ARM_ARCH_7M__ 1 - #elif defined(__ARM7EM__) && (__CORE__ == __ARM7EM__) - #define __ARM_ARCH_7EM__ 1 - #elif defined(__ARM8M_BASELINE__) && (__CORE == __ARM8M_BASELINE__) - #define __ARM_ARCH_8M_BASE__ 1 - #elif defined(__ARM8M_MAINLINE__) && (__CORE == __ARM8M_MAINLINE__) - #define __ARM_ARCH_8M_MAIN__ 1 - #elif defined(__ARM8EM_MAINLINE__) && (__CORE == __ARM8EM_MAINLINE__) - #define __ARM_ARCH_8M_MAIN__ 1 - #else - #error "Unknown target." - #endif -#endif - - - -#if defined(__ARM_ARCH_6M__) && __ARM_ARCH_6M__==1 - #define __IAR_M0_FAMILY 1 -#elif defined(__ARM_ARCH_8M_BASE__) && __ARM_ARCH_8M_BASE__==1 - #define __IAR_M0_FAMILY 1 -#else - #define __IAR_M0_FAMILY 0 -#endif - - -#ifndef __ASM - #define __ASM __asm -#endif - -#ifndef __INLINE - #define __INLINE inline -#endif - -#ifndef __NO_RETURN - #if __ICCARM_V8 - #define __NO_RETURN __attribute__((__noreturn__)) - #else - #define __NO_RETURN _Pragma("object_attribute=__noreturn") - #endif -#endif - -#ifndef __PACKED - #if __ICCARM_V8 - #define __PACKED __attribute__((packed, aligned(1))) - #else - /* Needs IAR language extensions */ - #define __PACKED __packed - #endif -#endif - -#ifndef __PACKED_STRUCT - #if __ICCARM_V8 - #define __PACKED_STRUCT struct __attribute__((packed, aligned(1))) - #else - /* Needs IAR language extensions */ - #define __PACKED_STRUCT __packed struct - #endif -#endif - -#ifndef __PACKED_UNION - #if __ICCARM_V8 - #define __PACKED_UNION union __attribute__((packed, aligned(1))) - #else - /* Needs IAR language extensions */ - #define __PACKED_UNION __packed union - #endif -#endif - -#ifndef __RESTRICT - #define __RESTRICT __restrict -#endif - -#ifndef __STATIC_INLINE - #define __STATIC_INLINE static inline -#endif - -#ifndef __FORCEINLINE - #define __FORCEINLINE _Pragma("inline=forced") -#endif - -#ifndef __STATIC_FORCEINLINE - #define __STATIC_FORCEINLINE __FORCEINLINE __STATIC_INLINE -#endif - -#ifndef __UNALIGNED_UINT16_READ -#pragma language=save -#pragma language=extended -__IAR_FT uint16_t __iar_uint16_read(void const *ptr) -{ - return *(__packed uint16_t*)(ptr); -} -#pragma language=restore -#define __UNALIGNED_UINT16_READ(PTR) __iar_uint16_read(PTR) -#endif - - -#ifndef __UNALIGNED_UINT16_WRITE -#pragma language=save -#pragma language=extended -__IAR_FT void __iar_uint16_write(void const *ptr, uint16_t val) -{ - *(__packed uint16_t*)(ptr) = val;; -} -#pragma language=restore -#define __UNALIGNED_UINT16_WRITE(PTR,VAL) __iar_uint16_write(PTR,VAL) -#endif - -#ifndef __UNALIGNED_UINT32_READ -#pragma language=save -#pragma language=extended -__IAR_FT uint32_t __iar_uint32_read(void const *ptr) -{ - return *(__packed uint32_t*)(ptr); -} -#pragma language=restore -#define __UNALIGNED_UINT32_READ(PTR) __iar_uint32_read(PTR) -#endif - -#ifndef __UNALIGNED_UINT32_WRITE -#pragma language=save -#pragma language=extended -__IAR_FT void __iar_uint32_write(void const *ptr, uint32_t val) -{ - *(__packed uint32_t*)(ptr) = val;; -} -#pragma language=restore -#define __UNALIGNED_UINT32_WRITE(PTR,VAL) __iar_uint32_write(PTR,VAL) -#endif - -#ifndef __UNALIGNED_UINT32 /* deprecated */ -#pragma language=save -#pragma language=extended -__packed struct __iar_u32 { uint32_t v; }; -#pragma language=restore -#define __UNALIGNED_UINT32(PTR) (((struct __iar_u32 *)(PTR))->v) -#endif - -#ifndef __USED - #if __ICCARM_V8 - #define __USED __attribute__((used)) - #else - #define __USED _Pragma("__root") - #endif -#endif - -#ifndef __WEAK - #if __ICCARM_V8 - #define __WEAK __attribute__((weak)) - #else - #define __WEAK _Pragma("__weak") - #endif -#endif - - -#ifndef __ICCARM_INTRINSICS_VERSION__ - #define __ICCARM_INTRINSICS_VERSION__ 0 -#endif - -#if __ICCARM_INTRINSICS_VERSION__ == 2 - - #if defined(__CLZ) - #undef __CLZ - #endif - #if defined(__REVSH) - #undef __REVSH - #endif - #if defined(__RBIT) - #undef __RBIT - #endif - #if defined(__SSAT) - #undef __SSAT - #endif - #if defined(__USAT) - #undef __USAT - #endif - - #include "iccarm_builtin.h" - - #define __disable_fault_irq __iar_builtin_disable_fiq - #define __disable_irq __iar_builtin_disable_interrupt - #define __enable_fault_irq __iar_builtin_enable_fiq - #define __enable_irq __iar_builtin_enable_interrupt - #define __arm_rsr __iar_builtin_rsr - #define __arm_wsr __iar_builtin_wsr - - - #define __get_APSR() (__arm_rsr("APSR")) - #define __get_BASEPRI() (__arm_rsr("BASEPRI")) - #define __get_CONTROL() (__arm_rsr("CONTROL")) - #define __get_FAULTMASK() (__arm_rsr("FAULTMASK")) - - #if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ - (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) - #define __get_FPSCR() (__arm_rsr("FPSCR")) - #define __set_FPSCR(VALUE) (__arm_wsr("FPSCR", (VALUE))) - #else - #define __get_FPSCR() ( 0 ) - #define __set_FPSCR(VALUE) ((void)VALUE) - #endif - - #define __get_IPSR() (__arm_rsr("IPSR")) - #define __get_MSP() (__arm_rsr("MSP")) - #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - #define __get_MSPLIM() (0U) - #else - #define __get_MSPLIM() (__arm_rsr("MSPLIM")) - #endif - #define __get_PRIMASK() (__arm_rsr("PRIMASK")) - #define __get_PSP() (__arm_rsr("PSP")) - - #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - #define __get_PSPLIM() (0U) - #else - #define __get_PSPLIM() (__arm_rsr("PSPLIM")) - #endif - - #define __get_xPSR() (__arm_rsr("xPSR")) - - #define __set_BASEPRI(VALUE) (__arm_wsr("BASEPRI", (VALUE))) - #define __set_BASEPRI_MAX(VALUE) (__arm_wsr("BASEPRI_MAX", (VALUE))) - #define __set_CONTROL(VALUE) (__arm_wsr("CONTROL", (VALUE))) - #define __set_FAULTMASK(VALUE) (__arm_wsr("FAULTMASK", (VALUE))) - #define __set_MSP(VALUE) (__arm_wsr("MSP", (VALUE))) - - #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - #define __set_MSPLIM(VALUE) ((void)(VALUE)) - #else - #define __set_MSPLIM(VALUE) (__arm_wsr("MSPLIM", (VALUE))) - #endif - #define __set_PRIMASK(VALUE) (__arm_wsr("PRIMASK", (VALUE))) - #define __set_PSP(VALUE) (__arm_wsr("PSP", (VALUE))) - #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - #define __set_PSPLIM(VALUE) ((void)(VALUE)) - #else - #define __set_PSPLIM(VALUE) (__arm_wsr("PSPLIM", (VALUE))) - #endif - - #define __TZ_get_CONTROL_NS() (__arm_rsr("CONTROL_NS")) - #define __TZ_set_CONTROL_NS(VALUE) (__arm_wsr("CONTROL_NS", (VALUE))) - #define __TZ_get_PSP_NS() (__arm_rsr("PSP_NS")) - #define __TZ_set_PSP_NS(VALUE) (__arm_wsr("PSP_NS", (VALUE))) - #define __TZ_get_MSP_NS() (__arm_rsr("MSP_NS")) - #define __TZ_set_MSP_NS(VALUE) (__arm_wsr("MSP_NS", (VALUE))) - #define __TZ_get_SP_NS() (__arm_rsr("SP_NS")) - #define __TZ_set_SP_NS(VALUE) (__arm_wsr("SP_NS", (VALUE))) - #define __TZ_get_PRIMASK_NS() (__arm_rsr("PRIMASK_NS")) - #define __TZ_set_PRIMASK_NS(VALUE) (__arm_wsr("PRIMASK_NS", (VALUE))) - #define __TZ_get_BASEPRI_NS() (__arm_rsr("BASEPRI_NS")) - #define __TZ_set_BASEPRI_NS(VALUE) (__arm_wsr("BASEPRI_NS", (VALUE))) - #define __TZ_get_FAULTMASK_NS() (__arm_rsr("FAULTMASK_NS")) - #define __TZ_set_FAULTMASK_NS(VALUE)(__arm_wsr("FAULTMASK_NS", (VALUE))) - - #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - #define __TZ_get_PSPLIM_NS() (0U) - #define __TZ_set_PSPLIM_NS(VALUE) ((void)(VALUE)) - #else - #define __TZ_get_PSPLIM_NS() (__arm_rsr("PSPLIM_NS")) - #define __TZ_set_PSPLIM_NS(VALUE) (__arm_wsr("PSPLIM_NS", (VALUE))) - #endif - - #define __TZ_get_MSPLIM_NS() (__arm_rsr("MSPLIM_NS")) - #define __TZ_set_MSPLIM_NS(VALUE) (__arm_wsr("MSPLIM_NS", (VALUE))) - - #define __NOP __iar_builtin_no_operation - - #define __CLZ __iar_builtin_CLZ - #define __CLREX __iar_builtin_CLREX - - #define __DMB __iar_builtin_DMB - #define __DSB __iar_builtin_DSB - #define __ISB __iar_builtin_ISB - - #define __LDREXB __iar_builtin_LDREXB - #define __LDREXH __iar_builtin_LDREXH - #define __LDREXW __iar_builtin_LDREX - - #define __RBIT __iar_builtin_RBIT - #define __REV __iar_builtin_REV - #define __REV16 __iar_builtin_REV16 - - __IAR_FT int16_t __REVSH(int16_t val) - { - return (int16_t) __iar_builtin_REVSH(val); - } - - #define __ROR __iar_builtin_ROR - #define __RRX __iar_builtin_RRX - - #define __SEV __iar_builtin_SEV - - #if !__IAR_M0_FAMILY - #define __SSAT __iar_builtin_SSAT - #endif - - #define __STREXB __iar_builtin_STREXB - #define __STREXH __iar_builtin_STREXH - #define __STREXW __iar_builtin_STREX - - #if !__IAR_M0_FAMILY - #define __USAT __iar_builtin_USAT - #endif - - #define __WFE __iar_builtin_WFE - #define __WFI __iar_builtin_WFI - - #if __ARM_MEDIA__ - #define __SADD8 __iar_builtin_SADD8 - #define __QADD8 __iar_builtin_QADD8 - #define __SHADD8 __iar_builtin_SHADD8 - #define __UADD8 __iar_builtin_UADD8 - #define __UQADD8 __iar_builtin_UQADD8 - #define __UHADD8 __iar_builtin_UHADD8 - #define __SSUB8 __iar_builtin_SSUB8 - #define __QSUB8 __iar_builtin_QSUB8 - #define __SHSUB8 __iar_builtin_SHSUB8 - #define __USUB8 __iar_builtin_USUB8 - #define __UQSUB8 __iar_builtin_UQSUB8 - #define __UHSUB8 __iar_builtin_UHSUB8 - #define __SADD16 __iar_builtin_SADD16 - #define __QADD16 __iar_builtin_QADD16 - #define __SHADD16 __iar_builtin_SHADD16 - #define __UADD16 __iar_builtin_UADD16 - #define __UQADD16 __iar_builtin_UQADD16 - #define __UHADD16 __iar_builtin_UHADD16 - #define __SSUB16 __iar_builtin_SSUB16 - #define __QSUB16 __iar_builtin_QSUB16 - #define __SHSUB16 __iar_builtin_SHSUB16 - #define __USUB16 __iar_builtin_USUB16 - #define __UQSUB16 __iar_builtin_UQSUB16 - #define __UHSUB16 __iar_builtin_UHSUB16 - #define __SASX __iar_builtin_SASX - #define __QASX __iar_builtin_QASX - #define __SHASX __iar_builtin_SHASX - #define __UASX __iar_builtin_UASX - #define __UQASX __iar_builtin_UQASX - #define __UHASX __iar_builtin_UHASX - #define __SSAX __iar_builtin_SSAX - #define __QSAX __iar_builtin_QSAX - #define __SHSAX __iar_builtin_SHSAX - #define __USAX __iar_builtin_USAX - #define __UQSAX __iar_builtin_UQSAX - #define __UHSAX __iar_builtin_UHSAX - #define __USAD8 __iar_builtin_USAD8 - #define __USADA8 __iar_builtin_USADA8 - #define __SSAT16 __iar_builtin_SSAT16 - #define __USAT16 __iar_builtin_USAT16 - #define __UXTB16 __iar_builtin_UXTB16 - #define __UXTAB16 __iar_builtin_UXTAB16 - #define __SXTB16 __iar_builtin_SXTB16 - #define __SXTAB16 __iar_builtin_SXTAB16 - #define __SMUAD __iar_builtin_SMUAD - #define __SMUADX __iar_builtin_SMUADX - #define __SMMLA __iar_builtin_SMMLA - #define __SMLAD __iar_builtin_SMLAD - #define __SMLADX __iar_builtin_SMLADX - #define __SMLALD __iar_builtin_SMLALD - #define __SMLALDX __iar_builtin_SMLALDX - #define __SMUSD __iar_builtin_SMUSD - #define __SMUSDX __iar_builtin_SMUSDX - #define __SMLSD __iar_builtin_SMLSD - #define __SMLSDX __iar_builtin_SMLSDX - #define __SMLSLD __iar_builtin_SMLSLD - #define __SMLSLDX __iar_builtin_SMLSLDX - #define __SEL __iar_builtin_SEL - #define __QADD __iar_builtin_QADD - #define __QSUB __iar_builtin_QSUB - #define __PKHBT __iar_builtin_PKHBT - #define __PKHTB __iar_builtin_PKHTB - #endif - -#else /* __ICCARM_INTRINSICS_VERSION__ == 2 */ - - #if __IAR_M0_FAMILY - /* Avoid clash between intrinsics.h and arm_math.h when compiling for Cortex-M0. */ - #define __CLZ __cmsis_iar_clz_not_active - #define __SSAT __cmsis_iar_ssat_not_active - #define __USAT __cmsis_iar_usat_not_active - #define __RBIT __cmsis_iar_rbit_not_active - #define __get_APSR __cmsis_iar_get_APSR_not_active - #endif - - - #if (!((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ - (defined (__FPU_USED ) && (__FPU_USED == 1U)) )) - #define __get_FPSCR __cmsis_iar_get_FPSR_not_active - #define __set_FPSCR __cmsis_iar_set_FPSR_not_active - #endif - - #ifdef __INTRINSICS_INCLUDED - #error intrinsics.h is already included previously! - #endif - - #include - - #if __IAR_M0_FAMILY - /* Avoid clash between intrinsics.h and arm_math.h when compiling for Cortex-M0. */ - #undef __CLZ - #undef __SSAT - #undef __USAT - #undef __RBIT - #undef __get_APSR - - __STATIC_INLINE uint8_t __CLZ(uint32_t data) - { - if (data == 0U) { return 32U; } - - uint32_t count = 0U; - uint32_t mask = 0x80000000U; - - while ((data & mask) == 0U) - { - count += 1U; - mask = mask >> 1U; - } - return count; - } - - __STATIC_INLINE uint32_t __RBIT(uint32_t v) - { - uint8_t sc = 31U; - uint32_t r = v; - for (v >>= 1U; v; v >>= 1U) - { - r <<= 1U; - r |= v & 1U; - sc--; - } - return (r << sc); - } - - __STATIC_INLINE uint32_t __get_APSR(void) - { - uint32_t res; - __asm("MRS %0,APSR" : "=r" (res)); - return res; - } - - #endif - - #if (!((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ - (defined (__FPU_USED ) && (__FPU_USED == 1U)) )) - #undef __get_FPSCR - #undef __set_FPSCR - #define __get_FPSCR() (0) - #define __set_FPSCR(VALUE) ((void)VALUE) - #endif - - #pragma diag_suppress=Pe940 - #pragma diag_suppress=Pe177 - - #define __enable_irq __enable_interrupt - #define __disable_irq __disable_interrupt - #define __NOP __no_operation - - #define __get_xPSR __get_PSR - - #if (!defined(__ARM_ARCH_6M__) || __ARM_ARCH_6M__==0) - - __IAR_FT uint32_t __LDREXW(uint32_t volatile *ptr) - { - return __LDREX((unsigned long *)ptr); - } - - __IAR_FT uint32_t __STREXW(uint32_t value, uint32_t volatile *ptr) - { - return __STREX(value, (unsigned long *)ptr); - } - #endif - - - /* __CORTEX_M is defined in core_cm0.h, core_cm3.h and core_cm4.h. */ - #if (__CORTEX_M >= 0x03) - - __IAR_FT uint32_t __RRX(uint32_t value) - { - uint32_t result; - __ASM("RRX %0, %1" : "=r"(result) : "r" (value) : "cc"); - return(result); - } - - __IAR_FT void __set_BASEPRI_MAX(uint32_t value) - { - __asm volatile("MSR BASEPRI_MAX,%0"::"r" (value)); - } - - - #define __enable_fault_irq __enable_fiq - #define __disable_fault_irq __disable_fiq - - - #endif /* (__CORTEX_M >= 0x03) */ - - __IAR_FT uint32_t __ROR(uint32_t op1, uint32_t op2) - { - return (op1 >> op2) | (op1 << ((sizeof(op1)*8)-op2)); - } - - #if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) - - __IAR_FT uint32_t __get_MSPLIM(void) - { - uint32_t res; - #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE ) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - res = 0U; - #else - __asm volatile("MRS %0,MSPLIM" : "=r" (res)); - #endif - return res; - } - - __IAR_FT void __set_MSPLIM(uint32_t value) - { - #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE ) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - (void)value; - #else - __asm volatile("MSR MSPLIM,%0" :: "r" (value)); - #endif - } - - __IAR_FT uint32_t __get_PSPLIM(void) - { - uint32_t res; - #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE ) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - res = 0U; - #else - __asm volatile("MRS %0,PSPLIM" : "=r" (res)); - #endif - return res; - } - - __IAR_FT void __set_PSPLIM(uint32_t value) - { - #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE ) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - (void)value; - #else - __asm volatile("MSR PSPLIM,%0" :: "r" (value)); - #endif - } - - __IAR_FT uint32_t __TZ_get_CONTROL_NS(void) - { - uint32_t res; - __asm volatile("MRS %0,CONTROL_NS" : "=r" (res)); - return res; - } - - __IAR_FT void __TZ_set_CONTROL_NS(uint32_t value) - { - __asm volatile("MSR CONTROL_NS,%0" :: "r" (value)); - } - - __IAR_FT uint32_t __TZ_get_PSP_NS(void) - { - uint32_t res; - __asm volatile("MRS %0,PSP_NS" : "=r" (res)); - return res; - } - - __IAR_FT void __TZ_set_PSP_NS(uint32_t value) - { - __asm volatile("MSR PSP_NS,%0" :: "r" (value)); - } - - __IAR_FT uint32_t __TZ_get_MSP_NS(void) - { - uint32_t res; - __asm volatile("MRS %0,MSP_NS" : "=r" (res)); - return res; - } - - __IAR_FT void __TZ_set_MSP_NS(uint32_t value) - { - __asm volatile("MSR MSP_NS,%0" :: "r" (value)); - } - - __IAR_FT uint32_t __TZ_get_SP_NS(void) - { - uint32_t res; - __asm volatile("MRS %0,SP_NS" : "=r" (res)); - return res; - } - __IAR_FT void __TZ_set_SP_NS(uint32_t value) - { - __asm volatile("MSR SP_NS,%0" :: "r" (value)); - } - - __IAR_FT uint32_t __TZ_get_PRIMASK_NS(void) - { - uint32_t res; - __asm volatile("MRS %0,PRIMASK_NS" : "=r" (res)); - return res; - } - - __IAR_FT void __TZ_set_PRIMASK_NS(uint32_t value) - { - __asm volatile("MSR PRIMASK_NS,%0" :: "r" (value)); - } - - __IAR_FT uint32_t __TZ_get_BASEPRI_NS(void) - { - uint32_t res; - __asm volatile("MRS %0,BASEPRI_NS" : "=r" (res)); - return res; - } - - __IAR_FT void __TZ_set_BASEPRI_NS(uint32_t value) - { - __asm volatile("MSR BASEPRI_NS,%0" :: "r" (value)); - } - - __IAR_FT uint32_t __TZ_get_FAULTMASK_NS(void) - { - uint32_t res; - __asm volatile("MRS %0,FAULTMASK_NS" : "=r" (res)); - return res; - } - - __IAR_FT void __TZ_set_FAULTMASK_NS(uint32_t value) - { - __asm volatile("MSR FAULTMASK_NS,%0" :: "r" (value)); - } - - __IAR_FT uint32_t __TZ_get_PSPLIM_NS(void) - { - uint32_t res; - #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE ) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - res = 0U; - #else - __asm volatile("MRS %0,PSPLIM_NS" : "=r" (res)); - #endif - return res; - } - - __IAR_FT void __TZ_set_PSPLIM_NS(uint32_t value) - { - #if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE ) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - (void)value; - #else - __asm volatile("MSR PSPLIM_NS,%0" :: "r" (value)); - #endif - } - - __IAR_FT uint32_t __TZ_get_MSPLIM_NS(void) - { - uint32_t res; - __asm volatile("MRS %0,MSPLIM_NS" : "=r" (res)); - return res; - } - - __IAR_FT void __TZ_set_MSPLIM_NS(uint32_t value) - { - __asm volatile("MSR MSPLIM_NS,%0" :: "r" (value)); - } - - #endif /* __ARM_ARCH_8M_MAIN__ or __ARM_ARCH_8M_BASE__ */ - -#endif /* __ICCARM_INTRINSICS_VERSION__ == 2 */ - -#define __BKPT(value) __asm volatile ("BKPT %0" : : "i"(value)) - -#if __IAR_M0_FAMILY - __STATIC_INLINE int32_t __SSAT(int32_t val, uint32_t sat) - { - if ((sat >= 1U) && (sat <= 32U)) - { - const int32_t max = (int32_t)((1U << (sat - 1U)) - 1U); - const int32_t min = -1 - max ; - if (val > max) - { - return max; - } - else if (val < min) - { - return min; - } - } - return val; - } - - __STATIC_INLINE uint32_t __USAT(int32_t val, uint32_t sat) - { - if (sat <= 31U) - { - const uint32_t max = ((1U << sat) - 1U); - if (val > (int32_t)max) - { - return max; - } - else if (val < 0) - { - return 0U; - } - } - return (uint32_t)val; - } -#endif - -#if (__CORTEX_M >= 0x03) /* __CORTEX_M is defined in core_cm0.h, core_cm3.h and core_cm4.h. */ - - __IAR_FT uint8_t __LDRBT(volatile uint8_t *addr) - { - uint32_t res; - __ASM("LDRBT %0, [%1]" : "=r" (res) : "r" (addr) : "memory"); - return ((uint8_t)res); - } - - __IAR_FT uint16_t __LDRHT(volatile uint16_t *addr) - { - uint32_t res; - __ASM("LDRHT %0, [%1]" : "=r" (res) : "r" (addr) : "memory"); - return ((uint16_t)res); - } - - __IAR_FT uint32_t __LDRT(volatile uint32_t *addr) - { - uint32_t res; - __ASM("LDRT %0, [%1]" : "=r" (res) : "r" (addr) : "memory"); - return res; - } - - __IAR_FT void __STRBT(uint8_t value, volatile uint8_t *addr) - { - __ASM("STRBT %1, [%0]" : : "r" (addr), "r" ((uint32_t)value) : "memory"); - } - - __IAR_FT void __STRHT(uint16_t value, volatile uint16_t *addr) - { - __ASM("STRHT %1, [%0]" : : "r" (addr), "r" ((uint32_t)value) : "memory"); - } - - __IAR_FT void __STRT(uint32_t value, volatile uint32_t *addr) - { - __ASM("STRT %1, [%0]" : : "r" (addr), "r" (value) : "memory"); - } - -#endif /* (__CORTEX_M >= 0x03) */ - -#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) - - - __IAR_FT uint8_t __LDAB(volatile uint8_t *ptr) - { - uint32_t res; - __ASM volatile ("LDAB %0, [%1]" : "=r" (res) : "r" (ptr) : "memory"); - return ((uint8_t)res); - } - - __IAR_FT uint16_t __LDAH(volatile uint16_t *ptr) - { - uint32_t res; - __ASM volatile ("LDAH %0, [%1]" : "=r" (res) : "r" (ptr) : "memory"); - return ((uint16_t)res); - } - - __IAR_FT uint32_t __LDA(volatile uint32_t *ptr) - { - uint32_t res; - __ASM volatile ("LDA %0, [%1]" : "=r" (res) : "r" (ptr) : "memory"); - return res; - } - - __IAR_FT void __STLB(uint8_t value, volatile uint8_t *ptr) - { - __ASM volatile ("STLB %1, [%0]" :: "r" (ptr), "r" (value) : "memory"); - } - - __IAR_FT void __STLH(uint16_t value, volatile uint16_t *ptr) - { - __ASM volatile ("STLH %1, [%0]" :: "r" (ptr), "r" (value) : "memory"); - } - - __IAR_FT void __STL(uint32_t value, volatile uint32_t *ptr) - { - __ASM volatile ("STL %1, [%0]" :: "r" (ptr), "r" (value) : "memory"); - } - - __IAR_FT uint8_t __LDAEXB(volatile uint8_t *ptr) - { - uint32_t res; - __ASM volatile ("LDAEXB %0, [%1]" : "=r" (res) : "r" (ptr) : "memory"); - return ((uint8_t)res); - } - - __IAR_FT uint16_t __LDAEXH(volatile uint16_t *ptr) - { - uint32_t res; - __ASM volatile ("LDAEXH %0, [%1]" : "=r" (res) : "r" (ptr) : "memory"); - return ((uint16_t)res); - } - - __IAR_FT uint32_t __LDAEX(volatile uint32_t *ptr) - { - uint32_t res; - __ASM volatile ("LDAEX %0, [%1]" : "=r" (res) : "r" (ptr) : "memory"); - return res; - } - - __IAR_FT uint32_t __STLEXB(uint8_t value, volatile uint8_t *ptr) - { - uint32_t res; - __ASM volatile ("STLEXB %0, %2, [%1]" : "=r" (res) : "r" (ptr), "r" (value) : "memory"); - return res; - } - - __IAR_FT uint32_t __STLEXH(uint16_t value, volatile uint16_t *ptr) - { - uint32_t res; - __ASM volatile ("STLEXH %0, %2, [%1]" : "=r" (res) : "r" (ptr), "r" (value) : "memory"); - return res; - } - - __IAR_FT uint32_t __STLEX(uint32_t value, volatile uint32_t *ptr) - { - uint32_t res; - __ASM volatile ("STLEX %0, %2, [%1]" : "=r" (res) : "r" (ptr), "r" (value) : "memory"); - return res; - } - -#endif /* __ARM_ARCH_8M_MAIN__ or __ARM_ARCH_8M_BASE__ */ - -#undef __IAR_FT -#undef __IAR_M0_FAMILY -#undef __ICCARM_V8 - -#pragma diag_default=Pe940 -#pragma diag_default=Pe177 - -#endif /* __CMSIS_ICCARM_H__ */ diff --git a/body/board/inc/cmsis_version.h b/body/board/inc/cmsis_version.h deleted file mode 100644 index 660f612..0000000 --- a/body/board/inc/cmsis_version.h +++ /dev/null @@ -1,39 +0,0 @@ -/**************************************************************************//** - * @file cmsis_version.h - * @brief CMSIS Core(M) Version definitions - * @version V5.0.2 - * @date 19. April 2017 - ******************************************************************************/ -/* - * Copyright (c) 2009-2017 ARM Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef __CMSIS_VERSION_H -#define __CMSIS_VERSION_H - -/* CMSIS Version definitions */ -#define __CM_CMSIS_VERSION_MAIN ( 5U) /*!< [31:16] CMSIS Core(M) main version */ -#define __CM_CMSIS_VERSION_SUB ( 1U) /*!< [15:0] CMSIS Core(M) sub version */ -#define __CM_CMSIS_VERSION ((__CM_CMSIS_VERSION_MAIN << 16U) | \ - __CM_CMSIS_VERSION_SUB ) /*!< CMSIS Core(M) version number */ -#endif diff --git a/body/board/inc/core_armv8mbl.h b/body/board/inc/core_armv8mbl.h deleted file mode 100644 index 251e4ed..0000000 --- a/body/board/inc/core_armv8mbl.h +++ /dev/null @@ -1,1918 +0,0 @@ -/**************************************************************************//** - * @file core_armv8mbl.h - * @brief CMSIS Armv8-M Baseline Core Peripheral Access Layer Header File - * @version V5.0.7 - * @date 22. June 2018 - ******************************************************************************/ -/* - * Copyright (c) 2009-2018 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef __CORE_ARMV8MBL_H_GENERIC -#define __CORE_ARMV8MBL_H_GENERIC - -#include - -#ifdef __cplusplus - extern "C" { -#endif - -/** - \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions - CMSIS violates the following MISRA-C:2004 rules: - - \li Required Rule 8.5, object/function definition in header file.
- Function definitions in header files are used to allow 'inlining'. - - \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
- Unions are used for effective representation of core registers. - - \li Advisory Rule 19.7, Function-like macro defined.
- Function-like macros are used to allow more efficient code. - */ - - -/******************************************************************************* - * CMSIS definitions - ******************************************************************************/ -/** - \ingroup Cortex_ARMv8MBL - @{ - */ - -#include "cmsis_version.h" - -/* CMSIS definitions */ -#define __ARMv8MBL_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */ -#define __ARMv8MBL_CMSIS_VERSION_SUB (__CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */ -#define __ARMv8MBL_CMSIS_VERSION ((__ARMv8MBL_CMSIS_VERSION_MAIN << 16U) | \ - __ARMv8MBL_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */ - -#define __CORTEX_M ( 2U) /*!< Cortex-M Core */ - -/** __FPU_USED indicates whether an FPU is used or not. - This core does not support an FPU at all -*/ -#define __FPU_USED 0U - -#if defined ( __CC_ARM ) - #if defined __TARGET_FPU_VFP - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #if defined __ARM_PCS_VFP - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __GNUC__ ) - #if defined (__VFP_FP__) && !defined(__SOFTFP__) - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __ICCARM__ ) - #if defined __ARMVFP__ - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __TI_ARM__ ) - #if defined __TI_VFP_SUPPORT__ - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __TASKING__ ) - #if defined __FPU_VFP__ - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __CSMC__ ) - #if ( __CSMC__ & 0x400U) - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#endif - -#include "cmsis_compiler.h" /* CMSIS compiler specific defines */ - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_ARMV8MBL_H_GENERIC */ - -#ifndef __CMSIS_GENERIC - -#ifndef __CORE_ARMV8MBL_H_DEPENDANT -#define __CORE_ARMV8MBL_H_DEPENDANT - -#ifdef __cplusplus - extern "C" { -#endif - -/* check device defines and use defaults */ -#if defined __CHECK_DEVICE_DEFINES - #ifndef __ARMv8MBL_REV - #define __ARMv8MBL_REV 0x0000U - #warning "__ARMv8MBL_REV not defined in device header file; using default!" - #endif - - #ifndef __FPU_PRESENT - #define __FPU_PRESENT 0U - #warning "__FPU_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __MPU_PRESENT - #define __MPU_PRESENT 0U - #warning "__MPU_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __SAUREGION_PRESENT - #define __SAUREGION_PRESENT 0U - #warning "__SAUREGION_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __VTOR_PRESENT - #define __VTOR_PRESENT 0U - #warning "__VTOR_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __NVIC_PRIO_BITS - #define __NVIC_PRIO_BITS 2U - #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" - #endif - - #ifndef __Vendor_SysTickConfig - #define __Vendor_SysTickConfig 0U - #warning "__Vendor_SysTickConfig not defined in device header file; using default!" - #endif - - #ifndef __ETM_PRESENT - #define __ETM_PRESENT 0U - #warning "__ETM_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __MTB_PRESENT - #define __MTB_PRESENT 0U - #warning "__MTB_PRESENT not defined in device header file; using default!" - #endif - -#endif - -/* IO definitions (access restrictions to peripheral registers) */ -/** - \defgroup CMSIS_glob_defs CMSIS Global Defines - - IO Type Qualifiers are used - \li to specify the access to peripheral variables. - \li for automatic generation of peripheral register debug information. -*/ -#ifdef __cplusplus - #define __I volatile /*!< Defines 'read only' permissions */ -#else - #define __I volatile const /*!< Defines 'read only' permissions */ -#endif -#define __O volatile /*!< Defines 'write only' permissions */ -#define __IO volatile /*!< Defines 'read / write' permissions */ - -/* following defines should be used for structure members */ -#define __IM volatile const /*! Defines 'read only' structure member permissions */ -#define __OM volatile /*! Defines 'write only' structure member permissions */ -#define __IOM volatile /*! Defines 'read / write' structure member permissions */ - -/*@} end of group ARMv8MBL */ - - - -/******************************************************************************* - * Register Abstraction - Core Register contain: - - Core Register - - Core NVIC Register - - Core SCB Register - - Core SysTick Register - - Core Debug Register - - Core MPU Register - - Core SAU Register - ******************************************************************************/ -/** - \defgroup CMSIS_core_register Defines and Type Definitions - \brief Type definitions and defines for Cortex-M processor based devices. -*/ - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CORE Status and Control Registers - \brief Core Register type definitions. - @{ - */ - -/** - \brief Union type to access the Application Program Status Register (APSR). - */ -typedef union -{ - struct - { - uint32_t _reserved0:28; /*!< bit: 0..27 Reserved */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} APSR_Type; - -/* APSR Register Definitions */ -#define APSR_N_Pos 31U /*!< APSR: N Position */ -#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ - -#define APSR_Z_Pos 30U /*!< APSR: Z Position */ -#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ - -#define APSR_C_Pos 29U /*!< APSR: C Position */ -#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ - -#define APSR_V_Pos 28U /*!< APSR: V Position */ -#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ - - -/** - \brief Union type to access the Interrupt Program Status Register (IPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} IPSR_Type; - -/* IPSR Register Definitions */ -#define IPSR_ISR_Pos 0U /*!< IPSR: ISR Position */ -#define IPSR_ISR_Msk (0x1FFUL /*<< IPSR_ISR_Pos*/) /*!< IPSR: ISR Mask */ - - -/** - \brief Union type to access the Special-Purpose Program Status Registers (xPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:15; /*!< bit: 9..23 Reserved */ - uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */ - uint32_t _reserved1:3; /*!< bit: 25..27 Reserved */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} xPSR_Type; - -/* xPSR Register Definitions */ -#define xPSR_N_Pos 31U /*!< xPSR: N Position */ -#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ - -#define xPSR_Z_Pos 30U /*!< xPSR: Z Position */ -#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ - -#define xPSR_C_Pos 29U /*!< xPSR: C Position */ -#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ - -#define xPSR_V_Pos 28U /*!< xPSR: V Position */ -#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ - -#define xPSR_T_Pos 24U /*!< xPSR: T Position */ -#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ - -#define xPSR_ISR_Pos 0U /*!< xPSR: ISR Position */ -#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ - - -/** - \brief Union type to access the Control Registers (CONTROL). - */ -typedef union -{ - struct - { - uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ - uint32_t SPSEL:1; /*!< bit: 1 Stack-pointer select */ - uint32_t _reserved1:30; /*!< bit: 2..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} CONTROL_Type; - -/* CONTROL Register Definitions */ -#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */ -#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ - -#define CONTROL_nPRIV_Pos 0U /*!< CONTROL: nPRIV Position */ -#define CONTROL_nPRIV_Msk (1UL /*<< CONTROL_nPRIV_Pos*/) /*!< CONTROL: nPRIV Mask */ - -/*@} end of group CMSIS_CORE */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC) - \brief Type definitions for the NVIC Registers - @{ - */ - -/** - \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). - */ -typedef struct -{ - __IOM uint32_t ISER[16U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ - uint32_t RESERVED0[16U]; - __IOM uint32_t ICER[16U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ - uint32_t RSERVED1[16U]; - __IOM uint32_t ISPR[16U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ - uint32_t RESERVED2[16U]; - __IOM uint32_t ICPR[16U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ - uint32_t RESERVED3[16U]; - __IOM uint32_t IABR[16U]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */ - uint32_t RESERVED4[16U]; - __IOM uint32_t ITNS[16U]; /*!< Offset: 0x280 (R/W) Interrupt Non-Secure State Register */ - uint32_t RESERVED5[16U]; - __IOM uint32_t IPR[124U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register */ -} NVIC_Type; - -/*@} end of group CMSIS_NVIC */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SCB System Control Block (SCB) - \brief Type definitions for the System Control Block Registers - @{ - */ - -/** - \brief Structure type to access the System Control Block (SCB). - */ -typedef struct -{ - __IM uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ - __IOM uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ -#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U) - __IOM uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ -#else - uint32_t RESERVED0; -#endif - __IOM uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ - __IOM uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ - __IOM uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ - uint32_t RESERVED1; - __IOM uint32_t SHPR[2U]; /*!< Offset: 0x01C (R/W) System Handlers Priority Registers. [0] is RESERVED */ - __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ -} SCB_Type; - -/* SCB CPUID Register Definitions */ -#define SCB_CPUID_IMPLEMENTER_Pos 24U /*!< SCB CPUID: IMPLEMENTER Position */ -#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ - -#define SCB_CPUID_VARIANT_Pos 20U /*!< SCB CPUID: VARIANT Position */ -#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ - -#define SCB_CPUID_ARCHITECTURE_Pos 16U /*!< SCB CPUID: ARCHITECTURE Position */ -#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ - -#define SCB_CPUID_PARTNO_Pos 4U /*!< SCB CPUID: PARTNO Position */ -#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ - -#define SCB_CPUID_REVISION_Pos 0U /*!< SCB CPUID: REVISION Position */ -#define SCB_CPUID_REVISION_Msk (0xFUL /*<< SCB_CPUID_REVISION_Pos*/) /*!< SCB CPUID: REVISION Mask */ - -/* SCB Interrupt Control State Register Definitions */ -#define SCB_ICSR_PENDNMISET_Pos 31U /*!< SCB ICSR: PENDNMISET Position */ -#define SCB_ICSR_PENDNMISET_Msk (1UL << SCB_ICSR_PENDNMISET_Pos) /*!< SCB ICSR: PENDNMISET Mask */ - -#define SCB_ICSR_NMIPENDSET_Pos SCB_ICSR_PENDNMISET_Pos /*!< SCB ICSR: NMIPENDSET Position, backward compatibility */ -#define SCB_ICSR_NMIPENDSET_Msk SCB_ICSR_PENDNMISET_Msk /*!< SCB ICSR: NMIPENDSET Mask, backward compatibility */ - -#define SCB_ICSR_PENDNMICLR_Pos 30U /*!< SCB ICSR: PENDNMICLR Position */ -#define SCB_ICSR_PENDNMICLR_Msk (1UL << SCB_ICSR_PENDNMICLR_Pos) /*!< SCB ICSR: PENDNMICLR Mask */ - -#define SCB_ICSR_PENDSVSET_Pos 28U /*!< SCB ICSR: PENDSVSET Position */ -#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ - -#define SCB_ICSR_PENDSVCLR_Pos 27U /*!< SCB ICSR: PENDSVCLR Position */ -#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ - -#define SCB_ICSR_PENDSTSET_Pos 26U /*!< SCB ICSR: PENDSTSET Position */ -#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ - -#define SCB_ICSR_PENDSTCLR_Pos 25U /*!< SCB ICSR: PENDSTCLR Position */ -#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ - -#define SCB_ICSR_STTNS_Pos 24U /*!< SCB ICSR: STTNS Position (Security Extension) */ -#define SCB_ICSR_STTNS_Msk (1UL << SCB_ICSR_STTNS_Pos) /*!< SCB ICSR: STTNS Mask (Security Extension) */ - -#define SCB_ICSR_ISRPREEMPT_Pos 23U /*!< SCB ICSR: ISRPREEMPT Position */ -#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ - -#define SCB_ICSR_ISRPENDING_Pos 22U /*!< SCB ICSR: ISRPENDING Position */ -#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ - -#define SCB_ICSR_VECTPENDING_Pos 12U /*!< SCB ICSR: VECTPENDING Position */ -#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ - -#define SCB_ICSR_RETTOBASE_Pos 11U /*!< SCB ICSR: RETTOBASE Position */ -#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */ - -#define SCB_ICSR_VECTACTIVE_Pos 0U /*!< SCB ICSR: VECTACTIVE Position */ -#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ - -#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U) -/* SCB Vector Table Offset Register Definitions */ -#define SCB_VTOR_TBLOFF_Pos 7U /*!< SCB VTOR: TBLOFF Position */ -#define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ -#endif - -/* SCB Application Interrupt and Reset Control Register Definitions */ -#define SCB_AIRCR_VECTKEY_Pos 16U /*!< SCB AIRCR: VECTKEY Position */ -#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ - -#define SCB_AIRCR_VECTKEYSTAT_Pos 16U /*!< SCB AIRCR: VECTKEYSTAT Position */ -#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ - -#define SCB_AIRCR_ENDIANESS_Pos 15U /*!< SCB AIRCR: ENDIANESS Position */ -#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ - -#define SCB_AIRCR_PRIS_Pos 14U /*!< SCB AIRCR: PRIS Position */ -#define SCB_AIRCR_PRIS_Msk (1UL << SCB_AIRCR_PRIS_Pos) /*!< SCB AIRCR: PRIS Mask */ - -#define SCB_AIRCR_BFHFNMINS_Pos 13U /*!< SCB AIRCR: BFHFNMINS Position */ -#define SCB_AIRCR_BFHFNMINS_Msk (1UL << SCB_AIRCR_BFHFNMINS_Pos) /*!< SCB AIRCR: BFHFNMINS Mask */ - -#define SCB_AIRCR_SYSRESETREQS_Pos 3U /*!< SCB AIRCR: SYSRESETREQS Position */ -#define SCB_AIRCR_SYSRESETREQS_Msk (1UL << SCB_AIRCR_SYSRESETREQS_Pos) /*!< SCB AIRCR: SYSRESETREQS Mask */ - -#define SCB_AIRCR_SYSRESETREQ_Pos 2U /*!< SCB AIRCR: SYSRESETREQ Position */ -#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ - -#define SCB_AIRCR_VECTCLRACTIVE_Pos 1U /*!< SCB AIRCR: VECTCLRACTIVE Position */ -#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ - -/* SCB System Control Register Definitions */ -#define SCB_SCR_SEVONPEND_Pos 4U /*!< SCB SCR: SEVONPEND Position */ -#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ - -#define SCB_SCR_SLEEPDEEPS_Pos 3U /*!< SCB SCR: SLEEPDEEPS Position */ -#define SCB_SCR_SLEEPDEEPS_Msk (1UL << SCB_SCR_SLEEPDEEPS_Pos) /*!< SCB SCR: SLEEPDEEPS Mask */ - -#define SCB_SCR_SLEEPDEEP_Pos 2U /*!< SCB SCR: SLEEPDEEP Position */ -#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ - -#define SCB_SCR_SLEEPONEXIT_Pos 1U /*!< SCB SCR: SLEEPONEXIT Position */ -#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ - -/* SCB Configuration Control Register Definitions */ -#define SCB_CCR_BP_Pos 18U /*!< SCB CCR: BP Position */ -#define SCB_CCR_BP_Msk (1UL << SCB_CCR_BP_Pos) /*!< SCB CCR: BP Mask */ - -#define SCB_CCR_IC_Pos 17U /*!< SCB CCR: IC Position */ -#define SCB_CCR_IC_Msk (1UL << SCB_CCR_IC_Pos) /*!< SCB CCR: IC Mask */ - -#define SCB_CCR_DC_Pos 16U /*!< SCB CCR: DC Position */ -#define SCB_CCR_DC_Msk (1UL << SCB_CCR_DC_Pos) /*!< SCB CCR: DC Mask */ - -#define SCB_CCR_STKOFHFNMIGN_Pos 10U /*!< SCB CCR: STKOFHFNMIGN Position */ -#define SCB_CCR_STKOFHFNMIGN_Msk (1UL << SCB_CCR_STKOFHFNMIGN_Pos) /*!< SCB CCR: STKOFHFNMIGN Mask */ - -#define SCB_CCR_BFHFNMIGN_Pos 8U /*!< SCB CCR: BFHFNMIGN Position */ -#define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */ - -#define SCB_CCR_DIV_0_TRP_Pos 4U /*!< SCB CCR: DIV_0_TRP Position */ -#define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */ - -#define SCB_CCR_UNALIGN_TRP_Pos 3U /*!< SCB CCR: UNALIGN_TRP Position */ -#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ - -#define SCB_CCR_USERSETMPEND_Pos 1U /*!< SCB CCR: USERSETMPEND Position */ -#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */ - -/* SCB System Handler Control and State Register Definitions */ -#define SCB_SHCSR_HARDFAULTPENDED_Pos 21U /*!< SCB SHCSR: HARDFAULTPENDED Position */ -#define SCB_SHCSR_HARDFAULTPENDED_Msk (1UL << SCB_SHCSR_HARDFAULTPENDED_Pos) /*!< SCB SHCSR: HARDFAULTPENDED Mask */ - -#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */ -#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ - -#define SCB_SHCSR_SYSTICKACT_Pos 11U /*!< SCB SHCSR: SYSTICKACT Position */ -#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */ - -#define SCB_SHCSR_PENDSVACT_Pos 10U /*!< SCB SHCSR: PENDSVACT Position */ -#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */ - -#define SCB_SHCSR_SVCALLACT_Pos 7U /*!< SCB SHCSR: SVCALLACT Position */ -#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */ - -#define SCB_SHCSR_NMIACT_Pos 5U /*!< SCB SHCSR: NMIACT Position */ -#define SCB_SHCSR_NMIACT_Msk (1UL << SCB_SHCSR_NMIACT_Pos) /*!< SCB SHCSR: NMIACT Mask */ - -#define SCB_SHCSR_HARDFAULTACT_Pos 2U /*!< SCB SHCSR: HARDFAULTACT Position */ -#define SCB_SHCSR_HARDFAULTACT_Msk (1UL << SCB_SHCSR_HARDFAULTACT_Pos) /*!< SCB SHCSR: HARDFAULTACT Mask */ - -/*@} end of group CMSIS_SCB */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SysTick System Tick Timer (SysTick) - \brief Type definitions for the System Timer Registers. - @{ - */ - -/** - \brief Structure type to access the System Timer (SysTick). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ - __IOM uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ - __IOM uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ - __IM uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ -} SysTick_Type; - -/* SysTick Control / Status Register Definitions */ -#define SysTick_CTRL_COUNTFLAG_Pos 16U /*!< SysTick CTRL: COUNTFLAG Position */ -#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ - -#define SysTick_CTRL_CLKSOURCE_Pos 2U /*!< SysTick CTRL: CLKSOURCE Position */ -#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ - -#define SysTick_CTRL_TICKINT_Pos 1U /*!< SysTick CTRL: TICKINT Position */ -#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ - -#define SysTick_CTRL_ENABLE_Pos 0U /*!< SysTick CTRL: ENABLE Position */ -#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ - -/* SysTick Reload Register Definitions */ -#define SysTick_LOAD_RELOAD_Pos 0U /*!< SysTick LOAD: RELOAD Position */ -#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ - -/* SysTick Current Register Definitions */ -#define SysTick_VAL_CURRENT_Pos 0U /*!< SysTick VAL: CURRENT Position */ -#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ - -/* SysTick Calibration Register Definitions */ -#define SysTick_CALIB_NOREF_Pos 31U /*!< SysTick CALIB: NOREF Position */ -#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ - -#define SysTick_CALIB_SKEW_Pos 30U /*!< SysTick CALIB: SKEW Position */ -#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ - -#define SysTick_CALIB_TENMS_Pos 0U /*!< SysTick CALIB: TENMS Position */ -#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ - -/*@} end of group CMSIS_SysTick */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_DWT Data Watchpoint and Trace (DWT) - \brief Type definitions for the Data Watchpoint and Trace (DWT) - @{ - */ - -/** - \brief Structure type to access the Data Watchpoint and Trace Register (DWT). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) Control Register */ - uint32_t RESERVED0[6U]; - __IM uint32_t PCSR; /*!< Offset: 0x01C (R/ ) Program Counter Sample Register */ - __IOM uint32_t COMP0; /*!< Offset: 0x020 (R/W) Comparator Register 0 */ - uint32_t RESERVED1[1U]; - __IOM uint32_t FUNCTION0; /*!< Offset: 0x028 (R/W) Function Register 0 */ - uint32_t RESERVED2[1U]; - __IOM uint32_t COMP1; /*!< Offset: 0x030 (R/W) Comparator Register 1 */ - uint32_t RESERVED3[1U]; - __IOM uint32_t FUNCTION1; /*!< Offset: 0x038 (R/W) Function Register 1 */ - uint32_t RESERVED4[1U]; - __IOM uint32_t COMP2; /*!< Offset: 0x040 (R/W) Comparator Register 2 */ - uint32_t RESERVED5[1U]; - __IOM uint32_t FUNCTION2; /*!< Offset: 0x048 (R/W) Function Register 2 */ - uint32_t RESERVED6[1U]; - __IOM uint32_t COMP3; /*!< Offset: 0x050 (R/W) Comparator Register 3 */ - uint32_t RESERVED7[1U]; - __IOM uint32_t FUNCTION3; /*!< Offset: 0x058 (R/W) Function Register 3 */ - uint32_t RESERVED8[1U]; - __IOM uint32_t COMP4; /*!< Offset: 0x060 (R/W) Comparator Register 4 */ - uint32_t RESERVED9[1U]; - __IOM uint32_t FUNCTION4; /*!< Offset: 0x068 (R/W) Function Register 4 */ - uint32_t RESERVED10[1U]; - __IOM uint32_t COMP5; /*!< Offset: 0x070 (R/W) Comparator Register 5 */ - uint32_t RESERVED11[1U]; - __IOM uint32_t FUNCTION5; /*!< Offset: 0x078 (R/W) Function Register 5 */ - uint32_t RESERVED12[1U]; - __IOM uint32_t COMP6; /*!< Offset: 0x080 (R/W) Comparator Register 6 */ - uint32_t RESERVED13[1U]; - __IOM uint32_t FUNCTION6; /*!< Offset: 0x088 (R/W) Function Register 6 */ - uint32_t RESERVED14[1U]; - __IOM uint32_t COMP7; /*!< Offset: 0x090 (R/W) Comparator Register 7 */ - uint32_t RESERVED15[1U]; - __IOM uint32_t FUNCTION7; /*!< Offset: 0x098 (R/W) Function Register 7 */ - uint32_t RESERVED16[1U]; - __IOM uint32_t COMP8; /*!< Offset: 0x0A0 (R/W) Comparator Register 8 */ - uint32_t RESERVED17[1U]; - __IOM uint32_t FUNCTION8; /*!< Offset: 0x0A8 (R/W) Function Register 8 */ - uint32_t RESERVED18[1U]; - __IOM uint32_t COMP9; /*!< Offset: 0x0B0 (R/W) Comparator Register 9 */ - uint32_t RESERVED19[1U]; - __IOM uint32_t FUNCTION9; /*!< Offset: 0x0B8 (R/W) Function Register 9 */ - uint32_t RESERVED20[1U]; - __IOM uint32_t COMP10; /*!< Offset: 0x0C0 (R/W) Comparator Register 10 */ - uint32_t RESERVED21[1U]; - __IOM uint32_t FUNCTION10; /*!< Offset: 0x0C8 (R/W) Function Register 10 */ - uint32_t RESERVED22[1U]; - __IOM uint32_t COMP11; /*!< Offset: 0x0D0 (R/W) Comparator Register 11 */ - uint32_t RESERVED23[1U]; - __IOM uint32_t FUNCTION11; /*!< Offset: 0x0D8 (R/W) Function Register 11 */ - uint32_t RESERVED24[1U]; - __IOM uint32_t COMP12; /*!< Offset: 0x0E0 (R/W) Comparator Register 12 */ - uint32_t RESERVED25[1U]; - __IOM uint32_t FUNCTION12; /*!< Offset: 0x0E8 (R/W) Function Register 12 */ - uint32_t RESERVED26[1U]; - __IOM uint32_t COMP13; /*!< Offset: 0x0F0 (R/W) Comparator Register 13 */ - uint32_t RESERVED27[1U]; - __IOM uint32_t FUNCTION13; /*!< Offset: 0x0F8 (R/W) Function Register 13 */ - uint32_t RESERVED28[1U]; - __IOM uint32_t COMP14; /*!< Offset: 0x100 (R/W) Comparator Register 14 */ - uint32_t RESERVED29[1U]; - __IOM uint32_t FUNCTION14; /*!< Offset: 0x108 (R/W) Function Register 14 */ - uint32_t RESERVED30[1U]; - __IOM uint32_t COMP15; /*!< Offset: 0x110 (R/W) Comparator Register 15 */ - uint32_t RESERVED31[1U]; - __IOM uint32_t FUNCTION15; /*!< Offset: 0x118 (R/W) Function Register 15 */ -} DWT_Type; - -/* DWT Control Register Definitions */ -#define DWT_CTRL_NUMCOMP_Pos 28U /*!< DWT CTRL: NUMCOMP Position */ -#define DWT_CTRL_NUMCOMP_Msk (0xFUL << DWT_CTRL_NUMCOMP_Pos) /*!< DWT CTRL: NUMCOMP Mask */ - -#define DWT_CTRL_NOTRCPKT_Pos 27U /*!< DWT CTRL: NOTRCPKT Position */ -#define DWT_CTRL_NOTRCPKT_Msk (0x1UL << DWT_CTRL_NOTRCPKT_Pos) /*!< DWT CTRL: NOTRCPKT Mask */ - -#define DWT_CTRL_NOEXTTRIG_Pos 26U /*!< DWT CTRL: NOEXTTRIG Position */ -#define DWT_CTRL_NOEXTTRIG_Msk (0x1UL << DWT_CTRL_NOEXTTRIG_Pos) /*!< DWT CTRL: NOEXTTRIG Mask */ - -#define DWT_CTRL_NOCYCCNT_Pos 25U /*!< DWT CTRL: NOCYCCNT Position */ -#define DWT_CTRL_NOCYCCNT_Msk (0x1UL << DWT_CTRL_NOCYCCNT_Pos) /*!< DWT CTRL: NOCYCCNT Mask */ - -#define DWT_CTRL_NOPRFCNT_Pos 24U /*!< DWT CTRL: NOPRFCNT Position */ -#define DWT_CTRL_NOPRFCNT_Msk (0x1UL << DWT_CTRL_NOPRFCNT_Pos) /*!< DWT CTRL: NOPRFCNT Mask */ - -/* DWT Comparator Function Register Definitions */ -#define DWT_FUNCTION_ID_Pos 27U /*!< DWT FUNCTION: ID Position */ -#define DWT_FUNCTION_ID_Msk (0x1FUL << DWT_FUNCTION_ID_Pos) /*!< DWT FUNCTION: ID Mask */ - -#define DWT_FUNCTION_MATCHED_Pos 24U /*!< DWT FUNCTION: MATCHED Position */ -#define DWT_FUNCTION_MATCHED_Msk (0x1UL << DWT_FUNCTION_MATCHED_Pos) /*!< DWT FUNCTION: MATCHED Mask */ - -#define DWT_FUNCTION_DATAVSIZE_Pos 10U /*!< DWT FUNCTION: DATAVSIZE Position */ -#define DWT_FUNCTION_DATAVSIZE_Msk (0x3UL << DWT_FUNCTION_DATAVSIZE_Pos) /*!< DWT FUNCTION: DATAVSIZE Mask */ - -#define DWT_FUNCTION_ACTION_Pos 4U /*!< DWT FUNCTION: ACTION Position */ -#define DWT_FUNCTION_ACTION_Msk (0x3UL << DWT_FUNCTION_ACTION_Pos) /*!< DWT FUNCTION: ACTION Mask */ - -#define DWT_FUNCTION_MATCH_Pos 0U /*!< DWT FUNCTION: MATCH Position */ -#define DWT_FUNCTION_MATCH_Msk (0xFUL /*<< DWT_FUNCTION_MATCH_Pos*/) /*!< DWT FUNCTION: MATCH Mask */ - -/*@}*/ /* end of group CMSIS_DWT */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_TPI Trace Port Interface (TPI) - \brief Type definitions for the Trace Port Interface (TPI) - @{ - */ - -/** - \brief Structure type to access the Trace Port Interface Register (TPI). - */ -typedef struct -{ - __IM uint32_t SSPSR; /*!< Offset: 0x000 (R/ ) Supported Parallel Port Sizes Register */ - __IOM uint32_t CSPSR; /*!< Offset: 0x004 (R/W) Current Parallel Port Sizes Register */ - uint32_t RESERVED0[2U]; - __IOM uint32_t ACPR; /*!< Offset: 0x010 (R/W) Asynchronous Clock Prescaler Register */ - uint32_t RESERVED1[55U]; - __IOM uint32_t SPPR; /*!< Offset: 0x0F0 (R/W) Selected Pin Protocol Register */ - uint32_t RESERVED2[131U]; - __IM uint32_t FFSR; /*!< Offset: 0x300 (R/ ) Formatter and Flush Status Register */ - __IOM uint32_t FFCR; /*!< Offset: 0x304 (R/W) Formatter and Flush Control Register */ - __IOM uint32_t PSCR; /*!< Offset: 0x308 (R/W) Periodic Synchronization Control Register */ - uint32_t RESERVED3[809U]; - __OM uint32_t LAR; /*!< Offset: 0xFB0 ( /W) Software Lock Access Register */ - __IM uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) Software Lock Status Register */ - uint32_t RESERVED4[4U]; - __IM uint32_t TYPE; /*!< Offset: 0xFC8 (R/ ) Device Identifier Register */ - __IM uint32_t DEVTYPE; /*!< Offset: 0xFCC (R/ ) Device Type Register */ -} TPI_Type; - -/* TPI Asynchronous Clock Prescaler Register Definitions */ -#define TPI_ACPR_SWOSCALER_Pos 0U /*!< TPI ACPR: SWOSCALER Position */ -#define TPI_ACPR_SWOSCALER_Msk (0xFFFFUL /*<< TPI_ACPR_SWOSCALER_Pos*/) /*!< TPI ACPR: SWOSCALER Mask */ - -/* TPI Selected Pin Protocol Register Definitions */ -#define TPI_SPPR_TXMODE_Pos 0U /*!< TPI SPPR: TXMODE Position */ -#define TPI_SPPR_TXMODE_Msk (0x3UL /*<< TPI_SPPR_TXMODE_Pos*/) /*!< TPI SPPR: TXMODE Mask */ - -/* TPI Formatter and Flush Status Register Definitions */ -#define TPI_FFSR_FtNonStop_Pos 3U /*!< TPI FFSR: FtNonStop Position */ -#define TPI_FFSR_FtNonStop_Msk (0x1UL << TPI_FFSR_FtNonStop_Pos) /*!< TPI FFSR: FtNonStop Mask */ - -#define TPI_FFSR_TCPresent_Pos 2U /*!< TPI FFSR: TCPresent Position */ -#define TPI_FFSR_TCPresent_Msk (0x1UL << TPI_FFSR_TCPresent_Pos) /*!< TPI FFSR: TCPresent Mask */ - -#define TPI_FFSR_FtStopped_Pos 1U /*!< TPI FFSR: FtStopped Position */ -#define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */ - -#define TPI_FFSR_FlInProg_Pos 0U /*!< TPI FFSR: FlInProg Position */ -#define TPI_FFSR_FlInProg_Msk (0x1UL /*<< TPI_FFSR_FlInProg_Pos*/) /*!< TPI FFSR: FlInProg Mask */ - -/* TPI Formatter and Flush Control Register Definitions */ -#define TPI_FFCR_TrigIn_Pos 8U /*!< TPI FFCR: TrigIn Position */ -#define TPI_FFCR_TrigIn_Msk (0x1UL << TPI_FFCR_TrigIn_Pos) /*!< TPI FFCR: TrigIn Mask */ - -#define TPI_FFCR_FOnMan_Pos 6U /*!< TPI FFCR: FOnMan Position */ -#define TPI_FFCR_FOnMan_Msk (0x1UL << TPI_FFCR_FOnMan_Pos) /*!< TPI FFCR: FOnMan Mask */ - -#define TPI_FFCR_EnFCont_Pos 1U /*!< TPI FFCR: EnFCont Position */ -#define TPI_FFCR_EnFCont_Msk (0x1UL << TPI_FFCR_EnFCont_Pos) /*!< TPI FFCR: EnFCont Mask */ - -/* TPI Periodic Synchronization Control Register Definitions */ -#define TPI_PSCR_PSCount_Pos 0U /*!< TPI PSCR: PSCount Position */ -#define TPI_PSCR_PSCount_Msk (0x1FUL /*<< TPI_PSCR_PSCount_Pos*/) /*!< TPI PSCR: TPSCount Mask */ - -/* TPI Software Lock Status Register Definitions */ -#define TPI_LSR_nTT_Pos 1U /*!< TPI LSR: Not thirty-two bit. Position */ -#define TPI_LSR_nTT_Msk (0x1UL << TPI_LSR_nTT_Pos) /*!< TPI LSR: Not thirty-two bit. Mask */ - -#define TPI_LSR_SLK_Pos 1U /*!< TPI LSR: Software Lock status Position */ -#define TPI_LSR_SLK_Msk (0x1UL << TPI_LSR_SLK_Pos) /*!< TPI LSR: Software Lock status Mask */ - -#define TPI_LSR_SLI_Pos 0U /*!< TPI LSR: Software Lock implemented Position */ -#define TPI_LSR_SLI_Msk (0x1UL /*<< TPI_LSR_SLI_Pos*/) /*!< TPI LSR: Software Lock implemented Mask */ - -/* TPI DEVID Register Definitions */ -#define TPI_DEVID_NRZVALID_Pos 11U /*!< TPI DEVID: NRZVALID Position */ -#define TPI_DEVID_NRZVALID_Msk (0x1UL << TPI_DEVID_NRZVALID_Pos) /*!< TPI DEVID: NRZVALID Mask */ - -#define TPI_DEVID_MANCVALID_Pos 10U /*!< TPI DEVID: MANCVALID Position */ -#define TPI_DEVID_MANCVALID_Msk (0x1UL << TPI_DEVID_MANCVALID_Pos) /*!< TPI DEVID: MANCVALID Mask */ - -#define TPI_DEVID_PTINVALID_Pos 9U /*!< TPI DEVID: PTINVALID Position */ -#define TPI_DEVID_PTINVALID_Msk (0x1UL << TPI_DEVID_PTINVALID_Pos) /*!< TPI DEVID: PTINVALID Mask */ - -#define TPI_DEVID_FIFOSZ_Pos 6U /*!< TPI DEVID: FIFO depth Position */ -#define TPI_DEVID_FIFOSZ_Msk (0x7UL << TPI_DEVID_FIFOSZ_Pos) /*!< TPI DEVID: FIFO depth Mask */ - -/* TPI DEVTYPE Register Definitions */ -#define TPI_DEVTYPE_SubType_Pos 4U /*!< TPI DEVTYPE: SubType Position */ -#define TPI_DEVTYPE_SubType_Msk (0xFUL /*<< TPI_DEVTYPE_SubType_Pos*/) /*!< TPI DEVTYPE: SubType Mask */ - -#define TPI_DEVTYPE_MajorType_Pos 0U /*!< TPI DEVTYPE: MajorType Position */ -#define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */ - -/*@}*/ /* end of group CMSIS_TPI */ - - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_MPU Memory Protection Unit (MPU) - \brief Type definitions for the Memory Protection Unit (MPU) - @{ - */ - -/** - \brief Structure type to access the Memory Protection Unit (MPU). - */ -typedef struct -{ - __IM uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */ - __IOM uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */ - __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region Number Register */ - __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */ - __IOM uint32_t RLAR; /*!< Offset: 0x010 (R/W) MPU Region Limit Address Register */ - uint32_t RESERVED0[7U]; - union { - __IOM uint32_t MAIR[2]; - struct { - __IOM uint32_t MAIR0; /*!< Offset: 0x030 (R/W) MPU Memory Attribute Indirection Register 0 */ - __IOM uint32_t MAIR1; /*!< Offset: 0x034 (R/W) MPU Memory Attribute Indirection Register 1 */ - }; - }; -} MPU_Type; - -#define MPU_TYPE_RALIASES 1U - -/* MPU Type Register Definitions */ -#define MPU_TYPE_IREGION_Pos 16U /*!< MPU TYPE: IREGION Position */ -#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ - -#define MPU_TYPE_DREGION_Pos 8U /*!< MPU TYPE: DREGION Position */ -#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ - -#define MPU_TYPE_SEPARATE_Pos 0U /*!< MPU TYPE: SEPARATE Position */ -#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */ - -/* MPU Control Register Definitions */ -#define MPU_CTRL_PRIVDEFENA_Pos 2U /*!< MPU CTRL: PRIVDEFENA Position */ -#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ - -#define MPU_CTRL_HFNMIENA_Pos 1U /*!< MPU CTRL: HFNMIENA Position */ -#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ - -#define MPU_CTRL_ENABLE_Pos 0U /*!< MPU CTRL: ENABLE Position */ -#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */ - -/* MPU Region Number Register Definitions */ -#define MPU_RNR_REGION_Pos 0U /*!< MPU RNR: REGION Position */ -#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */ - -/* MPU Region Base Address Register Definitions */ -#define MPU_RBAR_BASE_Pos 5U /*!< MPU RBAR: BASE Position */ -#define MPU_RBAR_BASE_Msk (0x7FFFFFFUL << MPU_RBAR_BASE_Pos) /*!< MPU RBAR: BASE Mask */ - -#define MPU_RBAR_SH_Pos 3U /*!< MPU RBAR: SH Position */ -#define MPU_RBAR_SH_Msk (0x3UL << MPU_RBAR_SH_Pos) /*!< MPU RBAR: SH Mask */ - -#define MPU_RBAR_AP_Pos 1U /*!< MPU RBAR: AP Position */ -#define MPU_RBAR_AP_Msk (0x3UL << MPU_RBAR_AP_Pos) /*!< MPU RBAR: AP Mask */ - -#define MPU_RBAR_XN_Pos 0U /*!< MPU RBAR: XN Position */ -#define MPU_RBAR_XN_Msk (01UL /*<< MPU_RBAR_XN_Pos*/) /*!< MPU RBAR: XN Mask */ - -/* MPU Region Limit Address Register Definitions */ -#define MPU_RLAR_LIMIT_Pos 5U /*!< MPU RLAR: LIMIT Position */ -#define MPU_RLAR_LIMIT_Msk (0x7FFFFFFUL << MPU_RLAR_LIMIT_Pos) /*!< MPU RLAR: LIMIT Mask */ - -#define MPU_RLAR_AttrIndx_Pos 1U /*!< MPU RLAR: AttrIndx Position */ -#define MPU_RLAR_AttrIndx_Msk (0x7UL << MPU_RLAR_AttrIndx_Pos) /*!< MPU RLAR: AttrIndx Mask */ - -#define MPU_RLAR_EN_Pos 0U /*!< MPU RLAR: EN Position */ -#define MPU_RLAR_EN_Msk (1UL /*<< MPU_RLAR_EN_Pos*/) /*!< MPU RLAR: EN Mask */ - -/* MPU Memory Attribute Indirection Register 0 Definitions */ -#define MPU_MAIR0_Attr3_Pos 24U /*!< MPU MAIR0: Attr3 Position */ -#define MPU_MAIR0_Attr3_Msk (0xFFUL << MPU_MAIR0_Attr3_Pos) /*!< MPU MAIR0: Attr3 Mask */ - -#define MPU_MAIR0_Attr2_Pos 16U /*!< MPU MAIR0: Attr2 Position */ -#define MPU_MAIR0_Attr2_Msk (0xFFUL << MPU_MAIR0_Attr2_Pos) /*!< MPU MAIR0: Attr2 Mask */ - -#define MPU_MAIR0_Attr1_Pos 8U /*!< MPU MAIR0: Attr1 Position */ -#define MPU_MAIR0_Attr1_Msk (0xFFUL << MPU_MAIR0_Attr1_Pos) /*!< MPU MAIR0: Attr1 Mask */ - -#define MPU_MAIR0_Attr0_Pos 0U /*!< MPU MAIR0: Attr0 Position */ -#define MPU_MAIR0_Attr0_Msk (0xFFUL /*<< MPU_MAIR0_Attr0_Pos*/) /*!< MPU MAIR0: Attr0 Mask */ - -/* MPU Memory Attribute Indirection Register 1 Definitions */ -#define MPU_MAIR1_Attr7_Pos 24U /*!< MPU MAIR1: Attr7 Position */ -#define MPU_MAIR1_Attr7_Msk (0xFFUL << MPU_MAIR1_Attr7_Pos) /*!< MPU MAIR1: Attr7 Mask */ - -#define MPU_MAIR1_Attr6_Pos 16U /*!< MPU MAIR1: Attr6 Position */ -#define MPU_MAIR1_Attr6_Msk (0xFFUL << MPU_MAIR1_Attr6_Pos) /*!< MPU MAIR1: Attr6 Mask */ - -#define MPU_MAIR1_Attr5_Pos 8U /*!< MPU MAIR1: Attr5 Position */ -#define MPU_MAIR1_Attr5_Msk (0xFFUL << MPU_MAIR1_Attr5_Pos) /*!< MPU MAIR1: Attr5 Mask */ - -#define MPU_MAIR1_Attr4_Pos 0U /*!< MPU MAIR1: Attr4 Position */ -#define MPU_MAIR1_Attr4_Msk (0xFFUL /*<< MPU_MAIR1_Attr4_Pos*/) /*!< MPU MAIR1: Attr4 Mask */ - -/*@} end of group CMSIS_MPU */ -#endif - - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SAU Security Attribution Unit (SAU) - \brief Type definitions for the Security Attribution Unit (SAU) - @{ - */ - -/** - \brief Structure type to access the Security Attribution Unit (SAU). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SAU Control Register */ - __IM uint32_t TYPE; /*!< Offset: 0x004 (R/ ) SAU Type Register */ -#if defined (__SAUREGION_PRESENT) && (__SAUREGION_PRESENT == 1U) - __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) SAU Region Number Register */ - __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) SAU Region Base Address Register */ - __IOM uint32_t RLAR; /*!< Offset: 0x010 (R/W) SAU Region Limit Address Register */ -#endif -} SAU_Type; - -/* SAU Control Register Definitions */ -#define SAU_CTRL_ALLNS_Pos 1U /*!< SAU CTRL: ALLNS Position */ -#define SAU_CTRL_ALLNS_Msk (1UL << SAU_CTRL_ALLNS_Pos) /*!< SAU CTRL: ALLNS Mask */ - -#define SAU_CTRL_ENABLE_Pos 0U /*!< SAU CTRL: ENABLE Position */ -#define SAU_CTRL_ENABLE_Msk (1UL /*<< SAU_CTRL_ENABLE_Pos*/) /*!< SAU CTRL: ENABLE Mask */ - -/* SAU Type Register Definitions */ -#define SAU_TYPE_SREGION_Pos 0U /*!< SAU TYPE: SREGION Position */ -#define SAU_TYPE_SREGION_Msk (0xFFUL /*<< SAU_TYPE_SREGION_Pos*/) /*!< SAU TYPE: SREGION Mask */ - -#if defined (__SAUREGION_PRESENT) && (__SAUREGION_PRESENT == 1U) -/* SAU Region Number Register Definitions */ -#define SAU_RNR_REGION_Pos 0U /*!< SAU RNR: REGION Position */ -#define SAU_RNR_REGION_Msk (0xFFUL /*<< SAU_RNR_REGION_Pos*/) /*!< SAU RNR: REGION Mask */ - -/* SAU Region Base Address Register Definitions */ -#define SAU_RBAR_BADDR_Pos 5U /*!< SAU RBAR: BADDR Position */ -#define SAU_RBAR_BADDR_Msk (0x7FFFFFFUL << SAU_RBAR_BADDR_Pos) /*!< SAU RBAR: BADDR Mask */ - -/* SAU Region Limit Address Register Definitions */ -#define SAU_RLAR_LADDR_Pos 5U /*!< SAU RLAR: LADDR Position */ -#define SAU_RLAR_LADDR_Msk (0x7FFFFFFUL << SAU_RLAR_LADDR_Pos) /*!< SAU RLAR: LADDR Mask */ - -#define SAU_RLAR_NSC_Pos 1U /*!< SAU RLAR: NSC Position */ -#define SAU_RLAR_NSC_Msk (1UL << SAU_RLAR_NSC_Pos) /*!< SAU RLAR: NSC Mask */ - -#define SAU_RLAR_ENABLE_Pos 0U /*!< SAU RLAR: ENABLE Position */ -#define SAU_RLAR_ENABLE_Msk (1UL /*<< SAU_RLAR_ENABLE_Pos*/) /*!< SAU RLAR: ENABLE Mask */ - -#endif /* defined (__SAUREGION_PRESENT) && (__SAUREGION_PRESENT == 1U) */ - -/*@} end of group CMSIS_SAU */ -#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug) - \brief Type definitions for the Core Debug Registers - @{ - */ - -/** - \brief Structure type to access the Core Debug Register (CoreDebug). - */ -typedef struct -{ - __IOM uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */ - __OM uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */ - __IOM uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */ - __IOM uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */ - uint32_t RESERVED4[1U]; - __IOM uint32_t DAUTHCTRL; /*!< Offset: 0x014 (R/W) Debug Authentication Control Register */ - __IOM uint32_t DSCSR; /*!< Offset: 0x018 (R/W) Debug Security Control and Status Register */ -} CoreDebug_Type; - -/* Debug Halting Control and Status Register Definitions */ -#define CoreDebug_DHCSR_DBGKEY_Pos 16U /*!< CoreDebug DHCSR: DBGKEY Position */ -#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */ - -#define CoreDebug_DHCSR_S_RESTART_ST_Pos 26U /*!< CoreDebug DHCSR: S_RESTART_ST Position */ -#define CoreDebug_DHCSR_S_RESTART_ST_Msk (1UL << CoreDebug_DHCSR_S_RESTART_ST_Pos) /*!< CoreDebug DHCSR: S_RESTART_ST Mask */ - -#define CoreDebug_DHCSR_S_RESET_ST_Pos 25U /*!< CoreDebug DHCSR: S_RESET_ST Position */ -#define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */ - -#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24U /*!< CoreDebug DHCSR: S_RETIRE_ST Position */ -#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */ - -#define CoreDebug_DHCSR_S_LOCKUP_Pos 19U /*!< CoreDebug DHCSR: S_LOCKUP Position */ -#define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */ - -#define CoreDebug_DHCSR_S_SLEEP_Pos 18U /*!< CoreDebug DHCSR: S_SLEEP Position */ -#define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */ - -#define CoreDebug_DHCSR_S_HALT_Pos 17U /*!< CoreDebug DHCSR: S_HALT Position */ -#define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */ - -#define CoreDebug_DHCSR_S_REGRDY_Pos 16U /*!< CoreDebug DHCSR: S_REGRDY Position */ -#define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */ - -#define CoreDebug_DHCSR_C_MASKINTS_Pos 3U /*!< CoreDebug DHCSR: C_MASKINTS Position */ -#define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */ - -#define CoreDebug_DHCSR_C_STEP_Pos 2U /*!< CoreDebug DHCSR: C_STEP Position */ -#define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */ - -#define CoreDebug_DHCSR_C_HALT_Pos 1U /*!< CoreDebug DHCSR: C_HALT Position */ -#define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */ - -#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0U /*!< CoreDebug DHCSR: C_DEBUGEN Position */ -#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL /*<< CoreDebug_DHCSR_C_DEBUGEN_Pos*/) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ - -/* Debug Core Register Selector Register Definitions */ -#define CoreDebug_DCRSR_REGWnR_Pos 16U /*!< CoreDebug DCRSR: REGWnR Position */ -#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */ - -#define CoreDebug_DCRSR_REGSEL_Pos 0U /*!< CoreDebug DCRSR: REGSEL Position */ -#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL /*<< CoreDebug_DCRSR_REGSEL_Pos*/) /*!< CoreDebug DCRSR: REGSEL Mask */ - -/* Debug Exception and Monitor Control Register */ -#define CoreDebug_DEMCR_DWTENA_Pos 24U /*!< CoreDebug DEMCR: DWTENA Position */ -#define CoreDebug_DEMCR_DWTENA_Msk (1UL << CoreDebug_DEMCR_DWTENA_Pos) /*!< CoreDebug DEMCR: DWTENA Mask */ - -#define CoreDebug_DEMCR_VC_HARDERR_Pos 10U /*!< CoreDebug DEMCR: VC_HARDERR Position */ -#define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */ - -#define CoreDebug_DEMCR_VC_CORERESET_Pos 0U /*!< CoreDebug DEMCR: VC_CORERESET Position */ -#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL /*<< CoreDebug_DEMCR_VC_CORERESET_Pos*/) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ - -/* Debug Authentication Control Register Definitions */ -#define CoreDebug_DAUTHCTRL_INTSPNIDEN_Pos 3U /*!< CoreDebug DAUTHCTRL: INTSPNIDEN, Position */ -#define CoreDebug_DAUTHCTRL_INTSPNIDEN_Msk (1UL << CoreDebug_DAUTHCTRL_INTSPNIDEN_Pos) /*!< CoreDebug DAUTHCTRL: INTSPNIDEN, Mask */ - -#define CoreDebug_DAUTHCTRL_SPNIDENSEL_Pos 2U /*!< CoreDebug DAUTHCTRL: SPNIDENSEL Position */ -#define CoreDebug_DAUTHCTRL_SPNIDENSEL_Msk (1UL << CoreDebug_DAUTHCTRL_SPNIDENSEL_Pos) /*!< CoreDebug DAUTHCTRL: SPNIDENSEL Mask */ - -#define CoreDebug_DAUTHCTRL_INTSPIDEN_Pos 1U /*!< CoreDebug DAUTHCTRL: INTSPIDEN Position */ -#define CoreDebug_DAUTHCTRL_INTSPIDEN_Msk (1UL << CoreDebug_DAUTHCTRL_INTSPIDEN_Pos) /*!< CoreDebug DAUTHCTRL: INTSPIDEN Mask */ - -#define CoreDebug_DAUTHCTRL_SPIDENSEL_Pos 0U /*!< CoreDebug DAUTHCTRL: SPIDENSEL Position */ -#define CoreDebug_DAUTHCTRL_SPIDENSEL_Msk (1UL /*<< CoreDebug_DAUTHCTRL_SPIDENSEL_Pos*/) /*!< CoreDebug DAUTHCTRL: SPIDENSEL Mask */ - -/* Debug Security Control and Status Register Definitions */ -#define CoreDebug_DSCSR_CDS_Pos 16U /*!< CoreDebug DSCSR: CDS Position */ -#define CoreDebug_DSCSR_CDS_Msk (1UL << CoreDebug_DSCSR_CDS_Pos) /*!< CoreDebug DSCSR: CDS Mask */ - -#define CoreDebug_DSCSR_SBRSEL_Pos 1U /*!< CoreDebug DSCSR: SBRSEL Position */ -#define CoreDebug_DSCSR_SBRSEL_Msk (1UL << CoreDebug_DSCSR_SBRSEL_Pos) /*!< CoreDebug DSCSR: SBRSEL Mask */ - -#define CoreDebug_DSCSR_SBRSELEN_Pos 0U /*!< CoreDebug DSCSR: SBRSELEN Position */ -#define CoreDebug_DSCSR_SBRSELEN_Msk (1UL /*<< CoreDebug_DSCSR_SBRSELEN_Pos*/) /*!< CoreDebug DSCSR: SBRSELEN Mask */ - -/*@} end of group CMSIS_CoreDebug */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_bitfield Core register bit field macros - \brief Macros for use with bit field definitions (xxx_Pos, xxx_Msk). - @{ - */ - -/** - \brief Mask and shift a bit field value for use in a register bit range. - \param[in] field Name of the register bit field. - \param[in] value Value of the bit field. This parameter is interpreted as an uint32_t type. - \return Masked and shifted value. -*/ -#define _VAL2FLD(field, value) (((uint32_t)(value) << field ## _Pos) & field ## _Msk) - -/** - \brief Mask and shift a register value to extract a bit filed value. - \param[in] field Name of the register bit field. - \param[in] value Value of register. This parameter is interpreted as an uint32_t type. - \return Masked and shifted bit field value. -*/ -#define _FLD2VAL(field, value) (((uint32_t)(value) & field ## _Msk) >> field ## _Pos) - -/*@} end of group CMSIS_core_bitfield */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_base Core Definitions - \brief Definitions for base addresses, unions, and structures. - @{ - */ - -/* Memory mapping of Core Hardware */ - #define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ - #define DWT_BASE (0xE0001000UL) /*!< DWT Base Address */ - #define TPI_BASE (0xE0040000UL) /*!< TPI Base Address */ - #define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug Base Address */ - #define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ - #define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ - #define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ - - - #define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ - #define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ - #define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ - #define DWT ((DWT_Type *) DWT_BASE ) /*!< DWT configuration struct */ - #define TPI ((TPI_Type *) TPI_BASE ) /*!< TPI configuration struct */ - #define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE ) /*!< Core Debug configuration struct */ - - #if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */ - #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */ - #endif - - #if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) - #define SAU_BASE (SCS_BASE + 0x0DD0UL) /*!< Security Attribution Unit */ - #define SAU ((SAU_Type *) SAU_BASE ) /*!< Security Attribution Unit */ - #endif - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) - #define SCS_BASE_NS (0xE002E000UL) /*!< System Control Space Base Address (non-secure address space) */ - #define CoreDebug_BASE_NS (0xE002EDF0UL) /*!< Core Debug Base Address (non-secure address space) */ - #define SysTick_BASE_NS (SCS_BASE_NS + 0x0010UL) /*!< SysTick Base Address (non-secure address space) */ - #define NVIC_BASE_NS (SCS_BASE_NS + 0x0100UL) /*!< NVIC Base Address (non-secure address space) */ - #define SCB_BASE_NS (SCS_BASE_NS + 0x0D00UL) /*!< System Control Block Base Address (non-secure address space) */ - - #define SCB_NS ((SCB_Type *) SCB_BASE_NS ) /*!< SCB configuration struct (non-secure address space) */ - #define SysTick_NS ((SysTick_Type *) SysTick_BASE_NS ) /*!< SysTick configuration struct (non-secure address space) */ - #define NVIC_NS ((NVIC_Type *) NVIC_BASE_NS ) /*!< NVIC configuration struct (non-secure address space) */ - #define CoreDebug_NS ((CoreDebug_Type *) CoreDebug_BASE_NS) /*!< Core Debug configuration struct (non-secure address space) */ - - #if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - #define MPU_BASE_NS (SCS_BASE_NS + 0x0D90UL) /*!< Memory Protection Unit (non-secure address space) */ - #define MPU_NS ((MPU_Type *) MPU_BASE_NS ) /*!< Memory Protection Unit (non-secure address space) */ - #endif - -#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ -/*@} */ - - - -/******************************************************************************* - * Hardware Abstraction Layer - Core Function Interface contains: - - Core NVIC Functions - - Core SysTick Functions - - Core Register Access Functions - ******************************************************************************/ -/** - \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference -*/ - - - -/* ########################## NVIC functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_NVICFunctions NVIC Functions - \brief Functions that manage interrupts and exceptions via the NVIC. - @{ - */ - -#ifdef CMSIS_NVIC_VIRTUAL - #ifndef CMSIS_NVIC_VIRTUAL_HEADER_FILE - #define CMSIS_NVIC_VIRTUAL_HEADER_FILE "cmsis_nvic_virtual.h" - #endif - #include CMSIS_NVIC_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetPriorityGrouping __NVIC_SetPriorityGrouping - #define NVIC_GetPriorityGrouping __NVIC_GetPriorityGrouping - #define NVIC_EnableIRQ __NVIC_EnableIRQ - #define NVIC_GetEnableIRQ __NVIC_GetEnableIRQ - #define NVIC_DisableIRQ __NVIC_DisableIRQ - #define NVIC_GetPendingIRQ __NVIC_GetPendingIRQ - #define NVIC_SetPendingIRQ __NVIC_SetPendingIRQ - #define NVIC_ClearPendingIRQ __NVIC_ClearPendingIRQ - #define NVIC_GetActive __NVIC_GetActive - #define NVIC_SetPriority __NVIC_SetPriority - #define NVIC_GetPriority __NVIC_GetPriority - #define NVIC_SystemReset __NVIC_SystemReset -#endif /* CMSIS_NVIC_VIRTUAL */ - -#ifdef CMSIS_VECTAB_VIRTUAL - #ifndef CMSIS_VECTAB_VIRTUAL_HEADER_FILE - #define CMSIS_VECTAB_VIRTUAL_HEADER_FILE "cmsis_vectab_virtual.h" - #endif - #include CMSIS_VECTAB_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetVector __NVIC_SetVector - #define NVIC_GetVector __NVIC_GetVector -#endif /* (CMSIS_VECTAB_VIRTUAL) */ - -#define NVIC_USER_IRQ_OFFSET 16 - - -/* Special LR values for Secure/Non-Secure call handling and exception handling */ - -/* Function Return Payload (from ARMv8-M Architecture Reference Manual) LR value on entry from Secure BLXNS */ -#define FNC_RETURN (0xFEFFFFFFUL) /* bit [0] ignored when processing a branch */ - -/* The following EXC_RETURN mask values are used to evaluate the LR on exception entry */ -#define EXC_RETURN_PREFIX (0xFF000000UL) /* bits [31:24] set to indicate an EXC_RETURN value */ -#define EXC_RETURN_S (0x00000040UL) /* bit [6] stack used to push registers: 0=Non-secure 1=Secure */ -#define EXC_RETURN_DCRS (0x00000020UL) /* bit [5] stacking rules for called registers: 0=skipped 1=saved */ -#define EXC_RETURN_FTYPE (0x00000010UL) /* bit [4] allocate stack for floating-point context: 0=done 1=skipped */ -#define EXC_RETURN_MODE (0x00000008UL) /* bit [3] processor mode for return: 0=Handler mode 1=Thread mode */ -#define EXC_RETURN_SPSEL (0x00000002UL) /* bit [1] stack pointer used to restore context: 0=MSP 1=PSP */ -#define EXC_RETURN_ES (0x00000001UL) /* bit [0] security state exception was taken to: 0=Non-secure 1=Secure */ - -/* Integrity Signature (from ARMv8-M Architecture Reference Manual) for exception context stacking */ -#if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) /* Value for processors with floating-point extension: */ -#define EXC_INTEGRITY_SIGNATURE (0xFEFA125AUL) /* bit [0] SFTC must match LR bit[4] EXC_RETURN_FTYPE */ -#else -#define EXC_INTEGRITY_SIGNATURE (0xFEFA125BUL) /* Value for processors without floating-point extension */ -#endif - - -/* Interrupt Priorities are WORD accessible only under Armv6-M */ -/* The following MACROS handle generation of the register offset and byte masks */ -#define _BIT_SHIFT(IRQn) ( ((((uint32_t)(int32_t)(IRQn)) ) & 0x03UL) * 8UL) -#define _SHP_IDX(IRQn) ( (((((uint32_t)(int32_t)(IRQn)) & 0x0FUL)-8UL) >> 2UL) ) -#define _IP_IDX(IRQn) ( (((uint32_t)(int32_t)(IRQn)) >> 2UL) ) - -#define __NVIC_SetPriorityGrouping(X) (void)(X) -#define __NVIC_GetPriorityGrouping() (0U) - -/** - \brief Enable Interrupt - \details Enables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_EnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Interrupt Enable status - \details Returns a device specific interrupt enable status from the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt is not enabled. - \return 1 Interrupt is enabled. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetEnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Disable Interrupt - \details Disables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_DisableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - __DSB(); - __ISB(); - } -} - - -/** - \brief Get Pending Interrupt - \details Reads the NVIC pending register and returns the pending bit for the specified device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not pending. - \return 1 Interrupt status is pending. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Pending Interrupt - \details Sets the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_SetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Clear Pending Interrupt - \details Clears the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_ClearPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Active Interrupt - \details Reads the active register in the NVIC and returns the active bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not active. - \return 1 Interrupt status is active. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetActive(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) -/** - \brief Get Interrupt Target State - \details Reads the interrupt target field in the NVIC and returns the interrupt target bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 if interrupt is assigned to Secure - \return 1 if interrupt is assigned to Non Secure - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t NVIC_GetTargetState(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Interrupt Target State - \details Sets the interrupt target field in the NVIC and returns the interrupt target bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 if interrupt is assigned to Secure - 1 if interrupt is assigned to Non Secure - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t NVIC_SetTargetState(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] |= ((uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL))); - return((uint32_t)(((NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Clear Interrupt Target State - \details Clears the interrupt target field in the NVIC and returns the interrupt target bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 if interrupt is assigned to Secure - 1 if interrupt is assigned to Non Secure - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t NVIC_ClearTargetState(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] &= ~((uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL))); - return((uint32_t)(((NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} -#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ - - -/** - \brief Set Interrupt Priority - \details Sets the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \param [in] priority Priority to set. - \note The priority cannot be set for every processor exception. - */ -__STATIC_INLINE void __NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->IPR[_IP_IDX(IRQn)] = ((uint32_t)(NVIC->IPR[_IP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | - (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); - } - else - { - SCB->SHPR[_SHP_IDX(IRQn)] = ((uint32_t)(SCB->SHPR[_SHP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | - (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); - } -} - - -/** - \brief Get Interrupt Priority - \details Reads the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Interrupt Priority. - Value is aligned automatically to the implemented priority bits of the microcontroller. - */ -__STATIC_INLINE uint32_t __NVIC_GetPriority(IRQn_Type IRQn) -{ - - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->IPR[ _IP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS))); - } - else - { - return((uint32_t)(((SCB->SHPR[_SHP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS))); - } -} - - -/** - \brief Encode Priority - \details Encodes the priority for an interrupt with the given priority group, - preemptive priority value, and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Used priority group. - \param [in] PreemptPriority Preemptive priority value (starting from 0). - \param [in] SubPriority Subpriority value (starting from 0). - \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority(). - */ -__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - return ( - ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | - ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) - ); -} - - -/** - \brief Decode Priority - \details Decodes an interrupt priority value with a given priority group to - preemptive priority value and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. - \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority(). - \param [in] PriorityGroup Used priority group. - \param [out] pPreemptPriority Preemptive priority value (starting from 0). - \param [out] pSubPriority Subpriority value (starting from 0). - */ -__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* const pPreemptPriority, uint32_t* const pSubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL); - *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL); -} - - -/** - \brief Set Interrupt Vector - \details Sets an interrupt vector in SRAM based interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - VTOR must been relocated to SRAM before. - If VTOR is not present address 0 must be mapped to SRAM. - \param [in] IRQn Interrupt number - \param [in] vector Address of interrupt handler function - */ -__STATIC_INLINE void __NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) -{ -#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U) - uint32_t *vectors = (uint32_t *)SCB->VTOR; -#else - uint32_t *vectors = (uint32_t *)0x0U; -#endif - vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET] = vector; -} - - -/** - \brief Get Interrupt Vector - \details Reads an interrupt vector from interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Address of interrupt handler function - */ -__STATIC_INLINE uint32_t __NVIC_GetVector(IRQn_Type IRQn) -{ -#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U) - uint32_t *vectors = (uint32_t *)SCB->VTOR; -#else - uint32_t *vectors = (uint32_t *)0x0U; -#endif - return vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET]; -} - - -/** - \brief System Reset - \details Initiates a system reset request to reset the MCU. - */ -__NO_RETURN __STATIC_INLINE void __NVIC_SystemReset(void) -{ - __DSB(); /* Ensure all outstanding memory accesses included - buffered write are completed before reset */ - SCB->AIRCR = ((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - SCB_AIRCR_SYSRESETREQ_Msk); - __DSB(); /* Ensure completion of memory access */ - - for(;;) /* wait until reset */ - { - __NOP(); - } -} - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) -/** - \brief Enable Interrupt (non-secure) - \details Enables a device specific interrupt in the non-secure NVIC interrupt controller when in secure state. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void TZ_NVIC_EnableIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC_NS->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Interrupt Enable status (non-secure) - \details Returns a device specific interrupt enable status from the non-secure NVIC interrupt controller when in secure state. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt is not enabled. - \return 1 Interrupt is enabled. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t TZ_NVIC_GetEnableIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC_NS->ISER[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Disable Interrupt (non-secure) - \details Disables a device specific interrupt in the non-secure NVIC interrupt controller when in secure state. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void TZ_NVIC_DisableIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC_NS->ICER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Pending Interrupt (non-secure) - \details Reads the NVIC pending register in the non-secure NVIC when in secure state and returns the pending bit for the specified device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not pending. - \return 1 Interrupt status is pending. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t TZ_NVIC_GetPendingIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC_NS->ISPR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Pending Interrupt (non-secure) - \details Sets the pending bit of a device specific interrupt in the non-secure NVIC pending register when in secure state. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void TZ_NVIC_SetPendingIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC_NS->ISPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Clear Pending Interrupt (non-secure) - \details Clears the pending bit of a device specific interrupt in the non-secure NVIC pending register when in secure state. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void TZ_NVIC_ClearPendingIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC_NS->ICPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Active Interrupt (non-secure) - \details Reads the active register in non-secure NVIC when in secure state and returns the active bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not active. - \return 1 Interrupt status is active. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t TZ_NVIC_GetActive_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC_NS->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Interrupt Priority (non-secure) - \details Sets the priority of a non-secure device specific interrupt or a non-secure processor exception when in secure state. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \param [in] priority Priority to set. - \note The priority cannot be set for every non-secure processor exception. - */ -__STATIC_INLINE void TZ_NVIC_SetPriority_NS(IRQn_Type IRQn, uint32_t priority) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC_NS->IPR[_IP_IDX(IRQn)] = ((uint32_t)(NVIC_NS->IPR[_IP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | - (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); - } - else - { - SCB_NS->SHPR[_SHP_IDX(IRQn)] = ((uint32_t)(SCB_NS->SHPR[_SHP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | - (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); - } -} - - -/** - \brief Get Interrupt Priority (non-secure) - \details Reads the priority of a non-secure device specific interrupt or a non-secure processor exception when in secure state. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Interrupt Priority. Value is aligned automatically to the implemented priority bits of the microcontroller. - */ -__STATIC_INLINE uint32_t TZ_NVIC_GetPriority_NS(IRQn_Type IRQn) -{ - - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC_NS->IPR[ _IP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS))); - } - else - { - return((uint32_t)(((SCB_NS->SHPR[_SHP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS))); - } -} -#endif /* defined (__ARM_FEATURE_CMSE) &&(__ARM_FEATURE_CMSE == 3U) */ - -/*@} end of CMSIS_Core_NVICFunctions */ - -/* ########################## MPU functions #################################### */ - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - -#include "mpu_armv8.h" - -#endif - -/* ########################## FPU functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_FpuFunctions FPU Functions - \brief Function that provides FPU type. - @{ - */ - -/** - \brief get FPU type - \details returns the FPU type - \returns - - \b 0: No FPU - - \b 1: Single precision FPU - - \b 2: Double + Single precision FPU - */ -__STATIC_INLINE uint32_t SCB_GetFPUType(void) -{ - return 0U; /* No FPU */ -} - - -/*@} end of CMSIS_Core_FpuFunctions */ - - - -/* ########################## SAU functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_SAUFunctions SAU Functions - \brief Functions that configure the SAU. - @{ - */ - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) - -/** - \brief Enable SAU - \details Enables the Security Attribution Unit (SAU). - */ -__STATIC_INLINE void TZ_SAU_Enable(void) -{ - SAU->CTRL |= (SAU_CTRL_ENABLE_Msk); -} - - - -/** - \brief Disable SAU - \details Disables the Security Attribution Unit (SAU). - */ -__STATIC_INLINE void TZ_SAU_Disable(void) -{ - SAU->CTRL &= ~(SAU_CTRL_ENABLE_Msk); -} - -#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ - -/*@} end of CMSIS_Core_SAUFunctions */ - - - - -/* ################################## SysTick function ############################################ */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_SysTickFunctions SysTick Functions - \brief Functions that configure the System. - @{ - */ - -#if defined (__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U) - -/** - \brief System Tick Configuration - \details Initializes the System Timer and its interrupt, and starts the System Tick Timer. - Counter is in free running mode to generate periodic interrupts. - \param [in] ticks Number of ticks between two interrupts. - \return 0 Function succeeded. - \return 1 Function failed. - \note When the variable __Vendor_SysTickConfig is set to 1, then the - function SysTick_Config is not included. In this case, the file device.h - must contain a vendor-specific implementation of this function. - */ -__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) -{ - if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) - { - return (1UL); /* Reload value impossible */ - } - - SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ - NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ - SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ - SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | - SysTick_CTRL_TICKINT_Msk | - SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ - return (0UL); /* Function successful */ -} - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) -/** - \brief System Tick Configuration (non-secure) - \details Initializes the non-secure System Timer and its interrupt when in secure state, and starts the System Tick Timer. - Counter is in free running mode to generate periodic interrupts. - \param [in] ticks Number of ticks between two interrupts. - \return 0 Function succeeded. - \return 1 Function failed. - \note When the variable __Vendor_SysTickConfig is set to 1, then the - function TZ_SysTick_Config_NS is not included. In this case, the file device.h - must contain a vendor-specific implementation of this function. - - */ -__STATIC_INLINE uint32_t TZ_SysTick_Config_NS(uint32_t ticks) -{ - if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) - { - return (1UL); /* Reload value impossible */ - } - - SysTick_NS->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ - TZ_NVIC_SetPriority_NS (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ - SysTick_NS->VAL = 0UL; /* Load the SysTick Counter Value */ - SysTick_NS->CTRL = SysTick_CTRL_CLKSOURCE_Msk | - SysTick_CTRL_TICKINT_Msk | - SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ - return (0UL); /* Function successful */ -} -#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ - -#endif - -/*@} end of CMSIS_Core_SysTickFunctions */ - - - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_ARMV8MBL_H_DEPENDANT */ - -#endif /* __CMSIS_GENERIC */ diff --git a/body/board/inc/core_armv8mml.h b/body/board/inc/core_armv8mml.h deleted file mode 100644 index 3a3148e..0000000 --- a/body/board/inc/core_armv8mml.h +++ /dev/null @@ -1,2927 +0,0 @@ -/**************************************************************************//** - * @file core_armv8mml.h - * @brief CMSIS Armv8-M Mainline Core Peripheral Access Layer Header File - * @version V5.0.7 - * @date 06. July 2018 - ******************************************************************************/ -/* - * Copyright (c) 2009-2018 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef __CORE_ARMV8MML_H_GENERIC -#define __CORE_ARMV8MML_H_GENERIC - -#include - -#ifdef __cplusplus - extern "C" { -#endif - -/** - \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions - CMSIS violates the following MISRA-C:2004 rules: - - \li Required Rule 8.5, object/function definition in header file.
- Function definitions in header files are used to allow 'inlining'. - - \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
- Unions are used for effective representation of core registers. - - \li Advisory Rule 19.7, Function-like macro defined.
- Function-like macros are used to allow more efficient code. - */ - - -/******************************************************************************* - * CMSIS definitions - ******************************************************************************/ -/** - \ingroup Cortex_ARMv8MML - @{ - */ - -#include "cmsis_version.h" - -/* CMSIS Armv8MML definitions */ -#define __ARMv8MML_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */ -#define __ARMv8MML_CMSIS_VERSION_SUB (__CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */ -#define __ARMv8MML_CMSIS_VERSION ((__ARMv8MML_CMSIS_VERSION_MAIN << 16U) | \ - __ARMv8MML_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */ - -#define __CORTEX_M (81U) /*!< Cortex-M Core */ - -/** __FPU_USED indicates whether an FPU is used or not. - For this, __FPU_PRESENT has to be checked prior to making use of FPU specific registers and functions. -*/ -#if defined ( __CC_ARM ) - #if defined __TARGET_FPU_VFP - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - - #if defined(__ARM_FEATURE_DSP) - #if defined(__DSP_PRESENT) && (__DSP_PRESENT == 1U) - #define __DSP_USED 1U - #else - #error "Compiler generates DSP (SIMD) instructions for a devices without DSP extensions (check __DSP_PRESENT)" - #define __DSP_USED 0U - #endif - #else - #define __DSP_USED 0U - #endif - -#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #if defined __ARM_PCS_VFP - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - - #if defined(__ARM_FEATURE_DSP) - #if defined(__DSP_PRESENT) && (__DSP_PRESENT == 1U) - #define __DSP_USED 1U - #else - #error "Compiler generates DSP (SIMD) instructions for a devices without DSP extensions (check __DSP_PRESENT)" - #define __DSP_USED 0U - #endif - #else - #define __DSP_USED 0U - #endif - -#elif defined ( __GNUC__ ) - #if defined (__VFP_FP__) && !defined(__SOFTFP__) - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - - #if defined(__ARM_FEATURE_DSP) - #if defined(__DSP_PRESENT) && (__DSP_PRESENT == 1U) - #define __DSP_USED 1U - #else - #error "Compiler generates DSP (SIMD) instructions for a devices without DSP extensions (check __DSP_PRESENT)" - #define __DSP_USED 0U - #endif - #else - #define __DSP_USED 0U - #endif - -#elif defined ( __ICCARM__ ) - #if defined __ARMVFP__ - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - - #if defined(__ARM_FEATURE_DSP) - #if defined(__DSP_PRESENT) && (__DSP_PRESENT == 1U) - #define __DSP_USED 1U - #else - #error "Compiler generates DSP (SIMD) instructions for a devices without DSP extensions (check __DSP_PRESENT)" - #define __DSP_USED 0U - #endif - #else - #define __DSP_USED 0U - #endif - -#elif defined ( __TI_ARM__ ) - #if defined __TI_VFP_SUPPORT__ - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __TASKING__ ) - #if defined __FPU_VFP__ - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __CSMC__ ) - #if ( __CSMC__ & 0x400U) - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#endif - -#include "cmsis_compiler.h" /* CMSIS compiler specific defines */ - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_ARMV8MML_H_GENERIC */ - -#ifndef __CMSIS_GENERIC - -#ifndef __CORE_ARMV8MML_H_DEPENDANT -#define __CORE_ARMV8MML_H_DEPENDANT - -#ifdef __cplusplus - extern "C" { -#endif - -/* check device defines and use defaults */ -#if defined __CHECK_DEVICE_DEFINES - #ifndef __ARMv8MML_REV - #define __ARMv8MML_REV 0x0000U - #warning "__ARMv8MML_REV not defined in device header file; using default!" - #endif - - #ifndef __FPU_PRESENT - #define __FPU_PRESENT 0U - #warning "__FPU_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __MPU_PRESENT - #define __MPU_PRESENT 0U - #warning "__MPU_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __SAUREGION_PRESENT - #define __SAUREGION_PRESENT 0U - #warning "__SAUREGION_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __DSP_PRESENT - #define __DSP_PRESENT 0U - #warning "__DSP_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __NVIC_PRIO_BITS - #define __NVIC_PRIO_BITS 3U - #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" - #endif - - #ifndef __Vendor_SysTickConfig - #define __Vendor_SysTickConfig 0U - #warning "__Vendor_SysTickConfig not defined in device header file; using default!" - #endif -#endif - -/* IO definitions (access restrictions to peripheral registers) */ -/** - \defgroup CMSIS_glob_defs CMSIS Global Defines - - IO Type Qualifiers are used - \li to specify the access to peripheral variables. - \li for automatic generation of peripheral register debug information. -*/ -#ifdef __cplusplus - #define __I volatile /*!< Defines 'read only' permissions */ -#else - #define __I volatile const /*!< Defines 'read only' permissions */ -#endif -#define __O volatile /*!< Defines 'write only' permissions */ -#define __IO volatile /*!< Defines 'read / write' permissions */ - -/* following defines should be used for structure members */ -#define __IM volatile const /*! Defines 'read only' structure member permissions */ -#define __OM volatile /*! Defines 'write only' structure member permissions */ -#define __IOM volatile /*! Defines 'read / write' structure member permissions */ - -/*@} end of group ARMv8MML */ - - - -/******************************************************************************* - * Register Abstraction - Core Register contain: - - Core Register - - Core NVIC Register - - Core SCB Register - - Core SysTick Register - - Core Debug Register - - Core MPU Register - - Core SAU Register - - Core FPU Register - ******************************************************************************/ -/** - \defgroup CMSIS_core_register Defines and Type Definitions - \brief Type definitions and defines for Cortex-M processor based devices. -*/ - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CORE Status and Control Registers - \brief Core Register type definitions. - @{ - */ - -/** - \brief Union type to access the Application Program Status Register (APSR). - */ -typedef union -{ - struct - { - uint32_t _reserved0:16; /*!< bit: 0..15 Reserved */ - uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ - uint32_t _reserved1:7; /*!< bit: 20..26 Reserved */ - uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} APSR_Type; - -/* APSR Register Definitions */ -#define APSR_N_Pos 31U /*!< APSR: N Position */ -#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ - -#define APSR_Z_Pos 30U /*!< APSR: Z Position */ -#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ - -#define APSR_C_Pos 29U /*!< APSR: C Position */ -#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ - -#define APSR_V_Pos 28U /*!< APSR: V Position */ -#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ - -#define APSR_Q_Pos 27U /*!< APSR: Q Position */ -#define APSR_Q_Msk (1UL << APSR_Q_Pos) /*!< APSR: Q Mask */ - -#define APSR_GE_Pos 16U /*!< APSR: GE Position */ -#define APSR_GE_Msk (0xFUL << APSR_GE_Pos) /*!< APSR: GE Mask */ - - -/** - \brief Union type to access the Interrupt Program Status Register (IPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} IPSR_Type; - -/* IPSR Register Definitions */ -#define IPSR_ISR_Pos 0U /*!< IPSR: ISR Position */ -#define IPSR_ISR_Msk (0x1FFUL /*<< IPSR_ISR_Pos*/) /*!< IPSR: ISR Mask */ - - -/** - \brief Union type to access the Special-Purpose Program Status Registers (xPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:7; /*!< bit: 9..15 Reserved */ - uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ - uint32_t _reserved1:4; /*!< bit: 20..23 Reserved */ - uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */ - uint32_t IT:2; /*!< bit: 25..26 saved IT state (read 0) */ - uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} xPSR_Type; - -/* xPSR Register Definitions */ -#define xPSR_N_Pos 31U /*!< xPSR: N Position */ -#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ - -#define xPSR_Z_Pos 30U /*!< xPSR: Z Position */ -#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ - -#define xPSR_C_Pos 29U /*!< xPSR: C Position */ -#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ - -#define xPSR_V_Pos 28U /*!< xPSR: V Position */ -#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ - -#define xPSR_Q_Pos 27U /*!< xPSR: Q Position */ -#define xPSR_Q_Msk (1UL << xPSR_Q_Pos) /*!< xPSR: Q Mask */ - -#define xPSR_IT_Pos 25U /*!< xPSR: IT Position */ -#define xPSR_IT_Msk (3UL << xPSR_IT_Pos) /*!< xPSR: IT Mask */ - -#define xPSR_T_Pos 24U /*!< xPSR: T Position */ -#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ - -#define xPSR_GE_Pos 16U /*!< xPSR: GE Position */ -#define xPSR_GE_Msk (0xFUL << xPSR_GE_Pos) /*!< xPSR: GE Mask */ - -#define xPSR_ISR_Pos 0U /*!< xPSR: ISR Position */ -#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ - - -/** - \brief Union type to access the Control Registers (CONTROL). - */ -typedef union -{ - struct - { - uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ - uint32_t SPSEL:1; /*!< bit: 1 Stack-pointer select */ - uint32_t FPCA:1; /*!< bit: 2 Floating-point context active */ - uint32_t SFPA:1; /*!< bit: 3 Secure floating-point active */ - uint32_t _reserved1:28; /*!< bit: 4..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} CONTROL_Type; - -/* CONTROL Register Definitions */ -#define CONTROL_SFPA_Pos 3U /*!< CONTROL: SFPA Position */ -#define CONTROL_SFPA_Msk (1UL << CONTROL_SFPA_Pos) /*!< CONTROL: SFPA Mask */ - -#define CONTROL_FPCA_Pos 2U /*!< CONTROL: FPCA Position */ -#define CONTROL_FPCA_Msk (1UL << CONTROL_FPCA_Pos) /*!< CONTROL: FPCA Mask */ - -#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */ -#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ - -#define CONTROL_nPRIV_Pos 0U /*!< CONTROL: nPRIV Position */ -#define CONTROL_nPRIV_Msk (1UL /*<< CONTROL_nPRIV_Pos*/) /*!< CONTROL: nPRIV Mask */ - -/*@} end of group CMSIS_CORE */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC) - \brief Type definitions for the NVIC Registers - @{ - */ - -/** - \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). - */ -typedef struct -{ - __IOM uint32_t ISER[16U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ - uint32_t RESERVED0[16U]; - __IOM uint32_t ICER[16U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ - uint32_t RSERVED1[16U]; - __IOM uint32_t ISPR[16U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ - uint32_t RESERVED2[16U]; - __IOM uint32_t ICPR[16U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ - uint32_t RESERVED3[16U]; - __IOM uint32_t IABR[16U]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */ - uint32_t RESERVED4[16U]; - __IOM uint32_t ITNS[16U]; /*!< Offset: 0x280 (R/W) Interrupt Non-Secure State Register */ - uint32_t RESERVED5[16U]; - __IOM uint8_t IPR[496U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register (8Bit wide) */ - uint32_t RESERVED6[580U]; - __OM uint32_t STIR; /*!< Offset: 0xE00 ( /W) Software Trigger Interrupt Register */ -} NVIC_Type; - -/* Software Triggered Interrupt Register Definitions */ -#define NVIC_STIR_INTID_Pos 0U /*!< STIR: INTLINESNUM Position */ -#define NVIC_STIR_INTID_Msk (0x1FFUL /*<< NVIC_STIR_INTID_Pos*/) /*!< STIR: INTLINESNUM Mask */ - -/*@} end of group CMSIS_NVIC */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SCB System Control Block (SCB) - \brief Type definitions for the System Control Block Registers - @{ - */ - -/** - \brief Structure type to access the System Control Block (SCB). - */ -typedef struct -{ - __IM uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ - __IOM uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ - __IOM uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ - __IOM uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ - __IOM uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ - __IOM uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ - __IOM uint8_t SHPR[12U]; /*!< Offset: 0x018 (R/W) System Handlers Priority Registers (4-7, 8-11, 12-15) */ - __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ - __IOM uint32_t CFSR; /*!< Offset: 0x028 (R/W) Configurable Fault Status Register */ - __IOM uint32_t HFSR; /*!< Offset: 0x02C (R/W) HardFault Status Register */ - __IOM uint32_t DFSR; /*!< Offset: 0x030 (R/W) Debug Fault Status Register */ - __IOM uint32_t MMFAR; /*!< Offset: 0x034 (R/W) MemManage Fault Address Register */ - __IOM uint32_t BFAR; /*!< Offset: 0x038 (R/W) BusFault Address Register */ - __IOM uint32_t AFSR; /*!< Offset: 0x03C (R/W) Auxiliary Fault Status Register */ - __IM uint32_t ID_PFR[2U]; /*!< Offset: 0x040 (R/ ) Processor Feature Register */ - __IM uint32_t ID_DFR; /*!< Offset: 0x048 (R/ ) Debug Feature Register */ - __IM uint32_t ID_ADR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */ - __IM uint32_t ID_MMFR[4U]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */ - __IM uint32_t ID_ISAR[6U]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */ - __IM uint32_t CLIDR; /*!< Offset: 0x078 (R/ ) Cache Level ID register */ - __IM uint32_t CTR; /*!< Offset: 0x07C (R/ ) Cache Type register */ - __IM uint32_t CCSIDR; /*!< Offset: 0x080 (R/ ) Cache Size ID Register */ - __IOM uint32_t CSSELR; /*!< Offset: 0x084 (R/W) Cache Size Selection Register */ - __IOM uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control Register */ - __IOM uint32_t NSACR; /*!< Offset: 0x08C (R/W) Non-Secure Access Control Register */ - uint32_t RESERVED3[92U]; - __OM uint32_t STIR; /*!< Offset: 0x200 ( /W) Software Triggered Interrupt Register */ - uint32_t RESERVED4[15U]; - __IM uint32_t MVFR0; /*!< Offset: 0x240 (R/ ) Media and VFP Feature Register 0 */ - __IM uint32_t MVFR1; /*!< Offset: 0x244 (R/ ) Media and VFP Feature Register 1 */ - __IM uint32_t MVFR2; /*!< Offset: 0x248 (R/ ) Media and VFP Feature Register 2 */ - uint32_t RESERVED5[1U]; - __OM uint32_t ICIALLU; /*!< Offset: 0x250 ( /W) I-Cache Invalidate All to PoU */ - uint32_t RESERVED6[1U]; - __OM uint32_t ICIMVAU; /*!< Offset: 0x258 ( /W) I-Cache Invalidate by MVA to PoU */ - __OM uint32_t DCIMVAC; /*!< Offset: 0x25C ( /W) D-Cache Invalidate by MVA to PoC */ - __OM uint32_t DCISW; /*!< Offset: 0x260 ( /W) D-Cache Invalidate by Set-way */ - __OM uint32_t DCCMVAU; /*!< Offset: 0x264 ( /W) D-Cache Clean by MVA to PoU */ - __OM uint32_t DCCMVAC; /*!< Offset: 0x268 ( /W) D-Cache Clean by MVA to PoC */ - __OM uint32_t DCCSW; /*!< Offset: 0x26C ( /W) D-Cache Clean by Set-way */ - __OM uint32_t DCCIMVAC; /*!< Offset: 0x270 ( /W) D-Cache Clean and Invalidate by MVA to PoC */ - __OM uint32_t DCCISW; /*!< Offset: 0x274 ( /W) D-Cache Clean and Invalidate by Set-way */ - uint32_t RESERVED7[6U]; - __IOM uint32_t ITCMCR; /*!< Offset: 0x290 (R/W) Instruction Tightly-Coupled Memory Control Register */ - __IOM uint32_t DTCMCR; /*!< Offset: 0x294 (R/W) Data Tightly-Coupled Memory Control Registers */ - __IOM uint32_t AHBPCR; /*!< Offset: 0x298 (R/W) AHBP Control Register */ - __IOM uint32_t CACR; /*!< Offset: 0x29C (R/W) L1 Cache Control Register */ - __IOM uint32_t AHBSCR; /*!< Offset: 0x2A0 (R/W) AHB Slave Control Register */ - uint32_t RESERVED8[1U]; - __IOM uint32_t ABFSR; /*!< Offset: 0x2A8 (R/W) Auxiliary Bus Fault Status Register */ -} SCB_Type; - -/* SCB CPUID Register Definitions */ -#define SCB_CPUID_IMPLEMENTER_Pos 24U /*!< SCB CPUID: IMPLEMENTER Position */ -#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ - -#define SCB_CPUID_VARIANT_Pos 20U /*!< SCB CPUID: VARIANT Position */ -#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ - -#define SCB_CPUID_ARCHITECTURE_Pos 16U /*!< SCB CPUID: ARCHITECTURE Position */ -#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ - -#define SCB_CPUID_PARTNO_Pos 4U /*!< SCB CPUID: PARTNO Position */ -#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ - -#define SCB_CPUID_REVISION_Pos 0U /*!< SCB CPUID: REVISION Position */ -#define SCB_CPUID_REVISION_Msk (0xFUL /*<< SCB_CPUID_REVISION_Pos*/) /*!< SCB CPUID: REVISION Mask */ - -/* SCB Interrupt Control State Register Definitions */ -#define SCB_ICSR_PENDNMISET_Pos 31U /*!< SCB ICSR: PENDNMISET Position */ -#define SCB_ICSR_PENDNMISET_Msk (1UL << SCB_ICSR_PENDNMISET_Pos) /*!< SCB ICSR: PENDNMISET Mask */ - -#define SCB_ICSR_NMIPENDSET_Pos SCB_ICSR_PENDNMISET_Pos /*!< SCB ICSR: NMIPENDSET Position, backward compatibility */ -#define SCB_ICSR_NMIPENDSET_Msk SCB_ICSR_PENDNMISET_Msk /*!< SCB ICSR: NMIPENDSET Mask, backward compatibility */ - -#define SCB_ICSR_PENDNMICLR_Pos 30U /*!< SCB ICSR: PENDNMICLR Position */ -#define SCB_ICSR_PENDNMICLR_Msk (1UL << SCB_ICSR_PENDNMICLR_Pos) /*!< SCB ICSR: PENDNMICLR Mask */ - -#define SCB_ICSR_PENDSVSET_Pos 28U /*!< SCB ICSR: PENDSVSET Position */ -#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ - -#define SCB_ICSR_PENDSVCLR_Pos 27U /*!< SCB ICSR: PENDSVCLR Position */ -#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ - -#define SCB_ICSR_PENDSTSET_Pos 26U /*!< SCB ICSR: PENDSTSET Position */ -#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ - -#define SCB_ICSR_PENDSTCLR_Pos 25U /*!< SCB ICSR: PENDSTCLR Position */ -#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ - -#define SCB_ICSR_STTNS_Pos 24U /*!< SCB ICSR: STTNS Position (Security Extension) */ -#define SCB_ICSR_STTNS_Msk (1UL << SCB_ICSR_STTNS_Pos) /*!< SCB ICSR: STTNS Mask (Security Extension) */ - -#define SCB_ICSR_ISRPREEMPT_Pos 23U /*!< SCB ICSR: ISRPREEMPT Position */ -#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ - -#define SCB_ICSR_ISRPENDING_Pos 22U /*!< SCB ICSR: ISRPENDING Position */ -#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ - -#define SCB_ICSR_VECTPENDING_Pos 12U /*!< SCB ICSR: VECTPENDING Position */ -#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ - -#define SCB_ICSR_RETTOBASE_Pos 11U /*!< SCB ICSR: RETTOBASE Position */ -#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */ - -#define SCB_ICSR_VECTACTIVE_Pos 0U /*!< SCB ICSR: VECTACTIVE Position */ -#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ - -/* SCB Vector Table Offset Register Definitions */ -#define SCB_VTOR_TBLOFF_Pos 7U /*!< SCB VTOR: TBLOFF Position */ -#define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ - -/* SCB Application Interrupt and Reset Control Register Definitions */ -#define SCB_AIRCR_VECTKEY_Pos 16U /*!< SCB AIRCR: VECTKEY Position */ -#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ - -#define SCB_AIRCR_VECTKEYSTAT_Pos 16U /*!< SCB AIRCR: VECTKEYSTAT Position */ -#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ - -#define SCB_AIRCR_ENDIANESS_Pos 15U /*!< SCB AIRCR: ENDIANESS Position */ -#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ - -#define SCB_AIRCR_PRIS_Pos 14U /*!< SCB AIRCR: PRIS Position */ -#define SCB_AIRCR_PRIS_Msk (1UL << SCB_AIRCR_PRIS_Pos) /*!< SCB AIRCR: PRIS Mask */ - -#define SCB_AIRCR_BFHFNMINS_Pos 13U /*!< SCB AIRCR: BFHFNMINS Position */ -#define SCB_AIRCR_BFHFNMINS_Msk (1UL << SCB_AIRCR_BFHFNMINS_Pos) /*!< SCB AIRCR: BFHFNMINS Mask */ - -#define SCB_AIRCR_PRIGROUP_Pos 8U /*!< SCB AIRCR: PRIGROUP Position */ -#define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */ - -#define SCB_AIRCR_SYSRESETREQS_Pos 3U /*!< SCB AIRCR: SYSRESETREQS Position */ -#define SCB_AIRCR_SYSRESETREQS_Msk (1UL << SCB_AIRCR_SYSRESETREQS_Pos) /*!< SCB AIRCR: SYSRESETREQS Mask */ - -#define SCB_AIRCR_SYSRESETREQ_Pos 2U /*!< SCB AIRCR: SYSRESETREQ Position */ -#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ - -#define SCB_AIRCR_VECTCLRACTIVE_Pos 1U /*!< SCB AIRCR: VECTCLRACTIVE Position */ -#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ - -/* SCB System Control Register Definitions */ -#define SCB_SCR_SEVONPEND_Pos 4U /*!< SCB SCR: SEVONPEND Position */ -#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ - -#define SCB_SCR_SLEEPDEEPS_Pos 3U /*!< SCB SCR: SLEEPDEEPS Position */ -#define SCB_SCR_SLEEPDEEPS_Msk (1UL << SCB_SCR_SLEEPDEEPS_Pos) /*!< SCB SCR: SLEEPDEEPS Mask */ - -#define SCB_SCR_SLEEPDEEP_Pos 2U /*!< SCB SCR: SLEEPDEEP Position */ -#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ - -#define SCB_SCR_SLEEPONEXIT_Pos 1U /*!< SCB SCR: SLEEPONEXIT Position */ -#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ - -/* SCB Configuration Control Register Definitions */ -#define SCB_CCR_BP_Pos 18U /*!< SCB CCR: BP Position */ -#define SCB_CCR_BP_Msk (1UL << SCB_CCR_BP_Pos) /*!< SCB CCR: BP Mask */ - -#define SCB_CCR_IC_Pos 17U /*!< SCB CCR: IC Position */ -#define SCB_CCR_IC_Msk (1UL << SCB_CCR_IC_Pos) /*!< SCB CCR: IC Mask */ - -#define SCB_CCR_DC_Pos 16U /*!< SCB CCR: DC Position */ -#define SCB_CCR_DC_Msk (1UL << SCB_CCR_DC_Pos) /*!< SCB CCR: DC Mask */ - -#define SCB_CCR_STKOFHFNMIGN_Pos 10U /*!< SCB CCR: STKOFHFNMIGN Position */ -#define SCB_CCR_STKOFHFNMIGN_Msk (1UL << SCB_CCR_STKOFHFNMIGN_Pos) /*!< SCB CCR: STKOFHFNMIGN Mask */ - -#define SCB_CCR_BFHFNMIGN_Pos 8U /*!< SCB CCR: BFHFNMIGN Position */ -#define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */ - -#define SCB_CCR_DIV_0_TRP_Pos 4U /*!< SCB CCR: DIV_0_TRP Position */ -#define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */ - -#define SCB_CCR_UNALIGN_TRP_Pos 3U /*!< SCB CCR: UNALIGN_TRP Position */ -#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ - -#define SCB_CCR_USERSETMPEND_Pos 1U /*!< SCB CCR: USERSETMPEND Position */ -#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */ - -/* SCB System Handler Control and State Register Definitions */ -#define SCB_SHCSR_HARDFAULTPENDED_Pos 21U /*!< SCB SHCSR: HARDFAULTPENDED Position */ -#define SCB_SHCSR_HARDFAULTPENDED_Msk (1UL << SCB_SHCSR_HARDFAULTPENDED_Pos) /*!< SCB SHCSR: HARDFAULTPENDED Mask */ - -#define SCB_SHCSR_SECUREFAULTPENDED_Pos 20U /*!< SCB SHCSR: SECUREFAULTPENDED Position */ -#define SCB_SHCSR_SECUREFAULTPENDED_Msk (1UL << SCB_SHCSR_SECUREFAULTPENDED_Pos) /*!< SCB SHCSR: SECUREFAULTPENDED Mask */ - -#define SCB_SHCSR_SECUREFAULTENA_Pos 19U /*!< SCB SHCSR: SECUREFAULTENA Position */ -#define SCB_SHCSR_SECUREFAULTENA_Msk (1UL << SCB_SHCSR_SECUREFAULTENA_Pos) /*!< SCB SHCSR: SECUREFAULTENA Mask */ - -#define SCB_SHCSR_USGFAULTENA_Pos 18U /*!< SCB SHCSR: USGFAULTENA Position */ -#define SCB_SHCSR_USGFAULTENA_Msk (1UL << SCB_SHCSR_USGFAULTENA_Pos) /*!< SCB SHCSR: USGFAULTENA Mask */ - -#define SCB_SHCSR_BUSFAULTENA_Pos 17U /*!< SCB SHCSR: BUSFAULTENA Position */ -#define SCB_SHCSR_BUSFAULTENA_Msk (1UL << SCB_SHCSR_BUSFAULTENA_Pos) /*!< SCB SHCSR: BUSFAULTENA Mask */ - -#define SCB_SHCSR_MEMFAULTENA_Pos 16U /*!< SCB SHCSR: MEMFAULTENA Position */ -#define SCB_SHCSR_MEMFAULTENA_Msk (1UL << SCB_SHCSR_MEMFAULTENA_Pos) /*!< SCB SHCSR: MEMFAULTENA Mask */ - -#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */ -#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ - -#define SCB_SHCSR_BUSFAULTPENDED_Pos 14U /*!< SCB SHCSR: BUSFAULTPENDED Position */ -#define SCB_SHCSR_BUSFAULTPENDED_Msk (1UL << SCB_SHCSR_BUSFAULTPENDED_Pos) /*!< SCB SHCSR: BUSFAULTPENDED Mask */ - -#define SCB_SHCSR_MEMFAULTPENDED_Pos 13U /*!< SCB SHCSR: MEMFAULTPENDED Position */ -#define SCB_SHCSR_MEMFAULTPENDED_Msk (1UL << SCB_SHCSR_MEMFAULTPENDED_Pos) /*!< SCB SHCSR: MEMFAULTPENDED Mask */ - -#define SCB_SHCSR_USGFAULTPENDED_Pos 12U /*!< SCB SHCSR: USGFAULTPENDED Position */ -#define SCB_SHCSR_USGFAULTPENDED_Msk (1UL << SCB_SHCSR_USGFAULTPENDED_Pos) /*!< SCB SHCSR: USGFAULTPENDED Mask */ - -#define SCB_SHCSR_SYSTICKACT_Pos 11U /*!< SCB SHCSR: SYSTICKACT Position */ -#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */ - -#define SCB_SHCSR_PENDSVACT_Pos 10U /*!< SCB SHCSR: PENDSVACT Position */ -#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */ - -#define SCB_SHCSR_MONITORACT_Pos 8U /*!< SCB SHCSR: MONITORACT Position */ -#define SCB_SHCSR_MONITORACT_Msk (1UL << SCB_SHCSR_MONITORACT_Pos) /*!< SCB SHCSR: MONITORACT Mask */ - -#define SCB_SHCSR_SVCALLACT_Pos 7U /*!< SCB SHCSR: SVCALLACT Position */ -#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */ - -#define SCB_SHCSR_NMIACT_Pos 5U /*!< SCB SHCSR: NMIACT Position */ -#define SCB_SHCSR_NMIACT_Msk (1UL << SCB_SHCSR_NMIACT_Pos) /*!< SCB SHCSR: NMIACT Mask */ - -#define SCB_SHCSR_SECUREFAULTACT_Pos 4U /*!< SCB SHCSR: SECUREFAULTACT Position */ -#define SCB_SHCSR_SECUREFAULTACT_Msk (1UL << SCB_SHCSR_SECUREFAULTACT_Pos) /*!< SCB SHCSR: SECUREFAULTACT Mask */ - -#define SCB_SHCSR_USGFAULTACT_Pos 3U /*!< SCB SHCSR: USGFAULTACT Position */ -#define SCB_SHCSR_USGFAULTACT_Msk (1UL << SCB_SHCSR_USGFAULTACT_Pos) /*!< SCB SHCSR: USGFAULTACT Mask */ - -#define SCB_SHCSR_HARDFAULTACT_Pos 2U /*!< SCB SHCSR: HARDFAULTACT Position */ -#define SCB_SHCSR_HARDFAULTACT_Msk (1UL << SCB_SHCSR_HARDFAULTACT_Pos) /*!< SCB SHCSR: HARDFAULTACT Mask */ - -#define SCB_SHCSR_BUSFAULTACT_Pos 1U /*!< SCB SHCSR: BUSFAULTACT Position */ -#define SCB_SHCSR_BUSFAULTACT_Msk (1UL << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */ - -#define SCB_SHCSR_MEMFAULTACT_Pos 0U /*!< SCB SHCSR: MEMFAULTACT Position */ -#define SCB_SHCSR_MEMFAULTACT_Msk (1UL /*<< SCB_SHCSR_MEMFAULTACT_Pos*/) /*!< SCB SHCSR: MEMFAULTACT Mask */ - -/* SCB Configurable Fault Status Register Definitions */ -#define SCB_CFSR_USGFAULTSR_Pos 16U /*!< SCB CFSR: Usage Fault Status Register Position */ -#define SCB_CFSR_USGFAULTSR_Msk (0xFFFFUL << SCB_CFSR_USGFAULTSR_Pos) /*!< SCB CFSR: Usage Fault Status Register Mask */ - -#define SCB_CFSR_BUSFAULTSR_Pos 8U /*!< SCB CFSR: Bus Fault Status Register Position */ -#define SCB_CFSR_BUSFAULTSR_Msk (0xFFUL << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */ - -#define SCB_CFSR_MEMFAULTSR_Pos 0U /*!< SCB CFSR: Memory Manage Fault Status Register Position */ -#define SCB_CFSR_MEMFAULTSR_Msk (0xFFUL /*<< SCB_CFSR_MEMFAULTSR_Pos*/) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */ - -/* MemManage Fault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_MMARVALID_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 7U) /*!< SCB CFSR (MMFSR): MMARVALID Position */ -#define SCB_CFSR_MMARVALID_Msk (1UL << SCB_CFSR_MMARVALID_Pos) /*!< SCB CFSR (MMFSR): MMARVALID Mask */ - -#define SCB_CFSR_MLSPERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 5U) /*!< SCB CFSR (MMFSR): MLSPERR Position */ -#define SCB_CFSR_MLSPERR_Msk (1UL << SCB_CFSR_MLSPERR_Pos) /*!< SCB CFSR (MMFSR): MLSPERR Mask */ - -#define SCB_CFSR_MSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 4U) /*!< SCB CFSR (MMFSR): MSTKERR Position */ -#define SCB_CFSR_MSTKERR_Msk (1UL << SCB_CFSR_MSTKERR_Pos) /*!< SCB CFSR (MMFSR): MSTKERR Mask */ - -#define SCB_CFSR_MUNSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 3U) /*!< SCB CFSR (MMFSR): MUNSTKERR Position */ -#define SCB_CFSR_MUNSTKERR_Msk (1UL << SCB_CFSR_MUNSTKERR_Pos) /*!< SCB CFSR (MMFSR): MUNSTKERR Mask */ - -#define SCB_CFSR_DACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 1U) /*!< SCB CFSR (MMFSR): DACCVIOL Position */ -#define SCB_CFSR_DACCVIOL_Msk (1UL << SCB_CFSR_DACCVIOL_Pos) /*!< SCB CFSR (MMFSR): DACCVIOL Mask */ - -#define SCB_CFSR_IACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 0U) /*!< SCB CFSR (MMFSR): IACCVIOL Position */ -#define SCB_CFSR_IACCVIOL_Msk (1UL /*<< SCB_CFSR_IACCVIOL_Pos*/) /*!< SCB CFSR (MMFSR): IACCVIOL Mask */ - -/* BusFault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_BFARVALID_Pos (SCB_CFSR_BUSFAULTSR_Pos + 7U) /*!< SCB CFSR (BFSR): BFARVALID Position */ -#define SCB_CFSR_BFARVALID_Msk (1UL << SCB_CFSR_BFARVALID_Pos) /*!< SCB CFSR (BFSR): BFARVALID Mask */ - -#define SCB_CFSR_LSPERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 5U) /*!< SCB CFSR (BFSR): LSPERR Position */ -#define SCB_CFSR_LSPERR_Msk (1UL << SCB_CFSR_LSPERR_Pos) /*!< SCB CFSR (BFSR): LSPERR Mask */ - -#define SCB_CFSR_STKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 4U) /*!< SCB CFSR (BFSR): STKERR Position */ -#define SCB_CFSR_STKERR_Msk (1UL << SCB_CFSR_STKERR_Pos) /*!< SCB CFSR (BFSR): STKERR Mask */ - -#define SCB_CFSR_UNSTKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 3U) /*!< SCB CFSR (BFSR): UNSTKERR Position */ -#define SCB_CFSR_UNSTKERR_Msk (1UL << SCB_CFSR_UNSTKERR_Pos) /*!< SCB CFSR (BFSR): UNSTKERR Mask */ - -#define SCB_CFSR_IMPRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 2U) /*!< SCB CFSR (BFSR): IMPRECISERR Position */ -#define SCB_CFSR_IMPRECISERR_Msk (1UL << SCB_CFSR_IMPRECISERR_Pos) /*!< SCB CFSR (BFSR): IMPRECISERR Mask */ - -#define SCB_CFSR_PRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 1U) /*!< SCB CFSR (BFSR): PRECISERR Position */ -#define SCB_CFSR_PRECISERR_Msk (1UL << SCB_CFSR_PRECISERR_Pos) /*!< SCB CFSR (BFSR): PRECISERR Mask */ - -#define SCB_CFSR_IBUSERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 0U) /*!< SCB CFSR (BFSR): IBUSERR Position */ -#define SCB_CFSR_IBUSERR_Msk (1UL << SCB_CFSR_IBUSERR_Pos) /*!< SCB CFSR (BFSR): IBUSERR Mask */ - -/* UsageFault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_DIVBYZERO_Pos (SCB_CFSR_USGFAULTSR_Pos + 9U) /*!< SCB CFSR (UFSR): DIVBYZERO Position */ -#define SCB_CFSR_DIVBYZERO_Msk (1UL << SCB_CFSR_DIVBYZERO_Pos) /*!< SCB CFSR (UFSR): DIVBYZERO Mask */ - -#define SCB_CFSR_UNALIGNED_Pos (SCB_CFSR_USGFAULTSR_Pos + 8U) /*!< SCB CFSR (UFSR): UNALIGNED Position */ -#define SCB_CFSR_UNALIGNED_Msk (1UL << SCB_CFSR_UNALIGNED_Pos) /*!< SCB CFSR (UFSR): UNALIGNED Mask */ - -#define SCB_CFSR_STKOF_Pos (SCB_CFSR_USGFAULTSR_Pos + 4U) /*!< SCB CFSR (UFSR): STKOF Position */ -#define SCB_CFSR_STKOF_Msk (1UL << SCB_CFSR_STKOF_Pos) /*!< SCB CFSR (UFSR): STKOF Mask */ - -#define SCB_CFSR_NOCP_Pos (SCB_CFSR_USGFAULTSR_Pos + 3U) /*!< SCB CFSR (UFSR): NOCP Position */ -#define SCB_CFSR_NOCP_Msk (1UL << SCB_CFSR_NOCP_Pos) /*!< SCB CFSR (UFSR): NOCP Mask */ - -#define SCB_CFSR_INVPC_Pos (SCB_CFSR_USGFAULTSR_Pos + 2U) /*!< SCB CFSR (UFSR): INVPC Position */ -#define SCB_CFSR_INVPC_Msk (1UL << SCB_CFSR_INVPC_Pos) /*!< SCB CFSR (UFSR): INVPC Mask */ - -#define SCB_CFSR_INVSTATE_Pos (SCB_CFSR_USGFAULTSR_Pos + 1U) /*!< SCB CFSR (UFSR): INVSTATE Position */ -#define SCB_CFSR_INVSTATE_Msk (1UL << SCB_CFSR_INVSTATE_Pos) /*!< SCB CFSR (UFSR): INVSTATE Mask */ - -#define SCB_CFSR_UNDEFINSTR_Pos (SCB_CFSR_USGFAULTSR_Pos + 0U) /*!< SCB CFSR (UFSR): UNDEFINSTR Position */ -#define SCB_CFSR_UNDEFINSTR_Msk (1UL << SCB_CFSR_UNDEFINSTR_Pos) /*!< SCB CFSR (UFSR): UNDEFINSTR Mask */ - -/* SCB Hard Fault Status Register Definitions */ -#define SCB_HFSR_DEBUGEVT_Pos 31U /*!< SCB HFSR: DEBUGEVT Position */ -#define SCB_HFSR_DEBUGEVT_Msk (1UL << SCB_HFSR_DEBUGEVT_Pos) /*!< SCB HFSR: DEBUGEVT Mask */ - -#define SCB_HFSR_FORCED_Pos 30U /*!< SCB HFSR: FORCED Position */ -#define SCB_HFSR_FORCED_Msk (1UL << SCB_HFSR_FORCED_Pos) /*!< SCB HFSR: FORCED Mask */ - -#define SCB_HFSR_VECTTBL_Pos 1U /*!< SCB HFSR: VECTTBL Position */ -#define SCB_HFSR_VECTTBL_Msk (1UL << SCB_HFSR_VECTTBL_Pos) /*!< SCB HFSR: VECTTBL Mask */ - -/* SCB Debug Fault Status Register Definitions */ -#define SCB_DFSR_EXTERNAL_Pos 4U /*!< SCB DFSR: EXTERNAL Position */ -#define SCB_DFSR_EXTERNAL_Msk (1UL << SCB_DFSR_EXTERNAL_Pos) /*!< SCB DFSR: EXTERNAL Mask */ - -#define SCB_DFSR_VCATCH_Pos 3U /*!< SCB DFSR: VCATCH Position */ -#define SCB_DFSR_VCATCH_Msk (1UL << SCB_DFSR_VCATCH_Pos) /*!< SCB DFSR: VCATCH Mask */ - -#define SCB_DFSR_DWTTRAP_Pos 2U /*!< SCB DFSR: DWTTRAP Position */ -#define SCB_DFSR_DWTTRAP_Msk (1UL << SCB_DFSR_DWTTRAP_Pos) /*!< SCB DFSR: DWTTRAP Mask */ - -#define SCB_DFSR_BKPT_Pos 1U /*!< SCB DFSR: BKPT Position */ -#define SCB_DFSR_BKPT_Msk (1UL << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */ - -#define SCB_DFSR_HALTED_Pos 0U /*!< SCB DFSR: HALTED Position */ -#define SCB_DFSR_HALTED_Msk (1UL /*<< SCB_DFSR_HALTED_Pos*/) /*!< SCB DFSR: HALTED Mask */ - -/* SCB Non-Secure Access Control Register Definitions */ -#define SCB_NSACR_CP11_Pos 11U /*!< SCB NSACR: CP11 Position */ -#define SCB_NSACR_CP11_Msk (1UL << SCB_NSACR_CP11_Pos) /*!< SCB NSACR: CP11 Mask */ - -#define SCB_NSACR_CP10_Pos 10U /*!< SCB NSACR: CP10 Position */ -#define SCB_NSACR_CP10_Msk (1UL << SCB_NSACR_CP10_Pos) /*!< SCB NSACR: CP10 Mask */ - -#define SCB_NSACR_CPn_Pos 0U /*!< SCB NSACR: CPn Position */ -#define SCB_NSACR_CPn_Msk (1UL /*<< SCB_NSACR_CPn_Pos*/) /*!< SCB NSACR: CPn Mask */ - -/* SCB Cache Level ID Register Definitions */ -#define SCB_CLIDR_LOUU_Pos 27U /*!< SCB CLIDR: LoUU Position */ -#define SCB_CLIDR_LOUU_Msk (7UL << SCB_CLIDR_LOUU_Pos) /*!< SCB CLIDR: LoUU Mask */ - -#define SCB_CLIDR_LOC_Pos 24U /*!< SCB CLIDR: LoC Position */ -#define SCB_CLIDR_LOC_Msk (7UL << SCB_CLIDR_LOC_Pos) /*!< SCB CLIDR: LoC Mask */ - -/* SCB Cache Type Register Definitions */ -#define SCB_CTR_FORMAT_Pos 29U /*!< SCB CTR: Format Position */ -#define SCB_CTR_FORMAT_Msk (7UL << SCB_CTR_FORMAT_Pos) /*!< SCB CTR: Format Mask */ - -#define SCB_CTR_CWG_Pos 24U /*!< SCB CTR: CWG Position */ -#define SCB_CTR_CWG_Msk (0xFUL << SCB_CTR_CWG_Pos) /*!< SCB CTR: CWG Mask */ - -#define SCB_CTR_ERG_Pos 20U /*!< SCB CTR: ERG Position */ -#define SCB_CTR_ERG_Msk (0xFUL << SCB_CTR_ERG_Pos) /*!< SCB CTR: ERG Mask */ - -#define SCB_CTR_DMINLINE_Pos 16U /*!< SCB CTR: DminLine Position */ -#define SCB_CTR_DMINLINE_Msk (0xFUL << SCB_CTR_DMINLINE_Pos) /*!< SCB CTR: DminLine Mask */ - -#define SCB_CTR_IMINLINE_Pos 0U /*!< SCB CTR: ImInLine Position */ -#define SCB_CTR_IMINLINE_Msk (0xFUL /*<< SCB_CTR_IMINLINE_Pos*/) /*!< SCB CTR: ImInLine Mask */ - -/* SCB Cache Size ID Register Definitions */ -#define SCB_CCSIDR_WT_Pos 31U /*!< SCB CCSIDR: WT Position */ -#define SCB_CCSIDR_WT_Msk (1UL << SCB_CCSIDR_WT_Pos) /*!< SCB CCSIDR: WT Mask */ - -#define SCB_CCSIDR_WB_Pos 30U /*!< SCB CCSIDR: WB Position */ -#define SCB_CCSIDR_WB_Msk (1UL << SCB_CCSIDR_WB_Pos) /*!< SCB CCSIDR: WB Mask */ - -#define SCB_CCSIDR_RA_Pos 29U /*!< SCB CCSIDR: RA Position */ -#define SCB_CCSIDR_RA_Msk (1UL << SCB_CCSIDR_RA_Pos) /*!< SCB CCSIDR: RA Mask */ - -#define SCB_CCSIDR_WA_Pos 28U /*!< SCB CCSIDR: WA Position */ -#define SCB_CCSIDR_WA_Msk (1UL << SCB_CCSIDR_WA_Pos) /*!< SCB CCSIDR: WA Mask */ - -#define SCB_CCSIDR_NUMSETS_Pos 13U /*!< SCB CCSIDR: NumSets Position */ -#define SCB_CCSIDR_NUMSETS_Msk (0x7FFFUL << SCB_CCSIDR_NUMSETS_Pos) /*!< SCB CCSIDR: NumSets Mask */ - -#define SCB_CCSIDR_ASSOCIATIVITY_Pos 3U /*!< SCB CCSIDR: Associativity Position */ -#define SCB_CCSIDR_ASSOCIATIVITY_Msk (0x3FFUL << SCB_CCSIDR_ASSOCIATIVITY_Pos) /*!< SCB CCSIDR: Associativity Mask */ - -#define SCB_CCSIDR_LINESIZE_Pos 0U /*!< SCB CCSIDR: LineSize Position */ -#define SCB_CCSIDR_LINESIZE_Msk (7UL /*<< SCB_CCSIDR_LINESIZE_Pos*/) /*!< SCB CCSIDR: LineSize Mask */ - -/* SCB Cache Size Selection Register Definitions */ -#define SCB_CSSELR_LEVEL_Pos 1U /*!< SCB CSSELR: Level Position */ -#define SCB_CSSELR_LEVEL_Msk (7UL << SCB_CSSELR_LEVEL_Pos) /*!< SCB CSSELR: Level Mask */ - -#define SCB_CSSELR_IND_Pos 0U /*!< SCB CSSELR: InD Position */ -#define SCB_CSSELR_IND_Msk (1UL /*<< SCB_CSSELR_IND_Pos*/) /*!< SCB CSSELR: InD Mask */ - -/* SCB Software Triggered Interrupt Register Definitions */ -#define SCB_STIR_INTID_Pos 0U /*!< SCB STIR: INTID Position */ -#define SCB_STIR_INTID_Msk (0x1FFUL /*<< SCB_STIR_INTID_Pos*/) /*!< SCB STIR: INTID Mask */ - -/* SCB D-Cache Invalidate by Set-way Register Definitions */ -#define SCB_DCISW_WAY_Pos 30U /*!< SCB DCISW: Way Position */ -#define SCB_DCISW_WAY_Msk (3UL << SCB_DCISW_WAY_Pos) /*!< SCB DCISW: Way Mask */ - -#define SCB_DCISW_SET_Pos 5U /*!< SCB DCISW: Set Position */ -#define SCB_DCISW_SET_Msk (0x1FFUL << SCB_DCISW_SET_Pos) /*!< SCB DCISW: Set Mask */ - -/* SCB D-Cache Clean by Set-way Register Definitions */ -#define SCB_DCCSW_WAY_Pos 30U /*!< SCB DCCSW: Way Position */ -#define SCB_DCCSW_WAY_Msk (3UL << SCB_DCCSW_WAY_Pos) /*!< SCB DCCSW: Way Mask */ - -#define SCB_DCCSW_SET_Pos 5U /*!< SCB DCCSW: Set Position */ -#define SCB_DCCSW_SET_Msk (0x1FFUL << SCB_DCCSW_SET_Pos) /*!< SCB DCCSW: Set Mask */ - -/* SCB D-Cache Clean and Invalidate by Set-way Register Definitions */ -#define SCB_DCCISW_WAY_Pos 30U /*!< SCB DCCISW: Way Position */ -#define SCB_DCCISW_WAY_Msk (3UL << SCB_DCCISW_WAY_Pos) /*!< SCB DCCISW: Way Mask */ - -#define SCB_DCCISW_SET_Pos 5U /*!< SCB DCCISW: Set Position */ -#define SCB_DCCISW_SET_Msk (0x1FFUL << SCB_DCCISW_SET_Pos) /*!< SCB DCCISW: Set Mask */ - -/* Instruction Tightly-Coupled Memory Control Register Definitions */ -#define SCB_ITCMCR_SZ_Pos 3U /*!< SCB ITCMCR: SZ Position */ -#define SCB_ITCMCR_SZ_Msk (0xFUL << SCB_ITCMCR_SZ_Pos) /*!< SCB ITCMCR: SZ Mask */ - -#define SCB_ITCMCR_RETEN_Pos 2U /*!< SCB ITCMCR: RETEN Position */ -#define SCB_ITCMCR_RETEN_Msk (1UL << SCB_ITCMCR_RETEN_Pos) /*!< SCB ITCMCR: RETEN Mask */ - -#define SCB_ITCMCR_RMW_Pos 1U /*!< SCB ITCMCR: RMW Position */ -#define SCB_ITCMCR_RMW_Msk (1UL << SCB_ITCMCR_RMW_Pos) /*!< SCB ITCMCR: RMW Mask */ - -#define SCB_ITCMCR_EN_Pos 0U /*!< SCB ITCMCR: EN Position */ -#define SCB_ITCMCR_EN_Msk (1UL /*<< SCB_ITCMCR_EN_Pos*/) /*!< SCB ITCMCR: EN Mask */ - -/* Data Tightly-Coupled Memory Control Register Definitions */ -#define SCB_DTCMCR_SZ_Pos 3U /*!< SCB DTCMCR: SZ Position */ -#define SCB_DTCMCR_SZ_Msk (0xFUL << SCB_DTCMCR_SZ_Pos) /*!< SCB DTCMCR: SZ Mask */ - -#define SCB_DTCMCR_RETEN_Pos 2U /*!< SCB DTCMCR: RETEN Position */ -#define SCB_DTCMCR_RETEN_Msk (1UL << SCB_DTCMCR_RETEN_Pos) /*!< SCB DTCMCR: RETEN Mask */ - -#define SCB_DTCMCR_RMW_Pos 1U /*!< SCB DTCMCR: RMW Position */ -#define SCB_DTCMCR_RMW_Msk (1UL << SCB_DTCMCR_RMW_Pos) /*!< SCB DTCMCR: RMW Mask */ - -#define SCB_DTCMCR_EN_Pos 0U /*!< SCB DTCMCR: EN Position */ -#define SCB_DTCMCR_EN_Msk (1UL /*<< SCB_DTCMCR_EN_Pos*/) /*!< SCB DTCMCR: EN Mask */ - -/* AHBP Control Register Definitions */ -#define SCB_AHBPCR_SZ_Pos 1U /*!< SCB AHBPCR: SZ Position */ -#define SCB_AHBPCR_SZ_Msk (7UL << SCB_AHBPCR_SZ_Pos) /*!< SCB AHBPCR: SZ Mask */ - -#define SCB_AHBPCR_EN_Pos 0U /*!< SCB AHBPCR: EN Position */ -#define SCB_AHBPCR_EN_Msk (1UL /*<< SCB_AHBPCR_EN_Pos*/) /*!< SCB AHBPCR: EN Mask */ - -/* L1 Cache Control Register Definitions */ -#define SCB_CACR_FORCEWT_Pos 2U /*!< SCB CACR: FORCEWT Position */ -#define SCB_CACR_FORCEWT_Msk (1UL << SCB_CACR_FORCEWT_Pos) /*!< SCB CACR: FORCEWT Mask */ - -#define SCB_CACR_ECCEN_Pos 1U /*!< SCB CACR: ECCEN Position */ -#define SCB_CACR_ECCEN_Msk (1UL << SCB_CACR_ECCEN_Pos) /*!< SCB CACR: ECCEN Mask */ - -#define SCB_CACR_SIWT_Pos 0U /*!< SCB CACR: SIWT Position */ -#define SCB_CACR_SIWT_Msk (1UL /*<< SCB_CACR_SIWT_Pos*/) /*!< SCB CACR: SIWT Mask */ - -/* AHBS Control Register Definitions */ -#define SCB_AHBSCR_INITCOUNT_Pos 11U /*!< SCB AHBSCR: INITCOUNT Position */ -#define SCB_AHBSCR_INITCOUNT_Msk (0x1FUL << SCB_AHBPCR_INITCOUNT_Pos) /*!< SCB AHBSCR: INITCOUNT Mask */ - -#define SCB_AHBSCR_TPRI_Pos 2U /*!< SCB AHBSCR: TPRI Position */ -#define SCB_AHBSCR_TPRI_Msk (0x1FFUL << SCB_AHBPCR_TPRI_Pos) /*!< SCB AHBSCR: TPRI Mask */ - -#define SCB_AHBSCR_CTL_Pos 0U /*!< SCB AHBSCR: CTL Position*/ -#define SCB_AHBSCR_CTL_Msk (3UL /*<< SCB_AHBPCR_CTL_Pos*/) /*!< SCB AHBSCR: CTL Mask */ - -/* Auxiliary Bus Fault Status Register Definitions */ -#define SCB_ABFSR_AXIMTYPE_Pos 8U /*!< SCB ABFSR: AXIMTYPE Position*/ -#define SCB_ABFSR_AXIMTYPE_Msk (3UL << SCB_ABFSR_AXIMTYPE_Pos) /*!< SCB ABFSR: AXIMTYPE Mask */ - -#define SCB_ABFSR_EPPB_Pos 4U /*!< SCB ABFSR: EPPB Position*/ -#define SCB_ABFSR_EPPB_Msk (1UL << SCB_ABFSR_EPPB_Pos) /*!< SCB ABFSR: EPPB Mask */ - -#define SCB_ABFSR_AXIM_Pos 3U /*!< SCB ABFSR: AXIM Position*/ -#define SCB_ABFSR_AXIM_Msk (1UL << SCB_ABFSR_AXIM_Pos) /*!< SCB ABFSR: AXIM Mask */ - -#define SCB_ABFSR_AHBP_Pos 2U /*!< SCB ABFSR: AHBP Position*/ -#define SCB_ABFSR_AHBP_Msk (1UL << SCB_ABFSR_AHBP_Pos) /*!< SCB ABFSR: AHBP Mask */ - -#define SCB_ABFSR_DTCM_Pos 1U /*!< SCB ABFSR: DTCM Position*/ -#define SCB_ABFSR_DTCM_Msk (1UL << SCB_ABFSR_DTCM_Pos) /*!< SCB ABFSR: DTCM Mask */ - -#define SCB_ABFSR_ITCM_Pos 0U /*!< SCB ABFSR: ITCM Position*/ -#define SCB_ABFSR_ITCM_Msk (1UL /*<< SCB_ABFSR_ITCM_Pos*/) /*!< SCB ABFSR: ITCM Mask */ - -/*@} end of group CMSIS_SCB */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SCnSCB System Controls not in SCB (SCnSCB) - \brief Type definitions for the System Control and ID Register not in the SCB - @{ - */ - -/** - \brief Structure type to access the System Control and ID Register not in the SCB. - */ -typedef struct -{ - uint32_t RESERVED0[1U]; - __IM uint32_t ICTR; /*!< Offset: 0x004 (R/ ) Interrupt Controller Type Register */ - __IOM uint32_t ACTLR; /*!< Offset: 0x008 (R/W) Auxiliary Control Register */ - __IOM uint32_t CPPWR; /*!< Offset: 0x00C (R/W) Coprocessor Power Control Register */ -} SCnSCB_Type; - -/* Interrupt Controller Type Register Definitions */ -#define SCnSCB_ICTR_INTLINESNUM_Pos 0U /*!< ICTR: INTLINESNUM Position */ -#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL /*<< SCnSCB_ICTR_INTLINESNUM_Pos*/) /*!< ICTR: INTLINESNUM Mask */ - -/*@} end of group CMSIS_SCnotSCB */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SysTick System Tick Timer (SysTick) - \brief Type definitions for the System Timer Registers. - @{ - */ - -/** - \brief Structure type to access the System Timer (SysTick). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ - __IOM uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ - __IOM uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ - __IM uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ -} SysTick_Type; - -/* SysTick Control / Status Register Definitions */ -#define SysTick_CTRL_COUNTFLAG_Pos 16U /*!< SysTick CTRL: COUNTFLAG Position */ -#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ - -#define SysTick_CTRL_CLKSOURCE_Pos 2U /*!< SysTick CTRL: CLKSOURCE Position */ -#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ - -#define SysTick_CTRL_TICKINT_Pos 1U /*!< SysTick CTRL: TICKINT Position */ -#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ - -#define SysTick_CTRL_ENABLE_Pos 0U /*!< SysTick CTRL: ENABLE Position */ -#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ - -/* SysTick Reload Register Definitions */ -#define SysTick_LOAD_RELOAD_Pos 0U /*!< SysTick LOAD: RELOAD Position */ -#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ - -/* SysTick Current Register Definitions */ -#define SysTick_VAL_CURRENT_Pos 0U /*!< SysTick VAL: CURRENT Position */ -#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ - -/* SysTick Calibration Register Definitions */ -#define SysTick_CALIB_NOREF_Pos 31U /*!< SysTick CALIB: NOREF Position */ -#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ - -#define SysTick_CALIB_SKEW_Pos 30U /*!< SysTick CALIB: SKEW Position */ -#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ - -#define SysTick_CALIB_TENMS_Pos 0U /*!< SysTick CALIB: TENMS Position */ -#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ - -/*@} end of group CMSIS_SysTick */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_ITM Instrumentation Trace Macrocell (ITM) - \brief Type definitions for the Instrumentation Trace Macrocell (ITM) - @{ - */ - -/** - \brief Structure type to access the Instrumentation Trace Macrocell Register (ITM). - */ -typedef struct -{ - __OM union - { - __OM uint8_t u8; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 8-bit */ - __OM uint16_t u16; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 16-bit */ - __OM uint32_t u32; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 32-bit */ - } PORT [32U]; /*!< Offset: 0x000 ( /W) ITM Stimulus Port Registers */ - uint32_t RESERVED0[864U]; - __IOM uint32_t TER; /*!< Offset: 0xE00 (R/W) ITM Trace Enable Register */ - uint32_t RESERVED1[15U]; - __IOM uint32_t TPR; /*!< Offset: 0xE40 (R/W) ITM Trace Privilege Register */ - uint32_t RESERVED2[15U]; - __IOM uint32_t TCR; /*!< Offset: 0xE80 (R/W) ITM Trace Control Register */ - uint32_t RESERVED3[29U]; - __OM uint32_t IWR; /*!< Offset: 0xEF8 ( /W) ITM Integration Write Register */ - __IM uint32_t IRR; /*!< Offset: 0xEFC (R/ ) ITM Integration Read Register */ - __IOM uint32_t IMCR; /*!< Offset: 0xF00 (R/W) ITM Integration Mode Control Register */ - uint32_t RESERVED4[43U]; - __OM uint32_t LAR; /*!< Offset: 0xFB0 ( /W) ITM Lock Access Register */ - __IM uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) ITM Lock Status Register */ - uint32_t RESERVED5[1U]; - __IM uint32_t DEVARCH; /*!< Offset: 0xFBC (R/ ) ITM Device Architecture Register */ - uint32_t RESERVED6[4U]; - __IM uint32_t PID4; /*!< Offset: 0xFD0 (R/ ) ITM Peripheral Identification Register #4 */ - __IM uint32_t PID5; /*!< Offset: 0xFD4 (R/ ) ITM Peripheral Identification Register #5 */ - __IM uint32_t PID6; /*!< Offset: 0xFD8 (R/ ) ITM Peripheral Identification Register #6 */ - __IM uint32_t PID7; /*!< Offset: 0xFDC (R/ ) ITM Peripheral Identification Register #7 */ - __IM uint32_t PID0; /*!< Offset: 0xFE0 (R/ ) ITM Peripheral Identification Register #0 */ - __IM uint32_t PID1; /*!< Offset: 0xFE4 (R/ ) ITM Peripheral Identification Register #1 */ - __IM uint32_t PID2; /*!< Offset: 0xFE8 (R/ ) ITM Peripheral Identification Register #2 */ - __IM uint32_t PID3; /*!< Offset: 0xFEC (R/ ) ITM Peripheral Identification Register #3 */ - __IM uint32_t CID0; /*!< Offset: 0xFF0 (R/ ) ITM Component Identification Register #0 */ - __IM uint32_t CID1; /*!< Offset: 0xFF4 (R/ ) ITM Component Identification Register #1 */ - __IM uint32_t CID2; /*!< Offset: 0xFF8 (R/ ) ITM Component Identification Register #2 */ - __IM uint32_t CID3; /*!< Offset: 0xFFC (R/ ) ITM Component Identification Register #3 */ -} ITM_Type; - -/* ITM Stimulus Port Register Definitions */ -#define ITM_STIM_DISABLED_Pos 1U /*!< ITM STIM: DISABLED Position */ -#define ITM_STIM_DISABLED_Msk (0x1UL << ITM_STIM_DISABLED_Pos) /*!< ITM STIM: DISABLED Mask */ - -#define ITM_STIM_FIFOREADY_Pos 0U /*!< ITM STIM: FIFOREADY Position */ -#define ITM_STIM_FIFOREADY_Msk (0x1UL /*<< ITM_STIM_FIFOREADY_Pos*/) /*!< ITM STIM: FIFOREADY Mask */ - -/* ITM Trace Privilege Register Definitions */ -#define ITM_TPR_PRIVMASK_Pos 0U /*!< ITM TPR: PRIVMASK Position */ -#define ITM_TPR_PRIVMASK_Msk (0xFUL /*<< ITM_TPR_PRIVMASK_Pos*/) /*!< ITM TPR: PRIVMASK Mask */ - -/* ITM Trace Control Register Definitions */ -#define ITM_TCR_BUSY_Pos 23U /*!< ITM TCR: BUSY Position */ -#define ITM_TCR_BUSY_Msk (1UL << ITM_TCR_BUSY_Pos) /*!< ITM TCR: BUSY Mask */ - -#define ITM_TCR_TRACEBUSID_Pos 16U /*!< ITM TCR: ATBID Position */ -#define ITM_TCR_TRACEBUSID_Msk (0x7FUL << ITM_TCR_TRACEBUSID_Pos) /*!< ITM TCR: ATBID Mask */ - -#define ITM_TCR_GTSFREQ_Pos 10U /*!< ITM TCR: Global timestamp frequency Position */ -#define ITM_TCR_GTSFREQ_Msk (3UL << ITM_TCR_GTSFREQ_Pos) /*!< ITM TCR: Global timestamp frequency Mask */ - -#define ITM_TCR_TSPRESCALE_Pos 8U /*!< ITM TCR: TSPRESCALE Position */ -#define ITM_TCR_TSPRESCALE_Msk (3UL << ITM_TCR_TSPRESCALE_Pos) /*!< ITM TCR: TSPRESCALE Mask */ - -#define ITM_TCR_STALLENA_Pos 5U /*!< ITM TCR: STALLENA Position */ -#define ITM_TCR_STALLENA_Msk (1UL << ITM_TCR_STALLENA_Pos) /*!< ITM TCR: STALLENA Mask */ - -#define ITM_TCR_SWOENA_Pos 4U /*!< ITM TCR: SWOENA Position */ -#define ITM_TCR_SWOENA_Msk (1UL << ITM_TCR_SWOENA_Pos) /*!< ITM TCR: SWOENA Mask */ - -#define ITM_TCR_DWTENA_Pos 3U /*!< ITM TCR: DWTENA Position */ -#define ITM_TCR_DWTENA_Msk (1UL << ITM_TCR_DWTENA_Pos) /*!< ITM TCR: DWTENA Mask */ - -#define ITM_TCR_SYNCENA_Pos 2U /*!< ITM TCR: SYNCENA Position */ -#define ITM_TCR_SYNCENA_Msk (1UL << ITM_TCR_SYNCENA_Pos) /*!< ITM TCR: SYNCENA Mask */ - -#define ITM_TCR_TSENA_Pos 1U /*!< ITM TCR: TSENA Position */ -#define ITM_TCR_TSENA_Msk (1UL << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */ - -#define ITM_TCR_ITMENA_Pos 0U /*!< ITM TCR: ITM Enable bit Position */ -#define ITM_TCR_ITMENA_Msk (1UL /*<< ITM_TCR_ITMENA_Pos*/) /*!< ITM TCR: ITM Enable bit Mask */ - -/* ITM Integration Write Register Definitions */ -#define ITM_IWR_ATVALIDM_Pos 0U /*!< ITM IWR: ATVALIDM Position */ -#define ITM_IWR_ATVALIDM_Msk (1UL /*<< ITM_IWR_ATVALIDM_Pos*/) /*!< ITM IWR: ATVALIDM Mask */ - -/* ITM Integration Read Register Definitions */ -#define ITM_IRR_ATREADYM_Pos 0U /*!< ITM IRR: ATREADYM Position */ -#define ITM_IRR_ATREADYM_Msk (1UL /*<< ITM_IRR_ATREADYM_Pos*/) /*!< ITM IRR: ATREADYM Mask */ - -/* ITM Integration Mode Control Register Definitions */ -#define ITM_IMCR_INTEGRATION_Pos 0U /*!< ITM IMCR: INTEGRATION Position */ -#define ITM_IMCR_INTEGRATION_Msk (1UL /*<< ITM_IMCR_INTEGRATION_Pos*/) /*!< ITM IMCR: INTEGRATION Mask */ - -/* ITM Lock Status Register Definitions */ -#define ITM_LSR_ByteAcc_Pos 2U /*!< ITM LSR: ByteAcc Position */ -#define ITM_LSR_ByteAcc_Msk (1UL << ITM_LSR_ByteAcc_Pos) /*!< ITM LSR: ByteAcc Mask */ - -#define ITM_LSR_Access_Pos 1U /*!< ITM LSR: Access Position */ -#define ITM_LSR_Access_Msk (1UL << ITM_LSR_Access_Pos) /*!< ITM LSR: Access Mask */ - -#define ITM_LSR_Present_Pos 0U /*!< ITM LSR: Present Position */ -#define ITM_LSR_Present_Msk (1UL /*<< ITM_LSR_Present_Pos*/) /*!< ITM LSR: Present Mask */ - -/*@}*/ /* end of group CMSIS_ITM */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_DWT Data Watchpoint and Trace (DWT) - \brief Type definitions for the Data Watchpoint and Trace (DWT) - @{ - */ - -/** - \brief Structure type to access the Data Watchpoint and Trace Register (DWT). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) Control Register */ - __IOM uint32_t CYCCNT; /*!< Offset: 0x004 (R/W) Cycle Count Register */ - __IOM uint32_t CPICNT; /*!< Offset: 0x008 (R/W) CPI Count Register */ - __IOM uint32_t EXCCNT; /*!< Offset: 0x00C (R/W) Exception Overhead Count Register */ - __IOM uint32_t SLEEPCNT; /*!< Offset: 0x010 (R/W) Sleep Count Register */ - __IOM uint32_t LSUCNT; /*!< Offset: 0x014 (R/W) LSU Count Register */ - __IOM uint32_t FOLDCNT; /*!< Offset: 0x018 (R/W) Folded-instruction Count Register */ - __IM uint32_t PCSR; /*!< Offset: 0x01C (R/ ) Program Counter Sample Register */ - __IOM uint32_t COMP0; /*!< Offset: 0x020 (R/W) Comparator Register 0 */ - uint32_t RESERVED1[1U]; - __IOM uint32_t FUNCTION0; /*!< Offset: 0x028 (R/W) Function Register 0 */ - uint32_t RESERVED2[1U]; - __IOM uint32_t COMP1; /*!< Offset: 0x030 (R/W) Comparator Register 1 */ - uint32_t RESERVED3[1U]; - __IOM uint32_t FUNCTION1; /*!< Offset: 0x038 (R/W) Function Register 1 */ - uint32_t RESERVED4[1U]; - __IOM uint32_t COMP2; /*!< Offset: 0x040 (R/W) Comparator Register 2 */ - uint32_t RESERVED5[1U]; - __IOM uint32_t FUNCTION2; /*!< Offset: 0x048 (R/W) Function Register 2 */ - uint32_t RESERVED6[1U]; - __IOM uint32_t COMP3; /*!< Offset: 0x050 (R/W) Comparator Register 3 */ - uint32_t RESERVED7[1U]; - __IOM uint32_t FUNCTION3; /*!< Offset: 0x058 (R/W) Function Register 3 */ - uint32_t RESERVED8[1U]; - __IOM uint32_t COMP4; /*!< Offset: 0x060 (R/W) Comparator Register 4 */ - uint32_t RESERVED9[1U]; - __IOM uint32_t FUNCTION4; /*!< Offset: 0x068 (R/W) Function Register 4 */ - uint32_t RESERVED10[1U]; - __IOM uint32_t COMP5; /*!< Offset: 0x070 (R/W) Comparator Register 5 */ - uint32_t RESERVED11[1U]; - __IOM uint32_t FUNCTION5; /*!< Offset: 0x078 (R/W) Function Register 5 */ - uint32_t RESERVED12[1U]; - __IOM uint32_t COMP6; /*!< Offset: 0x080 (R/W) Comparator Register 6 */ - uint32_t RESERVED13[1U]; - __IOM uint32_t FUNCTION6; /*!< Offset: 0x088 (R/W) Function Register 6 */ - uint32_t RESERVED14[1U]; - __IOM uint32_t COMP7; /*!< Offset: 0x090 (R/W) Comparator Register 7 */ - uint32_t RESERVED15[1U]; - __IOM uint32_t FUNCTION7; /*!< Offset: 0x098 (R/W) Function Register 7 */ - uint32_t RESERVED16[1U]; - __IOM uint32_t COMP8; /*!< Offset: 0x0A0 (R/W) Comparator Register 8 */ - uint32_t RESERVED17[1U]; - __IOM uint32_t FUNCTION8; /*!< Offset: 0x0A8 (R/W) Function Register 8 */ - uint32_t RESERVED18[1U]; - __IOM uint32_t COMP9; /*!< Offset: 0x0B0 (R/W) Comparator Register 9 */ - uint32_t RESERVED19[1U]; - __IOM uint32_t FUNCTION9; /*!< Offset: 0x0B8 (R/W) Function Register 9 */ - uint32_t RESERVED20[1U]; - __IOM uint32_t COMP10; /*!< Offset: 0x0C0 (R/W) Comparator Register 10 */ - uint32_t RESERVED21[1U]; - __IOM uint32_t FUNCTION10; /*!< Offset: 0x0C8 (R/W) Function Register 10 */ - uint32_t RESERVED22[1U]; - __IOM uint32_t COMP11; /*!< Offset: 0x0D0 (R/W) Comparator Register 11 */ - uint32_t RESERVED23[1U]; - __IOM uint32_t FUNCTION11; /*!< Offset: 0x0D8 (R/W) Function Register 11 */ - uint32_t RESERVED24[1U]; - __IOM uint32_t COMP12; /*!< Offset: 0x0E0 (R/W) Comparator Register 12 */ - uint32_t RESERVED25[1U]; - __IOM uint32_t FUNCTION12; /*!< Offset: 0x0E8 (R/W) Function Register 12 */ - uint32_t RESERVED26[1U]; - __IOM uint32_t COMP13; /*!< Offset: 0x0F0 (R/W) Comparator Register 13 */ - uint32_t RESERVED27[1U]; - __IOM uint32_t FUNCTION13; /*!< Offset: 0x0F8 (R/W) Function Register 13 */ - uint32_t RESERVED28[1U]; - __IOM uint32_t COMP14; /*!< Offset: 0x100 (R/W) Comparator Register 14 */ - uint32_t RESERVED29[1U]; - __IOM uint32_t FUNCTION14; /*!< Offset: 0x108 (R/W) Function Register 14 */ - uint32_t RESERVED30[1U]; - __IOM uint32_t COMP15; /*!< Offset: 0x110 (R/W) Comparator Register 15 */ - uint32_t RESERVED31[1U]; - __IOM uint32_t FUNCTION15; /*!< Offset: 0x118 (R/W) Function Register 15 */ - uint32_t RESERVED32[934U]; - __IM uint32_t LSR; /*!< Offset: 0xFB4 (R ) Lock Status Register */ - uint32_t RESERVED33[1U]; - __IM uint32_t DEVARCH; /*!< Offset: 0xFBC (R/ ) Device Architecture Register */ -} DWT_Type; - -/* DWT Control Register Definitions */ -#define DWT_CTRL_NUMCOMP_Pos 28U /*!< DWT CTRL: NUMCOMP Position */ -#define DWT_CTRL_NUMCOMP_Msk (0xFUL << DWT_CTRL_NUMCOMP_Pos) /*!< DWT CTRL: NUMCOMP Mask */ - -#define DWT_CTRL_NOTRCPKT_Pos 27U /*!< DWT CTRL: NOTRCPKT Position */ -#define DWT_CTRL_NOTRCPKT_Msk (0x1UL << DWT_CTRL_NOTRCPKT_Pos) /*!< DWT CTRL: NOTRCPKT Mask */ - -#define DWT_CTRL_NOEXTTRIG_Pos 26U /*!< DWT CTRL: NOEXTTRIG Position */ -#define DWT_CTRL_NOEXTTRIG_Msk (0x1UL << DWT_CTRL_NOEXTTRIG_Pos) /*!< DWT CTRL: NOEXTTRIG Mask */ - -#define DWT_CTRL_NOCYCCNT_Pos 25U /*!< DWT CTRL: NOCYCCNT Position */ -#define DWT_CTRL_NOCYCCNT_Msk (0x1UL << DWT_CTRL_NOCYCCNT_Pos) /*!< DWT CTRL: NOCYCCNT Mask */ - -#define DWT_CTRL_NOPRFCNT_Pos 24U /*!< DWT CTRL: NOPRFCNT Position */ -#define DWT_CTRL_NOPRFCNT_Msk (0x1UL << DWT_CTRL_NOPRFCNT_Pos) /*!< DWT CTRL: NOPRFCNT Mask */ - -#define DWT_CTRL_CYCDISS_Pos 23U /*!< DWT CTRL: CYCDISS Position */ -#define DWT_CTRL_CYCDISS_Msk (0x1UL << DWT_CTRL_CYCDISS_Pos) /*!< DWT CTRL: CYCDISS Mask */ - -#define DWT_CTRL_CYCEVTENA_Pos 22U /*!< DWT CTRL: CYCEVTENA Position */ -#define DWT_CTRL_CYCEVTENA_Msk (0x1UL << DWT_CTRL_CYCEVTENA_Pos) /*!< DWT CTRL: CYCEVTENA Mask */ - -#define DWT_CTRL_FOLDEVTENA_Pos 21U /*!< DWT CTRL: FOLDEVTENA Position */ -#define DWT_CTRL_FOLDEVTENA_Msk (0x1UL << DWT_CTRL_FOLDEVTENA_Pos) /*!< DWT CTRL: FOLDEVTENA Mask */ - -#define DWT_CTRL_LSUEVTENA_Pos 20U /*!< DWT CTRL: LSUEVTENA Position */ -#define DWT_CTRL_LSUEVTENA_Msk (0x1UL << DWT_CTRL_LSUEVTENA_Pos) /*!< DWT CTRL: LSUEVTENA Mask */ - -#define DWT_CTRL_SLEEPEVTENA_Pos 19U /*!< DWT CTRL: SLEEPEVTENA Position */ -#define DWT_CTRL_SLEEPEVTENA_Msk (0x1UL << DWT_CTRL_SLEEPEVTENA_Pos) /*!< DWT CTRL: SLEEPEVTENA Mask */ - -#define DWT_CTRL_EXCEVTENA_Pos 18U /*!< DWT CTRL: EXCEVTENA Position */ -#define DWT_CTRL_EXCEVTENA_Msk (0x1UL << DWT_CTRL_EXCEVTENA_Pos) /*!< DWT CTRL: EXCEVTENA Mask */ - -#define DWT_CTRL_CPIEVTENA_Pos 17U /*!< DWT CTRL: CPIEVTENA Position */ -#define DWT_CTRL_CPIEVTENA_Msk (0x1UL << DWT_CTRL_CPIEVTENA_Pos) /*!< DWT CTRL: CPIEVTENA Mask */ - -#define DWT_CTRL_EXCTRCENA_Pos 16U /*!< DWT CTRL: EXCTRCENA Position */ -#define DWT_CTRL_EXCTRCENA_Msk (0x1UL << DWT_CTRL_EXCTRCENA_Pos) /*!< DWT CTRL: EXCTRCENA Mask */ - -#define DWT_CTRL_PCSAMPLENA_Pos 12U /*!< DWT CTRL: PCSAMPLENA Position */ -#define DWT_CTRL_PCSAMPLENA_Msk (0x1UL << DWT_CTRL_PCSAMPLENA_Pos) /*!< DWT CTRL: PCSAMPLENA Mask */ - -#define DWT_CTRL_SYNCTAP_Pos 10U /*!< DWT CTRL: SYNCTAP Position */ -#define DWT_CTRL_SYNCTAP_Msk (0x3UL << DWT_CTRL_SYNCTAP_Pos) /*!< DWT CTRL: SYNCTAP Mask */ - -#define DWT_CTRL_CYCTAP_Pos 9U /*!< DWT CTRL: CYCTAP Position */ -#define DWT_CTRL_CYCTAP_Msk (0x1UL << DWT_CTRL_CYCTAP_Pos) /*!< DWT CTRL: CYCTAP Mask */ - -#define DWT_CTRL_POSTINIT_Pos 5U /*!< DWT CTRL: POSTINIT Position */ -#define DWT_CTRL_POSTINIT_Msk (0xFUL << DWT_CTRL_POSTINIT_Pos) /*!< DWT CTRL: POSTINIT Mask */ - -#define DWT_CTRL_POSTPRESET_Pos 1U /*!< DWT CTRL: POSTPRESET Position */ -#define DWT_CTRL_POSTPRESET_Msk (0xFUL << DWT_CTRL_POSTPRESET_Pos) /*!< DWT CTRL: POSTPRESET Mask */ - -#define DWT_CTRL_CYCCNTENA_Pos 0U /*!< DWT CTRL: CYCCNTENA Position */ -#define DWT_CTRL_CYCCNTENA_Msk (0x1UL /*<< DWT_CTRL_CYCCNTENA_Pos*/) /*!< DWT CTRL: CYCCNTENA Mask */ - -/* DWT CPI Count Register Definitions */ -#define DWT_CPICNT_CPICNT_Pos 0U /*!< DWT CPICNT: CPICNT Position */ -#define DWT_CPICNT_CPICNT_Msk (0xFFUL /*<< DWT_CPICNT_CPICNT_Pos*/) /*!< DWT CPICNT: CPICNT Mask */ - -/* DWT Exception Overhead Count Register Definitions */ -#define DWT_EXCCNT_EXCCNT_Pos 0U /*!< DWT EXCCNT: EXCCNT Position */ -#define DWT_EXCCNT_EXCCNT_Msk (0xFFUL /*<< DWT_EXCCNT_EXCCNT_Pos*/) /*!< DWT EXCCNT: EXCCNT Mask */ - -/* DWT Sleep Count Register Definitions */ -#define DWT_SLEEPCNT_SLEEPCNT_Pos 0U /*!< DWT SLEEPCNT: SLEEPCNT Position */ -#define DWT_SLEEPCNT_SLEEPCNT_Msk (0xFFUL /*<< DWT_SLEEPCNT_SLEEPCNT_Pos*/) /*!< DWT SLEEPCNT: SLEEPCNT Mask */ - -/* DWT LSU Count Register Definitions */ -#define DWT_LSUCNT_LSUCNT_Pos 0U /*!< DWT LSUCNT: LSUCNT Position */ -#define DWT_LSUCNT_LSUCNT_Msk (0xFFUL /*<< DWT_LSUCNT_LSUCNT_Pos*/) /*!< DWT LSUCNT: LSUCNT Mask */ - -/* DWT Folded-instruction Count Register Definitions */ -#define DWT_FOLDCNT_FOLDCNT_Pos 0U /*!< DWT FOLDCNT: FOLDCNT Position */ -#define DWT_FOLDCNT_FOLDCNT_Msk (0xFFUL /*<< DWT_FOLDCNT_FOLDCNT_Pos*/) /*!< DWT FOLDCNT: FOLDCNT Mask */ - -/* DWT Comparator Function Register Definitions */ -#define DWT_FUNCTION_ID_Pos 27U /*!< DWT FUNCTION: ID Position */ -#define DWT_FUNCTION_ID_Msk (0x1FUL << DWT_FUNCTION_ID_Pos) /*!< DWT FUNCTION: ID Mask */ - -#define DWT_FUNCTION_MATCHED_Pos 24U /*!< DWT FUNCTION: MATCHED Position */ -#define DWT_FUNCTION_MATCHED_Msk (0x1UL << DWT_FUNCTION_MATCHED_Pos) /*!< DWT FUNCTION: MATCHED Mask */ - -#define DWT_FUNCTION_DATAVSIZE_Pos 10U /*!< DWT FUNCTION: DATAVSIZE Position */ -#define DWT_FUNCTION_DATAVSIZE_Msk (0x3UL << DWT_FUNCTION_DATAVSIZE_Pos) /*!< DWT FUNCTION: DATAVSIZE Mask */ - -#define DWT_FUNCTION_ACTION_Pos 4U /*!< DWT FUNCTION: ACTION Position */ -#define DWT_FUNCTION_ACTION_Msk (0x1UL << DWT_FUNCTION_ACTION_Pos) /*!< DWT FUNCTION: ACTION Mask */ - -#define DWT_FUNCTION_MATCH_Pos 0U /*!< DWT FUNCTION: MATCH Position */ -#define DWT_FUNCTION_MATCH_Msk (0xFUL /*<< DWT_FUNCTION_MATCH_Pos*/) /*!< DWT FUNCTION: MATCH Mask */ - -/*@}*/ /* end of group CMSIS_DWT */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_TPI Trace Port Interface (TPI) - \brief Type definitions for the Trace Port Interface (TPI) - @{ - */ - -/** - \brief Structure type to access the Trace Port Interface Register (TPI). - */ -typedef struct -{ - __IM uint32_t SSPSR; /*!< Offset: 0x000 (R/ ) Supported Parallel Port Sizes Register */ - __IOM uint32_t CSPSR; /*!< Offset: 0x004 (R/W) Current Parallel Port Sizes Register */ - uint32_t RESERVED0[2U]; - __IOM uint32_t ACPR; /*!< Offset: 0x010 (R/W) Asynchronous Clock Prescaler Register */ - uint32_t RESERVED1[55U]; - __IOM uint32_t SPPR; /*!< Offset: 0x0F0 (R/W) Selected Pin Protocol Register */ - uint32_t RESERVED2[131U]; - __IM uint32_t FFSR; /*!< Offset: 0x300 (R/ ) Formatter and Flush Status Register */ - __IOM uint32_t FFCR; /*!< Offset: 0x304 (R/W) Formatter and Flush Control Register */ - __IOM uint32_t PSCR; /*!< Offset: 0x308 (R/W) Periodic Synchronization Control Register */ - uint32_t RESERVED3[809U]; - __OM uint32_t LAR; /*!< Offset: 0xFB0 ( /W) Software Lock Access Register */ - __IM uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) Software Lock Status Register */ - uint32_t RESERVED4[4U]; - __IM uint32_t TYPE; /*!< Offset: 0xFC8 (R/ ) Device Identifier Register */ - __IM uint32_t DEVTYPE; /*!< Offset: 0xFCC (R/ ) Device Type Register */ -} TPI_Type; - -/* TPI Asynchronous Clock Prescaler Register Definitions */ -#define TPI_ACPR_SWOSCALER_Pos 0U /*!< TPI ACPR: SWOSCALER Position */ -#define TPI_ACPR_SWOSCALER_Msk (0xFFFFUL /*<< TPI_ACPR_SWOSCALER_Pos*/) /*!< TPI ACPR: SWOSCALER Mask */ - -/* TPI Selected Pin Protocol Register Definitions */ -#define TPI_SPPR_TXMODE_Pos 0U /*!< TPI SPPR: TXMODE Position */ -#define TPI_SPPR_TXMODE_Msk (0x3UL /*<< TPI_SPPR_TXMODE_Pos*/) /*!< TPI SPPR: TXMODE Mask */ - -/* TPI Formatter and Flush Status Register Definitions */ -#define TPI_FFSR_FtNonStop_Pos 3U /*!< TPI FFSR: FtNonStop Position */ -#define TPI_FFSR_FtNonStop_Msk (0x1UL << TPI_FFSR_FtNonStop_Pos) /*!< TPI FFSR: FtNonStop Mask */ - -#define TPI_FFSR_TCPresent_Pos 2U /*!< TPI FFSR: TCPresent Position */ -#define TPI_FFSR_TCPresent_Msk (0x1UL << TPI_FFSR_TCPresent_Pos) /*!< TPI FFSR: TCPresent Mask */ - -#define TPI_FFSR_FtStopped_Pos 1U /*!< TPI FFSR: FtStopped Position */ -#define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */ - -#define TPI_FFSR_FlInProg_Pos 0U /*!< TPI FFSR: FlInProg Position */ -#define TPI_FFSR_FlInProg_Msk (0x1UL /*<< TPI_FFSR_FlInProg_Pos*/) /*!< TPI FFSR: FlInProg Mask */ - -/* TPI Formatter and Flush Control Register Definitions */ -#define TPI_FFCR_TrigIn_Pos 8U /*!< TPI FFCR: TrigIn Position */ -#define TPI_FFCR_TrigIn_Msk (0x1UL << TPI_FFCR_TrigIn_Pos) /*!< TPI FFCR: TrigIn Mask */ - -#define TPI_FFCR_FOnMan_Pos 6U /*!< TPI FFCR: FOnMan Position */ -#define TPI_FFCR_FOnMan_Msk (0x1UL << TPI_FFCR_FOnMan_Pos) /*!< TPI FFCR: FOnMan Mask */ - -#define TPI_FFCR_EnFCont_Pos 1U /*!< TPI FFCR: EnFCont Position */ -#define TPI_FFCR_EnFCont_Msk (0x1UL << TPI_FFCR_EnFCont_Pos) /*!< TPI FFCR: EnFCont Mask */ - -/* TPI Periodic Synchronization Control Register Definitions */ -#define TPI_PSCR_PSCount_Pos 0U /*!< TPI PSCR: PSCount Position */ -#define TPI_PSCR_PSCount_Msk (0x1FUL /*<< TPI_PSCR_PSCount_Pos*/) /*!< TPI PSCR: TPSCount Mask */ - -/* TPI Software Lock Status Register Definitions */ -#define TPI_LSR_nTT_Pos 1U /*!< TPI LSR: Not thirty-two bit. Position */ -#define TPI_LSR_nTT_Msk (0x1UL << TPI_LSR_nTT_Pos) /*!< TPI LSR: Not thirty-two bit. Mask */ - -#define TPI_LSR_SLK_Pos 1U /*!< TPI LSR: Software Lock status Position */ -#define TPI_LSR_SLK_Msk (0x1UL << TPI_LSR_SLK_Pos) /*!< TPI LSR: Software Lock status Mask */ - -#define TPI_LSR_SLI_Pos 0U /*!< TPI LSR: Software Lock implemented Position */ -#define TPI_LSR_SLI_Msk (0x1UL /*<< TPI_LSR_SLI_Pos*/) /*!< TPI LSR: Software Lock implemented Mask */ - -/* TPI DEVID Register Definitions */ -#define TPI_DEVID_NRZVALID_Pos 11U /*!< TPI DEVID: NRZVALID Position */ -#define TPI_DEVID_NRZVALID_Msk (0x1UL << TPI_DEVID_NRZVALID_Pos) /*!< TPI DEVID: NRZVALID Mask */ - -#define TPI_DEVID_MANCVALID_Pos 10U /*!< TPI DEVID: MANCVALID Position */ -#define TPI_DEVID_MANCVALID_Msk (0x1UL << TPI_DEVID_MANCVALID_Pos) /*!< TPI DEVID: MANCVALID Mask */ - -#define TPI_DEVID_PTINVALID_Pos 9U /*!< TPI DEVID: PTINVALID Position */ -#define TPI_DEVID_PTINVALID_Msk (0x1UL << TPI_DEVID_PTINVALID_Pos) /*!< TPI DEVID: PTINVALID Mask */ - -#define TPI_DEVID_FIFOSZ_Pos 6U /*!< TPI DEVID: FIFO depth Position */ -#define TPI_DEVID_FIFOSZ_Msk (0x7UL << TPI_DEVID_FIFOSZ_Pos) /*!< TPI DEVID: FIFO depth Mask */ - -/* TPI DEVTYPE Register Definitions */ -#define TPI_DEVTYPE_SubType_Pos 4U /*!< TPI DEVTYPE: SubType Position */ -#define TPI_DEVTYPE_SubType_Msk (0xFUL /*<< TPI_DEVTYPE_SubType_Pos*/) /*!< TPI DEVTYPE: SubType Mask */ - -#define TPI_DEVTYPE_MajorType_Pos 0U /*!< TPI DEVTYPE: MajorType Position */ -#define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */ - -/*@}*/ /* end of group CMSIS_TPI */ - - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_MPU Memory Protection Unit (MPU) - \brief Type definitions for the Memory Protection Unit (MPU) - @{ - */ - -/** - \brief Structure type to access the Memory Protection Unit (MPU). - */ -typedef struct -{ - __IM uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */ - __IOM uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */ - __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region Number Register */ - __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */ - __IOM uint32_t RLAR; /*!< Offset: 0x010 (R/W) MPU Region Limit Address Register */ - __IOM uint32_t RBAR_A1; /*!< Offset: 0x014 (R/W) MPU Region Base Address Register Alias 1 */ - __IOM uint32_t RLAR_A1; /*!< Offset: 0x018 (R/W) MPU Region Limit Address Register Alias 1 */ - __IOM uint32_t RBAR_A2; /*!< Offset: 0x01C (R/W) MPU Region Base Address Register Alias 2 */ - __IOM uint32_t RLAR_A2; /*!< Offset: 0x020 (R/W) MPU Region Limit Address Register Alias 2 */ - __IOM uint32_t RBAR_A3; /*!< Offset: 0x024 (R/W) MPU Region Base Address Register Alias 3 */ - __IOM uint32_t RLAR_A3; /*!< Offset: 0x028 (R/W) MPU Region Limit Address Register Alias 3 */ - uint32_t RESERVED0[1]; - union { - __IOM uint32_t MAIR[2]; - struct { - __IOM uint32_t MAIR0; /*!< Offset: 0x030 (R/W) MPU Memory Attribute Indirection Register 0 */ - __IOM uint32_t MAIR1; /*!< Offset: 0x034 (R/W) MPU Memory Attribute Indirection Register 1 */ - }; - }; -} MPU_Type; - -#define MPU_TYPE_RALIASES 4U - -/* MPU Type Register Definitions */ -#define MPU_TYPE_IREGION_Pos 16U /*!< MPU TYPE: IREGION Position */ -#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ - -#define MPU_TYPE_DREGION_Pos 8U /*!< MPU TYPE: DREGION Position */ -#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ - -#define MPU_TYPE_SEPARATE_Pos 0U /*!< MPU TYPE: SEPARATE Position */ -#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */ - -/* MPU Control Register Definitions */ -#define MPU_CTRL_PRIVDEFENA_Pos 2U /*!< MPU CTRL: PRIVDEFENA Position */ -#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ - -#define MPU_CTRL_HFNMIENA_Pos 1U /*!< MPU CTRL: HFNMIENA Position */ -#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ - -#define MPU_CTRL_ENABLE_Pos 0U /*!< MPU CTRL: ENABLE Position */ -#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */ - -/* MPU Region Number Register Definitions */ -#define MPU_RNR_REGION_Pos 0U /*!< MPU RNR: REGION Position */ -#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */ - -/* MPU Region Base Address Register Definitions */ -#define MPU_RBAR_BASE_Pos 5U /*!< MPU RBAR: BASE Position */ -#define MPU_RBAR_BASE_Msk (0x7FFFFFFUL << MPU_RBAR_BASE_Pos) /*!< MPU RBAR: BASE Mask */ - -#define MPU_RBAR_SH_Pos 3U /*!< MPU RBAR: SH Position */ -#define MPU_RBAR_SH_Msk (0x3UL << MPU_RBAR_SH_Pos) /*!< MPU RBAR: SH Mask */ - -#define MPU_RBAR_AP_Pos 1U /*!< MPU RBAR: AP Position */ -#define MPU_RBAR_AP_Msk (0x3UL << MPU_RBAR_AP_Pos) /*!< MPU RBAR: AP Mask */ - -#define MPU_RBAR_XN_Pos 0U /*!< MPU RBAR: XN Position */ -#define MPU_RBAR_XN_Msk (01UL /*<< MPU_RBAR_XN_Pos*/) /*!< MPU RBAR: XN Mask */ - -/* MPU Region Limit Address Register Definitions */ -#define MPU_RLAR_LIMIT_Pos 5U /*!< MPU RLAR: LIMIT Position */ -#define MPU_RLAR_LIMIT_Msk (0x7FFFFFFUL << MPU_RLAR_LIMIT_Pos) /*!< MPU RLAR: LIMIT Mask */ - -#define MPU_RLAR_AttrIndx_Pos 1U /*!< MPU RLAR: AttrIndx Position */ -#define MPU_RLAR_AttrIndx_Msk (0x7UL << MPU_RLAR_AttrIndx_Pos) /*!< MPU RLAR: AttrIndx Mask */ - -#define MPU_RLAR_EN_Pos 0U /*!< MPU RLAR: Region enable bit Position */ -#define MPU_RLAR_EN_Msk (1UL /*<< MPU_RLAR_EN_Pos*/) /*!< MPU RLAR: Region enable bit Disable Mask */ - -/* MPU Memory Attribute Indirection Register 0 Definitions */ -#define MPU_MAIR0_Attr3_Pos 24U /*!< MPU MAIR0: Attr3 Position */ -#define MPU_MAIR0_Attr3_Msk (0xFFUL << MPU_MAIR0_Attr3_Pos) /*!< MPU MAIR0: Attr3 Mask */ - -#define MPU_MAIR0_Attr2_Pos 16U /*!< MPU MAIR0: Attr2 Position */ -#define MPU_MAIR0_Attr2_Msk (0xFFUL << MPU_MAIR0_Attr2_Pos) /*!< MPU MAIR0: Attr2 Mask */ - -#define MPU_MAIR0_Attr1_Pos 8U /*!< MPU MAIR0: Attr1 Position */ -#define MPU_MAIR0_Attr1_Msk (0xFFUL << MPU_MAIR0_Attr1_Pos) /*!< MPU MAIR0: Attr1 Mask */ - -#define MPU_MAIR0_Attr0_Pos 0U /*!< MPU MAIR0: Attr0 Position */ -#define MPU_MAIR0_Attr0_Msk (0xFFUL /*<< MPU_MAIR0_Attr0_Pos*/) /*!< MPU MAIR0: Attr0 Mask */ - -/* MPU Memory Attribute Indirection Register 1 Definitions */ -#define MPU_MAIR1_Attr7_Pos 24U /*!< MPU MAIR1: Attr7 Position */ -#define MPU_MAIR1_Attr7_Msk (0xFFUL << MPU_MAIR1_Attr7_Pos) /*!< MPU MAIR1: Attr7 Mask */ - -#define MPU_MAIR1_Attr6_Pos 16U /*!< MPU MAIR1: Attr6 Position */ -#define MPU_MAIR1_Attr6_Msk (0xFFUL << MPU_MAIR1_Attr6_Pos) /*!< MPU MAIR1: Attr6 Mask */ - -#define MPU_MAIR1_Attr5_Pos 8U /*!< MPU MAIR1: Attr5 Position */ -#define MPU_MAIR1_Attr5_Msk (0xFFUL << MPU_MAIR1_Attr5_Pos) /*!< MPU MAIR1: Attr5 Mask */ - -#define MPU_MAIR1_Attr4_Pos 0U /*!< MPU MAIR1: Attr4 Position */ -#define MPU_MAIR1_Attr4_Msk (0xFFUL /*<< MPU_MAIR1_Attr4_Pos*/) /*!< MPU MAIR1: Attr4 Mask */ - -/*@} end of group CMSIS_MPU */ -#endif - - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SAU Security Attribution Unit (SAU) - \brief Type definitions for the Security Attribution Unit (SAU) - @{ - */ - -/** - \brief Structure type to access the Security Attribution Unit (SAU). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SAU Control Register */ - __IM uint32_t TYPE; /*!< Offset: 0x004 (R/ ) SAU Type Register */ -#if defined (__SAUREGION_PRESENT) && (__SAUREGION_PRESENT == 1U) - __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) SAU Region Number Register */ - __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) SAU Region Base Address Register */ - __IOM uint32_t RLAR; /*!< Offset: 0x010 (R/W) SAU Region Limit Address Register */ -#else - uint32_t RESERVED0[3]; -#endif - __IOM uint32_t SFSR; /*!< Offset: 0x014 (R/W) Secure Fault Status Register */ - __IOM uint32_t SFAR; /*!< Offset: 0x018 (R/W) Secure Fault Address Register */ -} SAU_Type; - -/* SAU Control Register Definitions */ -#define SAU_CTRL_ALLNS_Pos 1U /*!< SAU CTRL: ALLNS Position */ -#define SAU_CTRL_ALLNS_Msk (1UL << SAU_CTRL_ALLNS_Pos) /*!< SAU CTRL: ALLNS Mask */ - -#define SAU_CTRL_ENABLE_Pos 0U /*!< SAU CTRL: ENABLE Position */ -#define SAU_CTRL_ENABLE_Msk (1UL /*<< SAU_CTRL_ENABLE_Pos*/) /*!< SAU CTRL: ENABLE Mask */ - -/* SAU Type Register Definitions */ -#define SAU_TYPE_SREGION_Pos 0U /*!< SAU TYPE: SREGION Position */ -#define SAU_TYPE_SREGION_Msk (0xFFUL /*<< SAU_TYPE_SREGION_Pos*/) /*!< SAU TYPE: SREGION Mask */ - -#if defined (__SAUREGION_PRESENT) && (__SAUREGION_PRESENT == 1U) -/* SAU Region Number Register Definitions */ -#define SAU_RNR_REGION_Pos 0U /*!< SAU RNR: REGION Position */ -#define SAU_RNR_REGION_Msk (0xFFUL /*<< SAU_RNR_REGION_Pos*/) /*!< SAU RNR: REGION Mask */ - -/* SAU Region Base Address Register Definitions */ -#define SAU_RBAR_BADDR_Pos 5U /*!< SAU RBAR: BADDR Position */ -#define SAU_RBAR_BADDR_Msk (0x7FFFFFFUL << SAU_RBAR_BADDR_Pos) /*!< SAU RBAR: BADDR Mask */ - -/* SAU Region Limit Address Register Definitions */ -#define SAU_RLAR_LADDR_Pos 5U /*!< SAU RLAR: LADDR Position */ -#define SAU_RLAR_LADDR_Msk (0x7FFFFFFUL << SAU_RLAR_LADDR_Pos) /*!< SAU RLAR: LADDR Mask */ - -#define SAU_RLAR_NSC_Pos 1U /*!< SAU RLAR: NSC Position */ -#define SAU_RLAR_NSC_Msk (1UL << SAU_RLAR_NSC_Pos) /*!< SAU RLAR: NSC Mask */ - -#define SAU_RLAR_ENABLE_Pos 0U /*!< SAU RLAR: ENABLE Position */ -#define SAU_RLAR_ENABLE_Msk (1UL /*<< SAU_RLAR_ENABLE_Pos*/) /*!< SAU RLAR: ENABLE Mask */ - -#endif /* defined (__SAUREGION_PRESENT) && (__SAUREGION_PRESENT == 1U) */ - -/* Secure Fault Status Register Definitions */ -#define SAU_SFSR_LSERR_Pos 7U /*!< SAU SFSR: LSERR Position */ -#define SAU_SFSR_LSERR_Msk (1UL << SAU_SFSR_LSERR_Pos) /*!< SAU SFSR: LSERR Mask */ - -#define SAU_SFSR_SFARVALID_Pos 6U /*!< SAU SFSR: SFARVALID Position */ -#define SAU_SFSR_SFARVALID_Msk (1UL << SAU_SFSR_SFARVALID_Pos) /*!< SAU SFSR: SFARVALID Mask */ - -#define SAU_SFSR_LSPERR_Pos 5U /*!< SAU SFSR: LSPERR Position */ -#define SAU_SFSR_LSPERR_Msk (1UL << SAU_SFSR_LSPERR_Pos) /*!< SAU SFSR: LSPERR Mask */ - -#define SAU_SFSR_INVTRAN_Pos 4U /*!< SAU SFSR: INVTRAN Position */ -#define SAU_SFSR_INVTRAN_Msk (1UL << SAU_SFSR_INVTRAN_Pos) /*!< SAU SFSR: INVTRAN Mask */ - -#define SAU_SFSR_AUVIOL_Pos 3U /*!< SAU SFSR: AUVIOL Position */ -#define SAU_SFSR_AUVIOL_Msk (1UL << SAU_SFSR_AUVIOL_Pos) /*!< SAU SFSR: AUVIOL Mask */ - -#define SAU_SFSR_INVER_Pos 2U /*!< SAU SFSR: INVER Position */ -#define SAU_SFSR_INVER_Msk (1UL << SAU_SFSR_INVER_Pos) /*!< SAU SFSR: INVER Mask */ - -#define SAU_SFSR_INVIS_Pos 1U /*!< SAU SFSR: INVIS Position */ -#define SAU_SFSR_INVIS_Msk (1UL << SAU_SFSR_INVIS_Pos) /*!< SAU SFSR: INVIS Mask */ - -#define SAU_SFSR_INVEP_Pos 0U /*!< SAU SFSR: INVEP Position */ -#define SAU_SFSR_INVEP_Msk (1UL /*<< SAU_SFSR_INVEP_Pos*/) /*!< SAU SFSR: INVEP Mask */ - -/*@} end of group CMSIS_SAU */ -#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_FPU Floating Point Unit (FPU) - \brief Type definitions for the Floating Point Unit (FPU) - @{ - */ - -/** - \brief Structure type to access the Floating Point Unit (FPU). - */ -typedef struct -{ - uint32_t RESERVED0[1U]; - __IOM uint32_t FPCCR; /*!< Offset: 0x004 (R/W) Floating-Point Context Control Register */ - __IOM uint32_t FPCAR; /*!< Offset: 0x008 (R/W) Floating-Point Context Address Register */ - __IOM uint32_t FPDSCR; /*!< Offset: 0x00C (R/W) Floating-Point Default Status Control Register */ - __IM uint32_t MVFR0; /*!< Offset: 0x010 (R/ ) Media and FP Feature Register 0 */ - __IM uint32_t MVFR1; /*!< Offset: 0x014 (R/ ) Media and FP Feature Register 1 */ -} FPU_Type; - -/* Floating-Point Context Control Register Definitions */ -#define FPU_FPCCR_ASPEN_Pos 31U /*!< FPCCR: ASPEN bit Position */ -#define FPU_FPCCR_ASPEN_Msk (1UL << FPU_FPCCR_ASPEN_Pos) /*!< FPCCR: ASPEN bit Mask */ - -#define FPU_FPCCR_LSPEN_Pos 30U /*!< FPCCR: LSPEN Position */ -#define FPU_FPCCR_LSPEN_Msk (1UL << FPU_FPCCR_LSPEN_Pos) /*!< FPCCR: LSPEN bit Mask */ - -#define FPU_FPCCR_LSPENS_Pos 29U /*!< FPCCR: LSPENS Position */ -#define FPU_FPCCR_LSPENS_Msk (1UL << FPU_FPCCR_LSPENS_Pos) /*!< FPCCR: LSPENS bit Mask */ - -#define FPU_FPCCR_CLRONRET_Pos 28U /*!< FPCCR: CLRONRET Position */ -#define FPU_FPCCR_CLRONRET_Msk (1UL << FPU_FPCCR_CLRONRET_Pos) /*!< FPCCR: CLRONRET bit Mask */ - -#define FPU_FPCCR_CLRONRETS_Pos 27U /*!< FPCCR: CLRONRETS Position */ -#define FPU_FPCCR_CLRONRETS_Msk (1UL << FPU_FPCCR_CLRONRETS_Pos) /*!< FPCCR: CLRONRETS bit Mask */ - -#define FPU_FPCCR_TS_Pos 26U /*!< FPCCR: TS Position */ -#define FPU_FPCCR_TS_Msk (1UL << FPU_FPCCR_TS_Pos) /*!< FPCCR: TS bit Mask */ - -#define FPU_FPCCR_UFRDY_Pos 10U /*!< FPCCR: UFRDY Position */ -#define FPU_FPCCR_UFRDY_Msk (1UL << FPU_FPCCR_UFRDY_Pos) /*!< FPCCR: UFRDY bit Mask */ - -#define FPU_FPCCR_SPLIMVIOL_Pos 9U /*!< FPCCR: SPLIMVIOL Position */ -#define FPU_FPCCR_SPLIMVIOL_Msk (1UL << FPU_FPCCR_SPLIMVIOL_Pos) /*!< FPCCR: SPLIMVIOL bit Mask */ - -#define FPU_FPCCR_MONRDY_Pos 8U /*!< FPCCR: MONRDY Position */ -#define FPU_FPCCR_MONRDY_Msk (1UL << FPU_FPCCR_MONRDY_Pos) /*!< FPCCR: MONRDY bit Mask */ - -#define FPU_FPCCR_SFRDY_Pos 7U /*!< FPCCR: SFRDY Position */ -#define FPU_FPCCR_SFRDY_Msk (1UL << FPU_FPCCR_SFRDY_Pos) /*!< FPCCR: SFRDY bit Mask */ - -#define FPU_FPCCR_BFRDY_Pos 6U /*!< FPCCR: BFRDY Position */ -#define FPU_FPCCR_BFRDY_Msk (1UL << FPU_FPCCR_BFRDY_Pos) /*!< FPCCR: BFRDY bit Mask */ - -#define FPU_FPCCR_MMRDY_Pos 5U /*!< FPCCR: MMRDY Position */ -#define FPU_FPCCR_MMRDY_Msk (1UL << FPU_FPCCR_MMRDY_Pos) /*!< FPCCR: MMRDY bit Mask */ - -#define FPU_FPCCR_HFRDY_Pos 4U /*!< FPCCR: HFRDY Position */ -#define FPU_FPCCR_HFRDY_Msk (1UL << FPU_FPCCR_HFRDY_Pos) /*!< FPCCR: HFRDY bit Mask */ - -#define FPU_FPCCR_THREAD_Pos 3U /*!< FPCCR: processor mode bit Position */ -#define FPU_FPCCR_THREAD_Msk (1UL << FPU_FPCCR_THREAD_Pos) /*!< FPCCR: processor mode active bit Mask */ - -#define FPU_FPCCR_S_Pos 2U /*!< FPCCR: Security status of the FP context bit Position */ -#define FPU_FPCCR_S_Msk (1UL << FPU_FPCCR_S_Pos) /*!< FPCCR: Security status of the FP context bit Mask */ - -#define FPU_FPCCR_USER_Pos 1U /*!< FPCCR: privilege level bit Position */ -#define FPU_FPCCR_USER_Msk (1UL << FPU_FPCCR_USER_Pos) /*!< FPCCR: privilege level bit Mask */ - -#define FPU_FPCCR_LSPACT_Pos 0U /*!< FPCCR: Lazy state preservation active bit Position */ -#define FPU_FPCCR_LSPACT_Msk (1UL /*<< FPU_FPCCR_LSPACT_Pos*/) /*!< FPCCR: Lazy state preservation active bit Mask */ - -/* Floating-Point Context Address Register Definitions */ -#define FPU_FPCAR_ADDRESS_Pos 3U /*!< FPCAR: ADDRESS bit Position */ -#define FPU_FPCAR_ADDRESS_Msk (0x1FFFFFFFUL << FPU_FPCAR_ADDRESS_Pos) /*!< FPCAR: ADDRESS bit Mask */ - -/* Floating-Point Default Status Control Register Definitions */ -#define FPU_FPDSCR_AHP_Pos 26U /*!< FPDSCR: AHP bit Position */ -#define FPU_FPDSCR_AHP_Msk (1UL << FPU_FPDSCR_AHP_Pos) /*!< FPDSCR: AHP bit Mask */ - -#define FPU_FPDSCR_DN_Pos 25U /*!< FPDSCR: DN bit Position */ -#define FPU_FPDSCR_DN_Msk (1UL << FPU_FPDSCR_DN_Pos) /*!< FPDSCR: DN bit Mask */ - -#define FPU_FPDSCR_FZ_Pos 24U /*!< FPDSCR: FZ bit Position */ -#define FPU_FPDSCR_FZ_Msk (1UL << FPU_FPDSCR_FZ_Pos) /*!< FPDSCR: FZ bit Mask */ - -#define FPU_FPDSCR_RMode_Pos 22U /*!< FPDSCR: RMode bit Position */ -#define FPU_FPDSCR_RMode_Msk (3UL << FPU_FPDSCR_RMode_Pos) /*!< FPDSCR: RMode bit Mask */ - -/* Media and FP Feature Register 0 Definitions */ -#define FPU_MVFR0_FP_rounding_modes_Pos 28U /*!< MVFR0: FP rounding modes bits Position */ -#define FPU_MVFR0_FP_rounding_modes_Msk (0xFUL << FPU_MVFR0_FP_rounding_modes_Pos) /*!< MVFR0: FP rounding modes bits Mask */ - -#define FPU_MVFR0_Short_vectors_Pos 24U /*!< MVFR0: Short vectors bits Position */ -#define FPU_MVFR0_Short_vectors_Msk (0xFUL << FPU_MVFR0_Short_vectors_Pos) /*!< MVFR0: Short vectors bits Mask */ - -#define FPU_MVFR0_Square_root_Pos 20U /*!< MVFR0: Square root bits Position */ -#define FPU_MVFR0_Square_root_Msk (0xFUL << FPU_MVFR0_Square_root_Pos) /*!< MVFR0: Square root bits Mask */ - -#define FPU_MVFR0_Divide_Pos 16U /*!< MVFR0: Divide bits Position */ -#define FPU_MVFR0_Divide_Msk (0xFUL << FPU_MVFR0_Divide_Pos) /*!< MVFR0: Divide bits Mask */ - -#define FPU_MVFR0_FP_excep_trapping_Pos 12U /*!< MVFR0: FP exception trapping bits Position */ -#define FPU_MVFR0_FP_excep_trapping_Msk (0xFUL << FPU_MVFR0_FP_excep_trapping_Pos) /*!< MVFR0: FP exception trapping bits Mask */ - -#define FPU_MVFR0_Double_precision_Pos 8U /*!< MVFR0: Double-precision bits Position */ -#define FPU_MVFR0_Double_precision_Msk (0xFUL << FPU_MVFR0_Double_precision_Pos) /*!< MVFR0: Double-precision bits Mask */ - -#define FPU_MVFR0_Single_precision_Pos 4U /*!< MVFR0: Single-precision bits Position */ -#define FPU_MVFR0_Single_precision_Msk (0xFUL << FPU_MVFR0_Single_precision_Pos) /*!< MVFR0: Single-precision bits Mask */ - -#define FPU_MVFR0_A_SIMD_registers_Pos 0U /*!< MVFR0: A_SIMD registers bits Position */ -#define FPU_MVFR0_A_SIMD_registers_Msk (0xFUL /*<< FPU_MVFR0_A_SIMD_registers_Pos*/) /*!< MVFR0: A_SIMD registers bits Mask */ - -/* Media and FP Feature Register 1 Definitions */ -#define FPU_MVFR1_FP_fused_MAC_Pos 28U /*!< MVFR1: FP fused MAC bits Position */ -#define FPU_MVFR1_FP_fused_MAC_Msk (0xFUL << FPU_MVFR1_FP_fused_MAC_Pos) /*!< MVFR1: FP fused MAC bits Mask */ - -#define FPU_MVFR1_FP_HPFP_Pos 24U /*!< MVFR1: FP HPFP bits Position */ -#define FPU_MVFR1_FP_HPFP_Msk (0xFUL << FPU_MVFR1_FP_HPFP_Pos) /*!< MVFR1: FP HPFP bits Mask */ - -#define FPU_MVFR1_D_NaN_mode_Pos 4U /*!< MVFR1: D_NaN mode bits Position */ -#define FPU_MVFR1_D_NaN_mode_Msk (0xFUL << FPU_MVFR1_D_NaN_mode_Pos) /*!< MVFR1: D_NaN mode bits Mask */ - -#define FPU_MVFR1_FtZ_mode_Pos 0U /*!< MVFR1: FtZ mode bits Position */ -#define FPU_MVFR1_FtZ_mode_Msk (0xFUL /*<< FPU_MVFR1_FtZ_mode_Pos*/) /*!< MVFR1: FtZ mode bits Mask */ - -/*@} end of group CMSIS_FPU */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug) - \brief Type definitions for the Core Debug Registers - @{ - */ - -/** - \brief Structure type to access the Core Debug Register (CoreDebug). - */ -typedef struct -{ - __IOM uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */ - __OM uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */ - __IOM uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */ - __IOM uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */ - uint32_t RESERVED4[1U]; - __IOM uint32_t DAUTHCTRL; /*!< Offset: 0x014 (R/W) Debug Authentication Control Register */ - __IOM uint32_t DSCSR; /*!< Offset: 0x018 (R/W) Debug Security Control and Status Register */ -} CoreDebug_Type; - -/* Debug Halting Control and Status Register Definitions */ -#define CoreDebug_DHCSR_DBGKEY_Pos 16U /*!< CoreDebug DHCSR: DBGKEY Position */ -#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */ - -#define CoreDebug_DHCSR_S_RESTART_ST_Pos 26U /*!< CoreDebug DHCSR: S_RESTART_ST Position */ -#define CoreDebug_DHCSR_S_RESTART_ST_Msk (1UL << CoreDebug_DHCSR_S_RESTART_ST_Pos) /*!< CoreDebug DHCSR: S_RESTART_ST Mask */ - -#define CoreDebug_DHCSR_S_RESET_ST_Pos 25U /*!< CoreDebug DHCSR: S_RESET_ST Position */ -#define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */ - -#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24U /*!< CoreDebug DHCSR: S_RETIRE_ST Position */ -#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */ - -#define CoreDebug_DHCSR_S_LOCKUP_Pos 19U /*!< CoreDebug DHCSR: S_LOCKUP Position */ -#define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */ - -#define CoreDebug_DHCSR_S_SLEEP_Pos 18U /*!< CoreDebug DHCSR: S_SLEEP Position */ -#define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */ - -#define CoreDebug_DHCSR_S_HALT_Pos 17U /*!< CoreDebug DHCSR: S_HALT Position */ -#define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */ - -#define CoreDebug_DHCSR_S_REGRDY_Pos 16U /*!< CoreDebug DHCSR: S_REGRDY Position */ -#define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */ - -#define CoreDebug_DHCSR_C_SNAPSTALL_Pos 5U /*!< CoreDebug DHCSR: C_SNAPSTALL Position */ -#define CoreDebug_DHCSR_C_SNAPSTALL_Msk (1UL << CoreDebug_DHCSR_C_SNAPSTALL_Pos) /*!< CoreDebug DHCSR: C_SNAPSTALL Mask */ - -#define CoreDebug_DHCSR_C_MASKINTS_Pos 3U /*!< CoreDebug DHCSR: C_MASKINTS Position */ -#define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */ - -#define CoreDebug_DHCSR_C_STEP_Pos 2U /*!< CoreDebug DHCSR: C_STEP Position */ -#define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */ - -#define CoreDebug_DHCSR_C_HALT_Pos 1U /*!< CoreDebug DHCSR: C_HALT Position */ -#define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */ - -#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0U /*!< CoreDebug DHCSR: C_DEBUGEN Position */ -#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL /*<< CoreDebug_DHCSR_C_DEBUGEN_Pos*/) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ - -/* Debug Core Register Selector Register Definitions */ -#define CoreDebug_DCRSR_REGWnR_Pos 16U /*!< CoreDebug DCRSR: REGWnR Position */ -#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */ - -#define CoreDebug_DCRSR_REGSEL_Pos 0U /*!< CoreDebug DCRSR: REGSEL Position */ -#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL /*<< CoreDebug_DCRSR_REGSEL_Pos*/) /*!< CoreDebug DCRSR: REGSEL Mask */ - -/* Debug Exception and Monitor Control Register Definitions */ -#define CoreDebug_DEMCR_TRCENA_Pos 24U /*!< CoreDebug DEMCR: TRCENA Position */ -#define CoreDebug_DEMCR_TRCENA_Msk (1UL << CoreDebug_DEMCR_TRCENA_Pos) /*!< CoreDebug DEMCR: TRCENA Mask */ - -#define CoreDebug_DEMCR_MON_REQ_Pos 19U /*!< CoreDebug DEMCR: MON_REQ Position */ -#define CoreDebug_DEMCR_MON_REQ_Msk (1UL << CoreDebug_DEMCR_MON_REQ_Pos) /*!< CoreDebug DEMCR: MON_REQ Mask */ - -#define CoreDebug_DEMCR_MON_STEP_Pos 18U /*!< CoreDebug DEMCR: MON_STEP Position */ -#define CoreDebug_DEMCR_MON_STEP_Msk (1UL << CoreDebug_DEMCR_MON_STEP_Pos) /*!< CoreDebug DEMCR: MON_STEP Mask */ - -#define CoreDebug_DEMCR_MON_PEND_Pos 17U /*!< CoreDebug DEMCR: MON_PEND Position */ -#define CoreDebug_DEMCR_MON_PEND_Msk (1UL << CoreDebug_DEMCR_MON_PEND_Pos) /*!< CoreDebug DEMCR: MON_PEND Mask */ - -#define CoreDebug_DEMCR_MON_EN_Pos 16U /*!< CoreDebug DEMCR: MON_EN Position */ -#define CoreDebug_DEMCR_MON_EN_Msk (1UL << CoreDebug_DEMCR_MON_EN_Pos) /*!< CoreDebug DEMCR: MON_EN Mask */ - -#define CoreDebug_DEMCR_VC_HARDERR_Pos 10U /*!< CoreDebug DEMCR: VC_HARDERR Position */ -#define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */ - -#define CoreDebug_DEMCR_VC_INTERR_Pos 9U /*!< CoreDebug DEMCR: VC_INTERR Position */ -#define CoreDebug_DEMCR_VC_INTERR_Msk (1UL << CoreDebug_DEMCR_VC_INTERR_Pos) /*!< CoreDebug DEMCR: VC_INTERR Mask */ - -#define CoreDebug_DEMCR_VC_BUSERR_Pos 8U /*!< CoreDebug DEMCR: VC_BUSERR Position */ -#define CoreDebug_DEMCR_VC_BUSERR_Msk (1UL << CoreDebug_DEMCR_VC_BUSERR_Pos) /*!< CoreDebug DEMCR: VC_BUSERR Mask */ - -#define CoreDebug_DEMCR_VC_STATERR_Pos 7U /*!< CoreDebug DEMCR: VC_STATERR Position */ -#define CoreDebug_DEMCR_VC_STATERR_Msk (1UL << CoreDebug_DEMCR_VC_STATERR_Pos) /*!< CoreDebug DEMCR: VC_STATERR Mask */ - -#define CoreDebug_DEMCR_VC_CHKERR_Pos 6U /*!< CoreDebug DEMCR: VC_CHKERR Position */ -#define CoreDebug_DEMCR_VC_CHKERR_Msk (1UL << CoreDebug_DEMCR_VC_CHKERR_Pos) /*!< CoreDebug DEMCR: VC_CHKERR Mask */ - -#define CoreDebug_DEMCR_VC_NOCPERR_Pos 5U /*!< CoreDebug DEMCR: VC_NOCPERR Position */ -#define CoreDebug_DEMCR_VC_NOCPERR_Msk (1UL << CoreDebug_DEMCR_VC_NOCPERR_Pos) /*!< CoreDebug DEMCR: VC_NOCPERR Mask */ - -#define CoreDebug_DEMCR_VC_MMERR_Pos 4U /*!< CoreDebug DEMCR: VC_MMERR Position */ -#define CoreDebug_DEMCR_VC_MMERR_Msk (1UL << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */ - -#define CoreDebug_DEMCR_VC_CORERESET_Pos 0U /*!< CoreDebug DEMCR: VC_CORERESET Position */ -#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL /*<< CoreDebug_DEMCR_VC_CORERESET_Pos*/) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ - -/* Debug Authentication Control Register Definitions */ -#define CoreDebug_DAUTHCTRL_INTSPNIDEN_Pos 3U /*!< CoreDebug DAUTHCTRL: INTSPNIDEN, Position */ -#define CoreDebug_DAUTHCTRL_INTSPNIDEN_Msk (1UL << CoreDebug_DAUTHCTRL_INTSPNIDEN_Pos) /*!< CoreDebug DAUTHCTRL: INTSPNIDEN, Mask */ - -#define CoreDebug_DAUTHCTRL_SPNIDENSEL_Pos 2U /*!< CoreDebug DAUTHCTRL: SPNIDENSEL Position */ -#define CoreDebug_DAUTHCTRL_SPNIDENSEL_Msk (1UL << CoreDebug_DAUTHCTRL_SPNIDENSEL_Pos) /*!< CoreDebug DAUTHCTRL: SPNIDENSEL Mask */ - -#define CoreDebug_DAUTHCTRL_INTSPIDEN_Pos 1U /*!< CoreDebug DAUTHCTRL: INTSPIDEN Position */ -#define CoreDebug_DAUTHCTRL_INTSPIDEN_Msk (1UL << CoreDebug_DAUTHCTRL_INTSPIDEN_Pos) /*!< CoreDebug DAUTHCTRL: INTSPIDEN Mask */ - -#define CoreDebug_DAUTHCTRL_SPIDENSEL_Pos 0U /*!< CoreDebug DAUTHCTRL: SPIDENSEL Position */ -#define CoreDebug_DAUTHCTRL_SPIDENSEL_Msk (1UL /*<< CoreDebug_DAUTHCTRL_SPIDENSEL_Pos*/) /*!< CoreDebug DAUTHCTRL: SPIDENSEL Mask */ - -/* Debug Security Control and Status Register Definitions */ -#define CoreDebug_DSCSR_CDS_Pos 16U /*!< CoreDebug DSCSR: CDS Position */ -#define CoreDebug_DSCSR_CDS_Msk (1UL << CoreDebug_DSCSR_CDS_Pos) /*!< CoreDebug DSCSR: CDS Mask */ - -#define CoreDebug_DSCSR_SBRSEL_Pos 1U /*!< CoreDebug DSCSR: SBRSEL Position */ -#define CoreDebug_DSCSR_SBRSEL_Msk (1UL << CoreDebug_DSCSR_SBRSEL_Pos) /*!< CoreDebug DSCSR: SBRSEL Mask */ - -#define CoreDebug_DSCSR_SBRSELEN_Pos 0U /*!< CoreDebug DSCSR: SBRSELEN Position */ -#define CoreDebug_DSCSR_SBRSELEN_Msk (1UL /*<< CoreDebug_DSCSR_SBRSELEN_Pos*/) /*!< CoreDebug DSCSR: SBRSELEN Mask */ - -/*@} end of group CMSIS_CoreDebug */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_bitfield Core register bit field macros - \brief Macros for use with bit field definitions (xxx_Pos, xxx_Msk). - @{ - */ - -/** - \brief Mask and shift a bit field value for use in a register bit range. - \param[in] field Name of the register bit field. - \param[in] value Value of the bit field. This parameter is interpreted as an uint32_t type. - \return Masked and shifted value. -*/ -#define _VAL2FLD(field, value) (((uint32_t)(value) << field ## _Pos) & field ## _Msk) - -/** - \brief Mask and shift a register value to extract a bit filed value. - \param[in] field Name of the register bit field. - \param[in] value Value of register. This parameter is interpreted as an uint32_t type. - \return Masked and shifted bit field value. -*/ -#define _FLD2VAL(field, value) (((uint32_t)(value) & field ## _Msk) >> field ## _Pos) - -/*@} end of group CMSIS_core_bitfield */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_base Core Definitions - \brief Definitions for base addresses, unions, and structures. - @{ - */ - -/* Memory mapping of Core Hardware */ - #define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ - #define ITM_BASE (0xE0000000UL) /*!< ITM Base Address */ - #define DWT_BASE (0xE0001000UL) /*!< DWT Base Address */ - #define TPI_BASE (0xE0040000UL) /*!< TPI Base Address */ - #define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug Base Address */ - #define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ - #define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ - #define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ - - #define SCnSCB ((SCnSCB_Type *) SCS_BASE ) /*!< System control Register not in SCB */ - #define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ - #define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ - #define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ - #define ITM ((ITM_Type *) ITM_BASE ) /*!< ITM configuration struct */ - #define DWT ((DWT_Type *) DWT_BASE ) /*!< DWT configuration struct */ - #define TPI ((TPI_Type *) TPI_BASE ) /*!< TPI configuration struct */ - #define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE ) /*!< Core Debug configuration struct */ - - #if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */ - #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */ - #endif - - #if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) - #define SAU_BASE (SCS_BASE + 0x0DD0UL) /*!< Security Attribution Unit */ - #define SAU ((SAU_Type *) SAU_BASE ) /*!< Security Attribution Unit */ - #endif - - #define FPU_BASE (SCS_BASE + 0x0F30UL) /*!< Floating Point Unit */ - #define FPU ((FPU_Type *) FPU_BASE ) /*!< Floating Point Unit */ - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) - #define SCS_BASE_NS (0xE002E000UL) /*!< System Control Space Base Address (non-secure address space) */ - #define CoreDebug_BASE_NS (0xE002EDF0UL) /*!< Core Debug Base Address (non-secure address space) */ - #define SysTick_BASE_NS (SCS_BASE_NS + 0x0010UL) /*!< SysTick Base Address (non-secure address space) */ - #define NVIC_BASE_NS (SCS_BASE_NS + 0x0100UL) /*!< NVIC Base Address (non-secure address space) */ - #define SCB_BASE_NS (SCS_BASE_NS + 0x0D00UL) /*!< System Control Block Base Address (non-secure address space) */ - - #define SCnSCB_NS ((SCnSCB_Type *) SCS_BASE_NS ) /*!< System control Register not in SCB(non-secure address space) */ - #define SCB_NS ((SCB_Type *) SCB_BASE_NS ) /*!< SCB configuration struct (non-secure address space) */ - #define SysTick_NS ((SysTick_Type *) SysTick_BASE_NS ) /*!< SysTick configuration struct (non-secure address space) */ - #define NVIC_NS ((NVIC_Type *) NVIC_BASE_NS ) /*!< NVIC configuration struct (non-secure address space) */ - #define CoreDebug_NS ((CoreDebug_Type *) CoreDebug_BASE_NS) /*!< Core Debug configuration struct (non-secure address space) */ - - #if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - #define MPU_BASE_NS (SCS_BASE_NS + 0x0D90UL) /*!< Memory Protection Unit (non-secure address space) */ - #define MPU_NS ((MPU_Type *) MPU_BASE_NS ) /*!< Memory Protection Unit (non-secure address space) */ - #endif - - #define FPU_BASE_NS (SCS_BASE_NS + 0x0F30UL) /*!< Floating Point Unit (non-secure address space) */ - #define FPU_NS ((FPU_Type *) FPU_BASE_NS ) /*!< Floating Point Unit (non-secure address space) */ - -#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ -/*@} */ - - - -/******************************************************************************* - * Hardware Abstraction Layer - Core Function Interface contains: - - Core NVIC Functions - - Core SysTick Functions - - Core Debug Functions - - Core Register Access Functions - ******************************************************************************/ -/** - \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference -*/ - - - -/* ########################## NVIC functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_NVICFunctions NVIC Functions - \brief Functions that manage interrupts and exceptions via the NVIC. - @{ - */ - -#ifdef CMSIS_NVIC_VIRTUAL - #ifndef CMSIS_NVIC_VIRTUAL_HEADER_FILE - #define CMSIS_NVIC_VIRTUAL_HEADER_FILE "cmsis_nvic_virtual.h" - #endif - #include CMSIS_NVIC_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetPriorityGrouping __NVIC_SetPriorityGrouping - #define NVIC_GetPriorityGrouping __NVIC_GetPriorityGrouping - #define NVIC_EnableIRQ __NVIC_EnableIRQ - #define NVIC_GetEnableIRQ __NVIC_GetEnableIRQ - #define NVIC_DisableIRQ __NVIC_DisableIRQ - #define NVIC_GetPendingIRQ __NVIC_GetPendingIRQ - #define NVIC_SetPendingIRQ __NVIC_SetPendingIRQ - #define NVIC_ClearPendingIRQ __NVIC_ClearPendingIRQ - #define NVIC_GetActive __NVIC_GetActive - #define NVIC_SetPriority __NVIC_SetPriority - #define NVIC_GetPriority __NVIC_GetPriority - #define NVIC_SystemReset __NVIC_SystemReset -#endif /* CMSIS_NVIC_VIRTUAL */ - -#ifdef CMSIS_VECTAB_VIRTUAL - #ifndef CMSIS_VECTAB_VIRTUAL_HEADER_FILE - #define CMSIS_VECTAB_VIRTUAL_HEADER_FILE "cmsis_vectab_virtual.h" - #endif - #include CMSIS_VECTAB_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetVector __NVIC_SetVector - #define NVIC_GetVector __NVIC_GetVector -#endif /* (CMSIS_VECTAB_VIRTUAL) */ - -#define NVIC_USER_IRQ_OFFSET 16 - - -/* Special LR values for Secure/Non-Secure call handling and exception handling */ - -/* Function Return Payload (from ARMv8-M Architecture Reference Manual) LR value on entry from Secure BLXNS */ -#define FNC_RETURN (0xFEFFFFFFUL) /* bit [0] ignored when processing a branch */ - -/* The following EXC_RETURN mask values are used to evaluate the LR on exception entry */ -#define EXC_RETURN_PREFIX (0xFF000000UL) /* bits [31:24] set to indicate an EXC_RETURN value */ -#define EXC_RETURN_S (0x00000040UL) /* bit [6] stack used to push registers: 0=Non-secure 1=Secure */ -#define EXC_RETURN_DCRS (0x00000020UL) /* bit [5] stacking rules for called registers: 0=skipped 1=saved */ -#define EXC_RETURN_FTYPE (0x00000010UL) /* bit [4] allocate stack for floating-point context: 0=done 1=skipped */ -#define EXC_RETURN_MODE (0x00000008UL) /* bit [3] processor mode for return: 0=Handler mode 1=Thread mode */ -#define EXC_RETURN_SPSEL (0x00000002UL) /* bit [1] stack pointer used to restore context: 0=MSP 1=PSP */ -#define EXC_RETURN_ES (0x00000001UL) /* bit [0] security state exception was taken to: 0=Non-secure 1=Secure */ - -/* Integrity Signature (from ARMv8-M Architecture Reference Manual) for exception context stacking */ -#if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) /* Value for processors with floating-point extension: */ -#define EXC_INTEGRITY_SIGNATURE (0xFEFA125AUL) /* bit [0] SFTC must match LR bit[4] EXC_RETURN_FTYPE */ -#else -#define EXC_INTEGRITY_SIGNATURE (0xFEFA125BUL) /* Value for processors without floating-point extension */ -#endif - - -/** - \brief Set Priority Grouping - \details Sets the priority grouping field using the required unlock sequence. - The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field. - Only values from 0..7 are used. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Priority grouping field. - */ -__STATIC_INLINE void __NVIC_SetPriorityGrouping(uint32_t PriorityGroup) -{ - uint32_t reg_value; - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - - reg_value = SCB->AIRCR; /* read old register configuration */ - reg_value &= ~((uint32_t)(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk)); /* clear bits to change */ - reg_value = (reg_value | - ((uint32_t)0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - (PriorityGroupTmp << 8U) ); /* Insert write key and priorty group */ - SCB->AIRCR = reg_value; -} - - -/** - \brief Get Priority Grouping - \details Reads the priority grouping field from the NVIC Interrupt Controller. - \return Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field). - */ -__STATIC_INLINE uint32_t __NVIC_GetPriorityGrouping(void) -{ - return ((uint32_t)((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos)); -} - - -/** - \brief Enable Interrupt - \details Enables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_EnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Interrupt Enable status - \details Returns a device specific interrupt enable status from the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt is not enabled. - \return 1 Interrupt is enabled. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetEnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Disable Interrupt - \details Disables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_DisableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - __DSB(); - __ISB(); - } -} - - -/** - \brief Get Pending Interrupt - \details Reads the NVIC pending register and returns the pending bit for the specified device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not pending. - \return 1 Interrupt status is pending. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Pending Interrupt - \details Sets the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_SetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Clear Pending Interrupt - \details Clears the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_ClearPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Active Interrupt - \details Reads the active register in the NVIC and returns the active bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not active. - \return 1 Interrupt status is active. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetActive(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) -/** - \brief Get Interrupt Target State - \details Reads the interrupt target field in the NVIC and returns the interrupt target bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 if interrupt is assigned to Secure - \return 1 if interrupt is assigned to Non Secure - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t NVIC_GetTargetState(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Interrupt Target State - \details Sets the interrupt target field in the NVIC and returns the interrupt target bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 if interrupt is assigned to Secure - 1 if interrupt is assigned to Non Secure - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t NVIC_SetTargetState(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] |= ((uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL))); - return((uint32_t)(((NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Clear Interrupt Target State - \details Clears the interrupt target field in the NVIC and returns the interrupt target bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 if interrupt is assigned to Secure - 1 if interrupt is assigned to Non Secure - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t NVIC_ClearTargetState(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] &= ~((uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL))); - return((uint32_t)(((NVIC->ITNS[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} -#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ - - -/** - \brief Set Interrupt Priority - \details Sets the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \param [in] priority Priority to set. - \note The priority cannot be set for every processor exception. - */ -__STATIC_INLINE void __NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->IPR[((uint32_t)IRQn)] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); - } - else - { - SCB->SHPR[(((uint32_t)IRQn) & 0xFUL)-4UL] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); - } -} - - -/** - \brief Get Interrupt Priority - \details Reads the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Interrupt Priority. - Value is aligned automatically to the implemented priority bits of the microcontroller. - */ -__STATIC_INLINE uint32_t __NVIC_GetPriority(IRQn_Type IRQn) -{ - - if ((int32_t)(IRQn) >= 0) - { - return(((uint32_t)NVIC->IPR[((uint32_t)IRQn)] >> (8U - __NVIC_PRIO_BITS))); - } - else - { - return(((uint32_t)SCB->SHPR[(((uint32_t)IRQn) & 0xFUL)-4UL] >> (8U - __NVIC_PRIO_BITS))); - } -} - - -/** - \brief Encode Priority - \details Encodes the priority for an interrupt with the given priority group, - preemptive priority value, and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Used priority group. - \param [in] PreemptPriority Preemptive priority value (starting from 0). - \param [in] SubPriority Subpriority value (starting from 0). - \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority(). - */ -__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - return ( - ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | - ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) - ); -} - - -/** - \brief Decode Priority - \details Decodes an interrupt priority value with a given priority group to - preemptive priority value and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. - \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority(). - \param [in] PriorityGroup Used priority group. - \param [out] pPreemptPriority Preemptive priority value (starting from 0). - \param [out] pSubPriority Subpriority value (starting from 0). - */ -__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* const pPreemptPriority, uint32_t* const pSubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL); - *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL); -} - - -/** - \brief Set Interrupt Vector - \details Sets an interrupt vector in SRAM based interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - VTOR must been relocated to SRAM before. - \param [in] IRQn Interrupt number - \param [in] vector Address of interrupt handler function - */ -__STATIC_INLINE void __NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) -{ - uint32_t *vectors = (uint32_t *)SCB->VTOR; - vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET] = vector; -} - - -/** - \brief Get Interrupt Vector - \details Reads an interrupt vector from interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Address of interrupt handler function - */ -__STATIC_INLINE uint32_t __NVIC_GetVector(IRQn_Type IRQn) -{ - uint32_t *vectors = (uint32_t *)SCB->VTOR; - return vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET]; -} - - -/** - \brief System Reset - \details Initiates a system reset request to reset the MCU. - */ -__NO_RETURN __STATIC_INLINE void __NVIC_SystemReset(void) -{ - __DSB(); /* Ensure all outstanding memory accesses included - buffered write are completed before reset */ - SCB->AIRCR = (uint32_t)((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) | - SCB_AIRCR_SYSRESETREQ_Msk ); /* Keep priority group unchanged */ - __DSB(); /* Ensure completion of memory access */ - - for(;;) /* wait until reset */ - { - __NOP(); - } -} - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) -/** - \brief Set Priority Grouping (non-secure) - \details Sets the non-secure priority grouping field when in secure state using the required unlock sequence. - The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field. - Only values from 0..7 are used. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Priority grouping field. - */ -__STATIC_INLINE void TZ_NVIC_SetPriorityGrouping_NS(uint32_t PriorityGroup) -{ - uint32_t reg_value; - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - - reg_value = SCB_NS->AIRCR; /* read old register configuration */ - reg_value &= ~((uint32_t)(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk)); /* clear bits to change */ - reg_value = (reg_value | - ((uint32_t)0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - (PriorityGroupTmp << 8U) ); /* Insert write key and priorty group */ - SCB_NS->AIRCR = reg_value; -} - - -/** - \brief Get Priority Grouping (non-secure) - \details Reads the priority grouping field from the non-secure NVIC when in secure state. - \return Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field). - */ -__STATIC_INLINE uint32_t TZ_NVIC_GetPriorityGrouping_NS(void) -{ - return ((uint32_t)((SCB_NS->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos)); -} - - -/** - \brief Enable Interrupt (non-secure) - \details Enables a device specific interrupt in the non-secure NVIC interrupt controller when in secure state. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void TZ_NVIC_EnableIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC_NS->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Interrupt Enable status (non-secure) - \details Returns a device specific interrupt enable status from the non-secure NVIC interrupt controller when in secure state. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt is not enabled. - \return 1 Interrupt is enabled. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t TZ_NVIC_GetEnableIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC_NS->ISER[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Disable Interrupt (non-secure) - \details Disables a device specific interrupt in the non-secure NVIC interrupt controller when in secure state. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void TZ_NVIC_DisableIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC_NS->ICER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Pending Interrupt (non-secure) - \details Reads the NVIC pending register in the non-secure NVIC when in secure state and returns the pending bit for the specified device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not pending. - \return 1 Interrupt status is pending. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t TZ_NVIC_GetPendingIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC_NS->ISPR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Pending Interrupt (non-secure) - \details Sets the pending bit of a device specific interrupt in the non-secure NVIC pending register when in secure state. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void TZ_NVIC_SetPendingIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC_NS->ISPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Clear Pending Interrupt (non-secure) - \details Clears the pending bit of a device specific interrupt in the non-secure NVIC pending register when in secure state. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void TZ_NVIC_ClearPendingIRQ_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC_NS->ICPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Active Interrupt (non-secure) - \details Reads the active register in non-secure NVIC when in secure state and returns the active bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not active. - \return 1 Interrupt status is active. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t TZ_NVIC_GetActive_NS(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC_NS->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Interrupt Priority (non-secure) - \details Sets the priority of a non-secure device specific interrupt or a non-secure processor exception when in secure state. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \param [in] priority Priority to set. - \note The priority cannot be set for every non-secure processor exception. - */ -__STATIC_INLINE void TZ_NVIC_SetPriority_NS(IRQn_Type IRQn, uint32_t priority) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC_NS->IPR[((uint32_t)IRQn)] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); - } - else - { - SCB_NS->SHPR[(((uint32_t)IRQn) & 0xFUL)-4UL] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); - } -} - - -/** - \brief Get Interrupt Priority (non-secure) - \details Reads the priority of a non-secure device specific interrupt or a non-secure processor exception when in secure state. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Interrupt Priority. Value is aligned automatically to the implemented priority bits of the microcontroller. - */ -__STATIC_INLINE uint32_t TZ_NVIC_GetPriority_NS(IRQn_Type IRQn) -{ - - if ((int32_t)(IRQn) >= 0) - { - return(((uint32_t)NVIC_NS->IPR[((uint32_t)IRQn)] >> (8U - __NVIC_PRIO_BITS))); - } - else - { - return(((uint32_t)SCB_NS->SHPR[(((uint32_t)IRQn) & 0xFUL)-4UL] >> (8U - __NVIC_PRIO_BITS))); - } -} -#endif /* defined (__ARM_FEATURE_CMSE) &&(__ARM_FEATURE_CMSE == 3U) */ - -/*@} end of CMSIS_Core_NVICFunctions */ - -/* ########################## MPU functions #################################### */ - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - -#include "mpu_armv8.h" - -#endif - -/* ########################## FPU functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_FpuFunctions FPU Functions - \brief Function that provides FPU type. - @{ - */ - -/** - \brief get FPU type - \details returns the FPU type - \returns - - \b 0: No FPU - - \b 1: Single precision FPU - - \b 2: Double + Single precision FPU - */ -__STATIC_INLINE uint32_t SCB_GetFPUType(void) -{ - uint32_t mvfr0; - - mvfr0 = FPU->MVFR0; - if ((mvfr0 & (FPU_MVFR0_Single_precision_Msk | FPU_MVFR0_Double_precision_Msk)) == 0x220U) - { - return 2U; /* Double + Single precision FPU */ - } - else if ((mvfr0 & (FPU_MVFR0_Single_precision_Msk | FPU_MVFR0_Double_precision_Msk)) == 0x020U) - { - return 1U; /* Single precision FPU */ - } - else - { - return 0U; /* No FPU */ - } -} - - -/*@} end of CMSIS_Core_FpuFunctions */ - - - -/* ########################## SAU functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_SAUFunctions SAU Functions - \brief Functions that configure the SAU. - @{ - */ - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) - -/** - \brief Enable SAU - \details Enables the Security Attribution Unit (SAU). - */ -__STATIC_INLINE void TZ_SAU_Enable(void) -{ - SAU->CTRL |= (SAU_CTRL_ENABLE_Msk); -} - - - -/** - \brief Disable SAU - \details Disables the Security Attribution Unit (SAU). - */ -__STATIC_INLINE void TZ_SAU_Disable(void) -{ - SAU->CTRL &= ~(SAU_CTRL_ENABLE_Msk); -} - -#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ - -/*@} end of CMSIS_Core_SAUFunctions */ - - - - -/* ################################## SysTick function ############################################ */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_SysTickFunctions SysTick Functions - \brief Functions that configure the System. - @{ - */ - -#if defined (__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U) - -/** - \brief System Tick Configuration - \details Initializes the System Timer and its interrupt, and starts the System Tick Timer. - Counter is in free running mode to generate periodic interrupts. - \param [in] ticks Number of ticks between two interrupts. - \return 0 Function succeeded. - \return 1 Function failed. - \note When the variable __Vendor_SysTickConfig is set to 1, then the - function SysTick_Config is not included. In this case, the file device.h - must contain a vendor-specific implementation of this function. - */ -__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) -{ - if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) - { - return (1UL); /* Reload value impossible */ - } - - SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ - NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ - SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ - SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | - SysTick_CTRL_TICKINT_Msk | - SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ - return (0UL); /* Function successful */ -} - -#if defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) -/** - \brief System Tick Configuration (non-secure) - \details Initializes the non-secure System Timer and its interrupt when in secure state, and starts the System Tick Timer. - Counter is in free running mode to generate periodic interrupts. - \param [in] ticks Number of ticks between two interrupts. - \return 0 Function succeeded. - \return 1 Function failed. - \note When the variable __Vendor_SysTickConfig is set to 1, then the - function TZ_SysTick_Config_NS is not included. In this case, the file device.h - must contain a vendor-specific implementation of this function. - - */ -__STATIC_INLINE uint32_t TZ_SysTick_Config_NS(uint32_t ticks) -{ - if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) - { - return (1UL); /* Reload value impossible */ - } - - SysTick_NS->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ - TZ_NVIC_SetPriority_NS (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ - SysTick_NS->VAL = 0UL; /* Load the SysTick Counter Value */ - SysTick_NS->CTRL = SysTick_CTRL_CLKSOURCE_Msk | - SysTick_CTRL_TICKINT_Msk | - SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ - return (0UL); /* Function successful */ -} -#endif /* defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3U) */ - -#endif - -/*@} end of CMSIS_Core_SysTickFunctions */ - - - -/* ##################################### Debug In/Output function ########################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_core_DebugFunctions ITM Functions - \brief Functions that access the ITM debug interface. - @{ - */ - -extern volatile int32_t ITM_RxBuffer; /*!< External variable to receive characters. */ -#define ITM_RXBUFFER_EMPTY ((int32_t)0x5AA55AA5U) /*!< Value identifying \ref ITM_RxBuffer is ready for next character. */ - - -/** - \brief ITM Send Character - \details Transmits a character via the ITM channel 0, and - \li Just returns when no debugger is connected that has booked the output. - \li Is blocking when a debugger is connected, but the previous character sent has not been transmitted. - \param [in] ch Character to transmit. - \returns Character to transmit. - */ -__STATIC_INLINE uint32_t ITM_SendChar (uint32_t ch) -{ - if (((ITM->TCR & ITM_TCR_ITMENA_Msk) != 0UL) && /* ITM enabled */ - ((ITM->TER & 1UL ) != 0UL) ) /* ITM Port #0 enabled */ - { - while (ITM->PORT[0U].u32 == 0UL) - { - __NOP(); - } - ITM->PORT[0U].u8 = (uint8_t)ch; - } - return (ch); -} - - -/** - \brief ITM Receive Character - \details Inputs a character via the external variable \ref ITM_RxBuffer. - \return Received character. - \return -1 No character pending. - */ -__STATIC_INLINE int32_t ITM_ReceiveChar (void) -{ - int32_t ch = -1; /* no character available */ - - if (ITM_RxBuffer != ITM_RXBUFFER_EMPTY) - { - ch = ITM_RxBuffer; - ITM_RxBuffer = ITM_RXBUFFER_EMPTY; /* ready for next character */ - } - - return (ch); -} - - -/** - \brief ITM Check Character - \details Checks whether a character is pending for reading in the variable \ref ITM_RxBuffer. - \return 0 No character available. - \return 1 Character available. - */ -__STATIC_INLINE int32_t ITM_CheckChar (void) -{ - - if (ITM_RxBuffer == ITM_RXBUFFER_EMPTY) - { - return (0); /* no character available */ - } - else - { - return (1); /* character available */ - } -} - -/*@} end of CMSIS_core_DebugFunctions */ - - - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_ARMV8MML_H_DEPENDANT */ - -#endif /* __CMSIS_GENERIC */ diff --git a/body/board/inc/core_cm0plus.h b/body/board/inc/core_cm0plus.h deleted file mode 100644 index 424011a..0000000 --- a/body/board/inc/core_cm0plus.h +++ /dev/null @@ -1,1083 +0,0 @@ -/**************************************************************************//** - * @file core_cm0plus.h - * @brief CMSIS Cortex-M0+ Core Peripheral Access Layer Header File - * @version V5.0.6 - * @date 28. May 2018 - ******************************************************************************/ -/* - * Copyright (c) 2009-2018 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef __CORE_CM0PLUS_H_GENERIC -#define __CORE_CM0PLUS_H_GENERIC - -#include - -#ifdef __cplusplus - extern "C" { -#endif - -/** - \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions - CMSIS violates the following MISRA-C:2004 rules: - - \li Required Rule 8.5, object/function definition in header file.
- Function definitions in header files are used to allow 'inlining'. - - \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
- Unions are used for effective representation of core registers. - - \li Advisory Rule 19.7, Function-like macro defined.
- Function-like macros are used to allow more efficient code. - */ - - -/******************************************************************************* - * CMSIS definitions - ******************************************************************************/ -/** - \ingroup Cortex-M0+ - @{ - */ - -#include "cmsis_version.h" - -/* CMSIS CM0+ definitions */ -#define __CM0PLUS_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */ -#define __CM0PLUS_CMSIS_VERSION_SUB (__CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */ -#define __CM0PLUS_CMSIS_VERSION ((__CM0PLUS_CMSIS_VERSION_MAIN << 16U) | \ - __CM0PLUS_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */ - -#define __CORTEX_M (0U) /*!< Cortex-M Core */ - -/** __FPU_USED indicates whether an FPU is used or not. - This core does not support an FPU at all -*/ -#define __FPU_USED 0U - -#if defined ( __CC_ARM ) - #if defined __TARGET_FPU_VFP - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #if defined __ARM_PCS_VFP - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __GNUC__ ) - #if defined (__VFP_FP__) && !defined(__SOFTFP__) - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __ICCARM__ ) - #if defined __ARMVFP__ - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __TI_ARM__ ) - #if defined __TI_VFP_SUPPORT__ - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __TASKING__ ) - #if defined __FPU_VFP__ - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __CSMC__ ) - #if ( __CSMC__ & 0x400U) - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#endif - -#include "cmsis_compiler.h" /* CMSIS compiler specific defines */ - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_CM0PLUS_H_GENERIC */ - -#ifndef __CMSIS_GENERIC - -#ifndef __CORE_CM0PLUS_H_DEPENDANT -#define __CORE_CM0PLUS_H_DEPENDANT - -#ifdef __cplusplus - extern "C" { -#endif - -/* check device defines and use defaults */ -#if defined __CHECK_DEVICE_DEFINES - #ifndef __CM0PLUS_REV - #define __CM0PLUS_REV 0x0000U - #warning "__CM0PLUS_REV not defined in device header file; using default!" - #endif - - #ifndef __MPU_PRESENT - #define __MPU_PRESENT 0U - #warning "__MPU_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __VTOR_PRESENT - #define __VTOR_PRESENT 0U - #warning "__VTOR_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __NVIC_PRIO_BITS - #define __NVIC_PRIO_BITS 2U - #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" - #endif - - #ifndef __Vendor_SysTickConfig - #define __Vendor_SysTickConfig 0U - #warning "__Vendor_SysTickConfig not defined in device header file; using default!" - #endif -#endif - -/* IO definitions (access restrictions to peripheral registers) */ -/** - \defgroup CMSIS_glob_defs CMSIS Global Defines - - IO Type Qualifiers are used - \li to specify the access to peripheral variables. - \li for automatic generation of peripheral register debug information. -*/ -#ifdef __cplusplus - #define __I volatile /*!< Defines 'read only' permissions */ -#else - #define __I volatile const /*!< Defines 'read only' permissions */ -#endif -#define __O volatile /*!< Defines 'write only' permissions */ -#define __IO volatile /*!< Defines 'read / write' permissions */ - -/* following defines should be used for structure members */ -#define __IM volatile const /*! Defines 'read only' structure member permissions */ -#define __OM volatile /*! Defines 'write only' structure member permissions */ -#define __IOM volatile /*! Defines 'read / write' structure member permissions */ - -/*@} end of group Cortex-M0+ */ - - - -/******************************************************************************* - * Register Abstraction - Core Register contain: - - Core Register - - Core NVIC Register - - Core SCB Register - - Core SysTick Register - - Core MPU Register - ******************************************************************************/ -/** - \defgroup CMSIS_core_register Defines and Type Definitions - \brief Type definitions and defines for Cortex-M processor based devices. -*/ - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CORE Status and Control Registers - \brief Core Register type definitions. - @{ - */ - -/** - \brief Union type to access the Application Program Status Register (APSR). - */ -typedef union -{ - struct - { - uint32_t _reserved0:28; /*!< bit: 0..27 Reserved */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} APSR_Type; - -/* APSR Register Definitions */ -#define APSR_N_Pos 31U /*!< APSR: N Position */ -#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ - -#define APSR_Z_Pos 30U /*!< APSR: Z Position */ -#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ - -#define APSR_C_Pos 29U /*!< APSR: C Position */ -#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ - -#define APSR_V_Pos 28U /*!< APSR: V Position */ -#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ - - -/** - \brief Union type to access the Interrupt Program Status Register (IPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} IPSR_Type; - -/* IPSR Register Definitions */ -#define IPSR_ISR_Pos 0U /*!< IPSR: ISR Position */ -#define IPSR_ISR_Msk (0x1FFUL /*<< IPSR_ISR_Pos*/) /*!< IPSR: ISR Mask */ - - -/** - \brief Union type to access the Special-Purpose Program Status Registers (xPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:15; /*!< bit: 9..23 Reserved */ - uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */ - uint32_t _reserved1:3; /*!< bit: 25..27 Reserved */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} xPSR_Type; - -/* xPSR Register Definitions */ -#define xPSR_N_Pos 31U /*!< xPSR: N Position */ -#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ - -#define xPSR_Z_Pos 30U /*!< xPSR: Z Position */ -#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ - -#define xPSR_C_Pos 29U /*!< xPSR: C Position */ -#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ - -#define xPSR_V_Pos 28U /*!< xPSR: V Position */ -#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ - -#define xPSR_T_Pos 24U /*!< xPSR: T Position */ -#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ - -#define xPSR_ISR_Pos 0U /*!< xPSR: ISR Position */ -#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ - - -/** - \brief Union type to access the Control Registers (CONTROL). - */ -typedef union -{ - struct - { - uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ - uint32_t SPSEL:1; /*!< bit: 1 Stack to be used */ - uint32_t _reserved1:30; /*!< bit: 2..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} CONTROL_Type; - -/* CONTROL Register Definitions */ -#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */ -#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ - -#define CONTROL_nPRIV_Pos 0U /*!< CONTROL: nPRIV Position */ -#define CONTROL_nPRIV_Msk (1UL /*<< CONTROL_nPRIV_Pos*/) /*!< CONTROL: nPRIV Mask */ - -/*@} end of group CMSIS_CORE */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC) - \brief Type definitions for the NVIC Registers - @{ - */ - -/** - \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). - */ -typedef struct -{ - __IOM uint32_t ISER[1U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ - uint32_t RESERVED0[31U]; - __IOM uint32_t ICER[1U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ - uint32_t RSERVED1[31U]; - __IOM uint32_t ISPR[1U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ - uint32_t RESERVED2[31U]; - __IOM uint32_t ICPR[1U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ - uint32_t RESERVED3[31U]; - uint32_t RESERVED4[64U]; - __IOM uint32_t IP[8U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register */ -} NVIC_Type; - -/*@} end of group CMSIS_NVIC */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SCB System Control Block (SCB) - \brief Type definitions for the System Control Block Registers - @{ - */ - -/** - \brief Structure type to access the System Control Block (SCB). - */ -typedef struct -{ - __IM uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ - __IOM uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ -#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U) - __IOM uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ -#else - uint32_t RESERVED0; -#endif - __IOM uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ - __IOM uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ - __IOM uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ - uint32_t RESERVED1; - __IOM uint32_t SHP[2U]; /*!< Offset: 0x01C (R/W) System Handlers Priority Registers. [0] is RESERVED */ - __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ -} SCB_Type; - -/* SCB CPUID Register Definitions */ -#define SCB_CPUID_IMPLEMENTER_Pos 24U /*!< SCB CPUID: IMPLEMENTER Position */ -#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ - -#define SCB_CPUID_VARIANT_Pos 20U /*!< SCB CPUID: VARIANT Position */ -#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ - -#define SCB_CPUID_ARCHITECTURE_Pos 16U /*!< SCB CPUID: ARCHITECTURE Position */ -#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ - -#define SCB_CPUID_PARTNO_Pos 4U /*!< SCB CPUID: PARTNO Position */ -#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ - -#define SCB_CPUID_REVISION_Pos 0U /*!< SCB CPUID: REVISION Position */ -#define SCB_CPUID_REVISION_Msk (0xFUL /*<< SCB_CPUID_REVISION_Pos*/) /*!< SCB CPUID: REVISION Mask */ - -/* SCB Interrupt Control State Register Definitions */ -#define SCB_ICSR_NMIPENDSET_Pos 31U /*!< SCB ICSR: NMIPENDSET Position */ -#define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */ - -#define SCB_ICSR_PENDSVSET_Pos 28U /*!< SCB ICSR: PENDSVSET Position */ -#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ - -#define SCB_ICSR_PENDSVCLR_Pos 27U /*!< SCB ICSR: PENDSVCLR Position */ -#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ - -#define SCB_ICSR_PENDSTSET_Pos 26U /*!< SCB ICSR: PENDSTSET Position */ -#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ - -#define SCB_ICSR_PENDSTCLR_Pos 25U /*!< SCB ICSR: PENDSTCLR Position */ -#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ - -#define SCB_ICSR_ISRPREEMPT_Pos 23U /*!< SCB ICSR: ISRPREEMPT Position */ -#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ - -#define SCB_ICSR_ISRPENDING_Pos 22U /*!< SCB ICSR: ISRPENDING Position */ -#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ - -#define SCB_ICSR_VECTPENDING_Pos 12U /*!< SCB ICSR: VECTPENDING Position */ -#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ - -#define SCB_ICSR_VECTACTIVE_Pos 0U /*!< SCB ICSR: VECTACTIVE Position */ -#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ - -#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U) -/* SCB Interrupt Control State Register Definitions */ -#define SCB_VTOR_TBLOFF_Pos 8U /*!< SCB VTOR: TBLOFF Position */ -#define SCB_VTOR_TBLOFF_Msk (0xFFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ -#endif - -/* SCB Application Interrupt and Reset Control Register Definitions */ -#define SCB_AIRCR_VECTKEY_Pos 16U /*!< SCB AIRCR: VECTKEY Position */ -#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ - -#define SCB_AIRCR_VECTKEYSTAT_Pos 16U /*!< SCB AIRCR: VECTKEYSTAT Position */ -#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ - -#define SCB_AIRCR_ENDIANESS_Pos 15U /*!< SCB AIRCR: ENDIANESS Position */ -#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ - -#define SCB_AIRCR_SYSRESETREQ_Pos 2U /*!< SCB AIRCR: SYSRESETREQ Position */ -#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ - -#define SCB_AIRCR_VECTCLRACTIVE_Pos 1U /*!< SCB AIRCR: VECTCLRACTIVE Position */ -#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ - -/* SCB System Control Register Definitions */ -#define SCB_SCR_SEVONPEND_Pos 4U /*!< SCB SCR: SEVONPEND Position */ -#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ - -#define SCB_SCR_SLEEPDEEP_Pos 2U /*!< SCB SCR: SLEEPDEEP Position */ -#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ - -#define SCB_SCR_SLEEPONEXIT_Pos 1U /*!< SCB SCR: SLEEPONEXIT Position */ -#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ - -/* SCB Configuration Control Register Definitions */ -#define SCB_CCR_STKALIGN_Pos 9U /*!< SCB CCR: STKALIGN Position */ -#define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */ - -#define SCB_CCR_UNALIGN_TRP_Pos 3U /*!< SCB CCR: UNALIGN_TRP Position */ -#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ - -/* SCB System Handler Control and State Register Definitions */ -#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */ -#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ - -/*@} end of group CMSIS_SCB */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SysTick System Tick Timer (SysTick) - \brief Type definitions for the System Timer Registers. - @{ - */ - -/** - \brief Structure type to access the System Timer (SysTick). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ - __IOM uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ - __IOM uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ - __IM uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ -} SysTick_Type; - -/* SysTick Control / Status Register Definitions */ -#define SysTick_CTRL_COUNTFLAG_Pos 16U /*!< SysTick CTRL: COUNTFLAG Position */ -#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ - -#define SysTick_CTRL_CLKSOURCE_Pos 2U /*!< SysTick CTRL: CLKSOURCE Position */ -#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ - -#define SysTick_CTRL_TICKINT_Pos 1U /*!< SysTick CTRL: TICKINT Position */ -#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ - -#define SysTick_CTRL_ENABLE_Pos 0U /*!< SysTick CTRL: ENABLE Position */ -#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ - -/* SysTick Reload Register Definitions */ -#define SysTick_LOAD_RELOAD_Pos 0U /*!< SysTick LOAD: RELOAD Position */ -#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ - -/* SysTick Current Register Definitions */ -#define SysTick_VAL_CURRENT_Pos 0U /*!< SysTick VAL: CURRENT Position */ -#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ - -/* SysTick Calibration Register Definitions */ -#define SysTick_CALIB_NOREF_Pos 31U /*!< SysTick CALIB: NOREF Position */ -#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ - -#define SysTick_CALIB_SKEW_Pos 30U /*!< SysTick CALIB: SKEW Position */ -#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ - -#define SysTick_CALIB_TENMS_Pos 0U /*!< SysTick CALIB: TENMS Position */ -#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ - -/*@} end of group CMSIS_SysTick */ - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_MPU Memory Protection Unit (MPU) - \brief Type definitions for the Memory Protection Unit (MPU) - @{ - */ - -/** - \brief Structure type to access the Memory Protection Unit (MPU). - */ -typedef struct -{ - __IM uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */ - __IOM uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */ - __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region RNRber Register */ - __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */ - __IOM uint32_t RASR; /*!< Offset: 0x010 (R/W) MPU Region Attribute and Size Register */ -} MPU_Type; - -#define MPU_TYPE_RALIASES 1U - -/* MPU Type Register Definitions */ -#define MPU_TYPE_IREGION_Pos 16U /*!< MPU TYPE: IREGION Position */ -#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ - -#define MPU_TYPE_DREGION_Pos 8U /*!< MPU TYPE: DREGION Position */ -#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ - -#define MPU_TYPE_SEPARATE_Pos 0U /*!< MPU TYPE: SEPARATE Position */ -#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */ - -/* MPU Control Register Definitions */ -#define MPU_CTRL_PRIVDEFENA_Pos 2U /*!< MPU CTRL: PRIVDEFENA Position */ -#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ - -#define MPU_CTRL_HFNMIENA_Pos 1U /*!< MPU CTRL: HFNMIENA Position */ -#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ - -#define MPU_CTRL_ENABLE_Pos 0U /*!< MPU CTRL: ENABLE Position */ -#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */ - -/* MPU Region Number Register Definitions */ -#define MPU_RNR_REGION_Pos 0U /*!< MPU RNR: REGION Position */ -#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */ - -/* MPU Region Base Address Register Definitions */ -#define MPU_RBAR_ADDR_Pos 8U /*!< MPU RBAR: ADDR Position */ -#define MPU_RBAR_ADDR_Msk (0xFFFFFFUL << MPU_RBAR_ADDR_Pos) /*!< MPU RBAR: ADDR Mask */ - -#define MPU_RBAR_VALID_Pos 4U /*!< MPU RBAR: VALID Position */ -#define MPU_RBAR_VALID_Msk (1UL << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */ - -#define MPU_RBAR_REGION_Pos 0U /*!< MPU RBAR: REGION Position */ -#define MPU_RBAR_REGION_Msk (0xFUL /*<< MPU_RBAR_REGION_Pos*/) /*!< MPU RBAR: REGION Mask */ - -/* MPU Region Attribute and Size Register Definitions */ -#define MPU_RASR_ATTRS_Pos 16U /*!< MPU RASR: MPU Region Attribute field Position */ -#define MPU_RASR_ATTRS_Msk (0xFFFFUL << MPU_RASR_ATTRS_Pos) /*!< MPU RASR: MPU Region Attribute field Mask */ - -#define MPU_RASR_XN_Pos 28U /*!< MPU RASR: ATTRS.XN Position */ -#define MPU_RASR_XN_Msk (1UL << MPU_RASR_XN_Pos) /*!< MPU RASR: ATTRS.XN Mask */ - -#define MPU_RASR_AP_Pos 24U /*!< MPU RASR: ATTRS.AP Position */ -#define MPU_RASR_AP_Msk (0x7UL << MPU_RASR_AP_Pos) /*!< MPU RASR: ATTRS.AP Mask */ - -#define MPU_RASR_TEX_Pos 19U /*!< MPU RASR: ATTRS.TEX Position */ -#define MPU_RASR_TEX_Msk (0x7UL << MPU_RASR_TEX_Pos) /*!< MPU RASR: ATTRS.TEX Mask */ - -#define MPU_RASR_S_Pos 18U /*!< MPU RASR: ATTRS.S Position */ -#define MPU_RASR_S_Msk (1UL << MPU_RASR_S_Pos) /*!< MPU RASR: ATTRS.S Mask */ - -#define MPU_RASR_C_Pos 17U /*!< MPU RASR: ATTRS.C Position */ -#define MPU_RASR_C_Msk (1UL << MPU_RASR_C_Pos) /*!< MPU RASR: ATTRS.C Mask */ - -#define MPU_RASR_B_Pos 16U /*!< MPU RASR: ATTRS.B Position */ -#define MPU_RASR_B_Msk (1UL << MPU_RASR_B_Pos) /*!< MPU RASR: ATTRS.B Mask */ - -#define MPU_RASR_SRD_Pos 8U /*!< MPU RASR: Sub-Region Disable Position */ -#define MPU_RASR_SRD_Msk (0xFFUL << MPU_RASR_SRD_Pos) /*!< MPU RASR: Sub-Region Disable Mask */ - -#define MPU_RASR_SIZE_Pos 1U /*!< MPU RASR: Region Size Field Position */ -#define MPU_RASR_SIZE_Msk (0x1FUL << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */ - -#define MPU_RASR_ENABLE_Pos 0U /*!< MPU RASR: Region enable bit Position */ -#define MPU_RASR_ENABLE_Msk (1UL /*<< MPU_RASR_ENABLE_Pos*/) /*!< MPU RASR: Region enable bit Disable Mask */ - -/*@} end of group CMSIS_MPU */ -#endif - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug) - \brief Cortex-M0+ Core Debug Registers (DCB registers, SHCSR, and DFSR) are only accessible over DAP and not via processor. - Therefore they are not covered by the Cortex-M0+ header file. - @{ - */ -/*@} end of group CMSIS_CoreDebug */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_bitfield Core register bit field macros - \brief Macros for use with bit field definitions (xxx_Pos, xxx_Msk). - @{ - */ - -/** - \brief Mask and shift a bit field value for use in a register bit range. - \param[in] field Name of the register bit field. - \param[in] value Value of the bit field. This parameter is interpreted as an uint32_t type. - \return Masked and shifted value. -*/ -#define _VAL2FLD(field, value) (((uint32_t)(value) << field ## _Pos) & field ## _Msk) - -/** - \brief Mask and shift a register value to extract a bit filed value. - \param[in] field Name of the register bit field. - \param[in] value Value of register. This parameter is interpreted as an uint32_t type. - \return Masked and shifted bit field value. -*/ -#define _FLD2VAL(field, value) (((uint32_t)(value) & field ## _Msk) >> field ## _Pos) - -/*@} end of group CMSIS_core_bitfield */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_base Core Definitions - \brief Definitions for base addresses, unions, and structures. - @{ - */ - -/* Memory mapping of Core Hardware */ -#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ -#define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ -#define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ -#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ - -#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ -#define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ -#define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */ - #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */ -#endif - -/*@} */ - - - -/******************************************************************************* - * Hardware Abstraction Layer - Core Function Interface contains: - - Core NVIC Functions - - Core SysTick Functions - - Core Register Access Functions - ******************************************************************************/ -/** - \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference -*/ - - - -/* ########################## NVIC functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_NVICFunctions NVIC Functions - \brief Functions that manage interrupts and exceptions via the NVIC. - @{ - */ - -#ifdef CMSIS_NVIC_VIRTUAL - #ifndef CMSIS_NVIC_VIRTUAL_HEADER_FILE - #define CMSIS_NVIC_VIRTUAL_HEADER_FILE "cmsis_nvic_virtual.h" - #endif - #include CMSIS_NVIC_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetPriorityGrouping __NVIC_SetPriorityGrouping - #define NVIC_GetPriorityGrouping __NVIC_GetPriorityGrouping - #define NVIC_EnableIRQ __NVIC_EnableIRQ - #define NVIC_GetEnableIRQ __NVIC_GetEnableIRQ - #define NVIC_DisableIRQ __NVIC_DisableIRQ - #define NVIC_GetPendingIRQ __NVIC_GetPendingIRQ - #define NVIC_SetPendingIRQ __NVIC_SetPendingIRQ - #define NVIC_ClearPendingIRQ __NVIC_ClearPendingIRQ -/*#define NVIC_GetActive __NVIC_GetActive not available for Cortex-M0+ */ - #define NVIC_SetPriority __NVIC_SetPriority - #define NVIC_GetPriority __NVIC_GetPriority - #define NVIC_SystemReset __NVIC_SystemReset -#endif /* CMSIS_NVIC_VIRTUAL */ - -#ifdef CMSIS_VECTAB_VIRTUAL - #ifndef CMSIS_VECTAB_VIRTUAL_HEADER_FILE - #define CMSIS_VECTAB_VIRTUAL_HEADER_FILE "cmsis_vectab_virtual.h" - #endif - #include CMSIS_VECTAB_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetVector __NVIC_SetVector - #define NVIC_GetVector __NVIC_GetVector -#endif /* (CMSIS_VECTAB_VIRTUAL) */ - -#define NVIC_USER_IRQ_OFFSET 16 - - -/* The following EXC_RETURN values are saved the LR on exception entry */ -#define EXC_RETURN_HANDLER (0xFFFFFFF1UL) /* return to Handler mode, uses MSP after return */ -#define EXC_RETURN_THREAD_MSP (0xFFFFFFF9UL) /* return to Thread mode, uses MSP after return */ -#define EXC_RETURN_THREAD_PSP (0xFFFFFFFDUL) /* return to Thread mode, uses PSP after return */ - - -/* Interrupt Priorities are WORD accessible only under Armv6-M */ -/* The following MACROS handle generation of the register offset and byte masks */ -#define _BIT_SHIFT(IRQn) ( ((((uint32_t)(int32_t)(IRQn)) ) & 0x03UL) * 8UL) -#define _SHP_IDX(IRQn) ( (((((uint32_t)(int32_t)(IRQn)) & 0x0FUL)-8UL) >> 2UL) ) -#define _IP_IDX(IRQn) ( (((uint32_t)(int32_t)(IRQn)) >> 2UL) ) - -#define __NVIC_SetPriorityGrouping(X) (void)(X) -#define __NVIC_GetPriorityGrouping() (0U) - -/** - \brief Enable Interrupt - \details Enables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_EnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISER[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Interrupt Enable status - \details Returns a device specific interrupt enable status from the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt is not enabled. - \return 1 Interrupt is enabled. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetEnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISER[0U] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Disable Interrupt - \details Disables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_DisableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICER[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - __DSB(); - __ISB(); - } -} - - -/** - \brief Get Pending Interrupt - \details Reads the NVIC pending register and returns the pending bit for the specified device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not pending. - \return 1 Interrupt status is pending. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISPR[0U] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Pending Interrupt - \details Sets the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_SetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISPR[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Clear Pending Interrupt - \details Clears the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_ClearPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICPR[0U] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Set Interrupt Priority - \details Sets the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \param [in] priority Priority to set. - \note The priority cannot be set for every processor exception. - */ -__STATIC_INLINE void __NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->IP[_IP_IDX(IRQn)] = ((uint32_t)(NVIC->IP[_IP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | - (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); - } - else - { - SCB->SHP[_SHP_IDX(IRQn)] = ((uint32_t)(SCB->SHP[_SHP_IDX(IRQn)] & ~(0xFFUL << _BIT_SHIFT(IRQn))) | - (((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL) << _BIT_SHIFT(IRQn))); - } -} - - -/** - \brief Get Interrupt Priority - \details Reads the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Interrupt Priority. - Value is aligned automatically to the implemented priority bits of the microcontroller. - */ -__STATIC_INLINE uint32_t __NVIC_GetPriority(IRQn_Type IRQn) -{ - - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->IP[ _IP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS))); - } - else - { - return((uint32_t)(((SCB->SHP[_SHP_IDX(IRQn)] >> _BIT_SHIFT(IRQn) ) & (uint32_t)0xFFUL) >> (8U - __NVIC_PRIO_BITS))); - } -} - - -/** - \brief Encode Priority - \details Encodes the priority for an interrupt with the given priority group, - preemptive priority value, and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Used priority group. - \param [in] PreemptPriority Preemptive priority value (starting from 0). - \param [in] SubPriority Subpriority value (starting from 0). - \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority(). - */ -__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - return ( - ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | - ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) - ); -} - - -/** - \brief Decode Priority - \details Decodes an interrupt priority value with a given priority group to - preemptive priority value and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. - \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority(). - \param [in] PriorityGroup Used priority group. - \param [out] pPreemptPriority Preemptive priority value (starting from 0). - \param [out] pSubPriority Subpriority value (starting from 0). - */ -__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* const pPreemptPriority, uint32_t* const pSubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL); - *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL); -} - - -/** - \brief Set Interrupt Vector - \details Sets an interrupt vector in SRAM based interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - VTOR must been relocated to SRAM before. - If VTOR is not present address 0 must be mapped to SRAM. - \param [in] IRQn Interrupt number - \param [in] vector Address of interrupt handler function - */ -__STATIC_INLINE void __NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) -{ -#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U) - uint32_t *vectors = (uint32_t *)SCB->VTOR; -#else - uint32_t *vectors = (uint32_t *)0x0U; -#endif - vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET] = vector; -} - - -/** - \brief Get Interrupt Vector - \details Reads an interrupt vector from interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Address of interrupt handler function - */ -__STATIC_INLINE uint32_t __NVIC_GetVector(IRQn_Type IRQn) -{ -#if defined (__VTOR_PRESENT) && (__VTOR_PRESENT == 1U) - uint32_t *vectors = (uint32_t *)SCB->VTOR; -#else - uint32_t *vectors = (uint32_t *)0x0U; -#endif - return vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET]; - -} - - -/** - \brief System Reset - \details Initiates a system reset request to reset the MCU. - */ -__NO_RETURN __STATIC_INLINE void __NVIC_SystemReset(void) -{ - __DSB(); /* Ensure all outstanding memory accesses included - buffered write are completed before reset */ - SCB->AIRCR = ((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - SCB_AIRCR_SYSRESETREQ_Msk); - __DSB(); /* Ensure completion of memory access */ - - for(;;) /* wait until reset */ - { - __NOP(); - } -} - -/*@} end of CMSIS_Core_NVICFunctions */ - -/* ########################## MPU functions #################################### */ - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - -#include "mpu_armv7.h" - -#endif - -/* ########################## FPU functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_FpuFunctions FPU Functions - \brief Function that provides FPU type. - @{ - */ - -/** - \brief get FPU type - \details returns the FPU type - \returns - - \b 0: No FPU - - \b 1: Single precision FPU - - \b 2: Double + Single precision FPU - */ -__STATIC_INLINE uint32_t SCB_GetFPUType(void) -{ - return 0U; /* No FPU */ -} - - -/*@} end of CMSIS_Core_FpuFunctions */ - - - -/* ################################## SysTick function ############################################ */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_SysTickFunctions SysTick Functions - \brief Functions that configure the System. - @{ - */ - -#if defined (__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U) - -/** - \brief System Tick Configuration - \details Initializes the System Timer and its interrupt, and starts the System Tick Timer. - Counter is in free running mode to generate periodic interrupts. - \param [in] ticks Number of ticks between two interrupts. - \return 0 Function succeeded. - \return 1 Function failed. - \note When the variable __Vendor_SysTickConfig is set to 1, then the - function SysTick_Config is not included. In this case, the file device.h - must contain a vendor-specific implementation of this function. - */ -__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) -{ - if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) - { - return (1UL); /* Reload value impossible */ - } - - SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ - NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ - SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ - SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | - SysTick_CTRL_TICKINT_Msk | - SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ - return (0UL); /* Function successful */ -} - -#endif - -/*@} end of CMSIS_Core_SysTickFunctions */ - - - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_CM0PLUS_H_DEPENDANT */ - -#endif /* __CMSIS_GENERIC */ diff --git a/body/board/inc/core_cm4.h b/body/board/inc/core_cm4.h deleted file mode 100644 index 7d56873..0000000 --- a/body/board/inc/core_cm4.h +++ /dev/null @@ -1,2129 +0,0 @@ -/**************************************************************************//** - * @file core_cm4.h - * @brief CMSIS Cortex-M4 Core Peripheral Access Layer Header File - * @version V5.0.8 - * @date 04. June 2018 - ******************************************************************************/ -/* - * Copyright (c) 2009-2018 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef __CORE_CM4_H_GENERIC -#define __CORE_CM4_H_GENERIC - -#include - -#ifdef __cplusplus - extern "C" { -#endif - -/** - \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions - CMSIS violates the following MISRA-C:2004 rules: - - \li Required Rule 8.5, object/function definition in header file.
- Function definitions in header files are used to allow 'inlining'. - - \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
- Unions are used for effective representation of core registers. - - \li Advisory Rule 19.7, Function-like macro defined.
- Function-like macros are used to allow more efficient code. - */ - - -/******************************************************************************* - * CMSIS definitions - ******************************************************************************/ -/** - \ingroup Cortex_M4 - @{ - */ - -#include "cmsis_version.h" - -/* CMSIS CM4 definitions */ -#define __CM4_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */ -#define __CM4_CMSIS_VERSION_SUB (__CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */ -#define __CM4_CMSIS_VERSION ((__CM4_CMSIS_VERSION_MAIN << 16U) | \ - __CM4_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */ - -#define __CORTEX_M (4U) /*!< Cortex-M Core */ - -/** __FPU_USED indicates whether an FPU is used or not. - For this, __FPU_PRESENT has to be checked prior to making use of FPU specific registers and functions. -*/ -#if defined ( __CC_ARM ) - #if defined __TARGET_FPU_VFP - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #if defined __ARM_PCS_VFP - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __GNUC__ ) - #if defined (__VFP_FP__) && !defined(__SOFTFP__) - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __ICCARM__ ) - #if defined __ARMVFP__ - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __TI_ARM__ ) - #if defined __TI_VFP_SUPPORT__ - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __TASKING__ ) - #if defined __FPU_VFP__ - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __CSMC__ ) - #if ( __CSMC__ & 0x400U) - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#endif - -#include "cmsis_compiler.h" /* CMSIS compiler specific defines */ - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_CM4_H_GENERIC */ - -#ifndef __CMSIS_GENERIC - -#ifndef __CORE_CM4_H_DEPENDANT -#define __CORE_CM4_H_DEPENDANT - -#ifdef __cplusplus - extern "C" { -#endif - -/* check device defines and use defaults */ -#if defined __CHECK_DEVICE_DEFINES - #ifndef __CM4_REV - #define __CM4_REV 0x0000U - #warning "__CM4_REV not defined in device header file; using default!" - #endif - - #ifndef __FPU_PRESENT - #define __FPU_PRESENT 0U - #warning "__FPU_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __MPU_PRESENT - #define __MPU_PRESENT 0U - #warning "__MPU_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __NVIC_PRIO_BITS - #define __NVIC_PRIO_BITS 3U - #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" - #endif - - #ifndef __Vendor_SysTickConfig - #define __Vendor_SysTickConfig 0U - #warning "__Vendor_SysTickConfig not defined in device header file; using default!" - #endif -#endif - -/* IO definitions (access restrictions to peripheral registers) */ -/** - \defgroup CMSIS_glob_defs CMSIS Global Defines - - IO Type Qualifiers are used - \li to specify the access to peripheral variables. - \li for automatic generation of peripheral register debug information. -*/ -#ifdef __cplusplus - #define __I volatile /*!< Defines 'read only' permissions */ -#else - #define __I volatile const /*!< Defines 'read only' permissions */ -#endif -#define __O volatile /*!< Defines 'write only' permissions */ -#define __IO volatile /*!< Defines 'read / write' permissions */ - -/* following defines should be used for structure members */ -#define __IM volatile const /*! Defines 'read only' structure member permissions */ -#define __OM volatile /*! Defines 'write only' structure member permissions */ -#define __IOM volatile /*! Defines 'read / write' structure member permissions */ - -/*@} end of group Cortex_M4 */ - - - -/******************************************************************************* - * Register Abstraction - Core Register contain: - - Core Register - - Core NVIC Register - - Core SCB Register - - Core SysTick Register - - Core Debug Register - - Core MPU Register - - Core FPU Register - ******************************************************************************/ -/** - \defgroup CMSIS_core_register Defines and Type Definitions - \brief Type definitions and defines for Cortex-M processor based devices. -*/ - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CORE Status and Control Registers - \brief Core Register type definitions. - @{ - */ - -/** - \brief Union type to access the Application Program Status Register (APSR). - */ -typedef union -{ - struct - { - uint32_t _reserved0:16; /*!< bit: 0..15 Reserved */ - uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ - uint32_t _reserved1:7; /*!< bit: 20..26 Reserved */ - uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} APSR_Type; - -/* APSR Register Definitions */ -#define APSR_N_Pos 31U /*!< APSR: N Position */ -#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ - -#define APSR_Z_Pos 30U /*!< APSR: Z Position */ -#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ - -#define APSR_C_Pos 29U /*!< APSR: C Position */ -#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ - -#define APSR_V_Pos 28U /*!< APSR: V Position */ -#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ - -#define APSR_Q_Pos 27U /*!< APSR: Q Position */ -#define APSR_Q_Msk (1UL << APSR_Q_Pos) /*!< APSR: Q Mask */ - -#define APSR_GE_Pos 16U /*!< APSR: GE Position */ -#define APSR_GE_Msk (0xFUL << APSR_GE_Pos) /*!< APSR: GE Mask */ - - -/** - \brief Union type to access the Interrupt Program Status Register (IPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} IPSR_Type; - -/* IPSR Register Definitions */ -#define IPSR_ISR_Pos 0U /*!< IPSR: ISR Position */ -#define IPSR_ISR_Msk (0x1FFUL /*<< IPSR_ISR_Pos*/) /*!< IPSR: ISR Mask */ - - -/** - \brief Union type to access the Special-Purpose Program Status Registers (xPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:1; /*!< bit: 9 Reserved */ - uint32_t ICI_IT_1:6; /*!< bit: 10..15 ICI/IT part 1 */ - uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ - uint32_t _reserved1:4; /*!< bit: 20..23 Reserved */ - uint32_t T:1; /*!< bit: 24 Thumb bit */ - uint32_t ICI_IT_2:2; /*!< bit: 25..26 ICI/IT part 2 */ - uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} xPSR_Type; - -/* xPSR Register Definitions */ -#define xPSR_N_Pos 31U /*!< xPSR: N Position */ -#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ - -#define xPSR_Z_Pos 30U /*!< xPSR: Z Position */ -#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ - -#define xPSR_C_Pos 29U /*!< xPSR: C Position */ -#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ - -#define xPSR_V_Pos 28U /*!< xPSR: V Position */ -#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ - -#define xPSR_Q_Pos 27U /*!< xPSR: Q Position */ -#define xPSR_Q_Msk (1UL << xPSR_Q_Pos) /*!< xPSR: Q Mask */ - -#define xPSR_ICI_IT_2_Pos 25U /*!< xPSR: ICI/IT part 2 Position */ -#define xPSR_ICI_IT_2_Msk (3UL << xPSR_ICI_IT_2_Pos) /*!< xPSR: ICI/IT part 2 Mask */ - -#define xPSR_T_Pos 24U /*!< xPSR: T Position */ -#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ - -#define xPSR_GE_Pos 16U /*!< xPSR: GE Position */ -#define xPSR_GE_Msk (0xFUL << xPSR_GE_Pos) /*!< xPSR: GE Mask */ - -#define xPSR_ICI_IT_1_Pos 10U /*!< xPSR: ICI/IT part 1 Position */ -#define xPSR_ICI_IT_1_Msk (0x3FUL << xPSR_ICI_IT_1_Pos) /*!< xPSR: ICI/IT part 1 Mask */ - -#define xPSR_ISR_Pos 0U /*!< xPSR: ISR Position */ -#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ - - -/** - \brief Union type to access the Control Registers (CONTROL). - */ -typedef union -{ - struct - { - uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ - uint32_t SPSEL:1; /*!< bit: 1 Stack to be used */ - uint32_t FPCA:1; /*!< bit: 2 FP extension active flag */ - uint32_t _reserved0:29; /*!< bit: 3..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} CONTROL_Type; - -/* CONTROL Register Definitions */ -#define CONTROL_FPCA_Pos 2U /*!< CONTROL: FPCA Position */ -#define CONTROL_FPCA_Msk (1UL << CONTROL_FPCA_Pos) /*!< CONTROL: FPCA Mask */ - -#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */ -#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ - -#define CONTROL_nPRIV_Pos 0U /*!< CONTROL: nPRIV Position */ -#define CONTROL_nPRIV_Msk (1UL /*<< CONTROL_nPRIV_Pos*/) /*!< CONTROL: nPRIV Mask */ - -/*@} end of group CMSIS_CORE */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC) - \brief Type definitions for the NVIC Registers - @{ - */ - -/** - \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). - */ -typedef struct -{ - __IOM uint32_t ISER[8U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ - uint32_t RESERVED0[24U]; - __IOM uint32_t ICER[8U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ - uint32_t RSERVED1[24U]; - __IOM uint32_t ISPR[8U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ - uint32_t RESERVED2[24U]; - __IOM uint32_t ICPR[8U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ - uint32_t RESERVED3[24U]; - __IOM uint32_t IABR[8U]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */ - uint32_t RESERVED4[56U]; - __IOM uint8_t IP[240U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register (8Bit wide) */ - uint32_t RESERVED5[644U]; - __OM uint32_t STIR; /*!< Offset: 0xE00 ( /W) Software Trigger Interrupt Register */ -} NVIC_Type; - -/* Software Triggered Interrupt Register Definitions */ -#define NVIC_STIR_INTID_Pos 0U /*!< STIR: INTLINESNUM Position */ -#define NVIC_STIR_INTID_Msk (0x1FFUL /*<< NVIC_STIR_INTID_Pos*/) /*!< STIR: INTLINESNUM Mask */ - -/*@} end of group CMSIS_NVIC */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SCB System Control Block (SCB) - \brief Type definitions for the System Control Block Registers - @{ - */ - -/** - \brief Structure type to access the System Control Block (SCB). - */ -typedef struct -{ - __IM uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ - __IOM uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ - __IOM uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ - __IOM uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ - __IOM uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ - __IOM uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ - __IOM uint8_t SHP[12U]; /*!< Offset: 0x018 (R/W) System Handlers Priority Registers (4-7, 8-11, 12-15) */ - __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ - __IOM uint32_t CFSR; /*!< Offset: 0x028 (R/W) Configurable Fault Status Register */ - __IOM uint32_t HFSR; /*!< Offset: 0x02C (R/W) HardFault Status Register */ - __IOM uint32_t DFSR; /*!< Offset: 0x030 (R/W) Debug Fault Status Register */ - __IOM uint32_t MMFAR; /*!< Offset: 0x034 (R/W) MemManage Fault Address Register */ - __IOM uint32_t BFAR; /*!< Offset: 0x038 (R/W) BusFault Address Register */ - __IOM uint32_t AFSR; /*!< Offset: 0x03C (R/W) Auxiliary Fault Status Register */ - __IM uint32_t PFR[2U]; /*!< Offset: 0x040 (R/ ) Processor Feature Register */ - __IM uint32_t DFR; /*!< Offset: 0x048 (R/ ) Debug Feature Register */ - __IM uint32_t ADR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */ - __IM uint32_t MMFR[4U]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */ - __IM uint32_t ISAR[5U]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */ - uint32_t RESERVED0[5U]; - __IOM uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control Register */ -} SCB_Type; - -/* SCB CPUID Register Definitions */ -#define SCB_CPUID_IMPLEMENTER_Pos 24U /*!< SCB CPUID: IMPLEMENTER Position */ -#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ - -#define SCB_CPUID_VARIANT_Pos 20U /*!< SCB CPUID: VARIANT Position */ -#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ - -#define SCB_CPUID_ARCHITECTURE_Pos 16U /*!< SCB CPUID: ARCHITECTURE Position */ -#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ - -#define SCB_CPUID_PARTNO_Pos 4U /*!< SCB CPUID: PARTNO Position */ -#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ - -#define SCB_CPUID_REVISION_Pos 0U /*!< SCB CPUID: REVISION Position */ -#define SCB_CPUID_REVISION_Msk (0xFUL /*<< SCB_CPUID_REVISION_Pos*/) /*!< SCB CPUID: REVISION Mask */ - -/* SCB Interrupt Control State Register Definitions */ -#define SCB_ICSR_NMIPENDSET_Pos 31U /*!< SCB ICSR: NMIPENDSET Position */ -#define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */ - -#define SCB_ICSR_PENDSVSET_Pos 28U /*!< SCB ICSR: PENDSVSET Position */ -#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ - -#define SCB_ICSR_PENDSVCLR_Pos 27U /*!< SCB ICSR: PENDSVCLR Position */ -#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ - -#define SCB_ICSR_PENDSTSET_Pos 26U /*!< SCB ICSR: PENDSTSET Position */ -#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ - -#define SCB_ICSR_PENDSTCLR_Pos 25U /*!< SCB ICSR: PENDSTCLR Position */ -#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ - -#define SCB_ICSR_ISRPREEMPT_Pos 23U /*!< SCB ICSR: ISRPREEMPT Position */ -#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ - -#define SCB_ICSR_ISRPENDING_Pos 22U /*!< SCB ICSR: ISRPENDING Position */ -#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ - -#define SCB_ICSR_VECTPENDING_Pos 12U /*!< SCB ICSR: VECTPENDING Position */ -#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ - -#define SCB_ICSR_RETTOBASE_Pos 11U /*!< SCB ICSR: RETTOBASE Position */ -#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */ - -#define SCB_ICSR_VECTACTIVE_Pos 0U /*!< SCB ICSR: VECTACTIVE Position */ -#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ - -/* SCB Vector Table Offset Register Definitions */ -#define SCB_VTOR_TBLOFF_Pos 7U /*!< SCB VTOR: TBLOFF Position */ -#define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ - -/* SCB Application Interrupt and Reset Control Register Definitions */ -#define SCB_AIRCR_VECTKEY_Pos 16U /*!< SCB AIRCR: VECTKEY Position */ -#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ - -#define SCB_AIRCR_VECTKEYSTAT_Pos 16U /*!< SCB AIRCR: VECTKEYSTAT Position */ -#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ - -#define SCB_AIRCR_ENDIANESS_Pos 15U /*!< SCB AIRCR: ENDIANESS Position */ -#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ - -#define SCB_AIRCR_PRIGROUP_Pos 8U /*!< SCB AIRCR: PRIGROUP Position */ -#define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */ - -#define SCB_AIRCR_SYSRESETREQ_Pos 2U /*!< SCB AIRCR: SYSRESETREQ Position */ -#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ - -#define SCB_AIRCR_VECTCLRACTIVE_Pos 1U /*!< SCB AIRCR: VECTCLRACTIVE Position */ -#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ - -#define SCB_AIRCR_VECTRESET_Pos 0U /*!< SCB AIRCR: VECTRESET Position */ -#define SCB_AIRCR_VECTRESET_Msk (1UL /*<< SCB_AIRCR_VECTRESET_Pos*/) /*!< SCB AIRCR: VECTRESET Mask */ - -/* SCB System Control Register Definitions */ -#define SCB_SCR_SEVONPEND_Pos 4U /*!< SCB SCR: SEVONPEND Position */ -#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ - -#define SCB_SCR_SLEEPDEEP_Pos 2U /*!< SCB SCR: SLEEPDEEP Position */ -#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ - -#define SCB_SCR_SLEEPONEXIT_Pos 1U /*!< SCB SCR: SLEEPONEXIT Position */ -#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ - -/* SCB Configuration Control Register Definitions */ -#define SCB_CCR_STKALIGN_Pos 9U /*!< SCB CCR: STKALIGN Position */ -#define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */ - -#define SCB_CCR_BFHFNMIGN_Pos 8U /*!< SCB CCR: BFHFNMIGN Position */ -#define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */ - -#define SCB_CCR_DIV_0_TRP_Pos 4U /*!< SCB CCR: DIV_0_TRP Position */ -#define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */ - -#define SCB_CCR_UNALIGN_TRP_Pos 3U /*!< SCB CCR: UNALIGN_TRP Position */ -#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ - -#define SCB_CCR_USERSETMPEND_Pos 1U /*!< SCB CCR: USERSETMPEND Position */ -#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */ - -#define SCB_CCR_NONBASETHRDENA_Pos 0U /*!< SCB CCR: NONBASETHRDENA Position */ -#define SCB_CCR_NONBASETHRDENA_Msk (1UL /*<< SCB_CCR_NONBASETHRDENA_Pos*/) /*!< SCB CCR: NONBASETHRDENA Mask */ - -/* SCB System Handler Control and State Register Definitions */ -#define SCB_SHCSR_USGFAULTENA_Pos 18U /*!< SCB SHCSR: USGFAULTENA Position */ -#define SCB_SHCSR_USGFAULTENA_Msk (1UL << SCB_SHCSR_USGFAULTENA_Pos) /*!< SCB SHCSR: USGFAULTENA Mask */ - -#define SCB_SHCSR_BUSFAULTENA_Pos 17U /*!< SCB SHCSR: BUSFAULTENA Position */ -#define SCB_SHCSR_BUSFAULTENA_Msk (1UL << SCB_SHCSR_BUSFAULTENA_Pos) /*!< SCB SHCSR: BUSFAULTENA Mask */ - -#define SCB_SHCSR_MEMFAULTENA_Pos 16U /*!< SCB SHCSR: MEMFAULTENA Position */ -#define SCB_SHCSR_MEMFAULTENA_Msk (1UL << SCB_SHCSR_MEMFAULTENA_Pos) /*!< SCB SHCSR: MEMFAULTENA Mask */ - -#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */ -#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ - -#define SCB_SHCSR_BUSFAULTPENDED_Pos 14U /*!< SCB SHCSR: BUSFAULTPENDED Position */ -#define SCB_SHCSR_BUSFAULTPENDED_Msk (1UL << SCB_SHCSR_BUSFAULTPENDED_Pos) /*!< SCB SHCSR: BUSFAULTPENDED Mask */ - -#define SCB_SHCSR_MEMFAULTPENDED_Pos 13U /*!< SCB SHCSR: MEMFAULTPENDED Position */ -#define SCB_SHCSR_MEMFAULTPENDED_Msk (1UL << SCB_SHCSR_MEMFAULTPENDED_Pos) /*!< SCB SHCSR: MEMFAULTPENDED Mask */ - -#define SCB_SHCSR_USGFAULTPENDED_Pos 12U /*!< SCB SHCSR: USGFAULTPENDED Position */ -#define SCB_SHCSR_USGFAULTPENDED_Msk (1UL << SCB_SHCSR_USGFAULTPENDED_Pos) /*!< SCB SHCSR: USGFAULTPENDED Mask */ - -#define SCB_SHCSR_SYSTICKACT_Pos 11U /*!< SCB SHCSR: SYSTICKACT Position */ -#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */ - -#define SCB_SHCSR_PENDSVACT_Pos 10U /*!< SCB SHCSR: PENDSVACT Position */ -#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */ - -#define SCB_SHCSR_MONITORACT_Pos 8U /*!< SCB SHCSR: MONITORACT Position */ -#define SCB_SHCSR_MONITORACT_Msk (1UL << SCB_SHCSR_MONITORACT_Pos) /*!< SCB SHCSR: MONITORACT Mask */ - -#define SCB_SHCSR_SVCALLACT_Pos 7U /*!< SCB SHCSR: SVCALLACT Position */ -#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */ - -#define SCB_SHCSR_USGFAULTACT_Pos 3U /*!< SCB SHCSR: USGFAULTACT Position */ -#define SCB_SHCSR_USGFAULTACT_Msk (1UL << SCB_SHCSR_USGFAULTACT_Pos) /*!< SCB SHCSR: USGFAULTACT Mask */ - -#define SCB_SHCSR_BUSFAULTACT_Pos 1U /*!< SCB SHCSR: BUSFAULTACT Position */ -#define SCB_SHCSR_BUSFAULTACT_Msk (1UL << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */ - -#define SCB_SHCSR_MEMFAULTACT_Pos 0U /*!< SCB SHCSR: MEMFAULTACT Position */ -#define SCB_SHCSR_MEMFAULTACT_Msk (1UL /*<< SCB_SHCSR_MEMFAULTACT_Pos*/) /*!< SCB SHCSR: MEMFAULTACT Mask */ - -/* SCB Configurable Fault Status Register Definitions */ -#define SCB_CFSR_USGFAULTSR_Pos 16U /*!< SCB CFSR: Usage Fault Status Register Position */ -#define SCB_CFSR_USGFAULTSR_Msk (0xFFFFUL << SCB_CFSR_USGFAULTSR_Pos) /*!< SCB CFSR: Usage Fault Status Register Mask */ - -#define SCB_CFSR_BUSFAULTSR_Pos 8U /*!< SCB CFSR: Bus Fault Status Register Position */ -#define SCB_CFSR_BUSFAULTSR_Msk (0xFFUL << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */ - -#define SCB_CFSR_MEMFAULTSR_Pos 0U /*!< SCB CFSR: Memory Manage Fault Status Register Position */ -#define SCB_CFSR_MEMFAULTSR_Msk (0xFFUL /*<< SCB_CFSR_MEMFAULTSR_Pos*/) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */ - -/* MemManage Fault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_MMARVALID_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 7U) /*!< SCB CFSR (MMFSR): MMARVALID Position */ -#define SCB_CFSR_MMARVALID_Msk (1UL << SCB_CFSR_MMARVALID_Pos) /*!< SCB CFSR (MMFSR): MMARVALID Mask */ - -#define SCB_CFSR_MLSPERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 5U) /*!< SCB CFSR (MMFSR): MLSPERR Position */ -#define SCB_CFSR_MLSPERR_Msk (1UL << SCB_CFSR_MLSPERR_Pos) /*!< SCB CFSR (MMFSR): MLSPERR Mask */ - -#define SCB_CFSR_MSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 4U) /*!< SCB CFSR (MMFSR): MSTKERR Position */ -#define SCB_CFSR_MSTKERR_Msk (1UL << SCB_CFSR_MSTKERR_Pos) /*!< SCB CFSR (MMFSR): MSTKERR Mask */ - -#define SCB_CFSR_MUNSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 3U) /*!< SCB CFSR (MMFSR): MUNSTKERR Position */ -#define SCB_CFSR_MUNSTKERR_Msk (1UL << SCB_CFSR_MUNSTKERR_Pos) /*!< SCB CFSR (MMFSR): MUNSTKERR Mask */ - -#define SCB_CFSR_DACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 1U) /*!< SCB CFSR (MMFSR): DACCVIOL Position */ -#define SCB_CFSR_DACCVIOL_Msk (1UL << SCB_CFSR_DACCVIOL_Pos) /*!< SCB CFSR (MMFSR): DACCVIOL Mask */ - -#define SCB_CFSR_IACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 0U) /*!< SCB CFSR (MMFSR): IACCVIOL Position */ -#define SCB_CFSR_IACCVIOL_Msk (1UL /*<< SCB_CFSR_IACCVIOL_Pos*/) /*!< SCB CFSR (MMFSR): IACCVIOL Mask */ - -/* BusFault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_BFARVALID_Pos (SCB_CFSR_BUSFAULTSR_Pos + 7U) /*!< SCB CFSR (BFSR): BFARVALID Position */ -#define SCB_CFSR_BFARVALID_Msk (1UL << SCB_CFSR_BFARVALID_Pos) /*!< SCB CFSR (BFSR): BFARVALID Mask */ - -#define SCB_CFSR_LSPERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 5U) /*!< SCB CFSR (BFSR): LSPERR Position */ -#define SCB_CFSR_LSPERR_Msk (1UL << SCB_CFSR_LSPERR_Pos) /*!< SCB CFSR (BFSR): LSPERR Mask */ - -#define SCB_CFSR_STKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 4U) /*!< SCB CFSR (BFSR): STKERR Position */ -#define SCB_CFSR_STKERR_Msk (1UL << SCB_CFSR_STKERR_Pos) /*!< SCB CFSR (BFSR): STKERR Mask */ - -#define SCB_CFSR_UNSTKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 3U) /*!< SCB CFSR (BFSR): UNSTKERR Position */ -#define SCB_CFSR_UNSTKERR_Msk (1UL << SCB_CFSR_UNSTKERR_Pos) /*!< SCB CFSR (BFSR): UNSTKERR Mask */ - -#define SCB_CFSR_IMPRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 2U) /*!< SCB CFSR (BFSR): IMPRECISERR Position */ -#define SCB_CFSR_IMPRECISERR_Msk (1UL << SCB_CFSR_IMPRECISERR_Pos) /*!< SCB CFSR (BFSR): IMPRECISERR Mask */ - -#define SCB_CFSR_PRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 1U) /*!< SCB CFSR (BFSR): PRECISERR Position */ -#define SCB_CFSR_PRECISERR_Msk (1UL << SCB_CFSR_PRECISERR_Pos) /*!< SCB CFSR (BFSR): PRECISERR Mask */ - -#define SCB_CFSR_IBUSERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 0U) /*!< SCB CFSR (BFSR): IBUSERR Position */ -#define SCB_CFSR_IBUSERR_Msk (1UL << SCB_CFSR_IBUSERR_Pos) /*!< SCB CFSR (BFSR): IBUSERR Mask */ - -/* UsageFault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_DIVBYZERO_Pos (SCB_CFSR_USGFAULTSR_Pos + 9U) /*!< SCB CFSR (UFSR): DIVBYZERO Position */ -#define SCB_CFSR_DIVBYZERO_Msk (1UL << SCB_CFSR_DIVBYZERO_Pos) /*!< SCB CFSR (UFSR): DIVBYZERO Mask */ - -#define SCB_CFSR_UNALIGNED_Pos (SCB_CFSR_USGFAULTSR_Pos + 8U) /*!< SCB CFSR (UFSR): UNALIGNED Position */ -#define SCB_CFSR_UNALIGNED_Msk (1UL << SCB_CFSR_UNALIGNED_Pos) /*!< SCB CFSR (UFSR): UNALIGNED Mask */ - -#define SCB_CFSR_NOCP_Pos (SCB_CFSR_USGFAULTSR_Pos + 3U) /*!< SCB CFSR (UFSR): NOCP Position */ -#define SCB_CFSR_NOCP_Msk (1UL << SCB_CFSR_NOCP_Pos) /*!< SCB CFSR (UFSR): NOCP Mask */ - -#define SCB_CFSR_INVPC_Pos (SCB_CFSR_USGFAULTSR_Pos + 2U) /*!< SCB CFSR (UFSR): INVPC Position */ -#define SCB_CFSR_INVPC_Msk (1UL << SCB_CFSR_INVPC_Pos) /*!< SCB CFSR (UFSR): INVPC Mask */ - -#define SCB_CFSR_INVSTATE_Pos (SCB_CFSR_USGFAULTSR_Pos + 1U) /*!< SCB CFSR (UFSR): INVSTATE Position */ -#define SCB_CFSR_INVSTATE_Msk (1UL << SCB_CFSR_INVSTATE_Pos) /*!< SCB CFSR (UFSR): INVSTATE Mask */ - -#define SCB_CFSR_UNDEFINSTR_Pos (SCB_CFSR_USGFAULTSR_Pos + 0U) /*!< SCB CFSR (UFSR): UNDEFINSTR Position */ -#define SCB_CFSR_UNDEFINSTR_Msk (1UL << SCB_CFSR_UNDEFINSTR_Pos) /*!< SCB CFSR (UFSR): UNDEFINSTR Mask */ - -/* SCB Hard Fault Status Register Definitions */ -#define SCB_HFSR_DEBUGEVT_Pos 31U /*!< SCB HFSR: DEBUGEVT Position */ -#define SCB_HFSR_DEBUGEVT_Msk (1UL << SCB_HFSR_DEBUGEVT_Pos) /*!< SCB HFSR: DEBUGEVT Mask */ - -#define SCB_HFSR_FORCED_Pos 30U /*!< SCB HFSR: FORCED Position */ -#define SCB_HFSR_FORCED_Msk (1UL << SCB_HFSR_FORCED_Pos) /*!< SCB HFSR: FORCED Mask */ - -#define SCB_HFSR_VECTTBL_Pos 1U /*!< SCB HFSR: VECTTBL Position */ -#define SCB_HFSR_VECTTBL_Msk (1UL << SCB_HFSR_VECTTBL_Pos) /*!< SCB HFSR: VECTTBL Mask */ - -/* SCB Debug Fault Status Register Definitions */ -#define SCB_DFSR_EXTERNAL_Pos 4U /*!< SCB DFSR: EXTERNAL Position */ -#define SCB_DFSR_EXTERNAL_Msk (1UL << SCB_DFSR_EXTERNAL_Pos) /*!< SCB DFSR: EXTERNAL Mask */ - -#define SCB_DFSR_VCATCH_Pos 3U /*!< SCB DFSR: VCATCH Position */ -#define SCB_DFSR_VCATCH_Msk (1UL << SCB_DFSR_VCATCH_Pos) /*!< SCB DFSR: VCATCH Mask */ - -#define SCB_DFSR_DWTTRAP_Pos 2U /*!< SCB DFSR: DWTTRAP Position */ -#define SCB_DFSR_DWTTRAP_Msk (1UL << SCB_DFSR_DWTTRAP_Pos) /*!< SCB DFSR: DWTTRAP Mask */ - -#define SCB_DFSR_BKPT_Pos 1U /*!< SCB DFSR: BKPT Position */ -#define SCB_DFSR_BKPT_Msk (1UL << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */ - -#define SCB_DFSR_HALTED_Pos 0U /*!< SCB DFSR: HALTED Position */ -#define SCB_DFSR_HALTED_Msk (1UL /*<< SCB_DFSR_HALTED_Pos*/) /*!< SCB DFSR: HALTED Mask */ - -/*@} end of group CMSIS_SCB */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SCnSCB System Controls not in SCB (SCnSCB) - \brief Type definitions for the System Control and ID Register not in the SCB - @{ - */ - -/** - \brief Structure type to access the System Control and ID Register not in the SCB. - */ -typedef struct -{ - uint32_t RESERVED0[1U]; - __IM uint32_t ICTR; /*!< Offset: 0x004 (R/ ) Interrupt Controller Type Register */ - __IOM uint32_t ACTLR; /*!< Offset: 0x008 (R/W) Auxiliary Control Register */ -} SCnSCB_Type; - -/* Interrupt Controller Type Register Definitions */ -#define SCnSCB_ICTR_INTLINESNUM_Pos 0U /*!< ICTR: INTLINESNUM Position */ -#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL /*<< SCnSCB_ICTR_INTLINESNUM_Pos*/) /*!< ICTR: INTLINESNUM Mask */ - -/* Auxiliary Control Register Definitions */ -#define SCnSCB_ACTLR_DISOOFP_Pos 9U /*!< ACTLR: DISOOFP Position */ -#define SCnSCB_ACTLR_DISOOFP_Msk (1UL << SCnSCB_ACTLR_DISOOFP_Pos) /*!< ACTLR: DISOOFP Mask */ - -#define SCnSCB_ACTLR_DISFPCA_Pos 8U /*!< ACTLR: DISFPCA Position */ -#define SCnSCB_ACTLR_DISFPCA_Msk (1UL << SCnSCB_ACTLR_DISFPCA_Pos) /*!< ACTLR: DISFPCA Mask */ - -#define SCnSCB_ACTLR_DISFOLD_Pos 2U /*!< ACTLR: DISFOLD Position */ -#define SCnSCB_ACTLR_DISFOLD_Msk (1UL << SCnSCB_ACTLR_DISFOLD_Pos) /*!< ACTLR: DISFOLD Mask */ - -#define SCnSCB_ACTLR_DISDEFWBUF_Pos 1U /*!< ACTLR: DISDEFWBUF Position */ -#define SCnSCB_ACTLR_DISDEFWBUF_Msk (1UL << SCnSCB_ACTLR_DISDEFWBUF_Pos) /*!< ACTLR: DISDEFWBUF Mask */ - -#define SCnSCB_ACTLR_DISMCYCINT_Pos 0U /*!< ACTLR: DISMCYCINT Position */ -#define SCnSCB_ACTLR_DISMCYCINT_Msk (1UL /*<< SCnSCB_ACTLR_DISMCYCINT_Pos*/) /*!< ACTLR: DISMCYCINT Mask */ - -/*@} end of group CMSIS_SCnotSCB */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SysTick System Tick Timer (SysTick) - \brief Type definitions for the System Timer Registers. - @{ - */ - -/** - \brief Structure type to access the System Timer (SysTick). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ - __IOM uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ - __IOM uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ - __IM uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ -} SysTick_Type; - -/* SysTick Control / Status Register Definitions */ -#define SysTick_CTRL_COUNTFLAG_Pos 16U /*!< SysTick CTRL: COUNTFLAG Position */ -#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ - -#define SysTick_CTRL_CLKSOURCE_Pos 2U /*!< SysTick CTRL: CLKSOURCE Position */ -#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ - -#define SysTick_CTRL_TICKINT_Pos 1U /*!< SysTick CTRL: TICKINT Position */ -#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ - -#define SysTick_CTRL_ENABLE_Pos 0U /*!< SysTick CTRL: ENABLE Position */ -#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ - -/* SysTick Reload Register Definitions */ -#define SysTick_LOAD_RELOAD_Pos 0U /*!< SysTick LOAD: RELOAD Position */ -#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ - -/* SysTick Current Register Definitions */ -#define SysTick_VAL_CURRENT_Pos 0U /*!< SysTick VAL: CURRENT Position */ -#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ - -/* SysTick Calibration Register Definitions */ -#define SysTick_CALIB_NOREF_Pos 31U /*!< SysTick CALIB: NOREF Position */ -#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ - -#define SysTick_CALIB_SKEW_Pos 30U /*!< SysTick CALIB: SKEW Position */ -#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ - -#define SysTick_CALIB_TENMS_Pos 0U /*!< SysTick CALIB: TENMS Position */ -#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ - -/*@} end of group CMSIS_SysTick */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_ITM Instrumentation Trace Macrocell (ITM) - \brief Type definitions for the Instrumentation Trace Macrocell (ITM) - @{ - */ - -/** - \brief Structure type to access the Instrumentation Trace Macrocell Register (ITM). - */ -typedef struct -{ - __OM union - { - __OM uint8_t u8; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 8-bit */ - __OM uint16_t u16; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 16-bit */ - __OM uint32_t u32; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 32-bit */ - } PORT [32U]; /*!< Offset: 0x000 ( /W) ITM Stimulus Port Registers */ - uint32_t RESERVED0[864U]; - __IOM uint32_t TER; /*!< Offset: 0xE00 (R/W) ITM Trace Enable Register */ - uint32_t RESERVED1[15U]; - __IOM uint32_t TPR; /*!< Offset: 0xE40 (R/W) ITM Trace Privilege Register */ - uint32_t RESERVED2[15U]; - __IOM uint32_t TCR; /*!< Offset: 0xE80 (R/W) ITM Trace Control Register */ - uint32_t RESERVED3[29U]; - __OM uint32_t IWR; /*!< Offset: 0xEF8 ( /W) ITM Integration Write Register */ - __IM uint32_t IRR; /*!< Offset: 0xEFC (R/ ) ITM Integration Read Register */ - __IOM uint32_t IMCR; /*!< Offset: 0xF00 (R/W) ITM Integration Mode Control Register */ - uint32_t RESERVED4[43U]; - __OM uint32_t LAR; /*!< Offset: 0xFB0 ( /W) ITM Lock Access Register */ - __IM uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) ITM Lock Status Register */ - uint32_t RESERVED5[6U]; - __IM uint32_t PID4; /*!< Offset: 0xFD0 (R/ ) ITM Peripheral Identification Register #4 */ - __IM uint32_t PID5; /*!< Offset: 0xFD4 (R/ ) ITM Peripheral Identification Register #5 */ - __IM uint32_t PID6; /*!< Offset: 0xFD8 (R/ ) ITM Peripheral Identification Register #6 */ - __IM uint32_t PID7; /*!< Offset: 0xFDC (R/ ) ITM Peripheral Identification Register #7 */ - __IM uint32_t PID0; /*!< Offset: 0xFE0 (R/ ) ITM Peripheral Identification Register #0 */ - __IM uint32_t PID1; /*!< Offset: 0xFE4 (R/ ) ITM Peripheral Identification Register #1 */ - __IM uint32_t PID2; /*!< Offset: 0xFE8 (R/ ) ITM Peripheral Identification Register #2 */ - __IM uint32_t PID3; /*!< Offset: 0xFEC (R/ ) ITM Peripheral Identification Register #3 */ - __IM uint32_t CID0; /*!< Offset: 0xFF0 (R/ ) ITM Component Identification Register #0 */ - __IM uint32_t CID1; /*!< Offset: 0xFF4 (R/ ) ITM Component Identification Register #1 */ - __IM uint32_t CID2; /*!< Offset: 0xFF8 (R/ ) ITM Component Identification Register #2 */ - __IM uint32_t CID3; /*!< Offset: 0xFFC (R/ ) ITM Component Identification Register #3 */ -} ITM_Type; - -/* ITM Trace Privilege Register Definitions */ -#define ITM_TPR_PRIVMASK_Pos 0U /*!< ITM TPR: PRIVMASK Position */ -#define ITM_TPR_PRIVMASK_Msk (0xFFFFFFFFUL /*<< ITM_TPR_PRIVMASK_Pos*/) /*!< ITM TPR: PRIVMASK Mask */ - -/* ITM Trace Control Register Definitions */ -#define ITM_TCR_BUSY_Pos 23U /*!< ITM TCR: BUSY Position */ -#define ITM_TCR_BUSY_Msk (1UL << ITM_TCR_BUSY_Pos) /*!< ITM TCR: BUSY Mask */ - -#define ITM_TCR_TraceBusID_Pos 16U /*!< ITM TCR: ATBID Position */ -#define ITM_TCR_TraceBusID_Msk (0x7FUL << ITM_TCR_TraceBusID_Pos) /*!< ITM TCR: ATBID Mask */ - -#define ITM_TCR_GTSFREQ_Pos 10U /*!< ITM TCR: Global timestamp frequency Position */ -#define ITM_TCR_GTSFREQ_Msk (3UL << ITM_TCR_GTSFREQ_Pos) /*!< ITM TCR: Global timestamp frequency Mask */ - -#define ITM_TCR_TSPrescale_Pos 8U /*!< ITM TCR: TSPrescale Position */ -#define ITM_TCR_TSPrescale_Msk (3UL << ITM_TCR_TSPrescale_Pos) /*!< ITM TCR: TSPrescale Mask */ - -#define ITM_TCR_SWOENA_Pos 4U /*!< ITM TCR: SWOENA Position */ -#define ITM_TCR_SWOENA_Msk (1UL << ITM_TCR_SWOENA_Pos) /*!< ITM TCR: SWOENA Mask */ - -#define ITM_TCR_DWTENA_Pos 3U /*!< ITM TCR: DWTENA Position */ -#define ITM_TCR_DWTENA_Msk (1UL << ITM_TCR_DWTENA_Pos) /*!< ITM TCR: DWTENA Mask */ - -#define ITM_TCR_SYNCENA_Pos 2U /*!< ITM TCR: SYNCENA Position */ -#define ITM_TCR_SYNCENA_Msk (1UL << ITM_TCR_SYNCENA_Pos) /*!< ITM TCR: SYNCENA Mask */ - -#define ITM_TCR_TSENA_Pos 1U /*!< ITM TCR: TSENA Position */ -#define ITM_TCR_TSENA_Msk (1UL << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */ - -#define ITM_TCR_ITMENA_Pos 0U /*!< ITM TCR: ITM Enable bit Position */ -#define ITM_TCR_ITMENA_Msk (1UL /*<< ITM_TCR_ITMENA_Pos*/) /*!< ITM TCR: ITM Enable bit Mask */ - -/* ITM Integration Write Register Definitions */ -#define ITM_IWR_ATVALIDM_Pos 0U /*!< ITM IWR: ATVALIDM Position */ -#define ITM_IWR_ATVALIDM_Msk (1UL /*<< ITM_IWR_ATVALIDM_Pos*/) /*!< ITM IWR: ATVALIDM Mask */ - -/* ITM Integration Read Register Definitions */ -#define ITM_IRR_ATREADYM_Pos 0U /*!< ITM IRR: ATREADYM Position */ -#define ITM_IRR_ATREADYM_Msk (1UL /*<< ITM_IRR_ATREADYM_Pos*/) /*!< ITM IRR: ATREADYM Mask */ - -/* ITM Integration Mode Control Register Definitions */ -#define ITM_IMCR_INTEGRATION_Pos 0U /*!< ITM IMCR: INTEGRATION Position */ -#define ITM_IMCR_INTEGRATION_Msk (1UL /*<< ITM_IMCR_INTEGRATION_Pos*/) /*!< ITM IMCR: INTEGRATION Mask */ - -/* ITM Lock Status Register Definitions */ -#define ITM_LSR_ByteAcc_Pos 2U /*!< ITM LSR: ByteAcc Position */ -#define ITM_LSR_ByteAcc_Msk (1UL << ITM_LSR_ByteAcc_Pos) /*!< ITM LSR: ByteAcc Mask */ - -#define ITM_LSR_Access_Pos 1U /*!< ITM LSR: Access Position */ -#define ITM_LSR_Access_Msk (1UL << ITM_LSR_Access_Pos) /*!< ITM LSR: Access Mask */ - -#define ITM_LSR_Present_Pos 0U /*!< ITM LSR: Present Position */ -#define ITM_LSR_Present_Msk (1UL /*<< ITM_LSR_Present_Pos*/) /*!< ITM LSR: Present Mask */ - -/*@}*/ /* end of group CMSIS_ITM */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_DWT Data Watchpoint and Trace (DWT) - \brief Type definitions for the Data Watchpoint and Trace (DWT) - @{ - */ - -/** - \brief Structure type to access the Data Watchpoint and Trace Register (DWT). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) Control Register */ - __IOM uint32_t CYCCNT; /*!< Offset: 0x004 (R/W) Cycle Count Register */ - __IOM uint32_t CPICNT; /*!< Offset: 0x008 (R/W) CPI Count Register */ - __IOM uint32_t EXCCNT; /*!< Offset: 0x00C (R/W) Exception Overhead Count Register */ - __IOM uint32_t SLEEPCNT; /*!< Offset: 0x010 (R/W) Sleep Count Register */ - __IOM uint32_t LSUCNT; /*!< Offset: 0x014 (R/W) LSU Count Register */ - __IOM uint32_t FOLDCNT; /*!< Offset: 0x018 (R/W) Folded-instruction Count Register */ - __IM uint32_t PCSR; /*!< Offset: 0x01C (R/ ) Program Counter Sample Register */ - __IOM uint32_t COMP0; /*!< Offset: 0x020 (R/W) Comparator Register 0 */ - __IOM uint32_t MASK0; /*!< Offset: 0x024 (R/W) Mask Register 0 */ - __IOM uint32_t FUNCTION0; /*!< Offset: 0x028 (R/W) Function Register 0 */ - uint32_t RESERVED0[1U]; - __IOM uint32_t COMP1; /*!< Offset: 0x030 (R/W) Comparator Register 1 */ - __IOM uint32_t MASK1; /*!< Offset: 0x034 (R/W) Mask Register 1 */ - __IOM uint32_t FUNCTION1; /*!< Offset: 0x038 (R/W) Function Register 1 */ - uint32_t RESERVED1[1U]; - __IOM uint32_t COMP2; /*!< Offset: 0x040 (R/W) Comparator Register 2 */ - __IOM uint32_t MASK2; /*!< Offset: 0x044 (R/W) Mask Register 2 */ - __IOM uint32_t FUNCTION2; /*!< Offset: 0x048 (R/W) Function Register 2 */ - uint32_t RESERVED2[1U]; - __IOM uint32_t COMP3; /*!< Offset: 0x050 (R/W) Comparator Register 3 */ - __IOM uint32_t MASK3; /*!< Offset: 0x054 (R/W) Mask Register 3 */ - __IOM uint32_t FUNCTION3; /*!< Offset: 0x058 (R/W) Function Register 3 */ -} DWT_Type; - -/* DWT Control Register Definitions */ -#define DWT_CTRL_NUMCOMP_Pos 28U /*!< DWT CTRL: NUMCOMP Position */ -#define DWT_CTRL_NUMCOMP_Msk (0xFUL << DWT_CTRL_NUMCOMP_Pos) /*!< DWT CTRL: NUMCOMP Mask */ - -#define DWT_CTRL_NOTRCPKT_Pos 27U /*!< DWT CTRL: NOTRCPKT Position */ -#define DWT_CTRL_NOTRCPKT_Msk (0x1UL << DWT_CTRL_NOTRCPKT_Pos) /*!< DWT CTRL: NOTRCPKT Mask */ - -#define DWT_CTRL_NOEXTTRIG_Pos 26U /*!< DWT CTRL: NOEXTTRIG Position */ -#define DWT_CTRL_NOEXTTRIG_Msk (0x1UL << DWT_CTRL_NOEXTTRIG_Pos) /*!< DWT CTRL: NOEXTTRIG Mask */ - -#define DWT_CTRL_NOCYCCNT_Pos 25U /*!< DWT CTRL: NOCYCCNT Position */ -#define DWT_CTRL_NOCYCCNT_Msk (0x1UL << DWT_CTRL_NOCYCCNT_Pos) /*!< DWT CTRL: NOCYCCNT Mask */ - -#define DWT_CTRL_NOPRFCNT_Pos 24U /*!< DWT CTRL: NOPRFCNT Position */ -#define DWT_CTRL_NOPRFCNT_Msk (0x1UL << DWT_CTRL_NOPRFCNT_Pos) /*!< DWT CTRL: NOPRFCNT Mask */ - -#define DWT_CTRL_CYCEVTENA_Pos 22U /*!< DWT CTRL: CYCEVTENA Position */ -#define DWT_CTRL_CYCEVTENA_Msk (0x1UL << DWT_CTRL_CYCEVTENA_Pos) /*!< DWT CTRL: CYCEVTENA Mask */ - -#define DWT_CTRL_FOLDEVTENA_Pos 21U /*!< DWT CTRL: FOLDEVTENA Position */ -#define DWT_CTRL_FOLDEVTENA_Msk (0x1UL << DWT_CTRL_FOLDEVTENA_Pos) /*!< DWT CTRL: FOLDEVTENA Mask */ - -#define DWT_CTRL_LSUEVTENA_Pos 20U /*!< DWT CTRL: LSUEVTENA Position */ -#define DWT_CTRL_LSUEVTENA_Msk (0x1UL << DWT_CTRL_LSUEVTENA_Pos) /*!< DWT CTRL: LSUEVTENA Mask */ - -#define DWT_CTRL_SLEEPEVTENA_Pos 19U /*!< DWT CTRL: SLEEPEVTENA Position */ -#define DWT_CTRL_SLEEPEVTENA_Msk (0x1UL << DWT_CTRL_SLEEPEVTENA_Pos) /*!< DWT CTRL: SLEEPEVTENA Mask */ - -#define DWT_CTRL_EXCEVTENA_Pos 18U /*!< DWT CTRL: EXCEVTENA Position */ -#define DWT_CTRL_EXCEVTENA_Msk (0x1UL << DWT_CTRL_EXCEVTENA_Pos) /*!< DWT CTRL: EXCEVTENA Mask */ - -#define DWT_CTRL_CPIEVTENA_Pos 17U /*!< DWT CTRL: CPIEVTENA Position */ -#define DWT_CTRL_CPIEVTENA_Msk (0x1UL << DWT_CTRL_CPIEVTENA_Pos) /*!< DWT CTRL: CPIEVTENA Mask */ - -#define DWT_CTRL_EXCTRCENA_Pos 16U /*!< DWT CTRL: EXCTRCENA Position */ -#define DWT_CTRL_EXCTRCENA_Msk (0x1UL << DWT_CTRL_EXCTRCENA_Pos) /*!< DWT CTRL: EXCTRCENA Mask */ - -#define DWT_CTRL_PCSAMPLENA_Pos 12U /*!< DWT CTRL: PCSAMPLENA Position */ -#define DWT_CTRL_PCSAMPLENA_Msk (0x1UL << DWT_CTRL_PCSAMPLENA_Pos) /*!< DWT CTRL: PCSAMPLENA Mask */ - -#define DWT_CTRL_SYNCTAP_Pos 10U /*!< DWT CTRL: SYNCTAP Position */ -#define DWT_CTRL_SYNCTAP_Msk (0x3UL << DWT_CTRL_SYNCTAP_Pos) /*!< DWT CTRL: SYNCTAP Mask */ - -#define DWT_CTRL_CYCTAP_Pos 9U /*!< DWT CTRL: CYCTAP Position */ -#define DWT_CTRL_CYCTAP_Msk (0x1UL << DWT_CTRL_CYCTAP_Pos) /*!< DWT CTRL: CYCTAP Mask */ - -#define DWT_CTRL_POSTINIT_Pos 5U /*!< DWT CTRL: POSTINIT Position */ -#define DWT_CTRL_POSTINIT_Msk (0xFUL << DWT_CTRL_POSTINIT_Pos) /*!< DWT CTRL: POSTINIT Mask */ - -#define DWT_CTRL_POSTPRESET_Pos 1U /*!< DWT CTRL: POSTPRESET Position */ -#define DWT_CTRL_POSTPRESET_Msk (0xFUL << DWT_CTRL_POSTPRESET_Pos) /*!< DWT CTRL: POSTPRESET Mask */ - -#define DWT_CTRL_CYCCNTENA_Pos 0U /*!< DWT CTRL: CYCCNTENA Position */ -#define DWT_CTRL_CYCCNTENA_Msk (0x1UL /*<< DWT_CTRL_CYCCNTENA_Pos*/) /*!< DWT CTRL: CYCCNTENA Mask */ - -/* DWT CPI Count Register Definitions */ -#define DWT_CPICNT_CPICNT_Pos 0U /*!< DWT CPICNT: CPICNT Position */ -#define DWT_CPICNT_CPICNT_Msk (0xFFUL /*<< DWT_CPICNT_CPICNT_Pos*/) /*!< DWT CPICNT: CPICNT Mask */ - -/* DWT Exception Overhead Count Register Definitions */ -#define DWT_EXCCNT_EXCCNT_Pos 0U /*!< DWT EXCCNT: EXCCNT Position */ -#define DWT_EXCCNT_EXCCNT_Msk (0xFFUL /*<< DWT_EXCCNT_EXCCNT_Pos*/) /*!< DWT EXCCNT: EXCCNT Mask */ - -/* DWT Sleep Count Register Definitions */ -#define DWT_SLEEPCNT_SLEEPCNT_Pos 0U /*!< DWT SLEEPCNT: SLEEPCNT Position */ -#define DWT_SLEEPCNT_SLEEPCNT_Msk (0xFFUL /*<< DWT_SLEEPCNT_SLEEPCNT_Pos*/) /*!< DWT SLEEPCNT: SLEEPCNT Mask */ - -/* DWT LSU Count Register Definitions */ -#define DWT_LSUCNT_LSUCNT_Pos 0U /*!< DWT LSUCNT: LSUCNT Position */ -#define DWT_LSUCNT_LSUCNT_Msk (0xFFUL /*<< DWT_LSUCNT_LSUCNT_Pos*/) /*!< DWT LSUCNT: LSUCNT Mask */ - -/* DWT Folded-instruction Count Register Definitions */ -#define DWT_FOLDCNT_FOLDCNT_Pos 0U /*!< DWT FOLDCNT: FOLDCNT Position */ -#define DWT_FOLDCNT_FOLDCNT_Msk (0xFFUL /*<< DWT_FOLDCNT_FOLDCNT_Pos*/) /*!< DWT FOLDCNT: FOLDCNT Mask */ - -/* DWT Comparator Mask Register Definitions */ -#define DWT_MASK_MASK_Pos 0U /*!< DWT MASK: MASK Position */ -#define DWT_MASK_MASK_Msk (0x1FUL /*<< DWT_MASK_MASK_Pos*/) /*!< DWT MASK: MASK Mask */ - -/* DWT Comparator Function Register Definitions */ -#define DWT_FUNCTION_MATCHED_Pos 24U /*!< DWT FUNCTION: MATCHED Position */ -#define DWT_FUNCTION_MATCHED_Msk (0x1UL << DWT_FUNCTION_MATCHED_Pos) /*!< DWT FUNCTION: MATCHED Mask */ - -#define DWT_FUNCTION_DATAVADDR1_Pos 16U /*!< DWT FUNCTION: DATAVADDR1 Position */ -#define DWT_FUNCTION_DATAVADDR1_Msk (0xFUL << DWT_FUNCTION_DATAVADDR1_Pos) /*!< DWT FUNCTION: DATAVADDR1 Mask */ - -#define DWT_FUNCTION_DATAVADDR0_Pos 12U /*!< DWT FUNCTION: DATAVADDR0 Position */ -#define DWT_FUNCTION_DATAVADDR0_Msk (0xFUL << DWT_FUNCTION_DATAVADDR0_Pos) /*!< DWT FUNCTION: DATAVADDR0 Mask */ - -#define DWT_FUNCTION_DATAVSIZE_Pos 10U /*!< DWT FUNCTION: DATAVSIZE Position */ -#define DWT_FUNCTION_DATAVSIZE_Msk (0x3UL << DWT_FUNCTION_DATAVSIZE_Pos) /*!< DWT FUNCTION: DATAVSIZE Mask */ - -#define DWT_FUNCTION_LNK1ENA_Pos 9U /*!< DWT FUNCTION: LNK1ENA Position */ -#define DWT_FUNCTION_LNK1ENA_Msk (0x1UL << DWT_FUNCTION_LNK1ENA_Pos) /*!< DWT FUNCTION: LNK1ENA Mask */ - -#define DWT_FUNCTION_DATAVMATCH_Pos 8U /*!< DWT FUNCTION: DATAVMATCH Position */ -#define DWT_FUNCTION_DATAVMATCH_Msk (0x1UL << DWT_FUNCTION_DATAVMATCH_Pos) /*!< DWT FUNCTION: DATAVMATCH Mask */ - -#define DWT_FUNCTION_CYCMATCH_Pos 7U /*!< DWT FUNCTION: CYCMATCH Position */ -#define DWT_FUNCTION_CYCMATCH_Msk (0x1UL << DWT_FUNCTION_CYCMATCH_Pos) /*!< DWT FUNCTION: CYCMATCH Mask */ - -#define DWT_FUNCTION_EMITRANGE_Pos 5U /*!< DWT FUNCTION: EMITRANGE Position */ -#define DWT_FUNCTION_EMITRANGE_Msk (0x1UL << DWT_FUNCTION_EMITRANGE_Pos) /*!< DWT FUNCTION: EMITRANGE Mask */ - -#define DWT_FUNCTION_FUNCTION_Pos 0U /*!< DWT FUNCTION: FUNCTION Position */ -#define DWT_FUNCTION_FUNCTION_Msk (0xFUL /*<< DWT_FUNCTION_FUNCTION_Pos*/) /*!< DWT FUNCTION: FUNCTION Mask */ - -/*@}*/ /* end of group CMSIS_DWT */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_TPI Trace Port Interface (TPI) - \brief Type definitions for the Trace Port Interface (TPI) - @{ - */ - -/** - \brief Structure type to access the Trace Port Interface Register (TPI). - */ -typedef struct -{ - __IM uint32_t SSPSR; /*!< Offset: 0x000 (R/ ) Supported Parallel Port Size Register */ - __IOM uint32_t CSPSR; /*!< Offset: 0x004 (R/W) Current Parallel Port Size Register */ - uint32_t RESERVED0[2U]; - __IOM uint32_t ACPR; /*!< Offset: 0x010 (R/W) Asynchronous Clock Prescaler Register */ - uint32_t RESERVED1[55U]; - __IOM uint32_t SPPR; /*!< Offset: 0x0F0 (R/W) Selected Pin Protocol Register */ - uint32_t RESERVED2[131U]; - __IM uint32_t FFSR; /*!< Offset: 0x300 (R/ ) Formatter and Flush Status Register */ - __IOM uint32_t FFCR; /*!< Offset: 0x304 (R/W) Formatter and Flush Control Register */ - __IM uint32_t FSCR; /*!< Offset: 0x308 (R/ ) Formatter Synchronization Counter Register */ - uint32_t RESERVED3[759U]; - __IM uint32_t TRIGGER; /*!< Offset: 0xEE8 (R/ ) TRIGGER Register */ - __IM uint32_t FIFO0; /*!< Offset: 0xEEC (R/ ) Integration ETM Data */ - __IM uint32_t ITATBCTR2; /*!< Offset: 0xEF0 (R/ ) ITATBCTR2 */ - uint32_t RESERVED4[1U]; - __IM uint32_t ITATBCTR0; /*!< Offset: 0xEF8 (R/ ) ITATBCTR0 */ - __IM uint32_t FIFO1; /*!< Offset: 0xEFC (R/ ) Integration ITM Data */ - __IOM uint32_t ITCTRL; /*!< Offset: 0xF00 (R/W) Integration Mode Control */ - uint32_t RESERVED5[39U]; - __IOM uint32_t CLAIMSET; /*!< Offset: 0xFA0 (R/W) Claim tag set */ - __IOM uint32_t CLAIMCLR; /*!< Offset: 0xFA4 (R/W) Claim tag clear */ - uint32_t RESERVED7[8U]; - __IM uint32_t DEVID; /*!< Offset: 0xFC8 (R/ ) TPIU_DEVID */ - __IM uint32_t DEVTYPE; /*!< Offset: 0xFCC (R/ ) TPIU_DEVTYPE */ -} TPI_Type; - -/* TPI Asynchronous Clock Prescaler Register Definitions */ -#define TPI_ACPR_PRESCALER_Pos 0U /*!< TPI ACPR: PRESCALER Position */ -#define TPI_ACPR_PRESCALER_Msk (0x1FFFUL /*<< TPI_ACPR_PRESCALER_Pos*/) /*!< TPI ACPR: PRESCALER Mask */ - -/* TPI Selected Pin Protocol Register Definitions */ -#define TPI_SPPR_TXMODE_Pos 0U /*!< TPI SPPR: TXMODE Position */ -#define TPI_SPPR_TXMODE_Msk (0x3UL /*<< TPI_SPPR_TXMODE_Pos*/) /*!< TPI SPPR: TXMODE Mask */ - -/* TPI Formatter and Flush Status Register Definitions */ -#define TPI_FFSR_FtNonStop_Pos 3U /*!< TPI FFSR: FtNonStop Position */ -#define TPI_FFSR_FtNonStop_Msk (0x1UL << TPI_FFSR_FtNonStop_Pos) /*!< TPI FFSR: FtNonStop Mask */ - -#define TPI_FFSR_TCPresent_Pos 2U /*!< TPI FFSR: TCPresent Position */ -#define TPI_FFSR_TCPresent_Msk (0x1UL << TPI_FFSR_TCPresent_Pos) /*!< TPI FFSR: TCPresent Mask */ - -#define TPI_FFSR_FtStopped_Pos 1U /*!< TPI FFSR: FtStopped Position */ -#define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */ - -#define TPI_FFSR_FlInProg_Pos 0U /*!< TPI FFSR: FlInProg Position */ -#define TPI_FFSR_FlInProg_Msk (0x1UL /*<< TPI_FFSR_FlInProg_Pos*/) /*!< TPI FFSR: FlInProg Mask */ - -/* TPI Formatter and Flush Control Register Definitions */ -#define TPI_FFCR_TrigIn_Pos 8U /*!< TPI FFCR: TrigIn Position */ -#define TPI_FFCR_TrigIn_Msk (0x1UL << TPI_FFCR_TrigIn_Pos) /*!< TPI FFCR: TrigIn Mask */ - -#define TPI_FFCR_EnFCont_Pos 1U /*!< TPI FFCR: EnFCont Position */ -#define TPI_FFCR_EnFCont_Msk (0x1UL << TPI_FFCR_EnFCont_Pos) /*!< TPI FFCR: EnFCont Mask */ - -/* TPI TRIGGER Register Definitions */ -#define TPI_TRIGGER_TRIGGER_Pos 0U /*!< TPI TRIGGER: TRIGGER Position */ -#define TPI_TRIGGER_TRIGGER_Msk (0x1UL /*<< TPI_TRIGGER_TRIGGER_Pos*/) /*!< TPI TRIGGER: TRIGGER Mask */ - -/* TPI Integration ETM Data Register Definitions (FIFO0) */ -#define TPI_FIFO0_ITM_ATVALID_Pos 29U /*!< TPI FIFO0: ITM_ATVALID Position */ -#define TPI_FIFO0_ITM_ATVALID_Msk (0x3UL << TPI_FIFO0_ITM_ATVALID_Pos) /*!< TPI FIFO0: ITM_ATVALID Mask */ - -#define TPI_FIFO0_ITM_bytecount_Pos 27U /*!< TPI FIFO0: ITM_bytecount Position */ -#define TPI_FIFO0_ITM_bytecount_Msk (0x3UL << TPI_FIFO0_ITM_bytecount_Pos) /*!< TPI FIFO0: ITM_bytecount Mask */ - -#define TPI_FIFO0_ETM_ATVALID_Pos 26U /*!< TPI FIFO0: ETM_ATVALID Position */ -#define TPI_FIFO0_ETM_ATVALID_Msk (0x3UL << TPI_FIFO0_ETM_ATVALID_Pos) /*!< TPI FIFO0: ETM_ATVALID Mask */ - -#define TPI_FIFO0_ETM_bytecount_Pos 24U /*!< TPI FIFO0: ETM_bytecount Position */ -#define TPI_FIFO0_ETM_bytecount_Msk (0x3UL << TPI_FIFO0_ETM_bytecount_Pos) /*!< TPI FIFO0: ETM_bytecount Mask */ - -#define TPI_FIFO0_ETM2_Pos 16U /*!< TPI FIFO0: ETM2 Position */ -#define TPI_FIFO0_ETM2_Msk (0xFFUL << TPI_FIFO0_ETM2_Pos) /*!< TPI FIFO0: ETM2 Mask */ - -#define TPI_FIFO0_ETM1_Pos 8U /*!< TPI FIFO0: ETM1 Position */ -#define TPI_FIFO0_ETM1_Msk (0xFFUL << TPI_FIFO0_ETM1_Pos) /*!< TPI FIFO0: ETM1 Mask */ - -#define TPI_FIFO0_ETM0_Pos 0U /*!< TPI FIFO0: ETM0 Position */ -#define TPI_FIFO0_ETM0_Msk (0xFFUL /*<< TPI_FIFO0_ETM0_Pos*/) /*!< TPI FIFO0: ETM0 Mask */ - -/* TPI ITATBCTR2 Register Definitions */ -#define TPI_ITATBCTR2_ATREADY2_Pos 0U /*!< TPI ITATBCTR2: ATREADY2 Position */ -#define TPI_ITATBCTR2_ATREADY2_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY2_Pos*/) /*!< TPI ITATBCTR2: ATREADY2 Mask */ - -#define TPI_ITATBCTR2_ATREADY1_Pos 0U /*!< TPI ITATBCTR2: ATREADY1 Position */ -#define TPI_ITATBCTR2_ATREADY1_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY1_Pos*/) /*!< TPI ITATBCTR2: ATREADY1 Mask */ - -/* TPI Integration ITM Data Register Definitions (FIFO1) */ -#define TPI_FIFO1_ITM_ATVALID_Pos 29U /*!< TPI FIFO1: ITM_ATVALID Position */ -#define TPI_FIFO1_ITM_ATVALID_Msk (0x3UL << TPI_FIFO1_ITM_ATVALID_Pos) /*!< TPI FIFO1: ITM_ATVALID Mask */ - -#define TPI_FIFO1_ITM_bytecount_Pos 27U /*!< TPI FIFO1: ITM_bytecount Position */ -#define TPI_FIFO1_ITM_bytecount_Msk (0x3UL << TPI_FIFO1_ITM_bytecount_Pos) /*!< TPI FIFO1: ITM_bytecount Mask */ - -#define TPI_FIFO1_ETM_ATVALID_Pos 26U /*!< TPI FIFO1: ETM_ATVALID Position */ -#define TPI_FIFO1_ETM_ATVALID_Msk (0x3UL << TPI_FIFO1_ETM_ATVALID_Pos) /*!< TPI FIFO1: ETM_ATVALID Mask */ - -#define TPI_FIFO1_ETM_bytecount_Pos 24U /*!< TPI FIFO1: ETM_bytecount Position */ -#define TPI_FIFO1_ETM_bytecount_Msk (0x3UL << TPI_FIFO1_ETM_bytecount_Pos) /*!< TPI FIFO1: ETM_bytecount Mask */ - -#define TPI_FIFO1_ITM2_Pos 16U /*!< TPI FIFO1: ITM2 Position */ -#define TPI_FIFO1_ITM2_Msk (0xFFUL << TPI_FIFO1_ITM2_Pos) /*!< TPI FIFO1: ITM2 Mask */ - -#define TPI_FIFO1_ITM1_Pos 8U /*!< TPI FIFO1: ITM1 Position */ -#define TPI_FIFO1_ITM1_Msk (0xFFUL << TPI_FIFO1_ITM1_Pos) /*!< TPI FIFO1: ITM1 Mask */ - -#define TPI_FIFO1_ITM0_Pos 0U /*!< TPI FIFO1: ITM0 Position */ -#define TPI_FIFO1_ITM0_Msk (0xFFUL /*<< TPI_FIFO1_ITM0_Pos*/) /*!< TPI FIFO1: ITM0 Mask */ - -/* TPI ITATBCTR0 Register Definitions */ -#define TPI_ITATBCTR0_ATREADY2_Pos 0U /*!< TPI ITATBCTR0: ATREADY2 Position */ -#define TPI_ITATBCTR0_ATREADY2_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY2_Pos*/) /*!< TPI ITATBCTR0: ATREADY2 Mask */ - -#define TPI_ITATBCTR0_ATREADY1_Pos 0U /*!< TPI ITATBCTR0: ATREADY1 Position */ -#define TPI_ITATBCTR0_ATREADY1_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY1_Pos*/) /*!< TPI ITATBCTR0: ATREADY1 Mask */ - -/* TPI Integration Mode Control Register Definitions */ -#define TPI_ITCTRL_Mode_Pos 0U /*!< TPI ITCTRL: Mode Position */ -#define TPI_ITCTRL_Mode_Msk (0x3UL /*<< TPI_ITCTRL_Mode_Pos*/) /*!< TPI ITCTRL: Mode Mask */ - -/* TPI DEVID Register Definitions */ -#define TPI_DEVID_NRZVALID_Pos 11U /*!< TPI DEVID: NRZVALID Position */ -#define TPI_DEVID_NRZVALID_Msk (0x1UL << TPI_DEVID_NRZVALID_Pos) /*!< TPI DEVID: NRZVALID Mask */ - -#define TPI_DEVID_MANCVALID_Pos 10U /*!< TPI DEVID: MANCVALID Position */ -#define TPI_DEVID_MANCVALID_Msk (0x1UL << TPI_DEVID_MANCVALID_Pos) /*!< TPI DEVID: MANCVALID Mask */ - -#define TPI_DEVID_PTINVALID_Pos 9U /*!< TPI DEVID: PTINVALID Position */ -#define TPI_DEVID_PTINVALID_Msk (0x1UL << TPI_DEVID_PTINVALID_Pos) /*!< TPI DEVID: PTINVALID Mask */ - -#define TPI_DEVID_MinBufSz_Pos 6U /*!< TPI DEVID: MinBufSz Position */ -#define TPI_DEVID_MinBufSz_Msk (0x7UL << TPI_DEVID_MinBufSz_Pos) /*!< TPI DEVID: MinBufSz Mask */ - -#define TPI_DEVID_AsynClkIn_Pos 5U /*!< TPI DEVID: AsynClkIn Position */ -#define TPI_DEVID_AsynClkIn_Msk (0x1UL << TPI_DEVID_AsynClkIn_Pos) /*!< TPI DEVID: AsynClkIn Mask */ - -#define TPI_DEVID_NrTraceInput_Pos 0U /*!< TPI DEVID: NrTraceInput Position */ -#define TPI_DEVID_NrTraceInput_Msk (0x1FUL /*<< TPI_DEVID_NrTraceInput_Pos*/) /*!< TPI DEVID: NrTraceInput Mask */ - -/* TPI DEVTYPE Register Definitions */ -#define TPI_DEVTYPE_SubType_Pos 4U /*!< TPI DEVTYPE: SubType Position */ -#define TPI_DEVTYPE_SubType_Msk (0xFUL /*<< TPI_DEVTYPE_SubType_Pos*/) /*!< TPI DEVTYPE: SubType Mask */ - -#define TPI_DEVTYPE_MajorType_Pos 0U /*!< TPI DEVTYPE: MajorType Position */ -#define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */ - -/*@}*/ /* end of group CMSIS_TPI */ - - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_MPU Memory Protection Unit (MPU) - \brief Type definitions for the Memory Protection Unit (MPU) - @{ - */ - -/** - \brief Structure type to access the Memory Protection Unit (MPU). - */ -typedef struct -{ - __IM uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */ - __IOM uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */ - __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region RNRber Register */ - __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */ - __IOM uint32_t RASR; /*!< Offset: 0x010 (R/W) MPU Region Attribute and Size Register */ - __IOM uint32_t RBAR_A1; /*!< Offset: 0x014 (R/W) MPU Alias 1 Region Base Address Register */ - __IOM uint32_t RASR_A1; /*!< Offset: 0x018 (R/W) MPU Alias 1 Region Attribute and Size Register */ - __IOM uint32_t RBAR_A2; /*!< Offset: 0x01C (R/W) MPU Alias 2 Region Base Address Register */ - __IOM uint32_t RASR_A2; /*!< Offset: 0x020 (R/W) MPU Alias 2 Region Attribute and Size Register */ - __IOM uint32_t RBAR_A3; /*!< Offset: 0x024 (R/W) MPU Alias 3 Region Base Address Register */ - __IOM uint32_t RASR_A3; /*!< Offset: 0x028 (R/W) MPU Alias 3 Region Attribute and Size Register */ -} MPU_Type; - -#define MPU_TYPE_RALIASES 4U - -/* MPU Type Register Definitions */ -#define MPU_TYPE_IREGION_Pos 16U /*!< MPU TYPE: IREGION Position */ -#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ - -#define MPU_TYPE_DREGION_Pos 8U /*!< MPU TYPE: DREGION Position */ -#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ - -#define MPU_TYPE_SEPARATE_Pos 0U /*!< MPU TYPE: SEPARATE Position */ -#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */ - -/* MPU Control Register Definitions */ -#define MPU_CTRL_PRIVDEFENA_Pos 2U /*!< MPU CTRL: PRIVDEFENA Position */ -#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ - -#define MPU_CTRL_HFNMIENA_Pos 1U /*!< MPU CTRL: HFNMIENA Position */ -#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ - -#define MPU_CTRL_ENABLE_Pos 0U /*!< MPU CTRL: ENABLE Position */ -#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */ - -/* MPU Region Number Register Definitions */ -#define MPU_RNR_REGION_Pos 0U /*!< MPU RNR: REGION Position */ -#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */ - -/* MPU Region Base Address Register Definitions */ -#define MPU_RBAR_ADDR_Pos 5U /*!< MPU RBAR: ADDR Position */ -#define MPU_RBAR_ADDR_Msk (0x7FFFFFFUL << MPU_RBAR_ADDR_Pos) /*!< MPU RBAR: ADDR Mask */ - -#define MPU_RBAR_VALID_Pos 4U /*!< MPU RBAR: VALID Position */ -#define MPU_RBAR_VALID_Msk (1UL << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */ - -#define MPU_RBAR_REGION_Pos 0U /*!< MPU RBAR: REGION Position */ -#define MPU_RBAR_REGION_Msk (0xFUL /*<< MPU_RBAR_REGION_Pos*/) /*!< MPU RBAR: REGION Mask */ - -/* MPU Region Attribute and Size Register Definitions */ -#define MPU_RASR_ATTRS_Pos 16U /*!< MPU RASR: MPU Region Attribute field Position */ -#define MPU_RASR_ATTRS_Msk (0xFFFFUL << MPU_RASR_ATTRS_Pos) /*!< MPU RASR: MPU Region Attribute field Mask */ - -#define MPU_RASR_XN_Pos 28U /*!< MPU RASR: ATTRS.XN Position */ -#define MPU_RASR_XN_Msk (1UL << MPU_RASR_XN_Pos) /*!< MPU RASR: ATTRS.XN Mask */ - -#define MPU_RASR_AP_Pos 24U /*!< MPU RASR: ATTRS.AP Position */ -#define MPU_RASR_AP_Msk (0x7UL << MPU_RASR_AP_Pos) /*!< MPU RASR: ATTRS.AP Mask */ - -#define MPU_RASR_TEX_Pos 19U /*!< MPU RASR: ATTRS.TEX Position */ -#define MPU_RASR_TEX_Msk (0x7UL << MPU_RASR_TEX_Pos) /*!< MPU RASR: ATTRS.TEX Mask */ - -#define MPU_RASR_S_Pos 18U /*!< MPU RASR: ATTRS.S Position */ -#define MPU_RASR_S_Msk (1UL << MPU_RASR_S_Pos) /*!< MPU RASR: ATTRS.S Mask */ - -#define MPU_RASR_C_Pos 17U /*!< MPU RASR: ATTRS.C Position */ -#define MPU_RASR_C_Msk (1UL << MPU_RASR_C_Pos) /*!< MPU RASR: ATTRS.C Mask */ - -#define MPU_RASR_B_Pos 16U /*!< MPU RASR: ATTRS.B Position */ -#define MPU_RASR_B_Msk (1UL << MPU_RASR_B_Pos) /*!< MPU RASR: ATTRS.B Mask */ - -#define MPU_RASR_SRD_Pos 8U /*!< MPU RASR: Sub-Region Disable Position */ -#define MPU_RASR_SRD_Msk (0xFFUL << MPU_RASR_SRD_Pos) /*!< MPU RASR: Sub-Region Disable Mask */ - -#define MPU_RASR_SIZE_Pos 1U /*!< MPU RASR: Region Size Field Position */ -#define MPU_RASR_SIZE_Msk (0x1FUL << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */ - -#define MPU_RASR_ENABLE_Pos 0U /*!< MPU RASR: Region enable bit Position */ -#define MPU_RASR_ENABLE_Msk (1UL /*<< MPU_RASR_ENABLE_Pos*/) /*!< MPU RASR: Region enable bit Disable Mask */ - -/*@} end of group CMSIS_MPU */ -#endif /* defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_FPU Floating Point Unit (FPU) - \brief Type definitions for the Floating Point Unit (FPU) - @{ - */ - -/** - \brief Structure type to access the Floating Point Unit (FPU). - */ -typedef struct -{ - uint32_t RESERVED0[1U]; - __IOM uint32_t FPCCR; /*!< Offset: 0x004 (R/W) Floating-Point Context Control Register */ - __IOM uint32_t FPCAR; /*!< Offset: 0x008 (R/W) Floating-Point Context Address Register */ - __IOM uint32_t FPDSCR; /*!< Offset: 0x00C (R/W) Floating-Point Default Status Control Register */ - __IM uint32_t MVFR0; /*!< Offset: 0x010 (R/ ) Media and FP Feature Register 0 */ - __IM uint32_t MVFR1; /*!< Offset: 0x014 (R/ ) Media and FP Feature Register 1 */ -} FPU_Type; - -/* Floating-Point Context Control Register Definitions */ -#define FPU_FPCCR_ASPEN_Pos 31U /*!< FPCCR: ASPEN bit Position */ -#define FPU_FPCCR_ASPEN_Msk (1UL << FPU_FPCCR_ASPEN_Pos) /*!< FPCCR: ASPEN bit Mask */ - -#define FPU_FPCCR_LSPEN_Pos 30U /*!< FPCCR: LSPEN Position */ -#define FPU_FPCCR_LSPEN_Msk (1UL << FPU_FPCCR_LSPEN_Pos) /*!< FPCCR: LSPEN bit Mask */ - -#define FPU_FPCCR_MONRDY_Pos 8U /*!< FPCCR: MONRDY Position */ -#define FPU_FPCCR_MONRDY_Msk (1UL << FPU_FPCCR_MONRDY_Pos) /*!< FPCCR: MONRDY bit Mask */ - -#define FPU_FPCCR_BFRDY_Pos 6U /*!< FPCCR: BFRDY Position */ -#define FPU_FPCCR_BFRDY_Msk (1UL << FPU_FPCCR_BFRDY_Pos) /*!< FPCCR: BFRDY bit Mask */ - -#define FPU_FPCCR_MMRDY_Pos 5U /*!< FPCCR: MMRDY Position */ -#define FPU_FPCCR_MMRDY_Msk (1UL << FPU_FPCCR_MMRDY_Pos) /*!< FPCCR: MMRDY bit Mask */ - -#define FPU_FPCCR_HFRDY_Pos 4U /*!< FPCCR: HFRDY Position */ -#define FPU_FPCCR_HFRDY_Msk (1UL << FPU_FPCCR_HFRDY_Pos) /*!< FPCCR: HFRDY bit Mask */ - -#define FPU_FPCCR_THREAD_Pos 3U /*!< FPCCR: processor mode bit Position */ -#define FPU_FPCCR_THREAD_Msk (1UL << FPU_FPCCR_THREAD_Pos) /*!< FPCCR: processor mode active bit Mask */ - -#define FPU_FPCCR_USER_Pos 1U /*!< FPCCR: privilege level bit Position */ -#define FPU_FPCCR_USER_Msk (1UL << FPU_FPCCR_USER_Pos) /*!< FPCCR: privilege level bit Mask */ - -#define FPU_FPCCR_LSPACT_Pos 0U /*!< FPCCR: Lazy state preservation active bit Position */ -#define FPU_FPCCR_LSPACT_Msk (1UL /*<< FPU_FPCCR_LSPACT_Pos*/) /*!< FPCCR: Lazy state preservation active bit Mask */ - -/* Floating-Point Context Address Register Definitions */ -#define FPU_FPCAR_ADDRESS_Pos 3U /*!< FPCAR: ADDRESS bit Position */ -#define FPU_FPCAR_ADDRESS_Msk (0x1FFFFFFFUL << FPU_FPCAR_ADDRESS_Pos) /*!< FPCAR: ADDRESS bit Mask */ - -/* Floating-Point Default Status Control Register Definitions */ -#define FPU_FPDSCR_AHP_Pos 26U /*!< FPDSCR: AHP bit Position */ -#define FPU_FPDSCR_AHP_Msk (1UL << FPU_FPDSCR_AHP_Pos) /*!< FPDSCR: AHP bit Mask */ - -#define FPU_FPDSCR_DN_Pos 25U /*!< FPDSCR: DN bit Position */ -#define FPU_FPDSCR_DN_Msk (1UL << FPU_FPDSCR_DN_Pos) /*!< FPDSCR: DN bit Mask */ - -#define FPU_FPDSCR_FZ_Pos 24U /*!< FPDSCR: FZ bit Position */ -#define FPU_FPDSCR_FZ_Msk (1UL << FPU_FPDSCR_FZ_Pos) /*!< FPDSCR: FZ bit Mask */ - -#define FPU_FPDSCR_RMode_Pos 22U /*!< FPDSCR: RMode bit Position */ -#define FPU_FPDSCR_RMode_Msk (3UL << FPU_FPDSCR_RMode_Pos) /*!< FPDSCR: RMode bit Mask */ - -/* Media and FP Feature Register 0 Definitions */ -#define FPU_MVFR0_FP_rounding_modes_Pos 28U /*!< MVFR0: FP rounding modes bits Position */ -#define FPU_MVFR0_FP_rounding_modes_Msk (0xFUL << FPU_MVFR0_FP_rounding_modes_Pos) /*!< MVFR0: FP rounding modes bits Mask */ - -#define FPU_MVFR0_Short_vectors_Pos 24U /*!< MVFR0: Short vectors bits Position */ -#define FPU_MVFR0_Short_vectors_Msk (0xFUL << FPU_MVFR0_Short_vectors_Pos) /*!< MVFR0: Short vectors bits Mask */ - -#define FPU_MVFR0_Square_root_Pos 20U /*!< MVFR0: Square root bits Position */ -#define FPU_MVFR0_Square_root_Msk (0xFUL << FPU_MVFR0_Square_root_Pos) /*!< MVFR0: Square root bits Mask */ - -#define FPU_MVFR0_Divide_Pos 16U /*!< MVFR0: Divide bits Position */ -#define FPU_MVFR0_Divide_Msk (0xFUL << FPU_MVFR0_Divide_Pos) /*!< MVFR0: Divide bits Mask */ - -#define FPU_MVFR0_FP_excep_trapping_Pos 12U /*!< MVFR0: FP exception trapping bits Position */ -#define FPU_MVFR0_FP_excep_trapping_Msk (0xFUL << FPU_MVFR0_FP_excep_trapping_Pos) /*!< MVFR0: FP exception trapping bits Mask */ - -#define FPU_MVFR0_Double_precision_Pos 8U /*!< MVFR0: Double-precision bits Position */ -#define FPU_MVFR0_Double_precision_Msk (0xFUL << FPU_MVFR0_Double_precision_Pos) /*!< MVFR0: Double-precision bits Mask */ - -#define FPU_MVFR0_Single_precision_Pos 4U /*!< MVFR0: Single-precision bits Position */ -#define FPU_MVFR0_Single_precision_Msk (0xFUL << FPU_MVFR0_Single_precision_Pos) /*!< MVFR0: Single-precision bits Mask */ - -#define FPU_MVFR0_A_SIMD_registers_Pos 0U /*!< MVFR0: A_SIMD registers bits Position */ -#define FPU_MVFR0_A_SIMD_registers_Msk (0xFUL /*<< FPU_MVFR0_A_SIMD_registers_Pos*/) /*!< MVFR0: A_SIMD registers bits Mask */ - -/* Media and FP Feature Register 1 Definitions */ -#define FPU_MVFR1_FP_fused_MAC_Pos 28U /*!< MVFR1: FP fused MAC bits Position */ -#define FPU_MVFR1_FP_fused_MAC_Msk (0xFUL << FPU_MVFR1_FP_fused_MAC_Pos) /*!< MVFR1: FP fused MAC bits Mask */ - -#define FPU_MVFR1_FP_HPFP_Pos 24U /*!< MVFR1: FP HPFP bits Position */ -#define FPU_MVFR1_FP_HPFP_Msk (0xFUL << FPU_MVFR1_FP_HPFP_Pos) /*!< MVFR1: FP HPFP bits Mask */ - -#define FPU_MVFR1_D_NaN_mode_Pos 4U /*!< MVFR1: D_NaN mode bits Position */ -#define FPU_MVFR1_D_NaN_mode_Msk (0xFUL << FPU_MVFR1_D_NaN_mode_Pos) /*!< MVFR1: D_NaN mode bits Mask */ - -#define FPU_MVFR1_FtZ_mode_Pos 0U /*!< MVFR1: FtZ mode bits Position */ -#define FPU_MVFR1_FtZ_mode_Msk (0xFUL /*<< FPU_MVFR1_FtZ_mode_Pos*/) /*!< MVFR1: FtZ mode bits Mask */ - -/*@} end of group CMSIS_FPU */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug) - \brief Type definitions for the Core Debug Registers - @{ - */ - -/** - \brief Structure type to access the Core Debug Register (CoreDebug). - */ -typedef struct -{ - __IOM uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */ - __OM uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */ - __IOM uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */ - __IOM uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */ -} CoreDebug_Type; - -/* Debug Halting Control and Status Register Definitions */ -#define CoreDebug_DHCSR_DBGKEY_Pos 16U /*!< CoreDebug DHCSR: DBGKEY Position */ -#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */ - -#define CoreDebug_DHCSR_S_RESET_ST_Pos 25U /*!< CoreDebug DHCSR: S_RESET_ST Position */ -#define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */ - -#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24U /*!< CoreDebug DHCSR: S_RETIRE_ST Position */ -#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */ - -#define CoreDebug_DHCSR_S_LOCKUP_Pos 19U /*!< CoreDebug DHCSR: S_LOCKUP Position */ -#define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */ - -#define CoreDebug_DHCSR_S_SLEEP_Pos 18U /*!< CoreDebug DHCSR: S_SLEEP Position */ -#define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */ - -#define CoreDebug_DHCSR_S_HALT_Pos 17U /*!< CoreDebug DHCSR: S_HALT Position */ -#define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */ - -#define CoreDebug_DHCSR_S_REGRDY_Pos 16U /*!< CoreDebug DHCSR: S_REGRDY Position */ -#define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */ - -#define CoreDebug_DHCSR_C_SNAPSTALL_Pos 5U /*!< CoreDebug DHCSR: C_SNAPSTALL Position */ -#define CoreDebug_DHCSR_C_SNAPSTALL_Msk (1UL << CoreDebug_DHCSR_C_SNAPSTALL_Pos) /*!< CoreDebug DHCSR: C_SNAPSTALL Mask */ - -#define CoreDebug_DHCSR_C_MASKINTS_Pos 3U /*!< CoreDebug DHCSR: C_MASKINTS Position */ -#define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */ - -#define CoreDebug_DHCSR_C_STEP_Pos 2U /*!< CoreDebug DHCSR: C_STEP Position */ -#define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */ - -#define CoreDebug_DHCSR_C_HALT_Pos 1U /*!< CoreDebug DHCSR: C_HALT Position */ -#define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */ - -#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0U /*!< CoreDebug DHCSR: C_DEBUGEN Position */ -#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL /*<< CoreDebug_DHCSR_C_DEBUGEN_Pos*/) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ - -/* Debug Core Register Selector Register Definitions */ -#define CoreDebug_DCRSR_REGWnR_Pos 16U /*!< CoreDebug DCRSR: REGWnR Position */ -#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */ - -#define CoreDebug_DCRSR_REGSEL_Pos 0U /*!< CoreDebug DCRSR: REGSEL Position */ -#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL /*<< CoreDebug_DCRSR_REGSEL_Pos*/) /*!< CoreDebug DCRSR: REGSEL Mask */ - -/* Debug Exception and Monitor Control Register Definitions */ -#define CoreDebug_DEMCR_TRCENA_Pos 24U /*!< CoreDebug DEMCR: TRCENA Position */ -#define CoreDebug_DEMCR_TRCENA_Msk (1UL << CoreDebug_DEMCR_TRCENA_Pos) /*!< CoreDebug DEMCR: TRCENA Mask */ - -#define CoreDebug_DEMCR_MON_REQ_Pos 19U /*!< CoreDebug DEMCR: MON_REQ Position */ -#define CoreDebug_DEMCR_MON_REQ_Msk (1UL << CoreDebug_DEMCR_MON_REQ_Pos) /*!< CoreDebug DEMCR: MON_REQ Mask */ - -#define CoreDebug_DEMCR_MON_STEP_Pos 18U /*!< CoreDebug DEMCR: MON_STEP Position */ -#define CoreDebug_DEMCR_MON_STEP_Msk (1UL << CoreDebug_DEMCR_MON_STEP_Pos) /*!< CoreDebug DEMCR: MON_STEP Mask */ - -#define CoreDebug_DEMCR_MON_PEND_Pos 17U /*!< CoreDebug DEMCR: MON_PEND Position */ -#define CoreDebug_DEMCR_MON_PEND_Msk (1UL << CoreDebug_DEMCR_MON_PEND_Pos) /*!< CoreDebug DEMCR: MON_PEND Mask */ - -#define CoreDebug_DEMCR_MON_EN_Pos 16U /*!< CoreDebug DEMCR: MON_EN Position */ -#define CoreDebug_DEMCR_MON_EN_Msk (1UL << CoreDebug_DEMCR_MON_EN_Pos) /*!< CoreDebug DEMCR: MON_EN Mask */ - -#define CoreDebug_DEMCR_VC_HARDERR_Pos 10U /*!< CoreDebug DEMCR: VC_HARDERR Position */ -#define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */ - -#define CoreDebug_DEMCR_VC_INTERR_Pos 9U /*!< CoreDebug DEMCR: VC_INTERR Position */ -#define CoreDebug_DEMCR_VC_INTERR_Msk (1UL << CoreDebug_DEMCR_VC_INTERR_Pos) /*!< CoreDebug DEMCR: VC_INTERR Mask */ - -#define CoreDebug_DEMCR_VC_BUSERR_Pos 8U /*!< CoreDebug DEMCR: VC_BUSERR Position */ -#define CoreDebug_DEMCR_VC_BUSERR_Msk (1UL << CoreDebug_DEMCR_VC_BUSERR_Pos) /*!< CoreDebug DEMCR: VC_BUSERR Mask */ - -#define CoreDebug_DEMCR_VC_STATERR_Pos 7U /*!< CoreDebug DEMCR: VC_STATERR Position */ -#define CoreDebug_DEMCR_VC_STATERR_Msk (1UL << CoreDebug_DEMCR_VC_STATERR_Pos) /*!< CoreDebug DEMCR: VC_STATERR Mask */ - -#define CoreDebug_DEMCR_VC_CHKERR_Pos 6U /*!< CoreDebug DEMCR: VC_CHKERR Position */ -#define CoreDebug_DEMCR_VC_CHKERR_Msk (1UL << CoreDebug_DEMCR_VC_CHKERR_Pos) /*!< CoreDebug DEMCR: VC_CHKERR Mask */ - -#define CoreDebug_DEMCR_VC_NOCPERR_Pos 5U /*!< CoreDebug DEMCR: VC_NOCPERR Position */ -#define CoreDebug_DEMCR_VC_NOCPERR_Msk (1UL << CoreDebug_DEMCR_VC_NOCPERR_Pos) /*!< CoreDebug DEMCR: VC_NOCPERR Mask */ - -#define CoreDebug_DEMCR_VC_MMERR_Pos 4U /*!< CoreDebug DEMCR: VC_MMERR Position */ -#define CoreDebug_DEMCR_VC_MMERR_Msk (1UL << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */ - -#define CoreDebug_DEMCR_VC_CORERESET_Pos 0U /*!< CoreDebug DEMCR: VC_CORERESET Position */ -#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL /*<< CoreDebug_DEMCR_VC_CORERESET_Pos*/) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ - -/*@} end of group CMSIS_CoreDebug */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_bitfield Core register bit field macros - \brief Macros for use with bit field definitions (xxx_Pos, xxx_Msk). - @{ - */ - -/** - \brief Mask and shift a bit field value for use in a register bit range. - \param[in] field Name of the register bit field. - \param[in] value Value of the bit field. This parameter is interpreted as an uint32_t type. - \return Masked and shifted value. -*/ -#define _VAL2FLD(field, value) (((uint32_t)(value) << field ## _Pos) & field ## _Msk) - -/** - \brief Mask and shift a register value to extract a bit filed value. - \param[in] field Name of the register bit field. - \param[in] value Value of register. This parameter is interpreted as an uint32_t type. - \return Masked and shifted bit field value. -*/ -#define _FLD2VAL(field, value) (((uint32_t)(value) & field ## _Msk) >> field ## _Pos) - -/*@} end of group CMSIS_core_bitfield */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_base Core Definitions - \brief Definitions for base addresses, unions, and structures. - @{ - */ - -/* Memory mapping of Core Hardware */ -#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ -#define ITM_BASE (0xE0000000UL) /*!< ITM Base Address */ -#define DWT_BASE (0xE0001000UL) /*!< DWT Base Address */ -#define TPI_BASE (0xE0040000UL) /*!< TPI Base Address */ -#define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug Base Address */ -#define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ -#define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ -#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ - -#define SCnSCB ((SCnSCB_Type *) SCS_BASE ) /*!< System control Register not in SCB */ -#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ -#define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ -#define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ -#define ITM ((ITM_Type *) ITM_BASE ) /*!< ITM configuration struct */ -#define DWT ((DWT_Type *) DWT_BASE ) /*!< DWT configuration struct */ -#define TPI ((TPI_Type *) TPI_BASE ) /*!< TPI configuration struct */ -#define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE) /*!< Core Debug configuration struct */ - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */ - #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */ -#endif - -#define FPU_BASE (SCS_BASE + 0x0F30UL) /*!< Floating Point Unit */ -#define FPU ((FPU_Type *) FPU_BASE ) /*!< Floating Point Unit */ - -/*@} */ - - - -/******************************************************************************* - * Hardware Abstraction Layer - Core Function Interface contains: - - Core NVIC Functions - - Core SysTick Functions - - Core Debug Functions - - Core Register Access Functions - ******************************************************************************/ -/** - \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference -*/ - - - -/* ########################## NVIC functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_NVICFunctions NVIC Functions - \brief Functions that manage interrupts and exceptions via the NVIC. - @{ - */ - -#ifdef CMSIS_NVIC_VIRTUAL - #ifndef CMSIS_NVIC_VIRTUAL_HEADER_FILE - #define CMSIS_NVIC_VIRTUAL_HEADER_FILE "cmsis_nvic_virtual.h" - #endif - #include CMSIS_NVIC_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetPriorityGrouping __NVIC_SetPriorityGrouping - #define NVIC_GetPriorityGrouping __NVIC_GetPriorityGrouping - #define NVIC_EnableIRQ __NVIC_EnableIRQ - #define NVIC_GetEnableIRQ __NVIC_GetEnableIRQ - #define NVIC_DisableIRQ __NVIC_DisableIRQ - #define NVIC_GetPendingIRQ __NVIC_GetPendingIRQ - #define NVIC_SetPendingIRQ __NVIC_SetPendingIRQ - #define NVIC_ClearPendingIRQ __NVIC_ClearPendingIRQ - #define NVIC_GetActive __NVIC_GetActive - #define NVIC_SetPriority __NVIC_SetPriority - #define NVIC_GetPriority __NVIC_GetPriority - #define NVIC_SystemReset __NVIC_SystemReset -#endif /* CMSIS_NVIC_VIRTUAL */ - -#ifdef CMSIS_VECTAB_VIRTUAL - #ifndef CMSIS_VECTAB_VIRTUAL_HEADER_FILE - #define CMSIS_VECTAB_VIRTUAL_HEADER_FILE "cmsis_vectab_virtual.h" - #endif - #include CMSIS_VECTAB_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetVector __NVIC_SetVector - #define NVIC_GetVector __NVIC_GetVector -#endif /* (CMSIS_VECTAB_VIRTUAL) */ - -#define NVIC_USER_IRQ_OFFSET 16 - - -/* The following EXC_RETURN values are saved the LR on exception entry */ -#define EXC_RETURN_HANDLER (0xFFFFFFF1UL) /* return to Handler mode, uses MSP after return */ -#define EXC_RETURN_THREAD_MSP (0xFFFFFFF9UL) /* return to Thread mode, uses MSP after return */ -#define EXC_RETURN_THREAD_PSP (0xFFFFFFFDUL) /* return to Thread mode, uses PSP after return */ -#define EXC_RETURN_HANDLER_FPU (0xFFFFFFE1UL) /* return to Handler mode, uses MSP after return, restore floating-point state */ -#define EXC_RETURN_THREAD_MSP_FPU (0xFFFFFFE9UL) /* return to Thread mode, uses MSP after return, restore floating-point state */ -#define EXC_RETURN_THREAD_PSP_FPU (0xFFFFFFEDUL) /* return to Thread mode, uses PSP after return, restore floating-point state */ - - -/** - \brief Set Priority Grouping - \details Sets the priority grouping field using the required unlock sequence. - The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field. - Only values from 0..7 are used. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Priority grouping field. - */ -__STATIC_INLINE void __NVIC_SetPriorityGrouping(uint32_t PriorityGroup) -{ - uint32_t reg_value; - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - - reg_value = SCB->AIRCR; /* read old register configuration */ - reg_value &= ~((uint32_t)(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk)); /* clear bits to change */ - reg_value = (reg_value | - ((uint32_t)0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - (PriorityGroupTmp << SCB_AIRCR_PRIGROUP_Pos) ); /* Insert write key and priority group */ - SCB->AIRCR = reg_value; -} - - -/** - \brief Get Priority Grouping - \details Reads the priority grouping field from the NVIC Interrupt Controller. - \return Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field). - */ -__STATIC_INLINE uint32_t __NVIC_GetPriorityGrouping(void) -{ - return ((uint32_t)((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos)); -} - - -/** - \brief Enable Interrupt - \details Enables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_EnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Interrupt Enable status - \details Returns a device specific interrupt enable status from the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt is not enabled. - \return 1 Interrupt is enabled. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetEnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Disable Interrupt - \details Disables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_DisableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - __DSB(); - __ISB(); - } -} - - -/** - \brief Get Pending Interrupt - \details Reads the NVIC pending register and returns the pending bit for the specified device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not pending. - \return 1 Interrupt status is pending. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Pending Interrupt - \details Sets the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_SetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Clear Pending Interrupt - \details Clears the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_ClearPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Active Interrupt - \details Reads the active register in the NVIC and returns the active bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not active. - \return 1 Interrupt status is active. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetActive(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Interrupt Priority - \details Sets the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \param [in] priority Priority to set. - \note The priority cannot be set for every processor exception. - */ -__STATIC_INLINE void __NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->IP[((uint32_t)IRQn)] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); - } - else - { - SCB->SHP[(((uint32_t)IRQn) & 0xFUL)-4UL] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); - } -} - - -/** - \brief Get Interrupt Priority - \details Reads the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Interrupt Priority. - Value is aligned automatically to the implemented priority bits of the microcontroller. - */ -__STATIC_INLINE uint32_t __NVIC_GetPriority(IRQn_Type IRQn) -{ - - if ((int32_t)(IRQn) >= 0) - { - return(((uint32_t)NVIC->IP[((uint32_t)IRQn)] >> (8U - __NVIC_PRIO_BITS))); - } - else - { - return(((uint32_t)SCB->SHP[(((uint32_t)IRQn) & 0xFUL)-4UL] >> (8U - __NVIC_PRIO_BITS))); - } -} - - -/** - \brief Encode Priority - \details Encodes the priority for an interrupt with the given priority group, - preemptive priority value, and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Used priority group. - \param [in] PreemptPriority Preemptive priority value (starting from 0). - \param [in] SubPriority Subpriority value (starting from 0). - \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority(). - */ -__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - return ( - ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | - ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) - ); -} - - -/** - \brief Decode Priority - \details Decodes an interrupt priority value with a given priority group to - preemptive priority value and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. - \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority(). - \param [in] PriorityGroup Used priority group. - \param [out] pPreemptPriority Preemptive priority value (starting from 0). - \param [out] pSubPriority Subpriority value (starting from 0). - */ -__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* const pPreemptPriority, uint32_t* const pSubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL); - *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL); -} - - -/** - \brief Set Interrupt Vector - \details Sets an interrupt vector in SRAM based interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - VTOR must been relocated to SRAM before. - \param [in] IRQn Interrupt number - \param [in] vector Address of interrupt handler function - */ -__STATIC_INLINE void __NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) -{ - uint32_t *vectors = (uint32_t *)SCB->VTOR; - vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET] = vector; -} - - -/** - \brief Get Interrupt Vector - \details Reads an interrupt vector from interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Address of interrupt handler function - */ -__STATIC_INLINE uint32_t __NVIC_GetVector(IRQn_Type IRQn) -{ - uint32_t *vectors = (uint32_t *)SCB->VTOR; - return vectors[(int32_t)IRQn + NVIC_USER_IRQ_OFFSET]; -} - - -/** - \brief System Reset - \details Initiates a system reset request to reset the MCU. - */ -__NO_RETURN __STATIC_INLINE void __NVIC_SystemReset(void) -{ - __DSB(); /* Ensure all outstanding memory accesses included - buffered write are completed before reset */ - SCB->AIRCR = (uint32_t)((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) | - SCB_AIRCR_SYSRESETREQ_Msk ); /* Keep priority group unchanged */ - __DSB(); /* Ensure completion of memory access */ - - for(;;) /* wait until reset */ - { - __NOP(); - } -} - -/*@} end of CMSIS_Core_NVICFunctions */ - -/* ########################## MPU functions #################################### */ - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - -#include "mpu_armv7.h" - -#endif - - -/* ########################## FPU functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_FpuFunctions FPU Functions - \brief Function that provides FPU type. - @{ - */ - -/** - \brief get FPU type - \details returns the FPU type - \returns - - \b 0: No FPU - - \b 1: Single precision FPU - - \b 2: Double + Single precision FPU - */ -__STATIC_INLINE uint32_t SCB_GetFPUType(void) -{ - uint32_t mvfr0; - - mvfr0 = FPU->MVFR0; - if ((mvfr0 & (FPU_MVFR0_Single_precision_Msk | FPU_MVFR0_Double_precision_Msk)) == 0x020U) - { - return 1U; /* Single precision FPU */ - } - else - { - return 0U; /* No FPU */ - } -} - - -/*@} end of CMSIS_Core_FpuFunctions */ - - - -/* ################################## SysTick function ############################################ */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_SysTickFunctions SysTick Functions - \brief Functions that configure the System. - @{ - */ - -#if defined (__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U) - -/** - \brief System Tick Configuration - \details Initializes the System Timer and its interrupt, and starts the System Tick Timer. - Counter is in free running mode to generate periodic interrupts. - \param [in] ticks Number of ticks between two interrupts. - \return 0 Function succeeded. - \return 1 Function failed. - \note When the variable __Vendor_SysTickConfig is set to 1, then the - function SysTick_Config is not included. In this case, the file device.h - must contain a vendor-specific implementation of this function. - */ -__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) -{ - if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) - { - return (1UL); /* Reload value impossible */ - } - - SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ - NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ - SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ - SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | - SysTick_CTRL_TICKINT_Msk | - SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ - return (0UL); /* Function successful */ -} - -#endif - -/*@} end of CMSIS_Core_SysTickFunctions */ - - - -/* ##################################### Debug In/Output function ########################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_core_DebugFunctions ITM Functions - \brief Functions that access the ITM debug interface. - @{ - */ - -extern volatile int32_t ITM_RxBuffer; /*!< External variable to receive characters. */ -#define ITM_RXBUFFER_EMPTY ((int32_t)0x5AA55AA5U) /*!< Value identifying \ref ITM_RxBuffer is ready for next character. */ - - -/** - \brief ITM Send Character - \details Transmits a character via the ITM channel 0, and - \li Just returns when no debugger is connected that has booked the output. - \li Is blocking when a debugger is connected, but the previous character sent has not been transmitted. - \param [in] ch Character to transmit. - \returns Character to transmit. - */ -__STATIC_INLINE uint32_t ITM_SendChar (uint32_t ch) -{ - if (((ITM->TCR & ITM_TCR_ITMENA_Msk) != 0UL) && /* ITM enabled */ - ((ITM->TER & 1UL ) != 0UL) ) /* ITM Port #0 enabled */ - { - while (ITM->PORT[0U].u32 == 0UL) - { - __NOP(); - } - ITM->PORT[0U].u8 = (uint8_t)ch; - } - return (ch); -} - - -/** - \brief ITM Receive Character - \details Inputs a character via the external variable \ref ITM_RxBuffer. - \return Received character. - \return -1 No character pending. - */ -__STATIC_INLINE int32_t ITM_ReceiveChar (void) -{ - int32_t ch = -1; /* no character available */ - - if (ITM_RxBuffer != ITM_RXBUFFER_EMPTY) - { - ch = ITM_RxBuffer; - ITM_RxBuffer = ITM_RXBUFFER_EMPTY; /* ready for next character */ - } - - return (ch); -} - - -/** - \brief ITM Check Character - \details Checks whether a character is pending for reading in the variable \ref ITM_RxBuffer. - \return 0 No character available. - \return 1 Character available. - */ -__STATIC_INLINE int32_t ITM_CheckChar (void) -{ - - if (ITM_RxBuffer == ITM_RXBUFFER_EMPTY) - { - return (0); /* no character available */ - } - else - { - return (1); /* character available */ - } -} - -/*@} end of CMSIS_core_DebugFunctions */ - - - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_CM4_H_DEPENDANT */ - -#endif /* __CMSIS_GENERIC */ diff --git a/body/board/inc/core_cmFunc.h b/body/board/inc/core_cmFunc.h deleted file mode 100644 index 652a48a..0000000 --- a/body/board/inc/core_cmFunc.h +++ /dev/null @@ -1,87 +0,0 @@ -/**************************************************************************//** - * @file core_cmFunc.h - * @brief CMSIS Cortex-M Core Function Access Header File - * @version V4.30 - * @date 20. October 2015 - ******************************************************************************/ -/* Copyright (c) 2009 - 2015 ARM LIMITED - - All rights reserved. - Redistribution and use in source and binary forms, with or without - modification, are permitted provided that the following conditions are met: - - Redistributions of source code must retain the above copyright - notice, this list of conditions and the following disclaimer. - - Redistributions in binary form must reproduce the above copyright - notice, this list of conditions and the following disclaimer in the - documentation and/or other materials provided with the distribution. - - Neither the name of ARM nor the names of its contributors may be used - to endorse or promote products derived from this software without - specific prior written permission. - * - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE - LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - POSSIBILITY OF SUCH DAMAGE. - ---------------------------------------------------------------------------*/ - - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef __CORE_CMFUNC_H -#define __CORE_CMFUNC_H - - -/* ########################### Core Function Access ########################### */ -/** \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions - @{ -*/ - -/*------------------ RealView Compiler -----------------*/ -#if defined ( __CC_ARM ) - #include "cmsis_armcc.h" - -/*------------------ ARM Compiler V6 -------------------*/ -#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #include "cmsis_armcc_V6.h" - -/*------------------ GNU Compiler ----------------------*/ -#elif defined ( __GNUC__ ) - #include "cmsis_gcc.h" - -/*------------------ ICC Compiler ----------------------*/ -#elif defined ( __ICCARM__ ) - #include - -/*------------------ TI CCS Compiler -------------------*/ -#elif defined ( __TMS470__ ) - #include - -/*------------------ TASKING Compiler ------------------*/ -#elif defined ( __TASKING__ ) - /* - * The CMSIS functions have been implemented as intrinsics in the compiler. - * Please use "carm -?i" to get an up to date list of all intrinsics, - * Including the CMSIS ones. - */ - -/*------------------ COSMIC Compiler -------------------*/ -#elif defined ( __CSMC__ ) - #include - -#endif - -/*@} end of CMSIS_Core_RegAccFunctions */ - -#endif /* __CORE_CMFUNC_H */ diff --git a/body/board/inc/core_cmInstr.h b/body/board/inc/core_cmInstr.h deleted file mode 100644 index f474b0e..0000000 --- a/body/board/inc/core_cmInstr.h +++ /dev/null @@ -1,87 +0,0 @@ -/**************************************************************************//** - * @file core_cmInstr.h - * @brief CMSIS Cortex-M Core Instruction Access Header File - * @version V4.30 - * @date 20. October 2015 - ******************************************************************************/ -/* Copyright (c) 2009 - 2015 ARM LIMITED - - All rights reserved. - Redistribution and use in source and binary forms, with or without - modification, are permitted provided that the following conditions are met: - - Redistributions of source code must retain the above copyright - notice, this list of conditions and the following disclaimer. - - Redistributions in binary form must reproduce the above copyright - notice, this list of conditions and the following disclaimer in the - documentation and/or other materials provided with the distribution. - - Neither the name of ARM nor the names of its contributors may be used - to endorse or promote products derived from this software without - specific prior written permission. - * - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE - LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - POSSIBILITY OF SUCH DAMAGE. - ---------------------------------------------------------------------------*/ - - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef __CORE_CMINSTR_H -#define __CORE_CMINSTR_H - - -/* ########################## Core Instruction Access ######################### */ -/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface - Access to dedicated instructions - @{ -*/ - -/*------------------ RealView Compiler -----------------*/ -#if defined ( __CC_ARM ) - #include "cmsis_armcc.h" - -/*------------------ ARM Compiler V6 -------------------*/ -#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #include "cmsis_armcc_V6.h" - -/*------------------ GNU Compiler ----------------------*/ -#elif defined ( __GNUC__ ) - #include "cmsis_gcc.h" - -/*------------------ ICC Compiler ----------------------*/ -#elif defined ( __ICCARM__ ) - #include - -/*------------------ TI CCS Compiler -------------------*/ -#elif defined ( __TMS470__ ) - #include - -/*------------------ TASKING Compiler ------------------*/ -#elif defined ( __TASKING__ ) - /* - * The CMSIS functions have been implemented as intrinsics in the compiler. - * Please use "carm -?i" to get an up to date list of all intrinsics, - * Including the CMSIS ones. - */ - -/*------------------ COSMIC Compiler -------------------*/ -#elif defined ( __CSMC__ ) - #include - -#endif - -/*@}*/ /* end of group CMSIS_Core_InstructionInterface */ - -#endif /* __CORE_CMINSTR_H */ diff --git a/body/board/inc/core_cmSimd.h b/body/board/inc/core_cmSimd.h deleted file mode 100644 index 66bf5c2..0000000 --- a/body/board/inc/core_cmSimd.h +++ /dev/null @@ -1,96 +0,0 @@ -/**************************************************************************//** - * @file core_cmSimd.h - * @brief CMSIS Cortex-M SIMD Header File - * @version V4.30 - * @date 20. October 2015 - ******************************************************************************/ -/* Copyright (c) 2009 - 2015 ARM LIMITED - - All rights reserved. - Redistribution and use in source and binary forms, with or without - modification, are permitted provided that the following conditions are met: - - Redistributions of source code must retain the above copyright - notice, this list of conditions and the following disclaimer. - - Redistributions in binary form must reproduce the above copyright - notice, this list of conditions and the following disclaimer in the - documentation and/or other materials provided with the distribution. - - Neither the name of ARM nor the names of its contributors may be used - to endorse or promote products derived from this software without - specific prior written permission. - * - THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS AND CONTRIBUTORS BE - LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - POSSIBILITY OF SUCH DAMAGE. - ---------------------------------------------------------------------------*/ - - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef __CORE_CMSIMD_H -#define __CORE_CMSIMD_H - -#ifdef __cplusplus - extern "C" { -#endif - - -/* ################### Compiler specific Intrinsics ########################### */ -/** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics - Access to dedicated SIMD instructions - @{ -*/ - -/*------------------ RealView Compiler -----------------*/ -#if defined ( __CC_ARM ) - #include "cmsis_armcc.h" - -/*------------------ ARM Compiler V6 -------------------*/ -#elif defined(__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #include "cmsis_armcc_V6.h" - -/*------------------ GNU Compiler ----------------------*/ -#elif defined ( __GNUC__ ) - #include "cmsis_gcc.h" - -/*------------------ ICC Compiler ----------------------*/ -#elif defined ( __ICCARM__ ) - #include - -/*------------------ TI CCS Compiler -------------------*/ -#elif defined ( __TMS470__ ) - #include - -/*------------------ TASKING Compiler ------------------*/ -#elif defined ( __TASKING__ ) - /* - * The CMSIS functions have been implemented as intrinsics in the compiler. - * Please use "carm -?i" to get an up to date list of all intrinsics, - * Including the CMSIS ones. - */ - -/*------------------ COSMIC Compiler -------------------*/ -#elif defined ( __CSMC__ ) - #include - -#endif - -/*@} end of group CMSIS_SIMD_intrinsics */ - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_CMSIMD_H */ diff --git a/body/board/inc/mpu_armv7.h b/body/board/inc/mpu_armv7.h deleted file mode 100644 index 0142203..0000000 --- a/body/board/inc/mpu_armv7.h +++ /dev/null @@ -1,270 +0,0 @@ -/****************************************************************************** - * @file mpu_armv7.h - * @brief CMSIS MPU API for Armv7-M MPU - * @version V5.0.4 - * @date 10. January 2018 - ******************************************************************************/ -/* - * Copyright (c) 2017-2018 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef ARM_MPU_ARMV7_H -#define ARM_MPU_ARMV7_H - -#define ARM_MPU_REGION_SIZE_32B ((uint8_t)0x04U) ///!< MPU Region Size 32 Bytes -#define ARM_MPU_REGION_SIZE_64B ((uint8_t)0x05U) ///!< MPU Region Size 64 Bytes -#define ARM_MPU_REGION_SIZE_128B ((uint8_t)0x06U) ///!< MPU Region Size 128 Bytes -#define ARM_MPU_REGION_SIZE_256B ((uint8_t)0x07U) ///!< MPU Region Size 256 Bytes -#define ARM_MPU_REGION_SIZE_512B ((uint8_t)0x08U) ///!< MPU Region Size 512 Bytes -#define ARM_MPU_REGION_SIZE_1KB ((uint8_t)0x09U) ///!< MPU Region Size 1 KByte -#define ARM_MPU_REGION_SIZE_2KB ((uint8_t)0x0AU) ///!< MPU Region Size 2 KBytes -#define ARM_MPU_REGION_SIZE_4KB ((uint8_t)0x0BU) ///!< MPU Region Size 4 KBytes -#define ARM_MPU_REGION_SIZE_8KB ((uint8_t)0x0CU) ///!< MPU Region Size 8 KBytes -#define ARM_MPU_REGION_SIZE_16KB ((uint8_t)0x0DU) ///!< MPU Region Size 16 KBytes -#define ARM_MPU_REGION_SIZE_32KB ((uint8_t)0x0EU) ///!< MPU Region Size 32 KBytes -#define ARM_MPU_REGION_SIZE_64KB ((uint8_t)0x0FU) ///!< MPU Region Size 64 KBytes -#define ARM_MPU_REGION_SIZE_128KB ((uint8_t)0x10U) ///!< MPU Region Size 128 KBytes -#define ARM_MPU_REGION_SIZE_256KB ((uint8_t)0x11U) ///!< MPU Region Size 256 KBytes -#define ARM_MPU_REGION_SIZE_512KB ((uint8_t)0x12U) ///!< MPU Region Size 512 KBytes -#define ARM_MPU_REGION_SIZE_1MB ((uint8_t)0x13U) ///!< MPU Region Size 1 MByte -#define ARM_MPU_REGION_SIZE_2MB ((uint8_t)0x14U) ///!< MPU Region Size 2 MBytes -#define ARM_MPU_REGION_SIZE_4MB ((uint8_t)0x15U) ///!< MPU Region Size 4 MBytes -#define ARM_MPU_REGION_SIZE_8MB ((uint8_t)0x16U) ///!< MPU Region Size 8 MBytes -#define ARM_MPU_REGION_SIZE_16MB ((uint8_t)0x17U) ///!< MPU Region Size 16 MBytes -#define ARM_MPU_REGION_SIZE_32MB ((uint8_t)0x18U) ///!< MPU Region Size 32 MBytes -#define ARM_MPU_REGION_SIZE_64MB ((uint8_t)0x19U) ///!< MPU Region Size 64 MBytes -#define ARM_MPU_REGION_SIZE_128MB ((uint8_t)0x1AU) ///!< MPU Region Size 128 MBytes -#define ARM_MPU_REGION_SIZE_256MB ((uint8_t)0x1BU) ///!< MPU Region Size 256 MBytes -#define ARM_MPU_REGION_SIZE_512MB ((uint8_t)0x1CU) ///!< MPU Region Size 512 MBytes -#define ARM_MPU_REGION_SIZE_1GB ((uint8_t)0x1DU) ///!< MPU Region Size 1 GByte -#define ARM_MPU_REGION_SIZE_2GB ((uint8_t)0x1EU) ///!< MPU Region Size 2 GBytes -#define ARM_MPU_REGION_SIZE_4GB ((uint8_t)0x1FU) ///!< MPU Region Size 4 GBytes - -#define ARM_MPU_AP_NONE 0U ///!< MPU Access Permission no access -#define ARM_MPU_AP_PRIV 1U ///!< MPU Access Permission privileged access only -#define ARM_MPU_AP_URO 2U ///!< MPU Access Permission unprivileged access read-only -#define ARM_MPU_AP_FULL 3U ///!< MPU Access Permission full access -#define ARM_MPU_AP_PRO 5U ///!< MPU Access Permission privileged access read-only -#define ARM_MPU_AP_RO 6U ///!< MPU Access Permission read-only access - -/** MPU Region Base Address Register Value -* -* \param Region The region to be configured, number 0 to 15. -* \param BaseAddress The base address for the region. -*/ -#define ARM_MPU_RBAR(Region, BaseAddress) \ - (((BaseAddress) & MPU_RBAR_ADDR_Msk) | \ - ((Region) & MPU_RBAR_REGION_Msk) | \ - (MPU_RBAR_VALID_Msk)) - -/** -* MPU Memory Access Attributes -* -* \param TypeExtField Type extension field, allows you to configure memory access type, for example strongly ordered, peripheral. -* \param IsShareable Region is shareable between multiple bus masters. -* \param IsCacheable Region is cacheable, i.e. its value may be kept in cache. -* \param IsBufferable Region is bufferable, i.e. using write-back caching. Cacheable but non-bufferable regions use write-through policy. -*/ -#define ARM_MPU_ACCESS_(TypeExtField, IsShareable, IsCacheable, IsBufferable) \ - ((((TypeExtField ) << MPU_RASR_TEX_Pos) & MPU_RASR_TEX_Msk) | \ - (((IsShareable ) << MPU_RASR_S_Pos) & MPU_RASR_S_Msk) | \ - (((IsCacheable ) << MPU_RASR_C_Pos) & MPU_RASR_C_Msk) | \ - (((IsBufferable ) << MPU_RASR_B_Pos) & MPU_RASR_B_Msk)) - -/** -* MPU Region Attribute and Size Register Value -* -* \param DisableExec Instruction access disable bit, 1= disable instruction fetches. -* \param AccessPermission Data access permissions, allows you to configure read/write access for User and Privileged mode. -* \param AccessAttributes Memory access attribution, see \ref ARM_MPU_ACCESS_. -* \param SubRegionDisable Sub-region disable field. -* \param Size Region size of the region to be configured, for example 4K, 8K. -*/ -#define ARM_MPU_RASR_EX(DisableExec, AccessPermission, AccessAttributes, SubRegionDisable, Size) \ - ((((DisableExec ) << MPU_RASR_XN_Pos) & MPU_RASR_XN_Msk) | \ - (((AccessPermission) << MPU_RASR_AP_Pos) & MPU_RASR_AP_Msk) | \ - (((AccessAttributes) ) & (MPU_RASR_TEX_Msk | MPU_RASR_S_Msk | MPU_RASR_C_Msk | MPU_RASR_B_Msk))) - -/** -* MPU Region Attribute and Size Register Value -* -* \param DisableExec Instruction access disable bit, 1= disable instruction fetches. -* \param AccessPermission Data access permissions, allows you to configure read/write access for User and Privileged mode. -* \param TypeExtField Type extension field, allows you to configure memory access type, for example strongly ordered, peripheral. -* \param IsShareable Region is shareable between multiple bus masters. -* \param IsCacheable Region is cacheable, i.e. its value may be kept in cache. -* \param IsBufferable Region is bufferable, i.e. using write-back caching. Cacheable but non-bufferable regions use write-through policy. -* \param SubRegionDisable Sub-region disable field. -* \param Size Region size of the region to be configured, for example 4K, 8K. -*/ -#define ARM_MPU_RASR(DisableExec, AccessPermission, TypeExtField, IsShareable, IsCacheable, IsBufferable, SubRegionDisable, Size) \ - ARM_MPU_RASR_EX(DisableExec, AccessPermission, ARM_MPU_ACCESS_(TypeExtField, IsShareable, IsCacheable, IsBufferable), SubRegionDisable, Size) - -/** -* MPU Memory Access Attribute for strongly ordered memory. -* - TEX: 000b -* - Shareable -* - Non-cacheable -* - Non-bufferable -*/ -#define ARM_MPU_ACCESS_ORDERED ARM_MPU_ACCESS_(0U, 1U, 0U, 0U) - -/** -* MPU Memory Access Attribute for device memory. -* - TEX: 000b (if non-shareable) or 010b (if shareable) -* - Shareable or non-shareable -* - Non-cacheable -* - Bufferable (if shareable) or non-bufferable (if non-shareable) -* -* \param IsShareable Configures the device memory as shareable or non-shareable. -*/ -#define ARM_MPU_ACCESS_DEVICE(IsShareable) ((IsShareable) ? ARM_MPU_ACCESS_(0U, 1U, 0U, 1U) : ARM_MPU_ACCESS_(2U, 0U, 0U, 0U)) - -/** -* MPU Memory Access Attribute for normal memory. -* - TEX: 1BBb (reflecting outer cacheability rules) -* - Shareable or non-shareable -* - Cacheable or non-cacheable (reflecting inner cacheability rules) -* - Bufferable or non-bufferable (reflecting inner cacheability rules) -* -* \param OuterCp Configures the outer cache policy. -* \param InnerCp Configures the inner cache policy. -* \param IsShareable Configures the memory as shareable or non-shareable. -*/ -#define ARM_MPU_ACCESS_NORMAL(OuterCp, InnerCp, IsShareable) ARM_MPU_ACCESS_((4U | (OuterCp)), IsShareable, ((InnerCp) & 2U), ((InnerCp) & 1U)) - -/** -* MPU Memory Access Attribute non-cacheable policy. -*/ -#define ARM_MPU_CACHEP_NOCACHE 0U - -/** -* MPU Memory Access Attribute write-back, write and read allocate policy. -*/ -#define ARM_MPU_CACHEP_WB_WRA 1U - -/** -* MPU Memory Access Attribute write-through, no write allocate policy. -*/ -#define ARM_MPU_CACHEP_WT_NWA 2U - -/** -* MPU Memory Access Attribute write-back, no write allocate policy. -*/ -#define ARM_MPU_CACHEP_WB_NWA 3U - - -/** -* Struct for a single MPU Region -*/ -typedef struct { - uint32_t RBAR; //!< The region base address register value (RBAR) - uint32_t RASR; //!< The region attribute and size register value (RASR) \ref MPU_RASR -} ARM_MPU_Region_t; - -/** Enable the MPU. -* \param MPU_Control Default access permissions for unconfigured regions. -*/ -__STATIC_INLINE void ARM_MPU_Enable(uint32_t MPU_Control) -{ - __DSB(); - __ISB(); - MPU->CTRL = MPU_Control | MPU_CTRL_ENABLE_Msk; -#ifdef SCB_SHCSR_MEMFAULTENA_Msk - SCB->SHCSR |= SCB_SHCSR_MEMFAULTENA_Msk; -#endif -} - -/** Disable the MPU. -*/ -__STATIC_INLINE void ARM_MPU_Disable(void) -{ - __DSB(); - __ISB(); -#ifdef SCB_SHCSR_MEMFAULTENA_Msk - SCB->SHCSR &= ~SCB_SHCSR_MEMFAULTENA_Msk; -#endif - MPU->CTRL &= ~MPU_CTRL_ENABLE_Msk; -} - -/** Clear and disable the given MPU region. -* \param rnr Region number to be cleared. -*/ -__STATIC_INLINE void ARM_MPU_ClrRegion(uint32_t rnr) -{ - MPU->RNR = rnr; - MPU->RASR = 0U; -} - -/** Configure an MPU region. -* \param rbar Value for RBAR register. -* \param rsar Value for RSAR register. -*/ -__STATIC_INLINE void ARM_MPU_SetRegion(uint32_t rbar, uint32_t rasr) -{ - MPU->RBAR = rbar; - MPU->RASR = rasr; -} - -/** Configure the given MPU region. -* \param rnr Region number to be configured. -* \param rbar Value for RBAR register. -* \param rsar Value for RSAR register. -*/ -__STATIC_INLINE void ARM_MPU_SetRegionEx(uint32_t rnr, uint32_t rbar, uint32_t rasr) -{ - MPU->RNR = rnr; - MPU->RBAR = rbar; - MPU->RASR = rasr; -} - -/** Memcopy with strictly ordered memory access, e.g. for register targets. -* \param dst Destination data is copied to. -* \param src Source data is copied from. -* \param len Amount of data words to be copied. -*/ -__STATIC_INLINE void orderedCpy(volatile uint32_t* dst, const uint32_t* __RESTRICT src, uint32_t len) -{ - uint32_t i; - for (i = 0U; i < len; ++i) - { - dst[i] = src[i]; - } -} - -/** Load the given number of MPU regions from a table. -* \param table Pointer to the MPU configuration table. -* \param cnt Amount of regions to be configured. -*/ -__STATIC_INLINE void ARM_MPU_Load(ARM_MPU_Region_t const* table, uint32_t cnt) -{ - const uint32_t rowWordSize = sizeof(ARM_MPU_Region_t)/4U; - while (cnt > MPU_TYPE_RALIASES) { - orderedCpy(&(MPU->RBAR), &(table->RBAR), MPU_TYPE_RALIASES*rowWordSize); - table += MPU_TYPE_RALIASES; - cnt -= MPU_TYPE_RALIASES; - } - orderedCpy(&(MPU->RBAR), &(table->RBAR), cnt*rowWordSize); -} - -#endif diff --git a/body/board/inc/mpu_armv8.h b/body/board/inc/mpu_armv8.h deleted file mode 100644 index 62571da..0000000 --- a/body/board/inc/mpu_armv8.h +++ /dev/null @@ -1,333 +0,0 @@ -/****************************************************************************** - * @file mpu_armv8.h - * @brief CMSIS MPU API for Armv8-M MPU - * @version V5.0.4 - * @date 10. January 2018 - ******************************************************************************/ -/* - * Copyright (c) 2017-2018 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef ARM_MPU_ARMV8_H -#define ARM_MPU_ARMV8_H - -/** \brief Attribute for device memory (outer only) */ -#define ARM_MPU_ATTR_DEVICE ( 0U ) - -/** \brief Attribute for non-cacheable, normal memory */ -#define ARM_MPU_ATTR_NON_CACHEABLE ( 4U ) - -/** \brief Attribute for normal memory (outer and inner) -* \param NT Non-Transient: Set to 1 for non-transient data. -* \param WB Write-Back: Set to 1 to use write-back update policy. -* \param RA Read Allocation: Set to 1 to use cache allocation on read miss. -* \param WA Write Allocation: Set to 1 to use cache allocation on write miss. -*/ -#define ARM_MPU_ATTR_MEMORY_(NT, WB, RA, WA) \ - (((NT & 1U) << 3U) | ((WB & 1U) << 2U) | ((RA & 1U) << 1U) | (WA & 1U)) - -/** \brief Device memory type non Gathering, non Re-ordering, non Early Write Acknowledgement */ -#define ARM_MPU_ATTR_DEVICE_nGnRnE (0U) - -/** \brief Device memory type non Gathering, non Re-ordering, Early Write Acknowledgement */ -#define ARM_MPU_ATTR_DEVICE_nGnRE (1U) - -/** \brief Device memory type non Gathering, Re-ordering, Early Write Acknowledgement */ -#define ARM_MPU_ATTR_DEVICE_nGRE (2U) - -/** \brief Device memory type Gathering, Re-ordering, Early Write Acknowledgement */ -#define ARM_MPU_ATTR_DEVICE_GRE (3U) - -/** \brief Memory Attribute -* \param O Outer memory attributes -* \param I O == ARM_MPU_ATTR_DEVICE: Device memory attributes, else: Inner memory attributes -*/ -#define ARM_MPU_ATTR(O, I) (((O & 0xFU) << 4U) | (((O & 0xFU) != 0U) ? (I & 0xFU) : ((I & 0x3U) << 2U))) - -/** \brief Normal memory non-shareable */ -#define ARM_MPU_SH_NON (0U) - -/** \brief Normal memory outer shareable */ -#define ARM_MPU_SH_OUTER (2U) - -/** \brief Normal memory inner shareable */ -#define ARM_MPU_SH_INNER (3U) - -/** \brief Memory access permissions -* \param RO Read-Only: Set to 1 for read-only memory. -* \param NP Non-Privileged: Set to 1 for non-privileged memory. -*/ -#define ARM_MPU_AP_(RO, NP) (((RO & 1U) << 1U) | (NP & 1U)) - -/** \brief Region Base Address Register value -* \param BASE The base address bits [31:5] of a memory region. The value is zero extended. Effective address gets 32 byte aligned. -* \param SH Defines the Shareability domain for this memory region. -* \param RO Read-Only: Set to 1 for a read-only memory region. -* \param NP Non-Privileged: Set to 1 for a non-privileged memory region. -* \oaram XN eXecute Never: Set to 1 for a non-executable memory region. -*/ -#define ARM_MPU_RBAR(BASE, SH, RO, NP, XN) \ - ((BASE & MPU_RBAR_BASE_Msk) | \ - ((SH << MPU_RBAR_SH_Pos) & MPU_RBAR_SH_Msk) | \ - ((ARM_MPU_AP_(RO, NP) << MPU_RBAR_AP_Pos) & MPU_RBAR_AP_Msk) | \ - ((XN << MPU_RBAR_XN_Pos) & MPU_RBAR_XN_Msk)) - -/** \brief Region Limit Address Register value -* \param LIMIT The limit address bits [31:5] for this memory region. The value is one extended. -* \param IDX The attribute index to be associated with this memory region. -*/ -#define ARM_MPU_RLAR(LIMIT, IDX) \ - ((LIMIT & MPU_RLAR_LIMIT_Msk) | \ - ((IDX << MPU_RLAR_AttrIndx_Pos) & MPU_RLAR_AttrIndx_Msk) | \ - (MPU_RLAR_EN_Msk)) - -/** -* Struct for a single MPU Region -*/ -typedef struct { - uint32_t RBAR; /*!< Region Base Address Register value */ - uint32_t RLAR; /*!< Region Limit Address Register value */ -} ARM_MPU_Region_t; - -/** Enable the MPU. -* \param MPU_Control Default access permissions for unconfigured regions. -*/ -__STATIC_INLINE void ARM_MPU_Enable(uint32_t MPU_Control) -{ - __DSB(); - __ISB(); - MPU->CTRL = MPU_Control | MPU_CTRL_ENABLE_Msk; -#ifdef SCB_SHCSR_MEMFAULTENA_Msk - SCB->SHCSR |= SCB_SHCSR_MEMFAULTENA_Msk; -#endif -} - -/** Disable the MPU. -*/ -__STATIC_INLINE void ARM_MPU_Disable(void) -{ - __DSB(); - __ISB(); -#ifdef SCB_SHCSR_MEMFAULTENA_Msk - SCB->SHCSR &= ~SCB_SHCSR_MEMFAULTENA_Msk; -#endif - MPU->CTRL &= ~MPU_CTRL_ENABLE_Msk; -} - -#ifdef MPU_NS -/** Enable the Non-secure MPU. -* \param MPU_Control Default access permissions for unconfigured regions. -*/ -__STATIC_INLINE void ARM_MPU_Enable_NS(uint32_t MPU_Control) -{ - __DSB(); - __ISB(); - MPU_NS->CTRL = MPU_Control | MPU_CTRL_ENABLE_Msk; -#ifdef SCB_SHCSR_MEMFAULTENA_Msk - SCB_NS->SHCSR |= SCB_SHCSR_MEMFAULTENA_Msk; -#endif -} - -/** Disable the Non-secure MPU. -*/ -__STATIC_INLINE void ARM_MPU_Disable_NS(void) -{ - __DSB(); - __ISB(); -#ifdef SCB_SHCSR_MEMFAULTENA_Msk - SCB_NS->SHCSR &= ~SCB_SHCSR_MEMFAULTENA_Msk; -#endif - MPU_NS->CTRL &= ~MPU_CTRL_ENABLE_Msk; -} -#endif - -/** Set the memory attribute encoding to the given MPU. -* \param mpu Pointer to the MPU to be configured. -* \param idx The attribute index to be set [0-7] -* \param attr The attribute value to be set. -*/ -__STATIC_INLINE void ARM_MPU_SetMemAttrEx(MPU_Type* mpu, uint8_t idx, uint8_t attr) -{ - const uint8_t reg = idx / 4U; - const uint32_t pos = ((idx % 4U) * 8U); - const uint32_t mask = 0xFFU << pos; - - if (reg >= (sizeof(mpu->MAIR) / sizeof(mpu->MAIR[0]))) { - return; // invalid index - } - - mpu->MAIR[reg] = ((mpu->MAIR[reg] & ~mask) | ((attr << pos) & mask)); -} - -/** Set the memory attribute encoding. -* \param idx The attribute index to be set [0-7] -* \param attr The attribute value to be set. -*/ -__STATIC_INLINE void ARM_MPU_SetMemAttr(uint8_t idx, uint8_t attr) -{ - ARM_MPU_SetMemAttrEx(MPU, idx, attr); -} - -#ifdef MPU_NS -/** Set the memory attribute encoding to the Non-secure MPU. -* \param idx The attribute index to be set [0-7] -* \param attr The attribute value to be set. -*/ -__STATIC_INLINE void ARM_MPU_SetMemAttr_NS(uint8_t idx, uint8_t attr) -{ - ARM_MPU_SetMemAttrEx(MPU_NS, idx, attr); -} -#endif - -/** Clear and disable the given MPU region of the given MPU. -* \param mpu Pointer to MPU to be used. -* \param rnr Region number to be cleared. -*/ -__STATIC_INLINE void ARM_MPU_ClrRegionEx(MPU_Type* mpu, uint32_t rnr) -{ - mpu->RNR = rnr; - mpu->RLAR = 0U; -} - -/** Clear and disable the given MPU region. -* \param rnr Region number to be cleared. -*/ -__STATIC_INLINE void ARM_MPU_ClrRegion(uint32_t rnr) -{ - ARM_MPU_ClrRegionEx(MPU, rnr); -} - -#ifdef MPU_NS -/** Clear and disable the given Non-secure MPU region. -* \param rnr Region number to be cleared. -*/ -__STATIC_INLINE void ARM_MPU_ClrRegion_NS(uint32_t rnr) -{ - ARM_MPU_ClrRegionEx(MPU_NS, rnr); -} -#endif - -/** Configure the given MPU region of the given MPU. -* \param mpu Pointer to MPU to be used. -* \param rnr Region number to be configured. -* \param rbar Value for RBAR register. -* \param rlar Value for RLAR register. -*/ -__STATIC_INLINE void ARM_MPU_SetRegionEx(MPU_Type* mpu, uint32_t rnr, uint32_t rbar, uint32_t rlar) -{ - mpu->RNR = rnr; - mpu->RBAR = rbar; - mpu->RLAR = rlar; -} - -/** Configure the given MPU region. -* \param rnr Region number to be configured. -* \param rbar Value for RBAR register. -* \param rlar Value for RLAR register. -*/ -__STATIC_INLINE void ARM_MPU_SetRegion(uint32_t rnr, uint32_t rbar, uint32_t rlar) -{ - ARM_MPU_SetRegionEx(MPU, rnr, rbar, rlar); -} - -#ifdef MPU_NS -/** Configure the given Non-secure MPU region. -* \param rnr Region number to be configured. -* \param rbar Value for RBAR register. -* \param rlar Value for RLAR register. -*/ -__STATIC_INLINE void ARM_MPU_SetRegion_NS(uint32_t rnr, uint32_t rbar, uint32_t rlar) -{ - ARM_MPU_SetRegionEx(MPU_NS, rnr, rbar, rlar); -} -#endif - -/** Memcopy with strictly ordered memory access, e.g. for register targets. -* \param dst Destination data is copied to. -* \param src Source data is copied from. -* \param len Amount of data words to be copied. -*/ -__STATIC_INLINE void orderedCpy(volatile uint32_t* dst, const uint32_t* __RESTRICT src, uint32_t len) -{ - uint32_t i; - for (i = 0U; i < len; ++i) - { - dst[i] = src[i]; - } -} - -/** Load the given number of MPU regions from a table to the given MPU. -* \param mpu Pointer to the MPU registers to be used. -* \param rnr First region number to be configured. -* \param table Pointer to the MPU configuration table. -* \param cnt Amount of regions to be configured. -*/ -__STATIC_INLINE void ARM_MPU_LoadEx(MPU_Type* mpu, uint32_t rnr, ARM_MPU_Region_t const* table, uint32_t cnt) -{ - const uint32_t rowWordSize = sizeof(ARM_MPU_Region_t)/4U; - if (cnt == 1U) { - mpu->RNR = rnr; - orderedCpy(&(mpu->RBAR), &(table->RBAR), rowWordSize); - } else { - uint32_t rnrBase = rnr & ~(MPU_TYPE_RALIASES-1U); - uint32_t rnrOffset = rnr % MPU_TYPE_RALIASES; - - mpu->RNR = rnrBase; - while ((rnrOffset + cnt) > MPU_TYPE_RALIASES) { - uint32_t c = MPU_TYPE_RALIASES - rnrOffset; - orderedCpy(&(mpu->RBAR)+(rnrOffset*2U), &(table->RBAR), c*rowWordSize); - table += c; - cnt -= c; - rnrOffset = 0U; - rnrBase += MPU_TYPE_RALIASES; - mpu->RNR = rnrBase; - } - - orderedCpy(&(mpu->RBAR)+(rnrOffset*2U), &(table->RBAR), cnt*rowWordSize); - } -} - -/** Load the given number of MPU regions from a table. -* \param rnr First region number to be configured. -* \param table Pointer to the MPU configuration table. -* \param cnt Amount of regions to be configured. -*/ -__STATIC_INLINE void ARM_MPU_Load(uint32_t rnr, ARM_MPU_Region_t const* table, uint32_t cnt) -{ - ARM_MPU_LoadEx(MPU, rnr, table, cnt); -} - -#ifdef MPU_NS -/** Load the given number of MPU regions from a table to the Non-secure MPU. -* \param rnr First region number to be configured. -* \param table Pointer to the MPU configuration table. -* \param cnt Amount of regions to be configured. -*/ -__STATIC_INLINE void ARM_MPU_Load_NS(uint32_t rnr, ARM_MPU_Region_t const* table, uint32_t cnt) -{ - ARM_MPU_LoadEx(MPU_NS, rnr, table, cnt); -} -#endif - -#endif - diff --git a/body/board/inc/stm32f413xx.h b/body/board/inc/stm32f413xx.h deleted file mode 100644 index e9db50f..0000000 --- a/body/board/inc/stm32f413xx.h +++ /dev/null @@ -1,15467 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f413xx.h - * @author MCD Application Team - * @brief CMSIS STM32F413xx Device Peripheral Access Layer Header File. - * - * This file contains: - * - Data structures and the address mapping for all peripherals - * - peripherals registers declarations and bits definition - * - Macros to access peripheral’s registers hardware - * - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/** @addtogroup CMSIS_Device - * @{ - */ - -/** @addtogroup stm32f413xx - * @{ - */ - -#ifndef __STM32F413xx_H -#define __STM32F413xx_H - -#ifdef __cplusplus - extern "C" { -#endif /* __cplusplus */ - -/** @addtogroup Configuration_section_for_CMSIS - * @{ - */ - -/** - * @brief Configuration of the Cortex-M4 Processor and Core Peripherals - */ -#define __CM4_REV 0x0001U /*!< Core revision r0p1 */ -#define __MPU_PRESENT 1U /*!< STM32F4XX provides an MPU */ -#define __NVIC_PRIO_BITS 4U /*!< STM32F4XX uses 4 Bits for the Priority Levels */ -#define __Vendor_SysTickConfig 0U /*!< Set to 1 if different SysTick Config is used */ -#define __FPU_PRESENT 1U /*!< FPU present */ - -/** - * @} - */ - -/** @addtogroup Peripheral_interrupt_number_definition - * @{ - */ - -/** - * @brief STM32F4XX Interrupt Number Definition, according to the selected device - * in @ref Library_configuration_section - */ -typedef enum -{ -/****** Cortex-M4 Processor Exceptions Numbers ****************************************************************/ - NonMaskableInt_IRQn = -14, /*!< 2 Non Maskable Interrupt */ - MemoryManagement_IRQn = -12, /*!< 4 Cortex-M4 Memory Management Interrupt */ - BusFault_IRQn = -11, /*!< 5 Cortex-M4 Bus Fault Interrupt */ - UsageFault_IRQn = -10, /*!< 6 Cortex-M4 Usage Fault Interrupt */ - SVCall_IRQn = -5, /*!< 11 Cortex-M4 SV Call Interrupt */ - DebugMonitor_IRQn = -4, /*!< 12 Cortex-M4 Debug Monitor Interrupt */ - PendSV_IRQn = -2, /*!< 14 Cortex-M4 Pend SV Interrupt */ - SysTick_IRQn = -1, /*!< 15 Cortex-M4 System Tick Interrupt */ -/****** STM32 specific Interrupt Numbers **********************************************************************/ - WWDG_IRQn = 0, /*!< Window WatchDog Interrupt */ - PVD_IRQn = 1, /*!< PVD through EXTI Line detection Interrupt */ - TAMP_STAMP_IRQn = 2, /*!< Tamper and TimeStamp interrupts through the EXTI line */ - RTC_WKUP_IRQn = 3, /*!< RTC Wakeup interrupt through the EXTI line */ - FLASH_IRQn = 4, /*!< FLASH global Interrupt */ - RCC_IRQn = 5, /*!< RCC global Interrupt */ - EXTI0_IRQn = 6, /*!< EXTI Line0 Interrupt */ - EXTI1_IRQn = 7, /*!< EXTI Line1 Interrupt */ - EXTI2_IRQn = 8, /*!< EXTI Line2 Interrupt */ - EXTI3_IRQn = 9, /*!< EXTI Line3 Interrupt */ - EXTI4_IRQn = 10, /*!< EXTI Line4 Interrupt */ - DMA1_Stream0_IRQn = 11, /*!< DMA1 Stream 0 global Interrupt */ - DMA1_Stream1_IRQn = 12, /*!< DMA1 Stream 1 global Interrupt */ - DMA1_Stream2_IRQn = 13, /*!< DMA1 Stream 2 global Interrupt */ - DMA1_Stream3_IRQn = 14, /*!< DMA1 Stream 3 global Interrupt */ - DMA1_Stream4_IRQn = 15, /*!< DMA1 Stream 4 global Interrupt */ - DMA1_Stream5_IRQn = 16, /*!< DMA1 Stream 5 global Interrupt */ - DMA1_Stream6_IRQn = 17, /*!< DMA1 Stream 6 global Interrupt */ - ADC_IRQn = 18, /*!< ADC1, ADC2 and ADC3 global Interrupts */ - CAN1_TX_IRQn = 19, /*!< CAN1 TX Interrupt */ - CAN1_RX0_IRQn = 20, /*!< CAN1 RX0 Interrupt */ - CAN1_RX1_IRQn = 21, /*!< CAN1 RX1 Interrupt */ - CAN1_SCE_IRQn = 22, /*!< CAN1 SCE Interrupt */ - EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ - TIM1_BRK_TIM9_IRQn = 24, /*!< TIM1 Break interrupt and TIM9 global interrupt */ - TIM1_UP_TIM10_IRQn = 25, /*!< TIM1 Update Interrupt and TIM10 global interrupt */ - TIM1_TRG_COM_TIM11_IRQn = 26, /*!< TIM1 Trigger and Commutation Interrupt and TIM11 global interrupt */ - TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ - TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ - TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ - TIM4_IRQn = 30, /*!< TIM4 global Interrupt */ - I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ - I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ - I2C2_EV_IRQn = 33, /*!< I2C2 Event Interrupt */ - I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */ - SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ - SPI2_IRQn = 36, /*!< SPI2 global Interrupt */ - USART1_IRQn = 37, /*!< USART1 global Interrupt */ - USART2_IRQn = 38, /*!< USART2 global Interrupt */ - USART3_IRQn = 39, /*!< USART3 global Interrupt */ - EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ - RTC_Alarm_IRQn = 41, /*!< RTC Alarm (A and B) through EXTI Line Interrupt */ - OTG_FS_WKUP_IRQn = 42, /*!< USB OTG FS Wakeup through EXTI line interrupt */ - TIM8_BRK_TIM12_IRQn = 43, /*!< TIM8 Break Interrupt and TIM12 global interrupt */ - TIM8_UP_TIM13_IRQn = 44, /*!< TIM8 Update Interrupt and TIM13 global interrupt */ - TIM8_TRG_COM_TIM14_IRQn = 45, /*!< TIM8 Trigger and Commutation Interrupt and TIM14 global interrupt */ - TIM8_CC_IRQn = 46, /*!< TIM8 Capture Compare global interrupt */ - DMA1_Stream7_IRQn = 47, /*!< DMA1 Stream7 Interrupt */ - SDIO_IRQn = 49, /*!< SDIO global Interrupt */ - TIM5_IRQn = 50, /*!< TIM5 global Interrupt */ - SPI3_IRQn = 51, /*!< SPI3 global Interrupt */ - UART4_IRQn = 52, /*!< UART4 global Interrupt */ - UART5_IRQn = 53, /*!< UART5 global Interrupt */ - TIM6_DAC_IRQn = 54, /*!< TIM6 global and DAC1&2 underrun error interrupts */ - TIM7_IRQn = 55, /*!< TIM7 global interrupt */ - DMA2_Stream0_IRQn = 56, /*!< DMA2 Stream 0 global Interrupt */ - DMA2_Stream1_IRQn = 57, /*!< DMA2 Stream 1 global Interrupt */ - DMA2_Stream2_IRQn = 58, /*!< DMA2 Stream 2 global Interrupt */ - DMA2_Stream3_IRQn = 59, /*!< DMA2 Stream 3 global Interrupt */ - DMA2_Stream4_IRQn = 60, /*!< DMA2 Stream 4 global Interrupt */ - DFSDM1_FLT0_IRQn = 61, /*!< DFSDM1 Filter 0 global Interrupt */ - DFSDM1_FLT1_IRQn = 62, /*!< DFSDM1 Filter 1 global Interrupt */ - CAN2_TX_IRQn = 63, /*!< CAN2 TX Interrupt */ - CAN2_RX0_IRQn = 64, /*!< CAN2 RX0 Interrupt */ - CAN2_RX1_IRQn = 65, /*!< CAN2 RX1 Interrupt */ - CAN2_SCE_IRQn = 66, /*!< CAN2 SCE Interrupt */ - OTG_FS_IRQn = 67, /*!< USB OTG FS global Interrupt */ - DMA2_Stream5_IRQn = 68, /*!< DMA2 Stream 5 global interrupt */ - DMA2_Stream6_IRQn = 69, /*!< DMA2 Stream 6 global interrupt */ - DMA2_Stream7_IRQn = 70, /*!< DMA2 Stream 7 global interrupt */ - USART6_IRQn = 71, /*!< USART6 global interrupt */ - I2C3_EV_IRQn = 72, /*!< I2C3 event interrupt */ - I2C3_ER_IRQn = 73, /*!< I2C3 error interrupt */ - CAN3_TX_IRQn = 74, /*!< CAN3 TX Interrupt */ - CAN3_RX0_IRQn = 75, /*!< CAN3 RX0 Interrupt */ - CAN3_RX1_IRQn = 76, /*!< CAN3 RX1 Interrupt */ - CAN3_SCE_IRQn = 77, /*!< CAN3 SCE Interrupt */ - RNG_IRQn = 80, /*!< RNG global Interrupt */ - FPU_IRQn = 81, /*!< FPU global interrupt */ - UART7_IRQn = 82, /*!< UART7 global interrupt */ - UART8_IRQn = 83, /*!< UART8 global interrupt */ - SPI4_IRQn = 84, /*!< SPI4 global Interrupt */ - SPI5_IRQn = 85, /*!< SPI5 global Interrupt */ - SAI1_IRQn = 87, /*!< SAI1 global Interrupt */ - UART9_IRQn = 88, /*!< UART9 global Interrupt */ - UART10_IRQn = 89, /*!< UART10 global Interrupt */ - QUADSPI_IRQn = 92, /*!< QuadSPI global Interrupt */ - FMPI2C1_EV_IRQn = 95, /*!< FMPI2C1 Event Interrupt */ - FMPI2C1_ER_IRQn = 96, /*!< FMPI2C1 Error Interrupt */ - LPTIM1_IRQn = 97, /*!< LP TIM1 interrupt */ - DFSDM2_FLT0_IRQn = 98, /*!< DFSDM2 Filter 0 global Interrupt */ - DFSDM2_FLT1_IRQn = 99, /*!< DFSDM2 Filter 1 global Interrupt */ - DFSDM2_FLT2_IRQn = 100, /*!< DFSDM2 Filter 2 global Interrupt */ - DFSDM2_FLT3_IRQn = 101 /*!< DFSDM2 Filter 3 global Interrupt */ -} IRQn_Type; - -/** - * @} - */ - -#include "core_cm4.h" /* Cortex-M4 processor and core peripherals */ -#include "system_stm32f4xx.h" -#include - -/** @addtogroup Peripheral_registers_structures - * @{ - */ - -/** - * @brief Analog to Digital Converter - */ - -typedef struct -{ - __IO uint32_t SR; /*!< ADC status register, Address offset: 0x00 */ - __IO uint32_t CR1; /*!< ADC control register 1, Address offset: 0x04 */ - __IO uint32_t CR2; /*!< ADC control register 2, Address offset: 0x08 */ - __IO uint32_t SMPR1; /*!< ADC sample time register 1, Address offset: 0x0C */ - __IO uint32_t SMPR2; /*!< ADC sample time register 2, Address offset: 0x10 */ - __IO uint32_t JOFR1; /*!< ADC injected channel data offset register 1, Address offset: 0x14 */ - __IO uint32_t JOFR2; /*!< ADC injected channel data offset register 2, Address offset: 0x18 */ - __IO uint32_t JOFR3; /*!< ADC injected channel data offset register 3, Address offset: 0x1C */ - __IO uint32_t JOFR4; /*!< ADC injected channel data offset register 4, Address offset: 0x20 */ - __IO uint32_t HTR; /*!< ADC watchdog higher threshold register, Address offset: 0x24 */ - __IO uint32_t LTR; /*!< ADC watchdog lower threshold register, Address offset: 0x28 */ - __IO uint32_t SQR1; /*!< ADC regular sequence register 1, Address offset: 0x2C */ - __IO uint32_t SQR2; /*!< ADC regular sequence register 2, Address offset: 0x30 */ - __IO uint32_t SQR3; /*!< ADC regular sequence register 3, Address offset: 0x34 */ - __IO uint32_t JSQR; /*!< ADC injected sequence register, Address offset: 0x38*/ - __IO uint32_t JDR1; /*!< ADC injected data register 1, Address offset: 0x3C */ - __IO uint32_t JDR2; /*!< ADC injected data register 2, Address offset: 0x40 */ - __IO uint32_t JDR3; /*!< ADC injected data register 3, Address offset: 0x44 */ - __IO uint32_t JDR4; /*!< ADC injected data register 4, Address offset: 0x48 */ - __IO uint32_t DR; /*!< ADC regular data register, Address offset: 0x4C */ -} ADC_TypeDef; - -typedef struct -{ - __IO uint32_t CSR; /*!< ADC Common status register, Address offset: ADC1 base address + 0x300 */ - __IO uint32_t CCR; /*!< ADC common control register, Address offset: ADC1 base address + 0x304 */ - __IO uint32_t CDR; /*!< ADC common regular data register for dual - AND triple modes, Address offset: ADC1 base address + 0x308 */ -} ADC_Common_TypeDef; - - -/** - * @brief Controller Area Network TxMailBox - */ - -typedef struct -{ - __IO uint32_t TIR; /*!< CAN TX mailbox identifier register */ - __IO uint32_t TDTR; /*!< CAN mailbox data length control and time stamp register */ - __IO uint32_t TDLR; /*!< CAN mailbox data low register */ - __IO uint32_t TDHR; /*!< CAN mailbox data high register */ -} CAN_TxMailBox_TypeDef; - -/** - * @brief Controller Area Network FIFOMailBox - */ - -typedef struct -{ - __IO uint32_t RIR; /*!< CAN receive FIFO mailbox identifier register */ - __IO uint32_t RDTR; /*!< CAN receive FIFO mailbox data length control and time stamp register */ - __IO uint32_t RDLR; /*!< CAN receive FIFO mailbox data low register */ - __IO uint32_t RDHR; /*!< CAN receive FIFO mailbox data high register */ -} CAN_FIFOMailBox_TypeDef; - -/** - * @brief Controller Area Network FilterRegister - */ - -typedef struct -{ - __IO uint32_t FR1; /*!< CAN Filter bank register 1 */ - __IO uint32_t FR2; /*!< CAN Filter bank register 1 */ -} CAN_FilterRegister_TypeDef; - -/** - * @brief Controller Area Network - */ - -typedef struct -{ - __IO uint32_t MCR; /*!< CAN master control register, Address offset: 0x00 */ - __IO uint32_t MSR; /*!< CAN master status register, Address offset: 0x04 */ - __IO uint32_t TSR; /*!< CAN transmit status register, Address offset: 0x08 */ - __IO uint32_t RF0R; /*!< CAN receive FIFO 0 register, Address offset: 0x0C */ - __IO uint32_t RF1R; /*!< CAN receive FIFO 1 register, Address offset: 0x10 */ - __IO uint32_t IER; /*!< CAN interrupt enable register, Address offset: 0x14 */ - __IO uint32_t ESR; /*!< CAN error status register, Address offset: 0x18 */ - __IO uint32_t BTR; /*!< CAN bit timing register, Address offset: 0x1C */ - uint32_t RESERVED0[88]; /*!< Reserved, 0x020 - 0x17F */ - CAN_TxMailBox_TypeDef sTxMailBox[3]; /*!< CAN Tx MailBox, Address offset: 0x180 - 0x1AC */ - CAN_FIFOMailBox_TypeDef sFIFOMailBox[2]; /*!< CAN FIFO MailBox, Address offset: 0x1B0 - 0x1CC */ - uint32_t RESERVED1[12]; /*!< Reserved, 0x1D0 - 0x1FF */ - __IO uint32_t FMR; /*!< CAN filter master register, Address offset: 0x200 */ - __IO uint32_t FM1R; /*!< CAN filter mode register, Address offset: 0x204 */ - uint32_t RESERVED2; /*!< Reserved, 0x208 */ - __IO uint32_t FS1R; /*!< CAN filter scale register, Address offset: 0x20C */ - uint32_t RESERVED3; /*!< Reserved, 0x210 */ - __IO uint32_t FFA1R; /*!< CAN filter FIFO assignment register, Address offset: 0x214 */ - uint32_t RESERVED4; /*!< Reserved, 0x218 */ - __IO uint32_t FA1R; /*!< CAN filter activation register, Address offset: 0x21C */ - uint32_t RESERVED5[8]; /*!< Reserved, 0x220-0x23F */ - CAN_FilterRegister_TypeDef sFilterRegister[28]; /*!< CAN Filter Register, Address offset: 0x240-0x31C */ -} CAN_TypeDef; - -/** - * @brief CRC calculation unit - */ - -typedef struct -{ - __IO uint32_t DR; /*!< CRC Data register, Address offset: 0x00 */ - __IO uint8_t IDR; /*!< CRC Independent data register, Address offset: 0x04 */ - uint8_t RESERVED0; /*!< Reserved, 0x05 */ - uint16_t RESERVED1; /*!< Reserved, 0x06 */ - __IO uint32_t CR; /*!< CRC Control register, Address offset: 0x08 */ -} CRC_TypeDef; - -/** - * @brief DFSDM module registers - */ -typedef struct -{ - __IO uint32_t FLTCR1; /*!< DFSDM control register1, Address offset: 0x100 */ - __IO uint32_t FLTCR2; /*!< DFSDM control register2, Address offset: 0x104 */ - __IO uint32_t FLTISR; /*!< DFSDM interrupt and status register, Address offset: 0x108 */ - __IO uint32_t FLTICR; /*!< DFSDM interrupt flag clear register, Address offset: 0x10C */ - __IO uint32_t FLTJCHGR; /*!< DFSDM injected channel group selection register, Address offset: 0x110 */ - __IO uint32_t FLTFCR; /*!< DFSDM filter control register, Address offset: 0x114 */ - __IO uint32_t FLTJDATAR; /*!< DFSDM data register for injected group, Address offset: 0x118 */ - __IO uint32_t FLTRDATAR; /*!< DFSDM data register for regular group, Address offset: 0x11C */ - __IO uint32_t FLTAWHTR; /*!< DFSDM analog watchdog high threshold register, Address offset: 0x120 */ - __IO uint32_t FLTAWLTR; /*!< DFSDM analog watchdog low threshold register, Address offset: 0x124 */ - __IO uint32_t FLTAWSR; /*!< DFSDM analog watchdog status register Address offset: 0x128 */ - __IO uint32_t FLTAWCFR; /*!< DFSDM analog watchdog clear flag register Address offset: 0x12C */ - __IO uint32_t FLTEXMAX; /*!< DFSDM extreme detector maximum register, Address offset: 0x130 */ - __IO uint32_t FLTEXMIN; /*!< DFSDM extreme detector minimum register Address offset: 0x134 */ - __IO uint32_t FLTCNVTIMR; /*!< DFSDM conversion timer, Address offset: 0x138 */ -} DFSDM_Filter_TypeDef; - -/** - * @brief DFSDM channel configuration registers - */ -typedef struct -{ - __IO uint32_t CHCFGR1; /*!< DFSDM channel configuration register1, Address offset: 0x00 */ - __IO uint32_t CHCFGR2; /*!< DFSDM channel configuration register2, Address offset: 0x04 */ - __IO uint32_t CHAWSCDR; /*!< DFSDM channel analog watchdog and - short circuit detector register, Address offset: 0x08 */ - __IO uint32_t CHWDATAR; /*!< DFSDM channel watchdog filter data register, Address offset: 0x0C */ - __IO uint32_t CHDATINR; /*!< DFSDM channel data input register, Address offset: 0x10 */ -} DFSDM_Channel_TypeDef; - -/** - * @brief Digital to Analog Converter - */ - -typedef struct -{ - __IO uint32_t CR; /*!< DAC control register, Address offset: 0x00 */ - __IO uint32_t SWTRIGR; /*!< DAC software trigger register, Address offset: 0x04 */ - __IO uint32_t DHR12R1; /*!< DAC channel1 12-bit right-aligned data holding register, Address offset: 0x08 */ - __IO uint32_t DHR12L1; /*!< DAC channel1 12-bit left aligned data holding register, Address offset: 0x0C */ - __IO uint32_t DHR8R1; /*!< DAC channel1 8-bit right aligned data holding register, Address offset: 0x10 */ - __IO uint32_t DHR12R2; /*!< DAC channel2 12-bit right aligned data holding register, Address offset: 0x14 */ - __IO uint32_t DHR12L2; /*!< DAC channel2 12-bit left aligned data holding register, Address offset: 0x18 */ - __IO uint32_t DHR8R2; /*!< DAC channel2 8-bit right-aligned data holding register, Address offset: 0x1C */ - __IO uint32_t DHR12RD; /*!< Dual DAC 12-bit right-aligned data holding register, Address offset: 0x20 */ - __IO uint32_t DHR12LD; /*!< DUAL DAC 12-bit left aligned data holding register, Address offset: 0x24 */ - __IO uint32_t DHR8RD; /*!< DUAL DAC 8-bit right aligned data holding register, Address offset: 0x28 */ - __IO uint32_t DOR1; /*!< DAC channel1 data output register, Address offset: 0x2C */ - __IO uint32_t DOR2; /*!< DAC channel2 data output register, Address offset: 0x30 */ - __IO uint32_t SR; /*!< DAC status register, Address offset: 0x34 */ -} DAC_TypeDef; - -/** - * @brief Debug MCU - */ - -typedef struct -{ - __IO uint32_t IDCODE; /*!< MCU device ID code, Address offset: 0x00 */ - __IO uint32_t CR; /*!< Debug MCU configuration register, Address offset: 0x04 */ - __IO uint32_t APB1FZ; /*!< Debug MCU APB1 freeze register, Address offset: 0x08 */ - __IO uint32_t APB2FZ; /*!< Debug MCU APB2 freeze register, Address offset: 0x0C */ -}DBGMCU_TypeDef; - - -/** - * @brief DMA Controller - */ - -typedef struct -{ - __IO uint32_t CR; /*!< DMA stream x configuration register */ - __IO uint32_t NDTR; /*!< DMA stream x number of data register */ - __IO uint32_t PAR; /*!< DMA stream x peripheral address register */ - __IO uint32_t M0AR; /*!< DMA stream x memory 0 address register */ - __IO uint32_t M1AR; /*!< DMA stream x memory 1 address register */ - __IO uint32_t FCR; /*!< DMA stream x FIFO control register */ -} DMA_Stream_TypeDef; - -typedef struct -{ - __IO uint32_t LISR; /*!< DMA low interrupt status register, Address offset: 0x00 */ - __IO uint32_t HISR; /*!< DMA high interrupt status register, Address offset: 0x04 */ - __IO uint32_t LIFCR; /*!< DMA low interrupt flag clear register, Address offset: 0x08 */ - __IO uint32_t HIFCR; /*!< DMA high interrupt flag clear register, Address offset: 0x0C */ -} DMA_TypeDef; - -/** - * @brief External Interrupt/Event Controller - */ - -typedef struct -{ - __IO uint32_t IMR; /*!< EXTI Interrupt mask register, Address offset: 0x00 */ - __IO uint32_t EMR; /*!< EXTI Event mask register, Address offset: 0x04 */ - __IO uint32_t RTSR; /*!< EXTI Rising trigger selection register, Address offset: 0x08 */ - __IO uint32_t FTSR; /*!< EXTI Falling trigger selection register, Address offset: 0x0C */ - __IO uint32_t SWIER; /*!< EXTI Software interrupt event register, Address offset: 0x10 */ - __IO uint32_t PR; /*!< EXTI Pending register, Address offset: 0x14 */ -} EXTI_TypeDef; - -/** - * @brief FLASH Registers - */ - -typedef struct -{ - __IO uint32_t ACR; /*!< FLASH access control register, Address offset: 0x00 */ - __IO uint32_t KEYR; /*!< FLASH key register, Address offset: 0x04 */ - __IO uint32_t OPTKEYR; /*!< FLASH option key register, Address offset: 0x08 */ - __IO uint32_t SR; /*!< FLASH status register, Address offset: 0x0C */ - __IO uint32_t CR; /*!< FLASH control register, Address offset: 0x10 */ - __IO uint32_t OPTCR; /*!< FLASH option control register , Address offset: 0x14 */ - __IO uint32_t OPTCR1; /*!< FLASH option control register 1, Address offset: 0x18 */ -} FLASH_TypeDef; - - - -/** - * @brief Flexible Static Memory Controller - */ - -typedef struct -{ - __IO uint32_t BTCR[8]; /*!< NOR/PSRAM chip-select control register(BCR) and chip-select timing register(BTR), Address offset: 0x00-1C */ -} FSMC_Bank1_TypeDef; - -/** - * @brief Flexible Static Memory Controller Bank1E - */ - -typedef struct -{ - __IO uint32_t BWTR[7]; /*!< NOR/PSRAM write timing registers, Address offset: 0x104-0x11C */ -} FSMC_Bank1E_TypeDef; -/** - * @brief General Purpose I/O - */ - -typedef struct -{ - __IO uint32_t MODER; /*!< GPIO port mode register, Address offset: 0x00 */ - __IO uint32_t OTYPER; /*!< GPIO port output type register, Address offset: 0x04 */ - __IO uint32_t OSPEEDR; /*!< GPIO port output speed register, Address offset: 0x08 */ - __IO uint32_t PUPDR; /*!< GPIO port pull-up/pull-down register, Address offset: 0x0C */ - __IO uint32_t IDR; /*!< GPIO port input data register, Address offset: 0x10 */ - __IO uint32_t ODR; /*!< GPIO port output data register, Address offset: 0x14 */ - __IO uint32_t BSRR; /*!< GPIO port bit set/reset register, Address offset: 0x18 */ - __IO uint32_t LCKR; /*!< GPIO port configuration lock register, Address offset: 0x1C */ - __IO uint32_t AFR[2]; /*!< GPIO alternate function registers, Address offset: 0x20-0x24 */ -} GPIO_TypeDef; - -/** - * @brief System configuration controller - */ - -typedef struct -{ - __IO uint32_t MEMRMP; /*!< SYSCFG memory remap register, Address offset: 0x00 */ - __IO uint32_t PMC; /*!< SYSCFG peripheral mode configuration register, Address offset: 0x04 */ - __IO uint32_t EXTICR[4]; /*!< SYSCFG external interrupt configuration registers, Address offset: 0x08-0x14 */ - uint32_t RESERVED; /*!< Reserved, 0x18 */ - __IO uint32_t CFGR2; /*!< SYSCFG Configuration register2, Address offset: 0x1C */ - __IO uint32_t CMPCR; /*!< SYSCFG Compensation cell control register, Address offset: 0x20 */ - uint32_t RESERVED1[2]; /*!< Reserved, 0x24-0x28 */ - __IO uint32_t CFGR; /*!< SYSCFG Configuration register, Address offset: 0x2C */ - __IO uint32_t MCHDLYCR; /*!< SYSCFG multi-channel delay register, Address offset: 0x30 */ -} SYSCFG_TypeDef; - -/** - * @brief Inter-integrated Circuit Interface - */ - -typedef struct -{ - __IO uint32_t CR1; /*!< I2C Control register 1, Address offset: 0x00 */ - __IO uint32_t CR2; /*!< I2C Control register 2, Address offset: 0x04 */ - __IO uint32_t OAR1; /*!< I2C Own address register 1, Address offset: 0x08 */ - __IO uint32_t OAR2; /*!< I2C Own address register 2, Address offset: 0x0C */ - __IO uint32_t DR; /*!< I2C Data register, Address offset: 0x10 */ - __IO uint32_t SR1; /*!< I2C Status register 1, Address offset: 0x14 */ - __IO uint32_t SR2; /*!< I2C Status register 2, Address offset: 0x18 */ - __IO uint32_t CCR; /*!< I2C Clock control register, Address offset: 0x1C */ - __IO uint32_t TRISE; /*!< I2C TRISE register, Address offset: 0x20 */ - __IO uint32_t FLTR; /*!< I2C FLTR register, Address offset: 0x24 */ -} I2C_TypeDef; - -/** - * @brief Inter-integrated Circuit Interface - */ - -typedef struct -{ - __IO uint32_t CR1; /*!< FMPI2C Control register 1, Address offset: 0x00 */ - __IO uint32_t CR2; /*!< FMPI2C Control register 2, Address offset: 0x04 */ - __IO uint32_t OAR1; /*!< FMPI2C Own address 1 register, Address offset: 0x08 */ - __IO uint32_t OAR2; /*!< FMPI2C Own address 2 register, Address offset: 0x0C */ - __IO uint32_t TIMINGR; /*!< FMPI2C Timing register, Address offset: 0x10 */ - __IO uint32_t TIMEOUTR; /*!< FMPI2C Timeout register, Address offset: 0x14 */ - __IO uint32_t ISR; /*!< FMPI2C Interrupt and status register, Address offset: 0x18 */ - __IO uint32_t ICR; /*!< FMPI2C Interrupt clear register, Address offset: 0x1C */ - __IO uint32_t PECR; /*!< FMPI2C PEC register, Address offset: 0x20 */ - __IO uint32_t RXDR; /*!< FMPI2C Receive data register, Address offset: 0x24 */ - __IO uint32_t TXDR; /*!< FMPI2C Transmit data register, Address offset: 0x28 */ -} FMPI2C_TypeDef; - -/** - * @brief Independent WATCHDOG - */ - -typedef struct -{ - __IO uint32_t KR; /*!< IWDG Key register, Address offset: 0x00 */ - __IO uint32_t PR; /*!< IWDG Prescaler register, Address offset: 0x04 */ - __IO uint32_t RLR; /*!< IWDG Reload register, Address offset: 0x08 */ - __IO uint32_t SR; /*!< IWDG Status register, Address offset: 0x0C */ -} IWDG_TypeDef; - - -/** - * @brief Power Control - */ - -typedef struct -{ - __IO uint32_t CR; /*!< PWR power control register, Address offset: 0x00 */ - __IO uint32_t CSR; /*!< PWR power control/status register, Address offset: 0x04 */ -} PWR_TypeDef; - -/** - * @brief Reset and Clock Control - */ - -typedef struct -{ - __IO uint32_t CR; /*!< RCC clock control register, Address offset: 0x00 */ - __IO uint32_t PLLCFGR; /*!< RCC PLL configuration register, Address offset: 0x04 */ - __IO uint32_t CFGR; /*!< RCC clock configuration register, Address offset: 0x08 */ - __IO uint32_t CIR; /*!< RCC clock interrupt register, Address offset: 0x0C */ - __IO uint32_t AHB1RSTR; /*!< RCC AHB1 peripheral reset register, Address offset: 0x10 */ - __IO uint32_t AHB2RSTR; /*!< RCC AHB2 peripheral reset register, Address offset: 0x14 */ - __IO uint32_t AHB3RSTR; /*!< RCC AHB3 peripheral reset register, Address offset: 0x18 */ - uint32_t RESERVED0; /*!< Reserved, 0x1C */ - __IO uint32_t APB1RSTR; /*!< RCC APB1 peripheral reset register, Address offset: 0x20 */ - __IO uint32_t APB2RSTR; /*!< RCC APB2 peripheral reset register, Address offset: 0x24 */ - uint32_t RESERVED1[2]; /*!< Reserved, 0x28-0x2C */ - __IO uint32_t AHB1ENR; /*!< RCC AHB1 peripheral clock register, Address offset: 0x30 */ - __IO uint32_t AHB2ENR; /*!< RCC AHB2 peripheral clock register, Address offset: 0x34 */ - __IO uint32_t AHB3ENR; /*!< RCC AHB3 peripheral clock register, Address offset: 0x38 */ - uint32_t RESERVED2; /*!< Reserved, 0x3C */ - __IO uint32_t APB1ENR; /*!< RCC APB1 peripheral clock enable register, Address offset: 0x40 */ - __IO uint32_t APB2ENR; /*!< RCC APB2 peripheral clock enable register, Address offset: 0x44 */ - uint32_t RESERVED3[2]; /*!< Reserved, 0x48-0x4C */ - __IO uint32_t AHB1LPENR; /*!< RCC AHB1 peripheral clock enable in low power mode register, Address offset: 0x50 */ - __IO uint32_t AHB2LPENR; /*!< RCC AHB2 peripheral clock enable in low power mode register, Address offset: 0x54 */ - __IO uint32_t AHB3LPENR; /*!< RCC AHB3 peripheral clock enable in low power mode register, Address offset: 0x58 */ - uint32_t RESERVED4; /*!< Reserved, 0x5C */ - __IO uint32_t APB1LPENR; /*!< RCC APB1 peripheral clock enable in low power mode register, Address offset: 0x60 */ - __IO uint32_t APB2LPENR; /*!< RCC APB2 peripheral clock enable in low power mode register, Address offset: 0x64 */ - uint32_t RESERVED5[2]; /*!< Reserved, 0x68-0x6C */ - __IO uint32_t BDCR; /*!< RCC Backup domain control register, Address offset: 0x70 */ - __IO uint32_t CSR; /*!< RCC clock control & status register, Address offset: 0x74 */ - uint32_t RESERVED6[2]; /*!< Reserved, 0x78-0x7C */ - __IO uint32_t SSCGR; /*!< RCC spread spectrum clock generation register, Address offset: 0x80 */ - __IO uint32_t PLLI2SCFGR; /*!< RCC PLLI2S configuration register, Address offset: 0x84 */ - uint32_t RESERVED7; /*!< Reserved, 0x84 */ - __IO uint32_t DCKCFGR; /*!< RCC Dedicated Clocks configuration register, Address offset: 0x8C */ - __IO uint32_t CKGATENR; /*!< RCC Clocks Gated ENable Register, Address offset: 0x90 */ - __IO uint32_t DCKCFGR2; /*!< RCC Dedicated Clocks configuration register 2, Address offset: 0x94 */ -} RCC_TypeDef; - -/** - * @brief Real-Time Clock - */ - -typedef struct -{ - __IO uint32_t TR; /*!< RTC time register, Address offset: 0x00 */ - __IO uint32_t DR; /*!< RTC date register, Address offset: 0x04 */ - __IO uint32_t CR; /*!< RTC control register, Address offset: 0x08 */ - __IO uint32_t ISR; /*!< RTC initialization and status register, Address offset: 0x0C */ - __IO uint32_t PRER; /*!< RTC prescaler register, Address offset: 0x10 */ - __IO uint32_t WUTR; /*!< RTC wakeup timer register, Address offset: 0x14 */ - __IO uint32_t CALIBR; /*!< RTC calibration register, Address offset: 0x18 */ - __IO uint32_t ALRMAR; /*!< RTC alarm A register, Address offset: 0x1C */ - __IO uint32_t ALRMBR; /*!< RTC alarm B register, Address offset: 0x20 */ - __IO uint32_t WPR; /*!< RTC write protection register, Address offset: 0x24 */ - __IO uint32_t SSR; /*!< RTC sub second register, Address offset: 0x28 */ - __IO uint32_t SHIFTR; /*!< RTC shift control register, Address offset: 0x2C */ - __IO uint32_t TSTR; /*!< RTC time stamp time register, Address offset: 0x30 */ - __IO uint32_t TSDR; /*!< RTC time stamp date register, Address offset: 0x34 */ - __IO uint32_t TSSSR; /*!< RTC time-stamp sub second register, Address offset: 0x38 */ - __IO uint32_t CALR; /*!< RTC calibration register, Address offset: 0x3C */ - __IO uint32_t TAFCR; /*!< RTC tamper and alternate function configuration register, Address offset: 0x40 */ - __IO uint32_t ALRMASSR;/*!< RTC alarm A sub second register, Address offset: 0x44 */ - __IO uint32_t ALRMBSSR;/*!< RTC alarm B sub second register, Address offset: 0x48 */ - uint32_t RESERVED7; /*!< Reserved, 0x4C */ - __IO uint32_t BKP0R; /*!< RTC backup register 1, Address offset: 0x50 */ - __IO uint32_t BKP1R; /*!< RTC backup register 1, Address offset: 0x54 */ - __IO uint32_t BKP2R; /*!< RTC backup register 2, Address offset: 0x58 */ - __IO uint32_t BKP3R; /*!< RTC backup register 3, Address offset: 0x5C */ - __IO uint32_t BKP4R; /*!< RTC backup register 4, Address offset: 0x60 */ - __IO uint32_t BKP5R; /*!< RTC backup register 5, Address offset: 0x64 */ - __IO uint32_t BKP6R; /*!< RTC backup register 6, Address offset: 0x68 */ - __IO uint32_t BKP7R; /*!< RTC backup register 7, Address offset: 0x6C */ - __IO uint32_t BKP8R; /*!< RTC backup register 8, Address offset: 0x70 */ - __IO uint32_t BKP9R; /*!< RTC backup register 9, Address offset: 0x74 */ - __IO uint32_t BKP10R; /*!< RTC backup register 10, Address offset: 0x78 */ - __IO uint32_t BKP11R; /*!< RTC backup register 11, Address offset: 0x7C */ - __IO uint32_t BKP12R; /*!< RTC backup register 12, Address offset: 0x80 */ - __IO uint32_t BKP13R; /*!< RTC backup register 13, Address offset: 0x84 */ - __IO uint32_t BKP14R; /*!< RTC backup register 14, Address offset: 0x88 */ - __IO uint32_t BKP15R; /*!< RTC backup register 15, Address offset: 0x8C */ - __IO uint32_t BKP16R; /*!< RTC backup register 16, Address offset: 0x90 */ - __IO uint32_t BKP17R; /*!< RTC backup register 17, Address offset: 0x94 */ - __IO uint32_t BKP18R; /*!< RTC backup register 18, Address offset: 0x98 */ - __IO uint32_t BKP19R; /*!< RTC backup register 19, Address offset: 0x9C */ -} RTC_TypeDef; - -/** - * @brief Serial Audio Interface - */ - -typedef struct -{ - __IO uint32_t GCR; /*!< SAI global configuration register, Address offset: 0x00 */ -} SAI_TypeDef; - -typedef struct -{ - __IO uint32_t CR1; /*!< SAI block x configuration register 1, Address offset: 0x04 */ - __IO uint32_t CR2; /*!< SAI block x configuration register 2, Address offset: 0x08 */ - __IO uint32_t FRCR; /*!< SAI block x frame configuration register, Address offset: 0x0C */ - __IO uint32_t SLOTR; /*!< SAI block x slot register, Address offset: 0x10 */ - __IO uint32_t IMR; /*!< SAI block x interrupt mask register, Address offset: 0x14 */ - __IO uint32_t SR; /*!< SAI block x status register, Address offset: 0x18 */ - __IO uint32_t CLRFR; /*!< SAI block x clear flag register, Address offset: 0x1C */ - __IO uint32_t DR; /*!< SAI block x data register, Address offset: 0x20 */ -} SAI_Block_TypeDef; - -/** - * @brief SD host Interface - */ - -typedef struct -{ - __IO uint32_t POWER; /*!< SDIO power control register, Address offset: 0x00 */ - __IO uint32_t CLKCR; /*!< SDI clock control register, Address offset: 0x04 */ - __IO uint32_t ARG; /*!< SDIO argument register, Address offset: 0x08 */ - __IO uint32_t CMD; /*!< SDIO command register, Address offset: 0x0C */ - __IO const uint32_t RESPCMD; /*!< SDIO command response register, Address offset: 0x10 */ - __IO const uint32_t RESP1; /*!< SDIO response 1 register, Address offset: 0x14 */ - __IO const uint32_t RESP2; /*!< SDIO response 2 register, Address offset: 0x18 */ - __IO const uint32_t RESP3; /*!< SDIO response 3 register, Address offset: 0x1C */ - __IO const uint32_t RESP4; /*!< SDIO response 4 register, Address offset: 0x20 */ - __IO uint32_t DTIMER; /*!< SDIO data timer register, Address offset: 0x24 */ - __IO uint32_t DLEN; /*!< SDIO data length register, Address offset: 0x28 */ - __IO uint32_t DCTRL; /*!< SDIO data control register, Address offset: 0x2C */ - __IO const uint32_t DCOUNT; /*!< SDIO data counter register, Address offset: 0x30 */ - __IO const uint32_t STA; /*!< SDIO status register, Address offset: 0x34 */ - __IO uint32_t ICR; /*!< SDIO interrupt clear register, Address offset: 0x38 */ - __IO uint32_t MASK; /*!< SDIO mask register, Address offset: 0x3C */ - uint32_t RESERVED0[2]; /*!< Reserved, 0x40-0x44 */ - __IO const uint32_t FIFOCNT; /*!< SDIO FIFO counter register, Address offset: 0x48 */ - uint32_t RESERVED1[13]; /*!< Reserved, 0x4C-0x7C */ - __IO uint32_t FIFO; /*!< SDIO data FIFO register, Address offset: 0x80 */ -} SDIO_TypeDef; - -/** - * @brief Serial Peripheral Interface - */ - -typedef struct -{ - __IO uint32_t CR1; /*!< SPI control register 1 (not used in I2S mode), Address offset: 0x00 */ - __IO uint32_t CR2; /*!< SPI control register 2, Address offset: 0x04 */ - __IO uint32_t SR; /*!< SPI status register, Address offset: 0x08 */ - __IO uint32_t DR; /*!< SPI data register, Address offset: 0x0C */ - __IO uint32_t CRCPR; /*!< SPI CRC polynomial register (not used in I2S mode), Address offset: 0x10 */ - __IO uint32_t RXCRCR; /*!< SPI RX CRC register (not used in I2S mode), Address offset: 0x14 */ - __IO uint32_t TXCRCR; /*!< SPI TX CRC register (not used in I2S mode), Address offset: 0x18 */ - __IO uint32_t I2SCFGR; /*!< SPI_I2S configuration register, Address offset: 0x1C */ - __IO uint32_t I2SPR; /*!< SPI_I2S prescaler register, Address offset: 0x20 */ -} SPI_TypeDef; - -/** - * @brief QUAD Serial Peripheral Interface - */ - -typedef struct -{ - __IO uint32_t CR; /*!< QUADSPI Control register, Address offset: 0x00 */ - __IO uint32_t DCR; /*!< QUADSPI Device Configuration register, Address offset: 0x04 */ - __IO uint32_t SR; /*!< QUADSPI Status register, Address offset: 0x08 */ - __IO uint32_t FCR; /*!< QUADSPI Flag Clear register, Address offset: 0x0C */ - __IO uint32_t DLR; /*!< QUADSPI Data Length register, Address offset: 0x10 */ - __IO uint32_t CCR; /*!< QUADSPI Communication Configuration register, Address offset: 0x14 */ - __IO uint32_t AR; /*!< QUADSPI Address register, Address offset: 0x18 */ - __IO uint32_t ABR; /*!< QUADSPI Alternate Bytes register, Address offset: 0x1C */ - __IO uint32_t DR; /*!< QUADSPI Data register, Address offset: 0x20 */ - __IO uint32_t PSMKR; /*!< QUADSPI Polling Status Mask register, Address offset: 0x24 */ - __IO uint32_t PSMAR; /*!< QUADSPI Polling Status Match register, Address offset: 0x28 */ - __IO uint32_t PIR; /*!< QUADSPI Polling Interval register, Address offset: 0x2C */ - __IO uint32_t LPTR; /*!< QUADSPI Low Power Timeout register, Address offset: 0x30 */ -} QUADSPI_TypeDef; - -/** - * @brief TIM - */ - -typedef struct -{ - __IO uint32_t CR1; /*!< TIM control register 1, Address offset: 0x00 */ - __IO uint32_t CR2; /*!< TIM control register 2, Address offset: 0x04 */ - __IO uint32_t SMCR; /*!< TIM slave mode control register, Address offset: 0x08 */ - __IO uint32_t DIER; /*!< TIM DMA/interrupt enable register, Address offset: 0x0C */ - __IO uint32_t SR; /*!< TIM status register, Address offset: 0x10 */ - __IO uint32_t EGR; /*!< TIM event generation register, Address offset: 0x14 */ - __IO uint32_t CCMR1; /*!< TIM capture/compare mode register 1, Address offset: 0x18 */ - __IO uint32_t CCMR2; /*!< TIM capture/compare mode register 2, Address offset: 0x1C */ - __IO uint32_t CCER; /*!< TIM capture/compare enable register, Address offset: 0x20 */ - __IO uint32_t CNT; /*!< TIM counter register, Address offset: 0x24 */ - __IO uint32_t PSC; /*!< TIM prescaler, Address offset: 0x28 */ - __IO uint32_t ARR; /*!< TIM auto-reload register, Address offset: 0x2C */ - __IO uint32_t RCR; /*!< TIM repetition counter register, Address offset: 0x30 */ - __IO uint32_t CCR1; /*!< TIM capture/compare register 1, Address offset: 0x34 */ - __IO uint32_t CCR2; /*!< TIM capture/compare register 2, Address offset: 0x38 */ - __IO uint32_t CCR3; /*!< TIM capture/compare register 3, Address offset: 0x3C */ - __IO uint32_t CCR4; /*!< TIM capture/compare register 4, Address offset: 0x40 */ - __IO uint32_t BDTR; /*!< TIM break and dead-time register, Address offset: 0x44 */ - __IO uint32_t DCR; /*!< TIM DMA control register, Address offset: 0x48 */ - __IO uint32_t DMAR; /*!< TIM DMA address for full transfer, Address offset: 0x4C */ - __IO uint32_t OR; /*!< TIM option register, Address offset: 0x50 */ -} TIM_TypeDef; - -/** - * @brief Universal Synchronous Asynchronous Receiver Transmitter - */ - -typedef struct -{ - __IO uint32_t SR; /*!< USART Status register, Address offset: 0x00 */ - __IO uint32_t DR; /*!< USART Data register, Address offset: 0x04 */ - __IO uint32_t BRR; /*!< USART Baud rate register, Address offset: 0x08 */ - __IO uint32_t CR1; /*!< USART Control register 1, Address offset: 0x0C */ - __IO uint32_t CR2; /*!< USART Control register 2, Address offset: 0x10 */ - __IO uint32_t CR3; /*!< USART Control register 3, Address offset: 0x14 */ - __IO uint32_t GTPR; /*!< USART Guard time and prescaler register, Address offset: 0x18 */ -} USART_TypeDef; - -/** - * @brief Window WATCHDOG - */ - -typedef struct -{ - __IO uint32_t CR; /*!< WWDG Control register, Address offset: 0x00 */ - __IO uint32_t CFR; /*!< WWDG Configuration register, Address offset: 0x04 */ - __IO uint32_t SR; /*!< WWDG Status register, Address offset: 0x08 */ -} WWDG_TypeDef; - -/** - * @brief RNG - */ - -typedef struct -{ - __IO uint32_t CR; /*!< RNG control register, Address offset: 0x00 */ - __IO uint32_t SR; /*!< RNG status register, Address offset: 0x04 */ - __IO uint32_t DR; /*!< RNG data register, Address offset: 0x08 */ -} RNG_TypeDef; - -/** - * @brief USB_OTG_Core_Registers - */ -typedef struct -{ - __IO uint32_t GOTGCTL; /*!< USB_OTG Control and Status Register 000h */ - __IO uint32_t GOTGINT; /*!< USB_OTG Interrupt Register 004h */ - __IO uint32_t GAHBCFG; /*!< Core AHB Configuration Register 008h */ - __IO uint32_t GUSBCFG; /*!< Core USB Configuration Register 00Ch */ - __IO uint32_t GRSTCTL; /*!< Core Reset Register 010h */ - __IO uint32_t GINTSTS; /*!< Core Interrupt Register 014h */ - __IO uint32_t GINTMSK; /*!< Core Interrupt Mask Register 018h */ - __IO uint32_t GRXSTSR; /*!< Receive Sts Q Read Register 01Ch */ - __IO uint32_t GRXSTSP; /*!< Receive Sts Q Read & POP Register 020h */ - __IO uint32_t GRXFSIZ; /*!< Receive FIFO Size Register 024h */ - __IO uint32_t DIEPTXF0_HNPTXFSIZ; /*!< EP0 / Non Periodic Tx FIFO Size Register 028h */ - __IO uint32_t HNPTXSTS; /*!< Non Periodic Tx FIFO/Queue Sts reg 02Ch */ - uint32_t Reserved30[2]; /*!< Reserved 030h */ - __IO uint32_t GCCFG; /*!< General Purpose IO Register 038h */ - __IO uint32_t CID; /*!< User ID Register 03Ch */ - uint32_t Reserved5[3]; /*!< Reserved 040h-048h */ - __IO uint32_t GHWCFG3; /*!< User HW config3 04Ch */ - uint32_t Reserved6; /*!< Reserved 050h */ - __IO uint32_t GLPMCFG; /*!< LPM Register 054h */ - uint32_t Reserved; /*!< Reserved 058h */ - __IO uint32_t GDFIFOCFG; /*!< DFIFO Software Config Register 05Ch */ - uint32_t Reserved43[40]; /*!< Reserved 058h-0FFh */ - __IO uint32_t HPTXFSIZ; /*!< Host Periodic Tx FIFO Size Reg 100h */ - __IO uint32_t DIEPTXF[0x0F]; /*!< dev Periodic Transmit FIFO */ -} USB_OTG_GlobalTypeDef; - -/** - * @brief USB_OTG_device_Registers - */ -typedef struct -{ - __IO uint32_t DCFG; /*!< dev Configuration Register 800h */ - __IO uint32_t DCTL; /*!< dev Control Register 804h */ - __IO uint32_t DSTS; /*!< dev Status Register (RO) 808h */ - uint32_t Reserved0C; /*!< Reserved 80Ch */ - __IO uint32_t DIEPMSK; /*!< dev IN Endpoint Mask 810h */ - __IO uint32_t DOEPMSK; /*!< dev OUT Endpoint Mask 814h */ - __IO uint32_t DAINT; /*!< dev All Endpoints Itr Reg 818h */ - __IO uint32_t DAINTMSK; /*!< dev All Endpoints Itr Mask 81Ch */ - uint32_t Reserved20; /*!< Reserved 820h */ - uint32_t Reserved9; /*!< Reserved 824h */ - __IO uint32_t DVBUSDIS; /*!< dev VBUS discharge Register 828h */ - __IO uint32_t DVBUSPULSE; /*!< dev VBUS Pulse Register 82Ch */ - __IO uint32_t DTHRCTL; /*!< dev threshold 830h */ - __IO uint32_t DIEPEMPMSK; /*!< dev empty msk 834h */ - __IO uint32_t DEACHINT; /*!< dedicated EP interrupt 838h */ - __IO uint32_t DEACHMSK; /*!< dedicated EP msk 83Ch */ - uint32_t Reserved40; /*!< dedicated EP mask 840h */ - __IO uint32_t DINEP1MSK; /*!< dedicated EP mask 844h */ - uint32_t Reserved44[15]; /*!< Reserved 844-87Ch */ - __IO uint32_t DOUTEP1MSK; /*!< dedicated EP msk 884h */ -} USB_OTG_DeviceTypeDef; - -/** - * @brief USB_OTG_IN_Endpoint-Specific_Register - */ -typedef struct -{ - __IO uint32_t DIEPCTL; /*!< dev IN Endpoint Control Reg 900h + (ep_num * 20h) + 00h */ - uint32_t Reserved04; /*!< Reserved 900h + (ep_num * 20h) + 04h */ - __IO uint32_t DIEPINT; /*!< dev IN Endpoint Itr Reg 900h + (ep_num * 20h) + 08h */ - uint32_t Reserved0C; /*!< Reserved 900h + (ep_num * 20h) + 0Ch */ - __IO uint32_t DIEPTSIZ; /*!< IN Endpoint Txfer Size 900h + (ep_num * 20h) + 10h */ - __IO uint32_t DIEPDMA; /*!< IN Endpoint DMA Address Reg 900h + (ep_num * 20h) + 14h */ - __IO uint32_t DTXFSTS; /*!< IN Endpoint Tx FIFO Status Reg 900h + (ep_num * 20h) + 18h */ - uint32_t Reserved18; /*!< Reserved 900h+(ep_num*20h)+1Ch-900h+ (ep_num * 20h) + 1Ch */ -} USB_OTG_INEndpointTypeDef; - -/** - * @brief USB_OTG_OUT_Endpoint-Specific_Registers - */ -typedef struct -{ - __IO uint32_t DOEPCTL; /*!< dev OUT Endpoint Control Reg B00h + (ep_num * 20h) + 00h */ - uint32_t Reserved04; /*!< Reserved B00h + (ep_num * 20h) + 04h */ - __IO uint32_t DOEPINT; /*!< dev OUT Endpoint Itr Reg B00h + (ep_num * 20h) + 08h */ - uint32_t Reserved0C; /*!< Reserved B00h + (ep_num * 20h) + 0Ch */ - __IO uint32_t DOEPTSIZ; /*!< dev OUT Endpoint Txfer Size B00h + (ep_num * 20h) + 10h */ - __IO uint32_t DOEPDMA; /*!< dev OUT Endpoint DMA Address B00h + (ep_num * 20h) + 14h */ - uint32_t Reserved18[2]; /*!< Reserved B00h + (ep_num * 20h) + 18h - B00h + (ep_num * 20h) + 1Ch */ -} USB_OTG_OUTEndpointTypeDef; - -/** - * @brief USB_OTG_Host_Mode_Register_Structures - */ -typedef struct -{ - __IO uint32_t HCFG; /*!< Host Configuration Register 400h */ - __IO uint32_t HFIR; /*!< Host Frame Interval Register 404h */ - __IO uint32_t HFNUM; /*!< Host Frame Nbr/Frame Remaining 408h */ - uint32_t Reserved40C; /*!< Reserved 40Ch */ - __IO uint32_t HPTXSTS; /*!< Host Periodic Tx FIFO/ Queue Status 410h */ - __IO uint32_t HAINT; /*!< Host All Channels Interrupt Register 414h */ - __IO uint32_t HAINTMSK; /*!< Host All Channels Interrupt Mask 418h */ -} USB_OTG_HostTypeDef; - -/** - * @brief USB_OTG_Host_Channel_Specific_Registers - */ -typedef struct -{ - __IO uint32_t HCCHAR; /*!< Host Channel Characteristics Register 500h */ - __IO uint32_t HCSPLT; /*!< Host Channel Split Control Register 504h */ - __IO uint32_t HCINT; /*!< Host Channel Interrupt Register 508h */ - __IO uint32_t HCINTMSK; /*!< Host Channel Interrupt Mask Register 50Ch */ - __IO uint32_t HCTSIZ; /*!< Host Channel Transfer Size Register 510h */ - __IO uint32_t HCDMA; /*!< Host Channel DMA Address Register 514h */ - uint32_t Reserved[2]; /*!< Reserved */ -} USB_OTG_HostChannelTypeDef; - -/** - * @brief LPTIMER - */ -typedef struct -{ - __IO uint32_t ISR; /*!< LPTIM Interrupt and Status register, Address offset: 0x00 */ - __IO uint32_t ICR; /*!< LPTIM Interrupt Clear register, Address offset: 0x04 */ - __IO uint32_t IER; /*!< LPTIM Interrupt Enable register, Address offset: 0x08 */ - __IO uint32_t CFGR; /*!< LPTIM Configuration register, Address offset: 0x0C */ - __IO uint32_t CR; /*!< LPTIM Control register, Address offset: 0x10 */ - __IO uint32_t CMP; /*!< LPTIM Compare register, Address offset: 0x14 */ - __IO uint32_t ARR; /*!< LPTIM Autoreload register, Address offset: 0x18 */ - __IO uint32_t CNT; /*!< LPTIM Counter register, Address offset: 0x1C */ - __IO uint32_t OR; /*!< LPTIM Option register, Address offset: 0x20 */ -} LPTIM_TypeDef; - -/** - * @} - */ - -/** @addtogroup Peripheral_memory_map - * @{ - */ -#define FLASH_BASE 0x08000000UL /*!< FLASH (up to 1.5 MB) base address in the alias region */ -#define SRAM1_BASE 0x20000000UL /*!< SRAM1(256 KB) base address in the alias region */ -#define SRAM2_BASE 0x20040000UL /*!< SRAM2(64 KB) base address in the alias region */ -#define PERIPH_BASE 0x40000000UL /*!< Peripheral base address in the alias region */ -#define FSMC_R_BASE 0xA0000000UL /*!< FSMC registers base address */ -#define QSPI_R_BASE 0xA0001000UL /*!< QuadSPI registers base address */ -#define SRAM1_BB_BASE 0x22000000UL /*!< SRAM1(256 KB) base address in the bit-band region */ -#define SRAM2_BB_BASE 0x22800000UL /*!< SRAM2(64 KB) base address in the bit-band region */ -#define PERIPH_BB_BASE 0x42000000UL /*!< Peripheral base address in the bit-band region */ -#define FLASH_END 0x0817FFFFUL /*!< FLASH end address */ -#define FLASH_OTP_BASE 0x1FFF7800UL /*!< Base address of : (up to 528 Bytes) embedded FLASH OTP Area */ -#define FLASH_OTP_END 0x1FFF7A0FUL /*!< End address of : (up to 528 Bytes) embedded FLASH OTP Area */ - -/* Legacy defines */ -#define SRAM_BASE SRAM1_BASE -#define SRAM_BB_BASE SRAM1_BB_BASE - -/*!< Peripheral memory map */ -#define APB1PERIPH_BASE PERIPH_BASE -#define APB2PERIPH_BASE (PERIPH_BASE + 0x00010000UL) -#define AHB1PERIPH_BASE (PERIPH_BASE + 0x00020000UL) -#define AHB2PERIPH_BASE (PERIPH_BASE + 0x10000000UL) - -/*!< APB1 peripherals */ -#define TIM2_BASE (APB1PERIPH_BASE + 0x0000UL) -#define TIM3_BASE (APB1PERIPH_BASE + 0x0400UL) -#define TIM4_BASE (APB1PERIPH_BASE + 0x0800UL) -#define TIM5_BASE (APB1PERIPH_BASE + 0x0C00UL) -#define TIM6_BASE (APB1PERIPH_BASE + 0x1000UL) -#define TIM7_BASE (APB1PERIPH_BASE + 0x1400UL) -#define TIM12_BASE (APB1PERIPH_BASE + 0x1800UL) -#define TIM13_BASE (APB1PERIPH_BASE + 0x1C00UL) -#define TIM14_BASE (APB1PERIPH_BASE + 0x2000UL) -#define LPTIM1_BASE (APB1PERIPH_BASE + 0x2400UL) -#define RTC_BASE (APB1PERIPH_BASE + 0x2800UL) -#define WWDG_BASE (APB1PERIPH_BASE + 0x2C00UL) -#define IWDG_BASE (APB1PERIPH_BASE + 0x3000UL) -#define I2S2ext_BASE (APB1PERIPH_BASE + 0x3400UL) -#define SPI2_BASE (APB1PERIPH_BASE + 0x3800UL) -#define SPI3_BASE (APB1PERIPH_BASE + 0x3C00UL) -#define I2S3ext_BASE (APB1PERIPH_BASE + 0x4000UL) -#define USART2_BASE (APB1PERIPH_BASE + 0x4400UL) -#define USART3_BASE (APB1PERIPH_BASE + 0x4800UL) -#define UART4_BASE (APB1PERIPH_BASE + 0x4C00UL) -#define UART5_BASE (APB1PERIPH_BASE + 0x5000UL) -#define I2C1_BASE (APB1PERIPH_BASE + 0x5400UL) -#define I2C2_BASE (APB1PERIPH_BASE + 0x5800UL) -#define I2C3_BASE (APB1PERIPH_BASE + 0x5C00UL) -#define FMPI2C1_BASE (APB1PERIPH_BASE + 0x6000UL) -#define CAN1_BASE (APB1PERIPH_BASE + 0x6400UL) -#define CAN2_BASE (APB1PERIPH_BASE + 0x6800UL) -#define CAN3_BASE (APB1PERIPH_BASE + 0x6C00UL) -#define PWR_BASE (APB1PERIPH_BASE + 0x7000UL) -#define DAC_BASE (APB1PERIPH_BASE + 0x7400UL) -#define UART7_BASE (APB1PERIPH_BASE + 0x7800UL) -#define UART8_BASE (APB1PERIPH_BASE + 0x7C00UL) - -/*!< APB2 peripherals */ -#define TIM1_BASE (APB2PERIPH_BASE + 0x0000UL) -#define TIM8_BASE (APB2PERIPH_BASE + 0x0400UL) -#define USART1_BASE (APB2PERIPH_BASE + 0x1000UL) -#define USART6_BASE (APB2PERIPH_BASE + 0x1400UL) -#define UART9_BASE (APB2PERIPH_BASE + 0x1800UL) -#define UART10_BASE (APB2PERIPH_BASE + 0x1C00UL) -#define ADC1_BASE (APB2PERIPH_BASE + 0x2000UL) -#define ADC1_COMMON_BASE (APB2PERIPH_BASE + 0x2300UL) -/* Legacy define */ -#define ADC_BASE ADC1_COMMON_BASE -#define SDIO_BASE (APB2PERIPH_BASE + 0x2C00UL) -#define SPI1_BASE (APB2PERIPH_BASE + 0x3000UL) -#define SPI4_BASE (APB2PERIPH_BASE + 0x3400UL) -#define SYSCFG_BASE (APB2PERIPH_BASE + 0x3800UL) -#define EXTI_BASE (APB2PERIPH_BASE + 0x3C00UL) -#define TIM9_BASE (APB2PERIPH_BASE + 0x4000UL) -#define TIM10_BASE (APB2PERIPH_BASE + 0x4400UL) -#define TIM11_BASE (APB2PERIPH_BASE + 0x4800UL) -#define SPI5_BASE (APB2PERIPH_BASE + 0x5000UL) -#define DFSDM1_BASE (APB2PERIPH_BASE + 0x6000UL) -#define DFSDM2_BASE (APB2PERIPH_BASE + 0x6400UL) -#define DFSDM1_Channel0_BASE (DFSDM1_BASE + 0x00UL) -#define DFSDM1_Channel1_BASE (DFSDM1_BASE + 0x20UL) -#define DFSDM1_Channel2_BASE (DFSDM1_BASE + 0x40UL) -#define DFSDM1_Channel3_BASE (DFSDM1_BASE + 0x60UL) -#define DFSDM1_Filter0_BASE (DFSDM1_BASE + 0x100UL) -#define DFSDM1_Filter1_BASE (DFSDM1_BASE + 0x180UL) -#define DFSDM2_Channel0_BASE (DFSDM2_BASE + 0x00UL) -#define DFSDM2_Channel1_BASE (DFSDM2_BASE + 0x20UL) -#define DFSDM2_Channel2_BASE (DFSDM2_BASE + 0x40UL) -#define DFSDM2_Channel3_BASE (DFSDM2_BASE + 0x60UL) -#define DFSDM2_Channel4_BASE (DFSDM2_BASE + 0x80UL) -#define DFSDM2_Channel5_BASE (DFSDM2_BASE + 0xA0UL) -#define DFSDM2_Channel6_BASE (DFSDM2_BASE + 0xC0UL) -#define DFSDM2_Channel7_BASE (DFSDM2_BASE + 0xE0UL) -#define DFSDM2_Filter0_BASE (DFSDM2_BASE + 0x100UL) -#define DFSDM2_Filter1_BASE (DFSDM2_BASE + 0x180UL) -#define DFSDM2_Filter2_BASE (DFSDM2_BASE + 0x200UL) -#define DFSDM2_Filter3_BASE (DFSDM2_BASE + 0x280UL) -#define SAI1_BASE (APB2PERIPH_BASE + 0x5800UL) -#define SAI1_Block_A_BASE (SAI1_BASE + 0x004UL) -#define SAI1_Block_B_BASE (SAI1_BASE + 0x024UL) - -/*!< AHB1 peripherals */ -#define GPIOA_BASE (AHB1PERIPH_BASE + 0x0000UL) -#define GPIOB_BASE (AHB1PERIPH_BASE + 0x0400UL) -#define GPIOC_BASE (AHB1PERIPH_BASE + 0x0800UL) -#define GPIOD_BASE (AHB1PERIPH_BASE + 0x0C00UL) -#define GPIOE_BASE (AHB1PERIPH_BASE + 0x1000UL) -#define GPIOF_BASE (AHB1PERIPH_BASE + 0x1400UL) -#define GPIOG_BASE (AHB1PERIPH_BASE + 0x1800UL) -#define GPIOH_BASE (AHB1PERIPH_BASE + 0x1C00UL) -#define CRC_BASE (AHB1PERIPH_BASE + 0x3000UL) -#define RCC_BASE (AHB1PERIPH_BASE + 0x3800UL) -#define FLASH_R_BASE (AHB1PERIPH_BASE + 0x3C00UL) -#define DMA1_BASE (AHB1PERIPH_BASE + 0x6000UL) -#define DMA1_Stream0_BASE (DMA1_BASE + 0x010UL) -#define DMA1_Stream1_BASE (DMA1_BASE + 0x028UL) -#define DMA1_Stream2_BASE (DMA1_BASE + 0x040UL) -#define DMA1_Stream3_BASE (DMA1_BASE + 0x058UL) -#define DMA1_Stream4_BASE (DMA1_BASE + 0x070UL) -#define DMA1_Stream5_BASE (DMA1_BASE + 0x088UL) -#define DMA1_Stream6_BASE (DMA1_BASE + 0x0A0UL) -#define DMA1_Stream7_BASE (DMA1_BASE + 0x0B8UL) -#define DMA2_BASE (AHB1PERIPH_BASE + 0x6400UL) -#define DMA2_Stream0_BASE (DMA2_BASE + 0x010UL) -#define DMA2_Stream1_BASE (DMA2_BASE + 0x028UL) -#define DMA2_Stream2_BASE (DMA2_BASE + 0x040UL) -#define DMA2_Stream3_BASE (DMA2_BASE + 0x058UL) -#define DMA2_Stream4_BASE (DMA2_BASE + 0x070UL) -#define DMA2_Stream5_BASE (DMA2_BASE + 0x088UL) -#define DMA2_Stream6_BASE (DMA2_BASE + 0x0A0UL) -#define DMA2_Stream7_BASE (DMA2_BASE + 0x0B8UL) - -/*!< AHB2 peripherals */ -#define RNG_BASE (AHB2PERIPH_BASE + 0x60800UL) - - -/*!< FSMC Bankx registers base address */ -#define FSMC_Bank1_R_BASE (FSMC_R_BASE + 0x0000UL) -#define FSMC_Bank1E_R_BASE (FSMC_R_BASE + 0x0104UL) - -/*!< Debug MCU registers base address */ -#define DBGMCU_BASE 0xE0042000UL -/*!< USB registers base address */ -#define USB_OTG_FS_PERIPH_BASE 0x50000000UL - -#define USB_OTG_GLOBAL_BASE 0x000UL -#define USB_OTG_DEVICE_BASE 0x800UL -#define USB_OTG_IN_ENDPOINT_BASE 0x900UL -#define USB_OTG_OUT_ENDPOINT_BASE 0xB00UL -#define USB_OTG_EP_REG_SIZE 0x20UL -#define USB_OTG_HOST_BASE 0x400UL -#define USB_OTG_HOST_PORT_BASE 0x440UL -#define USB_OTG_HOST_CHANNEL_BASE 0x500UL -#define USB_OTG_HOST_CHANNEL_SIZE 0x20UL -#define USB_OTG_PCGCCTL_BASE 0xE00UL -#define USB_OTG_FIFO_BASE 0x1000UL -#define USB_OTG_FIFO_SIZE 0x1000UL - -#define UID_BASE 0x1FFF7A10UL /*!< Unique device ID register base address */ -#define FLASHSIZE_BASE 0x1FFF7A22UL /*!< FLASH Size register base address */ -#define PACKAGE_BASE 0x1FFF7BF0UL /*!< Package size register base address */ -/** - * @} - */ - -/** @addtogroup Peripheral_declaration - * @{ - */ -#define TIM2 ((TIM_TypeDef *) TIM2_BASE) -#define TIM3 ((TIM_TypeDef *) TIM3_BASE) -#define TIM4 ((TIM_TypeDef *) TIM4_BASE) -#define TIM5 ((TIM_TypeDef *) TIM5_BASE) -#define TIM6 ((TIM_TypeDef *) TIM6_BASE) -#define TIM7 ((TIM_TypeDef *) TIM7_BASE) -#define TIM12 ((TIM_TypeDef *) TIM12_BASE) -#define TIM13 ((TIM_TypeDef *) TIM13_BASE) -#define TIM14 ((TIM_TypeDef *) TIM14_BASE) -#define LPTIM1 ((LPTIM_TypeDef *) LPTIM1_BASE) -#define RTC ((RTC_TypeDef *) RTC_BASE) -#define WWDG ((WWDG_TypeDef *) WWDG_BASE) -#define IWDG ((IWDG_TypeDef *) IWDG_BASE) -#define I2S2ext ((SPI_TypeDef *) I2S2ext_BASE) -#define SPI2 ((SPI_TypeDef *) SPI2_BASE) -#define SPI3 ((SPI_TypeDef *) SPI3_BASE) -#define I2S3ext ((SPI_TypeDef *) I2S3ext_BASE) -#define USART2 ((USART_TypeDef *) USART2_BASE) -#define USART3 ((USART_TypeDef *) USART3_BASE) -#define UART4 ((USART_TypeDef *) UART4_BASE) -#define UART5 ((USART_TypeDef *) UART5_BASE) -#define I2C1 ((I2C_TypeDef *) I2C1_BASE) -#define I2C2 ((I2C_TypeDef *) I2C2_BASE) -#define I2C3 ((I2C_TypeDef *) I2C3_BASE) -#define FMPI2C1 ((FMPI2C_TypeDef *) FMPI2C1_BASE) -#define CAN1 ((CAN_TypeDef *) CAN1_BASE) -#define CAN2 ((CAN_TypeDef *) CAN2_BASE) -#define CAN3 ((CAN_TypeDef *) CAN3_BASE) -#define PWR ((PWR_TypeDef *) PWR_BASE) -#define DAC1 ((DAC_TypeDef *) DAC_BASE) -#define DAC ((DAC_TypeDef *) DAC_BASE) /* Kept for legacy purpose */ -#define UART7 ((USART_TypeDef *) UART7_BASE) -#define UART8 ((USART_TypeDef *) UART8_BASE) -#define TIM1 ((TIM_TypeDef *) TIM1_BASE) -#define TIM8 ((TIM_TypeDef *) TIM8_BASE) -#define USART1 ((USART_TypeDef *) USART1_BASE) -#define USART6 ((USART_TypeDef *) USART6_BASE) -#define UART9 ((USART_TypeDef *) UART9_BASE) -#define UART10 ((USART_TypeDef *) UART10_BASE) -#define ADC1 ((ADC_TypeDef *) ADC1_BASE) -#define ADC1_COMMON ((ADC_Common_TypeDef *) ADC1_COMMON_BASE) -/* Legacy define */ -#define ADC ADC1_COMMON -#define SDIO ((SDIO_TypeDef *) SDIO_BASE) -#define SPI1 ((SPI_TypeDef *) SPI1_BASE) -#define SPI4 ((SPI_TypeDef *) SPI4_BASE) -#define SYSCFG ((SYSCFG_TypeDef *) SYSCFG_BASE) -#define EXTI ((EXTI_TypeDef *) EXTI_BASE) -#define TIM9 ((TIM_TypeDef *) TIM9_BASE) -#define TIM10 ((TIM_TypeDef *) TIM10_BASE) -#define TIM11 ((TIM_TypeDef *) TIM11_BASE) -#define SPI5 ((SPI_TypeDef *) SPI5_BASE) -#define DFSDM1_Channel0 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel0_BASE) -#define DFSDM1_Channel1 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel1_BASE) -#define DFSDM1_Channel2 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel2_BASE) -#define DFSDM1_Channel3 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel3_BASE) -#define DFSDM1_Filter0 ((DFSDM_Filter_TypeDef *) DFSDM1_Filter0_BASE) -#define DFSDM1_Filter1 ((DFSDM_Filter_TypeDef *) DFSDM1_Filter1_BASE) -#define DFSDM2_Channel0 ((DFSDM_Channel_TypeDef *) DFSDM2_Channel0_BASE) -#define DFSDM2_Channel1 ((DFSDM_Channel_TypeDef *) DFSDM2_Channel1_BASE) -#define DFSDM2_Channel2 ((DFSDM_Channel_TypeDef *) DFSDM2_Channel2_BASE) -#define DFSDM2_Channel3 ((DFSDM_Channel_TypeDef *) DFSDM2_Channel3_BASE) -#define DFSDM2_Channel4 ((DFSDM_Channel_TypeDef *) DFSDM2_Channel4_BASE) -#define DFSDM2_Channel5 ((DFSDM_Channel_TypeDef *) DFSDM2_Channel5_BASE) -#define DFSDM2_Channel6 ((DFSDM_Channel_TypeDef *) DFSDM2_Channel6_BASE) -#define DFSDM2_Channel7 ((DFSDM_Channel_TypeDef *) DFSDM2_Channel7_BASE) -#define DFSDM2_Filter0 ((DFSDM_Filter_TypeDef *) DFSDM2_Filter0_BASE) -#define DFSDM2_Filter1 ((DFSDM_Filter_TypeDef *) DFSDM2_Filter1_BASE) -#define DFSDM2_Filter2 ((DFSDM_Filter_TypeDef *) DFSDM2_Filter2_BASE) -#define DFSDM2_Filter3 ((DFSDM_Filter_TypeDef *) DFSDM2_Filter3_BASE) -#define SAI1 ((SAI_TypeDef *) SAI1_BASE) -#define SAI1_Block_A ((SAI_Block_TypeDef *)SAI1_Block_A_BASE) -#define SAI1_Block_B ((SAI_Block_TypeDef *)SAI1_Block_B_BASE) -#define GPIOA ((GPIO_TypeDef *) GPIOA_BASE) -#define GPIOB ((GPIO_TypeDef *) GPIOB_BASE) -#define GPIOC ((GPIO_TypeDef *) GPIOC_BASE) -#define GPIOD ((GPIO_TypeDef *) GPIOD_BASE) -#define GPIOE ((GPIO_TypeDef *) GPIOE_BASE) -#define GPIOF ((GPIO_TypeDef *) GPIOF_BASE) -#define GPIOG ((GPIO_TypeDef *) GPIOG_BASE) -#define GPIOH ((GPIO_TypeDef *) GPIOH_BASE) -#define CRC ((CRC_TypeDef *) CRC_BASE) -#define RCC ((RCC_TypeDef *) RCC_BASE) -#define FLASH ((FLASH_TypeDef *) FLASH_R_BASE) -#define DMA1 ((DMA_TypeDef *) DMA1_BASE) -#define DMA1_Stream0 ((DMA_Stream_TypeDef *) DMA1_Stream0_BASE) -#define DMA1_Stream1 ((DMA_Stream_TypeDef *) DMA1_Stream1_BASE) -#define DMA1_Stream2 ((DMA_Stream_TypeDef *) DMA1_Stream2_BASE) -#define DMA1_Stream3 ((DMA_Stream_TypeDef *) DMA1_Stream3_BASE) -#define DMA1_Stream4 ((DMA_Stream_TypeDef *) DMA1_Stream4_BASE) -#define DMA1_Stream5 ((DMA_Stream_TypeDef *) DMA1_Stream5_BASE) -#define DMA1_Stream6 ((DMA_Stream_TypeDef *) DMA1_Stream6_BASE) -#define DMA1_Stream7 ((DMA_Stream_TypeDef *) DMA1_Stream7_BASE) -#define DMA2 ((DMA_TypeDef *) DMA2_BASE) -#define DMA2_Stream0 ((DMA_Stream_TypeDef *) DMA2_Stream0_BASE) -#define DMA2_Stream1 ((DMA_Stream_TypeDef *) DMA2_Stream1_BASE) -#define DMA2_Stream2 ((DMA_Stream_TypeDef *) DMA2_Stream2_BASE) -#define DMA2_Stream3 ((DMA_Stream_TypeDef *) DMA2_Stream3_BASE) -#define DMA2_Stream4 ((DMA_Stream_TypeDef *) DMA2_Stream4_BASE) -#define DMA2_Stream5 ((DMA_Stream_TypeDef *) DMA2_Stream5_BASE) -#define DMA2_Stream6 ((DMA_Stream_TypeDef *) DMA2_Stream6_BASE) -#define DMA2_Stream7 ((DMA_Stream_TypeDef *) DMA2_Stream7_BASE) -#define RNG ((RNG_TypeDef *) RNG_BASE) -#define FSMC_Bank1 ((FSMC_Bank1_TypeDef *) FSMC_Bank1_R_BASE) -#define FSMC_Bank1E ((FSMC_Bank1E_TypeDef *) FSMC_Bank1E_R_BASE) -#define QUADSPI ((QUADSPI_TypeDef *) QSPI_R_BASE) -#define DBGMCU ((DBGMCU_TypeDef *) DBGMCU_BASE) -#define USB_OTG_FS ((USB_OTG_GlobalTypeDef *) USB_OTG_FS_PERIPH_BASE) - -/** - * @} - */ - -/** @addtogroup Exported_constants - * @{ - */ - -/** @addtogroup Hardware_Constant_Definition - * @{ - */ -#define LSI_STARTUP_TIME 40U /*!< LSI Maximum startup time in us */ -/** - * @} - */ - - /** @addtogroup Peripheral_Registers_Bits_Definition - * @{ - */ - -/******************************************************************************/ -/* Peripheral Registers_Bits_Definition */ -/******************************************************************************/ - -/******************************************************************************/ -/* */ -/* Analog to Digital Converter */ -/* */ -/******************************************************************************/ - -/******************** Bit definition for ADC_SR register ********************/ -#define ADC_SR_AWD_Pos (0U) -#define ADC_SR_AWD_Msk (0x1UL << ADC_SR_AWD_Pos) /*!< 0x00000001 */ -#define ADC_SR_AWD ADC_SR_AWD_Msk /*!
© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.
- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/** @addtogroup CMSIS - * @{ - */ - -/** @addtogroup stm32f4xx - * @{ - */ - -#ifndef __STM32F4xx_H -#define __STM32F4xx_H - -#ifdef __cplusplus - extern "C" { -#endif /* __cplusplus */ - -/** @addtogroup Library_configuration_section - * @{ - */ - -/** - * @brief STM32 Family - */ -#if !defined (STM32F4) -#define STM32F4 -#endif /* STM32F4 */ - -/* Uncomment the line below according to the target STM32 device used in your - application - */ -#if !defined (STM32F405xx) && !defined (STM32F415xx) && !defined (STM32F407xx) && !defined (STM32F417xx) && \ - !defined (STM32F427xx) && !defined (STM32F437xx) && !defined (STM32F429xx) && !defined (STM32F439xx) && \ - !defined (STM32F401xC) && !defined (STM32F401xE) && !defined (STM32F410Tx) && !defined (STM32F410Cx) && \ - !defined (STM32F410Rx) && !defined (STM32F411xE) && !defined (STM32F446xx) && !defined (STM32F469xx) && \ - !defined (STM32F479xx) && !defined (STM32F412Cx) && !defined (STM32F412Rx) && !defined (STM32F412Vx) && \ - !defined (STM32F412Zx) && !defined (STM32F413xx) && !defined (STM32F423xx) - /* #define STM32F405xx */ /*!< STM32F405RG, STM32F405VG and STM32F405ZG Devices */ - /* #define STM32F415xx */ /*!< STM32F415RG, STM32F415VG and STM32F415ZG Devices */ - /* #define STM32F407xx */ /*!< STM32F407VG, STM32F407VE, STM32F407ZG, STM32F407ZE, STM32F407IG and STM32F407IE Devices */ - /* #define STM32F417xx */ /*!< STM32F417VG, STM32F417VE, STM32F417ZG, STM32F417ZE, STM32F417IG and STM32F417IE Devices */ - /* #define STM32F427xx */ /*!< STM32F427VG, STM32F427VI, STM32F427ZG, STM32F427ZI, STM32F427IG and STM32F427II Devices */ - /* #define STM32F437xx */ /*!< STM32F437VG, STM32F437VI, STM32F437ZG, STM32F437ZI, STM32F437IG and STM32F437II Devices */ - /* #define STM32F429xx */ /*!< STM32F429VG, STM32F429VI, STM32F429ZG, STM32F429ZI, STM32F429BG, STM32F429BI, STM32F429NG, - STM32F439NI, STM32F429IG and STM32F429II Devices */ - /* #define STM32F439xx */ /*!< STM32F439VG, STM32F439VI, STM32F439ZG, STM32F439ZI, STM32F439BG, STM32F439BI, STM32F439NG, - STM32F439NI, STM32F439IG and STM32F439II Devices */ - /* #define STM32F401xC */ /*!< STM32F401CB, STM32F401CC, STM32F401RB, STM32F401RC, STM32F401VB and STM32F401VC Devices */ - /* #define STM32F401xE */ /*!< STM32F401CD, STM32F401RD, STM32F401VD, STM32F401CE, STM32F401RE and STM32F401VE Devices */ - /* #define STM32F410Tx */ /*!< STM32F410T8 and STM32F410TB Devices */ - /* #define STM32F410Cx */ /*!< STM32F410C8 and STM32F410CB Devices */ - /* #define STM32F410Rx */ /*!< STM32F410R8 and STM32F410RB Devices */ - /* #define STM32F411xE */ /*!< STM32F411CC, STM32F411RC, STM32F411VC, STM32F411CE, STM32F411RE and STM32F411VE Devices */ - /* #define STM32F446xx */ /*!< STM32F446MC, STM32F446ME, STM32F446RC, STM32F446RE, STM32F446VC, STM32F446VE, STM32F446ZC, - and STM32F446ZE Devices */ - /* #define STM32F469xx */ /*!< STM32F469AI, STM32F469II, STM32F469BI, STM32F469NI, STM32F469AG, STM32F469IG, STM32F469BG, - STM32F469NG, STM32F469AE, STM32F469IE, STM32F469BE and STM32F469NE Devices */ - /* #define STM32F479xx */ /*!< STM32F479AI, STM32F479II, STM32F479BI, STM32F479NI, STM32F479AG, STM32F479IG, STM32F479BG - and STM32F479NG Devices */ - /* #define STM32F412Cx */ /*!< STM32F412CEU and STM32F412CGU Devices */ - /* #define STM32F412Zx */ /*!< STM32F412ZET, STM32F412ZGT, STM32F412ZEJ and STM32F412ZGJ Devices */ - /* #define STM32F412Vx */ /*!< STM32F412VET, STM32F412VGT, STM32F412VEH and STM32F412VGH Devices */ - /* #define STM32F412Rx */ /*!< STM32F412RET, STM32F412RGT, STM32F412REY and STM32F412RGY Devices */ - /* #define STM32F413xx */ /*!< STM32F413CH, STM32F413MH, STM32F413RH, STM32F413VH, STM32F413ZH, STM32F413CG, STM32F413MG, - STM32F413RG, STM32F413VG and STM32F413ZG Devices */ - /* #define STM32F423xx */ /*!< STM32F423CH, STM32F423RH, STM32F423VH and STM32F423ZH Devices */ -#endif - -/* Tip: To avoid modifying this file each time you need to switch between these - devices, you can define the device in your toolchain compiler preprocessor. - */ -#if !defined (USE_HAL_DRIVER) -/** - * @brief Comment the line below if you will not use the peripherals drivers. - In this case, these drivers will not be included and the application code will - be based on direct access to peripherals registers - */ - /*#define USE_HAL_DRIVER */ -#endif /* USE_HAL_DRIVER */ - -/** - * @brief CMSIS version number V2.6.7 - */ -#define __STM32F4xx_CMSIS_VERSION_MAIN (0x02U) /*!< [31:24] main version */ -#define __STM32F4xx_CMSIS_VERSION_SUB1 (0x06U) /*!< [23:16] sub1 version */ -#define __STM32F4xx_CMSIS_VERSION_SUB2 (0x07U) /*!< [15:8] sub2 version */ -#define __STM32F4xx_CMSIS_VERSION_RC (0x00U) /*!< [7:0] release candidate */ -#define __STM32F4xx_CMSIS_VERSION ((__STM32F4xx_CMSIS_VERSION_MAIN << 24)\ - |(__STM32F4xx_CMSIS_VERSION_SUB1 << 16)\ - |(__STM32F4xx_CMSIS_VERSION_SUB2 << 8 )\ - |(__STM32F4xx_CMSIS_VERSION_RC)) - -/** - * @} - */ - -/** @addtogroup Device_Included - * @{ - */ - -#if defined(STM32F405xx) - #include "stm32f405xx.h" -#elif defined(STM32F415xx) - #include "stm32f415xx.h" -#elif defined(STM32F407xx) - #include "stm32f407xx.h" -#elif defined(STM32F417xx) - #include "stm32f417xx.h" -#elif defined(STM32F427xx) - #include "stm32f427xx.h" -#elif defined(STM32F437xx) - #include "stm32f437xx.h" -#elif defined(STM32F429xx) - #include "stm32f429xx.h" -#elif defined(STM32F439xx) - #include "stm32f439xx.h" -#elif defined(STM32F401xC) - #include "stm32f401xc.h" -#elif defined(STM32F401xE) - #include "stm32f401xe.h" -#elif defined(STM32F410Tx) - #include "stm32f410tx.h" -#elif defined(STM32F410Cx) - #include "stm32f410cx.h" -#elif defined(STM32F410Rx) - #include "stm32f410rx.h" -#elif defined(STM32F411xE) - #include "stm32f411xe.h" -#elif defined(STM32F446xx) - #include "stm32f446xx.h" -#elif defined(STM32F469xx) - #include "stm32f469xx.h" -#elif defined(STM32F479xx) - #include "stm32f479xx.h" -#elif defined(STM32F412Cx) - #include "stm32f412cx.h" -#elif defined(STM32F412Zx) - #include "stm32f412zx.h" -#elif defined(STM32F412Rx) - #include "stm32f412rx.h" -#elif defined(STM32F412Vx) - #include "stm32f412vx.h" -#elif defined(STM32F413xx) - #include "stm32f413xx.h" -#elif defined(STM32F423xx) - #include "stm32f423xx.h" -#else - #error "Please select first the target STM32F4xx device used in your application (in stm32f4xx.h file)" -#endif - -/** - * @} - */ - -/** @addtogroup Exported_types - * @{ - */ -typedef enum -{ - RESET = 0U, - SET = !RESET -} FlagStatus, ITStatus; - -typedef enum -{ - DISABLE = 0U, - ENABLE = !DISABLE -} FunctionalState; -#define IS_FUNCTIONAL_STATE(STATE) (((STATE) == DISABLE) || ((STATE) == ENABLE)) - -typedef enum -{ - SUCCESS = 0U, - ERROR = !SUCCESS -} ErrorStatus; - -/** - * @} - */ - - -/** @addtogroup Exported_macro - * @{ - */ -#define SET_BIT(REG, BIT) ((REG) |= (BIT)) - -#define CLEAR_BIT(REG, BIT) ((REG) &= ~(BIT)) - -#define READ_BIT(REG, BIT) ((REG) & (BIT)) - -#define CLEAR_REG(REG) ((REG) = (0x0)) - -#define WRITE_REG(REG, VAL) ((REG) = (VAL)) - -#define READ_REG(REG) ((REG)) - -#define MODIFY_REG(REG, CLEARMASK, SETMASK) WRITE_REG((REG), (((READ_REG(REG)) & (~(CLEARMASK))) | (SETMASK))) - -#define POSITION_VAL(VAL) (__CLZ(__RBIT(VAL))) - -/* Use of CMSIS compiler intrinsics for register exclusive access */ -/* Atomic 32-bit register access macro to set one or several bits */ -#define ATOMIC_SET_BIT(REG, BIT) \ - do { \ - uint32_t val; \ - do { \ - val = __LDREXW((__IO uint32_t *)&(REG)) | (BIT); \ - } while ((__STREXW(val,(__IO uint32_t *)&(REG))) != 0U); \ - } while(0) - -/* Atomic 32-bit register access macro to clear one or several bits */ -#define ATOMIC_CLEAR_BIT(REG, BIT) \ - do { \ - uint32_t val; \ - do { \ - val = __LDREXW((__IO uint32_t *)&(REG)) & ~(BIT); \ - } while ((__STREXW(val,(__IO uint32_t *)&(REG))) != 0U); \ - } while(0) - -/* Atomic 32-bit register access macro to clear and set one or several bits */ -#define ATOMIC_MODIFY_REG(REG, CLEARMSK, SETMASK) \ - do { \ - uint32_t val; \ - do { \ - val = (__LDREXW((__IO uint32_t *)&(REG)) & ~(CLEARMSK)) | (SETMASK); \ - } while ((__STREXW(val,(__IO uint32_t *)&(REG))) != 0U); \ - } while(0) - -/* Atomic 16-bit register access macro to set one or several bits */ -#define ATOMIC_SETH_BIT(REG, BIT) \ - do { \ - uint16_t val; \ - do { \ - val = __LDREXH((__IO uint16_t *)&(REG)) | (BIT); \ - } while ((__STREXH(val,(__IO uint16_t *)&(REG))) != 0U); \ - } while(0) - -/* Atomic 16-bit register access macro to clear one or several bits */ -#define ATOMIC_CLEARH_BIT(REG, BIT) \ - do { \ - uint16_t val; \ - do { \ - val = __LDREXH((__IO uint16_t *)&(REG)) & ~(BIT); \ - } while ((__STREXH(val,(__IO uint16_t *)&(REG))) != 0U); \ - } while(0) - -/* Atomic 16-bit register access macro to clear and set one or several bits */ -#define ATOMIC_MODIFYH_REG(REG, CLEARMSK, SETMASK) \ - do { \ - uint16_t val; \ - do { \ - val = (__LDREXH((__IO uint16_t *)&(REG)) & ~(CLEARMSK)) | (SETMASK); \ - } while ((__STREXH(val,(__IO uint16_t *)&(REG))) != 0U); \ - } while(0) - -/** - * @} - */ - -#if defined (USE_HAL_DRIVER) - #include "stm32f4xx_hal.h" -#endif /* USE_HAL_DRIVER */ - -#ifdef __cplusplus -} -#endif /* __cplusplus */ - -#endif /* __STM32F4xx_H */ -/** - * @} - */ - -/** - * @} - */ - - - - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/stm32f4xx_hal_conf.h b/body/board/inc/stm32f4xx_hal_conf.h deleted file mode 100644 index 37e7626..0000000 --- a/body/board/inc/stm32f4xx_hal_conf.h +++ /dev/null @@ -1,477 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_conf.h - * @author MCD Application Team - * @brief HAL configuration file. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_CONF_H -#define __STM32F4xx_HAL_CONF_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ - -/* ########################## Module Selection ############################## */ -/** - * @brief This is the list of modules to be used in the HAL driver - */ -#define HAL_MODULE_ENABLED -#define HAL_ADC_MODULE_ENABLED -/* #define HAL_CAN_MODULE_ENABLED */ -/* #define HAL_CAN_LEGACY_MODULE_ENABLED */ -/* #define HAL_CRC_MODULE_ENABLED */ -/* #define HAL_CEC_MODULE_ENABLED */ -/* #define HAL_CRYP_MODULE_ENABLED */ -/* #define HAL_DAC_MODULE_ENABLED */ -/* #define HAL_DCMI_MODULE_ENABLED */ -#define HAL_DMA_MODULE_ENABLED -/* #define HAL_ETH_MODULE_ENABLED */ -#define HAL_FLASH_MODULE_ENABLED -/* #define HAL_NAND_MODULE_ENABLED */ -/* #define HAL_NOR_MODULE_ENABLED */ -/* #define HAL_PCCARD_MODULE_ENABLED */ -/* #define HAL_SRAM_MODULE_ENABLED */ -/* #define HAL_SDRAM_MODULE_ENABLED */ -/* #define HAL_HASH_MODULE_ENABLED */ -#define HAL_GPIO_MODULE_ENABLED -#define HAL_I2C_MODULE_ENABLED -/* #define HAL_I2S_MODULE_ENABLED */ -/* #define HAL_IWDG_MODULE_ENABLED */ -/* #define HAL_LTDC_MODULE_ENABLED */ -#define HAL_PWR_MODULE_ENABLED -/* #define HAL_QSPI_MODULE_ENABLED */ -#define HAL_RCC_MODULE_ENABLED -/* #define HAL_RNG_MODULE_ENABLED */ -/* #define HAL_RTC_MODULE_ENABLED */ -/* #define HAL_SAI_MODULE_ENABLED */ -/* #define HAL_SD_MODULE_ENABLED */ -/* #define HAL_SPI_MODULE_ENABLED */ -#define HAL_TIM_MODULE_ENABLED -#define HAL_UART_MODULE_ENABLED -/* #define HAL_USART_MODULE_ENABLED */ -/* #define HAL_IRDA_MODULE_ENABLED */ -/* #define HAL_SMARTCARD_MODULE_ENABLED */ -/* #define HAL_WWDG_MODULE_ENABLED */ -#define HAL_CORTEX_MODULE_ENABLED -/* #define HAL_PCD_MODULE_ENABLED */ -/* #define HAL_HCD_MODULE_ENABLED */ -/* #define HAL_FMPI2C_MODULE_ENABLED */ -/* #define HAL_SPDIFRX_MODULE_ENABLED */ -/* #define HAL_DFSDM_MODULE_ENABLED */ -/* #define HAL_LPTIM_MODULE_ENABLED */ - -/* ########################## HSE/HSI Values adaptation ##################### */ -/** - * @brief Adjust the value of External High Speed oscillator (HSE) used in your application. - * This value is used by the RCC HAL module to compute the system frequency - * (when HSE is used as system clock source, directly or through the PLL). - */ -#if !defined (HSE_VALUE) - #define HSE_VALUE 8000000U /*!< Value of the External oscillator in Hz */ -#endif /* HSE_VALUE */ - -#if !defined (HSE_STARTUP_TIMEOUT) - #define HSE_STARTUP_TIMEOUT 100U /*!< Time out for HSE start up, in ms */ -#endif /* HSE_STARTUP_TIMEOUT */ - -/** - * @brief Internal High Speed oscillator (HSI) value. - * This value is used by the RCC HAL module to compute the system frequency - * (when HSI is used as system clock source, directly or through the PLL). - */ -#if !defined (HSI_VALUE) - #define HSI_VALUE 16000000U /*!< Value of the Internal oscillator in Hz*/ -#endif /* HSI_VALUE */ - -/** - * @brief Internal Low Speed oscillator (LSI) value. - */ -#if !defined (LSI_VALUE) - #define LSI_VALUE 32000U /*!< LSI Typical Value in Hz*/ -#endif /* LSI_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz - The real value may vary depending on the variations - in voltage and temperature.*/ -/** - * @brief External Low Speed oscillator (LSE) value. - */ -#if !defined (LSE_VALUE) - #define LSE_VALUE 32768U /*!< Value of the External Low Speed oscillator in Hz */ -#endif /* LSE_VALUE */ - -#if !defined (LSE_STARTUP_TIMEOUT) - #define LSE_STARTUP_TIMEOUT 5000U /*!< Time out for LSE start up, in ms */ -#endif /* LSE_STARTUP_TIMEOUT */ - -/** - * @brief External clock source for I2S peripheral - * This value is used by the I2S HAL module to compute the I2S clock source - * frequency, this source is inserted directly through I2S_CKIN pad. - */ -#if !defined (EXTERNAL_CLOCK_VALUE) - #define EXTERNAL_CLOCK_VALUE 12288000U /*!< Value of the External oscillator in Hz*/ -#endif /* EXTERNAL_CLOCK_VALUE */ - -/* Tip: To avoid modifying this file each time you need to use different HSE, - === you can define the HSE value in your toolchain compiler preprocessor. */ - -/* ########################### System Configuration ######################### */ -/** - * @brief This is the HAL system configuration section - */ -#define VDD_VALUE 3300U /*!< Value of VDD in mv */ -#define TICK_INT_PRIORITY 0x0FU /*!< tick interrupt priority */ -#define USE_RTOS 0U -#define PREFETCH_ENABLE 1U -#define INSTRUCTION_CACHE_ENABLE 1U -#define DATA_CACHE_ENABLE 1U - -#define USE_HAL_ADC_REGISTER_CALLBACKS 0U /* ADC register callback disabled */ -#define USE_HAL_CAN_REGISTER_CALLBACKS 0U /* CAN register callback disabled */ -#define USE_HAL_CEC_REGISTER_CALLBACKS 0U /* CEC register callback disabled */ -#define USE_HAL_CRYP_REGISTER_CALLBACKS 0U /* CRYP register callback disabled */ -#define USE_HAL_DAC_REGISTER_CALLBACKS 0U /* DAC register callback disabled */ -#define USE_HAL_DCMI_REGISTER_CALLBACKS 0U /* DCMI register callback disabled */ -#define USE_HAL_DFSDM_REGISTER_CALLBACKS 0U /* DFSDM register callback disabled */ -#define USE_HAL_DMA2D_REGISTER_CALLBACKS 0U /* DMA2D register callback disabled */ -#define USE_HAL_DSI_REGISTER_CALLBACKS 0U /* DSI register callback disabled */ -#define USE_HAL_ETH_REGISTER_CALLBACKS 0U /* ETH register callback disabled */ -#define USE_HAL_HASH_REGISTER_CALLBACKS 0U /* HASH register callback disabled */ -#define USE_HAL_HCD_REGISTER_CALLBACKS 0U /* HCD register callback disabled */ -#define USE_HAL_I2C_REGISTER_CALLBACKS 0U /* I2C register callback disabled */ -#define USE_HAL_FMPI2C_REGISTER_CALLBACKS 0U /* FMPI2C register callback disabled */ -#define USE_HAL_I2S_REGISTER_CALLBACKS 0U /* I2S register callback disabled */ -#define USE_HAL_IRDA_REGISTER_CALLBACKS 0U /* IRDA register callback disabled */ -#define USE_HAL_LPTIM_REGISTER_CALLBACKS 0U /* LPTIM register callback disabled */ -#define USE_HAL_LTDC_REGISTER_CALLBACKS 0U /* LTDC register callback disabled */ -#define USE_HAL_MMC_REGISTER_CALLBACKS 0U /* MMC register callback disabled */ -#define USE_HAL_NAND_REGISTER_CALLBACKS 0U /* NAND register callback disabled */ -#define USE_HAL_NOR_REGISTER_CALLBACKS 0U /* NOR register callback disabled */ -#define USE_HAL_PCCARD_REGISTER_CALLBACKS 0U /* PCCARD register callback disabled */ -#define USE_HAL_PCD_REGISTER_CALLBACKS 0U /* PCD register callback disabled */ -#define USE_HAL_QSPI_REGISTER_CALLBACKS 0U /* QSPI register callback disabled */ -#define USE_HAL_RNG_REGISTER_CALLBACKS 0U /* RNG register callback disabled */ -#define USE_HAL_RTC_REGISTER_CALLBACKS 0U /* RTC register callback disabled */ -#define USE_HAL_SAI_REGISTER_CALLBACKS 0U /* SAI register callback disabled */ -#define USE_HAL_SD_REGISTER_CALLBACKS 0U /* SD register callback disabled */ -#define USE_HAL_SMARTCARD_REGISTER_CALLBACKS 0U /* SMARTCARD register callback disabled */ -#define USE_HAL_SDRAM_REGISTER_CALLBACKS 0U /* SDRAM register callback disabled */ -#define USE_HAL_SRAM_REGISTER_CALLBACKS 0U /* SRAM register callback disabled */ -#define USE_HAL_SPDIFRX_REGISTER_CALLBACKS 0U /* SPDIFRX register callback disabled */ -#define USE_HAL_SMBUS_REGISTER_CALLBACKS 0U /* SMBUS register callback disabled */ -#define USE_HAL_SPI_REGISTER_CALLBACKS 0U /* SPI register callback disabled */ -#define USE_HAL_TIM_REGISTER_CALLBACKS 0U /* TIM register callback disabled */ -#define USE_HAL_UART_REGISTER_CALLBACKS 0U /* UART register callback disabled */ -#define USE_HAL_USART_REGISTER_CALLBACKS 0U /* USART register callback disabled */ -#define USE_HAL_WWDG_REGISTER_CALLBACKS 0U /* WWDG register callback disabled */ - -/* ########################## Assert Selection ############################## */ -/** - * @brief Uncomment the line below to expanse the "assert_param" macro in the - * HAL drivers code - */ -/* #define USE_FULL_ASSERT 1 */ - -/* ################## Ethernet peripheral configuration for NUCLEO 144 board ##################### */ - -/* Section 1 : Ethernet peripheral configuration */ - -/* MAC ADDRESS: MAC_ADDR0:MAC_ADDR1:MAC_ADDR2:MAC_ADDR3:MAC_ADDR4:MAC_ADDR5 */ -#define MAC_ADDR0 2U -#define MAC_ADDR1 0U -#define MAC_ADDR2 0U -#define MAC_ADDR3 0U -#define MAC_ADDR4 0U -#define MAC_ADDR5 0U - -/* Definition of the Ethernet driver buffers size and count */ -#define ETH_RX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for receive */ -#define ETH_TX_BUF_SIZE ETH_MAX_PACKET_SIZE /* buffer size for transmit */ -#define ETH_RXBUFNB 5U /* 5 Rx buffers of size ETH_RX_BUF_SIZE */ -#define ETH_TXBUFNB 5U /* 5 Tx buffers of size ETH_TX_BUF_SIZE */ - -/* Section 2: PHY configuration section */ -/* LAN8742A PHY Address*/ -#define LAN8742A_PHY_ADDRESS 0x00U -/* PHY Reset delay these values are based on a 1 ms Systick interrupt*/ -#define PHY_RESET_DELAY 0x00000FFFU -/* PHY Configuration delay */ -#define PHY_CONFIG_DELAY 0x00000FFFU - -#define PHY_READ_TO 0x0000FFFFU -#define PHY_WRITE_TO 0x0000FFFFU - -/* Section 3: Common PHY Registers */ - -#define PHY_BCR ((uint16_t)0x00) /*!< Transceiver Basic Control Register */ -#define PHY_BSR ((uint16_t)0x01) /*!< Transceiver Basic Status Register */ - -#define PHY_RESET ((uint16_t)0x8000) /*!< PHY Reset */ -#define PHY_LOOPBACK ((uint16_t)0x4000) /*!< Select loop-back mode */ -#define PHY_FULLDUPLEX_100M ((uint16_t)0x2100) /*!< Set the full-duplex mode at 100 Mb/s */ -#define PHY_HALFDUPLEX_100M ((uint16_t)0x2000) /*!< Set the half-duplex mode at 100 Mb/s */ -#define PHY_FULLDUPLEX_10M ((uint16_t)0x0100) /*!< Set the full-duplex mode at 10 Mb/s */ -#define PHY_HALFDUPLEX_10M ((uint16_t)0x0000) /*!< Set the half-duplex mode at 10 Mb/s */ -#define PHY_AUTONEGOTIATION ((uint16_t)0x1000) /*!< Enable auto-negotiation function */ -#define PHY_RESTART_AUTONEGOTIATION ((uint16_t)0x0200) /*!< Restart auto-negotiation function */ -#define PHY_POWERDOWN ((uint16_t)0x0800) /*!< Select the power down mode */ -#define PHY_ISOLATE ((uint16_t)0x0400) /*!< Isolate PHY from MII */ - -#define PHY_AUTONEGO_COMPLETE ((uint16_t)0x0020) /*!< Auto-Negotiation process completed */ -#define PHY_LINKED_STATUS ((uint16_t)0x0004) /*!< Valid link established */ -#define PHY_JABBER_DETECTION ((uint16_t)0x0002) /*!< Jabber condition detected */ - -/* Section 4: Extended PHY Registers */ - -#define PHY_SR ((uint16_t)0x1F) /*!< PHY special control/ status register Offset */ - -#define PHY_SPEED_STATUS ((uint16_t)0x0004) /*!< PHY Speed mask */ -#define PHY_DUPLEX_STATUS ((uint16_t)0x0010) /*!< PHY Duplex mask */ - - -#define PHY_ISFR ((uint16_t)0x1D) /*!< PHY Interrupt Source Flag register Offset */ -#define PHY_ISFR_INT4 ((uint16_t)0x0010) /*!< PHY Link down inturrupt */ - -/* ################## SPI peripheral configuration ########################## */ - -/* CRC FEATURE: Use to activate CRC feature inside HAL SPI Driver -* Activated: CRC code is present inside driver -* Deactivated: CRC code cleaned from driver -*/ - -#define USE_SPI_CRC 1U - -/* Includes ------------------------------------------------------------------*/ -/** - * @brief Include module's header file - */ - -#ifdef HAL_RCC_MODULE_ENABLED - #include "stm32f4xx_hal_rcc.h" - #include "stm32f4xx_hal_rcc_ex.h" -#endif /* HAL_RCC_MODULE_ENABLED */ - -#ifdef HAL_GPIO_MODULE_ENABLED - #include "stm32f4xx_hal_gpio.h" - #include "stm32f4xx_hal_gpio_ex.h" -#endif /* HAL_GPIO_MODULE_ENABLED */ - -#ifdef HAL_DMA_MODULE_ENABLED - #include "stm32f4xx_hal_dma.h" - #include "stm32f4xx_hal_dma_ex.h" -#endif /* HAL_DMA_MODULE_ENABLED */ - -#ifdef HAL_CORTEX_MODULE_ENABLED - #include "stm32f4xx_hal_cortex.h" -#endif /* HAL_CORTEX_MODULE_ENABLED */ - -#ifdef HAL_ADC_MODULE_ENABLED - #include "stm32f4xx_hal_adc.h" -#endif /* HAL_ADC_MODULE_ENABLED */ - -#ifdef HAL_CAN_MODULE_ENABLED - #include "stm32f4xx_hal_can.h" -#endif /* HAL_CAN_MODULE_ENABLED */ - -#ifdef HAL_CAN_LEGACY_MODULE_ENABLED - #include "stm32f4xx_hal_can_legacy.h" -#endif /* HAL_CAN_LEGACY_MODULE_ENABLED */ - -#ifdef HAL_CRC_MODULE_ENABLED - #include "stm32f4xx_hal_crc.h" -#endif /* HAL_CRC_MODULE_ENABLED */ - -#ifdef HAL_CRYP_MODULE_ENABLED - #include "stm32f4xx_hal_cryp.h" - #include "stm32f4xx_hal_cryp_ex.h" -#endif /* HAL_CRYP_MODULE_ENABLED */ - -#ifdef HAL_DAC_MODULE_ENABLED - #include "stm32f4xx_hal_dac.h" -#endif /* HAL_DAC_MODULE_ENABLED */ - -#ifdef HAL_DCMI_MODULE_ENABLED - #include "stm32f4xx_hal_dcmi.h" -#endif /* HAL_DCMI_MODULE_ENABLED */ - -#ifdef HAL_ETH_MODULE_ENABLED - #include "stm32f4xx_hal_eth.h" -#endif /* HAL_ETH_MODULE_ENABLED */ - -#ifdef HAL_FLASH_MODULE_ENABLED - #include "stm32f4xx_hal_flash.h" - #include "stm32f4xx_hal_flash_ex.h" -#endif /* HAL_FLASH_MODULE_ENABLED */ - -#ifdef HAL_SRAM_MODULE_ENABLED - #include "stm32f4xx_hal_sram.h" -#endif /* HAL_SRAM_MODULE_ENABLED */ - -#ifdef HAL_NOR_MODULE_ENABLED - #include "stm32f4xx_hal_nor.h" -#endif /* HAL_NOR_MODULE_ENABLED */ - -#ifdef HAL_NAND_MODULE_ENABLED - #include "stm32f4xx_hal_nand.h" -#endif /* HAL_NAND_MODULE_ENABLED */ - -#ifdef HAL_PCCARD_MODULE_ENABLED - #include "stm32f4xx_hal_pccard.h" -#endif /* HAL_PCCARD_MODULE_ENABLED */ - -#ifdef HAL_SDRAM_MODULE_ENABLED - #include "stm32f4xx_hal_sdram.h" -#endif /* HAL_SDRAM_MODULE_ENABLED */ - -#ifdef HAL_HASH_MODULE_ENABLED - #include "stm32f4xx_hal_hash.h" -#endif /* HAL_HASH_MODULE_ENABLED */ - -#ifdef HAL_I2C_MODULE_ENABLED - #include "stm32f4xx_hal_i2c.h" - #include "stm32f4xx_hal_i2c_ex.h" -#endif /* HAL_I2C_MODULE_ENABLED */ - -#ifdef HAL_I2S_MODULE_ENABLED - #include "stm32f4xx_hal_i2s.h" - #include "stm32f4xx_hal_i2s_ex.h" -#endif /* HAL_I2S_MODULE_ENABLED */ - -#ifdef HAL_IWDG_MODULE_ENABLED - #include "stm32f4xx_hal_iwdg.h" -#endif /* HAL_IWDG_MODULE_ENABLED */ - -#ifdef HAL_LTDC_MODULE_ENABLED - #include "stm32f4xx_hal_ltdc.h" -#endif /* HAL_LTDC_MODULE_ENABLED */ - -#ifdef HAL_PWR_MODULE_ENABLED - #include "stm32f4xx_hal_pwr.h" - #include "stm32f4xx_hal_pwr_ex.h" -#endif /* HAL_PWR_MODULE_ENABLED */ - -#ifdef HAL_RNG_MODULE_ENABLED - #include "stm32f4xx_hal_rng.h" -#endif /* HAL_RNG_MODULE_ENABLED */ - -#ifdef HAL_RTC_MODULE_ENABLED - #include "stm32f4xx_hal_rtc.h" -#endif /* HAL_RTC_MODULE_ENABLED */ - -#ifdef HAL_SAI_MODULE_ENABLED - #include "stm32f4xx_hal_sai.h" -#endif /* HAL_SAI_MODULE_ENABLED */ - -#ifdef HAL_SD_MODULE_ENABLED - #include "stm32f4xx_hal_sd.h" -#endif /* HAL_SD_MODULE_ENABLED */ - -#ifdef HAL_SPI_MODULE_ENABLED - #include "stm32f4xx_hal_spi.h" -#endif /* HAL_SPI_MODULE_ENABLED */ - -#ifdef HAL_TIM_MODULE_ENABLED - #include "stm32f4xx_hal_tim.h" -#endif /* HAL_TIM_MODULE_ENABLED */ - -#ifdef HAL_UART_MODULE_ENABLED - #include "stm32f4xx_hal_uart.h" -#endif /* HAL_UART_MODULE_ENABLED */ - -#ifdef HAL_USART_MODULE_ENABLED - #include "stm32f4xx_hal_usart.h" -#endif /* HAL_USART_MODULE_ENABLED */ - -#ifdef HAL_IRDA_MODULE_ENABLED - #include "stm32f4xx_hal_irda.h" -#endif /* HAL_IRDA_MODULE_ENABLED */ - -#ifdef HAL_SMARTCARD_MODULE_ENABLED - #include "stm32f4xx_hal_smartcard.h" -#endif /* HAL_SMARTCARD_MODULE_ENABLED */ - -#ifdef HAL_WWDG_MODULE_ENABLED - #include "stm32f4xx_hal_wwdg.h" -#endif /* HAL_WWDG_MODULE_ENABLED */ - -#ifdef HAL_PCD_MODULE_ENABLED - #include "stm32f4xx_hal_pcd.h" -#endif /* HAL_PCD_MODULE_ENABLED */ - -#ifdef HAL_HCD_MODULE_ENABLED - #include "stm32f4xx_hal_hcd.h" -#endif /* HAL_HCD_MODULE_ENABLED */ - -#ifdef HAL_QSPI_MODULE_ENABLED - #include "stm32f4xx_hal_qspi.h" -#endif /* HAL_QSPI_MODULE_ENABLED */ - -#ifdef HAL_CEC_MODULE_ENABLED - #include "stm32f4xx_hal_cec.h" -#endif /* HAL_CEC_MODULE_ENABLED */ - -#ifdef HAL_FMPI2C_MODULE_ENABLED - #include "stm32f4xx_hal_fmpi2c.h" -#endif /* HAL_FMPI2C_MODULE_ENABLED */ - -#ifdef HAL_SPDIFRX_MODULE_ENABLED - #include "stm32f4xx_hal_spdifrx.h" -#endif /* HAL_SPDIFRX_MODULE_ENABLED */ - -#ifdef HAL_DFSDM_MODULE_ENABLED - #include "stm32f4xx_hal_dfsdm.h" -#endif /* HAL_DFSDM_MODULE_ENABLED */ - -#ifdef HAL_LPTIM_MODULE_ENABLED - #include "stm32f4xx_hal_lptim.h" -#endif /* HAL_LPTIM_MODULE_ENABLED */ - -/* Exported macro ------------------------------------------------------------*/ -#ifdef USE_FULL_ASSERT -/** - * @brief The assert_param macro is used for function's parameters check. - * @param expr: If expr is false, it calls assert_failed function - * which reports the name of the source file and the source - * line number of the call that failed. - * If expr is true, it returns no value. - * @retval None - */ - #define assert_param(expr) ((expr) ? (void)0 : assert_failed((uint8_t *)__FILE__, __LINE__)) -/* Exported functions ------------------------------------------------------- */ - void assert_failed(uint8_t* file, uint32_t line); -#else - #define assert_param(expr) ((void)0U) -#endif /* USE_FULL_ASSERT */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_CONF_H */ - - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/stm32f4xx_it.h b/body/board/inc/stm32f4xx_it.h deleted file mode 100644 index 47e94ac..0000000 --- a/body/board/inc/stm32f4xx_it.h +++ /dev/null @@ -1,50 +0,0 @@ -/** - ****************************************************************************** - * @file GPIO/GPIO_IOToggle/Inc/stm32f4xx_it.h - * @author MCD Application Team - * @brief This file contains the headers of the interrupt handlers. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_IT_H -#define __STM32F4xx_IT_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/* Exported macro ------------------------------------------------------------*/ -/* Exported functions ------------------------------------------------------- */ - -void NMI_Handler(void); -void HardFault_Handler(void); -void MemManage_Handler(void); -void BusFault_Handler(void); -void UsageFault_Handler(void); -void SVC_Handler(void); -void DebugMon_Handler(void); -void PendSV_Handler(void); -void SysTick_Handler(void); - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_IT_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/system_stm32f4xx.h b/body/board/inc/system_stm32f4xx.h deleted file mode 100644 index 99cb936..0000000 --- a/body/board/inc/system_stm32f4xx.h +++ /dev/null @@ -1,122 +0,0 @@ -/** - ****************************************************************************** - * @file system_stm32f4xx.h - * @author MCD Application Team - * @brief CMSIS Cortex-M4 Device System Source File for STM32F4xx devices. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT(c) 2017 STMicroelectronics

- * - * Redistribution and use in source and binary forms, with or without modification, - * are permitted provided that the following conditions are met: - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE - * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL - * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR - * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, - * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE - * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************** - */ - -/** @addtogroup CMSIS - * @{ - */ - -/** @addtogroup stm32f4xx_system - * @{ - */ - -/** - * @brief Define to prevent recursive inclusion - */ -#ifndef __SYSTEM_STM32F4XX_H -#define __SYSTEM_STM32F4XX_H - -#ifdef __cplusplus - extern "C" { -#endif - -/** @addtogroup STM32F4xx_System_Includes - * @{ - */ - -/** - * @} - */ - - -/** @addtogroup STM32F4xx_System_Exported_types - * @{ - */ - /* This variable is updated in three ways: - 1) by calling CMSIS function SystemCoreClockUpdate() - 2) by calling HAL API function HAL_RCC_GetSysClockFreq() - 3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency - Note: If you use this function to configure the system clock; then there - is no need to call the 2 first functions listed above, since SystemCoreClock - variable is updated automatically. - */ -extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */ - -extern const uint8_t AHBPrescTable[16]; /*!< AHB prescalers table values */ -extern const uint8_t APBPrescTable[8]; /*!< APB prescalers table values */ - -/** - * @} - */ - -/** @addtogroup STM32F4xx_System_Exported_Constants - * @{ - */ - -/** - * @} - */ - -/** @addtogroup STM32F4xx_System_Exported_Macros - * @{ - */ - -/** - * @} - */ - -/** @addtogroup STM32F4xx_System_Exported_Functions - * @{ - */ - -extern void SystemInit(void); -extern void SystemCoreClockUpdate(void); -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /*__SYSTEM_STM32F4XX_H */ - -/** - * @} - */ - -/** - * @} - */ -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/body/board/inc/tz_context.h b/body/board/inc/tz_context.h deleted file mode 100644 index 0d09749..0000000 --- a/body/board/inc/tz_context.h +++ /dev/null @@ -1,70 +0,0 @@ -/****************************************************************************** - * @file tz_context.h - * @brief Context Management for Armv8-M TrustZone - * @version V1.0.1 - * @date 10. January 2018 - ******************************************************************************/ -/* - * Copyright (c) 2017-2018 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef TZ_CONTEXT_H -#define TZ_CONTEXT_H - -#include - -#ifndef TZ_MODULEID_T -#define TZ_MODULEID_T -/// \details Data type that identifies secure software modules called by a process. -typedef uint32_t TZ_ModuleId_t; -#endif - -/// \details TZ Memory ID identifies an allocated memory slot. -typedef uint32_t TZ_MemoryId_t; - -/// Initialize secure context memory system -/// \return execution status (1: success, 0: error) -uint32_t TZ_InitContextSystem_S (void); - -/// Allocate context memory for calling secure software modules in TrustZone -/// \param[in] module identifies software modules called from non-secure mode -/// \return value != 0 id TrustZone memory slot identifier -/// \return value 0 no memory available or internal error -TZ_MemoryId_t TZ_AllocModuleContext_S (TZ_ModuleId_t module); - -/// Free context memory that was previously allocated with \ref TZ_AllocModuleContext_S -/// \param[in] id TrustZone memory slot identifier -/// \return execution status (1: success, 0: error) -uint32_t TZ_FreeModuleContext_S (TZ_MemoryId_t id); - -/// Load secure context (called on RTOS thread context switch) -/// \param[in] id TrustZone memory slot identifier -/// \return execution status (1: success, 0: error) -uint32_t TZ_LoadContext_S (TZ_MemoryId_t id); - -/// Store secure context (called on RTOS thread context switch) -/// \param[in] id TrustZone memory slot identifier -/// \return execution status (1: success, 0: error) -uint32_t TZ_StoreContext_S (TZ_MemoryId_t id); - -#endif // TZ_CONTEXT_H diff --git a/body/board/libc.h b/body/board/libc.h deleted file mode 100644 index 1e32d42..0000000 --- a/body/board/libc.h +++ /dev/null @@ -1,64 +0,0 @@ -// **** libc **** - -void delay(uint32_t a) { - volatile uint32_t i; - for (i = 0; i < a; i++); -} - -void *memset(void *str, int c, unsigned int n) { - uint8_t *s = str; - for (unsigned int i = 0; i < n; i++) { - *s = c; - s++; - } - return str; -} - -#define UNALIGNED(X, Y) \ - (((uint32_t)(X) & (sizeof(uint32_t) - 1U)) | ((uint32_t)(Y) & (sizeof(uint32_t) - 1U))) - -void *memcpy(void *dest, const void *src, unsigned int len) { - unsigned int n = len; - uint8_t *d8 = dest; - const uint8_t *s8 = src; - - if ((n >= 4U) && !UNALIGNED(s8, d8)) { - uint32_t *d32 = (uint32_t *)d8; // cppcheck-suppress misra-c2012-11.3 ; already checked that it's properly aligned - const uint32_t *s32 = (const uint32_t *)s8; // cppcheck-suppress misra-c2012-11.3 ; already checked that it's properly aligned - - while(n >= 16U) { - *d32 = *s32; d32++; s32++; - *d32 = *s32; d32++; s32++; - *d32 = *s32; d32++; s32++; - *d32 = *s32; d32++; s32++; - n -= 16U; - } - - while(n >= 4U) { - *d32 = *s32; d32++; s32++; - n -= 4U; - } - - d8 = (uint8_t *)d32; - s8 = (const uint8_t *)s32; - } - while (n-- > 0U) { - *d8 = *s8; d8++; s8++; - } - return dest; -} - -int memcmp(const void * ptr1, const void * ptr2, unsigned int num) { - int ret = 0; - const uint8_t *p1 = ptr1; - const uint8_t *p2 = ptr2; - for (unsigned int i = 0; i < num; i++) { - if (*p1 != *p2) { - ret = -1; - break; - } - p1++; - p2++; - } - return ret; -} diff --git a/body/board/obj/body.bin b/body/board/obj/body.bin new file mode 100755 index 0000000..dd56934 Binary files /dev/null and b/body/board/obj/body.bin differ diff --git a/body/board/obj/body.bin.signed b/body/board/obj/body.bin.signed new file mode 100644 index 0000000..3f0e789 Binary files /dev/null and b/body/board/obj/body.bin.signed differ diff --git a/body/board/obj/body.elf b/body/board/obj/body.elf new file mode 100755 index 0000000..297ff1d Binary files /dev/null and b/body/board/obj/body.elf differ diff --git a/body/board/obj/bootstub.body.bin b/body/board/obj/bootstub.body.bin new file mode 100755 index 0000000..b169280 Binary files /dev/null and b/body/board/obj/bootstub.body.bin differ diff --git a/body/board/obj/bootstub.body.elf b/body/board/obj/bootstub.body.elf new file mode 100755 index 0000000..4f0da78 Binary files /dev/null and b/body/board/obj/bootstub.body.elf differ diff --git a/body/board/provision.h b/body/board/provision.h deleted file mode 100644 index 0e549db..0000000 --- a/body/board/provision.h +++ /dev/null @@ -1,15 +0,0 @@ -#define PROVISION_CHUNK_LEN 0x20U -#define PROVISION_CHUNK_ADDRESS 0x1FFF79E0U - -void get_provision_chunk(uint8_t *resp) { - (void)memcpy(resp, (uint8_t *)PROVISION_CHUNK_ADDRESS, PROVISION_CHUNK_LEN); - if (memcmp(resp, "\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff", 0x20) == 0) { - (void)memcpy(resp, "unprovisioned\x00\x00\x00testing123\x00\x00\xa3\xa6\x99\xec", 0x20); - } -} - -uint8_t chunk[PROVISION_CHUNK_LEN]; -bool is_provisioned(void) { - (void)memcpy(chunk, (uint8_t *)PROVISION_CHUNK_ADDRESS, PROVISION_CHUNK_LEN); - return (memcmp(chunk, "\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff", 0x20) != 0); -} diff --git a/body/board/setup.h b/body/board/setup.h deleted file mode 100644 index 898b2f3..0000000 --- a/body/board/setup.h +++ /dev/null @@ -1,372 +0,0 @@ -// Define to prevent recursive inclusion -#ifndef SETUP_H -#define SETUP_H - -#include "stm32f4xx_hal.h" - -TIM_HandleTypeDef htim_right; -TIM_HandleTypeDef htim_left; -ADC_HandleTypeDef hadc; -I2C_HandleTypeDef hi2c1; - -volatile adc_buf_t adc_buffer; -extern board_t board; - - -void MX_GPIO_Clocks_Init(void) { - /* GPIO Ports Clock Enable */ - __HAL_RCC_GPIOA_CLK_ENABLE(); - __HAL_RCC_GPIOB_CLK_ENABLE(); - __HAL_RCC_GPIOC_CLK_ENABLE(); - __HAL_RCC_GPIOD_CLK_ENABLE(); - - __HAL_RCC_CAN1_CLK_ENABLE(); - __HAL_RCC_CAN2_CLK_ENABLE(); -} - -void MX_GPIO_Common_Init(void) { - GPIO_InitTypeDef GPIO_InitStruct = { 0 }; - - GPIO_InitStruct.Mode = GPIO_MODE_INPUT; - GPIO_InitStruct.Pull = GPIO_NOPULL; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_LOW; - - GPIO_InitStruct.Pin = board.hall_left.hall_pinA; - HAL_GPIO_Init(board.hall_left.hall_portA, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = board.hall_left.hall_pinB; - HAL_GPIO_Init(board.hall_left.hall_portB, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = board.hall_left.hall_pinC; - HAL_GPIO_Init(board.hall_left.hall_portC, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = board.hall_right.hall_pinA; - HAL_GPIO_Init(board.hall_right.hall_portA, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = board.hall_right.hall_pinB; - HAL_GPIO_Init(board.hall_right.hall_portB, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = board.hall_right.hall_pinC; - HAL_GPIO_Init(board.hall_right.hall_portC, &GPIO_InitStruct); - - GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Pin = CHARGER_PIN; - HAL_GPIO_Init(CHARGER_PORT, &GPIO_InitStruct); - - GPIO_InitStruct.Pull = GPIO_NOPULL; - - GPIO_InitStruct.Pin = BUTTON_PIN; - HAL_GPIO_Init(BUTTON_PORT, &GPIO_InitStruct); - - - GPIO_InitStruct.Mode = GPIO_MODE_OUTPUT_PP; - - GPIO_InitStruct.Pin = board.led_pinR; - HAL_GPIO_Init(board.led_portR, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = board.led_pinG; - HAL_GPIO_Init(board.led_portG, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = board.led_pinB; - HAL_GPIO_Init(board.led_portB, &GPIO_InitStruct); - - if (board.can_pinEN != 0) { - GPIO_InitStruct.Pin = board.can_pinEN; - HAL_GPIO_Init(board.can_portEN, &GPIO_InitStruct); - } - - if (board.ignition_pin != 0) { - GPIO_InitStruct.Pin = board.ignition_pin; - HAL_GPIO_Init(board.ignition_port, &GPIO_InitStruct); - - } - - GPIO_InitStruct.Pin = BUZZER_PIN; - HAL_GPIO_Init(BUZZER_PORT, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = OFF_PIN; - HAL_GPIO_Init(OFF_PORT, &GPIO_InitStruct); - - - GPIO_InitStruct.Mode = GPIO_MODE_ANALOG; - - GPIO_InitStruct.Pin = LEFT_DC_CUR_PIN; - HAL_GPIO_Init(LEFT_DC_CUR_PORT, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = LEFT_U_CUR_PIN; - HAL_GPIO_Init(LEFT_U_CUR_PORT, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = LEFT_V_CUR_PIN; - HAL_GPIO_Init(LEFT_V_CUR_PORT, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = RIGHT_DC_CUR_PIN; - HAL_GPIO_Init(RIGHT_DC_CUR_PORT, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = RIGHT_U_CUR_PIN; - HAL_GPIO_Init(RIGHT_U_CUR_PORT, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = RIGHT_V_CUR_PIN; - HAL_GPIO_Init(RIGHT_V_CUR_PORT, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = BATT_PIN; - HAL_GPIO_Init(BATT_PORT, &GPIO_InitStruct); - - GPIO_InitStruct.Mode = GPIO_MODE_AF_PP; - GPIO_InitStruct.Alternate = GPIO_AF3_TIM8; - - GPIO_InitStruct.Pin = LEFT_TIM_UH_PIN; - HAL_GPIO_Init(LEFT_TIM_UH_PORT, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = LEFT_TIM_VH_PIN; - HAL_GPIO_Init(LEFT_TIM_VH_PORT, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = LEFT_TIM_WH_PIN; - HAL_GPIO_Init(LEFT_TIM_WH_PORT, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = LEFT_TIM_UL_PIN; - HAL_GPIO_Init(LEFT_TIM_UL_PORT, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = LEFT_TIM_VL_PIN; - HAL_GPIO_Init(LEFT_TIM_VL_PORT, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = LEFT_TIM_WL_PIN; - HAL_GPIO_Init(LEFT_TIM_WL_PORT, &GPIO_InitStruct); - - GPIO_InitStruct.Alternate = GPIO_AF1_TIM1; - - GPIO_InitStruct.Pin = RIGHT_TIM_UH_PIN; - HAL_GPIO_Init(RIGHT_TIM_UH_PORT, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = RIGHT_TIM_VH_PIN; - HAL_GPIO_Init(RIGHT_TIM_VH_PORT, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = RIGHT_TIM_WH_PIN; - HAL_GPIO_Init(RIGHT_TIM_WH_PORT, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = RIGHT_TIM_UL_PIN; - HAL_GPIO_Init(RIGHT_TIM_UL_PORT, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = RIGHT_TIM_VL_PIN; - HAL_GPIO_Init(RIGHT_TIM_VL_PORT, &GPIO_InitStruct); - - GPIO_InitStruct.Pin = RIGHT_TIM_WL_PIN; - HAL_GPIO_Init(RIGHT_TIM_WL_PORT, &GPIO_InitStruct); - - // CAN bus - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; - - GPIO_InitStruct.Alternate = board.can_alt_rx; - GPIO_InitStruct.Pin = board.can_pinRX; - HAL_GPIO_Init(board.can_portRX, &GPIO_InitStruct); - - GPIO_InitStruct.Alternate = board.can_alt_tx; - GPIO_InitStruct.Pin = board.can_pinTX; - HAL_GPIO_Init(board.can_portTX, &GPIO_InitStruct); -} - - -void MX_I2C_Init(void) { - GPIO_InitTypeDef GPIO_InitStruct = { 0 }; - - GPIO_InitStruct.Pin = GPIO_PIN_6|GPIO_PIN_7; - GPIO_InitStruct.Mode = GPIO_MODE_AF_OD; - GPIO_InitStruct.Pull = GPIO_PULLUP; - GPIO_InitStruct.Speed = GPIO_SPEED_FREQ_VERY_HIGH; - GPIO_InitStruct.Alternate = GPIO_AF4_I2C1; - HAL_GPIO_Init(GPIOB, &GPIO_InitStruct); - - __HAL_RCC_I2C1_CLK_ENABLE(); - - hi2c1.Instance = I2C1; - hi2c1.Init.ClockSpeed = (I2C_CLOCKSPEED * 1000); - hi2c1.Init.DutyCycle = I2C_DUTYCYCLE_2; - hi2c1.Init.OwnAddress1 = 0; - hi2c1.Init.AddressingMode = I2C_ADDRESSINGMODE_7BIT; - hi2c1.Init.DualAddressMode = I2C_DUALADDRESS_DISABLE; - hi2c1.Init.OwnAddress2 = 0; - hi2c1.Init.GeneralCallMode = I2C_GENERALCALL_DISABLE; - hi2c1.Init.NoStretchMode = I2C_NOSTRETCH_DISABLE; - HAL_I2C_Init(&hi2c1); -} - - -void MX_TIM_Init(void) { - __HAL_RCC_TIM1_CLK_ENABLE(); - __HAL_RCC_TIM8_CLK_ENABLE(); - - TIM_MasterConfigTypeDef sMasterConfig; - TIM_OC_InitTypeDef sConfigOC; - TIM_BreakDeadTimeConfigTypeDef sBreakDeadTimeConfig; - TIM_SlaveConfigTypeDef sTimConfig; - - htim_right.Instance = RIGHT_TIM; - htim_right.Init.Prescaler = 0; - htim_right.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED1; - htim_right.Init.Period = CORE_FREQ / 2 / PWM_FREQ; - htim_right.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; - htim_right.Init.RepetitionCounter = 0; - htim_right.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; - HAL_TIM_PWM_Init(&htim_right); - - sMasterConfig.MasterOutputTrigger = TIM_TRGO_ENABLE; - sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_DISABLE; - HAL_TIMEx_MasterConfigSynchronization(&htim_right, &sMasterConfig); - - sConfigOC.OCMode = TIM_OCMODE_PWM1; - sConfigOC.Pulse = 0; - sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH; - sConfigOC.OCNPolarity = TIM_OCNPOLARITY_LOW; - sConfigOC.OCFastMode = TIM_OCFAST_DISABLE; - sConfigOC.OCIdleState = TIM_OCIDLESTATE_RESET; - sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_SET; - HAL_TIM_PWM_ConfigChannel(&htim_right, &sConfigOC, TIM_CHANNEL_1); - HAL_TIM_PWM_ConfigChannel(&htim_right, &sConfigOC, TIM_CHANNEL_2); - HAL_TIM_PWM_ConfigChannel(&htim_right, &sConfigOC, TIM_CHANNEL_3); - - sBreakDeadTimeConfig.OffStateRunMode = TIM_OSSR_ENABLE; - sBreakDeadTimeConfig.OffStateIDLEMode = TIM_OSSI_ENABLE; - sBreakDeadTimeConfig.LockLevel = TIM_LOCKLEVEL_OFF; - sBreakDeadTimeConfig.DeadTime = DEAD_TIME; - sBreakDeadTimeConfig.BreakState = TIM_BREAK_DISABLE; - sBreakDeadTimeConfig.BreakPolarity = TIM_BREAKPOLARITY_LOW; - sBreakDeadTimeConfig.AutomaticOutput = TIM_AUTOMATICOUTPUT_DISABLE; - HAL_TIMEx_ConfigBreakDeadTime(&htim_right, &sBreakDeadTimeConfig); - - htim_left.Instance = LEFT_TIM; - htim_left.Init.Prescaler = 0; - htim_left.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED1; - htim_left.Init.Period = CORE_FREQ / 2 / PWM_FREQ; - htim_left.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1; - htim_left.Init.RepetitionCounter = 0; - htim_left.Init.AutoReloadPreload = TIM_AUTORELOAD_PRELOAD_DISABLE; - HAL_TIM_PWM_Init(&htim_left); - - sMasterConfig.MasterOutputTrigger = TIM_TRGO_UPDATE; - sMasterConfig.MasterSlaveMode = TIM_MASTERSLAVEMODE_ENABLE; - HAL_TIMEx_MasterConfigSynchronization(&htim_left, &sMasterConfig); - - sTimConfig.InputTrigger = TIM_TS_ITR0; - sTimConfig.SlaveMode = TIM_SLAVEMODE_GATED; - HAL_TIM_SlaveConfigSynchronization(&htim_left, &sTimConfig); - - // Start counting >0 to effectively offset timers by the time it takes for one ADC conversion to complete. - // This method allows that the Phase currents ADC measurements are properly aligned with LOW-FET ON region for both motors - LEFT_TIM->CNT = ADC_TOTAL_CONV_TIME; - - sConfigOC.OCMode = TIM_OCMODE_PWM1; - sConfigOC.Pulse = 0; - sConfigOC.OCPolarity = TIM_OCPOLARITY_HIGH; - sConfigOC.OCNPolarity = TIM_OCNPOLARITY_LOW; - sConfigOC.OCFastMode = TIM_OCFAST_DISABLE; - sConfigOC.OCIdleState = TIM_OCIDLESTATE_RESET; - sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_SET; - HAL_TIM_PWM_ConfigChannel(&htim_left, &sConfigOC, TIM_CHANNEL_1); - HAL_TIM_PWM_ConfigChannel(&htim_left, &sConfigOC, TIM_CHANNEL_2); - HAL_TIM_PWM_ConfigChannel(&htim_left, &sConfigOC, TIM_CHANNEL_3); - - sBreakDeadTimeConfig.OffStateRunMode = TIM_OSSR_ENABLE; - sBreakDeadTimeConfig.OffStateIDLEMode = TIM_OSSI_ENABLE; - sBreakDeadTimeConfig.LockLevel = TIM_LOCKLEVEL_OFF; - sBreakDeadTimeConfig.DeadTime = DEAD_TIME; - sBreakDeadTimeConfig.BreakState = TIM_BREAK_DISABLE; - sBreakDeadTimeConfig.BreakPolarity = TIM_BREAKPOLARITY_LOW; - sBreakDeadTimeConfig.AutomaticOutput = TIM_AUTOMATICOUTPUT_DISABLE; - HAL_TIMEx_ConfigBreakDeadTime(&htim_left, &sBreakDeadTimeConfig); - - LEFT_TIM->BDTR &= ~TIM_BDTR_MOE; - RIGHT_TIM->BDTR &= ~TIM_BDTR_MOE; - - HAL_TIM_PWM_Start(&htim_left, TIM_CHANNEL_1); - HAL_TIM_PWM_Start(&htim_left, TIM_CHANNEL_2); - HAL_TIM_PWM_Start(&htim_left, TIM_CHANNEL_3); - HAL_TIMEx_PWMN_Start(&htim_left, TIM_CHANNEL_1); - HAL_TIMEx_PWMN_Start(&htim_left, TIM_CHANNEL_2); - HAL_TIMEx_PWMN_Start(&htim_left, TIM_CHANNEL_3); - - HAL_TIM_PWM_Start(&htim_right, TIM_CHANNEL_1); - HAL_TIM_PWM_Start(&htim_right, TIM_CHANNEL_2); - HAL_TIM_PWM_Start(&htim_right, TIM_CHANNEL_3); - HAL_TIMEx_PWMN_Start(&htim_right, TIM_CHANNEL_1); - HAL_TIMEx_PWMN_Start(&htim_right, TIM_CHANNEL_2); - HAL_TIMEx_PWMN_Start(&htim_right, TIM_CHANNEL_3); - - htim_left.Instance->RCR = 1; - - __HAL_TIM_ENABLE(&htim_right); -} - -void MX_ADC_Init(void) { - ADC_MultiModeTypeDef multimode; - ADC_ChannelConfTypeDef sConfig; - - __HAL_RCC_ADC1_CLK_ENABLE(); - - hadc.Instance = ADC1; - hadc.Init.ClockPrescaler = ADC_CLOCK_SYNC_PCLK_DIV4; - hadc.Init.Resolution = ADC_RESOLUTION_12B; - hadc.Init.ScanConvMode = ENABLE; - hadc.Init.ContinuousConvMode = DISABLE; - hadc.Init.DiscontinuousConvMode = DISABLE; - hadc.Init.ExternalTrigConv = ADC_EXTERNALTRIGCONV_T8_TRGO; - hadc.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_RISING; - hadc.Init.DataAlign = ADC_DATAALIGN_RIGHT; - hadc.Init.NbrOfConversion = 8; - HAL_ADC_Init(&hadc); - - HAL_ADCEx_MultiModeConfigChannel(&hadc, &multimode); - sConfig.SamplingTime = ADC_SAMPLETIME_15CYCLES; - - sConfig.Channel = ADC_CHANNEL_5; // pa5 left b -> right - sConfig.Rank = 1; - HAL_ADC_ConfigChannel(&hadc, &sConfig); - - sConfig.Channel = ADC_CHANNEL_6; // pa6 left c -> right - sConfig.Rank = 2; - HAL_ADC_ConfigChannel(&hadc, &sConfig); - - sConfig.Channel = ADC_CHANNEL_0; // pa0 right a -> left - sConfig.Rank = 3; - HAL_ADC_ConfigChannel(&hadc, &sConfig); - - sConfig.Channel = ADC_CHANNEL_1; // pa1 right b -> left - sConfig.Rank = 4; - HAL_ADC_ConfigChannel(&hadc, &sConfig); - - sConfig.Channel = ADC_CHANNEL_3; // pa3 left cur -> right - sConfig.Rank = 5; - HAL_ADC_ConfigChannel(&hadc, &sConfig); - - sConfig.Channel = ADC_CHANNEL_2; // pa2 right cur -> left - sConfig.Rank = 6; - HAL_ADC_ConfigChannel(&hadc, &sConfig); - - sConfig.Channel = ADC_CHANNEL_4; // pa4 vbat - sConfig.Rank = 7; - HAL_ADC_ConfigChannel(&hadc, &sConfig); - - sConfig.SamplingTime = ADC_SAMPLETIME_144CYCLES; - sConfig.Channel = ADC_CHANNEL_TEMPSENSOR; // internal temp - sConfig.Rank = 8; - HAL_ADC_ConfigChannel(&hadc, &sConfig); - - hadc.Instance->CR2 |= ADC_CR2_DMA | ADC_CR2_DDS | ADC_CCR_TSVREFE; - - __HAL_ADC_ENABLE(&hadc); - - __HAL_RCC_DMA2_CLK_ENABLE(); - - DMA2_Stream0->CR = 0; - DMA2_Stream0->NDTR = 8; - DMA2_Stream0->PAR = (uint32_t)&(ADC1->DR); - DMA2_Stream0->M0AR = (uint32_t)&adc_buffer; - DMA2_Stream0->CR = DMA_SxCR_MSIZE_1 | DMA_SxCR_PSIZE_1 | DMA_SxCR_MINC | DMA_SxCR_CIRC | DMA_SxCR_TCIE; - DMA2_Stream0->CR &= ~DMA_SxCR_CHSEL; - DMA2_Stream0->FCR &= ~DMA_SxFCR_DMDIS; - DMA2_Stream0->CR |= DMA_SxCR_EN; - - HAL_NVIC_SetPriority(DMA2_Stream0_IRQn, 0, 0); - HAL_NVIC_EnableIRQ(DMA2_Stream0_IRQn); -} - - -#endif diff --git a/body/board/uds.h b/body/board/uds.h deleted file mode 100644 index f9e151b..0000000 --- a/body/board/uds.h +++ /dev/null @@ -1,127 +0,0 @@ -extern uint8_t hw_type; -void can_send_msg(uint32_t addr, uint32_t dhr, uint32_t dlr, uint8_t len); - -uint8_t uid[10]; -uint32_t uds_engine_request = 0; -uint32_t uds_debug_request = 0; -uint8_t knee_detected = 0; -uint8_t sep_time = 0; - -void process_uds(uint32_t addr, uint32_t dlr) { - memcpy(uid, (void *)0x1FFF7A10U, 0xAU); - - if ((hw_type == HW_TYPE_BASE) && - ((addr == BROADCAST_ADDR) || - (addr == FALLBACK_ADDR))) { // OBD2 broadcast request, redirect to UDS? - switch(dlr) { - // VIN 09 OBD2 - case 0x020902U: - can_send_msg(FALLBACK_R_ADDR, 0x4D4F4301U, 0x02491410U, 8U); - uds_engine_request = 0xF190U; - break; - // VIN : F190 on broadcast - case 0x90F12203U: - can_send_msg(FALLBACK_R_ADDR, 0x4D4F4390U, 0xF1621410U, 8U); - break; - // VIN continue - default: - if ((dlr & 0xFF) == 0x30U) { - sep_time = (dlr >> 16U) & 0xFF; - delay(sep_time); - can_send_msg(FALLBACK_R_ADDR, 0x5659444FU, 0x42414D21U, 8U); - can_send_msg(FALLBACK_R_ADDR, 0x314E4F49U, 0x53524522U, 8U); - } - break; - } - } else if (addr == (ENGINE_ADDR + board.uds_offset)) { // UDS request to "main" ECU - switch(dlr) { - // TESTER PRESENT - case 0x3E02U: - can_send_msg(ENGINE_R_ADDR + board.uds_offset, 0x0U, 0x7E02U, 8U); - break; - // DIAGNOSTIC SESSION CONTROL: DEFAULT - case 0x011002U: - can_send_msg(ENGINE_R_ADDR + board.uds_offset, 0x0U, 0x015002U, 8U); - break; - // DIAGNOSTIC SESSION CONTROL: EXTENDED - case 0x031002U: - can_send_msg(ENGINE_R_ADDR + board.uds_offset, 0x0U, 0x035002U, 8U); - break; - // APPLICATION SOFTWARE IDENTIFICATION : F181 (used for fingerprinting, firmware version) - case 0x81F12203U: - COMPILE_TIME_ASSERT(sizeof(version) == 6U); - can_send_msg(ENGINE_R_ADDR + board.uds_offset, ((version[2] << 24U) | (version[1] << 16U) | (version[0] << 8U) | 0x81U), 0xF1620A10U, 8U); - uds_engine_request = 0xF181U; - break; - // ECU SERIAL NUMBER : F18C - case 0x8CF12203U: - can_send_msg(ENGINE_R_ADDR + board.uds_offset, ((uid[2] << 24U) | (uid[1] << 16U) | (uid[0] << 8U) | 0x8CU), 0xF1620D10U, 8U); - uds_engine_request = 0xF18CU; - break; - // VIN : F190 - case 0x90F12203U: - can_send_msg(ENGINE_R_ADDR + board.uds_offset, 0x4D4F4390U, 0xF1621410U, 8U); - uds_engine_request = 0xF190U; - break; - // FLOW CONTROL MESSAGE - default: - if ((dlr & 0xFF) == 0x30U) { - sep_time = (dlr >> 16U) & 0xFF; - delay(sep_time); - switch(uds_engine_request) { - // APPLICATION SOFTWARE IDENTIFICATION : F181 - case 0xF181U: - can_send_msg(ENGINE_R_ADDR + board.uds_offset, (knee_detected + 0x61), ((version[5] << 24U) | (version[4] << 16U) | (version[3] << 8U) | 0x21U), 8U); - uds_engine_request = 0; - break; - // ECU SERIAL NUMBER : F18C - case 0xF18CU: - can_send_msg(ENGINE_R_ADDR + board.uds_offset, ((uid[9] << 24U) | (uid[8] << 16U) | (uid[7]<< 8U) | uid[6]), ((uid[5] << 24U) | (uid[4] << 16U) | (uid[3] << 8U) | 0x21U), 8U); - uds_engine_request = 0; - break; - // VIN : F190 - case 0xF190U: - can_send_msg(ENGINE_R_ADDR + board.uds_offset, 0x5659444FU, 0x42414D21U, 8U); - can_send_msg(ENGINE_R_ADDR + board.uds_offset, 0x314E4F49U, 0x53524522U, 8U); - uds_engine_request = 0; - break; - } - } - break; - } - } else if (addr == (DEBUG_ADDR + board.uds_offset)) { // UDS request to "DEBUG" ECU - switch(dlr) { - // TESTER PRESENT - case 0x3E02U: - can_send_msg(DEBUG_R_ADDR + board.uds_offset, 0x0U, 0x7E02U, 8U); - break; - // DIAGNOSTIC SESSION CONTROL: DEFAULT - case 0x011002U: - can_send_msg(DEBUG_R_ADDR + board.uds_offset, 0x0U, 0x015002U, 8U); - break; - // DIAGNOSTIC SESSION CONTROL: EXTENDED - case 0x031002U: - can_send_msg(DEBUG_R_ADDR + board.uds_offset, 0x0U, 0x035002U, 8U); - break; - // APPLICATION SOFTWARE IDENTIFICATION : F181 (used for git hash logging) - case 0x81F12203U: - COMPILE_TIME_ASSERT(sizeof(gitversion) == 8U); - can_send_msg((DEBUG_R_ADDR + board.uds_offset), ((gitversion[2] << 24U) | (gitversion[1] << 16U) | (gitversion[0] << 8U) | 0x81U), 0xF1620B10U, 8U); - uds_debug_request = 0xF181U; - break; - default: - if ((dlr & 0xFF) == 0x30U) { - sep_time = (dlr >> 16U) & 0xFF; - delay(sep_time); - switch(uds_debug_request) { - // APPLICATION SOFTWARE IDENTIFICATION : F181 - case 0xF181U: - can_send_msg((DEBUG_R_ADDR + board.uds_offset), ((gitversion[7]<< 8U) | gitversion[6]), ((gitversion[5] << 24U) | (gitversion[4] << 16U) | (gitversion[3] << 8U) | 0x21U), 8U); - uds_debug_request = 0; - break; - } - } - break; - } - } -} diff --git a/body/board/util.h b/body/board/util.h deleted file mode 100644 index 0eea10b..0000000 --- a/body/board/util.h +++ /dev/null @@ -1,33 +0,0 @@ -// Define to prevent recursive inclusion -#ifndef UTIL_H -#define UTIL_H - -#include -#include - -// Initialization Functions -void BLDC_Init(void); - -// General Functions -void out_enable(uint8_t led, bool enabled); -void poweronMelody(void); -void beepCount(uint8_t cnt, uint8_t freq, uint8_t pattern); -void beepLong(uint8_t freq); -void beepShort(uint8_t freq); -void beepShortMany(uint8_t cnt, int8_t dir); -void calcAvgSpeed(void); - -// Poweroff Functions -void poweroff(void); - -// GPIO functions -uint8_t detect_with_pull(GPIO_TypeDef* GPIOx, uint16_t GPIO_Pin, uint32_t mode); -uint8_t board_id(void); - -// Filtering Functions -void filtLowPass32(int32_t u, uint16_t coef, int32_t *y); -void rateLimiter16(int16_t u, int16_t rate, int16_t *y); - -uint8_t crc_checksum(uint8_t *dat, int len, const uint8_t poly); - -#endif diff --git a/body/board/version.h b/body/board/version.h deleted file mode 100644 index 2cc94a1..0000000 --- a/body/board/version.h +++ /dev/null @@ -1 +0,0 @@ -const uint8_t version[6] = "0.3.00"; diff --git a/body/crypto/hash-internal.h b/body/crypto/hash-internal.h deleted file mode 100644 index 05ec3ec..0000000 --- a/body/crypto/hash-internal.h +++ /dev/null @@ -1,63 +0,0 @@ -/* - * Copyright 2007 The Android Open Source Project - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in the - * documentation and/or other materials provided with the distribution. - * * Neither the name of Google Inc. nor the names of its contributors may - * be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY Google Inc. ``AS IS'' AND ANY EXPRESS OR - * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO - * EVENT SHALL Google Inc. BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, - * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, - * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; - * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, - * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR - * OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF - * ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - */ - -#ifndef SYSTEM_CORE_INCLUDE_MINCRYPT_HASH_INTERNAL_H_ -#define SYSTEM_CORE_INCLUDE_MINCRYPT_HASH_INTERNAL_H_ - -#include "stdint.h" - -#ifdef __cplusplus -extern "C" { -#endif // __cplusplus - -struct HASH_CTX; // forward decl - -typedef struct HASH_VTAB { - void (* const init)(struct HASH_CTX*); - void (* const update)(struct HASH_CTX*, const void*, int); - const uint8_t* (* const final)(struct HASH_CTX*); - const uint8_t* (* const hash)(const void*, int, uint8_t*); - int size; -} HASH_VTAB; - -typedef struct HASH_CTX { - const HASH_VTAB * f; - uint64_t count; - uint8_t buf[64]; - uint32_t state[8]; // upto SHA2 -} HASH_CTX; - -#define HASH_init(ctx) (ctx)->f->init(ctx) -#define HASH_update(ctx, data, len) (ctx)->f->update(ctx, data, len) -#define HASH_final(ctx) (ctx)->f->final(ctx) -#define HASH_hash(data, len, digest) (ctx)->f->hash(data, len, digest) -#define HASH_size(ctx) (ctx)->f->size - -#ifdef __cplusplus -} -#endif // __cplusplus - -#endif // SYSTEM_CORE_INCLUDE_MINCRYPT_HASH_INTERNAL_H_ diff --git a/body/crypto/rsa.h b/body/crypto/rsa.h deleted file mode 100644 index 77fef5a..0000000 --- a/body/crypto/rsa.h +++ /dev/null @@ -1,58 +0,0 @@ -/* rsa.h -** -** Copyright 2008, The Android Open Source Project -** -** Redistribution and use in source and binary forms, with or without -** modification, are permitted provided that the following conditions are met: -** * Redistributions of source code must retain the above copyright -** notice, this list of conditions and the following disclaimer. -** * Redistributions in binary form must reproduce the above copyright -** notice, this list of conditions and the following disclaimer in the -** documentation and/or other materials provided with the distribution. -** * Neither the name of Google Inc. nor the names of its contributors may -** be used to endorse or promote products derived from this software -** without specific prior written permission. -** -** THIS SOFTWARE IS PROVIDED BY Google Inc. ``AS IS'' AND ANY EXPRESS OR -** IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF -** MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO -** EVENT SHALL Google Inc. BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, -** SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, -** PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; -** OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, -** WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR -** OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF -** ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. -*/ - -#ifndef SYSTEM_CORE_INCLUDE_MINCRYPT_RSA_H_ -#define SYSTEM_CORE_INCLUDE_MINCRYPT_RSA_H_ - -#include "stdint.h" - -#ifdef __cplusplus -extern "C" { -#endif - -#define RSANUMBYTES 128 /* 1024 bit key length */ -#define RSANUMWORDS (RSANUMBYTES / sizeof(uint32_t)) - -typedef struct RSAPublicKey { - int len; /* Length of n[] in number of uint32_t */ - uint32_t n0inv; /* -1 / n[0] mod 2^32 */ - uint32_t n[RSANUMWORDS]; /* modulus as little endian array */ - uint32_t rr[RSANUMWORDS]; /* R^2 as little endian array */ - int exponent; /* 3 or 65537 */ -} RSAPublicKey; - -int RSA_verify(const RSAPublicKey *key, - const uint8_t* signature, - const int len, - const uint8_t* hash, - const int hash_len); - -#ifdef __cplusplus -} -#endif - -#endif // SYSTEM_CORE_INCLUDE_MINCRYPT_RSA_H_ diff --git a/body/crypto/sha.h b/body/crypto/sha.h deleted file mode 100644 index 4b51a53..0000000 --- a/body/crypto/sha.h +++ /dev/null @@ -1,51 +0,0 @@ -/* - * Copyright 2005 The Android Open Source Project - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in the - * documentation and/or other materials provided with the distribution. - * * Neither the name of Google Inc. nor the names of its contributors may - * be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY Google Inc. ``AS IS'' AND ANY EXPRESS OR - * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO - * EVENT SHALL Google Inc. BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, - * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, - * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; - * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, - * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR - * OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF - * ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - */ -#ifndef SYSTEM_CORE_INCLUDE_MINCRYPT_SHA1_H_ -#define SYSTEM_CORE_INCLUDE_MINCRYPT_SHA1_H_ - -#include "hash-internal.h" - -#ifdef __cplusplus -extern "C" { -#endif // __cplusplus - -typedef HASH_CTX SHA_CTX; - -void SHA_init(SHA_CTX* ctx); -void SHA_update(SHA_CTX* ctx, const void* data, int len); -const uint8_t* SHA_final(SHA_CTX* ctx); - -// Convenience method. Returns digest address. -// NOTE: *digest needs to hold SHA_DIGEST_SIZE bytes. -const uint8_t* SHA_hash(const void* data, int len, uint8_t* digest); - -#define SHA_DIGEST_SIZE 20 - -#ifdef __cplusplus -} -#endif // __cplusplus - -#endif // SYSTEM_CORE_INCLUDE_MINCRYPT_SHA1_H_ diff --git a/body/crypto/stdint.h b/body/crypto/stdint.h deleted file mode 100644 index 67ac93e..0000000 --- a/body/crypto/stdint.h +++ /dev/null @@ -1,4 +0,0 @@ -#define uint8_t unsigned char -#define uint32_t unsigned int -#define int64_t long long -#define uint64_t unsigned long long diff --git a/cereal/SConscript b/cereal/SConscript deleted file mode 100644 index a5d9d6b..0000000 --- a/cereal/SConscript +++ /dev/null @@ -1,76 +0,0 @@ -Import('env', 'envCython', 'arch', 'common') - -import shutil - -cereal_dir = Dir('.') -gen_dir = Dir('gen') -messaging_dir = Dir('messaging') - -# Build cereal - -schema_files = ['log.capnp', 'car.capnp', 'legacy.capnp', 'custom.capnp'] -env.Command(["gen/c/include/c++.capnp.h"], [], "mkdir -p " + gen_dir.path + "/c/include && touch $TARGETS") -env.Command([f'gen/cpp/{s}.c++' for s in schema_files] + [f'gen/cpp/{s}.h' for s in schema_files], - schema_files, - f"capnpc --src-prefix={cereal_dir.path} $SOURCES -o c++:{gen_dir.path}/cpp/") - -# TODO: remove non shared cereal and messaging -cereal_objects = env.SharedObject([f'gen/cpp/{s}.c++' for s in schema_files]) - -env.Library('cereal', cereal_objects) -env.SharedLibrary('cereal_shared', cereal_objects) - -# Build messaging - -services_h = env.Command(['services.h'], ['services.py'], 'python3 ' + cereal_dir.path + '/services.py > $TARGET') - -messaging_objects = env.SharedObject([ - 'messaging/messaging.cc', - 'messaging/event.cc', - 'messaging/impl_zmq.cc', - 'messaging/impl_msgq.cc', - 'messaging/impl_fake.cc', - 'messaging/msgq.cc', - 'messaging/socketmaster.cc', -]) - -messaging_lib = env.Library('messaging', messaging_objects) -Depends('messaging/impl_zmq.cc', services_h) - -env.Program('messaging/bridge', ['messaging/bridge.cc'], LIBS=[messaging_lib, 'zmq', common]) -Depends('messaging/bridge.cc', services_h) - -envCython.Program('messaging/messaging_pyx.so', 'messaging/messaging_pyx.pyx', LIBS=envCython["LIBS"]+[messaging_lib, "zmq", common]) - - -# Build Vision IPC -vipc_sources = [ - 'visionipc/ipc.cc', - 'visionipc/visionipc_server.cc', - 'visionipc/visionipc_client.cc', - 'visionipc/visionbuf.cc', -] - -if arch == "larch64": - vipc_sources += ['visionipc/visionbuf_ion.cc'] -else: - vipc_sources += ['visionipc/visionbuf_cl.cc'] - -vipc_objects = env.SharedObject(vipc_sources) -vipc = env.Library('visionipc', vipc_objects) - - -vipc_frameworks = [] -vipc_libs = envCython["LIBS"] + [vipc, messaging_lib, common, "zmq"] -if arch == "Darwin": - vipc_frameworks.append('OpenCL') -else: - vipc_libs.append('OpenCL') -envCython.Program('visionipc/visionipc_pyx.so', 'visionipc/visionipc_pyx.pyx', - LIBS=vipc_libs, FRAMEWORKS=vipc_frameworks) - -if GetOption('extras'): - env.Program('messaging/test_runner', ['messaging/test_runner.cc', 'messaging/msgq_tests.cc'], LIBS=[messaging_lib, common]) - - env.Program('visionipc/test_runner', ['visionipc/test_runner.cc', 'visionipc/visionipc_tests.cc'], - LIBS=['pthread'] + vipc_libs, FRAMEWORKS=vipc_frameworks) diff --git a/cereal/gen/cpp/car.capnp.c++ b/cereal/gen/cpp/car.capnp.c++ new file mode 100644 index 0000000..55fab30 --- /dev/null +++ b/cereal/gen/cpp/car.capnp.c++ @@ -0,0 +1,7034 @@ +// Generated by Cap'n Proto compiler, DO NOT EDIT +// source: car.capnp + +#include "car.capnp.h" + +namespace capnp { +namespace schemas { +static const ::capnp::_::AlignedData<195> b_9b1657f34caf3ad3 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 211, 58, 175, 76, 243, 87, 22, 155, + 10, 0, 0, 0, 1, 0, 1, 0, + 141, 139, 175, 8, 231, 241, 42, 142, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 154, 0, 0, 0, + 29, 0, 0, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 111, 2, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 46, 99, 97, 112, 110, + 112, 58, 67, 97, 114, 69, 118, 101, + 110, 116, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 1, 0, 1, 0, + 222, 39, 247, 5, 213, 197, 168, 186, + 1, 0, 0, 0, 82, 0, 0, 0, + 69, 118, 101, 110, 116, 78, 97, 109, + 101, 0, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 1, 0, 0, 3, 0, 1, 0, + 44, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 16, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 1, 0, 0, 3, 0, 1, 0, + 48, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 17, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 1, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 1, 0, 0, 3, 0, 1, 0, + 52, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 1, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 1, 0, 0, 3, 0, 1, 0, + 56, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 19, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 53, 1, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 52, 1, 0, 0, 3, 0, 1, 0, + 64, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 20, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 1, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 60, 1, 0, 0, 3, 0, 1, 0, + 72, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 21, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 1, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 1, 0, 0, 3, 0, 1, 0, + 84, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 22, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 81, 1, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 80, 1, 0, 0, 3, 0, 1, 0, + 92, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 23, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 89, 1, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 88, 1, 0, 0, 3, 0, 1, 0, + 100, 1, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 24, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 1, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 1, 0, 0, 3, 0, 1, 0, + 112, 1, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 25, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 1, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 1, 0, 0, 3, 0, 1, 0, + 120, 1, 0, 0, 2, 0, 1, 0, + 110, 97, 109, 101, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 222, 39, 247, 5, 213, 197, 168, 186, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 110, 97, 98, 108, 101, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 111, 69, 110, 116, 114, 121, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 119, 97, 114, 110, 105, 110, 103, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 115, 101, 114, 68, 105, 115, 97, + 98, 108, 101, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 111, 102, 116, 68, 105, 115, 97, + 98, 108, 101, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 109, 109, 101, 100, 105, 97, 116, + 101, 68, 105, 115, 97, 98, 108, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 114, 101, 69, 110, 97, 98, 108, + 101, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 101, 114, 109, 97, 110, 101, 110, + 116, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 118, 101, 114, 114, 105, 100, 101, + 76, 111, 110, 103, 105, 116, 117, 100, + 105, 110, 97, 108, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 118, 101, 114, 114, 105, 100, 101, + 76, 97, 116, 101, 114, 97, 108, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_9b1657f34caf3ad3 = b_9b1657f34caf3ad3.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_9b1657f34caf3ad3[] = { + &s_baa8c5d505f727de, +}; +static const uint16_t m_9b1657f34caf3ad3[] = {1, 6, 0, 2, 10, 9, 8, 7, 5, 4, 3}; +static const uint16_t i_9b1657f34caf3ad3[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10}; +const ::capnp::_::RawSchema s_9b1657f34caf3ad3 = { + 0x9b1657f34caf3ad3, b_9b1657f34caf3ad3.words, 195, d_9b1657f34caf3ad3, m_9b1657f34caf3ad3, + 1, 11, i_9b1657f34caf3ad3, nullptr, nullptr, { &s_9b1657f34caf3ad3, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<798> b_baa8c5d505f727de = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 222, 39, 247, 5, 213, 197, 168, 186, + 19, 0, 0, 0, 2, 0, 0, 0, + 211, 58, 175, 76, 243, 87, 22, 155, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 234, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 247, 12, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 46, 99, 97, 112, 110, + 112, 58, 67, 97, 114, 69, 118, 101, + 110, 116, 46, 69, 118, 101, 110, 116, + 78, 97, 109, 101, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 40, 2, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 6, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 109, 6, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 136, 0, 0, 0, 0, 0, 0, 0, + 109, 6, 0, 0, 218, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 0, 0, 0, 0, 0, 0, 0, + 113, 6, 0, 0, 202, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 117, 6, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 113, 6, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 109, 6, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 109, 6, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 105, 6, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 101, 6, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 101, 6, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 97, 6, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 93, 6, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 89, 6, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 85, 6, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 0, 0, 0, 0, 0, 0, 0, + 81, 6, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 0, 0, 0, 0, 0, 0, 0, + 81, 6, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 81, 6, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 0, 0, 0, 0, 0, 0, 0, + 77, 6, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 18, 0, 0, 0, 0, 0, 0, 0, + 73, 6, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 19, 0, 0, 0, 0, 0, 0, 0, + 69, 6, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 0, 0, 0, 0, 0, 0, 0, + 69, 6, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 22, 0, 0, 0, 0, 0, 0, 0, + 69, 6, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 23, 0, 0, 0, 0, 0, 0, 0, + 69, 6, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 24, 0, 0, 0, 0, 0, 0, 0, + 65, 6, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 135, 0, 0, 0, 0, 0, 0, 0, + 61, 6, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 0, 0, 0, 0, + 61, 6, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 119, 0, 0, 0, 0, 0, 0, 0, + 57, 6, 0, 0, 202, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 26, 0, 0, 0, 0, 0, 0, 0, + 61, 6, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 27, 0, 0, 0, 0, 0, 0, 0, + 57, 6, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 28, 0, 0, 0, 0, 0, 0, 0, + 53, 6, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 0, 0, 0, 0, + 49, 6, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 137, 0, 0, 0, 0, 0, 0, 0, + 45, 6, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 0, 0, 0, 0, 0, 0, 0, + 45, 6, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 30, 0, 0, 0, 0, 0, 0, 0, + 45, 6, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 31, 0, 0, 0, 0, 0, 0, 0, + 41, 6, 0, 0, 218, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 0, 0, 0, 0, 0, 0, 0, + 45, 6, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 0, 0, 0, 0, + 41, 6, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 34, 0, 0, 0, 0, 0, 0, 0, + 41, 6, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 35, 0, 0, 0, 0, 0, 0, 0, + 41, 6, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 0, 0, 0, 0, 0, 0, 0, + 41, 6, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 122, 0, 0, 0, 0, 0, 0, 0, + 41, 6, 0, 0, 210, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 123, 0, 0, 0, 0, 0, 0, 0, + 45, 6, 0, 0, 218, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 0, 0, 0, 0, + 49, 6, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 0, 0, 0, 0, + 49, 6, 0, 0, 202, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 38, 0, 0, 0, 0, 0, 0, 0, + 53, 6, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 39, 0, 0, 0, 0, 0, 0, 0, + 53, 6, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 0, 0, 0, 0, 0, 0, 0, + 49, 6, 0, 0, 242, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 0, 0, 0, 0, + 53, 6, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 0, 0, 0, 0, 0, 0, 0, + 49, 6, 0, 0, 242, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 0, 0, 0, 0, 0, 0, 0, + 53, 6, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 0, 0, 0, 0, + 53, 6, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 42, 0, 0, 0, 0, 0, 0, 0, + 49, 6, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 43, 0, 0, 0, 0, 0, 0, 0, + 49, 6, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 0, 0, 0, 0, + 45, 6, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 46, 0, 0, 0, 0, 0, 0, 0, + 41, 6, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 47, 0, 0, 0, 0, 0, 0, 0, + 37, 6, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 0, 0, 0, 0, 0, 0, 0, + 37, 6, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 0, 0, 0, 0, 0, 0, 0, + 37, 6, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 50, 0, 0, 0, 0, 0, 0, 0, + 37, 6, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 126, 0, 0, 0, 0, 0, 0, 0, + 33, 6, 0, 0, 250, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 127, 0, 0, 0, 0, 0, 0, 0, + 37, 6, 0, 0, 42, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 0, 0, 0, 0, 0, 0, 0, + 45, 6, 0, 0, 42, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 51, 0, 0, 0, 0, 0, 0, 0, + 53, 6, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 52, 0, 0, 0, 0, 0, 0, 0, + 49, 6, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 53, 0, 0, 0, 0, 0, 0, 0, + 45, 6, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 54, 0, 0, 0, 0, 0, 0, 0, + 37, 6, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 0, 0, 0, 0, 0, 0, 0, + 33, 6, 0, 0, 202, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 0, 0, 0, 0, 0, 0, 0, + 37, 6, 0, 0, 242, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 55, 0, 0, 0, 0, 0, 0, 0, + 41, 6, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 56, 0, 0, 0, 0, 0, 0, 0, + 41, 6, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 57, 0, 0, 0, 0, 0, 0, 0, + 37, 6, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 58, 0, 0, 0, 0, 0, 0, 0, + 37, 6, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 37, 6, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 59, 0, 0, 0, 0, 0, 0, 0, + 37, 6, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 60, 0, 0, 0, 0, 0, 0, 0, + 33, 6, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 0, 0, 0, 0, 0, 0, 0, + 25, 6, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 62, 0, 0, 0, 0, 0, 0, 0, + 21, 6, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 63, 0, 0, 0, 0, 0, 0, 0, + 21, 6, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 65, 0, 0, 0, 0, 0, 0, 0, + 17, 6, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 66, 0, 0, 0, 0, 0, 0, 0, + 9, 6, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 128, 0, 0, 0, 0, 0, 0, 0, + 5, 6, 0, 0, 2, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 0, 0, 0, 0, 0, 0, 0, + 9, 6, 0, 0, 202, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 129, 0, 0, 0, 0, 0, 0, 0, + 13, 6, 0, 0, 218, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 67, 0, 0, 0, 0, 0, 0, 0, + 17, 6, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 0, 0, 0, 0, 0, 0, 0, + 17, 6, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 130, 0, 0, 0, 0, 0, 0, 0, + 9, 6, 0, 0, 234, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 0, 0, 0, 0, + 13, 6, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 131, 0, 0, 0, 0, 0, 0, 0, + 9, 6, 0, 0, 234, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 70, 0, 0, 0, 0, 0, 0, 0, + 13, 6, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 71, 0, 0, 0, 0, 0, 0, 0, + 9, 6, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 0, 0, 0, 0, 0, 0, 0, + 5, 6, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 0, 0, 0, 0, + 1, 6, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 132, 0, 0, 0, 0, 0, 0, 0, + 1, 6, 0, 0, 210, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 75, 0, 0, 0, 0, 0, 0, 0, + 5, 6, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 0, 0, 0, 0, 0, 0, 0, + 1, 6, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 0, 0, 0, 0, + 1, 6, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 134, 0, 0, 0, 0, 0, 0, 0, + 253, 5, 0, 0, 18, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 78, 0, 0, 0, 0, 0, 0, 0, + 5, 6, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 79, 0, 0, 0, 0, 0, 0, 0, + 5, 6, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 80, 0, 0, 0, 0, 0, 0, 0, + 1, 6, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 81, 0, 0, 0, 0, 0, 0, 0, + 253, 5, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 82, 0, 0, 0, 0, 0, 0, 0, + 253, 5, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 91, 0, 0, 0, 0, 0, 0, 0, + 253, 5, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 0, 0, 0, 0, 0, 0, 0, + 253, 5, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 83, 0, 0, 0, 0, 0, 0, 0, + 249, 5, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 84, 0, 0, 0, 0, 0, 0, 0, + 245, 5, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 85, 0, 0, 0, 0, 0, 0, 0, + 241, 5, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 237, 5, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 0, 0, 0, 0, + 237, 5, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 74, 0, 0, 0, 0, 0, 0, 0, + 237, 5, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 86, 0, 0, 0, 0, 0, 0, 0, + 233, 5, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 87, 0, 0, 0, 0, 0, 0, 0, + 229, 5, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 88, 0, 0, 0, 0, 0, 0, 0, + 229, 5, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 225, 5, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 89, 0, 0, 0, 0, 0, 0, 0, + 221, 5, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 90, 0, 0, 0, 0, 0, 0, 0, + 217, 5, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 0, 0, 0, 0, + 217, 5, 0, 0, 202, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 0, 0, 0, 0, 0, 0, 0, + 221, 5, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 94, 0, 0, 0, 0, 0, 0, 0, + 221, 5, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 95, 0, 0, 0, 0, 0, 0, 0, + 221, 5, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 0, 0, 0, 0, 0, 0, 0, + 213, 5, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 0, 0, 0, 0, + 205, 5, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 0, 0, 0, 0, 0, 0, 0, + 205, 5, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 0, 0, 0, 0, 0, 0, 0, + 205, 5, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 0, 0, 0, 0, 0, 0, 0, + 201, 5, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 0, 0, 0, 0, 0, 0, 0, + 197, 5, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 0, 0, 0, 0, 0, 0, 0, + 197, 5, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 0, 0, 0, 0, 0, 0, 0, + 193, 5, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 0, 0, 0, 0, 0, 0, 0, + 189, 5, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 0, 0, 0, 0, 0, 0, 0, + 189, 5, 0, 0, 234, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 106, 0, 0, 0, 0, 0, 0, 0, + 193, 5, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 107, 0, 0, 0, 0, 0, 0, 0, + 193, 5, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 0, 0, 0, 0, 0, 0, 0, + 193, 5, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 0, 0, 0, 0, 0, 0, 0, + 189, 5, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 0, 0, 0, 0, 0, 0, 0, + 185, 5, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 0, 0, 0, 0, 0, 0, 0, + 181, 5, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 0, 0, 0, 0, 0, 0, 0, + 177, 5, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 110, 69, 114, 114, 111, 114, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 85, 110, 97, + 118, 97, 105, 108, 97, 98, 108, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 114, 97, 107, 101, 85, 110, 97, + 118, 97, 105, 108, 97, 98, 108, 101, + 68, 69, 80, 82, 69, 67, 65, 84, + 69, 68, 0, 0, 0, 0, 0, 0, + 103, 97, 115, 85, 110, 97, 118, 97, + 105, 108, 97, 98, 108, 101, 68, 69, + 80, 82, 69, 67, 65, 84, 69, 68, + 0, 0, 0, 0, 0, 0, 0, 0, + 119, 114, 111, 110, 103, 71, 101, 97, + 114, 0, 0, 0, 0, 0, 0, 0, + 100, 111, 111, 114, 79, 112, 101, 110, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 101, 97, 116, 98, 101, 108, 116, + 78, 111, 116, 76, 97, 116, 99, 104, + 101, 100, 0, 0, 0, 0, 0, 0, + 101, 115, 112, 68, 105, 115, 97, 98, + 108, 101, 100, 0, 0, 0, 0, 0, + 119, 114, 111, 110, 103, 67, 97, 114, + 77, 111, 100, 101, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 84, 101, 109, + 112, 85, 110, 97, 118, 97, 105, 108, + 97, 98, 108, 101, 0, 0, 0, 0, + 114, 101, 118, 101, 114, 115, 101, 71, + 101, 97, 114, 0, 0, 0, 0, 0, + 98, 117, 116, 116, 111, 110, 67, 97, + 110, 99, 101, 108, 0, 0, 0, 0, + 98, 117, 116, 116, 111, 110, 69, 110, + 97, 98, 108, 101, 0, 0, 0, 0, + 112, 101, 100, 97, 108, 80, 114, 101, + 115, 115, 101, 100, 0, 0, 0, 0, + 99, 114, 117, 105, 115, 101, 68, 105, + 115, 97, 98, 108, 101, 100, 0, 0, + 114, 97, 100, 97, 114, 67, 97, 110, + 69, 114, 114, 111, 114, 68, 69, 80, + 82, 69, 67, 65, 84, 69, 68, 0, + 100, 97, 116, 97, 78, 101, 101, 100, + 101, 100, 68, 69, 80, 82, 69, 67, + 65, 84, 69, 68, 0, 0, 0, 0, + 115, 112, 101, 101, 100, 84, 111, 111, + 76, 111, 119, 0, 0, 0, 0, 0, + 111, 117, 116, 79, 102, 83, 112, 97, + 99, 101, 0, 0, 0, 0, 0, 0, + 111, 118, 101, 114, 104, 101, 97, 116, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 108, 105, 98, 114, 97, 116, + 105, 111, 110, 73, 110, 99, 111, 109, + 112, 108, 101, 116, 101, 0, 0, 0, + 99, 97, 108, 105, 98, 114, 97, 116, + 105, 111, 110, 73, 110, 118, 97, 108, + 105, 100, 0, 0, 0, 0, 0, 0, + 99, 111, 110, 116, 114, 111, 108, 115, + 77, 105, 115, 109, 97, 116, 99, 104, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 99, 109, 69, 110, 97, 98, 108, + 101, 0, 0, 0, 0, 0, 0, 0, + 112, 99, 109, 68, 105, 115, 97, 98, + 108, 101, 0, 0, 0, 0, 0, 0, + 110, 111, 84, 97, 114, 103, 101, 116, + 68, 69, 80, 82, 69, 67, 65, 84, + 69, 68, 0, 0, 0, 0, 0, 0, + 114, 97, 100, 97, 114, 70, 97, 117, + 108, 116, 0, 0, 0, 0, 0, 0, + 109, 111, 100, 101, 108, 67, 111, 109, + 109, 73, 115, 115, 117, 101, 68, 69, + 80, 82, 69, 67, 65, 84, 69, 68, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 114, 97, 107, 101, 72, 111, 108, + 100, 0, 0, 0, 0, 0, 0, 0, + 112, 97, 114, 107, 66, 114, 97, 107, + 101, 0, 0, 0, 0, 0, 0, 0, + 109, 97, 110, 117, 97, 108, 82, 101, + 115, 116, 97, 114, 116, 0, 0, 0, + 108, 111, 119, 83, 112, 101, 101, 100, + 76, 111, 99, 107, 111, 117, 116, 0, + 112, 108, 97, 110, 110, 101, 114, 69, + 114, 114, 111, 114, 68, 69, 80, 82, + 69, 67, 65, 84, 69, 68, 0, 0, + 105, 112, 97, 115, 79, 118, 101, 114, + 114, 105, 100, 101, 68, 69, 80, 82, + 69, 67, 65, 84, 69, 68, 0, 0, + 106, 111, 121, 115, 116, 105, 99, 107, + 68, 101, 98, 117, 103, 0, 0, 0, + 115, 116, 101, 101, 114, 84, 101, 109, + 112, 85, 110, 97, 118, 97, 105, 108, + 97, 98, 108, 101, 83, 105, 108, 101, + 110, 116, 0, 0, 0, 0, 0, 0, + 114, 101, 115, 117, 109, 101, 82, 101, + 113, 117, 105, 114, 101, 100, 0, 0, + 112, 114, 101, 68, 114, 105, 118, 101, + 114, 68, 105, 115, 116, 114, 97, 99, + 116, 101, 100, 0, 0, 0, 0, 0, + 112, 114, 111, 109, 112, 116, 68, 114, + 105, 118, 101, 114, 68, 105, 115, 116, + 114, 97, 99, 116, 101, 100, 0, 0, + 100, 114, 105, 118, 101, 114, 68, 105, + 115, 116, 114, 97, 99, 116, 101, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 101, 111, 102, 101, 110, 99, 101, + 68, 69, 80, 82, 69, 67, 65, 84, + 69, 68, 0, 0, 0, 0, 0, 0, + 100, 114, 105, 118, 101, 114, 77, 111, + 110, 105, 116, 111, 114, 79, 110, 68, + 69, 80, 82, 69, 67, 65, 84, 69, + 68, 0, 0, 0, 0, 0, 0, 0, + 100, 114, 105, 118, 101, 114, 77, 111, + 110, 105, 116, 111, 114, 79, 102, 102, + 68, 69, 80, 82, 69, 67, 65, 84, + 69, 68, 0, 0, 0, 0, 0, 0, + 112, 114, 101, 68, 114, 105, 118, 101, + 114, 85, 110, 114, 101, 115, 112, 111, + 110, 115, 105, 118, 101, 0, 0, 0, + 112, 114, 111, 109, 112, 116, 68, 114, + 105, 118, 101, 114, 85, 110, 114, 101, + 115, 112, 111, 110, 115, 105, 118, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 114, 105, 118, 101, 114, 85, 110, + 114, 101, 115, 112, 111, 110, 115, 105, + 118, 101, 0, 0, 0, 0, 0, 0, + 98, 101, 108, 111, 119, 83, 116, 101, + 101, 114, 83, 112, 101, 101, 100, 0, + 99, 97, 108, 105, 98, 114, 97, 116, + 105, 111, 110, 80, 114, 111, 103, 114, + 101, 115, 115, 68, 69, 80, 82, 69, + 67, 65, 84, 69, 68, 0, 0, 0, + 108, 111, 119, 66, 97, 116, 116, 101, + 114, 121, 0, 0, 0, 0, 0, 0, + 105, 110, 118, 97, 108, 105, 100, 71, + 105, 114, 97, 102, 102, 101, 72, 111, + 110, 100, 97, 68, 69, 80, 82, 69, + 67, 65, 84, 69, 68, 0, 0, 0, + 112, 97, 114, 97, 109, 115, 100, 84, + 101, 109, 112, 111, 114, 97, 114, 121, + 69, 114, 114, 111, 114, 0, 0, 0, + 97, 99, 99, 70, 97, 117, 108, 116, + 101, 100, 0, 0, 0, 0, 0, 0, + 115, 101, 110, 115, 111, 114, 68, 97, + 116, 97, 73, 110, 118, 97, 108, 105, + 100, 0, 0, 0, 0, 0, 0, 0, + 99, 111, 109, 109, 73, 115, 115, 117, + 101, 0, 0, 0, 0, 0, 0, 0, + 116, 111, 111, 68, 105, 115, 116, 114, + 97, 99, 116, 101, 100, 0, 0, 0, + 112, 111, 115, 101, 110, 101, 116, 73, + 110, 118, 97, 108, 105, 100, 0, 0, + 115, 111, 117, 110, 100, 115, 85, 110, + 97, 118, 97, 105, 108, 97, 98, 108, + 101, 0, 0, 0, 0, 0, 0, 0, + 112, 114, 101, 76, 97, 110, 101, 67, + 104, 97, 110, 103, 101, 76, 101, 102, + 116, 0, 0, 0, 0, 0, 0, 0, + 112, 114, 101, 76, 97, 110, 101, 67, + 104, 97, 110, 103, 101, 82, 105, 103, + 104, 116, 0, 0, 0, 0, 0, 0, + 108, 97, 110, 101, 67, 104, 97, 110, + 103, 101, 0, 0, 0, 0, 0, 0, + 105, 110, 118, 97, 108, 105, 100, 71, + 105, 114, 97, 102, 102, 101, 84, 111, + 121, 111, 116, 97, 68, 69, 80, 82, + 69, 67, 65, 84, 69, 68, 0, 0, + 105, 110, 116, 101, 114, 110, 101, 116, + 67, 111, 110, 110, 101, 99, 116, 105, + 118, 105, 116, 121, 78, 101, 101, 100, + 101, 100, 68, 69, 80, 82, 69, 67, + 65, 84, 69, 68, 0, 0, 0, 0, + 99, 111, 109, 109, 117, 110, 105, 116, + 121, 70, 101, 97, 116, 117, 114, 101, + 68, 105, 115, 97, 108, 108, 111, 119, + 101, 100, 68, 69, 80, 82, 69, 67, + 65, 84, 69, 68, 0, 0, 0, 0, + 108, 111, 119, 77, 101, 109, 111, 114, + 121, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 111, 99, 107, 65, 101, 98, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 100, 119, 0, 0, 0, 0, 0, + 99, 97, 114, 85, 110, 114, 101, 99, + 111, 103, 110, 105, 122, 101, 100, 0, + 114, 97, 100, 97, 114, 67, 111, 109, + 109, 73, 115, 115, 117, 101, 68, 69, + 80, 82, 69, 67, 65, 84, 69, 68, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 114, 105, 118, 101, 114, 77, 111, + 110, 105, 116, 111, 114, 76, 111, 119, + 65, 99, 99, 68, 69, 80, 82, 69, + 67, 65, 84, 69, 68, 0, 0, 0, + 105, 110, 118, 97, 108, 105, 100, 76, + 107, 97, 115, 83, 101, 116, 116, 105, + 110, 103, 0, 0, 0, 0, 0, 0, + 115, 112, 101, 101, 100, 84, 111, 111, + 72, 105, 103, 104, 0, 0, 0, 0, + 108, 97, 110, 101, 67, 104, 97, 110, + 103, 101, 66, 108, 111, 99, 107, 101, + 100, 0, 0, 0, 0, 0, 0, 0, + 114, 101, 108, 97, 121, 77, 97, 108, + 102, 117, 110, 99, 116, 105, 111, 110, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 114, 101, 69, 110, 97, 98, 108, + 101, 83, 116, 97, 110, 100, 115, 116, + 105, 108, 108, 0, 0, 0, 0, 0, + 115, 116, 111, 99, 107, 70, 99, 119, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 114, 116, 117, 112, 0, + 115, 116, 97, 114, 116, 117, 112, 78, + 111, 67, 97, 114, 0, 0, 0, 0, + 115, 116, 97, 114, 116, 117, 112, 78, + 111, 67, 111, 110, 116, 114, 111, 108, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 114, 116, 117, 112, 77, + 97, 115, 116, 101, 114, 0, 0, 0, + 102, 99, 119, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 83, 97, 116, + 117, 114, 97, 116, 101, 100, 0, 0, + 119, 104, 105, 116, 101, 80, 97, 110, + 100, 97, 85, 110, 115, 117, 112, 112, + 111, 114, 116, 101, 100, 68, 69, 80, + 82, 69, 67, 65, 84, 69, 68, 0, + 115, 116, 97, 114, 116, 117, 112, 79, + 110, 101, 112, 108, 117, 115, 68, 69, + 80, 82, 69, 67, 65, 84, 69, 68, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 111, 109, 109, 73, 115, 115, 117, + 101, 87, 97, 114, 110, 105, 110, 103, + 68, 69, 80, 82, 69, 67, 65, 84, + 69, 68, 0, 0, 0, 0, 0, 0, + 98, 101, 108, 111, 119, 69, 110, 103, + 97, 103, 101, 83, 112, 101, 101, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 111, 71, 112, 115, 0, 0, 0, + 102, 111, 99, 117, 115, 82, 101, 99, + 111, 118, 101, 114, 65, 99, 116, 105, + 118, 101, 68, 69, 80, 82, 69, 67, + 65, 84, 69, 68, 0, 0, 0, 0, + 119, 114, 111, 110, 103, 67, 114, 117, + 105, 115, 101, 77, 111, 100, 101, 0, + 110, 101, 111, 115, 85, 112, 100, 97, + 116, 101, 82, 101, 113, 117, 105, 114, + 101, 100, 68, 69, 80, 82, 69, 67, + 65, 84, 69, 68, 0, 0, 0, 0, + 109, 111, 100, 101, 108, 100, 76, 97, + 103, 103, 105, 110, 103, 0, 0, 0, + 100, 101, 118, 105, 99, 101, 70, 97, + 108, 108, 105, 110, 103, 0, 0, 0, + 102, 97, 110, 77, 97, 108, 102, 117, + 110, 99, 116, 105, 111, 110, 0, 0, + 99, 97, 109, 101, 114, 97, 77, 97, + 108, 102, 117, 110, 99, 116, 105, 111, + 110, 0, 0, 0, 0, 0, 0, 0, + 109, 111, 100, 101, 108, 76, 97, 103, + 87, 97, 114, 110, 105, 110, 103, 68, + 69, 80, 82, 69, 67, 65, 84, 69, + 68, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 77, 97, 108, 102, 117, + 110, 99, 116, 105, 111, 110, 0, 0, + 112, 114, 111, 99, 101, 115, 115, 78, + 111, 116, 82, 117, 110, 110, 105, 110, + 103, 0, 0, 0, 0, 0, 0, 0, + 100, 97, 115, 104, 99, 97, 109, 77, + 111, 100, 101, 0, 0, 0, 0, 0, + 115, 116, 97, 114, 116, 117, 112, 70, + 117, 122, 122, 121, 70, 105, 110, 103, + 101, 114, 112, 114, 105, 110, 116, 68, + 69, 80, 82, 69, 67, 65, 84, 69, + 68, 0, 0, 0, 0, 0, 0, 0, + 99, 111, 110, 116, 114, 111, 108, 115, + 73, 110, 105, 116, 105, 97, 108, 105, + 122, 105, 110, 103, 0, 0, 0, 0, + 117, 115, 98, 69, 114, 114, 111, 114, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 111, 97, 100, 67, 97, 109, 101, + 114, 97, 69, 114, 114, 111, 114, 0, + 100, 114, 105, 118, 101, 114, 67, 97, + 109, 101, 114, 97, 69, 114, 114, 111, + 114, 0, 0, 0, 0, 0, 0, 0, + 119, 105, 100, 101, 82, 111, 97, 100, + 67, 97, 109, 101, 114, 97, 69, 114, + 114, 111, 114, 0, 0, 0, 0, 0, + 108, 111, 99, 97, 116, 105, 111, 110, + 100, 84, 101, 109, 112, 111, 114, 97, + 114, 121, 69, 114, 114, 111, 114, 0, + 115, 116, 97, 114, 116, 117, 112, 78, + 111, 70, 119, 0, 0, 0, 0, 0, + 104, 105, 103, 104, 67, 112, 117, 85, + 115, 97, 103, 101, 0, 0, 0, 0, + 99, 114, 117, 105, 115, 101, 77, 105, + 115, 109, 97, 116, 99, 104, 0, 0, + 108, 107, 97, 115, 68, 105, 115, 97, + 98, 108, 101, 100, 0, 0, 0, 0, + 103, 97, 115, 80, 114, 101, 115, 115, + 101, 100, 79, 118, 101, 114, 114, 105, + 100, 101, 0, 0, 0, 0, 0, 0, + 99, 111, 109, 109, 73, 115, 115, 117, + 101, 65, 118, 103, 70, 114, 101, 113, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 109, 101, 114, 97, 70, 114, + 97, 109, 101, 82, 97, 116, 101, 0, + 99, 97, 110, 66, 117, 115, 77, 105, + 115, 115, 105, 110, 103, 0, 0, 0, + 99, 111, 110, 116, 114, 111, 108, 115, + 100, 76, 97, 103, 103, 105, 110, 103, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 101, 115, 117, 109, 101, 66, 108, + 111, 99, 107, 101, 100, 0, 0, 0, + 115, 116, 101, 101, 114, 79, 118, 101, + 114, 114, 105, 100, 101, 0, 0, 0, + 115, 116, 101, 101, 114, 84, 105, 109, + 101, 76, 105, 109, 105, 116, 0, 0, + 118, 101, 104, 105, 99, 108, 101, 83, + 101, 110, 115, 111, 114, 115, 73, 110, + 118, 97, 108, 105, 100, 0, 0, 0, + 99, 97, 108, 105, 98, 114, 97, 116, + 105, 111, 110, 82, 101, 99, 97, 108, + 105, 98, 114, 97, 116, 105, 110, 103, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 99, 97, 116, 105, 111, 110, + 100, 80, 101, 114, 109, 97, 110, 101, + 110, 116, 69, 114, 114, 111, 114, 0, + 112, 97, 114, 97, 109, 115, 100, 80, + 101, 114, 109, 97, 110, 101, 110, 116, + 69, 114, 114, 111, 114, 0, 0, 0, + 97, 99, 99, 101, 108, 51, 48, 0, + 97, 99, 99, 101, 108, 51, 53, 0, + 102, 105, 114, 101, 102, 111, 120, 83, + 116, 101, 101, 114, 83, 97, 116, 117, + 114, 97, 116, 101, 100, 0, 0, 0, + 102, 114, 111, 103, 83, 116, 101, 101, + 114, 83, 97, 116, 117, 114, 97, 116, + 101, 100, 0, 0, 0, 0, 0, 0, + 103, 114, 101, 101, 110, 76, 105, 103, + 104, 116, 0, 0, 0, 0, 0, 0, + 104, 111, 108, 105, 100, 97, 121, 65, + 99, 116, 105, 118, 101, 0, 0, 0, + 108, 97, 110, 101, 67, 104, 97, 110, + 103, 101, 66, 108, 111, 99, 107, 101, + 100, 76, 111, 117, 100, 0, 0, 0, + 108, 101, 97, 100, 68, 101, 112, 97, + 114, 116, 105, 110, 103, 0, 0, 0, + 110, 111, 76, 97, 110, 101, 65, 118, + 97, 105, 108, 97, 98, 108, 101, 0, + 111, 112, 101, 110, 112, 105, 108, 111, + 116, 67, 114, 97, 115, 104, 101, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 112, 101, 110, 112, 105, 108, 111, + 116, 67, 114, 97, 115, 104, 101, 100, + 82, 97, 110, 100, 111, 109, 69, 118, + 101, 110, 116, 115, 0, 0, 0, 0, + 112, 101, 100, 97, 108, 73, 110, 116, + 101, 114, 99, 101, 112, 116, 111, 114, + 78, 111, 66, 114, 97, 107, 101, 0, + 115, 112, 101, 101, 100, 76, 105, 109, + 105, 116, 67, 104, 97, 110, 103, 101, + 100, 0, 0, 0, 0, 0, 0, 0, + 116, 111, 114, 113, 117, 101, 78, 78, + 76, 111, 97, 100, 0, 0, 0, 0, + 116, 117, 114, 110, 105, 110, 103, 76, + 101, 102, 116, 0, 0, 0, 0, 0, + 116, 117, 114, 110, 105, 110, 103, 82, + 105, 103, 104, 116, 0, 0, 0, 0, + 118, 67, 114, 117, 105, 115, 101, 54, + 57, 0, 0, 0, 0, 0, 0, 0, + 121, 111, 117, 114, 70, 114, 111, 103, + 84, 114, 105, 101, 100, 84, 111, 75, + 105, 108, 108, 77, 101, 0, 0, 0, } +}; +::capnp::word const* const bp_baa8c5d505f727de = b_baa8c5d505f727de.words; +#if !CAPNP_LITE +static const uint16_t m_baa8c5d505f727de[] = {51, 120, 121, 84, 46, 28, 2, 11, 12, 20, 21, 47, 117, 110, 92, 111, 0, 66, 53, 109, 83, 62, 98, 22, 112, 14, 106, 96, 16, 90, 5, 101, 39, 68, 42, 41, 45, 7, 91, 79, 122, 86, 123, 108, 3, 40, 94, 124, 105, 125, 61, 49, 60, 69, 33, 34, 59, 71, 126, 65, 127, 107, 118, 103, 48, 63, 31, 30, 27, 93, 89, 88, 85, 128, 25, 129, 130, 18, 19, 119, 50, 29, 24, 23, 131, 13, 32, 55, 37, 43, 73, 57, 58, 95, 38, 44, 15, 67, 26, 72, 113, 36, 10, 100, 6, 52, 56, 132, 70, 17, 75, 97, 78, 76, 77, 104, 82, 114, 80, 9, 35, 115, 1, 64, 74, 54, 133, 134, 135, 99, 136, 116, 81, 102, 8, 87, 4, 137}; +const ::capnp::_::RawSchema s_baa8c5d505f727de = { + 0xbaa8c5d505f727de, b_baa8c5d505f727de.words, 798, nullptr, m_baa8c5d505f727de, + 0, 138, nullptr, nullptr, nullptr, { &s_baa8c5d505f727de, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(EventName_baa8c5d505f727de, baa8c5d505f727de); +static const ::capnp::_::AlignedData<822> b_9da4fa09e052903c = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 60, 144, 82, 224, 9, 250, 164, 157, + 10, 0, 0, 0, 1, 0, 8, 0, + 141, 139, 175, 8, 231, 241, 42, 142, + 6, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 154, 0, 0, 0, + 29, 0, 0, 0, 71, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 89, 0, 0, 0, 135, 10, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 46, 99, 97, 112, 110, + 112, 58, 67, 97, 114, 83, 116, 97, + 116, 101, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 1, 0, 1, 0, + 163, 53, 89, 21, 166, 55, 26, 153, + 25, 0, 0, 0, 98, 0, 0, 0, + 175, 96, 110, 142, 71, 129, 78, 230, + 25, 0, 0, 0, 98, 0, 0, 0, + 137, 106, 111, 19, 69, 202, 4, 224, + 25, 0, 0, 0, 98, 0, 0, 0, + 246, 206, 74, 91, 131, 166, 92, 255, + 25, 0, 0, 0, 98, 0, 0, 0, + 87, 104, 101, 101, 108, 83, 112, 101, + 101, 100, 115, 0, 0, 0, 0, 0, + 67, 114, 117, 105, 115, 101, 83, 116, + 97, 116, 101, 0, 0, 0, 0, 0, + 71, 101, 97, 114, 83, 104, 105, 102, + 116, 101, 114, 0, 0, 0, 0, 0, + 66, 117, 116, 116, 111, 110, 69, 118, + 101, 110, 116, 0, 0, 0, 0, 0, + 192, 0, 0, 0, 3, 0, 4, 0, + 44, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 5, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 52, 5, 0, 0, 3, 0, 1, 0, + 80, 5, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 5, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 5, 0, 0, 3, 0, 1, 0, + 84, 5, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 81, 5, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 80, 5, 0, 0, 3, 0, 1, 0, + 92, 5, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 89, 5, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 84, 5, 0, 0, 3, 0, 1, 0, + 96, 5, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 64, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 5, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 5, 0, 0, 3, 0, 1, 0, + 104, 5, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 5, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 5, 0, 0, 3, 0, 1, 0, + 108, 5, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 65, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 5, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 5, 0, 0, 3, 0, 1, 0, + 116, 5, 0, 0, 2, 0, 1, 0, + 18, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 5, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 5, 0, 0, 3, 0, 1, 0, + 128, 5, 0, 0, 2, 0, 1, 0, + 21, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 5, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 5, 0, 0, 3, 0, 1, 0, + 136, 5, 0, 0, 2, 0, 1, 0, + 23, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 5, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 132, 5, 0, 0, 3, 0, 1, 0, + 144, 5, 0, 0, 2, 0, 1, 0, + 31, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 5, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 140, 5, 0, 0, 3, 0, 1, 0, + 152, 5, 0, 0, 2, 0, 1, 0, + 33, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 149, 5, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 5, 0, 0, 3, 0, 1, 0, + 176, 5, 0, 0, 2, 0, 1, 0, + 47, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 173, 5, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 5, 0, 0, 3, 0, 1, 0, + 204, 5, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 5, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 5, 0, 0, 3, 0, 1, 0, + 224, 5, 0, 0, 2, 0, 1, 0, + 32, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 5, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 220, 5, 0, 0, 3, 0, 1, 0, + 232, 5, 0, 0, 2, 0, 1, 0, + 20, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 15, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 5, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 228, 5, 0, 0, 3, 0, 1, 0, + 240, 5, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 16, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 5, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 5, 0, 0, 3, 0, 1, 0, + 244, 5, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 17, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 5, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 236, 5, 0, 0, 3, 0, 1, 0, + 248, 5, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 67, 0, 0, 0, + 0, 0, 1, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 245, 5, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 244, 5, 0, 0, 3, 0, 1, 0, + 0, 6, 0, 0, 2, 0, 1, 0, + 45, 0, 0, 0, 68, 0, 0, 0, + 0, 0, 1, 0, 19, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 253, 5, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 6, 0, 0, 3, 0, 1, 0, + 12, 6, 0, 0, 2, 0, 1, 0, + 34, 0, 0, 0, 69, 0, 0, 0, + 0, 0, 1, 0, 20, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 6, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 6, 0, 0, 3, 0, 1, 0, + 20, 6, 0, 0, 2, 0, 1, 0, + 35, 0, 0, 0, 70, 0, 0, 0, + 0, 0, 1, 0, 21, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 6, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 6, 0, 0, 3, 0, 1, 0, + 28, 6, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 22, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 6, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 6, 0, 0, 3, 0, 1, 0, + 32, 6, 0, 0, 2, 0, 1, 0, + 36, 0, 0, 0, 71, 0, 0, 0, + 0, 0, 1, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 6, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 28, 6, 0, 0, 3, 0, 1, 0, + 40, 6, 0, 0, 2, 0, 1, 0, + 37, 0, 0, 0, 72, 0, 0, 0, + 0, 0, 1, 0, 24, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 6, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 6, 0, 0, 3, 0, 1, 0, + 48, 6, 0, 0, 2, 0, 1, 0, + 38, 0, 0, 0, 73, 0, 0, 0, + 0, 0, 1, 0, 25, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 6, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 6, 0, 0, 3, 0, 1, 0, + 60, 6, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 1, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 57, 6, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 56, 6, 0, 0, 3, 0, 1, 0, + 68, 6, 0, 0, 2, 0, 1, 0, + 22, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 27, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 65, 6, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 6, 0, 0, 3, 0, 1, 0, + 80, 6, 0, 0, 2, 0, 1, 0, + 39, 0, 0, 0, 75, 0, 0, 0, + 0, 0, 1, 0, 28, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 6, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 6, 0, 0, 3, 0, 1, 0, + 88, 6, 0, 0, 2, 0, 1, 0, + 46, 0, 0, 0, 76, 0, 0, 0, + 0, 0, 1, 0, 29, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 85, 6, 0, 0, 242, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 6, 0, 0, 3, 0, 1, 0, + 104, 6, 0, 0, 2, 0, 1, 0, + 26, 0, 0, 0, 77, 0, 0, 0, + 0, 0, 1, 0, 30, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 6, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 6, 0, 0, 3, 0, 1, 0, + 112, 6, 0, 0, 2, 0, 1, 0, + 27, 0, 0, 0, 78, 0, 0, 0, + 0, 0, 1, 0, 31, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 6, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 6, 0, 0, 3, 0, 1, 0, + 120, 6, 0, 0, 2, 0, 1, 0, + 28, 0, 0, 0, 79, 0, 0, 0, + 0, 0, 1, 0, 32, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 6, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 6, 0, 0, 3, 0, 1, 0, + 128, 6, 0, 0, 2, 0, 1, 0, + 40, 0, 0, 0, 96, 1, 0, 0, + 0, 0, 1, 0, 33, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 6, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 6, 0, 0, 3, 0, 1, 0, + 136, 6, 0, 0, 2, 0, 1, 0, + 41, 0, 0, 0, 97, 1, 0, 0, + 0, 0, 1, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 6, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 132, 6, 0, 0, 3, 0, 1, 0, + 144, 6, 0, 0, 2, 0, 1, 0, + 24, 0, 0, 0, 98, 1, 0, 0, + 0, 0, 1, 0, 35, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 6, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 144, 6, 0, 0, 3, 0, 1, 0, + 156, 6, 0, 0, 2, 0, 1, 0, + 25, 0, 0, 0, 99, 1, 0, 0, + 0, 0, 1, 0, 36, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 6, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 156, 6, 0, 0, 3, 0, 1, 0, + 168, 6, 0, 0, 2, 0, 1, 0, + 19, 0, 0, 0, 12, 0, 0, 0, + 0, 0, 1, 0, 37, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 165, 6, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 6, 0, 0, 3, 0, 1, 0, + 180, 6, 0, 0, 2, 0, 1, 0, + 17, 0, 0, 0, 100, 1, 0, 0, + 0, 0, 1, 0, 38, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 6, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 6, 0, 0, 3, 0, 1, 0, + 188, 6, 0, 0, 2, 0, 1, 0, + 16, 0, 0, 0, 101, 1, 0, 0, + 0, 0, 1, 0, 39, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 6, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 6, 0, 0, 3, 0, 1, 0, + 196, 6, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 102, 1, 0, 0, + 0, 0, 1, 0, 40, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 6, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 192, 6, 0, 0, 3, 0, 1, 0, + 204, 6, 0, 0, 2, 0, 1, 0, + 42, 0, 0, 0, 13, 0, 0, 0, + 0, 0, 1, 0, 41, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 6, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 200, 6, 0, 0, 3, 0, 1, 0, + 212, 6, 0, 0, 2, 0, 1, 0, + 29, 0, 0, 0, 103, 1, 0, 0, + 0, 0, 1, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 6, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 6, 0, 0, 3, 0, 1, 0, + 220, 6, 0, 0, 2, 0, 1, 0, + 43, 0, 0, 0, 104, 1, 0, 0, + 0, 0, 1, 0, 43, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 217, 6, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 6, 0, 0, 3, 0, 1, 0, + 228, 6, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 14, 0, 0, 0, + 0, 0, 1, 0, 44, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 225, 6, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 224, 6, 0, 0, 3, 0, 1, 0, + 236, 6, 0, 0, 2, 0, 1, 0, + 15, 0, 0, 0, 105, 1, 0, 0, + 0, 0, 1, 0, 45, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 233, 6, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 6, 0, 0, 3, 0, 1, 0, + 244, 6, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 15, 0, 0, 0, + 0, 0, 1, 0, 46, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 6, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 6, 0, 0, 3, 0, 1, 0, + 252, 6, 0, 0, 2, 0, 1, 0, + 30, 0, 0, 0, 106, 1, 0, 0, + 0, 0, 1, 0, 47, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 249, 6, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 252, 6, 0, 0, 3, 0, 1, 0, + 8, 7, 0, 0, 2, 0, 1, 0, + 101, 114, 114, 111, 114, 115, 68, 69, + 80, 82, 69, 67, 65, 84, 69, 68, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 222, 39, 247, 5, 213, 197, 168, 186, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 69, 103, 111, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 119, 104, 101, 101, 108, 83, 112, 101, + 101, 100, 115, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 163, 53, 89, 21, 166, 55, 26, 153, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 97, 115, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 97, 115, 80, 114, 101, 115, 115, + 101, 100, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 114, 97, 107, 101, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 114, 97, 107, 101, 80, 114, 101, + 115, 115, 101, 100, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 105, 110, 103, + 65, 110, 103, 108, 101, 68, 101, 103, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 105, 110, 103, + 84, 111, 114, 113, 117, 101, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 105, 110, 103, + 80, 114, 101, 115, 115, 101, 100, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 114, 117, 105, 115, 101, 83, 116, + 97, 116, 101, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 175, 96, 110, 142, 71, 129, 78, 230, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 117, 116, 116, 111, 110, 69, 118, + 101, 110, 116, 115, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 246, 206, 74, 91, 131, 166, 92, 255, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 110, 77, 111, 110, 111, 84, + 105, 109, 101, 115, 68, 69, 80, 82, + 69, 67, 65, 84, 69, 68, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 118, 101, 110, 116, 115, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 211, 58, 175, 76, 243, 87, 22, 155, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 101, 97, 114, 83, 104, 105, 102, + 116, 101, 114, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 137, 106, 111, 19, 69, 202, 4, 224, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 105, 110, 103, + 82, 97, 116, 101, 68, 101, 103, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 69, 103, 111, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 69, 103, 111, 82, 97, 119, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 110, 100, 115, 116, 105, + 108, 108, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 114, 97, 107, 101, 76, 105, 103, + 104, 116, 115, 68, 69, 80, 82, 69, + 67, 65, 84, 69, 68, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 102, 116, 66, 108, 105, 110, + 107, 101, 114, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 105, 103, 104, 116, 66, 108, 105, + 110, 107, 101, 114, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 97, 119, 82, 97, 116, 101, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 101, 110, 101, 114, 105, 99, 84, + 111, 103, 103, 108, 101, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 111, 111, 114, 79, 112, 101, 110, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 101, 97, 116, 98, 101, 108, 116, + 85, 110, 108, 97, 116, 99, 104, 101, + 100, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 110, 86, 97, 108, 105, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 105, 110, 103, + 84, 111, 114, 113, 117, 101, 69, 112, + 115, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 108, 117, 116, 99, 104, 80, 114, + 101, 115, 115, 101, 100, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 105, 110, 103, + 82, 97, 116, 101, 76, 105, 109, 105, + 116, 101, 100, 68, 69, 80, 82, 69, + 67, 65, 84, 69, 68, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 111, 99, 107, 65, 101, 98, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 111, 99, 107, 70, 99, 119, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 115, 112, 68, 105, 115, 97, 98, + 108, 101, 100, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 102, 116, 66, 108, 105, 110, + 100, 115, 112, 111, 116, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 105, 103, 104, 116, 66, 108, 105, + 110, 100, 115, 112, 111, 116, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 70, 97, 117, + 108, 116, 84, 101, 109, 112, 111, 114, + 97, 114, 121, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 70, 97, 117, + 108, 116, 80, 101, 114, 109, 97, 110, + 101, 110, 116, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 105, 110, 103, + 65, 110, 103, 108, 101, 79, 102, 102, + 115, 101, 116, 68, 101, 103, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 114, 97, 107, 101, 72, 111, 108, + 100, 65, 99, 116, 105, 118, 101, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 97, 114, 107, 105, 110, 103, 66, + 114, 97, 107, 101, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 110, 84, 105, 109, 101, 111, + 117, 116, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 117, 101, 108, 71, 97, 117, 103, + 101, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 99, 70, 97, 117, 108, 116, + 101, 100, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 104, 97, 114, 103, 105, 110, 103, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 69, 103, 111, 67, 108, 117, 115, + 116, 101, 114, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 101, 103, 101, 110, 66, 114, 97, + 107, 105, 110, 103, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 110, 103, 105, 110, 101, 82, 112, + 109, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 70, 97, 117, 108, 116, + 101, 100, 78, 111, 110, 67, 114, 105, + 116, 105, 99, 97, 108, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_9da4fa09e052903c = b_9da4fa09e052903c.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_9da4fa09e052903c[] = { + &s_991a37a6155935a3, + &s_9b1657f34caf3ad3, + &s_baa8c5d505f727de, + &s_e004ca45136f6a89, + &s_e64e81478e6e60af, + &s_ff5ca6835b4acef6, +}; +static const uint16_t m_9da4fa09e052903c[] = {16, 42, 5, 38, 19, 6, 11, 12, 40, 26, 47, 43, 28, 10, 24, 46, 0, 32, 13, 41, 3, 4, 14, 23, 33, 20, 39, 45, 34, 21, 25, 18, 36, 35, 7, 37, 9, 15, 29, 8, 27, 30, 31, 1, 44, 17, 2, 22}; +static const uint16_t i_9da4fa09e052903c[] = {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, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47}; +const ::capnp::_::RawSchema s_9da4fa09e052903c = { + 0x9da4fa09e052903c, b_9da4fa09e052903c.words, 822, d_9da4fa09e052903c, m_9da4fa09e052903c, + 6, 48, i_9da4fa09e052903c, nullptr, nullptr, { &s_9da4fa09e052903c, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<78> b_991a37a6155935a3 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 163, 53, 89, 21, 166, 55, 26, 153, + 19, 0, 0, 0, 1, 0, 2, 0, + 60, 144, 82, 224, 9, 250, 164, 157, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 250, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 231, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 46, 99, 97, 112, 110, + 112, 58, 67, 97, 114, 83, 116, 97, + 116, 101, 46, 87, 104, 101, 101, 108, + 83, 112, 101, 101, 100, 115, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 0, 0, 0, 3, 0, 1, 0, + 104, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 0, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 0, 0, 0, 3, 0, 1, 0, + 108, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 0, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 0, 0, 0, 3, 0, 1, 0, + 112, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 0, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 0, 0, 0, 3, 0, 1, 0, + 116, 0, 0, 0, 2, 0, 1, 0, + 102, 108, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 114, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 108, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 114, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_991a37a6155935a3 = b_991a37a6155935a3.words; +#if !CAPNP_LITE +static const uint16_t m_991a37a6155935a3[] = {0, 1, 2, 3}; +static const uint16_t i_991a37a6155935a3[] = {0, 1, 2, 3}; +const ::capnp::_::RawSchema s_991a37a6155935a3 = { + 0x991a37a6155935a3, b_991a37a6155935a3.words, 78, nullptr, m_991a37a6155935a3, + 0, 4, i_991a37a6155935a3, nullptr, nullptr, { &s_991a37a6155935a3, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<128> b_e64e81478e6e60af = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 175, 96, 110, 142, 71, 129, 78, 230, + 19, 0, 0, 0, 1, 0, 2, 0, + 60, 144, 82, 224, 9, 250, 164, 157, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 250, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 143, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 46, 99, 97, 112, 110, + 112, 58, 67, 97, 114, 83, 116, 97, + 116, 101, 46, 67, 114, 117, 105, 115, + 101, 83, 116, 97, 116, 101, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 28, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 0, 0, 0, 3, 0, 1, 0, + 188, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 0, 0, 0, 3, 0, 1, 0, + 192, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 0, 0, 0, 3, 0, 1, 0, + 200, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 0, 0, 0, 3, 0, 1, 0, + 208, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 0, 0, 0, 3, 0, 1, 0, + 216, 0, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 212, 0, 0, 0, 3, 0, 1, 0, + 224, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 220, 0, 0, 0, 3, 0, 1, 0, + 232, 0, 0, 0, 2, 0, 1, 0, + 101, 110, 97, 98, 108, 101, 100, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 112, 101, 101, 100, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 118, 97, 105, 108, 97, 98, 108, + 101, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 112, 101, 101, 100, 79, 102, 102, + 115, 101, 116, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 110, 100, 115, 116, 105, + 108, 108, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 111, 110, 65, 100, 97, 112, 116, + 105, 118, 101, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 112, 101, 101, 100, 67, 108, 117, + 115, 116, 101, 114, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e64e81478e6e60af = b_e64e81478e6e60af.words; +#if !CAPNP_LITE +static const uint16_t m_e64e81478e6e60af[] = {2, 0, 5, 1, 6, 3, 4}; +static const uint16_t i_e64e81478e6e60af[] = {0, 1, 2, 3, 4, 5, 6}; +const ::capnp::_::RawSchema s_e64e81478e6e60af = { + 0xe64e81478e6e60af, b_e64e81478e6e60af.words, 128, nullptr, m_e64e81478e6e60af, + 0, 7, i_e64e81478e6e60af, nullptr, nullptr, { &s_e64e81478e6e60af, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<59> b_e004ca45136f6a89 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 137, 106, 111, 19, 69, 202, 4, 224, + 19, 0, 0, 0, 2, 0, 0, 0, + 60, 144, 82, 224, 9, 250, 164, 157, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 250, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 247, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 46, 99, 97, 112, 110, + 112, 58, 67, 97, 114, 83, 116, 97, + 116, 101, 46, 71, 101, 97, 114, 83, + 104, 105, 102, 116, 101, 114, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 40, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 105, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 89, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 81, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 65, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 57, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 49, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 110, 107, 110, 111, 119, 110, 0, + 112, 97, 114, 107, 0, 0, 0, 0, + 100, 114, 105, 118, 101, 0, 0, 0, + 110, 101, 117, 116, 114, 97, 108, 0, + 114, 101, 118, 101, 114, 115, 101, 0, + 115, 112, 111, 114, 116, 0, 0, 0, + 108, 111, 119, 0, 0, 0, 0, 0, + 98, 114, 97, 107, 101, 0, 0, 0, + 101, 99, 111, 0, 0, 0, 0, 0, + 109, 97, 110, 117, 109, 97, 116, 105, + 99, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e004ca45136f6a89 = b_e004ca45136f6a89.words; +#if !CAPNP_LITE +static const uint16_t m_e004ca45136f6a89[] = {7, 2, 8, 6, 9, 3, 1, 4, 5, 0}; +const ::capnp::_::RawSchema s_e004ca45136f6a89 = { + 0xe004ca45136f6a89, b_e004ca45136f6a89.words, 59, nullptr, m_e004ca45136f6a89, + 0, 10, nullptr, nullptr, nullptr, { &s_e004ca45136f6a89, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(GearShifter_e004ca45136f6a89, e004ca45136f6a89); +static const ::capnp::_::AlignedData<51> b_ff5ca6835b4acef6 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 246, 206, 74, 91, 131, 166, 92, 255, + 19, 0, 0, 0, 1, 0, 1, 0, + 60, 144, 82, 224, 9, 250, 164, 157, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 250, 0, 0, 0, + 33, 0, 0, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 46, 99, 97, 112, 110, + 112, 58, 67, 97, 114, 83, 116, 97, + 116, 101, 46, 66, 117, 116, 116, 111, + 110, 69, 118, 101, 110, 116, 0, 0, + 4, 0, 0, 0, 1, 0, 1, 0, + 124, 113, 20, 84, 32, 0, 97, 225, + 1, 0, 0, 0, 42, 0, 0, 0, + 84, 121, 112, 101, 0, 0, 0, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 112, 114, 101, 115, 115, 101, 100, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 121, 112, 101, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 124, 113, 20, 84, 32, 0, 97, 225, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_ff5ca6835b4acef6 = b_ff5ca6835b4acef6.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_ff5ca6835b4acef6[] = { + &s_e16100205414717c, +}; +static const uint16_t m_ff5ca6835b4acef6[] = {0, 1}; +static const uint16_t i_ff5ca6835b4acef6[] = {0, 1}; +const ::capnp::_::RawSchema s_ff5ca6835b4acef6 = { + 0xff5ca6835b4acef6, b_ff5ca6835b4acef6.words, 51, d_ff5ca6835b4acef6, m_ff5ca6835b4acef6, + 1, 2, i_ff5ca6835b4acef6, nullptr, nullptr, { &s_ff5ca6835b4acef6, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<77> b_e16100205414717c = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 124, 113, 20, 84, 32, 0, 97, 225, + 31, 0, 0, 0, 2, 0, 0, 0, + 246, 206, 74, 91, 131, 166, 92, 255, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 34, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 39, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 46, 99, 97, 112, 110, + 112, 58, 67, 97, 114, 83, 116, 97, + 116, 101, 46, 66, 117, 116, 116, 111, + 110, 69, 118, 101, 110, 116, 46, 84, + 121, 112, 101, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 48, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 137, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 129, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 125, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 121, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 117, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 113, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 105, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 101, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 93, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 89, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 85, 0, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 110, 107, 110, 111, 119, 110, 0, + 108, 101, 102, 116, 66, 108, 105, 110, + 107, 101, 114, 0, 0, 0, 0, 0, + 114, 105, 103, 104, 116, 66, 108, 105, + 110, 107, 101, 114, 0, 0, 0, 0, + 97, 99, 99, 101, 108, 67, 114, 117, + 105, 115, 101, 0, 0, 0, 0, 0, + 100, 101, 99, 101, 108, 67, 114, 117, + 105, 115, 101, 0, 0, 0, 0, 0, + 99, 97, 110, 99, 101, 108, 0, 0, + 97, 108, 116, 66, 117, 116, 116, 111, + 110, 49, 0, 0, 0, 0, 0, 0, + 97, 108, 116, 66, 117, 116, 116, 111, + 110, 50, 0, 0, 0, 0, 0, 0, + 97, 108, 116, 66, 117, 116, 116, 111, + 110, 51, 0, 0, 0, 0, 0, 0, + 115, 101, 116, 67, 114, 117, 105, 115, + 101, 0, 0, 0, 0, 0, 0, 0, + 114, 101, 115, 117, 109, 101, 67, 114, + 117, 105, 115, 101, 0, 0, 0, 0, + 103, 97, 112, 65, 100, 106, 117, 115, + 116, 67, 114, 117, 105, 115, 101, 0, } +}; +::capnp::word const* const bp_e16100205414717c = b_e16100205414717c.words; +#if !CAPNP_LITE +static const uint16_t m_e16100205414717c[] = {3, 6, 7, 8, 5, 4, 11, 1, 10, 2, 9, 0}; +const ::capnp::_::RawSchema s_e16100205414717c = { + 0xe16100205414717c, b_e16100205414717c.words, 77, nullptr, m_e16100205414717c, + 0, 12, nullptr, nullptr, nullptr, { &s_e16100205414717c, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(Type_e16100205414717c, e16100205414717c); +static const ::capnp::_::AlignedData<83> b_888ad6581cf0aacb = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 203, 170, 240, 28, 88, 214, 138, 136, + 10, 0, 0, 0, 1, 0, 0, 0, + 141, 139, 175, 8, 231, 241, 42, 142, + 3, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 162, 0, 0, 0, + 29, 0, 0, 0, 39, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 53, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 46, 99, 97, 112, 110, + 112, 58, 82, 97, 100, 97, 114, 68, + 97, 116, 97, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 1, 0, 1, 0, + 173, 118, 186, 235, 121, 102, 168, 232, + 9, 0, 0, 0, 50, 0, 0, 0, + 54, 223, 31, 172, 235, 51, 243, 143, + 5, 0, 0, 0, 90, 0, 0, 0, + 69, 114, 114, 111, 114, 0, 0, 0, + 82, 97, 100, 97, 114, 80, 111, 105, + 110, 116, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 0, 0, 0, 3, 0, 1, 0, + 92, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 89, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 84, 0, 0, 0, 3, 0, 1, 0, + 112, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 0, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 0, 0, 0, 3, 0, 1, 0, + 140, 0, 0, 0, 2, 0, 1, 0, + 101, 114, 114, 111, 114, 115, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 173, 118, 186, 235, 121, 102, 168, 232, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 105, 110, 116, 115, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 54, 223, 31, 172, 235, 51, 243, 143, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 110, 77, 111, 110, 111, 84, + 105, 109, 101, 115, 68, 69, 80, 82, + 69, 67, 65, 84, 69, 68, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_888ad6581cf0aacb = b_888ad6581cf0aacb.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_888ad6581cf0aacb[] = { + &s_8ff333ebac1fdf36, + &s_e8a86679ebba76ad, +}; +static const uint16_t m_888ad6581cf0aacb[] = {2, 0, 1}; +static const uint16_t i_888ad6581cf0aacb[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_888ad6581cf0aacb = { + 0x888ad6581cf0aacb, b_888ad6581cf0aacb.words, 83, d_888ad6581cf0aacb, m_888ad6581cf0aacb, + 2, 3, i_888ad6581cf0aacb, nullptr, nullptr, { &s_888ad6581cf0aacb, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<32> b_e8a86679ebba76ad = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 173, 118, 186, 235, 121, 102, 168, 232, + 20, 0, 0, 0, 2, 0, 0, 0, + 203, 170, 240, 28, 88, 214, 138, 136, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 210, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 79, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 46, 99, 97, 112, 110, + 112, 58, 82, 97, 100, 97, 114, 68, + 97, 116, 97, 46, 69, 114, 114, 111, + 114, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 17, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 110, 69, 114, 114, 111, 114, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 97, 117, 108, 116, 0, 0, 0, + 119, 114, 111, 110, 103, 67, 111, 110, + 102, 105, 103, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e8a86679ebba76ad = b_e8a86679ebba76ad.words; +#if !CAPNP_LITE +static const uint16_t m_e8a86679ebba76ad[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_e8a86679ebba76ad = { + 0xe8a86679ebba76ad, b_e8a86679ebba76ad.words, 32, nullptr, m_e8a86679ebba76ad, + 0, 3, nullptr, nullptr, nullptr, { &s_e8a86679ebba76ad, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(Error_e8a86679ebba76ad, e8a86679ebba76ad); +static const ::capnp::_::AlignedData<124> b_8ff333ebac1fdf36 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 54, 223, 31, 172, 235, 51, 243, 143, + 20, 0, 0, 0, 1, 0, 4, 0, + 203, 170, 240, 28, 88, 214, 138, 136, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 250, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 143, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 46, 99, 97, 112, 110, + 112, 58, 82, 97, 100, 97, 114, 68, + 97, 116, 97, 46, 82, 97, 100, 97, + 114, 80, 111, 105, 110, 116, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 28, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 0, 0, 0, 3, 0, 1, 0, + 188, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 0, 0, 0, 3, 0, 1, 0, + 192, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 0, 0, 0, 3, 0, 1, 0, + 196, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 0, 0, 0, 3, 0, 1, 0, + 200, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 192, 0, 0, 0, 3, 0, 1, 0, + 204, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 0, 0, 0, 3, 0, 1, 0, + 208, 0, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 224, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 0, 0, 0, 3, 0, 1, 0, + 216, 0, 0, 0, 2, 0, 1, 0, + 116, 114, 97, 99, 107, 73, 100, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 82, 101, 108, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 82, 101, 108, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 82, 101, 108, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 82, 101, 108, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 118, 82, 101, 108, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 101, 97, 115, 117, 114, 101, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_8ff333ebac1fdf36 = b_8ff333ebac1fdf36.words; +#if !CAPNP_LITE +static const uint16_t m_8ff333ebac1fdf36[] = {4, 1, 6, 0, 3, 2, 5}; +static const uint16_t i_8ff333ebac1fdf36[] = {0, 1, 2, 3, 4, 5, 6}; +const ::capnp::_::RawSchema s_8ff333ebac1fdf36 = { + 0x8ff333ebac1fdf36, b_8ff333ebac1fdf36.words, 124, nullptr, m_8ff333ebac1fdf36, + 0, 7, i_8ff333ebac1fdf36, nullptr, nullptr, { &s_8ff333ebac1fdf36, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<311> b_f78829049ab814af = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 175, 20, 184, 154, 4, 41, 136, 247, + 10, 0, 0, 0, 1, 0, 3, 0, + 141, 139, 175, 8, 231, 241, 42, 142, + 6, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 170, 0, 0, 0, + 29, 0, 0, 0, 55, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 191, 3, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 46, 99, 97, 112, 110, + 112, 58, 67, 97, 114, 67, 111, 110, + 116, 114, 111, 108, 0, 0, 0, 0, + 12, 0, 0, 0, 1, 0, 1, 0, + 40, 40, 67, 25, 169, 117, 114, 233, + 17, 0, 0, 0, 82, 0, 0, 0, + 211, 168, 11, 14, 110, 56, 14, 178, + 17, 0, 0, 0, 114, 0, 0, 0, + 56, 58, 176, 78, 124, 200, 149, 216, + 17, 0, 0, 0, 90, 0, 0, 0, + 65, 99, 116, 117, 97, 116, 111, 114, + 115, 0, 0, 0, 0, 0, 0, 0, + 67, 114, 117, 105, 115, 101, 67, 111, + 110, 116, 114, 111, 108, 0, 0, 0, + 72, 85, 68, 67, 111, 110, 116, 114, + 111, 108, 0, 0, 0, 0, 0, 0, + 68, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 1, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 200, 1, 0, 0, 3, 0, 1, 0, + 212, 1, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 1, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 1, 0, 0, 3, 0, 1, 0, + 220, 1, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 217, 1, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 1, 0, 0, 3, 0, 1, 0, + 228, 1, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 225, 1, 0, 0, 202, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 1, 0, 0, 3, 0, 1, 0, + 244, 1, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 1, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 1, 0, 0, 3, 0, 1, 0, + 252, 1, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 249, 1, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 248, 1, 0, 0, 3, 0, 1, 0, + 4, 2, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 2, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 2, 0, 0, 3, 0, 1, 0, + 12, 2, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 2, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 2, 0, 0, 3, 0, 1, 0, + 24, 2, 0, 0, 2, 0, 1, 0, + 15, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 2, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 2, 0, 0, 3, 0, 1, 0, + 32, 2, 0, 0, 2, 0, 1, 0, + 16, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 2, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 28, 2, 0, 0, 3, 0, 1, 0, + 40, 2, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 2, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 2, 0, 0, 3, 0, 1, 0, + 48, 2, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 2, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 2, 0, 0, 3, 0, 1, 0, + 56, 2, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 53, 2, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 52, 2, 0, 0, 3, 0, 1, 0, + 64, 2, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 2, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 60, 2, 0, 0, 3, 0, 1, 0, + 88, 2, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 85, 2, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 84, 2, 0, 0, 3, 0, 1, 0, + 112, 2, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 15, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 2, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 2, 0, 0, 3, 0, 1, 0, + 120, 2, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 16, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 2, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 2, 0, 0, 3, 0, 1, 0, + 128, 2, 0, 0, 2, 0, 1, 0, + 101, 110, 97, 98, 108, 101, 100, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 97, 115, 68, 69, 80, 82, 69, + 67, 65, 84, 69, 68, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 114, 97, 107, 101, 68, 69, 80, + 82, 69, 67, 65, 84, 69, 68, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 105, 110, 103, + 84, 111, 114, 113, 117, 101, 68, 69, + 80, 82, 69, 67, 65, 84, 69, 68, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 114, 117, 105, 115, 101, 67, 111, + 110, 116, 114, 111, 108, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 211, 168, 11, 14, 110, 56, 14, 178, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 117, 100, 67, 111, 110, 116, 114, + 111, 108, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 56, 58, 176, 78, 124, 200, 149, 216, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 116, 117, 97, 116, 111, 114, + 115, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 40, 40, 67, 25, 169, 117, 114, 233, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 116, 105, 118, 101, 68, 69, + 80, 82, 69, 67, 65, 84, 69, 68, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 111, 108, 108, 68, 69, 80, 82, + 69, 67, 65, 84, 69, 68, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 105, 116, 99, 104, 68, 69, 80, + 82, 69, 67, 65, 84, 69, 68, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 116, 117, 97, 116, 111, 114, + 115, 79, 117, 116, 112, 117, 116, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 40, 40, 67, 25, 169, 117, 114, 233, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 116, 65, 99, 116, 105, 118, + 101, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 110, 103, 65, 99, 116, 105, + 118, 101, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 114, 105, 101, 110, 116, 97, 116, + 105, 111, 110, 78, 69, 68, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 110, 103, 117, 108, 97, 114, 86, + 101, 108, 111, 99, 105, 116, 121, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 102, 116, 66, 108, 105, 110, + 107, 101, 114, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 105, 103, 104, 116, 66, 108, 105, + 110, 107, 101, 114, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_f78829049ab814af = b_f78829049ab814af.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_f78829049ab814af[] = { + &s_b20e386e0e0ba8d3, + &s_d895c87c4eb03a38, + &s_e97275a919432828, +}; +static const uint16_t m_f78829049ab814af[] = {7, 6, 10, 14, 2, 4, 0, 1, 5, 11, 15, 12, 13, 9, 16, 8, 3}; +static const uint16_t i_f78829049ab814af[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16}; +const ::capnp::_::RawSchema s_f78829049ab814af = { + 0xf78829049ab814af, b_f78829049ab814af.words, 311, d_f78829049ab814af, m_f78829049ab814af, + 3, 17, i_f78829049ab814af, nullptr, nullptr, { &s_f78829049ab814af, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<164> b_e97275a919432828 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 40, 40, 67, 25, 169, 117, 114, 233, + 21, 0, 0, 0, 1, 0, 5, 0, + 175, 20, 184, 154, 4, 41, 136, 247, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 250, 0, 0, 0, + 33, 0, 0, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 0, 0, 0, 255, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 46, 99, 97, 112, 110, + 112, 58, 67, 97, 114, 67, 111, 110, + 116, 114, 111, 108, 46, 65, 99, 116, + 117, 97, 116, 111, 114, 115, 0, 0, + 4, 0, 0, 0, 1, 0, 1, 0, + 130, 130, 144, 125, 145, 58, 15, 228, + 1, 0, 0, 0, 138, 0, 0, 0, + 76, 111, 110, 103, 67, 111, 110, 116, + 114, 111, 108, 83, 116, 97, 116, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 0, 0, 0, 3, 0, 1, 0, + 244, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 236, 0, 0, 0, 3, 0, 1, 0, + 248, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 245, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 0, 0, 0, 3, 0, 1, 0, + 252, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 249, 0, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 252, 0, 0, 0, 3, 0, 1, 0, + 8, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 1, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 1, 0, 0, 3, 0, 1, 0, + 12, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 1, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 1, 0, 0, 3, 0, 1, 0, + 24, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 1, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 1, 0, 0, 3, 0, 1, 0, + 28, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 1, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 24, 1, 0, 0, 3, 0, 1, 0, + 36, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 1, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 1, 0, 0, 3, 0, 1, 0, + 44, 1, 0, 0, 2, 0, 1, 0, + 103, 97, 115, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 114, 97, 107, 101, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 105, 110, 103, + 65, 110, 103, 108, 101, 68, 101, 103, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 99, 101, 108, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 110, 103, 67, 111, 110, 116, + 114, 111, 108, 83, 116, 97, 116, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 130, 130, 144, 125, 145, 58, 15, 228, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 112, 101, 101, 100, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 114, 118, 97, 116, 117, 114, + 101, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 79, 117, 116, + 112, 117, 116, 67, 97, 110, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e97275a919432828 = b_e97275a919432828.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_e97275a919432828[] = { + &s_e40f3a917d908282, +}; +static const uint16_t m_e97275a919432828[] = {4, 1, 7, 0, 5, 6, 2, 8, 3}; +static const uint16_t i_e97275a919432828[] = {0, 1, 2, 3, 4, 5, 6, 7, 8}; +const ::capnp::_::RawSchema s_e97275a919432828 = { + 0xe97275a919432828, b_e97275a919432828.words, 164, d_e97275a919432828, m_e97275a919432828, + 1, 9, i_e97275a919432828, nullptr, nullptr, { &s_e97275a919432828, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<38> b_e40f3a917d908282 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 130, 130, 144, 125, 145, 58, 15, 228, + 31, 0, 0, 0, 2, 0, 0, 0, + 40, 40, 67, 25, 169, 117, 114, 233, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 130, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 103, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 46, 99, 97, 112, 110, + 112, 58, 67, 97, 114, 67, 111, 110, + 116, 114, 111, 108, 46, 65, 99, 116, + 117, 97, 116, 111, 114, 115, 46, 76, + 111, 110, 103, 67, 111, 110, 116, 114, + 111, 108, 83, 116, 97, 116, 101, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 102, 102, 0, 0, 0, 0, 0, + 112, 105, 100, 0, 0, 0, 0, 0, + 115, 116, 111, 112, 112, 105, 110, 103, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 114, 116, 105, 110, 103, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e40f3a917d908282 = b_e40f3a917d908282.words; +#if !CAPNP_LITE +static const uint16_t m_e40f3a917d908282[] = {0, 1, 3, 2}; +const ::capnp::_::RawSchema s_e40f3a917d908282 = { + 0xe40f3a917d908282, b_e40f3a917d908282.words, 38, nullptr, m_e40f3a917d908282, + 0, 4, nullptr, nullptr, nullptr, { &s_e40f3a917d908282, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(LongControlState_e40f3a917d908282, e40f3a917d908282); +static const ::capnp::_::AlignedData<99> b_b20e386e0e0ba8d3 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 211, 168, 11, 14, 110, 56, 14, 178, + 21, 0, 0, 0, 1, 0, 2, 0, + 175, 20, 184, 154, 4, 41, 136, 247, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 26, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 31, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 46, 99, 97, 112, 110, + 112, 58, 67, 97, 114, 67, 111, 110, + 116, 114, 111, 108, 46, 67, 114, 117, + 105, 115, 101, 67, 111, 110, 116, 114, + 111, 108, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 20, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 0, 0, 0, 3, 0, 1, 0, + 132, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 129, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 0, 0, 0, 3, 0, 1, 0, + 136, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 0, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 136, 0, 0, 0, 3, 0, 1, 0, + 148, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 145, 0, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 0, 0, 0, 3, 0, 1, 0, + 160, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 157, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 156, 0, 0, 0, 3, 0, 1, 0, + 168, 0, 0, 0, 2, 0, 1, 0, + 99, 97, 110, 99, 101, 108, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 101, 115, 117, 109, 101, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 112, 101, 101, 100, 79, 118, 101, + 114, 114, 105, 100, 101, 68, 69, 80, + 82, 69, 67, 65, 84, 69, 68, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 99, 101, 108, 79, 118, 101, + 114, 114, 105, 100, 101, 68, 69, 80, + 82, 69, 67, 65, 84, 69, 68, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 118, 101, 114, 114, 105, 100, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_b20e386e0e0ba8d3 = b_b20e386e0e0ba8d3.words; +#if !CAPNP_LITE +static const uint16_t m_b20e386e0e0ba8d3[] = {3, 0, 4, 1, 2}; +static const uint16_t i_b20e386e0e0ba8d3[] = {0, 1, 2, 3, 4}; +const ::capnp::_::RawSchema s_b20e386e0e0ba8d3 = { + 0xb20e386e0e0ba8d3, b_b20e386e0e0ba8d3.words, 99, nullptr, m_b20e386e0e0ba8d3, + 0, 5, i_b20e386e0e0ba8d3, nullptr, nullptr, { &s_b20e386e0e0ba8d3, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<203> b_d895c87c4eb03a38 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 56, 58, 176, 78, 124, 200, 149, 216, + 21, 0, 0, 0, 1, 0, 2, 0, + 175, 20, 184, 154, 4, 41, 136, 247, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 2, 1, 0, 0, + 33, 0, 0, 0, 39, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 0, 0, 0, 111, 2, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 46, 99, 97, 112, 110, + 112, 58, 67, 97, 114, 67, 111, 110, + 116, 114, 111, 108, 46, 72, 85, 68, + 67, 111, 110, 116, 114, 111, 108, 0, + 8, 0, 0, 0, 1, 0, 1, 0, + 212, 23, 110, 97, 132, 142, 215, 144, + 9, 0, 0, 0, 98, 0, 0, 0, + 158, 51, 78, 149, 108, 226, 165, 245, + 9, 0, 0, 0, 106, 0, 0, 0, + 86, 105, 115, 117, 97, 108, 65, 108, + 101, 114, 116, 0, 0, 0, 0, 0, + 65, 117, 100, 105, 98, 108, 101, 65, + 108, 101, 114, 116, 0, 0, 0, 0, + 44, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 1, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 1, 0, 0, 3, 0, 1, 0, + 48, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 1, 0, 0, 3, 0, 1, 0, + 56, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 53, 1, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 52, 1, 0, 0, 3, 0, 1, 0, + 64, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 1, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 60, 1, 0, 0, 3, 0, 1, 0, + 72, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 1, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 1, 0, 0, 3, 0, 1, 0, + 80, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 1, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 1, 0, 0, 3, 0, 1, 0, + 88, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 85, 1, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 88, 1, 0, 0, 3, 0, 1, 0, + 100, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 1, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 1, 0, 0, 3, 0, 1, 0, + 108, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 1, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 1, 0, 0, 3, 0, 1, 0, + 116, 1, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 1, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 1, 0, 0, 3, 0, 1, 0, + 124, 1, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 1, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 1, 0, 0, 3, 0, 1, 0, + 132, 1, 0, 0, 2, 0, 1, 0, + 115, 112, 101, 101, 100, 86, 105, 115, + 105, 98, 108, 101, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 101, 116, 83, 112, 101, 101, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 110, 101, 115, 86, 105, 115, + 105, 98, 108, 101, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 97, 100, 86, 105, 115, 105, + 98, 108, 101, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 105, 115, 117, 97, 108, 65, 108, + 101, 114, 116, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 212, 23, 110, 97, 132, 142, 215, 144, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 117, 100, 105, 98, 108, 101, 65, + 108, 101, 114, 116, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 158, 51, 78, 149, 108, 226, 165, 245, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 105, 103, 104, 116, 76, 97, 110, + 101, 86, 105, 115, 105, 98, 108, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 102, 116, 76, 97, 110, 101, + 86, 105, 115, 105, 98, 108, 101, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 105, 103, 104, 116, 76, 97, 110, + 101, 68, 101, 112, 97, 114, 116, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 102, 116, 76, 97, 110, 101, + 68, 101, 112, 97, 114, 116, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 97, 100, 86, 101, 108, 111, + 99, 105, 116, 121, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_d895c87c4eb03a38 = b_d895c87c4eb03a38.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_d895c87c4eb03a38[] = { + &s_90d78e84616e17d4, + &s_f5a5e26c954e339e, +}; +static const uint16_t m_d895c87c4eb03a38[] = {5, 2, 10, 3, 9, 7, 8, 6, 1, 0, 4}; +static const uint16_t i_d895c87c4eb03a38[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10}; +const ::capnp::_::RawSchema s_d895c87c4eb03a38 = { + 0xd895c87c4eb03a38, b_d895c87c4eb03a38.words, 203, d_d895c87c4eb03a38, m_d895c87c4eb03a38, + 2, 11, i_d895c87c4eb03a38, nullptr, nullptr, { &s_d895c87c4eb03a38, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<58> b_90d78e84616e17d4 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 212, 23, 110, 97, 132, 142, 215, 144, + 32, 0, 0, 0, 2, 0, 0, 0, + 56, 58, 176, 78, 124, 200, 149, 216, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 98, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 199, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 46, 99, 97, 112, 110, + 112, 58, 67, 97, 114, 67, 111, 110, + 116, 114, 111, 108, 46, 72, 85, 68, + 67, 111, 110, 116, 114, 111, 108, 46, + 86, 105, 115, 117, 97, 108, 65, 108, + 101, 114, 116, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 32, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 89, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 81, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 65, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 61, 0, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 61, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 57, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 111, 110, 101, 0, 0, 0, 0, + 102, 99, 119, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 82, 101, 113, + 117, 105, 114, 101, 100, 0, 0, 0, + 98, 114, 97, 107, 101, 80, 114, 101, + 115, 115, 101, 100, 0, 0, 0, 0, + 119, 114, 111, 110, 103, 71, 101, 97, + 114, 0, 0, 0, 0, 0, 0, 0, + 115, 101, 97, 116, 98, 101, 108, 116, + 85, 110, 98, 117, 99, 107, 108, 101, + 100, 0, 0, 0, 0, 0, 0, 0, + 115, 112, 101, 101, 100, 84, 111, 111, + 72, 105, 103, 104, 0, 0, 0, 0, + 108, 100, 119, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_90d78e84616e17d4 = b_90d78e84616e17d4.words; +#if !CAPNP_LITE +static const uint16_t m_90d78e84616e17d4[] = {3, 1, 7, 0, 5, 6, 2, 4}; +const ::capnp::_::RawSchema s_90d78e84616e17d4 = { + 0x90d78e84616e17d4, b_90d78e84616e17d4.words, 58, nullptr, m_90d78e84616e17d4, + 0, 8, nullptr, nullptr, nullptr, { &s_90d78e84616e17d4, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(VisualAlert_90d78e84616e17d4, 90d78e84616e17d4); +static const ::capnp::_::AlignedData<91> b_f5a5e26c954e339e = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 158, 51, 78, 149, 108, 226, 165, 245, + 32, 0, 0, 0, 2, 0, 0, 0, + 56, 58, 176, 78, 124, 200, 149, 216, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 106, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 135, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 46, 99, 97, 112, 110, + 112, 58, 67, 97, 114, 67, 111, 110, + 116, 114, 111, 108, 46, 72, 85, 68, + 67, 111, 110, 116, 114, 111, 108, 46, + 65, 117, 100, 105, 98, 108, 101, 65, + 108, 101, 114, 116, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 64, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 177, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 169, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 165, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 157, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 153, 0, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 153, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 145, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 141, 0, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 141, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 133, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 125, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 117, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 109, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 101, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 93, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 111, 110, 101, 0, 0, 0, 0, + 101, 110, 103, 97, 103, 101, 0, 0, + 100, 105, 115, 101, 110, 103, 97, 103, + 101, 0, 0, 0, 0, 0, 0, 0, + 114, 101, 102, 117, 115, 101, 0, 0, + 119, 97, 114, 110, 105, 110, 103, 83, + 111, 102, 116, 0, 0, 0, 0, 0, + 119, 97, 114, 110, 105, 110, 103, 73, + 109, 109, 101, 100, 105, 97, 116, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 114, 111, 109, 112, 116, 0, 0, + 112, 114, 111, 109, 112, 116, 82, 101, + 112, 101, 97, 116, 0, 0, 0, 0, + 112, 114, 111, 109, 112, 116, 68, 105, + 115, 116, 114, 97, 99, 116, 101, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 110, 103, 114, 121, 0, 0, 0, + 102, 97, 114, 116, 0, 0, 0, 0, + 102, 105, 114, 101, 102, 111, 120, 0, + 110, 101, 115, 115, 105, 101, 0, 0, + 110, 111, 105, 99, 101, 0, 0, 0, + 117, 119, 117, 0, 0, 0, 0, 0, + 103, 111, 97, 116, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_f5a5e26c954e339e = b_f5a5e26c954e339e.words; +#if !CAPNP_LITE +static const uint16_t m_f5a5e26c954e339e[] = {9, 2, 1, 10, 11, 15, 12, 13, 0, 6, 8, 7, 3, 14, 5, 4}; +const ::capnp::_::RawSchema s_f5a5e26c954e339e = { + 0xf5a5e26c954e339e, b_f5a5e26c954e339e.words, 91, nullptr, m_f5a5e26c954e339e, + 0, 16, nullptr, nullptr, nullptr, { &s_f5a5e26c954e339e, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(AudibleAlert_f5a5e26c954e339e, f5a5e26c954e339e); +static const ::capnp::_::AlignedData<1284> b_8c69372490aaa9da = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 218, 169, 170, 144, 36, 55, 105, 140, + 10, 0, 0, 0, 1, 0, 17, 0, + 141, 139, 175, 8, 231, 241, 42, 142, + 14, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 162, 0, 0, 0, + 29, 0, 0, 0, 231, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 1, 0, 0, 143, 15, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 46, 99, 97, 112, 110, + 112, 58, 67, 97, 114, 80, 97, 114, + 97, 109, 115, 0, 0, 0, 0, 0, + 56, 0, 0, 0, 1, 0, 1, 0, + 201, 176, 86, 96, 156, 52, 54, 232, + 105, 0, 0, 0, 106, 0, 0, 0, + 163, 221, 137, 28, 59, 178, 129, 181, + 105, 0, 0, 0, 114, 0, 0, 0, + 46, 76, 209, 203, 63, 114, 34, 150, + 105, 0, 0, 0, 138, 0, 0, 0, + 29, 204, 78, 128, 14, 110, 54, 128, + 109, 0, 0, 0, 162, 0, 0, 0, + 142, 155, 62, 48, 252, 206, 66, 195, + 113, 0, 0, 0, 178, 0, 0, 0, + 179, 51, 85, 4, 46, 71, 52, 163, + 117, 0, 0, 0, 146, 0, 0, 0, + 18, 106, 97, 40, 63, 30, 21, 157, + 121, 0, 0, 0, 138, 0, 0, 0, + 81, 244, 218, 30, 91, 30, 85, 149, + 125, 0, 0, 0, 98, 0, 0, 0, + 127, 247, 222, 226, 43, 81, 97, 214, + 125, 0, 0, 0, 138, 0, 0, 0, + 236, 192, 191, 20, 235, 46, 22, 143, + 129, 0, 0, 0, 138, 0, 0, 0, + 206, 89, 147, 12, 24, 86, 43, 150, + 133, 0, 0, 0, 50, 0, 0, 0, + 145, 214, 209, 89, 183, 155, 17, 247, + 129, 0, 0, 0, 34, 0, 0, 0, + 206, 64, 220, 216, 35, 85, 217, 159, + 125, 0, 0, 0, 146, 0, 0, 0, + 81, 60, 131, 42, 104, 227, 153, 255, + 129, 0, 0, 0, 130, 0, 0, 0, + 83, 97, 102, 101, 116, 121, 67, 111, + 110, 102, 105, 103, 0, 0, 0, 0, + 76, 97, 116, 101, 114, 97, 108, 80, + 97, 114, 97, 109, 115, 0, 0, 0, + 76, 97, 116, 101, 114, 97, 108, 80, + 73, 68, 84, 117, 110, 105, 110, 103, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 97, 116, 101, 114, 97, 108, 84, + 111, 114, 113, 117, 101, 84, 117, 110, + 105, 110, 103, 0, 0, 0, 0, 0, + 76, 111, 110, 103, 105, 116, 117, 100, + 105, 110, 97, 108, 80, 73, 68, 84, + 117, 110, 105, 110, 103, 0, 0, 0, + 76, 97, 116, 101, 114, 97, 108, 73, + 78, 68, 73, 84, 117, 110, 105, 110, + 103, 0, 0, 0, 0, 0, 0, 0, + 76, 97, 116, 101, 114, 97, 108, 76, + 81, 82, 84, 117, 110, 105, 110, 103, + 0, 0, 0, 0, 0, 0, 0, 0, + 83, 97, 102, 101, 116, 121, 77, 111, + 100, 101, 108, 0, 0, 0, 0, 0, + 83, 116, 101, 101, 114, 67, 111, 110, + 116, 114, 111, 108, 84, 121, 112, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 84, 114, 97, 110, 115, 109, 105, 115, + 115, 105, 111, 110, 84, 121, 112, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 67, 97, 114, 70, 119, 0, 0, 0, + 69, 99, 117, 0, 0, 0, 0, 0, + 70, 105, 110, 103, 101, 114, 112, 114, + 105, 110, 116, 83, 111, 117, 114, 99, + 101, 0, 0, 0, 0, 0, 0, 0, + 78, 101, 116, 119, 111, 114, 107, 76, + 111, 99, 97, 116, 105, 111, 110, 0, + 28, 1, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 7, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 7, 0, 0, 3, 0, 1, 0, + 188, 7, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 7, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 7, 0, 0, 3, 0, 1, 0, + 196, 7, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 7, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 7, 0, 0, 3, 0, 1, 0, + 208, 7, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 7, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 7, 0, 0, 3, 0, 1, 0, + 216, 7, 0, 0, 2, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 7, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 7, 0, 0, 3, 0, 1, 0, + 228, 7, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 225, 7, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 224, 7, 0, 0, 3, 0, 1, 0, + 236, 7, 0, 0, 2, 0, 1, 0, + 53, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 233, 7, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 236, 7, 0, 0, 3, 0, 1, 0, + 248, 7, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 245, 7, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 244, 7, 0, 0, 3, 0, 1, 0, + 0, 8, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 253, 7, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 252, 7, 0, 0, 3, 0, 1, 0, + 8, 8, 0, 0, 2, 0, 1, 0, + 58, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 8, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 8, 0, 0, 3, 0, 1, 0, + 20, 8, 0, 0, 2, 0, 1, 0, + 57, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 8, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 8, 0, 0, 3, 0, 1, 0, + 32, 8, 0, 0, 2, 0, 1, 0, + 63, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 8, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 8, 0, 0, 3, 0, 1, 0, + 60, 8, 0, 0, 2, 0, 1, 0, + 64, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 57, 8, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 60, 8, 0, 0, 3, 0, 1, 0, + 88, 8, 0, 0, 2, 0, 1, 0, + 65, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 85, 8, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 88, 8, 0, 0, 3, 0, 1, 0, + 116, 8, 0, 0, 2, 0, 1, 0, + 66, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 8, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 8, 0, 0, 3, 0, 1, 0, + 144, 8, 0, 0, 2, 0, 1, 0, + 67, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 15, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 8, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 144, 8, 0, 0, 3, 0, 1, 0, + 172, 8, 0, 0, 2, 0, 1, 0, + 68, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 16, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 169, 8, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 172, 8, 0, 0, 3, 0, 1, 0, + 200, 8, 0, 0, 2, 0, 1, 0, + 16, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 17, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 8, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 192, 8, 0, 0, 3, 0, 1, 0, + 204, 8, 0, 0, 2, 0, 1, 0, + 17, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 8, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 200, 8, 0, 0, 3, 0, 1, 0, + 212, 8, 0, 0, 2, 0, 1, 0, + 18, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 19, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 8, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 8, 0, 0, 3, 0, 1, 0, + 220, 8, 0, 0, 2, 0, 1, 0, + 19, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 20, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 217, 8, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 8, 0, 0, 3, 0, 1, 0, + 228, 8, 0, 0, 2, 0, 1, 0, + 20, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 21, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 225, 8, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 224, 8, 0, 0, 3, 0, 1, 0, + 236, 8, 0, 0, 2, 0, 1, 0, + 21, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 22, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 233, 8, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 236, 8, 0, 0, 3, 0, 1, 0, + 248, 8, 0, 0, 2, 0, 1, 0, + 23, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 245, 8, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 248, 8, 0, 0, 3, 0, 1, 0, + 4, 9, 0, 0, 2, 0, 1, 0, + 24, 0, 0, 0, 11, 0, 0, 0, + 0, 0, 1, 0, 24, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 9, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 9, 0, 0, 3, 0, 1, 0, + 16, 9, 0, 0, 2, 0, 1, 0, + 25, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 25, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 9, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 9, 0, 0, 3, 0, 1, 0, + 28, 9, 0, 0, 2, 0, 1, 0, + 27, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 104, 149, 51, 53, 10, 88, 252, 147, + 25, 9, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 28, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 28, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 9, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 9, 0, 0, 3, 0, 1, 0, + 16, 9, 0, 0, 2, 0, 1, 0, + 30, 0, 0, 0, 12, 0, 0, 0, + 0, 0, 1, 0, 29, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 9, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 9, 0, 0, 3, 0, 1, 0, + 24, 9, 0, 0, 2, 0, 1, 0, + 69, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 30, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 9, 0, 0, 234, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 28, 9, 0, 0, 3, 0, 1, 0, + 40, 9, 0, 0, 2, 0, 1, 0, + 32, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 31, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 9, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 9, 0, 0, 3, 0, 1, 0, + 48, 9, 0, 0, 2, 0, 1, 0, + 37, 0, 0, 0, 13, 0, 0, 0, + 0, 0, 1, 0, 32, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 9, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 9, 0, 0, 3, 0, 1, 0, + 56, 9, 0, 0, 2, 0, 1, 0, + 54, 0, 0, 0, 14, 0, 0, 0, + 0, 0, 1, 0, 33, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 53, 9, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 56, 9, 0, 0, 3, 0, 1, 0, + 68, 9, 0, 0, 2, 0, 1, 0, + 33, 0, 0, 0, 30, 0, 0, 0, + 0, 0, 1, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 65, 9, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 9, 0, 0, 3, 0, 1, 0, + 80, 9, 0, 0, 2, 0, 1, 0, + 34, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 35, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 9, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 80, 9, 0, 0, 3, 0, 1, 0, + 92, 9, 0, 0, 2, 0, 1, 0, + 39, 0, 0, 0, 16, 0, 0, 0, + 0, 0, 1, 0, 36, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 89, 9, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 9, 0, 0, 3, 0, 1, 0, + 104, 9, 0, 0, 2, 0, 1, 0, + 42, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 37, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 9, 0, 0, 234, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 9, 0, 0, 3, 0, 1, 0, + 120, 9, 0, 0, 2, 0, 1, 0, + 43, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 38, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 9, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 9, 0, 0, 3, 0, 1, 0, + 124, 9, 0, 0, 2, 0, 1, 0, + 55, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 39, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 9, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 9, 0, 0, 3, 0, 1, 0, + 136, 9, 0, 0, 2, 0, 1, 0, + 44, 0, 0, 0, 11, 0, 0, 0, + 0, 0, 1, 0, 41, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 9, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 132, 9, 0, 0, 3, 0, 1, 0, + 144, 9, 0, 0, 2, 0, 1, 0, + 59, 0, 0, 0, 31, 0, 0, 0, + 0, 0, 1, 0, 42, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 141, 9, 0, 0, 234, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 9, 0, 0, 3, 0, 1, 0, + 160, 9, 0, 0, 2, 0, 1, 0, + 46, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 1, 0, 43, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 157, 9, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 160, 9, 0, 0, 3, 0, 1, 0, + 172, 9, 0, 0, 2, 0, 1, 0, + 47, 0, 0, 0, 11, 0, 0, 0, + 0, 0, 1, 0, 44, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 169, 9, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 164, 9, 0, 0, 3, 0, 1, 0, + 192, 9, 0, 0, 2, 0, 1, 0, + 48, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 1, 0, 45, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 189, 9, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 9, 0, 0, 3, 0, 1, 0, + 200, 9, 0, 0, 2, 0, 1, 0, + 61, 0, 0, 0, 12, 0, 0, 0, + 0, 0, 1, 0, 46, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 9, 0, 0, 218, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 9, 0, 0, 3, 0, 1, 0, + 216, 9, 0, 0, 2, 0, 1, 0, + 29, 0, 0, 0, 19, 0, 0, 0, + 0, 0, 1, 0, 47, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 9, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 212, 9, 0, 0, 3, 0, 1, 0, + 224, 9, 0, 0, 2, 0, 1, 0, + 26, 0, 0, 0, 12, 0, 0, 0, + 0, 0, 1, 0, 48, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 9, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 220, 9, 0, 0, 3, 0, 1, 0, + 232, 9, 0, 0, 2, 0, 1, 0, + 49, 0, 0, 0, 35, 0, 0, 0, + 0, 0, 1, 0, 49, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 9, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 9, 0, 0, 3, 0, 1, 0, + 244, 9, 0, 0, 2, 0, 1, 0, + 50, 0, 0, 0, 40, 0, 0, 0, + 0, 0, 1, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 9, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 9, 0, 0, 3, 0, 1, 0, + 252, 9, 0, 0, 2, 0, 1, 0, + 60, 0, 0, 0, 21, 0, 0, 0, + 0, 0, 1, 0, 51, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 249, 9, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 252, 9, 0, 0, 3, 0, 1, 0, + 8, 10, 0, 0, 2, 0, 1, 0, + 36, 0, 0, 0, 22, 0, 0, 0, + 0, 0, 1, 0, 52, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 10, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 10, 0, 0, 3, 0, 1, 0, + 20, 10, 0, 0, 2, 0, 1, 0, + 62, 0, 0, 0, 23, 0, 0, 0, + 0, 0, 1, 0, 53, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 10, 0, 0, 226, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 24, 10, 0, 0, 3, 0, 1, 0, + 36, 10, 0, 0, 2, 0, 1, 0, + 70, 0, 0, 0, 24, 0, 0, 0, + 0, 0, 1, 0, 54, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 10, 0, 0, 242, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 10, 0, 0, 3, 0, 1, 0, + 52, 10, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 13, 0, 0, 0, + 0, 0, 1, 0, 55, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 10, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 52, 10, 0, 0, 3, 0, 1, 0, + 64, 10, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 14, 0, 0, 0, + 0, 0, 1, 0, 56, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 10, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 60, 10, 0, 0, 3, 0, 1, 0, + 72, 10, 0, 0, 2, 0, 1, 0, + 56, 0, 0, 0, 15, 0, 0, 0, + 0, 0, 1, 0, 57, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 10, 0, 0, 202, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 10, 0, 0, 3, 0, 1, 0, + 88, 10, 0, 0, 2, 0, 1, 0, + 41, 0, 0, 0, 25, 0, 0, 0, + 0, 0, 1, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 85, 10, 0, 0, 34, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 10, 0, 0, 3, 0, 1, 0, + 108, 10, 0, 0, 2, 0, 1, 0, + 31, 0, 0, 0, 26, 0, 0, 0, + 0, 0, 1, 0, 59, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 10, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 10, 0, 0, 3, 0, 1, 0, + 116, 10, 0, 0, 2, 0, 1, 0, + 35, 0, 0, 0, 27, 0, 0, 0, + 0, 0, 1, 0, 60, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 10, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 10, 0, 0, 3, 0, 1, 0, + 124, 10, 0, 0, 2, 0, 1, 0, + 40, 0, 0, 0, 28, 0, 0, 0, + 0, 0, 1, 0, 61, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 10, 0, 0, 34, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 132, 10, 0, 0, 3, 0, 1, 0, + 144, 10, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 13, 0, 0, 0, + 0, 0, 1, 0, 62, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 10, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 140, 10, 0, 0, 3, 0, 1, 0, + 168, 10, 0, 0, 2, 0, 1, 0, + 51, 0, 0, 0, 29, 0, 0, 0, + 0, 0, 1, 0, 63, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 165, 10, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 10, 0, 0, 3, 0, 1, 0, + 180, 10, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 30, 0, 0, 0, + 0, 0, 1, 0, 64, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 10, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 172, 10, 0, 0, 3, 0, 1, 0, + 184, 10, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 41, 0, 0, 0, + 0, 0, 1, 0, 65, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 10, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 10, 0, 0, 3, 0, 1, 0, + 196, 10, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 224, 3, 0, 0, + 0, 0, 1, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 10, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 10, 0, 0, 3, 0, 1, 0, + 200, 10, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 32, 0, 0, 0, + 0, 0, 1, 0, 68, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 10, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 10, 0, 0, 3, 0, 1, 0, + 208, 10, 0, 0, 2, 0, 1, 0, + 15, 0, 0, 0, 225, 3, 0, 0, + 0, 0, 1, 0, 69, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 10, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 10, 0, 0, 3, 0, 1, 0, + 216, 10, 0, 0, 2, 0, 1, 0, + 38, 0, 0, 0, 226, 3, 0, 0, + 0, 0, 1, 0, 70, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 10, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 212, 10, 0, 0, 3, 0, 1, 0, + 224, 10, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 227, 3, 0, 0, + 0, 0, 1, 0, 71, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 10, 0, 0, 18, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 10, 0, 0, 3, 0, 1, 0, + 244, 10, 0, 0, 2, 0, 1, 0, + 22, 0, 0, 0, 33, 0, 0, 0, + 0, 0, 1, 0, 72, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 10, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 244, 10, 0, 0, 3, 0, 1, 0, + 0, 11, 0, 0, 2, 0, 1, 0, + 45, 0, 0, 0, 228, 3, 0, 0, + 0, 0, 1, 0, 73, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 253, 10, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 248, 10, 0, 0, 3, 0, 1, 0, + 4, 11, 0, 0, 2, 0, 1, 0, + 99, 97, 114, 78, 97, 109, 101, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 70, 105, 110, 103, 101, + 114, 112, 114, 105, 110, 116, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 110, 97, 98, 108, 101, 71, 97, + 115, 73, 110, 116, 101, 114, 99, 101, + 112, 116, 111, 114, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 99, 109, 67, 114, 117, 105, 115, + 101, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 110, 97, 98, 108, 101, 67, 97, + 109, 101, 114, 97, 68, 69, 80, 82, + 69, 67, 65, 84, 69, 68, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 110, 97, 98, 108, 101, 68, 115, + 117, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 110, 97, 98, 108, 101, 65, 112, + 103, 115, 68, 69, 80, 82, 69, 67, + 65, 84, 69, 68, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 105, 110, 69, 110, 97, 98, 108, + 101, 83, 112, 101, 101, 100, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 105, 110, 83, 116, 101, 101, 114, + 83, 112, 101, 101, 100, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 97, 102, 101, 116, 121, 77, 111, + 100, 101, 108, 68, 69, 80, 82, 69, + 67, 65, 84, 69, 68, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 81, 244, 218, 30, 91, 30, 85, 149, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 97, 102, 101, 116, 121, 80, 97, + 114, 97, 109, 68, 69, 80, 82, 69, + 67, 65, 84, 69, 68, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 77, 97, 120, + 66, 80, 68, 69, 80, 82, 69, 67, + 65, 84, 69, 68, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 77, 97, 120, + 86, 68, 69, 80, 82, 69, 67, 65, + 84, 69, 68, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 97, 115, 77, 97, 120, 66, 80, + 68, 69, 80, 82, 69, 67, 65, 84, + 69, 68, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 97, 115, 77, 97, 120, 86, 68, + 69, 80, 82, 69, 67, 65, 84, 69, + 68, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 114, 97, 107, 101, 77, 97, 120, + 66, 80, 68, 69, 80, 82, 69, 67, + 65, 84, 69, 68, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 114, 97, 107, 101, 77, 97, 120, + 86, 68, 69, 80, 82, 69, 67, 65, + 84, 69, 68, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 97, 115, 115, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 119, 104, 101, 101, 108, 98, 97, 115, + 101, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 101, 110, 116, 101, 114, 84, 111, + 70, 114, 111, 110, 116, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 82, 97, 116, + 105, 111, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 82, 97, 116, + 105, 111, 82, 101, 97, 114, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 111, 116, 97, 116, 105, 111, 110, + 97, 108, 73, 110, 101, 114, 116, 105, + 97, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 114, 101, 83, 116, 105, 102, + 102, 110, 101, 115, 115, 70, 114, 111, + 110, 116, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 114, 101, 83, 116, 105, 102, + 102, 110, 101, 115, 115, 82, 101, 97, + 114, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 110, 103, 105, 116, 117, 100, + 105, 110, 97, 108, 84, 117, 110, 105, + 110, 103, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 142, 155, 62, 48, 252, 206, 66, 195, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 116, 101, 114, 97, 108, 84, + 117, 110, 105, 110, 103, 0, 0, 0, + 115, 116, 101, 101, 114, 76, 105, 109, + 105, 116, 65, 108, 101, 114, 116, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 69, 103, 111, 83, 116, 111, 112, + 112, 105, 110, 103, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 105, 114, 101, 99, 116, 65, 99, + 99, 101, 108, 67, 111, 110, 116, 114, + 111, 108, 68, 69, 80, 82, 69, 67, + 65, 84, 69, 68, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 111, 112, 112, 105, 110, 103, + 67, 111, 110, 116, 114, 111, 108, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 114, 116, 65, 99, 99, + 101, 108, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 82, 97, 116, + 101, 67, 111, 115, 116, 68, 69, 80, + 82, 69, 67, 65, 84, 69, 68, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 67, 111, 110, + 116, 114, 111, 108, 84, 121, 112, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 127, 247, 222, 226, 43, 81, 97, 214, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 97, 100, 97, 114, 85, 110, 97, + 118, 97, 105, 108, 97, 98, 108, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 65, 99, 116, + 117, 97, 116, 111, 114, 68, 101, 108, + 97, 121, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 112, 101, 110, 112, 105, 108, 111, + 116, 76, 111, 110, 103, 105, 116, 117, + 100, 105, 110, 97, 108, 67, 111, 110, + 116, 114, 111, 108, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 86, 105, 110, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 115, 80, 97, 110, 100, 97, 66, + 108, 97, 99, 107, 68, 69, 80, 82, + 69, 67, 65, 84, 69, 68, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 97, 115, 104, 99, 97, 109, 79, + 110, 108, 121, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 97, 102, 101, 116, 121, 77, 111, + 100, 101, 108, 80, 97, 115, 115, 105, + 118, 101, 68, 69, 80, 82, 69, 67, + 65, 84, 69, 68, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 81, 244, 218, 30, 91, 30, 85, 149, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 114, 97, 110, 115, 109, 105, 115, + 115, 105, 111, 110, 84, 121, 112, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 236, 192, 191, 20, 235, 46, 22, 143, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 70, 119, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 206, 89, 147, 12, 24, 86, 43, 150, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 97, 100, 97, 114, 84, 105, 109, + 101, 83, 116, 101, 112, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 205, 204, 76, 61, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 111, 109, 109, 117, 110, 105, 116, + 121, 70, 101, 97, 116, 117, 114, 101, + 68, 69, 80, 82, 69, 67, 65, 84, + 69, 68, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 76, 105, 109, + 105, 116, 84, 105, 109, 101, 114, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 116, 101, 114, 97, 108, 80, + 97, 114, 97, 109, 115, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 163, 221, 137, 28, 59, 178, 129, 181, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 105, 110, 103, 101, 114, 112, 114, + 105, 110, 116, 83, 111, 117, 114, 99, + 101, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 206, 64, 220, 216, 35, 85, 217, 159, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 101, 116, 119, 111, 114, 107, 76, + 111, 99, 97, 116, 105, 111, 110, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 81, 60, 131, 42, 104, 227, 153, 255, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 105, 110, 83, 112, 101, 101, 100, + 67, 97, 110, 68, 69, 80, 82, 69, + 67, 65, 84, 69, 68, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 111, 112, 112, 105, 110, 103, + 68, 101, 99, 101, 108, 82, 97, 116, + 101, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 114, 116, 105, 110, 103, + 65, 99, 99, 101, 108, 82, 97, 116, + 101, 68, 69, 80, 82, 69, 67, 65, + 84, 69, 68, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 97, 120, 83, 116, 101, 101, 114, + 105, 110, 103, 65, 110, 103, 108, 101, + 68, 101, 103, 68, 69, 80, 82, 69, + 67, 65, 84, 69, 68, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 117, 122, 122, 121, 70, 105, 110, + 103, 101, 114, 112, 114, 105, 110, 116, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 110, 97, 98, 108, 101, 66, 115, + 109, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 97, 115, 83, 116, 111, 99, 107, + 67, 97, 109, 101, 114, 97, 68, 69, + 80, 82, 69, 67, 65, 84, 69, 68, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 110, 103, 105, 116, 117, 100, + 105, 110, 97, 108, 65, 99, 116, 117, + 97, 116, 111, 114, 68, 101, 108, 97, + 121, 85, 112, 112, 101, 114, 66, 111, + 117, 110, 100, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 69, 103, 111, 83, 116, 97, 114, + 116, 105, 110, 103, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 111, 112, 65, 99, 99, 101, + 108, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 110, 103, 105, 116, 117, 100, + 105, 110, 97, 108, 65, 99, 116, 117, + 97, 116, 111, 114, 68, 101, 108, 97, + 121, 76, 111, 119, 101, 114, 66, 111, + 117, 110, 100, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 97, 102, 101, 116, 121, 67, 111, + 110, 102, 105, 103, 115, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 201, 176, 86, 96, 156, 52, 54, 232, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 119, 104, 101, 101, 108, 83, 112, 101, + 101, 100, 70, 97, 99, 116, 111, 114, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 108, 97, 103, 115, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 108, 116, 101, 114, 110, 97, 116, + 105, 118, 101, 69, 120, 112, 101, 114, + 105, 101, 110, 99, 101, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 111, 116, 67, 97, 114, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 97, 120, 76, 97, 116, 101, 114, + 97, 108, 65, 99, 99, 101, 108, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 117, 116, 111, 82, 101, 115, 117, + 109, 101, 83, 110, 103, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 114, 116, 105, 110, 103, + 83, 116, 97, 116, 101, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 120, 112, 101, 114, 105, 109, 101, + 110, 116, 97, 108, 76, 111, 110, 103, + 105, 116, 117, 100, 105, 110, 97, 108, + 65, 118, 97, 105, 108, 97, 98, 108, + 101, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 114, 101, 83, 116, 105, 102, + 102, 110, 101, 115, 115, 70, 97, 99, + 116, 111, 114, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 97, 115, 115, 105, 118, 101, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_8c69372490aaa9da = b_8c69372490aaa9da.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_8c69372490aaa9da[] = { + &s_8f162eeb14bfc0ec, + &s_93fc580a35339568, + &s_95551e5b1edaf451, + &s_962b56180c9359ce, + &s_9fd95523d8dc40ce, + &s_b581b23b1c89dda3, + &s_c342cefc303e9b8e, + &s_d661512be2def77f, + &s_e836349c6056b0c9, + &s_ff99e3682a833c51, +}; +static const uint16_t m_8c69372490aaa9da[] = {63, 66, 15, 16, 1, 42, 0, 37, 19, 44, 39, 29, 6, 54, 4, 5, 2, 68, 47, 62, 53, 13, 14, 55, 38, 46, 26, 59, 56, 25, 17, 65, 52, 7, 49, 8, 48, 64, 36, 70, 3, 43, 34, 22, 60, 9, 40, 10, 31, 51, 67, 35, 33, 27, 45, 11, 12, 32, 20, 21, 58, 30, 50, 69, 23, 24, 41, 57, 28, 61, 18}; +static const uint16_t i_8c69372490aaa9da[] = {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, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68, 69, 70}; +const ::capnp::_::RawSchema s_8c69372490aaa9da = { + 0x8c69372490aaa9da, b_8c69372490aaa9da.words, 1284, d_8c69372490aaa9da, m_8c69372490aaa9da, + 10, 71, i_8c69372490aaa9da, nullptr, nullptr, { &s_8c69372490aaa9da, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<85> b_e836349c6056b0c9 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 201, 176, 86, 96, 156, 52, 54, 232, + 20, 0, 0, 0, 1, 0, 2, 0, + 218, 169, 170, 144, 36, 55, 105, 140, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 10, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 231, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 46, 99, 97, 112, 110, + 112, 58, 67, 97, 114, 80, 97, 114, + 97, 109, 115, 46, 83, 97, 102, 101, + 116, 121, 67, 111, 110, 102, 105, 103, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 0, 0, 0, 3, 0, 1, 0, + 108, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 0, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 0, 0, 0, 3, 0, 1, 0, + 120, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 0, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 0, 0, 0, 3, 0, 1, 0, + 132, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 129, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 128, 0, 0, 0, 3, 0, 1, 0, + 140, 0, 0, 0, 2, 0, 1, 0, + 115, 97, 102, 101, 116, 121, 77, 111, + 100, 101, 108, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 81, 244, 218, 30, 91, 30, 85, 149, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 97, 102, 101, 116, 121, 80, 97, + 114, 97, 109, 68, 69, 80, 82, 69, + 67, 65, 84, 69, 68, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 97, 102, 101, 116, 121, 80, 97, + 114, 97, 109, 50, 68, 69, 80, 82, + 69, 67, 65, 84, 69, 68, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 97, 102, 101, 116, 121, 80, 97, + 114, 97, 109, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e836349c6056b0c9 = b_e836349c6056b0c9.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_e836349c6056b0c9[] = { + &s_95551e5b1edaf451, +}; +static const uint16_t m_e836349c6056b0c9[] = {0, 3, 2, 1}; +static const uint16_t i_e836349c6056b0c9[] = {0, 1, 2, 3}; +const ::capnp::_::RawSchema s_e836349c6056b0c9 = { + 0xe836349c6056b0c9, b_e836349c6056b0c9.words, 85, d_e836349c6056b0c9, m_e836349c6056b0c9, + 1, 4, i_e836349c6056b0c9, nullptr, nullptr, { &s_e836349c6056b0c9, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<58> b_b581b23b1c89dda3 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 163, 221, 137, 28, 59, 178, 129, 181, + 20, 0, 0, 0, 1, 0, 0, 0, + 218, 169, 170, 144, 36, 55, 105, 140, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 18, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 46, 99, 97, 112, 110, + 112, 58, 67, 97, 114, 80, 97, 114, + 97, 109, 115, 46, 76, 97, 116, 101, + 114, 97, 108, 80, 97, 114, 97, 109, + 115, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 68, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 65, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 60, 0, 0, 0, 3, 0, 1, 0, + 88, 0, 0, 0, 2, 0, 1, 0, + 116, 111, 114, 113, 117, 101, 66, 80, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 111, 114, 113, 117, 101, 86, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_b581b23b1c89dda3 = b_b581b23b1c89dda3.words; +#if !CAPNP_LITE +static const uint16_t m_b581b23b1c89dda3[] = {0, 1}; +static const uint16_t i_b581b23b1c89dda3[] = {0, 1}; +const ::capnp::_::RawSchema s_b581b23b1c89dda3 = { + 0xb581b23b1c89dda3, b_b581b23b1c89dda3.words, 58, nullptr, m_b581b23b1c89dda3, + 0, 2, i_b581b23b1c89dda3, nullptr, nullptr, { &s_b581b23b1c89dda3, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<110> b_9622723fcbd14c2e = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 46, 76, 209, 203, 63, 114, 34, 150, + 20, 0, 0, 0, 1, 0, 1, 0, + 218, 169, 170, 144, 36, 55, 105, 140, + 4, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 42, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 31, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 46, 99, 97, 112, 110, + 112, 58, 67, 97, 114, 80, 97, 114, + 97, 109, 115, 46, 76, 97, 116, 101, + 114, 97, 108, 80, 73, 68, 84, 117, + 110, 105, 110, 103, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 20, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 0, 0, 0, 3, 0, 1, 0, + 148, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 145, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 140, 0, 0, 0, 3, 0, 1, 0, + 168, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 165, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 160, 0, 0, 0, 3, 0, 1, 0, + 188, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 0, 0, 0, 3, 0, 1, 0, + 208, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 0, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 200, 0, 0, 0, 3, 0, 1, 0, + 212, 0, 0, 0, 2, 0, 1, 0, + 107, 112, 66, 80, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 107, 112, 86, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 107, 105, 66, 80, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 107, 105, 86, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 107, 102, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_9622723fcbd14c2e = b_9622723fcbd14c2e.words; +#if !CAPNP_LITE +static const uint16_t m_9622723fcbd14c2e[] = {4, 2, 3, 0, 1}; +static const uint16_t i_9622723fcbd14c2e[] = {0, 1, 2, 3, 4}; +const ::capnp::_::RawSchema s_9622723fcbd14c2e = { + 0x9622723fcbd14c2e, b_9622723fcbd14c2e.words, 110, nullptr, m_9622723fcbd14c2e, + 0, 5, i_9622723fcbd14c2e, nullptr, nullptr, { &s_9622723fcbd14c2e, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<147> b_80366e0e804ecc1d = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 29, 204, 78, 128, 14, 110, 54, 128, + 20, 0, 0, 0, 1, 0, 4, 0, + 218, 169, 170, 144, 36, 55, 105, 140, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 66, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 199, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 46, 99, 97, 112, 110, + 112, 58, 67, 97, 114, 80, 97, 114, + 97, 109, 115, 46, 76, 97, 116, 101, + 114, 97, 108, 84, 111, 114, 113, 117, + 101, 84, 117, 110, 105, 110, 103, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 32, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 0, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 212, 0, 0, 0, 3, 0, 1, 0, + 224, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 0, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 0, 0, 0, 3, 0, 1, 0, + 228, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 225, 0, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 220, 0, 0, 0, 3, 0, 1, 0, + 232, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 228, 0, 0, 0, 3, 0, 1, 0, + 240, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 0, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 0, 0, 0, 3, 0, 1, 0, + 244, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 0, 0, 0, 202, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 248, 0, 0, 0, 3, 0, 1, 0, + 4, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 1, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 1, 0, 0, 3, 0, 1, 0, + 12, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 1, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 1, 0, 0, 3, 0, 1, 0, + 20, 1, 0, 0, 2, 0, 1, 0, + 117, 115, 101, 83, 116, 101, 101, 114, + 105, 110, 103, 65, 110, 103, 108, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 107, 112, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 107, 105, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 114, 105, 99, 116, 105, 111, 110, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 107, 102, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 105, 110, 103, + 65, 110, 103, 108, 101, 68, 101, 97, + 100, 122, 111, 110, 101, 68, 101, 103, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 116, 65, 99, 99, 101, 108, + 70, 97, 99, 116, 111, 114, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 116, 65, 99, 99, 101, 108, + 79, 102, 102, 115, 101, 116, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_80366e0e804ecc1d = b_80366e0e804ecc1d.words; +#if !CAPNP_LITE +static const uint16_t m_80366e0e804ecc1d[] = {3, 4, 2, 1, 6, 7, 5, 0}; +static const uint16_t i_80366e0e804ecc1d[] = {0, 1, 2, 3, 4, 5, 6, 7}; +const ::capnp::_::RawSchema s_80366e0e804ecc1d = { + 0x80366e0e804ecc1d, b_80366e0e804ecc1d.words, 147, nullptr, m_80366e0e804ecc1d, + 0, 8, i_80366e0e804ecc1d, nullptr, nullptr, { &s_80366e0e804ecc1d, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<151> b_c342cefc303e9b8e = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 142, 155, 62, 48, 252, 206, 66, 195, + 20, 0, 0, 0, 1, 0, 1, 0, + 218, 169, 170, 144, 36, 55, 105, 140, + 6, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 82, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 143, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 46, 99, 97, 112, 110, + 112, 58, 67, 97, 114, 80, 97, 114, + 97, 109, 115, 46, 76, 111, 110, 103, + 105, 116, 117, 100, 105, 110, 97, 108, + 80, 73, 68, 84, 117, 110, 105, 110, + 103, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 28, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 0, 0, 0, 3, 0, 1, 0, + 204, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 0, 0, 0, 3, 0, 1, 0, + 224, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 0, 0, 0, 3, 0, 1, 0, + 244, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 236, 0, 0, 0, 3, 0, 1, 0, + 8, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 1, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 1, 0, 0, 3, 0, 1, 0, + 32, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 1, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 28, 1, 0, 0, 3, 0, 1, 0, + 56, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 53, 1, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 1, 0, 0, 3, 0, 1, 0, + 60, 1, 0, 0, 2, 0, 1, 0, + 107, 112, 66, 80, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 107, 112, 86, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 107, 105, 66, 80, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 107, 105, 86, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 97, 100, 122, 111, 110, 101, + 66, 80, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 97, 100, 122, 111, 110, 101, + 86, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 107, 102, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_c342cefc303e9b8e = b_c342cefc303e9b8e.words; +#if !CAPNP_LITE +static const uint16_t m_c342cefc303e9b8e[] = {4, 5, 6, 2, 3, 0, 1}; +static const uint16_t i_c342cefc303e9b8e[] = {0, 1, 2, 3, 4, 5, 6}; +const ::capnp::_::RawSchema s_c342cefc303e9b8e = { + 0xc342cefc303e9b8e, b_c342cefc303e9b8e.words, 151, nullptr, m_c342cefc303e9b8e, + 0, 7, i_c342cefc303e9b8e, nullptr, nullptr, { &s_c342cefc303e9b8e, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<250> b_a334472e045533b3 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 179, 51, 85, 4, 46, 71, 52, 163, + 20, 0, 0, 0, 1, 0, 2, 0, + 218, 169, 170, 144, 36, 55, 105, 140, + 8, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 50, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 167, 2, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 46, 99, 97, 112, 110, + 112, 58, 67, 97, 114, 80, 97, 114, + 97, 109, 115, 46, 76, 97, 116, 101, + 114, 97, 108, 73, 78, 68, 73, 84, + 117, 110, 105, 110, 103, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 48, 0, 0, 0, 3, 0, 4, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 65, 1, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 1, 0, 0, 3, 0, 1, 0, + 80, 1, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 1, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 80, 1, 0, 0, 3, 0, 1, 0, + 92, 1, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 89, 1, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 1, 0, 0, 3, 0, 1, 0, + 104, 1, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 1, 0, 0, 2, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 1, 0, 0, 3, 0, 1, 0, + 120, 1, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 1, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 1, 0, 0, 3, 0, 1, 0, + 144, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 1, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 140, 1, 0, 0, 3, 0, 1, 0, + 168, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 165, 1, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 164, 1, 0, 0, 3, 0, 1, 0, + 192, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 1, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 1, 0, 0, 3, 0, 1, 0, + 216, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 1, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 212, 1, 0, 0, 3, 0, 1, 0, + 240, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 1, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 236, 1, 0, 0, 3, 0, 1, 0, + 8, 2, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 2, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 2, 0, 0, 3, 0, 1, 0, + 36, 2, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 2, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 2, 0, 0, 3, 0, 1, 0, + 64, 2, 0, 0, 2, 0, 1, 0, + 111, 117, 116, 101, 114, 76, 111, 111, + 112, 71, 97, 105, 110, 68, 69, 80, + 82, 69, 67, 65, 84, 69, 68, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 110, 110, 101, 114, 76, 111, 111, + 112, 71, 97, 105, 110, 68, 69, 80, + 82, 69, 67, 65, 84, 69, 68, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 109, 101, 67, 111, 110, 115, + 116, 97, 110, 116, 68, 69, 80, 82, + 69, 67, 65, 84, 69, 68, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 116, 117, 97, 116, 111, 114, + 69, 102, 102, 101, 99, 116, 105, 118, + 101, 110, 101, 115, 115, 68, 69, 80, + 82, 69, 67, 65, 84, 69, 68, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 117, 116, 101, 114, 76, 111, 111, + 112, 71, 97, 105, 110, 66, 80, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 117, 116, 101, 114, 76, 111, 111, + 112, 71, 97, 105, 110, 86, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 110, 110, 101, 114, 76, 111, 111, + 112, 71, 97, 105, 110, 66, 80, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 110, 110, 101, 114, 76, 111, 111, + 112, 71, 97, 105, 110, 86, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 109, 101, 67, 111, 110, 115, + 116, 97, 110, 116, 66, 80, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 109, 101, 67, 111, 110, 115, + 116, 97, 110, 116, 86, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 116, 117, 97, 116, 111, 114, + 69, 102, 102, 101, 99, 116, 105, 118, + 101, 110, 101, 115, 115, 66, 80, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 116, 117, 97, 116, 111, 114, + 69, 102, 102, 101, 99, 116, 105, 118, + 101, 110, 101, 115, 115, 86, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_a334472e045533b3 = b_a334472e045533b3.words; +#if !CAPNP_LITE +static const uint16_t m_a334472e045533b3[] = {10, 3, 11, 6, 1, 7, 4, 0, 5, 8, 2, 9}; +static const uint16_t i_a334472e045533b3[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11}; +const ::capnp::_::RawSchema s_a334472e045533b3 = { + 0xa334472e045533b3, b_a334472e045533b3.words, 250, nullptr, m_a334472e045533b3, + 0, 12, i_a334472e045533b3, nullptr, nullptr, { &s_a334472e045533b3, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<159> b_9d151e3f28616a12 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 18, 106, 97, 40, 63, 30, 21, 157, + 20, 0, 0, 0, 1, 0, 2, 0, + 218, 169, 170, 144, 36, 55, 105, 140, + 5, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 42, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 199, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 46, 99, 97, 112, 110, + 112, 58, 67, 97, 114, 80, 97, 114, + 97, 109, 115, 46, 76, 97, 116, 101, + 114, 97, 108, 76, 81, 82, 84, 117, + 110, 105, 110, 103, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 32, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 0, 0, 0, 3, 0, 1, 0, + 216, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 0, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 0, 0, 0, 3, 0, 1, 0, + 220, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 217, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 212, 0, 0, 0, 3, 0, 1, 0, + 224, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 0, 0, 0, 3, 0, 1, 0, + 244, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 236, 0, 0, 0, 3, 0, 1, 0, + 8, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 1, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 1, 0, 0, 3, 0, 1, 0, + 28, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 1, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 1, 0, 0, 3, 0, 1, 0, + 48, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 1, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 1, 0, 0, 3, 0, 1, 0, + 68, 1, 0, 0, 2, 0, 1, 0, + 115, 99, 97, 108, 101, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 107, 105, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 99, 71, 97, 105, 110, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 107, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_9d151e3f28616a12 = b_9d151e3f28616a12.words; +#if !CAPNP_LITE +static const uint16_t m_9d151e3f28616a12[] = {3, 4, 5, 2, 6, 1, 7, 0}; +static const uint16_t i_9d151e3f28616a12[] = {0, 1, 2, 3, 4, 5, 6, 7}; +const ::capnp::_::RawSchema s_9d151e3f28616a12 = { + 0x9d151e3f28616a12, b_9d151e3f28616a12.words, 159, nullptr, m_9d151e3f28616a12, + 0, 8, i_9d151e3f28616a12, nullptr, nullptr, { &s_9d151e3f28616a12, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<163> b_95551e5b1edaf451 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 81, 244, 218, 30, 91, 30, 85, 149, + 20, 0, 0, 0, 2, 0, 0, 0, + 218, 169, 170, 144, 36, 55, 105, 140, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 2, 1, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 239, 2, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 46, 99, 97, 112, 110, + 112, 58, 67, 97, 114, 80, 97, 114, + 97, 109, 115, 46, 83, 97, 102, 101, + 116, 121, 77, 111, 100, 101, 108, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 124, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 101, 1, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 97, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 89, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 81, 1, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 73, 1, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 73, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 65, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 61, 1, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 53, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 49, 1, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 41, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 33, 1, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 29, 1, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 21, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 13, 1, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 9, 1, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 0, 0, 0, 0, 0, 0, 0, + 5, 1, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 18, 0, 0, 0, 0, 0, 0, 0, + 1, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 19, 0, 0, 0, 0, 0, 0, 0, + 249, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 0, 0, 0, 0, 0, 0, 0, + 245, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 0, 0, 0, 0, + 241, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 22, 0, 0, 0, 0, 0, 0, 0, + 237, 0, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 23, 0, 0, 0, 0, 0, 0, 0, + 233, 0, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 24, 0, 0, 0, 0, 0, 0, 0, + 229, 0, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 0, 0, 0, 0, + 229, 0, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 26, 0, 0, 0, 0, 0, 0, 0, + 225, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 27, 0, 0, 0, 0, 0, 0, 0, + 217, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 28, 0, 0, 0, 0, 0, 0, 0, + 209, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 0, 0, 0, 0, + 205, 0, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 30, 0, 0, 0, 0, 0, 0, 0, + 205, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 105, 108, 101, 110, 116, 0, 0, + 104, 111, 110, 100, 97, 78, 105, 100, + 101, 99, 0, 0, 0, 0, 0, 0, + 116, 111, 121, 111, 116, 97, 0, 0, + 101, 108, 109, 51, 50, 55, 0, 0, + 103, 109, 0, 0, 0, 0, 0, 0, + 104, 111, 110, 100, 97, 66, 111, 115, + 99, 104, 71, 105, 114, 97, 102, 102, + 101, 0, 0, 0, 0, 0, 0, 0, + 102, 111, 114, 100, 0, 0, 0, 0, + 99, 97, 100, 105, 108, 108, 97, 99, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 121, 117, 110, 100, 97, 105, 0, + 99, 104, 114, 121, 115, 108, 101, 114, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 101, 115, 108, 97, 0, 0, 0, + 115, 117, 98, 97, 114, 117, 0, 0, + 103, 109, 80, 97, 115, 115, 105, 118, + 101, 0, 0, 0, 0, 0, 0, 0, + 109, 97, 122, 100, 97, 0, 0, 0, + 110, 105, 115, 115, 97, 110, 0, 0, + 118, 111, 108, 107, 115, 119, 97, 103, + 101, 110, 0, 0, 0, 0, 0, 0, + 116, 111, 121, 111, 116, 97, 73, 112, + 97, 115, 0, 0, 0, 0, 0, 0, + 97, 108, 108, 79, 117, 116, 112, 117, + 116, 0, 0, 0, 0, 0, 0, 0, + 103, 109, 65, 115, 99, 109, 0, 0, + 110, 111, 79, 117, 116, 112, 117, 116, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 111, 110, 100, 97, 66, 111, 115, + 99, 104, 0, 0, 0, 0, 0, 0, + 118, 111, 108, 107, 115, 119, 97, 103, + 101, 110, 80, 113, 0, 0, 0, 0, + 115, 117, 98, 97, 114, 117, 80, 114, + 101, 103, 108, 111, 98, 97, 108, 0, + 104, 121, 117, 110, 100, 97, 105, 76, + 101, 103, 97, 99, 121, 0, 0, 0, + 104, 121, 117, 110, 100, 97, 105, 67, + 111, 109, 109, 117, 110, 105, 116, 121, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 111, 108, 107, 115, 119, 97, 103, + 101, 110, 77, 108, 98, 0, 0, 0, + 104, 111, 110, 103, 113, 105, 0, 0, + 98, 111, 100, 121, 0, 0, 0, 0, + 104, 121, 117, 110, 100, 97, 105, 67, + 97, 110, 102, 100, 0, 0, 0, 0, + 118, 111, 108, 107, 115, 119, 97, 103, + 101, 110, 77, 113, 98, 69, 118, 111, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 104, 114, 121, 115, 108, 101, 114, + 67, 117, 115, 119, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_95551e5b1edaf451 = b_95551e5b1edaf451.words; +#if !CAPNP_LITE +static const uint16_t m_95551e5b1edaf451[] = {17, 27, 7, 9, 30, 3, 6, 4, 18, 12, 20, 5, 1, 26, 8, 28, 24, 23, 13, 14, 19, 0, 11, 22, 10, 2, 16, 15, 25, 29, 21}; +const ::capnp::_::RawSchema s_95551e5b1edaf451 = { + 0x95551e5b1edaf451, b_95551e5b1edaf451.words, 163, nullptr, m_95551e5b1edaf451, + 0, 31, nullptr, nullptr, nullptr, { &s_95551e5b1edaf451, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(SafetyModel_95551e5b1edaf451, 95551e5b1edaf451); +static const ::capnp::_::AlignedData<33> b_d661512be2def77f = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 127, 247, 222, 226, 43, 81, 97, 214, + 20, 0, 0, 0, 2, 0, 0, 0, + 218, 169, 170, 144, 36, 55, 105, 140, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 42, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 79, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 46, 99, 97, 112, 110, + 112, 58, 67, 97, 114, 80, 97, 114, + 97, 109, 115, 46, 83, 116, 101, 101, + 114, 67, 111, 110, 116, 114, 111, 108, + 84, 121, 112, 101, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 111, 114, 113, 117, 101, 0, 0, + 97, 110, 103, 108, 101, 0, 0, 0, + 99, 117, 114, 118, 97, 116, 117, 114, + 101, 68, 69, 80, 82, 69, 67, 65, + 84, 69, 68, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_d661512be2def77f = b_d661512be2def77f.words; +#if !CAPNP_LITE +static const uint16_t m_d661512be2def77f[] = {1, 2, 0}; +const ::capnp::_::RawSchema s_d661512be2def77f = { + 0xd661512be2def77f, b_d661512be2def77f.words, 33, nullptr, m_d661512be2def77f, + 0, 3, nullptr, nullptr, nullptr, { &s_d661512be2def77f, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(SteerControlType_d661512be2def77f, d661512be2def77f); +static const ::capnp::_::AlignedData<40> b_8f162eeb14bfc0ec = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 236, 192, 191, 20, 235, 46, 22, 143, + 20, 0, 0, 0, 2, 0, 0, 0, + 218, 169, 170, 144, 36, 55, 105, 140, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 42, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 127, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 46, 99, 97, 112, 110, + 112, 58, 67, 97, 114, 80, 97, 114, + 97, 109, 115, 46, 84, 114, 97, 110, + 115, 109, 105, 115, 115, 105, 111, 110, + 84, 121, 112, 101, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 20, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 53, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 110, 107, 110, 111, 119, 110, 0, + 97, 117, 116, 111, 109, 97, 116, 105, + 99, 0, 0, 0, 0, 0, 0, 0, + 109, 97, 110, 117, 97, 108, 0, 0, + 100, 105, 114, 101, 99, 116, 0, 0, + 99, 118, 116, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_8f162eeb14bfc0ec = b_8f162eeb14bfc0ec.words; +#if !CAPNP_LITE +static const uint16_t m_8f162eeb14bfc0ec[] = {1, 4, 3, 2, 0}; +const ::capnp::_::RawSchema s_8f162eeb14bfc0ec = { + 0x8f162eeb14bfc0ec, b_8f162eeb14bfc0ec.words, 40, nullptr, m_8f162eeb14bfc0ec, + 0, 5, nullptr, nullptr, nullptr, { &s_8f162eeb14bfc0ec, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(TransmissionType_8f162eeb14bfc0ec, 8f162eeb14bfc0ec); +static const ::capnp::_::AlignedData<176> b_962b56180c9359ce = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 206, 89, 147, 12, 24, 86, 43, 150, + 20, 0, 0, 0, 1, 0, 2, 0, + 218, 169, 170, 144, 36, 55, 105, 140, + 3, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 210, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 55, 2, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 46, 99, 97, 112, 110, + 112, 58, 67, 97, 114, 80, 97, 114, + 97, 109, 115, 46, 67, 97, 114, 70, + 119, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 40, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 1, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 1, 0, 0, 3, 0, 1, 0, + 16, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 1, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 1, 0, 0, 3, 0, 1, 0, + 24, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 1, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 1, 0, 0, 3, 0, 1, 0, + 28, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 1, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 24, 1, 0, 0, 3, 0, 1, 0, + 36, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 1, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 1, 0, 0, 3, 0, 1, 0, + 44, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 1, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 1, 0, 0, 3, 0, 1, 0, + 64, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 1, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 56, 1, 0, 0, 3, 0, 1, 0, + 68, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 65, 1, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 60, 1, 0, 0, 3, 0, 1, 0, + 72, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 96, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 1, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 1, 0, 0, 3, 0, 1, 0, + 76, 1, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 97, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 1, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 1, 0, 0, 3, 0, 1, 0, + 84, 1, 0, 0, 2, 0, 1, 0, + 101, 99, 117, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 145, 214, 209, 89, 183, 155, 17, 247, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 119, 86, 101, 114, 115, 105, 111, + 110, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 100, 100, 114, 101, 115, 115, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 117, 98, 65, 100, 100, 114, 101, + 115, 115, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 101, 115, 112, 111, 110, 115, 101, + 65, 100, 100, 114, 101, 115, 115, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 101, 113, 117, 101, 115, 116, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 114, 97, 110, 100, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 117, 115, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 103, 105, 110, 103, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 98, 100, 77, 117, 108, 116, 105, + 112, 108, 101, 120, 105, 110, 103, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_962b56180c9359ce = b_962b56180c9359ce.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_962b56180c9359ce[] = { + &s_f7119bb759d1d691, +}; +static const uint16_t m_962b56180c9359ce[] = {2, 6, 7, 0, 1, 8, 9, 5, 4, 3}; +static const uint16_t i_962b56180c9359ce[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9}; +const ::capnp::_::RawSchema s_962b56180c9359ce = { + 0x962b56180c9359ce, b_962b56180c9359ce.words, 176, d_962b56180c9359ce, m_962b56180c9359ce, + 1, 10, i_962b56180c9359ce, nullptr, nullptr, { &s_962b56180c9359ce, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<130> b_f7119bb759d1d691 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 145, 214, 209, 89, 183, 155, 17, 247, + 20, 0, 0, 0, 2, 0, 0, 0, + 218, 169, 170, 144, 36, 55, 105, 140, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 194, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 95, 2, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 46, 99, 97, 112, 110, + 112, 58, 67, 97, 114, 80, 97, 114, + 97, 109, 115, 46, 69, 99, 117, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 100, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 1, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 29, 1, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 21, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 17, 1, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 13, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 5, 1, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 0, 0, 0, 0, + 253, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 0, 0, 0, 0, 0, 0, 0, + 245, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 241, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 237, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 229, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 221, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 213, 0, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 22, 0, 0, 0, 0, 0, 0, 0, + 213, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 23, 0, 0, 0, 0, 0, 0, 0, + 205, 0, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 205, 0, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 205, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 24, 0, 0, 0, 0, 0, 0, 0, + 201, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 193, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 185, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 177, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 169, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 18, 0, 0, 0, 0, 0, 0, 0, + 165, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 19, 0, 0, 0, 0, 0, 0, 0, + 157, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 0, 0, 0, 0, 0, 0, 0, + 153, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 112, 115, 0, 0, 0, 0, 0, + 97, 98, 115, 0, 0, 0, 0, 0, + 102, 119, 100, 82, 97, 100, 97, 114, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 119, 100, 67, 97, 109, 101, 114, + 97, 0, 0, 0, 0, 0, 0, 0, + 101, 110, 103, 105, 110, 101, 0, 0, + 117, 110, 107, 110, 111, 119, 110, 0, + 100, 115, 117, 0, 0, 0, 0, 0, + 112, 97, 114, 107, 105, 110, 103, 65, + 100, 97, 115, 0, 0, 0, 0, 0, + 116, 114, 97, 110, 115, 109, 105, 115, + 115, 105, 111, 110, 0, 0, 0, 0, + 115, 114, 115, 0, 0, 0, 0, 0, + 103, 97, 116, 101, 119, 97, 121, 0, + 104, 117, 100, 0, 0, 0, 0, 0, + 99, 111, 109, 98, 105, 110, 97, 116, + 105, 111, 110, 77, 101, 116, 101, 114, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 115, 97, 0, 0, 0, 0, 0, + 112, 114, 111, 103, 114, 97, 109, 109, + 101, 100, 70, 117, 101, 108, 73, 110, + 106, 101, 99, 116, 105, 111, 110, 0, + 101, 108, 101, 99, 116, 114, 105, 99, + 66, 114, 97, 107, 101, 66, 111, 111, + 115, 116, 101, 114, 0, 0, 0, 0, + 115, 104, 105, 102, 116, 66, 121, 87, + 105, 114, 101, 0, 0, 0, 0, 0, + 100, 101, 98, 117, 103, 0, 0, 0, + 104, 121, 98, 114, 105, 100, 0, 0, + 97, 100, 97, 115, 0, 0, 0, 0, + 104, 118, 97, 99, 0, 0, 0, 0, + 99, 111, 114, 110, 101, 114, 82, 97, + 100, 97, 114, 0, 0, 0, 0, 0, + 101, 112, 98, 0, 0, 0, 0, 0, + 116, 101, 108, 101, 109, 97, 116, 105, + 99, 115, 0, 0, 0, 0, 0, 0, + 98, 111, 100, 121, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_f7119bb759d1d691 = b_f7119bb759d1d691.words; +#if !CAPNP_LITE +static const uint16_t m_f7119bb759d1d691[] = {1, 19, 24, 12, 21, 17, 6, 15, 4, 22, 0, 3, 2, 10, 11, 20, 18, 7, 14, 16, 9, 23, 8, 5, 13}; +const ::capnp::_::RawSchema s_f7119bb759d1d691 = { + 0xf7119bb759d1d691, b_f7119bb759d1d691.words, 130, nullptr, m_f7119bb759d1d691, + 0, 25, nullptr, nullptr, nullptr, { &s_f7119bb759d1d691, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(Ecu_f7119bb759d1d691, f7119bb759d1d691); +static const ::capnp::_::AlignedData<31> b_9fd95523d8dc40ce = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 206, 64, 220, 216, 35, 85, 217, 159, + 20, 0, 0, 0, 2, 0, 0, 0, + 218, 169, 170, 144, 36, 55, 105, 140, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 50, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 79, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 46, 99, 97, 112, 110, + 112, 58, 67, 97, 114, 80, 97, 114, + 97, 109, 115, 46, 70, 105, 110, 103, + 101, 114, 112, 114, 105, 110, 116, 83, + 111, 117, 114, 99, 101, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 110, 0, 0, 0, 0, 0, + 102, 119, 0, 0, 0, 0, 0, 0, + 102, 105, 120, 101, 100, 0, 0, 0, } +}; +::capnp::word const* const bp_9fd95523d8dc40ce = b_9fd95523d8dc40ce.words; +#if !CAPNP_LITE +static const uint16_t m_9fd95523d8dc40ce[] = {0, 2, 1}; +const ::capnp::_::RawSchema s_9fd95523d8dc40ce = { + 0x9fd95523d8dc40ce, b_9fd95523d8dc40ce.words, 31, nullptr, m_9fd95523d8dc40ce, + 0, 3, nullptr, nullptr, nullptr, { &s_9fd95523d8dc40ce, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(FingerprintSource_9fd95523d8dc40ce, 9fd95523d8dc40ce); +static const ::capnp::_::AlignedData<28> b_ff99e3682a833c51 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 81, 60, 131, 42, 104, 227, 153, 255, + 20, 0, 0, 0, 2, 0, 0, 0, + 218, 169, 170, 144, 36, 55, 105, 140, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 34, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 55, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 46, 99, 97, 112, 110, + 112, 58, 67, 97, 114, 80, 97, 114, + 97, 109, 115, 46, 78, 101, 116, 119, + 111, 114, 107, 76, 111, 99, 97, 116, + 105, 111, 110, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 119, 100, 67, 97, 109, 101, 114, + 97, 0, 0, 0, 0, 0, 0, 0, + 103, 97, 116, 101, 119, 97, 121, 0, } +}; +::capnp::word const* const bp_ff99e3682a833c51 = b_ff99e3682a833c51.words; +#if !CAPNP_LITE +static const uint16_t m_ff99e3682a833c51[] = {0, 1}; +const ::capnp::_::RawSchema s_ff99e3682a833c51 = { + 0xff99e3682a833c51, b_ff99e3682a833c51.words, 28, nullptr, m_ff99e3682a833c51, + 0, 2, nullptr, nullptr, nullptr, { &s_ff99e3682a833c51, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(NetworkLocation_ff99e3682a833c51, ff99e3682a833c51); +static const ::capnp::_::AlignedData<80> b_93fc580a35339568 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 104, 149, 51, 53, 10, 88, 252, 147, + 20, 0, 0, 0, 1, 0, 17, 0, + 218, 169, 170, 144, 36, 55, 105, 140, + 14, 0, 7, 0, 1, 0, 4, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 18, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 231, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 46, 99, 97, 112, 110, + 112, 58, 67, 97, 114, 80, 97, 114, + 97, 109, 115, 46, 108, 97, 116, 101, + 114, 97, 108, 84, 117, 110, 105, 110, + 103, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 255, 255, 9, 0, 0, 0, + 0, 0, 1, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 0, 0, 0, 3, 0, 1, 0, + 104, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 254, 255, 9, 0, 0, 0, + 0, 0, 1, 0, 27, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 0, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 0, 0, 0, 3, 0, 1, 0, + 112, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 253, 255, 9, 0, 0, 0, + 0, 0, 1, 0, 40, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 0, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 0, 0, 0, 3, 0, 1, 0, + 120, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 252, 255, 9, 0, 0, 0, + 0, 0, 1, 0, 67, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 0, 0, 0, 3, 0, 1, 0, + 124, 0, 0, 0, 2, 0, 1, 0, + 112, 105, 100, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 46, 76, 209, 203, 63, 114, 34, 150, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 110, 100, 105, 68, 69, 80, 82, + 69, 67, 65, 84, 69, 68, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 179, 51, 85, 4, 46, 71, 52, 163, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 113, 114, 68, 69, 80, 82, 69, + 67, 65, 84, 69, 68, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 18, 106, 97, 40, 63, 30, 21, 157, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 111, 114, 113, 117, 101, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 29, 204, 78, 128, 14, 110, 54, 128, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_93fc580a35339568 = b_93fc580a35339568.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_93fc580a35339568[] = { + &s_80366e0e804ecc1d, + &s_8c69372490aaa9da, + &s_9622723fcbd14c2e, + &s_9d151e3f28616a12, + &s_a334472e045533b3, +}; +static const uint16_t m_93fc580a35339568[] = {1, 2, 0, 3}; +static const uint16_t i_93fc580a35339568[] = {0, 1, 2, 3}; +const ::capnp::_::RawSchema s_93fc580a35339568 = { + 0x93fc580a35339568, b_93fc580a35339568.words, 80, d_93fc580a35339568, m_93fc580a35339568, + 5, 4, i_93fc580a35339568, nullptr, nullptr, { &s_93fc580a35339568, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +} // namespace schemas +} // namespace capnp + +// ======================================================================================= + +namespace cereal { + +// CarEvent +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t CarEvent::_capnpPrivate::dataWordSize; +constexpr uint16_t CarEvent::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind CarEvent::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* CarEvent::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// CarState +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t CarState::_capnpPrivate::dataWordSize; +constexpr uint16_t CarState::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind CarState::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* CarState::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// CarState::WheelSpeeds +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t CarState::WheelSpeeds::_capnpPrivate::dataWordSize; +constexpr uint16_t CarState::WheelSpeeds::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind CarState::WheelSpeeds::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* CarState::WheelSpeeds::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// CarState::CruiseState +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t CarState::CruiseState::_capnpPrivate::dataWordSize; +constexpr uint16_t CarState::CruiseState::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind CarState::CruiseState::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* CarState::CruiseState::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// CarState::ButtonEvent +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t CarState::ButtonEvent::_capnpPrivate::dataWordSize; +constexpr uint16_t CarState::ButtonEvent::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind CarState::ButtonEvent::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* CarState::ButtonEvent::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// RadarData +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t RadarData::_capnpPrivate::dataWordSize; +constexpr uint16_t RadarData::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind RadarData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* RadarData::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// RadarData::RadarPoint +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t RadarData::RadarPoint::_capnpPrivate::dataWordSize; +constexpr uint16_t RadarData::RadarPoint::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind RadarData::RadarPoint::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* RadarData::RadarPoint::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// CarControl +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t CarControl::_capnpPrivate::dataWordSize; +constexpr uint16_t CarControl::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind CarControl::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* CarControl::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// CarControl::Actuators +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t CarControl::Actuators::_capnpPrivate::dataWordSize; +constexpr uint16_t CarControl::Actuators::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind CarControl::Actuators::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* CarControl::Actuators::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// CarControl::CruiseControl +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t CarControl::CruiseControl::_capnpPrivate::dataWordSize; +constexpr uint16_t CarControl::CruiseControl::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind CarControl::CruiseControl::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* CarControl::CruiseControl::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// CarControl::HUDControl +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t CarControl::HUDControl::_capnpPrivate::dataWordSize; +constexpr uint16_t CarControl::HUDControl::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind CarControl::HUDControl::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* CarControl::HUDControl::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// CarParams +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t CarParams::_capnpPrivate::dataWordSize; +constexpr uint16_t CarParams::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind CarParams::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* CarParams::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// CarParams::SafetyConfig +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t CarParams::SafetyConfig::_capnpPrivate::dataWordSize; +constexpr uint16_t CarParams::SafetyConfig::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind CarParams::SafetyConfig::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* CarParams::SafetyConfig::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// CarParams::LateralParams +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t CarParams::LateralParams::_capnpPrivate::dataWordSize; +constexpr uint16_t CarParams::LateralParams::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind CarParams::LateralParams::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* CarParams::LateralParams::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// CarParams::LateralPIDTuning +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t CarParams::LateralPIDTuning::_capnpPrivate::dataWordSize; +constexpr uint16_t CarParams::LateralPIDTuning::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind CarParams::LateralPIDTuning::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* CarParams::LateralPIDTuning::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// CarParams::LateralTorqueTuning +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t CarParams::LateralTorqueTuning::_capnpPrivate::dataWordSize; +constexpr uint16_t CarParams::LateralTorqueTuning::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind CarParams::LateralTorqueTuning::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* CarParams::LateralTorqueTuning::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// CarParams::LongitudinalPIDTuning +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t CarParams::LongitudinalPIDTuning::_capnpPrivate::dataWordSize; +constexpr uint16_t CarParams::LongitudinalPIDTuning::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind CarParams::LongitudinalPIDTuning::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* CarParams::LongitudinalPIDTuning::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// CarParams::LateralINDITuning +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t CarParams::LateralINDITuning::_capnpPrivate::dataWordSize; +constexpr uint16_t CarParams::LateralINDITuning::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind CarParams::LateralINDITuning::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* CarParams::LateralINDITuning::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// CarParams::LateralLQRTuning +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t CarParams::LateralLQRTuning::_capnpPrivate::dataWordSize; +constexpr uint16_t CarParams::LateralLQRTuning::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind CarParams::LateralLQRTuning::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* CarParams::LateralLQRTuning::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// CarParams::CarFw +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t CarParams::CarFw::_capnpPrivate::dataWordSize; +constexpr uint16_t CarParams::CarFw::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind CarParams::CarFw::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* CarParams::CarFw::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// CarParams::LateralTuning +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t CarParams::LateralTuning::_capnpPrivate::dataWordSize; +constexpr uint16_t CarParams::LateralTuning::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind CarParams::LateralTuning::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* CarParams::LateralTuning::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + + +} // namespace + diff --git a/cereal/gen/cpp/custom.capnp.c++ b/cereal/gen/cpp/custom.capnp.c++ new file mode 100644 index 0000000..3e959a1 --- /dev/null +++ b/cereal/gen/cpp/custom.capnp.c++ @@ -0,0 +1,762 @@ +// Generated by Cap'n Proto compiler, DO NOT EDIT +// source: custom.capnp + +#include "custom.capnp.h" + +namespace capnp { +namespace schemas { +static const ::capnp::_::AlignedData<52> b_81c2f05a394cf4af = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 175, 244, 76, 57, 90, 240, 194, 129, + 13, 0, 0, 0, 1, 0, 1, 0, + 89, 10, 85, 29, 102, 186, 38, 181, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 10, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 115, 116, 111, 109, 46, 99, + 97, 112, 110, 112, 58, 70, 114, 111, + 103, 80, 105, 108, 111, 116, 67, 97, + 114, 67, 111, 110, 116, 114, 111, 108, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 0, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 52, 0, 0, 0, 3, 0, 1, 0, + 64, 0, 0, 0, 2, 0, 1, 0, + 97, 108, 119, 97, 121, 115, 79, 110, + 76, 97, 116, 101, 114, 97, 108, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 112, 101, 101, 100, 76, 105, 109, + 105, 116, 67, 104, 97, 110, 103, 101, + 100, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_81c2f05a394cf4af = b_81c2f05a394cf4af.words; +#if !CAPNP_LITE +static const uint16_t m_81c2f05a394cf4af[] = {0, 1}; +static const uint16_t i_81c2f05a394cf4af[] = {0, 1}; +const ::capnp::_::RawSchema s_81c2f05a394cf4af = { + 0x81c2f05a394cf4af, b_81c2f05a394cf4af.words, 52, nullptr, m_81c2f05a394cf4af, + 0, 2, i_81c2f05a394cf4af, nullptr, nullptr, { &s_81c2f05a394cf4af, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<51> b_aedffd8f31e7b55d = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 93, 181, 231, 49, 143, 253, 223, 174, + 13, 0, 0, 0, 1, 0, 1, 0, + 89, 10, 85, 29, 102, 186, 38, 181, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 18, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 115, 116, 111, 109, 46, 99, + 97, 112, 110, 112, 58, 70, 114, 111, + 103, 80, 105, 108, 111, 116, 68, 101, + 118, 105, 99, 101, 83, 116, 97, 116, + 101, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 0, 0, 0, 3, 0, 1, 0, + 60, 0, 0, 0, 2, 0, 1, 0, + 102, 114, 101, 101, 83, 112, 97, 99, + 101, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 115, 101, 100, 83, 112, 97, 99, + 101, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_aedffd8f31e7b55d = b_aedffd8f31e7b55d.words; +#if !CAPNP_LITE +static const uint16_t m_aedffd8f31e7b55d[] = {0, 1}; +static const uint16_t i_aedffd8f31e7b55d[] = {0, 1}; +const ::capnp::_::RawSchema s_aedffd8f31e7b55d = { + 0xaedffd8f31e7b55d, b_aedffd8f31e7b55d.words, 51, nullptr, m_aedffd8f31e7b55d, + 0, 2, i_aedffd8f31e7b55d, nullptr, nullptr, { &s_aedffd8f31e7b55d, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<52> b_f35cc4560bbf6ec2 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 194, 110, 191, 11, 86, 196, 92, 243, + 13, 0, 0, 0, 1, 0, 1, 0, + 89, 10, 85, 29, 102, 186, 38, 181, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 10, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 115, 116, 111, 109, 46, 99, + 97, 112, 110, 112, 58, 70, 114, 111, + 103, 80, 105, 108, 111, 116, 78, 97, + 118, 105, 103, 97, 116, 105, 111, 110, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 3, 0, 1, 0, + 56, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 53, 0, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 52, 0, 0, 0, 3, 0, 1, 0, + 64, 0, 0, 0, 2, 0, 1, 0, + 97, 112, 112, 114, 111, 97, 99, 104, + 105, 110, 103, 73, 110, 116, 101, 114, + 115, 101, 99, 116, 105, 111, 110, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 112, 112, 114, 111, 97, 99, 104, + 105, 110, 103, 84, 117, 114, 110, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_f35cc4560bbf6ec2 = b_f35cc4560bbf6ec2.words; +#if !CAPNP_LITE +static const uint16_t m_f35cc4560bbf6ec2[] = {0, 1}; +static const uint16_t i_f35cc4560bbf6ec2[] = {0, 1}; +const ::capnp::_::RawSchema s_f35cc4560bbf6ec2 = { + 0xf35cc4560bbf6ec2, b_f35cc4560bbf6ec2.words, 52, nullptr, m_f35cc4560bbf6ec2, + 0, 2, i_f35cc4560bbf6ec2, nullptr, nullptr, { &s_f35cc4560bbf6ec2, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<270> b_da96579883444c35 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 53, 76, 68, 131, 152, 87, 150, 218, + 13, 0, 0, 0, 1, 0, 7, 0, + 89, 10, 85, 29, 102, 186, 38, 181, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 218, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 79, 3, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 115, 116, 111, 109, 46, 99, + 97, 112, 110, 112, 58, 70, 114, 111, + 103, 80, 105, 108, 111, 116, 80, 108, + 97, 110, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 60, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 149, 1, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 1, 0, 0, 3, 0, 1, 0, + 160, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 64, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 157, 1, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 160, 1, 0, 0, 3, 0, 1, 0, + 172, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 169, 1, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 172, 1, 0, 0, 3, 0, 1, 0, + 184, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 1, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 1, 0, 0, 3, 0, 1, 0, + 192, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 1, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 1, 0, 0, 3, 0, 1, 0, + 200, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 65, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 1, 0, 0, 3, 0, 1, 0, + 208, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 1, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 1, 0, 0, 3, 0, 1, 0, + 220, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 11, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 217, 1, 0, 0, 210, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 224, 1, 0, 0, 3, 0, 1, 0, + 236, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 233, 1, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 1, 0, 0, 3, 0, 1, 0, + 244, 1, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 1, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 244, 1, 0, 0, 3, 0, 1, 0, + 0, 2, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 253, 1, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 252, 1, 0, 0, 3, 0, 1, 0, + 8, 2, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 2, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 2, 0, 0, 3, 0, 1, 0, + 20, 2, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 22, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 2, 0, 0, 202, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 24, 2, 0, 0, 3, 0, 1, 0, + 36, 2, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 2, 0, 0, 202, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 2, 0, 0, 3, 0, 1, 0, + 52, 2, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 67, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 2, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 52, 2, 0, 0, 3, 0, 1, 0, + 64, 2, 0, 0, 2, 0, 1, 0, + 97, 100, 106, 117, 115, 116, 101, 100, + 67, 114, 117, 105, 115, 101, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 111, 110, 100, 105, 116, 105, 111, + 110, 97, 108, 69, 120, 112, 101, 114, + 105, 109, 101, 110, 116, 97, 108, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 115, 105, 114, 101, 100, 70, + 111, 108, 108, 111, 119, 68, 105, 115, + 116, 97, 110, 99, 101, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 110, 101, 87, 105, 100, 116, + 104, 76, 101, 102, 116, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 110, 101, 87, 105, 100, 116, + 104, 82, 105, 103, 104, 116, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 101, 100, 76, 105, 103, 104, 116, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 97, 102, 101, 79, 98, 115, 116, + 97, 99, 108, 101, 68, 105, 115, 116, + 97, 110, 99, 101, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 97, 102, 101, 79, 98, 115, 116, + 97, 99, 108, 101, 68, 105, 115, 116, + 97, 110, 99, 101, 83, 116, 111, 99, + 107, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 108, 99, 79, 118, 101, 114, 114, + 105, 100, 100, 101, 110, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 108, 99, 79, 118, 101, 114, 114, + 105, 100, 100, 101, 110, 83, 112, 101, + 101, 100, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 108, 99, 83, 112, 101, 101, 100, + 76, 105, 109, 105, 116, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 108, 99, 83, 112, 101, 101, 100, + 76, 105, 109, 105, 116, 79, 102, 102, + 115, 101, 116, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 111, 112, 112, 101, 100, 69, + 113, 117, 105, 118, 97, 108, 101, 110, + 99, 101, 70, 97, 99, 116, 111, 114, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 110, 99, 111, 110, 102, 105, 114, + 109, 101, 100, 83, 108, 99, 83, 112, + 101, 101, 100, 76, 105, 109, 105, 116, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 116, 115, 99, 67, 111, 110, 116, + 114, 111, 108, 108, 105, 110, 103, 67, + 117, 114, 118, 101, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_da96579883444c35 = b_da96579883444c35.words; +#if !CAPNP_LITE +static const uint16_t m_da96579883444c35[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14}; +static const uint16_t i_da96579883444c35[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14}; +const ::capnp::_::RawSchema s_da96579883444c35 = { + 0xda96579883444c35, b_da96579883444c35.words, 270, nullptr, m_da96579883444c35, + 0, 15, i_da96579883444c35, nullptr, nullptr, { &s_da96579883444c35, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<17> b_80ae746ee2596b11 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 17, 107, 89, 226, 110, 116, 174, 128, + 13, 0, 0, 0, 1, 0, 0, 0, + 89, 10, 85, 29, 102, 186, 38, 181, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 234, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 115, 116, 111, 109, 46, 99, + 97, 112, 110, 112, 58, 67, 117, 115, + 116, 111, 109, 82, 101, 115, 101, 114, + 118, 101, 100, 52, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, } +}; +::capnp::word const* const bp_80ae746ee2596b11 = b_80ae746ee2596b11.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_80ae746ee2596b11 = { + 0x80ae746ee2596b11, b_80ae746ee2596b11.words, 17, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_80ae746ee2596b11, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<17> b_a5cd762cd951a455 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 85, 164, 81, 217, 44, 118, 205, 165, + 13, 0, 0, 0, 1, 0, 0, 0, + 89, 10, 85, 29, 102, 186, 38, 181, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 234, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 115, 116, 111, 109, 46, 99, + 97, 112, 110, 112, 58, 67, 117, 115, + 116, 111, 109, 82, 101, 115, 101, 114, + 118, 101, 100, 53, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, } +}; +::capnp::word const* const bp_a5cd762cd951a455 = b_a5cd762cd951a455.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_a5cd762cd951a455 = { + 0xa5cd762cd951a455, b_a5cd762cd951a455.words, 17, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_a5cd762cd951a455, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<17> b_f98d843bfd7004a3 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 163, 4, 112, 253, 59, 132, 141, 249, + 13, 0, 0, 0, 1, 0, 0, 0, + 89, 10, 85, 29, 102, 186, 38, 181, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 234, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 115, 116, 111, 109, 46, 99, + 97, 112, 110, 112, 58, 67, 117, 115, + 116, 111, 109, 82, 101, 115, 101, 114, + 118, 101, 100, 54, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, } +}; +::capnp::word const* const bp_f98d843bfd7004a3 = b_f98d843bfd7004a3.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_f98d843bfd7004a3 = { + 0xf98d843bfd7004a3, b_f98d843bfd7004a3.words, 17, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_f98d843bfd7004a3, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<17> b_b86e6369214c01c8 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 200, 1, 76, 33, 105, 99, 110, 184, + 13, 0, 0, 0, 1, 0, 0, 0, + 89, 10, 85, 29, 102, 186, 38, 181, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 234, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 115, 116, 111, 109, 46, 99, + 97, 112, 110, 112, 58, 67, 117, 115, + 116, 111, 109, 82, 101, 115, 101, 114, + 118, 101, 100, 55, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, } +}; +::capnp::word const* const bp_b86e6369214c01c8 = b_b86e6369214c01c8.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_b86e6369214c01c8 = { + 0xb86e6369214c01c8, b_b86e6369214c01c8.words, 17, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_b86e6369214c01c8, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<17> b_f416ec09499d9d19 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 25, 157, 157, 73, 9, 236, 22, 244, + 13, 0, 0, 0, 1, 0, 0, 0, + 89, 10, 85, 29, 102, 186, 38, 181, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 234, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 115, 116, 111, 109, 46, 99, + 97, 112, 110, 112, 58, 67, 117, 115, + 116, 111, 109, 82, 101, 115, 101, 114, + 118, 101, 100, 56, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, } +}; +::capnp::word const* const bp_f416ec09499d9d19 = b_f416ec09499d9d19.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_f416ec09499d9d19 = { + 0xf416ec09499d9d19, b_f416ec09499d9d19.words, 17, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_f416ec09499d9d19, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<17> b_a1680744031fdb2d = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 45, 219, 31, 3, 68, 7, 104, 161, + 13, 0, 0, 0, 1, 0, 0, 0, + 89, 10, 85, 29, 102, 186, 38, 181, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 234, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 115, 116, 111, 109, 46, 99, + 97, 112, 110, 112, 58, 67, 117, 115, + 116, 111, 109, 82, 101, 115, 101, 114, + 118, 101, 100, 57, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, } +}; +::capnp::word const* const bp_a1680744031fdb2d = b_a1680744031fdb2d.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_a1680744031fdb2d = { + 0xa1680744031fdb2d, b_a1680744031fdb2d.words, 17, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_a1680744031fdb2d, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +} // namespace schemas +} // namespace capnp + +// ======================================================================================= + +namespace cereal { + +// FrogPilotCarControl +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t FrogPilotCarControl::_capnpPrivate::dataWordSize; +constexpr uint16_t FrogPilotCarControl::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind FrogPilotCarControl::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* FrogPilotCarControl::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// FrogPilotDeviceState +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t FrogPilotDeviceState::_capnpPrivate::dataWordSize; +constexpr uint16_t FrogPilotDeviceState::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind FrogPilotDeviceState::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* FrogPilotDeviceState::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// FrogPilotNavigation +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t FrogPilotNavigation::_capnpPrivate::dataWordSize; +constexpr uint16_t FrogPilotNavigation::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind FrogPilotNavigation::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* FrogPilotNavigation::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// FrogPilotPlan +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t FrogPilotPlan::_capnpPrivate::dataWordSize; +constexpr uint16_t FrogPilotPlan::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind FrogPilotPlan::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* FrogPilotPlan::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// CustomReserved4 +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t CustomReserved4::_capnpPrivate::dataWordSize; +constexpr uint16_t CustomReserved4::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind CustomReserved4::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* CustomReserved4::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// CustomReserved5 +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t CustomReserved5::_capnpPrivate::dataWordSize; +constexpr uint16_t CustomReserved5::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind CustomReserved5::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* CustomReserved5::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// CustomReserved6 +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t CustomReserved6::_capnpPrivate::dataWordSize; +constexpr uint16_t CustomReserved6::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind CustomReserved6::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* CustomReserved6::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// CustomReserved7 +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t CustomReserved7::_capnpPrivate::dataWordSize; +constexpr uint16_t CustomReserved7::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind CustomReserved7::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* CustomReserved7::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// CustomReserved8 +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t CustomReserved8::_capnpPrivate::dataWordSize; +constexpr uint16_t CustomReserved8::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind CustomReserved8::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* CustomReserved8::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// CustomReserved9 +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t CustomReserved9::_capnpPrivate::dataWordSize; +constexpr uint16_t CustomReserved9::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind CustomReserved9::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* CustomReserved9::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + + +} // namespace + diff --git a/cereal/gen/cpp/legacy.capnp.c++ b/cereal/gen/cpp/legacy.capnp.c++ new file mode 100644 index 0000000..1017959 --- /dev/null +++ b/cereal/gen/cpp/legacy.capnp.c++ @@ -0,0 +1,6878 @@ +// Generated by Cap'n Proto compiler, DO NOT EDIT +// source: legacy.capnp + +#include "legacy.capnp.h" + +namespace capnp { +namespace schemas { +static const ::capnp::_::AlignedData<48> b_9811e1f38f62f2d1 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 209, 242, 98, 143, 243, 225, 17, 152, + 13, 0, 0, 0, 1, 0, 1, 0, + 99, 42, 156, 136, 196, 30, 239, 128, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 186, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 76, 111, 103, + 82, 111, 116, 97, 116, 101, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 3, 0, 1, 0, + 56, 0, 0, 0, 2, 0, 1, 0, + 115, 101, 103, 109, 101, 110, 116, 78, + 117, 109, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 97, 116, 104, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_9811e1f38f62f2d1 = b_9811e1f38f62f2d1.words; +#if !CAPNP_LITE +static const uint16_t m_9811e1f38f62f2d1[] = {1, 0}; +static const uint16_t i_9811e1f38f62f2d1[] = {0, 1}; +const ::capnp::_::RawSchema s_9811e1f38f62f2d1 = { + 0x9811e1f38f62f2d1, b_9811e1f38f62f2d1.words, 48, nullptr, m_9811e1f38f62f2d1, + 0, 2, i_9811e1f38f62f2d1, nullptr, nullptr, { &s_9811e1f38f62f2d1, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<81> b_c08240f996aefced = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 237, 252, 174, 150, 249, 64, 130, 192, + 13, 0, 0, 0, 1, 0, 1, 0, + 99, 42, 156, 136, 196, 30, 239, 128, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 162, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 231, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 76, 105, 118, + 101, 85, 73, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 0, 0, 0, 3, 0, 1, 0, + 108, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 0, 0, 0, 3, 0, 1, 0, + 116, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 0, 0, 0, 3, 0, 1, 0, + 124, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 0, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 0, 0, 0, 3, 0, 1, 0, + 132, 0, 0, 0, 2, 0, 1, 0, + 114, 101, 97, 114, 86, 105, 101, 119, + 67, 97, 109, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 108, 101, 114, 116, 84, 101, 120, + 116, 49, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 108, 101, 114, 116, 84, 101, 120, + 116, 50, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 119, 97, 114, 101, 110, 101, 115, + 115, 83, 116, 97, 116, 117, 115, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_c08240f996aefced = b_c08240f996aefced.words; +#if !CAPNP_LITE +static const uint16_t m_c08240f996aefced[] = {1, 2, 3, 0}; +static const uint16_t i_c08240f996aefced[] = {0, 1, 2, 3}; +const ::capnp::_::RawSchema s_c08240f996aefced = { + 0xc08240f996aefced, b_c08240f996aefced.words, 81, nullptr, m_c08240f996aefced, + 0, 4, i_c08240f996aefced, nullptr, nullptr, { &s_c08240f996aefced, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<86> b_88dcce08ad29dda0 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 160, 221, 41, 173, 8, 206, 220, 136, + 13, 0, 0, 0, 1, 0, 1, 0, + 99, 42, 156, 136, 196, 30, 239, 128, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 218, 0, 0, 0, + 33, 0, 0, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 231, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 85, 105, 76, + 97, 121, 111, 117, 116, 83, 116, 97, + 116, 101, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 1, 0, 1, 0, + 133, 210, 148, 207, 10, 71, 23, 153, + 1, 0, 0, 0, 34, 0, 0, 0, + 65, 112, 112, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 0, 0, 0, 3, 0, 1, 0, + 108, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 16, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 0, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 0, 0, 0, 3, 0, 1, 0, + 120, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 17, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 0, 0, 0, 3, 0, 1, 0, + 128, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 0, 0, 0, 3, 0, 1, 0, + 136, 0, 0, 0, 2, 0, 1, 0, + 97, 99, 116, 105, 118, 101, 65, 112, + 112, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 133, 210, 148, 207, 10, 71, 23, 153, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 105, 100, 101, 98, 97, 114, 67, + 111, 108, 108, 97, 112, 115, 101, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 97, 112, 69, 110, 97, 98, 108, + 101, 100, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 111, 99, 107, 69, 110, 103, 97, + 103, 101, 100, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_88dcce08ad29dda0 = b_88dcce08ad29dda0.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_88dcce08ad29dda0[] = { + &s_9917470acf94d285, +}; +static const uint16_t m_88dcce08ad29dda0[] = {0, 2, 3, 1}; +static const uint16_t i_88dcce08ad29dda0[] = {0, 1, 2, 3}; +const ::capnp::_::RawSchema s_88dcce08ad29dda0 = { + 0x88dcce08ad29dda0, b_88dcce08ad29dda0.words, 86, d_88dcce08ad29dda0, m_88dcce08ad29dda0, + 1, 4, i_88dcce08ad29dda0, nullptr, nullptr, { &s_88dcce08ad29dda0, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<39> b_9917470acf94d285 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 133, 210, 148, 207, 10, 71, 23, 153, + 27, 0, 0, 0, 2, 0, 0, 0, + 160, 221, 41, 173, 8, 206, 220, 136, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 250, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 127, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 85, 105, 76, + 97, 121, 111, 117, 116, 83, 116, 97, + 116, 101, 46, 65, 112, 112, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 20, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 53, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 111, 109, 101, 0, 0, 0, 0, + 109, 117, 115, 105, 99, 0, 0, 0, + 110, 97, 118, 0, 0, 0, 0, 0, + 115, 101, 116, 116, 105, 110, 103, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 111, 110, 101, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_9917470acf94d285 = b_9917470acf94d285.words; +#if !CAPNP_LITE +static const uint16_t m_9917470acf94d285[] = {0, 1, 2, 4, 3}; +const ::capnp::_::RawSchema s_9917470acf94d285 = { + 0x9917470acf94d285, b_9917470acf94d285.words, 39, nullptr, m_9917470acf94d285, + 0, 5, nullptr, nullptr, nullptr, { &s_9917470acf94d285, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(App_9917470acf94d285, 9917470acf94d285); +static const ::capnp::_::AlignedData<133> b_8afd33dc9b35e1aa = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 170, 225, 53, 155, 220, 51, 253, 138, + 13, 0, 0, 0, 1, 0, 2, 0, + 99, 42, 156, 136, 196, 30, 239, 128, + 4, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 250, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 87, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 79, 114, 98, + 115, 108, 97, 109, 67, 111, 114, 114, + 101, 99, 116, 105, 111, 110, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 24, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 0, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 156, 0, 0, 0, 3, 0, 1, 0, + 168, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 165, 0, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 164, 0, 0, 0, 3, 0, 1, 0, + 192, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 0, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 192, 0, 0, 0, 3, 0, 1, 0, + 220, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 217, 0, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 0, 0, 0, 3, 0, 1, 0, + 244, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 0, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 244, 0, 0, 0, 3, 0, 1, 0, + 16, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 1, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 1, 0, 0, 3, 0, 1, 0, + 24, 1, 0, 0, 2, 0, 1, 0, + 99, 111, 114, 114, 101, 99, 116, 105, + 111, 110, 77, 111, 110, 111, 84, 105, + 109, 101, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 114, 101, 80, 111, 115, 105, 116, + 105, 111, 110, 69, 67, 69, 70, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 115, 116, 80, 111, 115, 105, + 116, 105, 111, 110, 69, 67, 69, 70, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 114, 101, 80, 111, 115, 101, 81, + 117, 97, 116, 69, 67, 69, 70, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 115, 116, 80, 111, 115, 101, + 81, 117, 97, 116, 69, 67, 69, 70, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 117, 109, 73, 110, 108, 105, 101, + 114, 115, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_8afd33dc9b35e1aa = b_8afd33dc9b35e1aa.words; +#if !CAPNP_LITE +static const uint16_t m_8afd33dc9b35e1aa[] = {0, 5, 4, 2, 3, 1}; +static const uint16_t i_8afd33dc9b35e1aa[] = {0, 1, 2, 3, 4, 5}; +const ::capnp::_::RawSchema s_8afd33dc9b35e1aa = { + 0x8afd33dc9b35e1aa, b_8afd33dc9b35e1aa.words, 133, nullptr, m_8afd33dc9b35e1aa, + 0, 6, i_8afd33dc9b35e1aa, nullptr, nullptr, { &s_8afd33dc9b35e1aa, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<48> b_a99a9d5b33cf5859 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 89, 88, 207, 51, 91, 157, 154, 169, + 13, 0, 0, 0, 1, 0, 1, 0, + 99, 42, 156, 136, 196, 30, 239, 128, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 226, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 69, 116, 104, + 101, 114, 110, 101, 116, 80, 97, 99, + 107, 101, 116, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 112, 107, 116, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 115, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_a99a9d5b33cf5859 = b_a99a9d5b33cf5859.words; +#if !CAPNP_LITE +static const uint16_t m_a99a9d5b33cf5859[] = {0, 1}; +static const uint16_t i_a99a9d5b33cf5859[] = {0, 1}; +const ::capnp::_::RawSchema s_a99a9d5b33cf5859 = { + 0xa99a9d5b33cf5859, b_a99a9d5b33cf5859.words, 48, nullptr, m_a99a9d5b33cf5859, + 0, 2, i_a99a9d5b33cf5859, nullptr, nullptr, { &s_a99a9d5b33cf5859, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<48> b_cff7566681c277ce = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 206, 119, 194, 129, 102, 86, 247, 207, + 13, 0, 0, 0, 1, 0, 1, 0, + 99, 42, 156, 136, 196, 30, 239, 128, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 178, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 67, 101, 108, + 108, 73, 110, 102, 111, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 3, 0, 1, 0, + 56, 0, 0, 0, 2, 0, 1, 0, + 116, 105, 109, 101, 115, 116, 97, 109, + 112, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 101, 112, 114, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_cff7566681c277ce = b_cff7566681c277ce.words; +#if !CAPNP_LITE +static const uint16_t m_cff7566681c277ce[] = {1, 0}; +static const uint16_t i_cff7566681c277ce[] = {0, 1}; +const ::capnp::_::RawSchema s_cff7566681c277ce = { + 0xcff7566681c277ce, b_cff7566681c277ce.words, 48, nullptr, m_cff7566681c277ce, + 0, 2, i_cff7566681c277ce, nullptr, nullptr, { &s_cff7566681c277ce, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<260> b_d4df5a192382ba0b = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 11, 186, 130, 35, 25, 90, 223, 212, + 13, 0, 0, 0, 1, 0, 5, 0, + 99, 42, 156, 136, 196, 30, 239, 128, + 5, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 178, 0, 0, 0, + 29, 0, 0, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 79, 3, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 87, 105, 102, + 105, 83, 99, 97, 110, 0, 0, 0, + 4, 0, 0, 0, 1, 0, 1, 0, + 81, 107, 95, 1, 159, 39, 106, 203, + 1, 0, 0, 0, 106, 0, 0, 0, + 67, 104, 97, 110, 110, 101, 108, 87, + 105, 100, 116, 104, 0, 0, 0, 0, + 60, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 149, 1, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 144, 1, 0, 0, 3, 0, 1, 0, + 156, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 1, 0, 0, 3, 0, 1, 0, + 160, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 157, 1, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 156, 1, 0, 0, 3, 0, 1, 0, + 168, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 165, 1, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 164, 1, 0, 0, 3, 0, 1, 0, + 176, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 173, 1, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 1, 0, 0, 3, 0, 1, 0, + 180, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 1, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 1, 0, 0, 3, 0, 1, 0, + 188, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 1, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 1, 0, 0, 3, 0, 1, 0, + 196, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 1, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 192, 1, 0, 0, 3, 0, 1, 0, + 204, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 12, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 1, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 200, 1, 0, 0, 3, 0, 1, 0, + 212, 1, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 1, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 212, 1, 0, 0, 3, 0, 1, 0, + 224, 1, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 1, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 220, 1, 0, 0, 3, 0, 1, 0, + 232, 1, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 208, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 1, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 1, 0, 0, 3, 0, 1, 0, + 244, 1, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 209, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 1, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 1, 0, 0, 3, 0, 1, 0, + 252, 1, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 249, 1, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 248, 1, 0, 0, 3, 0, 1, 0, + 4, 2, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 2, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 2, 0, 0, 3, 0, 1, 0, + 12, 2, 0, 0, 2, 0, 1, 0, + 98, 115, 115, 105, 100, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 115, 105, 100, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 112, 97, 98, 105, 108, 105, + 116, 105, 101, 115, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 114, 101, 113, 117, 101, 110, 99, + 121, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 118, 101, 108, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 109, 101, 115, 116, 97, 109, + 112, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 101, 110, 116, 101, 114, 70, 114, + 101, 113, 48, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 101, 110, 116, 101, 114, 70, 114, + 101, 113, 49, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 104, 97, 110, 110, 101, 108, 87, + 105, 100, 116, 104, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 81, 107, 95, 1, 159, 39, 106, 203, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 112, 101, 114, 97, 116, 111, 114, + 70, 114, 105, 101, 110, 100, 108, 121, + 78, 97, 109, 101, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 101, 110, 117, 101, 78, 97, 109, + 101, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 115, 56, 48, 50, 49, 49, 109, + 99, 82, 101, 115, 112, 111, 110, 100, + 101, 114, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 97, 115, 115, 112, 111, 105, 110, + 116, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 105, 115, 116, 97, 110, 99, 101, + 67, 109, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 105, 115, 116, 97, 110, 99, 101, + 83, 100, 67, 109, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_d4df5a192382ba0b = b_d4df5a192382ba0b.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_d4df5a192382ba0b[] = { + &s_cb6a279f015f6b51, +}; +static const uint16_t m_d4df5a192382ba0b[] = {0, 2, 6, 7, 8, 13, 14, 3, 11, 4, 9, 12, 1, 5, 10}; +static const uint16_t i_d4df5a192382ba0b[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14}; +const ::capnp::_::RawSchema s_d4df5a192382ba0b = { + 0xd4df5a192382ba0b, b_d4df5a192382ba0b.words, 260, d_d4df5a192382ba0b, m_d4df5a192382ba0b, + 1, 15, i_d4df5a192382ba0b, nullptr, nullptr, { &s_d4df5a192382ba0b, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<40> b_cb6a279f015f6b51 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 81, 107, 95, 1, 159, 39, 106, 203, + 22, 0, 0, 0, 2, 0, 0, 0, + 11, 186, 130, 35, 25, 90, 223, 212, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 26, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 127, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 87, 105, 102, + 105, 83, 99, 97, 110, 46, 67, 104, + 97, 110, 110, 101, 108, 87, 105, 100, + 116, 104, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 20, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 53, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 119, 50, 48, 77, 104, 122, 0, 0, + 119, 52, 48, 77, 104, 122, 0, 0, + 119, 56, 48, 77, 104, 122, 0, 0, + 119, 49, 54, 48, 77, 104, 122, 0, + 119, 56, 48, 80, 108, 117, 115, 56, + 48, 77, 104, 122, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_cb6a279f015f6b51 = b_cb6a279f015f6b51.words; +#if !CAPNP_LITE +static const uint16_t m_cb6a279f015f6b51[] = {3, 0, 1, 2, 4}; +const ::capnp::_::RawSchema s_cb6a279f015f6b51 = { + 0xcb6a279f015f6b51, b_cb6a279f015f6b51.words, 40, nullptr, m_cb6a279f015f6b51, + 0, 5, nullptr, nullptr, nullptr, { &s_cb6a279f015f6b51, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(ChannelWidth_cb6a279f015f6b51, cb6a279f015f6b51); +static const ::capnp::_::AlignedData<48> b_94b7baa90c5c321e = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 30, 50, 92, 12, 169, 186, 183, 148, + 13, 0, 0, 0, 1, 0, 1, 0, + 99, 42, 156, 136, 196, 30, 239, 128, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 218, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 76, 105, 118, + 101, 69, 118, 101, 110, 116, 68, 97, + 116, 97, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 110, 97, 109, 101, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 97, 108, 117, 101, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_94b7baa90c5c321e = b_94b7baa90c5c321e.words; +#if !CAPNP_LITE +static const uint16_t m_94b7baa90c5c321e[] = {0, 1}; +static const uint16_t i_94b7baa90c5c321e[] = {0, 1}; +const ::capnp::_::RawSchema s_94b7baa90c5c321e = { + 0x94b7baa90c5c321e, b_94b7baa90c5c321e.words, 48, nullptr, m_94b7baa90c5c321e, + 0, 2, i_94b7baa90c5c321e, nullptr, nullptr, { &s_94b7baa90c5c321e, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<314> b_b8aad62cffef28a9 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 169, 40, 239, 255, 44, 214, 170, 184, + 13, 0, 0, 0, 1, 0, 4, 0, + 99, 42, 156, 136, 196, 30, 239, 128, + 11, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 186, 0, 0, 0, + 29, 0, 0, 0, 87, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 0, 0, 0, 191, 3, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 77, 111, 100, + 101, 108, 68, 97, 116, 97, 0, 0, + 20, 0, 0, 0, 1, 0, 1, 0, + 8, 159, 158, 56, 234, 238, 23, 136, + 33, 0, 0, 0, 74, 0, 0, 0, + 145, 250, 38, 109, 249, 190, 201, 209, + 33, 0, 0, 0, 74, 0, 0, 0, + 20, 233, 211, 239, 16, 55, 110, 162, + 33, 0, 0, 0, 114, 0, 0, 0, + 248, 43, 15, 182, 95, 242, 68, 151, + 33, 0, 0, 0, 74, 0, 0, 0, + 34, 17, 7, 106, 156, 153, 143, 249, + 33, 0, 0, 0, 138, 0, 0, 0, + 80, 97, 116, 104, 68, 97, 116, 97, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 101, 97, 100, 68, 97, 116, 97, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 111, 100, 101, 108, 83, 101, 116, + 116, 105, 110, 103, 115, 0, 0, 0, + 77, 101, 116, 97, 68, 97, 116, 97, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 111, 110, 103, 105, 116, 117, 100, + 105, 110, 97, 108, 68, 97, 116, 97, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 1, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 200, 1, 0, 0, 3, 0, 1, 0, + 212, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 1, 0, 0, 3, 0, 1, 0, + 216, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 212, 1, 0, 0, 3, 0, 1, 0, + 224, 1, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 1, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 220, 1, 0, 0, 3, 0, 1, 0, + 232, 1, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 224, 1, 0, 0, 3, 0, 1, 0, + 236, 1, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 233, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 1, 0, 0, 3, 0, 1, 0, + 244, 1, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 1, 0, 0, 3, 0, 1, 0, + 12, 2, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 2, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 2, 0, 0, 3, 0, 1, 0, + 20, 2, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 2, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 2, 0, 0, 3, 0, 1, 0, + 40, 2, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 2, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 2, 0, 0, 3, 0, 1, 0, + 48, 2, 0, 0, 2, 0, 1, 0, + 15, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 2, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 2, 0, 0, 3, 0, 1, 0, + 52, 2, 0, 0, 2, 0, 1, 0, + 16, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 2, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 2, 0, 0, 3, 0, 1, 0, + 60, 2, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 57, 2, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 56, 2, 0, 0, 3, 0, 1, 0, + 68, 2, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 65, 2, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 2, 0, 0, 3, 0, 1, 0, + 76, 2, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 2, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 2, 0, 0, 3, 0, 1, 0, + 88, 2, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 15, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 85, 2, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 80, 2, 0, 0, 3, 0, 1, 0, + 92, 2, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 16, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 89, 2, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 2, 0, 0, 3, 0, 1, 0, + 104, 2, 0, 0, 2, 0, 1, 0, + 102, 114, 97, 109, 101, 73, 100, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 97, 116, 104, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 8, 159, 158, 56, 234, 238, 23, 136, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 102, 116, 76, 97, 110, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 8, 159, 158, 56, 234, 238, 23, 136, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 105, 103, 104, 116, 76, 97, 110, + 101, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 8, 159, 158, 56, 234, 238, 23, 136, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 97, 100, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 145, 250, 38, 109, 249, 190, 201, 209, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 101, 116, 116, 105, 110, 103, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 20, 233, 211, 239, 16, 55, 110, 162, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 114, 101, 101, 80, 97, 116, 104, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 97, 100, 70, 117, 116, 117, + 114, 101, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 145, 250, 38, 109, 249, 190, 201, 209, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 112, 101, 101, 100, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 109, 101, 115, 116, 97, 109, + 112, 69, 111, 102, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 101, 116, 97, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 248, 43, 15, 182, 95, 242, 68, 151, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 110, 103, 105, 116, 117, 100, + 105, 110, 97, 108, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 34, 17, 7, 106, 156, 153, 143, 249, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 114, 97, 109, 101, 65, 103, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 114, 97, 109, 101, 68, 114, 111, + 112, 80, 101, 114, 99, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 111, 100, 101, 108, 69, 120, 101, + 99, 117, 116, 105, 111, 110, 84, 105, + 109, 101, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 97, 119, 80, 114, 101, 100, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 117, 69, 120, 101, 99, 117, + 116, 105, 111, 110, 84, 105, 109, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_b8aad62cffef28a9 = b_b8aad62cffef28a9.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_b8aad62cffef28a9[] = { + &s_8817eeea389e9f08, + &s_9744f25fb60f2bf8, + &s_a26e3710efd3e914, + &s_d1c9bef96d26fa91, + &s_f98f999c6a071122, +}; +static const uint16_t m_b8aad62cffef28a9[] = {12, 13, 0, 6, 16, 4, 7, 2, 11, 10, 14, 1, 15, 3, 5, 8, 9}; +static const uint16_t i_b8aad62cffef28a9[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16}; +const ::capnp::_::RawSchema s_b8aad62cffef28a9 = { + 0xb8aad62cffef28a9, b_b8aad62cffef28a9.words, 314, d_b8aad62cffef28a9, m_b8aad62cffef28a9, + 5, 17, i_b8aad62cffef28a9, nullptr, nullptr, { &s_b8aad62cffef28a9, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<121> b_8817eeea389e9f08 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 8, 159, 158, 56, 234, 238, 23, 136, + 23, 0, 0, 0, 1, 0, 2, 0, + 169, 40, 239, 255, 44, 214, 170, 184, + 3, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 2, 1, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 87, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 77, 111, 100, + 101, 108, 68, 97, 116, 97, 46, 80, + 97, 116, 104, 68, 97, 116, 97, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 24, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 0, 0, 0, 3, 0, 1, 0, + 176, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 173, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 0, 0, 0, 3, 0, 1, 0, + 180, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 172, 0, 0, 0, 3, 0, 1, 0, + 184, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 0, 0, 0, 3, 0, 1, 0, + 204, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 0, 0, 0, 3, 0, 1, 0, + 224, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 220, 0, 0, 0, 3, 0, 1, 0, + 232, 0, 0, 0, 2, 0, 1, 0, + 112, 111, 105, 110, 116, 115, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 114, 111, 98, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 100, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 100, 115, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 108, 121, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 97, 108, 105, 100, 76, 101, 110, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_8817eeea389e9f08 = b_8817eeea389e9f08.words; +#if !CAPNP_LITE +static const uint16_t m_8817eeea389e9f08[] = {0, 4, 1, 2, 3, 5}; +static const uint16_t i_8817eeea389e9f08[] = {0, 1, 2, 3, 4, 5}; +const ::capnp::_::RawSchema s_8817eeea389e9f08 = { + 0x8817eeea389e9f08, b_8817eeea389e9f08.words, 121, nullptr, m_8817eeea389e9f08, + 0, 6, i_8817eeea389e9f08, nullptr, nullptr, { &s_8817eeea389e9f08, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<154> b_d1c9bef96d26fa91 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 145, 250, 38, 109, 249, 190, 201, 209, + 23, 0, 0, 0, 1, 0, 5, 0, + 169, 40, 239, 255, 44, 214, 170, 184, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 2, 1, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 255, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 77, 111, 100, + 101, 108, 68, 97, 116, 97, 46, 76, + 101, 97, 100, 68, 97, 116, 97, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 36, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 0, 0, 0, 3, 0, 1, 0, + 244, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 236, 0, 0, 0, 3, 0, 1, 0, + 248, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 245, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 0, 0, 0, 3, 0, 1, 0, + 252, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 249, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 244, 0, 0, 0, 3, 0, 1, 0, + 0, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 253, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 252, 0, 0, 0, 3, 0, 1, 0, + 8, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 1, 0, 0, 3, 0, 1, 0, + 12, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 1, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 1, 0, 0, 3, 0, 1, 0, + 16, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 1, 0, 0, 3, 0, 1, 0, + 20, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 1, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 1, 0, 0, 3, 0, 1, 0, + 24, 1, 0, 0, 2, 0, 1, 0, + 100, 105, 115, 116, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 114, 111, 98, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 100, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 101, 108, 86, 101, 108, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 101, 108, 86, 101, 108, 83, 116, + 100, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 101, 108, 89, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 101, 108, 89, 83, 116, 100, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 101, 108, 65, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 101, 108, 65, 83, 116, 100, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_d1c9bef96d26fa91 = b_d1c9bef96d26fa91.words; +#if !CAPNP_LITE +static const uint16_t m_d1c9bef96d26fa91[] = {0, 1, 7, 8, 3, 4, 5, 6, 2}; +static const uint16_t i_d1c9bef96d26fa91[] = {0, 1, 2, 3, 4, 5, 6, 7, 8}; +const ::capnp::_::RawSchema s_d1c9bef96d26fa91 = { + 0xd1c9bef96d26fa91, b_d1c9bef96d26fa91.words, 154, nullptr, m_d1c9bef96d26fa91, + 0, 9, i_d1c9bef96d26fa91, nullptr, nullptr, { &s_d1c9bef96d26fa91, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<141> b_a26e3710efd3e914 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 20, 233, 211, 239, 16, 55, 110, 162, + 23, 0, 0, 0, 1, 0, 1, 0, + 169, 40, 239, 255, 44, 214, 170, 184, + 3, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 42, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 143, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 77, 111, 100, + 101, 108, 68, 97, 116, 97, 46, 77, + 111, 100, 101, 108, 83, 101, 116, 116, + 105, 110, 103, 115, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 28, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 0, 0, 0, 3, 0, 1, 0, + 188, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 0, 0, 0, 3, 0, 1, 0, + 192, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 0, 0, 0, 3, 0, 1, 0, + 200, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 0, 0, 0, 3, 0, 1, 0, + 208, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 0, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 0, 0, 0, 3, 0, 1, 0, + 232, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 0, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 228, 0, 0, 0, 3, 0, 1, 0, + 0, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 253, 0, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 252, 0, 0, 0, 3, 0, 1, 0, + 24, 1, 0, 0, 2, 0, 1, 0, + 98, 105, 103, 66, 111, 120, 88, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 105, 103, 66, 111, 120, 89, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 105, 103, 66, 111, 120, 87, 105, + 100, 116, 104, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 105, 103, 66, 111, 120, 72, 101, + 105, 103, 104, 116, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 111, 120, 80, 114, 111, 106, 101, + 99, 116, 105, 111, 110, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 117, 118, 67, 111, 114, 114, 101, + 99, 116, 105, 111, 110, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 110, 112, 117, 116, 84, 114, 97, + 110, 115, 102, 111, 114, 109, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_a26e3710efd3e914 = b_a26e3710efd3e914.words; +#if !CAPNP_LITE +static const uint16_t m_a26e3710efd3e914[] = {3, 2, 0, 1, 4, 6, 5}; +static const uint16_t i_a26e3710efd3e914[] = {0, 1, 2, 3, 4, 5, 6}; +const ::capnp::_::RawSchema s_a26e3710efd3e914 = { + 0xa26e3710efd3e914, b_a26e3710efd3e914.words, 141, nullptr, m_a26e3710efd3e914, + 0, 7, i_a26e3710efd3e914, nullptr, nullptr, { &s_a26e3710efd3e914, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<126> b_9744f25fb60f2bf8 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 248, 43, 15, 182, 95, 242, 68, 151, + 23, 0, 0, 0, 1, 0, 2, 0, + 169, 40, 239, 255, 44, 214, 170, 184, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 2, 1, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 87, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 77, 111, 100, + 101, 108, 68, 97, 116, 97, 46, 77, + 101, 116, 97, 68, 97, 116, 97, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 24, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 152, 0, 0, 0, 3, 0, 1, 0, + 164, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 161, 0, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 164, 0, 0, 0, 3, 0, 1, 0, + 192, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 0, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 192, 0, 0, 0, 3, 0, 1, 0, + 204, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 0, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 0, 0, 0, 3, 0, 1, 0, + 216, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 0, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 0, 0, 0, 3, 0, 1, 0, + 228, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 225, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 224, 0, 0, 0, 3, 0, 1, 0, + 252, 0, 0, 0, 2, 0, 1, 0, + 101, 110, 103, 97, 103, 101, 100, 80, + 114, 111, 98, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 115, 105, 114, 101, 80, 114, + 101, 100, 105, 99, 116, 105, 111, 110, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 114, 97, 107, 101, 68, 105, 115, + 101, 110, 103, 97, 103, 101, 80, 114, + 111, 98, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 97, 115, 68, 105, 115, 101, 110, + 103, 97, 103, 101, 80, 114, 111, 98, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 79, 118, 101, + 114, 114, 105, 100, 101, 80, 114, 111, + 98, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 115, 105, 114, 101, 83, 116, + 97, 116, 101, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_9744f25fb60f2bf8 = b_9744f25fb60f2bf8.words; +#if !CAPNP_LITE +static const uint16_t m_9744f25fb60f2bf8[] = {2, 1, 5, 0, 3, 4}; +static const uint16_t i_9744f25fb60f2bf8[] = {0, 1, 2, 3, 4, 5}; +const ::capnp::_::RawSchema s_9744f25fb60f2bf8 = { + 0x9744f25fb60f2bf8, b_9744f25fb60f2bf8.words, 126, nullptr, m_9744f25fb60f2bf8, + 0, 6, i_9744f25fb60f2bf8, nullptr, nullptr, { &s_9744f25fb60f2bf8, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<78> b_f98f999c6a071122 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 34, 17, 7, 106, 156, 153, 143, 249, + 23, 0, 0, 0, 1, 0, 0, 0, + 169, 40, 239, 255, 44, 214, 170, 184, + 3, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 66, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 77, 111, 100, + 101, 108, 68, 97, 116, 97, 46, 76, + 111, 110, 103, 105, 116, 117, 100, 105, + 110, 97, 108, 68, 97, 116, 97, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 0, 0, 0, 3, 0, 1, 0, + 92, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 89, 0, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 88, 0, 0, 0, 3, 0, 1, 0, + 116, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 0, 0, 0, 3, 0, 1, 0, + 140, 0, 0, 0, 2, 0, 1, 0, + 115, 112, 101, 101, 100, 115, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 99, 101, 108, 101, 114, 97, + 116, 105, 111, 110, 115, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 105, 115, 116, 97, 110, 99, 101, + 115, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_f98f999c6a071122 = b_f98f999c6a071122.words; +#if !CAPNP_LITE +static const uint16_t m_f98f999c6a071122[] = {1, 2, 0}; +static const uint16_t i_f98f999c6a071122[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_f98f999c6a071122 = { + 0xf98f999c6a071122, b_f98f999c6a071122.words, 78, nullptr, m_f98f999c6a071122, + 0, 3, i_f98f999c6a071122, nullptr, nullptr, { &s_f98f999c6a071122, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<62> b_c25bbbd524983447 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 71, 52, 152, 36, 213, 187, 91, 194, + 13, 0, 0, 0, 1, 0, 3, 0, + 99, 42, 156, 136, 196, 30, 239, 128, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 186, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 69, 67, 69, + 70, 80, 111, 105, 110, 116, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 0, 0, 0, 3, 0, 1, 0, + 76, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 0, 0, 0, 3, 0, 1, 0, + 80, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 0, 0, 0, 3, 0, 1, 0, + 84, 0, 0, 0, 2, 0, 1, 0, + 120, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 122, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_c25bbbd524983447 = b_c25bbbd524983447.words; +#if !CAPNP_LITE +static const uint16_t m_c25bbbd524983447[] = {0, 1, 2}; +static const uint16_t i_c25bbbd524983447[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_c25bbbd524983447 = { + 0xc25bbbd524983447, b_c25bbbd524983447.words, 62, nullptr, m_c25bbbd524983447, + 0, 3, i_c25bbbd524983447, nullptr, nullptr, { &s_c25bbbd524983447, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<64> b_e10e21168db0c7f7 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 247, 199, 176, 141, 22, 33, 14, 225, + 13, 0, 0, 0, 1, 0, 2, 0, + 99, 42, 156, 136, 196, 30, 239, 128, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 10, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 69, 67, 69, + 70, 80, 111, 105, 110, 116, 68, 69, + 80, 82, 69, 67, 65, 84, 69, 68, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 0, 0, 0, 3, 0, 1, 0, + 76, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 0, 0, 0, 3, 0, 1, 0, + 80, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 0, 0, 0, 3, 0, 1, 0, + 84, 0, 0, 0, 2, 0, 1, 0, + 120, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 122, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e10e21168db0c7f7 = b_e10e21168db0c7f7.words; +#if !CAPNP_LITE +static const uint16_t m_e10e21168db0c7f7[] = {0, 1, 2}; +static const uint16_t i_e10e21168db0c7f7[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_e10e21168db0c7f7 = { + 0xe10e21168db0c7f7, b_e10e21168db0c7f7.words, 64, nullptr, m_e10e21168db0c7f7, + 0, 3, i_e10e21168db0c7f7, nullptr, nullptr, { &s_e10e21168db0c7f7, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<153> b_ab54c59699f8f9f3 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 243, 249, 248, 153, 150, 197, 84, 171, + 13, 0, 0, 0, 1, 0, 2, 0, + 99, 42, 156, 136, 196, 30, 239, 128, + 5, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 242, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 199, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 71, 80, 83, + 80, 108, 97, 110, 110, 101, 114, 80, + 111, 105, 110, 116, 115, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 32, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 0, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 212, 0, 0, 0, 3, 0, 1, 0, + 224, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 0, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 224, 0, 0, 0, 3, 0, 1, 0, + 252, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 249, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 244, 0, 0, 0, 3, 0, 1, 0, + 0, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 253, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 252, 0, 0, 0, 3, 0, 1, 0, + 8, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 1, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 1, 0, 0, 3, 0, 1, 0, + 16, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 1, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 1, 0, 0, 3, 0, 1, 0, + 24, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 1, 0, 0, 3, 0, 1, 0, + 28, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 1, 0, 0, 3, 0, 1, 0, + 48, 1, 0, 0, 2, 0, 1, 0, + 99, 117, 114, 80, 111, 115, 68, 69, + 80, 82, 69, 67, 65, 84, 69, 68, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 247, 199, 176, 141, 22, 33, 14, 225, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 105, 110, 116, 115, 68, 69, + 80, 82, 69, 67, 65, 84, 69, 68, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 247, 199, 176, 141, 22, 33, 14, 225, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 97, 108, 105, 100, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 114, 97, 99, 107, 78, 97, 109, + 101, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 112, 101, 101, 100, 76, 105, 109, + 105, 116, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 99, 101, 108, 84, 97, 114, + 103, 101, 116, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 114, 80, 111, 115, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 71, 52, 152, 36, 213, 187, 91, 194, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 105, 110, 116, 115, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 71, 52, 152, 36, 213, 187, 91, 194, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_ab54c59699f8f9f3 = b_ab54c59699f8f9f3.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_ab54c59699f8f9f3[] = { + &s_c25bbbd524983447, + &s_e10e21168db0c7f7, +}; +static const uint16_t m_ab54c59699f8f9f3[] = {5, 6, 0, 7, 1, 4, 3, 2}; +static const uint16_t i_ab54c59699f8f9f3[] = {0, 1, 2, 3, 4, 5, 6, 7}; +const ::capnp::_::RawSchema s_ab54c59699f8f9f3 = { + 0xab54c59699f8f9f3, b_ab54c59699f8f9f3.words, 153, d_ab54c59699f8f9f3, m_ab54c59699f8f9f3, + 2, 8, i_ab54c59699f8f9f3, nullptr, nullptr, { &s_ab54c59699f8f9f3, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<155> b_f5ad1d90cdc1dd6b = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 107, 221, 193, 205, 144, 29, 173, 245, + 13, 0, 0, 0, 1, 0, 2, 0, + 99, 42, 156, 136, 196, 30, 239, 128, + 4, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 226, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 199, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 71, 80, 83, + 80, 108, 97, 110, 110, 101, 114, 80, + 108, 97, 110, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 32, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 0, 0, 0, 3, 0, 1, 0, + 216, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 0, 0, 0, 3, 0, 1, 0, + 236, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 233, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 0, 0, 0, 3, 0, 1, 0, + 244, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 236, 0, 0, 0, 3, 0, 1, 0, + 248, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 245, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 244, 0, 0, 0, 3, 0, 1, 0, + 0, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 253, 0, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 1, 0, 0, 3, 0, 1, 0, + 28, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 1, 0, 0, 3, 0, 1, 0, + 48, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 1, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 1, 0, 0, 3, 0, 1, 0, + 56, 1, 0, 0, 2, 0, 1, 0, + 118, 97, 108, 105, 100, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 108, 121, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 114, 97, 99, 107, 78, 97, 109, + 101, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 112, 101, 101, 100, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 99, 101, 108, 101, 114, 97, + 116, 105, 111, 110, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 105, 110, 116, 115, 68, 69, + 80, 82, 69, 67, 65, 84, 69, 68, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 247, 199, 176, 141, 22, 33, 14, 225, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 105, 110, 116, 115, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 71, 52, 152, 36, 213, 187, 91, 194, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 76, 111, 111, 107, 97, 104, 101, + 97, 100, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_f5ad1d90cdc1dd6b = b_f5ad1d90cdc1dd6b.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_f5ad1d90cdc1dd6b[] = { + &s_c25bbbd524983447, + &s_e10e21168db0c7f7, +}; +static const uint16_t m_f5ad1d90cdc1dd6b[] = {4, 6, 5, 1, 3, 2, 0, 7}; +static const uint16_t i_f5ad1d90cdc1dd6b[] = {0, 1, 2, 3, 4, 5, 6, 7}; +const ::capnp::_::RawSchema s_f5ad1d90cdc1dd6b = { + 0xf5ad1d90cdc1dd6b, b_f5ad1d90cdc1dd6b.words, 155, d_f5ad1d90cdc1dd6b, m_f5ad1d90cdc1dd6b, + 2, 8, i_f5ad1d90cdc1dd6b, nullptr, nullptr, { &s_f5ad1d90cdc1dd6b, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<103> b_90c8426c3eaddd3b = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 59, 221, 173, 62, 108, 66, 200, 144, + 13, 0, 0, 0, 1, 0, 1, 0, + 99, 42, 156, 136, 196, 30, 239, 128, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 250, 0, 0, 0, + 33, 0, 0, 0, 39, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 53, 0, 0, 0, 31, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 85, 105, 78, + 97, 118, 105, 103, 97, 116, 105, 111, + 110, 69, 118, 101, 110, 116, 0, 0, + 8, 0, 0, 0, 1, 0, 1, 0, + 5, 234, 252, 248, 220, 7, 219, 232, + 9, 0, 0, 0, 42, 0, 0, 0, + 31, 154, 249, 94, 199, 136, 170, 185, + 5, 0, 0, 0, 58, 0, 0, 0, + 84, 121, 112, 101, 0, 0, 0, 0, + 83, 116, 97, 116, 117, 115, 0, 0, + 20, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 0, 0, 0, 3, 0, 1, 0, + 132, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 129, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 0, 0, 0, 3, 0, 1, 0, + 136, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 132, 0, 0, 0, 3, 0, 1, 0, + 144, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 0, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 144, 0, 0, 0, 3, 0, 1, 0, + 156, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 152, 0, 0, 0, 3, 0, 1, 0, + 164, 0, 0, 0, 2, 0, 1, 0, + 116, 121, 112, 101, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 5, 234, 252, 248, 220, 7, 219, 232, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 116, 117, 115, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 31, 154, 249, 94, 199, 136, 170, 185, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 105, 115, 116, 97, 110, 99, 101, + 84, 111, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 110, 100, 82, 111, 97, 100, 80, + 111, 105, 110, 116, 68, 69, 80, 82, + 69, 67, 65, 84, 69, 68, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 247, 199, 176, 141, 22, 33, 14, 225, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 110, 100, 82, 111, 97, 100, 80, + 111, 105, 110, 116, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 71, 52, 152, 36, 213, 187, 91, 194, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_90c8426c3eaddd3b = b_90c8426c3eaddd3b.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_90c8426c3eaddd3b[] = { + &s_b9aa88c75ef99a1f, + &s_c25bbbd524983447, + &s_e10e21168db0c7f7, + &s_e8db07dcf8fcea05, +}; +static const uint16_t m_90c8426c3eaddd3b[] = {2, 4, 3, 1, 0}; +static const uint16_t i_90c8426c3eaddd3b[] = {0, 1, 2, 3, 4}; +const ::capnp::_::RawSchema s_90c8426c3eaddd3b = { + 0x90c8426c3eaddd3b, b_90c8426c3eaddd3b.words, 103, d_90c8426c3eaddd3b, m_90c8426c3eaddd3b, + 4, 5, i_90c8426c3eaddd3b, nullptr, nullptr, { &s_90c8426c3eaddd3b, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<53> b_e8db07dcf8fcea05 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 5, 234, 252, 248, 220, 7, 219, 232, + 31, 0, 0, 0, 2, 0, 0, 0, + 59, 221, 173, 62, 108, 66, 200, 144, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 34, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 85, 105, 78, + 97, 118, 105, 103, 97, 116, 105, 111, + 110, 69, 118, 101, 110, 116, 46, 84, + 121, 112, 101, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 28, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 65, 0, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 61, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 57, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 53, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 49, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 111, 110, 101, 0, 0, 0, 0, + 108, 97, 110, 101, 67, 104, 97, 110, + 103, 101, 76, 101, 102, 116, 0, 0, + 108, 97, 110, 101, 67, 104, 97, 110, + 103, 101, 82, 105, 103, 104, 116, 0, + 109, 101, 114, 103, 101, 76, 101, 102, + 116, 0, 0, 0, 0, 0, 0, 0, + 109, 101, 114, 103, 101, 82, 105, 103, + 104, 116, 0, 0, 0, 0, 0, 0, + 116, 117, 114, 110, 76, 101, 102, 116, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 117, 114, 110, 82, 105, 103, 104, + 116, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e8db07dcf8fcea05 = b_e8db07dcf8fcea05.words; +#if !CAPNP_LITE +static const uint16_t m_e8db07dcf8fcea05[] = {1, 2, 3, 4, 0, 5, 6}; +const ::capnp::_::RawSchema s_e8db07dcf8fcea05 = { + 0xe8db07dcf8fcea05, b_e8db07dcf8fcea05.words, 53, nullptr, m_e8db07dcf8fcea05, + 0, 7, nullptr, nullptr, nullptr, { &s_e8db07dcf8fcea05, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(Type_e8db07dcf8fcea05, e8db07dcf8fcea05); +static const ::capnp::_::AlignedData<36> b_b9aa88c75ef99a1f = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 31, 154, 249, 94, 199, 136, 170, 185, + 31, 0, 0, 0, 2, 0, 0, 0, + 59, 221, 173, 62, 108, 66, 200, 144, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 50, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 103, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 85, 105, 78, + 97, 118, 105, 103, 97, 116, 105, 111, + 110, 69, 118, 101, 110, 116, 46, 83, + 116, 97, 116, 117, 115, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 111, 110, 101, 0, 0, 0, 0, + 112, 97, 115, 115, 105, 118, 101, 0, + 97, 112, 112, 114, 111, 97, 99, 104, + 105, 110, 103, 0, 0, 0, 0, 0, + 97, 99, 116, 105, 118, 101, 0, 0, } +}; +::capnp::word const* const bp_b9aa88c75ef99a1f = b_b9aa88c75ef99a1f.words; +#if !CAPNP_LITE +static const uint16_t m_b9aa88c75ef99a1f[] = {3, 2, 0, 1}; +const ::capnp::_::RawSchema s_b9aa88c75ef99a1f = { + 0xb9aa88c75ef99a1f, b_b9aa88c75ef99a1f.words, 36, nullptr, m_b9aa88c75ef99a1f, + 0, 4, nullptr, nullptr, nullptr, { &s_b9aa88c75ef99a1f, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(Status_b9aa88c75ef99a1f, b9aa88c75ef99a1f); +static const ::capnp::_::AlignedData<406> b_b99b2bc7a57e8128 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 40, 129, 126, 165, 199, 43, 155, 185, + 13, 0, 0, 0, 1, 0, 10, 0, + 99, 42, 156, 136, 196, 30, 239, 128, + 7, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 242, 0, 0, 0, + 33, 0, 0, 0, 39, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 0, 0, 0, 15, 5, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 76, 105, 118, + 101, 76, 111, 99, 97, 116, 105, 111, + 110, 68, 97, 116, 97, 0, 0, 0, + 8, 0, 0, 0, 1, 0, 1, 0, + 63, 176, 115, 84, 98, 196, 61, 148, + 9, 0, 0, 0, 74, 0, 0, 0, + 87, 246, 42, 37, 204, 211, 113, 200, + 9, 0, 0, 0, 106, 0, 0, 0, + 65, 99, 99, 117, 114, 97, 99, 121, + 0, 0, 0, 0, 0, 0, 0, 0, + 83, 101, 110, 115, 111, 114, 83, 111, + 117, 114, 99, 101, 0, 0, 0, 0, + 92, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 2, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 2, 0, 0, 3, 0, 1, 0, + 124, 2, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 2, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 2, 0, 0, 3, 0, 1, 0, + 128, 2, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 2, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 2, 0, 0, 3, 0, 1, 0, + 132, 2, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 129, 2, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 2, 0, 0, 3, 0, 1, 0, + 136, 2, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 2, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 128, 2, 0, 0, 3, 0, 1, 0, + 140, 2, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 137, 2, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 132, 2, 0, 0, 3, 0, 1, 0, + 160, 2, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 157, 2, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 152, 2, 0, 0, 3, 0, 1, 0, + 164, 2, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 161, 2, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 156, 2, 0, 0, 3, 0, 1, 0, + 168, 2, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 165, 2, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 160, 2, 0, 0, 3, 0, 1, 0, + 172, 2, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 169, 2, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 2, 0, 0, 3, 0, 1, 0, + 180, 2, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 11, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 2, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 2, 0, 0, 3, 0, 1, 0, + 188, 2, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 2, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 2, 0, 0, 3, 0, 1, 0, + 208, 2, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 2, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 200, 2, 0, 0, 3, 0, 1, 0, + 228, 2, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 225, 2, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 224, 2, 0, 0, 3, 0, 1, 0, + 236, 2, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 233, 2, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 228, 2, 0, 0, 3, 0, 1, 0, + 240, 2, 0, 0, 2, 0, 1, 0, + 15, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 15, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 2, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 236, 2, 0, 0, 3, 0, 1, 0, + 248, 2, 0, 0, 2, 0, 1, 0, + 16, 0, 0, 0, 14, 0, 0, 0, + 0, 0, 1, 0, 16, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 245, 2, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 2, 0, 0, 3, 0, 1, 0, + 252, 2, 0, 0, 2, 0, 1, 0, + 17, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 17, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 249, 2, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 248, 2, 0, 0, 3, 0, 1, 0, + 4, 3, 0, 0, 2, 0, 1, 0, + 18, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 3, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 3, 0, 0, 3, 0, 1, 0, + 28, 3, 0, 0, 2, 0, 1, 0, + 19, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 19, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 3, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 24, 3, 0, 0, 3, 0, 1, 0, + 52, 3, 0, 0, 2, 0, 1, 0, + 20, 0, 0, 0, 15, 0, 0, 0, + 0, 0, 1, 0, 20, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 3, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 52, 3, 0, 0, 3, 0, 1, 0, + 64, 3, 0, 0, 2, 0, 1, 0, + 21, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 1, 0, 21, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 3, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 60, 3, 0, 0, 3, 0, 1, 0, + 72, 3, 0, 0, 2, 0, 1, 0, + 22, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 22, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 3, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 3, 0, 0, 3, 0, 1, 0, + 96, 3, 0, 0, 2, 0, 1, 0, + 115, 116, 97, 116, 117, 115, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 116, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 110, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 108, 116, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 112, 101, 101, 100, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 78, 69, 68, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 111, 108, 108, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 105, 116, 99, 104, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 101, 97, 100, 105, 110, 103, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 119, 97, 110, 100, 101, 114, 65, 110, + 103, 108, 101, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 114, 97, 99, 107, 65, 110, 103, + 108, 101, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 121, 114, 111, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 99, 101, 108, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 99, 117, 114, 97, 99, 121, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 63, 176, 115, 84, 98, 196, 61, 148, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 111, 117, 114, 99, 101, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 87, 246, 42, 37, 204, 211, 113, 200, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 105, 120, 77, 111, 110, 111, 84, + 105, 109, 101, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 87, 101, 101, 107, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 109, 101, 79, 102, 87, 101, + 101, 107, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 115, 105, 116, 105, 111, 110, + 69, 67, 69, 70, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 115, 101, 81, 117, 97, 116, + 69, 67, 69, 70, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 105, 116, 99, 104, 67, 97, 108, + 105, 98, 114, 97, 116, 105, 111, 110, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 97, 119, 67, 97, 108, 105, 98, + 114, 97, 116, 105, 111, 110, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 109, 117, 70, 114, 97, 109, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_b99b2bc7a57e8128 = b_b99b2bc7a57e8128.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_b99b2bc7a57e8128[] = { + &s_943dc4625473b03f, + &s_c871d3cc252af657, +}; +static const uint16_t m_b99b2bc7a57e8128[] = {12, 13, 3, 15, 16, 11, 8, 22, 1, 2, 7, 20, 19, 18, 6, 14, 4, 0, 17, 10, 5, 9, 21}; +static const uint16_t i_b99b2bc7a57e8128[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22}; +const ::capnp::_::RawSchema s_b99b2bc7a57e8128 = { + 0xb99b2bc7a57e8128, b_b99b2bc7a57e8128.words, 406, d_b99b2bc7a57e8128, m_b99b2bc7a57e8128, + 2, 23, i_b99b2bc7a57e8128, nullptr, nullptr, { &s_b99b2bc7a57e8128, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<159> b_943dc4625473b03f = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 63, 176, 115, 84, 98, 196, 61, 148, + 30, 0, 0, 0, 1, 0, 3, 0, + 40, 129, 126, 165, 199, 43, 155, 185, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 58, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 199, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 76, 105, 118, + 101, 76, 111, 99, 97, 116, 105, 111, + 110, 68, 97, 116, 97, 46, 65, 99, + 99, 117, 114, 97, 99, 121, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 32, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 0, 0, 0, 3, 0, 1, 0, + 236, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 233, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 0, 0, 0, 3, 0, 1, 0, + 4, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 1, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 1, 0, 0, 3, 0, 1, 0, + 12, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 1, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 1, 0, 0, 3, 0, 1, 0, + 20, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 1, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 1, 0, 0, 3, 0, 1, 0, + 28, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 1, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 28, 1, 0, 0, 3, 0, 1, 0, + 40, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 1, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 1, 0, 0, 3, 0, 1, 0, + 52, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 1, 0, 0, 210, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 56, 1, 0, 0, 3, 0, 1, 0, + 68, 1, 0, 0, 2, 0, 1, 0, + 112, 78, 69, 68, 69, 114, 114, 111, + 114, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 78, 69, 68, 69, 114, 114, 111, + 114, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 111, 108, 108, 69, 114, 114, 111, + 114, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 105, 116, 99, 104, 69, 114, 114, + 111, 114, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 101, 97, 100, 105, 110, 103, 69, + 114, 114, 111, 114, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 108, 108, 105, 112, 115, 111, 105, + 100, 83, 101, 109, 105, 77, 97, 106, + 111, 114, 69, 114, 114, 111, 114, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 108, 108, 105, 112, 115, 111, 105, + 100, 83, 101, 109, 105, 77, 105, 110, + 111, 114, 69, 114, 114, 111, 114, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 108, 108, 105, 112, 115, 111, 105, + 100, 79, 114, 105, 101, 110, 116, 97, + 116, 105, 111, 110, 69, 114, 114, 111, + 114, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_943dc4625473b03f = b_943dc4625473b03f.words; +#if !CAPNP_LITE +static const uint16_t m_943dc4625473b03f[] = {7, 5, 6, 4, 0, 3, 2, 1}; +static const uint16_t i_943dc4625473b03f[] = {0, 1, 2, 3, 4, 5, 6, 7}; +const ::capnp::_::RawSchema s_943dc4625473b03f = { + 0x943dc4625473b03f, b_943dc4625473b03f.words, 159, nullptr, m_943dc4625473b03f, + 0, 8, i_943dc4625473b03f, nullptr, nullptr, { &s_943dc4625473b03f, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<41> b_c871d3cc252af657 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 87, 246, 42, 37, 204, 211, 113, 200, + 30, 0, 0, 0, 2, 0, 0, 0, + 40, 129, 126, 165, 199, 43, 155, 185, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 90, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 127, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 76, 105, 118, + 101, 76, 111, 99, 97, 116, 105, 111, + 110, 68, 97, 116, 97, 46, 83, 101, + 110, 115, 111, 114, 83, 111, 117, 114, + 99, 101, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 20, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 53, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 49, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 112, 112, 108, 97, 110, 105, 120, + 0, 0, 0, 0, 0, 0, 0, 0, + 107, 97, 108, 109, 97, 110, 0, 0, + 111, 114, 98, 115, 108, 97, 109, 0, + 116, 105, 109, 105, 110, 103, 0, 0, + 100, 117, 109, 109, 121, 0, 0, 0, } +}; +::capnp::word const* const bp_c871d3cc252af657 = b_c871d3cc252af657.words; +#if !CAPNP_LITE +static const uint16_t m_c871d3cc252af657[] = {0, 4, 1, 2, 3}; +const ::capnp::_::RawSchema s_c871d3cc252af657 = { + 0xc871d3cc252af657, b_c871d3cc252af657.words, 41, nullptr, m_c871d3cc252af657, + 0, 5, nullptr, nullptr, nullptr, { &s_c871d3cc252af657, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(SensorSource_c871d3cc252af657, c871d3cc252af657); +static const ::capnp::_::AlignedData<118> b_d7700859ed1f5b76 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 118, 91, 31, 237, 89, 8, 112, 215, + 13, 0, 0, 0, 1, 0, 4, 0, + 99, 42, 156, 136, 196, 30, 239, 128, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 202, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 87, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 79, 114, 98, + 79, 100, 111, 109, 101, 116, 114, 121, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 24, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 0, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 152, 0, 0, 0, 3, 0, 1, 0, + 164, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 161, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 160, 0, 0, 0, 3, 0, 1, 0, + 172, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 169, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 164, 0, 0, 0, 3, 0, 1, 0, + 192, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 0, 0, 0, 3, 0, 1, 0, + 196, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 0, 0, 0, 3, 0, 1, 0, + 200, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 192, 0, 0, 0, 3, 0, 1, 0, + 220, 0, 0, 0, 2, 0, 1, 0, + 115, 116, 97, 114, 116, 77, 111, 110, + 111, 84, 105, 109, 101, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 110, 100, 77, 111, 110, 111, 84, + 105, 109, 101, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 114, 114, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 110, 108, 105, 101, 114, 115, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 97, 116, 99, 104, 101, 115, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_d7700859ed1f5b76 = b_d7700859ed1f5b76.words; +#if !CAPNP_LITE +static const uint16_t m_d7700859ed1f5b76[] = {1, 3, 2, 4, 5, 0}; +static const uint16_t i_d7700859ed1f5b76[] = {0, 1, 2, 3, 4, 5}; +const ::capnp::_::RawSchema s_d7700859ed1f5b76 = { + 0xd7700859ed1f5b76, b_d7700859ed1f5b76.words, 118, nullptr, m_d7700859ed1f5b76, + 0, 6, i_d7700859ed1f5b76, nullptr, nullptr, { &s_d7700859ed1f5b76, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<143> b_cd60164a8a0159ef = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 239, 89, 1, 138, 74, 22, 96, 205, + 13, 0, 0, 0, 1, 0, 2, 0, + 99, 42, 156, 136, 196, 30, 239, 128, + 5, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 202, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 143, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 79, 114, 98, + 70, 101, 97, 116, 117, 114, 101, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 28, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 0, 0, 0, 3, 0, 1, 0, + 192, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 0, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 0, 0, 0, 3, 0, 1, 0, + 212, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 0, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 0, 0, 0, 3, 0, 1, 0, + 232, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 228, 0, 0, 0, 3, 0, 1, 0, + 240, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 0, 0, 0, 3, 0, 1, 0, + 4, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 1, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 1, 0, 0, 3, 0, 1, 0, + 16, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 1, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 1, 0, 0, 3, 0, 1, 0, + 36, 1, 0, 0, 2, 0, 1, 0, + 116, 105, 109, 101, 115, 116, 97, 109, + 112, 69, 111, 102, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 115, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 115, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 115, 99, 114, 105, 112, 116, + 111, 114, 115, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 99, 116, 97, 118, 101, 115, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 109, 101, 115, 116, 97, 109, + 112, 76, 97, 115, 116, 69, 111, 102, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 97, 116, 99, 104, 101, 115, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_cd60164a8a0159ef = b_cd60164a8a0159ef.words; +#if !CAPNP_LITE +static const uint16_t m_cd60164a8a0159ef[] = {3, 6, 4, 0, 5, 1, 2}; +static const uint16_t i_cd60164a8a0159ef[] = {0, 1, 2, 3, 4, 5, 6}; +const ::capnp::_::RawSchema s_cd60164a8a0159ef = { + 0xcd60164a8a0159ef, b_cd60164a8a0159ef.words, 143, nullptr, m_cd60164a8a0159ef, + 0, 7, i_cd60164a8a0159ef, nullptr, nullptr, { &s_cd60164a8a0159ef, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<99> b_d500d30c5803fa4f = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 79, 250, 3, 88, 12, 211, 0, 213, + 13, 0, 0, 0, 1, 0, 4, 0, + 99, 42, 156, 136, 196, 30, 239, 128, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 2, 1, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 31, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 79, 114, 98, + 70, 101, 97, 116, 117, 114, 101, 115, + 83, 117, 109, 109, 97, 114, 121, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 20, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 0, 0, 0, 3, 0, 1, 0, + 136, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 0, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 136, 0, 0, 0, 3, 0, 1, 0, + 148, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 145, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 144, 0, 0, 0, 3, 0, 1, 0, + 156, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 152, 0, 0, 0, 3, 0, 1, 0, + 164, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 161, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 160, 0, 0, 0, 3, 0, 1, 0, + 172, 0, 0, 0, 2, 0, 1, 0, + 116, 105, 109, 101, 115, 116, 97, 109, + 112, 69, 111, 102, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 109, 101, 115, 116, 97, 109, + 112, 76, 97, 115, 116, 69, 111, 102, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 101, 97, 116, 117, 114, 101, 67, + 111, 117, 110, 116, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 97, 116, 99, 104, 67, 111, 117, + 110, 116, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 111, 109, 112, 117, 116, 101, 78, + 115, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_d500d30c5803fa4f = b_d500d30c5803fa4f.words; +#if !CAPNP_LITE +static const uint16_t m_d500d30c5803fa4f[] = {4, 2, 3, 0, 1}; +static const uint16_t i_d500d30c5803fa4f[] = {0, 1, 2, 3, 4}; +const ::capnp::_::RawSchema s_d500d30c5803fa4f = { + 0xd500d30c5803fa4f, b_d500d30c5803fa4f.words, 99, nullptr, m_d500d30c5803fa4f, + 0, 5, i_d500d30c5803fa4f, nullptr, nullptr, { &s_d500d30c5803fa4f, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<83> b_c8233c0345e27e24 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 36, 126, 226, 69, 3, 60, 35, 200, + 13, 0, 0, 0, 1, 0, 1, 0, + 99, 42, 156, 136, 196, 30, 239, 128, + 3, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 202, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 231, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 79, 114, 98, + 75, 101, 121, 70, 114, 97, 109, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 0, 0, 0, 3, 0, 1, 0, + 104, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 0, 0, 0, 3, 0, 1, 0, + 108, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 0, 0, 0, 3, 0, 1, 0, + 128, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 0, 0, 0, 3, 0, 1, 0, + 136, 0, 0, 0, 2, 0, 1, 0, + 105, 100, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 115, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 71, 52, 152, 36, 213, 187, 91, 194, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 112, 111, 115, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 71, 52, 152, 36, 213, 187, 91, 194, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 115, 99, 114, 105, 112, 116, + 111, 114, 115, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_c8233c0345e27e24 = b_c8233c0345e27e24.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_c8233c0345e27e24[] = { + &s_c25bbbd524983447, +}; +static const uint16_t m_c8233c0345e27e24[] = {3, 2, 0, 1}; +static const uint16_t i_c8233c0345e27e24[] = {0, 1, 2, 3}; +const ::capnp::_::RawSchema s_c8233c0345e27e24 = { + 0xc8233c0345e27e24, b_c8233c0345e27e24.words, 83, d_c8233c0345e27e24, m_c8233c0345e27e24, + 1, 4, i_c8233c0345e27e24, nullptr, nullptr, { &s_c8233c0345e27e24, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<95> b_92e21bb7ea38793a = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 58, 121, 56, 234, 183, 27, 226, 146, + 13, 0, 0, 0, 1, 0, 0, 0, + 99, 42, 156, 136, 196, 30, 239, 128, + 4, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 226, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 231, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 75, 97, 108, + 109, 97, 110, 79, 100, 111, 109, 101, + 116, 114, 121, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 0, 0, 0, 3, 0, 1, 0, + 120, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 0, 0, 0, 3, 0, 1, 0, + 140, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 137, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 136, 0, 0, 0, 3, 0, 1, 0, + 164, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 161, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 156, 0, 0, 0, 3, 0, 1, 0, + 184, 0, 0, 0, 2, 0, 1, 0, + 116, 114, 97, 110, 115, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 111, 116, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 114, 97, 110, 115, 83, 116, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 111, 116, 83, 116, 100, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_92e21bb7ea38793a = b_92e21bb7ea38793a.words; +#if !CAPNP_LITE +static const uint16_t m_92e21bb7ea38793a[] = {1, 3, 0, 2}; +static const uint16_t i_92e21bb7ea38793a[] = {0, 1, 2, 3}; +const ::capnp::_::RawSchema s_92e21bb7ea38793a = { + 0x92e21bb7ea38793a, b_92e21bb7ea38793a.words, 95, nullptr, m_92e21bb7ea38793a, + 0, 4, i_92e21bb7ea38793a, nullptr, nullptr, { &s_92e21bb7ea38793a, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<92> b_9b326d4e436afec7 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 199, 254, 106, 67, 78, 109, 50, 155, + 13, 0, 0, 0, 1, 0, 2, 0, + 99, 42, 156, 136, 196, 30, 239, 128, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 226, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 231, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 79, 114, 98, + 79, 98, 115, 101, 114, 118, 97, 116, + 105, 111, 110, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 0, 0, 0, 3, 0, 1, 0, + 112, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 0, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 0, 0, 0, 3, 0, 1, 0, + 140, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 137, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 136, 0, 0, 0, 3, 0, 1, 0, + 164, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 161, 0, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 160, 0, 0, 0, 3, 0, 1, 0, + 172, 0, 0, 0, 2, 0, 1, 0, + 111, 98, 115, 101, 114, 118, 97, 116, + 105, 111, 110, 77, 111, 110, 111, 84, + 105, 109, 101, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 111, 114, 109, 97, 108, 105, 122, + 101, 100, 67, 111, 111, 114, 100, 105, + 110, 97, 116, 101, 115, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 99, 97, 116, 105, 111, 110, + 69, 67, 69, 70, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 97, 116, 99, 104, 68, 105, 115, + 116, 97, 110, 99, 101, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_9b326d4e436afec7 = b_9b326d4e436afec7.words; +#if !CAPNP_LITE +static const uint16_t m_9b326d4e436afec7[] = {2, 3, 1, 0}; +static const uint16_t i_9b326d4e436afec7[] = {0, 1, 2, 3}; +const ::capnp::_::RawSchema s_9b326d4e436afec7 = { + 0x9b326d4e436afec7, b_9b326d4e436afec7.words, 92, nullptr, m_9b326d4e436afec7, + 0, 4, i_9b326d4e436afec7, nullptr, nullptr, { &s_9b326d4e436afec7, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<91> b_8fdfadb254ea867a = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 122, 134, 234, 84, 178, 173, 223, 143, + 13, 0, 0, 0, 1, 0, 1, 0, + 99, 42, 156, 136, 196, 30, 239, 128, + 3, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 10, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 231, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 67, 97, 108, + 105, 98, 114, 97, 116, 105, 111, 110, + 70, 101, 97, 116, 117, 114, 101, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 0, 0, 0, 3, 0, 1, 0, + 104, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 0, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 0, 0, 0, 3, 0, 1, 0, + 124, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 0, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 0, 0, 0, 3, 0, 1, 0, + 144, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 136, 0, 0, 0, 3, 0, 1, 0, + 164, 0, 0, 0, 2, 0, 1, 0, + 102, 114, 97, 109, 101, 73, 100, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 48, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 49, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 116, 117, 115, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_8fdfadb254ea867a = b_8fdfadb254ea867a.words; +#if !CAPNP_LITE +static const uint16_t m_8fdfadb254ea867a[] = {0, 1, 2, 3}; +static const uint16_t i_8fdfadb254ea867a[] = {0, 1, 2, 3}; +const ::capnp::_::RawSchema s_8fdfadb254ea867a = { + 0x8fdfadb254ea867a, b_8fdfadb254ea867a.words, 91, nullptr, m_8fdfadb254ea867a, + 0, 4, i_8fdfadb254ea867a, nullptr, nullptr, { &s_8fdfadb254ea867a, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<52> b_bd8822120928120c = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 12, 18, 40, 9, 18, 34, 136, 189, + 13, 0, 0, 0, 1, 0, 1, 0, + 99, 42, 156, 136, 196, 30, 239, 128, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 186, 0, 0, 0, + 29, 0, 0, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 78, 97, 118, + 83, 116, 97, 116, 117, 115, 0, 0, + 4, 0, 0, 0, 1, 0, 1, 0, + 20, 120, 204, 202, 114, 214, 124, 206, + 1, 0, 0, 0, 66, 0, 0, 0, + 65, 100, 100, 114, 101, 115, 115, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 0, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 0, 0, 0, 3, 0, 1, 0, + 60, 0, 0, 0, 2, 0, 1, 0, + 105, 115, 78, 97, 118, 105, 103, 97, + 116, 105, 110, 103, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 114, 114, 101, 110, 116, 65, + 100, 100, 114, 101, 115, 115, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 20, 120, 204, 202, 114, 214, 124, 206, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_bd8822120928120c = b_bd8822120928120c.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_bd8822120928120c[] = { + &s_ce7cd672cacc7814, +}; +static const uint16_t m_bd8822120928120c[] = {1, 0}; +static const uint16_t i_bd8822120928120c[] = {0, 1}; +const ::capnp::_::RawSchema s_bd8822120928120c = { + 0xbd8822120928120c, b_bd8822120928120c.words, 52, d_bd8822120928120c, m_bd8822120928120c, + 1, 2, i_bd8822120928120c, nullptr, nullptr, { &s_bd8822120928120c, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<153> b_ce7cd672cacc7814 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 20, 120, 204, 202, 114, 214, 124, 206, + 23, 0, 0, 0, 1, 0, 2, 0, + 12, 18, 40, 9, 18, 34, 136, 189, + 7, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 250, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 255, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 78, 97, 118, + 83, 116, 97, 116, 117, 115, 46, 65, + 100, 100, 114, 101, 115, 115, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 36, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 0, 0, 0, 3, 0, 1, 0, + 244, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 236, 0, 0, 0, 3, 0, 1, 0, + 248, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 245, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 0, 0, 0, 3, 0, 1, 0, + 252, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 249, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 244, 0, 0, 0, 3, 0, 1, 0, + 0, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 253, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 248, 0, 0, 0, 3, 0, 1, 0, + 4, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 252, 0, 0, 0, 3, 0, 1, 0, + 8, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 1, 0, 0, 3, 0, 1, 0, + 12, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 1, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 1, 0, 0, 3, 0, 1, 0, + 16, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 1, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 1, 0, 0, 3, 0, 1, 0, + 20, 1, 0, 0, 2, 0, 1, 0, + 116, 105, 116, 108, 101, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 116, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 110, 103, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 111, 117, 115, 101, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 100, 100, 114, 101, 115, 115, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 114, 101, 101, 116, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 105, 116, 121, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 116, 101, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 111, 117, 110, 116, 114, 121, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_ce7cd672cacc7814 = b_ce7cd672cacc7814.words; +#if !CAPNP_LITE +static const uint16_t m_ce7cd672cacc7814[] = {4, 6, 8, 3, 1, 2, 7, 5, 0}; +static const uint16_t i_ce7cd672cacc7814[] = {0, 1, 2, 3, 4, 5, 6, 7, 8}; +const ::capnp::_::RawSchema s_ce7cd672cacc7814 = { + 0xce7cd672cacc7814, b_ce7cd672cacc7814.words, 153, nullptr, m_ce7cd672cacc7814, + 0, 9, i_ce7cd672cacc7814, nullptr, nullptr, { &s_ce7cd672cacc7814, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<75> b_db98be6565516acb = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 203, 106, 81, 101, 101, 190, 152, 219, + 13, 0, 0, 0, 1, 0, 1, 0, + 99, 42, 156, 136, 196, 30, 239, 128, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 186, 0, 0, 0, + 29, 0, 0, 0, 39, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 78, 97, 118, + 85, 112, 100, 97, 116, 101, 0, 0, + 8, 0, 0, 0, 1, 0, 1, 0, + 155, 187, 173, 124, 24, 249, 174, 158, + 9, 0, 0, 0, 58, 0, 0, 0, + 63, 218, 215, 196, 79, 155, 179, 165, + 5, 0, 0, 0, 66, 0, 0, 0, + 76, 97, 116, 76, 110, 103, 0, 0, + 83, 101, 103, 109, 101, 110, 116, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 0, 0, 0, 3, 0, 1, 0, + 80, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 0, 0, 0, 3, 0, 1, 0, + 88, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 85, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 84, 0, 0, 0, 3, 0, 1, 0, + 112, 0, 0, 0, 2, 0, 1, 0, + 105, 115, 78, 97, 118, 105, 103, 97, + 116, 105, 110, 103, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 114, 83, 101, 103, 109, 101, + 110, 116, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 101, 103, 109, 101, 110, 116, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 63, 218, 215, 196, 79, 155, 179, 165, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_db98be6565516acb = b_db98be6565516acb.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_db98be6565516acb[] = { + &s_a5b39b4fc4d7da3f, +}; +static const uint16_t m_db98be6565516acb[] = {1, 0, 2}; +static const uint16_t i_db98be6565516acb[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_db98be6565516acb = { + 0xdb98be6565516acb, b_db98be6565516acb.words, 75, d_db98be6565516acb, m_db98be6565516acb, + 1, 3, i_db98be6565516acb, nullptr, nullptr, { &s_db98be6565516acb, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<48> b_9eaef9187cadbb9b = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 155, 187, 173, 124, 24, 249, 174, 158, + 23, 0, 0, 0, 1, 0, 2, 0, + 203, 106, 81, 101, 101, 190, 152, 219, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 242, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 78, 97, 118, + 85, 112, 100, 97, 116, 101, 46, 76, + 97, 116, 76, 110, 103, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 108, 97, 116, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 110, 103, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_9eaef9187cadbb9b = b_9eaef9187cadbb9b.words; +#if !CAPNP_LITE +static const uint16_t m_9eaef9187cadbb9b[] = {0, 1}; +static const uint16_t i_9eaef9187cadbb9b[] = {0, 1}; +const ::capnp::_::RawSchema s_9eaef9187cadbb9b = { + 0x9eaef9187cadbb9b, b_9eaef9187cadbb9b.words, 48, nullptr, m_9eaef9187cadbb9b, + 0, 2, i_9eaef9187cadbb9b, nullptr, nullptr, { &s_9eaef9187cadbb9b, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<150> b_a5b39b4fc4d7da3f = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 63, 218, 215, 196, 79, 155, 179, 165, + 23, 0, 0, 0, 1, 0, 3, 0, + 203, 106, 81, 101, 101, 190, 152, 219, + 3, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 250, 0, 0, 0, + 33, 0, 0, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 199, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 78, 97, 118, + 85, 112, 100, 97, 116, 101, 46, 83, + 101, 103, 109, 101, 110, 116, 0, 0, + 4, 0, 0, 0, 1, 0, 1, 0, + 111, 36, 81, 116, 99, 122, 65, 197, + 1, 0, 0, 0, 98, 0, 0, 0, + 73, 110, 115, 116, 114, 117, 99, 116, + 105, 111, 110, 0, 0, 0, 0, 0, + 32, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 0, 0, 0, 3, 0, 1, 0, + 216, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 0, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 0, 0, 0, 3, 0, 1, 0, + 220, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 217, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 0, 0, 0, 3, 0, 1, 0, + 228, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 225, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 224, 0, 0, 0, 3, 0, 1, 0, + 236, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 233, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 0, 0, 0, 3, 0, 1, 0, + 244, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 236, 0, 0, 0, 3, 0, 1, 0, + 248, 0, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 245, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 244, 0, 0, 0, 3, 0, 1, 0, + 0, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 253, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 248, 0, 0, 0, 3, 0, 1, 0, + 20, 1, 0, 0, 2, 0, 1, 0, + 102, 114, 111, 109, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 155, 187, 173, 124, 24, 249, 174, 158, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 111, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 155, 187, 173, 124, 24, 249, 174, 158, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 112, 100, 97, 116, 101, 84, 105, + 109, 101, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 105, 115, 116, 97, 110, 99, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 114, 111, 115, 115, 84, 105, 109, + 101, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 120, 105, 116, 78, 111, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 110, 115, 116, 114, 117, 99, 116, + 105, 111, 110, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 111, 36, 81, 116, 99, 122, 65, 197, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 97, 114, 116, 115, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 155, 187, 173, 124, 24, 249, 174, 158, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_a5b39b4fc4d7da3f = b_a5b39b4fc4d7da3f.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_a5b39b4fc4d7da3f[] = { + &s_9eaef9187cadbb9b, + &s_c5417a637451246f, +}; +static const uint16_t m_a5b39b4fc4d7da3f[] = {4, 3, 5, 0, 6, 7, 1, 2}; +static const uint16_t i_a5b39b4fc4d7da3f[] = {0, 1, 2, 3, 4, 5, 6, 7}; +const ::capnp::_::RawSchema s_a5b39b4fc4d7da3f = { + 0xa5b39b4fc4d7da3f, b_a5b39b4fc4d7da3f.words, 150, d_a5b39b4fc4d7da3f, m_a5b39b4fc4d7da3f, + 2, 8, i_a5b39b4fc4d7da3f, nullptr, nullptr, { &s_a5b39b4fc4d7da3f, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<117> b_c5417a637451246f = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 111, 36, 81, 116, 99, 122, 65, 197, + 31, 0, 0, 0, 2, 0, 0, 0, + 63, 218, 215, 196, 79, 155, 179, 165, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 90, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 231, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 78, 97, 118, + 85, 112, 100, 97, 116, 101, 46, 83, + 101, 103, 109, 101, 110, 116, 46, 73, + 110, 115, 116, 114, 117, 99, 116, 105, + 111, 110, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 80, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 233, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 229, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 225, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 221, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 217, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 213, 0, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 213, 0, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 209, 0, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 209, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 201, 0, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 201, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 193, 0, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 193, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 185, 0, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 181, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 173, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 165, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 0, 0, 0, 0, 0, 0, 0, + 161, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 18, 0, 0, 0, 0, 0, 0, 0, + 157, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 19, 0, 0, 0, 0, 0, 0, 0, + 149, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 117, 114, 110, 76, 101, 102, 116, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 117, 114, 110, 82, 105, 103, 104, + 116, 0, 0, 0, 0, 0, 0, 0, + 107, 101, 101, 112, 76, 101, 102, 116, + 0, 0, 0, 0, 0, 0, 0, 0, + 107, 101, 101, 112, 82, 105, 103, 104, + 116, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 114, 97, 105, 103, 104, 116, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 111, 117, 110, 100, 97, 98, 111, + 117, 116, 69, 120, 105, 116, 78, 117, + 109, 98, 101, 114, 0, 0, 0, 0, + 114, 111, 117, 110, 100, 97, 98, 111, + 117, 116, 69, 120, 105, 116, 0, 0, + 114, 111, 117, 110, 100, 97, 98, 111, + 117, 116, 84, 117, 114, 110, 76, 101, + 102, 116, 0, 0, 0, 0, 0, 0, + 117, 110, 107, 110, 56, 0, 0, 0, + 114, 111, 117, 110, 100, 97, 98, 111, + 117, 116, 83, 116, 114, 97, 105, 103, + 104, 116, 0, 0, 0, 0, 0, 0, + 117, 110, 107, 110, 49, 48, 0, 0, + 114, 111, 117, 110, 100, 97, 98, 111, + 117, 116, 84, 117, 114, 110, 82, 105, + 103, 104, 116, 0, 0, 0, 0, 0, + 117, 110, 107, 110, 49, 50, 0, 0, + 114, 111, 117, 110, 100, 97, 98, 111, + 117, 116, 85, 116, 117, 114, 110, 0, + 117, 110, 107, 110, 49, 52, 0, 0, + 97, 114, 114, 105, 118, 101, 0, 0, + 101, 120, 105, 116, 76, 101, 102, 116, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 120, 105, 116, 82, 105, 103, 104, + 116, 0, 0, 0, 0, 0, 0, 0, + 117, 110, 107, 110, 49, 56, 0, 0, + 117, 116, 117, 114, 110, 0, 0, 0, } +}; +::capnp::word const* const bp_c5417a637451246f = b_c5417a637451246f.words; +#if !CAPNP_LITE +static const uint16_t m_c5417a637451246f[] = {15, 16, 17, 2, 3, 6, 5, 9, 7, 11, 13, 4, 0, 1, 10, 12, 14, 18, 8, 19}; +const ::capnp::_::RawSchema s_c5417a637451246f = { + 0xc5417a637451246f, b_c5417a637451246f.words, 117, nullptr, m_c5417a637451246f, + 0, 20, nullptr, nullptr, nullptr, { &s_c5417a637451246f, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(Instruction_c5417a637451246f, c5417a637451246f); +static const ::capnp::_::AlignedData<86> b_acfa74a094e62626 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 38, 38, 230, 148, 160, 116, 250, 172, + 13, 0, 0, 0, 1, 0, 2, 0, + 99, 42, 156, 136, 196, 30, 239, 128, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 210, 0, 0, 0, + 33, 0, 0, 0, 39, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 53, 0, 0, 0, 231, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 84, 114, 97, + 102, 102, 105, 99, 69, 118, 101, 110, + 116, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 1, 0, 1, 0, + 75, 191, 53, 52, 37, 117, 93, 216, + 9, 0, 0, 0, 42, 0, 0, 0, + 73, 203, 92, 22, 114, 206, 246, 166, + 5, 0, 0, 0, 58, 0, 0, 0, + 84, 121, 112, 101, 0, 0, 0, 0, + 65, 99, 116, 105, 111, 110, 0, 0, + 16, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 0, 0, 0, 3, 0, 1, 0, + 104, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 0, 0, 0, 3, 0, 1, 0, + 112, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 0, 0, 0, 3, 0, 1, 0, + 116, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 64, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 0, 0, 0, 3, 0, 1, 0, + 124, 0, 0, 0, 2, 0, 1, 0, + 116, 121, 112, 101, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 75, 191, 53, 52, 37, 117, 93, 216, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 105, 115, 116, 97, 110, 99, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 116, 105, 111, 110, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 73, 203, 92, 22, 114, 206, 246, 166, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 101, 115, 117, 109, 105, 110, 103, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_acfa74a094e62626 = b_acfa74a094e62626.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_acfa74a094e62626[] = { + &s_a6f6ce72165ccb49, + &s_d85d75253435bf4b, +}; +static const uint16_t m_acfa74a094e62626[] = {2, 1, 3, 0}; +static const uint16_t i_acfa74a094e62626[] = {0, 1, 2, 3}; +const ::capnp::_::RawSchema s_acfa74a094e62626 = { + 0xacfa74a094e62626, b_acfa74a094e62626.words, 86, d_acfa74a094e62626, m_acfa74a094e62626, + 2, 4, i_acfa74a094e62626, nullptr, nullptr, { &s_acfa74a094e62626, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<43> b_d85d75253435bf4b = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 75, 191, 53, 52, 37, 117, 93, 216, + 26, 0, 0, 0, 2, 0, 0, 0, + 38, 38, 230, 148, 160, 116, 250, 172, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 250, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 127, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 84, 114, 97, + 102, 102, 105, 99, 69, 118, 101, 110, + 116, 46, 84, 121, 112, 101, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 20, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 53, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 49, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 111, 112, 83, 105, 103, 110, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 105, 103, 104, 116, 82, 101, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 105, 103, 104, 116, 89, 101, 108, + 108, 111, 119, 0, 0, 0, 0, 0, + 108, 105, 103, 104, 116, 71, 114, 101, + 101, 110, 0, 0, 0, 0, 0, 0, + 115, 116, 111, 112, 76, 105, 103, 104, + 116, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_d85d75253435bf4b = b_d85d75253435bf4b.words; +#if !CAPNP_LITE +static const uint16_t m_d85d75253435bf4b[] = {3, 1, 2, 4, 0}; +const ::capnp::_::RawSchema s_d85d75253435bf4b = { + 0xd85d75253435bf4b, b_d85d75253435bf4b.words, 43, nullptr, m_d85d75253435bf4b, + 0, 5, nullptr, nullptr, nullptr, { &s_d85d75253435bf4b, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(Type_d85d75253435bf4b, d85d75253435bf4b); +static const ::capnp::_::AlignedData<36> b_a6f6ce72165ccb49 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 73, 203, 92, 22, 114, 206, 246, 166, + 26, 0, 0, 0, 2, 0, 0, 0, + 38, 38, 230, 148, 160, 116, 250, 172, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 10, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 103, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 84, 114, 97, + 102, 102, 105, 99, 69, 118, 101, 110, + 116, 46, 65, 99, 116, 105, 111, 110, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 17, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 111, 110, 101, 0, 0, 0, 0, + 121, 105, 101, 108, 100, 0, 0, 0, + 115, 116, 111, 112, 0, 0, 0, 0, + 114, 101, 115, 117, 109, 101, 82, 101, + 97, 100, 121, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_a6f6ce72165ccb49 = b_a6f6ce72165ccb49.words; +#if !CAPNP_LITE +static const uint16_t m_a6f6ce72165ccb49[] = {0, 3, 2, 1}; +const ::capnp::_::RawSchema s_a6f6ce72165ccb49 = { + 0xa6f6ce72165ccb49, b_a6f6ce72165ccb49.words, 36, nullptr, m_a6f6ce72165ccb49, + 0, 4, nullptr, nullptr, nullptr, { &s_a6f6ce72165ccb49, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(Action_a6f6ce72165ccb49, a6f6ce72165ccb49); +static const ::capnp::_::AlignedData<60> b_dfdf30d03fc485bd = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 189, 133, 196, 63, 208, 48, 223, 223, + 13, 0, 0, 0, 1, 0, 1, 0, + 99, 42, 156, 136, 196, 30, 239, 128, + 1, 0, 7, 0, 0, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 202, 0, 0, 0, + 33, 0, 0, 0, 39, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 65, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 65, 110, 100, + 114, 111, 105, 100, 71, 110, 115, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 1, 0, 1, 0, + 205, 214, 40, 244, 212, 16, 7, 162, + 9, 0, 0, 0, 106, 0, 0, 0, + 78, 253, 149, 48, 8, 123, 81, 226, + 9, 0, 0, 0, 146, 0, 0, 0, + 77, 101, 97, 115, 117, 114, 101, 109, + 101, 110, 116, 115, 0, 0, 0, 0, + 78, 97, 118, 105, 103, 97, 116, 105, + 111, 110, 77, 101, 115, 115, 97, 103, + 101, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 255, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 254, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 0, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 52, 0, 0, 0, 3, 0, 1, 0, + 64, 0, 0, 0, 2, 0, 1, 0, + 109, 101, 97, 115, 117, 114, 101, 109, + 101, 110, 116, 115, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 205, 214, 40, 244, 212, 16, 7, 162, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 97, 118, 105, 103, 97, 116, 105, + 111, 110, 77, 101, 115, 115, 97, 103, + 101, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 78, 253, 149, 48, 8, 123, 81, 226, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_dfdf30d03fc485bd = b_dfdf30d03fc485bd.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_dfdf30d03fc485bd[] = { + &s_a20710d4f428d6cd, + &s_e2517b083095fd4e, +}; +static const uint16_t m_dfdf30d03fc485bd[] = {0, 1}; +static const uint16_t i_dfdf30d03fc485bd[] = {0, 1}; +const ::capnp::_::RawSchema s_dfdf30d03fc485bd = { + 0xdfdf30d03fc485bd, b_dfdf30d03fc485bd.words, 60, d_dfdf30d03fc485bd, m_dfdf30d03fc485bd, + 2, 2, i_dfdf30d03fc485bd, nullptr, nullptr, { &s_dfdf30d03fc485bd, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<61> b_a20710d4f428d6cd = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 205, 214, 40, 244, 212, 16, 7, 162, + 25, 0, 0, 0, 1, 0, 0, 0, + 189, 133, 196, 63, 208, 48, 223, 223, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 50, 1, 0, 0, + 37, 0, 0, 0, 39, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 65, 110, 100, + 114, 111, 105, 100, 71, 110, 115, 115, + 46, 77, 101, 97, 115, 117, 114, 101, + 109, 101, 110, 116, 115, 0, 0, 0, + 8, 0, 0, 0, 1, 0, 1, 0, + 80, 244, 56, 58, 69, 123, 226, 160, + 9, 0, 0, 0, 50, 0, 0, 0, + 77, 97, 119, 125, 113, 191, 73, 217, + 5, 0, 0, 0, 98, 0, 0, 0, + 67, 108, 111, 99, 107, 0, 0, 0, + 77, 101, 97, 115, 117, 114, 101, 109, + 101, 110, 116, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 3, 0, 1, 0, + 72, 0, 0, 0, 2, 0, 1, 0, + 99, 108, 111, 99, 107, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 80, 244, 56, 58, 69, 123, 226, 160, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 101, 97, 115, 117, 114, 101, 109, + 101, 110, 116, 115, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 77, 97, 119, 125, 113, 191, 73, 217, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_a20710d4f428d6cd = b_a20710d4f428d6cd.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_a20710d4f428d6cd[] = { + &s_a0e27b453a38f450, + &s_d949bf717d77614d, +}; +static const uint16_t m_a20710d4f428d6cd[] = {0, 1}; +static const uint16_t i_a20710d4f428d6cd[] = {0, 1}; +const ::capnp::_::RawSchema s_a20710d4f428d6cd = { + 0xa20710d4f428d6cd, b_a20710d4f428d6cd.words, 61, d_a20710d4f428d6cd, m_a20710d4f428d6cd, + 2, 2, i_a20710d4f428d6cd, nullptr, nullptr, { &s_a20710d4f428d6cd, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<290> b_a0e27b453a38f450 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 80, 244, 56, 58, 69, 123, 226, 160, + 38, 0, 0, 0, 1, 0, 9, 0, + 205, 214, 40, 244, 212, 16, 7, 162, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 98, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 135, 3, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 65, 110, 100, + 114, 111, 105, 100, 71, 110, 115, 115, + 46, 77, 101, 97, 115, 117, 114, 101, + 109, 101, 110, 116, 115, 46, 67, 108, + 111, 99, 107, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 64, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 1, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 1, 0, 0, 3, 0, 1, 0, + 188, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 1, 0, 0, 2, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 192, 1, 0, 0, 3, 0, 1, 0, + 204, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 96, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 1, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 1, 0, 0, 3, 0, 1, 0, + 216, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 1, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 1, 0, 0, 3, 0, 1, 0, + 228, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 97, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 225, 1, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 224, 1, 0, 0, 3, 0, 1, 0, + 236, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 233, 1, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 1, 0, 0, 3, 0, 1, 0, + 244, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 1, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 244, 1, 0, 0, 3, 0, 1, 0, + 0, 2, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 253, 1, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 252, 1, 0, 0, 3, 0, 1, 0, + 8, 2, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 99, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 2, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 2, 0, 0, 3, 0, 1, 0, + 16, 2, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 2, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 2, 0, 0, 3, 0, 1, 0, + 24, 2, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 100, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 2, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 24, 2, 0, 0, 3, 0, 1, 0, + 36, 2, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 2, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 2, 0, 0, 3, 0, 1, 0, + 48, 2, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 101, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 2, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 2, 0, 0, 3, 0, 1, 0, + 60, 2, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 57, 2, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 60, 2, 0, 0, 3, 0, 1, 0, + 72, 2, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 102, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 2, 0, 0, 18, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 80, 2, 0, 0, 3, 0, 1, 0, + 92, 2, 0, 0, 2, 0, 1, 0, + 15, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 15, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 89, 2, 0, 0, 250, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 2, 0, 0, 3, 0, 1, 0, + 108, 2, 0, 0, 2, 0, 1, 0, + 116, 105, 109, 101, 78, 97, 110, 111, + 115, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 97, 114, 100, 119, 97, 114, 101, + 67, 108, 111, 99, 107, 68, 105, 115, + 99, 111, 110, 116, 105, 110, 117, 105, + 116, 121, 67, 111, 117, 110, 116, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 97, 115, 84, 105, 109, 101, 85, + 110, 99, 101, 114, 116, 97, 105, 110, + 116, 121, 78, 97, 110, 111, 115, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 109, 101, 85, 110, 99, 101, + 114, 116, 97, 105, 110, 116, 121, 78, + 97, 110, 111, 115, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 97, 115, 76, 101, 97, 112, 83, + 101, 99, 111, 110, 100, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 97, 112, 83, 101, 99, 111, + 110, 100, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 97, 115, 70, 117, 108, 108, 66, + 105, 97, 115, 78, 97, 110, 111, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 117, 108, 108, 66, 105, 97, 115, + 78, 97, 110, 111, 115, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 97, 115, 66, 105, 97, 115, 78, + 97, 110, 111, 115, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 105, 97, 115, 78, 97, 110, 111, + 115, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 97, 115, 66, 105, 97, 115, 85, + 110, 99, 101, 114, 116, 97, 105, 110, + 116, 121, 78, 97, 110, 111, 115, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 105, 97, 115, 85, 110, 99, 101, + 114, 116, 97, 105, 110, 116, 121, 78, + 97, 110, 111, 115, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 97, 115, 68, 114, 105, 102, 116, + 78, 97, 110, 111, 115, 80, 101, 114, + 83, 101, 99, 111, 110, 100, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 114, 105, 102, 116, 78, 97, 110, + 111, 115, 80, 101, 114, 83, 101, 99, + 111, 110, 100, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 97, 115, 68, 114, 105, 102, 116, + 85, 110, 99, 101, 114, 116, 97, 105, + 110, 116, 121, 78, 97, 110, 111, 115, + 80, 101, 114, 83, 101, 99, 111, 110, + 100, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 114, 105, 102, 116, 85, 110, 99, + 101, 114, 116, 97, 105, 110, 116, 121, + 78, 97, 110, 111, 115, 80, 101, 114, + 83, 101, 99, 111, 110, 100, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_a0e27b453a38f450 = b_a0e27b453a38f450.words; +#if !CAPNP_LITE +static const uint16_t m_a0e27b453a38f450[] = {9, 11, 13, 15, 7, 1, 8, 10, 12, 14, 6, 4, 2, 5, 0, 3}; +static const uint16_t i_a0e27b453a38f450[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15}; +const ::capnp::_::RawSchema s_a0e27b453a38f450 = { + 0xa0e27b453a38f450, b_a0e27b453a38f450.words, 290, nullptr, m_a0e27b453a38f450, + 0, 16, i_a0e27b453a38f450, nullptr, nullptr, { &s_a0e27b453a38f450, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<420> b_d949bf717d77614d = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 77, 97, 119, 125, 113, 191, 73, 217, + 38, 0, 0, 0, 1, 0, 15, 0, + 205, 214, 40, 244, 212, 16, 7, 162, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 146, 1, 0, 0, + 45, 0, 0, 0, 55, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 89, 0, 0, 0, 15, 5, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 65, 110, 100, + 114, 111, 105, 100, 71, 110, 115, 115, + 46, 77, 101, 97, 115, 117, 114, 101, + 109, 101, 110, 116, 115, 46, 77, 101, + 97, 115, 117, 114, 101, 109, 101, 110, + 116, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 1, 0, 1, 0, + 251, 95, 235, 13, 255, 243, 241, 158, + 17, 0, 0, 0, 114, 0, 0, 0, + 114, 45, 225, 220, 10, 73, 185, 203, + 17, 0, 0, 0, 50, 0, 0, 0, + 168, 202, 212, 49, 98, 123, 78, 192, + 13, 0, 0, 0, 154, 0, 0, 0, + 67, 111, 110, 115, 116, 101, 108, 108, + 97, 116, 105, 111, 110, 0, 0, 0, + 83, 116, 97, 116, 101, 0, 0, 0, + 77, 117, 108, 116, 105, 112, 97, 116, + 104, 73, 110, 100, 105, 99, 97, 116, + 111, 114, 0, 0, 0, 0, 0, 0, + 92, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 2, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 2, 0, 0, 3, 0, 1, 0, + 124, 2, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 2, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 2, 0, 0, 3, 0, 1, 0, + 132, 2, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 129, 2, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 128, 2, 0, 0, 3, 0, 1, 0, + 140, 2, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 137, 2, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 132, 2, 0, 0, 3, 0, 1, 0, + 144, 2, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 2, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 144, 2, 0, 0, 3, 0, 1, 0, + 156, 2, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 2, 0, 0, 250, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 160, 2, 0, 0, 3, 0, 1, 0, + 172, 2, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 169, 2, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 164, 2, 0, 0, 3, 0, 1, 0, + 176, 2, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 173, 2, 0, 0, 250, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 2, 0, 0, 3, 0, 1, 0, + 192, 2, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 2, 0, 0, 82, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 2, 0, 0, 3, 0, 1, 0, + 216, 2, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 2, 0, 0, 218, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 220, 2, 0, 0, 3, 0, 1, 0, + 232, 2, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 2, 0, 0, 226, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 236, 2, 0, 0, 3, 0, 1, 0, + 248, 2, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 245, 2, 0, 0, 58, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 3, 0, 0, 3, 0, 1, 0, + 12, 3, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 48, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 3, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 3, 0, 0, 3, 0, 1, 0, + 24, 3, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 20, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 3, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 24, 3, 0, 0, 3, 0, 1, 0, + 36, 3, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 49, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 3, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 3, 0, 0, 3, 0, 1, 0, + 48, 3, 0, 0, 2, 0, 1, 0, + 15, 0, 0, 0, 11, 0, 0, 0, + 0, 0, 1, 0, 15, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 3, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 3, 0, 0, 3, 0, 1, 0, + 56, 3, 0, 0, 2, 0, 1, 0, + 16, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 1, 0, 16, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 53, 3, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 52, 3, 0, 0, 3, 0, 1, 0, + 64, 3, 0, 0, 2, 0, 1, 0, + 17, 0, 0, 0, 12, 0, 0, 0, + 0, 0, 1, 0, 17, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 3, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 60, 3, 0, 0, 3, 0, 1, 0, + 72, 3, 0, 0, 2, 0, 1, 0, + 18, 0, 0, 0, 51, 0, 0, 0, + 0, 0, 1, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 3, 0, 0, 218, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 3, 0, 0, 3, 0, 1, 0, + 88, 3, 0, 0, 2, 0, 1, 0, + 19, 0, 0, 0, 13, 0, 0, 0, + 0, 0, 1, 0, 19, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 85, 3, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 88, 3, 0, 0, 3, 0, 1, 0, + 100, 3, 0, 0, 2, 0, 1, 0, + 20, 0, 0, 0, 52, 0, 0, 0, + 0, 0, 1, 0, 20, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 3, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 3, 0, 0, 3, 0, 1, 0, + 108, 3, 0, 0, 2, 0, 1, 0, + 21, 0, 0, 0, 14, 0, 0, 0, + 0, 0, 1, 0, 21, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 3, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 3, 0, 0, 3, 0, 1, 0, + 112, 3, 0, 0, 2, 0, 1, 0, + 22, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 1, 0, 22, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 3, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 3, 0, 0, 3, 0, 1, 0, + 124, 3, 0, 0, 2, 0, 1, 0, + 115, 118, 73, 100, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 111, 110, 115, 116, 101, 108, 108, + 97, 116, 105, 111, 110, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 251, 95, 235, 13, 255, 243, 241, 158, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 109, 101, 79, 102, 102, 115, + 101, 116, 78, 97, 110, 111, 115, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 116, 101, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 101, 99, 101, 105, 118, 101, 100, + 83, 118, 84, 105, 109, 101, 78, 97, + 110, 111, 115, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 101, 99, 101, 105, 118, 101, 100, + 83, 118, 84, 105, 109, 101, 85, 110, + 99, 101, 114, 116, 97, 105, 110, 116, + 121, 78, 97, 110, 111, 115, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 110, 48, 68, 98, 72, 122, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 115, 101, 117, 100, 111, 114, 97, + 110, 103, 101, 82, 97, 116, 101, 77, + 101, 116, 101, 114, 115, 80, 101, 114, + 83, 101, 99, 111, 110, 100, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 115, 101, 117, 100, 111, 114, 97, + 110, 103, 101, 82, 97, 116, 101, 85, + 110, 99, 101, 114, 116, 97, 105, 110, + 116, 121, 77, 101, 116, 101, 114, 115, + 80, 101, 114, 83, 101, 99, 111, 110, + 100, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 99, 117, 109, 117, 108, 97, + 116, 101, 100, 68, 101, 108, 116, 97, + 82, 97, 110, 103, 101, 83, 116, 97, + 116, 101, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 99, 117, 109, 117, 108, 97, + 116, 101, 100, 68, 101, 108, 116, 97, + 82, 97, 110, 103, 101, 77, 101, 116, + 101, 114, 115, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 99, 117, 109, 117, 108, 97, + 116, 101, 100, 68, 101, 108, 116, 97, + 82, 97, 110, 103, 101, 85, 110, 99, + 101, 114, 116, 97, 105, 110, 116, 121, + 77, 101, 116, 101, 114, 115, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 97, 115, 67, 97, 114, 114, 105, + 101, 114, 70, 114, 101, 113, 117, 101, + 110, 99, 121, 72, 122, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 114, 105, 101, 114, 70, + 114, 101, 113, 117, 101, 110, 99, 121, + 72, 122, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 97, 115, 67, 97, 114, 114, 105, + 101, 114, 67, 121, 99, 108, 101, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 114, 105, 101, 114, 67, + 121, 99, 108, 101, 115, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 97, 115, 67, 97, 114, 114, 105, + 101, 114, 80, 104, 97, 115, 101, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 114, 105, 101, 114, 80, + 104, 97, 115, 101, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 97, 115, 67, 97, 114, 114, 105, + 101, 114, 80, 104, 97, 115, 101, 85, + 110, 99, 101, 114, 116, 97, 105, 110, + 116, 121, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 114, 105, 101, 114, 80, + 104, 97, 115, 101, 85, 110, 99, 101, + 114, 116, 97, 105, 110, 116, 121, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 97, 115, 83, 110, 114, 73, 110, + 68, 98, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 110, 114, 73, 110, 68, 98, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 117, 108, 116, 105, 112, 97, 116, + 104, 73, 110, 100, 105, 99, 97, 116, + 111, 114, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 168, 202, 212, 49, 98, 123, 78, 192, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_d949bf717d77614d = b_d949bf717d77614d.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_d949bf717d77614d[] = { + &s_9ef1f3ff0deb5ffb, + &s_c04e7b6231d4caa8, +}; +static const uint16_t m_d949bf717d77614d[] = {10, 9, 11, 15, 13, 17, 19, 6, 1, 14, 12, 16, 18, 20, 22, 7, 8, 4, 5, 21, 3, 0, 2}; +static const uint16_t i_d949bf717d77614d[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22}; +const ::capnp::_::RawSchema s_d949bf717d77614d = { + 0xd949bf717d77614d, b_d949bf717d77614d.words, 420, d_d949bf717d77614d, m_d949bf717d77614d, + 2, 23, i_d949bf717d77614d, nullptr, nullptr, { &s_d949bf717d77614d, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<50> b_9ef1f3ff0deb5ffb = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 251, 95, 235, 13, 255, 243, 241, 158, + 50, 0, 0, 0, 2, 0, 0, 0, + 77, 97, 119, 125, 113, 191, 73, 217, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 2, 2, 0, 0, + 49, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 65, 110, 100, + 114, 111, 105, 100, 71, 110, 115, 115, + 46, 77, 101, 97, 115, 117, 114, 101, + 109, 101, 110, 116, 115, 46, 77, 101, + 97, 115, 117, 114, 101, 109, 101, 110, + 116, 46, 67, 111, 110, 115, 116, 101, + 108, 108, 97, 116, 105, 111, 110, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 28, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 61, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 53, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 110, 107, 110, 111, 119, 110, 0, + 103, 112, 115, 0, 0, 0, 0, 0, + 115, 98, 97, 115, 0, 0, 0, 0, + 103, 108, 111, 110, 97, 115, 115, 0, + 113, 122, 115, 115, 0, 0, 0, 0, + 98, 101, 105, 100, 111, 117, 0, 0, + 103, 97, 108, 105, 108, 101, 111, 0, } +}; +::capnp::word const* const bp_9ef1f3ff0deb5ffb = b_9ef1f3ff0deb5ffb.words; +#if !CAPNP_LITE +static const uint16_t m_9ef1f3ff0deb5ffb[] = {5, 6, 3, 1, 4, 2, 0}; +const ::capnp::_::RawSchema s_9ef1f3ff0deb5ffb = { + 0x9ef1f3ff0deb5ffb, b_9ef1f3ff0deb5ffb.words, 50, nullptr, m_9ef1f3ff0deb5ffb, + 0, 7, nullptr, nullptr, nullptr, { &s_9ef1f3ff0deb5ffb, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(Constellation_9ef1f3ff0deb5ffb, 9ef1f3ff0deb5ffb); +static const ::capnp::_::AlignedData<96> b_cbb9490adce12d72 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 114, 45, 225, 220, 10, 73, 185, 203, + 50, 0, 0, 0, 2, 0, 0, 0, + 77, 97, 119, 125, 113, 191, 73, 217, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 194, 1, 0, 0, + 45, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 111, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 65, 110, 100, + 114, 111, 105, 100, 71, 110, 115, 115, + 46, 77, 101, 97, 115, 117, 114, 101, + 109, 101, 110, 116, 115, 46, 77, 101, + 97, 115, 117, 114, 101, 109, 101, 110, + 116, 46, 83, 116, 97, 116, 101, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 60, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 173, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 165, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 161, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 153, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 149, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 145, 0, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 141, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 137, 0, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 133, 0, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 129, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 125, 0, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 125, 0, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 121, 0, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 121, 0, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 117, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 110, 107, 110, 111, 119, 110, 0, + 99, 111, 100, 101, 76, 111, 99, 107, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 105, 116, 83, 121, 110, 99, 0, + 115, 117, 98, 102, 114, 97, 109, 101, + 83, 121, 110, 99, 0, 0, 0, 0, + 116, 111, 119, 68, 101, 99, 111, 100, + 101, 100, 0, 0, 0, 0, 0, 0, + 109, 115, 101, 99, 65, 109, 98, 105, + 103, 117, 111, 117, 115, 0, 0, 0, + 115, 121, 109, 98, 111, 108, 83, 121, + 110, 99, 0, 0, 0, 0, 0, 0, + 103, 108, 111, 83, 116, 114, 105, 110, + 103, 83, 121, 110, 99, 0, 0, 0, + 103, 108, 111, 84, 111, 100, 68, 101, + 99, 111, 100, 101, 100, 0, 0, 0, + 98, 100, 115, 68, 50, 66, 105, 116, + 83, 121, 110, 99, 0, 0, 0, 0, + 98, 100, 115, 68, 50, 83, 117, 98, + 102, 114, 97, 109, 101, 83, 121, 110, + 99, 0, 0, 0, 0, 0, 0, 0, + 103, 97, 108, 69, 49, 98, 99, 67, + 111, 100, 101, 76, 111, 99, 107, 0, + 103, 97, 108, 69, 49, 99, 50, 110, + 100, 67, 111, 100, 101, 76, 111, 99, + 107, 0, 0, 0, 0, 0, 0, 0, + 103, 97, 108, 69, 49, 98, 80, 97, + 103, 101, 83, 121, 110, 99, 0, 0, + 115, 98, 97, 115, 83, 121, 110, 99, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_cbb9490adce12d72 = b_cbb9490adce12d72.words; +#if !CAPNP_LITE +static const uint16_t m_cbb9490adce12d72[] = {9, 10, 2, 1, 13, 11, 12, 7, 8, 5, 14, 3, 6, 4, 0}; +const ::capnp::_::RawSchema s_cbb9490adce12d72 = { + 0xcbb9490adce12d72, b_cbb9490adce12d72.words, 96, nullptr, m_cbb9490adce12d72, + 0, 15, nullptr, nullptr, nullptr, { &s_cbb9490adce12d72, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(State_cbb9490adce12d72, cbb9490adce12d72); +static const ::capnp::_::AlignedData<37> b_c04e7b6231d4caa8 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 168, 202, 212, 49, 98, 123, 78, 192, + 50, 0, 0, 0, 2, 0, 0, 0, + 77, 97, 119, 125, 113, 191, 73, 217, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 42, 2, 0, 0, + 53, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 0, 0, 0, 79, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 65, 110, 100, + 114, 111, 105, 100, 71, 110, 115, 115, + 46, 77, 101, 97, 115, 117, 114, 101, + 109, 101, 110, 116, 115, 46, 77, 101, + 97, 115, 117, 114, 101, 109, 101, 110, + 116, 46, 77, 117, 108, 116, 105, 112, + 97, 116, 104, 73, 110, 100, 105, 99, + 97, 116, 111, 114, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 17, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 110, 107, 110, 111, 119, 110, 0, + 100, 101, 116, 101, 99, 116, 101, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 111, 116, 68, 101, 116, 101, 99, + 116, 101, 100, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_c04e7b6231d4caa8 = b_c04e7b6231d4caa8.words; +#if !CAPNP_LITE +static const uint16_t m_c04e7b6231d4caa8[] = {1, 2, 0}; +const ::capnp::_::RawSchema s_c04e7b6231d4caa8 = { + 0xc04e7b6231d4caa8, b_c04e7b6231d4caa8.words, 37, nullptr, m_c04e7b6231d4caa8, + 0, 3, nullptr, nullptr, nullptr, { &s_c04e7b6231d4caa8, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(MultipathIndicator_c04e7b6231d4caa8, c04e7b6231d4caa8); +static const ::capnp::_::AlignedData<115> b_e2517b083095fd4e = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 78, 253, 149, 48, 8, 123, 81, 226, + 25, 0, 0, 0, 1, 0, 3, 0, + 189, 133, 196, 63, 208, 48, 223, 223, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 90, 1, 0, 0, + 41, 0, 0, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 0, 0, 0, 87, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 65, 110, 100, + 114, 111, 105, 100, 71, 110, 115, 115, + 46, 78, 97, 118, 105, 103, 97, 116, + 105, 111, 110, 77, 101, 115, 115, 97, + 103, 101, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 1, 0, 1, 0, + 111, 54, 53, 107, 153, 247, 31, 236, + 1, 0, 0, 0, 58, 0, 0, 0, + 83, 116, 97, 116, 117, 115, 0, 0, + 24, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 0, 0, 0, 3, 0, 1, 0, + 160, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 157, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 152, 0, 0, 0, 3, 0, 1, 0, + 164, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 161, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 160, 0, 0, 0, 3, 0, 1, 0, + 172, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 169, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 0, 0, 0, 3, 0, 1, 0, + 180, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 172, 0, 0, 0, 3, 0, 1, 0, + 184, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 0, 0, 0, 3, 0, 1, 0, + 188, 0, 0, 0, 2, 0, 1, 0, + 116, 121, 112, 101, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 118, 73, 100, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 101, 115, 115, 97, 103, 101, 73, + 100, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 117, 98, 109, 101, 115, 115, 97, + 103, 101, 73, 100, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 97, 116, 97, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 116, 117, 115, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 111, 54, 53, 107, 153, 247, 31, 236, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e2517b083095fd4e = b_e2517b083095fd4e.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_e2517b083095fd4e[] = { + &s_ec1ff7996b35366f, +}; +static const uint16_t m_e2517b083095fd4e[] = {4, 2, 5, 3, 1, 0}; +static const uint16_t i_e2517b083095fd4e[] = {0, 1, 2, 3, 4, 5}; +const ::capnp::_::RawSchema s_e2517b083095fd4e = { + 0xe2517b083095fd4e, b_e2517b083095fd4e.words, 115, d_e2517b083095fd4e, m_e2517b083095fd4e, + 1, 6, i_e2517b083095fd4e, nullptr, nullptr, { &s_e2517b083095fd4e, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<35> b_ec1ff7996b35366f = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 111, 54, 53, 107, 153, 247, 31, 236, + 43, 0, 0, 0, 2, 0, 0, 0, + 78, 253, 149, 48, 8, 123, 81, 226, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 146, 1, 0, 0, + 45, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 79, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 65, 110, 100, + 114, 111, 105, 100, 71, 110, 115, 115, + 46, 78, 97, 118, 105, 103, 97, 116, + 105, 111, 110, 77, 101, 115, 115, 97, + 103, 101, 46, 83, 116, 97, 116, 117, + 115, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 17, 0, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 110, 107, 110, 111, 119, 110, 0, + 112, 97, 114, 105, 116, 121, 80, 97, + 115, 115, 101, 100, 0, 0, 0, 0, + 112, 97, 114, 105, 116, 121, 82, 101, + 98, 117, 105, 108, 116, 0, 0, 0, } +}; +::capnp::word const* const bp_ec1ff7996b35366f = b_ec1ff7996b35366f.words; +#if !CAPNP_LITE +static const uint16_t m_ec1ff7996b35366f[] = {1, 2, 0}; +const ::capnp::_::RawSchema s_ec1ff7996b35366f = { + 0xec1ff7996b35366f, b_ec1ff7996b35366f.words, 35, nullptr, m_ec1ff7996b35366f, + 0, 3, nullptr, nullptr, nullptr, { &s_ec1ff7996b35366f, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(Status_ec1ff7996b35366f, ec1ff7996b35366f); +static const ::capnp::_::AlignedData<104> b_e3d6685d4e9d8f7a = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 122, 143, 157, 78, 93, 104, 214, 227, + 13, 0, 0, 0, 1, 0, 1, 0, + 99, 42, 156, 136, 196, 30, 239, 128, + 4, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 178, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 31, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 103, 97, 99, 121, 46, 99, + 97, 112, 110, 112, 58, 76, 105, 100, + 97, 114, 80, 116, 115, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 20, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 0, 0, 0, 3, 0, 1, 0, + 148, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 145, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 140, 0, 0, 0, 3, 0, 1, 0, + 168, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 165, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 160, 0, 0, 0, 3, 0, 1, 0, + 188, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 0, 0, 0, 3, 0, 1, 0, + 192, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 0, 0, 0, 3, 0, 1, 0, + 196, 0, 0, 0, 2, 0, 1, 0, + 114, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 104, 101, 116, 97, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 101, 102, 108, 101, 99, 116, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 100, 120, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 107, 116, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e3d6685d4e9d8f7a = b_e3d6685d4e9d8f7a.words; +#if !CAPNP_LITE +static const uint16_t m_e3d6685d4e9d8f7a[] = {3, 4, 0, 2, 1}; +static const uint16_t i_e3d6685d4e9d8f7a[] = {0, 1, 2, 3, 4}; +const ::capnp::_::RawSchema s_e3d6685d4e9d8f7a = { + 0xe3d6685d4e9d8f7a, b_e3d6685d4e9d8f7a.words, 104, nullptr, m_e3d6685d4e9d8f7a, + 0, 5, i_e3d6685d4e9d8f7a, nullptr, nullptr, { &s_e3d6685d4e9d8f7a, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +} // namespace schemas +} // namespace capnp + +// ======================================================================================= + +namespace cereal { + +// LogRotate +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t LogRotate::_capnpPrivate::dataWordSize; +constexpr uint16_t LogRotate::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind LogRotate::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* LogRotate::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// LiveUI +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t LiveUI::_capnpPrivate::dataWordSize; +constexpr uint16_t LiveUI::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind LiveUI::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* LiveUI::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// UiLayoutState +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t UiLayoutState::_capnpPrivate::dataWordSize; +constexpr uint16_t UiLayoutState::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind UiLayoutState::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* UiLayoutState::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// OrbslamCorrection +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t OrbslamCorrection::_capnpPrivate::dataWordSize; +constexpr uint16_t OrbslamCorrection::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind OrbslamCorrection::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* OrbslamCorrection::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// EthernetPacket +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t EthernetPacket::_capnpPrivate::dataWordSize; +constexpr uint16_t EthernetPacket::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind EthernetPacket::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* EthernetPacket::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// CellInfo +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t CellInfo::_capnpPrivate::dataWordSize; +constexpr uint16_t CellInfo::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind CellInfo::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* CellInfo::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// WifiScan +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t WifiScan::_capnpPrivate::dataWordSize; +constexpr uint16_t WifiScan::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind WifiScan::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* WifiScan::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// LiveEventData +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t LiveEventData::_capnpPrivate::dataWordSize; +constexpr uint16_t LiveEventData::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind LiveEventData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* LiveEventData::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// ModelData +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t ModelData::_capnpPrivate::dataWordSize; +constexpr uint16_t ModelData::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind ModelData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ModelData::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// ModelData::PathData +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t ModelData::PathData::_capnpPrivate::dataWordSize; +constexpr uint16_t ModelData::PathData::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind ModelData::PathData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ModelData::PathData::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// ModelData::LeadData +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t ModelData::LeadData::_capnpPrivate::dataWordSize; +constexpr uint16_t ModelData::LeadData::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind ModelData::LeadData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ModelData::LeadData::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// ModelData::ModelSettings +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t ModelData::ModelSettings::_capnpPrivate::dataWordSize; +constexpr uint16_t ModelData::ModelSettings::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind ModelData::ModelSettings::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ModelData::ModelSettings::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// ModelData::MetaData +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t ModelData::MetaData::_capnpPrivate::dataWordSize; +constexpr uint16_t ModelData::MetaData::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind ModelData::MetaData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ModelData::MetaData::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// ModelData::LongitudinalData +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t ModelData::LongitudinalData::_capnpPrivate::dataWordSize; +constexpr uint16_t ModelData::LongitudinalData::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind ModelData::LongitudinalData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ModelData::LongitudinalData::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// ECEFPoint +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t ECEFPoint::_capnpPrivate::dataWordSize; +constexpr uint16_t ECEFPoint::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind ECEFPoint::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ECEFPoint::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// ECEFPointDEPRECATED +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t ECEFPointDEPRECATED::_capnpPrivate::dataWordSize; +constexpr uint16_t ECEFPointDEPRECATED::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind ECEFPointDEPRECATED::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ECEFPointDEPRECATED::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// GPSPlannerPoints +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t GPSPlannerPoints::_capnpPrivate::dataWordSize; +constexpr uint16_t GPSPlannerPoints::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind GPSPlannerPoints::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* GPSPlannerPoints::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// GPSPlannerPlan +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t GPSPlannerPlan::_capnpPrivate::dataWordSize; +constexpr uint16_t GPSPlannerPlan::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind GPSPlannerPlan::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* GPSPlannerPlan::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// UiNavigationEvent +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t UiNavigationEvent::_capnpPrivate::dataWordSize; +constexpr uint16_t UiNavigationEvent::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind UiNavigationEvent::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* UiNavigationEvent::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// LiveLocationData +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t LiveLocationData::_capnpPrivate::dataWordSize; +constexpr uint16_t LiveLocationData::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind LiveLocationData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* LiveLocationData::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// LiveLocationData::Accuracy +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t LiveLocationData::Accuracy::_capnpPrivate::dataWordSize; +constexpr uint16_t LiveLocationData::Accuracy::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind LiveLocationData::Accuracy::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* LiveLocationData::Accuracy::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// OrbOdometry +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t OrbOdometry::_capnpPrivate::dataWordSize; +constexpr uint16_t OrbOdometry::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind OrbOdometry::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* OrbOdometry::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// OrbFeatures +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t OrbFeatures::_capnpPrivate::dataWordSize; +constexpr uint16_t OrbFeatures::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind OrbFeatures::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* OrbFeatures::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// OrbFeaturesSummary +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t OrbFeaturesSummary::_capnpPrivate::dataWordSize; +constexpr uint16_t OrbFeaturesSummary::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind OrbFeaturesSummary::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* OrbFeaturesSummary::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// OrbKeyFrame +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t OrbKeyFrame::_capnpPrivate::dataWordSize; +constexpr uint16_t OrbKeyFrame::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind OrbKeyFrame::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* OrbKeyFrame::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// KalmanOdometry +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t KalmanOdometry::_capnpPrivate::dataWordSize; +constexpr uint16_t KalmanOdometry::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind KalmanOdometry::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* KalmanOdometry::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// OrbObservation +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t OrbObservation::_capnpPrivate::dataWordSize; +constexpr uint16_t OrbObservation::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind OrbObservation::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* OrbObservation::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// CalibrationFeatures +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t CalibrationFeatures::_capnpPrivate::dataWordSize; +constexpr uint16_t CalibrationFeatures::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind CalibrationFeatures::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* CalibrationFeatures::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// NavStatus +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t NavStatus::_capnpPrivate::dataWordSize; +constexpr uint16_t NavStatus::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind NavStatus::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* NavStatus::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// NavStatus::Address +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t NavStatus::Address::_capnpPrivate::dataWordSize; +constexpr uint16_t NavStatus::Address::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind NavStatus::Address::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* NavStatus::Address::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// NavUpdate +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t NavUpdate::_capnpPrivate::dataWordSize; +constexpr uint16_t NavUpdate::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind NavUpdate::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* NavUpdate::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// NavUpdate::LatLng +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t NavUpdate::LatLng::_capnpPrivate::dataWordSize; +constexpr uint16_t NavUpdate::LatLng::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind NavUpdate::LatLng::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* NavUpdate::LatLng::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// NavUpdate::Segment +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t NavUpdate::Segment::_capnpPrivate::dataWordSize; +constexpr uint16_t NavUpdate::Segment::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind NavUpdate::Segment::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* NavUpdate::Segment::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// TrafficEvent +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t TrafficEvent::_capnpPrivate::dataWordSize; +constexpr uint16_t TrafficEvent::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind TrafficEvent::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* TrafficEvent::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// AndroidGnss +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t AndroidGnss::_capnpPrivate::dataWordSize; +constexpr uint16_t AndroidGnss::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind AndroidGnss::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* AndroidGnss::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// AndroidGnss::Measurements +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t AndroidGnss::Measurements::_capnpPrivate::dataWordSize; +constexpr uint16_t AndroidGnss::Measurements::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind AndroidGnss::Measurements::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* AndroidGnss::Measurements::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// AndroidGnss::Measurements::Clock +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t AndroidGnss::Measurements::Clock::_capnpPrivate::dataWordSize; +constexpr uint16_t AndroidGnss::Measurements::Clock::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind AndroidGnss::Measurements::Clock::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* AndroidGnss::Measurements::Clock::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// AndroidGnss::Measurements::Measurement +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t AndroidGnss::Measurements::Measurement::_capnpPrivate::dataWordSize; +constexpr uint16_t AndroidGnss::Measurements::Measurement::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind AndroidGnss::Measurements::Measurement::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* AndroidGnss::Measurements::Measurement::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// AndroidGnss::NavigationMessage +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t AndroidGnss::NavigationMessage::_capnpPrivate::dataWordSize; +constexpr uint16_t AndroidGnss::NavigationMessage::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind AndroidGnss::NavigationMessage::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* AndroidGnss::NavigationMessage::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// LidarPts +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t LidarPts::_capnpPrivate::dataWordSize; +constexpr uint16_t LidarPts::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind LidarPts::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* LidarPts::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + + +} // namespace + diff --git a/cereal/gen/cpp/log.capnp.c++ b/cereal/gen/cpp/log.capnp.c++ new file mode 100644 index 0000000..4b3924a --- /dev/null +++ b/cereal/gen/cpp/log.capnp.c++ @@ -0,0 +1,31118 @@ +// Generated by Cap'n Proto compiler, DO NOT EDIT +// source: log.capnp + +#include "log.capnp.h" + +namespace capnp { +namespace schemas { +static const ::capnp::_::AlignedData<23> b_d578fb3372ed5043 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 67, 80, 237, 114, 51, 251, 120, 213, + 10, 0, 0, 0, 4, 0, 0, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 170, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 24, 0, 0, 0, 3, 0, 1, 0, + 36, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 108, 111, 103, 86, 101, 114, + 115, 105, 111, 110, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_d578fb3372ed5043 = b_d578fb3372ed5043.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_d578fb3372ed5043 = { + 0xd578fb3372ed5043, b_d578fb3372ed5043.words, 23, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_d578fb3372ed5043, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<48> b_f8b13ce2183eb696 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 150, 182, 62, 24, 226, 60, 177, 248, + 10, 0, 0, 0, 1, 0, 0, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 0, 0, + 21, 0, 0, 0, 114, 0, 0, 0, + 25, 0, 0, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 63, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 0, 0, 0, 23, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 77, 97, 112, 0, 0, 0, + 4, 0, 0, 0, 1, 0, 1, 0, + 14, 234, 110, 74, 8, 221, 223, 165, + 1, 0, 0, 0, 50, 0, 0, 0, + 69, 110, 116, 114, 121, 0, 0, 0, + 4, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 3, 0, 1, 0, + 56, 0, 0, 0, 2, 0, 1, 0, + 101, 110, 116, 114, 105, 101, 115, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 14, 234, 110, 74, 8, 221, 223, 165, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 1, 0, + 1, 0, 0, 0, 31, 0, 0, 0, + 4, 0, 0, 0, 2, 0, 1, 0, + 150, 182, 62, 24, 226, 60, 177, 248, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 1, 0, + 5, 0, 0, 0, 34, 0, 0, 0, + 5, 0, 0, 0, 50, 0, 0, 0, + 75, 101, 121, 0, 0, 0, 0, 0, + 86, 97, 108, 117, 101, 0, 0, 0, } +}; +::capnp::word const* const bp_f8b13ce2183eb696 = b_f8b13ce2183eb696.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_f8b13ce2183eb696[] = { + &s_a5dfdd084a6eea0e, +}; +static const uint16_t m_f8b13ce2183eb696[] = {0}; +static const uint16_t i_f8b13ce2183eb696[] = {0}; +KJ_CONSTEXPR(const) ::capnp::_::RawBrandedSchema::Dependency bd_f8b13ce2183eb696[] = { + { 16777216, ::cereal::Map< ::capnp::AnyPointer, ::capnp::AnyPointer>::Entry::_capnpPrivate::brand() }, +}; +const ::capnp::_::RawSchema s_f8b13ce2183eb696 = { + 0xf8b13ce2183eb696, b_f8b13ce2183eb696.words, 48, d_f8b13ce2183eb696, m_f8b13ce2183eb696, + 1, 1, i_f8b13ce2183eb696, nullptr, nullptr, { &s_f8b13ce2183eb696, nullptr, bd_f8b13ce2183eb696, 0, sizeof(bd_f8b13ce2183eb696) / sizeof(bd_f8b13ce2183eb696[0]), nullptr }, true +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<47> b_a5dfdd084a6eea0e = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 14, 234, 110, 74, 8, 221, 223, 165, + 14, 0, 0, 0, 1, 0, 0, 0, + 150, 182, 62, 24, 226, 60, 177, 248, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 0, 0, + 21, 0, 0, 0, 162, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 77, 97, 112, 46, 69, 110, + 116, 114, 121, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 107, 101, 121, 0, 0, 0, 0, 0, + 18, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 150, 182, 62, 24, 226, 60, 177, 248, + 0, 0, 0, 0, 0, 0, 0, 0, + 18, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 97, 108, 117, 101, 0, 0, 0, + 18, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 1, 0, 0, 0, 0, 0, + 150, 182, 62, 24, 226, 60, 177, 248, + 0, 0, 0, 0, 0, 0, 0, 0, + 18, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_a5dfdd084a6eea0e = b_a5dfdd084a6eea0e.words; +#if !CAPNP_LITE +static const uint16_t m_a5dfdd084a6eea0e[] = {0, 1}; +static const uint16_t i_a5dfdd084a6eea0e[] = {0, 1}; +const ::capnp::_::RawSchema s_a5dfdd084a6eea0e = { + 0xa5dfdd084a6eea0e, b_a5dfdd084a6eea0e.words, 47, nullptr, m_a5dfdd084a6eea0e, + 0, 2, i_a5dfdd084a6eea0e, nullptr, nullptr, { &s_a5dfdd084a6eea0e, nullptr, nullptr, 0, 0, nullptr }, true +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<33> b_d692e23d1a247d99 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 153, 125, 36, 26, 61, 226, 146, 214, + 10, 0, 0, 0, 2, 0, 0, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 18, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 79, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 76, 111, 110, 103, 105, 116, + 117, 100, 105, 110, 97, 108, 80, 101, + 114, 115, 111, 110, 97, 108, 105, 116, + 121, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 103, 103, 114, 101, 115, 115, 105, + 118, 101, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 110, 100, 97, 114, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 101, 108, 97, 120, 101, 100, 0, } +}; +::capnp::word const* const bp_d692e23d1a247d99 = b_d692e23d1a247d99.words; +#if !CAPNP_LITE +static const uint16_t m_d692e23d1a247d99[] = {0, 2, 1}; +const ::capnp::_::RawSchema s_d692e23d1a247d99 = { + 0xd692e23d1a247d99, b_d692e23d1a247d99.words, 33, nullptr, m_d692e23d1a247d99, + 0, 3, nullptr, nullptr, nullptr, { &s_d692e23d1a247d99, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(LongitudinalPersonality_d692e23d1a247d99, d692e23d1a247d99); +static const ::capnp::_::AlignedData<460> b_e71008caeb3fb65c = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 92, 182, 63, 235, 202, 8, 16, 231, + 10, 0, 0, 0, 1, 0, 2, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 18, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 154, 0, 0, 0, + 29, 0, 0, 0, 103, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 129, 0, 0, 0, 215, 4, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 73, 110, 105, 116, 68, 97, + 116, 97, 0, 0, 0, 0, 0, 0, + 24, 0, 0, 0, 1, 0, 1, 0, + 8, 102, 168, 235, 56, 114, 93, 157, + 41, 0, 0, 0, 90, 0, 0, 0, + 173, 240, 223, 92, 114, 232, 115, 230, + 41, 0, 0, 0, 82, 0, 0, 0, + 108, 66, 31, 194, 213, 25, 41, 254, + 41, 0, 0, 0, 138, 0, 0, 0, + 205, 219, 135, 168, 147, 59, 81, 155, + 45, 0, 0, 0, 114, 0, 0, 0, + 165, 21, 246, 164, 83, 93, 251, 156, + 45, 0, 0, 0, 146, 0, 0, 0, + 128, 85, 159, 35, 40, 59, 126, 217, + 49, 0, 0, 0, 106, 0, 0, 0, + 68, 101, 118, 105, 99, 101, 84, 121, + 112, 101, 0, 0, 0, 0, 0, 0, + 80, 97, 110, 100, 97, 73, 110, 102, + 111, 0, 0, 0, 0, 0, 0, 0, + 65, 110, 100, 114, 111, 105, 100, 66, + 117, 105, 108, 100, 73, 110, 102, 111, + 0, 0, 0, 0, 0, 0, 0, 0, + 65, 110, 100, 114, 111, 105, 100, 83, + 101, 110, 115, 111, 114, 0, 0, 0, + 67, 104, 102, 102, 114, 65, 110, 100, + 114, 111, 105, 100, 69, 120, 116, 114, + 97, 0, 0, 0, 0, 0, 0, 0, + 73, 111, 115, 66, 117, 105, 108, 100, + 73, 110, 102, 111, 0, 0, 0, 0, + 88, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 89, 2, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 88, 2, 0, 0, 3, 0, 1, 0, + 116, 2, 0, 0, 2, 0, 1, 0, + 17, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 2, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 2, 0, 0, 3, 0, 1, 0, + 124, 2, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 2, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 2, 0, 0, 3, 0, 1, 0, + 132, 2, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 129, 2, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 128, 2, 0, 0, 3, 0, 1, 0, + 140, 2, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 137, 2, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 132, 2, 0, 0, 3, 0, 1, 0, + 144, 2, 0, 0, 2, 0, 1, 0, + 18, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 2, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 144, 2, 0, 0, 3, 0, 1, 0, + 156, 2, 0, 0, 2, 0, 1, 0, + 19, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 2, 0, 0, 202, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 160, 2, 0, 0, 3, 0, 1, 0, + 188, 2, 0, 0, 2, 0, 1, 0, + 20, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 2, 0, 0, 226, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 192, 2, 0, 0, 3, 0, 1, 0, + 204, 2, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 2, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 200, 2, 0, 0, 3, 0, 1, 0, + 212, 2, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 16, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 2, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 2, 0, 0, 3, 0, 1, 0, + 216, 2, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 2, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 212, 2, 0, 0, 3, 0, 1, 0, + 224, 2, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 2, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 220, 2, 0, 0, 3, 0, 1, 0, + 232, 2, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 17, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 2, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 224, 2, 0, 0, 3, 0, 1, 0, + 236, 2, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 233, 2, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 2, 0, 0, 3, 0, 1, 0, + 244, 2, 0, 0, 2, 0, 1, 0, + 21, 0, 0, 0, 11, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 2, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 244, 2, 0, 0, 3, 0, 1, 0, + 0, 3, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 12, 0, 0, 0, + 0, 0, 1, 0, 15, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 253, 2, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 252, 2, 0, 0, 3, 0, 1, 0, + 8, 3, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 13, 0, 0, 0, + 0, 0, 1, 0, 16, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 3, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 3, 0, 0, 3, 0, 1, 0, + 92, 3, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 14, 0, 0, 0, + 0, 0, 1, 0, 17, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 89, 3, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 84, 3, 0, 0, 3, 0, 1, 0, + 168, 3, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 15, 0, 0, 0, + 0, 0, 1, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 165, 3, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 164, 3, 0, 0, 3, 0, 1, 0, + 176, 3, 0, 0, 2, 0, 1, 0, + 15, 0, 0, 0, 16, 0, 0, 0, + 0, 0, 1, 0, 19, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 173, 3, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 172, 3, 0, 0, 3, 0, 1, 0, + 0, 4, 0, 0, 2, 0, 1, 0, + 16, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 20, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 253, 3, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 252, 3, 0, 0, 3, 0, 1, 0, + 8, 4, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 17, 0, 0, 0, + 0, 0, 1, 0, 21, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 4, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 4, 0, 0, 3, 0, 1, 0, + 16, 4, 0, 0, 2, 0, 1, 0, + 107, 101, 114, 110, 101, 108, 65, 114, + 103, 115, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 99, 116, 120, 68, 69, 80, 82, + 69, 67, 65, 84, 69, 68, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 111, 110, 103, 108, 101, 73, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 118, 105, 99, 101, 84, 121, + 112, 101, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 8, 102, 168, 235, 56, 114, 93, 157, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 101, 114, 115, 105, 111, 110, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 110, 100, 114, 111, 105, 100, 66, + 117, 105, 108, 100, 73, 110, 102, 111, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 108, 66, 31, 194, 213, 25, 41, 254, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 110, 100, 114, 111, 105, 100, 83, + 101, 110, 115, 111, 114, 115, 68, 69, + 80, 82, 69, 67, 65, 84, 69, 68, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 205, 219, 135, 168, 147, 59, 81, 155, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 104, 102, 102, 114, 65, 110, 100, + 114, 111, 105, 100, 69, 120, 116, 114, + 97, 68, 69, 80, 82, 69, 67, 65, + 84, 69, 68, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 165, 21, 246, 164, 83, 93, 251, 156, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 97, 110, 100, 97, 73, 110, 102, + 111, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 173, 240, 223, 92, 114, 232, 115, 230, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 105, 114, 116, 121, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 105, 116, 67, 111, 109, 109, 105, + 116, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 105, 116, 66, 114, 97, 110, 99, + 104, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 97, 115, 115, 105, 118, 101, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 105, 116, 82, 101, 109, 111, 116, + 101, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 111, 115, 66, 117, 105, 108, 100, + 73, 110, 102, 111, 68, 69, 80, 82, + 69, 67, 65, 84, 69, 68, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 128, 85, 159, 35, 40, 59, 126, 217, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 107, 101, 114, 110, 101, 108, 86, 101, + 114, 115, 105, 111, 110, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 110, 100, 114, 111, 105, 100, 80, + 114, 111, 112, 101, 114, 116, 105, 101, + 115, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 150, 182, 62, 24, 226, 60, 177, 248, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 1, 0, + 1, 0, 0, 0, 31, 0, 0, 0, + 4, 0, 0, 0, 2, 0, 1, 0, + 150, 182, 62, 24, 226, 60, 177, 248, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 39, 0, 0, 0, + 8, 0, 0, 0, 1, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 3, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 3, 0, 1, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 97, 114, 97, 109, 115, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 150, 182, 62, 24, 226, 60, 177, 248, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 1, 0, + 1, 0, 0, 0, 31, 0, 0, 0, + 4, 0, 0, 0, 2, 0, 1, 0, + 150, 182, 62, 24, 226, 60, 177, 248, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 39, 0, 0, 0, + 8, 0, 0, 0, 1, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 3, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 3, 0, 1, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 115, 86, 101, 114, 115, 105, 111, + 110, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 111, 109, 109, 97, 110, 100, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 150, 182, 62, 24, 226, 60, 177, 248, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 1, 0, + 1, 0, 0, 0, 31, 0, 0, 0, + 4, 0, 0, 0, 2, 0, 1, 0, + 150, 182, 62, 24, 226, 60, 177, 248, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 39, 0, 0, 0, + 8, 0, 0, 0, 1, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 3, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 3, 0, 1, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 119, 97, 108, 108, 84, 105, 109, 101, + 78, 97, 110, 111, 115, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 105, 116, 67, 111, 109, 109, 105, + 116, 68, 97, 116, 101, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e71008caeb3fb65c = b_e71008caeb3fb65c.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_e71008caeb3fb65c[] = { + &s_9b513b93a887dbcd, + &s_9cfb5d53a4f615a5, + &s_9d5d7238eba86608, + &s_d97e3b28239f5580, + &s_e673e8725cdff0ad, + &s_f8b13ce2183eb696, + &s_fe2919d5c21f426c, +}; +static const uint16_t m_e71008caeb3fb65c[] = {5, 16, 6, 7, 19, 3, 9, 2, 1, 11, 10, 21, 13, 14, 0, 15, 18, 8, 17, 12, 4, 20}; +static const uint16_t i_e71008caeb3fb65c[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21}; +KJ_CONSTEXPR(const) ::capnp::_::RawBrandedSchema::Dependency bd_e71008caeb3fb65c[] = { + { 16777232, ::cereal::Map< ::capnp::Text, ::capnp::Text>::_capnpPrivate::brand() }, + { 16777233, ::cereal::Map< ::capnp::Text, ::capnp::Data>::_capnpPrivate::brand() }, + { 16777235, ::cereal::Map< ::capnp::Text, ::capnp::Data>::_capnpPrivate::brand() }, +}; +const ::capnp::_::RawSchema s_e71008caeb3fb65c = { + 0xe71008caeb3fb65c, b_e71008caeb3fb65c.words, 460, d_e71008caeb3fb65c, m_e71008caeb3fb65c, + 7, 22, i_e71008caeb3fb65c, nullptr, nullptr, { &s_e71008caeb3fb65c, nullptr, bd_e71008caeb3fb65c, 0, sizeof(bd_e71008caeb3fb65c) / sizeof(bd_e71008caeb3fb65c[0]), nullptr }, true +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<48> b_9d5d7238eba86608 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 8, 102, 168, 235, 56, 114, 93, 157, + 19, 0, 0, 0, 2, 0, 0, 0, + 92, 182, 63, 235, 202, 8, 16, 231, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 242, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 73, 110, 105, 116, 68, 97, + 116, 97, 46, 68, 101, 118, 105, 99, + 101, 84, 121, 112, 101, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 28, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 61, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 57, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 53, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 110, 107, 110, 111, 119, 110, 0, + 110, 101, 111, 0, 0, 0, 0, 0, + 99, 104, 102, 102, 114, 65, 110, 100, + 114, 111, 105, 100, 0, 0, 0, 0, + 99, 104, 102, 102, 114, 73, 111, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 99, 105, 0, 0, 0, 0, + 112, 99, 0, 0, 0, 0, 0, 0, + 116, 105, 122, 105, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_9d5d7238eba86608 = b_9d5d7238eba86608.words; +#if !CAPNP_LITE +static const uint16_t m_9d5d7238eba86608[] = {2, 3, 1, 5, 4, 6, 0}; +const ::capnp::_::RawSchema s_9d5d7238eba86608 = { + 0x9d5d7238eba86608, b_9d5d7238eba86608.words, 48, nullptr, m_9d5d7238eba86608, + 0, 7, nullptr, nullptr, nullptr, { &s_9d5d7238eba86608, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(DeviceType_9d5d7238eba86608, 9d5d7238eba86608); +static const ::capnp::_::AlignedData<82> b_e673e8725cdff0ad = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 173, 240, 223, 92, 114, 232, 115, 230, + 19, 0, 0, 0, 1, 0, 1, 0, + 92, 182, 63, 235, 202, 8, 16, 231, + 3, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 234, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 231, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 73, 110, 105, 116, 68, 97, + 116, 97, 46, 80, 97, 110, 100, 97, + 73, 110, 102, 111, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 0, 0, 0, 3, 0, 1, 0, + 108, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 0, 0, 0, 3, 0, 1, 0, + 116, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 0, 0, 0, 3, 0, 1, 0, + 124, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 0, 0, 0, 3, 0, 1, 0, + 132, 0, 0, 0, 2, 0, 1, 0, + 104, 97, 115, 80, 97, 110, 100, 97, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 111, 110, 103, 108, 101, 73, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 86, 101, 114, 115, 105, 111, + 110, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 115, 112, 86, 101, 114, 115, 105, + 111, 110, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e673e8725cdff0ad = b_e673e8725cdff0ad.words; +#if !CAPNP_LITE +static const uint16_t m_e673e8725cdff0ad[] = {1, 3, 0, 2}; +static const uint16_t i_e673e8725cdff0ad[] = {0, 1, 2, 3}; +const ::capnp::_::RawSchema s_e673e8725cdff0ad = { + 0xe673e8725cdff0ad, b_e673e8725cdff0ad.words, 82, nullptr, m_e673e8725cdff0ad, + 0, 4, i_e673e8725cdff0ad, nullptr, nullptr, { &s_e673e8725cdff0ad, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<379> b_fe2919d5c21f426c = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 108, 66, 31, 194, 213, 25, 41, 254, + 19, 0, 0, 0, 1, 0, 2, 0, + 92, 182, 63, 235, 202, 8, 16, 231, + 21, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 34, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 15, 5, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 73, 110, 105, 116, 68, 97, + 116, 97, 46, 65, 110, 100, 114, 111, + 105, 100, 66, 117, 105, 108, 100, 73, + 110, 102, 111, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 92, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 2, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 2, 0, 0, 3, 0, 1, 0, + 124, 2, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 2, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 2, 0, 0, 3, 0, 1, 0, + 132, 2, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 129, 2, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 2, 0, 0, 3, 0, 1, 0, + 136, 2, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 2, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 128, 2, 0, 0, 3, 0, 1, 0, + 140, 2, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 137, 2, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 132, 2, 0, 0, 3, 0, 1, 0, + 144, 2, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 2, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 140, 2, 0, 0, 3, 0, 1, 0, + 152, 2, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 149, 2, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 2, 0, 0, 3, 0, 1, 0, + 160, 2, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 157, 2, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 152, 2, 0, 0, 3, 0, 1, 0, + 164, 2, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 161, 2, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 156, 2, 0, 0, 3, 0, 1, 0, + 168, 2, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 165, 2, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 164, 2, 0, 0, 3, 0, 1, 0, + 176, 2, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 173, 2, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 2, 0, 0, 3, 0, 1, 0, + 180, 2, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 11, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 2, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 172, 2, 0, 0, 3, 0, 1, 0, + 184, 2, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 12, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 2, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 2, 0, 0, 3, 0, 1, 0, + 192, 2, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 13, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 2, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 2, 0, 0, 3, 0, 1, 0, + 196, 2, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 14, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 2, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 192, 2, 0, 0, 3, 0, 1, 0, + 220, 2, 0, 0, 2, 0, 1, 0, + 15, 0, 0, 0, 15, 0, 0, 0, + 0, 0, 1, 0, 15, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 217, 2, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 212, 2, 0, 0, 3, 0, 1, 0, + 224, 2, 0, 0, 2, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 16, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 2, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 2, 0, 0, 3, 0, 1, 0, + 228, 2, 0, 0, 2, 0, 1, 0, + 17, 0, 0, 0, 16, 0, 0, 0, + 0, 0, 1, 0, 17, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 225, 2, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 220, 2, 0, 0, 3, 0, 1, 0, + 232, 2, 0, 0, 2, 0, 1, 0, + 18, 0, 0, 0, 17, 0, 0, 0, + 0, 0, 1, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 2, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 224, 2, 0, 0, 3, 0, 1, 0, + 236, 2, 0, 0, 2, 0, 1, 0, + 19, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 1, 0, 19, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 233, 2, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 2, 0, 0, 3, 0, 1, 0, + 244, 2, 0, 0, 2, 0, 1, 0, + 20, 0, 0, 0, 19, 0, 0, 0, + 0, 0, 1, 0, 20, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 2, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 2, 0, 0, 3, 0, 1, 0, + 252, 2, 0, 0, 2, 0, 1, 0, + 21, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 21, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 249, 2, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 248, 2, 0, 0, 3, 0, 1, 0, + 4, 3, 0, 0, 2, 0, 1, 0, + 22, 0, 0, 0, 20, 0, 0, 0, + 0, 0, 1, 0, 22, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 3, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 3, 0, 0, 3, 0, 1, 0, + 16, 3, 0, 0, 2, 0, 1, 0, + 98, 111, 97, 114, 100, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 111, 111, 116, 108, 111, 97, 100, + 101, 114, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 114, 97, 110, 100, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 118, 105, 99, 101, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 105, 115, 112, 108, 97, 121, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 105, 110, 103, 101, 114, 112, 114, + 105, 110, 116, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 97, 114, 100, 119, 97, 114, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 111, 115, 116, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 100, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 97, 110, 117, 102, 97, 99, 116, + 117, 114, 101, 114, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 111, 100, 101, 108, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 114, 111, 100, 117, 99, 116, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 97, 100, 105, 111, 86, 101, 114, + 115, 105, 111, 110, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 101, 114, 105, 97, 108, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 117, 112, 112, 111, 114, 116, 101, + 100, 65, 98, 105, 115, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 97, 103, 115, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 109, 101, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 121, 112, 101, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 115, 101, 114, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 101, 114, 115, 105, 111, 110, 67, + 111, 100, 101, 110, 97, 109, 101, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 101, 114, 115, 105, 111, 110, 82, + 101, 108, 101, 97, 115, 101, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 101, 114, 115, 105, 111, 110, 83, + 100, 107, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 101, 114, 115, 105, 111, 110, 83, + 101, 99, 117, 114, 105, 116, 121, 80, + 97, 116, 99, 104, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_fe2919d5c21f426c = b_fe2919d5c21f426c.words; +#if !CAPNP_LITE +static const uint16_t m_fe2919d5c21f426c[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22}; +static const uint16_t i_fe2919d5c21f426c[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22}; +const ::capnp::_::RawSchema s_fe2919d5c21f426c = { + 0xfe2919d5c21f426c, b_fe2919d5c21f426c.words, 379, nullptr, m_fe2919d5c21f426c, + 0, 23, i_fe2919d5c21f426c, nullptr, nullptr, { &s_fe2919d5c21f426c, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<238> b_9b513b93a887dbcd = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 205, 219, 135, 168, 147, 59, 81, 155, + 19, 0, 0, 0, 1, 0, 6, 0, + 92, 182, 63, 235, 202, 8, 16, 231, + 3, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 10, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 23, 3, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 73, 110, 105, 116, 68, 97, + 116, 97, 46, 65, 110, 100, 114, 111, + 105, 100, 83, 101, 110, 115, 111, 114, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 56, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 1, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 1, 0, 0, 3, 0, 1, 0, + 128, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 1, 0, 0, 3, 0, 1, 0, + 132, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 129, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 1, 0, 0, 3, 0, 1, 0, + 136, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 1, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 128, 1, 0, 0, 3, 0, 1, 0, + 140, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 137, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 132, 1, 0, 0, 3, 0, 1, 0, + 144, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 136, 1, 0, 0, 3, 0, 1, 0, + 148, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 145, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 144, 1, 0, 0, 3, 0, 1, 0, + 156, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 1, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 152, 1, 0, 0, 3, 0, 1, 0, + 164, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 161, 1, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 156, 1, 0, 0, 3, 0, 1, 0, + 168, 1, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 165, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 164, 1, 0, 0, 3, 0, 1, 0, + 176, 1, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 173, 1, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 1, 0, 0, 3, 0, 1, 0, + 188, 1, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 1, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 1, 0, 0, 3, 0, 1, 0, + 200, 1, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 1, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 1, 0, 0, 3, 0, 1, 0, + 208, 1, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 1, 0, 0, 3, 0, 1, 0, + 216, 1, 0, 0, 2, 0, 1, 0, + 105, 100, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 97, 109, 101, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 101, 110, 100, 111, 114, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 101, 114, 115, 105, 111, 110, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 97, 110, 100, 108, 101, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 121, 112, 101, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 97, 120, 82, 97, 110, 103, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 101, 115, 111, 108, 117, 116, 105, + 111, 110, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 119, 101, 114, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 105, 110, 68, 101, 108, 97, 121, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 105, 102, 111, 82, 101, 115, 101, + 114, 118, 101, 100, 69, 118, 101, 110, + 116, 67, 111, 117, 110, 116, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 105, 102, 111, 77, 97, 120, 69, + 118, 101, 110, 116, 67, 111, 117, 110, + 116, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 114, 105, 110, 103, 84, 121, + 112, 101, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 97, 120, 68, 101, 108, 97, 121, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_9b513b93a887dbcd = b_9b513b93a887dbcd.words; +#if !CAPNP_LITE +static const uint16_t m_9b513b93a887dbcd[] = {11, 10, 4, 0, 13, 6, 9, 1, 8, 7, 12, 5, 2, 3}; +static const uint16_t i_9b513b93a887dbcd[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13}; +const ::capnp::_::RawSchema s_9b513b93a887dbcd = { + 0x9b513b93a887dbcd, b_9b513b93a887dbcd.words, 238, nullptr, m_9b513b93a887dbcd, + 0, 14, i_9b513b93a887dbcd, nullptr, nullptr, { &s_9b513b93a887dbcd, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<55> b_9cfb5d53a4f615a5 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 165, 21, 246, 164, 83, 93, 251, 156, + 19, 0, 0, 0, 1, 0, 0, 0, + 92, 182, 63, 235, 202, 8, 16, 231, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 42, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 63, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 73, 110, 105, 116, 68, 97, + 116, 97, 46, 67, 104, 102, 102, 114, + 65, 110, 100, 114, 111, 105, 100, 69, + 120, 116, 114, 97, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 4, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 202, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 0, 0, 0, 3, 0, 1, 0, + 104, 0, 0, 0, 2, 0, 1, 0, + 97, 108, 108, 67, 97, 109, 101, 114, + 97, 67, 104, 97, 114, 97, 99, 116, + 101, 114, 105, 115, 116, 105, 99, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 150, 182, 62, 24, 226, 60, 177, 248, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 1, 0, + 1, 0, 0, 0, 31, 0, 0, 0, + 4, 0, 0, 0, 2, 0, 1, 0, + 150, 182, 62, 24, 226, 60, 177, 248, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 39, 0, 0, 0, + 8, 0, 0, 0, 1, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 3, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 3, 0, 1, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_9cfb5d53a4f615a5 = b_9cfb5d53a4f615a5.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_9cfb5d53a4f615a5[] = { + &s_f8b13ce2183eb696, +}; +static const uint16_t m_9cfb5d53a4f615a5[] = {0}; +static const uint16_t i_9cfb5d53a4f615a5[] = {0}; +KJ_CONSTEXPR(const) ::capnp::_::RawBrandedSchema::Dependency bd_9cfb5d53a4f615a5[] = { + { 16777216, ::cereal::Map< ::capnp::Text, ::capnp::Text>::_capnpPrivate::brand() }, +}; +const ::capnp::_::RawSchema s_9cfb5d53a4f615a5 = { + 0x9cfb5d53a4f615a5, b_9cfb5d53a4f615a5.words, 55, d_9cfb5d53a4f615a5, m_9cfb5d53a4f615a5, + 1, 1, i_9cfb5d53a4f615a5, nullptr, nullptr, { &s_9cfb5d53a4f615a5, nullptr, bd_9cfb5d53a4f615a5, 0, sizeof(bd_9cfb5d53a4f615a5) / sizeof(bd_9cfb5d53a4f615a5[0]), nullptr }, true +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<82> b_d97e3b28239f5580 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 128, 85, 159, 35, 40, 59, 126, 217, + 19, 0, 0, 0, 1, 0, 1, 0, + 92, 182, 63, 235, 202, 8, 16, 231, + 3, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 2, 1, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 231, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 73, 110, 105, 116, 68, 97, + 116, 97, 46, 73, 111, 115, 66, 117, + 105, 108, 100, 73, 110, 102, 111, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 0, 0, 0, 3, 0, 1, 0, + 108, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 0, 0, 0, 3, 0, 1, 0, + 116, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 0, 0, 0, 3, 0, 1, 0, + 124, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 0, 0, 0, 3, 0, 1, 0, + 132, 0, 0, 0, 2, 0, 1, 0, + 97, 112, 112, 86, 101, 114, 115, 105, + 111, 110, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 112, 112, 66, 117, 105, 108, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 115, 86, 101, 114, 115, 105, 111, + 110, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 118, 105, 99, 101, 77, 111, + 100, 101, 108, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_d97e3b28239f5580 = b_d97e3b28239f5580.words; +#if !CAPNP_LITE +static const uint16_t m_d97e3b28239f5580[] = {1, 0, 3, 2}; +static const uint16_t i_d97e3b28239f5580[] = {0, 1, 2, 3}; +const ::capnp::_::RawSchema s_d97e3b28239f5580 = { + 0xd97e3b28239f5580, b_d97e3b28239f5580.words, 82, nullptr, m_d97e3b28239f5580, + 0, 4, i_d97e3b28239f5580, nullptr, nullptr, { &s_d97e3b28239f5580, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<527> b_ea0245f695ae0a33 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 51, 10, 174, 149, 246, 69, 2, 234, + 10, 0, 0, 0, 1, 0, 12, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 7, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 162, 0, 0, 0, + 29, 0, 0, 0, 55, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 95, 6, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 70, 114, 97, 109, 101, 68, + 97, 116, 97, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 1, 0, 1, 0, + 121, 40, 16, 30, 240, 105, 177, 221, + 17, 0, 0, 0, 82, 0, 0, 0, + 156, 214, 93, 112, 231, 177, 16, 216, + 17, 0, 0, 0, 98, 0, 0, 0, + 72, 32, 29, 196, 186, 239, 195, 188, + 17, 0, 0, 0, 170, 0, 0, 0, + 70, 114, 97, 109, 101, 84, 121, 112, + 101, 0, 0, 0, 0, 0, 0, 0, + 73, 109, 97, 103, 101, 83, 101, 110, + 115, 111, 114, 0, 0, 0, 0, 0, + 65, 110, 100, 114, 111, 105, 100, 67, + 97, 112, 116, 117, 114, 101, 82, 101, + 115, 117, 108, 116, 0, 0, 0, 0, + 116, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 3, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 24, 3, 0, 0, 3, 0, 1, 0, + 36, 3, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 3, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 3, 0, 0, 3, 0, 1, 0, + 44, 3, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 3, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 3, 0, 0, 3, 0, 1, 0, + 52, 3, 0, 0, 2, 0, 1, 0, + 18, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 3, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 52, 3, 0, 0, 3, 0, 1, 0, + 64, 3, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 3, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 60, 3, 0, 0, 3, 0, 1, 0, + 72, 3, 0, 0, 2, 0, 1, 0, + 19, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 3, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 3, 0, 0, 3, 0, 1, 0, + 84, 3, 0, 0, 2, 0, 1, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 81, 3, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 3, 0, 0, 3, 0, 1, 0, + 88, 3, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 14, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 85, 3, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 84, 3, 0, 0, 3, 0, 1, 0, + 96, 3, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 3, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 3, 0, 0, 3, 0, 1, 0, + 104, 3, 0, 0, 2, 0, 1, 0, + 20, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 3, 0, 0, 250, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 3, 0, 0, 3, 0, 1, 0, + 120, 3, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 3, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 3, 0, 0, 3, 0, 1, 0, + 144, 3, 0, 0, 2, 0, 1, 0, + 21, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 3, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 144, 3, 0, 0, 3, 0, 1, 0, + 156, 3, 0, 0, 2, 0, 1, 0, + 22, 0, 0, 0, 11, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 3, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 156, 3, 0, 0, 3, 0, 1, 0, + 168, 3, 0, 0, 2, 0, 1, 0, + 23, 0, 0, 0, 12, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 165, 3, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 3, 0, 0, 3, 0, 1, 0, + 180, 3, 0, 0, 2, 0, 1, 0, + 24, 0, 0, 0, 13, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 3, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 3, 0, 0, 3, 0, 1, 0, + 192, 3, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 14, 0, 0, 0, + 0, 0, 1, 0, 15, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 3, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 3, 0, 0, 3, 0, 1, 0, + 196, 3, 0, 0, 2, 0, 1, 0, + 25, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 16, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 3, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 3, 0, 0, 3, 0, 1, 0, + 224, 3, 0, 0, 2, 0, 1, 0, + 26, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 17, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 3, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 224, 3, 0, 0, 3, 0, 1, 0, + 252, 3, 0, 0, 2, 0, 1, 0, + 27, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 249, 3, 0, 0, 202, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 4, 0, 0, 3, 0, 1, 0, + 28, 4, 0, 0, 2, 0, 1, 0, + 28, 0, 0, 0, 15, 0, 0, 0, + 0, 0, 1, 0, 19, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 4, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 28, 4, 0, 0, 3, 0, 1, 0, + 40, 4, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 240, 0, 0, 0, + 0, 0, 1, 0, 20, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 4, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 4, 0, 0, 3, 0, 1, 0, + 52, 4, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 16, 0, 0, 0, + 0, 0, 1, 0, 21, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 4, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 52, 4, 0, 0, 3, 0, 1, 0, + 64, 4, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 17, 0, 0, 0, + 0, 0, 1, 0, 22, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 4, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 4, 0, 0, 3, 0, 1, 0, + 76, 4, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 1, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 4, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 4, 0, 0, 3, 0, 1, 0, + 84, 4, 0, 0, 2, 0, 1, 0, + 16, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 24, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 81, 4, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 80, 4, 0, 0, 3, 0, 1, 0, + 108, 4, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 19, 0, 0, 0, + 0, 0, 1, 0, 25, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 4, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 4, 0, 0, 3, 0, 1, 0, + 116, 4, 0, 0, 2, 0, 1, 0, + 17, 0, 0, 0, 40, 0, 0, 0, + 0, 0, 1, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 4, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 4, 0, 0, 3, 0, 1, 0, + 120, 4, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 21, 0, 0, 0, + 0, 0, 1, 0, 27, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 4, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 4, 0, 0, 3, 0, 1, 0, + 132, 4, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 22, 0, 0, 0, + 0, 0, 1, 0, 28, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 129, 4, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 128, 4, 0, 0, 3, 0, 1, 0, + 140, 4, 0, 0, 2, 0, 1, 0, + 102, 114, 97, 109, 101, 73, 100, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 110, 99, 111, 100, 101, 73, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 109, 101, 115, 116, 97, 109, + 112, 69, 111, 102, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 114, 97, 109, 101, 76, 101, 110, + 103, 116, 104, 68, 69, 80, 82, 69, + 67, 65, 84, 69, 68, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 110, 116, 101, 103, 76, 105, 110, + 101, 115, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 108, 111, 98, 97, 108, 71, 97, + 105, 110, 68, 69, 80, 82, 69, 67, + 65, 84, 69, 68, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 109, 97, 103, 101, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 114, 97, 109, 101, 84, 121, 112, + 101, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 121, 40, 16, 30, 240, 105, 177, 221, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 109, 101, 115, 116, 97, 109, + 112, 83, 111, 102, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 110, 100, 114, 111, 105, 100, 67, + 97, 112, 116, 117, 114, 101, 82, 101, + 115, 117, 108, 116, 68, 69, 80, 82, + 69, 67, 65, 84, 69, 68, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 72, 32, 29, 196, 186, 239, 195, 188, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 114, 97, 110, 115, 102, 111, 114, + 109, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 110, 115, 80, 111, 115, 68, + 69, 80, 82, 69, 67, 65, 84, 69, + 68, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 110, 115, 83, 97, 103, 68, + 69, 80, 82, 69, 67, 65, 84, 69, + 68, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 110, 115, 69, 114, 114, 68, + 69, 80, 82, 69, 67, 65, 84, 69, + 68, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 110, 115, 84, 114, 117, 101, + 80, 111, 115, 68, 69, 80, 82, 69, + 67, 65, 84, 69, 68, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 97, 105, 110, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 111, 99, 117, 115, 86, 97, 108, + 68, 69, 80, 82, 69, 67, 65, 84, + 69, 68, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 111, 99, 117, 115, 67, 111, 110, + 102, 68, 69, 80, 82, 69, 67, 65, + 84, 69, 68, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 104, 97, 114, 112, 110, 101, 115, + 115, 83, 99, 111, 114, 101, 68, 69, + 80, 82, 69, 67, 65, 84, 69, 68, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 101, 99, 111, 118, 101, 114, 83, + 116, 97, 116, 101, 68, 69, 80, 82, + 69, 67, 65, 84, 69, 68, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 105, 103, 104, 67, 111, 110, 118, + 101, 114, 115, 105, 111, 110, 71, 97, + 105, 110, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 101, 97, 115, 117, 114, 101, 100, + 71, 114, 101, 121, 70, 114, 97, 99, + 116, 105, 111, 110, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 97, 114, 103, 101, 116, 71, 114, + 101, 121, 70, 114, 97, 99, 116, 105, + 111, 110, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 114, 111, 99, 101, 115, 115, 105, + 110, 103, 84, 105, 109, 101, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 101, 109, 112, 101, 114, 97, 116, + 117, 114, 101, 115, 67, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 114, 97, 109, 101, 73, 100, 83, + 101, 110, 115, 111, 114, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 101, 110, 115, 111, 114, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 156, 214, 93, 112, 231, 177, 16, 216, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 120, 112, 111, 115, 117, 114, 101, + 86, 97, 108, 80, 101, 114, 99, 101, + 110, 116, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 101, 113, 117, 101, 115, 116, 73, + 100, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_ea0245f695ae0a33 = b_ea0245f695ae0a33.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_ea0245f695ae0a33[] = { + &s_bcc3efbac41d2048, + &s_d810b1e7705dd69c, + &s_ddb169f01e102879, +}; +static const uint16_t m_ea0245f695ae0a33[] = {9, 1, 27, 17, 16, 0, 25, 3, 7, 15, 5, 20, 6, 4, 13, 11, 12, 14, 21, 23, 19, 28, 26, 18, 22, 24, 2, 8, 10}; +static const uint16_t i_ea0245f695ae0a33[] = {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}; +const ::capnp::_::RawSchema s_ea0245f695ae0a33 = { + 0xea0245f695ae0a33, b_ea0245f695ae0a33.words, 527, d_ea0245f695ae0a33, m_ea0245f695ae0a33, + 3, 29, i_ea0245f695ae0a33, nullptr, nullptr, { &s_ea0245f695ae0a33, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<35> b_ddb169f01e102879 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 121, 40, 16, 30, 240, 105, 177, 221, + 20, 0, 0, 0, 2, 0, 0, 0, + 51, 10, 174, 149, 246, 69, 2, 234, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 242, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 103, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 70, 114, 97, 109, 101, 68, + 97, 116, 97, 46, 70, 114, 97, 109, + 101, 84, 121, 112, 101, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 110, 107, 110, 111, 119, 110, 0, + 110, 101, 111, 0, 0, 0, 0, 0, + 99, 104, 102, 102, 114, 65, 110, 100, + 114, 111, 105, 100, 0, 0, 0, 0, + 102, 114, 111, 110, 116, 0, 0, 0, } +}; +::capnp::word const* const bp_ddb169f01e102879 = b_ddb169f01e102879.words; +#if !CAPNP_LITE +static const uint16_t m_ddb169f01e102879[] = {2, 3, 1, 0}; +const ::capnp::_::RawSchema s_ddb169f01e102879 = { + 0xddb169f01e102879, b_ddb169f01e102879.words, 35, nullptr, m_ddb169f01e102879, + 0, 4, nullptr, nullptr, nullptr, { &s_ddb169f01e102879, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(FrameType_ddb169f01e102879, ddb169f01e102879); +static const ::capnp::_::AlignedData<34> b_d810b1e7705dd69c = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 156, 214, 93, 112, 231, 177, 16, 216, + 20, 0, 0, 0, 2, 0, 0, 0, + 51, 10, 174, 149, 246, 69, 2, 234, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 2, 1, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 103, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 70, 114, 97, 109, 101, 68, + 97, 116, 97, 46, 73, 109, 97, 103, + 101, 83, 101, 110, 115, 111, 114, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 17, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 110, 107, 110, 111, 119, 110, 0, + 97, 114, 48, 50, 51, 49, 0, 0, + 111, 120, 48, 51, 99, 49, 48, 0, + 111, 115, 48, 52, 99, 49, 48, 0, } +}; +::capnp::word const* const bp_d810b1e7705dd69c = b_d810b1e7705dd69c.words; +#if !CAPNP_LITE +static const uint16_t m_d810b1e7705dd69c[] = {1, 3, 2, 0}; +const ::capnp::_::RawSchema s_d810b1e7705dd69c = { + 0xd810b1e7705dd69c, b_d810b1e7705dd69c.words, 34, nullptr, m_d810b1e7705dd69c, + 0, 4, nullptr, nullptr, nullptr, { &s_d810b1e7705dd69c, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(ImageSensor_d810b1e7705dd69c, d810b1e7705dd69c); +static const ::capnp::_::AlignedData<144> b_bcc3efbac41d2048 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 72, 32, 29, 196, 186, 239, 195, 188, + 20, 0, 0, 0, 1, 0, 4, 0, + 51, 10, 174, 149, 246, 69, 2, 234, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 74, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 143, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 70, 114, 97, 109, 101, 68, + 97, 116, 97, 46, 65, 110, 100, 114, + 111, 105, 100, 67, 97, 112, 116, 117, + 114, 101, 82, 101, 115, 117, 108, 116, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 28, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 0, 0, 0, 3, 0, 1, 0, + 192, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 0, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 0, 0, 0, 3, 0, 1, 0, + 200, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 0, 0, 0, 3, 0, 1, 0, + 208, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 0, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 0, 0, 0, 3, 0, 1, 0, + 220, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 217, 0, 0, 0, 202, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 224, 0, 0, 0, 3, 0, 1, 0, + 252, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 249, 0, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 252, 0, 0, 0, 3, 0, 1, 0, + 24, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 1, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 1, 0, 0, 3, 0, 1, 0, + 32, 1, 0, 0, 2, 0, 1, 0, + 115, 101, 110, 115, 105, 116, 105, 118, + 105, 116, 121, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 114, 97, 109, 101, 68, 117, 114, + 97, 116, 105, 111, 110, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 120, 112, 111, 115, 117, 114, 101, + 84, 105, 109, 101, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 111, 108, 108, 105, 110, 103, 83, + 104, 117, 116, 116, 101, 114, 83, 107, + 101, 119, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 111, 108, 111, 114, 67, 111, 114, + 114, 101, 99, 116, 105, 111, 110, 84, + 114, 97, 110, 115, 102, 111, 114, 109, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 111, 108, 111, 114, 67, 111, 114, + 114, 101, 99, 116, 105, 111, 110, 71, + 97, 105, 110, 115, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 105, 115, 112, 108, 97, 121, 82, + 111, 116, 97, 116, 105, 111, 110, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_bcc3efbac41d2048 = b_bcc3efbac41d2048.words; +#if !CAPNP_LITE +static const uint16_t m_bcc3efbac41d2048[] = {5, 4, 6, 2, 1, 3, 0}; +static const uint16_t i_bcc3efbac41d2048[] = {0, 1, 2, 3, 4, 5, 6}; +const ::capnp::_::RawSchema s_bcc3efbac41d2048 = { + 0xbcc3efbac41d2048, b_bcc3efbac41d2048.words, 144, nullptr, m_bcc3efbac41d2048, + 0, 7, i_bcc3efbac41d2048, nullptr, nullptr, { &s_bcc3efbac41d2048, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<64> b_b65fce64120af7d3 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 211, 247, 10, 18, 100, 206, 95, 182, + 10, 0, 0, 0, 1, 0, 2, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 162, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 84, 104, 117, 109, 98, 110, + 97, 105, 108, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 0, 0, 0, 3, 0, 1, 0, + 76, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 0, 0, 0, 3, 0, 1, 0, + 84, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 81, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 80, 0, 0, 0, 3, 0, 1, 0, + 92, 0, 0, 0, 2, 0, 1, 0, + 102, 114, 97, 109, 101, 73, 100, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 109, 101, 115, 116, 97, 109, + 112, 69, 111, 102, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 104, 117, 109, 98, 110, 97, 105, + 108, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_b65fce64120af7d3 = b_b65fce64120af7d3.words; +#if !CAPNP_LITE +static const uint16_t m_b65fce64120af7d3[] = {0, 2, 1}; +static const uint16_t i_b65fce64120af7d3[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_b65fce64120af7d3 = { + 0xb65fce64120af7d3, b_b65fce64120af7d3.words, 64, nullptr, m_b65fce64120af7d3, + 0, 3, i_b65fce64120af7d3, nullptr, nullptr, { &s_b65fce64120af7d3, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<64> b_9d291d7813ba4a88 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 136, 74, 186, 19, 120, 29, 41, 157, + 10, 0, 0, 0, 1, 0, 2, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 178, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 71, 80, 83, 78, 77, 69, + 65, 68, 97, 116, 97, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 0, 0, 0, 3, 0, 1, 0, + 80, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 0, 0, 0, 3, 0, 1, 0, + 88, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 85, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 80, 0, 0, 0, 3, 0, 1, 0, + 92, 0, 0, 0, 2, 0, 1, 0, + 116, 105, 109, 101, 115, 116, 97, 109, + 112, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 99, 97, 108, 87, 97, 108, + 108, 84, 105, 109, 101, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 109, 101, 97, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_9d291d7813ba4a88 = b_9d291d7813ba4a88.words; +#if !CAPNP_LITE +static const uint16_t m_9d291d7813ba4a88[] = {1, 2, 0}; +static const uint16_t i_9d291d7813ba4a88[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_9d291d7813ba4a88 = { + 0x9d291d7813ba4a88, b_9d291d7813ba4a88.words, 64, nullptr, m_9d291d7813ba4a88, + 0, 3, i_9d291d7813ba4a88, nullptr, nullptr, { &s_9d291d7813ba4a88, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<279> b_a2b29a69d44529a1 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 161, 41, 69, 212, 105, 154, 178, 162, + 10, 0, 0, 0, 1, 0, 4, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 1, 0, 7, 0, 0, 0, 10, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 210, 0, 0, 0, + 33, 0, 0, 0, 39, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 0, 0, 0, 135, 3, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 83, 101, 110, 115, 111, 114, + 69, 118, 101, 110, 116, 68, 97, 116, + 97, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 1, 0, 1, 0, + 252, 36, 252, 43, 189, 41, 52, 164, + 9, 0, 0, 0, 82, 0, 0, 0, + 13, 141, 244, 247, 232, 60, 155, 228, + 9, 0, 0, 0, 106, 0, 0, 0, + 83, 101, 110, 115, 111, 114, 86, 101, + 99, 0, 0, 0, 0, 0, 0, 0, + 83, 101, 110, 115, 111, 114, 83, 111, + 117, 114, 99, 101, 0, 0, 0, 0, + 64, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 1, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 172, 1, 0, 0, 3, 0, 1, 0, + 184, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 1, 0, 0, 3, 0, 1, 0, + 188, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 1, 0, 0, 3, 0, 1, 0, + 192, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 1, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 1, 0, 0, 3, 0, 1, 0, + 200, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 255, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 1, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 1, 0, 0, 3, 0, 1, 0, + 208, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 254, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 1, 0, 0, 3, 0, 1, 0, + 216, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 253, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 1, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 212, 1, 0, 0, 3, 0, 1, 0, + 224, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 252, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 1, 0, 0, 3, 0, 1, 0, + 228, 1, 0, 0, 2, 0, 1, 0, + 15, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 225, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 220, 1, 0, 0, 3, 0, 1, 0, + 232, 1, 0, 0, 2, 0, 1, 0, + 9, 0, 251, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 228, 1, 0, 0, 3, 0, 1, 0, + 240, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 192, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 1, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 1, 0, 0, 3, 0, 1, 0, + 252, 1, 0, 0, 2, 0, 1, 0, + 10, 0, 250, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 249, 1, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 252, 1, 0, 0, 3, 0, 1, 0, + 8, 2, 0, 0, 2, 0, 1, 0, + 11, 0, 249, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 2, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 2, 0, 0, 3, 0, 1, 0, + 20, 2, 0, 0, 2, 0, 1, 0, + 12, 0, 248, 255, 7, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 2, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 2, 0, 0, 3, 0, 1, 0, + 28, 2, 0, 0, 2, 0, 1, 0, + 13, 0, 247, 255, 7, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 2, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 2, 0, 0, 3, 0, 1, 0, + 32, 2, 0, 0, 2, 0, 1, 0, + 14, 0, 246, 255, 7, 0, 0, 0, + 0, 0, 1, 0, 15, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 2, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 28, 2, 0, 0, 3, 0, 1, 0, + 40, 2, 0, 0, 2, 0, 1, 0, + 118, 101, 114, 115, 105, 111, 110, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 101, 110, 115, 111, 114, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 121, 112, 101, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 109, 101, 115, 116, 97, 109, + 112, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 99, 101, 108, 101, 114, 97, + 116, 105, 111, 110, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 252, 36, 252, 43, 189, 41, 52, 164, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 97, 103, 110, 101, 116, 105, 99, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 252, 36, 252, 43, 189, 41, 52, 164, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 114, 105, 101, 110, 116, 97, 116, + 105, 111, 110, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 252, 36, 252, 43, 189, 41, 52, 164, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 121, 114, 111, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 252, 36, 252, 43, 189, 41, 52, 164, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 111, 117, 114, 99, 101, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 13, 141, 244, 247, 232, 60, 155, 228, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 114, 101, 115, 115, 117, 114, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 252, 36, 252, 43, 189, 41, 52, 164, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 110, 99, 97, 108, 105, 98, 114, + 97, 116, 101, 100, 68, 69, 80, 82, + 69, 67, 65, 84, 69, 68, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 97, 103, 110, 101, 116, 105, 99, + 85, 110, 99, 97, 108, 105, 98, 114, + 97, 116, 101, 100, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 252, 36, 252, 43, 189, 41, 52, 164, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 121, 114, 111, 85, 110, 99, 97, + 108, 105, 98, 114, 97, 116, 101, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 252, 36, 252, 43, 189, 41, 52, 164, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 114, 111, 120, 105, 109, 105, 116, + 121, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 105, 103, 104, 116, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 101, 109, 112, 101, 114, 97, 116, + 117, 114, 101, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_a2b29a69d44529a1 = b_a2b29a69d44529a1.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_a2b29a69d44529a1[] = { + &s_a43429bd2bfc24fc, + &s_e49b3ce8f7f48d0d, +}; +static const uint16_t m_a2b29a69d44529a1[] = {4, 7, 12, 14, 5, 11, 6, 9, 13, 1, 8, 15, 3, 2, 10, 0}; +static const uint16_t i_a2b29a69d44529a1[] = {4, 5, 6, 7, 9, 11, 12, 13, 14, 15, 0, 1, 2, 3, 8, 10}; +const ::capnp::_::RawSchema s_a2b29a69d44529a1 = { + 0xa2b29a69d44529a1, b_a2b29a69d44529a1.words, 279, d_a2b29a69d44529a1, m_a2b29a69d44529a1, + 2, 16, i_a2b29a69d44529a1, nullptr, nullptr, { &s_a2b29a69d44529a1, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<53> b_a43429bd2bfc24fc = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 252, 36, 252, 43, 189, 41, 52, 164, + 26, 0, 0, 0, 1, 0, 1, 0, + 161, 41, 69, 212, 105, 154, 178, 162, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 34, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 83, 101, 110, 115, 111, 114, + 69, 118, 101, 110, 116, 68, 97, 116, + 97, 46, 83, 101, 110, 115, 111, 114, + 86, 101, 99, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 64, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 56, 0, 0, 0, 3, 0, 1, 0, + 68, 0, 0, 0, 2, 0, 1, 0, + 118, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 116, 117, 115, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_a43429bd2bfc24fc = b_a43429bd2bfc24fc.words; +#if !CAPNP_LITE +static const uint16_t m_a43429bd2bfc24fc[] = {1, 0}; +static const uint16_t i_a43429bd2bfc24fc[] = {0, 1}; +const ::capnp::_::RawSchema s_a43429bd2bfc24fc = { + 0xa43429bd2bfc24fc, b_a43429bd2bfc24fc.words, 53, nullptr, m_a43429bd2bfc24fc, + 0, 2, i_a43429bd2bfc24fc, nullptr, nullptr, { &s_a43429bd2bfc24fc, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<71> b_e49b3ce8f7f48d0d = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 13, 141, 244, 247, 232, 60, 155, 228, + 26, 0, 0, 0, 2, 0, 0, 0, + 161, 41, 69, 212, 105, 154, 178, 162, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 58, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 39, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 83, 101, 110, 115, 111, 114, + 69, 118, 101, 110, 116, 68, 97, 116, + 97, 46, 83, 101, 110, 115, 111, 114, + 83, 111, 117, 114, 99, 101, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 48, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 137, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 129, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 121, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 113, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 109, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 101, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 93, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 85, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 81, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 65, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 61, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 110, 100, 114, 111, 105, 100, 0, + 105, 79, 83, 0, 0, 0, 0, 0, + 102, 105, 98, 101, 114, 0, 0, 0, + 118, 101, 108, 111, 100, 121, 110, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 110, 111, 48, 53, 53, 0, 0, + 108, 115, 109, 54, 100, 115, 51, 0, + 98, 109, 112, 50, 56, 48, 0, 0, + 109, 109, 99, 51, 52, 49, 54, 120, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 109, 120, 48, 53, 53, 0, 0, + 114, 112, 114, 48, 53, 50, 49, 0, + 108, 115, 109, 54, 100, 115, 51, 116, + 114, 99, 0, 0, 0, 0, 0, 0, + 109, 109, 99, 53, 54, 48, 51, 110, + 106, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e49b3ce8f7f48d0d = b_e49b3ce8f7f48d0d.words; +#if !CAPNP_LITE +static const uint16_t m_e49b3ce8f7f48d0d[] = {0, 6, 8, 4, 2, 1, 5, 10, 7, 11, 9, 3}; +const ::capnp::_::RawSchema s_e49b3ce8f7f48d0d = { + 0xe49b3ce8f7f48d0d, b_e49b3ce8f7f48d0d.words, 71, nullptr, m_e49b3ce8f7f48d0d, + 0, 12, nullptr, nullptr, nullptr, { &s_e49b3ce8f7f48d0d, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(SensorSource_e49b3ce8f7f48d0d, e49b3ce8f7f48d0d); +static const ::capnp::_::AlignedData<233> b_e946524859add50e = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 14, 213, 173, 89, 72, 82, 70, 233, + 10, 0, 0, 0, 1, 0, 8, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 210, 0, 0, 0, + 33, 0, 0, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 223, 2, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 71, 112, 115, 76, 111, 99, + 97, 116, 105, 111, 110, 68, 97, 116, + 97, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 1, 0, 1, 0, + 99, 72, 115, 92, 242, 121, 255, 211, + 1, 0, 0, 0, 106, 0, 0, 0, + 83, 101, 110, 115, 111, 114, 83, 111, + 117, 114, 99, 101, 0, 0, 0, 0, + 52, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 1, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 88, 1, 0, 0, 3, 0, 1, 0, + 100, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 1, 0, 0, 3, 0, 1, 0, + 108, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 1, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 1, 0, 0, 3, 0, 1, 0, + 116, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 1, 0, 0, 3, 0, 1, 0, + 124, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 1, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 1, 0, 0, 3, 0, 1, 0, + 128, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 1, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 1, 0, 0, 3, 0, 1, 0, + 136, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 132, 1, 0, 0, 3, 0, 1, 0, + 144, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 1, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 144, 1, 0, 0, 3, 0, 1, 0, + 156, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 1, 0, 0, 3, 0, 1, 0, + 160, 1, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 157, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 152, 1, 0, 0, 3, 0, 1, 0, + 180, 1, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 12, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 1, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 1, 0, 0, 3, 0, 1, 0, + 192, 1, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 13, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 1, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 192, 1, 0, 0, 3, 0, 1, 0, + 204, 1, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 14, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 1, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 200, 1, 0, 0, 3, 0, 1, 0, + 212, 1, 0, 0, 2, 0, 1, 0, + 102, 108, 97, 103, 115, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 116, 105, 116, 117, 100, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 110, 103, 105, 116, 117, 100, + 101, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 108, 116, 105, 116, 117, 100, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 112, 101, 101, 100, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 101, 97, 114, 105, 110, 103, 68, + 101, 103, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 99, 117, 114, 97, 99, 121, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 110, 105, 120, 84, 105, 109, 101, + 115, 116, 97, 109, 112, 77, 105, 108, + 108, 105, 115, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 111, 117, 114, 99, 101, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 99, 72, 115, 92, 242, 121, 255, 211, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 78, 69, 68, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 101, 114, 116, 105, 99, 97, 108, + 65, 99, 99, 117, 114, 97, 99, 121, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 101, 97, 114, 105, 110, 103, 65, + 99, 99, 117, 114, 97, 99, 121, 68, + 101, 103, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 112, 101, 101, 100, 65, 99, 99, + 117, 114, 97, 99, 121, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e946524859add50e = b_e946524859add50e.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_e946524859add50e[] = { + &s_d3ff79f25c734863, +}; +static const uint16_t m_e946524859add50e[] = {6, 3, 11, 5, 0, 1, 2, 8, 4, 12, 7, 9, 10}; +static const uint16_t i_e946524859add50e[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12}; +const ::capnp::_::RawSchema s_e946524859add50e = { + 0xe946524859add50e, b_e946524859add50e.words, 233, d_e946524859add50e, m_e946524859add50e, + 1, 13, i_e946524859add50e, nullptr, nullptr, { &s_e946524859add50e, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<58> b_d3ff79f25c734863 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 99, 72, 115, 92, 242, 121, 255, 211, + 26, 0, 0, 0, 2, 0, 0, 0, + 14, 213, 173, 89, 72, 82, 70, 233, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 58, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 223, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 71, 112, 115, 76, 111, 99, + 97, 116, 105, 111, 110, 68, 97, 116, + 97, 46, 83, 101, 110, 115, 111, 114, + 83, 111, 117, 114, 99, 101, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 36, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 93, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 85, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 65, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 61, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 53, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 110, 100, 114, 111, 105, 100, 0, + 105, 79, 83, 0, 0, 0, 0, 0, + 99, 97, 114, 0, 0, 0, 0, 0, + 118, 101, 108, 111, 100, 121, 110, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 117, 115, 105, 111, 110, 0, 0, + 101, 120, 116, 101, 114, 110, 97, 108, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 98, 108, 111, 120, 0, 0, 0, + 116, 114, 105, 109, 98, 108, 101, 0, + 113, 99, 111, 109, 100, 105, 97, 103, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_d3ff79f25c734863 = b_d3ff79f25c734863.words; +#if !CAPNP_LITE +static const uint16_t m_d3ff79f25c734863[] = {0, 2, 5, 4, 1, 8, 7, 6, 3}; +const ::capnp::_::RawSchema s_d3ff79f25c734863 = { + 0xd3ff79f25c734863, b_d3ff79f25c734863.words, 58, nullptr, m_d3ff79f25c734863, + 0, 9, nullptr, nullptr, nullptr, { &s_d3ff79f25c734863, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(SensorSource_d3ff79f25c734863, d3ff79f25c734863); +static const ::capnp::_::AlignedData<51> b_ae674a34ba421466 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 102, 20, 66, 186, 52, 74, 103, 174, + 10, 0, 0, 0, 2, 0, 0, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 138, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 68, 101, 115, 105, 114, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 28, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 65, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 61, 0, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 57, 0, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 53, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 49, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 111, 110, 101, 0, 0, 0, 0, + 116, 117, 114, 110, 76, 101, 102, 116, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 117, 114, 110, 82, 105, 103, 104, + 116, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 110, 101, 67, 104, 97, 110, + 103, 101, 76, 101, 102, 116, 0, 0, + 108, 97, 110, 101, 67, 104, 97, 110, + 103, 101, 82, 105, 103, 104, 116, 0, + 107, 101, 101, 112, 76, 101, 102, 116, + 0, 0, 0, 0, 0, 0, 0, 0, + 107, 101, 101, 112, 82, 105, 103, 104, + 116, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_ae674a34ba421466 = b_ae674a34ba421466.words; +#if !CAPNP_LITE +static const uint16_t m_ae674a34ba421466[] = {5, 6, 3, 4, 0, 1, 2}; +const ::capnp::_::RawSchema s_ae674a34ba421466 = { + 0xae674a34ba421466, b_ae674a34ba421466.words, 51, nullptr, m_ae674a34ba421466, + 0, 7, nullptr, nullptr, nullptr, { &s_ae674a34ba421466, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(Desire_ae674a34ba421466, ae674a34ba421466); +static const ::capnp::_::AlignedData<39> b_cd37924bf7b2d3d2 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 210, 211, 178, 247, 75, 146, 55, 205, + 10, 0, 0, 0, 2, 0, 0, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 210, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 103, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 76, 97, 110, 101, 67, 104, + 97, 110, 103, 101, 83, 116, 97, 116, + 101, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 102, 102, 0, 0, 0, 0, 0, + 112, 114, 101, 76, 97, 110, 101, 67, + 104, 97, 110, 103, 101, 0, 0, 0, + 108, 97, 110, 101, 67, 104, 97, 110, + 103, 101, 83, 116, 97, 114, 116, 105, + 110, 103, 0, 0, 0, 0, 0, 0, + 108, 97, 110, 101, 67, 104, 97, 110, + 103, 101, 70, 105, 110, 105, 115, 104, + 105, 110, 103, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_cd37924bf7b2d3d2 = b_cd37924bf7b2d3d2.words; +#if !CAPNP_LITE +static const uint16_t m_cd37924bf7b2d3d2[] = {3, 2, 0, 1}; +const ::capnp::_::RawSchema s_cd37924bf7b2d3d2 = { + 0xcd37924bf7b2d3d2, b_cd37924bf7b2d3d2.words, 39, nullptr, m_cd37924bf7b2d3d2, + 0, 4, nullptr, nullptr, nullptr, { &s_cd37924bf7b2d3d2, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(LaneChangeState_cd37924bf7b2d3d2, cd37924bf7b2d3d2); +static const ::capnp::_::AlignedData<30> b_9d0bc0c1fe671176 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 118, 17, 103, 254, 193, 192, 11, 157, + 10, 0, 0, 0, 2, 0, 0, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 242, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 79, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 76, 97, 110, 101, 67, 104, + 97, 110, 103, 101, 68, 105, 114, 101, + 99, 116, 105, 111, 110, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 111, 110, 101, 0, 0, 0, 0, + 108, 101, 102, 116, 0, 0, 0, 0, + 114, 105, 103, 104, 116, 0, 0, 0, } +}; +::capnp::word const* const bp_9d0bc0c1fe671176 = b_9d0bc0c1fe671176.words; +#if !CAPNP_LITE +static const uint16_t m_9d0bc0c1fe671176[] = {1, 0, 2}; +const ::capnp::_::RawSchema s_9d0bc0c1fe671176 = { + 0x9d0bc0c1fe671176, b_9d0bc0c1fe671176.words, 30, nullptr, m_9d0bc0c1fe671176, + 0, 3, nullptr, nullptr, nullptr, { &s_9d0bc0c1fe671176, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(LaneChangeDirection_9d0bc0c1fe671176, 9d0bc0c1fe671176); +static const ::capnp::_::AlignedData<31> b_eeb9ea49d5c19b23 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 35, 155, 193, 213, 73, 234, 185, 238, + 10, 0, 0, 0, 2, 0, 0, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 194, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 79, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 84, 117, 114, 110, 68, 105, + 114, 101, 99, 116, 105, 111, 110, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 17, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 111, 110, 101, 0, 0, 0, 0, + 116, 117, 114, 110, 76, 101, 102, 116, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 117, 114, 110, 82, 105, 103, 104, + 116, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_eeb9ea49d5c19b23 = b_eeb9ea49d5c19b23.words; +#if !CAPNP_LITE +static const uint16_t m_eeb9ea49d5c19b23[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_eeb9ea49d5c19b23 = { + 0xeeb9ea49d5c19b23, b_eeb9ea49d5c19b23.words, 31, nullptr, m_eeb9ea49d5c19b23, + 0, 3, nullptr, nullptr, nullptr, { &s_eeb9ea49d5c19b23, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(TurnDirection_eeb9ea49d5c19b23, eeb9ea49d5c19b23); +static const ::capnp::_::AlignedData<77> b_8785009a964c7c59 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 89, 124, 76, 150, 154, 0, 133, 135, + 10, 0, 0, 0, 1, 0, 1, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 146, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 231, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 67, 97, 110, 68, 97, 116, + 97, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 0, 0, 0, 3, 0, 1, 0, + 104, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 0, 0, 0, 3, 0, 1, 0, + 108, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 0, 0, 0, 3, 0, 1, 0, + 112, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 0, 0, 0, 3, 0, 1, 0, + 116, 0, 0, 0, 2, 0, 1, 0, + 97, 100, 100, 114, 101, 115, 115, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 117, 115, 84, 105, 109, 101, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 97, 116, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 114, 99, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_8785009a964c7c59 = b_8785009a964c7c59.words; +#if !CAPNP_LITE +static const uint16_t m_8785009a964c7c59[] = {0, 1, 2, 3}; +static const uint16_t i_8785009a964c7c59[] = {0, 1, 2, 3}; +const ::capnp::_::RawSchema s_8785009a964c7c59 = { + 0x8785009a964c7c59, b_8785009a964c7c59.words, 77, nullptr, m_8785009a964c7c59, + 0, 4, i_8785009a964c7c59, nullptr, nullptr, { &s_8785009a964c7c59, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<810> b_a4d8b5af2aa492eb = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 235, 146, 164, 42, 175, 181, 216, 164, + 10, 0, 0, 0, 1, 0, 12, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 10, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 178, 0, 0, 0, + 29, 0, 0, 0, 103, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 0, 0, 0, 223, 9, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 68, 101, 118, 105, 99, 101, + 83, 116, 97, 116, 101, 0, 0, 0, + 24, 0, 0, 0, 1, 0, 1, 0, + 111, 246, 61, 133, 41, 0, 121, 208, + 41, 0, 0, 0, 98, 0, 0, 0, + 126, 247, 84, 194, 16, 113, 15, 175, + 41, 0, 0, 0, 114, 0, 0, 0, + 157, 4, 209, 88, 201, 156, 199, 187, + 41, 0, 0, 0, 98, 0, 0, 0, + 19, 62, 32, 19, 138, 140, 48, 221, + 41, 0, 0, 0, 130, 0, 0, 0, + 252, 74, 192, 130, 45, 83, 87, 157, + 41, 0, 0, 0, 98, 0, 0, 0, + 160, 142, 137, 39, 234, 100, 140, 185, + 41, 0, 0, 0, 106, 0, 0, 0, + 84, 104, 101, 114, 109, 97, 108, 90, + 111, 110, 101, 0, 0, 0, 0, 0, + 84, 104, 101, 114, 109, 97, 108, 83, + 116, 97, 116, 117, 115, 0, 0, 0, + 78, 101, 116, 119, 111, 114, 107, 84, + 121, 112, 101, 0, 0, 0, 0, 0, + 78, 101, 116, 119, 111, 114, 107, 83, + 116, 114, 101, 110, 103, 116, 104, 0, + 78, 101, 116, 119, 111, 114, 107, 73, + 110, 102, 111, 0, 0, 0, 0, 0, + 78, 101, 116, 119, 111, 114, 107, 83, + 116, 97, 116, 115, 0, 0, 0, 0, + 180, 0, 0, 0, 3, 0, 4, 0, + 27, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 4, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 220, 4, 0, 0, 3, 0, 1, 0, + 232, 4, 0, 0, 2, 0, 1, 0, + 28, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 4, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 228, 4, 0, 0, 3, 0, 1, 0, + 240, 4, 0, 0, 2, 0, 1, 0, + 29, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 4, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 236, 4, 0, 0, 3, 0, 1, 0, + 248, 4, 0, 0, 2, 0, 1, 0, + 30, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 245, 4, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 244, 4, 0, 0, 3, 0, 1, 0, + 0, 5, 0, 0, 2, 0, 1, 0, + 31, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 253, 4, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 252, 4, 0, 0, 3, 0, 1, 0, + 8, 5, 0, 0, 2, 0, 1, 0, + 32, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 5, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 5, 0, 0, 3, 0, 1, 0, + 16, 5, 0, 0, 2, 0, 1, 0, + 33, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 5, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 5, 0, 0, 3, 0, 1, 0, + 24, 5, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 5, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 24, 5, 0, 0, 3, 0, 1, 0, + 36, 5, 0, 0, 2, 0, 1, 0, + 39, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 5, 0, 0, 202, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 5, 0, 0, 3, 0, 1, 0, + 52, 5, 0, 0, 2, 0, 1, 0, + 36, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 5, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 52, 5, 0, 0, 3, 0, 1, 0, + 64, 5, 0, 0, 2, 0, 1, 0, + 25, 0, 0, 0, 11, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 5, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 5, 0, 0, 3, 0, 1, 0, + 76, 5, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 192, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 5, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 5, 0, 0, 3, 0, 1, 0, + 80, 5, 0, 0, 2, 0, 1, 0, + 43, 0, 0, 0, 193, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 5, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 80, 5, 0, 0, 3, 0, 1, 0, + 92, 5, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 89, 5, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 88, 5, 0, 0, 3, 0, 1, 0, + 100, 5, 0, 0, 2, 0, 1, 0, + 24, 0, 0, 0, 13, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 5, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 5, 0, 0, 3, 0, 1, 0, + 108, 5, 0, 0, 2, 0, 1, 0, + 40, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 15, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 5, 0, 0, 202, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 5, 0, 0, 3, 0, 1, 0, + 124, 5, 0, 0, 2, 0, 1, 0, + 37, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 16, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 5, 0, 0, 202, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 128, 5, 0, 0, 3, 0, 1, 0, + 140, 5, 0, 0, 2, 0, 1, 0, + 41, 0, 0, 0, 194, 0, 0, 0, + 0, 0, 1, 0, 17, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 137, 5, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 140, 5, 0, 0, 3, 0, 1, 0, + 152, 5, 0, 0, 2, 0, 1, 0, + 42, 0, 0, 0, 195, 0, 0, 0, + 0, 0, 1, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 149, 5, 0, 0, 218, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 156, 5, 0, 0, 3, 0, 1, 0, + 168, 5, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 25, 0, 0, 0, + 0, 0, 1, 0, 19, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 165, 5, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 5, 0, 0, 3, 0, 1, 0, + 180, 5, 0, 0, 2, 0, 1, 0, + 35, 0, 0, 0, 44, 0, 0, 0, + 0, 0, 1, 0, 20, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 5, 0, 0, 210, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 5, 0, 0, 3, 0, 1, 0, + 196, 5, 0, 0, 2, 0, 1, 0, + 34, 0, 0, 0, 23, 0, 0, 0, + 0, 0, 1, 0, 21, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 5, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 192, 5, 0, 0, 3, 0, 1, 0, + 204, 5, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 24, 0, 0, 0, + 0, 0, 1, 0, 22, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 5, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 200, 5, 0, 0, 3, 0, 1, 0, + 212, 5, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 13, 0, 0, 0, + 0, 0, 1, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 5, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 212, 5, 0, 0, 3, 0, 1, 0, + 224, 5, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 25, 0, 0, 0, + 0, 0, 1, 0, 24, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 5, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 220, 5, 0, 0, 3, 0, 1, 0, + 232, 5, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 14, 0, 0, 0, + 0, 0, 1, 0, 25, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 5, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 5, 0, 0, 3, 0, 1, 0, + 244, 5, 0, 0, 2, 0, 1, 0, + 16, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 5, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 5, 0, 0, 3, 0, 1, 0, + 12, 6, 0, 0, 2, 0, 1, 0, + 17, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 27, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 6, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 6, 0, 0, 3, 0, 1, 0, + 36, 6, 0, 0, 2, 0, 1, 0, + 18, 0, 0, 0, 15, 0, 0, 0, + 0, 0, 1, 0, 28, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 6, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 6, 0, 0, 3, 0, 1, 0, + 44, 6, 0, 0, 2, 0, 1, 0, + 38, 0, 0, 0, 16, 0, 0, 0, + 0, 0, 1, 0, 29, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 6, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 6, 0, 0, 3, 0, 1, 0, + 56, 6, 0, 0, 2, 0, 1, 0, + 44, 0, 0, 0, 17, 0, 0, 0, + 0, 0, 1, 0, 30, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 53, 6, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 56, 6, 0, 0, 3, 0, 1, 0, + 68, 6, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 31, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 65, 6, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 6, 0, 0, 3, 0, 1, 0, + 76, 6, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 32, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 6, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 6, 0, 0, 3, 0, 1, 0, + 88, 6, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 45, 0, 0, 0, + 0, 0, 1, 0, 33, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 85, 6, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 84, 6, 0, 0, 3, 0, 1, 0, + 96, 6, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 6, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 6, 0, 0, 3, 0, 1, 0, + 120, 6, 0, 0, 2, 0, 1, 0, + 19, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 35, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 6, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 6, 0, 0, 3, 0, 1, 0, + 144, 6, 0, 0, 2, 0, 1, 0, + 20, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 36, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 6, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 140, 6, 0, 0, 3, 0, 1, 0, + 168, 6, 0, 0, 2, 0, 1, 0, + 26, 0, 0, 0, 80, 0, 0, 0, + 0, 0, 1, 0, 37, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 165, 6, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 6, 0, 0, 3, 0, 1, 0, + 180, 6, 0, 0, 2, 0, 1, 0, + 23, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 38, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 6, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 6, 0, 0, 3, 0, 1, 0, + 204, 6, 0, 0, 2, 0, 1, 0, + 21, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 39, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 6, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 200, 6, 0, 0, 3, 0, 1, 0, + 228, 6, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 21, 0, 0, 0, + 0, 0, 1, 0, 40, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 225, 6, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 224, 6, 0, 0, 3, 0, 1, 0, + 236, 6, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 196, 0, 0, 0, + 0, 0, 1, 0, 41, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 233, 6, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 6, 0, 0, 3, 0, 1, 0, + 244, 6, 0, 0, 2, 0, 1, 0, + 15, 0, 0, 0, 22, 0, 0, 0, + 0, 0, 1, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 6, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 6, 0, 0, 3, 0, 1, 0, + 252, 6, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 43, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 249, 6, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 248, 6, 0, 0, 3, 0, 1, 0, + 4, 7, 0, 0, 2, 0, 1, 0, + 22, 0, 0, 0, 23, 0, 0, 0, + 0, 0, 1, 0, 44, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 7, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 7, 0, 0, 3, 0, 1, 0, + 12, 7, 0, 0, 2, 0, 1, 0, + 99, 112, 117, 48, 68, 69, 80, 82, + 69, 67, 65, 84, 69, 68, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 112, 117, 49, 68, 69, 80, 82, + 69, 67, 65, 84, 69, 68, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 112, 117, 50, 68, 69, 80, 82, + 69, 67, 65, 84, 69, 68, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 112, 117, 51, 68, 69, 80, 82, + 69, 67, 65, 84, 69, 68, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 101, 109, 68, 69, 80, 82, 69, + 67, 65, 84, 69, 68, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 117, 68, 69, 80, 82, 69, + 67, 65, 84, 69, 68, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 97, 116, 68, 69, 80, 82, 69, + 67, 65, 84, 69, 68, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 114, 101, 101, 83, 112, 97, 99, + 101, 80, 101, 114, 99, 101, 110, 116, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 97, 116, 116, 101, 114, 121, 80, + 101, 114, 99, 101, 110, 116, 68, 69, + 80, 82, 69, 67, 65, 84, 69, 68, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 97, 116, 116, 101, 114, 121, 83, + 116, 97, 116, 117, 115, 68, 69, 80, + 82, 69, 67, 65, 84, 69, 68, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 97, 110, 83, 112, 101, 101, 100, + 80, 101, 114, 99, 101, 110, 116, 68, + 101, 115, 105, 114, 101, 100, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 114, 116, 101, 100, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 115, 98, 79, 110, 108, 105, 110, + 101, 68, 69, 80, 82, 69, 67, 65, + 84, 69, 68, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 114, 116, 101, 100, 77, + 111, 110, 111, 84, 105, 109, 101, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 104, 101, 114, 109, 97, 108, 83, + 116, 97, 116, 117, 115, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 126, 247, 84, 194, 16, 113, 15, 175, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 97, 116, 116, 101, 114, 121, 67, + 117, 114, 114, 101, 110, 116, 68, 69, + 80, 82, 69, 67, 65, 84, 69, 68, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 97, 116, 116, 101, 114, 121, 86, + 111, 108, 116, 97, 103, 101, 68, 69, + 80, 82, 69, 67, 65, 84, 69, 68, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 104, 97, 114, 103, 105, 110, 103, + 69, 114, 114, 111, 114, 68, 69, 80, + 82, 69, 67, 65, 84, 69, 68, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 104, 97, 114, 103, 105, 110, 103, + 68, 105, 115, 97, 98, 108, 101, 100, + 68, 69, 80, 82, 69, 67, 65, 84, + 69, 68, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 101, 109, 111, 114, 121, 85, 115, + 97, 103, 101, 80, 101, 114, 99, 101, + 110, 116, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 112, 117, 85, 115, 97, 103, 101, + 80, 101, 114, 99, 101, 110, 116, 68, + 69, 80, 82, 69, 67, 65, 84, 69, + 68, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 97, 48, 68, 69, 80, 82, 69, + 67, 65, 84, 69, 68, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 101, 116, 119, 111, 114, 107, 84, + 121, 112, 101, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 157, 4, 209, 88, 201, 156, 199, 187, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 102, 102, 114, 111, 97, 100, 80, + 111, 119, 101, 114, 85, 115, 97, 103, + 101, 85, 119, 104, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 101, 116, 119, 111, 114, 107, 83, + 116, 114, 101, 110, 103, 116, 104, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 19, 62, 32, 19, 138, 140, 48, 221, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 66, 97, 116, 116, 101, + 114, 121, 67, 97, 112, 97, 99, 105, + 116, 121, 85, 119, 104, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 112, 117, 84, 101, 109, 112, 67, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 117, 84, 101, 109, 112, 67, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 101, 109, 111, 114, 121, 84, 101, + 109, 112, 67, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 97, 116, 116, 101, 114, 121, 84, + 101, 109, 112, 67, 68, 69, 80, 82, + 69, 67, 65, 84, 69, 68, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 109, 98, 105, 101, 110, 116, 84, + 101, 109, 112, 67, 68, 69, 80, 82, + 69, 67, 65, 84, 69, 68, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 101, 116, 119, 111, 114, 107, 73, + 110, 102, 111, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 252, 74, 192, 130, 45, 83, 87, 157, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 115, 116, 65, 116, 104, 101, + 110, 97, 80, 105, 110, 103, 84, 105, + 109, 101, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 117, 85, 115, 97, 103, 101, + 80, 101, 114, 99, 101, 110, 116, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 112, 117, 85, 115, 97, 103, 101, + 80, 101, 114, 99, 101, 110, 116, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 118, 109, 101, 84, 101, 109, 112, + 67, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 111, 100, 101, 109, 84, 101, 109, + 112, 67, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 99, 114, 101, 101, 110, 66, 114, + 105, 103, 104, 116, 110, 101, 115, 115, + 80, 101, 114, 99, 101, 110, 116, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 104, 101, 114, 109, 97, 108, 90, + 111, 110, 101, 115, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 111, 246, 61, 133, 41, 0, 121, 208, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 109, 105, 99, 84, 101, 109, 112, + 67, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 119, 101, 114, 68, 114, 97, + 119, 87, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 101, 116, 119, 111, 114, 107, 77, + 101, 116, 101, 114, 101, 100, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 111, 109, 80, 111, 119, 101, 114, + 68, 114, 97, 119, 87, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 101, 116, 119, 111, 114, 107, 83, + 116, 97, 116, 115, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 160, 142, 137, 39, 234, 100, 140, 185, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 97, 120, 84, 101, 109, 112, 67, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_a4d8b5af2aa492eb = b_a4d8b5af2aa492eb.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_a4d8b5af2aa492eb[] = { + &s_9d57532d82c04afc, + &s_af0f7110c254f77e, + &s_b98c64ea27898ea0, + &s_bbc79cc958d1049d, + &s_d0790029853df66f, + &s_dd308c8a13203e13, +}; +static const uint16_t m_a4d8b5af2aa492eb[] = {30, 6, 15, 8, 9, 29, 16, 25, 18, 17, 0, 1, 2, 3, 26, 34, 20, 10, 7, 5, 27, 33, 32, 44, 4, 28, 19, 36, 31, 41, 43, 24, 22, 35, 23, 21, 39, 40, 37, 42, 11, 13, 14, 38, 12}; +static const uint16_t i_a4d8b5af2aa492eb[] = {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, 37, 38, 39, 40, 41, 42, 43, 44}; +const ::capnp::_::RawSchema s_a4d8b5af2aa492eb = { + 0xa4d8b5af2aa492eb, b_a4d8b5af2aa492eb.words, 810, d_a4d8b5af2aa492eb, m_a4d8b5af2aa492eb, + 6, 45, i_a4d8b5af2aa492eb, nullptr, nullptr, { &s_a4d8b5af2aa492eb, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<49> b_d0790029853df66f = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 111, 246, 61, 133, 41, 0, 121, 208, + 22, 0, 0, 0, 1, 0, 1, 0, + 235, 146, 164, 42, 175, 181, 216, 164, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 18, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 68, 101, 118, 105, 99, 101, + 83, 116, 97, 116, 101, 46, 84, 104, + 101, 114, 109, 97, 108, 90, 111, 110, + 101, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 110, 97, 109, 101, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 101, 109, 112, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_d0790029853df66f = b_d0790029853df66f.words; +#if !CAPNP_LITE +static const uint16_t m_d0790029853df66f[] = {0, 1}; +static const uint16_t i_d0790029853df66f[] = {0, 1}; +const ::capnp::_::RawSchema s_d0790029853df66f = { + 0xd0790029853df66f, b_d0790029853df66f.words, 49, nullptr, m_d0790029853df66f, + 0, 2, i_d0790029853df66f, nullptr, nullptr, { &s_d0790029853df66f, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<35> b_af0f7110c254f77e = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 126, 247, 84, 194, 16, 113, 15, 175, + 22, 0, 0, 0, 2, 0, 0, 0, + 235, 146, 164, 42, 175, 181, 216, 164, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 34, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 103, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 68, 101, 118, 105, 99, 101, + 83, 116, 97, 116, 101, 46, 84, 104, + 101, 114, 109, 97, 108, 83, 116, 97, + 116, 117, 115, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 17, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 114, 101, 101, 110, 0, 0, 0, + 121, 101, 108, 108, 111, 119, 0, 0, + 114, 101, 100, 0, 0, 0, 0, 0, + 100, 97, 110, 103, 101, 114, 0, 0, } +}; +::capnp::word const* const bp_af0f7110c254f77e = b_af0f7110c254f77e.words; +#if !CAPNP_LITE +static const uint16_t m_af0f7110c254f77e[] = {3, 0, 2, 1}; +const ::capnp::_::RawSchema s_af0f7110c254f77e = { + 0xaf0f7110c254f77e, b_af0f7110c254f77e.words, 35, nullptr, m_af0f7110c254f77e, + 0, 4, nullptr, nullptr, nullptr, { &s_af0f7110c254f77e, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(ThermalStatus_af0f7110c254f77e, af0f7110c254f77e); +static const ::capnp::_::AlignedData<48> b_bbc79cc958d1049d = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 157, 4, 209, 88, 201, 156, 199, 187, + 22, 0, 0, 0, 2, 0, 0, 0, + 235, 146, 164, 42, 175, 181, 216, 164, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 18, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 68, 101, 118, 105, 99, 101, + 83, 116, 97, 116, 101, 46, 78, 101, + 116, 119, 111, 114, 107, 84, 121, 112, + 101, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 28, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 61, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 53, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 111, 110, 101, 0, 0, 0, 0, + 119, 105, 102, 105, 0, 0, 0, 0, + 99, 101, 108, 108, 50, 71, 0, 0, + 99, 101, 108, 108, 51, 71, 0, 0, + 99, 101, 108, 108, 52, 71, 0, 0, + 99, 101, 108, 108, 53, 71, 0, 0, + 101, 116, 104, 101, 114, 110, 101, 116, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_bbc79cc958d1049d = b_bbc79cc958d1049d.words; +#if !CAPNP_LITE +static const uint16_t m_bbc79cc958d1049d[] = {2, 3, 4, 5, 6, 0, 1}; +const ::capnp::_::RawSchema s_bbc79cc958d1049d = { + 0xbbc79cc958d1049d, b_bbc79cc958d1049d.words, 48, nullptr, m_bbc79cc958d1049d, + 0, 7, nullptr, nullptr, nullptr, { &s_bbc79cc958d1049d, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(NetworkType_bbc79cc958d1049d, bbc79cc958d1049d); +static const ::capnp::_::AlignedData<40> b_dd308c8a13203e13 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 19, 62, 32, 19, 138, 140, 48, 221, + 22, 0, 0, 0, 2, 0, 0, 0, + 235, 146, 164, 42, 175, 181, 216, 164, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 50, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 127, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 68, 101, 118, 105, 99, 101, + 83, 116, 97, 116, 101, 46, 78, 101, + 116, 119, 111, 114, 107, 83, 116, 114, + 101, 110, 103, 116, 104, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 20, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 53, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 110, 107, 110, 111, 119, 110, 0, + 112, 111, 111, 114, 0, 0, 0, 0, + 109, 111, 100, 101, 114, 97, 116, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 111, 111, 100, 0, 0, 0, 0, + 103, 114, 101, 97, 116, 0, 0, 0, } +}; +::capnp::word const* const bp_dd308c8a13203e13 = b_dd308c8a13203e13.words; +#if !CAPNP_LITE +static const uint16_t m_dd308c8a13203e13[] = {3, 4, 2, 1, 0}; +const ::capnp::_::RawSchema s_dd308c8a13203e13 = { + 0xdd308c8a13203e13, b_dd308c8a13203e13.words, 40, nullptr, m_dd308c8a13203e13, + 0, 5, nullptr, nullptr, nullptr, { &s_dd308c8a13203e13, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(NetworkStrength_dd308c8a13203e13, dd308c8a13203e13); +static const ::capnp::_::AlignedData<111> b_9d57532d82c04afc = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 252, 74, 192, 130, 45, 83, 87, 157, + 22, 0, 0, 0, 1, 0, 1, 0, + 235, 146, 164, 42, 175, 181, 216, 164, + 5, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 18, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 87, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 68, 101, 118, 105, 99, 101, + 83, 116, 97, 116, 101, 46, 78, 101, + 116, 119, 111, 114, 107, 73, 110, 102, + 111, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 24, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 152, 0, 0, 0, 3, 0, 1, 0, + 164, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 161, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 160, 0, 0, 0, 3, 0, 1, 0, + 172, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 169, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 164, 0, 0, 0, 3, 0, 1, 0, + 176, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 173, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 0, 0, 0, 3, 0, 1, 0, + 180, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 172, 0, 0, 0, 3, 0, 1, 0, + 184, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 0, 0, 0, 3, 0, 1, 0, + 188, 0, 0, 0, 2, 0, 1, 0, + 116, 101, 99, 104, 110, 111, 108, 111, + 103, 121, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 112, 101, 114, 97, 116, 111, 114, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 97, 110, 100, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 104, 97, 110, 110, 101, 108, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 120, 116, 114, 97, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 116, 101, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_9d57532d82c04afc = b_9d57532d82c04afc.words; +#if !CAPNP_LITE +static const uint16_t m_9d57532d82c04afc[] = {2, 3, 4, 1, 5, 0}; +static const uint16_t i_9d57532d82c04afc[] = {0, 1, 2, 3, 4, 5}; +const ::capnp::_::RawSchema s_9d57532d82c04afc = { + 0x9d57532d82c04afc, b_9d57532d82c04afc.words, 111, nullptr, m_9d57532d82c04afc, + 0, 6, i_9d57532d82c04afc, nullptr, nullptr, { &s_9d57532d82c04afc, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<49> b_b98c64ea27898ea0 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 160, 142, 137, 39, 234, 100, 140, 185, + 22, 0, 0, 0, 1, 0, 2, 0, + 235, 146, 164, 42, 175, 181, 216, 164, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 26, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 68, 101, 118, 105, 99, 101, + 83, 116, 97, 116, 101, 46, 78, 101, + 116, 119, 111, 114, 107, 83, 116, 97, + 116, 115, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 119, 119, 97, 110, 84, 120, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 119, 119, 97, 110, 82, 120, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_b98c64ea27898ea0 = b_b98c64ea27898ea0.words; +#if !CAPNP_LITE +static const uint16_t m_b98c64ea27898ea0[] = {1, 0}; +static const uint16_t i_b98c64ea27898ea0[] = {0, 1}; +const ::capnp::_::RawSchema s_b98c64ea27898ea0 = { + 0xb98c64ea27898ea0, b_b98c64ea27898ea0.words, 49, nullptr, m_b98c64ea27898ea0, + 0, 2, i_b98c64ea27898ea0, nullptr, nullptr, { &s_b98c64ea27898ea0, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<645> b_a7649e2575e4591e = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 30, 89, 228, 117, 37, 158, 100, 167, + 10, 0, 0, 0, 1, 0, 9, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 4, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 170, 0, 0, 0, + 29, 0, 0, 0, 87, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 0, 0, 0, 31, 8, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 80, 97, 110, 100, 97, 83, + 116, 97, 116, 101, 0, 0, 0, 0, + 20, 0, 0, 0, 1, 0, 1, 0, + 187, 173, 201, 10, 139, 11, 253, 242, + 33, 0, 0, 0, 98, 0, 0, 0, + 152, 151, 36, 105, 127, 192, 85, 205, + 33, 0, 0, 0, 82, 0, 0, 0, + 81, 55, 91, 62, 249, 173, 88, 138, + 33, 0, 0, 0, 82, 0, 0, 0, + 191, 129, 192, 232, 209, 62, 154, 246, + 33, 0, 0, 0, 114, 0, 0, 0, + 92, 212, 12, 235, 45, 151, 210, 248, + 33, 0, 0, 0, 114, 0, 0, 0, + 70, 97, 117, 108, 116, 83, 116, 97, + 116, 117, 115, 0, 0, 0, 0, 0, + 70, 97, 117, 108, 116, 84, 121, 112, + 101, 0, 0, 0, 0, 0, 0, 0, + 80, 97, 110, 100, 97, 84, 121, 112, + 101, 0, 0, 0, 0, 0, 0, 0, + 72, 97, 114, 110, 101, 115, 115, 83, + 116, 97, 116, 117, 115, 0, 0, 0, + 80, 97, 110, 100, 97, 67, 97, 110, + 83, 116, 97, 116, 101, 0, 0, 0, + 148, 0, 0, 0, 3, 0, 4, 0, + 28, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 253, 3, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 248, 3, 0, 0, 3, 0, 1, 0, + 4, 4, 0, 0, 2, 0, 1, 0, + 29, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 4, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 252, 3, 0, 0, 3, 0, 1, 0, + 8, 4, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 64, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 4, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 4, 0, 0, 3, 0, 1, 0, + 16, 4, 0, 0, 2, 0, 1, 0, + 21, 0, 0, 0, 65, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 4, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 4, 0, 0, 3, 0, 1, 0, + 24, 4, 0, 0, 2, 0, 1, 0, + 30, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 4, 0, 0, 10, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 4, 0, 0, 3, 0, 1, 0, + 44, 4, 0, 0, 2, 0, 1, 0, + 31, 0, 0, 0, 67, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 4, 0, 0, 2, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 4, 0, 0, 3, 0, 1, 0, + 60, 4, 0, 0, 2, 0, 1, 0, + 32, 0, 0, 0, 68, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 57, 4, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 60, 4, 0, 0, 3, 0, 1, 0, + 72, 4, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 4, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 4, 0, 0, 3, 0, 1, 0, + 84, 4, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 81, 4, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 84, 4, 0, 0, 3, 0, 1, 0, + 96, 4, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 4, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 4, 0, 0, 3, 0, 1, 0, + 104, 4, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 4, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 4, 0, 0, 3, 0, 1, 0, + 112, 4, 0, 0, 2, 0, 1, 0, + 33, 0, 0, 0, 12, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 4, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 4, 0, 0, 3, 0, 1, 0, + 124, 4, 0, 0, 2, 0, 1, 0, + 34, 0, 0, 0, 13, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 4, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 4, 0, 0, 3, 0, 1, 0, + 136, 4, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 69, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 4, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 132, 4, 0, 0, 3, 0, 1, 0, + 144, 4, 0, 0, 2, 0, 1, 0, + 24, 0, 0, 0, 14, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 4, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 140, 4, 0, 0, 3, 0, 1, 0, + 152, 4, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 15, 0, 0, 0, + 0, 0, 1, 0, 15, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 149, 4, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 4, 0, 0, 3, 0, 1, 0, + 160, 4, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 70, 0, 0, 0, + 0, 0, 1, 0, 16, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 157, 4, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 160, 4, 0, 0, 3, 0, 1, 0, + 172, 4, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 17, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 169, 4, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 164, 4, 0, 0, 3, 0, 1, 0, + 176, 4, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 173, 4, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 4, 0, 0, 3, 0, 1, 0, + 196, 4, 0, 0, 2, 0, 1, 0, + 22, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 19, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 4, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 192, 4, 0, 0, 3, 0, 1, 0, + 204, 4, 0, 0, 2, 0, 1, 0, + 35, 0, 0, 0, 20, 0, 0, 0, + 0, 0, 1, 0, 20, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 4, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 4, 0, 0, 3, 0, 1, 0, + 216, 4, 0, 0, 2, 0, 1, 0, + 15, 0, 0, 0, 21, 0, 0, 0, + 0, 0, 1, 0, 21, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 4, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 212, 4, 0, 0, 3, 0, 1, 0, + 224, 4, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 71, 0, 0, 0, + 0, 0, 1, 0, 22, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 4, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 220, 4, 0, 0, 3, 0, 1, 0, + 232, 4, 0, 0, 2, 0, 1, 0, + 26, 0, 0, 0, 22, 0, 0, 0, + 0, 0, 1, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 4, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 4, 0, 0, 3, 0, 1, 0, + 244, 4, 0, 0, 2, 0, 1, 0, + 23, 0, 0, 0, 12, 0, 0, 0, + 0, 0, 1, 0, 24, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 4, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 4, 0, 0, 3, 0, 1, 0, + 252, 4, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 13, 0, 0, 0, + 0, 0, 1, 0, 25, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 249, 4, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 248, 4, 0, 0, 3, 0, 1, 0, + 4, 5, 0, 0, 2, 0, 1, 0, + 36, 0, 0, 0, 14, 0, 0, 0, + 0, 0, 1, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 5, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 5, 0, 0, 3, 0, 1, 0, + 16, 5, 0, 0, 2, 0, 1, 0, + 25, 0, 0, 0, 23, 0, 0, 0, + 0, 0, 1, 0, 27, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 5, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 5, 0, 0, 3, 0, 1, 0, + 24, 5, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 28, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 5, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 5, 0, 0, 3, 0, 1, 0, + 32, 5, 0, 0, 2, 0, 1, 0, + 18, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 29, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 5, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 28, 5, 0, 0, 3, 0, 1, 0, + 40, 5, 0, 0, 2, 0, 1, 0, + 19, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 30, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 5, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 5, 0, 0, 3, 0, 1, 0, + 48, 5, 0, 0, 2, 0, 1, 0, + 20, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 31, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 5, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 5, 0, 0, 3, 0, 1, 0, + 56, 5, 0, 0, 2, 0, 1, 0, + 27, 0, 0, 0, 224, 1, 0, 0, + 0, 0, 1, 0, 32, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 53, 5, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 56, 5, 0, 0, 3, 0, 1, 0, + 68, 5, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 31, 0, 0, 0, + 0, 0, 1, 0, 33, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 65, 5, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 5, 0, 0, 3, 0, 1, 0, + 80, 5, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 61, 0, 0, 0, + 0, 0, 1, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 5, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 5, 0, 0, 3, 0, 1, 0, + 88, 5, 0, 0, 2, 0, 1, 0, + 16, 0, 0, 0, 16, 0, 0, 0, + 0, 0, 1, 0, 35, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 85, 5, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 84, 5, 0, 0, 3, 0, 1, 0, + 96, 5, 0, 0, 2, 0, 1, 0, + 17, 0, 0, 0, 17, 0, 0, 0, + 0, 0, 1, 0, 36, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 5, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 5, 0, 0, 3, 0, 1, 0, + 104, 5, 0, 0, 2, 0, 1, 0, + 118, 111, 108, 116, 97, 103, 101, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 114, 114, 101, 110, 116, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 103, 110, 105, 116, 105, 111, 110, + 76, 105, 110, 101, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 111, 110, 116, 114, 111, 108, 115, + 65, 108, 108, 111, 119, 101, 100, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 97, 115, 73, 110, 116, 101, 114, + 99, 101, 112, 116, 111, 114, 68, 101, + 116, 101, 99, 116, 101, 100, 68, 69, + 80, 82, 69, 67, 65, 84, 69, 68, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 114, 116, 101, 100, 83, + 105, 103, 110, 97, 108, 68, 101, 116, + 101, 99, 116, 101, 100, 68, 69, 80, + 82, 69, 67, 65, 84, 69, 68, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 97, 115, 71, 112, 115, 68, 69, + 80, 82, 69, 67, 65, 84, 69, 68, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 120, 66, 117, 102, 102, 101, 114, + 79, 118, 101, 114, 102, 108, 111, 119, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 120, 66, 117, 102, 102, 101, 114, + 79, 118, 101, 114, 102, 108, 111, 119, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 109, 108, 97, 110, 83, 101, 110, + 100, 69, 114, 114, 115, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 97, 110, 100, 97, 84, 121, 112, + 101, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 81, 55, 91, 62, 249, 173, 88, 138, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 97, 110, 83, 112, 101, 101, 100, + 82, 112, 109, 68, 69, 80, 82, 69, + 67, 65, 84, 69, 68, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 115, 98, 80, 111, 119, 101, 114, + 77, 111, 100, 101, 68, 69, 80, 82, + 69, 67, 65, 84, 69, 68, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 119, 152, 44, 179, 131, 53, 136, 168, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 103, 110, 105, 116, 105, 111, 110, + 67, 97, 110, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 97, 102, 101, 116, 121, 77, 111, + 100, 101, 108, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 81, 244, 218, 30, 91, 30, 85, 149, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 97, 117, 108, 116, 83, 116, 97, + 116, 117, 115, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 187, 173, 201, 10, 139, 11, 253, 242, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 119, 101, 114, 83, 97, 118, + 101, 69, 110, 97, 98, 108, 101, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 112, 116, 105, 109, 101, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 97, 117, 108, 116, 115, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 152, 151, 36, 105, 127, 192, 85, 205, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 97, 102, 101, 116, 121, 82, 120, + 73, 110, 118, 97, 108, 105, 100, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 97, 102, 101, 116, 121, 80, 97, + 114, 97, 109, 68, 69, 80, 82, 69, + 67, 65, 84, 69, 68, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 97, 114, 110, 101, 115, 115, 83, + 116, 97, 116, 117, 115, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 191, 129, 192, 232, 209, 62, 154, 246, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 101, 97, 114, 116, 98, 101, 97, + 116, 76, 111, 115, 116, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 108, 116, 101, 114, 110, 97, 116, + 105, 118, 101, 69, 120, 112, 101, 114, + 105, 101, 110, 99, 101, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 97, 102, 101, 116, 121, 84, 120, + 66, 108, 111, 99, 107, 101, 100, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 110, 116, 101, 114, 114, 117, 112, + 116, 76, 111, 97, 100, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 97, 102, 101, 116, 121, 80, 97, + 114, 97, 109, 50, 68, 69, 80, 82, + 69, 67, 65, 84, 69, 68, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 97, 102, 101, 116, 121, 80, 97, + 114, 97, 109, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 97, 110, 80, 111, 119, 101, 114, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 110, 83, 116, 97, 116, 101, + 48, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 92, 212, 12, 235, 45, 151, 210, 248, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 110, 83, 116, 97, 116, 101, + 49, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 92, 212, 12, 235, 45, 151, 210, 248, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 110, 83, 116, 97, 116, 101, + 50, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 92, 212, 12, 235, 45, 151, 210, 248, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 97, 102, 101, 116, 121, 82, 120, + 67, 104, 101, 99, 107, 115, 73, 110, + 118, 97, 108, 105, 100, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 112, 105, 67, 104, 101, 99, 107, + 115, 117, 109, 69, 114, 114, 111, 114, + 67, 111, 117, 110, 116, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 97, 110, 83, 116, 97, 108, 108, + 67, 111, 117, 110, 116, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 98, 117, 49, 86, 111, 108, 116, + 97, 103, 101, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 98, 117, 50, 86, 111, 108, 116, + 97, 103, 101, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_a7649e2575e4591e = b_a7649e2575e4591e.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_a7649e2575e4591e[] = { + &s_8a58adf93e5b3751, + &s_95551e5b1edaf451, + &s_a8883583b32c9877, + &s_cd55c07f69249798, + &s_f2fd0b8b0ac9adbb, + &s_f69a3ed1e8c081bf, + &s_f8d2972deb0cd45c, +}; +static const uint16_t m_a7649e2575e4591e[] = {23, 29, 30, 31, 3, 1, 28, 11, 34, 15, 18, 4, 9, 21, 6, 22, 13, 2, 25, 10, 16, 7, 14, 27, 26, 20, 32, 19, 24, 35, 36, 33, 5, 8, 17, 12, 0}; +static const uint16_t i_a7649e2575e4591e[] = {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}; +const ::capnp::_::RawSchema s_a7649e2575e4591e = { + 0xa7649e2575e4591e, b_a7649e2575e4591e.words, 645, d_a7649e2575e4591e, m_a7649e2575e4591e, + 7, 37, i_a7649e2575e4591e, nullptr, nullptr, { &s_a7649e2575e4591e, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<33> b_f2fd0b8b0ac9adbb = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 187, 173, 201, 10, 139, 11, 253, 242, + 21, 0, 0, 0, 2, 0, 0, 0, + 30, 89, 228, 117, 37, 158, 100, 167, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 10, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 79, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 80, 97, 110, 100, 97, 83, + 116, 97, 116, 101, 46, 70, 97, 117, + 108, 116, 83, 116, 97, 116, 117, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 17, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 111, 110, 101, 0, 0, 0, 0, + 102, 97, 117, 108, 116, 84, 101, 109, + 112, 0, 0, 0, 0, 0, 0, 0, + 102, 97, 117, 108, 116, 80, 101, 114, + 109, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_f2fd0b8b0ac9adbb = b_f2fd0b8b0ac9adbb.words; +#if !CAPNP_LITE +static const uint16_t m_f2fd0b8b0ac9adbb[] = {2, 1, 0}; +const ::capnp::_::RawSchema s_f2fd0b8b0ac9adbb = { + 0xf2fd0b8b0ac9adbb, b_f2fd0b8b0ac9adbb.words, 33, nullptr, m_f2fd0b8b0ac9adbb, + 0, 3, nullptr, nullptr, nullptr, { &s_f2fd0b8b0ac9adbb, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(FaultStatus_f2fd0b8b0ac9adbb, f2fd0b8b0ac9adbb); +static const ::capnp::_::AlignedData<181> b_cd55c07f69249798 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 152, 151, 36, 105, 127, 192, 85, 205, + 21, 0, 0, 0, 2, 0, 0, 0, + 30, 89, 228, 117, 37, 158, 100, 167, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 250, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 143, 2, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 80, 97, 110, 100, 97, 83, + 116, 97, 116, 101, 46, 70, 97, 117, + 108, 116, 84, 121, 112, 101, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 108, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 1, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 61, 1, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 61, 1, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 61, 1, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 61, 1, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 61, 1, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 61, 1, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 61, 1, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 61, 1, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 61, 1, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 61, 1, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 61, 1, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 61, 1, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 61, 1, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 61, 1, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 61, 1, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 61, 1, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 0, 0, 0, 0, 0, 0, 0, + 61, 1, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 18, 0, 0, 0, 0, 0, 0, 0, + 61, 1, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 19, 0, 0, 0, 0, 0, 0, 0, + 61, 1, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 0, 0, 0, 0, 0, 0, 0, + 61, 1, 0, 0, 202, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 0, 0, 0, 0, + 65, 1, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 22, 0, 0, 0, 0, 0, 0, 0, + 65, 1, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 23, 0, 0, 0, 0, 0, 0, 0, + 65, 1, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 24, 0, 0, 0, 0, 0, 0, 0, + 65, 1, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 0, 0, 0, 0, + 65, 1, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 26, 0, 0, 0, 0, 0, 0, 0, + 65, 1, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 101, 108, 97, 121, 77, 97, 108, + 102, 117, 110, 99, 116, 105, 111, 110, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 110, 117, 115, 101, 100, 73, 110, + 116, 101, 114, 114, 117, 112, 116, 72, + 97, 110, 100, 108, 101, 100, 0, 0, + 105, 110, 116, 101, 114, 114, 117, 112, + 116, 82, 97, 116, 101, 67, 97, 110, + 49, 0, 0, 0, 0, 0, 0, 0, + 105, 110, 116, 101, 114, 114, 117, 112, + 116, 82, 97, 116, 101, 67, 97, 110, + 50, 0, 0, 0, 0, 0, 0, 0, + 105, 110, 116, 101, 114, 114, 117, 112, + 116, 82, 97, 116, 101, 67, 97, 110, + 51, 0, 0, 0, 0, 0, 0, 0, + 105, 110, 116, 101, 114, 114, 117, 112, + 116, 82, 97, 116, 101, 84, 97, 99, + 104, 0, 0, 0, 0, 0, 0, 0, + 105, 110, 116, 101, 114, 114, 117, 112, + 116, 82, 97, 116, 101, 71, 109, 108, + 97, 110, 0, 0, 0, 0, 0, 0, + 105, 110, 116, 101, 114, 114, 117, 112, + 116, 82, 97, 116, 101, 73, 110, 116, + 101, 114, 114, 117, 112, 116, 115, 0, + 105, 110, 116, 101, 114, 114, 117, 112, + 116, 82, 97, 116, 101, 83, 112, 105, + 68, 109, 97, 0, 0, 0, 0, 0, + 105, 110, 116, 101, 114, 114, 117, 112, + 116, 82, 97, 116, 101, 83, 112, 105, + 67, 115, 0, 0, 0, 0, 0, 0, + 105, 110, 116, 101, 114, 114, 117, 112, + 116, 82, 97, 116, 101, 85, 97, 114, + 116, 49, 0, 0, 0, 0, 0, 0, + 105, 110, 116, 101, 114, 114, 117, 112, + 116, 82, 97, 116, 101, 85, 97, 114, + 116, 50, 0, 0, 0, 0, 0, 0, + 105, 110, 116, 101, 114, 114, 117, 112, + 116, 82, 97, 116, 101, 85, 97, 114, + 116, 51, 0, 0, 0, 0, 0, 0, + 105, 110, 116, 101, 114, 114, 117, 112, + 116, 82, 97, 116, 101, 85, 97, 114, + 116, 53, 0, 0, 0, 0, 0, 0, + 105, 110, 116, 101, 114, 114, 117, 112, + 116, 82, 97, 116, 101, 85, 97, 114, + 116, 68, 109, 97, 0, 0, 0, 0, + 105, 110, 116, 101, 114, 114, 117, 112, + 116, 82, 97, 116, 101, 85, 115, 98, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 110, 116, 101, 114, 114, 117, 112, + 116, 82, 97, 116, 101, 84, 105, 109, + 49, 0, 0, 0, 0, 0, 0, 0, + 105, 110, 116, 101, 114, 114, 117, 112, + 116, 82, 97, 116, 101, 84, 105, 109, + 51, 0, 0, 0, 0, 0, 0, 0, + 114, 101, 103, 105, 115, 116, 101, 114, + 68, 105, 118, 101, 114, 103, 101, 110, + 116, 0, 0, 0, 0, 0, 0, 0, + 105, 110, 116, 101, 114, 114, 117, 112, + 116, 82, 97, 116, 101, 75, 108, 105, + 110, 101, 73, 110, 105, 116, 0, 0, + 105, 110, 116, 101, 114, 114, 117, 112, + 116, 82, 97, 116, 101, 67, 108, 111, + 99, 107, 83, 111, 117, 114, 99, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 110, 116, 101, 114, 114, 117, 112, + 116, 82, 97, 116, 101, 84, 105, 99, + 107, 0, 0, 0, 0, 0, 0, 0, + 105, 110, 116, 101, 114, 114, 117, 112, + 116, 82, 97, 116, 101, 69, 120, 116, + 105, 0, 0, 0, 0, 0, 0, 0, + 105, 110, 116, 101, 114, 114, 117, 112, + 116, 82, 97, 116, 101, 83, 112, 105, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 110, 116, 101, 114, 114, 117, 112, + 116, 82, 97, 116, 101, 85, 97, 114, + 116, 55, 0, 0, 0, 0, 0, 0, + 115, 105, 114, 101, 110, 77, 97, 108, + 102, 117, 110, 99, 116, 105, 111, 110, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 101, 97, 114, 116, 98, 101, 97, + 116, 76, 111, 111, 112, 87, 97, 116, + 99, 104, 100, 111, 103, 0, 0, 0, } +}; +::capnp::word const* const bp_cd55c07f69249798 = b_cd55c07f69249798.words; +#if !CAPNP_LITE +static const uint16_t m_cd55c07f69249798[] = {26, 2, 3, 4, 20, 22, 6, 7, 19, 23, 9, 8, 5, 21, 16, 17, 10, 11, 12, 13, 24, 14, 15, 18, 0, 25, 1}; +const ::capnp::_::RawSchema s_cd55c07f69249798 = { + 0xcd55c07f69249798, b_cd55c07f69249798.words, 181, nullptr, m_cd55c07f69249798, + 0, 27, nullptr, nullptr, nullptr, { &s_cd55c07f69249798, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(FaultType_cd55c07f69249798, cd55c07f69249798); +static const ::capnp::_::AlignedData<67> b_8a58adf93e5b3751 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 81, 55, 91, 62, 249, 173, 88, 138, + 21, 0, 0, 0, 2, 0, 0, 0, + 30, 89, 228, 117, 37, 158, 100, 167, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 250, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 15, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 80, 97, 110, 100, 97, 83, + 116, 97, 116, 101, 46, 80, 97, 110, + 100, 97, 84, 121, 112, 101, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 44, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 117, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 113, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 109, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 105, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 89, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 81, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 65, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 110, 107, 110, 111, 119, 110, 0, + 119, 104, 105, 116, 101, 80, 97, 110, + 100, 97, 0, 0, 0, 0, 0, 0, + 103, 114, 101, 121, 80, 97, 110, 100, + 97, 0, 0, 0, 0, 0, 0, 0, + 98, 108, 97, 99, 107, 80, 97, 110, + 100, 97, 0, 0, 0, 0, 0, 0, + 112, 101, 100, 97, 108, 0, 0, 0, + 117, 110, 111, 0, 0, 0, 0, 0, + 100, 111, 115, 0, 0, 0, 0, 0, + 114, 101, 100, 80, 97, 110, 100, 97, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 101, 100, 80, 97, 110, 100, 97, + 86, 50, 0, 0, 0, 0, 0, 0, + 116, 114, 101, 115, 0, 0, 0, 0, + 99, 117, 97, 116, 114, 111, 0, 0, } +}; +::capnp::word const* const bp_8a58adf93e5b3751 = b_8a58adf93e5b3751.words; +#if !CAPNP_LITE +static const uint16_t m_8a58adf93e5b3751[] = {3, 10, 6, 2, 4, 7, 8, 9, 0, 5, 1}; +const ::capnp::_::RawSchema s_8a58adf93e5b3751 = { + 0x8a58adf93e5b3751, b_8a58adf93e5b3751.words, 67, nullptr, m_8a58adf93e5b3751, + 0, 11, nullptr, nullptr, nullptr, { &s_8a58adf93e5b3751, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(PandaType_8a58adf93e5b3751, 8a58adf93e5b3751); +static const ::capnp::_::AlignedData<32> b_f69a3ed1e8c081bf = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 191, 129, 192, 232, 209, 62, 154, 246, + 21, 0, 0, 0, 2, 0, 0, 0, + 30, 89, 228, 117, 37, 158, 100, 167, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 26, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 79, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 80, 97, 110, 100, 97, 83, + 116, 97, 116, 101, 46, 72, 97, 114, + 110, 101, 115, 115, 83, 116, 97, 116, + 117, 115, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 17, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 111, 116, 67, 111, 110, 110, 101, + 99, 116, 101, 100, 0, 0, 0, 0, + 110, 111, 114, 109, 97, 108, 0, 0, + 102, 108, 105, 112, 112, 101, 100, 0, } +}; +::capnp::word const* const bp_f69a3ed1e8c081bf = b_f69a3ed1e8c081bf.words; +#if !CAPNP_LITE +static const uint16_t m_f69a3ed1e8c081bf[] = {2, 1, 0}; +const ::capnp::_::RawSchema s_f69a3ed1e8c081bf = { + 0xf69a3ed1e8c081bf, b_f69a3ed1e8c081bf.words, 32, nullptr, m_f69a3ed1e8c081bf, + 0, 3, nullptr, nullptr, nullptr, { &s_f69a3ed1e8c081bf, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(HarnessStatus_f69a3ed1e8c081bf, f69a3ed1e8c081bf); +static const ::capnp::_::AlignedData<424> b_f8d2972deb0cd45c = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 92, 212, 12, 235, 45, 151, 210, 248, + 21, 0, 0, 0, 1, 0, 8, 0, + 30, 89, 228, 117, 37, 158, 100, 167, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 26, 1, 0, 0, + 37, 0, 0, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 0, 0, 0, 127, 5, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 80, 97, 110, 100, 97, 83, + 116, 97, 116, 101, 46, 80, 97, 110, + 100, 97, 67, 97, 110, 83, 116, 97, + 116, 101, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 1, 0, 1, 0, + 255, 131, 50, 209, 180, 80, 219, 192, + 1, 0, 0, 0, 106, 0, 0, 0, + 76, 101, 99, 69, 114, 114, 111, 114, + 67, 111, 100, 101, 0, 0, 0, 0, + 100, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 173, 2, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 2, 0, 0, 3, 0, 1, 0, + 180, 2, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 2, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 2, 0, 0, 3, 0, 1, 0, + 188, 2, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 2, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 2, 0, 0, 3, 0, 1, 0, + 196, 2, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 2, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 192, 2, 0, 0, 3, 0, 1, 0, + 204, 2, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 2, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 200, 2, 0, 0, 3, 0, 1, 0, + 212, 2, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 2, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 2, 0, 0, 3, 0, 1, 0, + 220, 2, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 217, 2, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 2, 0, 0, 3, 0, 1, 0, + 228, 2, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 225, 2, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 228, 2, 0, 0, 3, 0, 1, 0, + 240, 2, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 2, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 236, 2, 0, 0, 3, 0, 1, 0, + 248, 2, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 14, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 245, 2, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 248, 2, 0, 0, 3, 0, 1, 0, + 4, 3, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 3, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 3, 0, 0, 3, 0, 1, 0, + 12, 3, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 3, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 3, 0, 0, 3, 0, 1, 0, + 20, 3, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 3, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 3, 0, 0, 3, 0, 1, 0, + 28, 3, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 3, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 24, 3, 0, 0, 3, 0, 1, 0, + 36, 3, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 3, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 3, 0, 0, 3, 0, 1, 0, + 44, 3, 0, 0, 2, 0, 1, 0, + 15, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 15, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 3, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 3, 0, 0, 3, 0, 1, 0, + 52, 3, 0, 0, 2, 0, 1, 0, + 16, 0, 0, 0, 20, 0, 0, 0, + 0, 0, 1, 0, 16, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 3, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 3, 0, 0, 3, 0, 1, 0, + 60, 3, 0, 0, 2, 0, 1, 0, + 17, 0, 0, 0, 21, 0, 0, 0, + 0, 0, 1, 0, 17, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 57, 3, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 56, 3, 0, 0, 3, 0, 1, 0, + 68, 3, 0, 0, 2, 0, 1, 0, + 18, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 65, 3, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 3, 0, 0, 3, 0, 1, 0, + 76, 3, 0, 0, 2, 0, 1, 0, + 19, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 19, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 3, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 3, 0, 0, 3, 0, 1, 0, + 84, 3, 0, 0, 2, 0, 1, 0, + 20, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 20, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 81, 3, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 80, 3, 0, 0, 3, 0, 1, 0, + 92, 3, 0, 0, 2, 0, 1, 0, + 21, 0, 0, 0, 11, 0, 0, 0, + 0, 0, 1, 0, 21, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 89, 3, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 88, 3, 0, 0, 3, 0, 1, 0, + 100, 3, 0, 0, 2, 0, 1, 0, + 22, 0, 0, 0, 12, 0, 0, 0, + 0, 0, 1, 0, 22, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 3, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 3, 0, 0, 3, 0, 1, 0, + 108, 3, 0, 0, 2, 0, 1, 0, + 23, 0, 0, 0, 13, 0, 0, 0, + 0, 0, 1, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 3, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 3, 0, 0, 3, 0, 1, 0, + 116, 3, 0, 0, 2, 0, 1, 0, + 24, 0, 0, 0, 14, 0, 0, 0, + 0, 0, 1, 0, 24, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 3, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 3, 0, 0, 3, 0, 1, 0, + 124, 3, 0, 0, 2, 0, 1, 0, + 98, 117, 115, 79, 102, 102, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 117, 115, 79, 102, 102, 67, 110, + 116, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 114, 114, 111, 114, 87, 97, 114, + 110, 105, 110, 103, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 114, 114, 111, 114, 80, 97, 115, + 115, 105, 118, 101, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 115, 116, 69, 114, 114, 111, + 114, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 255, 131, 50, 209, 180, 80, 219, 192, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 115, 116, 83, 116, 111, 114, + 101, 100, 69, 114, 114, 111, 114, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 255, 131, 50, 209, 180, 80, 219, 192, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 115, 116, 68, 97, 116, 97, + 69, 114, 114, 111, 114, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 255, 131, 50, 209, 180, 80, 219, 192, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 115, 116, 68, 97, 116, 97, + 83, 116, 111, 114, 101, 100, 69, 114, + 114, 111, 114, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 255, 131, 50, 209, 180, 80, 219, 192, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 101, 99, 101, 105, 118, 101, 69, + 114, 114, 111, 114, 67, 110, 116, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 114, 97, 110, 115, 109, 105, 116, + 69, 114, 114, 111, 114, 67, 110, 116, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 111, 116, 97, 108, 69, 114, 114, + 111, 114, 67, 110, 116, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 111, 116, 97, 108, 84, 120, 76, + 111, 115, 116, 67, 110, 116, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 111, 116, 97, 108, 82, 120, 76, + 111, 115, 116, 67, 110, 116, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 111, 116, 97, 108, 84, 120, 67, + 110, 116, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 111, 116, 97, 108, 82, 120, 67, + 110, 116, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 111, 116, 97, 108, 70, 119, 100, + 67, 110, 116, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 110, 83, 112, 101, 101, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 110, 68, 97, 116, 97, 83, + 112, 101, 101, 100, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 110, 102, 100, 69, 110, 97, + 98, 108, 101, 100, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 114, 115, 69, 110, 97, 98, 108, + 101, 100, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 110, 102, 100, 78, 111, 110, + 73, 115, 111, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 114, 113, 48, 67, 97, 108, 108, + 82, 97, 116, 101, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 114, 113, 49, 67, 97, 108, 108, + 82, 97, 116, 101, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 114, 113, 50, 67, 97, 108, 108, + 82, 97, 116, 101, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 110, 67, 111, 114, 101, 82, + 101, 115, 101, 116, 67, 110, 116, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_f8d2972deb0cd45c = b_f8d2972deb0cd45c.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_f8d2972deb0cd45c[] = { + &s_c0db50b4d13283ff, +}; +static const uint16_t m_f8d2972deb0cd45c[] = {19, 0, 1, 24, 17, 16, 18, 20, 3, 2, 21, 22, 23, 6, 7, 4, 5, 8, 10, 15, 14, 12, 13, 11, 9}; +static const uint16_t i_f8d2972deb0cd45c[] = {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}; +const ::capnp::_::RawSchema s_f8d2972deb0cd45c = { + 0xf8d2972deb0cd45c, b_f8d2972deb0cd45c.words, 424, d_f8d2972deb0cd45c, m_f8d2972deb0cd45c, + 1, 25, i_f8d2972deb0cd45c, nullptr, nullptr, { &s_f8d2972deb0cd45c, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<59> b_c0db50b4d13283ff = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 255, 131, 50, 209, 180, 80, 219, 192, + 35, 0, 0, 0, 2, 0, 0, 0, + 92, 212, 12, 235, 45, 151, 210, 248, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 130, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 199, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 80, 97, 110, 100, 97, 83, + 116, 97, 116, 101, 46, 80, 97, 110, + 100, 97, 67, 97, 110, 83, 116, 97, + 116, 101, 46, 76, 101, 99, 69, 114, + 114, 111, 114, 67, 111, 100, 101, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 32, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 89, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 81, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 65, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 61, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 57, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 111, 69, 114, 114, 111, 114, 0, + 115, 116, 117, 102, 102, 69, 114, 114, + 111, 114, 0, 0, 0, 0, 0, 0, + 102, 111, 114, 109, 69, 114, 114, 111, + 114, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 107, 69, 114, 114, 111, 114, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 105, 116, 49, 69, 114, 114, 111, + 114, 0, 0, 0, 0, 0, 0, 0, + 98, 105, 116, 48, 69, 114, 114, 111, + 114, 0, 0, 0, 0, 0, 0, 0, + 99, 114, 99, 69, 114, 114, 111, 114, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 111, 67, 104, 97, 110, 103, 101, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_c0db50b4d13283ff = b_c0db50b4d13283ff.words; +#if !CAPNP_LITE +static const uint16_t m_c0db50b4d13283ff[] = {3, 5, 4, 6, 2, 7, 0, 1}; +const ::capnp::_::RawSchema s_c0db50b4d13283ff = { + 0xc0db50b4d13283ff, b_c0db50b4d13283ff.words, 59, nullptr, m_c0db50b4d13283ff, + 0, 8, nullptr, nullptr, nullptr, { &s_c0db50b4d13283ff, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(LecErrorCode_c0db50b4d13283ff, c0db50b4d13283ff); +static const ::capnp::_::AlignedData<102> b_ceb8f49734857a88 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 136, 122, 133, 52, 151, 244, 184, 206, + 10, 0, 0, 0, 1, 0, 2, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 210, 0, 0, 0, + 33, 0, 0, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 0, 0, 0, 31, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 80, 101, 114, 105, 112, 104, + 101, 114, 97, 108, 83, 116, 97, 116, + 101, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 1, 0, 1, 0, + 119, 152, 44, 179, 131, 53, 136, 168, + 1, 0, 0, 0, 186, 0, 0, 0, + 85, 115, 98, 80, 111, 119, 101, 114, + 77, 111, 100, 101, 68, 69, 80, 82, + 69, 67, 65, 84, 69, 68, 0, 0, + 20, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 0, 0, 0, 3, 0, 1, 0, + 136, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 128, 0, 0, 0, 3, 0, 1, 0, + 140, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 137, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 132, 0, 0, 0, 3, 0, 1, 0, + 144, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 140, 0, 0, 0, 3, 0, 1, 0, + 152, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 149, 0, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 152, 0, 0, 0, 3, 0, 1, 0, + 164, 0, 0, 0, 2, 0, 1, 0, + 112, 97, 110, 100, 97, 84, 121, 112, + 101, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 81, 55, 91, 62, 249, 173, 88, 138, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 111, 108, 116, 97, 103, 101, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 114, 114, 101, 110, 116, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 97, 110, 83, 112, 101, 101, 100, + 82, 112, 109, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 115, 98, 80, 111, 119, 101, 114, + 77, 111, 100, 101, 68, 69, 80, 82, + 69, 67, 65, 84, 69, 68, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 119, 152, 44, 179, 131, 53, 136, 168, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_ceb8f49734857a88 = b_ceb8f49734857a88.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_ceb8f49734857a88[] = { + &s_8a58adf93e5b3751, + &s_a8883583b32c9877, +}; +static const uint16_t m_ceb8f49734857a88[] = {2, 3, 0, 4, 1}; +static const uint16_t i_ceb8f49734857a88[] = {0, 1, 2, 3, 4}; +const ::capnp::_::RawSchema s_ceb8f49734857a88 = { + 0xceb8f49734857a88, b_ceb8f49734857a88.words, 102, d_ceb8f49734857a88, m_ceb8f49734857a88, + 2, 5, i_ceb8f49734857a88, nullptr, nullptr, { &s_ceb8f49734857a88, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<37> b_a8883583b32c9877 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 119, 152, 44, 179, 131, 53, 136, 168, + 26, 0, 0, 0, 2, 0, 0, 0, + 136, 122, 133, 52, 151, 244, 184, 206, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 138, 1, 0, 0, + 45, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 103, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 80, 101, 114, 105, 112, 104, + 101, 114, 97, 108, 83, 116, 97, 116, + 101, 46, 85, 115, 98, 80, 111, 119, + 101, 114, 77, 111, 100, 101, 68, 69, + 80, 82, 69, 67, 65, 84, 69, 68, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 17, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 111, 110, 101, 0, 0, 0, 0, + 99, 108, 105, 101, 110, 116, 0, 0, + 99, 100, 112, 0, 0, 0, 0, 0, + 100, 99, 112, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_a8883583b32c9877 = b_a8883583b32c9877.words; +#if !CAPNP_LITE +static const uint16_t m_a8883583b32c9877[] = {2, 1, 3, 0}; +const ::capnp::_::RawSchema s_a8883583b32c9877 = { + 0xa8883583b32c9877, b_a8883583b32c9877.words, 37, nullptr, m_a8883583b32c9877, + 0, 4, nullptr, nullptr, nullptr, { &s_a8883583b32c9877, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(UsbPowerModeDEPRECATED_a8883583b32c9877, a8883583b32c9877); +static const ::capnp::_::AlignedData<247> b_9a185389d6fdd05f = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 95, 208, 253, 214, 137, 83, 24, 154, + 10, 0, 0, 0, 1, 0, 5, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 5, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 170, 0, 0, 0, + 29, 0, 0, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 223, 2, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 82, 97, 100, 97, 114, 83, + 116, 97, 116, 101, 0, 0, 0, 0, + 4, 0, 0, 0, 1, 0, 1, 0, + 133, 240, 12, 23, 217, 58, 111, 185, + 1, 0, 0, 0, 74, 0, 0, 0, + 76, 101, 97, 100, 68, 97, 116, 97, + 0, 0, 0, 0, 0, 0, 0, 0, + 52, 0, 0, 0, 3, 0, 4, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 1, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 1, 0, 0, 3, 0, 1, 0, + 124, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 1, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 1, 0, 0, 3, 0, 1, 0, + 136, 1, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 1, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 136, 1, 0, 0, 3, 0, 1, 0, + 148, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 145, 1, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 140, 1, 0, 0, 3, 0, 1, 0, + 152, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 149, 1, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 144, 1, 0, 0, 3, 0, 1, 0, + 156, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 152, 1, 0, 0, 3, 0, 1, 0, + 164, 1, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 161, 1, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 160, 1, 0, 0, 3, 0, 1, 0, + 172, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 169, 1, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 172, 1, 0, 0, 3, 0, 1, 0, + 184, 1, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 1, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 1, 0, 0, 3, 0, 1, 0, + 196, 1, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 1, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 1, 0, 0, 3, 0, 1, 0, + 208, 1, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 1, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 1, 0, 0, 3, 0, 1, 0, + 236, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 233, 1, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 236, 1, 0, 0, 3, 0, 1, 0, + 248, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 245, 1, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 244, 1, 0, 0, 3, 0, 1, 0, + 16, 2, 0, 0, 2, 0, 1, 0, + 119, 97, 114, 112, 77, 97, 116, 114, + 105, 120, 68, 69, 80, 82, 69, 67, + 65, 84, 69, 68, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 110, 103, 108, 101, 79, 102, 102, + 115, 101, 116, 68, 69, 80, 82, 69, + 67, 65, 84, 69, 68, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 108, 83, 116, 97, 116, 117, + 115, 68, 69, 80, 82, 69, 67, 65, + 84, 69, 68, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 97, 100, 79, 110, 101, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 133, 240, 12, 23, 217, 58, 111, 185, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 97, 100, 84, 119, 111, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 133, 240, 12, 23, 217, 58, 111, 185, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 109, 76, 97, 103, 77, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 100, 77, 111, 110, 111, 84, 105, + 109, 101, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 116, 77, 111, 110, 111, 84, 105, + 109, 101, 68, 69, 80, 82, 69, 67, + 65, 84, 69, 68, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 108, 67, 121, 99, 108, 101, + 68, 69, 80, 82, 69, 67, 65, 84, + 69, 68, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 108, 80, 101, 114, 99, 68, + 69, 80, 82, 69, 67, 65, 84, 69, + 68, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 110, 77, 111, 110, 111, 84, + 105, 109, 101, 115, 68, 69, 80, 82, + 69, 67, 65, 84, 69, 68, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 83, 116, 97, 116, 101, + 77, 111, 110, 111, 84, 105, 109, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 97, 100, 97, 114, 69, 114, 114, + 111, 114, 115, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 173, 118, 186, 235, 121, 102, 168, 232, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_9a185389d6fdd05f = b_9a185389d6fdd05f.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_9a185389d6fdd05f[] = { + &s_b96f3ad9170cf085, + &s_e8a86679ebba76ad, +}; +static const uint16_t m_9a185389d6fdd05f[] = {1, 8, 9, 2, 10, 11, 5, 7, 3, 4, 6, 12, 0}; +static const uint16_t i_9a185389d6fdd05f[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12}; +const ::capnp::_::RawSchema s_9a185389d6fdd05f = { + 0x9a185389d6fdd05f, b_9a185389d6fdd05f.words, 247, d_9a185389d6fdd05f, m_9a185389d6fdd05f, + 2, 13, i_9a185389d6fdd05f, nullptr, nullptr, { &s_9a185389d6fdd05f, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<262> b_b96f3ad9170cf085 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 133, 240, 12, 23, 217, 58, 111, 185, + 21, 0, 0, 0, 1, 0, 7, 0, + 95, 208, 253, 214, 137, 83, 24, 154, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 242, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 135, 3, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 82, 97, 100, 97, 114, 83, + 116, 97, 116, 101, 46, 76, 101, 97, + 100, 68, 97, 116, 97, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 64, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 172, 1, 0, 0, 3, 0, 1, 0, + 184, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 1, 0, 0, 3, 0, 1, 0, + 188, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 1, 0, 0, 3, 0, 1, 0, + 192, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 1, 0, 0, 3, 0, 1, 0, + 196, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 1, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 1, 0, 0, 3, 0, 1, 0, + 200, 1, 0, 0, 2, 0, 1, 0, + 15, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 1, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 1, 0, 0, 3, 0, 1, 0, + 208, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 1, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 200, 1, 0, 0, 3, 0, 1, 0, + 212, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 1, 0, 0, 3, 0, 1, 0, + 216, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 1, 0, 0, 3, 0, 1, 0, + 220, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 217, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 212, 1, 0, 0, 3, 0, 1, 0, + 224, 1, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 64, 1, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 1, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 1, 0, 0, 3, 0, 1, 0, + 228, 1, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 65, 1, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 225, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 220, 1, 0, 0, 3, 0, 1, 0, + 232, 1, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 11, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 228, 1, 0, 0, 3, 0, 1, 0, + 240, 1, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 12, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 1, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 236, 1, 0, 0, 3, 0, 1, 0, + 248, 1, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 66, 1, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 245, 1, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 1, 0, 0, 3, 0, 1, 0, + 252, 1, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 13, 0, 0, 0, + 0, 0, 1, 0, 15, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 249, 1, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 248, 1, 0, 0, 3, 0, 1, 0, + 4, 2, 0, 0, 2, 0, 1, 0, + 100, 82, 101, 108, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 82, 101, 108, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 82, 101, 108, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 82, 101, 108, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 76, 101, 97, 100, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 76, 101, 97, 100, 68, 69, 80, + 82, 69, 67, 65, 84, 69, 68, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 80, 97, 116, 104, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 76, 97, 116, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 76, 101, 97, 100, 75, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 76, 101, 97, 100, 75, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 99, 119, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 116, 117, 115, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 76, 101, 97, 100, 84, 97, 117, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 111, 100, 101, 108, 80, 114, 111, + 98, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 97, 100, 97, 114, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 97, 100, 97, 114, 84, 114, 97, + 99, 107, 73, 100, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 255, 255, 255, 255, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_b96f3ad9170cf085 = b_b96f3ad9170cf085.words; +#if !CAPNP_LITE +static const uint16_t m_b96f3ad9170cf085[] = {5, 9, 12, 3, 6, 0, 10, 13, 14, 15, 11, 7, 4, 8, 2, 1}; +static const uint16_t i_b96f3ad9170cf085[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15}; +const ::capnp::_::RawSchema s_b96f3ad9170cf085 = { + 0xb96f3ad9170cf085, b_b96f3ad9170cf085.words, 262, nullptr, m_b96f3ad9170cf085, + 0, 16, i_b96f3ad9170cf085, nullptr, nullptr, { &s_b96f3ad9170cf085, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<264> b_96df70754d8390bc = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 188, 144, 131, 77, 117, 112, 223, 150, + 10, 0, 0, 0, 1, 0, 2, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 8, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 242, 0, 0, 0, + 33, 0, 0, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 223, 2, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 76, 105, 118, 101, 67, 97, + 108, 105, 98, 114, 97, 116, 105, 111, + 110, 68, 97, 116, 97, 0, 0, 0, + 4, 0, 0, 0, 1, 0, 1, 0, + 77, 57, 173, 102, 148, 2, 170, 202, + 1, 0, 0, 0, 58, 0, 0, 0, + 83, 116, 97, 116, 117, 115, 0, 0, + 52, 0, 0, 0, 3, 0, 4, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 1, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 1, 0, 0, 3, 0, 1, 0, + 124, 1, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 1, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 1, 0, 0, 3, 0, 1, 0, + 136, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 132, 1, 0, 0, 3, 0, 1, 0, + 144, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 1, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 136, 1, 0, 0, 3, 0, 1, 0, + 148, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 145, 1, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 144, 1, 0, 0, 3, 0, 1, 0, + 172, 1, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 169, 1, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 172, 1, 0, 0, 3, 0, 1, 0, + 200, 1, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 1, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 200, 1, 0, 0, 3, 0, 1, 0, + 228, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 225, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 224, 1, 0, 0, 3, 0, 1, 0, + 252, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 249, 1, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 248, 1, 0, 0, 3, 0, 1, 0, + 20, 2, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 2, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 2, 0, 0, 3, 0, 1, 0, + 28, 2, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 2, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 28, 2, 0, 0, 3, 0, 1, 0, + 56, 2, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 53, 2, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 52, 2, 0, 0, 3, 0, 1, 0, + 64, 2, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 2, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 56, 2, 0, 0, 3, 0, 1, 0, + 84, 2, 0, 0, 2, 0, 1, 0, + 119, 97, 114, 112, 77, 97, 116, 114, + 105, 120, 68, 69, 80, 82, 69, 67, + 65, 84, 69, 68, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 108, 83, 116, 97, 116, 117, + 115, 68, 69, 80, 82, 69, 67, 65, + 84, 69, 68, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 108, 67, 121, 99, 108, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 108, 80, 101, 114, 99, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 120, 116, 114, 105, 110, 115, 105, + 99, 77, 97, 116, 114, 105, 120, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 119, 97, 114, 112, 77, 97, 116, 114, + 105, 120, 50, 68, 69, 80, 82, 69, + 67, 65, 84, 69, 68, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 119, 97, 114, 112, 77, 97, 116, 114, + 105, 120, 66, 105, 103, 68, 69, 80, + 82, 69, 67, 65, 84, 69, 68, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 112, 121, 67, 97, 108, 105, 98, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 112, 121, 67, 97, 108, 105, 98, + 83, 112, 114, 101, 97, 100, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 97, 108, 105, 100, 66, 108, 111, + 99, 107, 115, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 119, 105, 100, 101, 70, 114, 111, 109, + 68, 101, 118, 105, 99, 101, 69, 117, + 108, 101, 114, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 108, 83, 116, 97, 116, 117, + 115, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 77, 57, 173, 102, 148, 2, 170, 202, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 101, 105, 103, 104, 116, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_96df70754d8390bc = b_96df70754d8390bc.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_96df70754d8390bc[] = { + &s_caaa029466ad394d, +}; +static const uint16_t m_96df70754d8390bc[] = {2, 3, 11, 1, 4, 12, 7, 8, 9, 5, 6, 0, 10}; +static const uint16_t i_96df70754d8390bc[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12}; +const ::capnp::_::RawSchema s_96df70754d8390bc = { + 0x96df70754d8390bc, b_96df70754d8390bc.words, 264, d_96df70754d8390bc, m_96df70754d8390bc, + 1, 13, i_96df70754d8390bc, nullptr, nullptr, { &s_96df70754d8390bc, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<38> b_caaa029466ad394d = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 77, 57, 173, 102, 148, 2, 170, 202, + 30, 0, 0, 0, 2, 0, 0, 0, + 188, 144, 131, 77, 117, 112, 223, 150, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 42, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 103, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 76, 105, 118, 101, 67, 97, + 108, 105, 98, 114, 97, 116, 105, 111, + 110, 68, 97, 116, 97, 46, 83, 116, + 97, 116, 117, 115, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 110, 99, 97, 108, 105, 98, 114, + 97, 116, 101, 100, 0, 0, 0, 0, + 99, 97, 108, 105, 98, 114, 97, 116, + 101, 100, 0, 0, 0, 0, 0, 0, + 105, 110, 118, 97, 108, 105, 100, 0, + 114, 101, 99, 97, 108, 105, 98, 114, + 97, 116, 105, 110, 103, 0, 0, 0, } +}; +::capnp::word const* const bp_caaa029466ad394d = b_caaa029466ad394d.words; +#if !CAPNP_LITE +static const uint16_t m_caaa029466ad394d[] = {1, 2, 3, 0}; +const ::capnp::_::RawSchema s_caaa029466ad394d = { + 0xcaaa029466ad394d, b_caaa029466ad394d.words, 38, nullptr, m_caaa029466ad394d, + 0, 4, nullptr, nullptr, nullptr, { &s_caaa029466ad394d, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(Status_caaa029466ad394d, caaa029466ad394d); +static const ::capnp::_::AlignedData<171> b_8faa644732dec251 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 81, 194, 222, 50, 71, 100, 170, 143, + 10, 0, 0, 0, 1, 0, 5, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 170, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 55, 2, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 76, 105, 118, 101, 84, 114, + 97, 99, 107, 115, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 40, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 1, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 1, 0, 0, 3, 0, 1, 0, + 16, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 1, 0, 0, 3, 0, 1, 0, + 20, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 1, 0, 0, 3, 0, 1, 0, + 24, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 1, 0, 0, 3, 0, 1, 0, + 28, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 1, 0, 0, 3, 0, 1, 0, + 32, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 1, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 28, 1, 0, 0, 3, 0, 1, 0, + 40, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 1, 0, 0, 3, 0, 1, 0, + 44, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 1, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 1, 0, 0, 3, 0, 1, 0, + 52, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 0, 1, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 1, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 1, 0, 0, 3, 0, 1, 0, + 60, 1, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 1, 1, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 57, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 56, 1, 0, 0, 3, 0, 1, 0, + 68, 1, 0, 0, 2, 0, 1, 0, + 116, 114, 97, 99, 107, 73, 100, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 82, 101, 108, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 82, 101, 108, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 82, 101, 108, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 82, 101, 108, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 109, 101, 83, 116, 97, 109, + 112, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 116, 117, 115, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 114, 114, 101, 110, 116, 84, + 105, 109, 101, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 116, 105, 111, 110, 97, + 114, 121, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 110, 99, 111, 109, 105, 110, 103, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_8faa644732dec251 = b_8faa644732dec251.words; +#if !CAPNP_LITE +static const uint16_t m_8faa644732dec251[] = {4, 7, 1, 9, 8, 6, 5, 0, 3, 2}; +static const uint16_t i_8faa644732dec251[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9}; +const ::capnp::_::RawSchema s_8faa644732dec251 = { + 0x8faa644732dec251, b_8faa644732dec251.words, 171, nullptr, m_8faa644732dec251, + 0, 10, i_8faa644732dec251, nullptr, nullptr, { &s_8faa644732dec251, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<1056> b_97ff69c53601abf1 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 241, 171, 1, 54, 197, 105, 255, 151, + 10, 0, 0, 0, 1, 0, 24, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 6, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 194, 0, 0, 0, + 29, 0, 0, 0, 167, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 0, 0, 0, 39, 13, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 67, 111, 110, 116, 114, 111, + 108, 115, 83, 116, 97, 116, 101, 0, + 40, 0, 0, 0, 1, 0, 1, 0, + 97, 172, 209, 210, 150, 139, 229, 219, + 73, 0, 0, 0, 122, 0, 0, 0, + 98, 60, 25, 19, 209, 220, 208, 160, + 73, 0, 0, 0, 98, 0, 0, 0, + 100, 95, 152, 110, 157, 185, 139, 233, + 73, 0, 0, 0, 82, 0, 0, 0, + 94, 55, 50, 134, 52, 99, 148, 147, + 73, 0, 0, 0, 138, 0, 0, 0, + 227, 117, 147, 224, 201, 93, 140, 242, + 77, 0, 0, 0, 130, 0, 0, 0, + 164, 137, 246, 203, 80, 160, 116, 231, + 77, 0, 0, 0, 154, 0, 0, 0, + 222, 42, 200, 144, 215, 226, 36, 144, + 81, 0, 0, 0, 130, 0, 0, 0, + 241, 128, 153, 172, 136, 234, 228, 162, + 81, 0, 0, 0, 146, 0, 0, 0, + 97, 124, 111, 192, 149, 128, 157, 173, + 85, 0, 0, 0, 178, 0, 0, 0, + 45, 155, 136, 242, 240, 70, 58, 166, + 89, 0, 0, 0, 146, 0, 0, 0, + 79, 112, 101, 110, 112, 105, 108, 111, + 116, 83, 116, 97, 116, 101, 0, 0, + 65, 108, 101, 114, 116, 83, 116, 97, + 116, 117, 115, 0, 0, 0, 0, 0, + 65, 108, 101, 114, 116, 83, 105, 122, + 101, 0, 0, 0, 0, 0, 0, 0, + 76, 97, 116, 101, 114, 97, 108, 73, + 78, 68, 73, 83, 116, 97, 116, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 97, 116, 101, 114, 97, 108, 80, + 73, 68, 83, 116, 97, 116, 101, 0, + 76, 97, 116, 101, 114, 97, 108, 84, + 111, 114, 113, 117, 101, 83, 116, 97, + 116, 101, 0, 0, 0, 0, 0, 0, + 76, 97, 116, 101, 114, 97, 108, 76, + 81, 82, 83, 116, 97, 116, 101, 0, + 76, 97, 116, 101, 114, 97, 108, 65, + 110, 103, 108, 101, 83, 116, 97, 116, + 101, 0, 0, 0, 0, 0, 0, 0, + 76, 97, 116, 101, 114, 97, 108, 67, + 117, 114, 118, 97, 116, 117, 114, 101, + 83, 116, 97, 116, 101, 0, 0, 0, + 76, 97, 116, 101, 114, 97, 108, 68, + 101, 98, 117, 103, 83, 116, 97, 116, + 101, 0, 0, 0, 0, 0, 0, 0, + 240, 0, 0, 0, 3, 0, 4, 0, + 30, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 129, 6, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 128, 6, 0, 0, 3, 0, 1, 0, + 140, 6, 0, 0, 2, 0, 1, 0, + 32, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 137, 6, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 136, 6, 0, 0, 3, 0, 1, 0, + 148, 6, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 145, 6, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 140, 6, 0, 0, 3, 0, 1, 0, + 152, 6, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 149, 6, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 6, 0, 0, 3, 0, 1, 0, + 160, 6, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 157, 6, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 156, 6, 0, 0, 3, 0, 1, 0, + 168, 6, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 165, 6, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 164, 6, 0, 0, 3, 0, 1, 0, + 176, 6, 0, 0, 2, 0, 1, 0, + 36, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 173, 6, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 6, 0, 0, 3, 0, 1, 0, + 188, 6, 0, 0, 2, 0, 1, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 6, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 6, 0, 0, 3, 0, 1, 0, + 196, 6, 0, 0, 2, 0, 1, 0, + 38, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 6, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 6, 0, 0, 3, 0, 1, 0, + 208, 6, 0, 0, 2, 0, 1, 0, + 39, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 6, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 6, 0, 0, 3, 0, 1, 0, + 220, 6, 0, 0, 2, 0, 1, 0, + 41, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 217, 6, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 220, 6, 0, 0, 3, 0, 1, 0, + 232, 6, 0, 0, 2, 0, 1, 0, + 42, 0, 0, 0, 11, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 6, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 6, 0, 0, 3, 0, 1, 0, + 244, 6, 0, 0, 2, 0, 1, 0, + 55, 0, 0, 0, 12, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 6, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 244, 6, 0, 0, 3, 0, 1, 0, + 0, 7, 0, 0, 2, 0, 1, 0, + 52, 0, 0, 0, 13, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 253, 6, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 7, 0, 0, 3, 0, 1, 0, + 12, 7, 0, 0, 2, 0, 1, 0, + 45, 0, 0, 0, 14, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 7, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 7, 0, 0, 3, 0, 1, 0, + 24, 7, 0, 0, 2, 0, 1, 0, + 27, 0, 0, 0, 15, 0, 0, 0, + 0, 0, 1, 0, 15, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 7, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 7, 0, 0, 3, 0, 1, 0, + 32, 7, 0, 0, 2, 0, 1, 0, + 33, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 16, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 7, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 7, 0, 0, 3, 0, 1, 0, + 44, 7, 0, 0, 2, 0, 1, 0, + 34, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 17, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 7, 0, 0, 234, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 7, 0, 0, 3, 0, 1, 0, + 60, 7, 0, 0, 2, 0, 1, 0, + 35, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 57, 7, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 60, 7, 0, 0, 3, 0, 1, 0, + 72, 7, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 192, 2, 0, 0, + 0, 0, 1, 0, 19, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 7, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 7, 0, 0, 3, 0, 1, 0, + 76, 7, 0, 0, 2, 0, 1, 0, + 56, 0, 0, 0, 193, 2, 0, 0, + 0, 0, 1, 0, 20, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 7, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 7, 0, 0, 3, 0, 1, 0, + 88, 7, 0, 0, 2, 0, 1, 0, + 58, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 21, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 85, 7, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 88, 7, 0, 0, 3, 0, 1, 0, + 116, 7, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 23, 0, 0, 0, + 0, 0, 1, 0, 22, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 7, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 7, 0, 0, 3, 0, 1, 0, + 120, 7, 0, 0, 2, 0, 1, 0, + 43, 0, 0, 0, 194, 2, 0, 0, + 0, 0, 1, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 7, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 7, 0, 0, 3, 0, 1, 0, + 132, 7, 0, 0, 2, 0, 1, 0, + 19, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 24, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 129, 7, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 128, 7, 0, 0, 3, 0, 1, 0, + 140, 7, 0, 0, 2, 0, 1, 0, + 20, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 25, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 137, 7, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 136, 7, 0, 0, 3, 0, 1, 0, + 148, 7, 0, 0, 2, 0, 1, 0, + 51, 0, 0, 0, 24, 0, 0, 0, + 0, 0, 1, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 145, 7, 0, 0, 210, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 152, 7, 0, 0, 3, 0, 1, 0, + 164, 7, 0, 0, 2, 0, 1, 0, + 47, 0, 0, 0, 25, 0, 0, 0, + 0, 0, 1, 0, 27, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 161, 7, 0, 0, 202, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 7, 0, 0, 3, 0, 1, 0, + 180, 7, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 13, 0, 0, 0, + 0, 0, 1, 0, 28, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 7, 0, 0, 202, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 7, 0, 0, 3, 0, 1, 0, + 196, 7, 0, 0, 2, 0, 1, 0, + 57, 0, 0, 0, 28, 0, 0, 0, + 0, 0, 1, 0, 29, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 7, 0, 0, 18, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 7, 0, 0, 3, 0, 1, 0, + 216, 7, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 45, 0, 0, 0, + 0, 0, 1, 0, 30, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 7, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 7, 0, 0, 3, 0, 1, 0, + 228, 7, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 1, 0, 31, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 225, 7, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 220, 7, 0, 0, 3, 0, 1, 0, + 232, 7, 0, 0, 2, 0, 1, 0, + 31, 0, 0, 0, 30, 0, 0, 0, + 0, 0, 1, 0, 32, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 7, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 7, 0, 0, 3, 0, 1, 0, + 244, 7, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 31, 0, 0, 0, + 0, 0, 1, 0, 33, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 7, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 7, 0, 0, 3, 0, 1, 0, + 252, 7, 0, 0, 2, 0, 1, 0, + 40, 0, 0, 0, 32, 0, 0, 0, + 0, 0, 1, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 249, 7, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 252, 7, 0, 0, 3, 0, 1, 0, + 8, 8, 0, 0, 2, 0, 1, 0, + 15, 0, 0, 0, 33, 0, 0, 0, + 0, 0, 1, 0, 35, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 8, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 8, 0, 0, 3, 0, 1, 0, + 12, 8, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 195, 2, 0, 0, + 0, 0, 1, 0, 36, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 8, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 8, 0, 0, 3, 0, 1, 0, + 16, 8, 0, 0, 2, 0, 1, 0, + 16, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 1, 0, 37, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 8, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 8, 0, 0, 3, 0, 1, 0, + 24, 8, 0, 0, 2, 0, 1, 0, + 21, 0, 0, 0, 59, 0, 0, 0, + 0, 0, 1, 0, 38, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 8, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 8, 0, 0, 3, 0, 1, 0, + 32, 8, 0, 0, 2, 0, 1, 0, + 22, 0, 0, 0, 70, 0, 0, 0, + 0, 0, 1, 0, 39, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 8, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 28, 8, 0, 0, 3, 0, 1, 0, + 40, 8, 0, 0, 2, 0, 1, 0, + 48, 0, 0, 0, 196, 2, 0, 0, + 0, 0, 1, 0, 40, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 8, 0, 0, 218, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 8, 0, 0, 3, 0, 1, 0, + 56, 8, 0, 0, 2, 0, 1, 0, + 26, 0, 0, 0, 197, 2, 0, 0, + 0, 0, 1, 0, 41, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 53, 8, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 52, 8, 0, 0, 3, 0, 1, 0, + 64, 8, 0, 0, 2, 0, 1, 0, + 23, 0, 0, 0, 36, 0, 0, 0, + 0, 0, 1, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 8, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 8, 0, 0, 3, 0, 1, 0, + 76, 8, 0, 0, 2, 0, 1, 0, + 44, 0, 0, 0, 198, 2, 0, 0, + 0, 0, 1, 0, 43, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 8, 0, 0, 234, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 80, 8, 0, 0, 3, 0, 1, 0, + 92, 8, 0, 0, 2, 0, 1, 0, + 24, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 44, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 89, 8, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 88, 8, 0, 0, 3, 0, 1, 0, + 100, 8, 0, 0, 2, 0, 1, 0, + 46, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 45, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 8, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 8, 0, 0, 3, 0, 1, 0, + 112, 8, 0, 0, 2, 0, 1, 0, + 53, 0, 0, 0, 37, 0, 0, 0, + 0, 0, 1, 0, 46, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 8, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 8, 0, 0, 3, 0, 1, 0, + 124, 8, 0, 0, 2, 0, 1, 0, + 49, 0, 0, 0, 199, 2, 0, 0, + 0, 0, 1, 0, 47, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 8, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 8, 0, 0, 3, 0, 1, 0, + 136, 8, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 19, 0, 0, 0, + 0, 0, 1, 0, 48, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 8, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 132, 8, 0, 0, 3, 0, 1, 0, + 144, 8, 0, 0, 2, 0, 1, 0, + 54, 0, 0, 0, 200, 2, 0, 0, + 0, 0, 1, 0, 49, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 8, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 144, 8, 0, 0, 3, 0, 1, 0, + 156, 8, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 20, 0, 0, 0, + 0, 0, 1, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 8, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 156, 8, 0, 0, 3, 0, 1, 0, + 168, 8, 0, 0, 2, 0, 1, 0, + 18, 0, 0, 0, 201, 2, 0, 0, + 0, 0, 1, 0, 51, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 165, 8, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 164, 8, 0, 0, 3, 0, 1, 0, + 176, 8, 0, 0, 2, 0, 1, 0, + 29, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 149, 70, 68, 107, 77, 145, 91, 253, + 173, 8, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 50, 0, 0, 0, 202, 2, 0, 0, + 0, 0, 1, 0, 54, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 157, 8, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 160, 8, 0, 0, 3, 0, 1, 0, + 172, 8, 0, 0, 2, 0, 1, 0, + 25, 0, 0, 0, 84, 0, 0, 0, + 0, 0, 1, 0, 56, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 169, 8, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 8, 0, 0, 3, 0, 1, 0, + 180, 8, 0, 0, 2, 0, 1, 0, + 28, 0, 0, 0, 43, 0, 0, 0, + 0, 0, 1, 0, 57, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 8, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 8, 0, 0, 3, 0, 1, 0, + 188, 8, 0, 0, 2, 0, 1, 0, + 17, 0, 0, 0, 44, 0, 0, 0, + 0, 0, 1, 0, 61, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 8, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 8, 0, 0, 3, 0, 1, 0, + 200, 8, 0, 0, 2, 0, 1, 0, + 59, 0, 0, 0, 45, 0, 0, 0, + 0, 0, 1, 0, 62, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 8, 0, 0, 250, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 8, 0, 0, 3, 0, 1, 0, + 216, 8, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 46, 0, 0, 0, + 0, 0, 1, 0, 63, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 8, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 212, 8, 0, 0, 3, 0, 1, 0, + 224, 8, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 203, 2, 0, 0, + 0, 0, 1, 0, 64, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 8, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 224, 8, 0, 0, 3, 0, 1, 0, + 236, 8, 0, 0, 2, 0, 1, 0, + 118, 69, 103, 111, 68, 69, 80, 82, + 69, 67, 65, 84, 69, 68, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 69, 103, 111, 68, 69, 80, 82, + 69, 67, 65, 84, 69, 68, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 80, 105, 100, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 84, 97, 114, 103, 101, 116, 76, + 101, 97, 100, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 112, 65, 99, 99, 101, 108, 67, + 109, 100, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 105, 65, 99, 99, 101, 108, 67, + 109, 100, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 65, 99, 116, 117, 97, 108, 68, + 69, 80, 82, 69, 67, 65, 84, 69, + 68, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 68, 101, 115, 68, 69, 80, 82, + 69, 67, 65, 84, 69, 68, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 112, 83, 116, 101, 101, 114, 68, + 69, 80, 82, 69, 67, 65, 84, 69, + 68, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 105, 83, 116, 101, 101, 114, 68, + 69, 80, 82, 69, 67, 65, 84, 69, + 68, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 84, 97, 114, 103, 101, 116, 77, + 105, 110, 68, 69, 80, 82, 69, 67, + 65, 84, 69, 68, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 84, 97, 114, 103, 101, 116, 77, + 97, 120, 68, 69, 80, 82, 69, 67, + 65, 84, 69, 68, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 106, 101, 114, 107, 70, 97, 99, 116, + 111, 114, 68, 69, 80, 82, 69, 67, + 65, 84, 69, 68, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 110, 103, 108, 101, 83, 116, 101, + 101, 114, 115, 68, 69, 80, 82, 69, + 67, 65, 84, 69, 68, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 117, 100, 76, 101, 97, 100, 68, + 69, 80, 82, 69, 67, 65, 84, 69, + 68, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 109, 76, 97, 103, 77, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 110, 77, 111, 110, 111, 84, + 105, 109, 101, 68, 69, 80, 82, 69, + 67, 65, 84, 69, 68, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 97, 100, 97, 114, 83, 116, 97, + 116, 101, 77, 111, 110, 111, 84, 105, + 109, 101, 68, 69, 80, 82, 69, 67, + 65, 84, 69, 68, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 100, 77, 111, 110, 111, 84, 105, + 109, 101, 68, 69, 80, 82, 69, 67, + 65, 84, 69, 68, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 110, 97, 98, 108, 101, 100, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 79, 118, 101, + 114, 114, 105, 100, 101, 68, 69, 80, + 82, 69, 67, 65, 84, 69, 68, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 110, 77, 111, 110, 111, 84, + 105, 109, 101, 115, 68, 69, 80, 82, + 69, 67, 65, 84, 69, 68, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 67, 114, 117, 105, 115, 101, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 101, 97, 114, 86, 105, 101, 119, + 67, 97, 109, 68, 69, 80, 82, 69, + 67, 65, 84, 69, 68, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 108, 101, 114, 116, 84, 101, 120, + 116, 49, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 108, 101, 114, 116, 84, 101, 120, + 116, 50, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 119, 97, 114, 101, 110, 101, 115, + 115, 83, 116, 97, 116, 117, 115, 68, + 69, 80, 82, 69, 67, 65, 84, 69, + 68, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 110, 103, 108, 101, 77, 111, 100, + 101, 108, 66, 105, 97, 115, 68, 69, + 80, 82, 69, 67, 65, 84, 69, 68, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 110, 103, 105, 116, 117, 100, + 105, 110, 97, 108, 80, 108, 97, 110, + 77, 111, 110, 111, 84, 105, 109, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 105, 110, 103, + 65, 110, 103, 108, 101, 68, 101, 115, + 105, 114, 101, 100, 68, 101, 103, 68, + 69, 80, 82, 69, 67, 65, 84, 69, + 68, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 110, 103, 67, 111, 110, 116, + 114, 111, 108, 83, 116, 97, 116, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 130, 130, 144, 125, 145, 58, 15, 228, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 116, 101, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 97, 172, 209, 210, 150, 139, 229, 219, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 69, 103, 111, 82, 97, 119, 68, + 69, 80, 82, 69, 67, 65, 84, 69, + 68, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 102, 65, 99, 99, 101, 108, 67, + 109, 100, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 102, 83, 116, 101, 101, 114, 68, + 69, 80, 82, 69, 67, 65, 84, 69, + 68, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 84, 97, 114, 103, 101, 116, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 116, 105, 118, 101, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 114, 118, 97, 116, 117, 114, + 101, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 108, 101, 114, 116, 83, 116, 97, + 116, 117, 115, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 98, 60, 25, 19, 209, 220, 208, 160, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 108, 101, 114, 116, 83, 105, 122, + 101, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 100, 95, 152, 110, 157, 185, 139, 233, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 80, 108, 97, 110, 110, + 101, 114, 65, 99, 116, 105, 118, 101, + 68, 69, 80, 82, 69, 67, 65, 84, + 69, 68, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 110, 103, 97, 103, 101, 97, 98, + 108, 101, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 108, 101, 114, 116, 66, 108, 105, + 110, 107, 105, 110, 103, 82, 97, 116, + 101, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 114, 105, 118, 101, 114, 77, 111, + 110, 105, 116, 111, 114, 105, 110, 103, + 79, 110, 68, 69, 80, 82, 69, 67, + 65, 84, 69, 68, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 108, 101, 114, 116, 84, 121, 112, + 101, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 108, 101, 114, 116, 83, 111, 117, + 110, 100, 68, 69, 80, 82, 69, 67, + 65, 84, 69, 68, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 67, 117, 114, 118, 97, 116, 117, + 114, 101, 68, 69, 80, 82, 69, 67, + 65, 84, 69, 68, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 99, 101, 108, 70, 111, 114, + 84, 117, 114, 110, 68, 69, 80, 82, + 69, 67, 65, 84, 69, 68, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 114, 116, 77, 111, 110, + 111, 84, 105, 109, 101, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 97, 112, 86, 97, 108, 105, 100, + 68, 69, 80, 82, 69, 67, 65, 84, + 69, 68, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 116, 101, 114, 97, 108, 80, + 108, 97, 110, 77, 111, 110, 111, 84, + 105, 109, 101, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 111, 114, 99, 101, 68, 101, 99, + 101, 108, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 116, 101, 114, 97, 108, 67, + 111, 110, 116, 114, 111, 108, 83, 116, + 97, 116, 101, 0, 0, 0, 0, 0, + 100, 101, 99, 101, 108, 70, 111, 114, + 77, 111, 100, 101, 108, 68, 69, 80, + 82, 69, 67, 65, 84, 69, 68, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 108, 101, 114, 116, 83, 111, 117, + 110, 100, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 158, 51, 78, 149, 108, 226, 165, 245, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 110, 69, 114, 114, 111, 114, + 67, 111, 117, 110, 116, 101, 114, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 115, 105, 114, 101, 100, 67, + 117, 114, 118, 97, 116, 117, 114, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 115, 105, 114, 101, 100, 67, + 117, 114, 118, 97, 116, 117, 114, 101, + 82, 97, 116, 101, 68, 69, 80, 82, + 69, 67, 65, 84, 69, 68, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 67, 114, 117, 105, 115, 101, 67, + 108, 117, 115, 116, 101, 114, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 120, 112, 101, 114, 105, 109, 101, + 110, 116, 97, 108, 77, 111, 100, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_97ff69c53601abf1 = b_97ff69c53601abf1.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_97ff69c53601abf1[] = { + &s_a0d0dcd113193c62, + &s_dbe58b96d2d1ac61, + &s_e40f3a917d908282, + &s_e98bb99d6e985f64, + &s_f5a5e26c954e339e, + &s_fd5b914d6b444695, +}; +static const uint16_t m_97ff69c53601abf1[] = {1, 35, 11, 10, 36, 42, 39, 54, 45, 38, 24, 25, 44, 27, 13, 26, 55, 16, 21, 15, 37, 53, 47, 56, 57, 43, 19, 41, 59, 51, 40, 14, 12, 52, 50, 30, 28, 49, 18, 17, 23, 48, 31, 20, 29, 33, 34, 5, 9, 4, 8, 22, 58, 46, 0, 32, 2, 3, 6, 7}; +static const uint16_t i_97ff69c53601abf1[] = {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, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59}; +const ::capnp::_::RawSchema s_97ff69c53601abf1 = { + 0x97ff69c53601abf1, b_97ff69c53601abf1.words, 1056, d_97ff69c53601abf1, m_97ff69c53601abf1, + 6, 60, i_97ff69c53601abf1, nullptr, nullptr, { &s_97ff69c53601abf1, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<43> b_dbe58b96d2d1ac61 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 97, 172, 209, 210, 150, 139, 229, 219, + 24, 0, 0, 0, 2, 0, 0, 0, + 241, 171, 1, 54, 197, 105, 255, 151, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 58, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 127, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 67, 111, 110, 116, 114, 111, + 108, 115, 83, 116, 97, 116, 101, 46, + 79, 112, 101, 110, 112, 105, 108, 111, + 116, 83, 116, 97, 116, 101, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 20, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 53, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 49, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 105, 115, 97, 98, 108, 101, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 114, 101, 69, 110, 97, 98, 108, + 101, 100, 0, 0, 0, 0, 0, 0, + 101, 110, 97, 98, 108, 101, 100, 0, + 115, 111, 102, 116, 68, 105, 115, 97, + 98, 108, 105, 110, 103, 0, 0, 0, + 111, 118, 101, 114, 114, 105, 100, 105, + 110, 103, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_dbe58b96d2d1ac61 = b_dbe58b96d2d1ac61.words; +#if !CAPNP_LITE +static const uint16_t m_dbe58b96d2d1ac61[] = {0, 2, 4, 1, 3}; +const ::capnp::_::RawSchema s_dbe58b96d2d1ac61 = { + 0xdbe58b96d2d1ac61, b_dbe58b96d2d1ac61.words, 43, nullptr, m_dbe58b96d2d1ac61, + 0, 5, nullptr, nullptr, nullptr, { &s_dbe58b96d2d1ac61, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(OpenpilotState_dbe58b96d2d1ac61, dbe58b96d2d1ac61); +static const ::capnp::_::AlignedData<38> b_a0d0dcd113193c62 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 98, 60, 25, 19, 209, 220, 208, 160, + 24, 0, 0, 0, 2, 0, 0, 0, + 241, 171, 1, 54, 197, 105, 255, 151, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 34, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 103, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 67, 111, 110, 116, 114, 111, + 108, 115, 83, 116, 97, 116, 101, 46, + 65, 108, 101, 114, 116, 83, 116, 97, + 116, 117, 115, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 111, 114, 109, 97, 108, 0, 0, + 117, 115, 101, 114, 80, 114, 111, 109, + 112, 116, 0, 0, 0, 0, 0, 0, + 99, 114, 105, 116, 105, 99, 97, 108, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 114, 111, 103, 112, 105, 108, 111, + 116, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_a0d0dcd113193c62 = b_a0d0dcd113193c62.words; +#if !CAPNP_LITE +static const uint16_t m_a0d0dcd113193c62[] = {2, 3, 0, 1}; +const ::capnp::_::RawSchema s_a0d0dcd113193c62 = { + 0xa0d0dcd113193c62, b_a0d0dcd113193c62.words, 38, nullptr, m_a0d0dcd113193c62, + 0, 4, nullptr, nullptr, nullptr, { &s_a0d0dcd113193c62, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(AlertStatus_a0d0dcd113193c62, a0d0dcd113193c62); +static const ::capnp::_::AlignedData<35> b_e98bb99d6e985f64 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 100, 95, 152, 110, 157, 185, 139, 233, + 24, 0, 0, 0, 2, 0, 0, 0, + 241, 171, 1, 54, 197, 105, 255, 151, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 18, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 103, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 67, 111, 110, 116, 114, 111, + 108, 115, 83, 116, 97, 116, 101, 46, + 65, 108, 101, 114, 116, 83, 105, 122, + 101, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 17, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 111, 110, 101, 0, 0, 0, 0, + 115, 109, 97, 108, 108, 0, 0, 0, + 109, 105, 100, 0, 0, 0, 0, 0, + 102, 117, 108, 108, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e98bb99d6e985f64 = b_e98bb99d6e985f64.words; +#if !CAPNP_LITE +static const uint16_t m_e98bb99d6e985f64[] = {3, 2, 0, 1}; +const ::capnp::_::RawSchema s_e98bb99d6e985f64 = { + 0xe98bb99d6e985f64, b_e98bb99d6e985f64.words, 35, nullptr, m_e98bb99d6e985f64, + 0, 4, nullptr, nullptr, nullptr, { &s_e98bb99d6e985f64, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(AlertSize_e98bb99d6e985f64, e98bb99d6e985f64); +static const ::capnp::_::AlignedData<229> b_939463348632375e = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 94, 55, 50, 134, 52, 99, 148, 147, + 24, 0, 0, 0, 1, 0, 6, 0, + 241, 171, 1, 54, 197, 105, 255, 151, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 74, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 223, 2, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 67, 111, 110, 116, 114, 111, + 108, 115, 83, 116, 97, 116, 101, 46, + 76, 97, 116, 101, 114, 97, 108, 73, + 78, 68, 73, 83, 116, 97, 116, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 52, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 88, 1, 0, 0, 3, 0, 1, 0, + 100, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 1, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 1, 0, 0, 3, 0, 1, 0, + 112, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 1, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 1, 0, 0, 3, 0, 1, 0, + 120, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 1, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 1, 0, 0, 3, 0, 1, 0, + 132, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 129, 1, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 128, 1, 0, 0, 3, 0, 1, 0, + 140, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 137, 1, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 136, 1, 0, 0, 3, 0, 1, 0, + 148, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 145, 1, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 144, 1, 0, 0, 3, 0, 1, 0, + 156, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 1, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 152, 1, 0, 0, 3, 0, 1, 0, + 164, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 161, 1, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 156, 1, 0, 0, 3, 0, 1, 0, + 168, 1, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 165, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 160, 1, 0, 0, 3, 0, 1, 0, + 172, 1, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 169, 1, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 1, 0, 0, 3, 0, 1, 0, + 180, 1, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 1, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 1, 0, 0, 3, 0, 1, 0, + 192, 1, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 11, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 1, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 192, 1, 0, 0, 3, 0, 1, 0, + 204, 1, 0, 0, 2, 0, 1, 0, + 97, 99, 116, 105, 118, 101, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 105, 110, 103, + 65, 110, 103, 108, 101, 68, 101, 103, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 105, 110, 103, + 82, 97, 116, 101, 68, 101, 103, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 105, 110, 103, + 65, 99, 99, 101, 108, 68, 101, 103, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 97, 116, 101, 83, 101, 116, 80, + 111, 105, 110, 116, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 99, 101, 108, 83, 101, 116, + 80, 111, 105, 110, 116, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 99, 101, 108, 69, 114, 114, + 111, 114, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 108, 97, 121, 101, 100, 79, + 117, 116, 112, 117, 116, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 108, 116, 97, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 117, 116, 112, 117, 116, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 97, 116, 117, 114, 97, 116, 101, + 100, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 105, 110, 103, + 65, 110, 103, 108, 101, 68, 101, 115, + 105, 114, 101, 100, 68, 101, 103, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 105, 110, 103, + 82, 97, 116, 101, 68, 101, 115, 105, + 114, 101, 100, 68, 101, 103, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_939463348632375e = b_939463348632375e.words; +#if !CAPNP_LITE +static const uint16_t m_939463348632375e[] = {6, 5, 0, 7, 8, 9, 4, 10, 3, 1, 11, 2, 12}; +static const uint16_t i_939463348632375e[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12}; +const ::capnp::_::RawSchema s_939463348632375e = { + 0x939463348632375e, b_939463348632375e.words, 229, nullptr, m_939463348632375e, + 0, 13, i_939463348632375e, nullptr, nullptr, { &s_939463348632375e, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<176> b_f28c5dc9e09375e3 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 227, 117, 147, 224, 201, 93, 140, 242, + 24, 0, 0, 0, 1, 0, 5, 0, + 241, 171, 1, 54, 197, 105, 255, 151, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 66, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 55, 2, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 67, 111, 110, 116, 114, 111, + 108, 115, 83, 116, 97, 116, 101, 46, + 76, 97, 116, 101, 114, 97, 108, 80, + 73, 68, 83, 116, 97, 116, 101, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 40, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 1, 0, 0, 3, 0, 1, 0, + 16, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 1, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 1, 0, 0, 3, 0, 1, 0, + 28, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 1, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 24, 1, 0, 0, 3, 0, 1, 0, + 36, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 1, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 1, 0, 0, 3, 0, 1, 0, + 44, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 1, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 1, 0, 0, 3, 0, 1, 0, + 48, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 1, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 1, 0, 0, 3, 0, 1, 0, + 52, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 1, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 1, 0, 0, 3, 0, 1, 0, + 56, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 53, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 1, 0, 0, 3, 0, 1, 0, + 60, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 57, 1, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 56, 1, 0, 0, 3, 0, 1, 0, + 68, 1, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 65, 1, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 1, 0, 0, 3, 0, 1, 0, + 80, 1, 0, 0, 2, 0, 1, 0, + 97, 99, 116, 105, 118, 101, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 105, 110, 103, + 65, 110, 103, 108, 101, 68, 101, 103, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 105, 110, 103, + 82, 97, 116, 101, 68, 101, 103, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 110, 103, 108, 101, 69, 114, 114, + 111, 114, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 117, 116, 112, 117, 116, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 97, 116, 117, 114, 97, 116, 101, + 100, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 105, 110, 103, + 65, 110, 103, 108, 101, 68, 101, 115, + 105, 114, 101, 100, 68, 101, 103, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_f28c5dc9e09375e3 = b_f28c5dc9e09375e3.words; +#if !CAPNP_LITE +static const uint16_t m_f28c5dc9e09375e3[] = {0, 3, 6, 5, 7, 4, 8, 1, 9, 2}; +static const uint16_t i_f28c5dc9e09375e3[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9}; +const ::capnp::_::RawSchema s_f28c5dc9e09375e3 = { + 0xf28c5dc9e09375e3, b_f28c5dc9e09375e3.words, 176, nullptr, m_f28c5dc9e09375e3, + 0, 10, i_f28c5dc9e09375e3, nullptr, nullptr, { &s_f28c5dc9e09375e3, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<210> b_e774a050cbf689a4 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 164, 137, 246, 203, 80, 160, 116, 231, + 24, 0, 0, 0, 1, 0, 5, 0, + 241, 171, 1, 54, 197, 105, 255, 151, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 90, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 167, 2, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 67, 111, 110, 116, 114, 111, + 108, 115, 83, 116, 97, 116, 101, 46, + 76, 97, 116, 101, 114, 97, 108, 84, + 111, 114, 113, 117, 101, 83, 116, 97, + 116, 101, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 48, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 65, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 60, 1, 0, 0, 3, 0, 1, 0, + 72, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 1, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 1, 0, 0, 3, 0, 1, 0, + 76, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 1, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 1, 0, 0, 3, 0, 1, 0, + 80, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 1, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 1, 0, 0, 3, 0, 1, 0, + 84, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 81, 1, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 1, 0, 0, 3, 0, 1, 0, + 88, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 85, 1, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 80, 1, 0, 0, 3, 0, 1, 0, + 92, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 89, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 84, 1, 0, 0, 3, 0, 1, 0, + 96, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 1, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 1, 0, 0, 3, 0, 1, 0, + 104, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 1, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 1, 0, 0, 3, 0, 1, 0, + 112, 1, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 1, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 1, 0, 0, 3, 0, 1, 0, + 124, 1, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 1, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 1, 0, 0, 3, 0, 1, 0, + 136, 1, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 1, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 128, 1, 0, 0, 3, 0, 1, 0, + 156, 1, 0, 0, 2, 0, 1, 0, + 97, 99, 116, 105, 118, 101, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 114, 114, 111, 114, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 117, 116, 112, 117, 116, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 97, 116, 117, 114, 97, 116, 101, + 100, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 114, 114, 111, 114, 82, 97, 116, + 101, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 116, 117, 97, 108, 76, 97, + 116, 101, 114, 97, 108, 65, 99, 99, + 101, 108, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 115, 105, 114, 101, 100, 76, + 97, 116, 101, 114, 97, 108, 65, 99, + 99, 101, 108, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 110, 76, 111, 103, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e774a050cbf689a4 = b_e774a050cbf689a4.words; +#if !CAPNP_LITE +static const uint16_t m_e774a050cbf689a4[] = {0, 9, 4, 10, 1, 8, 5, 3, 11, 6, 2, 7}; +static const uint16_t i_e774a050cbf689a4[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11}; +const ::capnp::_::RawSchema s_e774a050cbf689a4 = { + 0xe774a050cbf689a4, b_e774a050cbf689a4.words, 210, nullptr, m_e774a050cbf689a4, + 0, 12, i_e774a050cbf689a4, nullptr, nullptr, { &s_e774a050cbf689a4, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<130> b_9024e2d790c82ade = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 222, 42, 200, 144, 215, 226, 36, 144, + 24, 0, 0, 0, 1, 0, 3, 0, + 241, 171, 1, 54, 197, 105, 255, 151, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 66, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 143, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 67, 111, 110, 116, 114, 111, + 108, 115, 83, 116, 97, 116, 101, 46, + 76, 97, 116, 101, 114, 97, 108, 76, + 81, 82, 83, 116, 97, 116, 101, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 28, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 0, 0, 0, 3, 0, 1, 0, + 188, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 0, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 0, 0, 0, 3, 0, 1, 0, + 200, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 192, 0, 0, 0, 3, 0, 1, 0, + 204, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 0, 0, 0, 3, 0, 1, 0, + 208, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 0, 0, 0, 3, 0, 1, 0, + 216, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 212, 0, 0, 0, 3, 0, 1, 0, + 224, 0, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 0, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 224, 0, 0, 0, 3, 0, 1, 0, + 236, 0, 0, 0, 2, 0, 1, 0, + 97, 99, 116, 105, 118, 101, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 105, 110, 103, + 65, 110, 103, 108, 101, 68, 101, 103, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 117, 116, 112, 117, 116, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 113, 114, 79, 117, 116, 112, 117, + 116, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 97, 116, 117, 114, 97, 116, 101, + 100, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 105, 110, 103, + 65, 110, 103, 108, 101, 68, 101, 115, + 105, 114, 101, 100, 68, 101, 103, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_9024e2d790c82ade = b_9024e2d790c82ade.words; +#if !CAPNP_LITE +static const uint16_t m_9024e2d790c82ade[] = {0, 2, 4, 3, 5, 1, 6}; +static const uint16_t i_9024e2d790c82ade[] = {0, 1, 2, 3, 4, 5, 6}; +const ::capnp::_::RawSchema s_9024e2d790c82ade = { + 0x9024e2d790c82ade, b_9024e2d790c82ade.words, 130, nullptr, m_9024e2d790c82ade, + 0, 7, i_9024e2d790c82ade, nullptr, nullptr, { &s_9024e2d790c82ade, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<100> b_a2e4ea88ac9980f1 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 241, 128, 153, 172, 136, 234, 228, 162, + 24, 0, 0, 0, 1, 0, 2, 0, + 241, 171, 1, 54, 197, 105, 255, 151, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 82, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 31, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 67, 111, 110, 116, 114, 111, + 108, 115, 83, 116, 97, 116, 101, 46, + 76, 97, 116, 101, 114, 97, 108, 65, + 110, 103, 108, 101, 83, 116, 97, 116, + 101, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 20, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 0, 0, 0, 3, 0, 1, 0, + 132, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 129, 0, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 132, 0, 0, 0, 3, 0, 1, 0, + 144, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 136, 0, 0, 0, 3, 0, 1, 0, + 148, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 145, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 144, 0, 0, 0, 3, 0, 1, 0, + 156, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 0, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 156, 0, 0, 0, 3, 0, 1, 0, + 168, 0, 0, 0, 2, 0, 1, 0, + 97, 99, 116, 105, 118, 101, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 105, 110, 103, + 65, 110, 103, 108, 101, 68, 101, 103, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 117, 116, 112, 117, 116, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 97, 116, 117, 114, 97, 116, 101, + 100, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 105, 110, 103, + 65, 110, 103, 108, 101, 68, 101, 115, + 105, 114, 101, 100, 68, 101, 103, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_a2e4ea88ac9980f1 = b_a2e4ea88ac9980f1.words; +#if !CAPNP_LITE +static const uint16_t m_a2e4ea88ac9980f1[] = {0, 2, 3, 1, 4}; +static const uint16_t i_a2e4ea88ac9980f1[] = {0, 1, 2, 3, 4}; +const ::capnp::_::RawSchema s_a2e4ea88ac9980f1 = { + 0xa2e4ea88ac9980f1, b_a2e4ea88ac9980f1.words, 100, nullptr, m_a2e4ea88ac9980f1, + 0, 5, i_a2e4ea88ac9980f1, nullptr, nullptr, { &s_a2e4ea88ac9980f1, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<159> b_ad9d8095c06f7c61 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 97, 124, 111, 192, 149, 128, 157, 173, + 24, 0, 0, 0, 1, 0, 4, 0, + 241, 171, 1, 54, 197, 105, 255, 151, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 114, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 255, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 67, 111, 110, 116, 114, 111, + 108, 115, 83, 116, 97, 116, 101, 46, + 76, 97, 116, 101, 114, 97, 108, 67, + 117, 114, 118, 97, 116, 117, 114, 101, + 83, 116, 97, 116, 101, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 36, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 0, 0, 0, 3, 0, 1, 0, + 244, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 0, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 0, 0, 0, 3, 0, 1, 0, + 252, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 249, 0, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 252, 0, 0, 0, 3, 0, 1, 0, + 8, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 1, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 1, 0, 0, 3, 0, 1, 0, + 12, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 1, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 1, 0, 0, 3, 0, 1, 0, + 16, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 1, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 1, 0, 0, 3, 0, 1, 0, + 20, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 1, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 1, 0, 0, 3, 0, 1, 0, + 24, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 1, 0, 0, 3, 0, 1, 0, + 28, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 1, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 24, 1, 0, 0, 3, 0, 1, 0, + 36, 1, 0, 0, 2, 0, 1, 0, + 97, 99, 116, 105, 118, 101, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 116, 117, 97, 108, 67, 117, + 114, 118, 97, 116, 117, 114, 101, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 115, 105, 114, 101, 100, 67, + 117, 114, 118, 97, 116, 117, 114, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 114, 114, 111, 114, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 117, 116, 112, 117, 116, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 97, 116, 117, 114, 97, 116, 101, + 100, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_ad9d8095c06f7c61 = b_ad9d8095c06f7c61.words; +#if !CAPNP_LITE +static const uint16_t m_ad9d8095c06f7c61[] = {0, 1, 2, 3, 6, 5, 7, 4, 8}; +static const uint16_t i_ad9d8095c06f7c61[] = {0, 1, 2, 3, 4, 5, 6, 7, 8}; +const ::capnp::_::RawSchema s_ad9d8095c06f7c61 = { + 0xad9d8095c06f7c61, b_ad9d8095c06f7c61.words, 159, nullptr, m_ad9d8095c06f7c61, + 0, 9, i_ad9d8095c06f7c61, nullptr, nullptr, { &s_ad9d8095c06f7c61, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<83> b_a63a46f0f2889b2d = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 45, 155, 136, 242, 240, 70, 58, 166, + 24, 0, 0, 0, 1, 0, 2, 0, + 241, 171, 1, 54, 197, 105, 255, 151, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 82, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 231, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 67, 111, 110, 116, 114, 111, + 108, 115, 83, 116, 97, 116, 101, 46, + 76, 97, 116, 101, 114, 97, 108, 68, + 101, 98, 117, 103, 83, 116, 97, 116, + 101, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 0, 0, 0, 3, 0, 1, 0, + 104, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 0, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 0, 0, 0, 3, 0, 1, 0, + 116, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 0, 0, 0, 3, 0, 1, 0, + 120, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 0, 0, 0, 3, 0, 1, 0, + 128, 0, 0, 0, 2, 0, 1, 0, + 97, 99, 116, 105, 118, 101, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 105, 110, 103, + 65, 110, 103, 108, 101, 68, 101, 103, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 117, 116, 112, 117, 116, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 97, 116, 117, 114, 97, 116, 101, + 100, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_a63a46f0f2889b2d = b_a63a46f0f2889b2d.words; +#if !CAPNP_LITE +static const uint16_t m_a63a46f0f2889b2d[] = {0, 2, 3, 1}; +static const uint16_t i_a63a46f0f2889b2d[] = {0, 1, 2, 3}; +const ::capnp::_::RawSchema s_a63a46f0f2889b2d = { + 0xa63a46f0f2889b2d, b_a63a46f0f2889b2d.words, 83, nullptr, m_a63a46f0f2889b2d, + 0, 4, i_a63a46f0f2889b2d, nullptr, nullptr, { &s_a63a46f0f2889b2d, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<134> b_fd5b914d6b444695 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 149, 70, 68, 107, 77, 145, 91, 253, + 24, 0, 0, 0, 1, 0, 24, 0, + 241, 171, 1, 54, 197, 105, 255, 151, + 6, 0, 7, 0, 1, 0, 7, 0, + 71, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 98, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 143, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 67, 111, 110, 116, 114, 111, + 108, 115, 83, 116, 97, 116, 101, 46, + 108, 97, 116, 101, 114, 97, 108, 67, + 111, 110, 116, 114, 111, 108, 83, 116, + 97, 116, 101, 0, 0, 0, 0, 0, + 28, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 255, 255, 5, 0, 0, 0, + 0, 0, 1, 0, 52, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 0, 0, 0, 3, 0, 1, 0, + 192, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 254, 255, 5, 0, 0, 0, + 0, 0, 1, 0, 53, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 0, 0, 0, 3, 0, 1, 0, + 200, 0, 0, 0, 2, 0, 1, 0, + 6, 0, 253, 255, 5, 0, 0, 0, + 0, 0, 1, 0, 55, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 0, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 200, 0, 0, 0, 3, 0, 1, 0, + 212, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 252, 255, 5, 0, 0, 0, + 0, 0, 1, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 0, 0, 0, 3, 0, 1, 0, + 220, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 251, 255, 5, 0, 0, 0, + 0, 0, 1, 0, 59, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 217, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 0, 0, 0, 3, 0, 1, 0, + 228, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 250, 255, 5, 0, 0, 0, + 0, 0, 1, 0, 60, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 225, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 224, 0, 0, 0, 3, 0, 1, 0, + 236, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 249, 255, 5, 0, 0, 0, + 0, 0, 1, 0, 65, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 233, 0, 0, 0, 202, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 0, 0, 0, 3, 0, 1, 0, + 252, 0, 0, 0, 2, 0, 1, 0, + 105, 110, 100, 105, 83, 116, 97, 116, + 101, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 94, 55, 50, 134, 52, 99, 148, 147, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 105, 100, 83, 116, 97, 116, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 227, 117, 147, 224, 201, 93, 140, 242, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 113, 114, 83, 116, 97, 116, 101, + 68, 69, 80, 82, 69, 67, 65, 84, + 69, 68, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 222, 42, 200, 144, 215, 226, 36, 144, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 110, 103, 108, 101, 83, 116, 97, + 116, 101, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 241, 128, 153, 172, 136, 234, 228, 162, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 98, 117, 103, 83, 116, 97, + 116, 101, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 45, 155, 136, 242, 240, 70, 58, 166, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 111, 114, 113, 117, 101, 83, 116, + 97, 116, 101, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 164, 137, 246, 203, 80, 160, 116, 231, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 114, 118, 97, 116, 117, 114, + 101, 83, 116, 97, 116, 101, 68, 69, + 80, 82, 69, 67, 65, 84, 69, 68, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 97, 124, 111, 192, 149, 128, 157, 173, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_fd5b914d6b444695 = b_fd5b914d6b444695.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_fd5b914d6b444695[] = { + &s_9024e2d790c82ade, + &s_939463348632375e, + &s_97ff69c53601abf1, + &s_a2e4ea88ac9980f1, + &s_a63a46f0f2889b2d, + &s_ad9d8095c06f7c61, + &s_e774a050cbf689a4, + &s_f28c5dc9e09375e3, +}; +static const uint16_t m_fd5b914d6b444695[] = {3, 6, 4, 0, 2, 1, 5}; +static const uint16_t i_fd5b914d6b444695[] = {0, 1, 2, 3, 4, 5, 6}; +const ::capnp::_::RawSchema s_fd5b914d6b444695 = { + 0xfd5b914d6b444695, b_fd5b914d6b444695.words, 134, d_fd5b914d6b444695, m_fd5b914d6b444695, + 8, 7, i_fd5b914d6b444695, nullptr, nullptr, { &s_fd5b914d6b444695, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<150> b_c3cbae1fd505ae80 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 128, 174, 5, 213, 31, 174, 203, 195, + 10, 0, 0, 0, 1, 0, 0, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 7, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 154, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 143, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 88, 89, 90, 84, 68, 97, + 116, 97, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 28, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 0, 0, 0, 3, 0, 1, 0, + 204, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 0, 0, 0, 3, 0, 1, 0, + 224, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 0, 0, 0, 3, 0, 1, 0, + 244, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 236, 0, 0, 0, 3, 0, 1, 0, + 8, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 1, 0, 0, 3, 0, 1, 0, + 28, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 1, 0, 0, 3, 0, 1, 0, + 48, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 1, 0, 0, 3, 0, 1, 0, + 68, 1, 0, 0, 2, 0, 1, 0, + 120, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 122, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 83, 116, 100, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 83, 116, 100, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 122, 83, 116, 100, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_c3cbae1fd505ae80 = b_c3cbae1fd505ae80.words; +#if !CAPNP_LITE +static const uint16_t m_c3cbae1fd505ae80[] = {3, 0, 4, 1, 5, 2, 6}; +static const uint16_t i_c3cbae1fd505ae80[] = {0, 1, 2, 3, 4, 5, 6}; +const ::capnp::_::RawSchema s_c3cbae1fd505ae80 = { + 0xc3cbae1fd505ae80, b_c3cbae1fd505ae80.words, 150, nullptr, m_c3cbae1fd505ae80, + 0, 7, i_c3cbae1fd505ae80, nullptr, nullptr, { &s_c3cbae1fd505ae80, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<510> b_c4713f6b0d36abe9 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 233, 171, 54, 13, 107, 63, 113, 196, + 10, 0, 0, 0, 1, 0, 6, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 17, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 178, 0, 0, 0, + 29, 0, 0, 0, 135, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 0, 0, 0, 239, 5, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 77, 111, 100, 101, 108, 68, + 97, 116, 97, 86, 50, 0, 0, 0, + 32, 0, 0, 0, 1, 0, 1, 0, + 40, 175, 135, 33, 43, 237, 68, 164, + 57, 0, 0, 0, 90, 0, 0, 0, + 235, 127, 206, 208, 26, 136, 152, 214, + 57, 0, 0, 0, 90, 0, 0, 0, + 189, 250, 92, 180, 179, 106, 100, 209, + 57, 0, 0, 0, 74, 0, 0, 0, + 212, 28, 166, 210, 217, 71, 50, 170, + 57, 0, 0, 0, 130, 0, 0, 0, + 37, 141, 220, 188, 221, 165, 10, 134, + 57, 0, 0, 0, 170, 0, 0, 0, + 79, 136, 103, 46, 112, 192, 62, 251, + 61, 0, 0, 0, 42, 0, 0, 0, + 254, 172, 180, 166, 165, 236, 202, 132, + 57, 0, 0, 0, 186, 0, 0, 0, + 132, 69, 118, 90, 179, 188, 208, 148, + 61, 0, 0, 0, 58, 0, 0, 0, + 76, 101, 97, 100, 68, 97, 116, 97, + 86, 50, 0, 0, 0, 0, 0, 0, + 76, 101, 97, 100, 68, 97, 116, 97, + 86, 51, 0, 0, 0, 0, 0, 0, + 77, 101, 116, 97, 68, 97, 116, 97, + 0, 0, 0, 0, 0, 0, 0, 0, + 67, 111, 110, 102, 105, 100, 101, 110, + 99, 101, 67, 108, 97, 115, 115, 0, + 68, 105, 115, 101, 110, 103, 97, 103, + 101, 80, 114, 101, 100, 105, 99, 116, + 105, 111, 110, 115, 0, 0, 0, 0, + 80, 111, 115, 101, 0, 0, 0, 0, + 76, 97, 116, 101, 114, 97, 108, 80, + 108, 97, 110, 110, 101, 114, 83, 111, + 108, 117, 116, 105, 111, 110, 0, 0, + 65, 99, 116, 105, 111, 110, 0, 0, + 108, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 2, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 224, 2, 0, 0, 3, 0, 1, 0, + 236, 2, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 233, 2, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 2, 0, 0, 3, 0, 1, 0, + 244, 2, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 2, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 2, 0, 0, 3, 0, 1, 0, + 252, 2, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 249, 2, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 248, 2, 0, 0, 3, 0, 1, 0, + 4, 3, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 3, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 3, 0, 0, 3, 0, 1, 0, + 12, 3, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 3, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 3, 0, 0, 3, 0, 1, 0, + 20, 3, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 3, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 3, 0, 0, 3, 0, 1, 0, + 28, 3, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 3, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 24, 3, 0, 0, 3, 0, 1, 0, + 36, 3, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 3, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 3, 0, 0, 3, 0, 1, 0, + 60, 3, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 57, 3, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 56, 3, 0, 0, 3, 0, 1, 0, + 84, 3, 0, 0, 2, 0, 1, 0, + 16, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 81, 3, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 80, 3, 0, 0, 3, 0, 1, 0, + 108, 3, 0, 0, 2, 0, 1, 0, + 18, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 3, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 3, 0, 0, 3, 0, 1, 0, + 128, 3, 0, 0, 2, 0, 1, 0, + 20, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 3, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 3, 0, 0, 3, 0, 1, 0, + 132, 3, 0, 0, 2, 0, 1, 0, + 15, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 129, 3, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 128, 3, 0, 0, 3, 0, 1, 0, + 156, 3, 0, 0, 2, 0, 1, 0, + 17, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 3, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 152, 3, 0, 0, 3, 0, 1, 0, + 180, 3, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 15, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 3, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 3, 0, 0, 3, 0, 1, 0, + 192, 3, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 11, 0, 0, 0, + 0, 0, 1, 0, 16, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 3, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 3, 0, 0, 3, 0, 1, 0, + 200, 3, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 17, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 3, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 200, 3, 0, 0, 3, 0, 1, 0, + 212, 3, 0, 0, 2, 0, 1, 0, + 19, 0, 0, 0, 12, 0, 0, 0, + 0, 0, 1, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 3, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 3, 0, 0, 3, 0, 1, 0, + 232, 3, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 13, 0, 0, 0, + 0, 0, 1, 0, 19, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 3, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 228, 3, 0, 0, 3, 0, 1, 0, + 240, 3, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 20, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 3, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 236, 3, 0, 0, 3, 0, 1, 0, + 248, 3, 0, 0, 2, 0, 1, 0, + 22, 0, 0, 0, 14, 0, 0, 0, + 0, 0, 1, 0, 21, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 245, 3, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 244, 3, 0, 0, 3, 0, 1, 0, + 0, 4, 0, 0, 2, 0, 1, 0, + 23, 0, 0, 0, 0, 1, 0, 0, + 0, 0, 1, 0, 22, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 253, 3, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 252, 3, 0, 0, 3, 0, 1, 0, + 8, 4, 0, 0, 2, 0, 1, 0, + 21, 0, 0, 0, 17, 0, 0, 0, + 0, 0, 1, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 4, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 4, 0, 0, 3, 0, 1, 0, + 16, 4, 0, 0, 2, 0, 1, 0, + 24, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 24, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 4, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 4, 0, 0, 3, 0, 1, 0, + 28, 4, 0, 0, 2, 0, 1, 0, + 25, 0, 0, 0, 15, 0, 0, 0, + 0, 0, 1, 0, 25, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 4, 0, 0, 10, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 4, 0, 0, 3, 0, 1, 0, + 48, 4, 0, 0, 2, 0, 1, 0, + 26, 0, 0, 0, 16, 0, 0, 0, + 0, 0, 1, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 4, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 4, 0, 0, 3, 0, 1, 0, + 52, 4, 0, 0, 2, 0, 1, 0, + 102, 114, 97, 109, 101, 73, 100, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 114, 97, 109, 101, 65, 103, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 114, 97, 109, 101, 68, 114, 111, + 112, 80, 101, 114, 99, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 109, 101, 115, 116, 97, 109, + 112, 69, 111, 102, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 115, 105, 116, 105, 111, 110, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 128, 174, 5, 213, 31, 174, 203, 195, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 114, 105, 101, 110, 116, 97, 116, + 105, 111, 110, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 128, 174, 5, 213, 31, 174, 203, 195, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 101, 108, 111, 99, 105, 116, 121, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 128, 174, 5, 213, 31, 174, 203, 195, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 114, 105, 101, 110, 116, 97, 116, + 105, 111, 110, 82, 97, 116, 101, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 128, 174, 5, 213, 31, 174, 203, 195, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 110, 101, 76, 105, 110, 101, + 115, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 128, 174, 5, 213, 31, 174, 203, 195, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 110, 101, 76, 105, 110, 101, + 80, 114, 111, 98, 115, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 111, 97, 100, 69, 100, 103, 101, + 115, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 128, 174, 5, 213, 31, 174, 203, 195, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 97, 100, 115, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 40, 175, 135, 33, 43, 237, 68, 164, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 101, 116, 97, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 189, 250, 92, 180, 179, 106, 100, 209, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 110, 101, 76, 105, 110, 101, + 83, 116, 100, 115, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 111, 97, 100, 69, 100, 103, 101, + 83, 116, 100, 115, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 111, 100, 101, 108, 69, 120, 101, + 99, 117, 116, 105, 111, 110, 84, 105, + 109, 101, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 97, 119, 80, 114, 101, 100, 105, + 99, 116, 105, 111, 110, 115, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 117, 69, 120, 101, 99, 117, + 116, 105, 111, 110, 84, 105, 109, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 97, 100, 115, 86, 51, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 235, 127, 206, 208, 26, 136, 152, 214, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 99, 101, 108, 101, 114, 97, + 116, 105, 111, 110, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 128, 174, 5, 213, 31, 174, 203, 195, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 114, 97, 109, 101, 73, 100, 69, + 120, 116, 114, 97, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 101, 109, 112, 111, 114, 97, 108, + 80, 111, 115, 101, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 79, 136, 103, 46, 112, 192, 62, 251, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 97, 118, 69, 110, 97, 98, 108, + 101, 100, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 111, 110, 102, 105, 100, 101, 110, + 99, 101, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 212, 28, 166, 210, 217, 71, 50, 170, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 99, 97, 116, 105, 111, 110, + 77, 111, 110, 111, 84, 105, 109, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 116, 101, 114, 97, 108, 80, + 108, 97, 110, 110, 101, 114, 83, 111, + 108, 117, 116, 105, 111, 110, 68, 69, + 80, 82, 69, 67, 65, 84, 69, 68, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 254, 172, 180, 166, 165, 236, 202, 132, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 116, 105, 111, 110, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 132, 69, 118, 90, 179, 188, 208, 148, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_c4713f6b0d36abe9 = b_c4713f6b0d36abe9.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_c4713f6b0d36abe9[] = { + &s_84caeca5a6b4acfe, + &s_94d0bcb35a764584, + &s_a444ed2b2187af28, + &s_aa3247d9d2a61cd4, + &s_c3cbae1fd505ae80, + &s_d1646ab3b45cfabd, + &s_d698881ad0ce7feb, + &s_fb3ec0702e67884f, +}; +static const uint16_t m_c4713f6b0d36abe9[] = {19, 26, 23, 1, 2, 0, 20, 17, 9, 13, 8, 25, 11, 18, 24, 12, 15, 22, 5, 7, 4, 16, 14, 10, 21, 3, 6}; +static const uint16_t i_c4713f6b0d36abe9[] = {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}; +const ::capnp::_::RawSchema s_c4713f6b0d36abe9 = { + 0xc4713f6b0d36abe9, b_c4713f6b0d36abe9.words, 510, d_c4713f6b0d36abe9, m_c4713f6b0d36abe9, + 8, 27, i_c4713f6b0d36abe9, nullptr, nullptr, { &s_c4713f6b0d36abe9, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<87> b_a444ed2b2187af28 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 40, 175, 135, 33, 43, 237, 68, 164, + 22, 0, 0, 0, 1, 0, 1, 0, + 233, 171, 54, 13, 107, 63, 113, 196, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 10, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 231, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 77, 111, 100, 101, 108, 68, + 97, 116, 97, 86, 50, 46, 76, 101, + 97, 100, 68, 97, 116, 97, 86, 50, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 0, 0, 0, 3, 0, 1, 0, + 104, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 0, 0, 0, 3, 0, 1, 0, + 108, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 0, 0, 0, 3, 0, 1, 0, + 128, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 0, 0, 0, 3, 0, 1, 0, + 148, 0, 0, 0, 2, 0, 1, 0, + 112, 114, 111, 98, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 121, 118, 97, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 121, 118, 97, 83, 116, 100, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_a444ed2b2187af28 = b_a444ed2b2187af28.words; +#if !CAPNP_LITE +static const uint16_t m_a444ed2b2187af28[] = {0, 1, 2, 3}; +static const uint16_t i_a444ed2b2187af28[] = {0, 1, 2, 3}; +const ::capnp::_::RawSchema s_a444ed2b2187af28 = { + 0xa444ed2b2187af28, b_a444ed2b2187af28.words, 87, nullptr, m_a444ed2b2187af28, + 0, 4, i_a444ed2b2187af28, nullptr, nullptr, { &s_a444ed2b2187af28, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<221> b_d698881ad0ce7feb = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 235, 127, 206, 208, 26, 136, 152, 214, + 22, 0, 0, 0, 1, 0, 1, 0, + 233, 171, 54, 13, 107, 63, 113, 196, + 9, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 10, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 111, 2, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 77, 111, 100, 101, 108, 68, + 97, 116, 97, 86, 50, 46, 76, 101, + 97, 100, 68, 97, 116, 97, 86, 51, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 44, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 1, 0, 0, 3, 0, 1, 0, + 44, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 1, 0, 0, 3, 0, 1, 0, + 52, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 1, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 1, 0, 0, 3, 0, 1, 0, + 72, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 1, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 1, 0, 0, 3, 0, 1, 0, + 92, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 89, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 84, 1, 0, 0, 3, 0, 1, 0, + 112, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 1, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 1, 0, 0, 3, 0, 1, 0, + 132, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 129, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 1, 0, 0, 3, 0, 1, 0, + 152, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 149, 1, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 144, 1, 0, 0, 3, 0, 1, 0, + 172, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 169, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 164, 1, 0, 0, 3, 0, 1, 0, + 192, 1, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 1, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 1, 0, 0, 3, 0, 1, 0, + 212, 1, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 1, 0, 0, 3, 0, 1, 0, + 232, 1, 0, 0, 2, 0, 1, 0, + 112, 114, 111, 98, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 114, 111, 98, 84, 105, 109, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 83, 116, 100, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 83, 116, 100, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 83, 116, 100, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 83, 116, 100, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_d698881ad0ce7feb = b_d698881ad0ce7feb.words; +#if !CAPNP_LITE +static const uint16_t m_d698881ad0ce7feb[] = {9, 10, 0, 1, 2, 7, 8, 3, 4, 5, 6}; +static const uint16_t i_d698881ad0ce7feb[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10}; +const ::capnp::_::RawSchema s_d698881ad0ce7feb = { + 0xd698881ad0ce7feb, b_d698881ad0ce7feb.words, 221, nullptr, m_d698881ad0ce7feb, + 0, 11, i_d698881ad0ce7feb, nullptr, nullptr, { &s_d698881ad0ce7feb, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<212> b_d1646ab3b45cfabd = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 189, 250, 92, 180, 179, 106, 100, 209, + 22, 0, 0, 0, 1, 0, 3, 0, + 233, 171, 54, 13, 107, 63, 113, 196, + 3, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 250, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 111, 2, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 77, 111, 100, 101, 108, 68, + 97, 116, 97, 86, 50, 46, 77, 101, + 116, 97, 68, 97, 116, 97, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 44, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 1, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 1, 0, 0, 3, 0, 1, 0, + 48, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 1, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 1, 0, 0, 3, 0, 1, 0, + 76, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 1, 0, 0, 234, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 80, 1, 0, 0, 3, 0, 1, 0, + 92, 1, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 89, 1, 0, 0, 218, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 1, 0, 0, 3, 0, 1, 0, + 108, 1, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 1, 0, 0, 226, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 1, 0, 0, 3, 0, 1, 0, + 124, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 1, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 1, 0, 0, 3, 0, 1, 0, + 148, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 145, 1, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 1, 0, 0, 3, 0, 1, 0, + 160, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 128, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 157, 1, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 160, 1, 0, 0, 3, 0, 1, 0, + 172, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 169, 1, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 1, 0, 0, 3, 0, 1, 0, + 180, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 1, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 1, 0, 0, 3, 0, 1, 0, + 192, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 11, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 1, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 1, 0, 0, 3, 0, 1, 0, + 200, 1, 0, 0, 2, 0, 1, 0, + 101, 110, 103, 97, 103, 101, 100, 80, + 114, 111, 98, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 115, 105, 114, 101, 80, 114, + 101, 100, 105, 99, 116, 105, 111, 110, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 114, 97, 107, 101, 68, 105, 115, + 101, 110, 103, 97, 103, 101, 80, 114, + 111, 98, 68, 69, 80, 82, 69, 67, + 65, 84, 69, 68, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 97, 115, 68, 105, 115, 101, 110, + 103, 97, 103, 101, 80, 114, 111, 98, + 68, 69, 80, 82, 69, 67, 65, 84, + 69, 68, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 79, 118, 101, + 114, 114, 105, 100, 101, 80, 114, 111, + 98, 68, 69, 80, 82, 69, 67, 65, + 84, 69, 68, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 115, 105, 114, 101, 83, 116, + 97, 116, 101, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 105, 115, 101, 110, 103, 97, 103, + 101, 80, 114, 101, 100, 105, 99, 116, + 105, 111, 110, 115, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 37, 141, 220, 188, 221, 165, 10, 134, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 97, 114, 100, 66, 114, 97, 107, + 101, 80, 114, 101, 100, 105, 99, 116, + 101, 100, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 110, 101, 67, 104, 97, 110, + 103, 101, 83, 116, 97, 116, 101, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 210, 211, 178, 247, 75, 146, 55, 205, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 110, 101, 67, 104, 97, 110, + 103, 101, 68, 105, 114, 101, 99, 116, + 105, 111, 110, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 118, 17, 103, 254, 193, 192, 11, 157, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 117, 114, 110, 68, 105, 114, 101, + 99, 116, 105, 111, 110, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 35, 155, 193, 213, 73, 234, 185, 238, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_d1646ab3b45cfabd = b_d1646ab3b45cfabd.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_d1646ab3b45cfabd[] = { + &s_860aa5ddbcdc8d25, + &s_9d0bc0c1fe671176, + &s_cd37924bf7b2d3d2, + &s_eeb9ea49d5c19b23, +}; +static const uint16_t m_d1646ab3b45cfabd[] = {2, 1, 5, 6, 0, 3, 7, 9, 8, 4, 10}; +static const uint16_t i_d1646ab3b45cfabd[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10}; +const ::capnp::_::RawSchema s_d1646ab3b45cfabd = { + 0xd1646ab3b45cfabd, b_d1646ab3b45cfabd.words, 212, d_d1646ab3b45cfabd, m_d1646ab3b45cfabd, + 4, 11, i_d1646ab3b45cfabd, nullptr, nullptr, { &s_d1646ab3b45cfabd, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<31> b_aa3247d9d2a61cd4 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 212, 28, 166, 210, 217, 71, 50, 170, + 22, 0, 0, 0, 2, 0, 0, 0, + 233, 171, 54, 13, 107, 63, 113, 196, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 50, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 79, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 77, 111, 100, 101, 108, 68, + 97, 116, 97, 86, 50, 46, 67, 111, + 110, 102, 105, 100, 101, 110, 99, 101, + 67, 108, 97, 115, 115, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 101, 100, 0, 0, 0, 0, 0, + 121, 101, 108, 108, 111, 119, 0, 0, + 103, 114, 101, 101, 110, 0, 0, 0, } +}; +::capnp::word const* const bp_aa3247d9d2a61cd4 = b_aa3247d9d2a61cd4.words; +#if !CAPNP_LITE +static const uint16_t m_aa3247d9d2a61cd4[] = {2, 0, 1}; +const ::capnp::_::RawSchema s_aa3247d9d2a61cd4 = { + 0xaa3247d9d2a61cd4, b_aa3247d9d2a61cd4.words, 31, nullptr, m_aa3247d9d2a61cd4, + 0, 3, nullptr, nullptr, nullptr, { &s_aa3247d9d2a61cd4, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(ConfidenceClass_aa3247d9d2a61cd4, aa3247d9d2a61cd4); +static const ::capnp::_::AlignedData<171> b_860aa5ddbcdc8d25 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 37, 141, 220, 188, 221, 165, 10, 134, + 22, 0, 0, 0, 1, 0, 0, 0, + 233, 171, 54, 13, 107, 63, 113, 196, + 7, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 90, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 143, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 77, 111, 100, 101, 108, 68, + 97, 116, 97, 86, 50, 46, 68, 105, + 115, 101, 110, 103, 97, 103, 101, 80, + 114, 101, 100, 105, 99, 116, 105, 111, + 110, 115, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 28, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 0, 0, 0, 3, 0, 1, 0, + 204, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 0, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 0, 0, 0, 3, 0, 1, 0, + 232, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 0, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 0, 0, 0, 3, 0, 1, 0, + 4, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 1, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 1, 0, 0, 3, 0, 1, 0, + 32, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 1, 0, 0, 18, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 1, 0, 0, 3, 0, 1, 0, + 68, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 65, 1, 0, 0, 18, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 1, 0, 0, 3, 0, 1, 0, + 104, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 1, 0, 0, 18, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 1, 0, 0, 3, 0, 1, 0, + 140, 1, 0, 0, 2, 0, 1, 0, + 116, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 114, 97, 107, 101, 68, 105, 115, + 101, 110, 103, 97, 103, 101, 80, 114, + 111, 98, 115, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 97, 115, 68, 105, 115, 101, 110, + 103, 97, 103, 101, 80, 114, 111, 98, + 115, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 79, 118, 101, + 114, 114, 105, 100, 101, 80, 114, 111, + 98, 115, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 114, 97, 107, 101, 51, 77, 101, + 116, 101, 114, 115, 80, 101, 114, 83, + 101, 99, 111, 110, 100, 83, 113, 117, + 97, 114, 101, 100, 80, 114, 111, 98, + 115, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 114, 97, 107, 101, 52, 77, 101, + 116, 101, 114, 115, 80, 101, 114, 83, + 101, 99, 111, 110, 100, 83, 113, 117, + 97, 114, 101, 100, 80, 114, 111, 98, + 115, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 114, 97, 107, 101, 53, 77, 101, + 116, 101, 114, 115, 80, 101, 114, 83, + 101, 99, 111, 110, 100, 83, 113, 117, + 97, 114, 101, 100, 80, 114, 111, 98, + 115, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_860aa5ddbcdc8d25 = b_860aa5ddbcdc8d25.words; +#if !CAPNP_LITE +static const uint16_t m_860aa5ddbcdc8d25[] = {4, 5, 6, 1, 2, 3, 0}; +static const uint16_t i_860aa5ddbcdc8d25[] = {0, 1, 2, 3, 4, 5, 6}; +const ::capnp::_::RawSchema s_860aa5ddbcdc8d25 = { + 0x860aa5ddbcdc8d25, b_860aa5ddbcdc8d25.words, 171, nullptr, m_860aa5ddbcdc8d25, + 0, 7, i_860aa5ddbcdc8d25, nullptr, nullptr, { &s_860aa5ddbcdc8d25, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<95> b_fb3ec0702e67884f = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 79, 136, 103, 46, 112, 192, 62, 251, + 22, 0, 0, 0, 1, 0, 0, 0, + 233, 171, 54, 13, 107, 63, 113, 196, + 4, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 218, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 231, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 77, 111, 100, 101, 108, 68, + 97, 116, 97, 86, 50, 46, 80, 111, + 115, 101, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 0, 0, 0, 3, 0, 1, 0, + 120, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 0, 0, 0, 3, 0, 1, 0, + 140, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 137, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 136, 0, 0, 0, 3, 0, 1, 0, + 164, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 161, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 156, 0, 0, 0, 3, 0, 1, 0, + 184, 0, 0, 0, 2, 0, 1, 0, + 116, 114, 97, 110, 115, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 111, 116, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 114, 97, 110, 115, 83, 116, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 111, 116, 83, 116, 100, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_fb3ec0702e67884f = b_fb3ec0702e67884f.words; +#if !CAPNP_LITE +static const uint16_t m_fb3ec0702e67884f[] = {1, 3, 0, 2}; +static const uint16_t i_fb3ec0702e67884f[] = {0, 1, 2, 3}; +const ::capnp::_::RawSchema s_fb3ec0702e67884f = { + 0xfb3ec0702e67884f, b_fb3ec0702e67884f.words, 95, nullptr, m_fb3ec0702e67884f, + 0, 4, i_fb3ec0702e67884f, nullptr, nullptr, { &s_fb3ec0702e67884f, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<173> b_84caeca5a6b4acfe = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 254, 172, 180, 166, 165, 236, 202, 132, + 22, 0, 0, 0, 1, 0, 0, 0, + 233, 171, 54, 13, 107, 63, 113, 196, + 8, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 106, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 199, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 77, 111, 100, 101, 108, 68, + 97, 116, 97, 86, 50, 46, 76, 97, + 116, 101, 114, 97, 108, 80, 108, 97, + 110, 110, 101, 114, 83, 111, 108, 117, + 116, 105, 111, 110, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 32, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 0, 0, 0, 3, 0, 1, 0, + 232, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 224, 0, 0, 0, 3, 0, 1, 0, + 252, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 249, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 244, 0, 0, 0, 3, 0, 1, 0, + 16, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 1, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 1, 0, 0, 3, 0, 1, 0, + 36, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 28, 1, 0, 0, 3, 0, 1, 0, + 56, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 53, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 1, 0, 0, 3, 0, 1, 0, + 76, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 1, 0, 0, 3, 0, 1, 0, + 96, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 1, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 1, 0, 0, 3, 0, 1, 0, + 120, 1, 0, 0, 2, 0, 1, 0, + 120, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 97, 119, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 97, 119, 82, 97, 116, 101, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 83, 116, 100, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 83, 116, 100, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 97, 119, 83, 116, 100, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 97, 119, 82, 97, 116, 101, 83, + 116, 100, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_84caeca5a6b4acfe = b_84caeca5a6b4acfe.words; +#if !CAPNP_LITE +static const uint16_t m_84caeca5a6b4acfe[] = {0, 4, 1, 5, 2, 3, 7, 6}; +static const uint16_t i_84caeca5a6b4acfe[] = {0, 1, 2, 3, 4, 5, 6, 7}; +const ::capnp::_::RawSchema s_84caeca5a6b4acfe = { + 0x84caeca5a6b4acfe, b_84caeca5a6b4acfe.words, 173, nullptr, m_84caeca5a6b4acfe, + 0, 8, i_84caeca5a6b4acfe, nullptr, nullptr, { &s_84caeca5a6b4acfe, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<35> b_94d0bcb35a764584 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 132, 69, 118, 90, 179, 188, 208, 148, + 22, 0, 0, 0, 1, 0, 1, 0, + 233, 171, 54, 13, 107, 63, 113, 196, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 234, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 63, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 77, 111, 100, 101, 108, 68, + 97, 116, 97, 86, 50, 46, 65, 99, + 116, 105, 111, 110, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 4, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 3, 0, 1, 0, + 28, 0, 0, 0, 2, 0, 1, 0, + 100, 101, 115, 105, 114, 101, 100, 67, + 117, 114, 118, 97, 116, 117, 114, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_94d0bcb35a764584 = b_94d0bcb35a764584.words; +#if !CAPNP_LITE +static const uint16_t m_94d0bcb35a764584[] = {0}; +static const uint16_t i_94d0bcb35a764584[] = {0}; +const ::capnp::_::RawSchema s_94d0bcb35a764584 = { + 0x94d0bcb35a764584, b_94d0bcb35a764584.words, 35, nullptr, m_94d0bcb35a764584, + 0, 1, i_94d0bcb35a764584, nullptr, nullptr, { &s_94d0bcb35a764584, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<176> b_89d394e3541735fc = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 252, 53, 23, 84, 227, 148, 211, 137, + 10, 0, 0, 0, 1, 0, 6, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 178, 0, 0, 0, + 29, 0, 0, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 55, 2, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 69, 110, 99, 111, 100, 101, + 73, 110, 100, 101, 120, 0, 0, 0, + 4, 0, 0, 0, 1, 0, 1, 0, + 211, 204, 87, 193, 158, 37, 173, 192, + 1, 0, 0, 0, 42, 0, 0, 0, + 84, 121, 112, 101, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 1, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 1, 0, 0, 3, 0, 1, 0, + 16, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 1, 0, 0, 3, 0, 1, 0, + 20, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 1, 0, 0, 3, 0, 1, 0, + 28, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 1, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 24, 1, 0, 0, 3, 0, 1, 0, + 36, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 1, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 1, 0, 0, 3, 0, 1, 0, + 44, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 1, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 1, 0, 0, 3, 0, 1, 0, + 52, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 1, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 1, 0, 0, 3, 0, 1, 0, + 60, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 57, 1, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 56, 1, 0, 0, 3, 0, 1, 0, + 68, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 65, 1, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 60, 1, 0, 0, 3, 0, 1, 0, + 72, 1, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 11, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 1, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 1, 0, 0, 3, 0, 1, 0, + 76, 1, 0, 0, 2, 0, 1, 0, + 102, 114, 97, 109, 101, 73, 100, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 121, 112, 101, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 211, 204, 87, 193, 158, 37, 173, 192, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 110, 99, 111, 100, 101, 73, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 101, 103, 109, 101, 110, 116, 78, + 117, 109, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 101, 103, 109, 101, 110, 116, 73, + 100, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 101, 103, 109, 101, 110, 116, 73, + 100, 69, 110, 99, 111, 100, 101, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 109, 101, 115, 116, 97, 109, + 112, 83, 111, 102, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 109, 101, 115, 116, 97, 109, + 112, 69, 111, 102, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 108, 97, 103, 115, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 110, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_89d394e3541735fc = b_89d394e3541735fc.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_89d394e3541735fc[] = { + &s_c0ad259ec157ccd3, +}; +static const uint16_t m_89d394e3541735fc[] = {2, 8, 0, 9, 4, 5, 3, 7, 6, 1}; +static const uint16_t i_89d394e3541735fc[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9}; +const ::capnp::_::RawSchema s_89d394e3541735fc = { + 0x89d394e3541735fc, b_89d394e3541735fc.words, 176, d_89d394e3541735fc, m_89d394e3541735fc, + 1, 10, i_89d394e3541735fc, nullptr, nullptr, { &s_89d394e3541735fc, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<63> b_c0ad259ec157ccd3 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 211, 204, 87, 193, 158, 37, 173, 192, + 22, 0, 0, 0, 2, 0, 0, 0, + 252, 53, 23, 84, 227, 148, 211, 137, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 218, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 199, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 69, 110, 99, 111, 100, 101, + 73, 110, 100, 101, 120, 46, 84, 121, + 112, 101, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 32, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 89, 0, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 85, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 81, 0, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 81, 0, 0, 0, 218, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 85, 0, 0, 0, 218, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 89, 0, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 85, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 81, 0, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 105, 103, 66, 111, 120, 76, 111, + 115, 115, 108, 101, 115, 115, 0, 0, + 102, 117, 108, 108, 72, 69, 86, 67, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 105, 103, 66, 111, 120, 72, 69, + 86, 67, 68, 69, 80, 82, 69, 67, + 65, 84, 69, 68, 0, 0, 0, 0, + 99, 104, 102, 102, 114, 65, 110, 100, + 114, 111, 105, 100, 72, 50, 54, 52, + 68, 69, 80, 82, 69, 67, 65, 84, + 69, 68, 0, 0, 0, 0, 0, 0, + 102, 117, 108, 108, 76, 111, 115, 115, + 108, 101, 115, 115, 67, 108, 105, 112, + 68, 69, 80, 82, 69, 67, 65, 84, + 69, 68, 0, 0, 0, 0, 0, 0, + 102, 114, 111, 110, 116, 68, 69, 80, + 82, 69, 67, 65, 84, 69, 68, 0, + 113, 99, 97, 109, 101, 114, 97, 72, + 50, 54, 52, 0, 0, 0, 0, 0, + 108, 105, 118, 101, 115, 116, 114, 101, + 97, 109, 72, 50, 54, 52, 0, 0, } +}; +::capnp::word const* const bp_c0ad259ec157ccd3 = b_c0ad259ec157ccd3.words; +#if !CAPNP_LITE +static const uint16_t m_c0ad259ec157ccd3[] = {2, 0, 3, 5, 1, 4, 7, 6}; +const ::capnp::_::RawSchema s_c0ad259ec157ccd3 = { + 0xc0ad259ec157ccd3, b_c0ad259ec157ccd3.words, 63, nullptr, m_c0ad259ec157ccd3, + 0, 8, nullptr, nullptr, nullptr, { &s_c0ad259ec157ccd3, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(Type_c0ad259ec157ccd3, c0ad259ec157ccd3); +static const ::capnp::_::AlignedData<124> b_ea095da1894f7d85 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 133, 125, 79, 137, 161, 93, 9, 234, + 10, 0, 0, 0, 1, 0, 3, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 210, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 143, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 65, 110, 100, 114, 111, 105, + 100, 76, 111, 103, 69, 110, 116, 114, + 121, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 28, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 0, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 0, 0, 0, 3, 0, 1, 0, + 188, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 0, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 0, 0, 0, 3, 0, 1, 0, + 192, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 0, 0, 0, 3, 0, 1, 0, + 200, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 192, 0, 0, 0, 3, 0, 1, 0, + 204, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 0, 0, 0, 3, 0, 1, 0, + 208, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 200, 0, 0, 0, 3, 0, 1, 0, + 212, 0, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 0, 0, 0, 3, 0, 1, 0, + 216, 0, 0, 0, 2, 0, 1, 0, + 105, 100, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 115, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 114, 105, 111, 114, 105, 116, 121, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 105, 100, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 100, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 97, 103, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 101, 115, 115, 97, 103, 101, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_ea095da1894f7d85 = b_ea095da1894f7d85.words; +#if !CAPNP_LITE +static const uint16_t m_ea095da1894f7d85[] = {0, 6, 3, 2, 5, 4, 1}; +static const uint16_t i_ea095da1894f7d85[] = {0, 1, 2, 3, 4, 5, 6}; +const ::capnp::_::RawSchema s_ea095da1894f7d85 = { + 0xea095da1894f7d85, b_ea095da1894f7d85.words, 124, nullptr, m_ea095da1894f7d85, + 0, 7, i_ea095da1894f7d85, nullptr, nullptr, { &s_ea095da1894f7d85, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<664> b_e00b5b3eba12876c = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 108, 135, 18, 186, 62, 91, 11, 224, + 10, 0, 0, 0, 1, 0, 11, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 6, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 218, 0, 0, 0, + 33, 0, 0, 0, 39, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 65, 0, 0, 0, 31, 8, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 76, 111, 110, 103, 105, 116, + 117, 100, 105, 110, 97, 108, 80, 108, + 97, 110, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 1, 0, 1, 0, + 32, 145, 7, 204, 83, 167, 49, 178, + 9, 0, 0, 0, 186, 0, 0, 0, + 0, 16, 48, 245, 114, 176, 254, 140, + 13, 0, 0, 0, 114, 0, 0, 0, + 76, 111, 110, 103, 105, 116, 117, 100, + 105, 110, 97, 108, 80, 108, 97, 110, + 83, 111, 117, 114, 99, 101, 0, 0, + 71, 112, 115, 84, 114, 97, 106, 101, + 99, 116, 111, 114, 121, 0, 0, 0, + 148, 0, 0, 0, 3, 0, 4, 0, + 24, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 253, 3, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 4, 0, 0, 3, 0, 1, 0, + 12, 4, 0, 0, 2, 0, 1, 0, + 26, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 4, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 4, 0, 0, 3, 0, 1, 0, + 36, 4, 0, 0, 2, 0, 1, 0, + 25, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 4, 0, 0, 226, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 4, 0, 0, 3, 0, 1, 0, + 52, 4, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 4, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 52, 4, 0, 0, 3, 0, 1, 0, + 64, 4, 0, 0, 2, 0, 1, 0, + 22, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 4, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 4, 0, 0, 3, 0, 1, 0, + 76, 4, 0, 0, 2, 0, 1, 0, + 23, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 4, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 4, 0, 0, 3, 0, 1, 0, + 88, 4, 0, 0, 2, 0, 1, 0, + 19, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 85, 4, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 88, 4, 0, 0, 3, 0, 1, 0, + 100, 4, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 4, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 4, 0, 0, 3, 0, 1, 0, + 104, 4, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 4, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 4, 0, 0, 3, 0, 1, 0, + 108, 4, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 4, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 4, 0, 0, 3, 0, 1, 0, + 116, 4, 0, 0, 2, 0, 1, 0, + 18, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 4, 0, 0, 234, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 4, 0, 0, 3, 0, 1, 0, + 132, 4, 0, 0, 2, 0, 1, 0, + 27, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 129, 4, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 132, 4, 0, 0, 3, 0, 1, 0, + 144, 4, 0, 0, 2, 0, 1, 0, + 35, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 4, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 144, 4, 0, 0, 3, 0, 1, 0, + 156, 4, 0, 0, 2, 0, 1, 0, + 34, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 4, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 156, 4, 0, 0, 3, 0, 1, 0, + 184, 4, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 4, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 4, 0, 0, 3, 0, 1, 0, + 196, 4, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 15, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 4, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 4, 0, 0, 3, 0, 1, 0, + 208, 4, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 11, 0, 0, 0, + 0, 0, 1, 0, 16, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 4, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 4, 0, 0, 3, 0, 1, 0, + 220, 4, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 12, 0, 0, 0, + 0, 0, 1, 0, 17, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 217, 4, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 220, 4, 0, 0, 3, 0, 1, 0, + 232, 4, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 13, 0, 0, 0, + 0, 0, 1, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 4, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 4, 0, 0, 3, 0, 1, 0, + 244, 4, 0, 0, 2, 0, 1, 0, + 36, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 19, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 4, 0, 0, 218, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 248, 4, 0, 0, 3, 0, 1, 0, + 4, 5, 0, 0, 2, 0, 1, 0, + 17, 0, 0, 0, 14, 0, 0, 0, + 0, 0, 1, 0, 20, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 5, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 5, 0, 0, 3, 0, 1, 0, + 12, 5, 0, 0, 2, 0, 1, 0, + 28, 0, 0, 0, 15, 0, 0, 0, + 0, 0, 1, 0, 21, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 5, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 5, 0, 0, 3, 0, 1, 0, + 24, 5, 0, 0, 2, 0, 1, 0, + 29, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 22, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 5, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 24, 5, 0, 0, 3, 0, 1, 0, + 36, 5, 0, 0, 2, 0, 1, 0, + 20, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 5, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 5, 0, 0, 3, 0, 1, 0, + 48, 5, 0, 0, 2, 0, 1, 0, + 21, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 24, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 5, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 5, 0, 0, 3, 0, 1, 0, + 60, 5, 0, 0, 2, 0, 1, 0, + 30, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 25, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 57, 5, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 60, 5, 0, 0, 3, 0, 1, 0, + 72, 5, 0, 0, 2, 0, 1, 0, + 15, 0, 0, 0, 16, 0, 0, 0, + 0, 0, 1, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 5, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 5, 0, 0, 3, 0, 1, 0, + 84, 5, 0, 0, 2, 0, 1, 0, + 16, 0, 0, 0, 17, 0, 0, 0, + 0, 0, 1, 0, 27, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 81, 5, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 84, 5, 0, 0, 3, 0, 1, 0, + 96, 5, 0, 0, 2, 0, 1, 0, + 31, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 28, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 5, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 5, 0, 0, 3, 0, 1, 0, + 108, 5, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 1, 0, 29, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 5, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 5, 0, 0, 3, 0, 1, 0, + 116, 5, 0, 0, 2, 0, 1, 0, + 32, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 30, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 5, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 5, 0, 0, 3, 0, 1, 0, + 128, 5, 0, 0, 2, 0, 1, 0, + 33, 0, 0, 0, 11, 0, 0, 0, + 0, 0, 1, 0, 31, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 5, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 128, 5, 0, 0, 3, 0, 1, 0, + 140, 5, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 32, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 137, 5, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 132, 5, 0, 0, 3, 0, 1, 0, + 160, 5, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 33, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 157, 5, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 152, 5, 0, 0, 3, 0, 1, 0, + 180, 5, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 5, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 172, 5, 0, 0, 3, 0, 1, 0, + 200, 5, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 19, 0, 0, 0, + 0, 0, 1, 0, 35, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 5, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 200, 5, 0, 0, 3, 0, 1, 0, + 212, 5, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 40, 0, 0, 0, + 0, 0, 1, 0, 36, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 5, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 5, 0, 0, 3, 0, 1, 0, + 220, 5, 0, 0, 2, 0, 1, 0, + 108, 97, 116, 101, 114, 97, 108, 86, + 97, 108, 105, 100, 68, 69, 80, 82, + 69, 67, 65, 84, 69, 68, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 80, 111, 108, 121, 68, 69, 80, + 82, 69, 67, 65, 84, 69, 68, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 110, 103, 105, 116, 117, 100, + 105, 110, 97, 108, 86, 97, 108, 105, + 100, 68, 69, 80, 82, 69, 67, 65, + 84, 69, 68, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 84, 97, 114, 103, 101, 116, 68, + 69, 80, 82, 69, 67, 65, 84, 69, + 68, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 84, 97, 114, 103, 101, 116, 77, + 105, 110, 68, 69, 80, 82, 69, 67, + 65, 84, 69, 68, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 84, 97, 114, 103, 101, 116, 77, + 97, 120, 68, 69, 80, 82, 69, 67, + 65, 84, 69, 68, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 106, 101, 114, 107, 70, 97, 99, 116, + 111, 114, 68, 69, 80, 82, 69, 67, + 65, 84, 69, 68, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 97, 115, 76, 101, 97, 100, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 99, 119, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 111, 100, 101, 108, 77, 111, 110, + 111, 84, 105, 109, 101, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 97, 100, 97, 114, 83, 116, 97, + 116, 101, 77, 111, 110, 111, 84, 105, + 109, 101, 68, 69, 80, 82, 69, 67, + 65, 84, 69, 68, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 110, 101, 87, 105, 100, 116, + 104, 68, 69, 80, 82, 69, 67, 65, + 84, 69, 68, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 84, 114, 97, 106, 101, + 99, 116, 111, 114, 121, 68, 69, 80, + 82, 69, 67, 65, 84, 69, 68, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 16, 48, 245, 114, 176, 254, 140, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 118, 101, 110, 116, 115, 68, 69, + 80, 82, 69, 67, 65, 84, 69, 68, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 211, 58, 175, 76, 243, 87, 22, 155, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 84, 97, 114, 103, 101, 116, 70, + 117, 116, 117, 114, 101, 68, 69, 80, + 82, 69, 67, 65, 84, 69, 68, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 110, 103, 105, 116, 117, 100, + 105, 110, 97, 108, 80, 108, 97, 110, + 83, 111, 117, 114, 99, 101, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 32, 145, 7, 204, 83, 167, 49, 178, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 67, 114, 117, 105, 115, 101, 68, + 69, 80, 82, 69, 67, 65, 84, 69, + 68, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 67, 114, 117, 105, 115, 101, 68, + 69, 80, 82, 69, 67, 65, 84, 69, + 68, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 84, 97, 114, 103, 101, 116, 68, + 69, 80, 82, 69, 67, 65, 84, 69, + 68, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 80, 108, 97, 110, 110, + 101, 114, 65, 99, 116, 105, 118, 101, + 68, 69, 80, 82, 69, 67, 65, 84, + 69, 68, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 77, 97, 120, 68, 69, 80, 82, + 69, 67, 65, 84, 69, 68, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 67, 117, 114, 118, 97, 116, 117, + 114, 101, 68, 69, 80, 82, 69, 67, + 65, 84, 69, 68, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 99, 101, 108, 70, 111, 114, + 84, 117, 114, 110, 68, 69, 80, 82, + 69, 67, 65, 84, 69, 68, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 97, 115, 76, 101, 102, 116, 76, + 97, 110, 101, 68, 69, 80, 82, 69, + 67, 65, 84, 69, 68, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 97, 115, 82, 105, 103, 104, 116, + 76, 97, 110, 101, 68, 69, 80, 82, + 69, 67, 65, 84, 69, 68, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 97, 112, 86, 97, 108, 105, 100, + 68, 69, 80, 82, 69, 67, 65, 84, + 69, 68, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 83, 116, 97, 114, 116, 68, 69, + 80, 82, 69, 67, 65, 84, 69, 68, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 83, 116, 97, 114, 116, 68, 69, + 80, 82, 69, 67, 65, 84, 69, 68, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 97, 100, 97, 114, 86, 97, 108, + 105, 100, 68, 69, 80, 82, 69, 67, + 65, 84, 69, 68, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 114, 111, 99, 101, 115, 115, 105, + 110, 103, 68, 101, 108, 97, 121, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 97, 100, 97, 114, 67, 97, 110, + 69, 114, 114, 111, 114, 68, 69, 80, + 82, 69, 67, 65, 84, 69, 68, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 111, 109, 109, 73, 115, 115, 117, + 101, 68, 69, 80, 82, 69, 67, 65, + 84, 69, 68, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 99, 101, 108, 115, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 112, 101, 101, 100, 115, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 106, 101, 114, 107, 115, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 111, 108, 118, 101, 114, 69, 120, + 101, 99, 117, 116, 105, 111, 110, 84, + 105, 109, 101, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 101, 114, 115, 111, 110, 97, 108, + 105, 116, 121, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 153, 125, 36, 26, 61, 226, 146, 214, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e00b5b3eba12876c = b_e00b5b3eba12876c.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_e00b5b3eba12876c[] = { + &s_8cfeb072f5301000, + &s_9b1657f34caf3ad3, + &s_b231a753cc079120, + &s_d692e23d1a247d99, +}; +static const uint16_t m_e00b5b3eba12876c[] = {17, 27, 18, 5, 4, 32, 31, 1, 22, 13, 8, 19, 12, 7, 23, 24, 6, 34, 11, 0, 15, 2, 25, 9, 36, 29, 30, 10, 28, 35, 33, 16, 21, 20, 26, 3, 14}; +static const uint16_t i_e00b5b3eba12876c[] = {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}; +const ::capnp::_::RawSchema s_e00b5b3eba12876c = { + 0xe00b5b3eba12876c, b_e00b5b3eba12876c.words, 664, d_e00b5b3eba12876c, m_e00b5b3eba12876c, + 4, 37, i_e00b5b3eba12876c, nullptr, nullptr, { &s_e00b5b3eba12876c, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<41> b_b231a753cc079120 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 32, 145, 7, 204, 83, 167, 49, 178, + 27, 0, 0, 0, 2, 0, 0, 0, + 108, 135, 18, 186, 62, 91, 11, 224, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 146, 1, 0, 0, + 45, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 127, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 76, 111, 110, 103, 105, 116, + 117, 100, 105, 110, 97, 108, 80, 108, + 97, 110, 46, 76, 111, 110, 103, 105, + 116, 117, 100, 105, 110, 97, 108, 80, + 108, 97, 110, 83, 111, 117, 114, 99, + 101, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 20, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 53, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 114, 117, 105, 115, 101, 0, 0, + 108, 101, 97, 100, 48, 0, 0, 0, + 108, 101, 97, 100, 49, 0, 0, 0, + 108, 101, 97, 100, 50, 0, 0, 0, + 101, 50, 101, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_b231a753cc079120 = b_b231a753cc079120.words; +#if !CAPNP_LITE +static const uint16_t m_b231a753cc079120[] = {0, 4, 1, 2, 3}; +const ::capnp::_::RawSchema s_b231a753cc079120 = { + 0xb231a753cc079120, b_b231a753cc079120.words, 41, nullptr, m_b231a753cc079120, + 0, 5, nullptr, nullptr, nullptr, { &s_b231a753cc079120, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(LongitudinalPlanSource_b231a753cc079120, b231a753cc079120); +static const ::capnp::_::AlignedData<58> b_8cfeb072f5301000 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 0, 16, 48, 245, 114, 176, 254, 140, + 27, 0, 0, 0, 1, 0, 0, 0, + 108, 135, 18, 186, 62, 91, 11, 224, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 74, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 76, 111, 110, 103, 105, 116, + 117, 100, 105, 110, 97, 108, 80, 108, + 97, 110, 46, 71, 112, 115, 84, 114, + 97, 106, 101, 99, 116, 111, 114, 121, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 64, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 56, 0, 0, 0, 3, 0, 1, 0, + 84, 0, 0, 0, 2, 0, 1, 0, + 120, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_8cfeb072f5301000 = b_8cfeb072f5301000.words; +#if !CAPNP_LITE +static const uint16_t m_8cfeb072f5301000[] = {0, 1}; +static const uint16_t i_8cfeb072f5301000[] = {0, 1}; +const ::capnp::_::RawSchema s_8cfeb072f5301000 = { + 0x8cfeb072f5301000, b_8cfeb072f5301000.words, 58, nullptr, m_8cfeb072f5301000, + 0, 2, i_8cfeb072f5301000, nullptr, nullptr, { &s_8cfeb072f5301000, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<67> b_fc0c9bb05e3927c1 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 193, 39, 57, 94, 176, 155, 12, 252, + 10, 0, 0, 0, 1, 0, 1, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 138, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 85, 105, 80, 108, 97, 110, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 0, 0, 0, 3, 0, 1, 0, + 80, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 0, 0, 0, 3, 0, 1, 0, + 100, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 0, 0, 0, 3, 0, 1, 0, + 104, 0, 0, 0, 2, 0, 1, 0, + 112, 111, 115, 105, 116, 105, 111, 110, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 128, 174, 5, 213, 31, 174, 203, 195, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 99, 101, 108, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 114, 97, 109, 101, 73, 100, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_fc0c9bb05e3927c1 = b_fc0c9bb05e3927c1.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_fc0c9bb05e3927c1[] = { + &s_c3cbae1fd505ae80, +}; +static const uint16_t m_fc0c9bb05e3927c1[] = {1, 2, 0}; +static const uint16_t i_fc0c9bb05e3927c1[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_fc0c9bb05e3927c1 = { + 0xfc0c9bb05e3927c1, b_fc0c9bb05e3927c1.words, 67, d_fc0c9bb05e3927c1, m_fc0c9bb05e3927c1, + 1, 3, i_fc0c9bb05e3927c1, nullptr, nullptr, { &s_fc0c9bb05e3927c1, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<627> b_e1e9318e2ae8b51e = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 30, 181, 232, 42, 142, 49, 233, 225, + 10, 0, 0, 0, 1, 0, 9, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 9, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 178, 0, 0, 0, + 29, 0, 0, 0, 71, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 89, 0, 0, 0, 119, 7, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 76, 97, 116, 101, 114, 97, + 108, 80, 108, 97, 110, 0, 0, 0, + 16, 0, 0, 0, 1, 0, 1, 0, + 198, 33, 112, 91, 103, 124, 202, 253, + 25, 0, 0, 0, 98, 0, 0, 0, + 13, 127, 42, 207, 63, 239, 83, 187, + 25, 0, 0, 0, 58, 0, 0, 0, + 210, 86, 206, 149, 241, 151, 194, 250, + 21, 0, 0, 0, 130, 0, 0, 0, + 3, 211, 186, 188, 17, 99, 57, 247, + 21, 0, 0, 0, 162, 0, 0, 0, + 83, 111, 108, 118, 101, 114, 83, 116, + 97, 116, 101, 0, 0, 0, 0, 0, + 68, 101, 115, 105, 114, 101, 0, 0, + 76, 97, 110, 101, 67, 104, 97, 110, + 103, 101, 83, 116, 97, 116, 101, 0, + 76, 97, 110, 101, 67, 104, 97, 110, + 103, 101, 68, 105, 114, 101, 99, 116, + 105, 111, 110, 0, 0, 0, 0, 0, + 136, 0, 0, 0, 3, 0, 4, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 169, 3, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 172, 3, 0, 0, 3, 0, 1, 0, + 184, 3, 0, 0, 2, 0, 1, 0, + 22, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 3, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 3, 0, 0, 3, 0, 1, 0, + 208, 3, 0, 0, 2, 0, 1, 0, + 23, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 3, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 3, 0, 0, 3, 0, 1, 0, + 232, 3, 0, 0, 2, 0, 1, 0, + 21, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 3, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 228, 3, 0, 0, 3, 0, 1, 0, + 240, 3, 0, 0, 2, 0, 1, 0, + 24, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 3, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 236, 3, 0, 0, 3, 0, 1, 0, + 8, 4, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 4, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 4, 0, 0, 3, 0, 1, 0, + 16, 4, 0, 0, 2, 0, 1, 0, + 25, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 4, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 4, 0, 0, 3, 0, 1, 0, + 40, 4, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 4, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 4, 0, 0, 3, 0, 1, 0, + 48, 4, 0, 0, 2, 0, 1, 0, + 31, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 4, 0, 0, 218, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 52, 4, 0, 0, 3, 0, 1, 0, + 64, 4, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 160, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 4, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 4, 0, 0, 3, 0, 1, 0, + 76, 4, 0, 0, 2, 0, 1, 0, + 30, 0, 0, 0, 161, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 4, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 4, 0, 0, 3, 0, 1, 0, + 88, 4, 0, 0, 2, 0, 1, 0, + 33, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 85, 4, 0, 0, 202, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 4, 0, 0, 3, 0, 1, 0, + 104, 4, 0, 0, 2, 0, 1, 0, + 26, 0, 0, 0, 162, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 4, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 4, 0, 0, 3, 0, 1, 0, + 116, 4, 0, 0, 2, 0, 1, 0, + 32, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 4, 0, 0, 210, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 4, 0, 0, 3, 0, 1, 0, + 132, 4, 0, 0, 2, 0, 1, 0, + 29, 0, 0, 0, 163, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 129, 4, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 132, 4, 0, 0, 3, 0, 1, 0, + 144, 4, 0, 0, 2, 0, 1, 0, + 27, 0, 0, 0, 164, 0, 0, 0, + 0, 0, 1, 0, 15, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 4, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 144, 4, 0, 0, 3, 0, 1, 0, + 156, 4, 0, 0, 2, 0, 1, 0, + 28, 0, 0, 0, 165, 0, 0, 0, + 0, 0, 1, 0, 16, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 4, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 156, 4, 0, 0, 3, 0, 1, 0, + 168, 4, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 11, 0, 0, 0, + 0, 0, 1, 0, 17, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 165, 4, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 160, 4, 0, 0, 3, 0, 1, 0, + 172, 4, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 16, 0, 0, 0, + 0, 0, 1, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 169, 4, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 4, 0, 0, 3, 0, 1, 0, + 180, 4, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 17, 0, 0, 0, + 0, 0, 1, 0, 19, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 4, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 4, 0, 0, 3, 0, 1, 0, + 192, 4, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 20, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 4, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 4, 0, 0, 3, 0, 1, 0, + 216, 4, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 21, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 4, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 212, 4, 0, 0, 3, 0, 1, 0, + 224, 4, 0, 0, 2, 0, 1, 0, + 17, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 22, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 4, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 224, 4, 0, 0, 3, 0, 1, 0, + 236, 4, 0, 0, 2, 0, 1, 0, + 18, 0, 0, 0, 11, 0, 0, 0, + 0, 0, 1, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 233, 4, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 236, 4, 0, 0, 3, 0, 1, 0, + 248, 4, 0, 0, 2, 0, 1, 0, + 19, 0, 0, 0, 12, 0, 0, 0, + 0, 0, 1, 0, 24, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 245, 4, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 248, 4, 0, 0, 3, 0, 1, 0, + 4, 5, 0, 0, 2, 0, 1, 0, + 20, 0, 0, 0, 13, 0, 0, 0, + 0, 0, 1, 0, 25, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 5, 0, 0, 218, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 5, 0, 0, 3, 0, 1, 0, + 20, 5, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 5, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 5, 0, 0, 3, 0, 1, 0, + 40, 5, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 27, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 5, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 5, 0, 0, 3, 0, 1, 0, + 64, 5, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 28, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 5, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 60, 5, 0, 0, 3, 0, 1, 0, + 88, 5, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 166, 0, 0, 0, + 0, 0, 1, 0, 29, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 85, 5, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 84, 5, 0, 0, 3, 0, 1, 0, + 96, 5, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 14, 0, 0, 0, + 0, 0, 1, 0, 30, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 5, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 5, 0, 0, 3, 0, 1, 0, + 108, 5, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 31, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 5, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 5, 0, 0, 3, 0, 1, 0, + 116, 5, 0, 0, 2, 0, 1, 0, + 15, 0, 0, 0, 15, 0, 0, 0, + 0, 0, 1, 0, 32, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 5, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 5, 0, 0, 3, 0, 1, 0, + 124, 5, 0, 0, 2, 0, 1, 0, + 16, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 33, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 5, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 5, 0, 0, 3, 0, 1, 0, + 132, 5, 0, 0, 2, 0, 1, 0, + 108, 97, 110, 101, 87, 105, 100, 116, + 104, 68, 69, 80, 82, 69, 67, 65, + 84, 69, 68, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 80, 111, 108, 121, 68, 69, 80, + 82, 69, 67, 65, 84, 69, 68, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 80, 111, 108, 121, 68, 69, 80, + 82, 69, 67, 65, 84, 69, 68, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 80, 114, 111, 98, 68, 69, 80, + 82, 69, 67, 65, 84, 69, 68, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 80, 111, 108, 121, 68, 69, 80, + 82, 69, 67, 65, 84, 69, 68, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 80, 114, 111, 98, 68, 69, 80, + 82, 69, 67, 65, 84, 69, 68, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 80, 111, 108, 121, 68, 69, 80, + 82, 69, 67, 65, 84, 69, 68, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 80, 114, 111, 98, 68, 69, 80, + 82, 69, 67, 65, 84, 69, 68, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 105, 110, 103, + 65, 110, 103, 108, 101, 68, 101, 103, + 68, 69, 80, 82, 69, 67, 65, 84, + 69, 68, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 112, 99, 83, 111, 108, 117, 116, + 105, 111, 110, 86, 97, 108, 105, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 97, 114, 97, 109, 115, 86, 97, + 108, 105, 100, 68, 69, 80, 82, 69, + 67, 65, 84, 69, 68, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 110, 103, 108, 101, 79, 102, 102, + 115, 101, 116, 68, 101, 103, 68, 69, + 80, 82, 69, 67, 65, 84, 69, 68, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 111, 100, 101, 108, 86, 97, 108, + 105, 100, 68, 69, 80, 82, 69, 67, + 65, 84, 69, 68, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 105, 110, 103, + 82, 97, 116, 101, 68, 101, 103, 68, + 69, 80, 82, 69, 67, 65, 84, 69, + 68, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 101, 110, 115, 111, 114, 86, 97, + 108, 105, 100, 68, 69, 80, 82, 69, + 67, 65, 84, 69, 68, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 111, 109, 109, 73, 115, 115, 117, + 101, 68, 69, 80, 82, 69, 67, 65, + 84, 69, 68, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 115, 101, 110, 101, 116, 86, + 97, 108, 105, 100, 68, 69, 80, 82, + 69, 67, 65, 84, 69, 68, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 115, 105, 114, 101, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 13, 127, 42, 207, 63, 239, 83, 187, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 110, 101, 67, 104, 97, 110, + 103, 101, 83, 116, 97, 116, 101, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 210, 86, 206, 149, 241, 151, 194, 250, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 110, 101, 67, 104, 97, 110, + 103, 101, 68, 105, 114, 101, 99, 116, + 105, 111, 110, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 3, 211, 186, 188, 17, 99, 57, 247, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 80, 97, 116, 104, 80, 111, 105, + 110, 116, 115, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 80, 114, 111, 98, 68, 69, 80, + 82, 69, 67, 65, 84, 69, 68, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 114, 118, 97, 116, 117, 114, + 101, 68, 69, 80, 82, 69, 67, 65, + 84, 69, 68, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 114, 118, 97, 116, 117, 114, + 101, 82, 97, 116, 101, 68, 69, 80, + 82, 69, 67, 65, 84, 69, 68, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 97, 119, 67, 117, 114, 118, 97, + 116, 117, 114, 101, 68, 69, 80, 82, + 69, 67, 65, 84, 69, 68, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 97, 119, 67, 117, 114, 118, 97, + 116, 117, 114, 101, 82, 97, 116, 101, + 68, 69, 80, 82, 69, 67, 65, 84, + 69, 68, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 115, 105, 115, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 114, 118, 97, 116, 117, 114, + 101, 115, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 114, 118, 97, 116, 117, 114, + 101, 82, 97, 116, 101, 115, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 115, 101, 76, 97, 110, 101, 76, + 105, 110, 101, 115, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 111, 108, 118, 101, 114, 69, 120, + 101, 99, 117, 116, 105, 111, 110, 84, + 105, 109, 101, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 111, 100, 101, 108, 77, 111, 110, + 111, 84, 105, 109, 101, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 111, 108, 118, 101, 114, 67, 111, + 115, 116, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 111, 108, 118, 101, 114, 83, 116, + 97, 116, 101, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 198, 33, 112, 91, 103, 124, 202, 253, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e1e9318e2ae8b51e = b_e1e9318e2ae8b51e.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_e1e9318e2ae8b51e[] = { + &s_bb53ef3fcf2a7f0d, + &s_f7396311bcbad303, + &s_fac297f195ce56d2, + &s_fdca7c675b7021c6, +}; +static const uint16_t m_e1e9318e2ae8b51e[] = {11, 2, 3, 15, 22, 23, 28, 27, 20, 1, 21, 17, 4, 5, 19, 18, 0, 31, 12, 9, 10, 16, 26, 6, 7, 24, 25, 14, 32, 30, 33, 8, 13, 29}; +static const uint16_t i_e1e9318e2ae8b51e[] = {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}; +const ::capnp::_::RawSchema s_e1e9318e2ae8b51e = { + 0xe1e9318e2ae8b51e, b_e1e9318e2ae8b51e.words, 627, d_e1e9318e2ae8b51e, m_e1e9318e2ae8b51e, + 4, 34, i_e1e9318e2ae8b51e, nullptr, nullptr, { &s_e1e9318e2ae8b51e, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<61> b_fdca7c675b7021c6 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 198, 33, 112, 91, 103, 124, 202, 253, + 22, 0, 0, 0, 1, 0, 0, 0, + 30, 181, 232, 42, 142, 49, 233, 225, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 18, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 76, 97, 116, 101, 114, 97, + 108, 80, 108, 97, 110, 46, 83, 111, + 108, 118, 101, 114, 83, 116, 97, 116, + 101, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 80, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 0, 0, 0, 3, 0, 1, 0, + 100, 0, 0, 0, 2, 0, 1, 0, + 120, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_fdca7c675b7021c6 = b_fdca7c675b7021c6.words; +#if !CAPNP_LITE +static const uint16_t m_fdca7c675b7021c6[] = {1, 0}; +static const uint16_t i_fdca7c675b7021c6[] = {0, 1}; +const ::capnp::_::RawSchema s_fdca7c675b7021c6 = { + 0xfdca7c675b7021c6, b_fdca7c675b7021c6.words, 61, nullptr, m_fdca7c675b7021c6, + 0, 2, i_fdca7c675b7021c6, nullptr, nullptr, { &s_fdca7c675b7021c6, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<52> b_bb53ef3fcf2a7f0d = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 13, 127, 42, 207, 63, 239, 83, 187, + 22, 0, 0, 0, 2, 0, 0, 0, + 30, 181, 232, 42, 142, 49, 233, 225, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 234, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 76, 97, 116, 101, 114, 97, + 108, 80, 108, 97, 110, 46, 68, 101, + 115, 105, 114, 101, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 28, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 65, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 61, 0, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 57, 0, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 53, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 49, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 111, 110, 101, 0, 0, 0, 0, + 116, 117, 114, 110, 76, 101, 102, 116, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 117, 114, 110, 82, 105, 103, 104, + 116, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 110, 101, 67, 104, 97, 110, + 103, 101, 76, 101, 102, 116, 0, 0, + 108, 97, 110, 101, 67, 104, 97, 110, + 103, 101, 82, 105, 103, 104, 116, 0, + 107, 101, 101, 112, 76, 101, 102, 116, + 0, 0, 0, 0, 0, 0, 0, 0, + 107, 101, 101, 112, 82, 105, 103, 104, + 116, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_bb53ef3fcf2a7f0d = b_bb53ef3fcf2a7f0d.words; +#if !CAPNP_LITE +static const uint16_t m_bb53ef3fcf2a7f0d[] = {5, 6, 3, 4, 0, 1, 2}; +const ::capnp::_::RawSchema s_bb53ef3fcf2a7f0d = { + 0xbb53ef3fcf2a7f0d, b_bb53ef3fcf2a7f0d.words, 52, nullptr, m_bb53ef3fcf2a7f0d, + 0, 7, nullptr, nullptr, nullptr, { &s_bb53ef3fcf2a7f0d, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(Desire_bb53ef3fcf2a7f0d, bb53ef3fcf2a7f0d); +static const ::capnp::_::AlignedData<40> b_fac297f195ce56d2 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 210, 86, 206, 149, 241, 151, 194, 250, + 22, 0, 0, 0, 2, 0, 0, 0, + 30, 181, 232, 42, 142, 49, 233, 225, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 50, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 103, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 76, 97, 116, 101, 114, 97, + 108, 80, 108, 97, 110, 46, 76, 97, + 110, 101, 67, 104, 97, 110, 103, 101, + 83, 116, 97, 116, 101, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 102, 102, 0, 0, 0, 0, 0, + 112, 114, 101, 76, 97, 110, 101, 67, + 104, 97, 110, 103, 101, 0, 0, 0, + 108, 97, 110, 101, 67, 104, 97, 110, + 103, 101, 83, 116, 97, 114, 116, 105, + 110, 103, 0, 0, 0, 0, 0, 0, + 108, 97, 110, 101, 67, 104, 97, 110, + 103, 101, 70, 105, 110, 105, 115, 104, + 105, 110, 103, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_fac297f195ce56d2 = b_fac297f195ce56d2.words; +#if !CAPNP_LITE +static const uint16_t m_fac297f195ce56d2[] = {3, 2, 0, 1}; +const ::capnp::_::RawSchema s_fac297f195ce56d2 = { + 0xfac297f195ce56d2, b_fac297f195ce56d2.words, 40, nullptr, m_fac297f195ce56d2, + 0, 4, nullptr, nullptr, nullptr, { &s_fac297f195ce56d2, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(LaneChangeState_fac297f195ce56d2, fac297f195ce56d2); +static const ::capnp::_::AlignedData<32> b_f7396311bcbad303 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 3, 211, 186, 188, 17, 99, 57, 247, + 22, 0, 0, 0, 2, 0, 0, 0, + 30, 181, 232, 42, 142, 49, 233, 225, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 82, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 79, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 76, 97, 116, 101, 114, 97, + 108, 80, 108, 97, 110, 46, 76, 97, + 110, 101, 67, 104, 97, 110, 103, 101, + 68, 105, 114, 101, 99, 116, 105, 111, + 110, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 111, 110, 101, 0, 0, 0, 0, + 108, 101, 102, 116, 0, 0, 0, 0, + 114, 105, 103, 104, 116, 0, 0, 0, } +}; +::capnp::word const* const bp_f7396311bcbad303 = b_f7396311bcbad303.words; +#if !CAPNP_LITE +static const uint16_t m_f7396311bcbad303[] = {1, 0, 2}; +const ::capnp::_::RawSchema s_f7396311bcbad303 = { + 0xf7396311bcbad303, b_f7396311bcbad303.words, 32, nullptr, m_f7396311bcbad303, + 0, 3, nullptr, nullptr, nullptr, { &s_f7396311bcbad303, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(LaneChangeDirection_f7396311bcbad303, f7396311bcbad303); +static const ::capnp::_::AlignedData<466> b_ebc5703d1ee7c129 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 41, 193, 231, 30, 61, 112, 197, 235, + 10, 0, 0, 0, 1, 0, 5, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 15, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 234, 0, 0, 0, + 33, 0, 0, 0, 39, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 57, 0, 0, 0, 239, 5, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 76, 105, 118, 101, 76, 111, + 99, 97, 116, 105, 111, 110, 75, 97, + 108, 109, 97, 110, 0, 0, 0, 0, + 8, 0, 0, 0, 1, 0, 1, 0, + 1, 252, 81, 75, 204, 200, 77, 142, + 9, 0, 0, 0, 58, 0, 0, 0, + 28, 206, 218, 102, 237, 249, 35, 191, + 5, 0, 0, 0, 98, 0, 0, 0, + 83, 116, 97, 116, 117, 115, 0, 0, + 77, 101, 97, 115, 117, 114, 101, 109, + 101, 110, 116, 0, 0, 0, 0, 0, + 108, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 2, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 228, 2, 0, 0, 3, 0, 1, 0, + 240, 2, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 2, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 2, 0, 0, 3, 0, 1, 0, + 252, 2, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 249, 2, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 248, 2, 0, 0, 3, 0, 1, 0, + 4, 3, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 3, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 3, 0, 0, 3, 0, 1, 0, + 12, 3, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 3, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 3, 0, 0, 3, 0, 1, 0, + 20, 3, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 3, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 3, 0, 0, 3, 0, 1, 0, + 32, 3, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 3, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 28, 3, 0, 0, 3, 0, 1, 0, + 40, 3, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 3, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 3, 0, 0, 3, 0, 1, 0, + 48, 3, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 3, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 3, 0, 0, 3, 0, 1, 0, + 60, 3, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 57, 3, 0, 0, 202, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 3, 0, 0, 3, 0, 1, 0, + 76, 3, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 3, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 3, 0, 0, 3, 0, 1, 0, + 88, 3, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 11, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 85, 3, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 88, 3, 0, 0, 3, 0, 1, 0, + 100, 3, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 12, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 3, 0, 0, 210, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 3, 0, 0, 3, 0, 1, 0, + 116, 3, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 3, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 3, 0, 0, 3, 0, 1, 0, + 120, 3, 0, 0, 2, 0, 1, 0, + 15, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 3, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 3, 0, 0, 3, 0, 1, 0, + 128, 3, 0, 0, 2, 0, 1, 0, + 16, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 15, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 3, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 3, 0, 0, 3, 0, 1, 0, + 132, 3, 0, 0, 2, 0, 1, 0, + 17, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 16, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 129, 3, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 132, 3, 0, 0, 3, 0, 1, 0, + 144, 3, 0, 0, 2, 0, 1, 0, + 18, 0, 0, 0, 48, 0, 0, 0, + 0, 0, 1, 0, 17, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 141, 3, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 140, 3, 0, 0, 3, 0, 1, 0, + 152, 3, 0, 0, 2, 0, 1, 0, + 19, 0, 0, 0, 49, 0, 0, 0, + 0, 0, 1, 0, 18, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 149, 3, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 3, 0, 0, 3, 0, 1, 0, + 160, 3, 0, 0, 2, 0, 1, 0, + 20, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 1, 0, 19, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 157, 3, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 152, 3, 0, 0, 3, 0, 1, 0, + 164, 3, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 13, 0, 0, 0, + 0, 0, 1, 0, 20, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 161, 3, 0, 0, 210, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 3, 0, 0, 3, 0, 1, 0, + 180, 3, 0, 0, 2, 0, 1, 0, + 21, 0, 0, 0, 51, 0, 0, 0, + 0, 0, 1, 0, 21, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 177, 3, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 3, 0, 0, 3, 0, 1, 0, + 188, 3, 0, 0, 2, 0, 1, 0, + 22, 0, 0, 0, 52, 0, 0, 0, + 0, 0, 1, 0, 22, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 185, 3, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 3, 0, 0, 3, 0, 1, 0, + 196, 3, 0, 0, 2, 0, 1, 0, + 23, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 3, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 192, 3, 0, 0, 3, 0, 1, 0, + 204, 3, 0, 0, 2, 0, 1, 0, + 24, 0, 0, 0, 53, 0, 0, 0, + 0, 0, 1, 0, 24, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 3, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 200, 3, 0, 0, 3, 0, 1, 0, + 212, 3, 0, 0, 2, 0, 1, 0, + 25, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 25, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 3, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 3, 0, 0, 3, 0, 1, 0, + 220, 3, 0, 0, 2, 0, 1, 0, + 26, 0, 0, 0, 14, 0, 0, 0, + 0, 0, 1, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 217, 3, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 3, 0, 0, 3, 0, 1, 0, + 228, 3, 0, 0, 2, 0, 1, 0, + 112, 111, 115, 105, 116, 105, 111, 110, + 69, 67, 69, 70, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 28, 206, 218, 102, 237, 249, 35, 191, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 115, 105, 116, 105, 111, 110, + 71, 101, 111, 100, 101, 116, 105, 99, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 28, 206, 218, 102, 237, 249, 35, 191, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 101, 108, 111, 99, 105, 116, 121, + 69, 67, 69, 70, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 28, 206, 218, 102, 237, 249, 35, 191, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 101, 108, 111, 99, 105, 116, 121, + 78, 69, 68, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 28, 206, 218, 102, 237, 249, 35, 191, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 101, 108, 111, 99, 105, 116, 121, + 68, 101, 118, 105, 99, 101, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 28, 206, 218, 102, 237, 249, 35, 191, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 99, 101, 108, 101, 114, 97, + 116, 105, 111, 110, 68, 101, 118, 105, + 99, 101, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 28, 206, 218, 102, 237, 249, 35, 191, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 114, 105, 101, 110, 116, 97, 116, + 105, 111, 110, 69, 67, 69, 70, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 28, 206, 218, 102, 237, 249, 35, 191, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 114, 105, 101, 110, 116, 97, 116, + 105, 111, 110, 78, 69, 68, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 28, 206, 218, 102, 237, 249, 35, 191, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 110, 103, 117, 108, 97, 114, 86, + 101, 108, 111, 99, 105, 116, 121, 68, + 101, 118, 105, 99, 101, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 28, 206, 218, 102, 237, 249, 35, 191, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 108, 105, 98, 114, 97, 116, + 101, 100, 79, 114, 105, 101, 110, 116, + 97, 116, 105, 111, 110, 78, 69, 68, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 28, 206, 218, 102, 237, 249, 35, 191, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 101, 108, 111, 99, 105, 116, 121, + 67, 97, 108, 105, 98, 114, 97, 116, + 101, 100, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 28, 206, 218, 102, 237, 249, 35, 191, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 99, 101, 108, 101, 114, 97, + 116, 105, 111, 110, 67, 97, 108, 105, + 98, 114, 97, 116, 101, 100, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 28, 206, 218, 102, 237, 249, 35, 191, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 110, 103, 117, 108, 97, 114, 86, + 101, 108, 111, 99, 105, 116, 121, 67, + 97, 108, 105, 98, 114, 97, 116, 101, + 100, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 28, 206, 218, 102, 237, 249, 35, 191, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 87, 101, 101, 107, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 84, 105, 109, 101, 79, + 102, 87, 101, 101, 107, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 116, 117, 115, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 1, 252, 81, 75, 204, 200, 77, 142, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 110, 105, 120, 84, 105, 109, 101, + 115, 116, 97, 109, 112, 77, 105, 108, + 108, 105, 115, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 110, 112, 117, 116, 115, 79, 75, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 115, 101, 110, 101, 116, 79, + 75, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 79, 75, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 108, 105, 98, 114, 97, 116, + 101, 100, 79, 114, 105, 101, 110, 116, + 97, 116, 105, 111, 110, 69, 67, 69, + 70, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 28, 206, 218, 102, 237, 249, 35, 191, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 101, 110, 115, 111, 114, 115, 79, + 75, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 118, 105, 99, 101, 83, 116, + 97, 98, 108, 101, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 109, 101, 83, 105, 110, 99, + 101, 82, 101, 115, 101, 116, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 120, 99, 101, 115, 115, 105, 118, + 101, 82, 101, 115, 101, 116, 115, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 109, 101, 84, 111, 70, 105, + 114, 115, 116, 70, 105, 120, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 105, 108, 116, 101, 114, 83, 116, + 97, 116, 101, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 28, 206, 218, 102, 237, 249, 35, 191, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_ebc5703d1ee7c129 = b_ebc5703d1ee7c129.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_ebc5703d1ee7c129[] = { + &s_8e4dc8cc4b51fc01, + &s_bf23f9ed66dace1c, +}; +static const uint16_t m_ebc5703d1ee7c129[] = {11, 5, 12, 8, 20, 9, 22, 24, 26, 19, 14, 13, 17, 6, 7, 18, 0, 1, 21, 15, 23, 25, 16, 10, 4, 2, 3}; +static const uint16_t i_ebc5703d1ee7c129[] = {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}; +const ::capnp::_::RawSchema s_ebc5703d1ee7c129 = { + 0xebc5703d1ee7c129, b_ebc5703d1ee7c129.words, 466, d_ebc5703d1ee7c129, m_ebc5703d1ee7c129, + 2, 27, i_ebc5703d1ee7c129, nullptr, nullptr, { &s_ebc5703d1ee7c129, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<33> b_8e4dc8cc4b51fc01 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 1, 252, 81, 75, 204, 200, 77, 142, + 29, 0, 0, 0, 2, 0, 0, 0, + 41, 193, 231, 30, 61, 112, 197, 235, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 34, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 79, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 76, 105, 118, 101, 76, 111, + 99, 97, 116, 105, 111, 110, 75, 97, + 108, 109, 97, 110, 46, 83, 116, 97, + 116, 117, 115, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 110, 105, 110, 105, 116, 105, 97, + 108, 105, 122, 101, 100, 0, 0, 0, + 117, 110, 99, 97, 108, 105, 98, 114, + 97, 116, 101, 100, 0, 0, 0, 0, + 118, 97, 108, 105, 100, 0, 0, 0, } +}; +::capnp::word const* const bp_8e4dc8cc4b51fc01 = b_8e4dc8cc4b51fc01.words; +#if !CAPNP_LITE +static const uint16_t m_8e4dc8cc4b51fc01[] = {1, 0, 2}; +const ::capnp::_::RawSchema s_8e4dc8cc4b51fc01 = { + 0x8e4dc8cc4b51fc01, b_8e4dc8cc4b51fc01.words, 33, nullptr, m_8e4dc8cc4b51fc01, + 0, 3, nullptr, nullptr, nullptr, { &s_8e4dc8cc4b51fc01, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(Status_8e4dc8cc4b51fc01, 8e4dc8cc4b51fc01); +static const ::capnp::_::AlignedData<73> b_bf23f9ed66dace1c = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 28, 206, 218, 102, 237, 249, 35, 191, + 29, 0, 0, 0, 1, 0, 1, 0, + 41, 193, 231, 30, 61, 112, 197, 235, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 74, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 76, 105, 118, 101, 76, 111, + 99, 97, 116, 105, 111, 110, 75, 97, + 108, 109, 97, 110, 46, 77, 101, 97, + 115, 117, 114, 101, 109, 101, 110, 116, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 0, 0, 0, 3, 0, 1, 0, + 92, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 89, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 84, 0, 0, 0, 3, 0, 1, 0, + 112, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 0, 0, 0, 3, 0, 1, 0, + 116, 0, 0, 0, 2, 0, 1, 0, + 118, 97, 108, 117, 101, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 100, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 97, 108, 105, 100, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_bf23f9ed66dace1c = b_bf23f9ed66dace1c.words; +#if !CAPNP_LITE +static const uint16_t m_bf23f9ed66dace1c[] = {1, 2, 0}; +static const uint16_t i_bf23f9ed66dace1c[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_bf23f9ed66dace1c = { + 0xbf23f9ed66dace1c, b_bf23f9ed66dace1c.words, 73, nullptr, m_bf23f9ed66dace1c, + 0, 3, i_bf23f9ed66dace1c, nullptr, nullptr, { &s_bf23f9ed66dace1c, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<81> b_af85387b3f681406 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 6, 20, 104, 63, 123, 56, 133, 175, + 10, 0, 0, 0, 1, 0, 0, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 3, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 146, 0, 0, 0, + 29, 0, 0, 0, 55, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 65, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 80, 114, 111, 99, 76, 111, + 103, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 1, 0, 1, 0, + 40, 109, 158, 241, 19, 86, 184, 176, + 17, 0, 0, 0, 66, 0, 0, 0, + 135, 224, 44, 191, 197, 200, 137, 241, + 13, 0, 0, 0, 74, 0, 0, 0, + 212, 63, 139, 240, 148, 95, 9, 253, + 13, 0, 0, 0, 34, 0, 0, 0, + 80, 114, 111, 99, 101, 115, 115, 0, + 67, 80, 85, 84, 105, 109, 101, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 101, 109, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 0, 0, 0, 3, 0, 1, 0, + 96, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 88, 0, 0, 0, 3, 0, 1, 0, + 100, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 0, 0, 0, 3, 0, 1, 0, + 120, 0, 0, 0, 2, 0, 1, 0, + 99, 112, 117, 84, 105, 109, 101, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 135, 224, 44, 191, 197, 200, 137, 241, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 101, 109, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 212, 63, 139, 240, 148, 95, 9, 253, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 114, 111, 99, 115, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 40, 109, 158, 241, 19, 86, 184, 176, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_af85387b3f681406 = b_af85387b3f681406.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_af85387b3f681406[] = { + &s_b0b85613f19e6d28, + &s_f189c8c5bf2ce087, + &s_fd095f94f08b3fd4, +}; +static const uint16_t m_af85387b3f681406[] = {0, 1, 2}; +static const uint16_t i_af85387b3f681406[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_af85387b3f681406 = { + 0xaf85387b3f681406, b_af85387b3f681406.words, 81, d_af85387b3f681406, m_af85387b3f681406, + 3, 3, i_af85387b3f681406, nullptr, nullptr, { &s_af85387b3f681406, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<285> b_b0b85613f19e6d28 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 40, 109, 158, 241, 19, 86, 184, 176, + 18, 0, 0, 0, 1, 0, 9, 0, + 6, 20, 104, 63, 123, 56, 133, 175, + 3, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 210, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 191, 3, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 80, 114, 111, 99, 76, 111, + 103, 46, 80, 114, 111, 99, 101, 115, + 115, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 68, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 1, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 200, 1, 0, 0, 3, 0, 1, 0, + 212, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 1, 0, 0, 3, 0, 1, 0, + 216, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 1, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 1, 0, 0, 3, 0, 1, 0, + 220, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 217, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 212, 1, 0, 0, 3, 0, 1, 0, + 224, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 1, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 1, 0, 0, 3, 0, 1, 0, + 228, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 225, 1, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 224, 1, 0, 0, 3, 0, 1, 0, + 236, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 233, 1, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 1, 0, 0, 3, 0, 1, 0, + 244, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 1, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 244, 1, 0, 0, 3, 0, 1, 0, + 0, 2, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 253, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 252, 1, 0, 0, 3, 0, 1, 0, + 8, 2, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 2, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 2, 0, 0, 3, 0, 1, 0, + 12, 2, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 2, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 2, 0, 0, 3, 0, 1, 0, + 20, 2, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 2, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 2, 0, 0, 3, 0, 1, 0, + 28, 2, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 2, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 2, 0, 0, 3, 0, 1, 0, + 32, 2, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 2, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 24, 2, 0, 0, 3, 0, 1, 0, + 36, 2, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 11, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 2, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 2, 0, 0, 3, 0, 1, 0, + 44, 2, 0, 0, 2, 0, 1, 0, + 15, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 15, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 2, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 2, 0, 0, 3, 0, 1, 0, + 64, 2, 0, 0, 2, 0, 1, 0, + 16, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 16, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 2, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 56, 2, 0, 0, 3, 0, 1, 0, + 68, 2, 0, 0, 2, 0, 1, 0, + 112, 105, 100, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 97, 109, 101, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 116, 101, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 112, 105, 100, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 112, 117, 85, 115, 101, 114, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 112, 117, 83, 121, 115, 116, 101, + 109, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 112, 117, 67, 104, 105, 108, 100, + 114, 101, 110, 85, 115, 101, 114, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 112, 117, 67, 104, 105, 108, 100, + 114, 101, 110, 83, 121, 115, 116, 101, + 109, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 114, 105, 111, 114, 105, 116, 121, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 105, 99, 101, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 117, 109, 84, 104, 114, 101, 97, + 100, 115, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 114, 116, 84, 105, 109, + 101, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 101, 109, 86, 109, 115, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 101, 109, 82, 115, 115, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 114, 111, 99, 101, 115, 115, 111, + 114, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 109, 100, 108, 105, 110, 101, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 120, 101, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_b0b85613f19e6d28 = b_b0b85613f19e6d28.words; +#if !CAPNP_LITE +static const uint16_t m_b0b85613f19e6d28[] = {15, 7, 6, 5, 4, 16, 13, 12, 1, 9, 10, 0, 3, 8, 14, 11, 2}; +static const uint16_t i_b0b85613f19e6d28[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16}; +const ::capnp::_::RawSchema s_b0b85613f19e6d28 = { + 0xb0b85613f19e6d28, b_b0b85613f19e6d28.words, 285, nullptr, m_b0b85613f19e6d28, + 0, 17, i_b0b85613f19e6d28, nullptr, nullptr, { &s_b0b85613f19e6d28, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<138> b_f189c8c5bf2ce087 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 135, 224, 44, 191, 197, 200, 137, 241, + 18, 0, 0, 0, 1, 0, 5, 0, + 6, 20, 104, 63, 123, 56, 133, 175, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 218, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 199, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 80, 114, 111, 99, 76, 111, + 103, 46, 67, 80, 85, 84, 105, 109, + 101, 115, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 32, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 0, 0, 0, 3, 0, 1, 0, + 216, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 0, 0, 0, 3, 0, 1, 0, + 220, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 217, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 212, 0, 0, 0, 3, 0, 1, 0, + 224, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 0, 0, 0, 3, 0, 1, 0, + 228, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 225, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 220, 0, 0, 0, 3, 0, 1, 0, + 232, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 224, 0, 0, 0, 3, 0, 1, 0, + 236, 0, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 233, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 228, 0, 0, 0, 3, 0, 1, 0, + 240, 0, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 0, 0, 0, 3, 0, 1, 0, + 244, 0, 0, 0, 2, 0, 1, 0, + 99, 112, 117, 78, 117, 109, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 115, 101, 114, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 105, 99, 101, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 121, 115, 116, 101, 109, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 100, 108, 101, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 111, 119, 97, 105, 116, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 114, 113, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 111, 102, 116, 105, 114, 113, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_f189c8c5bf2ce087 = b_f189c8c5bf2ce087.words; +#if !CAPNP_LITE +static const uint16_t m_f189c8c5bf2ce087[] = {0, 4, 5, 6, 2, 7, 3, 1}; +static const uint16_t i_f189c8c5bf2ce087[] = {0, 1, 2, 3, 4, 5, 6, 7}; +const ::capnp::_::RawSchema s_f189c8c5bf2ce087 = { + 0xf189c8c5bf2ce087, b_f189c8c5bf2ce087.words, 138, nullptr, m_f189c8c5bf2ce087, + 0, 8, i_f189c8c5bf2ce087, nullptr, nullptr, { &s_f189c8c5bf2ce087, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<139> b_fd095f94f08b3fd4 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 212, 63, 139, 240, 148, 95, 9, 253, + 18, 0, 0, 0, 1, 0, 8, 0, + 6, 20, 104, 63, 123, 56, 133, 175, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 178, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 199, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 80, 114, 111, 99, 76, 111, + 103, 46, 77, 101, 109, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 32, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 0, 0, 0, 3, 0, 1, 0, + 216, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 0, 0, 0, 3, 0, 1, 0, + 220, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 217, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 0, 0, 0, 3, 0, 1, 0, + 228, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 225, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 220, 0, 0, 0, 3, 0, 1, 0, + 232, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 224, 0, 0, 0, 3, 0, 1, 0, + 236, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 233, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 228, 0, 0, 0, 3, 0, 1, 0, + 240, 0, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 236, 0, 0, 0, 3, 0, 1, 0, + 248, 0, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 245, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 0, 0, 0, 3, 0, 1, 0, + 252, 0, 0, 0, 2, 0, 1, 0, + 116, 111, 116, 97, 108, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 114, 101, 101, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 118, 97, 105, 108, 97, 98, 108, + 101, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 117, 102, 102, 101, 114, 115, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 99, 104, 101, 100, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 116, 105, 118, 101, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 110, 97, 99, 116, 105, 118, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 104, 97, 114, 101, 100, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_fd095f94f08b3fd4 = b_fd095f94f08b3fd4.words; +#if !CAPNP_LITE +static const uint16_t m_fd095f94f08b3fd4[] = {5, 2, 3, 4, 1, 6, 7, 0}; +static const uint16_t i_fd095f94f08b3fd4[] = {0, 1, 2, 3, 4, 5, 6, 7}; +const ::capnp::_::RawSchema s_fd095f94f08b3fd4 = { + 0xfd095f94f08b3fd4, b_fd095f94f08b3fd4.words, 139, nullptr, m_fd095f94f08b3fd4, + 0, 8, i_fd095f94f08b3fd4, nullptr, nullptr, { &s_fd095f94f08b3fd4, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<216> b_afd47016570e9d09 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 9, 157, 14, 87, 22, 112, 212, 175, + 10, 0, 0, 0, 1, 0, 3, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 6, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 218, 0, 0, 0, + 33, 0, 0, 0, 103, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 137, 0, 0, 0, 55, 2, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 71, 110, 115, 115, 77, 101, + 97, 115, 117, 114, 101, 109, 101, 110, + 116, 115, 0, 0, 0, 0, 0, 0, + 24, 0, 0, 0, 1, 0, 1, 0, + 96, 184, 191, 168, 230, 107, 40, 243, + 41, 0, 0, 0, 130, 0, 0, 0, + 176, 118, 172, 134, 125, 161, 164, 234, + 41, 0, 0, 0, 170, 0, 0, 0, + 133, 173, 192, 135, 80, 239, 194, 188, + 45, 0, 0, 0, 210, 0, 0, 0, + 119, 8, 69, 168, 46, 156, 7, 130, + 53, 0, 0, 0, 130, 0, 0, 0, + 147, 141, 176, 4, 24, 188, 153, 194, + 53, 0, 0, 0, 114, 0, 0, 0, + 246, 153, 166, 150, 51, 155, 227, 246, + 53, 0, 0, 0, 130, 0, 0, 0, + 69, 112, 104, 101, 109, 101, 114, 105, + 115, 83, 116, 97, 116, 117, 115, 0, + 67, 111, 114, 114, 101, 99, 116, 101, + 100, 77, 101, 97, 115, 117, 114, 101, + 109, 101, 110, 116, 0, 0, 0, 0, + 69, 112, 104, 101, 109, 101, 114, 105, + 115, 83, 111, 117, 114, 99, 101, 68, + 69, 80, 82, 69, 67, 65, 84, 69, + 68, 0, 0, 0, 0, 0, 0, 0, + 67, 111, 110, 115, 116, 101, 108, 108, + 97, 116, 105, 111, 110, 73, 100, 0, + 69, 112, 104, 101, 109, 101, 114, 105, + 115, 84, 121, 112, 101, 0, 0, 0, + 69, 112, 104, 101, 109, 101, 114, 105, + 115, 83, 111, 117, 114, 99, 101, 0, + 40, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 1, 0, 0, 3, 0, 1, 0, + 20, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 1, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 1, 0, 0, 3, 0, 1, 0, + 24, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 1, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 1, 0, 0, 3, 0, 1, 0, + 32, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 1, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 1, 0, 0, 3, 0, 1, 0, + 60, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 57, 1, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 60, 1, 0, 0, 3, 0, 1, 0, + 72, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 1, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 1, 0, 0, 3, 0, 1, 0, + 84, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 81, 1, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 80, 1, 0, 0, 3, 0, 1, 0, + 92, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 89, 1, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 88, 1, 0, 0, 3, 0, 1, 0, + 100, 1, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 1, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 1, 0, 0, 3, 0, 1, 0, + 108, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 1, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 1, 0, 0, 3, 0, 1, 0, + 136, 1, 0, 0, 2, 0, 1, 0, + 109, 101, 97, 115, 84, 105, 109, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 87, 101, 101, 107, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 84, 105, 109, 101, 79, + 102, 87, 101, 101, 107, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 111, 114, 114, 101, 99, 116, 101, + 100, 77, 101, 97, 115, 117, 114, 101, + 109, 101, 110, 116, 115, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 176, 118, 172, 134, 125, 161, 164, 234, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 107, 97, 108, 109, 97, 110, 80, 111, + 115, 105, 116, 105, 111, 110, 69, 67, + 69, 70, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 28, 206, 218, 102, 237, 249, 35, 191, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 107, 97, 108, 109, 97, 110, 86, 101, + 108, 111, 99, 105, 116, 121, 69, 67, + 69, 70, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 28, 206, 218, 102, 237, 249, 35, 191, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 115, 105, 116, 105, 111, 110, + 69, 67, 69, 70, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 28, 206, 218, 102, 237, 249, 35, 191, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 101, 108, 111, 99, 105, 116, 121, + 69, 67, 69, 70, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 28, 206, 218, 102, 237, 249, 35, 191, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 109, 101, 84, 111, 70, 105, + 114, 115, 116, 70, 105, 120, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 112, 104, 101, 109, 101, 114, 105, + 115, 83, 116, 97, 116, 117, 115, 101, + 115, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 96, 184, 191, 168, 230, 107, 40, 243, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_afd47016570e9d09 = b_afd47016570e9d09.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_afd47016570e9d09[] = { + &s_bf23f9ed66dace1c, + &s_eaa4a17d86ac76b0, + &s_f3286be6a8bfb860, +}; +static const uint16_t m_afd47016570e9d09[] = {3, 9, 2, 1, 4, 5, 0, 6, 8, 7}; +static const uint16_t i_afd47016570e9d09[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9}; +const ::capnp::_::RawSchema s_afd47016570e9d09 = { + 0xafd47016570e9d09, b_afd47016570e9d09.words, 216, d_afd47016570e9d09, m_afd47016570e9d09, + 3, 10, i_afd47016570e9d09, nullptr, nullptr, { &s_afd47016570e9d09, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<111> b_f3286be6a8bfb860 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 96, 184, 191, 168, 230, 107, 40, 243, + 27, 0, 0, 0, 1, 0, 3, 0, + 9, 157, 14, 87, 22, 112, 212, 175, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 90, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 87, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 71, 110, 115, 115, 77, 101, + 97, 115, 117, 114, 101, 109, 101, 110, + 116, 115, 46, 69, 112, 104, 101, 109, + 101, 114, 105, 115, 83, 116, 97, 116, + 117, 115, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 24, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 0, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 152, 0, 0, 0, 3, 0, 1, 0, + 164, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 161, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 156, 0, 0, 0, 3, 0, 1, 0, + 168, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 165, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 160, 0, 0, 0, 3, 0, 1, 0, + 172, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 169, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 164, 0, 0, 0, 3, 0, 1, 0, + 176, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 173, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 0, 0, 0, 3, 0, 1, 0, + 180, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 172, 0, 0, 0, 3, 0, 1, 0, + 184, 0, 0, 0, 2, 0, 1, 0, + 99, 111, 110, 115, 116, 101, 108, 108, + 97, 116, 105, 111, 110, 73, 100, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 119, 8, 69, 168, 46, 156, 7, 130, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 118, 73, 100, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 121, 112, 101, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 147, 141, 176, 4, 24, 188, 153, 194, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 111, 117, 114, 99, 101, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 246, 153, 166, 150, 51, 155, 227, 246, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 87, 101, 101, 107, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 111, 119, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_f3286be6a8bfb860 = b_f3286be6a8bfb860.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_f3286be6a8bfb860[] = { + &s_82079c2ea8450877, + &s_c299bc1804b08d93, + &s_f6e39b3396a699f6, +}; +static const uint16_t m_f3286be6a8bfb860[] = {0, 4, 3, 1, 5, 2}; +static const uint16_t i_f3286be6a8bfb860[] = {0, 1, 2, 3, 4, 5}; +const ::capnp::_::RawSchema s_f3286be6a8bfb860 = { + 0xf3286be6a8bfb860, b_f3286be6a8bfb860.words, 111, d_f3286be6a8bfb860, m_f3286be6a8bfb860, + 3, 6, i_f3286be6a8bfb860, nullptr, nullptr, { &s_f3286be6a8bfb860, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<189> b_eaa4a17d86ac76b0 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 176, 118, 172, 134, 125, 161, 164, 234, + 27, 0, 0, 0, 1, 0, 5, 0, + 9, 157, 14, 87, 22, 112, 212, 175, + 3, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 130, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 55, 2, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 71, 110, 115, 115, 77, 101, + 97, 115, 117, 114, 101, 109, 101, 110, + 116, 115, 46, 67, 111, 114, 114, 101, + 99, 116, 101, 100, 77, 101, 97, 115, + 117, 114, 101, 109, 101, 110, 116, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 40, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 1, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 1, 0, 0, 3, 0, 1, 0, + 20, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 1, 0, 0, 3, 0, 1, 0, + 24, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 1, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 24, 1, 0, 0, 3, 0, 1, 0, + 36, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 1, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 1, 0, 0, 3, 0, 1, 0, + 44, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 1, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 1, 0, 0, 3, 0, 1, 0, + 52, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 1, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 1, 0, 0, 3, 0, 1, 0, + 60, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 57, 1, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 60, 1, 0, 0, 3, 0, 1, 0, + 72, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 1, 0, 0, 3, 0, 1, 0, + 92, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 89, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 84, 1, 0, 0, 3, 0, 1, 0, + 112, 1, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 1, 0, 0, 210, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 1, 0, 0, 3, 0, 1, 0, + 128, 1, 0, 0, 2, 0, 1, 0, + 99, 111, 110, 115, 116, 101, 108, 108, + 97, 116, 105, 111, 110, 73, 100, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 119, 8, 69, 168, 46, 156, 7, 130, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 118, 73, 100, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 108, 111, 110, 97, 115, 115, 70, + 114, 101, 113, 117, 101, 110, 99, 121, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 115, 101, 117, 100, 111, 114, 97, + 110, 103, 101, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 115, 101, 117, 100, 111, 114, 97, + 110, 103, 101, 83, 116, 100, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 115, 101, 117, 100, 111, 114, 97, + 110, 103, 101, 82, 97, 116, 101, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 115, 101, 117, 100, 111, 114, 97, + 110, 103, 101, 82, 97, 116, 101, 83, + 116, 100, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 97, 116, 80, 111, 115, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 97, 116, 86, 101, 108, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 112, 104, 101, 109, 101, 114, 105, + 115, 83, 111, 117, 114, 99, 101, 68, + 69, 80, 82, 69, 67, 65, 84, 69, + 68, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 133, 173, 192, 135, 80, 239, 194, 188, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_eaa4a17d86ac76b0 = b_eaa4a17d86ac76b0.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_eaa4a17d86ac76b0[] = { + &s_82079c2ea8450877, + &s_bcc2ef5087c0ad85, +}; +static const uint16_t m_eaa4a17d86ac76b0[] = {0, 9, 2, 3, 5, 6, 4, 7, 8, 1}; +static const uint16_t i_eaa4a17d86ac76b0[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9}; +const ::capnp::_::RawSchema s_eaa4a17d86ac76b0 = { + 0xeaa4a17d86ac76b0, b_eaa4a17d86ac76b0.words, 189, d_eaa4a17d86ac76b0, m_eaa4a17d86ac76b0, + 2, 10, i_eaa4a17d86ac76b0, nullptr, nullptr, { &s_eaa4a17d86ac76b0, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<67> b_bcc2ef5087c0ad85 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 133, 173, 192, 135, 80, 239, 194, 188, + 27, 0, 0, 0, 1, 0, 1, 0, + 9, 157, 14, 87, 22, 112, 212, 175, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 170, 1, 0, 0, + 45, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 71, 110, 115, 115, 77, 101, + 97, 115, 117, 114, 101, 109, 101, 110, + 116, 115, 46, 69, 112, 104, 101, 109, + 101, 114, 105, 115, 83, 111, 117, 114, + 99, 101, 68, 69, 80, 82, 69, 67, + 65, 84, 69, 68, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 0, 0, 0, 3, 0, 1, 0, + 76, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 0, 0, 0, 3, 0, 1, 0, + 80, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 0, 0, 0, 3, 0, 1, 0, + 88, 0, 0, 0, 2, 0, 1, 0, + 116, 121, 112, 101, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 147, 141, 176, 4, 24, 188, 153, 194, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 87, 101, 101, 107, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 84, 105, 109, 101, 79, + 102, 87, 101, 101, 107, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_bcc2ef5087c0ad85 = b_bcc2ef5087c0ad85.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_bcc2ef5087c0ad85[] = { + &s_c299bc1804b08d93, +}; +static const uint16_t m_bcc2ef5087c0ad85[] = {2, 1, 0}; +static const uint16_t i_bcc2ef5087c0ad85[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_bcc2ef5087c0ad85 = { + 0xbcc2ef5087c0ad85, b_bcc2ef5087c0ad85.words, 67, d_bcc2ef5087c0ad85, m_bcc2ef5087c0ad85, + 1, 3, i_bcc2ef5087c0ad85, nullptr, nullptr, { &s_bcc2ef5087c0ad85, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<48> b_82079c2ea8450877 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 119, 8, 69, 168, 46, 156, 7, 130, + 27, 0, 0, 0, 2, 0, 0, 0, + 9, 157, 14, 87, 22, 112, 212, 175, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 90, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 71, 110, 115, 115, 77, 101, + 97, 115, 117, 114, 101, 109, 101, 110, + 116, 115, 46, 67, 111, 110, 115, 116, + 101, 108, 108, 97, 116, 105, 111, 110, + 73, 100, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 28, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 61, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 53, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 0, 0, 0, 0, 0, + 115, 98, 97, 115, 0, 0, 0, 0, + 103, 97, 108, 105, 108, 101, 111, 0, + 98, 101, 105, 100, 111, 117, 0, 0, + 105, 109, 101, 115, 0, 0, 0, 0, + 113, 122, 110, 115, 115, 0, 0, 0, + 103, 108, 111, 110, 97, 115, 115, 0, } +}; +::capnp::word const* const bp_82079c2ea8450877 = b_82079c2ea8450877.words; +#if !CAPNP_LITE +static const uint16_t m_82079c2ea8450877[] = {3, 2, 6, 0, 4, 5, 1}; +const ::capnp::_::RawSchema s_82079c2ea8450877 = { + 0x82079c2ea8450877, b_82079c2ea8450877.words, 48, nullptr, m_82079c2ea8450877, + 0, 7, nullptr, nullptr, nullptr, { &s_82079c2ea8450877, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(ConstellationId_82079c2ea8450877, 82079c2ea8450877); +static const ::capnp::_::AlignedData<39> b_c299bc1804b08d93 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 147, 141, 176, 4, 24, 188, 153, 194, + 27, 0, 0, 0, 2, 0, 0, 0, + 9, 157, 14, 87, 22, 112, 212, 175, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 74, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 103, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 71, 110, 115, 115, 77, 101, + 97, 115, 117, 114, 101, 109, 101, 110, + 116, 115, 46, 69, 112, 104, 101, 109, + 101, 114, 105, 115, 84, 121, 112, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 97, 118, 0, 0, 0, 0, 0, + 110, 97, 115, 97, 85, 108, 116, 114, + 97, 82, 97, 112, 105, 100, 0, 0, + 103, 108, 111, 110, 97, 115, 115, 73, + 97, 99, 85, 108, 116, 114, 97, 82, + 97, 112, 105, 100, 0, 0, 0, 0, + 113, 99, 111, 109, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_c299bc1804b08d93 = b_c299bc1804b08d93.words; +#if !CAPNP_LITE +static const uint16_t m_c299bc1804b08d93[] = {2, 1, 0, 3}; +const ::capnp::_::RawSchema s_c299bc1804b08d93 = { + 0xc299bc1804b08d93, b_c299bc1804b08d93.words, 39, nullptr, m_c299bc1804b08d93, + 0, 4, nullptr, nullptr, nullptr, { &s_c299bc1804b08d93, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(EphemerisType_c299bc1804b08d93, c299bc1804b08d93); +static const ::capnp::_::AlignedData<38> b_f6e39b3396a699f6 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 246, 153, 166, 150, 51, 155, 227, 246, + 27, 0, 0, 0, 2, 0, 0, 0, + 9, 157, 14, 87, 22, 112, 212, 175, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 90, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 103, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 71, 110, 115, 115, 77, 101, + 97, 115, 117, 114, 101, 109, 101, 110, + 116, 115, 46, 69, 112, 104, 101, 109, + 101, 114, 105, 115, 83, 111, 117, 114, + 99, 101, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 110, 115, 115, 67, 104, 105, 112, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 110, 116, 101, 114, 110, 101, 116, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 99, 104, 101, 0, 0, 0, + 117, 110, 107, 110, 111, 119, 110, 0, } +}; +::capnp::word const* const bp_f6e39b3396a699f6 = b_f6e39b3396a699f6.words; +#if !CAPNP_LITE +static const uint16_t m_f6e39b3396a699f6[] = {2, 0, 1, 3}; +const ::capnp::_::RawSchema s_f6e39b3396a699f6 = { + 0xf6e39b3396a699f6, b_f6e39b3396a699f6.words, 38, nullptr, m_f6e39b3396a699f6, + 0, 4, nullptr, nullptr, nullptr, { &s_f6e39b3396a699f6, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(EphemerisSource_f6e39b3396a699f6, f6e39b3396a699f6); +static const ::capnp::_::AlignedData<161> b_85dddd7ce6cefa5d = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 93, 250, 206, 230, 124, 221, 221, 133, + 10, 0, 0, 0, 1, 0, 1, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 1, 0, 7, 0, 0, 0, 7, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 162, 0, 0, 0, + 29, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 145, 0, 0, 0, 143, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 85, 98, 108, 111, 120, 71, + 110, 115, 115, 0, 0, 0, 0, 0, + 28, 0, 0, 0, 1, 0, 1, 0, + 83, 143, 104, 118, 255, 42, 100, 187, + 49, 0, 0, 0, 82, 0, 0, 0, + 244, 32, 152, 162, 70, 165, 59, 167, + 49, 0, 0, 0, 146, 0, 0, 0, + 92, 248, 24, 129, 120, 140, 65, 216, + 53, 0, 0, 0, 82, 0, 0, 0, + 38, 74, 154, 81, 222, 168, 163, 195, + 53, 0, 0, 0, 74, 0, 0, 0, + 168, 90, 39, 20, 177, 54, 176, 235, + 53, 0, 0, 0, 74, 0, 0, 0, + 198, 83, 14, 185, 16, 180, 25, 249, + 53, 0, 0, 0, 82, 0, 0, 0, + 12, 142, 56, 152, 17, 145, 197, 185, + 53, 0, 0, 0, 138, 0, 0, 0, + 83, 97, 116, 82, 101, 112, 111, 114, + 116, 0, 0, 0, 0, 0, 0, 0, + 77, 101, 97, 115, 117, 114, 101, 109, + 101, 110, 116, 82, 101, 112, 111, 114, + 116, 0, 0, 0, 0, 0, 0, 0, + 69, 112, 104, 101, 109, 101, 114, 105, + 115, 0, 0, 0, 0, 0, 0, 0, + 73, 111, 110, 111, 68, 97, 116, 97, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 119, 83, 116, 97, 116, 117, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 119, 83, 116, 97, 116, 117, 115, + 50, 0, 0, 0, 0, 0, 0, 0, + 71, 108, 111, 110, 97, 115, 115, 69, + 112, 104, 101, 109, 101, 114, 105, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 28, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 255, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 0, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 0, 0, 0, 3, 0, 1, 0, + 196, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 254, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 192, 0, 0, 0, 3, 0, 1, 0, + 204, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 253, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 200, 0, 0, 0, 3, 0, 1, 0, + 212, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 252, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 0, 0, 0, 3, 0, 1, 0, + 220, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 251, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 217, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 0, 0, 0, 3, 0, 1, 0, + 228, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 250, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 225, 0, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 228, 0, 0, 0, 3, 0, 1, 0, + 240, 0, 0, 0, 2, 0, 1, 0, + 6, 0, 249, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 236, 0, 0, 0, 3, 0, 1, 0, + 248, 0, 0, 0, 2, 0, 1, 0, + 109, 101, 97, 115, 117, 114, 101, 109, + 101, 110, 116, 82, 101, 112, 111, 114, + 116, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 244, 32, 152, 162, 70, 165, 59, 167, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 112, 104, 101, 109, 101, 114, 105, + 115, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 92, 248, 24, 129, 120, 140, 65, 216, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 111, 110, 111, 68, 97, 116, 97, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 38, 74, 154, 81, 222, 168, 163, 195, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 119, 83, 116, 97, 116, 117, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 168, 90, 39, 20, 177, 54, 176, 235, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 119, 83, 116, 97, 116, 117, 115, + 50, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 198, 83, 14, 185, 16, 180, 25, 249, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 108, 111, 110, 97, 115, 115, 69, + 112, 104, 101, 109, 101, 114, 105, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 12, 142, 56, 152, 17, 145, 197, 185, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 97, 116, 82, 101, 112, 111, 114, + 116, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 83, 143, 104, 118, 255, 42, 100, 187, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_85dddd7ce6cefa5d = b_85dddd7ce6cefa5d.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_85dddd7ce6cefa5d[] = { + &s_a73ba546a29820f4, + &s_b9c5911198388e0c, + &s_bb642aff76688f53, + &s_c3a3a8de519a4a26, + &s_d8418c788118f85c, + &s_ebb036b114275aa8, + &s_f919b410b90e53c6, +}; +static const uint16_t m_85dddd7ce6cefa5d[] = {1, 5, 3, 4, 2, 0, 6}; +static const uint16_t i_85dddd7ce6cefa5d[] = {0, 1, 2, 3, 4, 5, 6}; +const ::capnp::_::RawSchema s_85dddd7ce6cefa5d = { + 0x85dddd7ce6cefa5d, b_85dddd7ce6cefa5d.words, 161, d_85dddd7ce6cefa5d, m_85dddd7ce6cefa5d, + 7, 7, i_85dddd7ce6cefa5d, nullptr, nullptr, { &s_85dddd7ce6cefa5d, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<55> b_bb642aff76688f53 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 83, 143, 104, 118, 255, 42, 100, 187, + 20, 0, 0, 0, 1, 0, 1, 0, + 93, 250, 206, 230, 124, 221, 221, 133, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 242, 0, 0, 0, + 33, 0, 0, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 85, 98, 108, 111, 120, 71, + 110, 115, 115, 46, 83, 97, 116, 82, + 101, 112, 111, 114, 116, 0, 0, 0, + 4, 0, 0, 0, 1, 0, 1, 0, + 67, 158, 215, 206, 2, 206, 157, 232, + 1, 0, 0, 0, 66, 0, 0, 0, + 83, 97, 116, 73, 110, 102, 111, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 68, 0, 0, 0, 2, 0, 1, 0, + 105, 84, 111, 119, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 118, 115, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 67, 158, 215, 206, 2, 206, 157, 232, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_bb642aff76688f53 = b_bb642aff76688f53.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_bb642aff76688f53[] = { + &s_e89dce02ced79e43, +}; +static const uint16_t m_bb642aff76688f53[] = {0, 1}; +static const uint16_t i_bb642aff76688f53[] = {0, 1}; +const ::capnp::_::RawSchema s_bb642aff76688f53 = { + 0xbb642aff76688f53, b_bb642aff76688f53.words, 55, d_bb642aff76688f53, m_bb642aff76688f53, + 1, 2, i_bb642aff76688f53, nullptr, nullptr, { &s_bb642aff76688f53, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<65> b_e89dce02ced79e43 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 67, 158, 215, 206, 2, 206, 157, 232, + 30, 0, 0, 0, 1, 0, 1, 0, + 83, 143, 104, 118, 255, 42, 100, 187, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 50, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 85, 98, 108, 111, 120, 71, + 110, 115, 115, 46, 83, 97, 116, 82, + 101, 112, 111, 114, 116, 46, 83, 97, + 116, 73, 110, 102, 111, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 0, 0, 0, 3, 0, 1, 0, + 76, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 0, 0, 0, 3, 0, 1, 0, + 80, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 0, 0, 0, 3, 0, 1, 0, + 88, 0, 0, 0, 2, 0, 1, 0, + 115, 118, 73, 100, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 110, 115, 115, 73, 100, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 108, 97, 103, 115, 66, 105, 116, + 102, 105, 101, 108, 100, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e89dce02ced79e43 = b_e89dce02ced79e43.words; +#if !CAPNP_LITE +static const uint16_t m_e89dce02ced79e43[] = {2, 1, 0}; +static const uint16_t i_e89dce02ced79e43[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_e89dce02ced79e43 = { + 0xe89dce02ced79e43, b_e89dce02ced79e43.words, 65, nullptr, m_e89dce02ced79e43, + 0, 3, i_e89dce02ced79e43, nullptr, nullptr, { &s_e89dce02ced79e43, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<124> b_a73ba546a29820f4 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 244, 32, 152, 162, 70, 165, 59, 167, + 20, 0, 0, 0, 1, 0, 2, 0, + 93, 250, 206, 230, 124, 221, 221, 133, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 50, 1, 0, 0, + 37, 0, 0, 0, 39, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 65, 0, 0, 0, 87, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 85, 98, 108, 111, 120, 71, + 110, 115, 115, 46, 77, 101, 97, 115, + 117, 114, 101, 109, 101, 110, 116, 82, + 101, 112, 111, 114, 116, 0, 0, 0, + 8, 0, 0, 0, 1, 0, 1, 0, + 182, 170, 96, 81, 214, 56, 184, 251, + 9, 0, 0, 0, 122, 0, 0, 0, + 1, 100, 50, 94, 95, 101, 138, 143, + 9, 0, 0, 0, 98, 0, 0, 0, + 82, 101, 99, 101, 105, 118, 101, 114, + 83, 116, 97, 116, 117, 115, 0, 0, + 77, 101, 97, 115, 117, 114, 101, 109, + 101, 110, 116, 0, 0, 0, 0, 0, + 24, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 0, 0, 0, 3, 0, 1, 0, + 160, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 157, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 152, 0, 0, 0, 3, 0, 1, 0, + 164, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 161, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 160, 0, 0, 0, 3, 0, 1, 0, + 172, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 169, 0, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 0, 0, 0, 3, 0, 1, 0, + 180, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 12, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 172, 0, 0, 0, 3, 0, 1, 0, + 184, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 0, 0, 0, 3, 0, 1, 0, + 208, 0, 0, 0, 2, 0, 1, 0, + 114, 99, 118, 84, 111, 119, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 87, 101, 101, 107, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 97, 112, 83, 101, 99, 111, + 110, 100, 115, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 101, 99, 101, 105, 118, 101, 114, + 83, 116, 97, 116, 117, 115, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 182, 170, 96, 81, 214, 56, 184, 251, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 117, 109, 77, 101, 97, 115, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 101, 97, 115, 117, 114, 101, 109, + 101, 110, 116, 115, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 1, 100, 50, 94, 95, 101, 138, 143, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_a73ba546a29820f4 = b_a73ba546a29820f4.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_a73ba546a29820f4[] = { + &s_8f8a655f5e326401, + &s_fbb838d65160aab6, +}; +static const uint16_t m_a73ba546a29820f4[] = {1, 2, 5, 4, 0, 3}; +static const uint16_t i_a73ba546a29820f4[] = {0, 1, 2, 3, 4, 5}; +const ::capnp::_::RawSchema s_a73ba546a29820f4 = { + 0xa73ba546a29820f4, b_a73ba546a29820f4.words, 124, d_a73ba546a29820f4, m_a73ba546a29820f4, + 2, 6, i_a73ba546a29820f4, nullptr, nullptr, { &s_a73ba546a29820f4, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<53> b_fbb838d65160aab6 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 182, 170, 96, 81, 214, 56, 184, 251, + 38, 0, 0, 0, 1, 0, 1, 0, + 244, 32, 152, 162, 70, 165, 59, 167, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 170, 1, 0, 0, + 45, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 85, 98, 108, 111, 120, 71, + 110, 115, 115, 46, 77, 101, 97, 115, + 117, 114, 101, 109, 101, 110, 116, 82, + 101, 112, 111, 114, 116, 46, 82, 101, + 99, 101, 105, 118, 101, 114, 83, 116, + 97, 116, 117, 115, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 0, 0, 0, 3, 0, 1, 0, + 60, 0, 0, 0, 2, 0, 1, 0, + 108, 101, 97, 112, 83, 101, 99, 86, + 97, 108, 105, 100, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 108, 107, 82, 101, 115, 101, 116, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_fbb838d65160aab6 = b_fbb838d65160aab6.words; +#if !CAPNP_LITE +static const uint16_t m_fbb838d65160aab6[] = {1, 0}; +static const uint16_t i_fbb838d65160aab6[] = {0, 1}; +const ::capnp::_::RawSchema s_fbb838d65160aab6 = { + 0xfbb838d65160aab6, b_fbb838d65160aab6.words, 53, nullptr, m_fbb838d65160aab6, + 0, 2, i_fbb838d65160aab6, nullptr, nullptr, { &s_fbb838d65160aab6, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<231> b_8f8a655f5e326401 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 1, 100, 50, 94, 95, 101, 138, 143, + 38, 0, 0, 0, 1, 0, 5, 0, + 244, 32, 152, 162, 70, 165, 59, 167, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 146, 1, 0, 0, + 45, 0, 0, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 57, 0, 0, 0, 223, 2, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 85, 98, 108, 111, 120, 71, + 110, 115, 115, 46, 77, 101, 97, 115, + 117, 114, 101, 109, 101, 110, 116, 82, + 101, 112, 111, 114, 116, 46, 77, 101, + 97, 115, 117, 114, 101, 109, 101, 110, + 116, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 1, 0, 1, 0, + 178, 153, 178, 2, 168, 179, 239, 232, + 1, 0, 0, 0, 122, 0, 0, 0, + 84, 114, 97, 99, 107, 105, 110, 103, + 83, 116, 97, 116, 117, 115, 0, 0, + 52, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 88, 1, 0, 0, 3, 0, 1, 0, + 100, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 1, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 1, 0, 0, 3, 0, 1, 0, + 108, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 1, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 1, 0, 0, 3, 0, 1, 0, + 116, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 1, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 1, 0, 0, 3, 0, 1, 0, + 124, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 1, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 1, 0, 0, 3, 0, 1, 0, + 128, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 1, 0, 0, 3, 0, 1, 0, + 132, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 129, 1, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 132, 1, 0, 0, 3, 0, 1, 0, + 144, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 12, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 140, 1, 0, 0, 3, 0, 1, 0, + 152, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 149, 1, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 144, 1, 0, 0, 3, 0, 1, 0, + 156, 1, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 1, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 156, 1, 0, 0, 3, 0, 1, 0, + 168, 1, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 165, 1, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 1, 0, 0, 3, 0, 1, 0, + 180, 1, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 1, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 1, 0, 0, 3, 0, 1, 0, + 188, 1, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 26, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 1, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 1, 0, 0, 3, 0, 1, 0, + 192, 1, 0, 0, 2, 0, 1, 0, + 115, 118, 73, 100, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 114, 97, 99, 107, 105, 110, 103, + 83, 116, 97, 116, 117, 115, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 178, 153, 178, 2, 168, 179, 239, 232, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 115, 101, 117, 100, 111, 114, 97, + 110, 103, 101, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 114, 105, 101, 114, 67, + 121, 99, 108, 101, 115, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 111, 112, 112, 108, 101, 114, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 110, 115, 115, 73, 100, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 108, 111, 110, 97, 115, 115, 70, + 114, 101, 113, 117, 101, 110, 99, 121, + 73, 110, 100, 101, 120, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 99, 107, 116, 105, 109, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 110, 111, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 115, 101, 117, 100, 111, 114, 97, + 110, 103, 101, 83, 116, 100, 101, 118, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 114, 105, 101, 114, 80, + 104, 97, 115, 101, 83, 116, 100, 101, + 118, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 111, 112, 112, 108, 101, 114, 83, + 116, 100, 101, 118, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 105, 103, 73, 100, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_8f8a655f5e326401 = b_8f8a655f5e326401.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_8f8a655f5e326401[] = { + &s_e8efb3a802b299b2, +}; +static const uint16_t m_8f8a655f5e326401[] = {3, 10, 8, 4, 11, 6, 5, 7, 2, 9, 12, 0, 1}; +static const uint16_t i_8f8a655f5e326401[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12}; +const ::capnp::_::RawSchema s_8f8a655f5e326401 = { + 0x8f8a655f5e326401, b_8f8a655f5e326401.words, 231, d_8f8a655f5e326401, m_8f8a655f5e326401, + 1, 13, i_8f8a655f5e326401, nullptr, nullptr, { &s_8f8a655f5e326401, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<90> b_e8efb3a802b299b2 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 178, 153, 178, 2, 168, 179, 239, 232, + 50, 0, 0, 0, 1, 0, 1, 0, + 1, 100, 50, 94, 95, 101, 138, 143, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 10, 2, 0, 0, + 53, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 0, 0, 0, 231, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 85, 98, 108, 111, 120, 71, + 110, 115, 115, 46, 77, 101, 97, 115, + 117, 114, 101, 109, 101, 110, 116, 82, + 101, 112, 111, 114, 116, 46, 77, 101, + 97, 115, 117, 114, 101, 109, 101, 110, + 116, 46, 84, 114, 97, 99, 107, 105, + 110, 103, 83, 116, 97, 116, 117, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 0, 0, 0, 3, 0, 1, 0, + 112, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 0, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 0, 0, 0, 3, 0, 1, 0, + 124, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 0, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 0, 0, 0, 3, 0, 1, 0, + 132, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 129, 0, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 132, 0, 0, 0, 3, 0, 1, 0, + 144, 0, 0, 0, 2, 0, 1, 0, + 112, 115, 101, 117, 100, 111, 114, 97, + 110, 103, 101, 86, 97, 108, 105, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 114, 105, 101, 114, 80, + 104, 97, 115, 101, 86, 97, 108, 105, + 100, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 97, 108, 102, 67, 121, 99, 108, + 101, 86, 97, 108, 105, 100, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 97, 108, 102, 67, 121, 99, 108, + 101, 83, 117, 98, 116, 114, 97, 99, + 116, 101, 100, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e8efb3a802b299b2 = b_e8efb3a802b299b2.words; +#if !CAPNP_LITE +static const uint16_t m_e8efb3a802b299b2[] = {1, 3, 2, 0}; +static const uint16_t i_e8efb3a802b299b2[] = {0, 1, 2, 3}; +const ::capnp::_::RawSchema s_e8efb3a802b299b2 = { + 0xe8efb3a802b299b2, b_e8efb3a802b299b2.words, 90, nullptr, m_e8efb3a802b299b2, + 0, 4, i_e8efb3a802b299b2, nullptr, nullptr, { &s_e8efb3a802b299b2, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<682> b_d8418c788118f85c = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 92, 248, 24, 129, 120, 140, 65, 216, + 20, 0, 0, 0, 1, 0, 34, 0, + 93, 250, 206, 230, 124, 221, 221, 133, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 242, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 111, 9, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 85, 98, 108, 111, 120, 71, + 110, 115, 115, 46, 69, 112, 104, 101, + 109, 101, 114, 105, 115, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 172, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 165, 4, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 160, 4, 0, 0, 3, 0, 1, 0, + 172, 4, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 169, 4, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 164, 4, 0, 0, 3, 0, 1, 0, + 176, 4, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 173, 4, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 4, 0, 0, 3, 0, 1, 0, + 180, 4, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 4, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 172, 4, 0, 0, 3, 0, 1, 0, + 184, 4, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 4, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 4, 0, 0, 3, 0, 1, 0, + 188, 4, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 4, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 4, 0, 0, 3, 0, 1, 0, + 192, 4, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 4, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 4, 0, 0, 3, 0, 1, 0, + 196, 4, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 4, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 4, 0, 0, 3, 0, 1, 0, + 200, 4, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 4, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 192, 4, 0, 0, 3, 0, 1, 0, + 204, 4, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 4, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 4, 0, 0, 3, 0, 1, 0, + 208, 4, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 4, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 200, 4, 0, 0, 3, 0, 1, 0, + 212, 4, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 4, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 4, 0, 0, 3, 0, 1, 0, + 216, 4, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 4, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 4, 0, 0, 3, 0, 1, 0, + 220, 4, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 217, 4, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 212, 4, 0, 0, 3, 0, 1, 0, + 224, 4, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 4, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 4, 0, 0, 3, 0, 1, 0, + 228, 4, 0, 0, 2, 0, 1, 0, + 15, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 15, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 225, 4, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 220, 4, 0, 0, 3, 0, 1, 0, + 232, 4, 0, 0, 2, 0, 1, 0, + 16, 0, 0, 0, 11, 0, 0, 0, + 0, 0, 1, 0, 16, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 4, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 224, 4, 0, 0, 3, 0, 1, 0, + 236, 4, 0, 0, 2, 0, 1, 0, + 17, 0, 0, 0, 12, 0, 0, 0, + 0, 0, 1, 0, 17, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 233, 4, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 228, 4, 0, 0, 3, 0, 1, 0, + 240, 4, 0, 0, 2, 0, 1, 0, + 18, 0, 0, 0, 13, 0, 0, 0, + 0, 0, 1, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 4, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 4, 0, 0, 3, 0, 1, 0, + 244, 4, 0, 0, 2, 0, 1, 0, + 19, 0, 0, 0, 14, 0, 0, 0, + 0, 0, 1, 0, 19, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 4, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 236, 4, 0, 0, 3, 0, 1, 0, + 248, 4, 0, 0, 2, 0, 1, 0, + 20, 0, 0, 0, 15, 0, 0, 0, + 0, 0, 1, 0, 20, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 245, 4, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 4, 0, 0, 3, 0, 1, 0, + 252, 4, 0, 0, 2, 0, 1, 0, + 21, 0, 0, 0, 16, 0, 0, 0, + 0, 0, 1, 0, 21, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 249, 4, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 244, 4, 0, 0, 3, 0, 1, 0, + 0, 5, 0, 0, 2, 0, 1, 0, + 22, 0, 0, 0, 17, 0, 0, 0, + 0, 0, 1, 0, 22, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 253, 4, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 248, 4, 0, 0, 3, 0, 1, 0, + 4, 5, 0, 0, 2, 0, 1, 0, + 23, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 1, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 5, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 252, 4, 0, 0, 3, 0, 1, 0, + 8, 5, 0, 0, 2, 0, 1, 0, + 24, 0, 0, 0, 19, 0, 0, 0, + 0, 0, 1, 0, 24, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 5, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 5, 0, 0, 3, 0, 1, 0, + 12, 5, 0, 0, 2, 0, 1, 0, + 25, 0, 0, 0, 20, 0, 0, 0, + 0, 0, 1, 0, 25, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 5, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 5, 0, 0, 3, 0, 1, 0, + 20, 5, 0, 0, 2, 0, 1, 0, + 26, 0, 0, 0, 21, 0, 0, 0, + 0, 0, 1, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 5, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 5, 0, 0, 3, 0, 1, 0, + 24, 5, 0, 0, 2, 0, 1, 0, + 27, 0, 0, 0, 22, 0, 0, 0, + 0, 0, 1, 0, 27, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 5, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 5, 0, 0, 3, 0, 1, 0, + 28, 5, 0, 0, 2, 0, 1, 0, + 28, 0, 0, 0, 23, 0, 0, 0, + 0, 0, 1, 0, 28, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 5, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 28, 5, 0, 0, 3, 0, 1, 0, + 40, 5, 0, 0, 2, 0, 1, 0, + 29, 0, 0, 0, 24, 0, 0, 0, + 0, 0, 1, 0, 29, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 5, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 5, 0, 0, 3, 0, 1, 0, + 44, 5, 0, 0, 2, 0, 1, 0, + 30, 0, 0, 0, 25, 0, 0, 0, + 0, 0, 1, 0, 30, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 5, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 5, 0, 0, 3, 0, 1, 0, + 48, 5, 0, 0, 2, 0, 1, 0, + 31, 0, 0, 0, 26, 0, 0, 0, + 0, 0, 1, 0, 31, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 5, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 5, 0, 0, 3, 0, 1, 0, + 56, 5, 0, 0, 2, 0, 1, 0, + 32, 0, 0, 0, 27, 0, 0, 0, + 0, 0, 1, 0, 32, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 53, 5, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 5, 0, 0, 3, 0, 1, 0, + 60, 5, 0, 0, 2, 0, 1, 0, + 33, 0, 0, 0, 28, 0, 0, 0, + 0, 0, 1, 0, 33, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 57, 5, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 52, 5, 0, 0, 3, 0, 1, 0, + 64, 5, 0, 0, 2, 0, 1, 0, + 34, 0, 0, 0, 29, 0, 0, 0, + 0, 0, 1, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 5, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 5, 0, 0, 3, 0, 1, 0, + 76, 5, 0, 0, 2, 0, 1, 0, + 35, 0, 0, 0, 30, 0, 0, 0, + 0, 0, 1, 0, 35, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 5, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 5, 0, 0, 3, 0, 1, 0, + 84, 5, 0, 0, 2, 0, 1, 0, + 36, 0, 0, 0, 31, 0, 0, 0, + 0, 0, 1, 0, 36, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 81, 5, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 5, 0, 0, 3, 0, 1, 0, + 88, 5, 0, 0, 2, 0, 1, 0, + 37, 0, 0, 0, 0, 8, 0, 0, + 0, 0, 1, 0, 37, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 85, 5, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 84, 5, 0, 0, 3, 0, 1, 0, + 96, 5, 0, 0, 2, 0, 1, 0, + 38, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 38, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 5, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 5, 0, 0, 3, 0, 1, 0, + 120, 5, 0, 0, 2, 0, 1, 0, + 39, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 39, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 5, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 5, 0, 0, 3, 0, 1, 0, + 144, 5, 0, 0, 2, 0, 1, 0, + 40, 0, 0, 0, 65, 0, 0, 0, + 0, 0, 1, 0, 40, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 5, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 140, 5, 0, 0, 3, 0, 1, 0, + 152, 5, 0, 0, 2, 0, 1, 0, + 41, 0, 0, 0, 129, 0, 0, 0, + 0, 0, 1, 0, 41, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 149, 5, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 144, 5, 0, 0, 3, 0, 1, 0, + 156, 5, 0, 0, 2, 0, 1, 0, + 42, 0, 0, 0, 132, 0, 0, 0, + 0, 0, 1, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 5, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 5, 0, 0, 3, 0, 1, 0, + 160, 5, 0, 0, 2, 0, 1, 0, + 115, 118, 73, 100, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 101, 97, 114, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 111, 110, 116, 104, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 97, 121, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 111, 117, 114, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 105, 110, 117, 116, 101, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 101, 99, 111, 110, 100, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 102, 48, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 102, 49, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 102, 50, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 111, 100, 101, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 114, 115, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 108, 116, 97, 78, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 48, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 99, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 99, 99, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 115, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 111, 101, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 105, 99, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 109, 101, 103, 97, 48, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 105, 115, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 48, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 114, 99, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 109, 101, 103, 97, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 109, 101, 103, 97, 68, 111, 116, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 68, 111, 116, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 111, 100, 101, 115, 76, 50, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 87, 101, 101, 107, 68, + 69, 80, 82, 69, 67, 65, 84, 69, + 68, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 50, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 118, 65, 99, 99, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 118, 72, 101, 97, 108, 116, 104, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 103, 100, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 111, 100, 99, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 114, 97, 110, 115, 109, 105, 115, + 115, 105, 111, 110, 84, 105, 109, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 105, 116, 73, 110, 116, 101, 114, + 118, 97, 108, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 111, 99, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 111, 110, 111, 67, 111, 101, 102, + 102, 115, 86, 97, 108, 105, 100, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 111, 110, 111, 65, 108, 112, 104, + 97, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 111, 110, 111, 66, 101, 116, 97, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 111, 119, 67, 111, 117, 110, 116, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 111, 101, 87, 101, 101, 107, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 111, 99, 87, 101, 101, 107, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_d8418c788118f85c = b_d8418c788118f85c.words; +#if !CAPNP_LITE +static const uint16_t m_d8418c788118f85c[] = {17, 7, 8, 9, 19, 21, 27, 23, 11, 14, 16, 3, 12, 15, 35, 28, 4, 22, 26, 33, 10, 38, 39, 37, 29, 13, 5, 2, 24, 20, 25, 6, 30, 31, 0, 32, 36, 42, 18, 41, 40, 34, 1}; +static const uint16_t i_d8418c788118f85c[] = {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, 37, 38, 39, 40, 41, 42}; +const ::capnp::_::RawSchema s_d8418c788118f85c = { + 0xd8418c788118f85c, b_d8418c788118f85c.words, 682, nullptr, m_d8418c788118f85c, + 0, 43, i_d8418c788118f85c, nullptr, nullptr, { &s_d8418c788118f85c, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<136> b_c3a3a8de519a4a26 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 38, 74, 154, 81, 222, 168, 163, 195, + 20, 0, 0, 0, 1, 0, 3, 0, + 93, 250, 206, 230, 124, 221, 221, 133, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 234, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 143, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 85, 98, 108, 111, 120, 71, + 110, 115, 115, 46, 73, 111, 110, 111, + 68, 97, 116, 97, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 28, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 0, 0, 0, 3, 0, 1, 0, + 192, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 0, 0, 0, 3, 0, 1, 0, + 196, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 0, 0, 0, 3, 0, 1, 0, + 200, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 0, 0, 0, 3, 0, 1, 0, + 224, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 220, 0, 0, 0, 3, 0, 1, 0, + 248, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 32, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 245, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 244, 0, 0, 0, 3, 0, 1, 0, + 0, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 33, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 253, 0, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 252, 0, 0, 0, 3, 0, 1, 0, + 8, 1, 0, 0, 2, 0, 1, 0, + 115, 118, 72, 101, 97, 108, 116, 104, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 111, 119, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 87, 101, 101, 107, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 111, 110, 111, 65, 108, 112, 104, + 97, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 111, 110, 111, 66, 101, 116, 97, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 101, 97, 108, 116, 104, 86, 97, + 108, 105, 100, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 111, 110, 111, 67, 111, 101, 102, + 102, 115, 86, 97, 108, 105, 100, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_c3a3a8de519a4a26 = b_c3a3a8de519a4a26.words; +#if !CAPNP_LITE +static const uint16_t m_c3a3a8de519a4a26[] = {2, 5, 3, 4, 6, 0, 1}; +static const uint16_t i_c3a3a8de519a4a26[] = {0, 1, 2, 3, 4, 5, 6}; +const ::capnp::_::RawSchema s_c3a3a8de519a4a26 = { + 0xc3a3a8de519a4a26, b_c3a3a8de519a4a26.words, 136, nullptr, m_c3a3a8de519a4a26, + 0, 7, i_c3a3a8de519a4a26, nullptr, nullptr, { &s_c3a3a8de519a4a26, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<119> b_ebb036b114275aa8 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 168, 90, 39, 20, 177, 54, 176, 235, + 20, 0, 0, 0, 1, 0, 2, 0, + 93, 250, 206, 230, 124, 221, 221, 133, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 234, 0, 0, 0, + 33, 0, 0, 0, 39, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 87, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 85, 98, 108, 111, 120, 71, + 110, 115, 115, 46, 72, 119, 83, 116, + 97, 116, 117, 115, 0, 0, 0, 0, + 8, 0, 0, 0, 1, 0, 1, 0, + 83, 91, 77, 171, 40, 17, 62, 194, + 9, 0, 0, 0, 186, 0, 0, 0, + 89, 101, 228, 36, 169, 81, 59, 254, + 13, 0, 0, 0, 154, 0, 0, 0, + 65, 110, 116, 101, 110, 110, 97, 83, + 117, 112, 101, 114, 118, 105, 115, 111, + 114, 83, 116, 97, 116, 101, 0, 0, + 65, 110, 116, 101, 110, 110, 97, 80, + 111, 119, 101, 114, 83, 116, 97, 116, + 117, 115, 0, 0, 0, 0, 0, 0, + 24, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 152, 0, 0, 0, 3, 0, 1, 0, + 164, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 161, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 156, 0, 0, 0, 3, 0, 1, 0, + 168, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 165, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 160, 0, 0, 0, 3, 0, 1, 0, + 172, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 169, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 164, 0, 0, 0, 3, 0, 1, 0, + 176, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 173, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 0, 0, 0, 3, 0, 1, 0, + 180, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 172, 0, 0, 0, 3, 0, 1, 0, + 184, 0, 0, 0, 2, 0, 1, 0, + 110, 111, 105, 115, 101, 80, 101, 114, + 77, 83, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 103, 99, 67, 110, 116, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 83, 116, 97, 116, 117, 115, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 83, 91, 77, 171, 40, 17, 62, 194, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 80, 111, 119, 101, 114, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 89, 101, 228, 36, 169, 81, 59, 254, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 106, 97, 109, 73, 110, 100, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 108, 97, 103, 115, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_ebb036b114275aa8 = b_ebb036b114275aa8.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_ebb036b114275aa8[] = { + &s_c23e1128ab4d5b53, + &s_fe3b51a924e46559, +}; +static const uint16_t m_ebb036b114275aa8[] = {3, 2, 1, 5, 4, 0}; +static const uint16_t i_ebb036b114275aa8[] = {0, 1, 2, 3, 4, 5}; +const ::capnp::_::RawSchema s_ebb036b114275aa8 = { + 0xebb036b114275aa8, b_ebb036b114275aa8.words, 119, d_ebb036b114275aa8, m_ebb036b114275aa8, + 2, 6, i_ebb036b114275aa8, nullptr, nullptr, { &s_ebb036b114275aa8, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<42> b_c23e1128ab4d5b53 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 83, 91, 77, 171, 40, 17, 62, 194, + 29, 0, 0, 0, 2, 0, 0, 0, + 168, 90, 39, 20, 177, 54, 176, 235, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 162, 1, 0, 0, + 45, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 127, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 85, 98, 108, 111, 120, 71, + 110, 115, 115, 46, 72, 119, 83, 116, + 97, 116, 117, 115, 46, 65, 110, 116, + 101, 110, 110, 97, 83, 117, 112, 101, + 114, 118, 105, 115, 111, 114, 83, 116, + 97, 116, 101, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 20, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 53, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 110, 105, 116, 0, 0, 0, 0, + 100, 111, 110, 116, 107, 110, 111, 119, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 107, 0, 0, 0, 0, 0, 0, + 115, 104, 111, 114, 116, 0, 0, 0, + 111, 112, 101, 110, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_c23e1128ab4d5b53 = b_c23e1128ab4d5b53.words; +#if !CAPNP_LITE +static const uint16_t m_c23e1128ab4d5b53[] = {1, 0, 2, 4, 3}; +const ::capnp::_::RawSchema s_c23e1128ab4d5b53 = { + 0xc23e1128ab4d5b53, b_c23e1128ab4d5b53.words, 42, nullptr, m_c23e1128ab4d5b53, + 0, 5, nullptr, nullptr, nullptr, { &s_c23e1128ab4d5b53, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(AntennaSupervisorState_c23e1128ab4d5b53, c23e1128ab4d5b53); +static const ::capnp::_::AlignedData<33> b_fe3b51a924e46559 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 89, 101, 228, 36, 169, 81, 59, 254, + 29, 0, 0, 0, 2, 0, 0, 0, + 168, 90, 39, 20, 177, 54, 176, 235, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 130, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 79, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 85, 98, 108, 111, 120, 71, + 110, 115, 115, 46, 72, 119, 83, 116, + 97, 116, 117, 115, 46, 65, 110, 116, + 101, 110, 110, 97, 80, 111, 119, 101, + 114, 83, 116, 97, 116, 117, 115, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 102, 102, 0, 0, 0, 0, 0, + 111, 110, 0, 0, 0, 0, 0, 0, + 100, 111, 110, 116, 107, 110, 111, 119, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_fe3b51a924e46559 = b_fe3b51a924e46559.words; +#if !CAPNP_LITE +static const uint16_t m_fe3b51a924e46559[] = {2, 0, 1}; +const ::capnp::_::RawSchema s_fe3b51a924e46559 = { + 0xfe3b51a924e46559, b_fe3b51a924e46559.words, 33, nullptr, m_fe3b51a924e46559, + 0, 3, nullptr, nullptr, nullptr, { &s_fe3b51a924e46559, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(AntennaPowerStatus_fe3b51a924e46559, fe3b51a924e46559); +static const ::capnp::_::AlignedData<130> b_f919b410b90e53c6 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 198, 83, 14, 185, 16, 180, 25, 249, + 20, 0, 0, 0, 1, 0, 2, 0, + 93, 250, 206, 230, 124, 221, 221, 133, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 242, 0, 0, 0, + 33, 0, 0, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 143, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 85, 98, 108, 111, 120, 71, + 110, 115, 115, 46, 72, 119, 83, 116, + 97, 116, 117, 115, 50, 0, 0, 0, + 4, 0, 0, 0, 1, 0, 1, 0, + 185, 151, 28, 181, 94, 152, 208, 178, + 1, 0, 0, 0, 106, 0, 0, 0, + 67, 111, 110, 102, 105, 103, 83, 111, + 117, 114, 99, 101, 0, 0, 0, 0, + 28, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 0, 0, 0, 3, 0, 1, 0, + 188, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 0, 0, 0, 3, 0, 1, 0, + 192, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 0, 0, 0, 3, 0, 1, 0, + 196, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 0, 0, 0, 3, 0, 1, 0, + 200, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 0, 0, 0, 3, 0, 1, 0, + 208, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 0, 0, 0, 3, 0, 1, 0, + 216, 0, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 212, 0, 0, 0, 3, 0, 1, 0, + 224, 0, 0, 0, 2, 0, 1, 0, + 111, 102, 115, 73, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 97, 103, 73, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 102, 115, 81, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 97, 103, 81, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 102, 103, 83, 111, 117, 114, 99, + 101, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 185, 151, 28, 181, 94, 152, 208, 178, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 119, 76, 101, 118, 67, 102, + 103, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 115, 116, 83, 116, 97, 116, + 117, 115, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_f919b410b90e53c6 = b_f919b410b90e53c6.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_f919b410b90e53c6[] = { + &s_b2d0985eb51c97b9, +}; +static const uint16_t m_f919b410b90e53c6[] = {4, 5, 1, 3, 0, 2, 6}; +static const uint16_t i_f919b410b90e53c6[] = {0, 1, 2, 3, 4, 5, 6}; +const ::capnp::_::RawSchema s_f919b410b90e53c6 = { + 0xf919b410b90e53c6, b_f919b410b90e53c6.words, 130, d_f919b410b90e53c6, m_f919b410b90e53c6, + 1, 7, i_f919b410b90e53c6, nullptr, nullptr, { &s_f919b410b90e53c6, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<42> b_b2d0985eb51c97b9 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 185, 151, 28, 181, 94, 152, 208, 178, + 30, 0, 0, 0, 2, 0, 0, 0, + 198, 83, 14, 185, 16, 180, 25, 249, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 90, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 127, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 85, 98, 108, 111, 120, 71, + 110, 115, 115, 46, 72, 119, 83, 116, + 97, 116, 117, 115, 50, 46, 67, 111, + 110, 102, 105, 103, 83, 111, 117, 114, + 99, 101, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 20, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 53, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 49, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 110, 100, 101, 102, 105, 110, 101, + 100, 0, 0, 0, 0, 0, 0, 0, + 114, 111, 109, 0, 0, 0, 0, 0, + 111, 116, 112, 0, 0, 0, 0, 0, + 99, 111, 110, 102, 105, 103, 112, 105, + 110, 115, 0, 0, 0, 0, 0, 0, + 102, 108, 97, 115, 104, 0, 0, 0, } +}; +::capnp::word const* const bp_b2d0985eb51c97b9 = b_b2d0985eb51c97b9.words; +#if !CAPNP_LITE +static const uint16_t m_b2d0985eb51c97b9[] = {3, 4, 2, 1, 0}; +const ::capnp::_::RawSchema s_b2d0985eb51c97b9 = { + 0xb2d0985eb51c97b9, b_b2d0985eb51c97b9.words, 42, nullptr, m_b2d0985eb51c97b9, + 0, 5, nullptr, nullptr, nullptr, { &s_b2d0985eb51c97b9, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(ConfigSource_b2d0985eb51c97b9, b2d0985eb51c97b9); +static const ::capnp::_::AlignedData<521> b_b9c5911198388e0c = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 12, 142, 56, 152, 17, 145, 197, 185, + 20, 0, 0, 0, 1, 0, 18, 0, + 93, 250, 206, 230, 124, 221, 221, 133, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 42, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 63, 7, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 85, 98, 108, 111, 120, 71, + 110, 115, 115, 46, 71, 108, 111, 110, + 97, 115, 115, 69, 112, 104, 101, 109, + 101, 114, 105, 115, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 132, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 3, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 136, 3, 0, 0, 3, 0, 1, 0, + 148, 3, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 145, 3, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 140, 3, 0, 0, 3, 0, 1, 0, + 152, 3, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 149, 3, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 3, 0, 0, 3, 0, 1, 0, + 160, 3, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 157, 3, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 152, 3, 0, 0, 3, 0, 1, 0, + 164, 3, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 161, 3, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 156, 3, 0, 0, 3, 0, 1, 0, + 168, 3, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 165, 3, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 160, 3, 0, 0, 3, 0, 1, 0, + 172, 3, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 169, 3, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 164, 3, 0, 0, 3, 0, 1, 0, + 176, 3, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 173, 3, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 3, 0, 0, 3, 0, 1, 0, + 180, 3, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 3, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 172, 3, 0, 0, 3, 0, 1, 0, + 184, 3, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 3, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 3, 0, 0, 3, 0, 1, 0, + 188, 3, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 3, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 3, 0, 0, 3, 0, 1, 0, + 192, 3, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 3, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 3, 0, 0, 3, 0, 1, 0, + 196, 3, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 3, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 3, 0, 0, 3, 0, 1, 0, + 200, 3, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 3, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 192, 3, 0, 0, 3, 0, 1, 0, + 204, 3, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 3, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 3, 0, 0, 3, 0, 1, 0, + 208, 3, 0, 0, 2, 0, 1, 0, + 15, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 15, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 3, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 200, 3, 0, 0, 3, 0, 1, 0, + 212, 3, 0, 0, 2, 0, 1, 0, + 16, 0, 0, 0, 22, 0, 0, 0, + 0, 0, 1, 0, 16, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 3, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 3, 0, 0, 3, 0, 1, 0, + 216, 3, 0, 0, 2, 0, 1, 0, + 17, 0, 0, 0, 11, 0, 0, 0, + 0, 0, 1, 0, 17, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 3, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 3, 0, 0, 3, 0, 1, 0, + 220, 3, 0, 0, 2, 0, 1, 0, + 18, 0, 0, 0, 92, 0, 0, 0, + 0, 0, 1, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 217, 3, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 3, 0, 0, 3, 0, 1, 0, + 228, 3, 0, 0, 2, 0, 1, 0, + 19, 0, 0, 0, 47, 0, 0, 0, + 0, 0, 1, 0, 19, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 225, 3, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 224, 3, 0, 0, 3, 0, 1, 0, + 236, 3, 0, 0, 2, 0, 1, 0, + 20, 0, 0, 0, 48, 0, 0, 0, + 0, 0, 1, 0, 20, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 233, 3, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 228, 3, 0, 0, 3, 0, 1, 0, + 240, 3, 0, 0, 2, 0, 1, 0, + 21, 0, 0, 0, 13, 0, 0, 0, + 0, 0, 1, 0, 21, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 3, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 3, 0, 0, 3, 0, 1, 0, + 244, 3, 0, 0, 2, 0, 1, 0, + 22, 0, 0, 0, 14, 0, 0, 0, + 0, 0, 1, 0, 22, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 3, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 3, 0, 0, 3, 0, 1, 0, + 252, 3, 0, 0, 2, 0, 1, 0, + 23, 0, 0, 0, 15, 0, 0, 0, + 0, 0, 1, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 249, 3, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 244, 3, 0, 0, 3, 0, 1, 0, + 0, 4, 0, 0, 2, 0, 1, 0, + 24, 0, 0, 0, 93, 0, 0, 0, + 0, 0, 1, 0, 24, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 253, 3, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 248, 3, 0, 0, 3, 0, 1, 0, + 4, 4, 0, 0, 2, 0, 1, 0, + 25, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 1, 0, 25, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 4, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 252, 3, 0, 0, 3, 0, 1, 0, + 8, 4, 0, 0, 2, 0, 1, 0, + 26, 0, 0, 0, 99, 0, 0, 0, + 0, 0, 1, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 4, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 4, 0, 0, 3, 0, 1, 0, + 12, 4, 0, 0, 2, 0, 1, 0, + 27, 0, 0, 0, 100, 0, 0, 0, + 0, 0, 1, 0, 27, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 4, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 4, 0, 0, 3, 0, 1, 0, + 16, 4, 0, 0, 2, 0, 1, 0, + 28, 0, 0, 0, 32, 0, 0, 0, + 0, 0, 1, 0, 28, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 4, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 4, 0, 0, 3, 0, 1, 0, + 28, 4, 0, 0, 2, 0, 1, 0, + 29, 0, 0, 0, 101, 0, 0, 0, + 0, 0, 1, 0, 29, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 4, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 4, 0, 0, 3, 0, 1, 0, + 32, 4, 0, 0, 2, 0, 1, 0, + 30, 0, 0, 0, 51, 0, 0, 0, + 0, 0, 1, 0, 30, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 4, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 24, 4, 0, 0, 3, 0, 1, 0, + 36, 4, 0, 0, 2, 0, 1, 0, + 31, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 1, 0, 31, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 4, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 28, 4, 0, 0, 3, 0, 1, 0, + 40, 4, 0, 0, 2, 0, 1, 0, + 32, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 1, 0, 32, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 4, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 4, 0, 0, 3, 0, 1, 0, + 48, 4, 0, 0, 2, 0, 1, 0, + 115, 118, 73, 100, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 101, 97, 114, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 97, 121, 73, 110, 89, 101, 97, + 114, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 111, 117, 114, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 105, 110, 117, 116, 101, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 101, 99, 111, 110, 100, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 86, 101, 108, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 65, 99, 99, 101, 108, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 86, 101, 108, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 65, 99, 99, 101, 108, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 122, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 122, 86, 101, 108, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 122, 65, 99, 99, 101, 108, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 118, 84, 121, 112, 101, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 118, 85, 82, 65, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 103, 101, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 118, 72, 101, 97, 108, 116, 104, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 107, 68, 69, 80, 82, 69, 67, + 65, 84, 69, 68, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 98, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 97, 117, 78, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 108, 116, 97, 84, 97, 117, + 78, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 97, 109, 109, 97, 78, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 49, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 50, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 51, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 52, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 114, 101, 113, 78, 117, 109, 68, + 69, 80, 82, 69, 67, 65, 84, 69, + 68, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 52, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 116, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 114, 101, 113, 78, 117, 109, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 107, 83, 101, 99, 111, 110, 100, + 115, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_b9c5911198388e0c = b_b9c5911198388e0c.words; +#if !CAPNP_LITE +static const uint16_t m_b9c5911198388e0c[] = {17, 2, 22, 31, 28, 23, 3, 4, 29, 30, 24, 25, 26, 27, 5, 18, 0, 15, 16, 21, 20, 19, 32, 6, 8, 7, 9, 11, 10, 1, 12, 14, 13}; +static const uint16_t i_b9c5911198388e0c[] = {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}; +const ::capnp::_::RawSchema s_b9c5911198388e0c = { + 0xb9c5911198388e0c, b_b9c5911198388e0c.words, 521, nullptr, m_b9c5911198388e0c, + 0, 33, i_b9c5911198388e0c, nullptr, nullptr, { &s_b9c5911198388e0c, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<146> b_de94674b07ae51c1 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 193, 81, 174, 7, 75, 103, 148, 222, + 10, 0, 0, 0, 1, 0, 2, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 1, 0, 7, 0, 0, 0, 5, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 154, 0, 0, 0, + 29, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 157, 0, 0, 0, 87, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 81, 99, 111, 109, 71, 110, + 115, 115, 0, 0, 0, 0, 0, 0, + 28, 0, 0, 0, 1, 0, 1, 0, + 238, 167, 173, 250, 182, 18, 26, 215, + 49, 0, 0, 0, 146, 0, 0, 0, + 233, 131, 108, 13, 154, 130, 30, 232, + 53, 0, 0, 0, 154, 0, 0, 0, + 59, 232, 202, 27, 14, 1, 1, 229, + 57, 0, 0, 0, 146, 0, 0, 0, + 146, 134, 123, 107, 216, 215, 128, 245, + 61, 0, 0, 0, 146, 0, 0, 0, + 11, 79, 143, 221, 74, 94, 150, 202, + 65, 0, 0, 0, 98, 0, 0, 0, + 92, 199, 198, 69, 148, 195, 83, 128, + 65, 0, 0, 0, 162, 0, 0, 0, + 112, 50, 103, 26, 129, 128, 251, 177, + 69, 0, 0, 0, 122, 0, 0, 0, + 77, 101, 97, 115, 117, 114, 101, 109, + 101, 110, 116, 83, 111, 117, 114, 99, + 101, 0, 0, 0, 0, 0, 0, 0, + 83, 86, 79, 98, 115, 101, 114, 118, + 97, 116, 105, 111, 110, 83, 116, 97, + 116, 101, 0, 0, 0, 0, 0, 0, + 77, 101, 97, 115, 117, 114, 101, 109, + 101, 110, 116, 83, 116, 97, 116, 117, + 115, 0, 0, 0, 0, 0, 0, 0, + 77, 101, 97, 115, 117, 114, 101, 109, + 101, 110, 116, 82, 101, 112, 111, 114, + 116, 0, 0, 0, 0, 0, 0, 0, + 67, 108, 111, 99, 107, 82, 101, 112, + 111, 114, 116, 0, 0, 0, 0, 0, + 68, 114, 77, 101, 97, 115, 117, 114, + 101, 109, 101, 110, 116, 82, 101, 112, + 111, 114, 116, 0, 0, 0, 0, 0, + 68, 114, 83, 118, 80, 111, 108, 121, + 82, 101, 112, 111, 114, 116, 0, 0, + 24, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 0, 0, 0, 3, 0, 1, 0, + 160, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 255, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 157, 0, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 160, 0, 0, 0, 3, 0, 1, 0, + 172, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 254, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 169, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 0, 0, 0, 3, 0, 1, 0, + 180, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 253, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 0, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 0, 0, 0, 3, 0, 1, 0, + 192, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 252, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 0, 0, 0, 3, 0, 1, 0, + 200, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 251, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 192, 0, 0, 0, 3, 0, 1, 0, + 204, 0, 0, 0, 2, 0, 1, 0, + 108, 111, 103, 84, 115, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 101, 97, 115, 117, 114, 101, 109, + 101, 110, 116, 82, 101, 112, 111, 114, + 116, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 146, 134, 123, 107, 216, 215, 128, 245, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 108, 111, 99, 107, 82, 101, 112, + 111, 114, 116, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 11, 79, 143, 221, 74, 94, 150, 202, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 114, 77, 101, 97, 115, 117, 114, + 101, 109, 101, 110, 116, 82, 101, 112, + 111, 114, 116, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 92, 199, 198, 69, 148, 195, 83, 128, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 114, 83, 118, 80, 111, 108, 121, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 112, 50, 103, 26, 129, 128, 251, 177, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 97, 119, 76, 111, 103, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_de94674b07ae51c1 = b_de94674b07ae51c1.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_de94674b07ae51c1[] = { + &s_8053c39445c6c75c, + &s_b1fb80811a673270, + &s_ca965e4add8f4f0b, + &s_f580d7d86b7b8692, +}; +static const uint16_t m_de94674b07ae51c1[] = {2, 3, 4, 0, 1, 5}; +static const uint16_t i_de94674b07ae51c1[] = {1, 2, 3, 4, 5, 0}; +const ::capnp::_::RawSchema s_de94674b07ae51c1 = { + 0xde94674b07ae51c1, b_de94674b07ae51c1.words, 146, d_de94674b07ae51c1, m_de94674b07ae51c1, + 4, 6, i_de94674b07ae51c1, nullptr, nullptr, { &s_de94674b07ae51c1, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<50> b_d71a12b6faada7ee = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 238, 167, 173, 250, 182, 18, 26, 215, + 19, 0, 0, 0, 2, 0, 0, 0, + 193, 81, 174, 7, 75, 103, 148, 222, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 42, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 81, 99, 111, 109, 71, 110, + 115, 115, 46, 77, 101, 97, 115, 117, + 114, 101, 109, 101, 110, 116, 83, 111, + 117, 114, 99, 101, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 28, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 61, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 53, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 49, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 0, 0, 0, 0, 0, + 103, 108, 111, 110, 97, 115, 115, 0, + 98, 101, 105, 100, 111, 117, 0, 0, + 117, 110, 107, 110, 111, 119, 110, 51, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 110, 107, 110, 111, 119, 110, 52, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 110, 107, 110, 111, 119, 110, 53, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 98, 97, 115, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_d71a12b6faada7ee = b_d71a12b6faada7ee.words; +#if !CAPNP_LITE +static const uint16_t m_d71a12b6faada7ee[] = {2, 1, 0, 6, 3, 4, 5}; +const ::capnp::_::RawSchema s_d71a12b6faada7ee = { + 0xd71a12b6faada7ee, b_d71a12b6faada7ee.words, 50, nullptr, m_d71a12b6faada7ee, + 0, 7, nullptr, nullptr, nullptr, { &s_d71a12b6faada7ee, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(MeasurementSource_d71a12b6faada7ee, d71a12b6faada7ee); +static const ::capnp::_::AlignedData<63> b_e81e829a0d6c83e9 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 233, 131, 108, 13, 154, 130, 30, 232, + 19, 0, 0, 0, 2, 0, 0, 0, + 193, 81, 174, 7, 75, 103, 148, 222, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 50, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 247, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 81, 99, 111, 109, 71, 110, + 115, 115, 46, 83, 86, 79, 98, 115, + 101, 114, 118, 97, 116, 105, 111, 110, + 83, 116, 97, 116, 101, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 40, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 105, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 93, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 85, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 81, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 73, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 65, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 57, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 53, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 100, 108, 101, 0, 0, 0, 0, + 115, 101, 97, 114, 99, 104, 0, 0, + 115, 101, 97, 114, 99, 104, 86, 101, + 114, 105, 102, 121, 0, 0, 0, 0, + 98, 105, 116, 69, 100, 103, 101, 0, + 116, 114, 97, 99, 107, 86, 101, 114, + 105, 102, 121, 0, 0, 0, 0, 0, + 116, 114, 97, 99, 107, 0, 0, 0, + 114, 101, 115, 116, 97, 114, 116, 0, + 100, 112, 111, 0, 0, 0, 0, 0, + 103, 108, 111, 49, 48, 109, 115, 66, + 101, 0, 0, 0, 0, 0, 0, 0, + 103, 108, 111, 49, 48, 109, 115, 65, + 116, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e81e829a0d6c83e9 = b_e81e829a0d6c83e9.words; +#if !CAPNP_LITE +static const uint16_t m_e81e829a0d6c83e9[] = {3, 7, 9, 8, 0, 6, 1, 2, 5, 4}; +const ::capnp::_::RawSchema s_e81e829a0d6c83e9 = { + 0xe81e829a0d6c83e9, b_e81e829a0d6c83e9.words, 63, nullptr, m_e81e829a0d6c83e9, + 0, 10, nullptr, nullptr, nullptr, { &s_e81e829a0d6c83e9, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(SVObservationState_e81e829a0d6c83e9, e81e829a0d6c83e9); +static const ::capnp::_::AlignedData<522> b_e501010e1bcae83b = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 59, 232, 202, 27, 14, 1, 1, 229, + 19, 0, 0, 0, 1, 0, 1, 0, + 193, 81, 174, 7, 75, 103, 148, 222, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 42, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 95, 6, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 81, 99, 111, 109, 71, 110, + 115, 115, 46, 77, 101, 97, 115, 117, + 114, 101, 109, 101, 110, 116, 83, 116, + 97, 116, 117, 115, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 116, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 3, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 3, 0, 0, 3, 0, 1, 0, + 44, 3, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 3, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 3, 0, 0, 3, 0, 1, 0, + 56, 3, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 53, 3, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 56, 3, 0, 0, 3, 0, 1, 0, + 68, 3, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 65, 3, 0, 0, 218, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 3, 0, 0, 3, 0, 1, 0, + 84, 3, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 81, 3, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 84, 3, 0, 0, 3, 0, 1, 0, + 96, 3, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 3, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 3, 0, 0, 3, 0, 1, 0, + 108, 3, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 3, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 3, 0, 0, 3, 0, 1, 0, + 116, 3, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 3, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 3, 0, 0, 3, 0, 1, 0, + 128, 3, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 3, 0, 0, 202, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 132, 3, 0, 0, 3, 0, 1, 0, + 144, 3, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 3, 0, 0, 10, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 152, 3, 0, 0, 3, 0, 1, 0, + 164, 3, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 161, 3, 0, 0, 18, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 172, 3, 0, 0, 3, 0, 1, 0, + 184, 3, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 11, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 3, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 3, 0, 0, 3, 0, 1, 0, + 196, 3, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 12, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 3, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 3, 0, 0, 3, 0, 1, 0, + 208, 3, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 13, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 3, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 3, 0, 0, 3, 0, 1, 0, + 220, 3, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 14, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 217, 3, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 3, 0, 0, 3, 0, 1, 0, + 228, 3, 0, 0, 2, 0, 1, 0, + 15, 0, 0, 0, 15, 0, 0, 0, + 0, 0, 1, 0, 15, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 225, 3, 0, 0, 218, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 3, 0, 0, 3, 0, 1, 0, + 244, 3, 0, 0, 2, 0, 1, 0, + 16, 0, 0, 0, 16, 0, 0, 0, + 0, 0, 1, 0, 16, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 3, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 244, 3, 0, 0, 3, 0, 1, 0, + 0, 4, 0, 0, 2, 0, 1, 0, + 17, 0, 0, 0, 17, 0, 0, 0, + 0, 0, 1, 0, 17, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 253, 3, 0, 0, 202, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 4, 0, 0, 3, 0, 1, 0, + 16, 4, 0, 0, 2, 0, 1, 0, + 18, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 1, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 4, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 4, 0, 0, 3, 0, 1, 0, + 24, 4, 0, 0, 2, 0, 1, 0, + 19, 0, 0, 0, 19, 0, 0, 0, + 0, 0, 1, 0, 19, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 4, 0, 0, 26, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 4, 0, 0, 3, 0, 1, 0, + 44, 4, 0, 0, 2, 0, 1, 0, + 20, 0, 0, 0, 20, 0, 0, 0, + 0, 0, 1, 0, 20, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 4, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 4, 0, 0, 3, 0, 1, 0, + 56, 4, 0, 0, 2, 0, 1, 0, + 21, 0, 0, 0, 21, 0, 0, 0, + 0, 0, 1, 0, 21, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 53, 4, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 56, 4, 0, 0, 3, 0, 1, 0, + 68, 4, 0, 0, 2, 0, 1, 0, + 22, 0, 0, 0, 22, 0, 0, 0, + 0, 0, 1, 0, 22, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 65, 4, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 4, 0, 0, 3, 0, 1, 0, + 80, 4, 0, 0, 2, 0, 1, 0, + 23, 0, 0, 0, 23, 0, 0, 0, + 0, 0, 1, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 4, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 80, 4, 0, 0, 3, 0, 1, 0, + 92, 4, 0, 0, 2, 0, 1, 0, + 24, 0, 0, 0, 24, 0, 0, 0, + 0, 0, 1, 0, 24, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 89, 4, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 4, 0, 0, 3, 0, 1, 0, + 104, 4, 0, 0, 2, 0, 1, 0, + 25, 0, 0, 0, 25, 0, 0, 0, + 0, 0, 1, 0, 25, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 4, 0, 0, 202, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 4, 0, 0, 3, 0, 1, 0, + 120, 4, 0, 0, 2, 0, 1, 0, + 26, 0, 0, 0, 26, 0, 0, 0, + 0, 0, 1, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 4, 0, 0, 210, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 4, 0, 0, 3, 0, 1, 0, + 136, 4, 0, 0, 2, 0, 1, 0, + 27, 0, 0, 0, 27, 0, 0, 0, + 0, 0, 1, 0, 27, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 4, 0, 0, 202, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 140, 4, 0, 0, 3, 0, 1, 0, + 152, 4, 0, 0, 2, 0, 1, 0, + 28, 0, 0, 0, 28, 0, 0, 0, + 0, 0, 1, 0, 28, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 149, 4, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 152, 4, 0, 0, 3, 0, 1, 0, + 164, 4, 0, 0, 2, 0, 1, 0, + 115, 117, 98, 77, 105, 108, 108, 105, + 115, 101, 99, 111, 110, 100, 73, 115, + 86, 97, 108, 105, 100, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 117, 98, 66, 105, 116, 84, 105, + 109, 101, 73, 115, 75, 110, 111, 119, + 110, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 97, 116, 101, 108, 108, 105, 116, + 101, 84, 105, 109, 101, 73, 115, 75, + 110, 111, 119, 110, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 105, 116, 69, 100, 103, 101, 67, + 111, 110, 102, 105, 114, 109, 101, 100, + 70, 114, 111, 109, 83, 105, 103, 110, + 97, 108, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 101, 97, 115, 117, 114, 101, 100, + 86, 101, 108, 111, 99, 105, 116, 121, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 105, 110, 101, 79, 114, 67, 111, + 97, 114, 115, 101, 86, 101, 108, 111, + 99, 105, 116, 121, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 99, 107, 80, 111, 105, 110, + 116, 86, 97, 108, 105, 100, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 99, 107, 80, 111, 105, 110, + 116, 80, 111, 115, 105, 116, 105, 118, + 101, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 115, 116, 85, 112, 100, 97, + 116, 101, 70, 114, 111, 109, 68, 105, + 102, 102, 101, 114, 101, 110, 99, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 115, 116, 85, 112, 100, 97, + 116, 101, 70, 114, 111, 109, 86, 101, + 108, 111, 99, 105, 116, 121, 68, 105, + 102, 102, 101, 114, 101, 110, 99, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 114, 111, 110, 103, 73, 110, + 100, 105, 99, 97, 116, 105, 111, 110, + 79, 102, 67, 114, 111, 115, 115, 67, + 111, 114, 101, 108, 97, 116, 105, 111, + 110, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 101, 110, 116, 97, 116, 105, 118, + 101, 77, 101, 97, 115, 117, 114, 101, + 109, 101, 110, 116, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 101, 97, 115, 117, 114, 101, 109, + 101, 110, 116, 78, 111, 116, 85, 115, + 97, 98, 108, 101, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 105, 114, 67, 104, 101, 99, 107, + 73, 115, 78, 101, 101, 100, 101, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 114, 111, 98, 97, 116, 105, 111, + 110, 77, 111, 100, 101, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 108, 111, 110, 97, 115, 115, 77, + 101, 97, 110, 100, 101, 114, 66, 105, + 116, 69, 100, 103, 101, 86, 97, 108, + 105, 100, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 108, 111, 110, 97, 115, 115, 84, + 105, 109, 101, 77, 97, 114, 107, 86, + 97, 108, 105, 100, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 82, 111, 117, 110, 100, + 82, 111, 98, 105, 110, 82, 120, 68, + 105, 118, 101, 114, 115, 105, 116, 121, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 82, 120, 68, 105, 118, + 101, 114, 115, 105, 116, 121, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 76, 111, 119, 66, 97, + 110, 100, 119, 105, 100, 116, 104, 82, + 120, 68, 105, 118, 101, 114, 115, 105, + 116, 121, 67, 111, 109, 98, 105, 110, + 101, 100, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 72, 105, 103, 104, 66, + 97, 110, 100, 119, 105, 100, 116, 104, + 78, 117, 52, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 72, 105, 103, 104, 66, + 97, 110, 100, 119, 105, 100, 116, 104, + 78, 117, 56, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 72, 105, 103, 104, 66, + 97, 110, 100, 119, 105, 100, 116, 104, + 85, 110, 105, 102, 111, 114, 109, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 117, 108, 116, 105, 112, 97, 116, + 104, 73, 110, 100, 105, 99, 97, 116, + 111, 114, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 109, 100, 74, 97, 109, 109, 105, + 110, 103, 73, 110, 100, 105, 99, 97, + 116, 111, 114, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 116, 101, 66, 49, 51, 84, 120, + 74, 97, 109, 109, 105, 110, 103, 73, + 110, 100, 105, 99, 97, 116, 111, 114, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 114, 101, 115, 104, 77, 101, 97, + 115, 117, 114, 101, 109, 101, 110, 116, + 73, 110, 100, 105, 99, 97, 116, 111, + 114, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 117, 108, 116, 105, 112, 97, 116, + 104, 69, 115, 116, 105, 109, 97, 116, + 101, 73, 115, 86, 97, 108, 105, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 105, 114, 101, 99, 116, 105, 111, + 110, 73, 115, 86, 97, 108, 105, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e501010e1bcae83b = b_e501010e1bcae83b.words; +#if !CAPNP_LITE +static const uint16_t m_e501010e1bcae83b[] = {3, 28, 5, 26, 15, 16, 20, 21, 22, 19, 17, 18, 24, 8, 9, 7, 6, 25, 4, 12, 27, 23, 14, 2, 13, 10, 1, 0, 11}; +static const uint16_t i_e501010e1bcae83b[] = {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}; +const ::capnp::_::RawSchema s_e501010e1bcae83b = { + 0xe501010e1bcae83b, b_e501010e1bcae83b.words, 522, nullptr, m_e501010e1bcae83b, + 0, 29, i_e501010e1bcae83b, nullptr, nullptr, { &s_e501010e1bcae83b, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<204> b_f580d7d86b7b8692 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 146, 134, 123, 107, 216, 215, 128, 245, + 19, 0, 0, 0, 1, 0, 4, 0, + 193, 81, 174, 7, 75, 103, 148, 222, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 42, 1, 0, 0, + 37, 0, 0, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 111, 2, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 81, 99, 111, 109, 71, 110, + 115, 115, 46, 77, 101, 97, 115, 117, + 114, 101, 109, 101, 110, 116, 82, 101, + 112, 111, 114, 116, 0, 0, 0, 0, + 4, 0, 0, 0, 1, 0, 1, 0, + 39, 44, 187, 231, 90, 89, 12, 241, + 1, 0, 0, 0, 26, 0, 0, 0, + 83, 86, 0, 0, 0, 0, 0, 0, + 44, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 1, 0, 0, 3, 0, 1, 0, + 44, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 1, 0, 0, 3, 0, 1, 0, + 48, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 1, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 1, 0, 0, 3, 0, 1, 0, + 52, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 1, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 52, 1, 0, 0, 3, 0, 1, 0, + 64, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 1, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 1, 0, 0, 3, 0, 1, 0, + 76, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 1, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 1, 0, 0, 3, 0, 1, 0, + 84, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 81, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 80, 1, 0, 0, 3, 0, 1, 0, + 92, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 89, 1, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 1, 0, 0, 3, 0, 1, 0, + 104, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 1, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 1, 0, 0, 3, 0, 1, 0, + 116, 1, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 1, 0, 0, 210, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 1, 0, 0, 3, 0, 1, 0, + 132, 1, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 129, 1, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 1, 0, 0, 3, 0, 1, 0, + 152, 1, 0, 0, 2, 0, 1, 0, + 115, 111, 117, 114, 99, 101, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 238, 167, 173, 250, 182, 18, 26, 215, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 67, 111, 117, 110, 116, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 87, 101, 101, 107, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 108, 111, 110, 97, 115, 115, 67, + 121, 99, 108, 101, 78, 117, 109, 98, + 101, 114, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 108, 111, 110, 97, 115, 115, 78, + 117, 109, 98, 101, 114, 79, 102, 68, + 97, 121, 115, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 105, 108, 108, 105, 115, 101, 99, + 111, 110, 100, 115, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 109, 101, 66, 105, 97, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 108, 111, 99, 107, 84, 105, 109, + 101, 85, 110, 99, 101, 114, 116, 97, + 105, 110, 116, 121, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 108, 111, 99, 107, 70, 114, 101, + 113, 117, 101, 110, 99, 121, 66, 105, + 97, 115, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 108, 111, 99, 107, 70, 114, 101, + 113, 117, 101, 110, 99, 121, 85, 110, + 99, 101, 114, 116, 97, 105, 110, 116, + 121, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 118, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 39, 44, 187, 231, 90, 89, 12, 241, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_f580d7d86b7b8692 = b_f580d7d86b7b8692.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_f580d7d86b7b8692[] = { + &s_d71a12b6faada7ee, + &s_f10c595ae7bb2c27, +}; +static const uint16_t m_f580d7d86b7b8692[] = {8, 9, 7, 1, 3, 4, 2, 5, 0, 10, 6}; +static const uint16_t i_f580d7d86b7b8692[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10}; +const ::capnp::_::RawSchema s_f580d7d86b7b8692 = { + 0xf580d7d86b7b8692, b_f580d7d86b7b8692.words, 204, d_f580d7d86b7b8692, m_f580d7d86b7b8692, + 2, 11, i_f580d7d86b7b8692, nullptr, nullptr, { &s_f580d7d86b7b8692, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<454> b_f10c595ae7bb2c27 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 39, 44, 187, 231, 90, 89, 12, 241, + 37, 0, 0, 0, 1, 0, 8, 0, + 146, 134, 123, 107, 216, 215, 128, 245, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 66, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 183, 5, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 81, 99, 111, 109, 71, 110, + 115, 115, 46, 77, 101, 97, 115, 117, + 114, 101, 109, 101, 110, 116, 82, 101, + 112, 111, 114, 116, 46, 83, 86, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 104, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 2, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 2, 0, 0, 3, 0, 1, 0, + 208, 2, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 2, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 2, 0, 0, 3, 0, 1, 0, + 220, 2, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 217, 2, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 220, 2, 0, 0, 3, 0, 1, 0, + 232, 2, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 2, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 228, 2, 0, 0, 3, 0, 1, 0, + 240, 2, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 2, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 2, 0, 0, 3, 0, 1, 0, + 252, 2, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 249, 2, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 252, 2, 0, 0, 3, 0, 1, 0, + 8, 3, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 3, 0, 0, 202, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 3, 0, 0, 3, 0, 1, 0, + 24, 3, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 3, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 3, 0, 0, 3, 0, 1, 0, + 32, 3, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 3, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 28, 3, 0, 0, 3, 0, 1, 0, + 40, 3, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 3, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 3, 0, 0, 3, 0, 1, 0, + 44, 3, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 14, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 3, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 3, 0, 0, 3, 0, 1, 0, + 56, 3, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 53, 3, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 52, 3, 0, 0, 3, 0, 1, 0, + 64, 3, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 3, 0, 0, 242, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 3, 0, 0, 3, 0, 1, 0, + 80, 3, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 3, 0, 0, 242, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 84, 3, 0, 0, 3, 0, 1, 0, + 96, 3, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 3, 0, 0, 210, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 3, 0, 0, 3, 0, 1, 0, + 112, 3, 0, 0, 2, 0, 1, 0, + 15, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 15, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 3, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 3, 0, 0, 3, 0, 1, 0, + 120, 3, 0, 0, 2, 0, 1, 0, + 16, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 16, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 3, 0, 0, 218, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 3, 0, 0, 3, 0, 1, 0, + 136, 3, 0, 0, 2, 0, 1, 0, + 17, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 17, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 3, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 136, 3, 0, 0, 3, 0, 1, 0, + 148, 3, 0, 0, 2, 0, 1, 0, + 18, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 145, 3, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 3, 0, 0, 3, 0, 1, 0, + 160, 3, 0, 0, 2, 0, 1, 0, + 19, 0, 0, 0, 11, 0, 0, 0, + 0, 0, 1, 0, 19, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 157, 3, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 152, 3, 0, 0, 3, 0, 1, 0, + 164, 3, 0, 0, 2, 0, 1, 0, + 20, 0, 0, 0, 12, 0, 0, 0, + 0, 0, 1, 0, 20, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 161, 3, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 160, 3, 0, 0, 3, 0, 1, 0, + 172, 3, 0, 0, 2, 0, 1, 0, + 21, 0, 0, 0, 13, 0, 0, 0, + 0, 0, 1, 0, 21, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 169, 3, 0, 0, 218, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 3, 0, 0, 3, 0, 1, 0, + 188, 3, 0, 0, 2, 0, 1, 0, + 22, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 22, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 3, 0, 0, 218, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 192, 3, 0, 0, 3, 0, 1, 0, + 204, 3, 0, 0, 2, 0, 1, 0, + 23, 0, 0, 0, 14, 0, 0, 0, + 0, 0, 1, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 3, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 200, 3, 0, 0, 3, 0, 1, 0, + 212, 3, 0, 0, 2, 0, 1, 0, + 24, 0, 0, 0, 15, 0, 0, 0, + 0, 0, 1, 0, 24, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 3, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 212, 3, 0, 0, 3, 0, 1, 0, + 224, 3, 0, 0, 2, 0, 1, 0, + 25, 0, 0, 0, 15, 0, 0, 0, + 0, 0, 1, 0, 25, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 3, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 220, 3, 0, 0, 3, 0, 1, 0, + 232, 3, 0, 0, 2, 0, 1, 0, + 115, 118, 73, 100, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 108, 111, 110, 97, 115, 115, 70, + 114, 101, 113, 117, 101, 110, 99, 121, + 73, 110, 100, 101, 120, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 98, 115, 101, 114, 118, 97, 116, + 105, 111, 110, 83, 116, 97, 116, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 233, 131, 108, 13, 154, 130, 30, 232, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 98, 115, 101, 114, 118, 97, 116, + 105, 111, 110, 115, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 111, 111, 100, 79, 98, 115, 101, + 114, 118, 97, 116, 105, 111, 110, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 80, 97, 114, 105, 116, + 121, 69, 114, 114, 111, 114, 67, 111, + 117, 110, 116, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 108, 111, 110, 97, 115, 115, 72, + 101, 109, 109, 105, 110, 103, 69, 114, + 114, 111, 114, 67, 111, 117, 110, 116, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 105, 108, 116, 101, 114, 83, 116, + 97, 103, 101, 115, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 114, 105, 101, 114, 78, + 111, 105, 115, 101, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 116, 101, 110, 99, 121, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 114, 101, 100, 101, 116, 101, 99, + 116, 73, 110, 116, 101, 114, 118, 97, + 108, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 115, 116, 100, 101, 116, 101, + 99, 116, 105, 111, 110, 115, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 110, 102, 105, 108, 116, 101, 114, + 101, 100, 77, 101, 97, 115, 117, 114, + 101, 109, 101, 110, 116, 73, 110, 116, + 101, 103, 114, 97, 108, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 110, 102, 105, 108, 116, 101, 114, + 101, 100, 77, 101, 97, 115, 117, 114, + 101, 109, 101, 110, 116, 70, 114, 97, + 99, 116, 105, 111, 110, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 110, 102, 105, 108, 116, 101, 114, + 101, 100, 84, 105, 109, 101, 85, 110, + 99, 101, 114, 116, 97, 105, 110, 116, + 121, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 110, 102, 105, 108, 116, 101, 114, + 101, 100, 83, 112, 101, 101, 100, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 110, 102, 105, 108, 116, 101, 114, + 101, 100, 83, 112, 101, 101, 100, 85, + 110, 99, 101, 114, 116, 97, 105, 110, + 116, 121, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 101, 97, 115, 117, 114, 101, 109, + 101, 110, 116, 83, 116, 97, 116, 117, + 115, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 59, 232, 202, 27, 14, 1, 1, 229, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 117, 108, 116, 105, 112, 97, 116, + 104, 69, 115, 116, 105, 109, 97, 116, + 101, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 122, 105, 109, 117, 116, 104, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 108, 101, 118, 97, 116, 105, 111, + 110, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 114, 105, 101, 114, 80, + 104, 97, 115, 101, 67, 121, 99, 108, + 101, 115, 73, 110, 116, 101, 103, 114, + 97, 108, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 114, 105, 101, 114, 80, + 104, 97, 115, 101, 67, 121, 99, 108, + 101, 115, 70, 114, 97, 99, 116, 105, + 111, 110, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 105, 110, 101, 83, 112, 101, 101, + 100, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 105, 110, 101, 83, 112, 101, 101, + 100, 85, 110, 99, 101, 114, 116, 97, + 105, 110, 116, 121, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 121, 99, 108, 101, 83, 108, 105, + 112, 67, 111, 117, 110, 116, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_f10c595ae7bb2c27 = b_f10c595ae7bb2c27.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_f10c595ae7bb2c27[] = { + &s_e501010e1bcae83b, + &s_e81e829a0d6c83e9, +}; +static const uint16_t m_f10c595ae7bb2c27[] = {19, 8, 22, 21, 25, 20, 7, 23, 24, 1, 6, 4, 5, 9, 17, 18, 2, 3, 11, 10, 0, 13, 12, 15, 16, 14}; +static const uint16_t i_f10c595ae7bb2c27[] = {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}; +const ::capnp::_::RawSchema s_f10c595ae7bb2c27 = { + 0xf10c595ae7bb2c27, b_f10c595ae7bb2c27.words, 454, d_f10c595ae7bb2c27, m_f10c595ae7bb2c27, + 2, 26, i_f10c595ae7bb2c27, nullptr, nullptr, { &s_f10c595ae7bb2c27, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<877> b_ca965e4add8f4f0b = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 11, 79, 143, 221, 74, 94, 150, 202, + 19, 0, 0, 0, 1, 0, 18, 0, + 193, 81, 174, 7, 75, 103, 148, 222, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 250, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 47, 11, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 81, 99, 111, 109, 71, 110, + 115, 115, 46, 67, 108, 111, 99, 107, + 82, 101, 112, 111, 114, 116, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 204, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 5, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 132, 5, 0, 0, 3, 0, 1, 0, + 144, 5, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 5, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 136, 5, 0, 0, 3, 0, 1, 0, + 148, 5, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 145, 5, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 144, 5, 0, 0, 3, 0, 1, 0, + 156, 5, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 5, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 5, 0, 0, 3, 0, 1, 0, + 160, 5, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 157, 5, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 160, 5, 0, 0, 3, 0, 1, 0, + 172, 5, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 169, 5, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 5, 0, 0, 3, 0, 1, 0, + 180, 5, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 5, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 5, 0, 0, 3, 0, 1, 0, + 188, 5, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 5, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 5, 0, 0, 3, 0, 1, 0, + 200, 5, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 5, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 5, 0, 0, 3, 0, 1, 0, + 208, 5, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 5, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 5, 0, 0, 3, 0, 1, 0, + 216, 5, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 20, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 5, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 212, 5, 0, 0, 3, 0, 1, 0, + 224, 5, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 5, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 220, 5, 0, 0, 3, 0, 1, 0, + 232, 5, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 11, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 5, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 228, 5, 0, 0, 3, 0, 1, 0, + 240, 5, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 5, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 5, 0, 0, 3, 0, 1, 0, + 252, 5, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 249, 5, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 252, 5, 0, 0, 3, 0, 1, 0, + 8, 6, 0, 0, 2, 0, 1, 0, + 15, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 15, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 6, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 6, 0, 0, 3, 0, 1, 0, + 16, 6, 0, 0, 2, 0, 1, 0, + 16, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 16, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 6, 0, 0, 226, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 6, 0, 0, 3, 0, 1, 0, + 32, 6, 0, 0, 2, 0, 1, 0, + 17, 0, 0, 0, 21, 0, 0, 0, + 0, 0, 1, 0, 17, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 6, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 6, 0, 0, 3, 0, 1, 0, + 44, 6, 0, 0, 2, 0, 1, 0, + 18, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 1, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 6, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 6, 0, 0, 3, 0, 1, 0, + 48, 6, 0, 0, 2, 0, 1, 0, + 19, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 19, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 6, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 6, 0, 0, 3, 0, 1, 0, + 56, 6, 0, 0, 2, 0, 1, 0, + 20, 0, 0, 0, 11, 0, 0, 0, + 0, 0, 1, 0, 20, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 53, 6, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 52, 6, 0, 0, 3, 0, 1, 0, + 64, 6, 0, 0, 2, 0, 1, 0, + 21, 0, 0, 0, 12, 0, 0, 0, + 0, 0, 1, 0, 21, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 6, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 6, 0, 0, 3, 0, 1, 0, + 76, 6, 0, 0, 2, 0, 1, 0, + 22, 0, 0, 0, 38, 0, 0, 0, + 0, 0, 1, 0, 22, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 6, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 6, 0, 0, 3, 0, 1, 0, + 84, 6, 0, 0, 2, 0, 1, 0, + 23, 0, 0, 0, 26, 0, 0, 0, + 0, 0, 1, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 81, 6, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 6, 0, 0, 3, 0, 1, 0, + 88, 6, 0, 0, 2, 0, 1, 0, + 24, 0, 0, 0, 14, 0, 0, 0, + 0, 0, 1, 0, 24, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 85, 6, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 84, 6, 0, 0, 3, 0, 1, 0, + 96, 6, 0, 0, 2, 0, 1, 0, + 25, 0, 0, 0, 15, 0, 0, 0, + 0, 0, 1, 0, 25, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 6, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 6, 0, 0, 3, 0, 1, 0, + 104, 6, 0, 0, 2, 0, 1, 0, + 26, 0, 0, 0, 16, 0, 0, 0, + 0, 0, 1, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 6, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 6, 0, 0, 3, 0, 1, 0, + 116, 6, 0, 0, 2, 0, 1, 0, + 27, 0, 0, 0, 39, 0, 0, 0, + 0, 0, 1, 0, 27, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 6, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 6, 0, 0, 3, 0, 1, 0, + 124, 6, 0, 0, 2, 0, 1, 0, + 28, 0, 0, 0, 17, 0, 0, 0, + 0, 0, 1, 0, 28, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 6, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 6, 0, 0, 3, 0, 1, 0, + 136, 6, 0, 0, 2, 0, 1, 0, + 29, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 1, 0, 29, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 6, 0, 0, 210, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 140, 6, 0, 0, 3, 0, 1, 0, + 152, 6, 0, 0, 2, 0, 1, 0, + 30, 0, 0, 0, 54, 0, 0, 0, + 0, 0, 1, 0, 30, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 149, 6, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 6, 0, 0, 3, 0, 1, 0, + 160, 6, 0, 0, 2, 0, 1, 0, + 31, 0, 0, 0, 55, 0, 0, 0, + 0, 0, 1, 0, 31, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 157, 6, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 156, 6, 0, 0, 3, 0, 1, 0, + 168, 6, 0, 0, 2, 0, 1, 0, + 32, 0, 0, 0, 76, 0, 0, 0, + 0, 0, 1, 0, 32, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 165, 6, 0, 0, 210, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 172, 6, 0, 0, 3, 0, 1, 0, + 184, 6, 0, 0, 2, 0, 1, 0, + 33, 0, 0, 0, 77, 0, 0, 0, + 0, 0, 1, 0, 33, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 6, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 6, 0, 0, 3, 0, 1, 0, + 196, 6, 0, 0, 2, 0, 1, 0, + 34, 0, 0, 0, 20, 0, 0, 0, + 0, 0, 1, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 6, 0, 0, 10, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 6, 0, 0, 3, 0, 1, 0, + 216, 6, 0, 0, 2, 0, 1, 0, + 35, 0, 0, 0, 21, 0, 0, 0, + 0, 0, 1, 0, 35, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 6, 0, 0, 98, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 228, 6, 0, 0, 3, 0, 1, 0, + 240, 6, 0, 0, 2, 0, 1, 0, + 36, 0, 0, 0, 22, 0, 0, 0, + 0, 0, 1, 0, 36, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 6, 0, 0, 234, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 244, 6, 0, 0, 3, 0, 1, 0, + 0, 7, 0, 0, 2, 0, 1, 0, + 37, 0, 0, 0, 23, 0, 0, 0, + 0, 0, 1, 0, 37, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 253, 6, 0, 0, 66, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 7, 0, 0, 3, 0, 1, 0, + 20, 7, 0, 0, 2, 0, 1, 0, + 38, 0, 0, 0, 24, 0, 0, 0, + 0, 0, 1, 0, 38, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 7, 0, 0, 234, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 24, 7, 0, 0, 3, 0, 1, 0, + 36, 7, 0, 0, 2, 0, 1, 0, + 39, 0, 0, 0, 25, 0, 0, 0, + 0, 0, 1, 0, 39, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 7, 0, 0, 66, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 7, 0, 0, 3, 0, 1, 0, + 56, 7, 0, 0, 2, 0, 1, 0, + 40, 0, 0, 0, 26, 0, 0, 0, + 0, 0, 1, 0, 40, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 53, 7, 0, 0, 234, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 60, 7, 0, 0, 3, 0, 1, 0, + 72, 7, 0, 0, 2, 0, 1, 0, + 41, 0, 0, 0, 27, 0, 0, 0, + 0, 0, 1, 0, 41, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 7, 0, 0, 66, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 80, 7, 0, 0, 3, 0, 1, 0, + 92, 7, 0, 0, 2, 0, 1, 0, + 42, 0, 0, 0, 28, 0, 0, 0, + 0, 0, 1, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 89, 7, 0, 0, 234, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 7, 0, 0, 3, 0, 1, 0, + 108, 7, 0, 0, 2, 0, 1, 0, + 43, 0, 0, 0, 29, 0, 0, 0, + 0, 0, 1, 0, 43, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 7, 0, 0, 66, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 7, 0, 0, 3, 0, 1, 0, + 128, 7, 0, 0, 2, 0, 1, 0, + 44, 0, 0, 0, 30, 0, 0, 0, + 0, 0, 1, 0, 44, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 7, 0, 0, 234, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 132, 7, 0, 0, 3, 0, 1, 0, + 144, 7, 0, 0, 2, 0, 1, 0, + 45, 0, 0, 0, 31, 0, 0, 0, + 0, 0, 1, 0, 45, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 7, 0, 0, 66, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 152, 7, 0, 0, 3, 0, 1, 0, + 164, 7, 0, 0, 2, 0, 1, 0, + 46, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 46, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 161, 7, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 160, 7, 0, 0, 3, 0, 1, 0, + 172, 7, 0, 0, 2, 0, 1, 0, + 47, 0, 0, 0, 32, 0, 0, 0, + 0, 0, 1, 0, 47, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 169, 7, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 7, 0, 0, 3, 0, 1, 0, + 180, 7, 0, 0, 2, 0, 1, 0, + 48, 0, 0, 0, 33, 0, 0, 0, + 0, 0, 1, 0, 48, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 7, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 7, 0, 0, 3, 0, 1, 0, + 188, 7, 0, 0, 2, 0, 1, 0, + 49, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 1, 0, 49, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 7, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 7, 0, 0, 3, 0, 1, 0, + 196, 7, 0, 0, 2, 0, 1, 0, + 50, 0, 0, 0, 35, 0, 0, 0, + 0, 0, 1, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 7, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 192, 7, 0, 0, 3, 0, 1, 0, + 204, 7, 0, 0, 2, 0, 1, 0, + 104, 97, 115, 70, 67, 111, 117, 110, + 116, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 67, 111, 117, 110, 116, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 97, 115, 71, 112, 115, 87, 101, + 101, 107, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 87, 101, 101, 107, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 97, 115, 71, 112, 115, 77, 105, + 108, 108, 105, 115, 101, 99, 111, 110, + 100, 115, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 77, 105, 108, 108, 105, + 115, 101, 99, 111, 110, 100, 115, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 84, 105, 109, 101, 66, + 105, 97, 115, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 67, 108, 111, 99, 107, + 84, 105, 109, 101, 85, 110, 99, 101, + 114, 116, 97, 105, 110, 116, 121, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 67, 108, 111, 99, 107, + 83, 111, 117, 114, 99, 101, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 97, 115, 71, 108, 111, 110, 97, + 115, 115, 89, 101, 97, 114, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 108, 111, 110, 97, 115, 115, 89, + 101, 97, 114, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 97, 115, 71, 108, 111, 110, 97, + 115, 115, 68, 97, 121, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 108, 111, 110, 97, 115, 115, 68, + 97, 121, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 97, 115, 71, 108, 111, 110, 97, + 115, 115, 77, 105, 108, 108, 105, 115, + 101, 99, 111, 110, 100, 115, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 108, 111, 110, 97, 115, 115, 77, + 105, 108, 108, 105, 115, 101, 99, 111, + 110, 100, 115, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 108, 111, 110, 97, 115, 115, 84, + 105, 109, 101, 66, 105, 97, 115, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 108, 111, 110, 97, 115, 115, 67, + 108, 111, 99, 107, 84, 105, 109, 101, + 85, 110, 99, 101, 114, 116, 97, 105, + 110, 116, 121, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 108, 111, 110, 97, 115, 115, 67, + 108, 111, 99, 107, 83, 111, 117, 114, + 99, 101, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 100, 115, 87, 101, 101, 107, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 100, 115, 77, 105, 108, 108, 105, + 115, 101, 99, 111, 110, 100, 115, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 100, 115, 84, 105, 109, 101, 66, + 105, 97, 115, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 100, 115, 67, 108, 111, 99, 107, + 84, 105, 109, 101, 85, 110, 99, 101, + 114, 116, 97, 105, 110, 116, 121, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 100, 115, 67, 108, 111, 99, 107, + 83, 111, 117, 114, 99, 101, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 97, 108, 87, 101, 101, 107, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 97, 108, 77, 105, 108, 108, 105, + 115, 101, 99, 111, 110, 100, 115, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 97, 108, 84, 105, 109, 101, 66, + 105, 97, 115, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 97, 108, 67, 108, 111, 99, 107, + 84, 105, 109, 101, 85, 110, 99, 101, + 114, 116, 97, 105, 110, 116, 121, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 97, 108, 67, 108, 111, 99, 107, + 83, 111, 117, 114, 99, 101, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 108, 111, 99, 107, 70, 114, 101, + 113, 117, 101, 110, 99, 121, 66, 105, + 97, 115, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 108, 111, 99, 107, 70, 114, 101, + 113, 117, 101, 110, 99, 121, 85, 110, + 99, 101, 114, 116, 97, 105, 110, 116, + 121, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 114, 101, 113, 117, 101, 110, 99, + 121, 83, 111, 117, 114, 99, 101, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 76, 101, 97, 112, 83, + 101, 99, 111, 110, 100, 115, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 76, 101, 97, 112, 83, + 101, 99, 111, 110, 100, 115, 85, 110, + 99, 101, 114, 116, 97, 105, 110, 116, + 121, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 76, 101, 97, 112, 83, + 101, 99, 111, 110, 100, 115, 83, 111, + 117, 114, 99, 101, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 84, 111, 71, 108, 111, + 110, 97, 115, 115, 84, 105, 109, 101, + 66, 105, 97, 115, 77, 105, 108, 108, + 105, 115, 101, 99, 111, 110, 100, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 84, 111, 71, 108, 111, + 110, 97, 115, 115, 84, 105, 109, 101, + 66, 105, 97, 115, 77, 105, 108, 108, + 105, 115, 101, 99, 111, 110, 100, 115, + 85, 110, 99, 101, 114, 116, 97, 105, + 110, 116, 121, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 84, 111, 66, 100, 115, + 84, 105, 109, 101, 66, 105, 97, 115, + 77, 105, 108, 108, 105, 115, 101, 99, + 111, 110, 100, 115, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 84, 111, 66, 100, 115, + 84, 105, 109, 101, 66, 105, 97, 115, + 77, 105, 108, 108, 105, 115, 101, 99, + 111, 110, 100, 115, 85, 110, 99, 101, + 114, 116, 97, 105, 110, 116, 121, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 100, 115, 84, 111, 71, 108, 111, + 84, 105, 109, 101, 66, 105, 97, 115, + 77, 105, 108, 108, 105, 115, 101, 99, + 111, 110, 100, 115, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 100, 115, 84, 111, 71, 108, 111, + 84, 105, 109, 101, 66, 105, 97, 115, + 77, 105, 108, 108, 105, 115, 101, 99, + 111, 110, 100, 115, 85, 110, 99, 101, + 114, 116, 97, 105, 110, 116, 121, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 84, 111, 71, 97, 108, + 84, 105, 109, 101, 66, 105, 97, 115, + 77, 105, 108, 108, 105, 115, 101, 99, + 111, 110, 100, 115, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 84, 111, 71, 97, 108, + 84, 105, 109, 101, 66, 105, 97, 115, + 77, 105, 108, 108, 105, 115, 101, 99, + 111, 110, 100, 115, 85, 110, 99, 101, + 114, 116, 97, 105, 110, 116, 121, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 97, 108, 84, 111, 71, 108, 111, + 84, 105, 109, 101, 66, 105, 97, 115, + 77, 105, 108, 108, 105, 115, 101, 99, + 111, 110, 100, 115, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 97, 108, 84, 111, 71, 108, 111, + 84, 105, 109, 101, 66, 105, 97, 115, + 77, 105, 108, 108, 105, 115, 101, 99, + 111, 110, 100, 115, 85, 110, 99, 101, + 114, 116, 97, 105, 110, 116, 121, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 97, 108, 84, 111, 66, 100, 115, + 84, 105, 109, 101, 66, 105, 97, 115, + 77, 105, 108, 108, 105, 115, 101, 99, + 111, 110, 100, 115, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 97, 108, 84, 111, 66, 100, 115, + 84, 105, 109, 101, 66, 105, 97, 115, + 77, 105, 108, 108, 105, 115, 101, 99, + 111, 110, 100, 115, 85, 110, 99, 101, + 114, 116, 97, 105, 110, 116, 121, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 97, 115, 82, 116, 99, 84, 105, + 109, 101, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 121, 115, 116, 101, 109, 82, 116, + 99, 84, 105, 109, 101, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 67, 111, 117, 110, 116, 79, 102, + 102, 115, 101, 116, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 112, 109, 82, 116, 99, 67, 111, + 117, 110, 116, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 108, 111, 99, 107, 82, 101, 115, + 101, 116, 115, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_ca965e4add8f4f0b = b_ca965e4add8f4f0b.words; +#if !CAPNP_LITE +static const uint16_t m_ca965e4add8f4f0b[] = {22, 21, 19, 20, 38, 39, 18, 28, 29, 50, 1, 48, 30, 27, 26, 24, 25, 44, 45, 42, 43, 23, 17, 16, 12, 14, 15, 10, 8, 7, 31, 33, 32, 5, 6, 36, 37, 40, 41, 34, 35, 3, 0, 11, 13, 9, 4, 2, 46, 49, 47}; +static const uint16_t i_ca965e4add8f4f0b[] = {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, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50}; +const ::capnp::_::RawSchema s_ca965e4add8f4f0b = { + 0xca965e4add8f4f0b, b_ca965e4add8f4f0b.words, 877, nullptr, m_ca965e4add8f4f0b, + 0, 51, i_ca965e4add8f4f0b, nullptr, nullptr, { &s_ca965e4add8f4f0b, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<484> b_8053c39445c6c75c = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 92, 199, 198, 69, 148, 195, 83, 128, + 19, 0, 0, 0, 1, 0, 10, 0, + 193, 81, 174, 7, 75, 103, 148, 222, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 58, 1, 0, 0, + 37, 0, 0, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 39, 6, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 81, 99, 111, 109, 71, 110, + 115, 115, 46, 68, 114, 77, 101, 97, + 115, 117, 114, 101, 109, 101, 110, 116, + 82, 101, 112, 111, 114, 116, 0, 0, + 4, 0, 0, 0, 1, 0, 1, 0, + 156, 69, 191, 140, 223, 129, 139, 240, + 1, 0, 0, 0, 26, 0, 0, 0, + 83, 86, 0, 0, 0, 0, 0, 0, + 112, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 3, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 252, 2, 0, 0, 3, 0, 1, 0, + 8, 3, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 3, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 3, 0, 0, 3, 0, 1, 0, + 12, 3, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 3, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 3, 0, 0, 3, 0, 1, 0, + 16, 3, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 3, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 3, 0, 0, 3, 0, 1, 0, + 20, 3, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 24, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 3, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 3, 0, 0, 3, 0, 1, 0, + 28, 3, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 3, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 3, 0, 0, 3, 0, 1, 0, + 32, 3, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 3, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 28, 3, 0, 0, 3, 0, 1, 0, + 40, 3, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 3, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 3, 0, 0, 3, 0, 1, 0, + 48, 3, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 3, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 3, 0, 0, 3, 0, 1, 0, + 56, 3, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 53, 3, 0, 0, 210, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 60, 3, 0, 0, 3, 0, 1, 0, + 72, 3, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 3, 0, 0, 10, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 80, 3, 0, 0, 3, 0, 1, 0, + 92, 3, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 89, 3, 0, 0, 98, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 3, 0, 0, 3, 0, 1, 0, + 116, 3, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 16, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 3, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 3, 0, 0, 3, 0, 1, 0, + 120, 3, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 3, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 3, 0, 0, 3, 0, 1, 0, + 128, 3, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 3, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 3, 0, 0, 3, 0, 1, 0, + 136, 3, 0, 0, 2, 0, 1, 0, + 15, 0, 0, 0, 11, 0, 0, 0, + 0, 0, 1, 0, 15, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 3, 0, 0, 210, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 140, 3, 0, 0, 3, 0, 1, 0, + 152, 3, 0, 0, 2, 0, 1, 0, + 16, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 1, 0, 16, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 149, 3, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 3, 0, 0, 3, 0, 1, 0, + 160, 3, 0, 0, 2, 0, 1, 0, + 17, 0, 0, 0, 35, 0, 0, 0, + 0, 0, 1, 0, 17, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 157, 3, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 160, 3, 0, 0, 3, 0, 1, 0, + 172, 3, 0, 0, 2, 0, 1, 0, + 18, 0, 0, 0, 48, 0, 0, 0, + 0, 0, 1, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 169, 3, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 3, 0, 0, 3, 0, 1, 0, + 180, 3, 0, 0, 2, 0, 1, 0, + 19, 0, 0, 0, 25, 0, 0, 0, + 0, 0, 1, 0, 19, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 3, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 3, 0, 0, 3, 0, 1, 0, + 188, 3, 0, 0, 2, 0, 1, 0, + 20, 0, 0, 0, 13, 0, 0, 0, + 0, 0, 1, 0, 20, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 3, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 3, 0, 0, 3, 0, 1, 0, + 200, 3, 0, 0, 2, 0, 1, 0, + 21, 0, 0, 0, 14, 0, 0, 0, + 0, 0, 1, 0, 21, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 3, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 3, 0, 0, 3, 0, 1, 0, + 208, 3, 0, 0, 2, 0, 1, 0, + 22, 0, 0, 0, 15, 0, 0, 0, + 0, 0, 1, 0, 22, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 3, 0, 0, 226, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 212, 3, 0, 0, 3, 0, 1, 0, + 224, 3, 0, 0, 2, 0, 1, 0, + 23, 0, 0, 0, 16, 0, 0, 0, + 0, 0, 1, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 3, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 224, 3, 0, 0, 3, 0, 1, 0, + 236, 3, 0, 0, 2, 0, 1, 0, + 24, 0, 0, 0, 17, 0, 0, 0, + 0, 0, 1, 0, 24, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 233, 3, 0, 0, 210, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 3, 0, 0, 3, 0, 1, 0, + 252, 3, 0, 0, 2, 0, 1, 0, + 25, 0, 0, 0, 49, 0, 0, 0, + 0, 0, 1, 0, 25, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 249, 3, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 248, 3, 0, 0, 3, 0, 1, 0, + 4, 4, 0, 0, 2, 0, 1, 0, + 26, 0, 0, 0, 36, 0, 0, 0, + 0, 0, 1, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 4, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 252, 3, 0, 0, 3, 0, 1, 0, + 8, 4, 0, 0, 2, 0, 1, 0, + 27, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 27, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 4, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 4, 0, 0, 3, 0, 1, 0, + 28, 4, 0, 0, 2, 0, 1, 0, + 114, 101, 97, 115, 111, 110, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 101, 113, 78, 117, 109, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 101, 113, 77, 97, 120, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 102, 76, 111, 115, 115, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 121, 115, 116, 101, 109, 82, 116, + 99, 86, 97, 108, 105, 100, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 67, 111, 117, 110, 116, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 108, 111, 99, 107, 82, 101, 115, + 101, 116, 115, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 121, 115, 116, 101, 109, 82, 116, + 99, 84, 105, 109, 101, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 76, 101, 97, 112, 83, + 101, 99, 111, 110, 100, 115, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 76, 101, 97, 112, 83, + 101, 99, 111, 110, 100, 115, 85, 110, + 99, 101, 114, 116, 97, 105, 110, 116, + 121, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 84, 111, 71, 108, 111, + 110, 97, 115, 115, 84, 105, 109, 101, + 66, 105, 97, 115, 77, 105, 108, 108, + 105, 115, 101, 99, 111, 110, 100, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 84, 111, 71, 108, 111, + 110, 97, 115, 115, 84, 105, 109, 101, + 66, 105, 97, 115, 77, 105, 108, 108, + 105, 115, 101, 99, 111, 110, 100, 115, + 85, 110, 99, 101, 114, 116, 97, 105, + 110, 116, 121, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 87, 101, 101, 107, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 77, 105, 108, 108, 105, + 115, 101, 99, 111, 110, 100, 115, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 84, 105, 109, 101, 66, + 105, 97, 115, 77, 115, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 67, 108, 111, 99, 107, + 84, 105, 109, 101, 85, 110, 99, 101, + 114, 116, 97, 105, 110, 116, 121, 77, + 115, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 67, 108, 111, 99, 107, + 83, 111, 117, 114, 99, 101, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 108, 111, 110, 97, 115, 115, 67, + 108, 111, 99, 107, 83, 111, 117, 114, + 99, 101, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 108, 111, 110, 97, 115, 115, 89, + 101, 97, 114, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 108, 111, 110, 97, 115, 115, 68, + 97, 121, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 108, 111, 110, 97, 115, 115, 77, + 105, 108, 108, 105, 115, 101, 99, 111, + 110, 100, 115, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 108, 111, 110, 97, 115, 115, 84, + 105, 109, 101, 66, 105, 97, 115, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 108, 111, 110, 97, 115, 115, 67, + 108, 111, 99, 107, 84, 105, 109, 101, + 85, 110, 99, 101, 114, 116, 97, 105, + 110, 116, 121, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 108, 111, 99, 107, 70, 114, 101, + 113, 117, 101, 110, 99, 121, 66, 105, + 97, 115, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 108, 111, 99, 107, 70, 114, 101, + 113, 117, 101, 110, 99, 121, 85, 110, + 99, 101, 114, 116, 97, 105, 110, 116, + 121, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 114, 101, 113, 117, 101, 110, 99, + 121, 83, 111, 117, 114, 99, 101, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 111, 117, 114, 99, 101, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 238, 167, 173, 250, 182, 18, 26, 215, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 118, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 156, 69, 191, 140, 223, 129, 139, 240, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_8053c39445c6c75c = b_8053c39445c6c75c.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_8053c39445c6c75c[] = { + &s_d71a12b6faada7ee, + &s_f08b81df8cbf459c, +}; +static const uint16_t m_8053c39445c6c75c[] = {23, 24, 6, 5, 25, 17, 22, 19, 20, 21, 18, 16, 15, 8, 9, 13, 14, 10, 11, 12, 0, 3, 2, 1, 26, 27, 7, 4}; +static const uint16_t i_8053c39445c6c75c[] = {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}; +const ::capnp::_::RawSchema s_8053c39445c6c75c = { + 0x8053c39445c6c75c, b_8053c39445c6c75c.words, 484, d_8053c39445c6c75c, m_8053c39445c6c75c, + 2, 28, i_8053c39445c6c75c, nullptr, nullptr, { &s_8053c39445c6c75c, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<567> b_f08b81df8cbf459c = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 156, 69, 191, 140, 223, 129, 139, 240, + 39, 0, 0, 0, 1, 0, 12, 0, + 92, 199, 198, 69, 148, 195, 83, 128, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 82, 1, 0, 0, + 41, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 63, 7, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 81, 99, 111, 109, 71, 110, + 115, 115, 46, 68, 114, 77, 101, 97, + 115, 117, 114, 101, 109, 101, 110, 116, + 82, 101, 112, 111, 114, 116, 46, 83, + 86, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 132, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 3, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 136, 3, 0, 0, 3, 0, 1, 0, + 148, 3, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 145, 3, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 3, 0, 0, 3, 0, 1, 0, + 160, 3, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 157, 3, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 160, 3, 0, 0, 3, 0, 1, 0, + 172, 3, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 169, 3, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 3, 0, 0, 3, 0, 1, 0, + 180, 3, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 3, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 3, 0, 0, 3, 0, 1, 0, + 192, 3, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 3, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 3, 0, 0, 3, 0, 1, 0, + 200, 3, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 3, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 200, 3, 0, 0, 3, 0, 1, 0, + 212, 3, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 3, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 3, 0, 0, 3, 0, 1, 0, + 220, 3, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 217, 3, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 3, 0, 0, 3, 0, 1, 0, + 228, 3, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 225, 3, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 228, 3, 0, 0, 3, 0, 1, 0, + 240, 3, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 3, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 236, 3, 0, 0, 3, 0, 1, 0, + 248, 3, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 245, 3, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 3, 0, 0, 3, 0, 1, 0, + 252, 3, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 249, 3, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 244, 3, 0, 0, 3, 0, 1, 0, + 0, 4, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 253, 3, 0, 0, 226, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 4, 0, 0, 3, 0, 1, 0, + 16, 4, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 4, 0, 0, 226, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 4, 0, 0, 3, 0, 1, 0, + 32, 4, 0, 0, 2, 0, 1, 0, + 15, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 15, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 4, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 4, 0, 0, 3, 0, 1, 0, + 44, 4, 0, 0, 2, 0, 1, 0, + 16, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 16, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 4, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 4, 0, 0, 3, 0, 1, 0, + 52, 4, 0, 0, 2, 0, 1, 0, + 17, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 17, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 4, 0, 0, 202, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 56, 4, 0, 0, 3, 0, 1, 0, + 68, 4, 0, 0, 2, 0, 1, 0, + 18, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 65, 4, 0, 0, 242, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 4, 0, 0, 3, 0, 1, 0, + 84, 4, 0, 0, 2, 0, 1, 0, + 19, 0, 0, 0, 11, 0, 0, 0, + 0, 0, 1, 0, 19, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 81, 4, 0, 0, 242, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 88, 4, 0, 0, 3, 0, 1, 0, + 100, 4, 0, 0, 2, 0, 1, 0, + 20, 0, 0, 0, 12, 0, 0, 0, + 0, 0, 1, 0, 20, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 4, 0, 0, 210, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 4, 0, 0, 3, 0, 1, 0, + 116, 4, 0, 0, 2, 0, 1, 0, + 21, 0, 0, 0, 13, 0, 0, 0, + 0, 0, 1, 0, 21, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 4, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 4, 0, 0, 3, 0, 1, 0, + 124, 4, 0, 0, 2, 0, 1, 0, + 22, 0, 0, 0, 14, 0, 0, 0, + 0, 0, 1, 0, 22, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 4, 0, 0, 218, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 128, 4, 0, 0, 3, 0, 1, 0, + 140, 4, 0, 0, 2, 0, 1, 0, + 23, 0, 0, 0, 15, 0, 0, 0, + 0, 0, 1, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 137, 4, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 140, 4, 0, 0, 3, 0, 1, 0, + 152, 4, 0, 0, 2, 0, 1, 0, + 24, 0, 0, 0, 16, 0, 0, 0, + 0, 0, 1, 0, 24, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 149, 4, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 144, 4, 0, 0, 3, 0, 1, 0, + 156, 4, 0, 0, 2, 0, 1, 0, + 25, 0, 0, 0, 17, 0, 0, 0, + 0, 0, 1, 0, 25, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 4, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 152, 4, 0, 0, 3, 0, 1, 0, + 164, 4, 0, 0, 2, 0, 1, 0, + 26, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 1, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 161, 4, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 164, 4, 0, 0, 3, 0, 1, 0, + 176, 4, 0, 0, 2, 0, 1, 0, + 27, 0, 0, 0, 19, 0, 0, 0, + 0, 0, 1, 0, 27, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 173, 4, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 172, 4, 0, 0, 3, 0, 1, 0, + 184, 4, 0, 0, 2, 0, 1, 0, + 28, 0, 0, 0, 20, 0, 0, 0, + 0, 0, 1, 0, 28, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 4, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 4, 0, 0, 3, 0, 1, 0, + 196, 4, 0, 0, 2, 0, 1, 0, + 29, 0, 0, 0, 11, 0, 0, 0, + 0, 0, 1, 0, 29, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 4, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 192, 4, 0, 0, 3, 0, 1, 0, + 204, 4, 0, 0, 2, 0, 1, 0, + 30, 0, 0, 0, 21, 0, 0, 0, + 0, 0, 1, 0, 30, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 4, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 4, 0, 0, 3, 0, 1, 0, + 208, 4, 0, 0, 2, 0, 1, 0, + 31, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 31, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 4, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 4, 0, 0, 3, 0, 1, 0, + 220, 4, 0, 0, 2, 0, 1, 0, + 32, 0, 0, 0, 72, 0, 0, 0, + 0, 0, 1, 0, 32, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 217, 4, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 4, 0, 0, 3, 0, 1, 0, + 228, 4, 0, 0, 2, 0, 1, 0, + 115, 118, 73, 100, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 108, 111, 110, 97, 115, 115, 70, + 114, 101, 113, 117, 101, 110, 99, 121, + 73, 110, 100, 101, 120, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 98, 115, 101, 114, 118, 97, 116, + 105, 111, 110, 83, 116, 97, 116, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 233, 131, 108, 13, 154, 130, 30, 232, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 98, 115, 101, 114, 118, 97, 116, + 105, 111, 110, 115, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 111, 111, 100, 79, 98, 115, 101, + 114, 118, 97, 116, 105, 111, 110, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 105, 108, 116, 101, 114, 83, 116, + 97, 103, 101, 115, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 114, 101, 100, 101, 116, 101, 99, + 116, 73, 110, 116, 101, 114, 118, 97, + 108, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 121, 99, 108, 101, 83, 108, 105, + 112, 67, 111, 117, 110, 116, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 115, 116, 100, 101, 116, 101, + 99, 116, 105, 111, 110, 115, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 101, 97, 115, 117, 114, 101, 109, + 101, 110, 116, 83, 116, 97, 116, 117, + 115, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 59, 232, 202, 27, 14, 1, 1, 229, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 114, 105, 101, 114, 78, + 111, 105, 115, 101, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 102, 76, 111, 115, 115, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 116, 101, 110, 99, 121, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 105, 108, 116, 101, 114, 101, 100, + 77, 101, 97, 115, 117, 114, 101, 109, + 101, 110, 116, 70, 114, 97, 99, 116, + 105, 111, 110, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 105, 108, 116, 101, 114, 101, 100, + 77, 101, 97, 115, 117, 114, 101, 109, + 101, 110, 116, 73, 110, 116, 101, 103, + 114, 97, 108, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 105, 108, 116, 101, 114, 101, 100, + 84, 105, 109, 101, 85, 110, 99, 101, + 114, 116, 97, 105, 110, 116, 121, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 105, 108, 116, 101, 114, 101, 100, + 83, 112, 101, 101, 100, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 105, 108, 116, 101, 114, 101, 100, + 83, 112, 101, 101, 100, 85, 110, 99, + 101, 114, 116, 97, 105, 110, 116, 121, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 110, 102, 105, 108, 116, 101, 114, + 101, 100, 77, 101, 97, 115, 117, 114, + 101, 109, 101, 110, 116, 70, 114, 97, + 99, 116, 105, 111, 110, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 110, 102, 105, 108, 116, 101, 114, + 101, 100, 77, 101, 97, 115, 117, 114, + 101, 109, 101, 110, 116, 73, 110, 116, + 101, 103, 114, 97, 108, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 110, 102, 105, 108, 116, 101, 114, + 101, 100, 84, 105, 109, 101, 85, 110, + 99, 101, 114, 116, 97, 105, 110, 116, + 121, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 110, 102, 105, 108, 116, 101, 114, + 101, 100, 83, 112, 101, 101, 100, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 110, 102, 105, 108, 116, 101, 114, + 101, 100, 83, 112, 101, 101, 100, 85, + 110, 99, 101, 114, 116, 97, 105, 110, + 116, 121, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 117, 108, 116, 105, 112, 97, 116, + 104, 69, 115, 116, 105, 109, 97, 116, + 101, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 122, 105, 109, 117, 116, 104, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 108, 101, 118, 97, 116, 105, 111, + 110, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 111, 112, 112, 108, 101, 114, 65, + 99, 99, 101, 108, 101, 114, 97, 116, + 105, 111, 110, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 105, 110, 101, 83, 112, 101, 101, + 100, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 105, 110, 101, 83, 112, 101, 101, + 100, 85, 110, 99, 101, 114, 116, 97, + 105, 110, 116, 121, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 114, 105, 101, 114, 80, + 104, 97, 115, 101, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 67, 111, 117, 110, 116, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 97, 114, 105, 116, 121, 69, 114, + 114, 111, 114, 67, 111, 117, 110, 116, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 111, 111, 100, 80, 97, 114, 105, + 116, 121, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_f08b81df8cbf459c = b_f08b81df8cbf459c.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_f08b81df8cbf459c[] = { + &s_e501010e1bcae83b, + &s_e81e829a0d6c83e9, +}; +static const uint16_t m_f08b81df8cbf459c[] = {24, 10, 29, 7, 26, 25, 30, 5, 13, 14, 16, 17, 15, 27, 28, 1, 4, 32, 12, 9, 23, 2, 3, 31, 8, 6, 11, 0, 18, 19, 21, 22, 20}; +static const uint16_t i_f08b81df8cbf459c[] = {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}; +const ::capnp::_::RawSchema s_f08b81df8cbf459c = { + 0xf08b81df8cbf459c, b_f08b81df8cbf459c.words, 567, d_f08b81df8cbf459c, m_f08b81df8cbf459c, + 2, 33, i_f08b81df8cbf459c, nullptr, nullptr, { &s_f08b81df8cbf459c, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<427> b_b1fb80811a673270 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 112, 50, 103, 26, 129, 128, 251, 177, + 19, 0, 0, 0, 1, 0, 8, 0, + 193, 81, 174, 7, 75, 103, 148, 222, + 4, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 18, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 127, 5, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 81, 99, 111, 109, 71, 110, + 115, 115, 46, 68, 114, 83, 118, 80, + 111, 108, 121, 82, 101, 112, 111, 114, + 116, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 100, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 173, 2, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 2, 0, 0, 3, 0, 1, 0, + 180, 2, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 2, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 2, 0, 0, 3, 0, 1, 0, + 188, 2, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 24, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 2, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 2, 0, 0, 3, 0, 1, 0, + 196, 2, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 25, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 2, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 2, 0, 0, 3, 0, 1, 0, + 200, 2, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 26, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 2, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 2, 0, 0, 3, 0, 1, 0, + 208, 2, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 27, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 2, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 2, 0, 0, 3, 0, 1, 0, + 216, 2, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 28, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 2, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 212, 2, 0, 0, 3, 0, 1, 0, + 224, 2, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 29, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 2, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 220, 2, 0, 0, 3, 0, 1, 0, + 232, 2, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 2, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 224, 2, 0, 0, 3, 0, 1, 0, + 236, 2, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 233, 2, 0, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 228, 2, 0, 0, 3, 0, 1, 0, + 240, 2, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 2, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 2, 0, 0, 3, 0, 1, 0, + 4, 3, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 3, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 252, 2, 0, 0, 3, 0, 1, 0, + 24, 3, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 3, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 3, 0, 0, 3, 0, 1, 0, + 44, 3, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 3, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 3, 0, 0, 3, 0, 1, 0, + 56, 3, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 53, 3, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 52, 3, 0, 0, 3, 0, 1, 0, + 64, 3, 0, 0, 2, 0, 1, 0, + 15, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 15, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 3, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 56, 3, 0, 0, 3, 0, 1, 0, + 68, 3, 0, 0, 2, 0, 1, 0, + 16, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 16, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 65, 3, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 3, 0, 0, 3, 0, 1, 0, + 76, 3, 0, 0, 2, 0, 1, 0, + 17, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 17, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 3, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 3, 0, 0, 3, 0, 1, 0, + 84, 3, 0, 0, 2, 0, 1, 0, + 18, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 81, 3, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 80, 3, 0, 0, 3, 0, 1, 0, + 92, 3, 0, 0, 2, 0, 1, 0, + 19, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 19, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 89, 3, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 88, 3, 0, 0, 3, 0, 1, 0, + 100, 3, 0, 0, 2, 0, 1, 0, + 20, 0, 0, 0, 11, 0, 0, 0, + 0, 0, 1, 0, 20, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 3, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 3, 0, 0, 3, 0, 1, 0, + 108, 3, 0, 0, 2, 0, 1, 0, + 21, 0, 0, 0, 12, 0, 0, 0, + 0, 0, 1, 0, 21, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 3, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 3, 0, 0, 3, 0, 1, 0, + 120, 3, 0, 0, 2, 0, 1, 0, + 22, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 22, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 3, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 3, 0, 0, 3, 0, 1, 0, + 144, 3, 0, 0, 2, 0, 1, 0, + 23, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 3, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 136, 3, 0, 0, 3, 0, 1, 0, + 148, 3, 0, 0, 2, 0, 1, 0, + 24, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 24, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 145, 3, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 140, 3, 0, 0, 3, 0, 1, 0, + 152, 3, 0, 0, 2, 0, 1, 0, + 115, 118, 73, 100, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 114, 101, 113, 117, 101, 110, 99, + 121, 73, 110, 100, 101, 120, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 97, 115, 80, 111, 115, 105, 116, + 105, 111, 110, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 97, 115, 73, 111, 110, 111, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 97, 115, 84, 114, 111, 112, 111, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 97, 115, 69, 108, 101, 118, 97, + 116, 105, 111, 110, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 108, 121, 70, 114, 111, 109, + 88, 116, 114, 97, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 97, 115, 83, 98, 97, 115, 73, + 111, 110, 111, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 111, 100, 101, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 48, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 121, 122, 48, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 121, 122, 78, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 116, 104, 101, 114, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 115, 105, 116, 105, 111, 110, + 85, 110, 99, 101, 114, 116, 97, 105, + 110, 116, 121, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 111, 110, 111, 68, 101, 108, 97, + 121, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 111, 110, 111, 68, 111, 116, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 98, 97, 115, 73, 111, 110, 111, + 68, 101, 108, 97, 121, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 98, 97, 115, 73, 111, 110, 111, + 68, 111, 116, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 114, 111, 112, 111, 68, 101, 108, + 97, 121, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 108, 101, 118, 97, 116, 105, 111, + 110, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 108, 101, 118, 97, 116, 105, 111, + 110, 68, 111, 116, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 108, 101, 118, 97, 116, 105, 111, + 110, 85, 110, 99, 101, 114, 116, 97, + 105, 110, 116, 121, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 101, 108, 111, 99, 105, 116, 121, + 67, 111, 101, 102, 102, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 87, 101, 101, 107, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 7, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 84, 111, 119, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_b1fb80811a673270 = b_b1fb80811a673270.words; +#if !CAPNP_LITE +static const uint16_t m_b1fb80811a673270[] = {19, 20, 21, 1, 24, 23, 5, 3, 2, 7, 4, 8, 14, 15, 12, 6, 13, 16, 17, 0, 9, 18, 22, 10, 11}; +static const uint16_t i_b1fb80811a673270[] = {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}; +const ::capnp::_::RawSchema s_b1fb80811a673270 = { + 0xb1fb80811a673270, b_b1fb80811a673270.words, 427, nullptr, m_b1fb80811a673270, + 0, 25, i_b1fb80811a673270, nullptr, nullptr, { &s_b1fb80811a673270, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<104> b_c95fb49a7bdc4618 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 24, 70, 220, 123, 154, 180, 95, 201, + 10, 0, 0, 0, 1, 0, 5, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 138, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 31, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 67, 108, 111, 99, 107, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 20, 0, 0, 0, 3, 0, 4, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 0, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 128, 0, 0, 0, 3, 0, 1, 0, + 140, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 137, 0, 0, 0, 202, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 144, 0, 0, 0, 3, 0, 1, 0, + 156, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 0, 0, 0, 218, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 160, 0, 0, 0, 3, 0, 1, 0, + 172, 0, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 169, 0, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 0, 0, 0, 3, 0, 1, 0, + 180, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 0, 0, 0, 226, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 0, 0, 0, 3, 0, 1, 0, + 196, 0, 0, 0, 2, 0, 1, 0, + 98, 111, 111, 116, 84, 105, 109, 101, + 78, 97, 110, 111, 115, 68, 69, 80, + 82, 69, 67, 65, 84, 69, 68, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 111, 110, 111, 116, 111, 110, 105, + 99, 78, 97, 110, 111, 115, 68, 69, + 80, 82, 69, 67, 65, 84, 69, 68, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 111, 110, 111, 116, 111, 110, 105, + 99, 82, 97, 119, 78, 97, 110, 111, + 115, 68, 69, 80, 82, 69, 67, 65, + 84, 68, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 119, 97, 108, 108, 84, 105, 109, 101, + 78, 97, 110, 111, 115, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 111, 100, 101, 109, 85, 112, 116, + 105, 109, 101, 77, 105, 108, 108, 105, + 115, 68, 69, 80, 82, 69, 67, 65, + 84, 69, 68, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_c95fb49a7bdc4618 = b_c95fb49a7bdc4618.words; +#if !CAPNP_LITE +static const uint16_t m_c95fb49a7bdc4618[] = {0, 4, 1, 2, 3}; +static const uint16_t i_c95fb49a7bdc4618[] = {0, 1, 2, 3, 4}; +const ::capnp::_::RawSchema s_c95fb49a7bdc4618 = { + 0xc95fb49a7bdc4618, b_c95fb49a7bdc4618.words, 104, nullptr, m_c95fb49a7bdc4618, + 0, 5, i_c95fb49a7bdc4618, nullptr, nullptr, { &s_c95fb49a7bdc4618, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<141> b_92a5e332a85f32a0 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 160, 50, 95, 168, 50, 227, 165, 146, + 10, 0, 0, 0, 1, 0, 3, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 4, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 178, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 143, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 76, 105, 118, 101, 77, 112, + 99, 68, 97, 116, 97, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 28, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 0, 0, 0, 3, 0, 1, 0, + 204, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 0, 0, 0, 3, 0, 1, 0, + 224, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 0, 0, 0, 3, 0, 1, 0, + 244, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 0, 0, 0, 3, 0, 1, 0, + 12, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 1, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 1, 0, 0, 3, 0, 1, 0, + 20, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 1, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 1, 0, 0, 3, 0, 1, 0, + 28, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 1, 0, 0, 3, 0, 1, 0, + 32, 1, 0, 0, 2, 0, 1, 0, + 120, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 115, 105, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 114, 118, 97, 116, 117, 114, + 101, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 112, 73, 116, 101, 114, 97, 116, + 105, 111, 110, 115, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 108, 99, 117, 108, 97, 116, + 105, 111, 110, 84, 105, 109, 101, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 111, 115, 116, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_92a5e332a85f32a0 = b_92a5e332a85f32a0.words; +#if !CAPNP_LITE +static const uint16_t m_92a5e332a85f32a0[] = {5, 6, 3, 2, 4, 0, 1}; +static const uint16_t i_92a5e332a85f32a0[] = {0, 1, 2, 3, 4, 5, 6}; +const ::capnp::_::RawSchema s_92a5e332a85f32a0 = { + 0x92a5e332a85f32a0, b_92a5e332a85f32a0.words, 141, nullptr, m_92a5e332a85f32a0, + 0, 7, i_92a5e332a85f32a0, nullptr, nullptr, { &s_92a5e332a85f32a0, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<211> b_e7e17c434f865ae2 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 226, 90, 134, 79, 67, 124, 225, 231, + 10, 0, 0, 0, 1, 0, 4, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 6, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 18, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 111, 2, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 76, 105, 118, 101, 76, 111, + 110, 103, 105, 116, 117, 100, 105, 110, + 97, 108, 77, 112, 99, 68, 97, 116, + 97, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 44, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 1, 0, 0, 3, 0, 1, 0, + 60, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 57, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 52, 1, 0, 0, 3, 0, 1, 0, + 80, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 1, 0, 0, 3, 0, 1, 0, + 100, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 1, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 1, 0, 0, 3, 0, 1, 0, + 120, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 1, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 1, 0, 0, 3, 0, 1, 0, + 140, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 137, 1, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 132, 1, 0, 0, 3, 0, 1, 0, + 160, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 157, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 156, 1, 0, 0, 3, 0, 1, 0, + 168, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 165, 1, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 164, 1, 0, 0, 3, 0, 1, 0, + 176, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 173, 1, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 1, 0, 0, 3, 0, 1, 0, + 180, 1, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 1, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 1, 0, 0, 3, 0, 1, 0, + 188, 1, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 1, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 1, 0, 0, 3, 0, 1, 0, + 192, 1, 0, 0, 2, 0, 1, 0, + 120, 69, 103, 111, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 69, 103, 111, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 69, 103, 111, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 76, 101, 97, 100, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 76, 101, 97, 100, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 76, 101, 97, 100, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 76, 101, 97, 100, 84, 97, 117, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 112, 73, 116, 101, 114, 97, 116, + 105, 111, 110, 115, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 112, 99, 73, 100, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 108, 99, 117, 108, 97, 116, + 105, 111, 110, 84, 105, 109, 101, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 111, 115, 116, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 11, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e7e17c434f865ae2 = b_e7e17c434f865ae2.words; +#if !CAPNP_LITE +static const uint16_t m_e7e17c434f865ae2[] = {2, 5, 6, 9, 10, 8, 7, 1, 4, 0, 3}; +static const uint16_t i_e7e17c434f865ae2[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10}; +const ::capnp::_::RawSchema s_e7e17c434f865ae2 = { + 0xe7e17c434f865ae2, b_e7e17c434f865ae2.words, 211, nullptr, m_e7e17c434f865ae2, + 0, 11, i_e7e17c434f865ae2, nullptr, nullptr, { &s_e7e17c434f865ae2, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<55> b_e42401658e2715e2 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 226, 21, 39, 142, 101, 1, 36, 228, + 10, 0, 0, 0, 1, 0, 0, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 154, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 74, 111, 121, 115, 116, 105, + 99, 107, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 64, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 56, 0, 0, 0, 3, 0, 1, 0, + 84, 0, 0, 0, 2, 0, 1, 0, + 97, 120, 101, 115, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 117, 116, 116, 111, 110, 115, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e42401658e2715e2 = b_e42401658e2715e2.words; +#if !CAPNP_LITE +static const uint16_t m_e42401658e2715e2[] = {0, 1}; +static const uint16_t i_e42401658e2715e2[] = {0, 1}; +const ::capnp::_::RawSchema s_e42401658e2715e2 = { + 0xe42401658e2715e2, b_e42401658e2715e2.words, 55, nullptr, m_e42401658e2715e2, + 0, 2, i_e42401658e2715e2, nullptr, nullptr, { &s_e42401658e2715e2, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<151> b_fc010c40147563b0 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 176, 99, 117, 20, 64, 12, 1, 252, + 10, 0, 0, 0, 1, 0, 3, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 3, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 194, 0, 0, 0, + 29, 0, 0, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 199, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 68, 114, 105, 118, 101, 114, + 83, 116, 97, 116, 101, 86, 50, 0, + 4, 0, 0, 0, 1, 0, 1, 0, + 106, 138, 242, 205, 177, 59, 247, 201, + 1, 0, 0, 0, 90, 0, 0, 0, + 68, 114, 105, 118, 101, 114, 68, 97, + 116, 97, 0, 0, 0, 0, 0, 0, + 32, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 0, 0, 0, 3, 0, 1, 0, + 216, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 0, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 0, 0, 0, 3, 0, 1, 0, + 228, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 225, 0, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 228, 0, 0, 0, 3, 0, 1, 0, + 240, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 0, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 236, 0, 0, 0, 3, 0, 1, 0, + 248, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 245, 0, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 244, 0, 0, 0, 3, 0, 1, 0, + 0, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 253, 0, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 1, 0, 0, 3, 0, 1, 0, + 12, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 1, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 1, 0, 0, 3, 0, 1, 0, + 20, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 1, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 1, 0, 0, 3, 0, 1, 0, + 28, 1, 0, 0, 2, 0, 1, 0, + 102, 114, 97, 109, 101, 73, 100, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 111, 100, 101, 108, 69, 120, 101, + 99, 117, 116, 105, 111, 110, 84, 105, + 109, 101, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 115, 112, 69, 120, 101, 99, 117, + 116, 105, 111, 110, 84, 105, 109, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 97, 119, 80, 114, 101, 100, 105, + 99, 116, 105, 111, 110, 115, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 111, 114, 86, 105, 115, 105, + 111, 110, 80, 114, 111, 98, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 119, 104, 101, 101, 108, 79, 110, 82, + 105, 103, 104, 116, 80, 114, 111, 98, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 102, 116, 68, 114, 105, 118, + 101, 114, 68, 97, 116, 97, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 106, 138, 242, 205, 177, 59, 247, 201, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 105, 103, 104, 116, 68, 114, 105, + 118, 101, 114, 68, 97, 116, 97, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 106, 138, 242, 205, 177, 59, 247, 201, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_fc010c40147563b0 = b_fc010c40147563b0.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_fc010c40147563b0[] = { + &s_c9f73bb1cdf28a6a, +}; +static const uint16_t m_fc010c40147563b0[] = {2, 0, 6, 1, 4, 3, 7, 5}; +static const uint16_t i_fc010c40147563b0[] = {0, 1, 2, 3, 4, 5, 6, 7}; +const ::capnp::_::RawSchema s_fc010c40147563b0 = { + 0xfc010c40147563b0, b_fc010c40147563b0.words, 151, d_fc010c40147563b0, m_fc010c40147563b0, + 1, 8, i_fc010c40147563b0, nullptr, nullptr, { &s_fc010c40147563b0, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<252> b_c9f73bb1cdf28a6a = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 106, 138, 242, 205, 177, 59, 247, 201, + 24, 0, 0, 0, 1, 0, 4, 0, + 176, 99, 117, 20, 64, 12, 1, 252, + 6, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 26, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 223, 2, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 68, 114, 105, 118, 101, 114, + 83, 116, 97, 116, 101, 86, 50, 46, + 68, 114, 105, 118, 101, 114, 68, 97, + 116, 97, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 52, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 1, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 1, 0, 0, 3, 0, 1, 0, + 120, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 1, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 1, 0, 0, 3, 0, 1, 0, + 148, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 145, 1, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 144, 1, 0, 0, 3, 0, 1, 0, + 172, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 169, 1, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 1, 0, 0, 3, 0, 1, 0, + 196, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 192, 1, 0, 0, 3, 0, 1, 0, + 204, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 1, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 200, 1, 0, 0, 3, 0, 1, 0, + 212, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 1, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 1, 0, 0, 3, 0, 1, 0, + 220, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 217, 1, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 1, 0, 0, 3, 0, 1, 0, + 228, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 225, 1, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 224, 1, 0, 0, 3, 0, 1, 0, + 236, 1, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 233, 1, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 1, 0, 0, 3, 0, 1, 0, + 244, 1, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 1, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 1, 0, 0, 3, 0, 1, 0, + 252, 1, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 249, 1, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 248, 1, 0, 0, 3, 0, 1, 0, + 20, 2, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 2, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 2, 0, 0, 3, 0, 1, 0, + 44, 2, 0, 0, 2, 0, 1, 0, + 102, 97, 99, 101, 79, 114, 105, 101, + 110, 116, 97, 116, 105, 111, 110, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 97, 99, 101, 79, 114, 105, 101, + 110, 116, 97, 116, 105, 111, 110, 83, + 116, 100, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 97, 99, 101, 80, 111, 115, 105, + 116, 105, 111, 110, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 97, 99, 101, 80, 111, 115, 105, + 116, 105, 111, 110, 83, 116, 100, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 97, 99, 101, 80, 114, 111, 98, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 102, 116, 69, 121, 101, 80, + 114, 111, 98, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 105, 103, 104, 116, 69, 121, 101, + 80, 114, 111, 98, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 102, 116, 66, 108, 105, 110, + 107, 80, 114, 111, 98, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 105, 103, 104, 116, 66, 108, 105, + 110, 107, 80, 114, 111, 98, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 117, 110, 103, 108, 97, 115, 115, + 101, 115, 80, 114, 111, 98, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 99, 99, 108, 117, 100, 101, 100, + 80, 114, 111, 98, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 101, 97, 100, 121, 80, 114, 111, + 98, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 111, 116, 82, 101, 97, 100, 121, + 80, 114, 111, 98, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_c9f73bb1cdf28a6a = b_c9f73bb1cdf28a6a.words; +#if !CAPNP_LITE +static const uint16_t m_c9f73bb1cdf28a6a[] = {0, 1, 2, 3, 4, 7, 5, 12, 10, 11, 8, 6, 9}; +static const uint16_t i_c9f73bb1cdf28a6a[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12}; +const ::capnp::_::RawSchema s_c9f73bb1cdf28a6a = { + 0xc9f73bb1cdf28a6a, b_c9f73bb1cdf28a6a.words, 252, nullptr, m_c9f73bb1cdf28a6a, + 0, 13, i_c9f73bb1cdf28a6a, nullptr, nullptr, { &s_c9f73bb1cdf28a6a, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<465> b_b83c6cc593ed0a00 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 0, 10, 237, 147, 197, 108, 60, 184, + 10, 0, 0, 0, 1, 0, 9, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 8, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 2, 1, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 183, 5, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 68, 114, 105, 118, 101, 114, + 83, 116, 97, 116, 101, 68, 69, 80, + 82, 69, 67, 65, 84, 69, 68, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 104, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 2, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 2, 0, 0, 3, 0, 1, 0, + 208, 2, 0, 0, 2, 0, 1, 0, + 24, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 2, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 2, 0, 0, 3, 0, 1, 0, + 236, 2, 0, 0, 2, 0, 1, 0, + 25, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 233, 2, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 2, 0, 0, 3, 0, 1, 0, + 244, 2, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 2, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 2, 0, 0, 3, 0, 1, 0, + 12, 3, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 3, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 3, 0, 0, 3, 0, 1, 0, + 36, 3, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 3, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 3, 0, 0, 3, 0, 1, 0, + 44, 3, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 3, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 3, 0, 0, 3, 0, 1, 0, + 52, 3, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 3, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 3, 0, 0, 3, 0, 1, 0, + 60, 3, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 57, 3, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 56, 3, 0, 0, 3, 0, 1, 0, + 68, 3, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 65, 3, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 3, 0, 0, 3, 0, 1, 0, + 76, 3, 0, 0, 2, 0, 1, 0, + 23, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 3, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 3, 0, 0, 3, 0, 1, 0, + 84, 3, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 81, 3, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 84, 3, 0, 0, 3, 0, 1, 0, + 112, 3, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 3, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 3, 0, 0, 3, 0, 1, 0, + 136, 3, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 3, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 132, 3, 0, 0, 3, 0, 1, 0, + 144, 3, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 3, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 144, 3, 0, 0, 3, 0, 1, 0, + 156, 3, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 15, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 3, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 152, 3, 0, 0, 3, 0, 1, 0, + 164, 3, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 16, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 161, 3, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 164, 3, 0, 0, 3, 0, 1, 0, + 176, 3, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 11, 0, 0, 0, + 0, 0, 1, 0, 17, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 173, 3, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 172, 3, 0, 0, 3, 0, 1, 0, + 184, 3, 0, 0, 2, 0, 1, 0, + 15, 0, 0, 0, 12, 0, 0, 0, + 0, 0, 1, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 3, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 3, 0, 0, 3, 0, 1, 0, + 192, 3, 0, 0, 2, 0, 1, 0, + 16, 0, 0, 0, 13, 0, 0, 0, + 0, 0, 1, 0, 19, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 3, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 3, 0, 0, 3, 0, 1, 0, + 200, 3, 0, 0, 2, 0, 1, 0, + 17, 0, 0, 0, 14, 0, 0, 0, + 0, 0, 1, 0, 20, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 3, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 3, 0, 0, 3, 0, 1, 0, + 208, 3, 0, 0, 2, 0, 1, 0, + 18, 0, 0, 0, 15, 0, 0, 0, + 0, 0, 1, 0, 21, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 3, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 3, 0, 0, 3, 0, 1, 0, + 216, 3, 0, 0, 2, 0, 1, 0, + 19, 0, 0, 0, 16, 0, 0, 0, + 0, 0, 1, 0, 22, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 3, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 212, 3, 0, 0, 3, 0, 1, 0, + 224, 3, 0, 0, 2, 0, 1, 0, + 20, 0, 0, 0, 17, 0, 0, 0, + 0, 0, 1, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 3, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 220, 3, 0, 0, 3, 0, 1, 0, + 232, 3, 0, 0, 2, 0, 1, 0, + 21, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 24, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 3, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 228, 3, 0, 0, 3, 0, 1, 0, + 0, 4, 0, 0, 2, 0, 1, 0, + 22, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 25, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 253, 3, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 252, 3, 0, 0, 3, 0, 1, 0, + 24, 4, 0, 0, 2, 0, 1, 0, + 102, 114, 97, 109, 101, 73, 100, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 115, 99, 114, 105, 112, 116, + 111, 114, 68, 69, 80, 82, 69, 67, + 65, 84, 69, 68, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 100, 68, 69, 80, 82, 69, + 67, 65, 84, 69, 68, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 97, 99, 101, 79, 114, 105, 101, + 110, 116, 97, 116, 105, 111, 110, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 97, 99, 101, 80, 111, 115, 105, + 116, 105, 111, 110, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 97, 99, 101, 80, 114, 111, 98, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 102, 116, 69, 121, 101, 80, + 114, 111, 98, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 105, 103, 104, 116, 69, 121, 101, + 80, 114, 111, 98, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 101, 102, 116, 66, 108, 105, 110, + 107, 80, 114, 111, 98, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 105, 103, 104, 116, 66, 108, 105, + 110, 107, 80, 114, 111, 98, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 114, 80, 119, 114, 68, 69, 80, + 82, 69, 67, 65, 84, 69, 68, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 97, 99, 101, 79, 114, 105, 101, + 110, 116, 97, 116, 105, 111, 110, 83, + 116, 100, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 97, 99, 101, 80, 111, 115, 105, + 116, 105, 111, 110, 83, 116, 100, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 117, 110, 103, 108, 97, 115, 115, + 101, 115, 80, 114, 111, 98, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 111, 100, 101, 108, 69, 120, 101, + 99, 117, 116, 105, 111, 110, 84, 105, + 109, 101, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 97, 119, 80, 114, 101, 100, 105, + 99, 116, 105, 111, 110, 115, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 115, 112, 69, 120, 101, 99, 117, + 116, 105, 111, 110, 84, 105, 109, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 111, 114, 86, 105, 115, 105, + 111, 110, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 97, 114, 116, 105, 97, 108, 70, + 97, 99, 101, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 105, 115, 116, 114, 97, 99, 116, + 101, 100, 80, 111, 115, 101, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 105, 115, 116, 114, 97, 99, 116, + 101, 100, 69, 121, 101, 115, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 121, 101, 115, 79, 110, 82, 111, + 97, 100, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 104, 111, 110, 101, 85, 115, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 99, 99, 108, 117, 100, 101, 100, + 80, 114, 111, 98, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 101, 97, 100, 121, 80, 114, 111, + 98, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 111, 116, 82, 101, 97, 100, 121, + 80, 114, 111, 98, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_b83c6cc593ed0a00 = b_b83c6cc593ed0a00.words; +#if !CAPNP_LITE +static const uint16_t m_b83c6cc593ed0a00[] = {1, 20, 19, 16, 21, 3, 11, 4, 12, 5, 0, 10, 8, 6, 14, 25, 23, 18, 22, 17, 15, 24, 9, 7, 2, 13}; +static const uint16_t i_b83c6cc593ed0a00[] = {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}; +const ::capnp::_::RawSchema s_b83c6cc593ed0a00 = { + 0xb83c6cc593ed0a00, b_b83c6cc593ed0a00.words, 465, nullptr, m_b83c6cc593ed0a00, + 0, 26, i_b83c6cc593ed0a00, nullptr, nullptr, { &s_b83c6cc593ed0a00, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<313> b_b83cda094a1da284 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 132, 162, 29, 74, 9, 218, 60, 184, + 10, 0, 0, 0, 1, 0, 6, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 2, 1, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 247, 3, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 68, 114, 105, 118, 101, 114, + 77, 111, 110, 105, 116, 111, 114, 105, + 110, 103, 83, 116, 97, 116, 101, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 72, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 233, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 228, 1, 0, 0, 3, 0, 1, 0, + 0, 2, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 253, 1, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 252, 1, 0, 0, 3, 0, 1, 0, + 8, 2, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 2, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 2, 0, 0, 3, 0, 1, 0, + 16, 2, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 2, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 2, 0, 0, 3, 0, 1, 0, + 24, 2, 0, 0, 2, 0, 1, 0, + 15, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 2, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 2, 0, 0, 3, 0, 1, 0, + 28, 2, 0, 0, 2, 0, 1, 0, + 17, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 2, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 28, 2, 0, 0, 3, 0, 1, 0, + 40, 2, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 2, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 2, 0, 0, 3, 0, 1, 0, + 48, 2, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 2, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 2, 0, 0, 3, 0, 1, 0, + 60, 2, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 57, 2, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 56, 2, 0, 0, 3, 0, 1, 0, + 68, 2, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 65, 2, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 2, 0, 0, 3, 0, 1, 0, + 80, 2, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 2, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 2, 0, 0, 3, 0, 1, 0, + 88, 2, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 85, 2, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 84, 2, 0, 0, 3, 0, 1, 0, + 96, 2, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 2, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 2, 0, 0, 3, 0, 1, 0, + 108, 2, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 2, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 2, 0, 0, 3, 0, 1, 0, + 116, 2, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 2, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 2, 0, 0, 3, 0, 1, 0, + 124, 2, 0, 0, 2, 0, 1, 0, + 16, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 15, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 2, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 2, 0, 0, 3, 0, 1, 0, + 136, 2, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 16, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 2, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 132, 2, 0, 0, 3, 0, 1, 0, + 144, 2, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 17, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 2, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 140, 2, 0, 0, 3, 0, 1, 0, + 152, 2, 0, 0, 2, 0, 1, 0, + 101, 118, 101, 110, 116, 115, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 211, 58, 175, 76, 243, 87, 22, 155, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 97, 99, 101, 68, 101, 116, 101, + 99, 116, 101, 100, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 115, 68, 105, 115, 116, 114, 97, + 99, 116, 101, 100, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 119, 97, 114, 101, 110, 101, 115, + 115, 83, 116, 97, 116, 117, 115, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 115, 82, 72, 68, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 104, 100, 67, 104, 101, 99, 107, + 101, 100, 68, 69, 80, 82, 69, 67, + 65, 84, 69, 68, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 115, 101, 80, 105, 116, 99, + 104, 79, 102, 102, 115, 101, 116, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 115, 101, 80, 105, 116, 99, + 104, 86, 97, 108, 105, 100, 67, 111, + 117, 110, 116, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 115, 101, 89, 97, 119, 79, + 102, 102, 115, 101, 116, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 115, 101, 89, 97, 119, 86, + 97, 108, 105, 100, 67, 111, 117, 110, + 116, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 112, 67, 104, 97, 110, + 103, 101, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 119, 97, 114, 101, 110, 101, 115, + 115, 65, 99, 116, 105, 118, 101, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 119, 97, 114, 101, 110, 101, 115, + 115, 80, 97, 115, 115, 105, 118, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 115, 76, 111, 119, 83, 116, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 105, 83, 116, 100, 67, 111, 117, + 110, 116, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 115, 80, 114, 101, 118, 105, 101, + 119, 68, 69, 80, 82, 69, 67, 65, + 84, 69, 68, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 115, 65, 99, 116, 105, 118, 101, + 77, 111, 100, 101, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 105, 115, 116, 114, 97, 99, 116, + 101, 100, 84, 121, 112, 101, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_b83cda094a1da284 = b_b83cda094a1da284.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_b83cda094a1da284[] = { + &s_9b1657f34caf3ad3, +}; +static const uint16_t m_b83cda094a1da284[] = {11, 12, 3, 17, 0, 1, 14, 16, 2, 13, 15, 4, 6, 7, 8, 9, 5, 10}; +static const uint16_t i_b83cda094a1da284[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17}; +const ::capnp::_::RawSchema s_b83cda094a1da284 = { + 0xb83cda094a1da284, b_b83cda094a1da284.words, 313, d_b83cda094a1da284, m_b83cda094a1da284, + 1, 18, i_b83cda094a1da284, nullptr, nullptr, { &s_b83cda094a1da284, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<149> b_a12e8670927a2549 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 73, 37, 122, 146, 112, 134, 46, 161, + 10, 0, 0, 0, 1, 0, 1, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 5, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 122, 0, 0, 0, + 25, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 87, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 66, 111, 111, 116, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 24, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 0, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 152, 0, 0, 0, 3, 0, 1, 0, + 164, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 161, 0, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 164, 0, 0, 0, 3, 0, 1, 0, + 176, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 173, 0, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 0, 0, 0, 3, 0, 1, 0, + 188, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 0, 0, 0, 3, 0, 1, 0, + 196, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 0, 0, 0, 3, 0, 1, 0, + 16, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 1, 0, 0, 3, 0, 1, 0, + 96, 1, 0, 0, 2, 0, 1, 0, + 119, 97, 108, 108, 84, 105, 109, 101, + 78, 97, 110, 111, 115, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 115, 116, 75, 109, 115, 103, + 68, 69, 80, 82, 69, 67, 65, 84, + 69, 68, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 115, 116, 80, 109, 115, 103, + 68, 69, 80, 82, 69, 67, 65, 84, + 69, 68, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 117, 110, 99, 104, 76, 111, + 103, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 115, 116, 111, 114, 101, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 150, 182, 62, 24, 226, 60, 177, 248, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 1, 0, + 1, 0, 0, 0, 31, 0, 0, 0, + 4, 0, 0, 0, 2, 0, 1, 0, + 150, 182, 62, 24, 226, 60, 177, 248, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 39, 0, 0, 0, + 8, 0, 0, 0, 1, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 3, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 3, 0, 1, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 111, 109, 109, 97, 110, 100, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 150, 182, 62, 24, 226, 60, 177, 248, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 1, 0, + 1, 0, 0, 0, 31, 0, 0, 0, + 4, 0, 0, 0, 2, 0, 1, 0, + 150, 182, 62, 24, 226, 60, 177, 248, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 39, 0, 0, 0, + 8, 0, 0, 0, 1, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 3, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 3, 0, 1, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_a12e8670927a2549 = b_a12e8670927a2549.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_a12e8670927a2549[] = { + &s_f8b13ce2183eb696, +}; +static const uint16_t m_a12e8670927a2549[] = {5, 1, 2, 3, 4, 0}; +static const uint16_t i_a12e8670927a2549[] = {0, 1, 2, 3, 4, 5}; +KJ_CONSTEXPR(const) ::capnp::_::RawBrandedSchema::Dependency bd_a12e8670927a2549[] = { + { 16777220, ::cereal::Map< ::capnp::Text, ::capnp::Data>::_capnpPrivate::brand() }, + { 16777221, ::cereal::Map< ::capnp::Text, ::capnp::Data>::_capnpPrivate::brand() }, +}; +const ::capnp::_::RawSchema s_a12e8670927a2549 = { + 0xa12e8670927a2549, b_a12e8670927a2549.words, 149, d_a12e8670927a2549, m_a12e8670927a2549, + 1, 6, i_a12e8670927a2549, nullptr, nullptr, { &s_a12e8670927a2549, nullptr, bd_a12e8670927a2549, 0, sizeof(bd_a12e8670927a2549) / sizeof(bd_a12e8670927a2549[0]), nullptr }, true +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<277> b_d9058dcb967c2753 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 83, 39, 124, 150, 203, 141, 5, 217, + 10, 0, 0, 0, 1, 0, 7, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 234, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 135, 3, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 76, 105, 118, 101, 80, 97, + 114, 97, 109, 101, 116, 101, 114, 115, + 68, 97, 116, 97, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 64, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 1, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 172, 1, 0, 0, 3, 0, 1, 0, + 184, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 1, 0, 0, 3, 0, 1, 0, + 192, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 1, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 1, 0, 0, 3, 0, 1, 0, + 200, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 1, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 200, 1, 0, 0, 3, 0, 1, 0, + 212, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 1, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 1, 0, 0, 3, 0, 1, 0, + 220, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 217, 1, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 1, 0, 0, 3, 0, 1, 0, + 228, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 225, 1, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 224, 1, 0, 0, 3, 0, 1, 0, + 236, 1, 0, 0, 2, 0, 1, 0, + 15, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 233, 1, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 236, 1, 0, 0, 3, 0, 1, 0, + 248, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 245, 1, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 244, 1, 0, 0, 3, 0, 1, 0, + 0, 2, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 253, 1, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 252, 1, 0, 0, 3, 0, 1, 0, + 8, 2, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 2, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 2, 0, 0, 3, 0, 1, 0, + 20, 2, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 2, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 2, 0, 0, 3, 0, 1, 0, + 32, 2, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 2, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 2, 0, 0, 3, 0, 1, 0, + 44, 2, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 11, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 2, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 2, 0, 0, 3, 0, 1, 0, + 52, 2, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 12, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 2, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 2, 0, 0, 3, 0, 1, 0, + 56, 2, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 15, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 53, 2, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 52, 2, 0, 0, 3, 0, 1, 0, + 64, 2, 0, 0, 2, 0, 1, 0, + 118, 97, 108, 105, 100, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 121, 114, 111, 66, 105, 97, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 110, 103, 108, 101, 79, 102, 102, + 115, 101, 116, 68, 101, 103, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 110, 103, 108, 101, 79, 102, 102, + 115, 101, 116, 65, 118, 101, 114, 97, + 103, 101, 68, 101, 103, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 105, 102, 102, 110, 101, 115, + 115, 70, 97, 99, 116, 111, 114, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 82, 97, 116, + 105, 111, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 101, 110, 115, 111, 114, 86, 97, + 108, 105, 100, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 97, 119, 82, 97, 116, 101, 68, + 69, 80, 82, 69, 67, 65, 84, 69, + 68, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 115, 101, 110, 101, 116, 83, + 112, 101, 101, 100, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 115, 101, 110, 101, 116, 86, + 97, 108, 105, 100, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 110, 103, 108, 101, 79, 102, 102, + 115, 101, 116, 70, 97, 115, 116, 83, + 116, 100, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 110, 103, 108, 101, 79, 102, 102, + 115, 101, 116, 65, 118, 101, 114, 97, + 103, 101, 83, 116, 100, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 105, 102, 102, 110, 101, 115, + 115, 70, 97, 99, 116, 111, 114, 83, + 116, 100, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 116, 101, 101, 114, 82, 97, 116, + 105, 111, 83, 116, 100, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 111, 108, 108, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 105, 108, 116, 101, 114, 83, 116, + 97, 116, 101, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 28, 206, 218, 102, 237, 249, 35, 191, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_d9058dcb967c2753 = b_d9058dcb967c2753.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_d9058dcb967c2753[] = { + &s_bf23f9ed66dace1c, +}; +static const uint16_t m_d9058dcb967c2753[] = {3, 11, 2, 10, 15, 1, 8, 9, 14, 6, 5, 13, 4, 12, 0, 7}; +static const uint16_t i_d9058dcb967c2753[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15}; +const ::capnp::_::RawSchema s_d9058dcb967c2753 = { + 0xd9058dcb967c2753, b_d9058dcb967c2753.words, 277, d_d9058dcb967c2753, m_d9058dcb967c2753, + 1, 16, i_d9058dcb967c2753, nullptr, nullptr, { &s_d9058dcb967c2753, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<240> b_e61690eb0b091692 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 146, 22, 9, 11, 235, 144, 22, 230, + 10, 0, 0, 0, 1, 0, 6, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 26, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 223, 2, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 76, 105, 118, 101, 84, 111, + 114, 113, 117, 101, 80, 97, 114, 97, + 109, 101, 116, 101, 114, 115, 68, 97, + 116, 97, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 52, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 1, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 1, 0, 0, 3, 0, 1, 0, + 104, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 1, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 1, 0, 0, 3, 0, 1, 0, + 116, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 1, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 1, 0, 0, 3, 0, 1, 0, + 128, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 1, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 128, 1, 0, 0, 3, 0, 1, 0, + 140, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 137, 1, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 140, 1, 0, 0, 3, 0, 1, 0, + 152, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 149, 1, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 152, 1, 0, 0, 3, 0, 1, 0, + 164, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 161, 1, 0, 0, 226, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 1, 0, 0, 3, 0, 1, 0, + 180, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 1, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 1, 0, 0, 3, 0, 1, 0, + 192, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 1, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 1, 0, 0, 3, 0, 1, 0, + 196, 1, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 1, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 192, 1, 0, 0, 3, 0, 1, 0, + 204, 1, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 1, 0, 0, 3, 0, 1, 0, + 240, 1, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 10, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 1, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 1, 0, 0, 3, 0, 1, 0, + 244, 1, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 1, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 1, 0, 0, 3, 0, 1, 0, + 252, 1, 0, 0, 2, 0, 1, 0, + 108, 105, 118, 101, 86, 97, 108, 105, + 100, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 116, 65, 99, 99, 101, 108, + 70, 97, 99, 116, 111, 114, 82, 97, + 119, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 116, 65, 99, 99, 101, 108, + 79, 102, 102, 115, 101, 116, 82, 97, + 119, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 114, 105, 99, 116, 105, 111, 110, + 67, 111, 101, 102, 102, 105, 99, 105, + 101, 110, 116, 82, 97, 119, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 116, 65, 99, 99, 101, 108, + 70, 97, 99, 116, 111, 114, 70, 105, + 108, 116, 101, 114, 101, 100, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 116, 65, 99, 99, 101, 108, + 79, 102, 102, 115, 101, 116, 70, 105, + 108, 116, 101, 114, 101, 100, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 114, 105, 99, 116, 105, 111, 110, + 67, 111, 101, 102, 102, 105, 99, 105, + 101, 110, 116, 70, 105, 108, 116, 101, + 114, 101, 100, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 111, 116, 97, 108, 66, 117, 99, + 107, 101, 116, 80, 111, 105, 110, 116, + 115, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 99, 97, 121, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 97, 120, 82, 101, 115, 101, 116, + 115, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 105, 110, 116, 115, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 101, 114, 115, 105, 111, 110, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 115, 101, 80, 97, 114, 97, 109, + 115, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_e61690eb0b091692 = b_e61690eb0b091692.words; +#if !CAPNP_LITE +static const uint16_t m_e61690eb0b091692[] = {8, 6, 3, 4, 1, 5, 2, 0, 9, 10, 7, 12, 11}; +static const uint16_t i_e61690eb0b091692[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12}; +const ::capnp::_::RawSchema s_e61690eb0b091692 = { + 0xe61690eb0b091692, b_e61690eb0b091692.words, 240, nullptr, m_e61690eb0b091692, + 0, 13, i_e61690eb0b091692, nullptr, nullptr, { &s_e61690eb0b091692, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<305> b_943e268f93f711a6 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 166, 17, 247, 147, 143, 38, 62, 148, + 10, 0, 0, 0, 1, 0, 5, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 5, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 2, 1, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 191, 3, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 76, 105, 118, 101, 77, 97, + 112, 68, 97, 116, 97, 68, 69, 80, + 82, 69, 67, 65, 84, 69, 68, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 68, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 1, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 1, 0, 0, 3, 0, 1, 0, + 216, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 1, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 212, 1, 0, 0, 3, 0, 1, 0, + 224, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 1, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 220, 1, 0, 0, 3, 0, 1, 0, + 232, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 1, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 228, 1, 0, 0, 3, 0, 1, 0, + 240, 1, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 1, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 1, 0, 0, 3, 0, 1, 0, + 244, 1, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 1, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 236, 1, 0, 0, 3, 0, 1, 0, + 8, 2, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 2, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 2, 0, 0, 3, 0, 1, 0, + 28, 2, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 2, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 2, 0, 0, 3, 0, 1, 0, + 32, 2, 0, 0, 2, 0, 1, 0, + 13, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 2, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 28, 2, 0, 0, 3, 0, 1, 0, + 56, 2, 0, 0, 2, 0, 1, 0, + 14, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 53, 2, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 52, 2, 0, 0, 3, 0, 1, 0, + 80, 2, 0, 0, 2, 0, 1, 0, + 15, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 2, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 2, 0, 0, 3, 0, 1, 0, + 88, 2, 0, 0, 2, 0, 1, 0, + 16, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 85, 2, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 84, 2, 0, 0, 3, 0, 1, 0, + 96, 2, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 2, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 2, 0, 0, 3, 0, 1, 0, + 108, 2, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 2, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 2, 0, 0, 3, 0, 1, 0, + 116, 2, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 2, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 2, 0, 0, 3, 0, 1, 0, + 128, 2, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 15, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 2, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 2, 0, 0, 3, 0, 1, 0, + 136, 2, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 8, 0, 0, 0, + 0, 0, 1, 0, 16, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 2, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 136, 2, 0, 0, 3, 0, 1, 0, + 148, 2, 0, 0, 2, 0, 1, 0, + 115, 112, 101, 101, 100, 76, 105, 109, + 105, 116, 86, 97, 108, 105, 100, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 112, 101, 101, 100, 76, 105, 109, + 105, 116, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 114, 118, 97, 116, 117, 114, + 101, 86, 97, 108, 105, 100, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 114, 118, 97, 116, 117, 114, + 101, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 119, 97, 121, 73, 100, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 111, 97, 100, 88, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 111, 97, 100, 89, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 115, 116, 71, 112, 115, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 14, 213, 173, 89, 72, 82, 70, 233, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 111, 97, 100, 67, 117, 114, 118, + 97, 116, 117, 114, 101, 88, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 111, 97, 100, 67, 117, 114, 118, + 97, 116, 117, 114, 101, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 105, 115, 116, 84, 111, 84, 117, + 114, 110, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 97, 112, 86, 97, 108, 105, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 112, 101, 101, 100, 65, 100, 118, + 105, 115, 111, 114, 121, 86, 97, 108, + 105, 100, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 112, 101, 101, 100, 65, 100, 118, + 105, 115, 111, 114, 121, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 112, 101, 101, 100, 76, 105, 109, + 105, 116, 65, 104, 101, 97, 100, 86, + 97, 108, 105, 100, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 112, 101, 101, 100, 76, 105, 109, + 105, 116, 65, 104, 101, 97, 100, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 112, 101, 101, 100, 76, 105, 109, + 105, 116, 65, 104, 101, 97, 100, 68, + 105, 115, 116, 97, 110, 99, 101, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_943e268f93f711a6 = b_943e268f93f711a6.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_943e268f93f711a6[] = { + &s_e946524859add50e, +}; +static const uint16_t m_943e268f93f711a6[] = {3, 2, 10, 7, 11, 9, 8, 5, 6, 13, 12, 1, 15, 16, 14, 0, 4}; +static const uint16_t i_943e268f93f711a6[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16}; +const ::capnp::_::RawSchema s_943e268f93f711a6 = { + 0x943e268f93f711a6, b_943e268f93f711a6.words, 305, d_943e268f93f711a6, m_943e268f93f711a6, + 1, 17, i_943e268f93f711a6, nullptr, nullptr, { &s_943e268f93f711a6, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<210> b_fa9a296b9fd41a96 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 150, 26, 212, 159, 107, 41, 154, 250, + 10, 0, 0, 0, 1, 0, 2, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 8, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 202, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 55, 2, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 67, 97, 109, 101, 114, 97, + 79, 100, 111, 109, 101, 116, 114, 121, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 40, 0, 0, 0, 3, 0, 4, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 1, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 1, 0, 0, 3, 0, 1, 0, + 32, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 1, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 24, 1, 0, 0, 3, 0, 1, 0, + 52, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 1, 0, 0, 3, 0, 1, 0, + 76, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 1, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 1, 0, 0, 3, 0, 1, 0, + 96, 1, 0, 0, 2, 0, 1, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 1, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 88, 1, 0, 0, 3, 0, 1, 0, + 100, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 1, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 1, 0, 0, 3, 0, 1, 0, + 108, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 1, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 1, 0, 0, 3, 0, 1, 0, + 136, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 1, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 136, 1, 0, 0, 3, 0, 1, 0, + 164, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 6, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 161, 1, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 164, 1, 0, 0, 3, 0, 1, 0, + 192, 1, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 1, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 192, 1, 0, 0, 3, 0, 1, 0, + 220, 1, 0, 0, 2, 0, 1, 0, + 116, 114, 97, 110, 115, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 111, 116, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 114, 97, 110, 115, 83, 116, 100, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 111, 116, 83, 116, 100, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 114, 97, 109, 101, 73, 100, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 109, 101, 115, 116, 97, 109, + 112, 69, 111, 102, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 119, 105, 100, 101, 70, 114, 111, 109, + 68, 101, 118, 105, 99, 101, 69, 117, + 108, 101, 114, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 119, 105, 100, 101, 70, 114, 111, 109, + 68, 101, 118, 105, 99, 101, 69, 117, + 108, 101, 114, 83, 116, 100, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 111, 97, 100, 84, 114, 97, 110, + 115, 102, 111, 114, 109, 84, 114, 97, + 110, 115, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 111, 97, 100, 84, 114, 97, 110, + 115, 102, 111, 114, 109, 84, 114, 97, + 110, 115, 83, 116, 100, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_fa9a296b9fd41a96 = b_fa9a296b9fd41a96.words; +#if !CAPNP_LITE +static const uint16_t m_fa9a296b9fd41a96[] = {4, 8, 9, 1, 3, 5, 0, 2, 6, 7}; +static const uint16_t i_fa9a296b9fd41a96[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9}; +const ::capnp::_::RawSchema s_fa9a296b9fd41a96 = { + 0xfa9a296b9fd41a96, b_fa9a296b9fd41a96.words, 210, nullptr, m_fa9a296b9fd41a96, + 0, 10, i_fa9a296b9fd41a96, nullptr, nullptr, { &s_fa9a296b9fd41a96, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<51> b_ef0382d244f56e38 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 56, 110, 245, 68, 210, 130, 3, 239, + 10, 0, 0, 0, 1, 0, 1, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 154, 0, 0, 0, + 29, 0, 0, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 83, 101, 110, 116, 105, 110, + 101, 108, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 1, 0, 1, 0, + 26, 3, 247, 182, 30, 230, 216, 162, + 1, 0, 0, 0, 106, 0, 0, 0, + 83, 101, 110, 116, 105, 110, 101, 108, + 84, 121, 112, 101, 0, 0, 0, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 0, 0, 0, 3, 0, 1, 0, + 48, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 116, 121, 112, 101, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 26, 3, 247, 182, 30, 230, 216, 162, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 105, 103, 110, 97, 108, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_ef0382d244f56e38 = b_ef0382d244f56e38.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_ef0382d244f56e38[] = { + &s_a2d8e61eb6f7031a, +}; +static const uint16_t m_ef0382d244f56e38[] = {1, 0}; +static const uint16_t i_ef0382d244f56e38[] = {0, 1}; +const ::capnp::_::RawSchema s_ef0382d244f56e38 = { + 0xef0382d244f56e38, b_ef0382d244f56e38.words, 51, d_ef0382d244f56e38, m_ef0382d244f56e38, + 1, 2, i_ef0382d244f56e38, nullptr, nullptr, { &s_ef0382d244f56e38, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<38> b_a2d8e61eb6f7031a = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 26, 3, 247, 182, 30, 230, 216, 162, + 19, 0, 0, 0, 2, 0, 0, 0, + 56, 110, 245, 68, 210, 130, 3, 239, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 2, 1, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 103, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 83, 101, 110, 116, 105, 110, + 101, 108, 46, 83, 101, 110, 116, 105, + 110, 101, 108, 84, 121, 112, 101, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 110, 100, 79, 102, 83, 101, 103, + 109, 101, 110, 116, 0, 0, 0, 0, + 101, 110, 100, 79, 102, 82, 111, 117, + 116, 101, 0, 0, 0, 0, 0, 0, + 115, 116, 97, 114, 116, 79, 102, 83, + 101, 103, 109, 101, 110, 116, 0, 0, + 115, 116, 97, 114, 116, 79, 102, 82, + 111, 117, 116, 101, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_a2d8e61eb6f7031a = b_a2d8e61eb6f7031a.words; +#if !CAPNP_LITE +static const uint16_t m_a2d8e61eb6f7031a[] = {1, 0, 3, 2}; +const ::capnp::_::RawSchema s_a2d8e61eb6f7031a = { + 0xa2d8e61eb6f7031a, b_a2d8e61eb6f7031a.words, 38, nullptr, m_a2d8e61eb6f7031a, + 0, 4, nullptr, nullptr, nullptr, { &s_a2d8e61eb6f7031a, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(SentinelType_a2d8e61eb6f7031a, a2d8e61eb6f7031a); +static const ::capnp::_::AlignedData<33> b_fe35ad896ffaeacf = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 207, 234, 250, 111, 137, 173, 53, 254, + 10, 0, 0, 0, 1, 0, 1, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 146, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 63, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 85, 73, 68, 101, 98, 117, + 103, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 4, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 3, 0, 1, 0, + 24, 0, 0, 0, 2, 0, 1, 0, + 100, 114, 97, 119, 84, 105, 109, 101, + 77, 105, 108, 108, 105, 115, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_fe35ad896ffaeacf = b_fe35ad896ffaeacf.words; +#if !CAPNP_LITE +static const uint16_t m_fe35ad896ffaeacf[] = {0}; +static const uint16_t i_fe35ad896ffaeacf[] = {0}; +const ::capnp::_::RawSchema s_fe35ad896ffaeacf = { + 0xfe35ad896ffaeacf, b_fe35ad896ffaeacf.words, 33, nullptr, m_fe35ad896ffaeacf, + 0, 1, i_fe35ad896ffaeacf, nullptr, nullptr, { &s_fe35ad896ffaeacf, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<41> b_cf7154b31a69635b = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 91, 99, 105, 26, 179, 84, 113, 207, + 10, 0, 0, 0, 1, 0, 0, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 186, 0, 0, 0, + 29, 0, 0, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 63, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 77, 97, 110, 97, 103, 101, + 114, 83, 116, 97, 116, 101, 0, 0, + 4, 0, 0, 0, 1, 0, 1, 0, + 234, 105, 132, 112, 210, 84, 154, 134, + 1, 0, 0, 0, 106, 0, 0, 0, + 80, 114, 111, 99, 101, 115, 115, 83, + 116, 97, 116, 101, 0, 0, 0, 0, + 4, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 3, 0, 1, 0, + 40, 0, 0, 0, 2, 0, 1, 0, + 112, 114, 111, 99, 101, 115, 115, 101, + 115, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 234, 105, 132, 112, 210, 84, 154, 134, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_cf7154b31a69635b = b_cf7154b31a69635b.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_cf7154b31a69635b[] = { + &s_869a54d2708469ea, +}; +static const uint16_t m_cf7154b31a69635b[] = {0}; +static const uint16_t i_cf7154b31a69635b[] = {0}; +const ::capnp::_::RawSchema s_cf7154b31a69635b = { + 0xcf7154b31a69635b, b_cf7154b31a69635b.words, 41, d_cf7154b31a69635b, m_cf7154b31a69635b, + 1, 1, i_cf7154b31a69635b, nullptr, nullptr, { &s_cf7154b31a69635b, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<96> b_869a54d2708469ea = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 234, 105, 132, 112, 210, 84, 154, 134, + 23, 0, 0, 0, 1, 0, 2, 0, + 91, 99, 105, 26, 179, 84, 113, 207, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 34, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 31, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 77, 97, 110, 97, 103, 101, + 114, 83, 116, 97, 116, 101, 46, 80, + 114, 111, 99, 101, 115, 115, 83, 116, + 97, 116, 101, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 20, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 0, 0, 0, 3, 0, 1, 0, + 132, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 129, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 0, 0, 0, 3, 0, 1, 0, + 136, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 32, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 128, 0, 0, 0, 3, 0, 1, 0, + 140, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 137, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 136, 0, 0, 0, 3, 0, 1, 0, + 148, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 33, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 145, 0, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 144, 0, 0, 0, 3, 0, 1, 0, + 156, 0, 0, 0, 2, 0, 1, 0, + 110, 97, 109, 101, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 105, 100, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 117, 110, 110, 105, 110, 103, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 120, 105, 116, 67, 111, 100, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 104, 111, 117, 108, 100, 66, 101, + 82, 117, 110, 110, 105, 110, 103, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_869a54d2708469ea = b_869a54d2708469ea.words; +#if !CAPNP_LITE +static const uint16_t m_869a54d2708469ea[] = {3, 0, 1, 2, 4}; +static const uint16_t i_869a54d2708469ea[] = {0, 1, 2, 3, 4}; +const ::capnp::_::RawSchema s_869a54d2708469ea = { + 0x869a54d2708469ea, b_869a54d2708469ea.words, 96, nullptr, m_869a54d2708469ea, + 0, 5, i_869a54d2708469ea, nullptr, nullptr, { &s_869a54d2708469ea, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<131> b_de266b39b76b461e = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 30, 70, 107, 183, 57, 107, 38, 222, + 10, 0, 0, 0, 1, 0, 3, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 194, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 143, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 85, 112, 108, 111, 97, 100, + 101, 114, 83, 116, 97, 116, 101, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 28, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 0, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 0, 0, 0, 3, 0, 1, 0, + 196, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 0, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 0, 0, 0, 3, 0, 1, 0, + 208, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 0, 0, 0, 3, 0, 1, 0, + 216, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 0, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 212, 0, 0, 0, 3, 0, 1, 0, + 224, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 220, 0, 0, 0, 3, 0, 1, 0, + 232, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 228, 0, 0, 0, 3, 0, 1, 0, + 240, 0, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 0, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 236, 0, 0, 0, 3, 0, 1, 0, + 248, 0, 0, 0, 2, 0, 1, 0, + 105, 109, 109, 101, 100, 105, 97, 116, + 101, 81, 117, 101, 117, 101, 83, 105, + 122, 101, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 109, 109, 101, 100, 105, 97, 116, + 101, 81, 117, 101, 117, 101, 67, 111, + 117, 110, 116, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 97, 119, 81, 117, 101, 117, 101, + 83, 105, 122, 101, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 97, 119, 81, 117, 101, 117, 101, + 67, 111, 117, 110, 116, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 115, 116, 84, 105, 109, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 115, 116, 83, 112, 101, 101, + 100, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 115, 116, 70, 105, 108, 101, + 110, 97, 109, 101, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_de266b39b76b461e = b_de266b39b76b461e.words; +#if !CAPNP_LITE +static const uint16_t m_de266b39b76b461e[] = {1, 0, 6, 5, 4, 3, 2}; +static const uint16_t i_de266b39b76b461e[] = {0, 1, 2, 3, 4, 5, 6}; +const ::capnp::_::RawSchema s_de266b39b76b461e = { + 0xde266b39b76b461e, b_de266b39b76b461e.words, 131, nullptr, m_de266b39b76b461e, + 0, 7, i_de266b39b76b461e, nullptr, nullptr, { &s_de266b39b76b461e, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<254> b_c18216b27f8602af = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 175, 2, 134, 127, 178, 22, 130, 193, + 10, 0, 0, 0, 1, 0, 3, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 6, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 202, 0, 0, 0, + 33, 0, 0, 0, 71, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 89, 0, 0, 0, 223, 2, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 78, 97, 118, 73, 110, 115, + 116, 114, 117, 99, 116, 105, 111, 110, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 1, 0, 1, 0, + 217, 57, 164, 192, 137, 22, 205, 164, + 25, 0, 0, 0, 42, 0, 0, 0, + 146, 193, 229, 201, 216, 185, 165, 238, + 21, 0, 0, 0, 82, 0, 0, 0, + 102, 156, 208, 104, 165, 10, 110, 182, + 21, 0, 0, 0, 122, 0, 0, 0, + 69, 10, 226, 108, 26, 74, 236, 179, + 21, 0, 0, 0, 74, 0, 0, 0, + 76, 97, 110, 101, 0, 0, 0, 0, + 68, 105, 114, 101, 99, 116, 105, 111, + 110, 0, 0, 0, 0, 0, 0, 0, + 83, 112, 101, 101, 100, 76, 105, 109, + 105, 116, 83, 105, 103, 110, 0, 0, + 77, 97, 110, 101, 117, 118, 101, 114, + 0, 0, 0, 0, 0, 0, 0, 0, + 52, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 1, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 1, 0, 0, 3, 0, 1, 0, + 108, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 1, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 1, 0, 0, 3, 0, 1, 0, + 120, 1, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 1, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 1, 0, 0, 3, 0, 1, 0, + 132, 1, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 129, 1, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 128, 1, 0, 0, 3, 0, 1, 0, + 140, 1, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 137, 1, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 140, 1, 0, 0, 3, 0, 1, 0, + 152, 1, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 149, 1, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 152, 1, 0, 0, 3, 0, 1, 0, + 164, 1, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 161, 1, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 160, 1, 0, 0, 3, 0, 1, 0, + 172, 1, 0, 0, 2, 0, 1, 0, + 7, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 169, 1, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 172, 1, 0, 0, 3, 0, 1, 0, + 184, 1, 0, 0, 2, 0, 1, 0, + 8, 0, 0, 0, 4, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 1, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 1, 0, 0, 3, 0, 1, 0, + 204, 1, 0, 0, 2, 0, 1, 0, + 9, 0, 0, 0, 128, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 1, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 200, 1, 0, 0, 3, 0, 1, 0, + 212, 1, 0, 0, 2, 0, 1, 0, + 10, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 1, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 1, 0, 0, 3, 0, 1, 0, + 220, 1, 0, 0, 2, 0, 1, 0, + 11, 0, 0, 0, 9, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 217, 1, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 1, 0, 0, 3, 0, 1, 0, + 228, 1, 0, 0, 2, 0, 1, 0, + 12, 0, 0, 0, 5, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 225, 1, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 224, 1, 0, 0, 3, 0, 1, 0, + 252, 1, 0, 0, 2, 0, 1, 0, + 109, 97, 110, 101, 117, 118, 101, 114, + 80, 114, 105, 109, 97, 114, 121, 84, + 101, 120, 116, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 97, 110, 101, 117, 118, 101, 114, + 83, 101, 99, 111, 110, 100, 97, 114, + 121, 84, 101, 120, 116, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 97, 110, 101, 117, 118, 101, 114, + 68, 105, 115, 116, 97, 110, 99, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 97, 110, 101, 117, 118, 101, 114, + 84, 121, 112, 101, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 97, 110, 101, 117, 118, 101, 114, + 77, 111, 100, 105, 102, 105, 101, 114, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 105, 115, 116, 97, 110, 99, 101, + 82, 101, 109, 97, 105, 110, 105, 110, + 103, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 109, 101, 82, 101, 109, 97, + 105, 110, 105, 110, 103, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 105, 109, 101, 82, 101, 109, 97, + 105, 110, 105, 110, 103, 84, 121, 112, + 105, 99, 97, 108, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 110, 101, 115, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 217, 57, 164, 192, 137, 22, 205, 164, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 104, 111, 119, 70, 117, 108, 108, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 112, 101, 101, 100, 76, 105, 109, + 105, 116, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 112, 101, 101, 100, 76, 105, 109, + 105, 116, 83, 105, 103, 110, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 102, 156, 208, 104, 165, 10, 110, 182, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 108, 108, 77, 97, 110, 101, 117, + 118, 101, 114, 115, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 69, 10, 226, 108, 26, 74, 236, 179, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_c18216b27f8602af = b_c18216b27f8602af.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_c18216b27f8602af[] = { + &s_a4cd1689c0a439d9, + &s_b3ec4a1a6ce20a45, + &s_b66e0aa568d09c66, +}; +static const uint16_t m_c18216b27f8602af[] = {12, 5, 8, 2, 4, 0, 1, 3, 9, 10, 11, 6, 7}; +static const uint16_t i_c18216b27f8602af[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12}; +const ::capnp::_::RawSchema s_c18216b27f8602af = { + 0xc18216b27f8602af, b_c18216b27f8602af.words, 254, d_c18216b27f8602af, m_c18216b27f8602af, + 3, 13, i_c18216b27f8602af, nullptr, nullptr, { &s_c18216b27f8602af, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<69> b_a4cd1689c0a439d9 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 217, 57, 164, 192, 137, 22, 205, 164, + 25, 0, 0, 0, 1, 0, 1, 0, + 175, 2, 134, 127, 178, 22, 130, 193, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 242, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 78, 97, 118, 73, 110, 115, + 116, 114, 117, 99, 116, 105, 111, 110, + 46, 76, 97, 110, 101, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 0, 0, 0, 3, 0, 1, 0, + 96, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 88, 0, 0, 0, 3, 0, 1, 0, + 100, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 0, 0, 0, 3, 0, 1, 0, + 108, 0, 0, 0, 2, 0, 1, 0, + 100, 105, 114, 101, 99, 116, 105, 111, + 110, 115, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 146, 193, 229, 201, 216, 185, 165, 238, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 116, 105, 118, 101, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 116, 105, 118, 101, 68, 105, + 114, 101, 99, 116, 105, 111, 110, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 146, 193, 229, 201, 216, 185, 165, 238, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 15, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_a4cd1689c0a439d9 = b_a4cd1689c0a439d9.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_a4cd1689c0a439d9[] = { + &s_eea5b9d8c9e5c192, +}; +static const uint16_t m_a4cd1689c0a439d9[] = {1, 2, 0}; +static const uint16_t i_a4cd1689c0a439d9[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_a4cd1689c0a439d9 = { + 0xa4cd1689c0a439d9, b_a4cd1689c0a439d9.words, 69, d_a4cd1689c0a439d9, m_a4cd1689c0a439d9, + 1, 3, i_a4cd1689c0a439d9, nullptr, nullptr, { &s_a4cd1689c0a439d9, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<46> b_eea5b9d8c9e5c192 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 146, 193, 229, 201, 216, 185, 165, 238, + 25, 0, 0, 0, 2, 0, 0, 0, + 175, 2, 134, 127, 178, 22, 130, 193, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 26, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 151, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 78, 97, 118, 73, 110, 115, + 116, 114, 117, 99, 116, 105, 111, 110, + 46, 68, 105, 114, 101, 99, 116, 105, + 111, 110, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 24, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 65, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 57, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 2, 0, 0, 0, 0, 0, 0, 0, + 49, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 111, 110, 101, 0, 0, 0, 0, + 108, 101, 102, 116, 0, 0, 0, 0, + 114, 105, 103, 104, 116, 0, 0, 0, + 115, 116, 114, 97, 105, 103, 104, 116, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 108, 105, 103, 104, 116, 76, 101, + 102, 116, 0, 0, 0, 0, 0, 0, + 115, 108, 105, 103, 104, 116, 82, 105, + 103, 104, 116, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_eea5b9d8c9e5c192 = b_eea5b9d8c9e5c192.words; +#if !CAPNP_LITE +static const uint16_t m_eea5b9d8c9e5c192[] = {1, 0, 2, 4, 5, 3}; +const ::capnp::_::RawSchema s_eea5b9d8c9e5c192 = { + 0xeea5b9d8c9e5c192, b_eea5b9d8c9e5c192.words, 46, nullptr, m_eea5b9d8c9e5c192, + 0, 6, nullptr, nullptr, nullptr, { &s_eea5b9d8c9e5c192, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(Direction_eea5b9d8c9e5c192, eea5b9d8c9e5c192); +static const ::capnp::_::AlignedData<27> b_b66e0aa568d09c66 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 102, 156, 208, 104, 165, 10, 110, 182, + 25, 0, 0, 0, 2, 0, 0, 0, + 175, 2, 134, 127, 178, 22, 130, 193, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 66, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 55, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 78, 97, 118, 73, 110, 115, + 116, 114, 117, 99, 116, 105, 111, 110, + 46, 83, 112, 101, 101, 100, 76, 105, + 109, 105, 116, 83, 105, 103, 110, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 1, 0, 2, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 117, 116, 99, 100, 0, 0, 0, + 118, 105, 101, 110, 110, 97, 0, 0, } +}; +::capnp::word const* const bp_b66e0aa568d09c66 = b_b66e0aa568d09c66.words; +#if !CAPNP_LITE +static const uint16_t m_b66e0aa568d09c66[] = {0, 1}; +const ::capnp::_::RawSchema s_b66e0aa568d09c66 = { + 0xb66e0aa568d09c66, b_b66e0aa568d09c66.words, 27, nullptr, m_b66e0aa568d09c66, + 0, 2, nullptr, nullptr, nullptr, { &s_b66e0aa568d09c66, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +CAPNP_DEFINE_ENUM(SpeedLimitSign_b66e0aa568d09c66, b66e0aa568d09c66); +static const ::capnp::_::AlignedData<66> b_b3ec4a1a6ce20a45 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 69, 10, 226, 108, 26, 74, 236, 179, + 25, 0, 0, 0, 1, 0, 1, 0, + 175, 2, 134, 127, 178, 22, 130, 193, + 2, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 18, 1, 0, 0, + 37, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 78, 97, 118, 73, 110, 115, + 116, 114, 117, 99, 116, 105, 111, 110, + 46, 77, 97, 110, 101, 117, 118, 101, + 114, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 0, 0, 0, 3, 0, 1, 0, + 80, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 0, 0, 0, 3, 0, 1, 0, + 84, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 81, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 80, 0, 0, 0, 3, 0, 1, 0, + 92, 0, 0, 0, 2, 0, 1, 0, + 100, 105, 115, 116, 97, 110, 99, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 121, 112, 101, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 111, 100, 105, 102, 105, 101, 114, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_b3ec4a1a6ce20a45 = b_b3ec4a1a6ce20a45.words; +#if !CAPNP_LITE +static const uint16_t m_b3ec4a1a6ce20a45[] = {0, 2, 1}; +static const uint16_t i_b3ec4a1a6ce20a45[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_b3ec4a1a6ce20a45 = { + 0xb3ec4a1a6ce20a45, b_b3ec4a1a6ce20a45.words, 66, nullptr, m_b3ec4a1a6ce20a45, + 0, 3, i_b3ec4a1a6ce20a45, nullptr, nullptr, { &s_b3ec4a1a6ce20a45, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<41> b_a61452f6440d97d3 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 211, 151, 13, 68, 246, 82, 20, 166, + 10, 0, 0, 0, 1, 0, 0, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 1, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 154, 0, 0, 0, + 29, 0, 0, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 63, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 78, 97, 118, 82, 111, 117, + 116, 101, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 1, 0, 1, 0, + 133, 116, 30, 173, 83, 111, 201, 196, + 1, 0, 0, 0, 90, 0, 0, 0, + 67, 111, 111, 114, 100, 105, 110, 97, + 116, 101, 0, 0, 0, 0, 0, 0, + 4, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 3, 0, 1, 0, + 40, 0, 0, 0, 2, 0, 1, 0, + 99, 111, 111, 114, 100, 105, 110, 97, + 116, 101, 115, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 133, 116, 30, 173, 83, 111, 201, 196, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_a61452f6440d97d3 = b_a61452f6440d97d3.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_a61452f6440d97d3[] = { + &s_c4c96f53ad1e7485, +}; +static const uint16_t m_a61452f6440d97d3[] = {0}; +static const uint16_t i_a61452f6440d97d3[] = {0}; +const ::capnp::_::RawSchema s_a61452f6440d97d3 = { + 0xa61452f6440d97d3, b_a61452f6440d97d3.words, 41, d_a61452f6440d97d3, m_a61452f6440d97d3, + 1, 1, i_a61452f6440d97d3, nullptr, nullptr, { &s_a61452f6440d97d3, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<50> b_c4c96f53ad1e7485 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 133, 116, 30, 173, 83, 111, 201, 196, + 19, 0, 0, 0, 1, 0, 1, 0, + 211, 151, 13, 68, 246, 82, 20, 166, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 242, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 78, 97, 118, 82, 111, 117, + 116, 101, 46, 67, 111, 111, 114, 100, + 105, 110, 97, 116, 101, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 8, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 0, 0, 0, 3, 0, 1, 0, + 52, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 0, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 0, 0, 0, 3, 0, 1, 0, + 60, 0, 0, 0, 2, 0, 1, 0, + 108, 97, 116, 105, 116, 117, 100, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 110, 103, 105, 116, 117, 100, + 101, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_c4c96f53ad1e7485 = b_c4c96f53ad1e7485.words; +#if !CAPNP_LITE +static const uint16_t m_c4c96f53ad1e7485[] = {0, 1}; +static const uint16_t i_c4c96f53ad1e7485[] = {0, 1}; +const ::capnp::_::RawSchema s_c4c96f53ad1e7485 = { + 0xc4c96f53ad1e7485, b_c4c96f53ad1e7485.words, 50, nullptr, m_c4c96f53ad1e7485, + 0, 2, i_c4c96f53ad1e7485, nullptr, nullptr, { &s_c4c96f53ad1e7485, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<66> b_a158dd2a4cfaa81b = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 27, 168, 250, 76, 42, 221, 88, 161, + 10, 0, 0, 0, 1, 0, 2, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 202, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 175, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 77, 97, 112, 82, 101, 110, + 100, 101, 114, 83, 116, 97, 116, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 12, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 0, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 72, 0, 0, 0, 3, 0, 1, 0, + 84, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 81, 0, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 80, 0, 0, 0, 3, 0, 1, 0, + 92, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 89, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 84, 0, 0, 0, 3, 0, 1, 0, + 96, 0, 0, 0, 2, 0, 1, 0, + 108, 111, 99, 97, 116, 105, 111, 110, + 77, 111, 110, 111, 84, 105, 109, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 101, 110, 100, 101, 114, 84, 105, + 109, 101, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 114, 97, 109, 101, 73, 100, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_a158dd2a4cfaa81b = b_a158dd2a4cfaa81b.words; +#if !CAPNP_LITE +static const uint16_t m_a158dd2a4cfaa81b[] = {2, 0, 1}; +static const uint16_t i_a158dd2a4cfaa81b[] = {0, 1, 2}; +const ::capnp::_::RawSchema s_a158dd2a4cfaa81b = { + 0xa158dd2a4cfaa81b, b_a158dd2a4cfaa81b.words, 66, nullptr, m_a158dd2a4cfaa81b, + 0, 3, i_a158dd2a4cfaa81b, nullptr, nullptr, { &s_a158dd2a4cfaa81b, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<143> b_ac3de5c437be057a = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 122, 5, 190, 55, 196, 229, 61, 172, + 10, 0, 0, 0, 1, 0, 3, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 3, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 186, 0, 0, 0, + 29, 0, 0, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 0, 0, 0, 143, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 78, 97, 118, 77, 111, 100, + 101, 108, 68, 97, 116, 97, 0, 0, + 4, 0, 0, 0, 1, 0, 1, 0, + 38, 126, 80, 178, 21, 230, 9, 190, + 1, 0, 0, 0, 58, 0, 0, 0, + 88, 89, 68, 97, 116, 97, 0, 0, + 28, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 0, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 0, 0, 0, 3, 0, 1, 0, + 188, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 0, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 0, 0, 0, 3, 0, 1, 0, + 200, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 0, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 200, 0, 0, 0, 3, 0, 1, 0, + 212, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 0, 0, 0, 3, 0, 1, 0, + 236, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 233, 0, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 0, 0, 0, 3, 0, 1, 0, + 244, 0, 0, 0, 2, 0, 1, 0, + 6, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 0, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 244, 0, 0, 0, 3, 0, 1, 0, + 16, 1, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 1, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 1, 0, 0, 3, 0, 1, 0, + 28, 1, 0, 0, 2, 0, 1, 0, + 102, 114, 97, 109, 101, 73, 100, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 111, 100, 101, 108, 69, 120, 101, + 99, 117, 116, 105, 111, 110, 84, 105, + 109, 101, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 115, 112, 69, 120, 101, 99, 117, + 116, 105, 111, 110, 84, 105, 109, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 101, 97, 116, 117, 114, 101, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 111, 115, 105, 116, 105, 111, 110, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 38, 126, 80, 178, 21, 230, 9, 190, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 115, 105, 114, 101, 80, 114, + 101, 100, 105, 99, 116, 105, 111, 110, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 99, 97, 116, 105, 111, 110, + 77, 111, 110, 111, 84, 105, 109, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_ac3de5c437be057a = b_ac3de5c437be057a.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_ac3de5c437be057a[] = { + &s_be09e615b2507e26, +}; +static const uint16_t m_ac3de5c437be057a[] = {5, 2, 3, 0, 6, 1, 4}; +static const uint16_t i_ac3de5c437be057a[] = {0, 1, 2, 3, 4, 5, 6}; +const ::capnp::_::RawSchema s_ac3de5c437be057a = { + 0xac3de5c437be057a, b_ac3de5c437be057a.words, 143, d_ac3de5c437be057a, m_ac3de5c437be057a, + 1, 7, i_ac3de5c437be057a, nullptr, nullptr, { &s_ac3de5c437be057a, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<94> b_be09e615b2507e26 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 38, 126, 80, 178, 21, 230, 9, 190, + 23, 0, 0, 0, 1, 0, 0, 0, + 122, 5, 190, 55, 196, 229, 61, 172, + 4, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 242, 0, 0, 0, + 33, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 0, 0, 0, 231, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 78, 97, 118, 77, 111, 100, + 101, 108, 68, 97, 116, 97, 46, 88, + 89, 68, 97, 116, 97, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 92, 0, 0, 0, 3, 0, 1, 0, + 120, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 0, 0, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 0, 0, 0, 3, 0, 1, 0, + 140, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 137, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 132, 0, 0, 0, 3, 0, 1, 0, + 160, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 157, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 152, 0, 0, 0, 3, 0, 1, 0, + 180, 0, 0, 0, 2, 0, 1, 0, + 120, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 120, 83, 116, 100, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 83, 116, 100, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_be09e615b2507e26 = b_be09e615b2507e26.words; +#if !CAPNP_LITE +static const uint16_t m_be09e615b2507e26[] = {0, 2, 1, 3}; +static const uint16_t i_be09e615b2507e26[] = {0, 1, 2, 3}; +const ::capnp::_::RawSchema s_be09e615b2507e26 = { + 0xbe09e615b2507e26, b_be09e615b2507e26.words, 94, nullptr, m_be09e615b2507e26, + 0, 4, i_be09e615b2507e26, nullptr, nullptr, { &s_be09e615b2507e26, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<109> b_cf9aeab355dd85f0 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 240, 133, 221, 85, 179, 234, 154, 207, + 10, 0, 0, 0, 1, 0, 2, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 3, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 170, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 87, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 69, 110, 99, 111, 100, 101, + 68, 97, 116, 97, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 24, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 0, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 0, 0, 0, 3, 0, 1, 0, + 160, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 157, 0, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 152, 0, 0, 0, 3, 0, 1, 0, + 164, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 161, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 156, 0, 0, 0, 3, 0, 1, 0, + 168, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 165, 0, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 0, 0, 0, 3, 0, 1, 0, + 180, 0, 0, 0, 2, 0, 1, 0, + 4, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 0, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 172, 0, 0, 0, 3, 0, 1, 0, + 184, 0, 0, 0, 2, 0, 1, 0, + 5, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 0, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 0, 0, 0, 3, 0, 1, 0, + 188, 0, 0, 0, 2, 0, 1, 0, + 105, 100, 120, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 252, 53, 23, 84, 227, 148, 211, 137, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 97, 116, 97, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 101, 97, 100, 101, 114, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 110, 105, 120, 84, 105, 109, 101, + 115, 116, 97, 109, 112, 78, 97, 110, + 111, 115, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 119, 105, 100, 116, 104, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 101, 105, 103, 104, 116, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_cf9aeab355dd85f0 = b_cf9aeab355dd85f0.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_cf9aeab355dd85f0[] = { + &s_89d394e3541735fc, +}; +static const uint16_t m_cf9aeab355dd85f0[] = {1, 2, 5, 0, 3, 4}; +static const uint16_t i_cf9aeab355dd85f0[] = {0, 1, 2, 3, 4, 5}; +const ::capnp::_::RawSchema s_cf9aeab355dd85f0 = { + 0xcf9aeab355dd85f0, b_cf9aeab355dd85f0.words, 109, d_cf9aeab355dd85f0, m_cf9aeab355dd85f0, + 1, 6, i_cf9aeab355dd85f0, nullptr, nullptr, { &s_cf9aeab355dd85f0, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<16> b_fe346a9de48d9b50 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 80, 155, 141, 228, 157, 106, 52, 254, + 10, 0, 0, 0, 1, 0, 0, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 154, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 85, 115, 101, 114, 70, 108, + 97, 103, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, } +}; +::capnp::word const* const bp_fe346a9de48d9b50 = b_fe346a9de48d9b50.words; +#if !CAPNP_LITE +const ::capnp::_::RawSchema s_fe346a9de48d9b50 = { + 0xfe346a9de48d9b50, b_fe346a9de48d9b50.words, 16, nullptr, nullptr, + 0, 0, nullptr, nullptr, nullptr, { &s_fe346a9de48d9b50, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<85> b_dc24138990726023 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 35, 96, 114, 144, 137, 19, 36, 220, + 10, 0, 0, 0, 1, 0, 2, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 0, 0, 7, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 170, 0, 0, 0, + 29, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 0, 0, 0, 231, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 77, 105, 99, 114, 111, 112, + 104, 111, 110, 101, 0, 0, 0, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 16, 0, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 0, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 0, 0, 0, 3, 0, 1, 0, + 108, 0, 0, 0, 2, 0, 1, 0, + 2, 0, 0, 0, 1, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 0, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 0, 0, 0, 3, 0, 1, 0, + 120, 0, 0, 0, 2, 0, 1, 0, + 3, 0, 0, 0, 2, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 0, 0, 0, 2, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 0, 0, 0, 3, 0, 1, 0, + 136, 0, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 3, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 0, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 136, 0, 0, 0, 3, 0, 1, 0, + 148, 0, 0, 0, 2, 0, 1, 0, + 115, 111, 117, 110, 100, 80, 114, 101, + 115, 115, 117, 114, 101, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 111, 117, 110, 100, 80, 114, 101, + 115, 115, 117, 114, 101, 87, 101, 105, + 103, 104, 116, 101, 100, 68, 98, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 105, 108, 116, 101, 114, 101, 100, + 83, 111, 117, 110, 100, 80, 114, 101, + 115, 115, 117, 114, 101, 87, 101, 105, + 103, 104, 116, 101, 100, 68, 98, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 111, 117, 110, 100, 80, 114, 101, + 115, 115, 117, 114, 101, 87, 101, 105, + 103, 104, 116, 101, 100, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 10, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_dc24138990726023 = b_dc24138990726023.words; +#if !CAPNP_LITE +static const uint16_t m_dc24138990726023[] = {2, 0, 3, 1}; +static const uint16_t i_dc24138990726023[] = {0, 1, 2, 3}; +const ::capnp::_::RawSchema s_dc24138990726023 = { + 0xdc24138990726023, b_dc24138990726023.words, 85, nullptr, m_dc24138990726023, + 0, 4, i_dc24138990726023, nullptr, nullptr, { &s_dc24138990726023, nullptr, nullptr, 0, 0, nullptr }, false +}; +#endif // !CAPNP_LITE +static const ::capnp::_::AlignedData<2164> b_d314cfd957229c11 = { + { 0, 0, 0, 0, 5, 0, 6, 0, + 17, 156, 34, 87, 217, 207, 20, 211, + 10, 0, 0, 0, 1, 0, 2, 0, + 91, 40, 164, 37, 126, 241, 177, 243, + 1, 0, 7, 0, 0, 0, 125, 0, + 4, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 130, 0, 0, 0, + 25, 0, 0, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 0, 0, 0, 207, 27, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 46, 99, 97, 112, 110, + 112, 58, 69, 118, 101, 110, 116, 0, + 0, 0, 0, 0, 1, 0, 1, 0, + 252, 1, 0, 0, 3, 0, 4, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 13, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 212, 13, 0, 0, 3, 0, 1, 0, + 224, 13, 0, 0, 2, 0, 1, 0, + 2, 0, 255, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 1, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 13, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 220, 13, 0, 0, 3, 0, 1, 0, + 232, 13, 0, 0, 2, 0, 1, 0, + 43, 0, 254, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 2, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 13, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 228, 13, 0, 0, 3, 0, 1, 0, + 240, 13, 0, 0, 2, 0, 1, 0, + 5, 0, 253, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 3, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 13, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 13, 0, 0, 3, 0, 1, 0, + 244, 13, 0, 0, 2, 0, 1, 0, + 95, 0, 252, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 4, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 13, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 244, 13, 0, 0, 3, 0, 1, 0, + 0, 14, 0, 0, 2, 0, 1, 0, + 6, 0, 251, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 5, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 253, 13, 0, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 248, 13, 0, 0, 3, 0, 1, 0, + 20, 14, 0, 0, 2, 0, 1, 0, + 59, 0, 250, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 6, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 14, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 14, 0, 0, 3, 0, 1, 0, + 28, 14, 0, 0, 2, 0, 1, 0, + 7, 0, 249, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 7, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 14, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 24, 14, 0, 0, 3, 0, 1, 0, + 36, 14, 0, 0, 2, 0, 1, 0, + 96, 0, 248, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 8, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 14, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 14, 0, 0, 3, 0, 1, 0, + 64, 14, 0, 0, 2, 0, 1, 0, + 89, 0, 247, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 9, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 14, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 56, 14, 0, 0, 3, 0, 1, 0, + 68, 14, 0, 0, 2, 0, 1, 0, + 120, 0, 246, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 10, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 65, 14, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 14, 0, 0, 3, 0, 1, 0, + 80, 14, 0, 0, 2, 0, 1, 0, + 125, 0, 245, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 11, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 14, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 80, 14, 0, 0, 3, 0, 1, 0, + 108, 14, 0, 0, 2, 0, 1, 0, + 123, 0, 244, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 12, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 14, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 14, 0, 0, 3, 0, 1, 0, + 120, 14, 0, 0, 2, 0, 1, 0, + 18, 0, 243, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 13, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 14, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 14, 0, 0, 3, 0, 1, 0, + 128, 14, 0, 0, 2, 0, 1, 0, + 94, 0, 242, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 14, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 14, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 128, 14, 0, 0, 3, 0, 1, 0, + 140, 14, 0, 0, 2, 0, 1, 0, + 46, 0, 241, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 15, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 137, 14, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 136, 14, 0, 0, 3, 0, 1, 0, + 148, 14, 0, 0, 2, 0, 1, 0, + 19, 0, 240, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 16, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 145, 14, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 144, 14, 0, 0, 3, 0, 1, 0, + 172, 14, 0, 0, 2, 0, 1, 0, + 20, 0, 239, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 17, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 169, 14, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 164, 14, 0, 0, 3, 0, 1, 0, + 192, 14, 0, 0, 2, 0, 1, 0, + 60, 0, 238, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 18, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 14, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 14, 0, 0, 3, 0, 1, 0, + 200, 14, 0, 0, 2, 0, 1, 0, + 21, 0, 237, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 19, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 14, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 14, 0, 0, 3, 0, 1, 0, + 208, 14, 0, 0, 2, 0, 1, 0, + 54, 0, 236, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 20, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 14, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 14, 0, 0, 3, 0, 1, 0, + 216, 14, 0, 0, 2, 0, 1, 0, + 30, 0, 235, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 21, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 14, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 212, 14, 0, 0, 3, 0, 1, 0, + 224, 14, 0, 0, 2, 0, 1, 0, + 22, 0, 234, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 22, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 14, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 220, 14, 0, 0, 3, 0, 1, 0, + 232, 14, 0, 0, 2, 0, 1, 0, + 23, 0, 233, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 23, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 14, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 228, 14, 0, 0, 3, 0, 1, 0, + 240, 14, 0, 0, 2, 0, 1, 0, + 24, 0, 232, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 24, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 14, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 14, 0, 0, 3, 0, 1, 0, + 252, 14, 0, 0, 2, 0, 1, 0, + 97, 0, 231, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 25, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 249, 14, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 252, 14, 0, 0, 3, 0, 1, 0, + 8, 15, 0, 0, 2, 0, 1, 0, + 98, 0, 230, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 26, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 15, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 15, 0, 0, 3, 0, 1, 0, + 36, 15, 0, 0, 2, 0, 1, 0, + 112, 0, 229, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 27, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 15, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 15, 0, 0, 3, 0, 1, 0, + 48, 15, 0, 0, 2, 0, 1, 0, + 99, 0, 228, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 28, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 15, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 48, 15, 0, 0, 3, 0, 1, 0, + 76, 15, 0, 0, 2, 0, 1, 0, + 100, 0, 227, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 29, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 73, 15, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 76, 15, 0, 0, 3, 0, 1, 0, + 104, 15, 0, 0, 2, 0, 1, 0, + 106, 0, 226, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 30, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 15, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 104, 15, 0, 0, 3, 0, 1, 0, + 116, 15, 0, 0, 2, 0, 1, 0, + 28, 0, 225, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 31, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 15, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 15, 0, 0, 3, 0, 1, 0, + 124, 15, 0, 0, 2, 0, 1, 0, + 107, 0, 224, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 32, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 15, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 15, 0, 0, 3, 0, 1, 0, + 136, 15, 0, 0, 2, 0, 1, 0, + 57, 0, 223, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 33, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 15, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 128, 15, 0, 0, 3, 0, 1, 0, + 140, 15, 0, 0, 2, 0, 1, 0, + 26, 0, 222, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 34, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 137, 15, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 136, 15, 0, 0, 3, 0, 1, 0, + 148, 15, 0, 0, 2, 0, 1, 0, + 58, 0, 221, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 35, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 145, 15, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 140, 15, 0, 0, 3, 0, 1, 0, + 152, 15, 0, 0, 2, 0, 1, 0, + 90, 0, 220, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 36, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 149, 15, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 152, 15, 0, 0, 3, 0, 1, 0, + 164, 15, 0, 0, 2, 0, 1, 0, + 91, 0, 219, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 37, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 161, 15, 0, 0, 242, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 15, 0, 0, 3, 0, 1, 0, + 180, 15, 0, 0, 2, 0, 1, 0, + 108, 0, 218, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 38, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 15, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 180, 15, 0, 0, 3, 0, 1, 0, + 192, 15, 0, 0, 2, 0, 1, 0, + 27, 0, 217, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 39, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 189, 15, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 15, 0, 0, 3, 0, 1, 0, + 200, 15, 0, 0, 2, 0, 1, 0, + 103, 0, 216, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 40, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 15, 0, 0, 218, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 204, 15, 0, 0, 3, 0, 1, 0, + 216, 15, 0, 0, 2, 0, 1, 0, + 104, 0, 215, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 41, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 213, 15, 0, 0, 202, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 220, 15, 0, 0, 3, 0, 1, 0, + 232, 15, 0, 0, 2, 0, 1, 0, + 105, 0, 214, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 229, 15, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 15, 0, 0, 3, 0, 1, 0, + 244, 15, 0, 0, 2, 0, 1, 0, + 109, 0, 213, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 43, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 15, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 244, 15, 0, 0, 3, 0, 1, 0, + 16, 16, 0, 0, 2, 0, 1, 0, + 110, 0, 212, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 44, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 16, 0, 0, 234, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 16, 0, 0, 3, 0, 1, 0, + 32, 16, 0, 0, 2, 0, 1, 0, + 93, 0, 211, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 45, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 16, 0, 0, 226, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 16, 0, 0, 3, 0, 1, 0, + 48, 16, 0, 0, 2, 0, 1, 0, + 111, 0, 210, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 46, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 16, 0, 0, 2, 1, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 52, 16, 0, 0, 3, 0, 1, 0, + 64, 16, 0, 0, 2, 0, 1, 0, + 113, 0, 209, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 47, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 16, 0, 0, 202, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 16, 0, 0, 3, 0, 1, 0, + 96, 16, 0, 0, 2, 0, 1, 0, + 29, 0, 208, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 48, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 16, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 16, 0, 0, 3, 0, 1, 0, + 108, 16, 0, 0, 2, 0, 1, 0, + 114, 0, 207, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 49, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 16, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 16, 0, 0, 3, 0, 1, 0, + 120, 16, 0, 0, 2, 0, 1, 0, + 101, 0, 206, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 16, 0, 0, 226, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 16, 0, 0, 3, 0, 1, 0, + 136, 16, 0, 0, 2, 0, 1, 0, + 92, 0, 205, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 51, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 16, 0, 0, 234, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 140, 16, 0, 0, 3, 0, 1, 0, + 152, 16, 0, 0, 2, 0, 1, 0, + 68, 0, 204, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 52, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 149, 16, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 16, 0, 0, 3, 0, 1, 0, + 160, 16, 0, 0, 2, 0, 1, 0, + 115, 0, 203, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 53, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 157, 16, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 160, 16, 0, 0, 3, 0, 1, 0, + 172, 16, 0, 0, 2, 0, 1, 0, + 116, 0, 202, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 54, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 169, 16, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 172, 16, 0, 0, 3, 0, 1, 0, + 184, 16, 0, 0, 2, 0, 1, 0, + 117, 0, 201, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 55, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 16, 0, 0, 218, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 188, 16, 0, 0, 3, 0, 1, 0, + 200, 16, 0, 0, 2, 0, 1, 0, + 118, 0, 200, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 56, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 197, 16, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 200, 16, 0, 0, 3, 0, 1, 0, + 212, 16, 0, 0, 2, 0, 1, 0, + 122, 0, 199, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 57, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 209, 16, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 212, 16, 0, 0, 3, 0, 1, 0, + 224, 16, 0, 0, 2, 0, 1, 0, + 119, 0, 198, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 221, 16, 0, 0, 234, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 228, 16, 0, 0, 3, 0, 1, 0, + 240, 16, 0, 0, 2, 0, 1, 0, + 124, 0, 197, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 59, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 237, 16, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 16, 0, 0, 3, 0, 1, 0, + 252, 16, 0, 0, 2, 0, 1, 0, + 4, 0, 196, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 60, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 249, 16, 0, 0, 42, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 244, 16, 0, 0, 3, 0, 1, 0, + 0, 17, 0, 0, 2, 0, 1, 0, + 32, 0, 195, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 61, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 253, 16, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 252, 16, 0, 0, 3, 0, 1, 0, + 8, 17, 0, 0, 2, 0, 1, 0, + 102, 0, 194, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 62, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 5, 17, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 17, 0, 0, 3, 0, 1, 0, + 20, 17, 0, 0, 2, 0, 1, 0, + 34, 0, 193, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 63, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 17, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 17, 0, 0, 3, 0, 1, 0, + 28, 17, 0, 0, 2, 0, 1, 0, + 126, 0, 192, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 64, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 25, 17, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 28, 17, 0, 0, 3, 0, 1, 0, + 40, 17, 0, 0, 2, 0, 1, 0, + 121, 0, 191, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 65, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 37, 17, 0, 0, 202, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 44, 17, 0, 0, 3, 0, 1, 0, + 56, 17, 0, 0, 2, 0, 1, 0, + 35, 0, 190, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 53, 17, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 52, 17, 0, 0, 3, 0, 1, 0, + 64, 17, 0, 0, 2, 0, 1, 0, + 1, 0, 0, 0, 80, 0, 0, 0, + 0, 0, 1, 0, 67, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 61, 17, 0, 0, 50, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 56, 17, 0, 0, 3, 0, 1, 0, + 68, 17, 0, 0, 2, 0, 1, 0, + 36, 0, 189, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 68, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 65, 17, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 64, 17, 0, 0, 3, 0, 1, 0, + 92, 17, 0, 0, 2, 0, 1, 0, + 37, 0, 188, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 69, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 89, 17, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 88, 17, 0, 0, 3, 0, 1, 0, + 100, 17, 0, 0, 2, 0, 1, 0, + 44, 0, 187, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 70, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 17, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 17, 0, 0, 3, 0, 1, 0, + 112, 17, 0, 0, 2, 0, 1, 0, + 38, 0, 186, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 71, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 17, 0, 0, 178, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 17, 0, 0, 3, 0, 1, 0, + 124, 17, 0, 0, 2, 0, 1, 0, + 39, 0, 185, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 72, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 17, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 17, 0, 0, 3, 0, 1, 0, + 136, 17, 0, 0, 2, 0, 1, 0, + 3, 0, 184, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 73, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 17, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 132, 17, 0, 0, 3, 0, 1, 0, + 144, 17, 0, 0, 2, 0, 1, 0, + 45, 0, 183, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 17, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 144, 17, 0, 0, 3, 0, 1, 0, + 156, 17, 0, 0, 2, 0, 1, 0, + 40, 0, 182, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 75, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 17, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 17, 0, 0, 3, 0, 1, 0, + 160, 17, 0, 0, 2, 0, 1, 0, + 47, 0, 181, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 76, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 157, 17, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 156, 17, 0, 0, 3, 0, 1, 0, + 168, 17, 0, 0, 2, 0, 1, 0, + 48, 0, 180, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 77, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 165, 17, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 17, 0, 0, 3, 0, 1, 0, + 180, 17, 0, 0, 2, 0, 1, 0, + 55, 0, 179, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 78, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 17, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 176, 17, 0, 0, 3, 0, 1, 0, + 188, 17, 0, 0, 2, 0, 1, 0, + 56, 0, 178, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 79, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 185, 17, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 17, 0, 0, 3, 0, 1, 0, + 196, 17, 0, 0, 2, 0, 1, 0, + 17, 0, 177, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 80, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 17, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 192, 17, 0, 0, 3, 0, 1, 0, + 204, 17, 0, 0, 2, 0, 1, 0, + 16, 0, 176, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 81, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 201, 17, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 200, 17, 0, 0, 3, 0, 1, 0, + 228, 17, 0, 0, 2, 0, 1, 0, + 62, 0, 175, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 225, 17, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 224, 17, 0, 0, 3, 0, 1, 0, + 236, 17, 0, 0, 2, 0, 1, 0, + 63, 0, 174, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 83, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 233, 17, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 17, 0, 0, 3, 0, 1, 0, + 244, 17, 0, 0, 2, 0, 1, 0, + 64, 0, 173, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 84, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 17, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 17, 0, 0, 3, 0, 1, 0, + 252, 17, 0, 0, 2, 0, 1, 0, + 61, 0, 172, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 85, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 249, 17, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 248, 17, 0, 0, 3, 0, 1, 0, + 4, 18, 0, 0, 2, 0, 1, 0, + 69, 0, 171, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 86, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 18, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 18, 0, 0, 3, 0, 1, 0, + 12, 18, 0, 0, 2, 0, 1, 0, + 70, 0, 170, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 87, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 18, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 18, 0, 0, 3, 0, 1, 0, + 24, 18, 0, 0, 2, 0, 1, 0, + 71, 0, 169, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 88, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 21, 18, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 24, 18, 0, 0, 3, 0, 1, 0, + 36, 18, 0, 0, 2, 0, 1, 0, + 72, 0, 168, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 89, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 33, 18, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 32, 18, 0, 0, 3, 0, 1, 0, + 44, 18, 0, 0, 2, 0, 1, 0, + 49, 0, 167, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 41, 18, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 40, 18, 0, 0, 3, 0, 1, 0, + 52, 18, 0, 0, 2, 0, 1, 0, + 31, 0, 166, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 91, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 49, 18, 0, 0, 138, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 52, 18, 0, 0, 3, 0, 1, 0, + 64, 18, 0, 0, 2, 0, 1, 0, + 41, 0, 165, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 92, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 18, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 60, 18, 0, 0, 3, 0, 1, 0, + 72, 18, 0, 0, 2, 0, 1, 0, + 66, 0, 164, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 93, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 69, 18, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 18, 0, 0, 3, 0, 1, 0, + 80, 18, 0, 0, 2, 0, 1, 0, + 33, 0, 163, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 94, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 18, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 80, 18, 0, 0, 3, 0, 1, 0, + 92, 18, 0, 0, 2, 0, 1, 0, + 12, 0, 162, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 95, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 89, 18, 0, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 88, 18, 0, 0, 3, 0, 1, 0, + 100, 18, 0, 0, 2, 0, 1, 0, + 13, 0, 161, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 96, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 18, 0, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 96, 18, 0, 0, 3, 0, 1, 0, + 108, 18, 0, 0, 2, 0, 1, 0, + 14, 0, 160, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 97, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 18, 0, 0, 146, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 18, 0, 0, 3, 0, 1, 0, + 120, 18, 0, 0, 2, 0, 1, 0, + 10, 0, 159, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 98, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 18, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 18, 0, 0, 3, 0, 1, 0, + 128, 18, 0, 0, 2, 0, 1, 0, + 8, 0, 158, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 99, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 125, 18, 0, 0, 82, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 18, 0, 0, 3, 0, 1, 0, + 136, 18, 0, 0, 2, 0, 1, 0, + 9, 0, 157, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 100, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 18, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 132, 18, 0, 0, 3, 0, 1, 0, + 144, 18, 0, 0, 2, 0, 1, 0, + 11, 0, 156, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 101, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 141, 18, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 140, 18, 0, 0, 3, 0, 1, 0, + 152, 18, 0, 0, 2, 0, 1, 0, + 67, 0, 155, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 102, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 149, 18, 0, 0, 66, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 144, 18, 0, 0, 3, 0, 1, 0, + 156, 18, 0, 0, 2, 0, 1, 0, + 53, 0, 154, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 103, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 153, 18, 0, 0, 90, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 152, 18, 0, 0, 3, 0, 1, 0, + 164, 18, 0, 0, 2, 0, 1, 0, + 42, 0, 153, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 104, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 161, 18, 0, 0, 74, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 160, 18, 0, 0, 3, 0, 1, 0, + 172, 18, 0, 0, 2, 0, 1, 0, + 65, 0, 152, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 105, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 169, 18, 0, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 168, 18, 0, 0, 3, 0, 1, 0, + 180, 18, 0, 0, 2, 0, 1, 0, + 25, 0, 151, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 106, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 177, 18, 0, 0, 58, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 172, 18, 0, 0, 3, 0, 1, 0, + 184, 18, 0, 0, 2, 0, 1, 0, + 79, 0, 150, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 107, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 181, 18, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 184, 18, 0, 0, 3, 0, 1, 0, + 196, 18, 0, 0, 2, 0, 1, 0, + 80, 0, 149, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 108, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 193, 18, 0, 0, 170, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 196, 18, 0, 0, 3, 0, 1, 0, + 208, 18, 0, 0, 2, 0, 1, 0, + 81, 0, 148, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 109, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 205, 18, 0, 0, 162, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 208, 18, 0, 0, 3, 0, 1, 0, + 220, 18, 0, 0, 2, 0, 1, 0, + 82, 0, 147, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 110, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 217, 18, 0, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 216, 18, 0, 0, 3, 0, 1, 0, + 228, 18, 0, 0, 2, 0, 1, 0, + 83, 0, 146, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 111, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 225, 18, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 224, 18, 0, 0, 3, 0, 1, 0, + 236, 18, 0, 0, 2, 0, 1, 0, + 84, 0, 145, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 112, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 233, 18, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 232, 18, 0, 0, 3, 0, 1, 0, + 244, 18, 0, 0, 2, 0, 1, 0, + 85, 0, 144, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 113, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 241, 18, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 240, 18, 0, 0, 3, 0, 1, 0, + 252, 18, 0, 0, 2, 0, 1, 0, + 86, 0, 143, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 114, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 249, 18, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 248, 18, 0, 0, 3, 0, 1, 0, + 4, 19, 0, 0, 2, 0, 1, 0, + 87, 0, 142, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 115, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 19, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 19, 0, 0, 3, 0, 1, 0, + 12, 19, 0, 0, 2, 0, 1, 0, + 88, 0, 141, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 116, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 19, 0, 0, 130, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 8, 19, 0, 0, 3, 0, 1, 0, + 20, 19, 0, 0, 2, 0, 1, 0, + 50, 0, 140, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 117, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 17, 19, 0, 0, 194, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 20, 19, 0, 0, 3, 0, 1, 0, + 32, 19, 0, 0, 2, 0, 1, 0, + 51, 0, 139, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 118, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 29, 19, 0, 0, 226, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 36, 19, 0, 0, 3, 0, 1, 0, + 48, 19, 0, 0, 2, 0, 1, 0, + 52, 0, 138, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 119, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 45, 19, 0, 0, 210, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 52, 19, 0, 0, 3, 0, 1, 0, + 64, 19, 0, 0, 2, 0, 1, 0, + 73, 0, 137, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 120, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 61, 19, 0, 0, 202, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 68, 19, 0, 0, 3, 0, 1, 0, + 80, 19, 0, 0, 2, 0, 1, 0, + 74, 0, 136, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 121, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 77, 19, 0, 0, 234, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 84, 19, 0, 0, 3, 0, 1, 0, + 96, 19, 0, 0, 2, 0, 1, 0, + 75, 0, 135, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 122, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 93, 19, 0, 0, 218, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 19, 0, 0, 3, 0, 1, 0, + 112, 19, 0, 0, 2, 0, 1, 0, + 15, 0, 134, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 123, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 19, 0, 0, 154, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 19, 0, 0, 3, 0, 1, 0, + 124, 19, 0, 0, 2, 0, 1, 0, + 76, 0, 133, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 124, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 121, 19, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 124, 19, 0, 0, 3, 0, 1, 0, + 136, 19, 0, 0, 2, 0, 1, 0, + 77, 0, 132, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 125, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 133, 19, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 136, 19, 0, 0, 3, 0, 1, 0, + 148, 19, 0, 0, 2, 0, 1, 0, + 78, 0, 131, 255, 0, 0, 0, 0, + 0, 0, 1, 0, 126, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 145, 19, 0, 0, 186, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 148, 19, 0, 0, 3, 0, 1, 0, + 160, 19, 0, 0, 2, 0, 1, 0, + 108, 111, 103, 77, 111, 110, 111, 84, + 105, 109, 101, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 9, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 105, 110, 105, 116, 68, 97, 116, 97, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 92, 182, 63, 235, 202, 8, 16, 231, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 111, 97, 100, 67, 97, 109, 101, + 114, 97, 83, 116, 97, 116, 101, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 51, 10, 174, 149, 246, 69, 2, 234, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 78, 77, 69, 65, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 136, 74, 186, 19, 120, 29, 41, 157, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 101, 110, 115, 111, 114, 69, 118, + 101, 110, 116, 68, 69, 80, 82, 69, + 67, 65, 84, 69, 68, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 161, 41, 69, 212, 105, 154, 178, 162, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 110, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 89, 124, 76, 150, 154, 0, 133, 135, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 101, 118, 105, 99, 101, 83, 116, + 97, 116, 101, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 235, 146, 164, 42, 175, 181, 216, 164, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 111, 110, 116, 114, 111, 108, 115, + 83, 116, 97, 116, 101, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 241, 171, 1, 54, 197, 105, 255, 151, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 105, 118, 101, 69, 118, 101, 110, + 116, 68, 69, 80, 82, 69, 67, 65, + 84, 69, 68, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 30, 50, 92, 12, 169, 186, 183, 148, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 111, 100, 101, 108, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 169, 40, 239, 255, 44, 214, 170, 184, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 101, 97, 116, 117, 114, 101, 115, + 68, 69, 80, 82, 69, 67, 65, 84, + 69, 68, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 122, 134, 234, 84, 178, 173, 223, 143, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 101, 110, 115, 111, 114, 69, 118, + 101, 110, 116, 115, 68, 69, 80, 82, + 69, 67, 65, 84, 69, 68, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 161, 41, 69, 212, 105, 154, 178, 162, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 97, 110, 100, 97, 83, 116, 97, + 116, 101, 68, 69, 80, 82, 69, 67, + 65, 84, 69, 68, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 30, 89, 228, 117, 37, 158, 100, 167, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 97, 100, 97, 114, 83, 116, 97, + 116, 101, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 95, 208, 253, 214, 137, 83, 24, 154, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 105, 118, 101, 85, 73, 68, 69, + 80, 82, 69, 67, 65, 84, 69, 68, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 237, 252, 174, 150, 249, 64, 130, 192, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 111, 97, 100, 69, 110, 99, 111, + 100, 101, 73, 100, 120, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 252, 53, 23, 84, 227, 148, 211, 137, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 105, 118, 101, 84, 114, 97, 99, + 107, 115, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 81, 194, 222, 50, 71, 100, 170, 143, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 101, 110, 100, 99, 97, 110, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 89, 124, 76, 150, 154, 0, 133, 135, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 103, 77, 101, 115, 115, 97, + 103, 101, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 105, 118, 101, 67, 97, 108, 105, + 98, 114, 97, 116, 105, 111, 110, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 188, 144, 131, 77, 117, 112, 223, 150, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 110, 100, 114, 111, 105, 100, 76, + 111, 103, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 133, 125, 79, 137, 161, 93, 9, 234, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 76, 111, 99, 97, 116, + 105, 111, 110, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 14, 213, 173, 89, 72, 82, 70, 233, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 83, 116, 97, 116, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 60, 144, 82, 224, 9, 250, 164, 157, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 67, 111, 110, 116, 114, + 111, 108, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 175, 20, 184, 154, 4, 41, 136, 247, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 110, 103, 105, 116, 117, 100, + 105, 110, 97, 108, 80, 108, 97, 110, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 108, 135, 18, 186, 62, 91, 11, 224, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 105, 118, 101, 76, 111, 99, 97, + 116, 105, 111, 110, 68, 69, 80, 82, + 69, 67, 65, 84, 69, 68, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 40, 129, 126, 165, 199, 43, 155, 185, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 116, 104, 101, 114, 110, 101, 116, + 68, 97, 116, 97, 68, 69, 80, 82, + 69, 67, 65, 84, 69, 68, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 89, 88, 207, 51, 91, 157, 154, 169, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 97, 118, 85, 112, 100, 97, 116, + 101, 68, 69, 80, 82, 69, 67, 65, + 84, 69, 68, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 203, 106, 81, 101, 101, 190, 152, 219, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 101, 108, 108, 73, 110, 102, 111, + 68, 69, 80, 82, 69, 67, 65, 84, + 69, 68, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 206, 119, 194, 129, 102, 86, 247, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 119, 105, 102, 105, 83, 99, 97, 110, + 68, 69, 80, 82, 69, 67, 65, 84, + 69, 68, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 11, 186, 130, 35, 25, 90, 223, 212, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 110, 100, 114, 111, 105, 100, 71, + 110, 115, 115, 68, 69, 80, 82, 69, + 67, 65, 84, 69, 68, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 189, 133, 196, 63, 208, 48, 223, 223, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 99, 111, 109, 71, 110, 115, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 193, 81, 174, 7, 75, 103, 148, 222, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 105, 100, 97, 114, 80, 116, 115, + 68, 69, 80, 82, 69, 67, 65, 84, + 69, 68, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 122, 143, 157, 78, 93, 104, 214, 227, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 114, 111, 99, 76, 111, 103, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 6, 20, 104, 63, 123, 56, 133, 175, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 98, 108, 111, 120, 71, 110, 115, + 115, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 93, 250, 206, 230, 124, 221, 221, 133, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 108, 111, 99, 107, 115, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 24, 70, 220, 123, 154, 180, 95, 201, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 105, 118, 101, 77, 112, 99, 68, + 69, 80, 82, 69, 67, 65, 84, 69, + 68, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 160, 50, 95, 168, 50, 227, 165, 146, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 105, 118, 101, 76, 111, 110, 103, + 105, 116, 117, 100, 105, 110, 97, 108, + 77, 112, 99, 68, 69, 80, 82, 69, + 67, 65, 84, 69, 68, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 226, 90, 134, 79, 67, 124, 225, 231, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 97, 118, 83, 116, 97, 116, 117, + 115, 68, 69, 80, 82, 69, 67, 65, + 84, 69, 68, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 12, 18, 40, 9, 18, 34, 136, 189, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 98, 108, 111, 120, 82, 97, 119, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 80, 108, 97, 110, 110, + 101, 114, 80, 111, 105, 110, 116, 115, + 68, 69, 80, 82, 69, 67, 65, 84, + 69, 68, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 243, 249, 248, 153, 150, 197, 84, 171, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 80, 108, 97, 110, 110, + 101, 114, 80, 108, 97, 110, 68, 69, + 80, 82, 69, 67, 65, 84, 69, 68, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 107, 221, 193, 205, 144, 29, 173, 245, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 112, 112, 108, 97, 110, 105, 120, + 82, 97, 119, 68, 69, 80, 82, 69, + 67, 65, 84, 69, 68, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 114, 97, 102, 102, 105, 99, 69, + 118, 101, 110, 116, 115, 68, 69, 80, + 82, 69, 67, 65, 84, 69, 68, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 38, 38, 230, 148, 160, 116, 250, 172, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 105, 118, 101, 76, 111, 99, 97, + 116, 105, 111, 110, 84, 105, 109, 105, + 110, 103, 68, 69, 80, 82, 69, 67, + 65, 84, 69, 68, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 40, 129, 126, 165, 199, 43, 155, 185, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 114, 98, 115, 108, 97, 109, 67, + 111, 114, 114, 101, 99, 116, 105, 111, + 110, 68, 69, 80, 82, 69, 67, 65, + 84, 69, 68, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 170, 225, 53, 155, 220, 51, 253, 138, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 105, 118, 101, 76, 111, 99, 97, + 116, 105, 111, 110, 67, 111, 114, 114, + 101, 99, 116, 101, 100, 68, 69, 80, + 82, 69, 67, 65, 84, 69, 68, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 40, 129, 126, 165, 199, 43, 155, 185, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 114, 98, 79, 98, 115, 101, 114, + 118, 97, 116, 105, 111, 110, 68, 69, + 80, 82, 69, 67, 65, 84, 69, 68, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 199, 254, 106, 67, 78, 109, 50, 155, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 112, 115, 76, 111, 99, 97, 116, + 105, 111, 110, 69, 120, 116, 101, 114, + 110, 97, 108, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 14, 213, 173, 89, 72, 82, 70, 233, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 111, 99, 97, 116, 105, 111, 110, + 68, 69, 80, 82, 69, 67, 65, 84, + 69, 68, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 40, 129, 126, 165, 199, 43, 155, 185, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 105, 78, 97, 118, 105, 103, 97, + 116, 105, 111, 110, 69, 118, 101, 110, + 116, 68, 69, 80, 82, 69, 67, 65, + 84, 69, 68, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 59, 221, 173, 62, 108, 66, 200, 144, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 105, 118, 101, 76, 111, 99, 97, + 116, 105, 111, 110, 75, 97, 108, 109, + 97, 110, 68, 69, 80, 82, 69, 67, + 65, 84, 69, 68, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 40, 129, 126, 165, 199, 43, 155, 185, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 101, 115, 116, 74, 111, 121, 115, + 116, 105, 99, 107, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 226, 21, 39, 142, 101, 1, 36, 228, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 114, 98, 79, 100, 111, 109, 101, + 116, 114, 121, 68, 69, 80, 82, 69, + 67, 65, 84, 69, 68, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 118, 91, 31, 237, 89, 8, 112, 215, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 114, 98, 70, 101, 97, 116, 117, + 114, 101, 115, 68, 69, 80, 82, 69, + 67, 65, 84, 69, 68, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 239, 89, 1, 138, 74, 22, 96, 205, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 112, 112, 108, 97, 110, 105, 120, + 76, 111, 99, 97, 116, 105, 111, 110, + 68, 69, 80, 82, 69, 67, 65, 84, + 69, 68, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 40, 129, 126, 165, 199, 43, 155, 185, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 114, 98, 75, 101, 121, 70, 114, + 97, 109, 101, 68, 69, 80, 82, 69, + 67, 65, 84, 69, 68, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 36, 126, 226, 69, 3, 60, 35, 200, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 105, 76, 97, 121, 111, 117, 116, + 83, 116, 97, 116, 101, 68, 69, 80, + 82, 69, 67, 65, 84, 69, 68, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 160, 221, 41, 173, 8, 206, 220, 136, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 114, 98, 70, 101, 97, 116, 117, + 114, 101, 115, 83, 117, 109, 109, 97, + 114, 121, 68, 69, 80, 82, 69, 67, + 65, 84, 69, 68, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 79, 250, 3, 88, 12, 211, 0, 213, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 114, 105, 118, 101, 114, 83, 116, + 97, 116, 101, 68, 69, 80, 82, 69, + 67, 65, 84, 69, 68, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 10, 237, 147, 197, 108, 60, 184, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 98, 111, 111, 116, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 73, 37, 122, 146, 112, 134, 46, 161, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 105, 118, 101, 80, 97, 114, 97, + 109, 101, 116, 101, 114, 115, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 83, 39, 124, 150, 203, 141, 5, 217, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 105, 118, 101, 77, 97, 112, 68, + 97, 116, 97, 68, 69, 80, 82, 69, + 67, 65, 84, 69, 68, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 166, 17, 247, 147, 143, 38, 62, 148, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 109, 101, 114, 97, 79, 100, + 111, 109, 101, 116, 114, 121, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 150, 26, 212, 159, 107, 41, 154, 250, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 97, 116, 101, 114, 97, 108, 80, + 108, 97, 110, 68, 69, 80, 82, 69, + 67, 65, 84, 69, 68, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 30, 181, 232, 42, 142, 49, 233, 225, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 107, 97, 108, 109, 97, 110, 79, 100, + 111, 109, 101, 116, 114, 121, 68, 69, + 80, 82, 69, 67, 65, 84, 69, 68, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 58, 121, 56, 234, 183, 27, 226, 146, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 104, 117, 109, 98, 110, 97, 105, + 108, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 211, 247, 10, 18, 100, 206, 95, 182, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 118, 97, 108, 105, 100, 0, 0, 0, + 1, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 1, 0, 1, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 111, 110, 114, 111, 97, 100, 69, 118, + 101, 110, 116, 115, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 211, 58, 175, 76, 243, 87, 22, 155, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 97, 114, 80, 97, 114, 97, 109, + 115, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 218, 169, 170, 144, 36, 55, 105, 140, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 114, 105, 118, 101, 114, 67, 97, + 109, 101, 114, 97, 83, 116, 97, 116, + 101, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 51, 10, 174, 149, 246, 69, 2, 234, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 114, 105, 118, 101, 114, 77, 111, + 110, 105, 116, 111, 114, 105, 110, 103, + 83, 116, 97, 116, 101, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 132, 162, 29, 74, 9, 218, 60, 184, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 105, 118, 101, 76, 111, 99, 97, + 116, 105, 111, 110, 75, 97, 108, 109, + 97, 110, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 41, 193, 231, 30, 61, 112, 197, 235, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 115, 101, 110, 116, 105, 110, 101, 108, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 56, 110, 245, 68, 210, 130, 3, 239, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 119, 105, 100, 101, 82, 111, 97, 100, + 67, 97, 109, 101, 114, 97, 83, 116, + 97, 116, 101, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 51, 10, 174, 149, 246, 69, 2, 234, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 111, 100, 101, 108, 86, 50, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 233, 171, 54, 13, 107, 63, 113, 196, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 114, 105, 118, 101, 114, 69, 110, + 99, 111, 100, 101, 73, 100, 120, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 252, 53, 23, 84, 227, 148, 211, 137, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 119, 105, 100, 101, 82, 111, 97, 100, + 69, 110, 99, 111, 100, 101, 73, 100, + 120, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 252, 53, 23, 84, 227, 148, 211, 137, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 97, 110, 97, 103, 101, 114, 83, + 116, 97, 116, 101, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 91, 99, 105, 26, 179, 84, 113, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 112, 108, 111, 97, 100, 101, 114, + 83, 116, 97, 116, 101, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 30, 70, 107, 183, 57, 107, 38, 222, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 101, 114, 105, 112, 104, 101, 114, + 97, 108, 83, 116, 97, 116, 101, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 136, 122, 133, 52, 151, 244, 184, 206, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 112, 97, 110, 100, 97, 83, 116, 97, + 116, 101, 115, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 3, 0, 1, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 30, 89, 228, 117, 37, 158, 100, 167, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 14, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 97, 118, 73, 110, 115, 116, 114, + 117, 99, 116, 105, 111, 110, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 175, 2, 134, 127, 178, 22, 130, 193, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 97, 118, 82, 111, 117, 116, 101, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 211, 151, 13, 68, 246, 82, 20, 166, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 97, 118, 84, 104, 117, 109, 98, + 110, 97, 105, 108, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 211, 247, 10, 18, 100, 206, 95, 182, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 101, 114, 114, 111, 114, 76, 111, 103, + 77, 101, 115, 115, 97, 103, 101, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 12, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 114, 111, 97, 100, 69, 110, 99, 111, + 100, 101, 68, 97, 116, 97, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 240, 133, 221, 85, 179, 234, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 114, 105, 118, 101, 114, 69, 110, + 99, 111, 100, 101, 68, 97, 116, 97, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 240, 133, 221, 85, 179, 234, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 119, 105, 100, 101, 82, 111, 97, 100, + 69, 110, 99, 111, 100, 101, 68, 97, + 116, 97, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 240, 133, 221, 85, 179, 234, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 82, 111, 97, 100, 69, 110, 99, + 111, 100, 101, 68, 97, 116, 97, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 240, 133, 221, 85, 179, 234, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 113, 82, 111, 97, 100, 69, 110, 99, + 111, 100, 101, 73, 100, 120, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 252, 53, 23, 84, 227, 148, 211, 137, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 110, 115, 115, 77, 101, 97, 115, + 117, 114, 101, 109, 101, 110, 116, 115, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 9, 157, 14, 87, 22, 112, 212, 175, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 100, 114, 105, 118, 101, 114, 83, 116, + 97, 116, 101, 86, 50, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 176, 99, 117, 20, 64, 12, 1, 252, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 115, 101, 114, 70, 108, 97, 103, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 80, 155, 141, 228, 157, 106, 52, 254, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 105, 118, 101, 84, 111, 114, 113, + 117, 101, 80, 97, 114, 97, 109, 101, + 116, 101, 114, 115, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 146, 22, 9, 11, 235, 144, 22, 230, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 97, 103, 110, 101, 116, 111, 109, + 101, 116, 101, 114, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 161, 41, 69, 212, 105, 154, 178, 162, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 105, 103, 104, 116, 83, 101, 110, + 115, 111, 114, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 161, 41, 69, 212, 105, 154, 178, 162, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 101, 109, 112, 101, 114, 97, 116, + 117, 114, 101, 83, 101, 110, 115, 111, + 114, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 161, 41, 69, 212, 105, 154, 178, 162, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 99, 101, 108, 101, 114, 111, + 109, 101, 116, 101, 114, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 161, 41, 69, 212, 105, 154, 178, 162, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 121, 114, 111, 115, 99, 111, 112, + 101, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 161, 41, 69, 212, 105, 154, 178, 162, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 103, 121, 114, 111, 115, 99, 111, 112, + 101, 50, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 161, 41, 69, 212, 105, 154, 178, 162, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 97, 99, 99, 101, 108, 101, 114, 111, + 109, 101, 116, 101, 114, 50, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 161, 41, 69, 212, 105, 154, 178, 162, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 105, 68, 101, 98, 117, 103, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 207, 234, 250, 111, 137, 173, 53, 254, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 105, 99, 114, 111, 112, 104, 111, + 110, 101, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 35, 96, 114, 144, 137, 19, 36, 220, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 110, 97, 118, 77, 111, 100, 101, 108, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 122, 5, 190, 55, 196, 229, 61, 172, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 109, 97, 112, 82, 101, 110, 100, 101, + 114, 83, 116, 97, 116, 101, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 27, 168, 250, 76, 42, 221, 88, 161, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 117, 105, 80, 108, 97, 110, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 193, 39, 57, 94, 176, 155, 12, 252, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 114, 111, 103, 112, 105, 108, 111, + 116, 67, 97, 114, 67, 111, 110, 116, + 114, 111, 108, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 175, 244, 76, 57, 90, 240, 194, 129, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 114, 111, 103, 112, 105, 108, 111, + 116, 68, 101, 118, 105, 99, 101, 83, + 116, 97, 116, 101, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 93, 181, 231, 49, 143, 253, 223, 174, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 114, 111, 103, 112, 105, 108, 111, + 116, 78, 97, 118, 105, 103, 97, 116, + 105, 111, 110, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 194, 110, 191, 11, 86, 196, 92, 243, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 102, 114, 111, 103, 112, 105, 108, 111, + 116, 80, 108, 97, 110, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 53, 76, 68, 131, 152, 87, 150, 218, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 115, 116, 111, 109, 82, 101, + 115, 101, 114, 118, 101, 100, 52, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 17, 107, 89, 226, 110, 116, 174, 128, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 115, 116, 111, 109, 82, 101, + 115, 101, 114, 118, 101, 100, 53, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 85, 164, 81, 217, 44, 118, 205, 165, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 115, 116, 111, 109, 82, 101, + 115, 101, 114, 118, 101, 100, 54, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 163, 4, 112, 253, 59, 132, 141, 249, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 115, 116, 111, 109, 82, 101, + 115, 101, 114, 118, 101, 100, 55, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 200, 1, 76, 33, 105, 99, 110, 184, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 115, 116, 111, 109, 82, 101, + 115, 101, 114, 118, 101, 100, 56, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 25, 157, 157, 73, 9, 236, 22, 244, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 115, 116, 111, 109, 82, 101, + 115, 101, 114, 118, 101, 100, 57, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 45, 219, 31, 3, 68, 7, 104, 161, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 105, 118, 101, 115, 116, 114, 101, + 97, 109, 82, 111, 97, 100, 69, 110, + 99, 111, 100, 101, 73, 100, 120, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 252, 53, 23, 84, 227, 148, 211, 137, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 105, 118, 101, 115, 116, 114, 101, + 97, 109, 87, 105, 100, 101, 82, 111, + 97, 100, 69, 110, 99, 111, 100, 101, + 73, 100, 120, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 252, 53, 23, 84, 227, 148, 211, 137, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 105, 118, 101, 115, 116, 114, 101, + 97, 109, 68, 114, 105, 118, 101, 114, + 69, 110, 99, 111, 100, 101, 73, 100, + 120, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 252, 53, 23, 84, 227, 148, 211, 137, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 105, 118, 101, 115, 116, 114, 101, + 97, 109, 82, 111, 97, 100, 69, 110, + 99, 111, 100, 101, 68, 97, 116, 97, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 240, 133, 221, 85, 179, 234, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 105, 118, 101, 115, 116, 114, 101, + 97, 109, 87, 105, 100, 101, 82, 111, + 97, 100, 69, 110, 99, 111, 100, 101, + 68, 97, 116, 97, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 240, 133, 221, 85, 179, 234, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 108, 105, 118, 101, 115, 116, 114, 101, + 97, 109, 68, 114, 105, 118, 101, 114, + 69, 110, 99, 111, 100, 101, 68, 97, + 116, 97, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 240, 133, 221, 85, 179, 234, 154, 207, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 116, 101, 109, 112, 101, 114, 97, 116, + 117, 114, 101, 83, 101, 110, 115, 111, + 114, 50, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 161, 41, 69, 212, 105, 154, 178, 162, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 16, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 115, 116, 111, 109, 82, 101, + 115, 101, 114, 118, 101, 100, 82, 97, + 119, 68, 97, 116, 97, 48, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 115, 116, 111, 109, 82, 101, + 115, 101, 114, 118, 101, 100, 82, 97, + 119, 68, 97, 116, 97, 49, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 99, 117, 115, 116, 111, 109, 82, 101, + 115, 101, 114, 118, 101, 100, 82, 97, + 119, 68, 97, 116, 97, 50, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 13, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, } +}; +::capnp::word const* const bp_d314cfd957229c11 = b_d314cfd957229c11.words; +#if !CAPNP_LITE +static const ::capnp::_::RawSchema* const d_d314cfd957229c11[] = { + &s_80ae746ee2596b11, + &s_81c2f05a394cf4af, + &s_85dddd7ce6cefa5d, + &s_8785009a964c7c59, + &s_88dcce08ad29dda0, + &s_89d394e3541735fc, + &s_8afd33dc9b35e1aa, + &s_8c69372490aaa9da, + &s_8faa644732dec251, + &s_8fdfadb254ea867a, + &s_90c8426c3eaddd3b, + &s_92a5e332a85f32a0, + &s_92e21bb7ea38793a, + &s_943e268f93f711a6, + &s_94b7baa90c5c321e, + &s_96df70754d8390bc, + &s_97ff69c53601abf1, + &s_9a185389d6fdd05f, + &s_9b1657f34caf3ad3, + &s_9b326d4e436afec7, + &s_9d291d7813ba4a88, + &s_9da4fa09e052903c, + &s_a12e8670927a2549, + &s_a158dd2a4cfaa81b, + &s_a1680744031fdb2d, + &s_a2b29a69d44529a1, + &s_a4d8b5af2aa492eb, + &s_a5cd762cd951a455, + &s_a61452f6440d97d3, + &s_a7649e2575e4591e, + &s_a99a9d5b33cf5859, + &s_ab54c59699f8f9f3, + &s_ac3de5c437be057a, + &s_acfa74a094e62626, + &s_aedffd8f31e7b55d, + &s_af85387b3f681406, + &s_afd47016570e9d09, + &s_b65fce64120af7d3, + &s_b83c6cc593ed0a00, + &s_b83cda094a1da284, + &s_b86e6369214c01c8, + &s_b8aad62cffef28a9, + &s_b99b2bc7a57e8128, + &s_bd8822120928120c, + &s_c08240f996aefced, + &s_c18216b27f8602af, + &s_c4713f6b0d36abe9, + &s_c8233c0345e27e24, + &s_c95fb49a7bdc4618, + &s_cd60164a8a0159ef, + &s_ceb8f49734857a88, + &s_cf7154b31a69635b, + &s_cf9aeab355dd85f0, + &s_cff7566681c277ce, + &s_d4df5a192382ba0b, + &s_d500d30c5803fa4f, + &s_d7700859ed1f5b76, + &s_d9058dcb967c2753, + &s_da96579883444c35, + &s_db98be6565516acb, + &s_dc24138990726023, + &s_de266b39b76b461e, + &s_de94674b07ae51c1, + &s_dfdf30d03fc485bd, + &s_e00b5b3eba12876c, + &s_e1e9318e2ae8b51e, + &s_e3d6685d4e9d8f7a, + &s_e42401658e2715e2, + &s_e61690eb0b091692, + &s_e71008caeb3fb65c, + &s_e7e17c434f865ae2, + &s_e946524859add50e, + &s_ea0245f695ae0a33, + &s_ea095da1894f7d85, + &s_ebc5703d1ee7c129, + &s_ef0382d244f56e38, + &s_f35cc4560bbf6ec2, + &s_f416ec09499d9d19, + &s_f5ad1d90cdc1dd6b, + &s_f78829049ab814af, + &s_f98d843bfd7004a3, + &s_fa9a296b9fd41a96, + &s_fc010c40147563b0, + &s_fc0c9bb05e3927c1, + &s_fe346a9de48d9b50, + &s_fe35ad896ffaeacf, +}; +static const uint16_t m_d314cfd957229c11[] = {98, 101, 30, 20, 55, 42, 60, 63, 5, 23, 69, 22, 28, 35, 7, 111, 112, 113, 114, 115, 116, 124, 125, 126, 6, 70, 87, 76, 71, 59, 92, 85, 26, 10, 107, 108, 109, 110, 91, 21, 48, 3, 41, 40, 99, 100, 1, 65, 64, 32, 96, 19, 8, 46, 25, 72, 51, 44, 37, 62, 36, 61, 94, 16, 14, 122, 119, 120, 117, 121, 118, 49, 18, 0, 24, 95, 78, 105, 103, 9, 75, 82, 104, 83, 38, 84, 27, 68, 54, 58, 56, 47, 53, 45, 12, 81, 80, 33, 89, 90, 31, 13, 2, 86, 15, 17, 4, 11, 73, 97, 123, 52, 66, 43, 34, 39, 102, 57, 50, 106, 79, 93, 67, 74, 88, 77, 29}; +static const uint16_t i_d314cfd957229c11[] = {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, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96, 97, 98, 99, 100, 101, 102, 103, 104, 105, 106, 107, 108, 109, 110, 111, 112, 113, 114, 115, 116, 117, 118, 119, 120, 121, 122, 123, 124, 125, 126, 0, 67}; +const ::capnp::_::RawSchema s_d314cfd957229c11 = { + 0xd314cfd957229c11, b_d314cfd957229c11.words, 2164, d_d314cfd957229c11, m_d314cfd957229c11, + 86, 127, i_d314cfd957229c11, nullptr, nullptr, { &s_d314cfd957229c11, nullptr, nullptr, 0, 0, nullptr }, true +}; +#endif // !CAPNP_LITE +} // namespace schemas +} // namespace capnp + +// ======================================================================================= + +namespace cereal { + +// InitData +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t InitData::_capnpPrivate::dataWordSize; +constexpr uint16_t InitData::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind InitData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* InitData::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// InitData::PandaInfo +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t InitData::PandaInfo::_capnpPrivate::dataWordSize; +constexpr uint16_t InitData::PandaInfo::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind InitData::PandaInfo::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* InitData::PandaInfo::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// InitData::AndroidBuildInfo +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t InitData::AndroidBuildInfo::_capnpPrivate::dataWordSize; +constexpr uint16_t InitData::AndroidBuildInfo::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind InitData::AndroidBuildInfo::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* InitData::AndroidBuildInfo::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// InitData::AndroidSensor +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t InitData::AndroidSensor::_capnpPrivate::dataWordSize; +constexpr uint16_t InitData::AndroidSensor::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind InitData::AndroidSensor::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* InitData::AndroidSensor::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// InitData::ChffrAndroidExtra +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t InitData::ChffrAndroidExtra::_capnpPrivate::dataWordSize; +constexpr uint16_t InitData::ChffrAndroidExtra::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind InitData::ChffrAndroidExtra::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* InitData::ChffrAndroidExtra::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// InitData::IosBuildInfo +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t InitData::IosBuildInfo::_capnpPrivate::dataWordSize; +constexpr uint16_t InitData::IosBuildInfo::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind InitData::IosBuildInfo::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* InitData::IosBuildInfo::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// FrameData +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t FrameData::_capnpPrivate::dataWordSize; +constexpr uint16_t FrameData::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind FrameData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* FrameData::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// FrameData::AndroidCaptureResult +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t FrameData::AndroidCaptureResult::_capnpPrivate::dataWordSize; +constexpr uint16_t FrameData::AndroidCaptureResult::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind FrameData::AndroidCaptureResult::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* FrameData::AndroidCaptureResult::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// Thumbnail +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t Thumbnail::_capnpPrivate::dataWordSize; +constexpr uint16_t Thumbnail::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind Thumbnail::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Thumbnail::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// GPSNMEAData +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t GPSNMEAData::_capnpPrivate::dataWordSize; +constexpr uint16_t GPSNMEAData::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind GPSNMEAData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* GPSNMEAData::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// SensorEventData +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t SensorEventData::_capnpPrivate::dataWordSize; +constexpr uint16_t SensorEventData::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind SensorEventData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* SensorEventData::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// SensorEventData::SensorVec +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t SensorEventData::SensorVec::_capnpPrivate::dataWordSize; +constexpr uint16_t SensorEventData::SensorVec::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind SensorEventData::SensorVec::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* SensorEventData::SensorVec::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// GpsLocationData +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t GpsLocationData::_capnpPrivate::dataWordSize; +constexpr uint16_t GpsLocationData::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind GpsLocationData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* GpsLocationData::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// CanData +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t CanData::_capnpPrivate::dataWordSize; +constexpr uint16_t CanData::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind CanData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* CanData::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// DeviceState +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t DeviceState::_capnpPrivate::dataWordSize; +constexpr uint16_t DeviceState::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind DeviceState::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* DeviceState::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// DeviceState::ThermalZone +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t DeviceState::ThermalZone::_capnpPrivate::dataWordSize; +constexpr uint16_t DeviceState::ThermalZone::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind DeviceState::ThermalZone::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* DeviceState::ThermalZone::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// DeviceState::NetworkInfo +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t DeviceState::NetworkInfo::_capnpPrivate::dataWordSize; +constexpr uint16_t DeviceState::NetworkInfo::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind DeviceState::NetworkInfo::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* DeviceState::NetworkInfo::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// DeviceState::NetworkStats +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t DeviceState::NetworkStats::_capnpPrivate::dataWordSize; +constexpr uint16_t DeviceState::NetworkStats::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind DeviceState::NetworkStats::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* DeviceState::NetworkStats::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// PandaState +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t PandaState::_capnpPrivate::dataWordSize; +constexpr uint16_t PandaState::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind PandaState::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* PandaState::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// PandaState::PandaCanState +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t PandaState::PandaCanState::_capnpPrivate::dataWordSize; +constexpr uint16_t PandaState::PandaCanState::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind PandaState::PandaCanState::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* PandaState::PandaCanState::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// PeripheralState +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t PeripheralState::_capnpPrivate::dataWordSize; +constexpr uint16_t PeripheralState::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind PeripheralState::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* PeripheralState::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// RadarState +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t RadarState::_capnpPrivate::dataWordSize; +constexpr uint16_t RadarState::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind RadarState::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* RadarState::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// RadarState::LeadData +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t RadarState::LeadData::_capnpPrivate::dataWordSize; +constexpr uint16_t RadarState::LeadData::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind RadarState::LeadData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* RadarState::LeadData::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// LiveCalibrationData +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t LiveCalibrationData::_capnpPrivate::dataWordSize; +constexpr uint16_t LiveCalibrationData::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind LiveCalibrationData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* LiveCalibrationData::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// LiveTracks +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t LiveTracks::_capnpPrivate::dataWordSize; +constexpr uint16_t LiveTracks::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind LiveTracks::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* LiveTracks::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// ControlsState +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t ControlsState::_capnpPrivate::dataWordSize; +constexpr uint16_t ControlsState::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind ControlsState::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ControlsState::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// ControlsState::LateralINDIState +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t ControlsState::LateralINDIState::_capnpPrivate::dataWordSize; +constexpr uint16_t ControlsState::LateralINDIState::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind ControlsState::LateralINDIState::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ControlsState::LateralINDIState::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// ControlsState::LateralPIDState +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t ControlsState::LateralPIDState::_capnpPrivate::dataWordSize; +constexpr uint16_t ControlsState::LateralPIDState::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind ControlsState::LateralPIDState::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ControlsState::LateralPIDState::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// ControlsState::LateralTorqueState +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t ControlsState::LateralTorqueState::_capnpPrivate::dataWordSize; +constexpr uint16_t ControlsState::LateralTorqueState::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind ControlsState::LateralTorqueState::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ControlsState::LateralTorqueState::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// ControlsState::LateralLQRState +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t ControlsState::LateralLQRState::_capnpPrivate::dataWordSize; +constexpr uint16_t ControlsState::LateralLQRState::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind ControlsState::LateralLQRState::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ControlsState::LateralLQRState::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// ControlsState::LateralAngleState +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t ControlsState::LateralAngleState::_capnpPrivate::dataWordSize; +constexpr uint16_t ControlsState::LateralAngleState::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind ControlsState::LateralAngleState::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ControlsState::LateralAngleState::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// ControlsState::LateralCurvatureState +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t ControlsState::LateralCurvatureState::_capnpPrivate::dataWordSize; +constexpr uint16_t ControlsState::LateralCurvatureState::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind ControlsState::LateralCurvatureState::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ControlsState::LateralCurvatureState::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// ControlsState::LateralDebugState +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t ControlsState::LateralDebugState::_capnpPrivate::dataWordSize; +constexpr uint16_t ControlsState::LateralDebugState::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind ControlsState::LateralDebugState::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ControlsState::LateralDebugState::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// ControlsState::LateralControlState +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t ControlsState::LateralControlState::_capnpPrivate::dataWordSize; +constexpr uint16_t ControlsState::LateralControlState::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind ControlsState::LateralControlState::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ControlsState::LateralControlState::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// XYZTData +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t XYZTData::_capnpPrivate::dataWordSize; +constexpr uint16_t XYZTData::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind XYZTData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* XYZTData::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// ModelDataV2 +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t ModelDataV2::_capnpPrivate::dataWordSize; +constexpr uint16_t ModelDataV2::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind ModelDataV2::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ModelDataV2::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// ModelDataV2::LeadDataV2 +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t ModelDataV2::LeadDataV2::_capnpPrivate::dataWordSize; +constexpr uint16_t ModelDataV2::LeadDataV2::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind ModelDataV2::LeadDataV2::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ModelDataV2::LeadDataV2::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// ModelDataV2::LeadDataV3 +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t ModelDataV2::LeadDataV3::_capnpPrivate::dataWordSize; +constexpr uint16_t ModelDataV2::LeadDataV3::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind ModelDataV2::LeadDataV3::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ModelDataV2::LeadDataV3::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// ModelDataV2::MetaData +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t ModelDataV2::MetaData::_capnpPrivate::dataWordSize; +constexpr uint16_t ModelDataV2::MetaData::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind ModelDataV2::MetaData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ModelDataV2::MetaData::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// ModelDataV2::DisengagePredictions +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t ModelDataV2::DisengagePredictions::_capnpPrivate::dataWordSize; +constexpr uint16_t ModelDataV2::DisengagePredictions::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind ModelDataV2::DisengagePredictions::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ModelDataV2::DisengagePredictions::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// ModelDataV2::Pose +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t ModelDataV2::Pose::_capnpPrivate::dataWordSize; +constexpr uint16_t ModelDataV2::Pose::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind ModelDataV2::Pose::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ModelDataV2::Pose::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// ModelDataV2::LateralPlannerSolution +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t ModelDataV2::LateralPlannerSolution::_capnpPrivate::dataWordSize; +constexpr uint16_t ModelDataV2::LateralPlannerSolution::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind ModelDataV2::LateralPlannerSolution::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ModelDataV2::LateralPlannerSolution::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// ModelDataV2::Action +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t ModelDataV2::Action::_capnpPrivate::dataWordSize; +constexpr uint16_t ModelDataV2::Action::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind ModelDataV2::Action::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ModelDataV2::Action::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// EncodeIndex +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t EncodeIndex::_capnpPrivate::dataWordSize; +constexpr uint16_t EncodeIndex::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind EncodeIndex::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* EncodeIndex::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// AndroidLogEntry +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t AndroidLogEntry::_capnpPrivate::dataWordSize; +constexpr uint16_t AndroidLogEntry::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind AndroidLogEntry::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* AndroidLogEntry::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// LongitudinalPlan +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t LongitudinalPlan::_capnpPrivate::dataWordSize; +constexpr uint16_t LongitudinalPlan::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind LongitudinalPlan::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* LongitudinalPlan::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// LongitudinalPlan::GpsTrajectory +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t LongitudinalPlan::GpsTrajectory::_capnpPrivate::dataWordSize; +constexpr uint16_t LongitudinalPlan::GpsTrajectory::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind LongitudinalPlan::GpsTrajectory::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* LongitudinalPlan::GpsTrajectory::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// UiPlan +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t UiPlan::_capnpPrivate::dataWordSize; +constexpr uint16_t UiPlan::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind UiPlan::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* UiPlan::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// LateralPlan +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t LateralPlan::_capnpPrivate::dataWordSize; +constexpr uint16_t LateralPlan::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind LateralPlan::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* LateralPlan::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// LateralPlan::SolverState +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t LateralPlan::SolverState::_capnpPrivate::dataWordSize; +constexpr uint16_t LateralPlan::SolverState::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind LateralPlan::SolverState::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* LateralPlan::SolverState::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// LiveLocationKalman +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t LiveLocationKalman::_capnpPrivate::dataWordSize; +constexpr uint16_t LiveLocationKalman::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind LiveLocationKalman::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* LiveLocationKalman::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// LiveLocationKalman::Measurement +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t LiveLocationKalman::Measurement::_capnpPrivate::dataWordSize; +constexpr uint16_t LiveLocationKalman::Measurement::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind LiveLocationKalman::Measurement::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* LiveLocationKalman::Measurement::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// ProcLog +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t ProcLog::_capnpPrivate::dataWordSize; +constexpr uint16_t ProcLog::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind ProcLog::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ProcLog::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// ProcLog::Process +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t ProcLog::Process::_capnpPrivate::dataWordSize; +constexpr uint16_t ProcLog::Process::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind ProcLog::Process::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ProcLog::Process::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// ProcLog::CPUTimes +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t ProcLog::CPUTimes::_capnpPrivate::dataWordSize; +constexpr uint16_t ProcLog::CPUTimes::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind ProcLog::CPUTimes::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ProcLog::CPUTimes::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// ProcLog::Mem +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t ProcLog::Mem::_capnpPrivate::dataWordSize; +constexpr uint16_t ProcLog::Mem::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind ProcLog::Mem::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ProcLog::Mem::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// GnssMeasurements +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t GnssMeasurements::_capnpPrivate::dataWordSize; +constexpr uint16_t GnssMeasurements::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind GnssMeasurements::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* GnssMeasurements::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// GnssMeasurements::EphemerisStatus +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t GnssMeasurements::EphemerisStatus::_capnpPrivate::dataWordSize; +constexpr uint16_t GnssMeasurements::EphemerisStatus::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind GnssMeasurements::EphemerisStatus::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* GnssMeasurements::EphemerisStatus::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// GnssMeasurements::CorrectedMeasurement +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t GnssMeasurements::CorrectedMeasurement::_capnpPrivate::dataWordSize; +constexpr uint16_t GnssMeasurements::CorrectedMeasurement::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind GnssMeasurements::CorrectedMeasurement::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* GnssMeasurements::CorrectedMeasurement::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// GnssMeasurements::EphemerisSourceDEPRECATED +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t GnssMeasurements::EphemerisSourceDEPRECATED::_capnpPrivate::dataWordSize; +constexpr uint16_t GnssMeasurements::EphemerisSourceDEPRECATED::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind GnssMeasurements::EphemerisSourceDEPRECATED::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* GnssMeasurements::EphemerisSourceDEPRECATED::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// UbloxGnss +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t UbloxGnss::_capnpPrivate::dataWordSize; +constexpr uint16_t UbloxGnss::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind UbloxGnss::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* UbloxGnss::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// UbloxGnss::SatReport +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t UbloxGnss::SatReport::_capnpPrivate::dataWordSize; +constexpr uint16_t UbloxGnss::SatReport::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind UbloxGnss::SatReport::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* UbloxGnss::SatReport::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// UbloxGnss::SatReport::SatInfo +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t UbloxGnss::SatReport::SatInfo::_capnpPrivate::dataWordSize; +constexpr uint16_t UbloxGnss::SatReport::SatInfo::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind UbloxGnss::SatReport::SatInfo::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* UbloxGnss::SatReport::SatInfo::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// UbloxGnss::MeasurementReport +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t UbloxGnss::MeasurementReport::_capnpPrivate::dataWordSize; +constexpr uint16_t UbloxGnss::MeasurementReport::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind UbloxGnss::MeasurementReport::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* UbloxGnss::MeasurementReport::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// UbloxGnss::MeasurementReport::ReceiverStatus +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t UbloxGnss::MeasurementReport::ReceiverStatus::_capnpPrivate::dataWordSize; +constexpr uint16_t UbloxGnss::MeasurementReport::ReceiverStatus::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind UbloxGnss::MeasurementReport::ReceiverStatus::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* UbloxGnss::MeasurementReport::ReceiverStatus::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// UbloxGnss::MeasurementReport::Measurement +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t UbloxGnss::MeasurementReport::Measurement::_capnpPrivate::dataWordSize; +constexpr uint16_t UbloxGnss::MeasurementReport::Measurement::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind UbloxGnss::MeasurementReport::Measurement::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* UbloxGnss::MeasurementReport::Measurement::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// UbloxGnss::MeasurementReport::Measurement::TrackingStatus +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t UbloxGnss::MeasurementReport::Measurement::TrackingStatus::_capnpPrivate::dataWordSize; +constexpr uint16_t UbloxGnss::MeasurementReport::Measurement::TrackingStatus::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind UbloxGnss::MeasurementReport::Measurement::TrackingStatus::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* UbloxGnss::MeasurementReport::Measurement::TrackingStatus::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// UbloxGnss::Ephemeris +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t UbloxGnss::Ephemeris::_capnpPrivate::dataWordSize; +constexpr uint16_t UbloxGnss::Ephemeris::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind UbloxGnss::Ephemeris::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* UbloxGnss::Ephemeris::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// UbloxGnss::IonoData +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t UbloxGnss::IonoData::_capnpPrivate::dataWordSize; +constexpr uint16_t UbloxGnss::IonoData::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind UbloxGnss::IonoData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* UbloxGnss::IonoData::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// UbloxGnss::HwStatus +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t UbloxGnss::HwStatus::_capnpPrivate::dataWordSize; +constexpr uint16_t UbloxGnss::HwStatus::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind UbloxGnss::HwStatus::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* UbloxGnss::HwStatus::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// UbloxGnss::HwStatus2 +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t UbloxGnss::HwStatus2::_capnpPrivate::dataWordSize; +constexpr uint16_t UbloxGnss::HwStatus2::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind UbloxGnss::HwStatus2::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* UbloxGnss::HwStatus2::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// UbloxGnss::GlonassEphemeris +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t UbloxGnss::GlonassEphemeris::_capnpPrivate::dataWordSize; +constexpr uint16_t UbloxGnss::GlonassEphemeris::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind UbloxGnss::GlonassEphemeris::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* UbloxGnss::GlonassEphemeris::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// QcomGnss +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t QcomGnss::_capnpPrivate::dataWordSize; +constexpr uint16_t QcomGnss::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind QcomGnss::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* QcomGnss::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// QcomGnss::MeasurementStatus +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t QcomGnss::MeasurementStatus::_capnpPrivate::dataWordSize; +constexpr uint16_t QcomGnss::MeasurementStatus::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind QcomGnss::MeasurementStatus::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* QcomGnss::MeasurementStatus::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// QcomGnss::MeasurementReport +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t QcomGnss::MeasurementReport::_capnpPrivate::dataWordSize; +constexpr uint16_t QcomGnss::MeasurementReport::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind QcomGnss::MeasurementReport::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* QcomGnss::MeasurementReport::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// QcomGnss::MeasurementReport::SV +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t QcomGnss::MeasurementReport::SV::_capnpPrivate::dataWordSize; +constexpr uint16_t QcomGnss::MeasurementReport::SV::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind QcomGnss::MeasurementReport::SV::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* QcomGnss::MeasurementReport::SV::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// QcomGnss::ClockReport +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t QcomGnss::ClockReport::_capnpPrivate::dataWordSize; +constexpr uint16_t QcomGnss::ClockReport::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind QcomGnss::ClockReport::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* QcomGnss::ClockReport::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// QcomGnss::DrMeasurementReport +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t QcomGnss::DrMeasurementReport::_capnpPrivate::dataWordSize; +constexpr uint16_t QcomGnss::DrMeasurementReport::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind QcomGnss::DrMeasurementReport::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* QcomGnss::DrMeasurementReport::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// QcomGnss::DrMeasurementReport::SV +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t QcomGnss::DrMeasurementReport::SV::_capnpPrivate::dataWordSize; +constexpr uint16_t QcomGnss::DrMeasurementReport::SV::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind QcomGnss::DrMeasurementReport::SV::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* QcomGnss::DrMeasurementReport::SV::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// QcomGnss::DrSvPolyReport +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t QcomGnss::DrSvPolyReport::_capnpPrivate::dataWordSize; +constexpr uint16_t QcomGnss::DrSvPolyReport::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind QcomGnss::DrSvPolyReport::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* QcomGnss::DrSvPolyReport::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// Clocks +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t Clocks::_capnpPrivate::dataWordSize; +constexpr uint16_t Clocks::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind Clocks::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Clocks::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// LiveMpcData +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t LiveMpcData::_capnpPrivate::dataWordSize; +constexpr uint16_t LiveMpcData::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind LiveMpcData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* LiveMpcData::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// LiveLongitudinalMpcData +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t LiveLongitudinalMpcData::_capnpPrivate::dataWordSize; +constexpr uint16_t LiveLongitudinalMpcData::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind LiveLongitudinalMpcData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* LiveLongitudinalMpcData::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// Joystick +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t Joystick::_capnpPrivate::dataWordSize; +constexpr uint16_t Joystick::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind Joystick::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Joystick::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// DriverStateV2 +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t DriverStateV2::_capnpPrivate::dataWordSize; +constexpr uint16_t DriverStateV2::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind DriverStateV2::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* DriverStateV2::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// DriverStateV2::DriverData +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t DriverStateV2::DriverData::_capnpPrivate::dataWordSize; +constexpr uint16_t DriverStateV2::DriverData::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind DriverStateV2::DriverData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* DriverStateV2::DriverData::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// DriverStateDEPRECATED +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t DriverStateDEPRECATED::_capnpPrivate::dataWordSize; +constexpr uint16_t DriverStateDEPRECATED::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind DriverStateDEPRECATED::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* DriverStateDEPRECATED::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// DriverMonitoringState +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t DriverMonitoringState::_capnpPrivate::dataWordSize; +constexpr uint16_t DriverMonitoringState::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind DriverMonitoringState::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* DriverMonitoringState::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// Boot +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t Boot::_capnpPrivate::dataWordSize; +constexpr uint16_t Boot::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind Boot::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Boot::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// LiveParametersData +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t LiveParametersData::_capnpPrivate::dataWordSize; +constexpr uint16_t LiveParametersData::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind LiveParametersData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* LiveParametersData::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// LiveTorqueParametersData +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t LiveTorqueParametersData::_capnpPrivate::dataWordSize; +constexpr uint16_t LiveTorqueParametersData::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind LiveTorqueParametersData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* LiveTorqueParametersData::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// LiveMapDataDEPRECATED +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t LiveMapDataDEPRECATED::_capnpPrivate::dataWordSize; +constexpr uint16_t LiveMapDataDEPRECATED::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind LiveMapDataDEPRECATED::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* LiveMapDataDEPRECATED::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// CameraOdometry +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t CameraOdometry::_capnpPrivate::dataWordSize; +constexpr uint16_t CameraOdometry::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind CameraOdometry::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* CameraOdometry::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// Sentinel +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t Sentinel::_capnpPrivate::dataWordSize; +constexpr uint16_t Sentinel::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind Sentinel::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Sentinel::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// UIDebug +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t UIDebug::_capnpPrivate::dataWordSize; +constexpr uint16_t UIDebug::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind UIDebug::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* UIDebug::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// ManagerState +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t ManagerState::_capnpPrivate::dataWordSize; +constexpr uint16_t ManagerState::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind ManagerState::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ManagerState::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// ManagerState::ProcessState +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t ManagerState::ProcessState::_capnpPrivate::dataWordSize; +constexpr uint16_t ManagerState::ProcessState::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind ManagerState::ProcessState::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* ManagerState::ProcessState::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// UploaderState +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t UploaderState::_capnpPrivate::dataWordSize; +constexpr uint16_t UploaderState::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind UploaderState::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* UploaderState::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// NavInstruction +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t NavInstruction::_capnpPrivate::dataWordSize; +constexpr uint16_t NavInstruction::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind NavInstruction::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* NavInstruction::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// NavInstruction::Lane +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t NavInstruction::Lane::_capnpPrivate::dataWordSize; +constexpr uint16_t NavInstruction::Lane::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind NavInstruction::Lane::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* NavInstruction::Lane::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// NavInstruction::Maneuver +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t NavInstruction::Maneuver::_capnpPrivate::dataWordSize; +constexpr uint16_t NavInstruction::Maneuver::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind NavInstruction::Maneuver::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* NavInstruction::Maneuver::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// NavRoute +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t NavRoute::_capnpPrivate::dataWordSize; +constexpr uint16_t NavRoute::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind NavRoute::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* NavRoute::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// NavRoute::Coordinate +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t NavRoute::Coordinate::_capnpPrivate::dataWordSize; +constexpr uint16_t NavRoute::Coordinate::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind NavRoute::Coordinate::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* NavRoute::Coordinate::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// MapRenderState +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t MapRenderState::_capnpPrivate::dataWordSize; +constexpr uint16_t MapRenderState::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind MapRenderState::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* MapRenderState::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// NavModelData +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t NavModelData::_capnpPrivate::dataWordSize; +constexpr uint16_t NavModelData::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind NavModelData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* NavModelData::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// NavModelData::XYData +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t NavModelData::XYData::_capnpPrivate::dataWordSize; +constexpr uint16_t NavModelData::XYData::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind NavModelData::XYData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* NavModelData::XYData::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// EncodeData +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t EncodeData::_capnpPrivate::dataWordSize; +constexpr uint16_t EncodeData::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind EncodeData::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* EncodeData::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// UserFlag +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t UserFlag::_capnpPrivate::dataWordSize; +constexpr uint16_t UserFlag::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind UserFlag::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* UserFlag::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// Microphone +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t Microphone::_capnpPrivate::dataWordSize; +constexpr uint16_t Microphone::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind Microphone::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Microphone::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + +// Event +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr uint16_t Event::_capnpPrivate::dataWordSize; +constexpr uint16_t Event::_capnpPrivate::pointerCount; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#if !CAPNP_LITE +#if CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +constexpr ::capnp::Kind Event::_capnpPrivate::kind; +constexpr ::capnp::_::RawSchema const* Event::_capnpPrivate::schema; +#endif // !CAPNP_NEED_REDUNDANT_CONSTEXPR_DECL +#endif // !CAPNP_LITE + + +} // namespace + diff --git a/cereal/libcereal_shared.so b/cereal/libcereal_shared.so new file mode 100755 index 0000000..c2c8f6f Binary files /dev/null and b/cereal/libcereal_shared.so differ diff --git a/cereal/logger/logger.h b/cereal/logger/logger.h deleted file mode 100644 index 03336f8..0000000 --- a/cereal/logger/logger.h +++ /dev/null @@ -1,21 +0,0 @@ -#pragma once - -#ifdef SWAGLOG -// cppcheck-suppress preprocessorErrorDirective -#include SWAGLOG -#else - -#define CLOUDLOG_DEBUG 10 -#define CLOUDLOG_INFO 20 -#define CLOUDLOG_WARNING 30 -#define CLOUDLOG_ERROR 40 -#define CLOUDLOG_CRITICAL 50 - -#define cloudlog(lvl, fmt, ...) printf(fmt "\n", ## __VA_ARGS__) - -#define LOGD(fmt, ...) cloudlog(CLOUDLOG_DEBUG, fmt, ## __VA_ARGS__) -#define LOG(fmt, ...) cloudlog(CLOUDLOG_INFO, fmt, ## __VA_ARGS__) -#define LOGW(fmt, ...) cloudlog(CLOUDLOG_WARNING, fmt, ## __VA_ARGS__) -#define LOGE(fmt, ...) cloudlog(CLOUDLOG_ERROR, fmt, ## __VA_ARGS__) - -#endif diff --git a/cereal/messaging/bridge b/cereal/messaging/bridge new file mode 100755 index 0000000..710027a Binary files /dev/null and b/cereal/messaging/bridge differ diff --git a/cereal/messaging/bridge.cc b/cereal/messaging/bridge.cc deleted file mode 100644 index 4a5390c..0000000 --- a/cereal/messaging/bridge.cc +++ /dev/null @@ -1,92 +0,0 @@ -#include -#include -#include -#include -#include -#include - -typedef void (*sighandler_t)(int sig); - -#include "cereal/services.h" -#include "cereal/messaging/impl_msgq.h" -#include "cereal/messaging/impl_zmq.h" - -std::atomic do_exit = false; -static void set_do_exit(int sig) { - do_exit = true; -} - -void sigpipe_handler(int sig) { - assert(sig == SIGPIPE); - std::cout << "SIGPIPE received" << std::endl; -} - -static std::vector get_services(std::string whitelist_str, bool zmq_to_msgq) { - std::vector service_list; - for (const auto& it : services) { - std::string name = it.second.name; - bool in_whitelist = whitelist_str.find(name) != std::string::npos; - if (name == "plusFrame" || name == "uiLayoutState" || (zmq_to_msgq && !in_whitelist)) { - continue; - } - service_list.push_back(name); - } - return service_list; -} - -int main(int argc, char** argv) { - signal(SIGPIPE, (sighandler_t)sigpipe_handler); - signal(SIGINT, (sighandler_t)set_do_exit); - signal(SIGTERM, (sighandler_t)set_do_exit); - - bool zmq_to_msgq = argc > 2; - std::string ip = zmq_to_msgq ? argv[1] : "127.0.0.1"; - std::string whitelist_str = zmq_to_msgq ? std::string(argv[2]) : ""; - - Poller *poller; - Context *pub_context; - Context *sub_context; - if (zmq_to_msgq) { // republishes zmq debugging messages as msgq - poller = new ZMQPoller(); - pub_context = new MSGQContext(); - sub_context = new ZMQContext(); - } else { - poller = new MSGQPoller(); - pub_context = new ZMQContext(); - sub_context = new MSGQContext(); - } - - std::map sub2pub; - for (auto endpoint : get_services(whitelist_str, zmq_to_msgq)) { - PubSocket * pub_sock; - SubSocket * sub_sock; - if (zmq_to_msgq) { - pub_sock = new MSGQPubSocket(); - sub_sock = new ZMQSubSocket(); - } else { - pub_sock = new ZMQPubSocket(); - sub_sock = new MSGQSubSocket(); - } - pub_sock->connect(pub_context, endpoint); - sub_sock->connect(sub_context, endpoint, ip, false); - - poller->registerSocket(sub_sock); - sub2pub[sub_sock] = pub_sock; - } - - while (!do_exit) { - for (auto sub_sock : poller->poll(100)) { - Message * msg = sub_sock->receive(); - if (msg == NULL) continue; - int ret; - do { - ret = sub2pub[sub_sock]->sendMessage(msg); - } while (ret == -1 && errno == EINTR && !do_exit); - assert(ret >= 0 || do_exit); - delete msg; - - if (do_exit) break; - } - } - return 0; -} diff --git a/cereal/messaging/event.cc b/cereal/messaging/event.cc deleted file mode 100644 index a708de9..0000000 --- a/cereal/messaging/event.cc +++ /dev/null @@ -1,236 +0,0 @@ -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include -#include -#include - -#include "cereal/messaging/event.h" - -#ifndef __APPLE__ -#include - -void event_state_shm_mmap(std::string endpoint, std::string identifier, char **shm_mem, std::string *shm_path) { - const char* op_prefix = std::getenv("OPENPILOT_PREFIX"); - - std::string full_path = "/dev/shm/"; - if (op_prefix) { - full_path += std::string(op_prefix) + "/"; - } - full_path += CEREAL_EVENTS_PREFIX + "/"; - if (identifier.size() > 0) { - full_path += identifier + "/"; - } - std::filesystem::create_directories(full_path); - full_path += endpoint; - - int shm_fd = open(full_path.c_str(), O_RDWR | O_CREAT, 0664); - if (shm_fd < 0) { - throw std::runtime_error("Could not open shared memory file."); - } - - int rc = ftruncate(shm_fd, sizeof(EventState)); - if (rc < 0){ - close(shm_fd); - throw std::runtime_error("Could not truncate shared memory file."); - } - - char * mem = (char*)mmap(NULL, sizeof(EventState), PROT_READ | PROT_WRITE, MAP_SHARED, shm_fd, 0); - close(shm_fd); - if (mem == nullptr) { - throw std::runtime_error("Could not map shared memory file."); - } - - if (shm_mem != nullptr) - *shm_mem = mem; - if (shm_path != nullptr) - *shm_path = full_path; -} - -SocketEventHandle::SocketEventHandle(std::string endpoint, std::string identifier, bool override) { - char *mem; - event_state_shm_mmap(endpoint, identifier, &mem, &this->shm_path); - - this->state = (EventState*)mem; - if (override) { - this->state->fds[0] = eventfd(0, EFD_NONBLOCK); - this->state->fds[1] = eventfd(0, EFD_NONBLOCK); - } -} - -SocketEventHandle::~SocketEventHandle() { - close(this->state->fds[0]); - close(this->state->fds[1]); - munmap(this->state, sizeof(EventState)); - unlink(this->shm_path.c_str()); -} - -bool SocketEventHandle::is_enabled() { - return this->state->enabled; -} - -void SocketEventHandle::set_enabled(bool enabled) { - this->state->enabled = enabled; -} - -Event SocketEventHandle::recv_called() { - return Event(this->state->fds[0]); -} - -Event SocketEventHandle::recv_ready() { - return Event(this->state->fds[1]); -} - -void SocketEventHandle::toggle_fake_events(bool enabled) { - if (enabled) - setenv("CEREAL_FAKE", "1", true); - else - unsetenv("CEREAL_FAKE"); -} - -void SocketEventHandle::set_fake_prefix(std::string prefix) { - if (prefix.size() == 0) { - unsetenv("CEREAL_FAKE_PREFIX"); - } else { - setenv("CEREAL_FAKE_PREFIX", prefix.c_str(), true); - } -} - -std::string SocketEventHandle::fake_prefix() { - const char* prefix = std::getenv("CEREAL_FAKE_PREFIX"); - if (prefix == nullptr) { - return ""; - } else { - return std::string(prefix); - } -} - -Event::Event(int fd): event_fd(fd) {} - -void Event::set() const { - throw_if_invalid(); - - uint64_t val = 1; - size_t count = write(this->event_fd, &val, sizeof(uint64_t)); - assert(count == sizeof(uint64_t)); -} - -int Event::clear() const { - throw_if_invalid(); - - uint64_t val = 0; - // read the eventfd to clear it - read(this->event_fd, &val, sizeof(uint64_t)); - - return val; -} - -void Event::wait(int timeout_sec) const { - throw_if_invalid(); - - int event_count; - struct pollfd fds = { this->event_fd, POLLIN, 0 }; - struct timespec timeout = { timeout_sec, 0 };; - - sigset_t signals; - sigfillset(&signals); - sigdelset(&signals, SIGALRM); - sigdelset(&signals, SIGINT); - sigdelset(&signals, SIGTERM); - sigdelset(&signals, SIGQUIT); - - event_count = ppoll(&fds, 1, timeout_sec < 0 ? nullptr : &timeout, &signals); - - if (event_count == 0) { - throw std::runtime_error("Event timed out pid: " + std::to_string(getpid())); - } else if (event_count < 0) { - throw std::runtime_error("Event poll failed, errno: " + std::to_string(errno) + " pid: " + std::to_string(getpid())); - } -} - -bool Event::peek() const { - throw_if_invalid(); - - int event_count; - - struct pollfd fds = { this->event_fd, POLLIN, 0 }; - - // poll with timeout zero to return status immediately - event_count = poll(&fds, 1, 0); - - return event_count != 0; -} - -bool Event::is_valid() const { - return event_fd != -1; -} - -int Event::fd() const { - return event_fd; -} - -int Event::wait_for_one(const std::vector& events, int timeout_sec) { - struct pollfd fds[events.size()]; - for (size_t i = 0; i < events.size(); i++) { - fds[i] = { events[i].fd(), POLLIN, 0 }; - } - - struct timespec timeout = { timeout_sec, 0 }; - - sigset_t signals; - sigfillset(&signals); - sigdelset(&signals, SIGALRM); - sigdelset(&signals, SIGINT); - sigdelset(&signals, SIGTERM); - sigdelset(&signals, SIGQUIT); - - int event_count = ppoll(fds, events.size(), timeout_sec < 0 ? nullptr : &timeout, &signals); - - if (event_count == 0) { - throw std::runtime_error("Event timed out pid: " + std::to_string(getpid())); - } else if (event_count < 0) { - throw std::runtime_error("Event poll failed, errno: " + std::to_string(errno) + " pid: " + std::to_string(getpid())); - } - - for (size_t i = 0; i < events.size(); i++) { - if (fds[i].revents & POLLIN) { - return i; - } - } - - throw std::runtime_error("Event poll failed, no events ready"); -} -#else -// Stub implementation for Darwin, which does not support eventfd -void event_state_shm_mmap(std::string endpoint, std::string identifier, char **shm_mem, std::string *shm_path) {} - -SocketEventHandle::SocketEventHandle(std::string endpoint, std::string identifier, bool override) { - std::cerr << "SocketEventHandle not supported on macOS" << std::endl; - assert(false); -} -SocketEventHandle::~SocketEventHandle() {} -bool SocketEventHandle::is_enabled() { return this->state->enabled; } -void SocketEventHandle::set_enabled(bool enabled) {} -Event SocketEventHandle::recv_called() { return Event(); } -Event SocketEventHandle::recv_ready() { return Event(); } -void SocketEventHandle::toggle_fake_events(bool enabled) {} -void SocketEventHandle::set_fake_prefix(std::string prefix) {} -std::string SocketEventHandle::fake_prefix() { return ""; } - -Event::Event(int fd): event_fd(fd) {} -void Event::set() const {} -int Event::clear() const { return 0; } -void Event::wait(int timeout_sec) const {} -bool Event::peek() const { return false; } -bool Event::is_valid() const { return false; } -int Event::fd() const { return this->event_fd; } -int Event::wait_for_one(const std::vector& events, int timeout_sec) { return -1; } -#endif diff --git a/cereal/messaging/event.h b/cereal/messaging/event.h deleted file mode 100644 index c638b6b..0000000 --- a/cereal/messaging/event.h +++ /dev/null @@ -1,58 +0,0 @@ -#pragma once - -#include -#include - -#define CEREAL_EVENTS_PREFIX std::string("cereal_events") - -void event_state_shm_mmap(std::string endpoint, std::string identifier, char **shm_mem, std::string *shm_path); - -enum EventPurpose { - RECV_CALLED, - RECV_READY -}; - -struct EventState { - int fds[2]; - bool enabled; -}; - -class Event { -private: - int event_fd = -1; - - inline void throw_if_invalid() const { - if (!this->is_valid()) { - throw std::runtime_error("Event does not have valid file descriptor."); - } - } -public: - Event(int fd = -1); - - void set() const; - int clear() const; - void wait(int timeout_sec = -1) const; - bool peek() const; - bool is_valid() const; - int fd() const; - - static int wait_for_one(const std::vector& events, int timeout_sec = -1); -}; - -class SocketEventHandle { -private: - std::string shm_path; - EventState* state; -public: - SocketEventHandle(std::string endpoint, std::string identifier = "", bool override = true); - ~SocketEventHandle(); - - bool is_enabled(); - void set_enabled(bool enabled); - Event recv_called(); - Event recv_ready(); - - static void toggle_fake_events(bool enabled); - static void set_fake_prefix(std::string prefix); - static std::string fake_prefix(); -}; diff --git a/cereal/messaging/impl_fake.cc b/cereal/messaging/impl_fake.cc deleted file mode 100644 index 178b8b7..0000000 --- a/cereal/messaging/impl_fake.cc +++ /dev/null @@ -1,9 +0,0 @@ -#include "cereal/messaging/impl_fake.h" - -void FakePoller::registerSocket(SubSocket *socket) { - this->sockets.push_back(socket); -} - -std::vector FakePoller::poll(int timeout) { - return this->sockets; -} diff --git a/cereal/messaging/impl_fake.h b/cereal/messaging/impl_fake.h deleted file mode 100644 index 0ec8486..0000000 --- a/cereal/messaging/impl_fake.h +++ /dev/null @@ -1,67 +0,0 @@ -#pragma once - -#include -#include -#include -#include -#include - -#include -#include -#include -#include - -#include "cereal/messaging/messaging.h" -#include "cereal/messaging/event.h" - -template -class FakeSubSocket: public TSubSocket { -private: - Event *recv_called = nullptr; - Event *recv_ready = nullptr; - EventState *state = nullptr; - -public: - FakeSubSocket(): TSubSocket() {} - ~FakeSubSocket() { - delete recv_called; - delete recv_ready; - if (state != nullptr) { - munmap(state, sizeof(EventState)); - } - } - - int connect(Context *context, std::string endpoint, std::string address, bool conflate=false, bool check_endpoint=true) override { - const char* cereal_prefix = std::getenv("CEREAL_FAKE_PREFIX"); - - char* mem; - std::string identifier = cereal_prefix != nullptr ? std::string(cereal_prefix) : ""; - event_state_shm_mmap(endpoint, identifier, &mem, nullptr); - - this->state = (EventState*)mem; - this->recv_called = new Event(state->fds[EventPurpose::RECV_CALLED]); - this->recv_ready = new Event(state->fds[EventPurpose::RECV_READY]); - - return TSubSocket::connect(context, endpoint, address, conflate, check_endpoint); - } - - Message *receive(bool non_blocking=false) override { - if (this->state->enabled) { - this->recv_called->set(); - this->recv_ready->wait(); - this->recv_ready->clear(); - } - - return TSubSocket::receive(non_blocking); - } -}; - -class FakePoller: public Poller { -private: - std::vector sockets; - -public: - void registerSocket(SubSocket *socket) override; - std::vector poll(int timeout) override; - ~FakePoller() {} -}; diff --git a/cereal/messaging/impl_msgq.cc b/cereal/messaging/impl_msgq.cc deleted file mode 100644 index 8f2c10a..0000000 --- a/cereal/messaging/impl_msgq.cc +++ /dev/null @@ -1,215 +0,0 @@ -#include -#include -#include -#include -#include -#include - -#include "cereal/services.h" -#include "cereal/messaging/impl_msgq.h" - - -volatile sig_atomic_t msgq_do_exit = 0; - -void sig_handler(int signal) { - assert(signal == SIGINT || signal == SIGTERM); - msgq_do_exit = 1; -} - -static bool service_exists(std::string path){ - return services.count(path) > 0; -} - - -MSGQContext::MSGQContext() { -} - -MSGQContext::~MSGQContext() { -} - -void MSGQMessage::init(size_t sz) { - size = sz; - data = new char[size]; -} - -void MSGQMessage::init(char * d, size_t sz) { - size = sz; - data = new char[size]; - memcpy(data, d, size); -} - -void MSGQMessage::takeOwnership(char * d, size_t sz) { - size = sz; - data = d; -} - -void MSGQMessage::close() { - if (size > 0){ - delete[] data; - } - size = 0; -} - -MSGQMessage::~MSGQMessage() { - this->close(); -} - -int MSGQSubSocket::connect(Context *context, std::string endpoint, std::string address, bool conflate, bool check_endpoint){ - assert(context); - assert(address == "127.0.0.1"); - - if (check_endpoint && !service_exists(std::string(endpoint))){ - std::cout << "Warning, " << std::string(endpoint) << " is not in service list." << std::endl; - } - - q = new msgq_queue_t; - int r = msgq_new_queue(q, endpoint.c_str(), DEFAULT_SEGMENT_SIZE); - if (r != 0){ - return r; - } - - msgq_init_subscriber(q); - - if (conflate){ - q->read_conflate = true; - } - - timeout = -1; - - return 0; -} - - -Message * MSGQSubSocket::receive(bool non_blocking){ - msgq_do_exit = 0; - - void (*prev_handler_sigint)(int); - void (*prev_handler_sigterm)(int); - if (!non_blocking){ - prev_handler_sigint = std::signal(SIGINT, sig_handler); - prev_handler_sigterm = std::signal(SIGTERM, sig_handler); - } - - msgq_msg_t msg; - - MSGQMessage *r = NULL; - - int rc = msgq_msg_recv(&msg, q); - - // Hack to implement blocking read with a poller. Don't use this - while (!non_blocking && rc == 0 && msgq_do_exit == 0){ - msgq_pollitem_t items[1]; - items[0].q = q; - - int t = (timeout != -1) ? timeout : 100; - - int n = msgq_poll(items, 1, t); - rc = msgq_msg_recv(&msg, q); - - // The poll indicated a message was ready, but the receive failed. Try again - if (n == 1 && rc == 0){ - continue; - } - - if (timeout != -1){ - break; - } - } - - - if (!non_blocking){ - std::signal(SIGINT, prev_handler_sigint); - std::signal(SIGTERM, prev_handler_sigterm); - } - - errno = msgq_do_exit ? EINTR : 0; - - if (rc > 0){ - if (msgq_do_exit){ - msgq_msg_close(&msg); // Free unused message on exit - } else { - r = new MSGQMessage; - r->takeOwnership(msg.data, msg.size); - } - } - - return (Message*)r; -} - -void MSGQSubSocket::setTimeout(int t){ - timeout = t; -} - -MSGQSubSocket::~MSGQSubSocket(){ - if (q != NULL){ - msgq_close_queue(q); - delete q; - } -} - -int MSGQPubSocket::connect(Context *context, std::string endpoint, bool check_endpoint){ - assert(context); - - if (check_endpoint && !service_exists(std::string(endpoint))){ - std::cout << "Warning, " << std::string(endpoint) << " is not in service list." << std::endl; - } - - q = new msgq_queue_t; - int r = msgq_new_queue(q, endpoint.c_str(), DEFAULT_SEGMENT_SIZE); - if (r != 0){ - return r; - } - - msgq_init_publisher(q); - - return 0; -} - -int MSGQPubSocket::sendMessage(Message *message){ - msgq_msg_t msg; - msg.data = message->getData(); - msg.size = message->getSize(); - - return msgq_msg_send(&msg, q); -} - -int MSGQPubSocket::send(char *data, size_t size){ - msgq_msg_t msg; - msg.data = data; - msg.size = size; - - return msgq_msg_send(&msg, q); -} - -bool MSGQPubSocket::all_readers_updated() { - return msgq_all_readers_updated(q); -} - -MSGQPubSocket::~MSGQPubSocket(){ - if (q != NULL){ - msgq_close_queue(q); - delete q; - } -} - - -void MSGQPoller::registerSocket(SubSocket * socket){ - assert(num_polls + 1 < MAX_POLLERS); - polls[num_polls].q = (msgq_queue_t*)socket->getRawSocket(); - - sockets.push_back(socket); - num_polls++; -} - -std::vector MSGQPoller::poll(int timeout){ - std::vector r; - - msgq_poll(polls, num_polls, timeout); - for (size_t i = 0; i < num_polls; i++){ - if (polls[i].revents){ - r.push_back(sockets[i]); - } - } - - return r; -} diff --git a/cereal/messaging/impl_msgq.h b/cereal/messaging/impl_msgq.h deleted file mode 100644 index 68235f0..0000000 --- a/cereal/messaging/impl_msgq.h +++ /dev/null @@ -1,67 +0,0 @@ -#pragma once - -#include -#include - -#include "cereal/messaging/messaging.h" -#include "cereal/messaging/msgq.h" - -#define MAX_POLLERS 128 - -class MSGQContext : public Context { -private: - void * context = NULL; -public: - MSGQContext(); - void * getRawContext() {return context;} - ~MSGQContext(); -}; - -class MSGQMessage : public Message { -private: - char * data; - size_t size; -public: - void init(size_t size); - void init(char *data, size_t size); - void takeOwnership(char *data, size_t size); - size_t getSize(){return size;} - char * getData(){return data;} - void close(); - ~MSGQMessage(); -}; - -class MSGQSubSocket : public SubSocket { -private: - msgq_queue_t * q = NULL; - int timeout; -public: - int connect(Context *context, std::string endpoint, std::string address, bool conflate=false, bool check_endpoint=true); - void setTimeout(int timeout); - void * getRawSocket() {return (void*)q;} - Message *receive(bool non_blocking=false); - ~MSGQSubSocket(); -}; - -class MSGQPubSocket : public PubSocket { -private: - msgq_queue_t * q = NULL; -public: - int connect(Context *context, std::string endpoint, bool check_endpoint=true); - int sendMessage(Message *message); - int send(char *data, size_t size); - bool all_readers_updated(); - ~MSGQPubSocket(); -}; - -class MSGQPoller : public Poller { -private: - std::vector sockets; - msgq_pollitem_t polls[MAX_POLLERS]; - size_t num_polls = 0; - -public: - void registerSocket(SubSocket *socket); - std::vector poll(int timeout); - ~MSGQPoller(){} -}; diff --git a/cereal/messaging/impl_zmq.cc b/cereal/messaging/impl_zmq.cc deleted file mode 100644 index 7da9df1..0000000 --- a/cereal/messaging/impl_zmq.cc +++ /dev/null @@ -1,162 +0,0 @@ -#include -#include -#include -#include -#include -#include - -#include "cereal/services.h" -#include "cereal/messaging/impl_zmq.h" - -static int get_port(std::string endpoint) { - return services.at(endpoint).port; -} - -ZMQContext::ZMQContext() { - context = zmq_ctx_new(); -} - -ZMQContext::~ZMQContext() { - zmq_ctx_term(context); -} - -void ZMQMessage::init(size_t sz) { - size = sz; - data = new char[size]; -} - -void ZMQMessage::init(char * d, size_t sz) { - size = sz; - data = new char[size]; - memcpy(data, d, size); -} - -void ZMQMessage::close() { - if (size > 0){ - delete[] data; - } - size = 0; -} - -ZMQMessage::~ZMQMessage() { - this->close(); -} - - -int ZMQSubSocket::connect(Context *context, std::string endpoint, std::string address, bool conflate, bool check_endpoint){ - sock = zmq_socket(context->getRawContext(), ZMQ_SUB); - if (sock == NULL){ - return -1; - } - - zmq_setsockopt(sock, ZMQ_SUBSCRIBE, "", 0); - - if (conflate){ - int arg = 1; - zmq_setsockopt(sock, ZMQ_CONFLATE, &arg, sizeof(int)); - } - - int reconnect_ivl = 500; - zmq_setsockopt(sock, ZMQ_RECONNECT_IVL_MAX, &reconnect_ivl, sizeof(reconnect_ivl)); - - full_endpoint = "tcp://" + address + ":"; - if (check_endpoint){ - full_endpoint += std::to_string(get_port(endpoint)); - } else { - full_endpoint += endpoint; - } - - return zmq_connect(sock, full_endpoint.c_str()); -} - - -Message * ZMQSubSocket::receive(bool non_blocking){ - zmq_msg_t msg; - assert(zmq_msg_init(&msg) == 0); - - int flags = non_blocking ? ZMQ_DONTWAIT : 0; - int rc = zmq_msg_recv(&msg, sock, flags); - Message *r = NULL; - - if (rc >= 0){ - // Make a copy to ensure the data is aligned - r = new ZMQMessage; - r->init((char*)zmq_msg_data(&msg), zmq_msg_size(&msg)); - } - - zmq_msg_close(&msg); - return r; -} - -void ZMQSubSocket::setTimeout(int timeout){ - zmq_setsockopt(sock, ZMQ_RCVTIMEO, &timeout, sizeof(int)); -} - -ZMQSubSocket::~ZMQSubSocket(){ - zmq_close(sock); -} - -int ZMQPubSocket::connect(Context *context, std::string endpoint, bool check_endpoint){ - sock = zmq_socket(context->getRawContext(), ZMQ_PUB); - if (sock == NULL){ - return -1; - } - - full_endpoint = "tcp://*:"; - if (check_endpoint){ - full_endpoint += std::to_string(get_port(endpoint)); - } else { - full_endpoint += endpoint; - } - - // ZMQ pub sockets cannot be shared between processes, so we need to ensure pid stays the same - pid = getpid(); - - return zmq_bind(sock, full_endpoint.c_str()); -} - -int ZMQPubSocket::sendMessage(Message *message) { - assert(pid == getpid()); - return zmq_send(sock, message->getData(), message->getSize(), ZMQ_DONTWAIT); -} - -int ZMQPubSocket::send(char *data, size_t size) { - assert(pid == getpid()); - return zmq_send(sock, data, size, ZMQ_DONTWAIT); -} - -bool ZMQPubSocket::all_readers_updated() { - assert(false); // TODO not implemented - return false; -} - -ZMQPubSocket::~ZMQPubSocket(){ - zmq_close(sock); -} - - -void ZMQPoller::registerSocket(SubSocket * socket){ - assert(num_polls + 1 < MAX_POLLERS); - polls[num_polls].socket = socket->getRawSocket(); - polls[num_polls].events = ZMQ_POLLIN; - - sockets.push_back(socket); - num_polls++; -} - -std::vector ZMQPoller::poll(int timeout){ - std::vector r; - - int rc = zmq_poll(polls, num_polls, timeout); - if (rc < 0){ - return r; - } - - for (size_t i = 0; i < num_polls; i++){ - if (polls[i].revents){ - r.push_back(sockets[i]); - } - } - - return r; -} diff --git a/cereal/messaging/impl_zmq.h b/cereal/messaging/impl_zmq.h deleted file mode 100644 index 903875f..0000000 --- a/cereal/messaging/impl_zmq.h +++ /dev/null @@ -1,68 +0,0 @@ -#pragma once - -#include -#include -#include - -#include "cereal/messaging/messaging.h" - -#define MAX_POLLERS 128 - -class ZMQContext : public Context { -private: - void * context = NULL; -public: - ZMQContext(); - void * getRawContext() {return context;} - ~ZMQContext(); -}; - -class ZMQMessage : public Message { -private: - char * data; - size_t size; -public: - void init(size_t size); - void init(char *data, size_t size); - size_t getSize(){return size;} - char * getData(){return data;} - void close(); - ~ZMQMessage(); -}; - -class ZMQSubSocket : public SubSocket { -private: - void * sock; - std::string full_endpoint; -public: - int connect(Context *context, std::string endpoint, std::string address, bool conflate=false, bool check_endpoint=true); - void setTimeout(int timeout); - void * getRawSocket() {return sock;} - Message *receive(bool non_blocking=false); - ~ZMQSubSocket(); -}; - -class ZMQPubSocket : public PubSocket { -private: - void * sock; - std::string full_endpoint; - int pid = -1; -public: - int connect(Context *context, std::string endpoint, bool check_endpoint=true); - int sendMessage(Message *message); - int send(char *data, size_t size); - bool all_readers_updated(); - ~ZMQPubSocket(); -}; - -class ZMQPoller : public Poller { -private: - std::vector sockets; - zmq_pollitem_t polls[MAX_POLLERS]; - size_t num_polls = 0; - -public: - void registerSocket(SubSocket *socket); - std::vector poll(int timeout); - ~ZMQPoller(){} -}; diff --git a/cereal/messaging/messaging.cc b/cereal/messaging/messaging.cc deleted file mode 100644 index 6b7fe8f..0000000 --- a/cereal/messaging/messaging.cc +++ /dev/null @@ -1,120 +0,0 @@ -#include -#include - -#include "cereal/messaging/messaging.h" -#include "cereal/messaging/impl_zmq.h" -#include "cereal/messaging/impl_msgq.h" -#include "cereal/messaging/impl_fake.h" - -#ifdef __APPLE__ -const bool MUST_USE_ZMQ = true; -#else -const bool MUST_USE_ZMQ = false; -#endif - -bool messaging_use_zmq(){ - if (std::getenv("ZMQ") || MUST_USE_ZMQ) { - if (std::getenv("OPENPILOT_PREFIX")) { - std::cerr << "OPENPILOT_PREFIX not supported with ZMQ backend\n"; - assert(false); - } - return true; - } - return false; -} - -bool messaging_use_fake(){ - char* fake_enabled = std::getenv("CEREAL_FAKE"); - return fake_enabled != NULL; -} - -Context * Context::create(){ - Context * c; - if (messaging_use_zmq()){ - c = new ZMQContext(); - } else { - c = new MSGQContext(); - } - return c; -} - -SubSocket * SubSocket::create(){ - SubSocket * s; - if (messaging_use_fake()) { - if (messaging_use_zmq()) { - s = new FakeSubSocket(); - } else { - s = new FakeSubSocket(); - } - } else { - if (messaging_use_zmq()){ - s = new ZMQSubSocket(); - } else { - s = new MSGQSubSocket(); - } - } - - return s; -} - -SubSocket * SubSocket::create(Context * context, std::string endpoint, std::string address, bool conflate, bool check_endpoint){ - SubSocket *s = SubSocket::create(); - int r = s->connect(context, endpoint, address, conflate, check_endpoint); - - if (r == 0) { - return s; - } else { - std::cerr << "Error, failed to connect SubSocket to " << endpoint << ": " << strerror(errno) << std::endl; - - delete s; - return nullptr; - } -} - -PubSocket * PubSocket::create(){ - PubSocket * s; - if (messaging_use_zmq()){ - s = new ZMQPubSocket(); - } else { - s = new MSGQPubSocket(); - } - - return s; -} - -PubSocket * PubSocket::create(Context * context, std::string endpoint, bool check_endpoint){ - PubSocket *s = PubSocket::create(); - int r = s->connect(context, endpoint, check_endpoint); - - if (r == 0) { - return s; - } else { - std::cerr << "Error, failed to bind PubSocket to " << endpoint << ": " << strerror(errno) << std::endl; - - delete s; - return nullptr; - } -} - -Poller * Poller::create(){ - Poller * p; - if (messaging_use_fake()) { - p = new FakePoller(); - } else { - if (messaging_use_zmq()){ - p = new ZMQPoller(); - } else { - p = new MSGQPoller(); - } - } - return p; -} - -Poller * Poller::create(std::vector sockets){ - Poller * p = Poller::create(); - - for (auto s : sockets){ - p->registerSocket(s); - } - return p; -} diff --git a/cereal/messaging/messaging.h b/cereal/messaging/messaging.h deleted file mode 100644 index 9110651..0000000 --- a/cereal/messaging/messaging.h +++ /dev/null @@ -1,162 +0,0 @@ -#pragma once - -#include -#include -#include -#include -#include -#include - -#include - -#include "cereal/gen/cpp/log.capnp.h" - -#ifdef __APPLE__ -#define CLOCK_BOOTTIME CLOCK_MONOTONIC -#endif - -#define MSG_MULTIPLE_PUBLISHERS 100 - -bool messaging_use_zmq(); - -class Context { -public: - virtual void * getRawContext() = 0; - static Context * create(); - virtual ~Context(){} -}; - -class Message { -public: - virtual void init(size_t size) = 0; - virtual void init(char * data, size_t size) = 0; - virtual void close() = 0; - virtual size_t getSize() = 0; - virtual char * getData() = 0; - virtual ~Message(){} -}; - - -class SubSocket { -public: - virtual int connect(Context *context, std::string endpoint, std::string address, bool conflate=false, bool check_endpoint=true) = 0; - virtual void setTimeout(int timeout) = 0; - virtual Message *receive(bool non_blocking=false) = 0; - virtual void * getRawSocket() = 0; - static SubSocket * create(); - static SubSocket * create(Context * context, std::string endpoint, std::string address="127.0.0.1", bool conflate=false, bool check_endpoint=true); - virtual ~SubSocket(){} -}; - -class PubSocket { -public: - virtual int connect(Context *context, std::string endpoint, bool check_endpoint=true) = 0; - virtual int sendMessage(Message *message) = 0; - virtual int send(char *data, size_t size) = 0; - virtual bool all_readers_updated() = 0; - static PubSocket * create(); - static PubSocket * create(Context * context, std::string endpoint, bool check_endpoint=true); - static PubSocket * create(Context * context, std::string endpoint, int port, bool check_endpoint=true); - virtual ~PubSocket(){} -}; - -class Poller { -public: - virtual void registerSocket(SubSocket *socket) = 0; - virtual std::vector poll(int timeout) = 0; - static Poller * create(); - static Poller * create(std::vector sockets); - virtual ~Poller(){} -}; - -class SubMaster { -public: - SubMaster(const std::vector &service_list, const std::vector &poll = {}, - const char *address = nullptr, const std::vector &ignore_alive = {}); - void update(int timeout = 1000); - void update_msgs(uint64_t current_time, const std::vector> &messages); - inline bool allAlive(const std::vector &service_list = {}) { return all_(service_list, false, true); } - inline bool allValid(const std::vector &service_list = {}) { return all_(service_list, true, false); } - inline bool allAliveAndValid(const std::vector &service_list = {}) { return all_(service_list, true, true); } - void drain(); - ~SubMaster(); - - uint64_t frame = 0; - bool updated(const char *name) const; - bool alive(const char *name) const; - bool valid(const char *name) const; - uint64_t rcv_frame(const char *name) const; - uint64_t rcv_time(const char *name) const; - cereal::Event::Reader &operator[](const char *name) const; - -private: - bool all_(const std::vector &service_list, bool valid, bool alive); - Poller *poller_ = nullptr; - struct SubMessage; - std::map messages_; - std::map services_; -}; - -class MessageBuilder : public capnp::MallocMessageBuilder { -public: - MessageBuilder() = default; - - cereal::Event::Builder initEvent(bool valid = true) { - cereal::Event::Builder event = initRoot(); - struct timespec t; - clock_gettime(CLOCK_BOOTTIME, &t); - uint64_t current_time = t.tv_sec * 1000000000ULL + t.tv_nsec; - event.setLogMonoTime(current_time); - event.setValid(valid); - return event; - } - - kj::ArrayPtr toBytes() { - heapArray_ = capnp::messageToFlatArray(*this); - return heapArray_.asBytes(); - } - - size_t getSerializedSize() { - return capnp::computeSerializedSizeInWords(*this) * sizeof(capnp::word); - } - - int serializeToBuffer(unsigned char *buffer, size_t buffer_size) { - size_t serialized_size = getSerializedSize(); - if (serialized_size > buffer_size) { return -1; } - kj::ArrayOutputStream out(kj::ArrayPtr(buffer, buffer_size)); - capnp::writeMessage(out, *this); - return serialized_size; - } - -private: - kj::Array heapArray_; -}; - -class PubMaster { -public: - PubMaster(const std::vector &service_list); - inline int send(const char *name, capnp::byte *data, size_t size) { return sockets_.at(name)->send((char *)data, size); } - int send(const char *name, MessageBuilder &msg); - ~PubMaster(); - -private: - std::map sockets_; -}; - -class AlignedBuffer { -public: - kj::ArrayPtr align(const char *data, const size_t size) { - words_size = size / sizeof(capnp::word) + 1; - if (aligned_buf.size() < words_size) { - aligned_buf = kj::heapArray(words_size < 512 ? 512 : words_size); - } - memcpy(aligned_buf.begin(), data, size); - return aligned_buf.slice(0, words_size); - } - inline kj::ArrayPtr align(Message *m) { - return align(m->getData(), m->getSize()); - } -private: - kj::Array aligned_buf; - size_t words_size; -}; diff --git a/cereal/messaging/messaging_pyx.cpp b/cereal/messaging/messaging_pyx.cpp new file mode 100644 index 0000000..637669d --- /dev/null +++ b/cereal/messaging/messaging_pyx.cpp @@ -0,0 +1,17670 @@ +/* Generated by Cython 3.0.8 */ + +/* BEGIN: Cython Metadata +{ + "distutils": { + "depends": [ + "cereal/messaging/impl_fake.h", + "cereal/messaging/messaging.h" + ], + "language": "c++", + "name": "cereal.messaging.messaging_pyx", + "sources": [ + "/data/openpilot/cereal/messaging/messaging_pyx.pyx" + ] + }, + "module_name": "cereal.messaging.messaging_pyx" +} +END: Cython Metadata */ + +#ifndef PY_SSIZE_T_CLEAN +#define PY_SSIZE_T_CLEAN +#endif /* PY_SSIZE_T_CLEAN */ +#if defined(CYTHON_LIMITED_API) && 0 + #ifndef Py_LIMITED_API + #if CYTHON_LIMITED_API+0 > 0x03030000 + #define Py_LIMITED_API CYTHON_LIMITED_API + #else + #define Py_LIMITED_API 0x03030000 + #endif + #endif +#endif + +#include "Python.h" +#ifndef Py_PYTHON_H + #error Python headers needed to compile C extensions, please install development version of Python. +#elif PY_VERSION_HEX < 0x02070000 || (0x03000000 <= PY_VERSION_HEX && PY_VERSION_HEX < 0x03030000) + #error Cython requires Python 2.7+ or Python 3.3+. +#else +#if defined(CYTHON_LIMITED_API) && CYTHON_LIMITED_API +#define __PYX_EXTRA_ABI_MODULE_NAME "limited" +#else +#define __PYX_EXTRA_ABI_MODULE_NAME "" +#endif +#define CYTHON_ABI "3_0_8" __PYX_EXTRA_ABI_MODULE_NAME +#define __PYX_ABI_MODULE_NAME "_cython_" CYTHON_ABI +#define __PYX_TYPE_MODULE_PREFIX __PYX_ABI_MODULE_NAME "." +#define CYTHON_HEX_VERSION 0x030008F0 +#define CYTHON_FUTURE_DIVISION 1 +#include +#ifndef offsetof + #define offsetof(type, member) ( (size_t) & ((type*)0) -> member ) +#endif +#if !defined(_WIN32) && !defined(WIN32) && !defined(MS_WINDOWS) + #ifndef __stdcall + #define __stdcall + #endif + #ifndef __cdecl + #define __cdecl + #endif + #ifndef __fastcall + #define __fastcall + #endif +#endif +#ifndef DL_IMPORT + #define DL_IMPORT(t) t +#endif +#ifndef DL_EXPORT + #define DL_EXPORT(t) t +#endif +#define __PYX_COMMA , +#ifndef HAVE_LONG_LONG + #define HAVE_LONG_LONG +#endif +#ifndef PY_LONG_LONG + #define PY_LONG_LONG LONG_LONG +#endif +#ifndef Py_HUGE_VAL + #define Py_HUGE_VAL HUGE_VAL +#endif +#define __PYX_LIMITED_VERSION_HEX PY_VERSION_HEX +#if defined(GRAALVM_PYTHON) + /* For very preliminary testing purposes. Most variables are set the same as PyPy. + The existence of this section does not imply that anything works or is even tested */ + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 1 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(PYPY_VERSION) + #define CYTHON_COMPILING_IN_PYPY 1 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #ifndef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #endif + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #if PY_VERSION_HEX < 0x03090000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE (PY_VERSION_HEX >= 0x030400a1 && PYPY_VERSION_NUM >= 0x07030C00) + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(CYTHON_LIMITED_API) + #ifdef Py_LIMITED_API + #undef __PYX_LIMITED_VERSION_HEX + #define __PYX_LIMITED_VERSION_HEX Py_LIMITED_API + #endif + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 1 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_CLINE_IN_TRACEBACK + #define CYTHON_CLINE_IN_TRACEBACK 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 1 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #endif + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 1 + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(Py_GIL_DISABLED) || defined(Py_NOGIL) + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 1 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #ifndef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 +#else + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 1 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #ifndef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #endif + #ifndef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 1 + #endif + #if PY_MAJOR_VERSION < 3 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #ifndef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 1 + #endif + #ifndef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 1 + #endif + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #if PY_VERSION_HEX < 0x030300F0 || PY_VERSION_HEX >= 0x030B00A2 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #elif !defined(CYTHON_USE_UNICODE_WRITER) + #define CYTHON_USE_UNICODE_WRITER 1 + #endif + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #ifndef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 1 + #endif + #ifndef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL (PY_MAJOR_VERSION < 3 || PY_VERSION_HEX >= 0x03060000 && PY_VERSION_HEX < 0x030C00A6) + #endif + #ifndef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL (PY_VERSION_HEX >= 0x030700A1) + #endif + #ifndef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 1 + #endif + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #endif + #if PY_VERSION_HEX < 0x030400a1 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #elif !defined(CYTHON_USE_TP_FINALIZE) + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #if PY_VERSION_HEX < 0x030600B1 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #elif !defined(CYTHON_USE_DICT_VERSIONS) + #define CYTHON_USE_DICT_VERSIONS (PY_VERSION_HEX < 0x030C00A5) + #endif + #if PY_VERSION_HEX < 0x030700A3 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #elif !defined(CYTHON_USE_EXC_INFO_STACK) + #define CYTHON_USE_EXC_INFO_STACK 1 + #endif + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 1 + #endif +#endif +#if !defined(CYTHON_FAST_PYCCALL) +#define CYTHON_FAST_PYCCALL (CYTHON_FAST_PYCALL && PY_VERSION_HEX >= 0x030600B1) +#endif +#if !defined(CYTHON_VECTORCALL) +#define CYTHON_VECTORCALL (CYTHON_FAST_PYCCALL && PY_VERSION_HEX >= 0x030800B1) +#endif +#define CYTHON_BACKPORT_VECTORCALL (CYTHON_METH_FASTCALL && PY_VERSION_HEX < 0x030800B1) +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_MAJOR_VERSION < 3 + #include "longintrepr.h" + #endif + #undef SHIFT + #undef BASE + #undef MASK + #ifdef SIZEOF_VOID_P + enum { __pyx_check_sizeof_voidp = 1 / (int)(SIZEOF_VOID_P == sizeof(void*)) }; + #endif +#endif +#ifndef __has_attribute + #define __has_attribute(x) 0 +#endif +#ifndef __has_cpp_attribute + #define __has_cpp_attribute(x) 0 +#endif +#ifndef CYTHON_RESTRICT + #if defined(__GNUC__) + #define CYTHON_RESTRICT __restrict__ + #elif defined(_MSC_VER) && _MSC_VER >= 1400 + #define CYTHON_RESTRICT __restrict + #elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define CYTHON_RESTRICT restrict + #else + #define CYTHON_RESTRICT + #endif +#endif +#ifndef CYTHON_UNUSED + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(maybe_unused) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(maybe_unused) + #define CYTHON_UNUSED [[maybe_unused]] + #endif + #endif + #endif +#endif +#ifndef CYTHON_UNUSED +# if defined(__GNUC__) +# if !(defined(__cplusplus)) || (__GNUC__ > 3 || (__GNUC__ == 3 && __GNUC_MINOR__ >= 4)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +# elif defined(__ICC) || (defined(__INTEL_COMPILER) && !defined(_MSC_VER)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +#endif +#ifndef CYTHON_UNUSED_VAR +# if defined(__cplusplus) + template void CYTHON_UNUSED_VAR( const T& ) { } +# else +# define CYTHON_UNUSED_VAR(x) (void)(x) +# endif +#endif +#ifndef CYTHON_MAYBE_UNUSED_VAR + #define CYTHON_MAYBE_UNUSED_VAR(x) CYTHON_UNUSED_VAR(x) +#endif +#ifndef CYTHON_NCP_UNUSED +# if CYTHON_COMPILING_IN_CPYTHON +# define CYTHON_NCP_UNUSED +# else +# define CYTHON_NCP_UNUSED CYTHON_UNUSED +# endif +#endif +#ifndef CYTHON_USE_CPP_STD_MOVE + #if defined(__cplusplus) && (\ + __cplusplus >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1600)) + #define CYTHON_USE_CPP_STD_MOVE 1 + #else + #define CYTHON_USE_CPP_STD_MOVE 0 + #endif +#endif +#define __Pyx_void_to_None(void_result) ((void)(void_result), Py_INCREF(Py_None), Py_None) +#ifdef _MSC_VER + #ifndef _MSC_STDINT_H_ + #if _MSC_VER < 1300 + typedef unsigned char uint8_t; + typedef unsigned short uint16_t; + typedef unsigned int uint32_t; + #else + typedef unsigned __int8 uint8_t; + typedef unsigned __int16 uint16_t; + typedef unsigned __int32 uint32_t; + #endif + #endif + #if _MSC_VER < 1300 + #ifdef _WIN64 + typedef unsigned long long __pyx_uintptr_t; + #else + typedef unsigned int __pyx_uintptr_t; + #endif + #else + #ifdef _WIN64 + typedef unsigned __int64 __pyx_uintptr_t; + #else + typedef unsigned __int32 __pyx_uintptr_t; + #endif + #endif +#else + #include + typedef uintptr_t __pyx_uintptr_t; +#endif +#ifndef CYTHON_FALLTHROUGH + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(fallthrough) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(fallthrough) + #define CYTHON_FALLTHROUGH [[fallthrough]] + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_cpp_attribute(clang::fallthrough) + #define CYTHON_FALLTHROUGH [[clang::fallthrough]] + #elif __has_cpp_attribute(gnu::fallthrough) + #define CYTHON_FALLTHROUGH [[gnu::fallthrough]] + #endif + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_attribute(fallthrough) + #define CYTHON_FALLTHROUGH __attribute__((fallthrough)) + #else + #define CYTHON_FALLTHROUGH + #endif + #endif + #if defined(__clang__) && defined(__apple_build_version__) + #if __apple_build_version__ < 7000000 + #undef CYTHON_FALLTHROUGH + #define CYTHON_FALLTHROUGH + #endif + #endif +#endif +#ifdef __cplusplus + template + struct __PYX_IS_UNSIGNED_IMPL {static const bool value = T(0) < T(-1);}; + #define __PYX_IS_UNSIGNED(type) (__PYX_IS_UNSIGNED_IMPL::value) +#else + #define __PYX_IS_UNSIGNED(type) (((type)-1) > 0) +#endif +#if CYTHON_COMPILING_IN_PYPY == 1 + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x030A0000) +#else + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x03090000) +#endif +#define __PYX_REINTERPRET_FUNCION(func_pointer, other_pointer) ((func_pointer)(void(*)(void))(other_pointer)) + +#ifndef __cplusplus + #error "Cython files generated with the C++ option must be compiled with a C++ compiler." +#endif +#ifndef CYTHON_INLINE + #if defined(__clang__) + #define CYTHON_INLINE __inline__ __attribute__ ((__unused__)) + #else + #define CYTHON_INLINE inline + #endif +#endif +template +void __Pyx_call_destructor(T& x) { + x.~T(); +} +template +class __Pyx_FakeReference { + public: + __Pyx_FakeReference() : ptr(NULL) { } + __Pyx_FakeReference(const T& ref) : ptr(const_cast(&ref)) { } + T *operator->() { return ptr; } + T *operator&() { return ptr; } + operator T&() { return *ptr; } + template bool operator ==(const U& other) const { return *ptr == other; } + template bool operator !=(const U& other) const { return *ptr != other; } + template bool operator==(const __Pyx_FakeReference& other) const { return *ptr == *other.ptr; } + template bool operator!=(const __Pyx_FakeReference& other) const { return *ptr != *other.ptr; } + private: + T *ptr; +}; + +#define __PYX_BUILD_PY_SSIZE_T "n" +#define CYTHON_FORMAT_SSIZE_T "z" +#if PY_MAJOR_VERSION < 3 + #define __Pyx_BUILTIN_MODULE_NAME "__builtin__" + #define __Pyx_DefaultClassType PyClass_Type + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a+k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_BUILTIN_MODULE_NAME "builtins" + #define __Pyx_DefaultClassType PyType_Type +#if CYTHON_COMPILING_IN_LIMITED_API + static CYTHON_INLINE PyObject* __Pyx_PyCode_New(int a, int p, int k, int l, int s, int f, + PyObject *code, PyObject *c, PyObject* n, PyObject *v, + PyObject *fv, PyObject *cell, PyObject* fn, + PyObject *name, int fline, PyObject *lnos) { + PyObject *exception_table = NULL; + PyObject *types_module=NULL, *code_type=NULL, *result=NULL; + #if __PYX_LIMITED_VERSION_HEX < 0x030B0000 + PyObject *version_info; + PyObject *py_minor_version = NULL; + #endif + long minor_version = 0; + PyObject *type, *value, *traceback; + PyErr_Fetch(&type, &value, &traceback); + #if __PYX_LIMITED_VERSION_HEX >= 0x030B0000 + minor_version = 11; + #else + if (!(version_info = PySys_GetObject("version_info"))) goto end; + if (!(py_minor_version = PySequence_GetItem(version_info, 1))) goto end; + minor_version = PyLong_AsLong(py_minor_version); + Py_DECREF(py_minor_version); + if (minor_version == -1 && PyErr_Occurred()) goto end; + #endif + if (!(types_module = PyImport_ImportModule("types"))) goto end; + if (!(code_type = PyObject_GetAttrString(types_module, "CodeType"))) goto end; + if (minor_version <= 7) { + (void)p; + result = PyObject_CallFunction(code_type, "iiiiiOOOOOOiOO", a, k, l, s, f, code, + c, n, v, fn, name, fline, lnos, fv, cell); + } else if (minor_version <= 10) { + result = PyObject_CallFunction(code_type, "iiiiiiOOOOOOiOO", a,p, k, l, s, f, code, + c, n, v, fn, name, fline, lnos, fv, cell); + } else { + if (!(exception_table = PyBytes_FromStringAndSize(NULL, 0))) goto end; + result = PyObject_CallFunction(code_type, "iiiiiiOOOOOOOiOO", a,p, k, l, s, f, code, + c, n, v, fn, name, name, fline, lnos, exception_table, fv, cell); + } + end: + Py_XDECREF(code_type); + Py_XDECREF(exception_table); + Py_XDECREF(types_module); + if (type) { + PyErr_Restore(type, value, traceback); + } + return result; + } + #ifndef CO_OPTIMIZED + #define CO_OPTIMIZED 0x0001 + #endif + #ifndef CO_NEWLOCALS + #define CO_NEWLOCALS 0x0002 + #endif + #ifndef CO_VARARGS + #define CO_VARARGS 0x0004 + #endif + #ifndef CO_VARKEYWORDS + #define CO_VARKEYWORDS 0x0008 + #endif + #ifndef CO_ASYNC_GENERATOR + #define CO_ASYNC_GENERATOR 0x0200 + #endif + #ifndef CO_GENERATOR + #define CO_GENERATOR 0x0020 + #endif + #ifndef CO_COROUTINE + #define CO_COROUTINE 0x0080 + #endif +#elif PY_VERSION_HEX >= 0x030B0000 + static CYTHON_INLINE PyCodeObject* __Pyx_PyCode_New(int a, int p, int k, int l, int s, int f, + PyObject *code, PyObject *c, PyObject* n, PyObject *v, + PyObject *fv, PyObject *cell, PyObject* fn, + PyObject *name, int fline, PyObject *lnos) { + PyCodeObject *result; + PyObject *empty_bytes = PyBytes_FromStringAndSize("", 0); + if (!empty_bytes) return NULL; + result = + #if PY_VERSION_HEX >= 0x030C0000 + PyUnstable_Code_NewWithPosOnlyArgs + #else + PyCode_NewWithPosOnlyArgs + #endif + (a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, name, fline, lnos, empty_bytes); + Py_DECREF(empty_bytes); + return result; + } +#elif PY_VERSION_HEX >= 0x030800B2 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_NewWithPosOnlyArgs(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#endif +#endif +#if PY_VERSION_HEX >= 0x030900A4 || defined(Py_IS_TYPE) + #define __Pyx_IS_TYPE(ob, type) Py_IS_TYPE(ob, type) +#else + #define __Pyx_IS_TYPE(ob, type) (((const PyObject*)ob)->ob_type == (type)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_Is) + #define __Pyx_Py_Is(x, y) Py_Is(x, y) +#else + #define __Pyx_Py_Is(x, y) ((x) == (y)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsNone) + #define __Pyx_Py_IsNone(ob) Py_IsNone(ob) +#else + #define __Pyx_Py_IsNone(ob) __Pyx_Py_Is((ob), Py_None) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsTrue) + #define __Pyx_Py_IsTrue(ob) Py_IsTrue(ob) +#else + #define __Pyx_Py_IsTrue(ob) __Pyx_Py_Is((ob), Py_True) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsFalse) + #define __Pyx_Py_IsFalse(ob) Py_IsFalse(ob) +#else + #define __Pyx_Py_IsFalse(ob) __Pyx_Py_Is((ob), Py_False) +#endif +#define __Pyx_NoneAsNull(obj) (__Pyx_Py_IsNone(obj) ? NULL : (obj)) +#if PY_VERSION_HEX >= 0x030900F0 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_GC_IsFinalized(o) PyObject_GC_IsFinalized(o) +#else + #define __Pyx_PyObject_GC_IsFinalized(o) _PyGC_FINALIZED(o) +#endif +#ifndef CO_COROUTINE + #define CO_COROUTINE 0x80 +#endif +#ifndef CO_ASYNC_GENERATOR + #define CO_ASYNC_GENERATOR 0x200 +#endif +#ifndef Py_TPFLAGS_CHECKTYPES + #define Py_TPFLAGS_CHECKTYPES 0 +#endif +#ifndef Py_TPFLAGS_HAVE_INDEX + #define Py_TPFLAGS_HAVE_INDEX 0 +#endif +#ifndef Py_TPFLAGS_HAVE_NEWBUFFER + #define Py_TPFLAGS_HAVE_NEWBUFFER 0 +#endif +#ifndef Py_TPFLAGS_HAVE_FINALIZE + #define Py_TPFLAGS_HAVE_FINALIZE 0 +#endif +#ifndef Py_TPFLAGS_SEQUENCE + #define Py_TPFLAGS_SEQUENCE 0 +#endif +#ifndef Py_TPFLAGS_MAPPING + #define Py_TPFLAGS_MAPPING 0 +#endif +#ifndef METH_STACKLESS + #define METH_STACKLESS 0 +#endif +#if PY_VERSION_HEX <= 0x030700A3 || !defined(METH_FASTCALL) + #ifndef METH_FASTCALL + #define METH_FASTCALL 0x80 + #endif + typedef PyObject *(*__Pyx_PyCFunctionFast) (PyObject *self, PyObject *const *args, Py_ssize_t nargs); + typedef PyObject *(*__Pyx_PyCFunctionFastWithKeywords) (PyObject *self, PyObject *const *args, + Py_ssize_t nargs, PyObject *kwnames); +#else + #define __Pyx_PyCFunctionFast _PyCFunctionFast + #define __Pyx_PyCFunctionFastWithKeywords _PyCFunctionFastWithKeywords +#endif +#if CYTHON_METH_FASTCALL + #define __Pyx_METH_FASTCALL METH_FASTCALL + #define __Pyx_PyCFunction_FastCall __Pyx_PyCFunctionFast + #define __Pyx_PyCFunction_FastCallWithKeywords __Pyx_PyCFunctionFastWithKeywords +#else + #define __Pyx_METH_FASTCALL METH_VARARGS + #define __Pyx_PyCFunction_FastCall PyCFunction + #define __Pyx_PyCFunction_FastCallWithKeywords PyCFunctionWithKeywords +#endif +#if CYTHON_VECTORCALL + #define __pyx_vectorcallfunc vectorcallfunc + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET PY_VECTORCALL_ARGUMENTS_OFFSET + #define __Pyx_PyVectorcall_NARGS(n) PyVectorcall_NARGS((size_t)(n)) +#elif CYTHON_BACKPORT_VECTORCALL + typedef PyObject *(*__pyx_vectorcallfunc)(PyObject *callable, PyObject *const *args, + size_t nargsf, PyObject *kwnames); + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET ((size_t)1 << (8 * sizeof(size_t) - 1)) + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(((size_t)(n)) & ~__Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET)) +#else + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET 0 + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(n)) +#endif +#if PY_MAJOR_VERSION >= 0x030900B1 +#define __Pyx_PyCFunction_CheckExact(func) PyCFunction_CheckExact(func) +#else +#define __Pyx_PyCFunction_CheckExact(func) PyCFunction_Check(func) +#endif +#define __Pyx_CyOrPyCFunction_Check(func) PyCFunction_Check(func) +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_CyOrPyCFunction_GET_FUNCTION(func) (((PyCFunctionObject*)(func))->m_ml->ml_meth) +#elif !CYTHON_COMPILING_IN_LIMITED_API +#define __Pyx_CyOrPyCFunction_GET_FUNCTION(func) PyCFunction_GET_FUNCTION(func) +#endif +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_CyOrPyCFunction_GET_FLAGS(func) (((PyCFunctionObject*)(func))->m_ml->ml_flags) +static CYTHON_INLINE PyObject* __Pyx_CyOrPyCFunction_GET_SELF(PyObject *func) { + return (__Pyx_CyOrPyCFunction_GET_FLAGS(func) & METH_STATIC) ? NULL : ((PyCFunctionObject*)func)->m_self; +} +#endif +static CYTHON_INLINE int __Pyx__IsSameCFunction(PyObject *func, void *cfunc) { +#if CYTHON_COMPILING_IN_LIMITED_API + return PyCFunction_Check(func) && PyCFunction_GetFunction(func) == (PyCFunction) cfunc; +#else + return PyCFunction_Check(func) && PyCFunction_GET_FUNCTION(func) == (PyCFunction) cfunc; +#endif +} +#define __Pyx_IsSameCFunction(func, cfunc) __Pyx__IsSameCFunction(func, cfunc) +#if __PYX_LIMITED_VERSION_HEX < 0x030900B1 + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) ((void)m, PyType_FromSpecWithBases(s, b)) + typedef PyObject *(*__Pyx_PyCMethod)(PyObject *, PyTypeObject *, PyObject *const *, size_t, PyObject *); +#else + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) PyType_FromModuleAndSpec(m, s, b) + #define __Pyx_PyCMethod PyCMethod +#endif +#ifndef METH_METHOD + #define METH_METHOD 0x200 +#endif +#if CYTHON_COMPILING_IN_PYPY && !defined(PyObject_Malloc) + #define PyObject_Malloc(s) PyMem_Malloc(s) + #define PyObject_Free(p) PyMem_Free(p) + #define PyObject_Realloc(p) PyMem_Realloc(p) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) +#else + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) (frame)->f_lineno = (lineno) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyThreadState_Current PyThreadState_Get() +#elif !CYTHON_FAST_THREAD_STATE + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#elif PY_VERSION_HEX >= 0x030d00A1 + #define __Pyx_PyThreadState_Current PyThreadState_GetUnchecked() +#elif PY_VERSION_HEX >= 0x03060000 + #define __Pyx_PyThreadState_Current _PyThreadState_UncheckedGet() +#elif PY_VERSION_HEX >= 0x03000000 + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#else + #define __Pyx_PyThreadState_Current _PyThreadState_Current +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE void *__Pyx_PyModule_GetState(PyObject *op) +{ + void *result; + result = PyModule_GetState(op); + if (!result) + Py_FatalError("Couldn't find the module state"); + return result; +} +#endif +#define __Pyx_PyObject_GetSlot(obj, name, func_ctype) __Pyx_PyType_GetSlot(Py_TYPE(obj), name, func_ctype) +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((func_ctype) PyType_GetSlot((type), Py_##name)) +#else + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((type)->name) +#endif +#if PY_VERSION_HEX < 0x030700A2 && !defined(PyThread_tss_create) && !defined(Py_tss_NEEDS_INIT) +#include "pythread.h" +#define Py_tss_NEEDS_INIT 0 +typedef int Py_tss_t; +static CYTHON_INLINE int PyThread_tss_create(Py_tss_t *key) { + *key = PyThread_create_key(); + return 0; +} +static CYTHON_INLINE Py_tss_t * PyThread_tss_alloc(void) { + Py_tss_t *key = (Py_tss_t *)PyObject_Malloc(sizeof(Py_tss_t)); + *key = Py_tss_NEEDS_INIT; + return key; +} +static CYTHON_INLINE void PyThread_tss_free(Py_tss_t *key) { + PyObject_Free(key); +} +static CYTHON_INLINE int PyThread_tss_is_created(Py_tss_t *key) { + return *key != Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE void PyThread_tss_delete(Py_tss_t *key) { + PyThread_delete_key(*key); + *key = Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE int PyThread_tss_set(Py_tss_t *key, void *value) { + return PyThread_set_key_value(*key, value); +} +static CYTHON_INLINE void * PyThread_tss_get(Py_tss_t *key) { + return PyThread_get_key_value(*key); +} +#endif +#if PY_MAJOR_VERSION < 3 + #if CYTHON_COMPILING_IN_PYPY + #if PYPY_VERSION_NUM < 0x07030600 + #if defined(__cplusplus) && __cplusplus >= 201402L + [[deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")]] + #elif defined(__GNUC__) || defined(__clang__) + __attribute__ ((__deprecated__("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6"))) + #elif defined(_MSC_VER) + __declspec(deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")) + #endif + static CYTHON_INLINE int PyGILState_Check(void) { + return 0; + } + #else // PYPY_VERSION_NUM < 0x07030600 + #endif // PYPY_VERSION_NUM < 0x07030600 + #else + static CYTHON_INLINE int PyGILState_Check(void) { + PyThreadState * tstate = _PyThreadState_Current; + return tstate && (tstate == PyGILState_GetThisThreadState()); + } + #endif +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030d0000 || defined(_PyDict_NewPresized) +#define __Pyx_PyDict_NewPresized(n) ((n <= 8) ? PyDict_New() : _PyDict_NewPresized(n)) +#else +#define __Pyx_PyDict_NewPresized(n) PyDict_New() +#endif +#if PY_MAJOR_VERSION >= 3 || CYTHON_FUTURE_DIVISION + #define __Pyx_PyNumber_Divide(x,y) PyNumber_TrueDivide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceTrueDivide(x,y) +#else + #define __Pyx_PyNumber_Divide(x,y) PyNumber_Divide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceDivide(x,y) +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX > 0x030600B4 && PY_VERSION_HEX < 0x030d0000 && CYTHON_USE_UNICODE_INTERNALS +#define __Pyx_PyDict_GetItemStrWithError(dict, name) _PyDict_GetItem_KnownHash(dict, name, ((PyASCIIObject *) name)->hash) +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStr(PyObject *dict, PyObject *name) { + PyObject *res = __Pyx_PyDict_GetItemStrWithError(dict, name); + if (res == NULL) PyErr_Clear(); + return res; +} +#elif PY_MAJOR_VERSION >= 3 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07020000) +#define __Pyx_PyDict_GetItemStrWithError PyDict_GetItemWithError +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#else +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStrWithError(PyObject *dict, PyObject *name) { +#if CYTHON_COMPILING_IN_PYPY + return PyDict_GetItem(dict, name); +#else + PyDictEntry *ep; + PyDictObject *mp = (PyDictObject*) dict; + long hash = ((PyStringObject *) name)->ob_shash; + assert(hash != -1); + ep = (mp->ma_lookup)(mp, name, hash); + if (ep == NULL) { + return NULL; + } + return ep->me_value; +#endif +} +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#endif +#if CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyType_GetFlags(tp) (((PyTypeObject *)tp)->tp_flags) + #define __Pyx_PyType_HasFeature(type, feature) ((__Pyx_PyType_GetFlags(type) & (feature)) != 0) + #define __Pyx_PyObject_GetIterNextFunc(obj) (Py_TYPE(obj)->tp_iternext) +#else + #define __Pyx_PyType_GetFlags(tp) (PyType_GetFlags((PyTypeObject *)tp)) + #define __Pyx_PyType_HasFeature(type, feature) PyType_HasFeature(type, feature) + #define __Pyx_PyObject_GetIterNextFunc(obj) PyIter_Next +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_SetItemOnTypeDict(tp, k, v) PyObject_GenericSetAttr((PyObject*)tp, k, v) +#else + #define __Pyx_SetItemOnTypeDict(tp, k, v) PyDict_SetItem(tp->tp_dict, k, v) +#endif +#if CYTHON_USE_TYPE_SPECS && PY_VERSION_HEX >= 0x03080000 +#define __Pyx_PyHeapTypeObject_GC_Del(obj) {\ + PyTypeObject *type = Py_TYPE((PyObject*)obj);\ + assert(__Pyx_PyType_HasFeature(type, Py_TPFLAGS_HEAPTYPE));\ + PyObject_GC_Del(obj);\ + Py_DECREF(type);\ +} +#else +#define __Pyx_PyHeapTypeObject_GC_Del(obj) PyObject_GC_Del(obj) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define CYTHON_PEP393_ENABLED 1 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GetLength(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_ReadChar(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((void)u, 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((void)u, (0)) + #define __Pyx_PyUnicode_DATA(u) ((void*)u) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)k, PyUnicode_ReadChar((PyObject*)(d), i)) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GetLength(u)) +#elif PY_VERSION_HEX > 0x03030000 && defined(PyUnicode_KIND) + #define CYTHON_PEP393_ENABLED 1 + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_READY(op) (0) + #else + #define __Pyx_PyUnicode_READY(op) (likely(PyUnicode_IS_READY(op)) ?\ + 0 : _PyUnicode_Ready((PyObject *)(op))) + #endif + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_LENGTH(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_READ_CHAR(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) PyUnicode_MAX_CHAR_VALUE(u) + #define __Pyx_PyUnicode_KIND(u) ((int)PyUnicode_KIND(u)) + #define __Pyx_PyUnicode_DATA(u) PyUnicode_DATA(u) + #define __Pyx_PyUnicode_READ(k, d, i) PyUnicode_READ(k, d, i) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) PyUnicode_WRITE(k, d, i, (Py_UCS4) ch) + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_LENGTH(u)) + #else + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x03090000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : ((PyCompactUnicodeObject *)(u))->wstr_length)) + #else + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : PyUnicode_GET_SIZE(u))) + #endif + #endif +#else + #define CYTHON_PEP393_ENABLED 0 + #define PyUnicode_1BYTE_KIND 1 + #define PyUnicode_2BYTE_KIND 2 + #define PyUnicode_4BYTE_KIND 4 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_SIZE(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) ((Py_UCS4)(PyUnicode_AS_UNICODE(u)[i])) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((sizeof(Py_UNICODE) == 2) ? 65535U : 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((int)sizeof(Py_UNICODE)) + #define __Pyx_PyUnicode_DATA(u) ((void*)PyUnicode_AS_UNICODE(u)) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)(k), (Py_UCS4)(((Py_UNICODE*)d)[i])) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) (((void)(k)), ((Py_UNICODE*)d)[i] = (Py_UNICODE) ch) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_SIZE(u)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyUnicode_Concat(a, b) PyNumber_Add(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) PyNumber_Add(a, b) +#else + #define __Pyx_PyUnicode_Concat(a, b) PyUnicode_Concat(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) ((unlikely((a) == Py_None) || unlikely((b) == Py_None)) ?\ + PyNumber_Add(a, b) : __Pyx_PyUnicode_Concat(a, b)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #if !defined(PyUnicode_DecodeUnicodeEscape) + #define PyUnicode_DecodeUnicodeEscape(s, size, errors) PyUnicode_Decode(s, size, "unicode_escape", errors) + #endif + #if !defined(PyUnicode_Contains) || (PY_MAJOR_VERSION == 2 && PYPY_VERSION_NUM < 0x07030500) + #undef PyUnicode_Contains + #define PyUnicode_Contains(u, s) PySequence_Contains(u, s) + #endif + #if !defined(PyByteArray_Check) + #define PyByteArray_Check(obj) PyObject_TypeCheck(obj, &PyByteArray_Type) + #endif + #if !defined(PyObject_Format) + #define PyObject_Format(obj, fmt) PyObject_CallMethod(obj, "__format__", "O", fmt) + #endif +#endif +#define __Pyx_PyString_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyString_Check(b) && !PyString_CheckExact(b)))) ? PyNumber_Remainder(a, b) : __Pyx_PyString_Format(a, b)) +#define __Pyx_PyUnicode_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyUnicode_Check(b) && !PyUnicode_CheckExact(b)))) ? PyNumber_Remainder(a, b) : PyUnicode_Format(a, b)) +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyString_Format(a, b) PyUnicode_Format(a, b) +#else + #define __Pyx_PyString_Format(a, b) PyString_Format(a, b) +#endif +#if PY_MAJOR_VERSION < 3 && !defined(PyObject_ASCII) + #define PyObject_ASCII(o) PyObject_Repr(o) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBaseString_Type PyUnicode_Type + #define PyStringObject PyUnicodeObject + #define PyString_Type PyUnicode_Type + #define PyString_Check PyUnicode_Check + #define PyString_CheckExact PyUnicode_CheckExact +#ifndef PyObject_Unicode + #define PyObject_Unicode PyObject_Str +#endif +#endif +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyBaseString_Check(obj) PyUnicode_Check(obj) + #define __Pyx_PyBaseString_CheckExact(obj) PyUnicode_CheckExact(obj) +#else + #define __Pyx_PyBaseString_Check(obj) (PyString_Check(obj) || PyUnicode_Check(obj)) + #define __Pyx_PyBaseString_CheckExact(obj) (PyString_CheckExact(obj) || PyUnicode_CheckExact(obj)) +#endif +#if CYTHON_COMPILING_IN_CPYTHON + #define __Pyx_PySequence_ListKeepNew(obj)\ + (likely(PyList_CheckExact(obj) && Py_REFCNT(obj) == 1) ? __Pyx_NewRef(obj) : PySequence_List(obj)) +#else + #define __Pyx_PySequence_ListKeepNew(obj) PySequence_List(obj) +#endif +#ifndef PySet_CheckExact + #define PySet_CheckExact(obj) __Pyx_IS_TYPE(obj, &PySet_Type) +#endif +#if PY_VERSION_HEX >= 0x030900A4 + #define __Pyx_SET_REFCNT(obj, refcnt) Py_SET_REFCNT(obj, refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SET_SIZE(obj, size) +#else + #define __Pyx_SET_REFCNT(obj, refcnt) Py_REFCNT(obj) = (refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SIZE(obj) = (size) +#endif +#if CYTHON_ASSUME_SAFE_MACROS + #define __Pyx_PySequence_ITEM(o, i) PySequence_ITEM(o, i) + #define __Pyx_PySequence_SIZE(seq) Py_SIZE(seq) + #define __Pyx_PyTuple_SET_ITEM(o, i, v) (PyTuple_SET_ITEM(o, i, v), (0)) + #define __Pyx_PyList_SET_ITEM(o, i, v) (PyList_SET_ITEM(o, i, v), (0)) + #define __Pyx_PyTuple_GET_SIZE(o) PyTuple_GET_SIZE(o) + #define __Pyx_PyList_GET_SIZE(o) PyList_GET_SIZE(o) + #define __Pyx_PySet_GET_SIZE(o) PySet_GET_SIZE(o) + #define __Pyx_PyBytes_GET_SIZE(o) PyBytes_GET_SIZE(o) + #define __Pyx_PyByteArray_GET_SIZE(o) PyByteArray_GET_SIZE(o) +#else + #define __Pyx_PySequence_ITEM(o, i) PySequence_GetItem(o, i) + #define __Pyx_PySequence_SIZE(seq) PySequence_Size(seq) + #define __Pyx_PyTuple_SET_ITEM(o, i, v) PyTuple_SetItem(o, i, v) + #define __Pyx_PyList_SET_ITEM(o, i, v) PyList_SetItem(o, i, v) + #define __Pyx_PyTuple_GET_SIZE(o) PyTuple_Size(o) + #define __Pyx_PyList_GET_SIZE(o) PyList_Size(o) + #define __Pyx_PySet_GET_SIZE(o) PySet_Size(o) + #define __Pyx_PyBytes_GET_SIZE(o) PyBytes_Size(o) + #define __Pyx_PyByteArray_GET_SIZE(o) PyByteArray_Size(o) +#endif +#if PY_VERSION_HEX >= 0x030d00A1 + #define __Pyx_PyImport_AddModuleRef(name) PyImport_AddModuleRef(name) +#else + static CYTHON_INLINE PyObject *__Pyx_PyImport_AddModuleRef(const char *name) { + PyObject *module = PyImport_AddModule(name); + Py_XINCREF(module); + return module; + } +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyIntObject PyLongObject + #define PyInt_Type PyLong_Type + #define PyInt_Check(op) PyLong_Check(op) + #define PyInt_CheckExact(op) PyLong_CheckExact(op) + #define __Pyx_Py3Int_Check(op) PyLong_Check(op) + #define __Pyx_Py3Int_CheckExact(op) PyLong_CheckExact(op) + #define PyInt_FromString PyLong_FromString + #define PyInt_FromUnicode PyLong_FromUnicode + #define PyInt_FromLong PyLong_FromLong + #define PyInt_FromSize_t PyLong_FromSize_t + #define PyInt_FromSsize_t PyLong_FromSsize_t + #define PyInt_AsLong PyLong_AsLong + #define PyInt_AS_LONG PyLong_AS_LONG + #define PyInt_AsSsize_t PyLong_AsSsize_t + #define PyInt_AsUnsignedLongMask PyLong_AsUnsignedLongMask + #define PyInt_AsUnsignedLongLongMask PyLong_AsUnsignedLongLongMask + #define PyNumber_Int PyNumber_Long +#else + #define __Pyx_Py3Int_Check(op) (PyLong_Check(op) || PyInt_Check(op)) + #define __Pyx_Py3Int_CheckExact(op) (PyLong_CheckExact(op) || PyInt_CheckExact(op)) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBoolObject PyLongObject +#endif +#if PY_MAJOR_VERSION >= 3 && CYTHON_COMPILING_IN_PYPY + #ifndef PyUnicode_InternFromString + #define PyUnicode_InternFromString(s) PyUnicode_FromString(s) + #endif +#endif +#if PY_VERSION_HEX < 0x030200A4 + typedef long Py_hash_t; + #define __Pyx_PyInt_FromHash_t PyInt_FromLong + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsHash_t +#else + #define __Pyx_PyInt_FromHash_t PyInt_FromSsize_t + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsSsize_t +#endif +#if CYTHON_USE_ASYNC_SLOTS + #if PY_VERSION_HEX >= 0x030500B1 + #define __Pyx_PyAsyncMethodsStruct PyAsyncMethods + #define __Pyx_PyType_AsAsync(obj) (Py_TYPE(obj)->tp_as_async) + #else + #define __Pyx_PyType_AsAsync(obj) ((__Pyx_PyAsyncMethodsStruct*) (Py_TYPE(obj)->tp_reserved)) + #endif +#else + #define __Pyx_PyType_AsAsync(obj) NULL +#endif +#ifndef __Pyx_PyAsyncMethodsStruct + typedef struct { + unaryfunc am_await; + unaryfunc am_aiter; + unaryfunc am_anext; + } __Pyx_PyAsyncMethodsStruct; +#endif + +#if defined(_WIN32) || defined(WIN32) || defined(MS_WINDOWS) + #if !defined(_USE_MATH_DEFINES) + #define _USE_MATH_DEFINES + #endif +#endif +#include +#ifdef NAN +#define __PYX_NAN() ((float) NAN) +#else +static CYTHON_INLINE float __PYX_NAN() { + float value; + memset(&value, 0xFF, sizeof(value)); + return value; +} +#endif +#if defined(__CYGWIN__) && defined(_LDBL_EQ_DBL) +#define __Pyx_truncl trunc +#else +#define __Pyx_truncl truncl +#endif + +#define __PYX_MARK_ERR_POS(f_index, lineno) \ + { __pyx_filename = __pyx_f[f_index]; (void)__pyx_filename; __pyx_lineno = lineno; (void)__pyx_lineno; __pyx_clineno = __LINE__; (void)__pyx_clineno; } +#define __PYX_ERR(f_index, lineno, Ln_error) \ + { __PYX_MARK_ERR_POS(f_index, lineno) goto Ln_error; } + +#ifdef CYTHON_EXTERN_C + #undef __PYX_EXTERN_C + #define __PYX_EXTERN_C CYTHON_EXTERN_C +#elif defined(__PYX_EXTERN_C) + #ifdef _MSC_VER + #pragma message ("Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead.") + #else + #warning Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead. + #endif +#else + #define __PYX_EXTERN_C extern "C++" +#endif + +#define __PYX_HAVE__cereal__messaging__messaging_pyx +#define __PYX_HAVE_API__cereal__messaging__messaging_pyx +/* Early includes */ +#include +#include +#include "ios" +#include "new" +#include "stdexcept" +#include "typeinfo" +#include +#include +#include "cereal/messaging/impl_fake.h" +#include "cereal/messaging/messaging.h" +#ifdef _OPENMP +#include +#endif /* _OPENMP */ + +#if defined(PYREX_WITHOUT_ASSERTIONS) && !defined(CYTHON_WITHOUT_ASSERTIONS) +#define CYTHON_WITHOUT_ASSERTIONS +#endif + +typedef struct {PyObject **p; const char *s; const Py_ssize_t n; const char* encoding; + const char is_unicode; const char is_str; const char intern; } __Pyx_StringTabEntry; + +#define __PYX_DEFAULT_STRING_ENCODING_IS_ASCII 1 +#define __PYX_DEFAULT_STRING_ENCODING_IS_UTF8 0 +#define __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT (PY_MAJOR_VERSION >= 3 && __PYX_DEFAULT_STRING_ENCODING_IS_UTF8) +#define __PYX_DEFAULT_STRING_ENCODING "ascii" +#define __Pyx_PyObject_FromString __Pyx_PyBytes_FromString +#define __Pyx_PyObject_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#define __Pyx_uchar_cast(c) ((unsigned char)c) +#define __Pyx_long_cast(x) ((long)x) +#define __Pyx_fits_Py_ssize_t(v, type, is_signed) (\ + (sizeof(type) < sizeof(Py_ssize_t)) ||\ + (sizeof(type) > sizeof(Py_ssize_t) &&\ + likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX) &&\ + (!is_signed || likely(v > (type)PY_SSIZE_T_MIN ||\ + v == (type)PY_SSIZE_T_MIN))) ||\ + (sizeof(type) == sizeof(Py_ssize_t) &&\ + (is_signed || likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX))) ) +static CYTHON_INLINE int __Pyx_is_valid_index(Py_ssize_t i, Py_ssize_t limit) { + return (size_t) i < (size_t) limit; +} +#if defined (__cplusplus) && __cplusplus >= 201103L + #include + #define __Pyx_sst_abs(value) std::abs(value) +#elif SIZEOF_INT >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) abs(value) +#elif SIZEOF_LONG >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) labs(value) +#elif defined (_MSC_VER) + #define __Pyx_sst_abs(value) ((Py_ssize_t)_abs64(value)) +#elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define __Pyx_sst_abs(value) llabs(value) +#elif defined (__GNUC__) + #define __Pyx_sst_abs(value) __builtin_llabs(value) +#else + #define __Pyx_sst_abs(value) ((value<0) ? -value : value) +#endif +static CYTHON_INLINE Py_ssize_t __Pyx_ssize_strlen(const char *s); +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject*); +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject*, Py_ssize_t* length); +static CYTHON_INLINE PyObject* __Pyx_PyByteArray_FromString(const char*); +#define __Pyx_PyByteArray_FromStringAndSize(s, l) PyByteArray_FromStringAndSize((const char*)s, l) +#define __Pyx_PyBytes_FromString PyBytes_FromString +#define __Pyx_PyBytes_FromStringAndSize PyBytes_FromStringAndSize +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char*); +#if PY_MAJOR_VERSION < 3 + #define __Pyx_PyStr_FromString __Pyx_PyBytes_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#else + #define __Pyx_PyStr_FromString __Pyx_PyUnicode_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyUnicode_FromStringAndSize +#endif +#define __Pyx_PyBytes_AsWritableString(s) ((char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableSString(s) ((signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableUString(s) ((unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsString(s) ((const char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsSString(s) ((const signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsUString(s) ((const unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyObject_AsWritableString(s) ((char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableSString(s) ((signed char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableUString(s) ((unsigned char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsSString(s) ((const signed char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsUString(s) ((const unsigned char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_FromCString(s) __Pyx_PyObject_FromString((const char*)s) +#define __Pyx_PyBytes_FromCString(s) __Pyx_PyBytes_FromString((const char*)s) +#define __Pyx_PyByteArray_FromCString(s) __Pyx_PyByteArray_FromString((const char*)s) +#define __Pyx_PyStr_FromCString(s) __Pyx_PyStr_FromString((const char*)s) +#define __Pyx_PyUnicode_FromCString(s) __Pyx_PyUnicode_FromString((const char*)s) +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const wchar_t *u) +{ + const wchar_t *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#else +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const Py_UNICODE *u) +{ + const Py_UNICODE *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#endif +#define __Pyx_PyUnicode_FromOrdinal(o) PyUnicode_FromOrdinal((int)o) +#define __Pyx_PyUnicode_FromUnicode(u) PyUnicode_FromUnicode(u, __Pyx_Py_UNICODE_strlen(u)) +#define __Pyx_PyUnicode_FromUnicodeAndLength PyUnicode_FromUnicode +#define __Pyx_PyUnicode_AsUnicode PyUnicode_AsUnicode +#define __Pyx_NewRef(obj) (Py_INCREF(obj), obj) +#define __Pyx_Owned_Py_None(b) __Pyx_NewRef(Py_None) +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b); +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject*); +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject*); +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x); +#define __Pyx_PySequence_Tuple(obj)\ + (likely(PyTuple_CheckExact(obj)) ? __Pyx_NewRef(obj) : PySequence_Tuple(obj)) +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject*); +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t); +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject*); +#if CYTHON_ASSUME_SAFE_MACROS +#define __pyx_PyFloat_AsDouble(x) (PyFloat_CheckExact(x) ? PyFloat_AS_DOUBLE(x) : PyFloat_AsDouble(x)) +#else +#define __pyx_PyFloat_AsDouble(x) PyFloat_AsDouble(x) +#endif +#define __pyx_PyFloat_AsFloat(x) ((float) __pyx_PyFloat_AsDouble(x)) +#if PY_MAJOR_VERSION >= 3 +#define __Pyx_PyNumber_Int(x) (PyLong_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Long(x)) +#else +#define __Pyx_PyNumber_Int(x) (PyInt_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Int(x)) +#endif +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_VERSION_HEX >= 0x030C00A7 + #ifndef _PyLong_SIGN_MASK + #define _PyLong_SIGN_MASK 3 + #endif + #ifndef _PyLong_NON_SIZE_BITS + #define _PyLong_NON_SIZE_BITS 3 + #endif + #define __Pyx_PyLong_Sign(x) (((PyLongObject*)x)->long_value.lv_tag & _PyLong_SIGN_MASK) + #define __Pyx_PyLong_IsNeg(x) ((__Pyx_PyLong_Sign(x) & 2) != 0) + #define __Pyx_PyLong_IsNonNeg(x) (!__Pyx_PyLong_IsNeg(x)) + #define __Pyx_PyLong_IsZero(x) (__Pyx_PyLong_Sign(x) & 1) + #define __Pyx_PyLong_IsPos(x) (__Pyx_PyLong_Sign(x) == 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) (__Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) ((Py_ssize_t) (((PyLongObject*)x)->long_value.lv_tag >> _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_SignedDigitCount(x)\ + ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * __Pyx_PyLong_DigitCount(x)) + #if defined(PyUnstable_Long_IsCompact) && defined(PyUnstable_Long_CompactValue) + #define __Pyx_PyLong_IsCompact(x) PyUnstable_Long_IsCompact((PyLongObject*) x) + #define __Pyx_PyLong_CompactValue(x) PyUnstable_Long_CompactValue((PyLongObject*) x) + #else + #define __Pyx_PyLong_IsCompact(x) (((PyLongObject*)x)->long_value.lv_tag < (2 << _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_CompactValue(x) ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * (Py_ssize_t) __Pyx_PyLong_Digits(x)[0]) + #endif + typedef Py_ssize_t __Pyx_compact_pylong; + typedef size_t __Pyx_compact_upylong; + #else + #define __Pyx_PyLong_IsNeg(x) (Py_SIZE(x) < 0) + #define __Pyx_PyLong_IsNonNeg(x) (Py_SIZE(x) >= 0) + #define __Pyx_PyLong_IsZero(x) (Py_SIZE(x) == 0) + #define __Pyx_PyLong_IsPos(x) (Py_SIZE(x) > 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) ((Py_SIZE(x) == 0) ? 0 : __Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) __Pyx_sst_abs(Py_SIZE(x)) + #define __Pyx_PyLong_SignedDigitCount(x) Py_SIZE(x) + #define __Pyx_PyLong_IsCompact(x) (Py_SIZE(x) == 0 || Py_SIZE(x) == 1 || Py_SIZE(x) == -1) + #define __Pyx_PyLong_CompactValue(x)\ + ((Py_SIZE(x) == 0) ? (sdigit) 0 : ((Py_SIZE(x) < 0) ? -(sdigit)__Pyx_PyLong_Digits(x)[0] : (sdigit)__Pyx_PyLong_Digits(x)[0])) + typedef sdigit __Pyx_compact_pylong; + typedef digit __Pyx_compact_upylong; + #endif + #if PY_VERSION_HEX >= 0x030C00A5 + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->long_value.ob_digit) + #else + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->ob_digit) + #endif +#endif +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII +#include +static int __Pyx_sys_getdefaultencoding_not_ascii; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + PyObject* ascii_chars_u = NULL; + PyObject* ascii_chars_b = NULL; + const char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + if (strcmp(default_encoding_c, "ascii") == 0) { + __Pyx_sys_getdefaultencoding_not_ascii = 0; + } else { + char ascii_chars[128]; + int c; + for (c = 0; c < 128; c++) { + ascii_chars[c] = (char) c; + } + __Pyx_sys_getdefaultencoding_not_ascii = 1; + ascii_chars_u = PyUnicode_DecodeASCII(ascii_chars, 128, NULL); + if (!ascii_chars_u) goto bad; + ascii_chars_b = PyUnicode_AsEncodedString(ascii_chars_u, default_encoding_c, NULL); + if (!ascii_chars_b || !PyBytes_Check(ascii_chars_b) || memcmp(ascii_chars, PyBytes_AS_STRING(ascii_chars_b), 128) != 0) { + PyErr_Format( + PyExc_ValueError, + "This module compiled with c_string_encoding=ascii, but default encoding '%.200s' is not a superset of ascii.", + default_encoding_c); + goto bad; + } + Py_DECREF(ascii_chars_u); + Py_DECREF(ascii_chars_b); + } + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + Py_XDECREF(ascii_chars_u); + Py_XDECREF(ascii_chars_b); + return -1; +} +#endif +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT && PY_MAJOR_VERSION >= 3 +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_DecodeUTF8(c_str, size, NULL) +#else +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_Decode(c_str, size, __PYX_DEFAULT_STRING_ENCODING, NULL) +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +#include +static char* __PYX_DEFAULT_STRING_ENCODING; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) (const char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + __PYX_DEFAULT_STRING_ENCODING = (char*) malloc(strlen(default_encoding_c) + 1); + if (!__PYX_DEFAULT_STRING_ENCODING) goto bad; + strcpy(__PYX_DEFAULT_STRING_ENCODING, default_encoding_c); + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + return -1; +} +#endif +#endif + + +/* Test for GCC > 2.95 */ +#if defined(__GNUC__) && (__GNUC__ > 2 || (__GNUC__ == 2 && (__GNUC_MINOR__ > 95))) + #define likely(x) __builtin_expect(!!(x), 1) + #define unlikely(x) __builtin_expect(!!(x), 0) +#else /* !__GNUC__ or GCC < 2.95 */ + #define likely(x) (x) + #define unlikely(x) (x) +#endif /* __GNUC__ */ +static CYTHON_INLINE void __Pyx_pretend_to_initialize(void* ptr) { (void)ptr; } + +#if !CYTHON_USE_MODULE_STATE +static PyObject *__pyx_m = NULL; +#endif +static int __pyx_lineno; +static int __pyx_clineno = 0; +static const char * __pyx_cfilenm = __FILE__; +static const char *__pyx_filename; + +/* #### Code section: filename_table ### */ + +static const char *__pyx_f[] = { + "cereal/messaging/messaging_pyx.pyx", + "", +}; +/* #### Code section: utility_code_proto_before_types ### */ +/* ForceInitThreads.proto */ +#ifndef __PYX_FORCE_INIT_THREADS + #define __PYX_FORCE_INIT_THREADS 0 +#endif + +/* NoFastGil.proto */ +#define __Pyx_PyGILState_Ensure PyGILState_Ensure +#define __Pyx_PyGILState_Release PyGILState_Release +#define __Pyx_FastGIL_Remember() +#define __Pyx_FastGIL_Forget() +#define __Pyx_FastGilFuncInit() + +/* #### Code section: numeric_typedefs ### */ +/* #### Code section: complex_type_declarations ### */ +/* #### Code section: type_declarations ### */ + +/*--- Type declarations ---*/ +struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event; +struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle; +struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context; +struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller; +struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket; +struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket; + +/* "cereal/messaging/messaging_pyx.pyx":55 + * + * + * cdef class Event: # <<<<<<<<<<<<<< + * cdef cppEvent event; + * + */ +struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event { + PyObject_HEAD + struct __pyx_vtabstruct_6cereal_9messaging_13messaging_pyx_Event *__pyx_vtab; + Event event; +}; + + +/* "cereal/messaging/messaging_pyx.pyx":85 + * + * + * cdef class SocketEventHandle: # <<<<<<<<<<<<<< + * cdef cppSocketEventHandle * handle; + * + */ +struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle { + PyObject_HEAD + SocketEventHandle *handle; +}; + + +/* "cereal/messaging/messaging_pyx.pyx":117 + * + * + * cdef class Context: # <<<<<<<<<<<<<< + * cdef cppContext * context + * + */ +struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context { + PyObject_HEAD + Context *context; +}; + + +/* "cereal/messaging/messaging_pyx.pyx":134 + * + * + * cdef class Poller: # <<<<<<<<<<<<<< + * cdef cppPoller * poller + * cdef list sub_sockets + */ +struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller { + PyObject_HEAD + Poller *poller; + PyObject *sub_sockets; +}; + + +/* "cereal/messaging/messaging_pyx.pyx":164 + * + * + * cdef class SubSocket: # <<<<<<<<<<<<<< + * cdef cppSubSocket * socket + * cdef bool is_owner + */ +struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket { + PyObject_HEAD + struct __pyx_vtabstruct_6cereal_9messaging_13messaging_pyx_SubSocket *__pyx_vtab; + SubSocket *socket; + bool is_owner; +}; + + +/* "cereal/messaging/messaging_pyx.pyx":216 + * + * + * cdef class PubSocket: # <<<<<<<<<<<<<< + * cdef cppPubSocket * socket + * + */ +struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket { + PyObject_HEAD + PubSocket *socket; +}; + + + +/* "cereal/messaging/messaging_pyx.pyx":55 + * + * + * cdef class Event: # <<<<<<<<<<<<<< + * cdef cppEvent event; + * + */ + +struct __pyx_vtabstruct_6cereal_9messaging_13messaging_pyx_Event { + PyObject *(*setEvent)(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *, Event); +}; +static struct __pyx_vtabstruct_6cereal_9messaging_13messaging_pyx_Event *__pyx_vtabptr_6cereal_9messaging_13messaging_pyx_Event; + + +/* "cereal/messaging/messaging_pyx.pyx":164 + * + * + * cdef class SubSocket: # <<<<<<<<<<<<<< + * cdef cppSubSocket * socket + * cdef bool is_owner + */ + +struct __pyx_vtabstruct_6cereal_9messaging_13messaging_pyx_SubSocket { + PyObject *(*setPtr)(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *, SubSocket *); +}; +static struct __pyx_vtabstruct_6cereal_9messaging_13messaging_pyx_SubSocket *__pyx_vtabptr_6cereal_9messaging_13messaging_pyx_SubSocket; +/* #### Code section: utility_code_proto ### */ + +/* --- Runtime support code (head) --- */ +/* Refnanny.proto */ +#ifndef CYTHON_REFNANNY + #define CYTHON_REFNANNY 0 +#endif +#if CYTHON_REFNANNY + typedef struct { + void (*INCREF)(void*, PyObject*, Py_ssize_t); + void (*DECREF)(void*, PyObject*, Py_ssize_t); + void (*GOTREF)(void*, PyObject*, Py_ssize_t); + void (*GIVEREF)(void*, PyObject*, Py_ssize_t); + void* (*SetupContext)(const char*, Py_ssize_t, const char*); + void (*FinishContext)(void**); + } __Pyx_RefNannyAPIStruct; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNanny = NULL; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname); + #define __Pyx_RefNannyDeclarations void *__pyx_refnanny = NULL; +#ifdef WITH_THREAD + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + if (acquire_gil) {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + PyGILState_Release(__pyx_gilstate_save);\ + } else {\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + } + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } +#else + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__)) + #define __Pyx_RefNannyFinishContextNogil() __Pyx_RefNannyFinishContext() +#endif + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } + #define __Pyx_RefNannyFinishContext()\ + __Pyx_RefNanny->FinishContext(&__pyx_refnanny) + #define __Pyx_INCREF(r) __Pyx_RefNanny->INCREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_DECREF(r) __Pyx_RefNanny->DECREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GOTREF(r) __Pyx_RefNanny->GOTREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GIVEREF(r) __Pyx_RefNanny->GIVEREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_XINCREF(r) do { if((r) == NULL); else {__Pyx_INCREF(r); }} while(0) + #define __Pyx_XDECREF(r) do { if((r) == NULL); else {__Pyx_DECREF(r); }} while(0) + #define __Pyx_XGOTREF(r) do { if((r) == NULL); else {__Pyx_GOTREF(r); }} while(0) + #define __Pyx_XGIVEREF(r) do { if((r) == NULL); else {__Pyx_GIVEREF(r);}} while(0) +#else + #define __Pyx_RefNannyDeclarations + #define __Pyx_RefNannySetupContext(name, acquire_gil) + #define __Pyx_RefNannyFinishContextNogil() + #define __Pyx_RefNannyFinishContext() + #define __Pyx_INCREF(r) Py_INCREF(r) + #define __Pyx_DECREF(r) Py_DECREF(r) + #define __Pyx_GOTREF(r) + #define __Pyx_GIVEREF(r) + #define __Pyx_XINCREF(r) Py_XINCREF(r) + #define __Pyx_XDECREF(r) Py_XDECREF(r) + #define __Pyx_XGOTREF(r) + #define __Pyx_XGIVEREF(r) +#endif +#define __Pyx_Py_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; Py_XDECREF(tmp);\ + } while (0) +#define __Pyx_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_XDECREF(tmp);\ + } while (0) +#define __Pyx_DECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_DECREF(tmp);\ + } while (0) +#define __Pyx_CLEAR(r) do { PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);} while(0) +#define __Pyx_XCLEAR(r) do { if((r) != NULL) {PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);}} while(0) + +/* PyErrExceptionMatches.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_ExceptionMatches(err) __Pyx_PyErr_ExceptionMatchesInState(__pyx_tstate, err) +static CYTHON_INLINE int __Pyx_PyErr_ExceptionMatchesInState(PyThreadState* tstate, PyObject* err); +#else +#define __Pyx_PyErr_ExceptionMatches(err) PyErr_ExceptionMatches(err) +#endif + +/* PyThreadStateGet.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyThreadState_declare PyThreadState *__pyx_tstate; +#define __Pyx_PyThreadState_assign __pyx_tstate = __Pyx_PyThreadState_Current; +#if PY_VERSION_HEX >= 0x030C00A6 +#define __Pyx_PyErr_Occurred() (__pyx_tstate->current_exception != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->current_exception ? (PyObject*) Py_TYPE(__pyx_tstate->current_exception) : (PyObject*) NULL) +#else +#define __Pyx_PyErr_Occurred() (__pyx_tstate->curexc_type != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->curexc_type) +#endif +#else +#define __Pyx_PyThreadState_declare +#define __Pyx_PyThreadState_assign +#define __Pyx_PyErr_Occurred() (PyErr_Occurred() != NULL) +#define __Pyx_PyErr_CurrentExceptionType() PyErr_Occurred() +#endif + +/* PyErrFetchRestore.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_Clear() __Pyx_ErrRestore(NULL, NULL, NULL) +#define __Pyx_ErrRestoreWithState(type, value, tb) __Pyx_ErrRestoreInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) __Pyx_ErrFetchInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) __Pyx_ErrRestoreInState(__pyx_tstate, type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) __Pyx_ErrFetchInState(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb); +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A6 +#define __Pyx_PyErr_SetNone(exc) (Py_INCREF(exc), __Pyx_ErrRestore((exc), NULL, NULL)) +#else +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#endif +#else +#define __Pyx_PyErr_Clear() PyErr_Clear() +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#define __Pyx_ErrRestoreWithState(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestoreInState(tstate, type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchInState(tstate, type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) PyErr_Fetch(type, value, tb) +#endif + +/* PyObjectGetAttrStr.proto */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GetAttrStr(o,n) PyObject_GetAttr(o,n) +#endif + +/* PyObjectGetAttrStrNoError.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name); + +/* GetBuiltinName.proto */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name); + +/* TupleAndListFromArray.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n); +static CYTHON_INLINE PyObject* __Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n); +#endif + +/* IncludeStringH.proto */ +#include + +/* BytesEquals.proto */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals); + +/* UnicodeEquals.proto */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals); + +/* fastcall.proto */ +#if CYTHON_AVOID_BORROWED_REFS + #define __Pyx_Arg_VARARGS(args, i) PySequence_GetItem(args, i) +#elif CYTHON_ASSUME_SAFE_MACROS + #define __Pyx_Arg_VARARGS(args, i) PyTuple_GET_ITEM(args, i) +#else + #define __Pyx_Arg_VARARGS(args, i) PyTuple_GetItem(args, i) +#endif +#if CYTHON_AVOID_BORROWED_REFS + #define __Pyx_Arg_NewRef_VARARGS(arg) __Pyx_NewRef(arg) + #define __Pyx_Arg_XDECREF_VARARGS(arg) Py_XDECREF(arg) +#else + #define __Pyx_Arg_NewRef_VARARGS(arg) arg + #define __Pyx_Arg_XDECREF_VARARGS(arg) +#endif +#define __Pyx_NumKwargs_VARARGS(kwds) PyDict_Size(kwds) +#define __Pyx_KwValues_VARARGS(args, nargs) NULL +#define __Pyx_GetKwValue_VARARGS(kw, kwvalues, s) __Pyx_PyDict_GetItemStrWithError(kw, s) +#define __Pyx_KwargsAsDict_VARARGS(kw, kwvalues) PyDict_Copy(kw) +#if CYTHON_METH_FASTCALL + #define __Pyx_Arg_FASTCALL(args, i) args[i] + #define __Pyx_NumKwargs_FASTCALL(kwds) PyTuple_GET_SIZE(kwds) + #define __Pyx_KwValues_FASTCALL(args, nargs) ((args) + (nargs)) + static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 + CYTHON_UNUSED static PyObject *__Pyx_KwargsAsDict_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues); + #else + #define __Pyx_KwargsAsDict_FASTCALL(kw, kwvalues) _PyStack_AsDict(kwvalues, kw) + #endif + #define __Pyx_Arg_NewRef_FASTCALL(arg) arg /* no-op, __Pyx_Arg_FASTCALL is direct and this needs + to have the same reference counting */ + #define __Pyx_Arg_XDECREF_FASTCALL(arg) +#else + #define __Pyx_Arg_FASTCALL __Pyx_Arg_VARARGS + #define __Pyx_NumKwargs_FASTCALL __Pyx_NumKwargs_VARARGS + #define __Pyx_KwValues_FASTCALL __Pyx_KwValues_VARARGS + #define __Pyx_GetKwValue_FASTCALL __Pyx_GetKwValue_VARARGS + #define __Pyx_KwargsAsDict_FASTCALL __Pyx_KwargsAsDict_VARARGS + #define __Pyx_Arg_NewRef_FASTCALL(arg) __Pyx_Arg_NewRef_VARARGS(arg) + #define __Pyx_Arg_XDECREF_FASTCALL(arg) __Pyx_Arg_XDECREF_VARARGS(arg) +#endif +#if CYTHON_COMPILING_IN_CPYTHON && CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_VARARGS(args, start), stop - start) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_FASTCALL(args, start), stop - start) +#else +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) PyTuple_GetSlice(args, start, stop) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) PyTuple_GetSlice(args, start, stop) +#endif + +/* RaiseDoubleKeywords.proto */ +static void __Pyx_RaiseDoubleKeywordsError(const char* func_name, PyObject* kw_name); + +/* ParseKeywords.proto */ +static int __Pyx_ParseOptionalKeywords(PyObject *kwds, PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, PyObject *values[], Py_ssize_t num_pos_args, + const char* function_name); + +/* RaiseArgTupleInvalid.proto */ +static void __Pyx_RaiseArgtupleInvalid(const char* func_name, int exact, + Py_ssize_t num_min, Py_ssize_t num_max, Py_ssize_t num_found); + +/* PyFunctionFastCall.proto */ +#if CYTHON_FAST_PYCALL +#if !CYTHON_VECTORCALL +#define __Pyx_PyFunction_FastCall(func, args, nargs)\ + __Pyx_PyFunction_FastCallDict((func), (args), (nargs), NULL) +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs); +#endif +#define __Pyx_BUILD_ASSERT_EXPR(cond)\ + (sizeof(char [1 - 2*!(cond)]) - 1) +#ifndef Py_MEMBER_SIZE +#define Py_MEMBER_SIZE(type, member) sizeof(((type *)0)->member) +#endif +#if !CYTHON_VECTORCALL +#if PY_VERSION_HEX >= 0x03080000 + #include "frameobject.h" +#if PY_VERSION_HEX >= 0x030b00a6 && !CYTHON_COMPILING_IN_LIMITED_API + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif + #define __Pxy_PyFrame_Initialize_Offsets() + #define __Pyx_PyFrame_GetLocalsplus(frame) ((frame)->f_localsplus) +#else + static size_t __pyx_pyframe_localsplus_offset = 0; + #include "frameobject.h" + #define __Pxy_PyFrame_Initialize_Offsets()\ + ((void)__Pyx_BUILD_ASSERT_EXPR(sizeof(PyFrameObject) == offsetof(PyFrameObject, f_localsplus) + Py_MEMBER_SIZE(PyFrameObject, f_localsplus)),\ + (void)(__pyx_pyframe_localsplus_offset = ((size_t)PyFrame_Type.tp_basicsize) - Py_MEMBER_SIZE(PyFrameObject, f_localsplus))) + #define __Pyx_PyFrame_GetLocalsplus(frame)\ + (assert(__pyx_pyframe_localsplus_offset), (PyObject **)(((char *)(frame)) + __pyx_pyframe_localsplus_offset)) +#endif +#endif +#endif + +/* PyObjectCall.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw); +#else +#define __Pyx_PyObject_Call(func, arg, kw) PyObject_Call(func, arg, kw) +#endif + +/* PyObjectCallMethO.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg); +#endif + +/* PyObjectFastCall.proto */ +#define __Pyx_PyObject_FastCall(func, args, nargs) __Pyx_PyObject_FastCallDict(func, args, (size_t)(nargs), NULL) +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs); + +/* PyObjectFormatSimple.proto */ +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + PyObject_Format(s, f)) +#elif PY_MAJOR_VERSION < 3 + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + likely(PyString_CheckExact(s)) ? PyUnicode_FromEncodedObject(s, NULL, "strict") :\ + PyObject_Format(s, f)) +#elif CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + likely(PyLong_CheckExact(s)) ? PyLong_Type.tp_repr(s) :\ + likely(PyFloat_CheckExact(s)) ? PyFloat_Type.tp_repr(s) :\ + PyObject_Format(s, f)) +#else + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + PyObject_Format(s, f)) +#endif + +/* PyUnicode_Unicode.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_Unicode(PyObject *obj); + +/* decode_c_string_utf16.proto */ +static CYTHON_INLINE PyObject *__Pyx_PyUnicode_DecodeUTF16(const char *s, Py_ssize_t size, const char *errors) { + int byteorder = 0; + return PyUnicode_DecodeUTF16(s, size, errors, &byteorder); +} +static CYTHON_INLINE PyObject *__Pyx_PyUnicode_DecodeUTF16LE(const char *s, Py_ssize_t size, const char *errors) { + int byteorder = -1; + return PyUnicode_DecodeUTF16(s, size, errors, &byteorder); +} +static CYTHON_INLINE PyObject *__Pyx_PyUnicode_DecodeUTF16BE(const char *s, Py_ssize_t size, const char *errors) { + int byteorder = 1; + return PyUnicode_DecodeUTF16(s, size, errors, &byteorder); +} + +/* decode_c_string.proto */ +static CYTHON_INLINE PyObject* __Pyx_decode_c_string( + const char* cstring, Py_ssize_t start, Py_ssize_t stop, + const char* encoding, const char* errors, + PyObject* (*decode_func)(const char *s, Py_ssize_t size, const char *errors)); + +/* JoinPyUnicode.proto */ +static PyObject* __Pyx_PyUnicode_Join(PyObject* value_tuple, Py_ssize_t value_count, Py_ssize_t result_ulength, + Py_UCS4 max_char); + +/* MoveIfSupported.proto */ +#if CYTHON_USE_CPP_STD_MOVE + #include + #define __PYX_STD_MOVE_IF_SUPPORTED(x) std::move(x) +#else + #define __PYX_STD_MOVE_IF_SUPPORTED(x) x +#endif + +/* ArgTypeTest.proto */ +#define __Pyx_ArgTypeTest(obj, type, none_allowed, name, exact)\ + ((likely(__Pyx_IS_TYPE(obj, type) | (none_allowed && (obj == Py_None)))) ? 1 :\ + __Pyx__ArgTypeTest(obj, type, name, exact)) +static int __Pyx__ArgTypeTest(PyObject *obj, PyTypeObject *type, const char *name, int exact); + +/* KeywordStringCheck.proto */ +static int __Pyx_CheckKeywordStrings(PyObject *kw, const char* function_name, int kw_allowed); + +/* RaiseException.proto */ +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause); + +/* PyObjectCallNoArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func); + +/* ListAppend.proto */ +#if CYTHON_USE_PYLIST_INTERNALS && CYTHON_ASSUME_SAFE_MACROS +static CYTHON_INLINE int __Pyx_PyList_Append(PyObject* list, PyObject* x) { + PyListObject* L = (PyListObject*) list; + Py_ssize_t len = Py_SIZE(list); + if (likely(L->allocated > len) & likely(len > (L->allocated >> 1))) { + Py_INCREF(x); + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 + L->ob_item[len] = x; + #else + PyList_SET_ITEM(list, len, x); + #endif + __Pyx_SET_SIZE(list, len + 1); + return 0; + } + return PyList_Append(list, x); +} +#else +#define __Pyx_PyList_Append(L,x) PyList_Append(L,x) +#endif + +/* PyDictVersioning.proto */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +#define __PYX_DICT_VERSION_INIT ((PY_UINT64_T) -1) +#define __PYX_GET_DICT_VERSION(dict) (((PyDictObject*)(dict))->ma_version_tag) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var)\ + (version_var) = __PYX_GET_DICT_VERSION(dict);\ + (cache_var) = (value); +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + if (likely(__PYX_GET_DICT_VERSION(DICT) == __pyx_dict_version)) {\ + (VAR) = __pyx_dict_cached_value;\ + } else {\ + (VAR) = __pyx_dict_cached_value = (LOOKUP);\ + __pyx_dict_version = __PYX_GET_DICT_VERSION(DICT);\ + }\ +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj); +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj); +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version); +#else +#define __PYX_GET_DICT_VERSION(dict) (0) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var) +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) (VAR) = (LOOKUP); +#endif + +/* GetModuleGlobalName.proto */ +#if CYTHON_USE_DICT_VERSIONS +#define __Pyx_GetModuleGlobalName(var, name) do {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + (var) = (likely(__pyx_dict_version == __PYX_GET_DICT_VERSION(__pyx_d))) ?\ + (likely(__pyx_dict_cached_value) ? __Pyx_NewRef(__pyx_dict_cached_value) : __Pyx_GetBuiltinName(name)) :\ + __Pyx__GetModuleGlobalName(name, &__pyx_dict_version, &__pyx_dict_cached_value);\ +} while(0) +#define __Pyx_GetModuleGlobalNameUncached(var, name) do {\ + PY_UINT64_T __pyx_dict_version;\ + PyObject *__pyx_dict_cached_value;\ + (var) = __Pyx__GetModuleGlobalName(name, &__pyx_dict_version, &__pyx_dict_cached_value);\ +} while(0) +static PyObject *__Pyx__GetModuleGlobalName(PyObject *name, PY_UINT64_T *dict_version, PyObject **dict_cached_value); +#else +#define __Pyx_GetModuleGlobalName(var, name) (var) = __Pyx__GetModuleGlobalName(name) +#define __Pyx_GetModuleGlobalNameUncached(var, name) (var) = __Pyx__GetModuleGlobalName(name) +static CYTHON_INLINE PyObject *__Pyx__GetModuleGlobalName(PyObject *name); +#endif + +/* IncludeStructmemberH.proto */ +#include + +/* FixUpExtensionType.proto */ +#if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type); +#endif + +/* PyObjectCallOneArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg); + +/* PyObjectGetMethod.proto */ +static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method); + +/* PyObjectCallMethod0.proto */ +static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name); + +/* ValidateBasesTuple.proto */ +#if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases); +#endif + +/* PyType_Ready.proto */ +CYTHON_UNUSED static int __Pyx_PyType_Ready(PyTypeObject *t); + +/* PyObject_GenericGetAttrNoDict.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttrNoDict PyObject_GenericGetAttr +#endif + +/* PyObject_GenericGetAttr.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttr PyObject_GenericGetAttr +#endif + +/* SetVTable.proto */ +static int __Pyx_SetVtable(PyTypeObject* typeptr , void* vtable); + +/* GetVTable.proto */ +static void* __Pyx_GetVtable(PyTypeObject *type); + +/* MergeVTables.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_MergeVtables(PyTypeObject *type); +#endif + +/* SetupReduce.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce(PyObject* type_obj); +#endif + +/* Import.proto */ +static PyObject *__Pyx_Import(PyObject *name, PyObject *from_list, int level); + +/* ImportDottedModule.proto */ +static PyObject *__Pyx_ImportDottedModule(PyObject *name, PyObject *parts_tuple); +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_ImportDottedModule_WalkParts(PyObject *module, PyObject *name, PyObject *parts_tuple); +#endif + +/* Py3UpdateBases.proto */ +static PyObject* __Pyx_PEP560_update_bases(PyObject *bases); + +/* CalculateMetaclass.proto */ +static PyObject *__Pyx_CalculateMetaclass(PyTypeObject *metaclass, PyObject *bases); + +/* FetchSharedCythonModule.proto */ +static PyObject *__Pyx_FetchSharedCythonABIModule(void); + +/* FetchCommonType.proto */ +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type); +#else +static PyTypeObject* __Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases); +#endif + +/* PyMethodNew.proto */ +#if CYTHON_COMPILING_IN_LIMITED_API +static PyObject *__Pyx_PyMethod_New(PyObject *func, PyObject *self, PyObject *typ) { + PyObject *typesModule=NULL, *methodType=NULL, *result=NULL; + CYTHON_UNUSED_VAR(typ); + if (!self) + return __Pyx_NewRef(func); + typesModule = PyImport_ImportModule("types"); + if (!typesModule) return NULL; + methodType = PyObject_GetAttrString(typesModule, "MethodType"); + Py_DECREF(typesModule); + if (!methodType) return NULL; + result = PyObject_CallFunctionObjArgs(methodType, func, self, NULL); + Py_DECREF(methodType); + return result; +} +#elif PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_PyMethod_New(PyObject *func, PyObject *self, PyObject *typ) { + CYTHON_UNUSED_VAR(typ); + if (!self) + return __Pyx_NewRef(func); + return PyMethod_New(func, self); +} +#else + #define __Pyx_PyMethod_New PyMethod_New +#endif + +/* PyVectorcallFastCallDict.proto */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw); +#endif + +/* CythonFunctionShared.proto */ +#define __Pyx_CyFunction_USED +#define __Pyx_CYFUNCTION_STATICMETHOD 0x01 +#define __Pyx_CYFUNCTION_CLASSMETHOD 0x02 +#define __Pyx_CYFUNCTION_CCLASS 0x04 +#define __Pyx_CYFUNCTION_COROUTINE 0x08 +#define __Pyx_CyFunction_GetClosure(f)\ + (((__pyx_CyFunctionObject *) (f))->func_closure) +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_CyFunction_GetClassObj(f)\ + (((__pyx_CyFunctionObject *) (f))->func_classobj) +#else + #define __Pyx_CyFunction_GetClassObj(f)\ + ((PyObject*) ((PyCMethodObject *) (f))->mm_class) +#endif +#define __Pyx_CyFunction_SetClassObj(f, classobj)\ + __Pyx__CyFunction_SetClassObj((__pyx_CyFunctionObject *) (f), (classobj)) +#define __Pyx_CyFunction_Defaults(type, f)\ + ((type *)(((__pyx_CyFunctionObject *) (f))->defaults)) +#define __Pyx_CyFunction_SetDefaultsGetter(f, g)\ + ((__pyx_CyFunctionObject *) (f))->defaults_getter = (g) +typedef struct { +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject_HEAD + PyObject *func; +#elif PY_VERSION_HEX < 0x030900B1 + PyCFunctionObject func; +#else + PyCMethodObject func; +#endif +#if CYTHON_BACKPORT_VECTORCALL + __pyx_vectorcallfunc func_vectorcall; +#endif +#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API + PyObject *func_weakreflist; +#endif + PyObject *func_dict; + PyObject *func_name; + PyObject *func_qualname; + PyObject *func_doc; + PyObject *func_globals; + PyObject *func_code; + PyObject *func_closure; +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + PyObject *func_classobj; +#endif + void *defaults; + int defaults_pyobjects; + size_t defaults_size; + int flags; + PyObject *defaults_tuple; + PyObject *defaults_kwdict; + PyObject *(*defaults_getter)(PyObject *); + PyObject *func_annotations; + PyObject *func_is_coroutine; +} __pyx_CyFunctionObject; +#undef __Pyx_CyOrPyCFunction_Check +#define __Pyx_CyFunction_Check(obj) __Pyx_TypeCheck(obj, __pyx_CyFunctionType) +#define __Pyx_CyOrPyCFunction_Check(obj) __Pyx_TypeCheck2(obj, __pyx_CyFunctionType, &PyCFunction_Type) +#define __Pyx_CyFunction_CheckExact(obj) __Pyx_IS_TYPE(obj, __pyx_CyFunctionType) +static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc); +#undef __Pyx_IsSameCFunction +#define __Pyx_IsSameCFunction(func, cfunc) __Pyx__IsSameCyOrCFunction(func, cfunc) +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject* op, PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj); +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *m, + size_t size, + int pyobjects); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *m, + PyObject *tuple); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *m, + PyObject *dict); +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *m, + PyObject *dict); +static int __pyx_CyFunction_init(PyObject *module); +#if CYTHON_METH_FASTCALL +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +#if CYTHON_BACKPORT_VECTORCALL +#define __Pyx_CyFunction_func_vectorcall(f) (((__pyx_CyFunctionObject*)f)->func_vectorcall) +#else +#define __Pyx_CyFunction_func_vectorcall(f) (((PyCFunctionObject*)f)->vectorcall) +#endif +#endif + +/* CythonFunction.proto */ +static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); + +/* SetNameInClass.proto */ +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030500A1 && PY_VERSION_HEX < 0x030d0000 +#define __Pyx_SetNameInClass(ns, name, value)\ + (likely(PyDict_CheckExact(ns)) ? _PyDict_SetItem_KnownHash(ns, name, value, ((PyASCIIObject *) name)->hash) : PyObject_SetItem(ns, name, value)) +#elif CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_SetNameInClass(ns, name, value)\ + (likely(PyDict_CheckExact(ns)) ? PyDict_SetItem(ns, name, value) : PyObject_SetItem(ns, name, value)) +#else +#define __Pyx_SetNameInClass(ns, name, value) PyObject_SetItem(ns, name, value) +#endif + +/* PyObjectCall2Args.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call2Args(PyObject* function, PyObject* arg1, PyObject* arg2); + +/* PyObjectLookupSpecial.proto */ +#if CYTHON_USE_PYTYPE_LOOKUP && CYTHON_USE_TYPE_SLOTS +#define __Pyx_PyObject_LookupSpecialNoError(obj, attr_name) __Pyx__PyObject_LookupSpecial(obj, attr_name, 0) +#define __Pyx_PyObject_LookupSpecial(obj, attr_name) __Pyx__PyObject_LookupSpecial(obj, attr_name, 1) +static CYTHON_INLINE PyObject* __Pyx__PyObject_LookupSpecial(PyObject* obj, PyObject* attr_name, int with_error); +#else +#define __Pyx_PyObject_LookupSpecialNoError(o,n) __Pyx_PyObject_GetAttrStrNoError(o,n) +#define __Pyx_PyObject_LookupSpecial(o,n) __Pyx_PyObject_GetAttrStr(o,n) +#endif + +/* Py3ClassCreate.proto */ +static PyObject *__Pyx_Py3MetaclassPrepare(PyObject *metaclass, PyObject *bases, PyObject *name, PyObject *qualname, + PyObject *mkw, PyObject *modname, PyObject *doc); +static PyObject *__Pyx_Py3ClassCreate(PyObject *metaclass, PyObject *name, PyObject *bases, PyObject *dict, + PyObject *mkw, int calculate_metaclass, int allow_py2_metaclass); + +/* CyFunctionClassCell.proto */ +static int __Pyx_CyFunction_InitClassCell(PyObject *cyfunctions, PyObject *classobj); + +/* CLineInTraceback.proto */ +#ifdef CYTHON_CLINE_IN_TRACEBACK +#define __Pyx_CLineForTraceback(tstate, c_line) (((CYTHON_CLINE_IN_TRACEBACK)) ? c_line : 0) +#else +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line); +#endif + +/* CodeObjectCache.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +typedef struct { + PyCodeObject* code_object; + int code_line; +} __Pyx_CodeObjectCacheEntry; +struct __Pyx_CodeObjectCache { + int count; + int max_count; + __Pyx_CodeObjectCacheEntry* entries; +}; +static struct __Pyx_CodeObjectCache __pyx_code_cache = {0,0,NULL}; +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line); +static PyCodeObject *__pyx_find_code_object(int code_line); +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object); +#endif + +/* AddTraceback.proto */ +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename); + +/* None.proto */ +#include + +/* GCCDiagnostics.proto */ +#if !defined(__INTEL_COMPILER) && defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 6)) +#define __Pyx_HAS_GCC_DIAGNOSTIC +#endif + +/* CppExceptionConversion.proto */ +#ifndef __Pyx_CppExn2PyErr +#include +#include +#include +#include +static void __Pyx_CppExn2PyErr() { + try { + if (PyErr_Occurred()) + ; // let the latest Python exn pass through and ignore the current one + else + throw; + } catch (const std::bad_alloc& exn) { + PyErr_SetString(PyExc_MemoryError, exn.what()); + } catch (const std::bad_cast& exn) { + PyErr_SetString(PyExc_TypeError, exn.what()); + } catch (const std::bad_typeid& exn) { + PyErr_SetString(PyExc_TypeError, exn.what()); + } catch (const std::domain_error& exn) { + PyErr_SetString(PyExc_ValueError, exn.what()); + } catch (const std::invalid_argument& exn) { + PyErr_SetString(PyExc_ValueError, exn.what()); + } catch (const std::ios_base::failure& exn) { + PyErr_SetString(PyExc_IOError, exn.what()); + } catch (const std::out_of_range& exn) { + PyErr_SetString(PyExc_IndexError, exn.what()); + } catch (const std::overflow_error& exn) { + PyErr_SetString(PyExc_OverflowError, exn.what()); + } catch (const std::range_error& exn) { + PyErr_SetString(PyExc_ArithmeticError, exn.what()); + } catch (const std::underflow_error& exn) { + PyErr_SetString(PyExc_ArithmeticError, exn.what()); + } catch (const std::exception& exn) { + PyErr_SetString(PyExc_RuntimeError, exn.what()); + } + catch (...) + { + PyErr_SetString(PyExc_RuntimeError, "Unknown exception"); + } +} +#endif + +/* CIntFromPy.proto */ +static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_int(int value); + +/* CIntFromPy.proto */ +static CYTHON_INLINE size_t __Pyx_PyInt_As_size_t(PyObject *); + +/* FormatTypeName.proto */ +#if CYTHON_COMPILING_IN_LIMITED_API +typedef PyObject *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%U" +static __Pyx_TypeName __Pyx_PyType_GetName(PyTypeObject* tp); +#define __Pyx_DECREF_TypeName(obj) Py_XDECREF(obj) +#else +typedef const char *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%.200s" +#define __Pyx_PyType_GetName(tp) ((tp)->tp_name) +#define __Pyx_DECREF_TypeName(obj) +#endif + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value); + +/* CIntFromPy.proto */ +static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *); + +/* FastTypeChecks.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_TypeCheck(obj, type) __Pyx_IsSubtype(Py_TYPE(obj), (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) __Pyx_IsAnySubtype2(Py_TYPE(obj), (PyTypeObject *)type1, (PyTypeObject *)type2) +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches(PyObject *err, PyObject *type); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches2(PyObject *err, PyObject *type1, PyObject *type2); +#else +#define __Pyx_TypeCheck(obj, type) PyObject_TypeCheck(obj, (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) (PyObject_TypeCheck(obj, (PyTypeObject *)type1) || PyObject_TypeCheck(obj, (PyTypeObject *)type2)) +#define __Pyx_PyErr_GivenExceptionMatches(err, type) PyErr_GivenExceptionMatches(err, type) +#define __Pyx_PyErr_GivenExceptionMatches2(err, type1, type2) (PyErr_GivenExceptionMatches(err, type1) || PyErr_GivenExceptionMatches(err, type2)) +#endif +#define __Pyx_PyErr_ExceptionMatches2(err1, err2) __Pyx_PyErr_GivenExceptionMatches2(__Pyx_PyErr_CurrentExceptionType(), err1, err2) +#define __Pyx_PyException_Check(obj) __Pyx_TypeCheck(obj, PyExc_Exception) + +/* CheckBinaryVersion.proto */ +static unsigned long __Pyx_get_runtime_version(void); +static int __Pyx_check_binary_version(unsigned long ct_version, unsigned long rt_version, int allow_newer); + +/* InitStrings.proto */ +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t); + +/* #### Code section: module_declarations ### */ +static PyObject *__pyx_f_6cereal_9messaging_13messaging_pyx_5Event_setEvent(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *__pyx_v_self, Event __pyx_v_event); /* proto*/ +static PyObject *__pyx_f_6cereal_9messaging_13messaging_pyx_9SubSocket_setPtr(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *__pyx_v_self, SubSocket *__pyx_v_ptr); /* proto*/ + +/* Module declarations from "libc.string" */ + +/* Module declarations from "libcpp.string" */ + +/* Module declarations from "libcpp.vector" */ + +/* Module declarations from "libcpp" */ + +/* Module declarations from "libc" */ + +/* Module declarations from "libc.errno" */ + +/* Module declarations from "cereal.messaging.messaging" */ + +/* Module declarations from "cereal.messaging.messaging_pyx" */ +static std::string __pyx_convert_string_from_py_std__in_string(PyObject *); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyObject_string_to_py_std__in_string(std::string const &); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyUnicode_string_to_py_std__in_string(std::string const &); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyStr_string_to_py_std__in_string(std::string const &); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyBytes_string_to_py_std__in_string(std::string const &); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyByteArray_string_to_py_std__in_string(std::string const &); /*proto*/ +/* #### Code section: typeinfo ### */ +/* #### Code section: before_global_var ### */ +#define __Pyx_MODULE_NAME "cereal.messaging.messaging_pyx" +extern int __pyx_module_is_main_cereal__messaging__messaging_pyx; +int __pyx_module_is_main_cereal__messaging__messaging_pyx = 0; + +/* Implementation of "cereal.messaging.messaging_pyx" */ +/* #### Code section: global_var ### */ +static PyObject *__pyx_builtin_super; +static PyObject *__pyx_builtin_TypeError; +static PyObject *__pyx_builtin_print; +/* #### Code section: string_decls ### */ +static const char __pyx_k_[] = ""; +static const char __pyx_k_m[] = "m"; +static const char __pyx_k_r[] = "r"; +static const char __pyx_k_s[] = "s"; +static const char __pyx_k_t[] = "t"; +static const char __pyx_k__2[] = ": "; +static const char __pyx_k__5[] = "*"; +static const char __pyx_k_gc[] = "gc"; +static const char __pyx_k_sz[] = "sz"; +static const char __pyx_k__53[] = "?"; +static const char __pyx_k_doc[] = "__doc__"; +static const char __pyx_k_msg[] = "msg"; +static const char __pyx_k_ptr[] = "ptr"; +static const char __pyx_k_set[] = "set"; +static const char __pyx_k_sys[] = "sys"; +static const char __pyx_k_None[] = "None"; +static const char __pyx_k_data[] = "data"; +static const char __pyx_k_dict[] = "__dict__"; +static const char __pyx_k_exit[] = "exit"; +static const char __pyx_k_init[] = "__init__"; +static const char __pyx_k_main[] = "__main__"; +static const char __pyx_k_name[] = "__name__"; +static const char __pyx_k_peek[] = "peek"; +static const char __pyx_k_poll[] = "poll"; +static const char __pyx_k_self[] = "self"; +static const char __pyx_k_send[] = "send"; +static const char __pyx_k_spec[] = "__spec__"; +static const char __pyx_k_term[] = "term"; +static const char __pyx_k_test[] = "__test__"; +static const char __pyx_k_wait[] = "wait"; +static const char __pyx_k_with[] = "with "; +static const char __pyx_k_Event[] = "Event"; +static const char __pyx_k_clear[] = "clear"; +static const char __pyx_k_event[] = "event"; +static const char __pyx_k_items[] = "items"; +static const char __pyx_k_print[] = "print"; +static const char __pyx_k_super[] = "super"; +static const char __pyx_k_utf_8[] = "utf-8"; +static const char __pyx_k_Poller[] = "Poller"; +static const char __pyx_k_decode[] = "decode"; +static const char __pyx_k_enable[] = "enable"; +static const char __pyx_k_events[] = "events"; +static const char __pyx_k_import[] = "__import__"; +static const char __pyx_k_length[] = "length"; +static const char __pyx_k_module[] = "__module__"; +static const char __pyx_k_prefix[] = "prefix"; +static const char __pyx_k_reduce[] = "__reduce__"; +static const char __pyx_k_result[] = "result"; +static const char __pyx_k_socket[] = "socket"; +static const char __pyx_k_suffix[] = "suffix"; +static const char __pyx_k_Context[] = "Context"; +static const char __pyx_k_address[] = "address"; +static const char __pyx_k_connect[] = "connect"; +static const char __pyx_k_context[] = "context"; +static const char __pyx_k_disable[] = "disable"; +static const char __pyx_k_enabled[] = "enabled"; +static const char __pyx_k_message[] = "message"; +static const char __pyx_k_prepare[] = "__prepare__"; +static const char __pyx_k_receive[] = "receive"; +static const char __pyx_k_sockets[] = "sockets"; +static const char __pyx_k_timeout[] = "timeout"; +static const char __pyx_k_conflate[] = "conflate"; +static const char __pyx_k_endpoint[] = "endpoint"; +static const char __pyx_k_getstate[] = "__getstate__"; +static const char __pyx_k_override[] = "override"; +static const char __pyx_k_qualname[] = "__qualname__"; +static const char __pyx_k_set_name[] = "__set_name__"; +static const char __pyx_k_setstate[] = "__setstate__"; +static const char __pyx_k_127_0_0_1[] = "127.0.0.1"; +static const char __pyx_k_Event_set[] = "Event.set"; +static const char __pyx_k_PubSocket[] = "PubSocket"; +static const char __pyx_k_SubSocket[] = "SubSocket"; +static const char __pyx_k_TypeError[] = "TypeError"; +static const char __pyx_k_isenabled[] = "isenabled"; +static const char __pyx_k_metaclass[] = "__metaclass__"; +static const char __pyx_k_pyx_state[] = "__pyx_state"; +static const char __pyx_k_reduce_ex[] = "__reduce_ex__"; +static const char __pyx_k_Event_peek[] = "Event.peek"; +static const char __pyx_k_Event_wait[] = "Event.wait"; +static const char __pyx_k_identifier[] = "identifier"; +static const char __pyx_k_pyx_vtable[] = "__pyx_vtable__"; +static const char __pyx_k_setTimeout[] = "setTimeout"; +static const char __pyx_k_Event_clear[] = "Event.clear"; +static const char __pyx_k_Poller_poll[] = "Poller.poll"; +static const char __pyx_k_mro_entries[] = "__mro_entries__"; +static const char __pyx_k_Context_term[] = "Context.term"; +static const char __pyx_k_initializing[] = "_initializing"; +static const char __pyx_k_is_coroutine[] = "_is_coroutine"; +static const char __pyx_k_non_blocking[] = "non_blocking"; +static const char __pyx_k_stringsource[] = ""; +static const char __pyx_k_init_subclass[] = "__init_subclass__"; +static const char __pyx_k_reduce_cython[] = "__reduce_cython__"; +static const char __pyx_k_MessagingError[] = "MessagingError"; +static const char __pyx_k_PubSocket_send[] = "PubSocket.send"; +static const char __pyx_k_registerSocket[] = "registerSocket"; +static const char __pyx_k_get_fake_prefix[] = "get_fake_prefix"; +static const char __pyx_k_set_fake_prefix[] = "set_fake_prefix"; +static const char __pyx_k_setstate_cython[] = "__setstate_cython__"; +static const char __pyx_k_Messaging_failure[] = "Messaging failure "; +static const char __pyx_k_PubSocket_connect[] = "PubSocket.connect"; +static const char __pyx_k_SocketEventHandle[] = "SocketEventHandle"; +static const char __pyx_k_SubSocket_connect[] = "SubSocket.connect"; +static const char __pyx_k_SubSocket_receive[] = "SubSocket.receive"; +static const char __pyx_k_asyncio_coroutines[] = "asyncio.coroutines"; +static const char __pyx_k_cline_in_traceback[] = "cline_in_traceback"; +static const char __pyx_k_delete_fake_prefix[] = "delete_fake_prefix"; +static const char __pyx_k_toggle_fake_events[] = "toggle_fake_events"; +static const char __pyx_k_wait_for_one_event[] = "wait_for_one_event"; +static const char __pyx_k_all_readers_updated[] = "all_readers_updated"; +static const char __pyx_k_SubSocket_setTimeout[] = "SubSocket.setTimeout"; +static const char __pyx_k_Event___reduce_cython[] = "Event.__reduce_cython__"; +static const char __pyx_k_MessagingError___init[] = "MessagingError.__init__"; +static const char __pyx_k_Poller_registerSocket[] = "Poller.registerSocket"; +static const char __pyx_k_Poller___reduce_cython[] = "Poller.__reduce_cython__"; +static const char __pyx_k_Context___reduce_cython[] = "Context.__reduce_cython__"; +static const char __pyx_k_Event___setstate_cython[] = "Event.__setstate_cython__"; +static const char __pyx_k_MultiplePublishersError[] = "MultiplePublishersError"; +static const char __pyx_k_SIGINT_received_exiting[] = "SIGINT received, exiting"; +static const char __pyx_k_Poller___setstate_cython[] = "Poller.__setstate_cython__"; +static const char __pyx_k_Context___setstate_cython[] = "Context.__setstate_cython__"; +static const char __pyx_k_PubSocket___reduce_cython[] = "PubSocket.__reduce_cython__"; +static const char __pyx_k_SubSocket___reduce_cython[] = "SubSocket.__reduce_cython__"; +static const char __pyx_k_PubSocket___setstate_cython[] = "PubSocket.__setstate_cython__"; +static const char __pyx_k_SubSocket___setstate_cython[] = "SubSocket.__setstate_cython__"; +static const char __pyx_k_PubSocket_all_readers_updated[] = "PubSocket.all_readers_updated"; +static const char __pyx_k_cereal_messaging_messaging_pyx[] = "cereal.messaging.messaging_pyx"; +static const char __pyx_k_SocketEventHandle___reduce_cytho[] = "SocketEventHandle.__reduce_cython__"; +static const char __pyx_k_SocketEventHandle___setstate_cyt[] = "SocketEventHandle.__setstate_cython__"; +static const char __pyx_k_cereal_messaging_messaging_pyx_p[] = "cereal/messaging/messaging_pyx.pyx"; +static const char __pyx_k_no_default___reduce___due_to_non[] = "no default __reduce__ due to non-trivial __cinit__"; +/* #### Code section: decls ### */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_14MessagingError___init__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_self, PyObject *__pyx_v_endpoint); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_toggle_fake_events(CYTHON_UNUSED PyObject *__pyx_self, bool __pyx_v_enabled); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_2set_fake_prefix(CYTHON_UNUSED PyObject *__pyx_self, std::string __pyx_v_prefix); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_4get_fake_prefix(CYTHON_UNUSED PyObject *__pyx_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_6delete_fake_prefix(CYTHON_UNUSED PyObject *__pyx_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_8wait_for_one_event(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_events, int __pyx_v_timeout); /* proto */ +static int __pyx_pf_6cereal_9messaging_13messaging_pyx_5Event___cinit__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_2set(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_4clear(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_6wait(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *__pyx_v_self, int __pyx_v_timeout); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_8peek(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_2fd___get__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_3ptr___get__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_10__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_12__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle___cinit__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *__pyx_v_self, std::string __pyx_v_endpoint, std::string __pyx_v_identifier, bool __pyx_v_override); /* proto */ +static void __pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_2__dealloc__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_7enabled___get__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *__pyx_v_self); /* proto */ +static int __pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_7enabled_2__set__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *__pyx_v_self, bool __pyx_v_value); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_17recv_called_event___get__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_16recv_ready_event___get__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_4__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_6__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_pf_6cereal_9messaging_13messaging_pyx_7Context___cinit__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_7Context_2term(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *__pyx_v_self); /* proto */ +static void __pyx_pf_6cereal_9messaging_13messaging_pyx_7Context_4__dealloc__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_7Context_6__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_7Context_8__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_pf_6cereal_9messaging_13messaging_pyx_6Poller___cinit__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *__pyx_v_self); /* proto */ +static void __pyx_pf_6cereal_9messaging_13messaging_pyx_6Poller_2__dealloc__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_6Poller_4registerSocket(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *__pyx_v_self, struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *__pyx_v_socket); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_6Poller_6poll(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *__pyx_v_self, PyObject *__pyx_v_timeout); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_6Poller_8__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_6Poller_10__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_pf_6cereal_9messaging_13messaging_pyx_9SubSocket___cinit__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *__pyx_v_self); /* proto */ +static void __pyx_pf_6cereal_9messaging_13messaging_pyx_9SubSocket_2__dealloc__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_9SubSocket_4connect(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *__pyx_v_self, struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *__pyx_v_context, std::string __pyx_v_endpoint, std::string __pyx_v_address, bool __pyx_v_conflate); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_9SubSocket_6setTimeout(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *__pyx_v_self, int __pyx_v_timeout); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_9SubSocket_8receive(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *__pyx_v_self, bool __pyx_v_non_blocking); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_9SubSocket_10__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_9SubSocket_12__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_pf_6cereal_9messaging_13messaging_pyx_9PubSocket___cinit__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket *__pyx_v_self); /* proto */ +static void __pyx_pf_6cereal_9messaging_13messaging_pyx_9PubSocket_2__dealloc__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_9PubSocket_4connect(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket *__pyx_v_self, struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *__pyx_v_context, std::string __pyx_v_endpoint); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_9PubSocket_6send(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket *__pyx_v_self, PyObject *__pyx_v_data); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_9PubSocket_8all_readers_updated(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_9PubSocket_10__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_9PubSocket_12__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_tp_new_6cereal_9messaging_13messaging_pyx_Event(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_6cereal_9messaging_13messaging_pyx_SocketEventHandle(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_6cereal_9messaging_13messaging_pyx_Context(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_6cereal_9messaging_13messaging_pyx_Poller(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_6cereal_9messaging_13messaging_pyx_SubSocket(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_6cereal_9messaging_13messaging_pyx_PubSocket(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +/* #### Code section: late_includes ### */ +/* #### Code section: module_state ### */ +typedef struct { + PyObject *__pyx_d; + PyObject *__pyx_b; + PyObject *__pyx_cython_runtime; + PyObject *__pyx_empty_tuple; + PyObject *__pyx_empty_bytes; + PyObject *__pyx_empty_unicode; + #ifdef __Pyx_CyFunction_USED + PyTypeObject *__pyx_CyFunctionType; + #endif + #ifdef __Pyx_FusedFunction_USED + PyTypeObject *__pyx_FusedFunctionType; + #endif + #ifdef __Pyx_Generator_USED + PyTypeObject *__pyx_GeneratorType; + #endif + #ifdef __Pyx_IterableCoroutine_USED + PyTypeObject *__pyx_IterableCoroutineType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineAwaitType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineType; + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + PyObject *__pyx_type_6cereal_9messaging_13messaging_pyx_Event; + PyObject *__pyx_type_6cereal_9messaging_13messaging_pyx_SocketEventHandle; + PyObject *__pyx_type_6cereal_9messaging_13messaging_pyx_Context; + PyObject *__pyx_type_6cereal_9messaging_13messaging_pyx_Poller; + PyObject *__pyx_type_6cereal_9messaging_13messaging_pyx_SubSocket; + PyObject *__pyx_type_6cereal_9messaging_13messaging_pyx_PubSocket; + #endif + PyTypeObject *__pyx_ptype_6cereal_9messaging_13messaging_pyx_Event; + PyTypeObject *__pyx_ptype_6cereal_9messaging_13messaging_pyx_SocketEventHandle; + PyTypeObject *__pyx_ptype_6cereal_9messaging_13messaging_pyx_Context; + PyTypeObject *__pyx_ptype_6cereal_9messaging_13messaging_pyx_Poller; + PyTypeObject *__pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket; + PyTypeObject *__pyx_ptype_6cereal_9messaging_13messaging_pyx_PubSocket; + PyObject *__pyx_kp_b_; + PyObject *__pyx_kp_u_; + PyObject *__pyx_kp_b_127_0_0_1; + PyObject *__pyx_n_s_Context; + PyObject *__pyx_n_s_Context___reduce_cython; + PyObject *__pyx_n_s_Context___setstate_cython; + PyObject *__pyx_n_s_Context_term; + PyObject *__pyx_n_s_Event; + PyObject *__pyx_n_s_Event___reduce_cython; + PyObject *__pyx_n_s_Event___setstate_cython; + PyObject *__pyx_n_s_Event_clear; + PyObject *__pyx_n_s_Event_peek; + PyObject *__pyx_n_s_Event_set; + PyObject *__pyx_n_s_Event_wait; + PyObject *__pyx_n_s_MessagingError; + PyObject *__pyx_n_s_MessagingError___init; + PyObject *__pyx_kp_u_Messaging_failure; + PyObject *__pyx_n_s_MultiplePublishersError; + PyObject *__pyx_kp_u_None; + PyObject *__pyx_n_s_Poller; + PyObject *__pyx_n_s_Poller___reduce_cython; + PyObject *__pyx_n_s_Poller___setstate_cython; + PyObject *__pyx_n_s_Poller_poll; + PyObject *__pyx_n_s_Poller_registerSocket; + PyObject *__pyx_n_s_PubSocket; + PyObject *__pyx_n_s_PubSocket___reduce_cython; + PyObject *__pyx_n_s_PubSocket___setstate_cython; + PyObject *__pyx_n_s_PubSocket_all_readers_updated; + PyObject *__pyx_n_s_PubSocket_connect; + PyObject *__pyx_n_s_PubSocket_send; + PyObject *__pyx_kp_u_SIGINT_received_exiting; + PyObject *__pyx_n_s_SocketEventHandle; + PyObject *__pyx_n_s_SocketEventHandle___reduce_cytho; + PyObject *__pyx_n_s_SocketEventHandle___setstate_cyt; + PyObject *__pyx_n_s_SubSocket; + PyObject *__pyx_n_s_SubSocket___reduce_cython; + PyObject *__pyx_n_s_SubSocket___setstate_cython; + PyObject *__pyx_n_s_SubSocket_connect; + PyObject *__pyx_n_s_SubSocket_receive; + PyObject *__pyx_n_s_SubSocket_setTimeout; + PyObject *__pyx_n_s_TypeError; + PyObject *__pyx_kp_u__2; + PyObject *__pyx_n_s__5; + PyObject *__pyx_n_s__53; + PyObject *__pyx_n_s_address; + PyObject *__pyx_n_s_all_readers_updated; + PyObject *__pyx_n_s_asyncio_coroutines; + PyObject *__pyx_n_s_cereal_messaging_messaging_pyx; + PyObject *__pyx_kp_s_cereal_messaging_messaging_pyx_p; + PyObject *__pyx_n_s_clear; + PyObject *__pyx_n_s_cline_in_traceback; + PyObject *__pyx_n_s_conflate; + PyObject *__pyx_n_s_connect; + PyObject *__pyx_n_s_context; + PyObject *__pyx_n_s_data; + PyObject *__pyx_n_s_decode; + PyObject *__pyx_n_s_delete_fake_prefix; + PyObject *__pyx_n_s_dict; + PyObject *__pyx_kp_u_disable; + PyObject *__pyx_n_s_doc; + PyObject *__pyx_kp_u_enable; + PyObject *__pyx_n_s_enabled; + PyObject *__pyx_n_s_endpoint; + PyObject *__pyx_n_s_event; + PyObject *__pyx_n_s_events; + PyObject *__pyx_n_s_exit; + PyObject *__pyx_kp_u_gc; + PyObject *__pyx_n_s_get_fake_prefix; + PyObject *__pyx_n_s_getstate; + PyObject *__pyx_n_s_identifier; + PyObject *__pyx_n_s_import; + PyObject *__pyx_n_s_init; + PyObject *__pyx_n_s_init_subclass; + PyObject *__pyx_n_s_initializing; + PyObject *__pyx_n_s_is_coroutine; + PyObject *__pyx_kp_u_isenabled; + PyObject *__pyx_n_s_items; + PyObject *__pyx_n_s_length; + PyObject *__pyx_n_s_m; + PyObject *__pyx_n_s_main; + PyObject *__pyx_n_s_message; + PyObject *__pyx_n_s_metaclass; + PyObject *__pyx_n_s_module; + PyObject *__pyx_n_s_mro_entries; + PyObject *__pyx_n_s_msg; + PyObject *__pyx_n_s_name; + PyObject *__pyx_kp_s_no_default___reduce___due_to_non; + PyObject *__pyx_n_s_non_blocking; + PyObject *__pyx_n_s_override; + PyObject *__pyx_n_s_peek; + PyObject *__pyx_n_s_poll; + PyObject *__pyx_n_s_prefix; + PyObject *__pyx_n_s_prepare; + PyObject *__pyx_n_s_print; + PyObject *__pyx_n_s_ptr; + PyObject *__pyx_n_s_pyx_state; + PyObject *__pyx_n_s_pyx_vtable; + PyObject *__pyx_n_s_qualname; + PyObject *__pyx_n_s_r; + PyObject *__pyx_n_s_receive; + PyObject *__pyx_n_s_reduce; + PyObject *__pyx_n_s_reduce_cython; + PyObject *__pyx_n_s_reduce_ex; + PyObject *__pyx_n_s_registerSocket; + PyObject *__pyx_n_s_result; + PyObject *__pyx_n_s_s; + PyObject *__pyx_n_s_self; + PyObject *__pyx_n_s_send; + PyObject *__pyx_n_s_set; + PyObject *__pyx_n_s_setTimeout; + PyObject *__pyx_n_s_set_fake_prefix; + PyObject *__pyx_n_s_set_name; + PyObject *__pyx_n_s_setstate; + PyObject *__pyx_n_s_setstate_cython; + PyObject *__pyx_n_s_socket; + PyObject *__pyx_n_s_sockets; + PyObject *__pyx_n_s_spec; + PyObject *__pyx_kp_s_stringsource; + PyObject *__pyx_n_s_suffix; + PyObject *__pyx_n_s_super; + PyObject *__pyx_n_s_sys; + PyObject *__pyx_n_s_sz; + PyObject *__pyx_n_s_t; + PyObject *__pyx_n_s_term; + PyObject *__pyx_n_s_test; + PyObject *__pyx_n_s_timeout; + PyObject *__pyx_n_s_toggle_fake_events; + PyObject *__pyx_kp_u_utf_8; + PyObject *__pyx_n_s_wait; + PyObject *__pyx_n_s_wait_for_one_event; + PyObject *__pyx_kp_u_with; + PyObject *__pyx_int_1; + PyObject *__pyx_int_neg_1; + std::string __pyx_k__3; + PyObject *__pyx_tuple__4; + PyObject *__pyx_tuple__6; + PyObject *__pyx_tuple__8; + PyObject *__pyx_tuple__9; + PyObject *__pyx_tuple__11; + PyObject *__pyx_tuple__15; + PyObject *__pyx_tuple__17; + PyObject *__pyx_tuple__20; + PyObject *__pyx_tuple__22; + PyObject *__pyx_tuple__25; + PyObject *__pyx_tuple__32; + PyObject *__pyx_tuple__34; + PyObject *__pyx_tuple__38; + PyObject *__pyx_tuple__41; + PyObject *__pyx_tuple__43; + PyObject *__pyx_tuple__46; + PyObject *__pyx_tuple__48; + PyObject *__pyx_codeobj__7; + PyObject *__pyx_codeobj__10; + PyObject *__pyx_codeobj__12; + PyObject *__pyx_codeobj__13; + PyObject *__pyx_codeobj__14; + PyObject *__pyx_codeobj__16; + PyObject *__pyx_codeobj__18; + PyObject *__pyx_codeobj__19; + PyObject *__pyx_codeobj__21; + PyObject *__pyx_codeobj__23; + PyObject *__pyx_codeobj__24; + PyObject *__pyx_codeobj__26; + PyObject *__pyx_codeobj__27; + PyObject *__pyx_codeobj__28; + PyObject *__pyx_codeobj__29; + PyObject *__pyx_codeobj__30; + PyObject *__pyx_codeobj__31; + PyObject *__pyx_codeobj__33; + PyObject *__pyx_codeobj__35; + PyObject *__pyx_codeobj__36; + PyObject *__pyx_codeobj__37; + PyObject *__pyx_codeobj__39; + PyObject *__pyx_codeobj__40; + PyObject *__pyx_codeobj__42; + PyObject *__pyx_codeobj__44; + PyObject *__pyx_codeobj__45; + PyObject *__pyx_codeobj__47; + PyObject *__pyx_codeobj__49; + PyObject *__pyx_codeobj__50; + PyObject *__pyx_codeobj__51; + PyObject *__pyx_codeobj__52; +} __pyx_mstate; + +#if CYTHON_USE_MODULE_STATE +#ifdef __cplusplus +namespace { + extern struct PyModuleDef __pyx_moduledef; +} /* anonymous namespace */ +#else +static struct PyModuleDef __pyx_moduledef; +#endif + +#define __pyx_mstate(o) ((__pyx_mstate *)__Pyx_PyModule_GetState(o)) + +#define __pyx_mstate_global (__pyx_mstate(PyState_FindModule(&__pyx_moduledef))) + +#define __pyx_m (PyState_FindModule(&__pyx_moduledef)) +#else +static __pyx_mstate __pyx_mstate_global_static = +#ifdef __cplusplus + {}; +#else + {0}; +#endif +static __pyx_mstate *__pyx_mstate_global = &__pyx_mstate_global_static; +#endif +/* #### Code section: module_state_clear ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_clear(PyObject *m) { + __pyx_mstate *clear_module_state = __pyx_mstate(m); + if (!clear_module_state) return 0; + Py_CLEAR(clear_module_state->__pyx_d); + Py_CLEAR(clear_module_state->__pyx_b); + Py_CLEAR(clear_module_state->__pyx_cython_runtime); + Py_CLEAR(clear_module_state->__pyx_empty_tuple); + Py_CLEAR(clear_module_state->__pyx_empty_bytes); + Py_CLEAR(clear_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_CLEAR(clear_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_CLEAR(clear_module_state->__pyx_FusedFunctionType); + #endif + Py_CLEAR(clear_module_state->__pyx_ptype_6cereal_9messaging_13messaging_pyx_Event); + Py_CLEAR(clear_module_state->__pyx_type_6cereal_9messaging_13messaging_pyx_Event); + Py_CLEAR(clear_module_state->__pyx_ptype_6cereal_9messaging_13messaging_pyx_SocketEventHandle); + Py_CLEAR(clear_module_state->__pyx_type_6cereal_9messaging_13messaging_pyx_SocketEventHandle); + Py_CLEAR(clear_module_state->__pyx_ptype_6cereal_9messaging_13messaging_pyx_Context); + Py_CLEAR(clear_module_state->__pyx_type_6cereal_9messaging_13messaging_pyx_Context); + Py_CLEAR(clear_module_state->__pyx_ptype_6cereal_9messaging_13messaging_pyx_Poller); + Py_CLEAR(clear_module_state->__pyx_type_6cereal_9messaging_13messaging_pyx_Poller); + Py_CLEAR(clear_module_state->__pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket); + Py_CLEAR(clear_module_state->__pyx_type_6cereal_9messaging_13messaging_pyx_SubSocket); + Py_CLEAR(clear_module_state->__pyx_ptype_6cereal_9messaging_13messaging_pyx_PubSocket); + Py_CLEAR(clear_module_state->__pyx_type_6cereal_9messaging_13messaging_pyx_PubSocket); + Py_CLEAR(clear_module_state->__pyx_kp_b_); + Py_CLEAR(clear_module_state->__pyx_kp_u_); + Py_CLEAR(clear_module_state->__pyx_kp_b_127_0_0_1); + Py_CLEAR(clear_module_state->__pyx_n_s_Context); + Py_CLEAR(clear_module_state->__pyx_n_s_Context___reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_Context___setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_Context_term); + Py_CLEAR(clear_module_state->__pyx_n_s_Event); + Py_CLEAR(clear_module_state->__pyx_n_s_Event___reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_Event___setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_Event_clear); + Py_CLEAR(clear_module_state->__pyx_n_s_Event_peek); + Py_CLEAR(clear_module_state->__pyx_n_s_Event_set); + Py_CLEAR(clear_module_state->__pyx_n_s_Event_wait); + Py_CLEAR(clear_module_state->__pyx_n_s_MessagingError); + Py_CLEAR(clear_module_state->__pyx_n_s_MessagingError___init); + Py_CLEAR(clear_module_state->__pyx_kp_u_Messaging_failure); + Py_CLEAR(clear_module_state->__pyx_n_s_MultiplePublishersError); + Py_CLEAR(clear_module_state->__pyx_kp_u_None); + Py_CLEAR(clear_module_state->__pyx_n_s_Poller); + Py_CLEAR(clear_module_state->__pyx_n_s_Poller___reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_Poller___setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_Poller_poll); + Py_CLEAR(clear_module_state->__pyx_n_s_Poller_registerSocket); + Py_CLEAR(clear_module_state->__pyx_n_s_PubSocket); + Py_CLEAR(clear_module_state->__pyx_n_s_PubSocket___reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_PubSocket___setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_PubSocket_all_readers_updated); + Py_CLEAR(clear_module_state->__pyx_n_s_PubSocket_connect); + Py_CLEAR(clear_module_state->__pyx_n_s_PubSocket_send); + Py_CLEAR(clear_module_state->__pyx_kp_u_SIGINT_received_exiting); + Py_CLEAR(clear_module_state->__pyx_n_s_SocketEventHandle); + Py_CLEAR(clear_module_state->__pyx_n_s_SocketEventHandle___reduce_cytho); + Py_CLEAR(clear_module_state->__pyx_n_s_SocketEventHandle___setstate_cyt); + Py_CLEAR(clear_module_state->__pyx_n_s_SubSocket); + Py_CLEAR(clear_module_state->__pyx_n_s_SubSocket___reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_SubSocket___setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_SubSocket_connect); + Py_CLEAR(clear_module_state->__pyx_n_s_SubSocket_receive); + Py_CLEAR(clear_module_state->__pyx_n_s_SubSocket_setTimeout); + Py_CLEAR(clear_module_state->__pyx_n_s_TypeError); + Py_CLEAR(clear_module_state->__pyx_kp_u__2); + Py_CLEAR(clear_module_state->__pyx_n_s__5); + Py_CLEAR(clear_module_state->__pyx_n_s__53); + Py_CLEAR(clear_module_state->__pyx_n_s_address); + Py_CLEAR(clear_module_state->__pyx_n_s_all_readers_updated); + Py_CLEAR(clear_module_state->__pyx_n_s_asyncio_coroutines); + Py_CLEAR(clear_module_state->__pyx_n_s_cereal_messaging_messaging_pyx); + Py_CLEAR(clear_module_state->__pyx_kp_s_cereal_messaging_messaging_pyx_p); + Py_CLEAR(clear_module_state->__pyx_n_s_clear); + Py_CLEAR(clear_module_state->__pyx_n_s_cline_in_traceback); + Py_CLEAR(clear_module_state->__pyx_n_s_conflate); + Py_CLEAR(clear_module_state->__pyx_n_s_connect); + Py_CLEAR(clear_module_state->__pyx_n_s_context); + Py_CLEAR(clear_module_state->__pyx_n_s_data); + Py_CLEAR(clear_module_state->__pyx_n_s_decode); + Py_CLEAR(clear_module_state->__pyx_n_s_delete_fake_prefix); + Py_CLEAR(clear_module_state->__pyx_n_s_dict); + Py_CLEAR(clear_module_state->__pyx_kp_u_disable); + Py_CLEAR(clear_module_state->__pyx_n_s_doc); + Py_CLEAR(clear_module_state->__pyx_kp_u_enable); + Py_CLEAR(clear_module_state->__pyx_n_s_enabled); + Py_CLEAR(clear_module_state->__pyx_n_s_endpoint); + Py_CLEAR(clear_module_state->__pyx_n_s_event); + Py_CLEAR(clear_module_state->__pyx_n_s_events); + Py_CLEAR(clear_module_state->__pyx_n_s_exit); + Py_CLEAR(clear_module_state->__pyx_kp_u_gc); + Py_CLEAR(clear_module_state->__pyx_n_s_get_fake_prefix); + Py_CLEAR(clear_module_state->__pyx_n_s_getstate); + Py_CLEAR(clear_module_state->__pyx_n_s_identifier); + Py_CLEAR(clear_module_state->__pyx_n_s_import); + Py_CLEAR(clear_module_state->__pyx_n_s_init); + Py_CLEAR(clear_module_state->__pyx_n_s_init_subclass); + Py_CLEAR(clear_module_state->__pyx_n_s_initializing); + Py_CLEAR(clear_module_state->__pyx_n_s_is_coroutine); + Py_CLEAR(clear_module_state->__pyx_kp_u_isenabled); + Py_CLEAR(clear_module_state->__pyx_n_s_items); + Py_CLEAR(clear_module_state->__pyx_n_s_length); + Py_CLEAR(clear_module_state->__pyx_n_s_m); + Py_CLEAR(clear_module_state->__pyx_n_s_main); + Py_CLEAR(clear_module_state->__pyx_n_s_message); + Py_CLEAR(clear_module_state->__pyx_n_s_metaclass); + Py_CLEAR(clear_module_state->__pyx_n_s_module); + Py_CLEAR(clear_module_state->__pyx_n_s_mro_entries); + Py_CLEAR(clear_module_state->__pyx_n_s_msg); + Py_CLEAR(clear_module_state->__pyx_n_s_name); + Py_CLEAR(clear_module_state->__pyx_kp_s_no_default___reduce___due_to_non); + Py_CLEAR(clear_module_state->__pyx_n_s_non_blocking); + Py_CLEAR(clear_module_state->__pyx_n_s_override); + Py_CLEAR(clear_module_state->__pyx_n_s_peek); + Py_CLEAR(clear_module_state->__pyx_n_s_poll); + Py_CLEAR(clear_module_state->__pyx_n_s_prefix); + Py_CLEAR(clear_module_state->__pyx_n_s_prepare); + Py_CLEAR(clear_module_state->__pyx_n_s_print); + Py_CLEAR(clear_module_state->__pyx_n_s_ptr); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_state); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_vtable); + Py_CLEAR(clear_module_state->__pyx_n_s_qualname); + Py_CLEAR(clear_module_state->__pyx_n_s_r); + Py_CLEAR(clear_module_state->__pyx_n_s_receive); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_ex); + Py_CLEAR(clear_module_state->__pyx_n_s_registerSocket); + Py_CLEAR(clear_module_state->__pyx_n_s_result); + Py_CLEAR(clear_module_state->__pyx_n_s_s); + Py_CLEAR(clear_module_state->__pyx_n_s_self); + Py_CLEAR(clear_module_state->__pyx_n_s_send); + Py_CLEAR(clear_module_state->__pyx_n_s_set); + Py_CLEAR(clear_module_state->__pyx_n_s_setTimeout); + Py_CLEAR(clear_module_state->__pyx_n_s_set_fake_prefix); + Py_CLEAR(clear_module_state->__pyx_n_s_set_name); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_socket); + Py_CLEAR(clear_module_state->__pyx_n_s_sockets); + Py_CLEAR(clear_module_state->__pyx_n_s_spec); + Py_CLEAR(clear_module_state->__pyx_kp_s_stringsource); + Py_CLEAR(clear_module_state->__pyx_n_s_suffix); + Py_CLEAR(clear_module_state->__pyx_n_s_super); + Py_CLEAR(clear_module_state->__pyx_n_s_sys); + Py_CLEAR(clear_module_state->__pyx_n_s_sz); + Py_CLEAR(clear_module_state->__pyx_n_s_t); + Py_CLEAR(clear_module_state->__pyx_n_s_term); + Py_CLEAR(clear_module_state->__pyx_n_s_test); + Py_CLEAR(clear_module_state->__pyx_n_s_timeout); + Py_CLEAR(clear_module_state->__pyx_n_s_toggle_fake_events); + Py_CLEAR(clear_module_state->__pyx_kp_u_utf_8); + Py_CLEAR(clear_module_state->__pyx_n_s_wait); + Py_CLEAR(clear_module_state->__pyx_n_s_wait_for_one_event); + Py_CLEAR(clear_module_state->__pyx_kp_u_with); + Py_CLEAR(clear_module_state->__pyx_int_1); + Py_CLEAR(clear_module_state->__pyx_int_neg_1); + Py_CLEAR(clear_module_state->__pyx_tuple__4); + Py_CLEAR(clear_module_state->__pyx_tuple__6); + Py_CLEAR(clear_module_state->__pyx_tuple__8); + Py_CLEAR(clear_module_state->__pyx_tuple__9); + Py_CLEAR(clear_module_state->__pyx_tuple__11); + Py_CLEAR(clear_module_state->__pyx_tuple__15); + Py_CLEAR(clear_module_state->__pyx_tuple__17); + Py_CLEAR(clear_module_state->__pyx_tuple__20); + Py_CLEAR(clear_module_state->__pyx_tuple__22); + Py_CLEAR(clear_module_state->__pyx_tuple__25); + Py_CLEAR(clear_module_state->__pyx_tuple__32); + Py_CLEAR(clear_module_state->__pyx_tuple__34); + Py_CLEAR(clear_module_state->__pyx_tuple__38); + Py_CLEAR(clear_module_state->__pyx_tuple__41); + Py_CLEAR(clear_module_state->__pyx_tuple__43); + Py_CLEAR(clear_module_state->__pyx_tuple__46); + Py_CLEAR(clear_module_state->__pyx_tuple__48); + Py_CLEAR(clear_module_state->__pyx_codeobj__7); + Py_CLEAR(clear_module_state->__pyx_codeobj__10); + Py_CLEAR(clear_module_state->__pyx_codeobj__12); + Py_CLEAR(clear_module_state->__pyx_codeobj__13); + Py_CLEAR(clear_module_state->__pyx_codeobj__14); + Py_CLEAR(clear_module_state->__pyx_codeobj__16); + Py_CLEAR(clear_module_state->__pyx_codeobj__18); + Py_CLEAR(clear_module_state->__pyx_codeobj__19); + Py_CLEAR(clear_module_state->__pyx_codeobj__21); + Py_CLEAR(clear_module_state->__pyx_codeobj__23); + Py_CLEAR(clear_module_state->__pyx_codeobj__24); + Py_CLEAR(clear_module_state->__pyx_codeobj__26); + Py_CLEAR(clear_module_state->__pyx_codeobj__27); + Py_CLEAR(clear_module_state->__pyx_codeobj__28); + Py_CLEAR(clear_module_state->__pyx_codeobj__29); + Py_CLEAR(clear_module_state->__pyx_codeobj__30); + Py_CLEAR(clear_module_state->__pyx_codeobj__31); + Py_CLEAR(clear_module_state->__pyx_codeobj__33); + Py_CLEAR(clear_module_state->__pyx_codeobj__35); + Py_CLEAR(clear_module_state->__pyx_codeobj__36); + Py_CLEAR(clear_module_state->__pyx_codeobj__37); + Py_CLEAR(clear_module_state->__pyx_codeobj__39); + Py_CLEAR(clear_module_state->__pyx_codeobj__40); + Py_CLEAR(clear_module_state->__pyx_codeobj__42); + Py_CLEAR(clear_module_state->__pyx_codeobj__44); + Py_CLEAR(clear_module_state->__pyx_codeobj__45); + Py_CLEAR(clear_module_state->__pyx_codeobj__47); + Py_CLEAR(clear_module_state->__pyx_codeobj__49); + Py_CLEAR(clear_module_state->__pyx_codeobj__50); + Py_CLEAR(clear_module_state->__pyx_codeobj__51); + Py_CLEAR(clear_module_state->__pyx_codeobj__52); + return 0; +} +#endif +/* #### Code section: module_state_traverse ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { + __pyx_mstate *traverse_module_state = __pyx_mstate(m); + if (!traverse_module_state) return 0; + Py_VISIT(traverse_module_state->__pyx_d); + Py_VISIT(traverse_module_state->__pyx_b); + Py_VISIT(traverse_module_state->__pyx_cython_runtime); + Py_VISIT(traverse_module_state->__pyx_empty_tuple); + Py_VISIT(traverse_module_state->__pyx_empty_bytes); + Py_VISIT(traverse_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_VISIT(traverse_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_VISIT(traverse_module_state->__pyx_FusedFunctionType); + #endif + Py_VISIT(traverse_module_state->__pyx_ptype_6cereal_9messaging_13messaging_pyx_Event); + Py_VISIT(traverse_module_state->__pyx_type_6cereal_9messaging_13messaging_pyx_Event); + Py_VISIT(traverse_module_state->__pyx_ptype_6cereal_9messaging_13messaging_pyx_SocketEventHandle); + Py_VISIT(traverse_module_state->__pyx_type_6cereal_9messaging_13messaging_pyx_SocketEventHandle); + Py_VISIT(traverse_module_state->__pyx_ptype_6cereal_9messaging_13messaging_pyx_Context); + Py_VISIT(traverse_module_state->__pyx_type_6cereal_9messaging_13messaging_pyx_Context); + Py_VISIT(traverse_module_state->__pyx_ptype_6cereal_9messaging_13messaging_pyx_Poller); + Py_VISIT(traverse_module_state->__pyx_type_6cereal_9messaging_13messaging_pyx_Poller); + Py_VISIT(traverse_module_state->__pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket); + Py_VISIT(traverse_module_state->__pyx_type_6cereal_9messaging_13messaging_pyx_SubSocket); + Py_VISIT(traverse_module_state->__pyx_ptype_6cereal_9messaging_13messaging_pyx_PubSocket); + Py_VISIT(traverse_module_state->__pyx_type_6cereal_9messaging_13messaging_pyx_PubSocket); + Py_VISIT(traverse_module_state->__pyx_kp_b_); + Py_VISIT(traverse_module_state->__pyx_kp_u_); + Py_VISIT(traverse_module_state->__pyx_kp_b_127_0_0_1); + Py_VISIT(traverse_module_state->__pyx_n_s_Context); + Py_VISIT(traverse_module_state->__pyx_n_s_Context___reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_Context___setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_Context_term); + Py_VISIT(traverse_module_state->__pyx_n_s_Event); + Py_VISIT(traverse_module_state->__pyx_n_s_Event___reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_Event___setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_Event_clear); + Py_VISIT(traverse_module_state->__pyx_n_s_Event_peek); + Py_VISIT(traverse_module_state->__pyx_n_s_Event_set); + Py_VISIT(traverse_module_state->__pyx_n_s_Event_wait); + Py_VISIT(traverse_module_state->__pyx_n_s_MessagingError); + Py_VISIT(traverse_module_state->__pyx_n_s_MessagingError___init); + Py_VISIT(traverse_module_state->__pyx_kp_u_Messaging_failure); + Py_VISIT(traverse_module_state->__pyx_n_s_MultiplePublishersError); + Py_VISIT(traverse_module_state->__pyx_kp_u_None); + Py_VISIT(traverse_module_state->__pyx_n_s_Poller); + Py_VISIT(traverse_module_state->__pyx_n_s_Poller___reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_Poller___setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_Poller_poll); + Py_VISIT(traverse_module_state->__pyx_n_s_Poller_registerSocket); + Py_VISIT(traverse_module_state->__pyx_n_s_PubSocket); + Py_VISIT(traverse_module_state->__pyx_n_s_PubSocket___reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_PubSocket___setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_PubSocket_all_readers_updated); + Py_VISIT(traverse_module_state->__pyx_n_s_PubSocket_connect); + Py_VISIT(traverse_module_state->__pyx_n_s_PubSocket_send); + Py_VISIT(traverse_module_state->__pyx_kp_u_SIGINT_received_exiting); + Py_VISIT(traverse_module_state->__pyx_n_s_SocketEventHandle); + Py_VISIT(traverse_module_state->__pyx_n_s_SocketEventHandle___reduce_cytho); + Py_VISIT(traverse_module_state->__pyx_n_s_SocketEventHandle___setstate_cyt); + Py_VISIT(traverse_module_state->__pyx_n_s_SubSocket); + Py_VISIT(traverse_module_state->__pyx_n_s_SubSocket___reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_SubSocket___setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_SubSocket_connect); + Py_VISIT(traverse_module_state->__pyx_n_s_SubSocket_receive); + Py_VISIT(traverse_module_state->__pyx_n_s_SubSocket_setTimeout); + Py_VISIT(traverse_module_state->__pyx_n_s_TypeError); + Py_VISIT(traverse_module_state->__pyx_kp_u__2); + Py_VISIT(traverse_module_state->__pyx_n_s__5); + Py_VISIT(traverse_module_state->__pyx_n_s__53); + Py_VISIT(traverse_module_state->__pyx_n_s_address); + Py_VISIT(traverse_module_state->__pyx_n_s_all_readers_updated); + Py_VISIT(traverse_module_state->__pyx_n_s_asyncio_coroutines); + Py_VISIT(traverse_module_state->__pyx_n_s_cereal_messaging_messaging_pyx); + Py_VISIT(traverse_module_state->__pyx_kp_s_cereal_messaging_messaging_pyx_p); + Py_VISIT(traverse_module_state->__pyx_n_s_clear); + Py_VISIT(traverse_module_state->__pyx_n_s_cline_in_traceback); + Py_VISIT(traverse_module_state->__pyx_n_s_conflate); + Py_VISIT(traverse_module_state->__pyx_n_s_connect); + Py_VISIT(traverse_module_state->__pyx_n_s_context); + Py_VISIT(traverse_module_state->__pyx_n_s_data); + Py_VISIT(traverse_module_state->__pyx_n_s_decode); + Py_VISIT(traverse_module_state->__pyx_n_s_delete_fake_prefix); + Py_VISIT(traverse_module_state->__pyx_n_s_dict); + Py_VISIT(traverse_module_state->__pyx_kp_u_disable); + Py_VISIT(traverse_module_state->__pyx_n_s_doc); + Py_VISIT(traverse_module_state->__pyx_kp_u_enable); + Py_VISIT(traverse_module_state->__pyx_n_s_enabled); + Py_VISIT(traverse_module_state->__pyx_n_s_endpoint); + Py_VISIT(traverse_module_state->__pyx_n_s_event); + Py_VISIT(traverse_module_state->__pyx_n_s_events); + Py_VISIT(traverse_module_state->__pyx_n_s_exit); + Py_VISIT(traverse_module_state->__pyx_kp_u_gc); + Py_VISIT(traverse_module_state->__pyx_n_s_get_fake_prefix); + Py_VISIT(traverse_module_state->__pyx_n_s_getstate); + Py_VISIT(traverse_module_state->__pyx_n_s_identifier); + Py_VISIT(traverse_module_state->__pyx_n_s_import); + Py_VISIT(traverse_module_state->__pyx_n_s_init); + Py_VISIT(traverse_module_state->__pyx_n_s_init_subclass); + Py_VISIT(traverse_module_state->__pyx_n_s_initializing); + Py_VISIT(traverse_module_state->__pyx_n_s_is_coroutine); + Py_VISIT(traverse_module_state->__pyx_kp_u_isenabled); + Py_VISIT(traverse_module_state->__pyx_n_s_items); + Py_VISIT(traverse_module_state->__pyx_n_s_length); + Py_VISIT(traverse_module_state->__pyx_n_s_m); + Py_VISIT(traverse_module_state->__pyx_n_s_main); + Py_VISIT(traverse_module_state->__pyx_n_s_message); + Py_VISIT(traverse_module_state->__pyx_n_s_metaclass); + Py_VISIT(traverse_module_state->__pyx_n_s_module); + Py_VISIT(traverse_module_state->__pyx_n_s_mro_entries); + Py_VISIT(traverse_module_state->__pyx_n_s_msg); + Py_VISIT(traverse_module_state->__pyx_n_s_name); + Py_VISIT(traverse_module_state->__pyx_kp_s_no_default___reduce___due_to_non); + Py_VISIT(traverse_module_state->__pyx_n_s_non_blocking); + Py_VISIT(traverse_module_state->__pyx_n_s_override); + Py_VISIT(traverse_module_state->__pyx_n_s_peek); + Py_VISIT(traverse_module_state->__pyx_n_s_poll); + Py_VISIT(traverse_module_state->__pyx_n_s_prefix); + Py_VISIT(traverse_module_state->__pyx_n_s_prepare); + Py_VISIT(traverse_module_state->__pyx_n_s_print); + Py_VISIT(traverse_module_state->__pyx_n_s_ptr); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_state); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_vtable); + Py_VISIT(traverse_module_state->__pyx_n_s_qualname); + Py_VISIT(traverse_module_state->__pyx_n_s_r); + Py_VISIT(traverse_module_state->__pyx_n_s_receive); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_ex); + Py_VISIT(traverse_module_state->__pyx_n_s_registerSocket); + Py_VISIT(traverse_module_state->__pyx_n_s_result); + Py_VISIT(traverse_module_state->__pyx_n_s_s); + Py_VISIT(traverse_module_state->__pyx_n_s_self); + Py_VISIT(traverse_module_state->__pyx_n_s_send); + Py_VISIT(traverse_module_state->__pyx_n_s_set); + Py_VISIT(traverse_module_state->__pyx_n_s_setTimeout); + Py_VISIT(traverse_module_state->__pyx_n_s_set_fake_prefix); + Py_VISIT(traverse_module_state->__pyx_n_s_set_name); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_socket); + Py_VISIT(traverse_module_state->__pyx_n_s_sockets); + Py_VISIT(traverse_module_state->__pyx_n_s_spec); + Py_VISIT(traverse_module_state->__pyx_kp_s_stringsource); + Py_VISIT(traverse_module_state->__pyx_n_s_suffix); + Py_VISIT(traverse_module_state->__pyx_n_s_super); + Py_VISIT(traverse_module_state->__pyx_n_s_sys); + Py_VISIT(traverse_module_state->__pyx_n_s_sz); + Py_VISIT(traverse_module_state->__pyx_n_s_t); + Py_VISIT(traverse_module_state->__pyx_n_s_term); + Py_VISIT(traverse_module_state->__pyx_n_s_test); + Py_VISIT(traverse_module_state->__pyx_n_s_timeout); + Py_VISIT(traverse_module_state->__pyx_n_s_toggle_fake_events); + Py_VISIT(traverse_module_state->__pyx_kp_u_utf_8); + Py_VISIT(traverse_module_state->__pyx_n_s_wait); + Py_VISIT(traverse_module_state->__pyx_n_s_wait_for_one_event); + Py_VISIT(traverse_module_state->__pyx_kp_u_with); + Py_VISIT(traverse_module_state->__pyx_int_1); + Py_VISIT(traverse_module_state->__pyx_int_neg_1); + Py_VISIT(traverse_module_state->__pyx_tuple__4); + Py_VISIT(traverse_module_state->__pyx_tuple__6); + Py_VISIT(traverse_module_state->__pyx_tuple__8); + Py_VISIT(traverse_module_state->__pyx_tuple__9); + Py_VISIT(traverse_module_state->__pyx_tuple__11); + Py_VISIT(traverse_module_state->__pyx_tuple__15); + Py_VISIT(traverse_module_state->__pyx_tuple__17); + Py_VISIT(traverse_module_state->__pyx_tuple__20); + Py_VISIT(traverse_module_state->__pyx_tuple__22); + Py_VISIT(traverse_module_state->__pyx_tuple__25); + Py_VISIT(traverse_module_state->__pyx_tuple__32); + Py_VISIT(traverse_module_state->__pyx_tuple__34); + Py_VISIT(traverse_module_state->__pyx_tuple__38); + Py_VISIT(traverse_module_state->__pyx_tuple__41); + Py_VISIT(traverse_module_state->__pyx_tuple__43); + Py_VISIT(traverse_module_state->__pyx_tuple__46); + Py_VISIT(traverse_module_state->__pyx_tuple__48); + Py_VISIT(traverse_module_state->__pyx_codeobj__7); + Py_VISIT(traverse_module_state->__pyx_codeobj__10); + Py_VISIT(traverse_module_state->__pyx_codeobj__12); + Py_VISIT(traverse_module_state->__pyx_codeobj__13); + Py_VISIT(traverse_module_state->__pyx_codeobj__14); + Py_VISIT(traverse_module_state->__pyx_codeobj__16); + Py_VISIT(traverse_module_state->__pyx_codeobj__18); + Py_VISIT(traverse_module_state->__pyx_codeobj__19); + Py_VISIT(traverse_module_state->__pyx_codeobj__21); + Py_VISIT(traverse_module_state->__pyx_codeobj__23); + Py_VISIT(traverse_module_state->__pyx_codeobj__24); + Py_VISIT(traverse_module_state->__pyx_codeobj__26); + Py_VISIT(traverse_module_state->__pyx_codeobj__27); + Py_VISIT(traverse_module_state->__pyx_codeobj__28); + Py_VISIT(traverse_module_state->__pyx_codeobj__29); + Py_VISIT(traverse_module_state->__pyx_codeobj__30); + Py_VISIT(traverse_module_state->__pyx_codeobj__31); + Py_VISIT(traverse_module_state->__pyx_codeobj__33); + Py_VISIT(traverse_module_state->__pyx_codeobj__35); + Py_VISIT(traverse_module_state->__pyx_codeobj__36); + Py_VISIT(traverse_module_state->__pyx_codeobj__37); + Py_VISIT(traverse_module_state->__pyx_codeobj__39); + Py_VISIT(traverse_module_state->__pyx_codeobj__40); + Py_VISIT(traverse_module_state->__pyx_codeobj__42); + Py_VISIT(traverse_module_state->__pyx_codeobj__44); + Py_VISIT(traverse_module_state->__pyx_codeobj__45); + Py_VISIT(traverse_module_state->__pyx_codeobj__47); + Py_VISIT(traverse_module_state->__pyx_codeobj__49); + Py_VISIT(traverse_module_state->__pyx_codeobj__50); + Py_VISIT(traverse_module_state->__pyx_codeobj__51); + Py_VISIT(traverse_module_state->__pyx_codeobj__52); + return 0; +} +#endif +/* #### Code section: module_state_defines ### */ +#define __pyx_d __pyx_mstate_global->__pyx_d +#define __pyx_b __pyx_mstate_global->__pyx_b +#define __pyx_cython_runtime __pyx_mstate_global->__pyx_cython_runtime +#define __pyx_empty_tuple __pyx_mstate_global->__pyx_empty_tuple +#define __pyx_empty_bytes __pyx_mstate_global->__pyx_empty_bytes +#define __pyx_empty_unicode __pyx_mstate_global->__pyx_empty_unicode +#ifdef __Pyx_CyFunction_USED +#define __pyx_CyFunctionType __pyx_mstate_global->__pyx_CyFunctionType +#endif +#ifdef __Pyx_FusedFunction_USED +#define __pyx_FusedFunctionType __pyx_mstate_global->__pyx_FusedFunctionType +#endif +#ifdef __Pyx_Generator_USED +#define __pyx_GeneratorType __pyx_mstate_global->__pyx_GeneratorType +#endif +#ifdef __Pyx_IterableCoroutine_USED +#define __pyx_IterableCoroutineType __pyx_mstate_global->__pyx_IterableCoroutineType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineAwaitType __pyx_mstate_global->__pyx_CoroutineAwaitType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineType __pyx_mstate_global->__pyx_CoroutineType +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#define __pyx_type_6cereal_9messaging_13messaging_pyx_Event __pyx_mstate_global->__pyx_type_6cereal_9messaging_13messaging_pyx_Event +#define __pyx_type_6cereal_9messaging_13messaging_pyx_SocketEventHandle __pyx_mstate_global->__pyx_type_6cereal_9messaging_13messaging_pyx_SocketEventHandle +#define __pyx_type_6cereal_9messaging_13messaging_pyx_Context __pyx_mstate_global->__pyx_type_6cereal_9messaging_13messaging_pyx_Context +#define __pyx_type_6cereal_9messaging_13messaging_pyx_Poller __pyx_mstate_global->__pyx_type_6cereal_9messaging_13messaging_pyx_Poller +#define __pyx_type_6cereal_9messaging_13messaging_pyx_SubSocket __pyx_mstate_global->__pyx_type_6cereal_9messaging_13messaging_pyx_SubSocket +#define __pyx_type_6cereal_9messaging_13messaging_pyx_PubSocket __pyx_mstate_global->__pyx_type_6cereal_9messaging_13messaging_pyx_PubSocket +#endif +#define __pyx_ptype_6cereal_9messaging_13messaging_pyx_Event __pyx_mstate_global->__pyx_ptype_6cereal_9messaging_13messaging_pyx_Event +#define __pyx_ptype_6cereal_9messaging_13messaging_pyx_SocketEventHandle __pyx_mstate_global->__pyx_ptype_6cereal_9messaging_13messaging_pyx_SocketEventHandle +#define __pyx_ptype_6cereal_9messaging_13messaging_pyx_Context __pyx_mstate_global->__pyx_ptype_6cereal_9messaging_13messaging_pyx_Context +#define __pyx_ptype_6cereal_9messaging_13messaging_pyx_Poller __pyx_mstate_global->__pyx_ptype_6cereal_9messaging_13messaging_pyx_Poller +#define __pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket __pyx_mstate_global->__pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket +#define __pyx_ptype_6cereal_9messaging_13messaging_pyx_PubSocket __pyx_mstate_global->__pyx_ptype_6cereal_9messaging_13messaging_pyx_PubSocket +#define __pyx_kp_b_ __pyx_mstate_global->__pyx_kp_b_ +#define __pyx_kp_u_ __pyx_mstate_global->__pyx_kp_u_ +#define __pyx_kp_b_127_0_0_1 __pyx_mstate_global->__pyx_kp_b_127_0_0_1 +#define __pyx_n_s_Context __pyx_mstate_global->__pyx_n_s_Context +#define __pyx_n_s_Context___reduce_cython __pyx_mstate_global->__pyx_n_s_Context___reduce_cython +#define __pyx_n_s_Context___setstate_cython __pyx_mstate_global->__pyx_n_s_Context___setstate_cython +#define __pyx_n_s_Context_term __pyx_mstate_global->__pyx_n_s_Context_term +#define __pyx_n_s_Event __pyx_mstate_global->__pyx_n_s_Event +#define __pyx_n_s_Event___reduce_cython __pyx_mstate_global->__pyx_n_s_Event___reduce_cython +#define __pyx_n_s_Event___setstate_cython __pyx_mstate_global->__pyx_n_s_Event___setstate_cython +#define __pyx_n_s_Event_clear __pyx_mstate_global->__pyx_n_s_Event_clear +#define __pyx_n_s_Event_peek __pyx_mstate_global->__pyx_n_s_Event_peek +#define __pyx_n_s_Event_set __pyx_mstate_global->__pyx_n_s_Event_set +#define __pyx_n_s_Event_wait __pyx_mstate_global->__pyx_n_s_Event_wait +#define __pyx_n_s_MessagingError __pyx_mstate_global->__pyx_n_s_MessagingError +#define __pyx_n_s_MessagingError___init __pyx_mstate_global->__pyx_n_s_MessagingError___init +#define __pyx_kp_u_Messaging_failure __pyx_mstate_global->__pyx_kp_u_Messaging_failure +#define __pyx_n_s_MultiplePublishersError __pyx_mstate_global->__pyx_n_s_MultiplePublishersError +#define __pyx_kp_u_None __pyx_mstate_global->__pyx_kp_u_None +#define __pyx_n_s_Poller __pyx_mstate_global->__pyx_n_s_Poller +#define __pyx_n_s_Poller___reduce_cython __pyx_mstate_global->__pyx_n_s_Poller___reduce_cython +#define __pyx_n_s_Poller___setstate_cython __pyx_mstate_global->__pyx_n_s_Poller___setstate_cython +#define __pyx_n_s_Poller_poll __pyx_mstate_global->__pyx_n_s_Poller_poll +#define __pyx_n_s_Poller_registerSocket __pyx_mstate_global->__pyx_n_s_Poller_registerSocket +#define __pyx_n_s_PubSocket __pyx_mstate_global->__pyx_n_s_PubSocket +#define __pyx_n_s_PubSocket___reduce_cython __pyx_mstate_global->__pyx_n_s_PubSocket___reduce_cython +#define __pyx_n_s_PubSocket___setstate_cython __pyx_mstate_global->__pyx_n_s_PubSocket___setstate_cython +#define __pyx_n_s_PubSocket_all_readers_updated __pyx_mstate_global->__pyx_n_s_PubSocket_all_readers_updated +#define __pyx_n_s_PubSocket_connect __pyx_mstate_global->__pyx_n_s_PubSocket_connect +#define __pyx_n_s_PubSocket_send __pyx_mstate_global->__pyx_n_s_PubSocket_send +#define __pyx_kp_u_SIGINT_received_exiting __pyx_mstate_global->__pyx_kp_u_SIGINT_received_exiting +#define __pyx_n_s_SocketEventHandle __pyx_mstate_global->__pyx_n_s_SocketEventHandle +#define __pyx_n_s_SocketEventHandle___reduce_cytho __pyx_mstate_global->__pyx_n_s_SocketEventHandle___reduce_cytho +#define __pyx_n_s_SocketEventHandle___setstate_cyt __pyx_mstate_global->__pyx_n_s_SocketEventHandle___setstate_cyt +#define __pyx_n_s_SubSocket __pyx_mstate_global->__pyx_n_s_SubSocket +#define __pyx_n_s_SubSocket___reduce_cython __pyx_mstate_global->__pyx_n_s_SubSocket___reduce_cython +#define __pyx_n_s_SubSocket___setstate_cython __pyx_mstate_global->__pyx_n_s_SubSocket___setstate_cython +#define __pyx_n_s_SubSocket_connect __pyx_mstate_global->__pyx_n_s_SubSocket_connect +#define __pyx_n_s_SubSocket_receive __pyx_mstate_global->__pyx_n_s_SubSocket_receive +#define __pyx_n_s_SubSocket_setTimeout __pyx_mstate_global->__pyx_n_s_SubSocket_setTimeout +#define __pyx_n_s_TypeError __pyx_mstate_global->__pyx_n_s_TypeError +#define __pyx_kp_u__2 __pyx_mstate_global->__pyx_kp_u__2 +#define __pyx_n_s__5 __pyx_mstate_global->__pyx_n_s__5 +#define __pyx_n_s__53 __pyx_mstate_global->__pyx_n_s__53 +#define __pyx_n_s_address __pyx_mstate_global->__pyx_n_s_address +#define __pyx_n_s_all_readers_updated __pyx_mstate_global->__pyx_n_s_all_readers_updated +#define __pyx_n_s_asyncio_coroutines __pyx_mstate_global->__pyx_n_s_asyncio_coroutines +#define __pyx_n_s_cereal_messaging_messaging_pyx __pyx_mstate_global->__pyx_n_s_cereal_messaging_messaging_pyx +#define __pyx_kp_s_cereal_messaging_messaging_pyx_p __pyx_mstate_global->__pyx_kp_s_cereal_messaging_messaging_pyx_p +#define __pyx_n_s_clear __pyx_mstate_global->__pyx_n_s_clear +#define __pyx_n_s_cline_in_traceback __pyx_mstate_global->__pyx_n_s_cline_in_traceback +#define __pyx_n_s_conflate __pyx_mstate_global->__pyx_n_s_conflate +#define __pyx_n_s_connect __pyx_mstate_global->__pyx_n_s_connect +#define __pyx_n_s_context __pyx_mstate_global->__pyx_n_s_context +#define __pyx_n_s_data __pyx_mstate_global->__pyx_n_s_data +#define __pyx_n_s_decode __pyx_mstate_global->__pyx_n_s_decode +#define __pyx_n_s_delete_fake_prefix __pyx_mstate_global->__pyx_n_s_delete_fake_prefix +#define __pyx_n_s_dict __pyx_mstate_global->__pyx_n_s_dict +#define __pyx_kp_u_disable __pyx_mstate_global->__pyx_kp_u_disable +#define __pyx_n_s_doc __pyx_mstate_global->__pyx_n_s_doc +#define __pyx_kp_u_enable __pyx_mstate_global->__pyx_kp_u_enable +#define __pyx_n_s_enabled __pyx_mstate_global->__pyx_n_s_enabled +#define __pyx_n_s_endpoint __pyx_mstate_global->__pyx_n_s_endpoint +#define __pyx_n_s_event __pyx_mstate_global->__pyx_n_s_event +#define __pyx_n_s_events __pyx_mstate_global->__pyx_n_s_events +#define __pyx_n_s_exit __pyx_mstate_global->__pyx_n_s_exit +#define __pyx_kp_u_gc __pyx_mstate_global->__pyx_kp_u_gc +#define __pyx_n_s_get_fake_prefix __pyx_mstate_global->__pyx_n_s_get_fake_prefix +#define __pyx_n_s_getstate __pyx_mstate_global->__pyx_n_s_getstate +#define __pyx_n_s_identifier __pyx_mstate_global->__pyx_n_s_identifier +#define __pyx_n_s_import __pyx_mstate_global->__pyx_n_s_import +#define __pyx_n_s_init __pyx_mstate_global->__pyx_n_s_init +#define __pyx_n_s_init_subclass __pyx_mstate_global->__pyx_n_s_init_subclass +#define __pyx_n_s_initializing __pyx_mstate_global->__pyx_n_s_initializing +#define __pyx_n_s_is_coroutine __pyx_mstate_global->__pyx_n_s_is_coroutine +#define __pyx_kp_u_isenabled __pyx_mstate_global->__pyx_kp_u_isenabled +#define __pyx_n_s_items __pyx_mstate_global->__pyx_n_s_items +#define __pyx_n_s_length __pyx_mstate_global->__pyx_n_s_length +#define __pyx_n_s_m __pyx_mstate_global->__pyx_n_s_m +#define __pyx_n_s_main __pyx_mstate_global->__pyx_n_s_main +#define __pyx_n_s_message __pyx_mstate_global->__pyx_n_s_message +#define __pyx_n_s_metaclass __pyx_mstate_global->__pyx_n_s_metaclass +#define __pyx_n_s_module __pyx_mstate_global->__pyx_n_s_module +#define __pyx_n_s_mro_entries __pyx_mstate_global->__pyx_n_s_mro_entries +#define __pyx_n_s_msg __pyx_mstate_global->__pyx_n_s_msg +#define __pyx_n_s_name __pyx_mstate_global->__pyx_n_s_name +#define __pyx_kp_s_no_default___reduce___due_to_non __pyx_mstate_global->__pyx_kp_s_no_default___reduce___due_to_non +#define __pyx_n_s_non_blocking __pyx_mstate_global->__pyx_n_s_non_blocking +#define __pyx_n_s_override __pyx_mstate_global->__pyx_n_s_override +#define __pyx_n_s_peek __pyx_mstate_global->__pyx_n_s_peek +#define __pyx_n_s_poll __pyx_mstate_global->__pyx_n_s_poll +#define __pyx_n_s_prefix __pyx_mstate_global->__pyx_n_s_prefix +#define __pyx_n_s_prepare __pyx_mstate_global->__pyx_n_s_prepare +#define __pyx_n_s_print __pyx_mstate_global->__pyx_n_s_print +#define __pyx_n_s_ptr __pyx_mstate_global->__pyx_n_s_ptr +#define __pyx_n_s_pyx_state __pyx_mstate_global->__pyx_n_s_pyx_state +#define __pyx_n_s_pyx_vtable __pyx_mstate_global->__pyx_n_s_pyx_vtable +#define __pyx_n_s_qualname __pyx_mstate_global->__pyx_n_s_qualname +#define __pyx_n_s_r __pyx_mstate_global->__pyx_n_s_r +#define __pyx_n_s_receive __pyx_mstate_global->__pyx_n_s_receive +#define __pyx_n_s_reduce __pyx_mstate_global->__pyx_n_s_reduce +#define __pyx_n_s_reduce_cython __pyx_mstate_global->__pyx_n_s_reduce_cython +#define __pyx_n_s_reduce_ex __pyx_mstate_global->__pyx_n_s_reduce_ex +#define __pyx_n_s_registerSocket __pyx_mstate_global->__pyx_n_s_registerSocket +#define __pyx_n_s_result __pyx_mstate_global->__pyx_n_s_result +#define __pyx_n_s_s __pyx_mstate_global->__pyx_n_s_s +#define __pyx_n_s_self __pyx_mstate_global->__pyx_n_s_self +#define __pyx_n_s_send __pyx_mstate_global->__pyx_n_s_send +#define __pyx_n_s_set __pyx_mstate_global->__pyx_n_s_set +#define __pyx_n_s_setTimeout __pyx_mstate_global->__pyx_n_s_setTimeout +#define __pyx_n_s_set_fake_prefix __pyx_mstate_global->__pyx_n_s_set_fake_prefix +#define __pyx_n_s_set_name __pyx_mstate_global->__pyx_n_s_set_name +#define __pyx_n_s_setstate __pyx_mstate_global->__pyx_n_s_setstate +#define __pyx_n_s_setstate_cython __pyx_mstate_global->__pyx_n_s_setstate_cython +#define __pyx_n_s_socket __pyx_mstate_global->__pyx_n_s_socket +#define __pyx_n_s_sockets __pyx_mstate_global->__pyx_n_s_sockets +#define __pyx_n_s_spec __pyx_mstate_global->__pyx_n_s_spec +#define __pyx_kp_s_stringsource __pyx_mstate_global->__pyx_kp_s_stringsource +#define __pyx_n_s_suffix __pyx_mstate_global->__pyx_n_s_suffix +#define __pyx_n_s_super __pyx_mstate_global->__pyx_n_s_super +#define __pyx_n_s_sys __pyx_mstate_global->__pyx_n_s_sys +#define __pyx_n_s_sz __pyx_mstate_global->__pyx_n_s_sz +#define __pyx_n_s_t __pyx_mstate_global->__pyx_n_s_t +#define __pyx_n_s_term __pyx_mstate_global->__pyx_n_s_term +#define __pyx_n_s_test __pyx_mstate_global->__pyx_n_s_test +#define __pyx_n_s_timeout __pyx_mstate_global->__pyx_n_s_timeout +#define __pyx_n_s_toggle_fake_events __pyx_mstate_global->__pyx_n_s_toggle_fake_events +#define __pyx_kp_u_utf_8 __pyx_mstate_global->__pyx_kp_u_utf_8 +#define __pyx_n_s_wait __pyx_mstate_global->__pyx_n_s_wait +#define __pyx_n_s_wait_for_one_event __pyx_mstate_global->__pyx_n_s_wait_for_one_event +#define __pyx_kp_u_with __pyx_mstate_global->__pyx_kp_u_with +#define __pyx_int_1 __pyx_mstate_global->__pyx_int_1 +#define __pyx_int_neg_1 __pyx_mstate_global->__pyx_int_neg_1 +#define __pyx_k__3 __pyx_mstate_global->__pyx_k__3 +#define __pyx_tuple__4 __pyx_mstate_global->__pyx_tuple__4 +#define __pyx_tuple__6 __pyx_mstate_global->__pyx_tuple__6 +#define __pyx_tuple__8 __pyx_mstate_global->__pyx_tuple__8 +#define __pyx_tuple__9 __pyx_mstate_global->__pyx_tuple__9 +#define __pyx_tuple__11 __pyx_mstate_global->__pyx_tuple__11 +#define __pyx_tuple__15 __pyx_mstate_global->__pyx_tuple__15 +#define __pyx_tuple__17 __pyx_mstate_global->__pyx_tuple__17 +#define __pyx_tuple__20 __pyx_mstate_global->__pyx_tuple__20 +#define __pyx_tuple__22 __pyx_mstate_global->__pyx_tuple__22 +#define __pyx_tuple__25 __pyx_mstate_global->__pyx_tuple__25 +#define __pyx_tuple__32 __pyx_mstate_global->__pyx_tuple__32 +#define __pyx_tuple__34 __pyx_mstate_global->__pyx_tuple__34 +#define __pyx_tuple__38 __pyx_mstate_global->__pyx_tuple__38 +#define __pyx_tuple__41 __pyx_mstate_global->__pyx_tuple__41 +#define __pyx_tuple__43 __pyx_mstate_global->__pyx_tuple__43 +#define __pyx_tuple__46 __pyx_mstate_global->__pyx_tuple__46 +#define __pyx_tuple__48 __pyx_mstate_global->__pyx_tuple__48 +#define __pyx_codeobj__7 __pyx_mstate_global->__pyx_codeobj__7 +#define __pyx_codeobj__10 __pyx_mstate_global->__pyx_codeobj__10 +#define __pyx_codeobj__12 __pyx_mstate_global->__pyx_codeobj__12 +#define __pyx_codeobj__13 __pyx_mstate_global->__pyx_codeobj__13 +#define __pyx_codeobj__14 __pyx_mstate_global->__pyx_codeobj__14 +#define __pyx_codeobj__16 __pyx_mstate_global->__pyx_codeobj__16 +#define __pyx_codeobj__18 __pyx_mstate_global->__pyx_codeobj__18 +#define __pyx_codeobj__19 __pyx_mstate_global->__pyx_codeobj__19 +#define __pyx_codeobj__21 __pyx_mstate_global->__pyx_codeobj__21 +#define __pyx_codeobj__23 __pyx_mstate_global->__pyx_codeobj__23 +#define __pyx_codeobj__24 __pyx_mstate_global->__pyx_codeobj__24 +#define __pyx_codeobj__26 __pyx_mstate_global->__pyx_codeobj__26 +#define __pyx_codeobj__27 __pyx_mstate_global->__pyx_codeobj__27 +#define __pyx_codeobj__28 __pyx_mstate_global->__pyx_codeobj__28 +#define __pyx_codeobj__29 __pyx_mstate_global->__pyx_codeobj__29 +#define __pyx_codeobj__30 __pyx_mstate_global->__pyx_codeobj__30 +#define __pyx_codeobj__31 __pyx_mstate_global->__pyx_codeobj__31 +#define __pyx_codeobj__33 __pyx_mstate_global->__pyx_codeobj__33 +#define __pyx_codeobj__35 __pyx_mstate_global->__pyx_codeobj__35 +#define __pyx_codeobj__36 __pyx_mstate_global->__pyx_codeobj__36 +#define __pyx_codeobj__37 __pyx_mstate_global->__pyx_codeobj__37 +#define __pyx_codeobj__39 __pyx_mstate_global->__pyx_codeobj__39 +#define __pyx_codeobj__40 __pyx_mstate_global->__pyx_codeobj__40 +#define __pyx_codeobj__42 __pyx_mstate_global->__pyx_codeobj__42 +#define __pyx_codeobj__44 __pyx_mstate_global->__pyx_codeobj__44 +#define __pyx_codeobj__45 __pyx_mstate_global->__pyx_codeobj__45 +#define __pyx_codeobj__47 __pyx_mstate_global->__pyx_codeobj__47 +#define __pyx_codeobj__49 __pyx_mstate_global->__pyx_codeobj__49 +#define __pyx_codeobj__50 __pyx_mstate_global->__pyx_codeobj__50 +#define __pyx_codeobj__51 __pyx_mstate_global->__pyx_codeobj__51 +#define __pyx_codeobj__52 __pyx_mstate_global->__pyx_codeobj__52 +/* #### Code section: module_code ### */ + +/* "string.from_py":13 + * + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: # <<<<<<<<<<<<<< + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + */ + +static std::string __pyx_convert_string_from_py_std__in_string(PyObject *__pyx_v_o) { + Py_ssize_t __pyx_v_length; + char const *__pyx_v_data; + std::string __pyx_r; + char const *__pyx_t_1; + std::string __pyx_t_2; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + + /* "string.from_py":14 + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: + * cdef Py_ssize_t length = 0 # <<<<<<<<<<<<<< + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + * return string(data, length) + */ + __pyx_v_length = 0; + + /* "string.from_py":15 + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) # <<<<<<<<<<<<<< + * return string(data, length) + * + */ + __pyx_t_1 = __Pyx_PyObject_AsStringAndSize(__pyx_v_o, (&__pyx_v_length)); if (unlikely(__pyx_t_1 == ((char const *)NULL))) __PYX_ERR(1, 15, __pyx_L1_error) + __pyx_v_data = __pyx_t_1; + + /* "string.from_py":16 + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + * return string(data, length) # <<<<<<<<<<<<<< + * + * + */ + try { + __pyx_t_2 = std::string(__pyx_v_data, __pyx_v_length); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(1, 16, __pyx_L1_error) + } + __pyx_r = __pyx_t_2; + goto __pyx_L0; + + /* "string.from_py":13 + * + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: # <<<<<<<<<<<<<< + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("string.from_py.__pyx_convert_string_from_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_pretend_to_initialize(&__pyx_r); + __pyx_L0:; + return __pyx_r; +} + +/* "string.to_py":31 + * + * @cname("__pyx_convert_PyObject_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyObject_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyObject_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyObject_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyObject_string_to_py_std__in_string", 1); + + /* "string.to_py":32 + * @cname("__pyx_convert_PyObject_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyObject_string_to_py_std__in_string(const string& s): + * return __Pyx_PyObject_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * cdef extern from *: + * cdef object __Pyx_PyUnicode_FromStringAndSize(const char*, size_t) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 32, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":31 + * + * @cname("__pyx_convert_PyObject_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyObject_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyObject_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyObject_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":37 + * + * @cname("__pyx_convert_PyUnicode_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyUnicode_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyUnicode_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyUnicode_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyUnicode_string_to_py_std__in_string", 1); + + /* "string.to_py":38 + * @cname("__pyx_convert_PyUnicode_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyUnicode_string_to_py_std__in_string(const string& s): + * return __Pyx_PyUnicode_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * cdef extern from *: + * cdef object __Pyx_PyStr_FromStringAndSize(const char*, size_t) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyUnicode_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 38, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":37 + * + * @cname("__pyx_convert_PyUnicode_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyUnicode_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyUnicode_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyUnicode_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":43 + * + * @cname("__pyx_convert_PyStr_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyStr_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyStr_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyStr_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyStr_string_to_py_std__in_string", 1); + + /* "string.to_py":44 + * @cname("__pyx_convert_PyStr_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyStr_string_to_py_std__in_string(const string& s): + * return __Pyx_PyStr_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * cdef extern from *: + * cdef object __Pyx_PyBytes_FromStringAndSize(const char*, size_t) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyStr_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 44, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":43 + * + * @cname("__pyx_convert_PyStr_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyStr_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyStr_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyStr_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":49 + * + * @cname("__pyx_convert_PyBytes_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyBytes_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyBytes_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyBytes_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyBytes_string_to_py_std__in_string", 1); + + /* "string.to_py":50 + * @cname("__pyx_convert_PyBytes_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyBytes_string_to_py_std__in_string(const string& s): + * return __Pyx_PyBytes_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * cdef extern from *: + * cdef object __Pyx_PyByteArray_FromStringAndSize(const char*, size_t) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyBytes_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 50, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":49 + * + * @cname("__pyx_convert_PyBytes_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyBytes_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyBytes_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyBytes_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":55 + * + * @cname("__pyx_convert_PyByteArray_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyByteArray_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyByteArray_FromStringAndSize(s.data(), s.size()) + * + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyByteArray_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyByteArray_string_to_py_std__in_string", 1); + + /* "string.to_py":56 + * @cname("__pyx_convert_PyByteArray_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyByteArray_string_to_py_std__in_string(const string& s): + * return __Pyx_PyByteArray_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyByteArray_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 56, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":55 + * + * @cname("__pyx_convert_PyByteArray_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyByteArray_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyByteArray_FromStringAndSize(s.data(), s.size()) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyByteArray_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":22 + * + * class MessagingError(Exception): + * def __init__(self, endpoint=None): # <<<<<<<<<<<<<< + * suffix = f"with {endpoint.decode('utf-8')}" if endpoint else "" + * message = f"Messaging failure {suffix}: {strerror(errno.errno).decode('utf-8')}" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_14MessagingError_1__init__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_14MessagingError_1__init__ = {"__init__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_14MessagingError_1__init__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_14MessagingError_1__init__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_self = 0; + PyObject *__pyx_v_endpoint = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[2] = {0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__init__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_self,&__pyx_n_s_endpoint,0}; + values[1] = __Pyx_Arg_NewRef_FASTCALL(((PyObject *)Py_None)); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_self)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 22, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_endpoint); + if (value) { values[1] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 22, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__init__") < 0)) __PYX_ERR(0, 22, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_self = values[0]; + __pyx_v_endpoint = values[1]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__init__", 0, 1, 2, __pyx_nargs); __PYX_ERR(0, 22, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.MessagingError.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_14MessagingError___init__(__pyx_self, __pyx_v_self, __pyx_v_endpoint); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_14MessagingError___init__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_self, PyObject *__pyx_v_endpoint) { + PyObject *__pyx_v_suffix = NULL; + PyObject *__pyx_v_message = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + Py_ssize_t __pyx_t_7; + Py_UCS4 __pyx_t_8; + char *__pyx_t_9; + Py_ssize_t __pyx_t_10; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__init__", 1); + + /* "cereal/messaging/messaging_pyx.pyx":23 + * class MessagingError(Exception): + * def __init__(self, endpoint=None): + * suffix = f"with {endpoint.decode('utf-8')}" if endpoint else "" # <<<<<<<<<<<<<< + * message = f"Messaging failure {suffix}: {strerror(errno.errno).decode('utf-8')}" + * super().__init__(message) + */ + __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_v_endpoint); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 23, __pyx_L1_error) + if (__pyx_t_2) { + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_v_endpoint, __pyx_n_s_decode); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 23, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_4))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_4); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_4); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_4, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_5, __pyx_kp_u_utf_8}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_6, 1+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 23, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + __pyx_t_4 = __Pyx_PyObject_FormatSimple(__pyx_t_3, __pyx_empty_unicode); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 23, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PyUnicode_Concat(__pyx_kp_u_with, __pyx_t_4); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 23, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_1 = __pyx_t_3; + __pyx_t_3 = 0; + } else { + __Pyx_INCREF(__pyx_kp_u_); + __pyx_t_1 = __pyx_kp_u_; + } + __pyx_v_suffix = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":24 + * def __init__(self, endpoint=None): + * suffix = f"with {endpoint.decode('utf-8')}" if endpoint else "" + * message = f"Messaging failure {suffix}: {strerror(errno.errno).decode('utf-8')}" # <<<<<<<<<<<<<< + * super().__init__(message) + * + */ + __pyx_t_1 = PyTuple_New(4); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 24, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = 0; + __pyx_t_8 = 127; + __Pyx_INCREF(__pyx_kp_u_Messaging_failure); + __pyx_t_7 += 18; + __Pyx_GIVEREF(__pyx_kp_u_Messaging_failure); + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_kp_u_Messaging_failure); + __pyx_t_3 = __Pyx_PyUnicode_Unicode(__pyx_v_suffix); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 24, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_8 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_3) > __pyx_t_8) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_3) : __pyx_t_8; + __pyx_t_7 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_3); + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_t_3); + __pyx_t_3 = 0; + __Pyx_INCREF(__pyx_kp_u__2); + __pyx_t_7 += 2; + __Pyx_GIVEREF(__pyx_kp_u__2); + PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_kp_u__2); + __pyx_t_9 = strerror(errno); + __pyx_t_10 = __Pyx_ssize_strlen(__pyx_t_9); if (unlikely(__pyx_t_10 == ((Py_ssize_t)-1))) __PYX_ERR(0, 24, __pyx_L1_error) + __pyx_t_3 = __Pyx_decode_c_string(__pyx_t_9, 0, __pyx_t_10, NULL, NULL, PyUnicode_DecodeUTF8); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 24, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_t_3); + __pyx_t_8 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_3) > __pyx_t_8) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_3) : __pyx_t_8; + __pyx_t_7 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_3); + PyTuple_SET_ITEM(__pyx_t_1, 3, __pyx_t_3); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PyUnicode_Join(__pyx_t_1, 4, __pyx_t_7, __pyx_t_8); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 24, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_message = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":25 + * suffix = f"with {endpoint.decode('utf-8')}" if endpoint else "" + * message = f"Messaging failure {suffix}: {strerror(errno.errno).decode('utf-8')}" + * super().__init__(message) # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_1 = __Pyx_CyFunction_GetClassObj(__pyx_self); + if (!__pyx_t_1) { PyErr_SetString(PyExc_SystemError, "super(): empty __class__ cell"); __PYX_ERR(0, 25, __pyx_L1_error) } + __Pyx_INCREF(__pyx_t_1); + __pyx_t_4 = PyTuple_New(2); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 25, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_1)) __PYX_ERR(0, 25, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_self); + __Pyx_GIVEREF(__pyx_v_self); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_v_self)) __PYX_ERR(0, 25, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_Call(__pyx_builtin_super, __pyx_t_4, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 25, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_init); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 25, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_4))) { + __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_4); + if (likely(__pyx_t_1)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_4); + __Pyx_INCREF(__pyx_t_1); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_4, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_1, __pyx_v_message}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_6, 1+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 25, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":22 + * + * class MessagingError(Exception): + * def __init__(self, endpoint=None): # <<<<<<<<<<<<<< + * suffix = f"with {endpoint.decode('utf-8')}" if endpoint else "" + * message = f"Messaging failure {suffix}: {strerror(errno.errno).decode('utf-8')}" + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.MessagingError.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_suffix); + __Pyx_XDECREF(__pyx_v_message); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":32 + * + * + * def toggle_fake_events(bool enabled): # <<<<<<<<<<<<<< + * cppSocketEventHandle.toggle_fake_events(enabled) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_1toggle_fake_events(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_1toggle_fake_events = {"toggle_fake_events", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_1toggle_fake_events, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_1toggle_fake_events(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + bool __pyx_v_enabled; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("toggle_fake_events (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_enabled,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_enabled)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 32, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "toggle_fake_events") < 0)) __PYX_ERR(0, 32, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_enabled = __Pyx_PyObject_IsTrue(values[0]); if (unlikely((__pyx_v_enabled == ((bool)-1)) && PyErr_Occurred())) __PYX_ERR(0, 32, __pyx_L3_error) + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("toggle_fake_events", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 32, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.toggle_fake_events", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_toggle_fake_events(__pyx_self, __pyx_v_enabled); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_toggle_fake_events(CYTHON_UNUSED PyObject *__pyx_self, bool __pyx_v_enabled) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("toggle_fake_events", 1); + + /* "cereal/messaging/messaging_pyx.pyx":33 + * + * def toggle_fake_events(bool enabled): + * cppSocketEventHandle.toggle_fake_events(enabled) # <<<<<<<<<<<<<< + * + * + */ + SocketEventHandle::toggle_fake_events(__pyx_v_enabled); + + /* "cereal/messaging/messaging_pyx.pyx":32 + * + * + * def toggle_fake_events(bool enabled): # <<<<<<<<<<<<<< + * cppSocketEventHandle.toggle_fake_events(enabled) + * + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":36 + * + * + * def set_fake_prefix(string prefix): # <<<<<<<<<<<<<< + * cppSocketEventHandle.set_fake_prefix(prefix) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_3set_fake_prefix(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_3set_fake_prefix = {"set_fake_prefix", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_3set_fake_prefix, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_3set_fake_prefix(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + std::string __pyx_v_prefix; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("set_fake_prefix (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_prefix,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_prefix)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 36, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "set_fake_prefix") < 0)) __PYX_ERR(0, 36, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_prefix = __pyx_convert_string_from_py_std__in_string(values[0]); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 36, __pyx_L3_error) + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("set_fake_prefix", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 36, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.set_fake_prefix", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_2set_fake_prefix(__pyx_self, __PYX_STD_MOVE_IF_SUPPORTED(__pyx_v_prefix)); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_2set_fake_prefix(CYTHON_UNUSED PyObject *__pyx_self, std::string __pyx_v_prefix) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("set_fake_prefix", 1); + + /* "cereal/messaging/messaging_pyx.pyx":37 + * + * def set_fake_prefix(string prefix): + * cppSocketEventHandle.set_fake_prefix(prefix) # <<<<<<<<<<<<<< + * + * + */ + SocketEventHandle::set_fake_prefix(__pyx_v_prefix); + + /* "cereal/messaging/messaging_pyx.pyx":36 + * + * + * def set_fake_prefix(string prefix): # <<<<<<<<<<<<<< + * cppSocketEventHandle.set_fake_prefix(prefix) + * + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":40 + * + * + * def get_fake_prefix(): # <<<<<<<<<<<<<< + * return cppSocketEventHandle.fake_prefix() + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_5get_fake_prefix(PyObject *__pyx_self, CYTHON_UNUSED PyObject *unused); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_5get_fake_prefix = {"get_fake_prefix", (PyCFunction)__pyx_pw_6cereal_9messaging_13messaging_pyx_5get_fake_prefix, METH_NOARGS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_5get_fake_prefix(PyObject *__pyx_self, CYTHON_UNUSED PyObject *unused) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("get_fake_prefix (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_4get_fake_prefix(__pyx_self); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_4get_fake_prefix(CYTHON_UNUSED PyObject *__pyx_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_fake_prefix", 1); + + /* "cereal/messaging/messaging_pyx.pyx":41 + * + * def get_fake_prefix(): + * return cppSocketEventHandle.fake_prefix() # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __pyx_convert_PyBytes_string_to_py_std__in_string(SocketEventHandle::fake_prefix()); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 41, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/messaging/messaging_pyx.pyx":40 + * + * + * def get_fake_prefix(): # <<<<<<<<<<<<<< + * return cppSocketEventHandle.fake_prefix() + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.get_fake_prefix", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":44 + * + * + * def delete_fake_prefix(): # <<<<<<<<<<<<<< + * cppSocketEventHandle.set_fake_prefix(b"") + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_7delete_fake_prefix(PyObject *__pyx_self, CYTHON_UNUSED PyObject *unused); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_7delete_fake_prefix = {"delete_fake_prefix", (PyCFunction)__pyx_pw_6cereal_9messaging_13messaging_pyx_7delete_fake_prefix, METH_NOARGS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_7delete_fake_prefix(PyObject *__pyx_self, CYTHON_UNUSED PyObject *unused) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("delete_fake_prefix (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_6delete_fake_prefix(__pyx_self); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_6delete_fake_prefix(CYTHON_UNUSED PyObject *__pyx_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + std::string __pyx_t_1; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("delete_fake_prefix", 1); + + /* "cereal/messaging/messaging_pyx.pyx":45 + * + * def delete_fake_prefix(): + * cppSocketEventHandle.set_fake_prefix(b"") # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_1 = __pyx_convert_string_from_py_std__in_string(__pyx_kp_b_); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 45, __pyx_L1_error) + SocketEventHandle::set_fake_prefix(__PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_1)); + + /* "cereal/messaging/messaging_pyx.pyx":44 + * + * + * def delete_fake_prefix(): # <<<<<<<<<<<<<< + * cppSocketEventHandle.set_fake_prefix(b"") + * + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.delete_fake_prefix", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":48 + * + * + * def wait_for_one_event(list events, int timeout=-1): # <<<<<<<<<<<<<< + * cdef vector[cppEvent] items + * for event in events: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_9wait_for_one_event(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_9wait_for_one_event = {"wait_for_one_event", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_9wait_for_one_event, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_9wait_for_one_event(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_events = 0; + int __pyx_v_timeout; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[2] = {0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("wait_for_one_event (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_events,&__pyx_n_s_timeout,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_events)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 48, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_timeout); + if (value) { values[1] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 48, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "wait_for_one_event") < 0)) __PYX_ERR(0, 48, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_events = ((PyObject*)values[0]); + if (values[1]) { + __pyx_v_timeout = __Pyx_PyInt_As_int(values[1]); if (unlikely((__pyx_v_timeout == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 48, __pyx_L3_error) + } else { + __pyx_v_timeout = ((int)((int)-1)); + } + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("wait_for_one_event", 0, 1, 2, __pyx_nargs); __PYX_ERR(0, 48, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.wait_for_one_event", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_events), (&PyList_Type), 1, "events", 1))) __PYX_ERR(0, 48, __pyx_L1_error) + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_8wait_for_one_event(__pyx_self, __pyx_v_events, __pyx_v_timeout); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = NULL; + __pyx_L0:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_8wait_for_one_event(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_events, int __pyx_v_timeout) { + std::vector __pyx_v_items; + PyObject *__pyx_v_event = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + Py_ssize_t __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + size_t __pyx_t_4; + int __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("wait_for_one_event", 1); + + /* "cereal/messaging/messaging_pyx.pyx":50 + * def wait_for_one_event(list events, int timeout=-1): + * cdef vector[cppEvent] items + * for event in events: # <<<<<<<<<<<<<< + * items.push_back(dereference(event.ptr)) + * return cppEvent.wait_for_one(items, timeout) + */ + if (unlikely(__pyx_v_events == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not iterable"); + __PYX_ERR(0, 50, __pyx_L1_error) + } + __pyx_t_1 = __pyx_v_events; __Pyx_INCREF(__pyx_t_1); + __pyx_t_2 = 0; + for (;;) { + { + Py_ssize_t __pyx_temp = __Pyx_PyList_GET_SIZE(__pyx_t_1); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 50, __pyx_L1_error) + #endif + if (__pyx_t_2 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_3 = PyList_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_3); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(0, 50, __pyx_L1_error) + #else + __pyx_t_3 = __Pyx_PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 50, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + #endif + __Pyx_XDECREF_SET(__pyx_v_event, __pyx_t_3); + __pyx_t_3 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":51 + * cdef vector[cppEvent] items + * for event in events: + * items.push_back(dereference(event.ptr)) # <<<<<<<<<<<<<< + * return cppEvent.wait_for_one(items, timeout) + * + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_v_event, __pyx_n_s_ptr); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 51, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = __Pyx_PyInt_As_size_t(__pyx_t_3); if (unlikely((__pyx_t_4 == (size_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 51, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + try { + __pyx_v_items.push_back((*((Event *)((size_t)__pyx_t_4)))); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(0, 51, __pyx_L1_error) + } + + /* "cereal/messaging/messaging_pyx.pyx":50 + * def wait_for_one_event(list events, int timeout=-1): + * cdef vector[cppEvent] items + * for event in events: # <<<<<<<<<<<<<< + * items.push_back(dereference(event.ptr)) + * return cppEvent.wait_for_one(items, timeout) + */ + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":52 + * for event in events: + * items.push_back(dereference(event.ptr)) + * return cppEvent.wait_for_one(items, timeout) # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + try { + __pyx_t_5 = Event::wait_for_one(__pyx_v_items, __pyx_v_timeout); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(0, 52, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_t_5); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 52, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/messaging/messaging_pyx.pyx":48 + * + * + * def wait_for_one_event(list events, int timeout=-1): # <<<<<<<<<<<<<< + * cdef vector[cppEvent] items + * for event in events: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.wait_for_one_event", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_event); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":58 + * cdef cppEvent event; + * + * def __cinit__(self): # <<<<<<<<<<<<<< + * pass + * + */ + +/* Python wrapper */ +static int __pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 0, 0, __pyx_nargs); return -1;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_VARARGS(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__cinit__", 0))) return -1; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_5Event___cinit__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_6cereal_9messaging_13messaging_pyx_5Event___cinit__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *__pyx_v_self) { + int __pyx_r; + + /* function exit code */ + __pyx_r = 0; + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":61 + * pass + * + * cdef setEvent(self, cppEvent event): # <<<<<<<<<<<<<< + * self.event = event + * + */ + +static PyObject *__pyx_f_6cereal_9messaging_13messaging_pyx_5Event_setEvent(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *__pyx_v_self, Event __pyx_v_event) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("setEvent", 1); + + /* "cereal/messaging/messaging_pyx.pyx":62 + * + * cdef setEvent(self, cppEvent event): + * self.event = event # <<<<<<<<<<<<<< + * + * def set(self): + */ + __pyx_v_self->event = __pyx_v_event; + + /* "cereal/messaging/messaging_pyx.pyx":61 + * pass + * + * cdef setEvent(self, cppEvent event): # <<<<<<<<<<<<<< + * self.event = event + * + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":64 + * self.event = event + * + * def set(self): # <<<<<<<<<<<<<< + * self.event.set() + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_3set(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_5Event_3set = {"set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_3set, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_3set(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("set (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("set", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "set", 0))) return NULL; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_2set(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_2set(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("set", 1); + + /* "cereal/messaging/messaging_pyx.pyx":65 + * + * def set(self): + * self.event.set() # <<<<<<<<<<<<<< + * + * def clear(self): + */ + __pyx_v_self->event.set(); + + /* "cereal/messaging/messaging_pyx.pyx":64 + * self.event = event + * + * def set(self): # <<<<<<<<<<<<<< + * self.event.set() + * + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":67 + * self.event.set() + * + * def clear(self): # <<<<<<<<<<<<<< + * return self.event.clear() + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_5clear(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_5Event_5clear = {"clear", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_5clear, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_5clear(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("clear (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("clear", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "clear", 0))) return NULL; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_4clear(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_4clear(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("clear", 1); + + /* "cereal/messaging/messaging_pyx.pyx":68 + * + * def clear(self): + * return self.event.clear() # <<<<<<<<<<<<<< + * + * def wait(self, int timeout=-1): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_self->event.clear()); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 68, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/messaging/messaging_pyx.pyx":67 + * self.event.set() + * + * def clear(self): # <<<<<<<<<<<<<< + * return self.event.clear() + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.Event.clear", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":70 + * return self.event.clear() + * + * def wait(self, int timeout=-1): # <<<<<<<<<<<<<< + * self.event.wait(timeout) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_7wait(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_5Event_7wait = {"wait", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_7wait, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_7wait(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + int __pyx_v_timeout; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("wait (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_timeout,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_timeout); + if (value) { values[0] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 70, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "wait") < 0)) __PYX_ERR(0, 70, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + } + if (values[0]) { + __pyx_v_timeout = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_timeout == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 70, __pyx_L3_error) + } else { + __pyx_v_timeout = ((int)-1); + } + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("wait", 0, 0, 1, __pyx_nargs); __PYX_ERR(0, 70, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.Event.wait", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_6wait(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *)__pyx_v_self), __pyx_v_timeout); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_6wait(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *__pyx_v_self, int __pyx_v_timeout) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("wait", 1); + + /* "cereal/messaging/messaging_pyx.pyx":71 + * + * def wait(self, int timeout=-1): + * self.event.wait(timeout) # <<<<<<<<<<<<<< + * + * def peek(self): + */ + try { + __pyx_v_self->event.wait(__pyx_v_timeout); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(0, 71, __pyx_L1_error) + } + + /* "cereal/messaging/messaging_pyx.pyx":70 + * return self.event.clear() + * + * def wait(self, int timeout=-1): # <<<<<<<<<<<<<< + * self.event.wait(timeout) + * + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.Event.wait", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":73 + * self.event.wait(timeout) + * + * def peek(self): # <<<<<<<<<<<<<< + * return self.event.peek() + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_9peek(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_5Event_9peek = {"peek", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_9peek, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_9peek(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("peek (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("peek", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "peek", 0))) return NULL; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_8peek(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_8peek(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("peek", 1); + + /* "cereal/messaging/messaging_pyx.pyx":74 + * + * def peek(self): + * return self.event.peek() # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyBool_FromLong(__pyx_v_self->event.peek()); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 74, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/messaging/messaging_pyx.pyx":73 + * self.event.wait(timeout) + * + * def peek(self): # <<<<<<<<<<<<<< + * return self.event.peek() + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.Event.peek", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":76 + * return self.event.peek() + * + * @property # <<<<<<<<<<<<<< + * def fd(self): + * return self.event.fd() + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_2fd_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_2fd_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_2fd___get__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_2fd___get__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "cereal/messaging/messaging_pyx.pyx":78 + * @property + * def fd(self): + * return self.event.fd() # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_self->event.fd()); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 78, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/messaging/messaging_pyx.pyx":76 + * return self.event.peek() + * + * @property # <<<<<<<<<<<<<< + * def fd(self): + * return self.event.fd() + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.Event.fd.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":80 + * return self.event.fd() + * + * @property # <<<<<<<<<<<<<< + * def ptr(self): + * return &self.event + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_3ptr_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_3ptr_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_3ptr___get__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_3ptr___get__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "cereal/messaging/messaging_pyx.pyx":82 + * @property + * def ptr(self): + * return &self.event # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_FromSize_t(((size_t)((void *)(&__pyx_v_self->event)))); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 82, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/messaging/messaging_pyx.pyx":80 + * return self.event.fd() + * + * @property # <<<<<<<<<<<<<< + * def ptr(self): + * return &self.event + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.Event.ptr.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_11__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_5Event_11__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_11__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_11__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_10__reduce_cython__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_10__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.Event.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_13__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_5Event_13__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_13__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_13__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.Event.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_12__setstate_cython__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_5Event_12__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.Event.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":88 + * cdef cppSocketEventHandle * handle; + * + * def __cinit__(self, string endpoint, string identifier, bool override): # <<<<<<<<<<<<<< + * self.handle = new cppSocketEventHandle(endpoint, identifier, override) + * + */ + +/* Python wrapper */ +static int __pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + std::string __pyx_v_endpoint; + std::string __pyx_v_identifier; + bool __pyx_v_override; + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_endpoint,&__pyx_n_s_identifier,&__pyx_n_s_override,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_endpoint)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 88, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_identifier)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 88, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 3, 3, 1); __PYX_ERR(0, 88, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_override)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 88, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 3, 3, 2); __PYX_ERR(0, 88, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(0, 88, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + } + __pyx_v_endpoint = __pyx_convert_string_from_py_std__in_string(values[0]); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 88, __pyx_L3_error) + __pyx_v_identifier = __pyx_convert_string_from_py_std__in_string(values[1]); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 88, __pyx_L3_error) + __pyx_v_override = __Pyx_PyObject_IsTrue(values[2]); if (unlikely((__pyx_v_override == ((bool)-1)) && PyErr_Occurred())) __PYX_ERR(0, 88, __pyx_L3_error) + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 88, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.SocketEventHandle.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle___cinit__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *)__pyx_v_self), __PYX_STD_MOVE_IF_SUPPORTED(__pyx_v_endpoint), __PYX_STD_MOVE_IF_SUPPORTED(__pyx_v_identifier), __pyx_v_override); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle___cinit__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *__pyx_v_self, std::string __pyx_v_endpoint, std::string __pyx_v_identifier, bool __pyx_v_override) { + int __pyx_r; + + /* "cereal/messaging/messaging_pyx.pyx":89 + * + * def __cinit__(self, string endpoint, string identifier, bool override): + * self.handle = new cppSocketEventHandle(endpoint, identifier, override) # <<<<<<<<<<<<<< + * + * def __dealloc__(self): + */ + __pyx_v_self->handle = new SocketEventHandle(__pyx_v_endpoint, __pyx_v_identifier, __pyx_v_override); + + /* "cereal/messaging/messaging_pyx.pyx":88 + * cdef cppSocketEventHandle * handle; + * + * def __cinit__(self, string endpoint, string identifier, bool override): # <<<<<<<<<<<<<< + * self.handle = new cppSocketEventHandle(endpoint, identifier, override) + * + */ + + /* function exit code */ + __pyx_r = 0; + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":91 + * self.handle = new cppSocketEventHandle(endpoint, identifier, override) + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * del self.handle + * + */ + +/* Python wrapper */ +static void __pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_3__dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_3__dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_2__dealloc__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_2__dealloc__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *__pyx_v_self) { + + /* "cereal/messaging/messaging_pyx.pyx":92 + * + * def __dealloc__(self): + * del self.handle # <<<<<<<<<<<<<< + * + * @property + */ + delete __pyx_v_self->handle; + + /* "cereal/messaging/messaging_pyx.pyx":91 + * self.handle = new cppSocketEventHandle(endpoint, identifier, override) + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * del self.handle + * + */ + + /* function exit code */ +} + +/* "cereal/messaging/messaging_pyx.pyx":94 + * del self.handle + * + * @property # <<<<<<<<<<<<<< + * def enabled(self): + * return self.handle.is_enabled() + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_7enabled_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_7enabled_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_7enabled___get__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_7enabled___get__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "cereal/messaging/messaging_pyx.pyx":96 + * @property + * def enabled(self): + * return self.handle.is_enabled() # <<<<<<<<<<<<<< + * + * @enabled.setter + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyBool_FromLong(__pyx_v_self->handle->is_enabled()); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 96, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/messaging/messaging_pyx.pyx":94 + * del self.handle + * + * @property # <<<<<<<<<<<<<< + * def enabled(self): + * return self.handle.is_enabled() + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.SocketEventHandle.enabled.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":98 + * return self.handle.is_enabled() + * + * @enabled.setter # <<<<<<<<<<<<<< + * def enabled(self, bool value): + * self.handle.set_enabled(value) + */ + +/* Python wrapper */ +static int __pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_7enabled_3__set__(PyObject *__pyx_v_self, PyObject *__pyx_arg_value); /*proto*/ +static int __pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_7enabled_3__set__(PyObject *__pyx_v_self, PyObject *__pyx_arg_value) { + bool __pyx_v_value; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__set__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + assert(__pyx_arg_value); { + __pyx_v_value = __Pyx_PyObject_IsTrue(__pyx_arg_value); if (unlikely((__pyx_v_value == ((bool)-1)) && PyErr_Occurred())) __PYX_ERR(0, 99, __pyx_L3_error) + } + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.SocketEventHandle.enabled.__set__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_7enabled_2__set__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *)__pyx_v_self), ((bool)__pyx_v_value)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_7enabled_2__set__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *__pyx_v_self, bool __pyx_v_value) { + int __pyx_r; + + /* "cereal/messaging/messaging_pyx.pyx":100 + * @enabled.setter + * def enabled(self, bool value): + * self.handle.set_enabled(value) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_v_self->handle->set_enabled(__pyx_v_value); + + /* "cereal/messaging/messaging_pyx.pyx":98 + * return self.handle.is_enabled() + * + * @enabled.setter # <<<<<<<<<<<<<< + * def enabled(self, bool value): + * self.handle.set_enabled(value) + */ + + /* function exit code */ + __pyx_r = 0; + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":102 + * self.handle.set_enabled(value) + * + * @property # <<<<<<<<<<<<<< + * def recv_called_event(self): + * e = Event() + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_17recv_called_event_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_17recv_called_event_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_17recv_called_event___get__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_17recv_called_event___get__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *__pyx_v_self) { + struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *__pyx_v_e = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "cereal/messaging/messaging_pyx.pyx":104 + * @property + * def recv_called_event(self): + * e = Event() # <<<<<<<<<<<<<< + * e.setEvent(self.handle.recv_called()) + * + */ + __pyx_t_1 = __Pyx_PyObject_CallNoArg(((PyObject *)__pyx_ptype_6cereal_9messaging_13messaging_pyx_Event)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 104, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_e = ((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *)__pyx_t_1); + __pyx_t_1 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":105 + * def recv_called_event(self): + * e = Event() + * e.setEvent(self.handle.recv_called()) # <<<<<<<<<<<<<< + * + * return e + */ + __pyx_t_1 = ((struct __pyx_vtabstruct_6cereal_9messaging_13messaging_pyx_Event *)__pyx_v_e->__pyx_vtab)->setEvent(__pyx_v_e, __pyx_v_self->handle->recv_called()); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 105, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":107 + * e.setEvent(self.handle.recv_called()) + * + * return e # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_e); + __pyx_r = ((PyObject *)__pyx_v_e); + goto __pyx_L0; + + /* "cereal/messaging/messaging_pyx.pyx":102 + * self.handle.set_enabled(value) + * + * @property # <<<<<<<<<<<<<< + * def recv_called_event(self): + * e = Event() + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.SocketEventHandle.recv_called_event.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_e); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":109 + * return e + * + * @property # <<<<<<<<<<<<<< + * def recv_ready_event(self): + * e = Event() + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_16recv_ready_event_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_16recv_ready_event_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_16recv_ready_event___get__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_16recv_ready_event___get__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *__pyx_v_self) { + struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *__pyx_v_e = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "cereal/messaging/messaging_pyx.pyx":111 + * @property + * def recv_ready_event(self): + * e = Event() # <<<<<<<<<<<<<< + * e.setEvent(self.handle.recv_ready()) + * + */ + __pyx_t_1 = __Pyx_PyObject_CallNoArg(((PyObject *)__pyx_ptype_6cereal_9messaging_13messaging_pyx_Event)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 111, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_e = ((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *)__pyx_t_1); + __pyx_t_1 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":112 + * def recv_ready_event(self): + * e = Event() + * e.setEvent(self.handle.recv_ready()) # <<<<<<<<<<<<<< + * + * return e + */ + __pyx_t_1 = ((struct __pyx_vtabstruct_6cereal_9messaging_13messaging_pyx_Event *)__pyx_v_e->__pyx_vtab)->setEvent(__pyx_v_e, __pyx_v_self->handle->recv_ready()); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 112, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":114 + * e.setEvent(self.handle.recv_ready()) + * + * return e # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_e); + __pyx_r = ((PyObject *)__pyx_v_e); + goto __pyx_L0; + + /* "cereal/messaging/messaging_pyx.pyx":109 + * return e + * + * @property # <<<<<<<<<<<<<< + * def recv_ready_event(self): + * e = Event() + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.SocketEventHandle.recv_ready_event.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_e); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_5__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_5__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_5__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_5__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_4__reduce_cython__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_4__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.SocketEventHandle.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_7__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_7__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_7__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_7__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.SocketEventHandle.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_6__setstate_cython__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_6__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.SocketEventHandle.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":120 + * cdef cppContext * context + * + * def __cinit__(self): # <<<<<<<<<<<<<< + * self.context = cppContext.create() + * + */ + +/* Python wrapper */ +static int __pyx_pw_6cereal_9messaging_13messaging_pyx_7Context_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_pw_6cereal_9messaging_13messaging_pyx_7Context_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 0, 0, __pyx_nargs); return -1;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_VARARGS(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__cinit__", 0))) return -1; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_7Context___cinit__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_6cereal_9messaging_13messaging_pyx_7Context___cinit__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *__pyx_v_self) { + int __pyx_r; + + /* "cereal/messaging/messaging_pyx.pyx":121 + * + * def __cinit__(self): + * self.context = cppContext.create() # <<<<<<<<<<<<<< + * + * def term(self): + */ + __pyx_v_self->context = Context::create(); + + /* "cereal/messaging/messaging_pyx.pyx":120 + * cdef cppContext * context + * + * def __cinit__(self): # <<<<<<<<<<<<<< + * self.context = cppContext.create() + * + */ + + /* function exit code */ + __pyx_r = 0; + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":123 + * self.context = cppContext.create() + * + * def term(self): # <<<<<<<<<<<<<< + * del self.context + * self.context = NULL + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_7Context_3term(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_7Context_3term = {"term", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_7Context_3term, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_7Context_3term(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("term (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("term", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "term", 0))) return NULL; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_7Context_2term(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_7Context_2term(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("term", 1); + + /* "cereal/messaging/messaging_pyx.pyx":124 + * + * def term(self): + * del self.context # <<<<<<<<<<<<<< + * self.context = NULL + * + */ + delete __pyx_v_self->context; + + /* "cereal/messaging/messaging_pyx.pyx":125 + * def term(self): + * del self.context + * self.context = NULL # <<<<<<<<<<<<<< + * + * def __dealloc__(self): + */ + __pyx_v_self->context = NULL; + + /* "cereal/messaging/messaging_pyx.pyx":123 + * self.context = cppContext.create() + * + * def term(self): # <<<<<<<<<<<<<< + * del self.context + * self.context = NULL + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":127 + * self.context = NULL + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * pass + * # Deleting the context will hang if sockets are still active + */ + +/* Python wrapper */ +static void __pyx_pw_6cereal_9messaging_13messaging_pyx_7Context_5__dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_pw_6cereal_9messaging_13messaging_pyx_7Context_5__dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_pf_6cereal_9messaging_13messaging_pyx_7Context_4__dealloc__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_pf_6cereal_9messaging_13messaging_pyx_7Context_4__dealloc__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *__pyx_v_self) { + + /* function exit code */ +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_7Context_7__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_7Context_7__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_7Context_7__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_7Context_7__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_7Context_6__reduce_cython__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_7Context_6__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.Context.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_7Context_9__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_7Context_9__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_7Context_9__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_7Context_9__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.Context.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_7Context_8__setstate_cython__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_7Context_8__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.Context.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":138 + * cdef list sub_sockets + * + * def __cinit__(self): # <<<<<<<<<<<<<< + * self.sub_sockets = [] + * self.poller = cppPoller.create() + */ + +/* Python wrapper */ +static int __pyx_pw_6cereal_9messaging_13messaging_pyx_6Poller_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_pw_6cereal_9messaging_13messaging_pyx_6Poller_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 0, 0, __pyx_nargs); return -1;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_VARARGS(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__cinit__", 0))) return -1; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_6Poller___cinit__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_6cereal_9messaging_13messaging_pyx_6Poller___cinit__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *__pyx_v_self) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__cinit__", 1); + + /* "cereal/messaging/messaging_pyx.pyx":139 + * + * def __cinit__(self): + * self.sub_sockets = [] # <<<<<<<<<<<<<< + * self.poller = cppPoller.create() + * + */ + __pyx_t_1 = PyList_New(0); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 139, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + __Pyx_GOTREF(__pyx_v_self->sub_sockets); + __Pyx_DECREF(__pyx_v_self->sub_sockets); + __pyx_v_self->sub_sockets = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":140 + * def __cinit__(self): + * self.sub_sockets = [] + * self.poller = cppPoller.create() # <<<<<<<<<<<<<< + * + * def __dealloc__(self): + */ + __pyx_v_self->poller = Poller::create(); + + /* "cereal/messaging/messaging_pyx.pyx":138 + * cdef list sub_sockets + * + * def __cinit__(self): # <<<<<<<<<<<<<< + * self.sub_sockets = [] + * self.poller = cppPoller.create() + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.Poller.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":142 + * self.poller = cppPoller.create() + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * del self.poller + * + */ + +/* Python wrapper */ +static void __pyx_pw_6cereal_9messaging_13messaging_pyx_6Poller_3__dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_pw_6cereal_9messaging_13messaging_pyx_6Poller_3__dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_pf_6cereal_9messaging_13messaging_pyx_6Poller_2__dealloc__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_pf_6cereal_9messaging_13messaging_pyx_6Poller_2__dealloc__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *__pyx_v_self) { + + /* "cereal/messaging/messaging_pyx.pyx":143 + * + * def __dealloc__(self): + * del self.poller # <<<<<<<<<<<<<< + * + * def registerSocket(self, SubSocket socket): + */ + delete __pyx_v_self->poller; + + /* "cereal/messaging/messaging_pyx.pyx":142 + * self.poller = cppPoller.create() + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * del self.poller + * + */ + + /* function exit code */ +} + +/* "cereal/messaging/messaging_pyx.pyx":145 + * del self.poller + * + * def registerSocket(self, SubSocket socket): # <<<<<<<<<<<<<< + * self.sub_sockets.append(socket) + * self.poller.registerSocket(socket.socket) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_6Poller_5registerSocket(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_6Poller_5registerSocket = {"registerSocket", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_6Poller_5registerSocket, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_6Poller_5registerSocket(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *__pyx_v_socket = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("registerSocket (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_socket,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_socket)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 145, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "registerSocket") < 0)) __PYX_ERR(0, 145, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_socket = ((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *)values[0]); + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("registerSocket", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 145, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.Poller.registerSocket", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_socket), __pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket, 1, "socket", 0))) __PYX_ERR(0, 145, __pyx_L1_error) + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_6Poller_4registerSocket(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *)__pyx_v_self), __pyx_v_socket); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = NULL; + __pyx_L0:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_6Poller_4registerSocket(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *__pyx_v_self, struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *__pyx_v_socket) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("registerSocket", 1); + + /* "cereal/messaging/messaging_pyx.pyx":146 + * + * def registerSocket(self, SubSocket socket): + * self.sub_sockets.append(socket) # <<<<<<<<<<<<<< + * self.poller.registerSocket(socket.socket) + * + */ + if (unlikely(__pyx_v_self->sub_sockets == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "append"); + __PYX_ERR(0, 146, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_PyList_Append(__pyx_v_self->sub_sockets, ((PyObject *)__pyx_v_socket)); if (unlikely(__pyx_t_1 == ((int)-1))) __PYX_ERR(0, 146, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":147 + * def registerSocket(self, SubSocket socket): + * self.sub_sockets.append(socket) + * self.poller.registerSocket(socket.socket) # <<<<<<<<<<<<<< + * + * def poll(self, timeout): + */ + __pyx_v_self->poller->registerSocket(__pyx_v_socket->socket); + + /* "cereal/messaging/messaging_pyx.pyx":145 + * del self.poller + * + * def registerSocket(self, SubSocket socket): # <<<<<<<<<<<<<< + * self.sub_sockets.append(socket) + * self.poller.registerSocket(socket.socket) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.Poller.registerSocket", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":149 + * self.poller.registerSocket(socket.socket) + * + * def poll(self, timeout): # <<<<<<<<<<<<<< + * sockets = [] + * cdef int t = timeout + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_6Poller_7poll(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_6Poller_7poll = {"poll", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_6Poller_7poll, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_6Poller_7poll(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_timeout = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("poll (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_timeout,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_timeout)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 149, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "poll") < 0)) __PYX_ERR(0, 149, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_timeout = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("poll", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 149, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.Poller.poll", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_6Poller_6poll(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *)__pyx_v_self), __pyx_v_timeout); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_6Poller_6poll(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *__pyx_v_self, PyObject *__pyx_v_timeout) { + PyObject *__pyx_v_sockets = NULL; + int __pyx_v_t; + std::vector __pyx_v_result; + SubSocket *__pyx_v_s; + struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *__pyx_v_socket = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + std::vector ::iterator __pyx_t_3; + SubSocket *__pyx_t_4; + int __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("poll", 1); + + /* "cereal/messaging/messaging_pyx.pyx":150 + * + * def poll(self, timeout): + * sockets = [] # <<<<<<<<<<<<<< + * cdef int t = timeout + * + */ + __pyx_t_1 = PyList_New(0); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 150, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_sockets = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":151 + * def poll(self, timeout): + * sockets = [] + * cdef int t = timeout # <<<<<<<<<<<<<< + * + * with nogil: + */ + __pyx_t_2 = __Pyx_PyInt_As_int(__pyx_v_timeout); if (unlikely((__pyx_t_2 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 151, __pyx_L1_error) + __pyx_v_t = __pyx_t_2; + + /* "cereal/messaging/messaging_pyx.pyx":153 + * cdef int t = timeout + * + * with nogil: # <<<<<<<<<<<<<< + * result = self.poller.poll(t) + * + */ + { + #ifdef WITH_THREAD + PyThreadState *_save; + _save = NULL; + Py_UNBLOCK_THREADS + __Pyx_FastGIL_Remember(); + #endif + /*try:*/ { + + /* "cereal/messaging/messaging_pyx.pyx":154 + * + * with nogil: + * result = self.poller.poll(t) # <<<<<<<<<<<<<< + * + * for s in result: + */ + __pyx_v_result = __pyx_v_self->poller->poll(__pyx_v_t); + } + + /* "cereal/messaging/messaging_pyx.pyx":153 + * cdef int t = timeout + * + * with nogil: # <<<<<<<<<<<<<< + * result = self.poller.poll(t) + * + */ + /*finally:*/ { + /*normal exit:*/{ + #ifdef WITH_THREAD + __Pyx_FastGIL_Forget(); + Py_BLOCK_THREADS + #endif + goto __pyx_L5; + } + __pyx_L5:; + } + } + + /* "cereal/messaging/messaging_pyx.pyx":156 + * result = self.poller.poll(t) + * + * for s in result: # <<<<<<<<<<<<<< + * socket = SubSocket() + * socket.setPtr(s) + */ + __pyx_t_3 = __pyx_v_result.begin(); + for (;;) { + if (!(__pyx_t_3 != __pyx_v_result.end())) break; + __pyx_t_4 = *__pyx_t_3; + ++__pyx_t_3; + __pyx_v_s = __pyx_t_4; + + /* "cereal/messaging/messaging_pyx.pyx":157 + * + * for s in result: + * socket = SubSocket() # <<<<<<<<<<<<<< + * socket.setPtr(s) + * sockets.append(socket) + */ + __pyx_t_1 = __Pyx_PyObject_CallNoArg(((PyObject *)__pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 157, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_XDECREF_SET(__pyx_v_socket, ((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *)__pyx_t_1)); + __pyx_t_1 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":158 + * for s in result: + * socket = SubSocket() + * socket.setPtr(s) # <<<<<<<<<<<<<< + * sockets.append(socket) + * + */ + __pyx_t_1 = ((struct __pyx_vtabstruct_6cereal_9messaging_13messaging_pyx_SubSocket *)__pyx_v_socket->__pyx_vtab)->setPtr(__pyx_v_socket, __pyx_v_s); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 158, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":159 + * socket = SubSocket() + * socket.setPtr(s) + * sockets.append(socket) # <<<<<<<<<<<<<< + * + * return sockets + */ + __pyx_t_5 = __Pyx_PyList_Append(__pyx_v_sockets, ((PyObject *)__pyx_v_socket)); if (unlikely(__pyx_t_5 == ((int)-1))) __PYX_ERR(0, 159, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":156 + * result = self.poller.poll(t) + * + * for s in result: # <<<<<<<<<<<<<< + * socket = SubSocket() + * socket.setPtr(s) + */ + } + + /* "cereal/messaging/messaging_pyx.pyx":161 + * sockets.append(socket) + * + * return sockets # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_sockets); + __pyx_r = __pyx_v_sockets; + goto __pyx_L0; + + /* "cereal/messaging/messaging_pyx.pyx":149 + * self.poller.registerSocket(socket.socket) + * + * def poll(self, timeout): # <<<<<<<<<<<<<< + * sockets = [] + * cdef int t = timeout + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.Poller.poll", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_sockets); + __Pyx_XDECREF((PyObject *)__pyx_v_socket); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_6Poller_9__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_6Poller_9__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_6Poller_9__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_6Poller_9__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_6Poller_8__reduce_cython__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_6Poller_8__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.Poller.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_6Poller_11__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_6Poller_11__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_6Poller_11__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_6Poller_11__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.Poller.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_6Poller_10__setstate_cython__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_6Poller_10__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.Poller.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":168 + * cdef bool is_owner + * + * def __cinit__(self): # <<<<<<<<<<<<<< + * self.socket = cppSubSocket.create() + * self.is_owner = True + */ + +/* Python wrapper */ +static int __pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 0, 0, __pyx_nargs); return -1;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_VARARGS(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__cinit__", 0))) return -1; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_9SubSocket___cinit__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_6cereal_9messaging_13messaging_pyx_9SubSocket___cinit__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *__pyx_v_self) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__cinit__", 1); + + /* "cereal/messaging/messaging_pyx.pyx":169 + * + * def __cinit__(self): + * self.socket = cppSubSocket.create() # <<<<<<<<<<<<<< + * self.is_owner = True + * + */ + __pyx_v_self->socket = SubSocket::create(); + + /* "cereal/messaging/messaging_pyx.pyx":170 + * def __cinit__(self): + * self.socket = cppSubSocket.create() + * self.is_owner = True # <<<<<<<<<<<<<< + * + * if self.socket == NULL: + */ + __pyx_v_self->is_owner = 1; + + /* "cereal/messaging/messaging_pyx.pyx":172 + * self.is_owner = True + * + * if self.socket == NULL: # <<<<<<<<<<<<<< + * raise MessagingError + * + */ + __pyx_t_1 = (__pyx_v_self->socket == NULL); + if (unlikely(__pyx_t_1)) { + + /* "cereal/messaging/messaging_pyx.pyx":173 + * + * if self.socket == NULL: + * raise MessagingError # <<<<<<<<<<<<<< + * + * def __dealloc__(self): + */ + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_MessagingError); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 173, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 173, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":172 + * self.is_owner = True + * + * if self.socket == NULL: # <<<<<<<<<<<<<< + * raise MessagingError + * + */ + } + + /* "cereal/messaging/messaging_pyx.pyx":168 + * cdef bool is_owner + * + * def __cinit__(self): # <<<<<<<<<<<<<< + * self.socket = cppSubSocket.create() + * self.is_owner = True + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.SubSocket.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":175 + * raise MessagingError + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * if self.is_owner: + * del self.socket + */ + +/* Python wrapper */ +static void __pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_3__dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_3__dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_pf_6cereal_9messaging_13messaging_pyx_9SubSocket_2__dealloc__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_pf_6cereal_9messaging_13messaging_pyx_9SubSocket_2__dealloc__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *__pyx_v_self) { + int __pyx_t_1; + + /* "cereal/messaging/messaging_pyx.pyx":176 + * + * def __dealloc__(self): + * if self.is_owner: # <<<<<<<<<<<<<< + * del self.socket + * + */ + __pyx_t_1 = (__pyx_v_self->is_owner != 0); + if (__pyx_t_1) { + + /* "cereal/messaging/messaging_pyx.pyx":177 + * def __dealloc__(self): + * if self.is_owner: + * del self.socket # <<<<<<<<<<<<<< + * + * cdef setPtr(self, cppSubSocket * ptr): + */ + delete __pyx_v_self->socket; + + /* "cereal/messaging/messaging_pyx.pyx":176 + * + * def __dealloc__(self): + * if self.is_owner: # <<<<<<<<<<<<<< + * del self.socket + * + */ + } + + /* "cereal/messaging/messaging_pyx.pyx":175 + * raise MessagingError + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * if self.is_owner: + * del self.socket + */ + + /* function exit code */ +} + +/* "cereal/messaging/messaging_pyx.pyx":179 + * del self.socket + * + * cdef setPtr(self, cppSubSocket * ptr): # <<<<<<<<<<<<<< + * if self.is_owner: + * del self.socket + */ + +static PyObject *__pyx_f_6cereal_9messaging_13messaging_pyx_9SubSocket_setPtr(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *__pyx_v_self, SubSocket *__pyx_v_ptr) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + __Pyx_RefNannySetupContext("setPtr", 1); + + /* "cereal/messaging/messaging_pyx.pyx":180 + * + * cdef setPtr(self, cppSubSocket * ptr): + * if self.is_owner: # <<<<<<<<<<<<<< + * del self.socket + * + */ + __pyx_t_1 = (__pyx_v_self->is_owner != 0); + if (__pyx_t_1) { + + /* "cereal/messaging/messaging_pyx.pyx":181 + * cdef setPtr(self, cppSubSocket * ptr): + * if self.is_owner: + * del self.socket # <<<<<<<<<<<<<< + * + * self.is_owner = False + */ + delete __pyx_v_self->socket; + + /* "cereal/messaging/messaging_pyx.pyx":180 + * + * cdef setPtr(self, cppSubSocket * ptr): + * if self.is_owner: # <<<<<<<<<<<<<< + * del self.socket + * + */ + } + + /* "cereal/messaging/messaging_pyx.pyx":183 + * del self.socket + * + * self.is_owner = False # <<<<<<<<<<<<<< + * self.socket = ptr + * + */ + __pyx_v_self->is_owner = 0; + + /* "cereal/messaging/messaging_pyx.pyx":184 + * + * self.is_owner = False + * self.socket = ptr # <<<<<<<<<<<<<< + * + * def connect(self, Context context, string endpoint, string address=b"127.0.0.1", bool conflate=False): + */ + __pyx_v_self->socket = __pyx_v_ptr; + + /* "cereal/messaging/messaging_pyx.pyx":179 + * del self.socket + * + * cdef setPtr(self, cppSubSocket * ptr): # <<<<<<<<<<<<<< + * if self.is_owner: + * del self.socket + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":186 + * self.socket = ptr + * + * def connect(self, Context context, string endpoint, string address=b"127.0.0.1", bool conflate=False): # <<<<<<<<<<<<<< + * r = self.socket.connect(context.context, endpoint, address, conflate) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_5connect(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_9SubSocket_5connect = {"connect", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_5connect, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_5connect(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *__pyx_v_context = 0; + std::string __pyx_v_endpoint; + std::string __pyx_v_address; + bool __pyx_v_conflate; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[4] = {0,0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("connect (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_context,&__pyx_n_s_endpoint,&__pyx_n_s_address,&__pyx_n_s_conflate,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 4: values[3] = __Pyx_Arg_FASTCALL(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_context)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 186, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_endpoint)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 186, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("connect", 0, 2, 4, 1); __PYX_ERR(0, 186, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_address); + if (value) { values[2] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 186, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 3: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_conflate); + if (value) { values[3] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 186, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "connect") < 0)) __PYX_ERR(0, 186, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 4: values[3] = __Pyx_Arg_FASTCALL(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_context = ((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *)values[0]); + __pyx_v_endpoint = __pyx_convert_string_from_py_std__in_string(values[1]); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 186, __pyx_L3_error) + if (values[2]) { + __pyx_v_address = __pyx_convert_string_from_py_std__in_string(values[2]); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 186, __pyx_L3_error) + } else { + __pyx_v_address = __pyx_k__3; + } + if (values[3]) { + __pyx_v_conflate = __Pyx_PyObject_IsTrue(values[3]); if (unlikely((__pyx_v_conflate == ((bool)-1)) && PyErr_Occurred())) __PYX_ERR(0, 186, __pyx_L3_error) + } else { + __pyx_v_conflate = ((bool)0); + } + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("connect", 0, 2, 4, __pyx_nargs); __PYX_ERR(0, 186, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.SubSocket.connect", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_context), __pyx_ptype_6cereal_9messaging_13messaging_pyx_Context, 1, "context", 0))) __PYX_ERR(0, 186, __pyx_L1_error) + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_9SubSocket_4connect(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *)__pyx_v_self), __pyx_v_context, __PYX_STD_MOVE_IF_SUPPORTED(__pyx_v_endpoint), __PYX_STD_MOVE_IF_SUPPORTED(__pyx_v_address), __pyx_v_conflate); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = NULL; + __pyx_L0:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_9SubSocket_4connect(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *__pyx_v_self, struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *__pyx_v_context, std::string __pyx_v_endpoint, std::string __pyx_v_address, bool __pyx_v_conflate) { + int __pyx_v_r; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("connect", 1); + + /* "cereal/messaging/messaging_pyx.pyx":187 + * + * def connect(self, Context context, string endpoint, string address=b"127.0.0.1", bool conflate=False): + * r = self.socket.connect(context.context, endpoint, address, conflate) # <<<<<<<<<<<<<< + * + * if r != 0: + */ + __pyx_v_r = __pyx_v_self->socket->connect(__pyx_v_context->context, __pyx_v_endpoint, __pyx_v_address, __pyx_v_conflate); + + /* "cereal/messaging/messaging_pyx.pyx":189 + * r = self.socket.connect(context.context, endpoint, address, conflate) + * + * if r != 0: # <<<<<<<<<<<<<< + * if errno.errno == errno.EADDRINUSE: + * raise MultiplePublishersError(endpoint) + */ + __pyx_t_1 = (__pyx_v_r != 0); + if (__pyx_t_1) { + + /* "cereal/messaging/messaging_pyx.pyx":190 + * + * if r != 0: + * if errno.errno == errno.EADDRINUSE: # <<<<<<<<<<<<<< + * raise MultiplePublishersError(endpoint) + * else: + */ + __pyx_t_1 = (errno == EADDRINUSE); + if (unlikely(__pyx_t_1)) { + + /* "cereal/messaging/messaging_pyx.pyx":191 + * if r != 0: + * if errno.errno == errno.EADDRINUSE: + * raise MultiplePublishersError(endpoint) # <<<<<<<<<<<<<< + * else: + * raise MessagingError(endpoint) + */ + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_MultiplePublishersError); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 191, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = __pyx_convert_PyBytes_string_to_py_std__in_string(__pyx_v_endpoint); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 191, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (unlikely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_5, __pyx_t_4}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_6, 1+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 191, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 191, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":190 + * + * if r != 0: + * if errno.errno == errno.EADDRINUSE: # <<<<<<<<<<<<<< + * raise MultiplePublishersError(endpoint) + * else: + */ + } + + /* "cereal/messaging/messaging_pyx.pyx":193 + * raise MultiplePublishersError(endpoint) + * else: + * raise MessagingError(endpoint) # <<<<<<<<<<<<<< + * + * def setTimeout(self, int timeout): + */ + /*else*/ { + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_MessagingError); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 193, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = __pyx_convert_PyBytes_string_to_py_std__in_string(__pyx_v_endpoint); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 193, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (unlikely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_5, __pyx_t_4}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_6, 1+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 193, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 193, __pyx_L1_error) + } + + /* "cereal/messaging/messaging_pyx.pyx":189 + * r = self.socket.connect(context.context, endpoint, address, conflate) + * + * if r != 0: # <<<<<<<<<<<<<< + * if errno.errno == errno.EADDRINUSE: + * raise MultiplePublishersError(endpoint) + */ + } + + /* "cereal/messaging/messaging_pyx.pyx":186 + * self.socket = ptr + * + * def connect(self, Context context, string endpoint, string address=b"127.0.0.1", bool conflate=False): # <<<<<<<<<<<<<< + * r = self.socket.connect(context.context, endpoint, address, conflate) + * + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.SubSocket.connect", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":195 + * raise MessagingError(endpoint) + * + * def setTimeout(self, int timeout): # <<<<<<<<<<<<<< + * self.socket.setTimeout(timeout) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_7setTimeout(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_9SubSocket_7setTimeout = {"setTimeout", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_7setTimeout, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_7setTimeout(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + int __pyx_v_timeout; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("setTimeout (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_timeout,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_timeout)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 195, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "setTimeout") < 0)) __PYX_ERR(0, 195, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_timeout = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_timeout == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 195, __pyx_L3_error) + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("setTimeout", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 195, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.SubSocket.setTimeout", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_9SubSocket_6setTimeout(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *)__pyx_v_self), __pyx_v_timeout); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_9SubSocket_6setTimeout(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *__pyx_v_self, int __pyx_v_timeout) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("setTimeout", 1); + + /* "cereal/messaging/messaging_pyx.pyx":196 + * + * def setTimeout(self, int timeout): + * self.socket.setTimeout(timeout) # <<<<<<<<<<<<<< + * + * def receive(self, bool non_blocking=False): + */ + __pyx_v_self->socket->setTimeout(__pyx_v_timeout); + + /* "cereal/messaging/messaging_pyx.pyx":195 + * raise MessagingError(endpoint) + * + * def setTimeout(self, int timeout): # <<<<<<<<<<<<<< + * self.socket.setTimeout(timeout) + * + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":198 + * self.socket.setTimeout(timeout) + * + * def receive(self, bool non_blocking=False): # <<<<<<<<<<<<<< + * msg = self.socket.receive(non_blocking) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_9receive(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_9SubSocket_9receive = {"receive", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_9receive, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_9receive(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + bool __pyx_v_non_blocking; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("receive (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_non_blocking,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_non_blocking); + if (value) { values[0] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 198, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "receive") < 0)) __PYX_ERR(0, 198, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + } + if (values[0]) { + __pyx_v_non_blocking = __Pyx_PyObject_IsTrue(values[0]); if (unlikely((__pyx_v_non_blocking == ((bool)-1)) && PyErr_Occurred())) __PYX_ERR(0, 198, __pyx_L3_error) + } else { + __pyx_v_non_blocking = ((bool)0); + } + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("receive", 0, 0, 1, __pyx_nargs); __PYX_ERR(0, 198, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.SubSocket.receive", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_9SubSocket_8receive(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *)__pyx_v_self), __pyx_v_non_blocking); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_9SubSocket_8receive(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *__pyx_v_self, bool __pyx_v_non_blocking) { + Message *__pyx_v_msg; + size_t __pyx_v_sz; + PyObject *__pyx_v_m = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("receive", 1); + + /* "cereal/messaging/messaging_pyx.pyx":199 + * + * def receive(self, bool non_blocking=False): + * msg = self.socket.receive(non_blocking) # <<<<<<<<<<<<<< + * + * if msg == NULL: + */ + __pyx_v_msg = __pyx_v_self->socket->receive(__pyx_v_non_blocking); + + /* "cereal/messaging/messaging_pyx.pyx":201 + * msg = self.socket.receive(non_blocking) + * + * if msg == NULL: # <<<<<<<<<<<<<< + * # If a blocking read returns no message check errno if SIGINT was caught in the C++ code + * if errno.errno == errno.EINTR: + */ + __pyx_t_1 = (__pyx_v_msg == NULL); + if (__pyx_t_1) { + + /* "cereal/messaging/messaging_pyx.pyx":203 + * if msg == NULL: + * # If a blocking read returns no message check errno if SIGINT was caught in the C++ code + * if errno.errno == errno.EINTR: # <<<<<<<<<<<<<< + * print("SIGINT received, exiting") + * sys.exit(1) + */ + __pyx_t_1 = (errno == EINTR); + if (__pyx_t_1) { + + /* "cereal/messaging/messaging_pyx.pyx":204 + * # If a blocking read returns no message check errno if SIGINT was caught in the C++ code + * if errno.errno == errno.EINTR: + * print("SIGINT received, exiting") # <<<<<<<<<<<<<< + * sys.exit(1) + * + */ + __pyx_t_2 = __Pyx_PyObject_Call(__pyx_builtin_print, __pyx_tuple__4, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 204, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":205 + * if errno.errno == errno.EINTR: + * print("SIGINT received, exiting") + * sys.exit(1) # <<<<<<<<<<<<<< + * + * return None + */ + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_sys); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 205, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_exit); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 205, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = NULL; + __pyx_t_5 = 0; + #if CYTHON_UNPACK_METHODS + if (unlikely(PyMethod_Check(__pyx_t_4))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_4); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_4); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_4, function); + __pyx_t_5 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_int_1}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_5, 1+__pyx_t_5); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 205, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":203 + * if msg == NULL: + * # If a blocking read returns no message check errno if SIGINT was caught in the C++ code + * if errno.errno == errno.EINTR: # <<<<<<<<<<<<<< + * print("SIGINT received, exiting") + * sys.exit(1) + */ + } + + /* "cereal/messaging/messaging_pyx.pyx":207 + * sys.exit(1) + * + * return None # <<<<<<<<<<<<<< + * else: + * sz = msg.getSize() + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "cereal/messaging/messaging_pyx.pyx":201 + * msg = self.socket.receive(non_blocking) + * + * if msg == NULL: # <<<<<<<<<<<<<< + * # If a blocking read returns no message check errno if SIGINT was caught in the C++ code + * if errno.errno == errno.EINTR: + */ + } + + /* "cereal/messaging/messaging_pyx.pyx":209 + * return None + * else: + * sz = msg.getSize() # <<<<<<<<<<<<<< + * m = msg.getData()[:sz] + * del msg + */ + /*else*/ { + __pyx_v_sz = __pyx_v_msg->getSize(); + + /* "cereal/messaging/messaging_pyx.pyx":210 + * else: + * sz = msg.getSize() + * m = msg.getData()[:sz] # <<<<<<<<<<<<<< + * del msg + * + */ + __pyx_t_2 = __Pyx_PyBytes_FromStringAndSize(__pyx_v_msg->getData() + 0, __pyx_v_sz - 0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 210, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_v_m = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":211 + * sz = msg.getSize() + * m = msg.getData()[:sz] + * del msg # <<<<<<<<<<<<<< + * + * return m + */ + delete __pyx_v_msg; + + /* "cereal/messaging/messaging_pyx.pyx":213 + * del msg + * + * return m # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_m); + __pyx_r = __pyx_v_m; + goto __pyx_L0; + } + + /* "cereal/messaging/messaging_pyx.pyx":198 + * self.socket.setTimeout(timeout) + * + * def receive(self, bool non_blocking=False): # <<<<<<<<<<<<<< + * msg = self.socket.receive(non_blocking) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.SubSocket.receive", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_m); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_11__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_9SubSocket_11__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_11__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_11__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_9SubSocket_10__reduce_cython__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_9SubSocket_10__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.SubSocket.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_13__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_9SubSocket_13__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_13__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_13__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.SubSocket.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_9SubSocket_12__setstate_cython__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_9SubSocket_12__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.SubSocket.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":219 + * cdef cppPubSocket * socket + * + * def __cinit__(self): # <<<<<<<<<<<<<< + * self.socket = cppPubSocket.create() + * if self.socket == NULL: + */ + +/* Python wrapper */ +static int __pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 0, 0, __pyx_nargs); return -1;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_VARARGS(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__cinit__", 0))) return -1; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_9PubSocket___cinit__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_6cereal_9messaging_13messaging_pyx_9PubSocket___cinit__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket *__pyx_v_self) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__cinit__", 1); + + /* "cereal/messaging/messaging_pyx.pyx":220 + * + * def __cinit__(self): + * self.socket = cppPubSocket.create() # <<<<<<<<<<<<<< + * if self.socket == NULL: + * raise MessagingError + */ + __pyx_v_self->socket = PubSocket::create(); + + /* "cereal/messaging/messaging_pyx.pyx":221 + * def __cinit__(self): + * self.socket = cppPubSocket.create() + * if self.socket == NULL: # <<<<<<<<<<<<<< + * raise MessagingError + * + */ + __pyx_t_1 = (__pyx_v_self->socket == NULL); + if (unlikely(__pyx_t_1)) { + + /* "cereal/messaging/messaging_pyx.pyx":222 + * self.socket = cppPubSocket.create() + * if self.socket == NULL: + * raise MessagingError # <<<<<<<<<<<<<< + * + * def __dealloc__(self): + */ + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_MessagingError); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 222, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 222, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":221 + * def __cinit__(self): + * self.socket = cppPubSocket.create() + * if self.socket == NULL: # <<<<<<<<<<<<<< + * raise MessagingError + * + */ + } + + /* "cereal/messaging/messaging_pyx.pyx":219 + * cdef cppPubSocket * socket + * + * def __cinit__(self): # <<<<<<<<<<<<<< + * self.socket = cppPubSocket.create() + * if self.socket == NULL: + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.PubSocket.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":224 + * raise MessagingError + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * del self.socket + * + */ + +/* Python wrapper */ +static void __pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_3__dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_3__dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_pf_6cereal_9messaging_13messaging_pyx_9PubSocket_2__dealloc__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_pf_6cereal_9messaging_13messaging_pyx_9PubSocket_2__dealloc__(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket *__pyx_v_self) { + + /* "cereal/messaging/messaging_pyx.pyx":225 + * + * def __dealloc__(self): + * del self.socket # <<<<<<<<<<<<<< + * + * def connect(self, Context context, string endpoint): + */ + delete __pyx_v_self->socket; + + /* "cereal/messaging/messaging_pyx.pyx":224 + * raise MessagingError + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * del self.socket + * + */ + + /* function exit code */ +} + +/* "cereal/messaging/messaging_pyx.pyx":227 + * del self.socket + * + * def connect(self, Context context, string endpoint): # <<<<<<<<<<<<<< + * r = self.socket.connect(context.context, endpoint) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_5connect(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_9PubSocket_5connect = {"connect", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_5connect, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_5connect(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *__pyx_v_context = 0; + std::string __pyx_v_endpoint; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[2] = {0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("connect (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_context,&__pyx_n_s_endpoint,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_context)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 227, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_endpoint)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 227, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("connect", 1, 2, 2, 1); __PYX_ERR(0, 227, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "connect") < 0)) __PYX_ERR(0, 227, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 2)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + } + __pyx_v_context = ((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *)values[0]); + __pyx_v_endpoint = __pyx_convert_string_from_py_std__in_string(values[1]); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 227, __pyx_L3_error) + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("connect", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 227, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.PubSocket.connect", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_context), __pyx_ptype_6cereal_9messaging_13messaging_pyx_Context, 1, "context", 0))) __PYX_ERR(0, 227, __pyx_L1_error) + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_9PubSocket_4connect(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket *)__pyx_v_self), __pyx_v_context, __PYX_STD_MOVE_IF_SUPPORTED(__pyx_v_endpoint)); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = NULL; + __pyx_L0:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_9PubSocket_4connect(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket *__pyx_v_self, struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context *__pyx_v_context, std::string __pyx_v_endpoint) { + int __pyx_v_r; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("connect", 1); + + /* "cereal/messaging/messaging_pyx.pyx":228 + * + * def connect(self, Context context, string endpoint): + * r = self.socket.connect(context.context, endpoint) # <<<<<<<<<<<<<< + * + * if r != 0: + */ + __pyx_v_r = __pyx_v_self->socket->connect(__pyx_v_context->context, __pyx_v_endpoint); + + /* "cereal/messaging/messaging_pyx.pyx":230 + * r = self.socket.connect(context.context, endpoint) + * + * if r != 0: # <<<<<<<<<<<<<< + * if errno.errno == errno.EADDRINUSE: + * raise MultiplePublishersError(endpoint) + */ + __pyx_t_1 = (__pyx_v_r != 0); + if (__pyx_t_1) { + + /* "cereal/messaging/messaging_pyx.pyx":231 + * + * if r != 0: + * if errno.errno == errno.EADDRINUSE: # <<<<<<<<<<<<<< + * raise MultiplePublishersError(endpoint) + * else: + */ + __pyx_t_1 = (errno == EADDRINUSE); + if (unlikely(__pyx_t_1)) { + + /* "cereal/messaging/messaging_pyx.pyx":232 + * if r != 0: + * if errno.errno == errno.EADDRINUSE: + * raise MultiplePublishersError(endpoint) # <<<<<<<<<<<<<< + * else: + * raise MessagingError(endpoint) + */ + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_MultiplePublishersError); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 232, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = __pyx_convert_PyBytes_string_to_py_std__in_string(__pyx_v_endpoint); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 232, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (unlikely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_5, __pyx_t_4}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_6, 1+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 232, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 232, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":231 + * + * if r != 0: + * if errno.errno == errno.EADDRINUSE: # <<<<<<<<<<<<<< + * raise MultiplePublishersError(endpoint) + * else: + */ + } + + /* "cereal/messaging/messaging_pyx.pyx":234 + * raise MultiplePublishersError(endpoint) + * else: + * raise MessagingError(endpoint) # <<<<<<<<<<<<<< + * + * def send(self, bytes data): + */ + /*else*/ { + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_MessagingError); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 234, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = __pyx_convert_PyBytes_string_to_py_std__in_string(__pyx_v_endpoint); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 234, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (unlikely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_5, __pyx_t_4}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_6, 1+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 234, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 234, __pyx_L1_error) + } + + /* "cereal/messaging/messaging_pyx.pyx":230 + * r = self.socket.connect(context.context, endpoint) + * + * if r != 0: # <<<<<<<<<<<<<< + * if errno.errno == errno.EADDRINUSE: + * raise MultiplePublishersError(endpoint) + */ + } + + /* "cereal/messaging/messaging_pyx.pyx":227 + * del self.socket + * + * def connect(self, Context context, string endpoint): # <<<<<<<<<<<<<< + * r = self.socket.connect(context.context, endpoint) + * + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.PubSocket.connect", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":236 + * raise MessagingError(endpoint) + * + * def send(self, bytes data): # <<<<<<<<<<<<<< + * length = len(data) + * r = self.socket.send(data, length) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_7send(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_9PubSocket_7send = {"send", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_7send, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_7send(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_data = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("send (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_data,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_data)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 236, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "send") < 0)) __PYX_ERR(0, 236, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_data = ((PyObject*)values[0]); + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("send", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 236, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.PubSocket.send", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_data), (&PyBytes_Type), 1, "data", 1))) __PYX_ERR(0, 236, __pyx_L1_error) + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_9PubSocket_6send(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket *)__pyx_v_self), __pyx_v_data); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = NULL; + __pyx_L0:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_9PubSocket_6send(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket *__pyx_v_self, PyObject *__pyx_v_data) { + Py_ssize_t __pyx_v_length; + int __pyx_v_r; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + char *__pyx_t_2; + int __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("send", 1); + + /* "cereal/messaging/messaging_pyx.pyx":237 + * + * def send(self, bytes data): + * length = len(data) # <<<<<<<<<<<<<< + * r = self.socket.send(data, length) + * + */ + if (unlikely(__pyx_v_data == Py_None)) { + PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); + __PYX_ERR(0, 237, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_PyBytes_GET_SIZE(__pyx_v_data); if (unlikely(__pyx_t_1 == ((Py_ssize_t)-1))) __PYX_ERR(0, 237, __pyx_L1_error) + __pyx_v_length = __pyx_t_1; + + /* "cereal/messaging/messaging_pyx.pyx":238 + * def send(self, bytes data): + * length = len(data) + * r = self.socket.send(data, length) # <<<<<<<<<<<<<< + * + * if r != length: + */ + if (unlikely(__pyx_v_data == Py_None)) { + PyErr_SetString(PyExc_TypeError, "expected bytes, NoneType found"); + __PYX_ERR(0, 238, __pyx_L1_error) + } + __pyx_t_2 = __Pyx_PyBytes_AsWritableString(__pyx_v_data); if (unlikely((!__pyx_t_2) && PyErr_Occurred())) __PYX_ERR(0, 238, __pyx_L1_error) + __pyx_v_r = __pyx_v_self->socket->send(((char *)__pyx_t_2), __pyx_v_length); + + /* "cereal/messaging/messaging_pyx.pyx":240 + * r = self.socket.send(data, length) + * + * if r != length: # <<<<<<<<<<<<<< + * if errno.errno == errno.EADDRINUSE: + * raise MultiplePublishersError + */ + __pyx_t_3 = (__pyx_v_r != __pyx_v_length); + if (__pyx_t_3) { + + /* "cereal/messaging/messaging_pyx.pyx":241 + * + * if r != length: + * if errno.errno == errno.EADDRINUSE: # <<<<<<<<<<<<<< + * raise MultiplePublishersError + * else: + */ + __pyx_t_3 = (errno == EADDRINUSE); + if (unlikely(__pyx_t_3)) { + + /* "cereal/messaging/messaging_pyx.pyx":242 + * if r != length: + * if errno.errno == errno.EADDRINUSE: + * raise MultiplePublishersError # <<<<<<<<<<<<<< + * else: + * raise MessagingError + */ + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_MultiplePublishersError); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 242, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_Raise(__pyx_t_4, 0, 0, 0); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __PYX_ERR(0, 242, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":241 + * + * if r != length: + * if errno.errno == errno.EADDRINUSE: # <<<<<<<<<<<<<< + * raise MultiplePublishersError + * else: + */ + } + + /* "cereal/messaging/messaging_pyx.pyx":244 + * raise MultiplePublishersError + * else: + * raise MessagingError # <<<<<<<<<<<<<< + * + * def all_readers_updated(self): + */ + /*else*/ { + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_MessagingError); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 244, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_Raise(__pyx_t_4, 0, 0, 0); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __PYX_ERR(0, 244, __pyx_L1_error) + } + + /* "cereal/messaging/messaging_pyx.pyx":240 + * r = self.socket.send(data, length) + * + * if r != length: # <<<<<<<<<<<<<< + * if errno.errno == errno.EADDRINUSE: + * raise MultiplePublishersError + */ + } + + /* "cereal/messaging/messaging_pyx.pyx":236 + * raise MessagingError(endpoint) + * + * def send(self, bytes data): # <<<<<<<<<<<<<< + * length = len(data) + * r = self.socket.send(data, length) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.PubSocket.send", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/messaging/messaging_pyx.pyx":246 + * raise MessagingError + * + * def all_readers_updated(self): # <<<<<<<<<<<<<< + * return self.socket.all_readers_updated() + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_9all_readers_updated(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_9PubSocket_9all_readers_updated = {"all_readers_updated", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_9all_readers_updated, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_9all_readers_updated(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("all_readers_updated (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("all_readers_updated", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "all_readers_updated", 0))) return NULL; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_9PubSocket_8all_readers_updated(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_9PubSocket_8all_readers_updated(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("all_readers_updated", 1); + + /* "cereal/messaging/messaging_pyx.pyx":247 + * + * def all_readers_updated(self): + * return self.socket.all_readers_updated() # <<<<<<<<<<<<<< + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyBool_FromLong(__pyx_v_self->socket->all_readers_updated()); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 247, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/messaging/messaging_pyx.pyx":246 + * raise MessagingError + * + * def all_readers_updated(self): # <<<<<<<<<<<<<< + * return self.socket.all_readers_updated() + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.PubSocket.all_readers_updated", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_11__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_9PubSocket_11__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_11__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_11__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_9PubSocket_10__reduce_cython__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_9PubSocket_10__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.PubSocket.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_13__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9messaging_13messaging_pyx_9PubSocket_13__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_13__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_13__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.PubSocket.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9messaging_13messaging_pyx_9PubSocket_12__setstate_cython__(((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9messaging_13messaging_pyx_9PubSocket_12__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.messaging.messaging_pyx.PubSocket.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} +static struct __pyx_vtabstruct_6cereal_9messaging_13messaging_pyx_Event __pyx_vtable_6cereal_9messaging_13messaging_pyx_Event; + +static PyObject *__pyx_tp_new_6cereal_9messaging_13messaging_pyx_Event(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { + struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *)o); + p->__pyx_vtab = __pyx_vtabptr_6cereal_9messaging_13messaging_pyx_Event; + new((void*)&(p->event)) Event(); + if (unlikely(__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_1__cinit__(o, __pyx_empty_tuple, NULL) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static void __pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_Event(PyObject *o) { + struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *p = (struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_Event) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + __Pyx_call_destructor(p->event); + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} + +static PyObject *__pyx_getprop_6cereal_9messaging_13messaging_pyx_5Event_fd(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_2fd_1__get__(o); +} + +static PyObject *__pyx_getprop_6cereal_9messaging_13messaging_pyx_5Event_ptr(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_3ptr_1__get__(o); +} + +static PyMethodDef __pyx_methods_6cereal_9messaging_13messaging_pyx_Event[] = { + {"set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_3set, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"clear", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_5clear, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"wait", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_7wait, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"peek", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_9peek, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_11__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_5Event_13__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; + +static struct PyGetSetDef __pyx_getsets_6cereal_9messaging_13messaging_pyx_Event[] = { + {(char *)"fd", __pyx_getprop_6cereal_9messaging_13messaging_pyx_5Event_fd, 0, (char *)0, 0}, + {(char *)"ptr", __pyx_getprop_6cereal_9messaging_13messaging_pyx_5Event_ptr, 0, (char *)0, 0}, + {0, 0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_6cereal_9messaging_13messaging_pyx_Event_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_Event}, + {Py_tp_methods, (void *)__pyx_methods_6cereal_9messaging_13messaging_pyx_Event}, + {Py_tp_getset, (void *)__pyx_getsets_6cereal_9messaging_13messaging_pyx_Event}, + {Py_tp_new, (void *)__pyx_tp_new_6cereal_9messaging_13messaging_pyx_Event}, + {0, 0}, +}; +static PyType_Spec __pyx_type_6cereal_9messaging_13messaging_pyx_Event_spec = { + "cereal.messaging.messaging_pyx.Event", + sizeof(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, + __pyx_type_6cereal_9messaging_13messaging_pyx_Event_slots, +}; +#else + +static PyTypeObject __pyx_type_6cereal_9messaging_13messaging_pyx_Event = { + PyVarObject_HEAD_INIT(0, 0) + "cereal.messaging.messaging_pyx.""Event", /*tp_name*/ + sizeof(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_Event, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, /*tp_flags*/ + 0, /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_6cereal_9messaging_13messaging_pyx_Event, /*tp_methods*/ + 0, /*tp_members*/ + __pyx_getsets_6cereal_9messaging_13messaging_pyx_Event, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_6cereal_9messaging_13messaging_pyx_Event, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyObject *__pyx_tp_new_6cereal_9messaging_13messaging_pyx_SocketEventHandle(PyTypeObject *t, PyObject *a, PyObject *k) { + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + if (unlikely(__pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_1__cinit__(o, a, k) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static void __pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_SocketEventHandle(PyObject *o) { + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_SocketEventHandle) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_3__dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} + +static PyObject *__pyx_getprop_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_enabled(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_7enabled_1__get__(o); +} + +static int __pyx_setprop_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_enabled(PyObject *o, PyObject *v, CYTHON_UNUSED void *x) { + if (v) { + return __pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_7enabled_3__set__(o, v); + } + else { + PyErr_SetString(PyExc_NotImplementedError, "__del__"); + return -1; + } +} + +static PyObject *__pyx_getprop_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_recv_called_event(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_17recv_called_event_1__get__(o); +} + +static PyObject *__pyx_getprop_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_recv_ready_event(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_16recv_ready_event_1__get__(o); +} + +static PyMethodDef __pyx_methods_6cereal_9messaging_13messaging_pyx_SocketEventHandle[] = { + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_5__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_7__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; + +static struct PyGetSetDef __pyx_getsets_6cereal_9messaging_13messaging_pyx_SocketEventHandle[] = { + {(char *)"enabled", __pyx_getprop_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_enabled, __pyx_setprop_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_enabled, (char *)0, 0}, + {(char *)"recv_called_event", __pyx_getprop_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_recv_called_event, 0, (char *)0, 0}, + {(char *)"recv_ready_event", __pyx_getprop_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_recv_ready_event, 0, (char *)0, 0}, + {0, 0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_6cereal_9messaging_13messaging_pyx_SocketEventHandle_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_SocketEventHandle}, + {Py_tp_methods, (void *)__pyx_methods_6cereal_9messaging_13messaging_pyx_SocketEventHandle}, + {Py_tp_getset, (void *)__pyx_getsets_6cereal_9messaging_13messaging_pyx_SocketEventHandle}, + {Py_tp_new, (void *)__pyx_tp_new_6cereal_9messaging_13messaging_pyx_SocketEventHandle}, + {0, 0}, +}; +static PyType_Spec __pyx_type_6cereal_9messaging_13messaging_pyx_SocketEventHandle_spec = { + "cereal.messaging.messaging_pyx.SocketEventHandle", + sizeof(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, + __pyx_type_6cereal_9messaging_13messaging_pyx_SocketEventHandle_slots, +}; +#else + +static PyTypeObject __pyx_type_6cereal_9messaging_13messaging_pyx_SocketEventHandle = { + PyVarObject_HEAD_INIT(0, 0) + "cereal.messaging.messaging_pyx.""SocketEventHandle", /*tp_name*/ + sizeof(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SocketEventHandle), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_SocketEventHandle, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, /*tp_flags*/ + 0, /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_6cereal_9messaging_13messaging_pyx_SocketEventHandle, /*tp_methods*/ + 0, /*tp_members*/ + __pyx_getsets_6cereal_9messaging_13messaging_pyx_SocketEventHandle, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_6cereal_9messaging_13messaging_pyx_SocketEventHandle, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyObject *__pyx_tp_new_6cereal_9messaging_13messaging_pyx_Context(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + if (unlikely(__pyx_pw_6cereal_9messaging_13messaging_pyx_7Context_1__cinit__(o, __pyx_empty_tuple, NULL) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static void __pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_Context(PyObject *o) { + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_Context) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_pw_6cereal_9messaging_13messaging_pyx_7Context_5__dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} + +static PyMethodDef __pyx_methods_6cereal_9messaging_13messaging_pyx_Context[] = { + {"term", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_7Context_3term, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_7Context_7__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_7Context_9__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_6cereal_9messaging_13messaging_pyx_Context_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_Context}, + {Py_tp_methods, (void *)__pyx_methods_6cereal_9messaging_13messaging_pyx_Context}, + {Py_tp_new, (void *)__pyx_tp_new_6cereal_9messaging_13messaging_pyx_Context}, + {0, 0}, +}; +static PyType_Spec __pyx_type_6cereal_9messaging_13messaging_pyx_Context_spec = { + "cereal.messaging.messaging_pyx.Context", + sizeof(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, + __pyx_type_6cereal_9messaging_13messaging_pyx_Context_slots, +}; +#else + +static PyTypeObject __pyx_type_6cereal_9messaging_13messaging_pyx_Context = { + PyVarObject_HEAD_INIT(0, 0) + "cereal.messaging.messaging_pyx.""Context", /*tp_name*/ + sizeof(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Context), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_Context, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, /*tp_flags*/ + 0, /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_6cereal_9messaging_13messaging_pyx_Context, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_6cereal_9messaging_13messaging_pyx_Context, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyObject *__pyx_tp_new_6cereal_9messaging_13messaging_pyx_Poller(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { + struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *)o); + p->sub_sockets = ((PyObject*)Py_None); Py_INCREF(Py_None); + if (unlikely(__pyx_pw_6cereal_9messaging_13messaging_pyx_6Poller_1__cinit__(o, __pyx_empty_tuple, NULL) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static void __pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_Poller(PyObject *o) { + struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *p = (struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_Poller) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_pw_6cereal_9messaging_13messaging_pyx_6Poller_3__dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + Py_CLEAR(p->sub_sockets); + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} + +static int __pyx_tp_traverse_6cereal_9messaging_13messaging_pyx_Poller(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *p = (struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *)o; + if (p->sub_sockets) { + e = (*v)(p->sub_sockets, a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear_6cereal_9messaging_13messaging_pyx_Poller(PyObject *o) { + PyObject* tmp; + struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *p = (struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller *)o; + tmp = ((PyObject*)p->sub_sockets); + p->sub_sockets = ((PyObject*)Py_None); Py_INCREF(Py_None); + Py_XDECREF(tmp); + return 0; +} + +static PyMethodDef __pyx_methods_6cereal_9messaging_13messaging_pyx_Poller[] = { + {"registerSocket", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_6Poller_5registerSocket, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"poll", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_6Poller_7poll, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_6Poller_9__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_6Poller_11__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_6cereal_9messaging_13messaging_pyx_Poller_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_Poller}, + {Py_tp_traverse, (void *)__pyx_tp_traverse_6cereal_9messaging_13messaging_pyx_Poller}, + {Py_tp_clear, (void *)__pyx_tp_clear_6cereal_9messaging_13messaging_pyx_Poller}, + {Py_tp_methods, (void *)__pyx_methods_6cereal_9messaging_13messaging_pyx_Poller}, + {Py_tp_new, (void *)__pyx_tp_new_6cereal_9messaging_13messaging_pyx_Poller}, + {0, 0}, +}; +static PyType_Spec __pyx_type_6cereal_9messaging_13messaging_pyx_Poller_spec = { + "cereal.messaging.messaging_pyx.Poller", + sizeof(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, + __pyx_type_6cereal_9messaging_13messaging_pyx_Poller_slots, +}; +#else + +static PyTypeObject __pyx_type_6cereal_9messaging_13messaging_pyx_Poller = { + PyVarObject_HEAD_INIT(0, 0) + "cereal.messaging.messaging_pyx.""Poller", /*tp_name*/ + sizeof(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Poller), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_Poller, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, /*tp_flags*/ + 0, /*tp_doc*/ + __pyx_tp_traverse_6cereal_9messaging_13messaging_pyx_Poller, /*tp_traverse*/ + __pyx_tp_clear_6cereal_9messaging_13messaging_pyx_Poller, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_6cereal_9messaging_13messaging_pyx_Poller, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_6cereal_9messaging_13messaging_pyx_Poller, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif +static struct __pyx_vtabstruct_6cereal_9messaging_13messaging_pyx_SubSocket __pyx_vtable_6cereal_9messaging_13messaging_pyx_SubSocket; + +static PyObject *__pyx_tp_new_6cereal_9messaging_13messaging_pyx_SubSocket(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { + struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *)o); + p->__pyx_vtab = __pyx_vtabptr_6cereal_9messaging_13messaging_pyx_SubSocket; + if (unlikely(__pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_1__cinit__(o, __pyx_empty_tuple, NULL) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static void __pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_SubSocket(PyObject *o) { + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_SubSocket) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_3__dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} + +static PyMethodDef __pyx_methods_6cereal_9messaging_13messaging_pyx_SubSocket[] = { + {"connect", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_5connect, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"setTimeout", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_7setTimeout, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"receive", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_9receive, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_11__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_9SubSocket_13__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_6cereal_9messaging_13messaging_pyx_SubSocket_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_SubSocket}, + {Py_tp_methods, (void *)__pyx_methods_6cereal_9messaging_13messaging_pyx_SubSocket}, + {Py_tp_new, (void *)__pyx_tp_new_6cereal_9messaging_13messaging_pyx_SubSocket}, + {0, 0}, +}; +static PyType_Spec __pyx_type_6cereal_9messaging_13messaging_pyx_SubSocket_spec = { + "cereal.messaging.messaging_pyx.SubSocket", + sizeof(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, + __pyx_type_6cereal_9messaging_13messaging_pyx_SubSocket_slots, +}; +#else + +static PyTypeObject __pyx_type_6cereal_9messaging_13messaging_pyx_SubSocket = { + PyVarObject_HEAD_INIT(0, 0) + "cereal.messaging.messaging_pyx.""SubSocket", /*tp_name*/ + sizeof(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_SubSocket, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, /*tp_flags*/ + 0, /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_6cereal_9messaging_13messaging_pyx_SubSocket, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_6cereal_9messaging_13messaging_pyx_SubSocket, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyObject *__pyx_tp_new_6cereal_9messaging_13messaging_pyx_PubSocket(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + if (unlikely(__pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_1__cinit__(o, __pyx_empty_tuple, NULL) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static void __pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_PubSocket(PyObject *o) { + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_PubSocket) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_3__dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} + +static PyMethodDef __pyx_methods_6cereal_9messaging_13messaging_pyx_PubSocket[] = { + {"connect", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_5connect, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"send", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_7send, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"all_readers_updated", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_9all_readers_updated, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_11__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9messaging_13messaging_pyx_9PubSocket_13__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_6cereal_9messaging_13messaging_pyx_PubSocket_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_PubSocket}, + {Py_tp_methods, (void *)__pyx_methods_6cereal_9messaging_13messaging_pyx_PubSocket}, + {Py_tp_new, (void *)__pyx_tp_new_6cereal_9messaging_13messaging_pyx_PubSocket}, + {0, 0}, +}; +static PyType_Spec __pyx_type_6cereal_9messaging_13messaging_pyx_PubSocket_spec = { + "cereal.messaging.messaging_pyx.PubSocket", + sizeof(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, + __pyx_type_6cereal_9messaging_13messaging_pyx_PubSocket_slots, +}; +#else + +static PyTypeObject __pyx_type_6cereal_9messaging_13messaging_pyx_PubSocket = { + PyVarObject_HEAD_INIT(0, 0) + "cereal.messaging.messaging_pyx.""PubSocket", /*tp_name*/ + sizeof(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_PubSocket), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_6cereal_9messaging_13messaging_pyx_PubSocket, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, /*tp_flags*/ + 0, /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_6cereal_9messaging_13messaging_pyx_PubSocket, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_6cereal_9messaging_13messaging_pyx_PubSocket, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyMethodDef __pyx_methods[] = { + {0, 0, 0, 0} +}; +#ifndef CYTHON_SMALL_CODE +#if defined(__clang__) + #define CYTHON_SMALL_CODE +#elif defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 3)) + #define CYTHON_SMALL_CODE __attribute__((cold)) +#else + #define CYTHON_SMALL_CODE +#endif +#endif +/* #### Code section: pystring_table ### */ + +static int __Pyx_CreateStringTabAndInitStrings(void) { + __Pyx_StringTabEntry __pyx_string_tab[] = { + {&__pyx_kp_b_, __pyx_k_, sizeof(__pyx_k_), 0, 0, 0, 0}, + {&__pyx_kp_u_, __pyx_k_, sizeof(__pyx_k_), 0, 1, 0, 0}, + {&__pyx_kp_b_127_0_0_1, __pyx_k_127_0_0_1, sizeof(__pyx_k_127_0_0_1), 0, 0, 0, 0}, + {&__pyx_n_s_Context, __pyx_k_Context, sizeof(__pyx_k_Context), 0, 0, 1, 1}, + {&__pyx_n_s_Context___reduce_cython, __pyx_k_Context___reduce_cython, sizeof(__pyx_k_Context___reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_Context___setstate_cython, __pyx_k_Context___setstate_cython, sizeof(__pyx_k_Context___setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_Context_term, __pyx_k_Context_term, sizeof(__pyx_k_Context_term), 0, 0, 1, 1}, + {&__pyx_n_s_Event, __pyx_k_Event, sizeof(__pyx_k_Event), 0, 0, 1, 1}, + {&__pyx_n_s_Event___reduce_cython, __pyx_k_Event___reduce_cython, sizeof(__pyx_k_Event___reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_Event___setstate_cython, __pyx_k_Event___setstate_cython, sizeof(__pyx_k_Event___setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_Event_clear, __pyx_k_Event_clear, sizeof(__pyx_k_Event_clear), 0, 0, 1, 1}, + {&__pyx_n_s_Event_peek, __pyx_k_Event_peek, sizeof(__pyx_k_Event_peek), 0, 0, 1, 1}, + {&__pyx_n_s_Event_set, __pyx_k_Event_set, sizeof(__pyx_k_Event_set), 0, 0, 1, 1}, + {&__pyx_n_s_Event_wait, __pyx_k_Event_wait, sizeof(__pyx_k_Event_wait), 0, 0, 1, 1}, + {&__pyx_n_s_MessagingError, __pyx_k_MessagingError, sizeof(__pyx_k_MessagingError), 0, 0, 1, 1}, + {&__pyx_n_s_MessagingError___init, __pyx_k_MessagingError___init, sizeof(__pyx_k_MessagingError___init), 0, 0, 1, 1}, + {&__pyx_kp_u_Messaging_failure, __pyx_k_Messaging_failure, sizeof(__pyx_k_Messaging_failure), 0, 1, 0, 0}, + {&__pyx_n_s_MultiplePublishersError, __pyx_k_MultiplePublishersError, sizeof(__pyx_k_MultiplePublishersError), 0, 0, 1, 1}, + {&__pyx_kp_u_None, __pyx_k_None, sizeof(__pyx_k_None), 0, 1, 0, 0}, + {&__pyx_n_s_Poller, __pyx_k_Poller, sizeof(__pyx_k_Poller), 0, 0, 1, 1}, + {&__pyx_n_s_Poller___reduce_cython, __pyx_k_Poller___reduce_cython, sizeof(__pyx_k_Poller___reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_Poller___setstate_cython, __pyx_k_Poller___setstate_cython, sizeof(__pyx_k_Poller___setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_Poller_poll, __pyx_k_Poller_poll, sizeof(__pyx_k_Poller_poll), 0, 0, 1, 1}, + {&__pyx_n_s_Poller_registerSocket, __pyx_k_Poller_registerSocket, sizeof(__pyx_k_Poller_registerSocket), 0, 0, 1, 1}, + {&__pyx_n_s_PubSocket, __pyx_k_PubSocket, sizeof(__pyx_k_PubSocket), 0, 0, 1, 1}, + {&__pyx_n_s_PubSocket___reduce_cython, __pyx_k_PubSocket___reduce_cython, sizeof(__pyx_k_PubSocket___reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_PubSocket___setstate_cython, __pyx_k_PubSocket___setstate_cython, sizeof(__pyx_k_PubSocket___setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_PubSocket_all_readers_updated, __pyx_k_PubSocket_all_readers_updated, sizeof(__pyx_k_PubSocket_all_readers_updated), 0, 0, 1, 1}, + {&__pyx_n_s_PubSocket_connect, __pyx_k_PubSocket_connect, sizeof(__pyx_k_PubSocket_connect), 0, 0, 1, 1}, + {&__pyx_n_s_PubSocket_send, __pyx_k_PubSocket_send, sizeof(__pyx_k_PubSocket_send), 0, 0, 1, 1}, + {&__pyx_kp_u_SIGINT_received_exiting, __pyx_k_SIGINT_received_exiting, sizeof(__pyx_k_SIGINT_received_exiting), 0, 1, 0, 0}, + {&__pyx_n_s_SocketEventHandle, __pyx_k_SocketEventHandle, sizeof(__pyx_k_SocketEventHandle), 0, 0, 1, 1}, + {&__pyx_n_s_SocketEventHandle___reduce_cytho, __pyx_k_SocketEventHandle___reduce_cytho, sizeof(__pyx_k_SocketEventHandle___reduce_cytho), 0, 0, 1, 1}, + {&__pyx_n_s_SocketEventHandle___setstate_cyt, __pyx_k_SocketEventHandle___setstate_cyt, sizeof(__pyx_k_SocketEventHandle___setstate_cyt), 0, 0, 1, 1}, + {&__pyx_n_s_SubSocket, __pyx_k_SubSocket, sizeof(__pyx_k_SubSocket), 0, 0, 1, 1}, + {&__pyx_n_s_SubSocket___reduce_cython, __pyx_k_SubSocket___reduce_cython, sizeof(__pyx_k_SubSocket___reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_SubSocket___setstate_cython, __pyx_k_SubSocket___setstate_cython, sizeof(__pyx_k_SubSocket___setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_SubSocket_connect, __pyx_k_SubSocket_connect, sizeof(__pyx_k_SubSocket_connect), 0, 0, 1, 1}, + {&__pyx_n_s_SubSocket_receive, __pyx_k_SubSocket_receive, sizeof(__pyx_k_SubSocket_receive), 0, 0, 1, 1}, + {&__pyx_n_s_SubSocket_setTimeout, __pyx_k_SubSocket_setTimeout, sizeof(__pyx_k_SubSocket_setTimeout), 0, 0, 1, 1}, + {&__pyx_n_s_TypeError, __pyx_k_TypeError, sizeof(__pyx_k_TypeError), 0, 0, 1, 1}, + {&__pyx_kp_u__2, __pyx_k__2, sizeof(__pyx_k__2), 0, 1, 0, 0}, + {&__pyx_n_s__5, __pyx_k__5, sizeof(__pyx_k__5), 0, 0, 1, 1}, + {&__pyx_n_s__53, __pyx_k__53, sizeof(__pyx_k__53), 0, 0, 1, 1}, + {&__pyx_n_s_address, __pyx_k_address, sizeof(__pyx_k_address), 0, 0, 1, 1}, + {&__pyx_n_s_all_readers_updated, __pyx_k_all_readers_updated, sizeof(__pyx_k_all_readers_updated), 0, 0, 1, 1}, + {&__pyx_n_s_asyncio_coroutines, __pyx_k_asyncio_coroutines, sizeof(__pyx_k_asyncio_coroutines), 0, 0, 1, 1}, + {&__pyx_n_s_cereal_messaging_messaging_pyx, __pyx_k_cereal_messaging_messaging_pyx, sizeof(__pyx_k_cereal_messaging_messaging_pyx), 0, 0, 1, 1}, + {&__pyx_kp_s_cereal_messaging_messaging_pyx_p, __pyx_k_cereal_messaging_messaging_pyx_p, sizeof(__pyx_k_cereal_messaging_messaging_pyx_p), 0, 0, 1, 0}, + {&__pyx_n_s_clear, __pyx_k_clear, sizeof(__pyx_k_clear), 0, 0, 1, 1}, + {&__pyx_n_s_cline_in_traceback, __pyx_k_cline_in_traceback, sizeof(__pyx_k_cline_in_traceback), 0, 0, 1, 1}, + {&__pyx_n_s_conflate, __pyx_k_conflate, sizeof(__pyx_k_conflate), 0, 0, 1, 1}, + {&__pyx_n_s_connect, __pyx_k_connect, sizeof(__pyx_k_connect), 0, 0, 1, 1}, + {&__pyx_n_s_context, __pyx_k_context, sizeof(__pyx_k_context), 0, 0, 1, 1}, + {&__pyx_n_s_data, __pyx_k_data, sizeof(__pyx_k_data), 0, 0, 1, 1}, + {&__pyx_n_s_decode, __pyx_k_decode, sizeof(__pyx_k_decode), 0, 0, 1, 1}, + {&__pyx_n_s_delete_fake_prefix, __pyx_k_delete_fake_prefix, sizeof(__pyx_k_delete_fake_prefix), 0, 0, 1, 1}, + {&__pyx_n_s_dict, __pyx_k_dict, sizeof(__pyx_k_dict), 0, 0, 1, 1}, + {&__pyx_kp_u_disable, __pyx_k_disable, sizeof(__pyx_k_disable), 0, 1, 0, 0}, + {&__pyx_n_s_doc, __pyx_k_doc, sizeof(__pyx_k_doc), 0, 0, 1, 1}, + {&__pyx_kp_u_enable, __pyx_k_enable, sizeof(__pyx_k_enable), 0, 1, 0, 0}, + {&__pyx_n_s_enabled, __pyx_k_enabled, sizeof(__pyx_k_enabled), 0, 0, 1, 1}, + {&__pyx_n_s_endpoint, __pyx_k_endpoint, sizeof(__pyx_k_endpoint), 0, 0, 1, 1}, + {&__pyx_n_s_event, __pyx_k_event, sizeof(__pyx_k_event), 0, 0, 1, 1}, + {&__pyx_n_s_events, __pyx_k_events, sizeof(__pyx_k_events), 0, 0, 1, 1}, + {&__pyx_n_s_exit, __pyx_k_exit, sizeof(__pyx_k_exit), 0, 0, 1, 1}, + {&__pyx_kp_u_gc, __pyx_k_gc, sizeof(__pyx_k_gc), 0, 1, 0, 0}, + {&__pyx_n_s_get_fake_prefix, __pyx_k_get_fake_prefix, sizeof(__pyx_k_get_fake_prefix), 0, 0, 1, 1}, + {&__pyx_n_s_getstate, __pyx_k_getstate, sizeof(__pyx_k_getstate), 0, 0, 1, 1}, + {&__pyx_n_s_identifier, __pyx_k_identifier, sizeof(__pyx_k_identifier), 0, 0, 1, 1}, + {&__pyx_n_s_import, __pyx_k_import, sizeof(__pyx_k_import), 0, 0, 1, 1}, + {&__pyx_n_s_init, __pyx_k_init, sizeof(__pyx_k_init), 0, 0, 1, 1}, + {&__pyx_n_s_init_subclass, __pyx_k_init_subclass, sizeof(__pyx_k_init_subclass), 0, 0, 1, 1}, + {&__pyx_n_s_initializing, __pyx_k_initializing, sizeof(__pyx_k_initializing), 0, 0, 1, 1}, + {&__pyx_n_s_is_coroutine, __pyx_k_is_coroutine, sizeof(__pyx_k_is_coroutine), 0, 0, 1, 1}, + {&__pyx_kp_u_isenabled, __pyx_k_isenabled, sizeof(__pyx_k_isenabled), 0, 1, 0, 0}, + {&__pyx_n_s_items, __pyx_k_items, sizeof(__pyx_k_items), 0, 0, 1, 1}, + {&__pyx_n_s_length, __pyx_k_length, sizeof(__pyx_k_length), 0, 0, 1, 1}, + {&__pyx_n_s_m, __pyx_k_m, sizeof(__pyx_k_m), 0, 0, 1, 1}, + {&__pyx_n_s_main, __pyx_k_main, sizeof(__pyx_k_main), 0, 0, 1, 1}, + {&__pyx_n_s_message, __pyx_k_message, sizeof(__pyx_k_message), 0, 0, 1, 1}, + {&__pyx_n_s_metaclass, __pyx_k_metaclass, sizeof(__pyx_k_metaclass), 0, 0, 1, 1}, + {&__pyx_n_s_module, __pyx_k_module, sizeof(__pyx_k_module), 0, 0, 1, 1}, + {&__pyx_n_s_mro_entries, __pyx_k_mro_entries, sizeof(__pyx_k_mro_entries), 0, 0, 1, 1}, + {&__pyx_n_s_msg, __pyx_k_msg, sizeof(__pyx_k_msg), 0, 0, 1, 1}, + {&__pyx_n_s_name, __pyx_k_name, sizeof(__pyx_k_name), 0, 0, 1, 1}, + {&__pyx_kp_s_no_default___reduce___due_to_non, __pyx_k_no_default___reduce___due_to_non, sizeof(__pyx_k_no_default___reduce___due_to_non), 0, 0, 1, 0}, + {&__pyx_n_s_non_blocking, __pyx_k_non_blocking, sizeof(__pyx_k_non_blocking), 0, 0, 1, 1}, + {&__pyx_n_s_override, __pyx_k_override, sizeof(__pyx_k_override), 0, 0, 1, 1}, + {&__pyx_n_s_peek, __pyx_k_peek, sizeof(__pyx_k_peek), 0, 0, 1, 1}, + {&__pyx_n_s_poll, __pyx_k_poll, sizeof(__pyx_k_poll), 0, 0, 1, 1}, + {&__pyx_n_s_prefix, __pyx_k_prefix, sizeof(__pyx_k_prefix), 0, 0, 1, 1}, + {&__pyx_n_s_prepare, __pyx_k_prepare, sizeof(__pyx_k_prepare), 0, 0, 1, 1}, + {&__pyx_n_s_print, __pyx_k_print, sizeof(__pyx_k_print), 0, 0, 1, 1}, + {&__pyx_n_s_ptr, __pyx_k_ptr, sizeof(__pyx_k_ptr), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_state, __pyx_k_pyx_state, sizeof(__pyx_k_pyx_state), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_vtable, __pyx_k_pyx_vtable, sizeof(__pyx_k_pyx_vtable), 0, 0, 1, 1}, + {&__pyx_n_s_qualname, __pyx_k_qualname, sizeof(__pyx_k_qualname), 0, 0, 1, 1}, + {&__pyx_n_s_r, __pyx_k_r, sizeof(__pyx_k_r), 0, 0, 1, 1}, + {&__pyx_n_s_receive, __pyx_k_receive, sizeof(__pyx_k_receive), 0, 0, 1, 1}, + {&__pyx_n_s_reduce, __pyx_k_reduce, sizeof(__pyx_k_reduce), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_cython, __pyx_k_reduce_cython, sizeof(__pyx_k_reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_ex, __pyx_k_reduce_ex, sizeof(__pyx_k_reduce_ex), 0, 0, 1, 1}, + {&__pyx_n_s_registerSocket, __pyx_k_registerSocket, sizeof(__pyx_k_registerSocket), 0, 0, 1, 1}, + {&__pyx_n_s_result, __pyx_k_result, sizeof(__pyx_k_result), 0, 0, 1, 1}, + {&__pyx_n_s_s, __pyx_k_s, sizeof(__pyx_k_s), 0, 0, 1, 1}, + {&__pyx_n_s_self, __pyx_k_self, sizeof(__pyx_k_self), 0, 0, 1, 1}, + {&__pyx_n_s_send, __pyx_k_send, sizeof(__pyx_k_send), 0, 0, 1, 1}, + {&__pyx_n_s_set, __pyx_k_set, sizeof(__pyx_k_set), 0, 0, 1, 1}, + {&__pyx_n_s_setTimeout, __pyx_k_setTimeout, sizeof(__pyx_k_setTimeout), 0, 0, 1, 1}, + {&__pyx_n_s_set_fake_prefix, __pyx_k_set_fake_prefix, sizeof(__pyx_k_set_fake_prefix), 0, 0, 1, 1}, + {&__pyx_n_s_set_name, __pyx_k_set_name, sizeof(__pyx_k_set_name), 0, 0, 1, 1}, + {&__pyx_n_s_setstate, __pyx_k_setstate, sizeof(__pyx_k_setstate), 0, 0, 1, 1}, + {&__pyx_n_s_setstate_cython, __pyx_k_setstate_cython, sizeof(__pyx_k_setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_socket, __pyx_k_socket, sizeof(__pyx_k_socket), 0, 0, 1, 1}, + {&__pyx_n_s_sockets, __pyx_k_sockets, sizeof(__pyx_k_sockets), 0, 0, 1, 1}, + {&__pyx_n_s_spec, __pyx_k_spec, sizeof(__pyx_k_spec), 0, 0, 1, 1}, + {&__pyx_kp_s_stringsource, __pyx_k_stringsource, sizeof(__pyx_k_stringsource), 0, 0, 1, 0}, + {&__pyx_n_s_suffix, __pyx_k_suffix, sizeof(__pyx_k_suffix), 0, 0, 1, 1}, + {&__pyx_n_s_super, __pyx_k_super, sizeof(__pyx_k_super), 0, 0, 1, 1}, + {&__pyx_n_s_sys, __pyx_k_sys, sizeof(__pyx_k_sys), 0, 0, 1, 1}, + {&__pyx_n_s_sz, __pyx_k_sz, sizeof(__pyx_k_sz), 0, 0, 1, 1}, + {&__pyx_n_s_t, __pyx_k_t, sizeof(__pyx_k_t), 0, 0, 1, 1}, + {&__pyx_n_s_term, __pyx_k_term, sizeof(__pyx_k_term), 0, 0, 1, 1}, + {&__pyx_n_s_test, __pyx_k_test, sizeof(__pyx_k_test), 0, 0, 1, 1}, + {&__pyx_n_s_timeout, __pyx_k_timeout, sizeof(__pyx_k_timeout), 0, 0, 1, 1}, + {&__pyx_n_s_toggle_fake_events, __pyx_k_toggle_fake_events, sizeof(__pyx_k_toggle_fake_events), 0, 0, 1, 1}, + {&__pyx_kp_u_utf_8, __pyx_k_utf_8, sizeof(__pyx_k_utf_8), 0, 1, 0, 0}, + {&__pyx_n_s_wait, __pyx_k_wait, sizeof(__pyx_k_wait), 0, 0, 1, 1}, + {&__pyx_n_s_wait_for_one_event, __pyx_k_wait_for_one_event, sizeof(__pyx_k_wait_for_one_event), 0, 0, 1, 1}, + {&__pyx_kp_u_with, __pyx_k_with, sizeof(__pyx_k_with), 0, 1, 0, 0}, + {0, 0, 0, 0, 0, 0, 0} + }; + return __Pyx_InitStrings(__pyx_string_tab); +} +/* #### Code section: cached_builtins ### */ +static CYTHON_SMALL_CODE int __Pyx_InitCachedBuiltins(void) { + __pyx_builtin_super = __Pyx_GetBuiltinName(__pyx_n_s_super); if (!__pyx_builtin_super) __PYX_ERR(0, 25, __pyx_L1_error) + __pyx_builtin_TypeError = __Pyx_GetBuiltinName(__pyx_n_s_TypeError); if (!__pyx_builtin_TypeError) __PYX_ERR(1, 2, __pyx_L1_error) + __pyx_builtin_print = __Pyx_GetBuiltinName(__pyx_n_s_print); if (!__pyx_builtin_print) __PYX_ERR(0, 204, __pyx_L1_error) + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: cached_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_InitCachedConstants", 0); + + /* "cereal/messaging/messaging_pyx.pyx":204 + * # If a blocking read returns no message check errno if SIGINT was caught in the C++ code + * if errno.errno == errno.EINTR: + * print("SIGINT received, exiting") # <<<<<<<<<<<<<< + * sys.exit(1) + * + */ + __pyx_tuple__4 = PyTuple_Pack(1, __pyx_kp_u_SIGINT_received_exiting); if (unlikely(!__pyx_tuple__4)) __PYX_ERR(0, 204, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__4); + __Pyx_GIVEREF(__pyx_tuple__4); + + /* "cereal/messaging/messaging_pyx.pyx":22 + * + * class MessagingError(Exception): + * def __init__(self, endpoint=None): # <<<<<<<<<<<<<< + * suffix = f"with {endpoint.decode('utf-8')}" if endpoint else "" + * message = f"Messaging failure {suffix}: {strerror(errno.errno).decode('utf-8')}" + */ + __pyx_tuple__6 = PyTuple_Pack(4, __pyx_n_s_self, __pyx_n_s_endpoint, __pyx_n_s_suffix, __pyx_n_s_message); if (unlikely(!__pyx_tuple__6)) __PYX_ERR(0, 22, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__6); + __Pyx_GIVEREF(__pyx_tuple__6); + __pyx_codeobj__7 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 4, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__6, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_messaging_messaging_pyx_p, __pyx_n_s_init, 22, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__7)) __PYX_ERR(0, 22, __pyx_L1_error) + __pyx_tuple__8 = PyTuple_Pack(1, Py_None); if (unlikely(!__pyx_tuple__8)) __PYX_ERR(0, 22, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__8); + __Pyx_GIVEREF(__pyx_tuple__8); + + /* "cereal/messaging/messaging_pyx.pyx":32 + * + * + * def toggle_fake_events(bool enabled): # <<<<<<<<<<<<<< + * cppSocketEventHandle.toggle_fake_events(enabled) + * + */ + __pyx_tuple__9 = PyTuple_Pack(1, __pyx_n_s_enabled); if (unlikely(!__pyx_tuple__9)) __PYX_ERR(0, 32, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__9); + __Pyx_GIVEREF(__pyx_tuple__9); + __pyx_codeobj__10 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__9, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_messaging_messaging_pyx_p, __pyx_n_s_toggle_fake_events, 32, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__10)) __PYX_ERR(0, 32, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":36 + * + * + * def set_fake_prefix(string prefix): # <<<<<<<<<<<<<< + * cppSocketEventHandle.set_fake_prefix(prefix) + * + */ + __pyx_tuple__11 = PyTuple_Pack(1, __pyx_n_s_prefix); if (unlikely(!__pyx_tuple__11)) __PYX_ERR(0, 36, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__11); + __Pyx_GIVEREF(__pyx_tuple__11); + __pyx_codeobj__12 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__11, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_messaging_messaging_pyx_p, __pyx_n_s_set_fake_prefix, 36, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__12)) __PYX_ERR(0, 36, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":40 + * + * + * def get_fake_prefix(): # <<<<<<<<<<<<<< + * return cppSocketEventHandle.fake_prefix() + * + */ + __pyx_codeobj__13 = (PyObject*)__Pyx_PyCode_New(0, 0, 0, 0, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_messaging_messaging_pyx_p, __pyx_n_s_get_fake_prefix, 40, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__13)) __PYX_ERR(0, 40, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":44 + * + * + * def delete_fake_prefix(): # <<<<<<<<<<<<<< + * cppSocketEventHandle.set_fake_prefix(b"") + * + */ + __pyx_codeobj__14 = (PyObject*)__Pyx_PyCode_New(0, 0, 0, 0, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_messaging_messaging_pyx_p, __pyx_n_s_delete_fake_prefix, 44, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__14)) __PYX_ERR(0, 44, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":48 + * + * + * def wait_for_one_event(list events, int timeout=-1): # <<<<<<<<<<<<<< + * cdef vector[cppEvent] items + * for event in events: + */ + __pyx_tuple__15 = PyTuple_Pack(4, __pyx_n_s_events, __pyx_n_s_timeout, __pyx_n_s_items, __pyx_n_s_event); if (unlikely(!__pyx_tuple__15)) __PYX_ERR(0, 48, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__15); + __Pyx_GIVEREF(__pyx_tuple__15); + __pyx_codeobj__16 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 4, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__15, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_messaging_messaging_pyx_p, __pyx_n_s_wait_for_one_event, 48, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__16)) __PYX_ERR(0, 48, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":64 + * self.event = event + * + * def set(self): # <<<<<<<<<<<<<< + * self.event.set() + * + */ + __pyx_tuple__17 = PyTuple_Pack(1, __pyx_n_s_self); if (unlikely(!__pyx_tuple__17)) __PYX_ERR(0, 64, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__17); + __Pyx_GIVEREF(__pyx_tuple__17); + __pyx_codeobj__18 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__17, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_messaging_messaging_pyx_p, __pyx_n_s_set, 64, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__18)) __PYX_ERR(0, 64, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":67 + * self.event.set() + * + * def clear(self): # <<<<<<<<<<<<<< + * return self.event.clear() + * + */ + __pyx_codeobj__19 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__17, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_messaging_messaging_pyx_p, __pyx_n_s_clear, 67, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__19)) __PYX_ERR(0, 67, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":70 + * return self.event.clear() + * + * def wait(self, int timeout=-1): # <<<<<<<<<<<<<< + * self.event.wait(timeout) + * + */ + __pyx_tuple__20 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_timeout); if (unlikely(!__pyx_tuple__20)) __PYX_ERR(0, 70, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__20); + __Pyx_GIVEREF(__pyx_tuple__20); + __pyx_codeobj__21 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__20, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_messaging_messaging_pyx_p, __pyx_n_s_wait, 70, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__21)) __PYX_ERR(0, 70, __pyx_L1_error) + __pyx_tuple__22 = PyTuple_Pack(1, __pyx_int_neg_1); if (unlikely(!__pyx_tuple__22)) __PYX_ERR(0, 70, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__22); + __Pyx_GIVEREF(__pyx_tuple__22); + + /* "cereal/messaging/messaging_pyx.pyx":73 + * self.event.wait(timeout) + * + * def peek(self): # <<<<<<<<<<<<<< + * return self.event.peek() + * + */ + __pyx_codeobj__23 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__17, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_messaging_messaging_pyx_p, __pyx_n_s_peek, 73, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__23)) __PYX_ERR(0, 73, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_codeobj__24 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__17, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__24)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_tuple__25 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_pyx_state); if (unlikely(!__pyx_tuple__25)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__25); + __Pyx_GIVEREF(__pyx_tuple__25); + __pyx_codeobj__26 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__25, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__26)) __PYX_ERR(1, 3, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_codeobj__27 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__17, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__27)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_codeobj__28 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__25, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__28)) __PYX_ERR(1, 3, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":123 + * self.context = cppContext.create() + * + * def term(self): # <<<<<<<<<<<<<< + * del self.context + * self.context = NULL + */ + __pyx_codeobj__29 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__17, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_messaging_messaging_pyx_p, __pyx_n_s_term, 123, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__29)) __PYX_ERR(0, 123, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_codeobj__30 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__17, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__30)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_codeobj__31 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__25, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__31)) __PYX_ERR(1, 3, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":145 + * del self.poller + * + * def registerSocket(self, SubSocket socket): # <<<<<<<<<<<<<< + * self.sub_sockets.append(socket) + * self.poller.registerSocket(socket.socket) + */ + __pyx_tuple__32 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_socket); if (unlikely(!__pyx_tuple__32)) __PYX_ERR(0, 145, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__32); + __Pyx_GIVEREF(__pyx_tuple__32); + __pyx_codeobj__33 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__32, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_messaging_messaging_pyx_p, __pyx_n_s_registerSocket, 145, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__33)) __PYX_ERR(0, 145, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":149 + * self.poller.registerSocket(socket.socket) + * + * def poll(self, timeout): # <<<<<<<<<<<<<< + * sockets = [] + * cdef int t = timeout + */ + __pyx_tuple__34 = PyTuple_Pack(7, __pyx_n_s_self, __pyx_n_s_timeout, __pyx_n_s_sockets, __pyx_n_s_t, __pyx_n_s_result, __pyx_n_s_s, __pyx_n_s_socket); if (unlikely(!__pyx_tuple__34)) __PYX_ERR(0, 149, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__34); + __Pyx_GIVEREF(__pyx_tuple__34); + __pyx_codeobj__35 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 7, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__34, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_messaging_messaging_pyx_p, __pyx_n_s_poll, 149, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__35)) __PYX_ERR(0, 149, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_codeobj__36 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__17, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__36)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_codeobj__37 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__25, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__37)) __PYX_ERR(1, 3, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":186 + * self.socket = ptr + * + * def connect(self, Context context, string endpoint, string address=b"127.0.0.1", bool conflate=False): # <<<<<<<<<<<<<< + * r = self.socket.connect(context.context, endpoint, address, conflate) + * + */ + __pyx_tuple__38 = PyTuple_Pack(6, __pyx_n_s_self, __pyx_n_s_context, __pyx_n_s_endpoint, __pyx_n_s_address, __pyx_n_s_conflate, __pyx_n_s_r); if (unlikely(!__pyx_tuple__38)) __PYX_ERR(0, 186, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__38); + __Pyx_GIVEREF(__pyx_tuple__38); + __pyx_codeobj__39 = (PyObject*)__Pyx_PyCode_New(5, 0, 0, 6, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__38, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_messaging_messaging_pyx_p, __pyx_n_s_connect, 186, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__39)) __PYX_ERR(0, 186, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":195 + * raise MessagingError(endpoint) + * + * def setTimeout(self, int timeout): # <<<<<<<<<<<<<< + * self.socket.setTimeout(timeout) + * + */ + __pyx_codeobj__40 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__20, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_messaging_messaging_pyx_p, __pyx_n_s_setTimeout, 195, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__40)) __PYX_ERR(0, 195, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":198 + * self.socket.setTimeout(timeout) + * + * def receive(self, bool non_blocking=False): # <<<<<<<<<<<<<< + * msg = self.socket.receive(non_blocking) + * + */ + __pyx_tuple__41 = PyTuple_Pack(5, __pyx_n_s_self, __pyx_n_s_non_blocking, __pyx_n_s_msg, __pyx_n_s_sz, __pyx_n_s_m); if (unlikely(!__pyx_tuple__41)) __PYX_ERR(0, 198, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__41); + __Pyx_GIVEREF(__pyx_tuple__41); + __pyx_codeobj__42 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__41, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_messaging_messaging_pyx_p, __pyx_n_s_receive, 198, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__42)) __PYX_ERR(0, 198, __pyx_L1_error) + __pyx_tuple__43 = PyTuple_Pack(1, Py_False); if (unlikely(!__pyx_tuple__43)) __PYX_ERR(0, 198, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__43); + __Pyx_GIVEREF(__pyx_tuple__43); + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_codeobj__44 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__17, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__44)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_codeobj__45 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__25, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__45)) __PYX_ERR(1, 3, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":227 + * del self.socket + * + * def connect(self, Context context, string endpoint): # <<<<<<<<<<<<<< + * r = self.socket.connect(context.context, endpoint) + * + */ + __pyx_tuple__46 = PyTuple_Pack(4, __pyx_n_s_self, __pyx_n_s_context, __pyx_n_s_endpoint, __pyx_n_s_r); if (unlikely(!__pyx_tuple__46)) __PYX_ERR(0, 227, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__46); + __Pyx_GIVEREF(__pyx_tuple__46); + __pyx_codeobj__47 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 4, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__46, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_messaging_messaging_pyx_p, __pyx_n_s_connect, 227, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__47)) __PYX_ERR(0, 227, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":236 + * raise MessagingError(endpoint) + * + * def send(self, bytes data): # <<<<<<<<<<<<<< + * length = len(data) + * r = self.socket.send(data, length) + */ + __pyx_tuple__48 = PyTuple_Pack(4, __pyx_n_s_self, __pyx_n_s_data, __pyx_n_s_length, __pyx_n_s_r); if (unlikely(!__pyx_tuple__48)) __PYX_ERR(0, 236, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__48); + __Pyx_GIVEREF(__pyx_tuple__48); + __pyx_codeobj__49 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 4, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__48, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_messaging_messaging_pyx_p, __pyx_n_s_send, 236, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__49)) __PYX_ERR(0, 236, __pyx_L1_error) + + /* "cereal/messaging/messaging_pyx.pyx":246 + * raise MessagingError + * + * def all_readers_updated(self): # <<<<<<<<<<<<<< + * return self.socket.all_readers_updated() + */ + __pyx_codeobj__50 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__17, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_messaging_messaging_pyx_p, __pyx_n_s_all_readers_updated, 246, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__50)) __PYX_ERR(0, 246, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_codeobj__51 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__17, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__51)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_codeobj__52 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__25, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__52)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_RefNannyFinishContext(); + return -1; +} +/* #### Code section: init_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitConstants(void) { + if (__Pyx_CreateStringTabAndInitStrings() < 0) __PYX_ERR(0, 1, __pyx_L1_error); + __pyx_int_1 = PyInt_FromLong(1); if (unlikely(!__pyx_int_1)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_neg_1 = PyInt_FromLong(-1); if (unlikely(!__pyx_int_neg_1)) __PYX_ERR(0, 1, __pyx_L1_error) + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: init_globals ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitGlobals(void) { + return 0; +} +/* #### Code section: init_module ### */ + +static CYTHON_SMALL_CODE int __Pyx_modinit_global_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_import_code(void); /*proto*/ + +static int __Pyx_modinit_global_init_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_global_init_code", 0); + /*--- Global init code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_variable_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_export_code", 0); + /*--- Variable export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_export_code", 0); + /*--- Function export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_type_init_code(void) { + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_modinit_type_init_code", 0); + /*--- Type init code ---*/ + __pyx_vtabptr_6cereal_9messaging_13messaging_pyx_Event = &__pyx_vtable_6cereal_9messaging_13messaging_pyx_Event; + __pyx_vtable_6cereal_9messaging_13messaging_pyx_Event.setEvent = (PyObject *(*)(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_Event *, Event))__pyx_f_6cereal_9messaging_13messaging_pyx_5Event_setEvent; + #if CYTHON_USE_TYPE_SPECS + __pyx_ptype_6cereal_9messaging_13messaging_pyx_Event = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_6cereal_9messaging_13messaging_pyx_Event_spec, NULL); if (unlikely(!__pyx_ptype_6cereal_9messaging_13messaging_pyx_Event)) __PYX_ERR(0, 55, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_6cereal_9messaging_13messaging_pyx_Event_spec, __pyx_ptype_6cereal_9messaging_13messaging_pyx_Event) < 0) __PYX_ERR(0, 55, __pyx_L1_error) + #else + __pyx_ptype_6cereal_9messaging_13messaging_pyx_Event = &__pyx_type_6cereal_9messaging_13messaging_pyx_Event; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_6cereal_9messaging_13messaging_pyx_Event) < 0) __PYX_ERR(0, 55, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_6cereal_9messaging_13messaging_pyx_Event->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_6cereal_9messaging_13messaging_pyx_Event->tp_dictoffset && __pyx_ptype_6cereal_9messaging_13messaging_pyx_Event->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_6cereal_9messaging_13messaging_pyx_Event->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (__Pyx_SetVtable(__pyx_ptype_6cereal_9messaging_13messaging_pyx_Event, __pyx_vtabptr_6cereal_9messaging_13messaging_pyx_Event) < 0) __PYX_ERR(0, 55, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_ptype_6cereal_9messaging_13messaging_pyx_Event) < 0) __PYX_ERR(0, 55, __pyx_L1_error) + #endif + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_Event, (PyObject *) __pyx_ptype_6cereal_9messaging_13messaging_pyx_Event) < 0) __PYX_ERR(0, 55, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_6cereal_9messaging_13messaging_pyx_Event) < 0) __PYX_ERR(0, 55, __pyx_L1_error) + #endif + #if CYTHON_USE_TYPE_SPECS + __pyx_ptype_6cereal_9messaging_13messaging_pyx_SocketEventHandle = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_6cereal_9messaging_13messaging_pyx_SocketEventHandle_spec, NULL); if (unlikely(!__pyx_ptype_6cereal_9messaging_13messaging_pyx_SocketEventHandle)) __PYX_ERR(0, 85, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_6cereal_9messaging_13messaging_pyx_SocketEventHandle_spec, __pyx_ptype_6cereal_9messaging_13messaging_pyx_SocketEventHandle) < 0) __PYX_ERR(0, 85, __pyx_L1_error) + #else + __pyx_ptype_6cereal_9messaging_13messaging_pyx_SocketEventHandle = &__pyx_type_6cereal_9messaging_13messaging_pyx_SocketEventHandle; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_6cereal_9messaging_13messaging_pyx_SocketEventHandle) < 0) __PYX_ERR(0, 85, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_6cereal_9messaging_13messaging_pyx_SocketEventHandle->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_6cereal_9messaging_13messaging_pyx_SocketEventHandle->tp_dictoffset && __pyx_ptype_6cereal_9messaging_13messaging_pyx_SocketEventHandle->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_6cereal_9messaging_13messaging_pyx_SocketEventHandle->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_SocketEventHandle, (PyObject *) __pyx_ptype_6cereal_9messaging_13messaging_pyx_SocketEventHandle) < 0) __PYX_ERR(0, 85, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_6cereal_9messaging_13messaging_pyx_SocketEventHandle) < 0) __PYX_ERR(0, 85, __pyx_L1_error) + #endif + #if CYTHON_USE_TYPE_SPECS + __pyx_ptype_6cereal_9messaging_13messaging_pyx_Context = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_6cereal_9messaging_13messaging_pyx_Context_spec, NULL); if (unlikely(!__pyx_ptype_6cereal_9messaging_13messaging_pyx_Context)) __PYX_ERR(0, 117, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_6cereal_9messaging_13messaging_pyx_Context_spec, __pyx_ptype_6cereal_9messaging_13messaging_pyx_Context) < 0) __PYX_ERR(0, 117, __pyx_L1_error) + #else + __pyx_ptype_6cereal_9messaging_13messaging_pyx_Context = &__pyx_type_6cereal_9messaging_13messaging_pyx_Context; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_6cereal_9messaging_13messaging_pyx_Context) < 0) __PYX_ERR(0, 117, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_6cereal_9messaging_13messaging_pyx_Context->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_6cereal_9messaging_13messaging_pyx_Context->tp_dictoffset && __pyx_ptype_6cereal_9messaging_13messaging_pyx_Context->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_6cereal_9messaging_13messaging_pyx_Context->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_Context, (PyObject *) __pyx_ptype_6cereal_9messaging_13messaging_pyx_Context) < 0) __PYX_ERR(0, 117, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_6cereal_9messaging_13messaging_pyx_Context) < 0) __PYX_ERR(0, 117, __pyx_L1_error) + #endif + #if CYTHON_USE_TYPE_SPECS + __pyx_ptype_6cereal_9messaging_13messaging_pyx_Poller = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_6cereal_9messaging_13messaging_pyx_Poller_spec, NULL); if (unlikely(!__pyx_ptype_6cereal_9messaging_13messaging_pyx_Poller)) __PYX_ERR(0, 134, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_6cereal_9messaging_13messaging_pyx_Poller_spec, __pyx_ptype_6cereal_9messaging_13messaging_pyx_Poller) < 0) __PYX_ERR(0, 134, __pyx_L1_error) + #else + __pyx_ptype_6cereal_9messaging_13messaging_pyx_Poller = &__pyx_type_6cereal_9messaging_13messaging_pyx_Poller; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_6cereal_9messaging_13messaging_pyx_Poller) < 0) __PYX_ERR(0, 134, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_6cereal_9messaging_13messaging_pyx_Poller->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_6cereal_9messaging_13messaging_pyx_Poller->tp_dictoffset && __pyx_ptype_6cereal_9messaging_13messaging_pyx_Poller->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_6cereal_9messaging_13messaging_pyx_Poller->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_Poller, (PyObject *) __pyx_ptype_6cereal_9messaging_13messaging_pyx_Poller) < 0) __PYX_ERR(0, 134, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_6cereal_9messaging_13messaging_pyx_Poller) < 0) __PYX_ERR(0, 134, __pyx_L1_error) + #endif + __pyx_vtabptr_6cereal_9messaging_13messaging_pyx_SubSocket = &__pyx_vtable_6cereal_9messaging_13messaging_pyx_SubSocket; + __pyx_vtable_6cereal_9messaging_13messaging_pyx_SubSocket.setPtr = (PyObject *(*)(struct __pyx_obj_6cereal_9messaging_13messaging_pyx_SubSocket *, SubSocket *))__pyx_f_6cereal_9messaging_13messaging_pyx_9SubSocket_setPtr; + #if CYTHON_USE_TYPE_SPECS + __pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_6cereal_9messaging_13messaging_pyx_SubSocket_spec, NULL); if (unlikely(!__pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket)) __PYX_ERR(0, 164, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_6cereal_9messaging_13messaging_pyx_SubSocket_spec, __pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket) < 0) __PYX_ERR(0, 164, __pyx_L1_error) + #else + __pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket = &__pyx_type_6cereal_9messaging_13messaging_pyx_SubSocket; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket) < 0) __PYX_ERR(0, 164, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket->tp_dictoffset && __pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (__Pyx_SetVtable(__pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket, __pyx_vtabptr_6cereal_9messaging_13messaging_pyx_SubSocket) < 0) __PYX_ERR(0, 164, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket) < 0) __PYX_ERR(0, 164, __pyx_L1_error) + #endif + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_SubSocket, (PyObject *) __pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket) < 0) __PYX_ERR(0, 164, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket) < 0) __PYX_ERR(0, 164, __pyx_L1_error) + #endif + #if CYTHON_USE_TYPE_SPECS + __pyx_ptype_6cereal_9messaging_13messaging_pyx_PubSocket = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_6cereal_9messaging_13messaging_pyx_PubSocket_spec, NULL); if (unlikely(!__pyx_ptype_6cereal_9messaging_13messaging_pyx_PubSocket)) __PYX_ERR(0, 216, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_6cereal_9messaging_13messaging_pyx_PubSocket_spec, __pyx_ptype_6cereal_9messaging_13messaging_pyx_PubSocket) < 0) __PYX_ERR(0, 216, __pyx_L1_error) + #else + __pyx_ptype_6cereal_9messaging_13messaging_pyx_PubSocket = &__pyx_type_6cereal_9messaging_13messaging_pyx_PubSocket; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_6cereal_9messaging_13messaging_pyx_PubSocket) < 0) __PYX_ERR(0, 216, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_6cereal_9messaging_13messaging_pyx_PubSocket->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_6cereal_9messaging_13messaging_pyx_PubSocket->tp_dictoffset && __pyx_ptype_6cereal_9messaging_13messaging_pyx_PubSocket->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_6cereal_9messaging_13messaging_pyx_PubSocket->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_PubSocket, (PyObject *) __pyx_ptype_6cereal_9messaging_13messaging_pyx_PubSocket) < 0) __PYX_ERR(0, 216, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_6cereal_9messaging_13messaging_pyx_PubSocket) < 0) __PYX_ERR(0, 216, __pyx_L1_error) + #endif + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_RefNannyFinishContext(); + return -1; +} + +static int __Pyx_modinit_type_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_type_import_code", 0); + /*--- Type import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_variable_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_import_code", 0); + /*--- Variable import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_import_code", 0); + /*--- Function import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + + +#if PY_MAJOR_VERSION >= 3 +#if CYTHON_PEP489_MULTI_PHASE_INIT +static PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def); /*proto*/ +static int __pyx_pymod_exec_messaging_pyx(PyObject* module); /*proto*/ +static PyModuleDef_Slot __pyx_moduledef_slots[] = { + {Py_mod_create, (void*)__pyx_pymod_create}, + {Py_mod_exec, (void*)__pyx_pymod_exec_messaging_pyx}, + {0, NULL} +}; +#endif + +#ifdef __cplusplus +namespace { + struct PyModuleDef __pyx_moduledef = + #else + static struct PyModuleDef __pyx_moduledef = + #endif + { + PyModuleDef_HEAD_INIT, + "messaging_pyx", + 0, /* m_doc */ + #if CYTHON_PEP489_MULTI_PHASE_INIT + 0, /* m_size */ + #elif CYTHON_USE_MODULE_STATE + sizeof(__pyx_mstate), /* m_size */ + #else + -1, /* m_size */ + #endif + __pyx_methods /* m_methods */, + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_moduledef_slots, /* m_slots */ + #else + NULL, /* m_reload */ + #endif + #if CYTHON_USE_MODULE_STATE + __pyx_m_traverse, /* m_traverse */ + __pyx_m_clear, /* m_clear */ + NULL /* m_free */ + #else + NULL, /* m_traverse */ + NULL, /* m_clear */ + NULL /* m_free */ + #endif + }; + #ifdef __cplusplus +} /* anonymous namespace */ +#endif +#endif + +#ifndef CYTHON_NO_PYINIT_EXPORT +#define __Pyx_PyMODINIT_FUNC PyMODINIT_FUNC +#elif PY_MAJOR_VERSION < 3 +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" void +#else +#define __Pyx_PyMODINIT_FUNC void +#endif +#else +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" PyObject * +#else +#define __Pyx_PyMODINIT_FUNC PyObject * +#endif +#endif + + +#if PY_MAJOR_VERSION < 3 +__Pyx_PyMODINIT_FUNC initmessaging_pyx(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC initmessaging_pyx(void) +#else +__Pyx_PyMODINIT_FUNC PyInit_messaging_pyx(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC PyInit_messaging_pyx(void) +#if CYTHON_PEP489_MULTI_PHASE_INIT +{ + return PyModuleDef_Init(&__pyx_moduledef); +} +static CYTHON_SMALL_CODE int __Pyx_check_single_interpreter(void) { + #if PY_VERSION_HEX >= 0x030700A1 + static PY_INT64_T main_interpreter_id = -1; + PY_INT64_T current_id = PyInterpreterState_GetID(PyThreadState_Get()->interp); + if (main_interpreter_id == -1) { + main_interpreter_id = current_id; + return (unlikely(current_id == -1)) ? -1 : 0; + } else if (unlikely(main_interpreter_id != current_id)) + #else + static PyInterpreterState *main_interpreter = NULL; + PyInterpreterState *current_interpreter = PyThreadState_Get()->interp; + if (!main_interpreter) { + main_interpreter = current_interpreter; + } else if (unlikely(main_interpreter != current_interpreter)) + #endif + { + PyErr_SetString( + PyExc_ImportError, + "Interpreter change detected - this module can only be loaded into one interpreter per process."); + return -1; + } + return 0; +} +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *module, const char* from_name, const char* to_name, int allow_none) +#else +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *moddict, const char* from_name, const char* to_name, int allow_none) +#endif +{ + PyObject *value = PyObject_GetAttrString(spec, from_name); + int result = 0; + if (likely(value)) { + if (allow_none || value != Py_None) { +#if CYTHON_COMPILING_IN_LIMITED_API + result = PyModule_AddObject(module, to_name, value); +#else + result = PyDict_SetItemString(moddict, to_name, value); +#endif + } + Py_DECREF(value); + } else if (PyErr_ExceptionMatches(PyExc_AttributeError)) { + PyErr_Clear(); + } else { + result = -1; + } + return result; +} +static CYTHON_SMALL_CODE PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def) { + PyObject *module = NULL, *moddict, *modname; + CYTHON_UNUSED_VAR(def); + if (__Pyx_check_single_interpreter()) + return NULL; + if (__pyx_m) + return __Pyx_NewRef(__pyx_m); + modname = PyObject_GetAttrString(spec, "name"); + if (unlikely(!modname)) goto bad; + module = PyModule_NewObject(modname); + Py_DECREF(modname); + if (unlikely(!module)) goto bad; +#if CYTHON_COMPILING_IN_LIMITED_API + moddict = module; +#else + moddict = PyModule_GetDict(module); + if (unlikely(!moddict)) goto bad; +#endif + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "loader", "__loader__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "origin", "__file__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "parent", "__package__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "submodule_search_locations", "__path__", 0) < 0)) goto bad; + return module; +bad: + Py_XDECREF(module); + return NULL; +} + + +static CYTHON_SMALL_CODE int __pyx_pymod_exec_messaging_pyx(PyObject *__pyx_pyinit_module) +#endif +#endif +{ + int stringtab_initialized = 0; + #if CYTHON_USE_MODULE_STATE + int pystate_addmodule_run = 0; + #endif + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + std::string __pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannyDeclarations + #if CYTHON_PEP489_MULTI_PHASE_INIT + if (__pyx_m) { + if (__pyx_m == __pyx_pyinit_module) return 0; + PyErr_SetString(PyExc_RuntimeError, "Module 'messaging_pyx' has already been imported. Re-initialisation is not supported."); + return -1; + } + #elif PY_MAJOR_VERSION >= 3 + if (__pyx_m) return __Pyx_NewRef(__pyx_m); + #endif + /*--- Module creation code ---*/ + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_m = __pyx_pyinit_module; + Py_INCREF(__pyx_m); + #else + #if PY_MAJOR_VERSION < 3 + __pyx_m = Py_InitModule4("messaging_pyx", __pyx_methods, 0, 0, PYTHON_API_VERSION); Py_XINCREF(__pyx_m); + if (unlikely(!__pyx_m)) __PYX_ERR(0, 1, __pyx_L1_error) + #elif CYTHON_USE_MODULE_STATE + __pyx_t_1 = PyModule_Create(&__pyx_moduledef); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 1, __pyx_L1_error) + { + int add_module_result = PyState_AddModule(__pyx_t_1, &__pyx_moduledef); + __pyx_t_1 = 0; /* transfer ownership from __pyx_t_1 to "messaging_pyx" pseudovariable */ + if (unlikely((add_module_result < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + pystate_addmodule_run = 1; + } + #else + __pyx_m = PyModule_Create(&__pyx_moduledef); + if (unlikely(!__pyx_m)) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #endif + CYTHON_UNUSED_VAR(__pyx_t_1); + __pyx_d = PyModule_GetDict(__pyx_m); if (unlikely(!__pyx_d)) __PYX_ERR(0, 1, __pyx_L1_error) + Py_INCREF(__pyx_d); + __pyx_b = __Pyx_PyImport_AddModuleRef(__Pyx_BUILTIN_MODULE_NAME); if (unlikely(!__pyx_b)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_cython_runtime = __Pyx_PyImport_AddModuleRef((const char *) "cython_runtime"); if (unlikely(!__pyx_cython_runtime)) __PYX_ERR(0, 1, __pyx_L1_error) + if (PyObject_SetAttrString(__pyx_m, "__builtins__", __pyx_b) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #if CYTHON_REFNANNY +__Pyx_RefNanny = __Pyx_RefNannyImportAPI("refnanny"); +if (!__Pyx_RefNanny) { + PyErr_Clear(); + __Pyx_RefNanny = __Pyx_RefNannyImportAPI("Cython.Runtime.refnanny"); + if (!__Pyx_RefNanny) + Py_FatalError("failed to import 'refnanny' module"); +} +#endif + __Pyx_RefNannySetupContext("__Pyx_PyMODINIT_FUNC PyInit_messaging_pyx(void)", 0); + if (__Pyx_check_binary_version(__PYX_LIMITED_VERSION_HEX, __Pyx_get_runtime_version(), CYTHON_COMPILING_IN_LIMITED_API) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #ifdef __Pxy_PyFrame_Initialize_Offsets + __Pxy_PyFrame_Initialize_Offsets(); + #endif + __pyx_empty_tuple = PyTuple_New(0); if (unlikely(!__pyx_empty_tuple)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_empty_bytes = PyBytes_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_bytes)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_empty_unicode = PyUnicode_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_unicode)) __PYX_ERR(0, 1, __pyx_L1_error) + #ifdef __Pyx_CyFunction_USED + if (__pyx_CyFunction_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_FusedFunction_USED + if (__pyx_FusedFunction_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Coroutine_USED + if (__pyx_Coroutine_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Generator_USED + if (__pyx_Generator_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_AsyncGen_USED + if (__pyx_AsyncGen_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_StopAsyncIteration_USED + if (__pyx_StopAsyncIteration_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + /*--- Library function declarations ---*/ + /*--- Threads initialization code ---*/ + #if defined(WITH_THREAD) && PY_VERSION_HEX < 0x030700F0 && defined(__PYX_FORCE_INIT_THREADS) && __PYX_FORCE_INIT_THREADS + PyEval_InitThreads(); + #endif + /*--- Initialize various global constants etc. ---*/ + if (__Pyx_InitConstants() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + stringtab_initialized = 1; + if (__Pyx_InitGlobals() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #if PY_MAJOR_VERSION < 3 && (__PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT) + if (__Pyx_init_sys_getdefaultencoding_params() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + if (__pyx_module_is_main_cereal__messaging__messaging_pyx) { + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_name, __pyx_n_s_main) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + } + #if PY_MAJOR_VERSION >= 3 + { + PyObject *modules = PyImport_GetModuleDict(); if (unlikely(!modules)) __PYX_ERR(0, 1, __pyx_L1_error) + if (!PyDict_GetItemString(modules, "cereal.messaging.messaging_pyx")) { + if (unlikely((PyDict_SetItemString(modules, "cereal.messaging.messaging_pyx", __pyx_m) < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + } + } + #endif + /*--- Builtin init code ---*/ + if (__Pyx_InitCachedBuiltins() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + /*--- Constants init code ---*/ + if (__Pyx_InitCachedConstants() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + /*--- Global type/function init code ---*/ + (void)__Pyx_modinit_global_init_code(); + (void)__Pyx_modinit_variable_export_code(); + (void)__Pyx_modinit_function_export_code(); + if (unlikely((__Pyx_modinit_type_init_code() < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + (void)__Pyx_modinit_type_import_code(); + (void)__Pyx_modinit_variable_import_code(); + (void)__Pyx_modinit_function_import_code(); + /*--- Execution code ---*/ + #if defined(__Pyx_Generator_USED) || defined(__Pyx_Coroutine_USED) + if (__Pyx_patch_abc() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + + /* "cereal/messaging/messaging_pyx.pyx":4 + * # cython: c_string_encoding=ascii, language_level=3 + * + * import sys # <<<<<<<<<<<<<< + * from libcpp.string cimport string + * from libcpp.vector cimport vector + */ + __pyx_t_2 = __Pyx_ImportDottedModule(__pyx_n_s_sys, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 4, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_sys, __pyx_t_2) < 0) __PYX_ERR(0, 4, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":21 + * + * + * class MessagingError(Exception): # <<<<<<<<<<<<<< + * def __init__(self, endpoint=None): + * suffix = f"with {endpoint.decode('utf-8')}" if endpoint else "" + */ + __pyx_t_2 = PyTuple_New(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 21, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_INCREF((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])); + __Pyx_GIVEREF((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_2, 0, ((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])))) __PYX_ERR(0, 21, __pyx_L1_error); + __pyx_t_3 = __Pyx_PEP560_update_bases(__pyx_t_2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 21, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = __Pyx_CalculateMetaclass(NULL, __pyx_t_3); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 21, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_Py3MetaclassPrepare(__pyx_t_4, __pyx_t_3, __pyx_n_s_MessagingError, __pyx_n_s_MessagingError, (PyObject *) NULL, __pyx_n_s_cereal_messaging_messaging_pyx, (PyObject *) NULL); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 21, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + if (__pyx_t_3 != __pyx_t_2) { + if (unlikely((PyDict_SetItemString(__pyx_t_5, "__orig_bases__", __pyx_t_2) < 0))) __PYX_ERR(0, 21, __pyx_L1_error) + } + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = PyList_New(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 21, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + + /* "cereal/messaging/messaging_pyx.pyx":22 + * + * class MessagingError(Exception): + * def __init__(self, endpoint=None): # <<<<<<<<<<<<<< + * suffix = f"with {endpoint.decode('utf-8')}" if endpoint else "" + * message = f"Messaging failure {suffix}: {strerror(errno.errno).decode('utf-8')}" + */ + __pyx_t_6 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_14MessagingError_1__init__, 0, __pyx_n_s_MessagingError___init, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__7)); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 22, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_INCREF(__pyx_t_6); + PyList_Append(__pyx_t_2, __pyx_t_6); + __Pyx_GIVEREF(__pyx_t_6); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_6, __pyx_tuple__8); + if (__Pyx_SetNameInClass(__pyx_t_5, __pyx_n_s_init, __pyx_t_6) < 0) __PYX_ERR(0, 22, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":21 + * + * + * class MessagingError(Exception): # <<<<<<<<<<<<<< + * def __init__(self, endpoint=None): + * suffix = f"with {endpoint.decode('utf-8')}" if endpoint else "" + */ + __pyx_t_6 = __Pyx_Py3ClassCreate(__pyx_t_4, __pyx_n_s_MessagingError, __pyx_t_3, __pyx_t_5, NULL, 0, 0); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 21, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (__Pyx_CyFunction_InitClassCell(__pyx_t_2, __pyx_t_6) < 0) __PYX_ERR(0, 21, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + if (PyDict_SetItem(__pyx_d, __pyx_n_s_MessagingError, __pyx_t_6) < 0) __PYX_ERR(0, 21, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":28 + * + * + * class MultiplePublishersError(MessagingError): # <<<<<<<<<<<<<< + * pass + * + */ + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_MessagingError); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 28, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PyTuple_New(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 28, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_3)) __PYX_ERR(0, 28, __pyx_L1_error); + __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PEP560_update_bases(__pyx_t_4); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 28, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = __Pyx_CalculateMetaclass(NULL, __pyx_t_3); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 28, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = __Pyx_Py3MetaclassPrepare(__pyx_t_5, __pyx_t_3, __pyx_n_s_MultiplePublishersError, __pyx_n_s_MultiplePublishersError, (PyObject *) NULL, __pyx_n_s_cereal_messaging_messaging_pyx, (PyObject *) NULL); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 28, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (__pyx_t_3 != __pyx_t_4) { + if (unlikely((PyDict_SetItemString(__pyx_t_6, "__orig_bases__", __pyx_t_4) < 0))) __PYX_ERR(0, 28, __pyx_L1_error) + } + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_Py3ClassCreate(__pyx_t_5, __pyx_n_s_MultiplePublishersError, __pyx_t_3, __pyx_t_6, NULL, 0, 0); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 28, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_MultiplePublishersError, __pyx_t_4) < 0) __PYX_ERR(0, 28, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":32 + * + * + * def toggle_fake_events(bool enabled): # <<<<<<<<<<<<<< + * cppSocketEventHandle.toggle_fake_events(enabled) + * + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_1toggle_fake_events, 0, __pyx_n_s_toggle_fake_events, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__10)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 32, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_toggle_fake_events, __pyx_t_3) < 0) __PYX_ERR(0, 32, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":36 + * + * + * def set_fake_prefix(string prefix): # <<<<<<<<<<<<<< + * cppSocketEventHandle.set_fake_prefix(prefix) + * + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_3set_fake_prefix, 0, __pyx_n_s_set_fake_prefix, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__12)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 36, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_set_fake_prefix, __pyx_t_3) < 0) __PYX_ERR(0, 36, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":40 + * + * + * def get_fake_prefix(): # <<<<<<<<<<<<<< + * return cppSocketEventHandle.fake_prefix() + * + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_5get_fake_prefix, 0, __pyx_n_s_get_fake_prefix, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__13)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_get_fake_prefix, __pyx_t_3) < 0) __PYX_ERR(0, 40, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":44 + * + * + * def delete_fake_prefix(): # <<<<<<<<<<<<<< + * cppSocketEventHandle.set_fake_prefix(b"") + * + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_7delete_fake_prefix, 0, __pyx_n_s_delete_fake_prefix, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__14)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 44, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_delete_fake_prefix, __pyx_t_3) < 0) __PYX_ERR(0, 44, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":48 + * + * + * def wait_for_one_event(list events, int timeout=-1): # <<<<<<<<<<<<<< + * cdef vector[cppEvent] items + * for event in events: + */ + __pyx_t_3 = __Pyx_PyInt_From_int(((int)-1)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 48, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = PyTuple_New(1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 48, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_t_3)) __PYX_ERR(0, 48, __pyx_L1_error); + __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_9wait_for_one_event, 0, __pyx_n_s_wait_for_one_event, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__16)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 48, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_3, __pyx_t_5); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (PyDict_SetItem(__pyx_d, __pyx_n_s_wait_for_one_event, __pyx_t_3) < 0) __PYX_ERR(0, 48, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":64 + * self.event = event + * + * def set(self): # <<<<<<<<<<<<<< + * self.event.set() + * + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_5Event_3set, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Event_set, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__18)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 64, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6cereal_9messaging_13messaging_pyx_Event, __pyx_n_s_set, __pyx_t_3) < 0) __PYX_ERR(0, 64, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + PyType_Modified(__pyx_ptype_6cereal_9messaging_13messaging_pyx_Event); + + /* "cereal/messaging/messaging_pyx.pyx":67 + * self.event.set() + * + * def clear(self): # <<<<<<<<<<<<<< + * return self.event.clear() + * + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_5Event_5clear, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Event_clear, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__19)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 67, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6cereal_9messaging_13messaging_pyx_Event, __pyx_n_s_clear, __pyx_t_3) < 0) __PYX_ERR(0, 67, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + PyType_Modified(__pyx_ptype_6cereal_9messaging_13messaging_pyx_Event); + + /* "cereal/messaging/messaging_pyx.pyx":70 + * return self.event.clear() + * + * def wait(self, int timeout=-1): # <<<<<<<<<<<<<< + * self.event.wait(timeout) + * + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_5Event_7wait, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Event_wait, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__21)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 70, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_3, __pyx_tuple__22); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6cereal_9messaging_13messaging_pyx_Event, __pyx_n_s_wait, __pyx_t_3) < 0) __PYX_ERR(0, 70, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + PyType_Modified(__pyx_ptype_6cereal_9messaging_13messaging_pyx_Event); + + /* "cereal/messaging/messaging_pyx.pyx":73 + * self.event.wait(timeout) + * + * def peek(self): # <<<<<<<<<<<<<< + * return self.event.peek() + * + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_5Event_9peek, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Event_peek, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__23)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 73, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6cereal_9messaging_13messaging_pyx_Event, __pyx_n_s_peek, __pyx_t_3) < 0) __PYX_ERR(0, 73, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + PyType_Modified(__pyx_ptype_6cereal_9messaging_13messaging_pyx_Event); + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_5Event_11__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Event___reduce_cython, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__24)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_3) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_5Event_13__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Event___setstate_cython, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__26)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_3) < 0) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_5__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_SocketEventHandle___reduce_cytho, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__27)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_3) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_17SocketEventHandle_7__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_SocketEventHandle___setstate_cyt, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__28)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_3) < 0) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":123 + * self.context = cppContext.create() + * + * def term(self): # <<<<<<<<<<<<<< + * del self.context + * self.context = NULL + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_7Context_3term, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Context_term, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__29)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 123, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6cereal_9messaging_13messaging_pyx_Context, __pyx_n_s_term, __pyx_t_3) < 0) __PYX_ERR(0, 123, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + PyType_Modified(__pyx_ptype_6cereal_9messaging_13messaging_pyx_Context); + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_7Context_7__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Context___reduce_cython, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__30)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_3) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_7Context_9__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Context___setstate_cython, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__31)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_3) < 0) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":145 + * del self.poller + * + * def registerSocket(self, SubSocket socket): # <<<<<<<<<<<<<< + * self.sub_sockets.append(socket) + * self.poller.registerSocket(socket.socket) + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_6Poller_5registerSocket, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Poller_registerSocket, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__33)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 145, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6cereal_9messaging_13messaging_pyx_Poller, __pyx_n_s_registerSocket, __pyx_t_3) < 0) __PYX_ERR(0, 145, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + PyType_Modified(__pyx_ptype_6cereal_9messaging_13messaging_pyx_Poller); + + /* "cereal/messaging/messaging_pyx.pyx":149 + * self.poller.registerSocket(socket.socket) + * + * def poll(self, timeout): # <<<<<<<<<<<<<< + * sockets = [] + * cdef int t = timeout + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_6Poller_7poll, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Poller_poll, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__35)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 149, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6cereal_9messaging_13messaging_pyx_Poller, __pyx_n_s_poll, __pyx_t_3) < 0) __PYX_ERR(0, 149, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + PyType_Modified(__pyx_ptype_6cereal_9messaging_13messaging_pyx_Poller); + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_6Poller_9__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Poller___reduce_cython, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__36)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_3) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_6Poller_11__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Poller___setstate_cython, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__37)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_3) < 0) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":186 + * self.socket = ptr + * + * def connect(self, Context context, string endpoint, string address=b"127.0.0.1", bool conflate=False): # <<<<<<<<<<<<<< + * r = self.socket.connect(context.context, endpoint, address, conflate) + * + */ + __pyx_t_7 = __pyx_convert_string_from_py_std__in_string(__pyx_kp_b_127_0_0_1); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 186, __pyx_L1_error) + __pyx_k__3 = __pyx_t_7; + __pyx_t_7 = __pyx_convert_string_from_py_std__in_string(__pyx_kp_b_127_0_0_1); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 186, __pyx_L1_error) + __pyx_t_3 = __pyx_convert_PyBytes_string_to_py_std__in_string(__pyx_t_7); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 186, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = PyTuple_New(2); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 186, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_t_3)) __PYX_ERR(0, 186, __pyx_L1_error); + __Pyx_INCREF(Py_False); + __Pyx_GIVEREF(Py_False); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_5, 1, Py_False)) __PYX_ERR(0, 186, __pyx_L1_error); + __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_9SubSocket_5connect, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_SubSocket_connect, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__39)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 186, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_3, __pyx_t_5); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket, __pyx_n_s_connect, __pyx_t_3) < 0) __PYX_ERR(0, 186, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + PyType_Modified(__pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket); + + /* "cereal/messaging/messaging_pyx.pyx":195 + * raise MessagingError(endpoint) + * + * def setTimeout(self, int timeout): # <<<<<<<<<<<<<< + * self.socket.setTimeout(timeout) + * + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_9SubSocket_7setTimeout, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_SubSocket_setTimeout, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__40)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 195, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket, __pyx_n_s_setTimeout, __pyx_t_3) < 0) __PYX_ERR(0, 195, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + PyType_Modified(__pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket); + + /* "cereal/messaging/messaging_pyx.pyx":198 + * self.socket.setTimeout(timeout) + * + * def receive(self, bool non_blocking=False): # <<<<<<<<<<<<<< + * msg = self.socket.receive(non_blocking) + * + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_9SubSocket_9receive, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_SubSocket_receive, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__42)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 198, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_3, __pyx_tuple__43); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket, __pyx_n_s_receive, __pyx_t_3) < 0) __PYX_ERR(0, 198, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + PyType_Modified(__pyx_ptype_6cereal_9messaging_13messaging_pyx_SubSocket); + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_9SubSocket_11__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_SubSocket___reduce_cython, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__44)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_3) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_9SubSocket_13__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_SubSocket___setstate_cython, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__45)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_3) < 0) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":227 + * del self.socket + * + * def connect(self, Context context, string endpoint): # <<<<<<<<<<<<<< + * r = self.socket.connect(context.context, endpoint) + * + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_9PubSocket_5connect, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_PubSocket_connect, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__47)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 227, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6cereal_9messaging_13messaging_pyx_PubSocket, __pyx_n_s_connect, __pyx_t_3) < 0) __PYX_ERR(0, 227, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + PyType_Modified(__pyx_ptype_6cereal_9messaging_13messaging_pyx_PubSocket); + + /* "cereal/messaging/messaging_pyx.pyx":236 + * raise MessagingError(endpoint) + * + * def send(self, bytes data): # <<<<<<<<<<<<<< + * length = len(data) + * r = self.socket.send(data, length) + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_9PubSocket_7send, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_PubSocket_send, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__49)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 236, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6cereal_9messaging_13messaging_pyx_PubSocket, __pyx_n_s_send, __pyx_t_3) < 0) __PYX_ERR(0, 236, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + PyType_Modified(__pyx_ptype_6cereal_9messaging_13messaging_pyx_PubSocket); + + /* "cereal/messaging/messaging_pyx.pyx":246 + * raise MessagingError + * + * def all_readers_updated(self): # <<<<<<<<<<<<<< + * return self.socket.all_readers_updated() + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_9PubSocket_9all_readers_updated, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_PubSocket_all_readers_updated, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__50)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 246, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6cereal_9messaging_13messaging_pyx_PubSocket, __pyx_n_s_all_readers_updated, __pyx_t_3) < 0) __PYX_ERR(0, 246, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + PyType_Modified(__pyx_ptype_6cereal_9messaging_13messaging_pyx_PubSocket); + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_9PubSocket_11__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_PubSocket___reduce_cython, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__51)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_3) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9messaging_13messaging_pyx_9PubSocket_13__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_PubSocket___setstate_cython, NULL, __pyx_n_s_cereal_messaging_messaging_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__52)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_3) < 0) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "cereal/messaging/messaging_pyx.pyx":1 + * # distutils: language = c++ # <<<<<<<<<<<<<< + * # cython: c_string_encoding=ascii, language_level=3 + * + */ + __pyx_t_3 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_test, __pyx_t_3) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /*--- Wrapped vars code ---*/ + + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + if (__pyx_m) { + if (__pyx_d && stringtab_initialized) { + __Pyx_AddTraceback("init cereal.messaging.messaging_pyx", __pyx_clineno, __pyx_lineno, __pyx_filename); + } + #if !CYTHON_USE_MODULE_STATE + Py_CLEAR(__pyx_m); + #else + Py_DECREF(__pyx_m); + if (pystate_addmodule_run) { + PyObject *tp, *value, *tb; + PyErr_Fetch(&tp, &value, &tb); + PyState_RemoveModule(&__pyx_moduledef); + PyErr_Restore(tp, value, tb); + } + #endif + } else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_ImportError, "init cereal.messaging.messaging_pyx"); + } + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + #if CYTHON_PEP489_MULTI_PHASE_INIT + return (__pyx_m != NULL) ? 0 : -1; + #elif PY_MAJOR_VERSION >= 3 + return __pyx_m; + #else + return; + #endif +} +/* #### Code section: cleanup_globals ### */ +/* #### Code section: cleanup_module ### */ +/* #### Code section: main_method ### */ +/* #### Code section: utility_code_pragmas ### */ +#ifdef _MSC_VER +#pragma warning( push ) +/* Warning 4127: conditional expression is constant + * Cython uses constant conditional expressions to allow in inline functions to be optimized at + * compile-time, so this warning is not useful + */ +#pragma warning( disable : 4127 ) +#endif + + + +/* #### Code section: utility_code_def ### */ + +/* --- Runtime support code --- */ +/* Refnanny */ +#if CYTHON_REFNANNY +static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname) { + PyObject *m = NULL, *p = NULL; + void *r = NULL; + m = PyImport_ImportModule(modname); + if (!m) goto end; + p = PyObject_GetAttrString(m, "RefNannyAPI"); + if (!p) goto end; + r = PyLong_AsVoidPtr(p); +end: + Py_XDECREF(p); + Py_XDECREF(m); + return (__Pyx_RefNannyAPIStruct *)r; +} +#endif + +/* PyErrExceptionMatches */ +#if CYTHON_FAST_THREAD_STATE +static int __Pyx_PyErr_ExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; i= 0x030C00A6 + PyObject *current_exception = tstate->current_exception; + if (unlikely(!current_exception)) return 0; + exc_type = (PyObject*) Py_TYPE(current_exception); + if (exc_type == err) return 1; +#else + exc_type = tstate->curexc_type; + if (exc_type == err) return 1; + if (unlikely(!exc_type)) return 0; +#endif + #if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(exc_type); + #endif + if (unlikely(PyTuple_Check(err))) { + result = __Pyx_PyErr_ExceptionMatchesTuple(exc_type, err); + } else { + result = __Pyx_PyErr_GivenExceptionMatches(exc_type, err); + } + #if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(exc_type); + #endif + return result; +} +#endif + +/* PyErrFetchRestore */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject *tmp_value; + assert(type == NULL || (value != NULL && type == (PyObject*) Py_TYPE(value))); + if (value) { + #if CYTHON_COMPILING_IN_CPYTHON + if (unlikely(((PyBaseExceptionObject*) value)->traceback != tb)) + #endif + PyException_SetTraceback(value, tb); + } + tmp_value = tstate->current_exception; + tstate->current_exception = value; + Py_XDECREF(tmp_value); + Py_XDECREF(type); + Py_XDECREF(tb); +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + tmp_type = tstate->curexc_type; + tmp_value = tstate->curexc_value; + tmp_tb = tstate->curexc_traceback; + tstate->curexc_type = type; + tstate->curexc_value = value; + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); +#endif +} +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject* exc_value; + exc_value = tstate->current_exception; + tstate->current_exception = 0; + *value = exc_value; + *type = NULL; + *tb = NULL; + if (exc_value) { + *type = (PyObject*) Py_TYPE(exc_value); + Py_INCREF(*type); + #if CYTHON_COMPILING_IN_CPYTHON + *tb = ((PyBaseExceptionObject*) exc_value)->traceback; + Py_XINCREF(*tb); + #else + *tb = PyException_GetTraceback(exc_value); + #endif + } +#else + *type = tstate->curexc_type; + *value = tstate->curexc_value; + *tb = tstate->curexc_traceback; + tstate->curexc_type = 0; + tstate->curexc_value = 0; + tstate->curexc_traceback = 0; +#endif +} +#endif + +/* PyObjectGetAttrStr */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name) { + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro)) + return tp->tp_getattro(obj, attr_name); +#if PY_MAJOR_VERSION < 3 + if (likely(tp->tp_getattr)) + return tp->tp_getattr(obj, PyString_AS_STRING(attr_name)); +#endif + return PyObject_GetAttr(obj, attr_name); +} +#endif + +/* PyObjectGetAttrStrNoError */ +#if __PYX_LIMITED_VERSION_HEX < 0x030d00A1 +static void __Pyx_PyObject_GetAttrStr_ClearAttributeError(void) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + if (likely(__Pyx_PyErr_ExceptionMatches(PyExc_AttributeError))) + __Pyx_PyErr_Clear(); +} +#endif +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name) { + PyObject *result; +#if __PYX_LIMITED_VERSION_HEX >= 0x030d00A1 + (void) PyObject_GetOptionalAttr(obj, attr_name, &result); + return result; +#else +#if CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_TYPE_SLOTS && PY_VERSION_HEX >= 0x030700B1 + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro == PyObject_GenericGetAttr)) { + return _PyObject_GenericGetAttrWithDict(obj, attr_name, NULL, 1); + } +#endif + result = __Pyx_PyObject_GetAttrStr(obj, attr_name); + if (unlikely(!result)) { + __Pyx_PyObject_GetAttrStr_ClearAttributeError(); + } + return result; +#endif +} + +/* GetBuiltinName */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name) { + PyObject* result = __Pyx_PyObject_GetAttrStrNoError(__pyx_b, name); + if (unlikely(!result) && !PyErr_Occurred()) { + PyErr_Format(PyExc_NameError, +#if PY_MAJOR_VERSION >= 3 + "name '%U' is not defined", name); +#else + "name '%.200s' is not defined", PyString_AS_STRING(name)); +#endif + } + return result; +} + +/* TupleAndListFromArray */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE void __Pyx_copy_object_array(PyObject *const *CYTHON_RESTRICT src, PyObject** CYTHON_RESTRICT dest, Py_ssize_t length) { + PyObject *v; + Py_ssize_t i; + for (i = 0; i < length; i++) { + v = dest[i] = src[i]; + Py_INCREF(v); + } +} +static CYTHON_INLINE PyObject * +__Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + Py_INCREF(__pyx_empty_tuple); + return __pyx_empty_tuple; + } + res = PyTuple_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyTupleObject*)res)->ob_item, n); + return res; +} +static CYTHON_INLINE PyObject * +__Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + return PyList_New(0); + } + res = PyList_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyListObject*)res)->ob_item, n); + return res; +} +#endif + +/* BytesEquals */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else + if (s1 == s2) { + return (equals == Py_EQ); + } else if (PyBytes_CheckExact(s1) & PyBytes_CheckExact(s2)) { + const char *ps1, *ps2; + Py_ssize_t length = PyBytes_GET_SIZE(s1); + if (length != PyBytes_GET_SIZE(s2)) + return (equals == Py_NE); + ps1 = PyBytes_AS_STRING(s1); + ps2 = PyBytes_AS_STRING(s2); + if (ps1[0] != ps2[0]) { + return (equals == Py_NE); + } else if (length == 1) { + return (equals == Py_EQ); + } else { + int result; +#if CYTHON_USE_UNICODE_INTERNALS && (PY_VERSION_HEX < 0x030B0000) + Py_hash_t hash1, hash2; + hash1 = ((PyBytesObject*)s1)->ob_shash; + hash2 = ((PyBytesObject*)s2)->ob_shash; + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + return (equals == Py_NE); + } +#endif + result = memcmp(ps1, ps2, (size_t)length); + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & PyBytes_CheckExact(s2)) { + return (equals == Py_NE); + } else if ((s2 == Py_None) & PyBytes_CheckExact(s1)) { + return (equals == Py_NE); + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +#endif +} + +/* UnicodeEquals */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else +#if PY_MAJOR_VERSION < 3 + PyObject* owned_ref = NULL; +#endif + int s1_is_unicode, s2_is_unicode; + if (s1 == s2) { + goto return_eq; + } + s1_is_unicode = PyUnicode_CheckExact(s1); + s2_is_unicode = PyUnicode_CheckExact(s2); +#if PY_MAJOR_VERSION < 3 + if ((s1_is_unicode & (!s2_is_unicode)) && PyString_CheckExact(s2)) { + owned_ref = PyUnicode_FromObject(s2); + if (unlikely(!owned_ref)) + return -1; + s2 = owned_ref; + s2_is_unicode = 1; + } else if ((s2_is_unicode & (!s1_is_unicode)) && PyString_CheckExact(s1)) { + owned_ref = PyUnicode_FromObject(s1); + if (unlikely(!owned_ref)) + return -1; + s1 = owned_ref; + s1_is_unicode = 1; + } else if (((!s2_is_unicode) & (!s1_is_unicode))) { + return __Pyx_PyBytes_Equals(s1, s2, equals); + } +#endif + if (s1_is_unicode & s2_is_unicode) { + Py_ssize_t length; + int kind; + void *data1, *data2; + if (unlikely(__Pyx_PyUnicode_READY(s1) < 0) || unlikely(__Pyx_PyUnicode_READY(s2) < 0)) + return -1; + length = __Pyx_PyUnicode_GET_LENGTH(s1); + if (length != __Pyx_PyUnicode_GET_LENGTH(s2)) { + goto return_ne; + } +#if CYTHON_USE_UNICODE_INTERNALS + { + Py_hash_t hash1, hash2; + #if CYTHON_PEP393_ENABLED + hash1 = ((PyASCIIObject*)s1)->hash; + hash2 = ((PyASCIIObject*)s2)->hash; + #else + hash1 = ((PyUnicodeObject*)s1)->hash; + hash2 = ((PyUnicodeObject*)s2)->hash; + #endif + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + goto return_ne; + } + } +#endif + kind = __Pyx_PyUnicode_KIND(s1); + if (kind != __Pyx_PyUnicode_KIND(s2)) { + goto return_ne; + } + data1 = __Pyx_PyUnicode_DATA(s1); + data2 = __Pyx_PyUnicode_DATA(s2); + if (__Pyx_PyUnicode_READ(kind, data1, 0) != __Pyx_PyUnicode_READ(kind, data2, 0)) { + goto return_ne; + } else if (length == 1) { + goto return_eq; + } else { + int result = memcmp(data1, data2, (size_t)(length * kind)); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & s2_is_unicode) { + goto return_ne; + } else if ((s2 == Py_None) & s1_is_unicode) { + goto return_ne; + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +return_eq: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ); +return_ne: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_NE); +#endif +} + +/* fastcall */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s) +{ + Py_ssize_t i, n = PyTuple_GET_SIZE(kwnames); + for (i = 0; i < n; i++) + { + if (s == PyTuple_GET_ITEM(kwnames, i)) return kwvalues[i]; + } + for (i = 0; i < n; i++) + { + int eq = __Pyx_PyUnicode_Equals(s, PyTuple_GET_ITEM(kwnames, i), Py_EQ); + if (unlikely(eq != 0)) { + if (unlikely(eq < 0)) return NULL; + return kwvalues[i]; + } + } + return NULL; +} +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 +CYTHON_UNUSED static PyObject *__Pyx_KwargsAsDict_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues) { + Py_ssize_t i, nkwargs = PyTuple_GET_SIZE(kwnames); + PyObject *dict; + dict = PyDict_New(); + if (unlikely(!dict)) + return NULL; + for (i=0; i= 3 + "%s() got multiple values for keyword argument '%U'", func_name, kw_name); + #else + "%s() got multiple values for keyword argument '%s'", func_name, + PyString_AsString(kw_name)); + #endif +} + +/* ParseKeywords */ +static int __Pyx_ParseOptionalKeywords( + PyObject *kwds, + PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, + PyObject *values[], + Py_ssize_t num_pos_args, + const char* function_name) +{ + PyObject *key = 0, *value = 0; + Py_ssize_t pos = 0; + PyObject*** name; + PyObject*** first_kw_arg = argnames + num_pos_args; + int kwds_is_tuple = CYTHON_METH_FASTCALL && likely(PyTuple_Check(kwds)); + while (1) { + Py_XDECREF(key); key = NULL; + Py_XDECREF(value); value = NULL; + if (kwds_is_tuple) { + Py_ssize_t size; +#if CYTHON_ASSUME_SAFE_MACROS + size = PyTuple_GET_SIZE(kwds); +#else + size = PyTuple_Size(kwds); + if (size < 0) goto bad; +#endif + if (pos >= size) break; +#if CYTHON_AVOID_BORROWED_REFS + key = __Pyx_PySequence_ITEM(kwds, pos); + if (!key) goto bad; +#elif CYTHON_ASSUME_SAFE_MACROS + key = PyTuple_GET_ITEM(kwds, pos); +#else + key = PyTuple_GetItem(kwds, pos); + if (!key) goto bad; +#endif + value = kwvalues[pos]; + pos++; + } + else + { + if (!PyDict_Next(kwds, &pos, &key, &value)) break; +#if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(key); +#endif + } + name = first_kw_arg; + while (*name && (**name != key)) name++; + if (*name) { + values[name-argnames] = value; +#if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(value); + Py_DECREF(key); +#endif + key = NULL; + value = NULL; + continue; + } +#if !CYTHON_AVOID_BORROWED_REFS + Py_INCREF(key); +#endif + Py_INCREF(value); + name = first_kw_arg; + #if PY_MAJOR_VERSION < 3 + if (likely(PyString_Check(key))) { + while (*name) { + if ((CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**name) == PyString_GET_SIZE(key)) + && _PyString_Eq(**name, key)) { + values[name-argnames] = value; +#if CYTHON_AVOID_BORROWED_REFS + value = NULL; +#endif + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + if ((**argname == key) || ( + (CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**argname) == PyString_GET_SIZE(key)) + && _PyString_Eq(**argname, key))) { + goto arg_passed_twice; + } + argname++; + } + } + } else + #endif + if (likely(PyUnicode_Check(key))) { + while (*name) { + int cmp = ( + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**name) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**name, key) + ); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) { + values[name-argnames] = value; +#if CYTHON_AVOID_BORROWED_REFS + value = NULL; +#endif + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + int cmp = (**argname == key) ? 0 : + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**argname) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**argname, key); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) goto arg_passed_twice; + argname++; + } + } + } else + goto invalid_keyword_type; + if (kwds2) { + if (unlikely(PyDict_SetItem(kwds2, key, value))) goto bad; + } else { + goto invalid_keyword; + } + } + Py_XDECREF(key); + Py_XDECREF(value); + return 0; +arg_passed_twice: + __Pyx_RaiseDoubleKeywordsError(function_name, key); + goto bad; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + goto bad; +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif +bad: + Py_XDECREF(key); + Py_XDECREF(value); + return -1; +} + +/* RaiseArgTupleInvalid */ +static void __Pyx_RaiseArgtupleInvalid( + const char* func_name, + int exact, + Py_ssize_t num_min, + Py_ssize_t num_max, + Py_ssize_t num_found) +{ + Py_ssize_t num_expected; + const char *more_or_less; + if (num_found < num_min) { + num_expected = num_min; + more_or_less = "at least"; + } else { + num_expected = num_max; + more_or_less = "at most"; + } + if (exact) { + more_or_less = "exactly"; + } + PyErr_Format(PyExc_TypeError, + "%.200s() takes %.8s %" CYTHON_FORMAT_SSIZE_T "d positional argument%.1s (%" CYTHON_FORMAT_SSIZE_T "d given)", + func_name, more_or_less, num_expected, + (num_expected == 1) ? "" : "s", num_found); +} + +/* PyFunctionFastCall */ +#if CYTHON_FAST_PYCALL && !CYTHON_VECTORCALL +static PyObject* __Pyx_PyFunction_FastCallNoKw(PyCodeObject *co, PyObject **args, Py_ssize_t na, + PyObject *globals) { + PyFrameObject *f; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject **fastlocals; + Py_ssize_t i; + PyObject *result; + assert(globals != NULL); + /* XXX Perhaps we should create a specialized + PyFrame_New() that doesn't take locals, but does + take builtins without sanity checking them. + */ + assert(tstate != NULL); + f = PyFrame_New(tstate, co, globals, NULL); + if (f == NULL) { + return NULL; + } + fastlocals = __Pyx_PyFrame_GetLocalsplus(f); + for (i = 0; i < na; i++) { + Py_INCREF(*args); + fastlocals[i] = *args++; + } + result = PyEval_EvalFrameEx(f,0); + ++tstate->recursion_depth; + Py_DECREF(f); + --tstate->recursion_depth; + return result; +} +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs) { + PyCodeObject *co = (PyCodeObject *)PyFunction_GET_CODE(func); + PyObject *globals = PyFunction_GET_GLOBALS(func); + PyObject *argdefs = PyFunction_GET_DEFAULTS(func); + PyObject *closure; +#if PY_MAJOR_VERSION >= 3 + PyObject *kwdefs; +#endif + PyObject *kwtuple, **k; + PyObject **d; + Py_ssize_t nd; + Py_ssize_t nk; + PyObject *result; + assert(kwargs == NULL || PyDict_Check(kwargs)); + nk = kwargs ? PyDict_Size(kwargs) : 0; + #if PY_MAJOR_VERSION < 3 + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) { + return NULL; + } + #else + if (unlikely(Py_EnterRecursiveCall(" while calling a Python object"))) { + return NULL; + } + #endif + if ( +#if PY_MAJOR_VERSION >= 3 + co->co_kwonlyargcount == 0 && +#endif + likely(kwargs == NULL || nk == 0) && + co->co_flags == (CO_OPTIMIZED | CO_NEWLOCALS | CO_NOFREE)) { + if (argdefs == NULL && co->co_argcount == nargs) { + result = __Pyx_PyFunction_FastCallNoKw(co, args, nargs, globals); + goto done; + } + else if (nargs == 0 && argdefs != NULL + && co->co_argcount == Py_SIZE(argdefs)) { + /* function called with no arguments, but all parameters have + a default value: use default values as arguments .*/ + args = &PyTuple_GET_ITEM(argdefs, 0); + result =__Pyx_PyFunction_FastCallNoKw(co, args, Py_SIZE(argdefs), globals); + goto done; + } + } + if (kwargs != NULL) { + Py_ssize_t pos, i; + kwtuple = PyTuple_New(2 * nk); + if (kwtuple == NULL) { + result = NULL; + goto done; + } + k = &PyTuple_GET_ITEM(kwtuple, 0); + pos = i = 0; + while (PyDict_Next(kwargs, &pos, &k[i], &k[i+1])) { + Py_INCREF(k[i]); + Py_INCREF(k[i+1]); + i += 2; + } + nk = i / 2; + } + else { + kwtuple = NULL; + k = NULL; + } + closure = PyFunction_GET_CLOSURE(func); +#if PY_MAJOR_VERSION >= 3 + kwdefs = PyFunction_GET_KW_DEFAULTS(func); +#endif + if (argdefs != NULL) { + d = &PyTuple_GET_ITEM(argdefs, 0); + nd = Py_SIZE(argdefs); + } + else { + d = NULL; + nd = 0; + } +#if PY_MAJOR_VERSION >= 3 + result = PyEval_EvalCodeEx((PyObject*)co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, kwdefs, closure); +#else + result = PyEval_EvalCodeEx(co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, closure); +#endif + Py_XDECREF(kwtuple); +done: + Py_LeaveRecursiveCall(); + return result; +} +#endif + +/* PyObjectCall */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw) { + PyObject *result; + ternaryfunc call = Py_TYPE(func)->tp_call; + if (unlikely(!call)) + return PyObject_Call(func, arg, kw); + #if PY_MAJOR_VERSION < 3 + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + #else + if (unlikely(Py_EnterRecursiveCall(" while calling a Python object"))) + return NULL; + #endif + result = (*call)(func, arg, kw); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* PyObjectCallMethO */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg) { + PyObject *self, *result; + PyCFunction cfunc; + cfunc = __Pyx_CyOrPyCFunction_GET_FUNCTION(func); + self = __Pyx_CyOrPyCFunction_GET_SELF(func); + #if PY_MAJOR_VERSION < 3 + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + #else + if (unlikely(Py_EnterRecursiveCall(" while calling a Python object"))) + return NULL; + #endif + result = cfunc(self, arg); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* PyObjectFastCall */ +#if PY_VERSION_HEX < 0x03090000 || CYTHON_COMPILING_IN_LIMITED_API +static PyObject* __Pyx_PyObject_FastCall_fallback(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs) { + PyObject *argstuple; + PyObject *result = 0; + size_t i; + argstuple = PyTuple_New((Py_ssize_t)nargs); + if (unlikely(!argstuple)) return NULL; + for (i = 0; i < nargs; i++) { + Py_INCREF(args[i]); + if (__Pyx_PyTuple_SET_ITEM(argstuple, (Py_ssize_t)i, args[i]) < 0) goto bad; + } + result = __Pyx_PyObject_Call(func, argstuple, kwargs); + bad: + Py_DECREF(argstuple); + return result; +} +#endif +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t _nargs, PyObject *kwargs) { + Py_ssize_t nargs = __Pyx_PyVectorcall_NARGS(_nargs); +#if CYTHON_COMPILING_IN_CPYTHON + if (nargs == 0 && kwargs == NULL) { + if (__Pyx_CyOrPyCFunction_Check(func) && likely( __Pyx_CyOrPyCFunction_GET_FLAGS(func) & METH_NOARGS)) + return __Pyx_PyObject_CallMethO(func, NULL); + } + else if (nargs == 1 && kwargs == NULL) { + if (__Pyx_CyOrPyCFunction_Check(func) && likely( __Pyx_CyOrPyCFunction_GET_FLAGS(func) & METH_O)) + return __Pyx_PyObject_CallMethO(func, args[0]); + } +#endif + #if PY_VERSION_HEX < 0x030800B1 + #if CYTHON_FAST_PYCCALL + if (PyCFunction_Check(func)) { + if (kwargs) { + return _PyCFunction_FastCallDict(func, args, nargs, kwargs); + } else { + return _PyCFunction_FastCallKeywords(func, args, nargs, NULL); + } + } + #if PY_VERSION_HEX >= 0x030700A1 + if (!kwargs && __Pyx_IS_TYPE(func, &PyMethodDescr_Type)) { + return _PyMethodDescr_FastCallKeywords(func, args, nargs, NULL); + } + #endif + #endif + #if CYTHON_FAST_PYCALL + if (PyFunction_Check(func)) { + return __Pyx_PyFunction_FastCallDict(func, args, nargs, kwargs); + } + #endif + #endif + if (kwargs == NULL) { + #if CYTHON_VECTORCALL + #if PY_VERSION_HEX < 0x03090000 + vectorcallfunc f = _PyVectorcall_Function(func); + #else + vectorcallfunc f = PyVectorcall_Function(func); + #endif + if (f) { + return f(func, args, (size_t)nargs, NULL); + } + #elif defined(__Pyx_CyFunction_USED) && CYTHON_BACKPORT_VECTORCALL + if (__Pyx_CyFunction_CheckExact(func)) { + __pyx_vectorcallfunc f = __Pyx_CyFunction_func_vectorcall(func); + if (f) return f(func, args, (size_t)nargs, NULL); + } + #endif + } + if (nargs == 0) { + return __Pyx_PyObject_Call(func, __pyx_empty_tuple, kwargs); + } + #if PY_VERSION_HEX >= 0x03090000 && !CYTHON_COMPILING_IN_LIMITED_API + return PyObject_VectorcallDict(func, args, (size_t)nargs, kwargs); + #else + return __Pyx_PyObject_FastCall_fallback(func, args, (size_t)nargs, kwargs); + #endif +} + +/* PyUnicode_Unicode */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_Unicode(PyObject *obj) { + if (unlikely(obj == Py_None)) + obj = __pyx_kp_u_None; + return __Pyx_NewRef(obj); +} + +/* decode_c_string */ +static CYTHON_INLINE PyObject* __Pyx_decode_c_string( + const char* cstring, Py_ssize_t start, Py_ssize_t stop, + const char* encoding, const char* errors, + PyObject* (*decode_func)(const char *s, Py_ssize_t size, const char *errors)) { + Py_ssize_t length; + if (unlikely((start < 0) | (stop < 0))) { + size_t slen = strlen(cstring); + if (unlikely(slen > (size_t) PY_SSIZE_T_MAX)) { + PyErr_SetString(PyExc_OverflowError, + "c-string too long to convert to Python"); + return NULL; + } + length = (Py_ssize_t) slen; + if (start < 0) { + start += length; + if (start < 0) + start = 0; + } + if (stop < 0) + stop += length; + } + if (unlikely(stop <= start)) + return __Pyx_NewRef(__pyx_empty_unicode); + length = stop - start; + cstring += start; + if (decode_func) { + return decode_func(cstring, length, errors); + } else { + return PyUnicode_Decode(cstring, length, encoding, errors); + } +} + +/* JoinPyUnicode */ +static PyObject* __Pyx_PyUnicode_Join(PyObject* value_tuple, Py_ssize_t value_count, Py_ssize_t result_ulength, + Py_UCS4 max_char) { +#if CYTHON_USE_UNICODE_INTERNALS && CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + PyObject *result_uval; + int result_ukind, kind_shift; + Py_ssize_t i, char_pos; + void *result_udata; + CYTHON_MAYBE_UNUSED_VAR(max_char); +#if CYTHON_PEP393_ENABLED + result_uval = PyUnicode_New(result_ulength, max_char); + if (unlikely(!result_uval)) return NULL; + result_ukind = (max_char <= 255) ? PyUnicode_1BYTE_KIND : (max_char <= 65535) ? PyUnicode_2BYTE_KIND : PyUnicode_4BYTE_KIND; + kind_shift = (result_ukind == PyUnicode_4BYTE_KIND) ? 2 : result_ukind - 1; + result_udata = PyUnicode_DATA(result_uval); +#else + result_uval = PyUnicode_FromUnicode(NULL, result_ulength); + if (unlikely(!result_uval)) return NULL; + result_ukind = sizeof(Py_UNICODE); + kind_shift = (result_ukind == 4) ? 2 : result_ukind - 1; + result_udata = PyUnicode_AS_UNICODE(result_uval); +#endif + assert(kind_shift == 2 || kind_shift == 1 || kind_shift == 0); + char_pos = 0; + for (i=0; i < value_count; i++) { + int ukind; + Py_ssize_t ulength; + void *udata; + PyObject *uval = PyTuple_GET_ITEM(value_tuple, i); + if (unlikely(__Pyx_PyUnicode_READY(uval))) + goto bad; + ulength = __Pyx_PyUnicode_GET_LENGTH(uval); + if (unlikely(!ulength)) + continue; + if (unlikely((PY_SSIZE_T_MAX >> kind_shift) - ulength < char_pos)) + goto overflow; + ukind = __Pyx_PyUnicode_KIND(uval); + udata = __Pyx_PyUnicode_DATA(uval); + if (!CYTHON_PEP393_ENABLED || ukind == result_ukind) { + memcpy((char *)result_udata + (char_pos << kind_shift), udata, (size_t) (ulength << kind_shift)); + } else { + #if PY_VERSION_HEX >= 0x030d0000 + if (unlikely(PyUnicode_CopyCharacters(result_uval, char_pos, uval, 0, ulength) < 0)) goto bad; + #elif CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030300F0 || defined(_PyUnicode_FastCopyCharacters) + _PyUnicode_FastCopyCharacters(result_uval, char_pos, uval, 0, ulength); + #else + Py_ssize_t j; + for (j=0; j < ulength; j++) { + Py_UCS4 uchar = __Pyx_PyUnicode_READ(ukind, udata, j); + __Pyx_PyUnicode_WRITE(result_ukind, result_udata, char_pos+j, uchar); + } + #endif + } + char_pos += ulength; + } + return result_uval; +overflow: + PyErr_SetString(PyExc_OverflowError, "join() result is too long for a Python string"); +bad: + Py_DECREF(result_uval); + return NULL; +#else + CYTHON_UNUSED_VAR(max_char); + CYTHON_UNUSED_VAR(result_ulength); + CYTHON_UNUSED_VAR(value_count); + return PyUnicode_Join(__pyx_empty_unicode, value_tuple); +#endif +} + +/* ArgTypeTest */ +static int __Pyx__ArgTypeTest(PyObject *obj, PyTypeObject *type, const char *name, int exact) +{ + __Pyx_TypeName type_name; + __Pyx_TypeName obj_type_name; + if (unlikely(!type)) { + PyErr_SetString(PyExc_SystemError, "Missing type object"); + return 0; + } + else if (exact) { + #if PY_MAJOR_VERSION == 2 + if ((type == &PyBaseString_Type) && likely(__Pyx_PyBaseString_CheckExact(obj))) return 1; + #endif + } + else { + if (likely(__Pyx_TypeCheck(obj, type))) return 1; + } + type_name = __Pyx_PyType_GetName(type); + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "Argument '%.200s' has incorrect type (expected " __Pyx_FMT_TYPENAME + ", got " __Pyx_FMT_TYPENAME ")", name, type_name, obj_type_name); + __Pyx_DECREF_TypeName(type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return 0; +} + +/* KeywordStringCheck */ +static int __Pyx_CheckKeywordStrings( + PyObject *kw, + const char* function_name, + int kw_allowed) +{ + PyObject* key = 0; + Py_ssize_t pos = 0; +#if CYTHON_COMPILING_IN_PYPY + if (!kw_allowed && PyDict_Next(kw, &pos, &key, 0)) + goto invalid_keyword; + return 1; +#else + if (CYTHON_METH_FASTCALL && likely(PyTuple_Check(kw))) { + Py_ssize_t kwsize; +#if CYTHON_ASSUME_SAFE_MACROS + kwsize = PyTuple_GET_SIZE(kw); +#else + kwsize = PyTuple_Size(kw); + if (kwsize < 0) return 0; +#endif + if (unlikely(kwsize == 0)) + return 1; + if (!kw_allowed) { +#if CYTHON_ASSUME_SAFE_MACROS + key = PyTuple_GET_ITEM(kw, 0); +#else + key = PyTuple_GetItem(kw, pos); + if (!key) return 0; +#endif + goto invalid_keyword; + } +#if PY_VERSION_HEX < 0x03090000 + for (pos = 0; pos < kwsize; pos++) { +#if CYTHON_ASSUME_SAFE_MACROS + key = PyTuple_GET_ITEM(kw, pos); +#else + key = PyTuple_GetItem(kw, pos); + if (!key) return 0; +#endif + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } +#endif + return 1; + } + while (PyDict_Next(kw, &pos, &key, 0)) { + #if PY_MAJOR_VERSION < 3 + if (unlikely(!PyString_Check(key))) + #endif + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } + if (!kw_allowed && unlikely(key)) + goto invalid_keyword; + return 1; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + return 0; +#endif +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif + return 0; +} + +/* RaiseException */ +#if PY_MAJOR_VERSION < 3 +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + __Pyx_PyThreadState_declare + CYTHON_UNUSED_VAR(cause); + Py_XINCREF(type); + if (!value || value == Py_None) + value = NULL; + else + Py_INCREF(value); + if (!tb || tb == Py_None) + tb = NULL; + else { + Py_INCREF(tb); + if (!PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto raise_error; + } + } + if (PyType_Check(type)) { +#if CYTHON_COMPILING_IN_PYPY + if (!value) { + Py_INCREF(Py_None); + value = Py_None; + } +#endif + PyErr_NormalizeException(&type, &value, &tb); + } else { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto raise_error; + } + value = type; + type = (PyObject*) Py_TYPE(type); + Py_INCREF(type); + if (!PyType_IsSubtype((PyTypeObject *)type, (PyTypeObject *)PyExc_BaseException)) { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto raise_error; + } + } + __Pyx_PyThreadState_assign + __Pyx_ErrRestore(type, value, tb); + return; +raise_error: + Py_XDECREF(value); + Py_XDECREF(type); + Py_XDECREF(tb); + return; +} +#else +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + PyObject* owned_instance = NULL; + if (tb == Py_None) { + tb = 0; + } else if (tb && !PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto bad; + } + if (value == Py_None) + value = 0; + if (PyExceptionInstance_Check(type)) { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto bad; + } + value = type; + type = (PyObject*) Py_TYPE(value); + } else if (PyExceptionClass_Check(type)) { + PyObject *instance_class = NULL; + if (value && PyExceptionInstance_Check(value)) { + instance_class = (PyObject*) Py_TYPE(value); + if (instance_class != type) { + int is_subclass = PyObject_IsSubclass(instance_class, type); + if (!is_subclass) { + instance_class = NULL; + } else if (unlikely(is_subclass == -1)) { + goto bad; + } else { + type = instance_class; + } + } + } + if (!instance_class) { + PyObject *args; + if (!value) + args = PyTuple_New(0); + else if (PyTuple_Check(value)) { + Py_INCREF(value); + args = value; + } else + args = PyTuple_Pack(1, value); + if (!args) + goto bad; + owned_instance = PyObject_Call(type, args, NULL); + Py_DECREF(args); + if (!owned_instance) + goto bad; + value = owned_instance; + if (!PyExceptionInstance_Check(value)) { + PyErr_Format(PyExc_TypeError, + "calling %R should have returned an instance of " + "BaseException, not %R", + type, Py_TYPE(value)); + goto bad; + } + } + } else { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto bad; + } + if (cause) { + PyObject *fixed_cause; + if (cause == Py_None) { + fixed_cause = NULL; + } else if (PyExceptionClass_Check(cause)) { + fixed_cause = PyObject_CallObject(cause, NULL); + if (fixed_cause == NULL) + goto bad; + } else if (PyExceptionInstance_Check(cause)) { + fixed_cause = cause; + Py_INCREF(fixed_cause); + } else { + PyErr_SetString(PyExc_TypeError, + "exception causes must derive from " + "BaseException"); + goto bad; + } + PyException_SetCause(value, fixed_cause); + } + PyErr_SetObject(type, value); + if (tb) { + #if PY_VERSION_HEX >= 0x030C00A6 + PyException_SetTraceback(value, tb); + #elif CYTHON_FAST_THREAD_STATE + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject* tmp_tb = tstate->curexc_traceback; + if (tb != tmp_tb) { + Py_INCREF(tb); + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_tb); + } +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + PyErr_Fetch(&tmp_type, &tmp_value, &tmp_tb); + Py_INCREF(tb); + PyErr_Restore(tmp_type, tmp_value, tb); + Py_XDECREF(tmp_tb); +#endif + } +bad: + Py_XDECREF(owned_instance); + return; +} +#endif + +/* PyObjectCallNoArg */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func) { + PyObject *arg[2] = {NULL, NULL}; + return __Pyx_PyObject_FastCall(func, arg + 1, 0 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* PyDictVersioning */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + return likely(dict) ? __PYX_GET_DICT_VERSION(dict) : 0; +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj) { + PyObject **dictptr = NULL; + Py_ssize_t offset = Py_TYPE(obj)->tp_dictoffset; + if (offset) { +#if CYTHON_COMPILING_IN_CPYTHON + dictptr = (likely(offset > 0)) ? (PyObject **) ((char *)obj + offset) : _PyObject_GetDictPtr(obj); +#else + dictptr = _PyObject_GetDictPtr(obj); +#endif + } + return (dictptr && *dictptr) ? __PYX_GET_DICT_VERSION(*dictptr) : 0; +} +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + if (unlikely(!dict) || unlikely(tp_dict_version != __PYX_GET_DICT_VERSION(dict))) + return 0; + return obj_dict_version == __Pyx_get_object_dict_version(obj); +} +#endif + +/* GetModuleGlobalName */ +#if CYTHON_USE_DICT_VERSIONS +static PyObject *__Pyx__GetModuleGlobalName(PyObject *name, PY_UINT64_T *dict_version, PyObject **dict_cached_value) +#else +static CYTHON_INLINE PyObject *__Pyx__GetModuleGlobalName(PyObject *name) +#endif +{ + PyObject *result; +#if !CYTHON_AVOID_BORROWED_REFS +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030500A1 && PY_VERSION_HEX < 0x030d0000 + result = _PyDict_GetItem_KnownHash(__pyx_d, name, ((PyASCIIObject *) name)->hash); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } else if (unlikely(PyErr_Occurred())) { + return NULL; + } +#elif CYTHON_COMPILING_IN_LIMITED_API + if (unlikely(!__pyx_m)) { + return NULL; + } + result = PyObject_GetAttr(__pyx_m, name); + if (likely(result)) { + return result; + } +#else + result = PyDict_GetItem(__pyx_d, name); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } +#endif +#else + result = PyObject_GetItem(__pyx_d, name); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } + PyErr_Clear(); +#endif + return __Pyx_GetBuiltinName(name); +} + +/* FixUpExtensionType */ +#if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type) { +#if PY_VERSION_HEX > 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + CYTHON_UNUSED_VAR(spec); + CYTHON_UNUSED_VAR(type); +#else + const PyType_Slot *slot = spec->slots; + while (slot && slot->slot && slot->slot != Py_tp_members) + slot++; + if (slot && slot->slot == Py_tp_members) { + int changed = 0; +#if !(PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON) + const +#endif + PyMemberDef *memb = (PyMemberDef*) slot->pfunc; + while (memb && memb->name) { + if (memb->name[0] == '_' && memb->name[1] == '_') { +#if PY_VERSION_HEX < 0x030900b1 + if (strcmp(memb->name, "__weaklistoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_weaklistoffset = memb->offset; + changed = 1; + } + else if (strcmp(memb->name, "__dictoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_dictoffset = memb->offset; + changed = 1; + } +#if CYTHON_METH_FASTCALL + else if (strcmp(memb->name, "__vectorcalloffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); +#if PY_VERSION_HEX >= 0x030800b4 + type->tp_vectorcall_offset = memb->offset; +#else + type->tp_print = (printfunc) memb->offset; +#endif + changed = 1; + } +#endif +#else + if ((0)); +#endif +#if PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON + else if (strcmp(memb->name, "__module__") == 0) { + PyObject *descr; + assert(memb->type == T_OBJECT); + assert(memb->flags == 0 || memb->flags == READONLY); + descr = PyDescr_NewMember(type, memb); + if (unlikely(!descr)) + return -1; + if (unlikely(PyDict_SetItem(type->tp_dict, PyDescr_NAME(descr), descr) < 0)) { + Py_DECREF(descr); + return -1; + } + Py_DECREF(descr); + changed = 1; + } +#endif + } + memb++; + } + if (changed) + PyType_Modified(type); + } +#endif + return 0; +} +#endif + +/* PyObjectCallOneArg */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg) { + PyObject *args[2] = {NULL, arg}; + return __Pyx_PyObject_FastCall(func, args+1, 1 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* PyObjectGetMethod */ +static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method) { + PyObject *attr; +#if CYTHON_UNPACK_METHODS && CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_PYTYPE_LOOKUP + __Pyx_TypeName type_name; + PyTypeObject *tp = Py_TYPE(obj); + PyObject *descr; + descrgetfunc f = NULL; + PyObject **dictptr, *dict; + int meth_found = 0; + assert (*method == NULL); + if (unlikely(tp->tp_getattro != PyObject_GenericGetAttr)) { + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; + } + if (unlikely(tp->tp_dict == NULL) && unlikely(PyType_Ready(tp) < 0)) { + return 0; + } + descr = _PyType_Lookup(tp, name); + if (likely(descr != NULL)) { + Py_INCREF(descr); +#if defined(Py_TPFLAGS_METHOD_DESCRIPTOR) && Py_TPFLAGS_METHOD_DESCRIPTOR + if (__Pyx_PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_METHOD_DESCRIPTOR)) +#elif PY_MAJOR_VERSION >= 3 + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type))) + #endif +#else + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr))) + #endif +#endif + { + meth_found = 1; + } else { + f = Py_TYPE(descr)->tp_descr_get; + if (f != NULL && PyDescr_IsData(descr)) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + } + } + dictptr = _PyObject_GetDictPtr(obj); + if (dictptr != NULL && (dict = *dictptr) != NULL) { + Py_INCREF(dict); + attr = __Pyx_PyDict_GetItemStr(dict, name); + if (attr != NULL) { + Py_INCREF(attr); + Py_DECREF(dict); + Py_XDECREF(descr); + goto try_unpack; + } + Py_DECREF(dict); + } + if (meth_found) { + *method = descr; + return 1; + } + if (f != NULL) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + if (likely(descr != NULL)) { + *method = descr; + return 0; + } + type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return 0; +#else + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; +#endif +try_unpack: +#if CYTHON_UNPACK_METHODS + if (likely(attr) && PyMethod_Check(attr) && likely(PyMethod_GET_SELF(attr) == obj)) { + PyObject *function = PyMethod_GET_FUNCTION(attr); + Py_INCREF(function); + Py_DECREF(attr); + *method = function; + return 1; + } +#endif + *method = attr; + return 0; +} + +/* PyObjectCallMethod0 */ +static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name) { + PyObject *method = NULL, *result = NULL; + int is_method = __Pyx_PyObject_GetMethod(obj, method_name, &method); + if (likely(is_method)) { + result = __Pyx_PyObject_CallOneArg(method, obj); + Py_DECREF(method); + return result; + } + if (unlikely(!method)) goto bad; + result = __Pyx_PyObject_CallNoArg(method); + Py_DECREF(method); +bad: + return result; +} + +/* ValidateBasesTuple */ +#if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases) { + Py_ssize_t i, n; +#if CYTHON_ASSUME_SAFE_MACROS + n = PyTuple_GET_SIZE(bases); +#else + n = PyTuple_Size(bases); + if (n < 0) return -1; +#endif + for (i = 1; i < n; i++) + { +#if CYTHON_AVOID_BORROWED_REFS + PyObject *b0 = PySequence_GetItem(bases, i); + if (!b0) return -1; +#elif CYTHON_ASSUME_SAFE_MACROS + PyObject *b0 = PyTuple_GET_ITEM(bases, i); +#else + PyObject *b0 = PyTuple_GetItem(bases, i); + if (!b0) return -1; +#endif + PyTypeObject *b; +#if PY_MAJOR_VERSION < 3 + if (PyClass_Check(b0)) + { + PyErr_Format(PyExc_TypeError, "base class '%.200s' is an old-style class", + PyString_AS_STRING(((PyClassObject*)b0)->cl_name)); +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + return -1; + } +#endif + b = (PyTypeObject*) b0; + if (!__Pyx_PyType_HasFeature(b, Py_TPFLAGS_HEAPTYPE)) + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "base class '" __Pyx_FMT_TYPENAME "' is not a heap type", b_name); + __Pyx_DECREF_TypeName(b_name); +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + return -1; + } + if (dictoffset == 0) + { + Py_ssize_t b_dictoffset = 0; +#if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + b_dictoffset = b->tp_dictoffset; +#else + PyObject *py_b_dictoffset = PyObject_GetAttrString((PyObject*)b, "__dictoffset__"); + if (!py_b_dictoffset) goto dictoffset_return; + b_dictoffset = PyLong_AsSsize_t(py_b_dictoffset); + Py_DECREF(py_b_dictoffset); + if (b_dictoffset == -1 && PyErr_Occurred()) goto dictoffset_return; +#endif + if (b_dictoffset) { + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "extension type '%.200s' has no __dict__ slot, " + "but base type '" __Pyx_FMT_TYPENAME "' has: " + "either add 'cdef dict __dict__' to the extension type " + "or add '__slots__ = [...]' to the base type", + type_name, b_name); + __Pyx_DECREF_TypeName(b_name); + } +#if !(CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY) + dictoffset_return: +#endif +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + return -1; + } + } +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + } + return 0; +} +#endif + +/* PyType_Ready */ +static int __Pyx_PyType_Ready(PyTypeObject *t) { +#if CYTHON_USE_TYPE_SPECS || !(CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API) || defined(PYSTON_MAJOR_VERSION) + (void)__Pyx_PyObject_CallMethod0; +#if CYTHON_USE_TYPE_SPECS + (void)__Pyx_validate_bases_tuple; +#endif + return PyType_Ready(t); +#else + int r; + PyObject *bases = __Pyx_PyType_GetSlot(t, tp_bases, PyObject*); + if (bases && unlikely(__Pyx_validate_bases_tuple(t->tp_name, t->tp_dictoffset, bases) == -1)) + return -1; +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + { + int gc_was_enabled; + #if PY_VERSION_HEX >= 0x030A00b1 + gc_was_enabled = PyGC_Disable(); + (void)__Pyx_PyObject_CallMethod0; + #else + PyObject *ret, *py_status; + PyObject *gc = NULL; + #if PY_VERSION_HEX >= 0x030700a1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM+0 >= 0x07030400) + gc = PyImport_GetModule(__pyx_kp_u_gc); + #endif + if (unlikely(!gc)) gc = PyImport_Import(__pyx_kp_u_gc); + if (unlikely(!gc)) return -1; + py_status = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_isenabled); + if (unlikely(!py_status)) { + Py_DECREF(gc); + return -1; + } + gc_was_enabled = __Pyx_PyObject_IsTrue(py_status); + Py_DECREF(py_status); + if (gc_was_enabled > 0) { + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_disable); + if (unlikely(!ret)) { + Py_DECREF(gc); + return -1; + } + Py_DECREF(ret); + } else if (unlikely(gc_was_enabled == -1)) { + Py_DECREF(gc); + return -1; + } + #endif + t->tp_flags |= Py_TPFLAGS_HEAPTYPE; +#if PY_VERSION_HEX >= 0x030A0000 + t->tp_flags |= Py_TPFLAGS_IMMUTABLETYPE; +#endif +#else + (void)__Pyx_PyObject_CallMethod0; +#endif + r = PyType_Ready(t); +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + t->tp_flags &= ~Py_TPFLAGS_HEAPTYPE; + #if PY_VERSION_HEX >= 0x030A00b1 + if (gc_was_enabled) + PyGC_Enable(); + #else + if (gc_was_enabled) { + PyObject *tp, *v, *tb; + PyErr_Fetch(&tp, &v, &tb); + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_enable); + if (likely(ret || r == -1)) { + Py_XDECREF(ret); + PyErr_Restore(tp, v, tb); + } else { + Py_XDECREF(tp); + Py_XDECREF(v); + Py_XDECREF(tb); + r = -1; + } + } + Py_DECREF(gc); + #endif + } +#endif + return r; +#endif +} + +/* PyObject_GenericGetAttrNoDict */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject *__Pyx_RaiseGenericGetAttributeError(PyTypeObject *tp, PyObject *attr_name) { + __Pyx_TypeName type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, attr_name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(attr_name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name) { + PyObject *descr; + PyTypeObject *tp = Py_TYPE(obj); + if (unlikely(!PyString_Check(attr_name))) { + return PyObject_GenericGetAttr(obj, attr_name); + } + assert(!tp->tp_dictoffset); + descr = _PyType_Lookup(tp, attr_name); + if (unlikely(!descr)) { + return __Pyx_RaiseGenericGetAttributeError(tp, attr_name); + } + Py_INCREF(descr); + #if PY_MAJOR_VERSION < 3 + if (likely(PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_HAVE_CLASS))) + #endif + { + descrgetfunc f = Py_TYPE(descr)->tp_descr_get; + if (unlikely(f)) { + PyObject *res = f(descr, obj, (PyObject *)tp); + Py_DECREF(descr); + return res; + } + } + return descr; +} +#endif + +/* PyObject_GenericGetAttr */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name) { + if (unlikely(Py_TYPE(obj)->tp_dictoffset)) { + return PyObject_GenericGetAttr(obj, attr_name); + } + return __Pyx_PyObject_GenericGetAttrNoDict(obj, attr_name); +} +#endif + +/* SetVTable */ +static int __Pyx_SetVtable(PyTypeObject *type, void *vtable) { + PyObject *ob = PyCapsule_New(vtable, 0, 0); + if (unlikely(!ob)) + goto bad; +#if CYTHON_COMPILING_IN_LIMITED_API + if (unlikely(PyObject_SetAttr((PyObject *) type, __pyx_n_s_pyx_vtable, ob) < 0)) +#else + if (unlikely(PyDict_SetItem(type->tp_dict, __pyx_n_s_pyx_vtable, ob) < 0)) +#endif + goto bad; + Py_DECREF(ob); + return 0; +bad: + Py_XDECREF(ob); + return -1; +} + +/* GetVTable */ +static void* __Pyx_GetVtable(PyTypeObject *type) { + void* ptr; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *ob = PyObject_GetAttr((PyObject *)type, __pyx_n_s_pyx_vtable); +#else + PyObject *ob = PyObject_GetItem(type->tp_dict, __pyx_n_s_pyx_vtable); +#endif + if (!ob) + goto bad; + ptr = PyCapsule_GetPointer(ob, 0); + if (!ptr && !PyErr_Occurred()) + PyErr_SetString(PyExc_RuntimeError, "invalid vtable found for imported type"); + Py_DECREF(ob); + return ptr; +bad: + Py_XDECREF(ob); + return NULL; +} + +/* MergeVTables */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_MergeVtables(PyTypeObject *type) { + int i; + void** base_vtables; + __Pyx_TypeName tp_base_name; + __Pyx_TypeName base_name; + void* unknown = (void*)-1; + PyObject* bases = type->tp_bases; + int base_depth = 0; + { + PyTypeObject* base = type->tp_base; + while (base) { + base_depth += 1; + base = base->tp_base; + } + } + base_vtables = (void**) malloc(sizeof(void*) * (size_t)(base_depth + 1)); + base_vtables[0] = unknown; + for (i = 1; i < PyTuple_GET_SIZE(bases); i++) { + void* base_vtable = __Pyx_GetVtable(((PyTypeObject*)PyTuple_GET_ITEM(bases, i))); + if (base_vtable != NULL) { + int j; + PyTypeObject* base = type->tp_base; + for (j = 0; j < base_depth; j++) { + if (base_vtables[j] == unknown) { + base_vtables[j] = __Pyx_GetVtable(base); + base_vtables[j + 1] = unknown; + } + if (base_vtables[j] == base_vtable) { + break; + } else if (base_vtables[j] == NULL) { + goto bad; + } + base = base->tp_base; + } + } + } + PyErr_Clear(); + free(base_vtables); + return 0; +bad: + tp_base_name = __Pyx_PyType_GetName(type->tp_base); + base_name = __Pyx_PyType_GetName((PyTypeObject*)PyTuple_GET_ITEM(bases, i)); + PyErr_Format(PyExc_TypeError, + "multiple bases have vtable conflict: '" __Pyx_FMT_TYPENAME "' and '" __Pyx_FMT_TYPENAME "'", tp_base_name, base_name); + __Pyx_DECREF_TypeName(tp_base_name); + __Pyx_DECREF_TypeName(base_name); + free(base_vtables); + return -1; +} +#endif + +/* SetupReduce */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce_is_named(PyObject* meth, PyObject* name) { + int ret; + PyObject *name_attr; + name_attr = __Pyx_PyObject_GetAttrStrNoError(meth, __pyx_n_s_name); + if (likely(name_attr)) { + ret = PyObject_RichCompareBool(name_attr, name, Py_EQ); + } else { + ret = -1; + } + if (unlikely(ret < 0)) { + PyErr_Clear(); + ret = 0; + } + Py_XDECREF(name_attr); + return ret; +} +static int __Pyx_setup_reduce(PyObject* type_obj) { + int ret = 0; + PyObject *object_reduce = NULL; + PyObject *object_getstate = NULL; + PyObject *object_reduce_ex = NULL; + PyObject *reduce = NULL; + PyObject *reduce_ex = NULL; + PyObject *reduce_cython = NULL; + PyObject *setstate = NULL; + PyObject *setstate_cython = NULL; + PyObject *getstate = NULL; +#if CYTHON_USE_PYTYPE_LOOKUP + getstate = _PyType_Lookup((PyTypeObject*)type_obj, __pyx_n_s_getstate); +#else + getstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_getstate); + if (!getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (getstate) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_getstate = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_getstate); +#else + object_getstate = __Pyx_PyObject_GetAttrStrNoError((PyObject*)&PyBaseObject_Type, __pyx_n_s_getstate); + if (!object_getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (object_getstate != getstate) { + goto __PYX_GOOD; + } + } +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce_ex = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#else + object_reduce_ex = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#endif + reduce_ex = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce_ex); if (unlikely(!reduce_ex)) goto __PYX_BAD; + if (reduce_ex == object_reduce_ex) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#else + object_reduce = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#endif + reduce = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce); if (unlikely(!reduce)) goto __PYX_BAD; + if (reduce == object_reduce || __Pyx_setup_reduce_is_named(reduce, __pyx_n_s_reduce_cython)) { + reduce_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_reduce_cython); + if (likely(reduce_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce, reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (reduce == object_reduce || PyErr_Occurred()) { + goto __PYX_BAD; + } + setstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate); + if (!setstate) PyErr_Clear(); + if (!setstate || __Pyx_setup_reduce_is_named(setstate, __pyx_n_s_setstate_cython)) { + setstate_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate_cython); + if (likely(setstate_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate, setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (!setstate || PyErr_Occurred()) { + goto __PYX_BAD; + } + } + PyType_Modified((PyTypeObject*)type_obj); + } + } + goto __PYX_GOOD; +__PYX_BAD: + if (!PyErr_Occurred()) { + __Pyx_TypeName type_obj_name = + __Pyx_PyType_GetName((PyTypeObject*)type_obj); + PyErr_Format(PyExc_RuntimeError, + "Unable to initialize pickling for " __Pyx_FMT_TYPENAME, type_obj_name); + __Pyx_DECREF_TypeName(type_obj_name); + } + ret = -1; +__PYX_GOOD: +#if !CYTHON_USE_PYTYPE_LOOKUP + Py_XDECREF(object_reduce); + Py_XDECREF(object_reduce_ex); + Py_XDECREF(object_getstate); + Py_XDECREF(getstate); +#endif + Py_XDECREF(reduce); + Py_XDECREF(reduce_ex); + Py_XDECREF(reduce_cython); + Py_XDECREF(setstate); + Py_XDECREF(setstate_cython); + return ret; +} +#endif + +/* Import */ +static PyObject *__Pyx_Import(PyObject *name, PyObject *from_list, int level) { + PyObject *module = 0; + PyObject *empty_dict = 0; + PyObject *empty_list = 0; + #if PY_MAJOR_VERSION < 3 + PyObject *py_import; + py_import = __Pyx_PyObject_GetAttrStr(__pyx_b, __pyx_n_s_import); + if (unlikely(!py_import)) + goto bad; + if (!from_list) { + empty_list = PyList_New(0); + if (unlikely(!empty_list)) + goto bad; + from_list = empty_list; + } + #endif + empty_dict = PyDict_New(); + if (unlikely(!empty_dict)) + goto bad; + { + #if PY_MAJOR_VERSION >= 3 + if (level == -1) { + if (strchr(__Pyx_MODULE_NAME, '.') != NULL) { + module = PyImport_ImportModuleLevelObject( + name, __pyx_d, empty_dict, from_list, 1); + if (unlikely(!module)) { + if (unlikely(!PyErr_ExceptionMatches(PyExc_ImportError))) + goto bad; + PyErr_Clear(); + } + } + level = 0; + } + #endif + if (!module) { + #if PY_MAJOR_VERSION < 3 + PyObject *py_level = PyInt_FromLong(level); + if (unlikely(!py_level)) + goto bad; + module = PyObject_CallFunctionObjArgs(py_import, + name, __pyx_d, empty_dict, from_list, py_level, (PyObject *)NULL); + Py_DECREF(py_level); + #else + module = PyImport_ImportModuleLevelObject( + name, __pyx_d, empty_dict, from_list, level); + #endif + } + } +bad: + Py_XDECREF(empty_dict); + Py_XDECREF(empty_list); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_import); + #endif + return module; +} + +/* ImportDottedModule */ +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx__ImportDottedModule_Error(PyObject *name, PyObject *parts_tuple, Py_ssize_t count) { + PyObject *partial_name = NULL, *slice = NULL, *sep = NULL; + if (unlikely(PyErr_Occurred())) { + PyErr_Clear(); + } + if (likely(PyTuple_GET_SIZE(parts_tuple) == count)) { + partial_name = name; + } else { + slice = PySequence_GetSlice(parts_tuple, 0, count); + if (unlikely(!slice)) + goto bad; + sep = PyUnicode_FromStringAndSize(".", 1); + if (unlikely(!sep)) + goto bad; + partial_name = PyUnicode_Join(sep, slice); + } + PyErr_Format( +#if PY_MAJOR_VERSION < 3 + PyExc_ImportError, + "No module named '%s'", PyString_AS_STRING(partial_name)); +#else +#if PY_VERSION_HEX >= 0x030600B1 + PyExc_ModuleNotFoundError, +#else + PyExc_ImportError, +#endif + "No module named '%U'", partial_name); +#endif +bad: + Py_XDECREF(sep); + Py_XDECREF(slice); + Py_XDECREF(partial_name); + return NULL; +} +#endif +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx__ImportDottedModule_Lookup(PyObject *name) { + PyObject *imported_module; +#if PY_VERSION_HEX < 0x030700A1 || (CYTHON_COMPILING_IN_PYPY && PYPY_VERSION_NUM < 0x07030400) + PyObject *modules = PyImport_GetModuleDict(); + if (unlikely(!modules)) + return NULL; + imported_module = __Pyx_PyDict_GetItemStr(modules, name); + Py_XINCREF(imported_module); +#else + imported_module = PyImport_GetModule(name); +#endif + return imported_module; +} +#endif +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_ImportDottedModule_WalkParts(PyObject *module, PyObject *name, PyObject *parts_tuple) { + Py_ssize_t i, nparts; + nparts = PyTuple_GET_SIZE(parts_tuple); + for (i=1; i < nparts && module; i++) { + PyObject *part, *submodule; +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + part = PyTuple_GET_ITEM(parts_tuple, i); +#else + part = PySequence_ITEM(parts_tuple, i); +#endif + submodule = __Pyx_PyObject_GetAttrStrNoError(module, part); +#if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(part); +#endif + Py_DECREF(module); + module = submodule; + } + if (unlikely(!module)) { + return __Pyx__ImportDottedModule_Error(name, parts_tuple, i); + } + return module; +} +#endif +static PyObject *__Pyx__ImportDottedModule(PyObject *name, PyObject *parts_tuple) { +#if PY_MAJOR_VERSION < 3 + PyObject *module, *from_list, *star = __pyx_n_s__5; + CYTHON_UNUSED_VAR(parts_tuple); + from_list = PyList_New(1); + if (unlikely(!from_list)) + return NULL; + Py_INCREF(star); + PyList_SET_ITEM(from_list, 0, star); + module = __Pyx_Import(name, from_list, 0); + Py_DECREF(from_list); + return module; +#else + PyObject *imported_module; + PyObject *module = __Pyx_Import(name, NULL, 0); + if (!parts_tuple || unlikely(!module)) + return module; + imported_module = __Pyx__ImportDottedModule_Lookup(name); + if (likely(imported_module)) { + Py_DECREF(module); + return imported_module; + } + PyErr_Clear(); + return __Pyx_ImportDottedModule_WalkParts(module, name, parts_tuple); +#endif +} +static PyObject *__Pyx_ImportDottedModule(PyObject *name, PyObject *parts_tuple) { +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030400B1 + PyObject *module = __Pyx__ImportDottedModule_Lookup(name); + if (likely(module)) { + PyObject *spec = __Pyx_PyObject_GetAttrStrNoError(module, __pyx_n_s_spec); + if (likely(spec)) { + PyObject *unsafe = __Pyx_PyObject_GetAttrStrNoError(spec, __pyx_n_s_initializing); + if (likely(!unsafe || !__Pyx_PyObject_IsTrue(unsafe))) { + Py_DECREF(spec); + spec = NULL; + } + Py_XDECREF(unsafe); + } + if (likely(!spec)) { + PyErr_Clear(); + return module; + } + Py_DECREF(spec); + Py_DECREF(module); + } else if (PyErr_Occurred()) { + PyErr_Clear(); + } +#endif + return __Pyx__ImportDottedModule(name, parts_tuple); +} + +/* Py3UpdateBases */ +static PyObject* +__Pyx_PEP560_update_bases(PyObject *bases) +{ + Py_ssize_t i, j, size_bases; + PyObject *base, *meth, *new_base, *result, *new_bases = NULL; + size_bases = PyTuple_GET_SIZE(bases); + for (i = 0; i < size_bases; i++) { + base = PyTuple_GET_ITEM(bases, i); + if (PyType_Check(base)) { + if (new_bases) { + if (PyList_Append(new_bases, base) < 0) { + goto error; + } + } + continue; + } + meth = __Pyx_PyObject_GetAttrStrNoError(base, __pyx_n_s_mro_entries); + if (!meth && PyErr_Occurred()) { + goto error; + } + if (!meth) { + if (new_bases) { + if (PyList_Append(new_bases, base) < 0) { + goto error; + } + } + continue; + } + new_base = __Pyx_PyObject_CallOneArg(meth, bases); + Py_DECREF(meth); + if (!new_base) { + goto error; + } + if (!PyTuple_Check(new_base)) { + PyErr_SetString(PyExc_TypeError, + "__mro_entries__ must return a tuple"); + Py_DECREF(new_base); + goto error; + } + if (!new_bases) { + if (!(new_bases = PyList_New(i))) { + goto error; + } + for (j = 0; j < i; j++) { + base = PyTuple_GET_ITEM(bases, j); + PyList_SET_ITEM(new_bases, j, base); + Py_INCREF(base); + } + } + j = PyList_GET_SIZE(new_bases); + if (PyList_SetSlice(new_bases, j, j, new_base) < 0) { + goto error; + } + Py_DECREF(new_base); + } + if (!new_bases) { + Py_INCREF(bases); + return bases; + } + result = PyList_AsTuple(new_bases); + Py_DECREF(new_bases); + return result; +error: + Py_XDECREF(new_bases); + return NULL; +} + +/* CalculateMetaclass */ +static PyObject *__Pyx_CalculateMetaclass(PyTypeObject *metaclass, PyObject *bases) { + Py_ssize_t i, nbases; +#if CYTHON_ASSUME_SAFE_MACROS + nbases = PyTuple_GET_SIZE(bases); +#else + nbases = PyTuple_Size(bases); + if (nbases < 0) return NULL; +#endif + for (i=0; i < nbases; i++) { + PyTypeObject *tmptype; +#if CYTHON_ASSUME_SAFE_MACROS + PyObject *tmp = PyTuple_GET_ITEM(bases, i); +#else + PyObject *tmp = PyTuple_GetItem(bases, i); + if (!tmp) return NULL; +#endif + tmptype = Py_TYPE(tmp); +#if PY_MAJOR_VERSION < 3 + if (tmptype == &PyClass_Type) + continue; +#endif + if (!metaclass) { + metaclass = tmptype; + continue; + } + if (PyType_IsSubtype(metaclass, tmptype)) + continue; + if (PyType_IsSubtype(tmptype, metaclass)) { + metaclass = tmptype; + continue; + } + PyErr_SetString(PyExc_TypeError, + "metaclass conflict: " + "the metaclass of a derived class " + "must be a (non-strict) subclass " + "of the metaclasses of all its bases"); + return NULL; + } + if (!metaclass) { +#if PY_MAJOR_VERSION < 3 + metaclass = &PyClass_Type; +#else + metaclass = &PyType_Type; +#endif + } + Py_INCREF((PyObject*) metaclass); + return (PyObject*) metaclass; +} + +/* FetchSharedCythonModule */ +static PyObject *__Pyx_FetchSharedCythonABIModule(void) { + return __Pyx_PyImport_AddModuleRef((char*) __PYX_ABI_MODULE_NAME); +} + +/* FetchCommonType */ +static int __Pyx_VerifyCachedType(PyObject *cached_type, + const char *name, + Py_ssize_t basicsize, + Py_ssize_t expected_basicsize) { + if (!PyType_Check(cached_type)) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s is not a type object", name); + return -1; + } + if (basicsize != expected_basicsize) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s has the wrong size, try recompiling", + name); + return -1; + } + return 0; +} +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type) { + PyObject* abi_module; + const char* object_name; + PyTypeObject *cached_type = NULL; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + object_name = strrchr(type->tp_name, '.'); + object_name = object_name ? object_name+1 : type->tp_name; + cached_type = (PyTypeObject*) PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + if (__Pyx_VerifyCachedType( + (PyObject *)cached_type, + object_name, + cached_type->tp_basicsize, + type->tp_basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + if (PyType_Ready(type) < 0) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, (PyObject *)type) < 0) + goto bad; + Py_INCREF(type); + cached_type = type; +done: + Py_DECREF(abi_module); + return cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#else +static PyTypeObject *__Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases) { + PyObject *abi_module, *cached_type = NULL; + const char* object_name = strrchr(spec->name, '.'); + object_name = object_name ? object_name+1 : spec->name; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + cached_type = PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + Py_ssize_t basicsize; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *py_basicsize; + py_basicsize = PyObject_GetAttrString(cached_type, "__basicsize__"); + if (unlikely(!py_basicsize)) goto bad; + basicsize = PyLong_AsSsize_t(py_basicsize); + Py_DECREF(py_basicsize); + py_basicsize = 0; + if (unlikely(basicsize == (Py_ssize_t)-1) && PyErr_Occurred()) goto bad; +#else + basicsize = likely(PyType_Check(cached_type)) ? ((PyTypeObject*) cached_type)->tp_basicsize : -1; +#endif + if (__Pyx_VerifyCachedType( + cached_type, + object_name, + basicsize, + spec->basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + CYTHON_UNUSED_VAR(module); + cached_type = __Pyx_PyType_FromModuleAndSpec(abi_module, spec, bases); + if (unlikely(!cached_type)) goto bad; + if (unlikely(__Pyx_fix_up_extension_type_from_spec(spec, (PyTypeObject *) cached_type) < 0)) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, cached_type) < 0) goto bad; +done: + Py_DECREF(abi_module); + assert(cached_type == NULL || PyType_Check(cached_type)); + return (PyTypeObject *) cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#endif + +/* PyVectorcallFastCallDict */ +#if CYTHON_METH_FASTCALL +static PyObject *__Pyx_PyVectorcall_FastCallDict_kw(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + PyObject *res = NULL; + PyObject *kwnames; + PyObject **newargs; + PyObject **kwvalues; + Py_ssize_t i, pos; + size_t j; + PyObject *key, *value; + unsigned long keys_are_strings; + Py_ssize_t nkw = PyDict_GET_SIZE(kw); + newargs = (PyObject **)PyMem_Malloc((nargs + (size_t)nkw) * sizeof(args[0])); + if (unlikely(newargs == NULL)) { + PyErr_NoMemory(); + return NULL; + } + for (j = 0; j < nargs; j++) newargs[j] = args[j]; + kwnames = PyTuple_New(nkw); + if (unlikely(kwnames == NULL)) { + PyMem_Free(newargs); + return NULL; + } + kwvalues = newargs + nargs; + pos = i = 0; + keys_are_strings = Py_TPFLAGS_UNICODE_SUBCLASS; + while (PyDict_Next(kw, &pos, &key, &value)) { + keys_are_strings &= Py_TYPE(key)->tp_flags; + Py_INCREF(key); + Py_INCREF(value); + PyTuple_SET_ITEM(kwnames, i, key); + kwvalues[i] = value; + i++; + } + if (unlikely(!keys_are_strings)) { + PyErr_SetString(PyExc_TypeError, "keywords must be strings"); + goto cleanup; + } + res = vc(func, newargs, nargs, kwnames); +cleanup: + Py_DECREF(kwnames); + for (i = 0; i < nkw; i++) + Py_DECREF(kwvalues[i]); + PyMem_Free(newargs); + return res; +} +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + if (likely(kw == NULL) || PyDict_GET_SIZE(kw) == 0) { + return vc(func, args, nargs, NULL); + } + return __Pyx_PyVectorcall_FastCallDict_kw(func, vc, args, nargs, kw); +} +#endif + +/* CythonFunctionShared */ +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc) { + if (__Pyx_CyFunction_Check(func)) { + return PyCFunction_GetFunction(((__pyx_CyFunctionObject*)func)->func) == (PyCFunction) cfunc; + } else if (PyCFunction_Check(func)) { + return PyCFunction_GetFunction(func) == (PyCFunction) cfunc; + } + return 0; +} +#else +static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc) { + return __Pyx_CyOrPyCFunction_Check(func) && __Pyx_CyOrPyCFunction_GET_FUNCTION(func) == (PyCFunction) cfunc; +} +#endif +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj) { +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + __Pyx_Py_XDECREF_SET( + __Pyx_CyFunction_GetClassObj(f), + ((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#else + __Pyx_Py_XDECREF_SET( + ((PyCMethodObject *) (f))->mm_class, + (PyTypeObject*)((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#endif +} +static PyObject * +__Pyx_CyFunction_get_doc(__pyx_CyFunctionObject *op, void *closure) +{ + CYTHON_UNUSED_VAR(closure); + if (unlikely(op->func_doc == NULL)) { +#if CYTHON_COMPILING_IN_LIMITED_API + op->func_doc = PyObject_GetAttrString(op->func, "__doc__"); + if (unlikely(!op->func_doc)) return NULL; +#else + if (((PyCFunctionObject*)op)->m_ml->ml_doc) { +#if PY_MAJOR_VERSION >= 3 + op->func_doc = PyUnicode_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#else + op->func_doc = PyString_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#endif + if (unlikely(op->func_doc == NULL)) + return NULL; + } else { + Py_INCREF(Py_None); + return Py_None; + } +#endif + } + Py_INCREF(op->func_doc); + return op->func_doc; +} +static int +__Pyx_CyFunction_set_doc(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (value == NULL) { + value = Py_None; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_doc, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_name(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_name == NULL)) { +#if CYTHON_COMPILING_IN_LIMITED_API + op->func_name = PyObject_GetAttrString(op->func, "__name__"); +#elif PY_MAJOR_VERSION >= 3 + op->func_name = PyUnicode_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#else + op->func_name = PyString_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#endif + if (unlikely(op->func_name == NULL)) + return NULL; + } + Py_INCREF(op->func_name); + return op->func_name; +} +static int +__Pyx_CyFunction_set_name(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__name__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_name, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_qualname(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_qualname); + return op->func_qualname; +} +static int +__Pyx_CyFunction_set_qualname(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__qualname__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_qualname, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_dict(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_dict == NULL)) { + op->func_dict = PyDict_New(); + if (unlikely(op->func_dict == NULL)) + return NULL; + } + Py_INCREF(op->func_dict); + return op->func_dict; +} +static int +__Pyx_CyFunction_set_dict(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(value == NULL)) { + PyErr_SetString(PyExc_TypeError, + "function's dictionary may not be deleted"); + return -1; + } + if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "setting function's dictionary to a non-dict"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_dict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_globals(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_globals); + return op->func_globals; +} +static PyObject * +__Pyx_CyFunction_get_closure(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(op); + CYTHON_UNUSED_VAR(context); + Py_INCREF(Py_None); + return Py_None; +} +static PyObject * +__Pyx_CyFunction_get_code(__pyx_CyFunctionObject *op, void *context) +{ + PyObject* result = (op->func_code) ? op->func_code : Py_None; + CYTHON_UNUSED_VAR(context); + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_init_defaults(__pyx_CyFunctionObject *op) { + int result = 0; + PyObject *res = op->defaults_getter((PyObject *) op); + if (unlikely(!res)) + return -1; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + op->defaults_tuple = PyTuple_GET_ITEM(res, 0); + Py_INCREF(op->defaults_tuple); + op->defaults_kwdict = PyTuple_GET_ITEM(res, 1); + Py_INCREF(op->defaults_kwdict); + #else + op->defaults_tuple = __Pyx_PySequence_ITEM(res, 0); + if (unlikely(!op->defaults_tuple)) result = -1; + else { + op->defaults_kwdict = __Pyx_PySequence_ITEM(res, 1); + if (unlikely(!op->defaults_kwdict)) result = -1; + } + #endif + Py_DECREF(res); + return result; +} +static int +__Pyx_CyFunction_set_defaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyTuple_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__defaults__ must be set to a tuple object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__defaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_tuple, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_defaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_tuple; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_tuple; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_kwdefaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__kwdefaults__ must be set to a dict object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__kwdefaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_kwdict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_kwdefaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_kwdict; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_kwdict; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_annotations(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value || value == Py_None) { + value = NULL; + } else if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__annotations__ must be set to a dict object"); + return -1; + } + Py_XINCREF(value); + __Pyx_Py_XDECREF_SET(op->func_annotations, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_annotations(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->func_annotations; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + result = PyDict_New(); + if (unlikely(!result)) return NULL; + op->func_annotations = result; + } + Py_INCREF(result); + return result; +} +static PyObject * +__Pyx_CyFunction_get_is_coroutine(__pyx_CyFunctionObject *op, void *context) { + int is_coroutine; + CYTHON_UNUSED_VAR(context); + if (op->func_is_coroutine) { + return __Pyx_NewRef(op->func_is_coroutine); + } + is_coroutine = op->flags & __Pyx_CYFUNCTION_COROUTINE; +#if PY_VERSION_HEX >= 0x03050000 + if (is_coroutine) { + PyObject *module, *fromlist, *marker = __pyx_n_s_is_coroutine; + fromlist = PyList_New(1); + if (unlikely(!fromlist)) return NULL; + Py_INCREF(marker); +#if CYTHON_ASSUME_SAFE_MACROS + PyList_SET_ITEM(fromlist, 0, marker); +#else + if (unlikely(PyList_SetItem(fromlist, 0, marker) < 0)) { + Py_DECREF(marker); + Py_DECREF(fromlist); + return NULL; + } +#endif + module = PyImport_ImportModuleLevelObject(__pyx_n_s_asyncio_coroutines, NULL, NULL, fromlist, 0); + Py_DECREF(fromlist); + if (unlikely(!module)) goto ignore; + op->func_is_coroutine = __Pyx_PyObject_GetAttrStr(module, marker); + Py_DECREF(module); + if (likely(op->func_is_coroutine)) { + return __Pyx_NewRef(op->func_is_coroutine); + } +ignore: + PyErr_Clear(); + } +#endif + op->func_is_coroutine = __Pyx_PyBool_FromLong(is_coroutine); + return __Pyx_NewRef(op->func_is_coroutine); +} +#if CYTHON_COMPILING_IN_LIMITED_API +static PyObject * +__Pyx_CyFunction_get_module(__pyx_CyFunctionObject *op, void *context) { + CYTHON_UNUSED_VAR(context); + return PyObject_GetAttrString(op->func, "__module__"); +} +static int +__Pyx_CyFunction_set_module(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + return PyObject_SetAttrString(op->func, "__module__", value); +} +#endif +static PyGetSetDef __pyx_CyFunction_getsets[] = { + {(char *) "func_doc", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "__doc__", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "func_name", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__name__", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__qualname__", (getter)__Pyx_CyFunction_get_qualname, (setter)__Pyx_CyFunction_set_qualname, 0, 0}, + {(char *) "func_dict", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "__dict__", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "func_globals", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "__globals__", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "func_closure", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "__closure__", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "func_code", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "__code__", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "func_defaults", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__defaults__", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__kwdefaults__", (getter)__Pyx_CyFunction_get_kwdefaults, (setter)__Pyx_CyFunction_set_kwdefaults, 0, 0}, + {(char *) "__annotations__", (getter)__Pyx_CyFunction_get_annotations, (setter)__Pyx_CyFunction_set_annotations, 0, 0}, + {(char *) "_is_coroutine", (getter)__Pyx_CyFunction_get_is_coroutine, 0, 0, 0}, +#if CYTHON_COMPILING_IN_LIMITED_API + {"__module__", (getter)__Pyx_CyFunction_get_module, (setter)__Pyx_CyFunction_set_module, 0, 0}, +#endif + {0, 0, 0, 0, 0} +}; +static PyMemberDef __pyx_CyFunction_members[] = { +#if !CYTHON_COMPILING_IN_LIMITED_API + {(char *) "__module__", T_OBJECT, offsetof(PyCFunctionObject, m_module), 0, 0}, +#endif +#if CYTHON_USE_TYPE_SPECS + {(char *) "__dictoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_dict), READONLY, 0}, +#if CYTHON_METH_FASTCALL +#if CYTHON_BACKPORT_VECTORCALL + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_vectorcall), READONLY, 0}, +#else +#if !CYTHON_COMPILING_IN_LIMITED_API + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(PyCFunctionObject, vectorcall), READONLY, 0}, +#endif +#endif +#endif +#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_weakreflist), READONLY, 0}, +#else + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(PyCFunctionObject, m_weakreflist), READONLY, 0}, +#endif +#endif + {0, 0, 0, 0, 0} +}; +static PyObject * +__Pyx_CyFunction_reduce(__pyx_CyFunctionObject *m, PyObject *args) +{ + CYTHON_UNUSED_VAR(args); +#if PY_MAJOR_VERSION >= 3 + Py_INCREF(m->func_qualname); + return m->func_qualname; +#else + return PyString_FromString(((PyCFunctionObject*)m)->m_ml->ml_name); +#endif +} +static PyMethodDef __pyx_CyFunction_methods[] = { + {"__reduce__", (PyCFunction)__Pyx_CyFunction_reduce, METH_VARARGS, 0}, + {0, 0, 0, 0} +}; +#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API +#define __Pyx_CyFunction_weakreflist(cyfunc) ((cyfunc)->func_weakreflist) +#else +#define __Pyx_CyFunction_weakreflist(cyfunc) (((PyCFunctionObject*)cyfunc)->m_weakreflist) +#endif +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject *op, PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { +#if !CYTHON_COMPILING_IN_LIMITED_API + PyCFunctionObject *cf = (PyCFunctionObject*) op; +#endif + if (unlikely(op == NULL)) + return NULL; +#if CYTHON_COMPILING_IN_LIMITED_API + op->func = PyCFunction_NewEx(ml, (PyObject*)op, module); + if (unlikely(!op->func)) return NULL; +#endif + op->flags = flags; + __Pyx_CyFunction_weakreflist(op) = NULL; +#if !CYTHON_COMPILING_IN_LIMITED_API + cf->m_ml = ml; + cf->m_self = (PyObject *) op; +#endif + Py_XINCREF(closure); + op->func_closure = closure; +#if !CYTHON_COMPILING_IN_LIMITED_API + Py_XINCREF(module); + cf->m_module = module; +#endif + op->func_dict = NULL; + op->func_name = NULL; + Py_INCREF(qualname); + op->func_qualname = qualname; + op->func_doc = NULL; +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + op->func_classobj = NULL; +#else + ((PyCMethodObject*)op)->mm_class = NULL; +#endif + op->func_globals = globals; + Py_INCREF(op->func_globals); + Py_XINCREF(code); + op->func_code = code; + op->defaults_pyobjects = 0; + op->defaults_size = 0; + op->defaults = NULL; + op->defaults_tuple = NULL; + op->defaults_kwdict = NULL; + op->defaults_getter = NULL; + op->func_annotations = NULL; + op->func_is_coroutine = NULL; +#if CYTHON_METH_FASTCALL + switch (ml->ml_flags & (METH_VARARGS | METH_FASTCALL | METH_NOARGS | METH_O | METH_KEYWORDS | METH_METHOD)) { + case METH_NOARGS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_NOARGS; + break; + case METH_O: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_O; + break; + case METH_METHOD | METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD; + break; + case METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS; + break; + case METH_VARARGS | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = NULL; + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + Py_DECREF(op); + return NULL; + } +#endif + return (PyObject *) op; +} +static int +__Pyx_CyFunction_clear(__pyx_CyFunctionObject *m) +{ + Py_CLEAR(m->func_closure); +#if CYTHON_COMPILING_IN_LIMITED_API + Py_CLEAR(m->func); +#else + Py_CLEAR(((PyCFunctionObject*)m)->m_module); +#endif + Py_CLEAR(m->func_dict); + Py_CLEAR(m->func_name); + Py_CLEAR(m->func_qualname); + Py_CLEAR(m->func_doc); + Py_CLEAR(m->func_globals); + Py_CLEAR(m->func_code); +#if !CYTHON_COMPILING_IN_LIMITED_API +#if PY_VERSION_HEX < 0x030900B1 + Py_CLEAR(__Pyx_CyFunction_GetClassObj(m)); +#else + { + PyObject *cls = (PyObject*) ((PyCMethodObject *) (m))->mm_class; + ((PyCMethodObject *) (m))->mm_class = NULL; + Py_XDECREF(cls); + } +#endif +#endif + Py_CLEAR(m->defaults_tuple); + Py_CLEAR(m->defaults_kwdict); + Py_CLEAR(m->func_annotations); + Py_CLEAR(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_XDECREF(pydefaults[i]); + PyObject_Free(m->defaults); + m->defaults = NULL; + } + return 0; +} +static void __Pyx__CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + if (__Pyx_CyFunction_weakreflist(m) != NULL) + PyObject_ClearWeakRefs((PyObject *) m); + __Pyx_CyFunction_clear(m); + __Pyx_PyHeapTypeObject_GC_Del(m); +} +static void __Pyx_CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + PyObject_GC_UnTrack(m); + __Pyx__CyFunction_dealloc(m); +} +static int __Pyx_CyFunction_traverse(__pyx_CyFunctionObject *m, visitproc visit, void *arg) +{ + Py_VISIT(m->func_closure); +#if CYTHON_COMPILING_IN_LIMITED_API + Py_VISIT(m->func); +#else + Py_VISIT(((PyCFunctionObject*)m)->m_module); +#endif + Py_VISIT(m->func_dict); + Py_VISIT(m->func_name); + Py_VISIT(m->func_qualname); + Py_VISIT(m->func_doc); + Py_VISIT(m->func_globals); + Py_VISIT(m->func_code); +#if !CYTHON_COMPILING_IN_LIMITED_API + Py_VISIT(__Pyx_CyFunction_GetClassObj(m)); +#endif + Py_VISIT(m->defaults_tuple); + Py_VISIT(m->defaults_kwdict); + Py_VISIT(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_VISIT(pydefaults[i]); + } + return 0; +} +static PyObject* +__Pyx_CyFunction_repr(__pyx_CyFunctionObject *op) +{ +#if PY_MAJOR_VERSION >= 3 + return PyUnicode_FromFormat("", + op->func_qualname, (void *)op); +#else + return PyString_FromFormat("", + PyString_AsString(op->func_qualname), (void *)op); +#endif +} +static PyObject * __Pyx_CyFunction_CallMethod(PyObject *func, PyObject *self, PyObject *arg, PyObject *kw) { +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *f = ((__pyx_CyFunctionObject*)func)->func; + PyObject *py_name = NULL; + PyCFunction meth; + int flags; + meth = PyCFunction_GetFunction(f); + if (unlikely(!meth)) return NULL; + flags = PyCFunction_GetFlags(f); + if (unlikely(flags < 0)) return NULL; +#else + PyCFunctionObject* f = (PyCFunctionObject*)func; + PyCFunction meth = f->m_ml->ml_meth; + int flags = f->m_ml->ml_flags; +#endif + Py_ssize_t size; + switch (flags & (METH_VARARGS | METH_KEYWORDS | METH_NOARGS | METH_O)) { + case METH_VARARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) + return (*meth)(self, arg); + break; + case METH_VARARGS | METH_KEYWORDS: + return (*(PyCFunctionWithKeywords)(void*)meth)(self, arg, kw); + case METH_NOARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { +#if CYTHON_ASSUME_SAFE_MACROS + size = PyTuple_GET_SIZE(arg); +#else + size = PyTuple_Size(arg); + if (unlikely(size < 0)) return NULL; +#endif + if (likely(size == 0)) + return (*meth)(self, NULL); +#if CYTHON_COMPILING_IN_LIMITED_API + py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); + if (!py_name) return NULL; + PyErr_Format(PyExc_TypeError, + "%.200S() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + py_name, size); + Py_DECREF(py_name); +#else + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); +#endif + return NULL; + } + break; + case METH_O: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { +#if CYTHON_ASSUME_SAFE_MACROS + size = PyTuple_GET_SIZE(arg); +#else + size = PyTuple_Size(arg); + if (unlikely(size < 0)) return NULL; +#endif + if (likely(size == 1)) { + PyObject *result, *arg0; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + arg0 = PyTuple_GET_ITEM(arg, 0); + #else + arg0 = __Pyx_PySequence_ITEM(arg, 0); if (unlikely(!arg0)) return NULL; + #endif + result = (*meth)(self, arg0); + #if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(arg0); + #endif + return result; + } +#if CYTHON_COMPILING_IN_LIMITED_API + py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); + if (!py_name) return NULL; + PyErr_Format(PyExc_TypeError, + "%.200S() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + py_name, size); + Py_DECREF(py_name); +#else + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); +#endif + return NULL; + } + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + return NULL; + } +#if CYTHON_COMPILING_IN_LIMITED_API + py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); + if (!py_name) return NULL; + PyErr_Format(PyExc_TypeError, "%.200S() takes no keyword arguments", + py_name); + Py_DECREF(py_name); +#else + PyErr_Format(PyExc_TypeError, "%.200s() takes no keyword arguments", + f->m_ml->ml_name); +#endif + return NULL; +} +static CYTHON_INLINE PyObject *__Pyx_CyFunction_Call(PyObject *func, PyObject *arg, PyObject *kw) { + PyObject *self, *result; +#if CYTHON_COMPILING_IN_LIMITED_API + self = PyCFunction_GetSelf(((__pyx_CyFunctionObject*)func)->func); + if (unlikely(!self) && PyErr_Occurred()) return NULL; +#else + self = ((PyCFunctionObject*)func)->m_self; +#endif + result = __Pyx_CyFunction_CallMethod(func, self, arg, kw); + return result; +} +static PyObject *__Pyx_CyFunction_CallAsMethod(PyObject *func, PyObject *args, PyObject *kw) { + PyObject *result; + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *) func; +#if CYTHON_METH_FASTCALL + __pyx_vectorcallfunc vc = __Pyx_CyFunction_func_vectorcall(cyfunc); + if (vc) { +#if CYTHON_ASSUME_SAFE_MACROS + return __Pyx_PyVectorcall_FastCallDict(func, vc, &PyTuple_GET_ITEM(args, 0), (size_t)PyTuple_GET_SIZE(args), kw); +#else + (void) &__Pyx_PyVectorcall_FastCallDict; + return PyVectorcall_Call(func, args, kw); +#endif + } +#endif + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + Py_ssize_t argc; + PyObject *new_args; + PyObject *self; +#if CYTHON_ASSUME_SAFE_MACROS + argc = PyTuple_GET_SIZE(args); +#else + argc = PyTuple_Size(args); + if (unlikely(!argc) < 0) return NULL; +#endif + new_args = PyTuple_GetSlice(args, 1, argc); + if (unlikely(!new_args)) + return NULL; + self = PyTuple_GetItem(args, 0); + if (unlikely(!self)) { + Py_DECREF(new_args); +#if PY_MAJOR_VERSION > 2 + PyErr_Format(PyExc_TypeError, + "unbound method %.200S() needs an argument", + cyfunc->func_qualname); +#else + PyErr_SetString(PyExc_TypeError, + "unbound method needs an argument"); +#endif + return NULL; + } + result = __Pyx_CyFunction_CallMethod(func, self, new_args, kw); + Py_DECREF(new_args); + } else { + result = __Pyx_CyFunction_Call(func, args, kw); + } + return result; +} +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE int __Pyx_CyFunction_Vectorcall_CheckArgs(__pyx_CyFunctionObject *cyfunc, Py_ssize_t nargs, PyObject *kwnames) +{ + int ret = 0; + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + if (unlikely(nargs < 1)) { + PyErr_Format(PyExc_TypeError, "%.200s() needs an argument", + ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + ret = 1; + } + if (unlikely(kwnames) && unlikely(PyTuple_GET_SIZE(kwnames))) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no keyword arguments", ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + return ret; +} +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 0)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, NULL); +} +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 1)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, args[0]); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((_PyCFunctionFastWithKeywords)(void(*)(void))def->ml_meth)(self, args, nargs, kwnames); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; + PyTypeObject *cls = (PyTypeObject *) __Pyx_CyFunction_GetClassObj(cyfunc); +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((__Pyx_PyCMethod)(void(*)(void))def->ml_meth)(self, cls, args, (size_t)nargs, kwnames); +} +#endif +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_CyFunctionType_slots[] = { + {Py_tp_dealloc, (void *)__Pyx_CyFunction_dealloc}, + {Py_tp_repr, (void *)__Pyx_CyFunction_repr}, + {Py_tp_call, (void *)__Pyx_CyFunction_CallAsMethod}, + {Py_tp_traverse, (void *)__Pyx_CyFunction_traverse}, + {Py_tp_clear, (void *)__Pyx_CyFunction_clear}, + {Py_tp_methods, (void *)__pyx_CyFunction_methods}, + {Py_tp_members, (void *)__pyx_CyFunction_members}, + {Py_tp_getset, (void *)__pyx_CyFunction_getsets}, + {Py_tp_descr_get, (void *)__Pyx_PyMethod_New}, + {0, 0}, +}; +static PyType_Spec __pyx_CyFunctionType_spec = { + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#if (defined(_Py_TPFLAGS_HAVE_VECTORCALL) && CYTHON_METH_FASTCALL) + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + __pyx_CyFunctionType_slots +}; +#else +static PyTypeObject __pyx_CyFunctionType_type = { + PyVarObject_HEAD_INIT(0, 0) + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, + (destructor) __Pyx_CyFunction_dealloc, +#if !CYTHON_METH_FASTCALL + 0, +#elif CYTHON_BACKPORT_VECTORCALL + (printfunc)offsetof(__pyx_CyFunctionObject, func_vectorcall), +#else + offsetof(PyCFunctionObject, vectorcall), +#endif + 0, + 0, +#if PY_MAJOR_VERSION < 3 + 0, +#else + 0, +#endif + (reprfunc) __Pyx_CyFunction_repr, + 0, + 0, + 0, + 0, + __Pyx_CyFunction_CallAsMethod, + 0, + 0, + 0, + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#if defined(_Py_TPFLAGS_HAVE_VECTORCALL) && CYTHON_METH_FASTCALL + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + 0, + (traverseproc) __Pyx_CyFunction_traverse, + (inquiry) __Pyx_CyFunction_clear, + 0, +#if PY_VERSION_HEX < 0x030500A0 + offsetof(__pyx_CyFunctionObject, func_weakreflist), +#else + offsetof(PyCFunctionObject, m_weakreflist), +#endif + 0, + 0, + __pyx_CyFunction_methods, + __pyx_CyFunction_members, + __pyx_CyFunction_getsets, + 0, + 0, + __Pyx_PyMethod_New, + 0, + offsetof(__pyx_CyFunctionObject, func_dict), + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, +#if PY_VERSION_HEX >= 0x030400a1 + 0, +#endif +#if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, +#endif +#if __PYX_NEED_TP_PRINT_SLOT + 0, +#endif +#if PY_VERSION_HEX >= 0x030C0000 + 0, +#endif +#if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, +#endif +}; +#endif +static int __pyx_CyFunction_init(PyObject *module) { +#if CYTHON_USE_TYPE_SPECS + __pyx_CyFunctionType = __Pyx_FetchCommonTypeFromSpec(module, &__pyx_CyFunctionType_spec, NULL); +#else + CYTHON_UNUSED_VAR(module); + __pyx_CyFunctionType = __Pyx_FetchCommonType(&__pyx_CyFunctionType_type); +#endif + if (unlikely(__pyx_CyFunctionType == NULL)) { + return -1; + } + return 0; +} +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *func, size_t size, int pyobjects) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults = PyObject_Malloc(size); + if (unlikely(!m->defaults)) + return PyErr_NoMemory(); + memset(m->defaults, 0, size); + m->defaults_pyobjects = pyobjects; + m->defaults_size = size; + return m->defaults; +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *func, PyObject *tuple) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_tuple = tuple; + Py_INCREF(tuple); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_kwdict = dict; + Py_INCREF(dict); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->func_annotations = dict; + Py_INCREF(dict); +} + +/* CythonFunction */ +static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { + PyObject *op = __Pyx_CyFunction_Init( + PyObject_GC_New(__pyx_CyFunctionObject, __pyx_CyFunctionType), + ml, flags, qualname, closure, module, globals, code + ); + if (likely(op)) { + PyObject_GC_Track(op); + } + return op; +} + +/* PyObjectCall2Args */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call2Args(PyObject* function, PyObject* arg1, PyObject* arg2) { + PyObject *args[3] = {NULL, arg1, arg2}; + return __Pyx_PyObject_FastCall(function, args+1, 2 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* PyObjectLookupSpecial */ +#if CYTHON_USE_PYTYPE_LOOKUP && CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx__PyObject_LookupSpecial(PyObject* obj, PyObject* attr_name, int with_error) { + PyObject *res; + PyTypeObject *tp = Py_TYPE(obj); +#if PY_MAJOR_VERSION < 3 + if (unlikely(PyInstance_Check(obj))) + return with_error ? __Pyx_PyObject_GetAttrStr(obj, attr_name) : __Pyx_PyObject_GetAttrStrNoError(obj, attr_name); +#endif + res = _PyType_Lookup(tp, attr_name); + if (likely(res)) { + descrgetfunc f = Py_TYPE(res)->tp_descr_get; + if (!f) { + Py_INCREF(res); + } else { + res = f(res, obj, (PyObject *)tp); + } + } else if (with_error) { + PyErr_SetObject(PyExc_AttributeError, attr_name); + } + return res; +} +#endif + +/* Py3ClassCreate */ +static PyObject *__Pyx_Py3MetaclassPrepare(PyObject *metaclass, PyObject *bases, PyObject *name, + PyObject *qualname, PyObject *mkw, PyObject *modname, PyObject *doc) { + PyObject *ns; + if (metaclass) { + PyObject *prep = __Pyx_PyObject_GetAttrStrNoError(metaclass, __pyx_n_s_prepare); + if (prep) { + PyObject *pargs[3] = {NULL, name, bases}; + ns = __Pyx_PyObject_FastCallDict(prep, pargs+1, 2 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET, mkw); + Py_DECREF(prep); + } else { + if (unlikely(PyErr_Occurred())) + return NULL; + ns = PyDict_New(); + } + } else { + ns = PyDict_New(); + } + if (unlikely(!ns)) + return NULL; + if (unlikely(PyObject_SetItem(ns, __pyx_n_s_module, modname) < 0)) goto bad; +#if PY_VERSION_HEX >= 0x03030000 + if (unlikely(PyObject_SetItem(ns, __pyx_n_s_qualname, qualname) < 0)) goto bad; +#else + CYTHON_MAYBE_UNUSED_VAR(qualname); +#endif + if (unlikely(doc && PyObject_SetItem(ns, __pyx_n_s_doc, doc) < 0)) goto bad; + return ns; +bad: + Py_DECREF(ns); + return NULL; +} +#if PY_VERSION_HEX < 0x030600A4 && CYTHON_PEP487_INIT_SUBCLASS +static int __Pyx_SetNamesPEP487(PyObject *type_obj) { + PyTypeObject *type = (PyTypeObject*) type_obj; + PyObject *names_to_set, *key, *value, *set_name, *tmp; + Py_ssize_t i = 0; +#if CYTHON_USE_TYPE_SLOTS + names_to_set = PyDict_Copy(type->tp_dict); +#else + { + PyObject *d = PyObject_GetAttr(type_obj, __pyx_n_s_dict); + names_to_set = NULL; + if (likely(d)) { + PyObject *names_to_set = PyDict_New(); + int ret = likely(names_to_set) ? PyDict_Update(names_to_set, d) : -1; + Py_DECREF(d); + if (unlikely(ret < 0)) + Py_CLEAR(names_to_set); + } + } +#endif + if (unlikely(names_to_set == NULL)) + goto bad; + while (PyDict_Next(names_to_set, &i, &key, &value)) { + set_name = __Pyx_PyObject_LookupSpecialNoError(value, __pyx_n_s_set_name); + if (unlikely(set_name != NULL)) { + tmp = __Pyx_PyObject_Call2Args(set_name, type_obj, key); + Py_DECREF(set_name); + if (unlikely(tmp == NULL)) { + __Pyx_TypeName value_type_name = + __Pyx_PyType_GetName(Py_TYPE(value)); + __Pyx_TypeName type_name = __Pyx_PyType_GetName(type); + PyErr_Format(PyExc_RuntimeError, +#if PY_MAJOR_VERSION >= 3 + "Error calling __set_name__ on '" __Pyx_FMT_TYPENAME "' instance %R " "in '" __Pyx_FMT_TYPENAME "'", + value_type_name, key, type_name); +#else + "Error calling __set_name__ on '" __Pyx_FMT_TYPENAME "' instance %.100s in '" __Pyx_FMT_TYPENAME "'", + value_type_name, + PyString_Check(key) ? PyString_AS_STRING(key) : "?", + type_name); +#endif + goto bad; + } else { + Py_DECREF(tmp); + } + } + else if (unlikely(PyErr_Occurred())) { + goto bad; + } + } + Py_DECREF(names_to_set); + return 0; +bad: + Py_XDECREF(names_to_set); + return -1; +} +static PyObject *__Pyx_InitSubclassPEP487(PyObject *type_obj, PyObject *mkw) { +#if CYTHON_USE_TYPE_SLOTS && CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + PyTypeObject *type = (PyTypeObject*) type_obj; + PyObject *mro = type->tp_mro; + Py_ssize_t i, nbases; + if (unlikely(!mro)) goto done; + (void) &__Pyx_GetBuiltinName; + Py_INCREF(mro); + nbases = PyTuple_GET_SIZE(mro); + assert(PyTuple_GET_ITEM(mro, 0) == type_obj); + for (i = 1; i < nbases-1; i++) { + PyObject *base, *dict, *meth; + base = PyTuple_GET_ITEM(mro, i); + dict = ((PyTypeObject *)base)->tp_dict; + meth = __Pyx_PyDict_GetItemStrWithError(dict, __pyx_n_s_init_subclass); + if (unlikely(meth)) { + descrgetfunc f = Py_TYPE(meth)->tp_descr_get; + PyObject *res; + Py_INCREF(meth); + if (likely(f)) { + res = f(meth, NULL, type_obj); + Py_DECREF(meth); + if (unlikely(!res)) goto bad; + meth = res; + } + res = __Pyx_PyObject_FastCallDict(meth, NULL, 0, mkw); + Py_DECREF(meth); + if (unlikely(!res)) goto bad; + Py_DECREF(res); + goto done; + } else if (unlikely(PyErr_Occurred())) { + goto bad; + } + } +done: + Py_XDECREF(mro); + return type_obj; +bad: + Py_XDECREF(mro); + Py_DECREF(type_obj); + return NULL; +#else + PyObject *super_type, *super, *func, *res; +#if CYTHON_COMPILING_IN_PYPY && !defined(PySuper_Type) + super_type = __Pyx_GetBuiltinName(__pyx_n_s_super); +#else + super_type = (PyObject*) &PySuper_Type; + (void) &__Pyx_GetBuiltinName; +#endif + super = likely(super_type) ? __Pyx_PyObject_Call2Args(super_type, type_obj, type_obj) : NULL; +#if CYTHON_COMPILING_IN_PYPY && !defined(PySuper_Type) + Py_XDECREF(super_type); +#endif + if (unlikely(!super)) { + Py_CLEAR(type_obj); + goto done; + } + func = __Pyx_PyObject_GetAttrStrNoError(super, __pyx_n_s_init_subclass); + Py_DECREF(super); + if (likely(!func)) { + if (unlikely(PyErr_Occurred())) + Py_CLEAR(type_obj); + goto done; + } + res = __Pyx_PyObject_FastCallDict(func, NULL, 0, mkw); + Py_DECREF(func); + if (unlikely(!res)) + Py_CLEAR(type_obj); + Py_XDECREF(res); +done: + return type_obj; +#endif +} +#endif +static PyObject *__Pyx_Py3ClassCreate(PyObject *metaclass, PyObject *name, PyObject *bases, + PyObject *dict, PyObject *mkw, + int calculate_metaclass, int allow_py2_metaclass) { + PyObject *result; + PyObject *owned_metaclass = NULL; + PyObject *margs[4] = {NULL, name, bases, dict}; + if (allow_py2_metaclass) { + owned_metaclass = PyObject_GetItem(dict, __pyx_n_s_metaclass); + if (owned_metaclass) { + metaclass = owned_metaclass; + } else if (likely(PyErr_ExceptionMatches(PyExc_KeyError))) { + PyErr_Clear(); + } else { + return NULL; + } + } + if (calculate_metaclass && (!metaclass || PyType_Check(metaclass))) { + metaclass = __Pyx_CalculateMetaclass((PyTypeObject*) metaclass, bases); + Py_XDECREF(owned_metaclass); + if (unlikely(!metaclass)) + return NULL; + owned_metaclass = metaclass; + } + result = __Pyx_PyObject_FastCallDict(metaclass, margs+1, 3 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET, +#if PY_VERSION_HEX < 0x030600A4 + (metaclass == (PyObject*)&PyType_Type) ? NULL : mkw +#else + mkw +#endif + ); + Py_XDECREF(owned_metaclass); +#if PY_VERSION_HEX < 0x030600A4 && CYTHON_PEP487_INIT_SUBCLASS + if (likely(result) && likely(PyType_Check(result))) { + if (unlikely(__Pyx_SetNamesPEP487(result) < 0)) { + Py_CLEAR(result); + } else { + result = __Pyx_InitSubclassPEP487(result, mkw); + } + } +#else + (void) &__Pyx_GetBuiltinName; +#endif + return result; +} + +/* CyFunctionClassCell */ +static int __Pyx_CyFunction_InitClassCell(PyObject *cyfunctions, PyObject *classobj) { + Py_ssize_t i, count = PyList_GET_SIZE(cyfunctions); + for (i = 0; i < count; i++) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + PyList_GET_ITEM(cyfunctions, i); +#else + PySequence_ITEM(cyfunctions, i); + if (unlikely(!m)) + return -1; +#endif + __Pyx_CyFunction_SetClassObj(m, classobj); +#if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF((PyObject*)m); +#endif + } + return 0; +} + +/* CLineInTraceback */ +#ifndef CYTHON_CLINE_IN_TRACEBACK +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line) { + PyObject *use_cline; + PyObject *ptype, *pvalue, *ptraceback; +#if CYTHON_COMPILING_IN_CPYTHON + PyObject **cython_runtime_dict; +#endif + CYTHON_MAYBE_UNUSED_VAR(tstate); + if (unlikely(!__pyx_cython_runtime)) { + return c_line; + } + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); +#if CYTHON_COMPILING_IN_CPYTHON + cython_runtime_dict = _PyObject_GetDictPtr(__pyx_cython_runtime); + if (likely(cython_runtime_dict)) { + __PYX_PY_DICT_LOOKUP_IF_MODIFIED( + use_cline, *cython_runtime_dict, + __Pyx_PyDict_GetItemStr(*cython_runtime_dict, __pyx_n_s_cline_in_traceback)) + } else +#endif + { + PyObject *use_cline_obj = __Pyx_PyObject_GetAttrStrNoError(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback); + if (use_cline_obj) { + use_cline = PyObject_Not(use_cline_obj) ? Py_False : Py_True; + Py_DECREF(use_cline_obj); + } else { + PyErr_Clear(); + use_cline = NULL; + } + } + if (!use_cline) { + c_line = 0; + (void) PyObject_SetAttr(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback, Py_False); + } + else if (use_cline == Py_False || (use_cline != Py_True && PyObject_Not(use_cline) != 0)) { + c_line = 0; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + return c_line; +} +#endif + +/* CodeObjectCache */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line) { + int start = 0, mid = 0, end = count - 1; + if (end >= 0 && code_line > entries[end].code_line) { + return count; + } + while (start < end) { + mid = start + (end - start) / 2; + if (code_line < entries[mid].code_line) { + end = mid; + } else if (code_line > entries[mid].code_line) { + start = mid + 1; + } else { + return mid; + } + } + if (code_line <= entries[mid].code_line) { + return mid; + } else { + return mid + 1; + } +} +static PyCodeObject *__pyx_find_code_object(int code_line) { + PyCodeObject* code_object; + int pos; + if (unlikely(!code_line) || unlikely(!__pyx_code_cache.entries)) { + return NULL; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if (unlikely(pos >= __pyx_code_cache.count) || unlikely(__pyx_code_cache.entries[pos].code_line != code_line)) { + return NULL; + } + code_object = __pyx_code_cache.entries[pos].code_object; + Py_INCREF(code_object); + return code_object; +} +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object) { + int pos, i; + __Pyx_CodeObjectCacheEntry* entries = __pyx_code_cache.entries; + if (unlikely(!code_line)) { + return; + } + if (unlikely(!entries)) { + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Malloc(64*sizeof(__Pyx_CodeObjectCacheEntry)); + if (likely(entries)) { + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = 64; + __pyx_code_cache.count = 1; + entries[0].code_line = code_line; + entries[0].code_object = code_object; + Py_INCREF(code_object); + } + return; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if ((pos < __pyx_code_cache.count) && unlikely(__pyx_code_cache.entries[pos].code_line == code_line)) { + PyCodeObject* tmp = entries[pos].code_object; + entries[pos].code_object = code_object; + Py_DECREF(tmp); + return; + } + if (__pyx_code_cache.count == __pyx_code_cache.max_count) { + int new_max = __pyx_code_cache.max_count + 64; + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Realloc( + __pyx_code_cache.entries, ((size_t)new_max) * sizeof(__Pyx_CodeObjectCacheEntry)); + if (unlikely(!entries)) { + return; + } + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = new_max; + } + for (i=__pyx_code_cache.count; i>pos; i--) { + entries[i] = entries[i-1]; + } + entries[pos].code_line = code_line; + entries[pos].code_object = code_object; + __pyx_code_cache.count++; + Py_INCREF(code_object); +} +#endif + +/* AddTraceback */ +#include "compile.h" +#include "frameobject.h" +#include "traceback.h" +#if PY_VERSION_HEX >= 0x030b00a6 && !CYTHON_COMPILING_IN_LIMITED_API + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static PyObject *__Pyx_PyCode_Replace_For_AddTraceback(PyObject *code, PyObject *scratch_dict, + PyObject *firstlineno, PyObject *name) { + PyObject *replace = NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "co_firstlineno", firstlineno))) return NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "co_name", name))) return NULL; + replace = PyObject_GetAttrString(code, "replace"); + if (likely(replace)) { + PyObject *result; + result = PyObject_Call(replace, __pyx_empty_tuple, scratch_dict); + Py_DECREF(replace); + return result; + } + PyErr_Clear(); + #if __PYX_LIMITED_VERSION_HEX < 0x030780000 + { + PyObject *compiled = NULL, *result = NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "code", code))) return NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "type", (PyObject*)(&PyType_Type)))) return NULL; + compiled = Py_CompileString( + "out = type(code)(\n" + " code.co_argcount, code.co_kwonlyargcount, code.co_nlocals, code.co_stacksize,\n" + " code.co_flags, code.co_code, code.co_consts, code.co_names,\n" + " code.co_varnames, code.co_filename, co_name, co_firstlineno,\n" + " code.co_lnotab)\n", "", Py_file_input); + if (!compiled) return NULL; + result = PyEval_EvalCode(compiled, scratch_dict, scratch_dict); + Py_DECREF(compiled); + if (!result) PyErr_Print(); + Py_DECREF(result); + result = PyDict_GetItemString(scratch_dict, "out"); + if (result) Py_INCREF(result); + return result; + } + #else + return NULL; + #endif +} +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + PyObject *code_object = NULL, *py_py_line = NULL, *py_funcname = NULL, *dict = NULL; + PyObject *replace = NULL, *getframe = NULL, *frame = NULL; + PyObject *exc_type, *exc_value, *exc_traceback; + int success = 0; + if (c_line) { + (void) __pyx_cfilenm; + (void) __Pyx_CLineForTraceback(__Pyx_PyThreadState_Current, c_line); + } + PyErr_Fetch(&exc_type, &exc_value, &exc_traceback); + code_object = Py_CompileString("_getframe()", filename, Py_eval_input); + if (unlikely(!code_object)) goto bad; + py_py_line = PyLong_FromLong(py_line); + if (unlikely(!py_py_line)) goto bad; + py_funcname = PyUnicode_FromString(funcname); + if (unlikely(!py_funcname)) goto bad; + dict = PyDict_New(); + if (unlikely(!dict)) goto bad; + { + PyObject *old_code_object = code_object; + code_object = __Pyx_PyCode_Replace_For_AddTraceback(code_object, dict, py_py_line, py_funcname); + Py_DECREF(old_code_object); + } + if (unlikely(!code_object)) goto bad; + getframe = PySys_GetObject("_getframe"); + if (unlikely(!getframe)) goto bad; + if (unlikely(PyDict_SetItemString(dict, "_getframe", getframe))) goto bad; + frame = PyEval_EvalCode(code_object, dict, dict); + if (unlikely(!frame) || frame == Py_None) goto bad; + success = 1; + bad: + PyErr_Restore(exc_type, exc_value, exc_traceback); + Py_XDECREF(code_object); + Py_XDECREF(py_py_line); + Py_XDECREF(py_funcname); + Py_XDECREF(dict); + Py_XDECREF(replace); + if (success) { + PyTraceBack_Here( + (struct _frame*)frame); + } + Py_XDECREF(frame); +} +#else +static PyCodeObject* __Pyx_CreateCodeObjectForTraceback( + const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = NULL; + PyObject *py_funcname = NULL; + #if PY_MAJOR_VERSION < 3 + PyObject *py_srcfile = NULL; + py_srcfile = PyString_FromString(filename); + if (!py_srcfile) goto bad; + #endif + if (c_line) { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + #else + py_funcname = PyUnicode_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + funcname = PyUnicode_AsUTF8(py_funcname); + if (!funcname) goto bad; + #endif + } + else { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromString(funcname); + if (!py_funcname) goto bad; + #endif + } + #if PY_MAJOR_VERSION < 3 + py_code = __Pyx_PyCode_New( + 0, + 0, + 0, + 0, + 0, + 0, + __pyx_empty_bytes, /*PyObject *code,*/ + __pyx_empty_tuple, /*PyObject *consts,*/ + __pyx_empty_tuple, /*PyObject *names,*/ + __pyx_empty_tuple, /*PyObject *varnames,*/ + __pyx_empty_tuple, /*PyObject *freevars,*/ + __pyx_empty_tuple, /*PyObject *cellvars,*/ + py_srcfile, /*PyObject *filename,*/ + py_funcname, /*PyObject *name,*/ + py_line, + __pyx_empty_bytes /*PyObject *lnotab*/ + ); + Py_DECREF(py_srcfile); + #else + py_code = PyCode_NewEmpty(filename, funcname, py_line); + #endif + Py_XDECREF(py_funcname); + return py_code; +bad: + Py_XDECREF(py_funcname); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_srcfile); + #endif + return NULL; +} +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = 0; + PyFrameObject *py_frame = 0; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject *ptype, *pvalue, *ptraceback; + if (c_line) { + c_line = __Pyx_CLineForTraceback(tstate, c_line); + } + py_code = __pyx_find_code_object(c_line ? -c_line : py_line); + if (!py_code) { + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); + py_code = __Pyx_CreateCodeObjectForTraceback( + funcname, c_line, py_line, filename); + if (!py_code) { + /* If the code object creation fails, then we should clear the + fetched exception references and propagate the new exception */ + Py_XDECREF(ptype); + Py_XDECREF(pvalue); + Py_XDECREF(ptraceback); + goto bad; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + __pyx_insert_code_object(c_line ? -c_line : py_line, py_code); + } + py_frame = PyFrame_New( + tstate, /*PyThreadState *tstate,*/ + py_code, /*PyCodeObject *code,*/ + __pyx_d, /*PyObject *globals,*/ + 0 /*PyObject *locals*/ + ); + if (!py_frame) goto bad; + __Pyx_PyFrame_SetLineNumber(py_frame, py_line); + PyTraceBack_Here(py_frame); +bad: + Py_XDECREF(py_code); + Py_XDECREF(py_frame); +} +#endif + +/* CIntFromPyVerify */ +#define __PYX_VERIFY_RETURN_INT(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 0) +#define __PYX_VERIFY_RETURN_INT_EXC(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 1) +#define __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, exc)\ + {\ + func_type value = func_value;\ + if (sizeof(target_type) < sizeof(func_type)) {\ + if (unlikely(value != (func_type) (target_type) value)) {\ + func_type zero = 0;\ + if (exc && unlikely(value == (func_type)-1 && PyErr_Occurred()))\ + return (target_type) -1;\ + if (is_unsigned && unlikely(value < zero))\ + goto raise_neg_overflow;\ + else\ + goto raise_overflow;\ + }\ + }\ + return (target_type) value;\ + } + +/* CIntFromPy */ +static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(int) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(int, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (int) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 2 * PyLong_SHIFT)) { + return (int) (((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 3 * PyLong_SHIFT)) { + return (int) (((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 4 * PyLong_SHIFT)) { + return (int) (((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(int) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(int) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) ((((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) ((((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) ((((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(int) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + int val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (int) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (int) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (int) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (int) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(int) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(int) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((int) 1) << (sizeof(int) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (int) -1; + } + } else { + int val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (int) -1; + val = __Pyx_PyInt_As_int(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to int"); + return (int) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to int"); + return (int) -1; +} + +/* CIntToPy */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_int(int value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(int) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(int) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(int) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(int) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(int) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; +#if !CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030d0000 + return _PyLong_FromByteArray(bytes, sizeof(int), + little, !is_unsigned); +#else + PyObject *from_bytes, *result = NULL; + PyObject *py_bytes = NULL, *arg_tuple = NULL, *kwds = NULL, *order_str = NULL; + from_bytes = PyObject_GetAttrString((PyObject*)&PyLong_Type, "from_bytes"); + if (!from_bytes) return NULL; + py_bytes = PyBytes_FromStringAndSize((char*)bytes, sizeof(int)); + if (!py_bytes) goto limited_bad; + order_str = PyUnicode_FromString(little ? "little" : "big"); + if (!order_str) goto limited_bad; + arg_tuple = PyTuple_Pack(2, py_bytes, order_str); + if (!arg_tuple) goto limited_bad; + if (!is_unsigned) { + kwds = PyDict_New(); + if (!kwds) goto limited_bad; + if (PyDict_SetItemString(kwds, "signed", __Pyx_NewRef(Py_True))) goto limited_bad; + } + result = PyObject_Call(from_bytes, arg_tuple, kwds); + limited_bad: + Py_XDECREF(kwds); + Py_XDECREF(arg_tuple); + Py_XDECREF(order_str); + Py_XDECREF(py_bytes); + Py_XDECREF(from_bytes); + return result; +#endif + } +} + +/* CIntFromPy */ +static CYTHON_INLINE size_t __Pyx_PyInt_As_size_t(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const size_t neg_one = (size_t) -1, const_zero = (size_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(size_t) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(size_t, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (size_t) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(size_t, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(size_t) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) >= 2 * PyLong_SHIFT)) { + return (size_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(size_t) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) >= 3 * PyLong_SHIFT)) { + return (size_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(size_t) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) >= 4 * PyLong_SHIFT)) { + return (size_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (size_t) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(size_t) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(size_t) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(size_t, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(size_t) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 2 * PyLong_SHIFT)) { + return (size_t) (((size_t)-1)*(((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(size_t) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 2 * PyLong_SHIFT)) { + return (size_t) ((((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(size_t) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 3 * PyLong_SHIFT)) { + return (size_t) (((size_t)-1)*(((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(size_t) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 3 * PyLong_SHIFT)) { + return (size_t) ((((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(size_t) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 4 * PyLong_SHIFT)) { + return (size_t) (((size_t)-1)*(((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(size_t) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 4 * PyLong_SHIFT)) { + return (size_t) ((((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(size_t) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(size_t) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + size_t val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (size_t) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (size_t) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (size_t) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (size_t) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (size_t) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(size_t) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((size_t) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(size_t) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((size_t) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((size_t) 1) << (sizeof(size_t) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (size_t) -1; + } + } else { + size_t val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (size_t) -1; + val = __Pyx_PyInt_As_size_t(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to size_t"); + return (size_t) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to size_t"); + return (size_t) -1; +} + +/* FormatTypeName */ +#if CYTHON_COMPILING_IN_LIMITED_API +static __Pyx_TypeName +__Pyx_PyType_GetName(PyTypeObject* tp) +{ + PyObject *name = __Pyx_PyObject_GetAttrStr((PyObject *)tp, + __pyx_n_s_name); + if (unlikely(name == NULL) || unlikely(!PyUnicode_Check(name))) { + PyErr_Clear(); + Py_XDECREF(name); + name = __Pyx_NewRef(__pyx_n_s__53); + } + return name; +} +#endif + +/* CIntToPy */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(long) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(long) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(long) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; +#if !CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030d0000 + return _PyLong_FromByteArray(bytes, sizeof(long), + little, !is_unsigned); +#else + PyObject *from_bytes, *result = NULL; + PyObject *py_bytes = NULL, *arg_tuple = NULL, *kwds = NULL, *order_str = NULL; + from_bytes = PyObject_GetAttrString((PyObject*)&PyLong_Type, "from_bytes"); + if (!from_bytes) return NULL; + py_bytes = PyBytes_FromStringAndSize((char*)bytes, sizeof(long)); + if (!py_bytes) goto limited_bad; + order_str = PyUnicode_FromString(little ? "little" : "big"); + if (!order_str) goto limited_bad; + arg_tuple = PyTuple_Pack(2, py_bytes, order_str); + if (!arg_tuple) goto limited_bad; + if (!is_unsigned) { + kwds = PyDict_New(); + if (!kwds) goto limited_bad; + if (PyDict_SetItemString(kwds, "signed", __Pyx_NewRef(Py_True))) goto limited_bad; + } + result = PyObject_Call(from_bytes, arg_tuple, kwds); + limited_bad: + Py_XDECREF(kwds); + Py_XDECREF(arg_tuple); + Py_XDECREF(order_str); + Py_XDECREF(py_bytes); + Py_XDECREF(from_bytes); + return result; +#endif + } +} + +/* CIntFromPy */ +static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(long) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(long, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (long) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 2 * PyLong_SHIFT)) { + return (long) (((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 3 * PyLong_SHIFT)) { + return (long) (((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 4 * PyLong_SHIFT)) { + return (long) (((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(long) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(long) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) ((((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) ((((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) ((((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(long) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + long val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (long) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (long) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (long) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (long) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(long) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(long) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((long) 1) << (sizeof(long) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (long) -1; + } + } else { + long val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (long) -1; + val = __Pyx_PyInt_As_long(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to long"); + return (long) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to long"); + return (long) -1; +} + +/* FastTypeChecks */ +#if CYTHON_COMPILING_IN_CPYTHON +static int __Pyx_InBases(PyTypeObject *a, PyTypeObject *b) { + while (a) { + a = __Pyx_PyType_GetSlot(a, tp_base, PyTypeObject*); + if (a == b) + return 1; + } + return b == &PyBaseObject_Type; +} +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (a == b) return 1; + mro = a->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + if (PyTuple_GET_ITEM(mro, i) == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(a, b); +} +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (cls == a || cls == b) return 1; + mro = cls->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + PyObject *base = PyTuple_GET_ITEM(mro, i); + if (base == (PyObject *)a || base == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(cls, a) || __Pyx_InBases(cls, b); +} +#if PY_MAJOR_VERSION == 2 +static int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject* exc_type2) { + PyObject *exception, *value, *tb; + int res; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&exception, &value, &tb); + res = exc_type1 ? PyObject_IsSubclass(err, exc_type1) : 0; + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + if (!res) { + res = PyObject_IsSubclass(err, exc_type2); + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + } + __Pyx_ErrRestore(exception, value, tb); + return res; +} +#else +static CYTHON_INLINE int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject *exc_type2) { + if (exc_type1) { + return __Pyx_IsAnySubtype2((PyTypeObject*)err, (PyTypeObject*)exc_type1, (PyTypeObject*)exc_type2); + } else { + return __Pyx_IsSubtype((PyTypeObject*)err, (PyTypeObject*)exc_type2); + } +} +#endif +static int __Pyx_PyErr_GivenExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + assert(PyExceptionClass_Check(exc_type)); + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; i= 0x030B00A4 + return Py_Version & ~0xFFUL; +#else + const char* rt_version = Py_GetVersion(); + unsigned long version = 0; + unsigned long factor = 0x01000000UL; + unsigned int digit = 0; + int i = 0; + while (factor) { + while ('0' <= rt_version[i] && rt_version[i] <= '9') { + digit = digit * 10 + (unsigned int) (rt_version[i] - '0'); + ++i; + } + version += factor * digit; + if (rt_version[i] != '.') + break; + digit = 0; + factor >>= 8; + ++i; + } + return version; +#endif +} +static int __Pyx_check_binary_version(unsigned long ct_version, unsigned long rt_version, int allow_newer) { + const unsigned long MAJOR_MINOR = 0xFFFF0000UL; + if ((rt_version & MAJOR_MINOR) == (ct_version & MAJOR_MINOR)) + return 0; + if (likely(allow_newer && (rt_version & MAJOR_MINOR) > (ct_version & MAJOR_MINOR))) + return 1; + { + char message[200]; + PyOS_snprintf(message, sizeof(message), + "compile time Python version %d.%d " + "of module '%.100s' " + "%s " + "runtime version %d.%d", + (int) (ct_version >> 24), (int) ((ct_version >> 16) & 0xFF), + __Pyx_MODULE_NAME, + (allow_newer) ? "was newer than" : "does not match", + (int) (rt_version >> 24), (int) ((rt_version >> 16) & 0xFF) + ); + return PyErr_WarnEx(NULL, message, 1); + } +} + +/* InitStrings */ +#if PY_MAJOR_VERSION >= 3 +static int __Pyx_InitString(__Pyx_StringTabEntry t, PyObject **str) { + if (t.is_unicode | t.is_str) { + if (t.intern) { + *str = PyUnicode_InternFromString(t.s); + } else if (t.encoding) { + *str = PyUnicode_Decode(t.s, t.n - 1, t.encoding, NULL); + } else { + *str = PyUnicode_FromStringAndSize(t.s, t.n - 1); + } + } else { + *str = PyBytes_FromStringAndSize(t.s, t.n - 1); + } + if (!*str) + return -1; + if (PyObject_Hash(*str) == -1) + return -1; + return 0; +} +#endif +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t) { + while (t->p) { + #if PY_MAJOR_VERSION >= 3 + __Pyx_InitString(*t, t->p); + #else + if (t->is_unicode) { + *t->p = PyUnicode_DecodeUTF8(t->s, t->n - 1, NULL); + } else if (t->intern) { + *t->p = PyString_InternFromString(t->s); + } else { + *t->p = PyString_FromStringAndSize(t->s, t->n - 1); + } + if (!*t->p) + return -1; + if (PyObject_Hash(*t->p) == -1) + return -1; + #endif + ++t; + } + return 0; +} + +#include +static CYTHON_INLINE Py_ssize_t __Pyx_ssize_strlen(const char *s) { + size_t len = strlen(s); + if (unlikely(len > (size_t) PY_SSIZE_T_MAX)) { + PyErr_SetString(PyExc_OverflowError, "byte string is too long"); + return -1; + } + return (Py_ssize_t) len; +} +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char* c_str) { + Py_ssize_t len = __Pyx_ssize_strlen(c_str); + if (unlikely(len < 0)) return NULL; + return __Pyx_PyUnicode_FromStringAndSize(c_str, len); +} +static CYTHON_INLINE PyObject* __Pyx_PyByteArray_FromString(const char* c_str) { + Py_ssize_t len = __Pyx_ssize_strlen(c_str); + if (unlikely(len < 0)) return NULL; + return PyByteArray_FromStringAndSize(c_str, len); +} +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject* o) { + Py_ssize_t ignore; + return __Pyx_PyObject_AsStringAndSize(o, &ignore); +} +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +#if !CYTHON_PEP393_ENABLED +static const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + char* defenc_c; + PyObject* defenc = _PyUnicode_AsDefaultEncodedString(o, NULL); + if (!defenc) return NULL; + defenc_c = PyBytes_AS_STRING(defenc); +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + { + char* end = defenc_c + PyBytes_GET_SIZE(defenc); + char* c; + for (c = defenc_c; c < end; c++) { + if ((unsigned char) (*c) >= 128) { + PyUnicode_AsASCIIString(o); + return NULL; + } + } + } +#endif + *length = PyBytes_GET_SIZE(defenc); + return defenc_c; +} +#else +static CYTHON_INLINE const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + if (unlikely(__Pyx_PyUnicode_READY(o) == -1)) return NULL; +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + if (likely(PyUnicode_IS_ASCII(o))) { + *length = PyUnicode_GET_LENGTH(o); + return PyUnicode_AsUTF8(o); + } else { + PyUnicode_AsASCIIString(o); + return NULL; + } +#else + return PyUnicode_AsUTF8AndSize(o, length); +#endif +} +#endif +#endif +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject* o, Py_ssize_t *length) { +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT + if ( +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + __Pyx_sys_getdefaultencoding_not_ascii && +#endif + PyUnicode_Check(o)) { + return __Pyx_PyUnicode_AsStringAndSize(o, length); + } else +#endif +#if (!CYTHON_COMPILING_IN_PYPY && !CYTHON_COMPILING_IN_LIMITED_API) || (defined(PyByteArray_AS_STRING) && defined(PyByteArray_GET_SIZE)) + if (PyByteArray_Check(o)) { + *length = PyByteArray_GET_SIZE(o); + return PyByteArray_AS_STRING(o); + } else +#endif + { + char* result; + int r = PyBytes_AsStringAndSize(o, &result, length); + if (unlikely(r < 0)) { + return NULL; + } else { + return result; + } + } +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject* x) { + int is_true = x == Py_True; + if (is_true | (x == Py_False) | (x == Py_None)) return is_true; + else return PyObject_IsTrue(x); +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject* x) { + int retval; + if (unlikely(!x)) return -1; + retval = __Pyx_PyObject_IsTrue(x); + Py_DECREF(x); + return retval; +} +static PyObject* __Pyx_PyNumber_IntOrLongWrongResultType(PyObject* result, const char* type_name) { + __Pyx_TypeName result_type_name = __Pyx_PyType_GetName(Py_TYPE(result)); +#if PY_MAJOR_VERSION >= 3 + if (PyLong_Check(result)) { + if (PyErr_WarnFormat(PyExc_DeprecationWarning, 1, + "__int__ returned non-int (type " __Pyx_FMT_TYPENAME "). " + "The ability to return an instance of a strict subclass of int is deprecated, " + "and may be removed in a future version of Python.", + result_type_name)) { + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; + } + __Pyx_DECREF_TypeName(result_type_name); + return result; + } +#endif + PyErr_Format(PyExc_TypeError, + "__%.4s__ returned non-%.4s (type " __Pyx_FMT_TYPENAME ")", + type_name, type_name, result_type_name); + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x) { +#if CYTHON_USE_TYPE_SLOTS + PyNumberMethods *m; +#endif + const char *name = NULL; + PyObject *res = NULL; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x) || PyLong_Check(x))) +#else + if (likely(PyLong_Check(x))) +#endif + return __Pyx_NewRef(x); +#if CYTHON_USE_TYPE_SLOTS + m = Py_TYPE(x)->tp_as_number; + #if PY_MAJOR_VERSION < 3 + if (m && m->nb_int) { + name = "int"; + res = m->nb_int(x); + } + else if (m && m->nb_long) { + name = "long"; + res = m->nb_long(x); + } + #else + if (likely(m && m->nb_int)) { + name = "int"; + res = m->nb_int(x); + } + #endif +#else + if (!PyBytes_CheckExact(x) && !PyUnicode_CheckExact(x)) { + res = PyNumber_Int(x); + } +#endif + if (likely(res)) { +#if PY_MAJOR_VERSION < 3 + if (unlikely(!PyInt_Check(res) && !PyLong_Check(res))) { +#else + if (unlikely(!PyLong_CheckExact(res))) { +#endif + return __Pyx_PyNumber_IntOrLongWrongResultType(res, name); + } + } + else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_TypeError, + "an integer is required"); + } + return res; +} +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject* b) { + Py_ssize_t ival; + PyObject *x; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_CheckExact(b))) { + if (sizeof(Py_ssize_t) >= sizeof(long)) + return PyInt_AS_LONG(b); + else + return PyInt_AsSsize_t(b); + } +#endif + if (likely(PyLong_CheckExact(b))) { + #if CYTHON_USE_PYLONG_INTERNALS + if (likely(__Pyx_PyLong_IsCompact(b))) { + return __Pyx_PyLong_CompactValue(b); + } else { + const digit* digits = __Pyx_PyLong_Digits(b); + const Py_ssize_t size = __Pyx_PyLong_SignedDigitCount(b); + switch (size) { + case 2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return (Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + } + } + #endif + return PyLong_AsSsize_t(b); + } + x = PyNumber_Index(b); + if (!x) return -1; + ival = PyInt_AsSsize_t(x); + Py_DECREF(x); + return ival; +} +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject* o) { + if (sizeof(Py_hash_t) == sizeof(Py_ssize_t)) { + return (Py_hash_t) __Pyx_PyIndex_AsSsize_t(o); +#if PY_MAJOR_VERSION < 3 + } else if (likely(PyInt_CheckExact(o))) { + return PyInt_AS_LONG(o); +#endif + } else { + Py_ssize_t ival; + PyObject *x; + x = PyNumber_Index(o); + if (!x) return -1; + ival = PyInt_AsLong(x); + Py_DECREF(x); + return ival; + } +} +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b) { + return b ? __Pyx_NewRef(Py_True) : __Pyx_NewRef(Py_False); +} +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t ival) { + return PyInt_FromSize_t(ival); +} + + +/* #### Code section: utility_code_pragmas_end ### */ +#ifdef _MSC_VER +#pragma warning( pop ) +#endif + + + +/* #### Code section: end ### */ +#endif /* Py_PYTHON_H */ diff --git a/cereal/messaging/messaging_pyx.so b/cereal/messaging/messaging_pyx.so new file mode 100755 index 0000000..7096d0e Binary files /dev/null and b/cereal/messaging/messaging_pyx.so differ diff --git a/cereal/messaging/msgq.cc b/cereal/messaging/msgq.cc deleted file mode 100644 index af93bbf..0000000 --- a/cereal/messaging/msgq.cc +++ /dev/null @@ -1,468 +0,0 @@ -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include - -#include - -#include "cereal/messaging/msgq.h" - -void sigusr2_handler(int signal) { - assert(signal == SIGUSR2); -} - -uint64_t msgq_get_uid(void){ - std::random_device rd("/dev/urandom"); - std::uniform_int_distribution distribution(0, std::numeric_limits::max()); - - #ifdef __APPLE__ - // TODO: this doesn't work - uint64_t uid = distribution(rd) << 32 | getpid(); - #else - uint64_t uid = distribution(rd) << 32 | syscall(SYS_gettid); - #endif - - return uid; -} - -int msgq_msg_init_size(msgq_msg_t * msg, size_t size){ - msg->size = size; - msg->data = new(std::nothrow) char[size]; - - return (msg->data == NULL) ? -1 : 0; -} - - -int msgq_msg_init_data(msgq_msg_t * msg, char * data, size_t size) { - int r = msgq_msg_init_size(msg, size); - - if (r == 0) - memcpy(msg->data, data, size); - - return r; -} - -int msgq_msg_close(msgq_msg_t * msg){ - if (msg->size > 0) - delete[] msg->data; - - msg->size = 0; - - return 0; -} - -void msgq_reset_reader(msgq_queue_t * q){ - int id = q->reader_id; - q->read_valids[id]->store(true); - q->read_pointers[id]->store(*q->write_pointer); -} - -void msgq_wait_for_subscriber(msgq_queue_t *q){ - while (*q->num_readers == 0){ - // wait for subscriber - } - - return; -} - -int msgq_new_queue(msgq_queue_t * q, const char * path, size_t size){ - assert(size < 0xFFFFFFFF); // Buffer must be smaller than 2^32 bytes - std::signal(SIGUSR2, sigusr2_handler); - - std::string full_path = "/dev/shm/"; - const char* prefix = std::getenv("OPENPILOT_PREFIX"); - if (prefix) { - full_path += std::string(prefix) + "/"; - } - full_path += path; - - auto fd = open(full_path.c_str(), O_RDWR | O_CREAT, 0664); - if (fd < 0) { - std::cout << "Warning, could not open: " << full_path << std::endl; - return -1; - } - - int rc = ftruncate(fd, size + sizeof(msgq_header_t)); - if (rc < 0){ - close(fd); - return -1; - } - char * mem = (char*)mmap(NULL, size + sizeof(msgq_header_t), PROT_READ | PROT_WRITE, MAP_SHARED, fd, 0); - close(fd); - - if (mem == NULL){ - return -1; - } - q->mmap_p = mem; - - msgq_header_t *header = (msgq_header_t *)mem; - - // Setup pointers to header segment - q->num_readers = reinterpret_cast*>(&header->num_readers); - q->write_pointer = reinterpret_cast*>(&header->write_pointer); - q->write_uid = reinterpret_cast*>(&header->write_uid); - - for (size_t i = 0; i < NUM_READERS; i++){ - q->read_pointers[i] = reinterpret_cast*>(&header->read_pointers[i]); - q->read_valids[i] = reinterpret_cast*>(&header->read_valids[i]); - q->read_uids[i] = reinterpret_cast*>(&header->read_uids[i]); - } - - q->data = mem + sizeof(msgq_header_t); - q->size = size; - q->reader_id = -1; - - q->endpoint = path; - q->read_conflate = false; - - return 0; -} - -void msgq_close_queue(msgq_queue_t *q){ - if (q->mmap_p != NULL){ - munmap(q->mmap_p, q->size + sizeof(msgq_header_t)); - } -} - - -void msgq_init_publisher(msgq_queue_t * q) { - //std::cout << "Starting publisher" << std::endl; - uint64_t uid = msgq_get_uid(); - - *q->write_uid = uid; - *q->num_readers = 0; - - for (size_t i = 0; i < NUM_READERS; i++){ - *q->read_valids[i] = false; - *q->read_uids[i] = 0; - } - - q->write_uid_local = uid; -} - -static void thread_signal(uint32_t tid) { - #ifndef SYS_tkill - // TODO: this won't work for multithreaded programs - kill(tid, SIGUSR2); - #else - syscall(SYS_tkill, tid, SIGUSR2); - #endif -} - -void msgq_init_subscriber(msgq_queue_t * q) { - assert(q != NULL); - assert(q->num_readers != NULL); - - uint64_t uid = msgq_get_uid(); - - // Get reader id - while (true){ - uint64_t cur_num_readers = *q->num_readers; - uint64_t new_num_readers = cur_num_readers + 1; - - // No more slots available. Reset all subscribers to kick out inactive ones - if (new_num_readers > NUM_READERS){ - //std::cout << "Warning, evicting all subscribers!" << std::endl; - *q->num_readers = 0; - - for (size_t i = 0; i < NUM_READERS; i++){ - *q->read_valids[i] = false; - - uint64_t old_uid = *q->read_uids[i]; - *q->read_uids[i] = 0; - - // Wake up reader in case they are in a poll - thread_signal(old_uid & 0xFFFFFFFF); - } - - continue; - } - - // Use atomic compare and swap to handle race condition - // where two subscribers start at the same time - if (std::atomic_compare_exchange_strong(q->num_readers, - &cur_num_readers, - new_num_readers)){ - q->reader_id = cur_num_readers; - q->read_uid_local = uid; - - // We start with read_valid = false, - // on the first read the read pointer will be synchronized with the write pointer - *q->read_valids[cur_num_readers] = false; - *q->read_pointers[cur_num_readers] = 0; - *q->read_uids[cur_num_readers] = uid; - break; - } - } - - //std::cout << "New subscriber id: " << q->reader_id << " uid: " << q->read_uid_local << " " << q->endpoint << std::endl; - msgq_reset_reader(q); -} - -int msgq_msg_send(msgq_msg_t * msg, msgq_queue_t *q){ - // Die if we are no longer the active publisher - if (q->write_uid_local != *q->write_uid){ - std::cout << "Killing old publisher: " << q->endpoint << std::endl; - errno = EADDRINUSE; - return -1; - } - - uint64_t total_msg_size = ALIGN(msg->size + sizeof(int64_t)); - - // We need to fit at least three messages in the queue, - // then we can always safely access the last message - assert(3 * total_msg_size <= q->size); - - uint64_t num_readers = *q->num_readers; - - uint32_t write_cycles, write_pointer; - UNPACK64(write_cycles, write_pointer, *q->write_pointer); - - char *p = q->data + write_pointer; // add base offset - - // Check remaining space - // Always leave space for a wraparound tag for the next message, including alignment - int64_t remaining_space = q->size - write_pointer - total_msg_size - sizeof(int64_t); - if (remaining_space <= 0){ - // Write -1 size tag indicating wraparound - *(int64_t*)p = -1; - - // Invalidate all readers that are beyond the write pointer - // TODO: should we handle the case where a new reader shows up while this is running? - for (uint64_t i = 0; i < num_readers; i++){ - uint64_t read_pointer = *q->read_pointers[i]; - uint64_t read_cycles = read_pointer >> 32; - read_pointer &= 0xFFFFFFFF; - - if ((read_pointer > write_pointer) && (read_cycles != write_cycles)) { - *q->read_valids[i] = false; - } - } - - // Update global and local copies of write pointer and write_cycles - write_pointer = 0; - write_cycles = write_cycles + 1; - PACK64(*q->write_pointer, write_cycles, write_pointer); - - // Set actual pointer to the beginning of the data segment - p = q->data; - } - - // Invalidate readers that are in the area that will be written - uint64_t start = write_pointer; - uint64_t end = ALIGN(start + sizeof(int64_t) + msg->size); - - for (uint64_t i = 0; i < num_readers; i++){ - uint32_t read_cycles, read_pointer; - UNPACK64(read_cycles, read_pointer, *q->read_pointers[i]); - - if ((read_pointer >= start) && (read_pointer < end) && (read_cycles != write_cycles)) { - *q->read_valids[i] = false; - } - } - - - // Write size tag - std::atomic *size_p = reinterpret_cast*>(p); - *size_p = msg->size; - - // Copy data - memcpy(p + sizeof(int64_t), msg->data, msg->size); - __sync_synchronize(); - - // Update write pointer - uint32_t new_ptr = ALIGN(write_pointer + msg->size + sizeof(int64_t)); - PACK64(*q->write_pointer, write_cycles, new_ptr); - - // Notify readers - for (uint64_t i = 0; i < num_readers; i++){ - uint64_t reader_uid = *q->read_uids[i]; - thread_signal(reader_uid & 0xFFFFFFFF); - } - - return msg->size; -} - - -int msgq_msg_ready(msgq_queue_t * q){ - start: - int id = q->reader_id; - assert(id >= 0); // Make sure subscriber is initialized - - if (q->read_uid_local != *q->read_uids[id]){ - //std::cout << q->endpoint << ": Reader was evicted, reconnecting" << std::endl; - msgq_init_subscriber(q); - goto start; - } - - // Check valid - if (!*q->read_valids[id]){ - msgq_reset_reader(q); - goto start; - } - - uint32_t read_cycles, read_pointer; - UNPACK64(read_cycles, read_pointer, *q->read_pointers[id]); - UNUSED(read_cycles); - - uint32_t write_cycles, write_pointer; - UNPACK64(write_cycles, write_pointer, *q->write_pointer); - UNUSED(write_cycles); - - // Check if new message is available - return (read_pointer != write_pointer); -} - -int msgq_msg_recv(msgq_msg_t * msg, msgq_queue_t * q){ - start: - int id = q->reader_id; - assert(id >= 0); // Make sure subscriber is initialized - - if (q->read_uid_local != *q->read_uids[id]){ - //std::cout << q->endpoint << ": Reader was evicted, reconnecting" << std::endl; - msgq_init_subscriber(q); - goto start; - } - - // Check valid - if (!*q->read_valids[id]){ - msgq_reset_reader(q); - goto start; - } - - uint32_t read_cycles, read_pointer; - UNPACK64(read_cycles, read_pointer, *q->read_pointers[id]); - - uint32_t write_cycles, write_pointer; - UNPACK64(write_cycles, write_pointer, *q->write_pointer); - UNUSED(write_cycles); - - char * p = q->data + read_pointer; - - // Check if new message is available - if (read_pointer == write_pointer) { - msg->size = 0; - return 0; - } - - // Read potential message size - std::atomic *size_p = reinterpret_cast*>(p); - std::int64_t size = *size_p; - - // Check if the size that was read is valid - if (!*q->read_valids[id]){ - msgq_reset_reader(q); - goto start; - } - - // If size is -1 the buffer was full, and we need to wrap around - if (size == -1){ - read_cycles++; - PACK64(*q->read_pointers[id], read_cycles, 0); - goto start; - } - - // crashing is better than passing garbage data to the consumer - // the size will have weird value if it was overwritten by data accidentally - assert((uint64_t)size < q->size); - assert(size > 0); - - uint32_t new_read_pointer = ALIGN(read_pointer + sizeof(std::int64_t) + size); - - // If conflate is true, check if this is the latest message, else start over - if (q->read_conflate){ - if (new_read_pointer != write_pointer){ - // Update read pointer - PACK64(*q->read_pointers[id], read_cycles, new_read_pointer); - goto start; - } - } - - // Copy message - if (msgq_msg_init_size(msg, size) < 0) - return -1; - - __sync_synchronize(); - memcpy(msg->data, p + sizeof(int64_t), size); - __sync_synchronize(); - - // Update read pointer - PACK64(*q->read_pointers[id], read_cycles, new_read_pointer); - - // Check if the actual data that was copied is valid - if (!*q->read_valids[id]){ - msgq_msg_close(msg); - msgq_reset_reader(q); - goto start; - } - - - return msg->size; -} - - - -int msgq_poll(msgq_pollitem_t * items, size_t nitems, int timeout){ - int num = 0; - - // Check if messages ready - for (size_t i = 0; i < nitems; i++) { - items[i].revents = msgq_msg_ready(items[i].q); - if (items[i].revents) num++; - } - - int ms = (timeout == -1) ? 100 : timeout; - struct timespec ts; - ts.tv_sec = ms / 1000; - ts.tv_nsec = (ms % 1000) * 1000 * 1000; - - - while (num == 0) { - int ret; - - ret = nanosleep(&ts, &ts); - - // Check if messages ready - for (size_t i = 0; i < nitems; i++) { - if (items[i].revents == 0 && msgq_msg_ready(items[i].q)){ - num += 1; - items[i].revents = 1; - } - } - - // exit if we had a timeout and the sleep finished - if (timeout != -1 && ret == 0){ - break; - } - } - - return num; -} - -bool msgq_all_readers_updated(msgq_queue_t *q) { - uint64_t num_readers = *q->num_readers; - for (uint64_t i = 0; i < num_readers; i++) { - if (*q->read_valids[i] && *q->write_pointer != *q->read_pointers[i]) { - return false; - } - } - return num_readers > 0; -} diff --git a/cereal/messaging/msgq.h b/cereal/messaging/msgq.h deleted file mode 100644 index 0a72a38..0000000 --- a/cereal/messaging/msgq.h +++ /dev/null @@ -1,70 +0,0 @@ -#pragma once - -#include -#include -#include -#include - -#define DEFAULT_SEGMENT_SIZE (10 * 1024 * 1024) -#define NUM_READERS 12 -#define ALIGN(n) ((n + (8 - 1)) & -8) - -#define UNUSED(x) (void)x -#define UNPACK64(higher, lower, input) do {uint64_t tmp = input; higher = tmp >> 32; lower = tmp & 0xFFFFFFFF;} while (0) -#define PACK64(output, higher, lower) output = ((uint64_t)higher << 32) | ((uint64_t)lower & 0xFFFFFFFF) - -struct msgq_header_t { - uint64_t num_readers; - uint64_t write_pointer; - uint64_t write_uid; - uint64_t read_pointers[NUM_READERS]; - uint64_t read_valids[NUM_READERS]; - uint64_t read_uids[NUM_READERS]; -}; - -struct msgq_queue_t { - std::atomic *num_readers; - std::atomic *write_pointer; - std::atomic *write_uid; - std::atomic *read_pointers[NUM_READERS]; - std::atomic *read_valids[NUM_READERS]; - std::atomic *read_uids[NUM_READERS]; - char * mmap_p; - char * data; - size_t size; - int reader_id; - uint64_t read_uid_local; - uint64_t write_uid_local; - - bool read_conflate; - std::string endpoint; -}; - -struct msgq_msg_t { - size_t size; - char * data; -}; - -struct msgq_pollitem_t { - msgq_queue_t *q; - int revents; -}; - -void msgq_wait_for_subscriber(msgq_queue_t *q); -void msgq_reset_reader(msgq_queue_t *q); - -int msgq_msg_init_size(msgq_msg_t *msg, size_t size); -int msgq_msg_init_data(msgq_msg_t *msg, char * data, size_t size); -int msgq_msg_close(msgq_msg_t *msg); - -int msgq_new_queue(msgq_queue_t * q, const char * path, size_t size); -void msgq_close_queue(msgq_queue_t *q); -void msgq_init_publisher(msgq_queue_t * q); -void msgq_init_subscriber(msgq_queue_t * q); - -int msgq_msg_send(msgq_msg_t *msg, msgq_queue_t *q); -int msgq_msg_recv(msgq_msg_t *msg, msgq_queue_t *q); -int msgq_msg_ready(msgq_queue_t * q); -int msgq_poll(msgq_pollitem_t * items, size_t nitems, int timeout); - -bool msgq_all_readers_updated(msgq_queue_t *q); diff --git a/cereal/messaging/socketmaster.cc b/cereal/messaging/socketmaster.cc deleted file mode 100644 index 3054b4f..0000000 --- a/cereal/messaging/socketmaster.cc +++ /dev/null @@ -1,210 +0,0 @@ -#include -#include -#include -#include -#include - -#include "cereal/services.h" -#include "cereal/messaging/messaging.h" - -const bool SIMULATION = (getenv("SIMULATION") != nullptr) && (std::string(getenv("SIMULATION")) == "1"); - -static inline uint64_t nanos_since_boot() { - struct timespec t; - clock_gettime(CLOCK_BOOTTIME, &t); - return t.tv_sec * 1000000000ULL + t.tv_nsec; -} - -static inline bool inList(const std::vector &list, const char *value) { - for (auto &v : list) { - if (strcmp(value, v) == 0) return true; - } - return false; -} - -class MessageContext { -public: - MessageContext() : ctx_(nullptr) {} - ~MessageContext() { delete ctx_; } - inline Context *context() { - std::call_once(init_flag, [=]() { ctx_ = Context::create(); }); - return ctx_; - } -private: - Context *ctx_; - std::once_flag init_flag; -}; - -MessageContext message_context; - -struct SubMaster::SubMessage { - std::string name; - SubSocket *socket = nullptr; - int freq = 0; - bool updated = false, alive = false, valid = true, ignore_alive; - uint64_t rcv_time = 0, rcv_frame = 0; - void *allocated_msg_reader = nullptr; - bool is_polled = false; - capnp::FlatArrayMessageReader *msg_reader = nullptr; - AlignedBuffer aligned_buf; - cereal::Event::Reader event; -}; - -SubMaster::SubMaster(const std::vector &service_list, const std::vector &poll, - const char *address, const std::vector &ignore_alive) { - poller_ = Poller::create(); - for (auto name : service_list) { - assert(services.count(std::string(name)) > 0); - - service serv = services.at(std::string(name)); - SubSocket *socket = SubSocket::create(message_context.context(), name, address ? address : "127.0.0.1", true); - assert(socket != 0); - bool is_polled = inList(poll, name) || poll.empty(); - if (is_polled) poller_->registerSocket(socket); - SubMessage *m = new SubMessage{ - .name = name, - .socket = socket, - .freq = serv.frequency, - .ignore_alive = inList(ignore_alive, name), - .allocated_msg_reader = malloc(sizeof(capnp::FlatArrayMessageReader)), - .is_polled = is_polled}; - m->msg_reader = new (m->allocated_msg_reader) capnp::FlatArrayMessageReader({}); - messages_[socket] = m; - services_[name] = m; - } -} - -void SubMaster::update(int timeout) { - for (auto &kv : messages_) kv.second->updated = false; - - auto sockets = poller_->poll(timeout); - - // add non-polled sockets for non-blocking receive - for (auto &kv : messages_) { - SubMessage *m = kv.second; - SubSocket *s = kv.first; - if (!m->is_polled) sockets.push_back(s); - } - - uint64_t current_time = nanos_since_boot(); - - std::vector> messages; - - for (auto s : sockets) { - Message *msg = s->receive(true); - if (msg == nullptr) continue; - - SubMessage *m = messages_.at(s); - - m->msg_reader->~FlatArrayMessageReader(); - capnp::ReaderOptions options; - options.traversalLimitInWords = kj::maxValue; // Don't limit - m->msg_reader = new (m->allocated_msg_reader) capnp::FlatArrayMessageReader(m->aligned_buf.align(msg), options); - delete msg; - messages.push_back({m->name, m->msg_reader->getRoot()}); - } - - update_msgs(current_time, messages); -} - -void SubMaster::update_msgs(uint64_t current_time, const std::vector> &messages){ - if (++frame == UINT64_MAX) frame = 1; - - for (auto &kv : messages) { - auto m_find = services_.find(kv.first); - if (m_find == services_.end()){ - continue; - } - SubMessage *m = m_find->second; - m->event = kv.second; - m->updated = true; - m->rcv_time = current_time; - m->rcv_frame = frame; - m->valid = m->event.getValid(); - if (SIMULATION) m->alive = true; - } - - if (!SIMULATION) { - for (auto &kv : messages_) { - SubMessage *m = kv.second; - m->alive = (m->freq <= (1e-5) || ((current_time - m->rcv_time) * (1e-9)) < (10.0 / m->freq)); - } - } -} - -bool SubMaster::all_(const std::vector &service_list, bool valid, bool alive) { - int found = 0; - for (auto &kv : messages_) { - SubMessage *m = kv.second; - if (service_list.size() == 0 || inList(service_list, m->name.c_str())) { - found += (!valid || m->valid) && (!alive || (m->alive || m->ignore_alive)); - } - } - return service_list.size() == 0 ? found == messages_.size() : found == service_list.size(); -} - -void SubMaster::drain() { - while (true) { - auto polls = poller_->poll(0); - if (polls.size() == 0) - break; - - for (auto sock : polls) { - Message *msg = sock->receive(true); - delete msg; - } - } -} - -bool SubMaster::updated(const char *name) const { - return services_.at(name)->updated; -} - -bool SubMaster::alive(const char *name) const { - return services_.at(name)->alive; -} - -bool SubMaster::valid(const char *name) const { - return services_.at(name)->valid; -} - -uint64_t SubMaster::rcv_frame(const char *name) const { - return services_.at(name)->rcv_frame; -} - -uint64_t SubMaster::rcv_time(const char *name) const { - return services_.at(name)->rcv_time; -} - -cereal::Event::Reader &SubMaster::operator[](const char *name) const { - return services_.at(name)->event; -} - -SubMaster::~SubMaster() { - delete poller_; - for (auto &kv : messages_) { - SubMessage *m = kv.second; - m->msg_reader->~FlatArrayMessageReader(); - free(m->allocated_msg_reader); - delete m->socket; - delete m; - } -} - -PubMaster::PubMaster(const std::vector &service_list) { - for (auto name : service_list) { - assert(services.count(name) > 0); - PubSocket *socket = PubSocket::create(message_context.context(), name); - assert(socket); - sockets_[name] = socket; - } -} - -int PubMaster::send(const char *name, MessageBuilder &msg) { - auto bytes = msg.toBytes(); - return send(name, bytes.begin(), bytes.size()); -} - -PubMaster::~PubMaster() { - for (auto s : sockets_) delete s.second; -} diff --git a/cereal/visionipc/ipc.cc b/cereal/visionipc/ipc.cc deleted file mode 100644 index c4ab9a4..0000000 --- a/cereal/visionipc/ipc.cc +++ /dev/null @@ -1,121 +0,0 @@ -#include -#include -#include -#include -#include -#include - -#include -#include -#include - -#ifdef __APPLE__ -#define getsocket() socket(AF_UNIX, SOCK_STREAM, 0) -#else -#define getsocket() socket(AF_UNIX, SOCK_SEQPACKET, 0) -#endif - -#include "cereal/visionipc/ipc.h" - -int ipc_connect(const char* socket_path) { - int err; - - int sock = getsocket(); - - if (sock < 0) return -1; - struct sockaddr_un addr = { - .sun_family = AF_UNIX, - }; - snprintf(addr.sun_path, sizeof(addr.sun_path), "%s", socket_path); - err = connect(sock, (struct sockaddr*)&addr, sizeof(addr)); - if (err != 0) { - close(sock); - return -1; - } - - return sock; -} - -int ipc_bind(const char* socket_path) { - int err; - - unlink(socket_path); - - int sock = getsocket(); - - struct sockaddr_un addr = { - .sun_family = AF_UNIX, - }; - snprintf(addr.sun_path, sizeof(addr.sun_path), "%s", socket_path); - err = bind(sock, (struct sockaddr *)&addr, sizeof(addr)); - assert(err == 0); - - err = listen(sock, 3); - assert(err == 0); - - return sock; -} - - -int ipc_sendrecv_with_fds(bool send, int fd, void *buf, size_t buf_size, int* fds, int num_fds, - int *out_num_fds) { - char control_buf[CMSG_SPACE(sizeof(int) * num_fds)]; - memset(control_buf, 0, CMSG_SPACE(sizeof(int) * num_fds)); - - struct iovec iov = { - .iov_base = buf, - .iov_len = buf_size, - }; - struct msghdr msg = { - .msg_iov = &iov, - .msg_iovlen = 1, - }; - - if (num_fds > 0) { - assert(fds); - - msg.msg_control = control_buf; - msg.msg_controllen = CMSG_SPACE(sizeof(int) * num_fds); - } - - if (send) { - if (num_fds) { - struct cmsghdr *cmsg = CMSG_FIRSTHDR(&msg); - assert(cmsg); - cmsg->cmsg_level = SOL_SOCKET; - cmsg->cmsg_type = SCM_RIGHTS; - cmsg->cmsg_len = CMSG_LEN(sizeof(int) * num_fds); - memcpy(CMSG_DATA(cmsg), fds, sizeof(int) * num_fds); - } - return sendmsg(fd, &msg, 0); - } else { - int r = recvmsg(fd, &msg, 0); - if (r < 0) return r; - - int recv_fds = 0; - if (msg.msg_controllen > 0) { - struct cmsghdr *cmsg = CMSG_FIRSTHDR(&msg); - assert(cmsg); - assert(cmsg->cmsg_level == SOL_SOCKET && cmsg->cmsg_type == SCM_RIGHTS); - recv_fds = (cmsg->cmsg_len - CMSG_LEN(0)); - assert(recv_fds > 0 && (recv_fds % sizeof(int)) == 0); - recv_fds /= sizeof(int); - - assert(fds && recv_fds <= num_fds); - memcpy(fds, CMSG_DATA(cmsg), sizeof(int) * recv_fds); - } - - if (msg.msg_flags) { - for (int i=0; i - -int ipc_connect(const char* socket_path); -int ipc_bind(const char* socket_path); -int ipc_sendrecv_with_fds(bool send, int fd, void *buf, size_t buf_size, int* fds, int num_fds, - int *out_num_fds); diff --git a/cereal/visionipc/test_runner.cc b/cereal/visionipc/test_runner.cc deleted file mode 100644 index 62bf747..0000000 --- a/cereal/visionipc/test_runner.cc +++ /dev/null @@ -1,2 +0,0 @@ -#define CATCH_CONFIG_MAIN -#include "catch2/catch.hpp" diff --git a/cereal/visionipc/visionbuf.cc b/cereal/visionipc/visionbuf.cc deleted file mode 100644 index e9e0ff3..0000000 --- a/cereal/visionipc/visionbuf.cc +++ /dev/null @@ -1,35 +0,0 @@ -#include "cereal/visionipc/visionbuf.h" - -#define ALIGN(x, align) (((x) + (align)-1) & ~((align)-1)) - -void visionbuf_compute_aligned_width_and_height(int width, int height, int *aligned_w, int *aligned_h) { - *aligned_w = width; - *aligned_h = height; -} - -void VisionBuf::init_rgb(size_t init_width, size_t init_height, size_t init_stride) { - this->rgb = true; - this->width = init_width; - this->height = init_height; - this->stride = init_stride; -} - -void VisionBuf::init_yuv(size_t init_width, size_t init_height, size_t init_stride, size_t init_uv_offset){ - this->rgb = false; - this->width = init_width; - this->height = init_height; - this->stride = init_stride; - this->uv_offset = init_uv_offset; - - this->y = (uint8_t *)this->addr; - this->uv = this->y + this->uv_offset; -} - - -uint64_t VisionBuf::get_frame_id() { - return *frame_id; -} - -void VisionBuf::set_frame_id(uint64_t id) { - *frame_id = id; -} diff --git a/cereal/visionipc/visionbuf.h b/cereal/visionipc/visionbuf.h deleted file mode 100644 index e0e78f4..0000000 --- a/cereal/visionipc/visionbuf.h +++ /dev/null @@ -1,66 +0,0 @@ -#pragma once - -#include "cereal/visionipc/visionipc.h" - -#define CL_USE_DEPRECATED_OPENCL_1_2_APIS -#ifdef __APPLE__ -#include -#else -#include -#endif - -#define VISIONBUF_SYNC_FROM_DEVICE 0 -#define VISIONBUF_SYNC_TO_DEVICE 1 - -enum VisionStreamType { - VISION_STREAM_ROAD, - VISION_STREAM_DRIVER, - VISION_STREAM_WIDE_ROAD, - - VISION_STREAM_MAP, - VISION_STREAM_MAX, -}; - -class VisionBuf { - public: - size_t len = 0; - size_t mmap_len = 0; - void * addr = nullptr; - uint64_t *frame_id; - int fd = 0; - - bool rgb = false; - size_t width = 0; - size_t height = 0; - size_t stride = 0; - size_t uv_offset = 0; - - // YUV - uint8_t * y = nullptr; - uint8_t * uv = nullptr; - - // Visionipc - uint64_t server_id = 0; - size_t idx = 0; - VisionStreamType type; - - // OpenCL - cl_mem buf_cl = nullptr; - cl_command_queue copy_q = nullptr; - - // ion - int handle = 0; - - void allocate(size_t len); - void import(); - void init_cl(cl_device_id device_id, cl_context ctx); - void init_rgb(size_t width, size_t height, size_t stride); - void init_yuv(size_t width, size_t height, size_t stride, size_t uv_offset); - int sync(int dir); - int free(); - - void set_frame_id(uint64_t id); - uint64_t get_frame_id(); -}; - -void visionbuf_compute_aligned_width_and_height(int width, int height, int *aligned_w, int *aligned_h); diff --git a/cereal/visionipc/visionbuf_cl.cc b/cereal/visionipc/visionbuf_cl.cc deleted file mode 100644 index 0315d8d..0000000 --- a/cereal/visionipc/visionbuf_cl.cc +++ /dev/null @@ -1,94 +0,0 @@ -#include "cereal/visionipc/visionbuf.h" - -#include -#include -#include -#include -#include -#include -#include -#include - -std::atomic offset = 0; - -static void *malloc_with_fd(size_t len, int *fd) { - char full_path[0x100]; - -#ifdef __APPLE__ - snprintf(full_path, sizeof(full_path)-1, "/tmp/visionbuf_%d_%d", getpid(), offset++); -#else - snprintf(full_path, sizeof(full_path)-1, "/dev/shm/visionbuf_%d_%d", getpid(), offset++); -#endif - - *fd = open(full_path, O_RDWR | O_CREAT, 0664); - assert(*fd >= 0); - - unlink(full_path); - - ftruncate(*fd, len); - void *addr = mmap(NULL, len, PROT_READ | PROT_WRITE, MAP_SHARED, *fd, 0); - assert(addr != MAP_FAILED); - - return addr; -} - -void VisionBuf::allocate(size_t length) { - this->len = length; - this->mmap_len = this->len + sizeof(uint64_t); - this->addr = malloc_with_fd(this->mmap_len, &this->fd); - this->frame_id = (uint64_t*)((uint8_t*)this->addr + this->len); -} - -void VisionBuf::init_cl(cl_device_id device_id, cl_context ctx){ - int err; - - this->copy_q = clCreateCommandQueue(ctx, device_id, 0, &err); - assert(err == 0); - - this->buf_cl = clCreateBuffer(ctx, CL_MEM_READ_WRITE | CL_MEM_USE_HOST_PTR, this->len, this->addr, &err); - assert(err == 0); -} - - -void VisionBuf::import(){ - assert(this->fd >= 0); - this->addr = mmap(NULL, this->mmap_len, PROT_READ | PROT_WRITE, MAP_SHARED, this->fd, 0); - assert(this->addr != MAP_FAILED); - - this->frame_id = (uint64_t*)((uint8_t*)this->addr + this->len); -} - - -int VisionBuf::sync(int dir) { - int err = 0; - if (!this->buf_cl) return 0; - - if (dir == VISIONBUF_SYNC_FROM_DEVICE) { - err = clEnqueueReadBuffer(this->copy_q, this->buf_cl, CL_FALSE, 0, this->len, this->addr, 0, NULL, NULL); - } else { - err = clEnqueueWriteBuffer(this->copy_q, this->buf_cl, CL_FALSE, 0, this->len, this->addr, 0, NULL, NULL); - } - - if (err == 0){ - err = clFinish(this->copy_q); - } - - return err; -} - -int VisionBuf::free() { - int err = 0; - if (this->buf_cl){ - err = clReleaseMemObject(this->buf_cl); - if (err != 0) return err; - - err = clReleaseCommandQueue(this->copy_q); - if (err != 0) return err; - } - - err = munmap(this->addr, this->len); - if (err != 0) return err; - - err = close(this->fd); - return err; -} diff --git a/cereal/visionipc/visionbuf_ion.cc b/cereal/visionipc/visionbuf_ion.cc deleted file mode 100644 index f72e76c..0000000 --- a/cereal/visionipc/visionbuf_ion.cc +++ /dev/null @@ -1,161 +0,0 @@ -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include - -#include "cereal/visionipc/visionbuf.h" - -// keep trying if x gets interrupted by a signal -#define HANDLE_EINTR(x) \ - ({ \ - decltype(x) ret; \ - int try_cnt = 0; \ - do { \ - ret = (x); \ - } while (ret == -1 && errno == EINTR && try_cnt++ < 100); \ - ret; \ - }) - -// just hard-code these for convenience -// size_t device_page_size = 0; -// clGetDeviceInfo(device_id, CL_DEVICE_PAGE_SIZE_QCOM, -// sizeof(device_page_size), &device_page_size, -// NULL); - -// size_t padding_cl = 0; -// clGetDeviceInfo(device_id, CL_DEVICE_EXT_MEM_PADDING_IN_BYTES_QCOM, -// sizeof(padding_cl), &padding_cl, -// NULL); -#define DEVICE_PAGE_SIZE_CL 4096 -#define PADDING_CL 0 - -struct IonFileHandle { - IonFileHandle() { - fd = open("/dev/ion", O_RDWR | O_NONBLOCK); - assert(fd >= 0); - } - ~IonFileHandle() { - close(fd); - } - int fd = -1; -}; - -int ion_fd() { - static IonFileHandle fh; - return fh.fd; -} - -void VisionBuf::allocate(size_t length) { - struct ion_allocation_data ion_alloc = {0}; - ion_alloc.len = length + PADDING_CL + sizeof(uint64_t); - ion_alloc.align = 4096; - ion_alloc.heap_id_mask = 1 << ION_IOMMU_HEAP_ID; - ion_alloc.flags = ION_FLAG_CACHED; - - int err = HANDLE_EINTR(ioctl(ion_fd(), ION_IOC_ALLOC, &ion_alloc)); - assert(err == 0); - - struct ion_fd_data ion_fd_data = {0}; - ion_fd_data.handle = ion_alloc.handle; - err = HANDLE_EINTR(ioctl(ion_fd(), ION_IOC_SHARE, &ion_fd_data)); - assert(err == 0); - - void *mmap_addr = mmap(NULL, ion_alloc.len, - PROT_READ | PROT_WRITE, - MAP_SHARED, ion_fd_data.fd, 0); - assert(mmap_addr != MAP_FAILED); - - memset(mmap_addr, 0, ion_alloc.len); - - this->len = length; - this->mmap_len = ion_alloc.len; - this->addr = mmap_addr; - this->handle = ion_alloc.handle; - this->fd = ion_fd_data.fd; - this->frame_id = (uint64_t*)((uint8_t*)this->addr + this->len + PADDING_CL); -} - -void VisionBuf::import(){ - int err; - assert(this->fd >= 0); - - // Get handle - struct ion_fd_data fd_data = {0}; - fd_data.fd = this->fd; - err = HANDLE_EINTR(ioctl(ion_fd(), ION_IOC_IMPORT, &fd_data)); - assert(err == 0); - - this->handle = fd_data.handle; - this->addr = mmap(NULL, this->mmap_len, PROT_READ | PROT_WRITE, MAP_SHARED, this->fd, 0); - assert(this->addr != MAP_FAILED); - - this->frame_id = (uint64_t*)((uint8_t*)this->addr + this->len + PADDING_CL); -} - -void VisionBuf::init_cl(cl_device_id device_id, cl_context ctx) { - int err; - - assert(((uintptr_t)this->addr % DEVICE_PAGE_SIZE_CL) == 0); - - cl_mem_ion_host_ptr ion_cl = {0}; - ion_cl.ext_host_ptr.allocation_type = CL_MEM_ION_HOST_PTR_QCOM; - ion_cl.ext_host_ptr.host_cache_policy = CL_MEM_HOST_UNCACHED_QCOM; - ion_cl.ion_filedesc = this->fd; - ion_cl.ion_hostptr = this->addr; - - this->buf_cl = clCreateBuffer(ctx, - CL_MEM_USE_HOST_PTR | CL_MEM_EXT_HOST_PTR_QCOM, - this->len, &ion_cl, &err); - assert(err == 0); -} - - -int VisionBuf::sync(int dir) { - struct ion_flush_data flush_data = {0}; - flush_data.handle = this->handle; - flush_data.vaddr = this->addr; - flush_data.offset = 0; - flush_data.length = this->len; - - // ION_IOC_INV_CACHES ~= DMA_FROM_DEVICE - // ION_IOC_CLEAN_CACHES ~= DMA_TO_DEVICE - // ION_IOC_CLEAN_INV_CACHES ~= DMA_BIDIRECTIONAL - - struct ion_custom_data custom_data = {0}; - - assert(dir == VISIONBUF_SYNC_FROM_DEVICE || dir == VISIONBUF_SYNC_TO_DEVICE); - custom_data.cmd = (dir == VISIONBUF_SYNC_FROM_DEVICE) ? - ION_IOC_INV_CACHES : ION_IOC_CLEAN_CACHES; - - custom_data.arg = (unsigned long)&flush_data; - return HANDLE_EINTR(ioctl(ion_fd(), ION_IOC_CUSTOM, &custom_data)); -} - -int VisionBuf::free() { - int err = 0; - - if (this->buf_cl){ - err = clReleaseMemObject(this->buf_cl); - if (err != 0) return err; - } - - err = munmap(this->addr, this->mmap_len); - if (err != 0) return err; - - err = close(this->fd); - if (err != 0) return err; - - struct ion_handle_data handle_data = {.handle = this->handle}; - return HANDLE_EINTR(ioctl(ion_fd(), ION_IOC_FREE, &handle_data)); -} diff --git a/cereal/visionipc/visionipc.h b/cereal/visionipc/visionipc.h deleted file mode 100644 index 7489bc9..0000000 --- a/cereal/visionipc/visionipc.h +++ /dev/null @@ -1,19 +0,0 @@ -#pragma once - -#include -#include - -constexpr int VISIONIPC_MAX_FDS = 128; - -struct VisionIpcBufExtra { - uint32_t frame_id; - uint64_t timestamp_sof; - uint64_t timestamp_eof; - bool valid; -}; - -struct VisionIpcPacket { - uint64_t server_id; - size_t idx; - struct VisionIpcBufExtra extra; -}; diff --git a/cereal/visionipc/visionipc_client.cc b/cereal/visionipc/visionipc_client.cc deleted file mode 100644 index e3c6d0d..0000000 --- a/cereal/visionipc/visionipc_client.cc +++ /dev/null @@ -1,143 +0,0 @@ -#include -#include -#include -#include - -#include -#include "cereal/visionipc/ipc.h" -#include "cereal/visionipc/visionipc_client.h" -#include "cereal/visionipc/visionipc_server.h" -#include "cereal/logger/logger.h" - -static int connect_to_vipc_server(const std::string &name, bool blocking) { - const std::string ipc_path = get_ipc_path(name); - int socket_fd = ipc_connect(ipc_path.c_str()); - while (socket_fd < 0 && blocking) { - std::cout << "VisionIpcClient connecting" << std::endl; - std::this_thread::sleep_for(std::chrono::milliseconds(100)); - socket_fd = ipc_connect(ipc_path.c_str()); - } - return socket_fd; -} - -VisionIpcClient::VisionIpcClient(std::string name, VisionStreamType type, bool conflate, cl_device_id device_id, cl_context ctx) : name(name), type(type), device_id(device_id), ctx(ctx) { - msg_ctx = Context::create(); - sock = SubSocket::create(msg_ctx, get_endpoint_name(name, type), "127.0.0.1", conflate, false); - - poller = Poller::create(); - poller->registerSocket(sock); -} - -// Connect is not thread safe. Do not use the buffers while calling connect -bool VisionIpcClient::connect(bool blocking){ - connected = false; - - // Cleanup old buffers on reconnect - for (size_t i = 0; i < num_buffers; i++){ - if (buffers[i].free() != 0) { - LOGE("Failed to free buffer %zu", i); - } - } - - num_buffers = 0; - - int socket_fd = connect_to_vipc_server(name, blocking); - if (socket_fd < 0) { - return false; - } - // Send stream type to server to request FDs - int r = ipc_sendrecv_with_fds(true, socket_fd, &type, sizeof(type), nullptr, 0, nullptr); - assert(r == sizeof(type)); - - // Get FDs - int fds[VISIONIPC_MAX_FDS]; - VisionBuf bufs[VISIONIPC_MAX_FDS]; - r = ipc_sendrecv_with_fds(false, socket_fd, &bufs, sizeof(bufs), fds, VISIONIPC_MAX_FDS, &num_buffers); - - assert(num_buffers >= 0); - assert(r == sizeof(VisionBuf) * num_buffers); - - // Import buffers - for (size_t i = 0; i < num_buffers; i++){ - buffers[i] = bufs[i]; - buffers[i].fd = fds[i]; - buffers[i].import(); - if (buffers[i].rgb) { - buffers[i].init_rgb(buffers[i].width, buffers[i].height, buffers[i].stride); - } else { - buffers[i].init_yuv(buffers[i].width, buffers[i].height, buffers[i].stride, buffers[i].uv_offset); - } - - if (device_id) buffers[i].init_cl(device_id, ctx); - } - - close(socket_fd); - connected = true; - return true; -} - -VisionBuf * VisionIpcClient::recv(VisionIpcBufExtra * extra, const int timeout_ms){ - auto p = poller->poll(timeout_ms); - - if (!p.size()){ - return nullptr; - } - - Message * r = sock->receive(true); - if (r == nullptr){ - return nullptr; - } - - // Get buffer - assert(r->getSize() == sizeof(VisionIpcPacket)); - VisionIpcPacket *packet = (VisionIpcPacket*)r->getData(); - - assert(packet->idx < num_buffers); - VisionBuf * buf = &buffers[packet->idx]; - - if (buf->server_id != packet->server_id){ - connected = false; - delete r; - return nullptr; - } - - if (extra) { - *extra = packet->extra; - } - - if (buf->sync(VISIONBUF_SYNC_TO_DEVICE) != 0) { - LOGE("Failed to sync buffer"); - } - - delete r; - return buf; -} - -std::set VisionIpcClient::getAvailableStreams(const std::string &name, bool blocking) { - int socket_fd = connect_to_vipc_server(name, blocking); - if (socket_fd < 0) { - return {}; - } - // Send VISION_STREAM_MAX to server to request available streams - int request = VISION_STREAM_MAX; - int r = ipc_sendrecv_with_fds(true, socket_fd, &request, sizeof(request), nullptr, 0, nullptr); - assert(r == sizeof(request)); - - VisionStreamType available_streams[VISION_STREAM_MAX] = {}; - r = ipc_sendrecv_with_fds(false, socket_fd, &available_streams, sizeof(available_streams), nullptr, 0, nullptr); - assert((r >= 0) && (r % sizeof(VisionStreamType) == 0)); - close(socket_fd); - return std::set(available_streams, available_streams + r / sizeof(VisionStreamType)); -} - -VisionIpcClient::~VisionIpcClient(){ - for (size_t i = 0; i < num_buffers; i++){ - if (buffers[i].free() != 0) { - LOGE("Failed to free buffer %zu", i); - } - } - - delete sock; - delete poller; - delete msg_ctx; -} diff --git a/cereal/visionipc/visionipc_client.h b/cereal/visionipc/visionipc_client.h deleted file mode 100644 index 970bac3..0000000 --- a/cereal/visionipc/visionipc_client.h +++ /dev/null @@ -1,30 +0,0 @@ -#pragma once - -#include -#include - -#include "cereal/messaging/messaging.h" -#include "cereal/visionipc/visionbuf.h" - -class VisionIpcClient { -private: - std::string name; - Context * msg_ctx; - SubSocket * sock; - Poller * poller; - - cl_device_id device_id = nullptr; - cl_context ctx = nullptr; - -public: - bool connected = false; - VisionStreamType type; - int num_buffers = 0; - VisionBuf buffers[VISIONIPC_MAX_FDS]; - VisionIpcClient(std::string name, VisionStreamType type, bool conflate, cl_device_id device_id=nullptr, cl_context ctx=nullptr); - ~VisionIpcClient(); - VisionBuf * recv(VisionIpcBufExtra * extra=nullptr, const int timeout_ms=100); - bool connect(bool blocking=true); - bool is_connected() { return connected; } - static std::set getAvailableStreams(const std::string &name, bool blocking = true); -}; diff --git a/cereal/visionipc/visionipc_pyx.cpp b/cereal/visionipc/visionipc_pyx.cpp new file mode 100644 index 0000000..8c34b29 --- /dev/null +++ b/cereal/visionipc/visionipc_pyx.cpp @@ -0,0 +1,42217 @@ +/* Generated by Cython 3.0.8 */ + +/* BEGIN: Cython Metadata +{ + "distutils": { + "depends": [ + "cereal/visionipc/visionbuf.h", + "cereal/visionipc/visionipc.h", + "cereal/visionipc/visionipc_client.h", + "cereal/visionipc/visionipc_server.h" + ], + "language": "c++", + "name": "cereal.visionipc.visionipc_pyx", + "sources": [ + "/data/openpilot/cereal/visionipc/visionipc_pyx.pyx" + ] + }, + "module_name": "cereal.visionipc.visionipc_pyx" +} +END: Cython Metadata */ + +#ifndef PY_SSIZE_T_CLEAN +#define PY_SSIZE_T_CLEAN +#endif /* PY_SSIZE_T_CLEAN */ +#if defined(CYTHON_LIMITED_API) && 0 + #ifndef Py_LIMITED_API + #if CYTHON_LIMITED_API+0 > 0x03030000 + #define Py_LIMITED_API CYTHON_LIMITED_API + #else + #define Py_LIMITED_API 0x03030000 + #endif + #endif +#endif + +#include "Python.h" +#ifndef Py_PYTHON_H + #error Python headers needed to compile C extensions, please install development version of Python. +#elif PY_VERSION_HEX < 0x02070000 || (0x03000000 <= PY_VERSION_HEX && PY_VERSION_HEX < 0x03030000) + #error Cython requires Python 2.7+ or Python 3.3+. +#else +#if defined(CYTHON_LIMITED_API) && CYTHON_LIMITED_API +#define __PYX_EXTRA_ABI_MODULE_NAME "limited" +#else +#define __PYX_EXTRA_ABI_MODULE_NAME "" +#endif +#define CYTHON_ABI "3_0_8" __PYX_EXTRA_ABI_MODULE_NAME +#define __PYX_ABI_MODULE_NAME "_cython_" CYTHON_ABI +#define __PYX_TYPE_MODULE_PREFIX __PYX_ABI_MODULE_NAME "." +#define CYTHON_HEX_VERSION 0x030008F0 +#define CYTHON_FUTURE_DIVISION 1 +#include +#ifndef offsetof + #define offsetof(type, member) ( (size_t) & ((type*)0) -> member ) +#endif +#if !defined(_WIN32) && !defined(WIN32) && !defined(MS_WINDOWS) + #ifndef __stdcall + #define __stdcall + #endif + #ifndef __cdecl + #define __cdecl + #endif + #ifndef __fastcall + #define __fastcall + #endif +#endif +#ifndef DL_IMPORT + #define DL_IMPORT(t) t +#endif +#ifndef DL_EXPORT + #define DL_EXPORT(t) t +#endif +#define __PYX_COMMA , +#ifndef HAVE_LONG_LONG + #define HAVE_LONG_LONG +#endif +#ifndef PY_LONG_LONG + #define PY_LONG_LONG LONG_LONG +#endif +#ifndef Py_HUGE_VAL + #define Py_HUGE_VAL HUGE_VAL +#endif +#define __PYX_LIMITED_VERSION_HEX PY_VERSION_HEX +#if defined(GRAALVM_PYTHON) + /* For very preliminary testing purposes. Most variables are set the same as PyPy. + The existence of this section does not imply that anything works or is even tested */ + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 1 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(PYPY_VERSION) + #define CYTHON_COMPILING_IN_PYPY 1 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #ifndef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #endif + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #if PY_VERSION_HEX < 0x03090000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE (PY_VERSION_HEX >= 0x030400a1 && PYPY_VERSION_NUM >= 0x07030C00) + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(CYTHON_LIMITED_API) + #ifdef Py_LIMITED_API + #undef __PYX_LIMITED_VERSION_HEX + #define __PYX_LIMITED_VERSION_HEX Py_LIMITED_API + #endif + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 1 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_CLINE_IN_TRACEBACK + #define CYTHON_CLINE_IN_TRACEBACK 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 1 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #endif + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 1 + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(Py_GIL_DISABLED) || defined(Py_NOGIL) + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 1 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #ifndef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 +#else + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 1 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #ifndef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #endif + #ifndef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 1 + #endif + #if PY_MAJOR_VERSION < 3 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #ifndef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 1 + #endif + #ifndef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 1 + #endif + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #if PY_VERSION_HEX < 0x030300F0 || PY_VERSION_HEX >= 0x030B00A2 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #elif !defined(CYTHON_USE_UNICODE_WRITER) + #define CYTHON_USE_UNICODE_WRITER 1 + #endif + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #ifndef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 1 + #endif + #ifndef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL (PY_MAJOR_VERSION < 3 || PY_VERSION_HEX >= 0x03060000 && PY_VERSION_HEX < 0x030C00A6) + #endif + #ifndef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL (PY_VERSION_HEX >= 0x030700A1) + #endif + #ifndef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 1 + #endif + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #endif + #if PY_VERSION_HEX < 0x030400a1 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #elif !defined(CYTHON_USE_TP_FINALIZE) + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #if PY_VERSION_HEX < 0x030600B1 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #elif !defined(CYTHON_USE_DICT_VERSIONS) + #define CYTHON_USE_DICT_VERSIONS (PY_VERSION_HEX < 0x030C00A5) + #endif + #if PY_VERSION_HEX < 0x030700A3 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #elif !defined(CYTHON_USE_EXC_INFO_STACK) + #define CYTHON_USE_EXC_INFO_STACK 1 + #endif + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 1 + #endif +#endif +#if !defined(CYTHON_FAST_PYCCALL) +#define CYTHON_FAST_PYCCALL (CYTHON_FAST_PYCALL && PY_VERSION_HEX >= 0x030600B1) +#endif +#if !defined(CYTHON_VECTORCALL) +#define CYTHON_VECTORCALL (CYTHON_FAST_PYCCALL && PY_VERSION_HEX >= 0x030800B1) +#endif +#define CYTHON_BACKPORT_VECTORCALL (CYTHON_METH_FASTCALL && PY_VERSION_HEX < 0x030800B1) +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_MAJOR_VERSION < 3 + #include "longintrepr.h" + #endif + #undef SHIFT + #undef BASE + #undef MASK + #ifdef SIZEOF_VOID_P + enum { __pyx_check_sizeof_voidp = 1 / (int)(SIZEOF_VOID_P == sizeof(void*)) }; + #endif +#endif +#ifndef __has_attribute + #define __has_attribute(x) 0 +#endif +#ifndef __has_cpp_attribute + #define __has_cpp_attribute(x) 0 +#endif +#ifndef CYTHON_RESTRICT + #if defined(__GNUC__) + #define CYTHON_RESTRICT __restrict__ + #elif defined(_MSC_VER) && _MSC_VER >= 1400 + #define CYTHON_RESTRICT __restrict + #elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define CYTHON_RESTRICT restrict + #else + #define CYTHON_RESTRICT + #endif +#endif +#ifndef CYTHON_UNUSED + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(maybe_unused) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(maybe_unused) + #define CYTHON_UNUSED [[maybe_unused]] + #endif + #endif + #endif +#endif +#ifndef CYTHON_UNUSED +# if defined(__GNUC__) +# if !(defined(__cplusplus)) || (__GNUC__ > 3 || (__GNUC__ == 3 && __GNUC_MINOR__ >= 4)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +# elif defined(__ICC) || (defined(__INTEL_COMPILER) && !defined(_MSC_VER)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +#endif +#ifndef CYTHON_UNUSED_VAR +# if defined(__cplusplus) + template void CYTHON_UNUSED_VAR( const T& ) { } +# else +# define CYTHON_UNUSED_VAR(x) (void)(x) +# endif +#endif +#ifndef CYTHON_MAYBE_UNUSED_VAR + #define CYTHON_MAYBE_UNUSED_VAR(x) CYTHON_UNUSED_VAR(x) +#endif +#ifndef CYTHON_NCP_UNUSED +# if CYTHON_COMPILING_IN_CPYTHON +# define CYTHON_NCP_UNUSED +# else +# define CYTHON_NCP_UNUSED CYTHON_UNUSED +# endif +#endif +#ifndef CYTHON_USE_CPP_STD_MOVE + #if defined(__cplusplus) && (\ + __cplusplus >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1600)) + #define CYTHON_USE_CPP_STD_MOVE 1 + #else + #define CYTHON_USE_CPP_STD_MOVE 0 + #endif +#endif +#define __Pyx_void_to_None(void_result) ((void)(void_result), Py_INCREF(Py_None), Py_None) +#ifdef _MSC_VER + #ifndef _MSC_STDINT_H_ + #if _MSC_VER < 1300 + typedef unsigned char uint8_t; + typedef unsigned short uint16_t; + typedef unsigned int uint32_t; + #else + typedef unsigned __int8 uint8_t; + typedef unsigned __int16 uint16_t; + typedef unsigned __int32 uint32_t; + #endif + #endif + #if _MSC_VER < 1300 + #ifdef _WIN64 + typedef unsigned long long __pyx_uintptr_t; + #else + typedef unsigned int __pyx_uintptr_t; + #endif + #else + #ifdef _WIN64 + typedef unsigned __int64 __pyx_uintptr_t; + #else + typedef unsigned __int32 __pyx_uintptr_t; + #endif + #endif +#else + #include + typedef uintptr_t __pyx_uintptr_t; +#endif +#ifndef CYTHON_FALLTHROUGH + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(fallthrough) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(fallthrough) + #define CYTHON_FALLTHROUGH [[fallthrough]] + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_cpp_attribute(clang::fallthrough) + #define CYTHON_FALLTHROUGH [[clang::fallthrough]] + #elif __has_cpp_attribute(gnu::fallthrough) + #define CYTHON_FALLTHROUGH [[gnu::fallthrough]] + #endif + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_attribute(fallthrough) + #define CYTHON_FALLTHROUGH __attribute__((fallthrough)) + #else + #define CYTHON_FALLTHROUGH + #endif + #endif + #if defined(__clang__) && defined(__apple_build_version__) + #if __apple_build_version__ < 7000000 + #undef CYTHON_FALLTHROUGH + #define CYTHON_FALLTHROUGH + #endif + #endif +#endif +#ifdef __cplusplus + template + struct __PYX_IS_UNSIGNED_IMPL {static const bool value = T(0) < T(-1);}; + #define __PYX_IS_UNSIGNED(type) (__PYX_IS_UNSIGNED_IMPL::value) +#else + #define __PYX_IS_UNSIGNED(type) (((type)-1) > 0) +#endif +#if CYTHON_COMPILING_IN_PYPY == 1 + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x030A0000) +#else + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x03090000) +#endif +#define __PYX_REINTERPRET_FUNCION(func_pointer, other_pointer) ((func_pointer)(void(*)(void))(other_pointer)) + +#ifndef __cplusplus + #error "Cython files generated with the C++ option must be compiled with a C++ compiler." +#endif +#ifndef CYTHON_INLINE + #if defined(__clang__) + #define CYTHON_INLINE __inline__ __attribute__ ((__unused__)) + #else + #define CYTHON_INLINE inline + #endif +#endif +template +void __Pyx_call_destructor(T& x) { + x.~T(); +} +template +class __Pyx_FakeReference { + public: + __Pyx_FakeReference() : ptr(NULL) { } + __Pyx_FakeReference(const T& ref) : ptr(const_cast(&ref)) { } + T *operator->() { return ptr; } + T *operator&() { return ptr; } + operator T&() { return *ptr; } + template bool operator ==(const U& other) const { return *ptr == other; } + template bool operator !=(const U& other) const { return *ptr != other; } + template bool operator==(const __Pyx_FakeReference& other) const { return *ptr == *other.ptr; } + template bool operator!=(const __Pyx_FakeReference& other) const { return *ptr != *other.ptr; } + private: + T *ptr; +}; + +#define __PYX_BUILD_PY_SSIZE_T "n" +#define CYTHON_FORMAT_SSIZE_T "z" +#if PY_MAJOR_VERSION < 3 + #define __Pyx_BUILTIN_MODULE_NAME "__builtin__" + #define __Pyx_DefaultClassType PyClass_Type + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a+k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_BUILTIN_MODULE_NAME "builtins" + #define __Pyx_DefaultClassType PyType_Type +#if CYTHON_COMPILING_IN_LIMITED_API + static CYTHON_INLINE PyObject* __Pyx_PyCode_New(int a, int p, int k, int l, int s, int f, + PyObject *code, PyObject *c, PyObject* n, PyObject *v, + PyObject *fv, PyObject *cell, PyObject* fn, + PyObject *name, int fline, PyObject *lnos) { + PyObject *exception_table = NULL; + PyObject *types_module=NULL, *code_type=NULL, *result=NULL; + #if __PYX_LIMITED_VERSION_HEX < 0x030B0000 + PyObject *version_info; + PyObject *py_minor_version = NULL; + #endif + long minor_version = 0; + PyObject *type, *value, *traceback; + PyErr_Fetch(&type, &value, &traceback); + #if __PYX_LIMITED_VERSION_HEX >= 0x030B0000 + minor_version = 11; + #else + if (!(version_info = PySys_GetObject("version_info"))) goto end; + if (!(py_minor_version = PySequence_GetItem(version_info, 1))) goto end; + minor_version = PyLong_AsLong(py_minor_version); + Py_DECREF(py_minor_version); + if (minor_version == -1 && PyErr_Occurred()) goto end; + #endif + if (!(types_module = PyImport_ImportModule("types"))) goto end; + if (!(code_type = PyObject_GetAttrString(types_module, "CodeType"))) goto end; + if (minor_version <= 7) { + (void)p; + result = PyObject_CallFunction(code_type, "iiiiiOOOOOOiOO", a, k, l, s, f, code, + c, n, v, fn, name, fline, lnos, fv, cell); + } else if (minor_version <= 10) { + result = PyObject_CallFunction(code_type, "iiiiiiOOOOOOiOO", a,p, k, l, s, f, code, + c, n, v, fn, name, fline, lnos, fv, cell); + } else { + if (!(exception_table = PyBytes_FromStringAndSize(NULL, 0))) goto end; + result = PyObject_CallFunction(code_type, "iiiiiiOOOOOOOiOO", a,p, k, l, s, f, code, + c, n, v, fn, name, name, fline, lnos, exception_table, fv, cell); + } + end: + Py_XDECREF(code_type); + Py_XDECREF(exception_table); + Py_XDECREF(types_module); + if (type) { + PyErr_Restore(type, value, traceback); + } + return result; + } + #ifndef CO_OPTIMIZED + #define CO_OPTIMIZED 0x0001 + #endif + #ifndef CO_NEWLOCALS + #define CO_NEWLOCALS 0x0002 + #endif + #ifndef CO_VARARGS + #define CO_VARARGS 0x0004 + #endif + #ifndef CO_VARKEYWORDS + #define CO_VARKEYWORDS 0x0008 + #endif + #ifndef CO_ASYNC_GENERATOR + #define CO_ASYNC_GENERATOR 0x0200 + #endif + #ifndef CO_GENERATOR + #define CO_GENERATOR 0x0020 + #endif + #ifndef CO_COROUTINE + #define CO_COROUTINE 0x0080 + #endif +#elif PY_VERSION_HEX >= 0x030B0000 + static CYTHON_INLINE PyCodeObject* __Pyx_PyCode_New(int a, int p, int k, int l, int s, int f, + PyObject *code, PyObject *c, PyObject* n, PyObject *v, + PyObject *fv, PyObject *cell, PyObject* fn, + PyObject *name, int fline, PyObject *lnos) { + PyCodeObject *result; + PyObject *empty_bytes = PyBytes_FromStringAndSize("", 0); + if (!empty_bytes) return NULL; + result = + #if PY_VERSION_HEX >= 0x030C0000 + PyUnstable_Code_NewWithPosOnlyArgs + #else + PyCode_NewWithPosOnlyArgs + #endif + (a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, name, fline, lnos, empty_bytes); + Py_DECREF(empty_bytes); + return result; + } +#elif PY_VERSION_HEX >= 0x030800B2 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_NewWithPosOnlyArgs(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#endif +#endif +#if PY_VERSION_HEX >= 0x030900A4 || defined(Py_IS_TYPE) + #define __Pyx_IS_TYPE(ob, type) Py_IS_TYPE(ob, type) +#else + #define __Pyx_IS_TYPE(ob, type) (((const PyObject*)ob)->ob_type == (type)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_Is) + #define __Pyx_Py_Is(x, y) Py_Is(x, y) +#else + #define __Pyx_Py_Is(x, y) ((x) == (y)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsNone) + #define __Pyx_Py_IsNone(ob) Py_IsNone(ob) +#else + #define __Pyx_Py_IsNone(ob) __Pyx_Py_Is((ob), Py_None) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsTrue) + #define __Pyx_Py_IsTrue(ob) Py_IsTrue(ob) +#else + #define __Pyx_Py_IsTrue(ob) __Pyx_Py_Is((ob), Py_True) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsFalse) + #define __Pyx_Py_IsFalse(ob) Py_IsFalse(ob) +#else + #define __Pyx_Py_IsFalse(ob) __Pyx_Py_Is((ob), Py_False) +#endif +#define __Pyx_NoneAsNull(obj) (__Pyx_Py_IsNone(obj) ? NULL : (obj)) +#if PY_VERSION_HEX >= 0x030900F0 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_GC_IsFinalized(o) PyObject_GC_IsFinalized(o) +#else + #define __Pyx_PyObject_GC_IsFinalized(o) _PyGC_FINALIZED(o) +#endif +#ifndef CO_COROUTINE + #define CO_COROUTINE 0x80 +#endif +#ifndef CO_ASYNC_GENERATOR + #define CO_ASYNC_GENERATOR 0x200 +#endif +#ifndef Py_TPFLAGS_CHECKTYPES + #define Py_TPFLAGS_CHECKTYPES 0 +#endif +#ifndef Py_TPFLAGS_HAVE_INDEX + #define Py_TPFLAGS_HAVE_INDEX 0 +#endif +#ifndef Py_TPFLAGS_HAVE_NEWBUFFER + #define Py_TPFLAGS_HAVE_NEWBUFFER 0 +#endif +#ifndef Py_TPFLAGS_HAVE_FINALIZE + #define Py_TPFLAGS_HAVE_FINALIZE 0 +#endif +#ifndef Py_TPFLAGS_SEQUENCE + #define Py_TPFLAGS_SEQUENCE 0 +#endif +#ifndef Py_TPFLAGS_MAPPING + #define Py_TPFLAGS_MAPPING 0 +#endif +#ifndef METH_STACKLESS + #define METH_STACKLESS 0 +#endif +#if PY_VERSION_HEX <= 0x030700A3 || !defined(METH_FASTCALL) + #ifndef METH_FASTCALL + #define METH_FASTCALL 0x80 + #endif + typedef PyObject *(*__Pyx_PyCFunctionFast) (PyObject *self, PyObject *const *args, Py_ssize_t nargs); + typedef PyObject *(*__Pyx_PyCFunctionFastWithKeywords) (PyObject *self, PyObject *const *args, + Py_ssize_t nargs, PyObject *kwnames); +#else + #define __Pyx_PyCFunctionFast _PyCFunctionFast + #define __Pyx_PyCFunctionFastWithKeywords _PyCFunctionFastWithKeywords +#endif +#if CYTHON_METH_FASTCALL + #define __Pyx_METH_FASTCALL METH_FASTCALL + #define __Pyx_PyCFunction_FastCall __Pyx_PyCFunctionFast + #define __Pyx_PyCFunction_FastCallWithKeywords __Pyx_PyCFunctionFastWithKeywords +#else + #define __Pyx_METH_FASTCALL METH_VARARGS + #define __Pyx_PyCFunction_FastCall PyCFunction + #define __Pyx_PyCFunction_FastCallWithKeywords PyCFunctionWithKeywords +#endif +#if CYTHON_VECTORCALL + #define __pyx_vectorcallfunc vectorcallfunc + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET PY_VECTORCALL_ARGUMENTS_OFFSET + #define __Pyx_PyVectorcall_NARGS(n) PyVectorcall_NARGS((size_t)(n)) +#elif CYTHON_BACKPORT_VECTORCALL + typedef PyObject *(*__pyx_vectorcallfunc)(PyObject *callable, PyObject *const *args, + size_t nargsf, PyObject *kwnames); + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET ((size_t)1 << (8 * sizeof(size_t) - 1)) + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(((size_t)(n)) & ~__Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET)) +#else + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET 0 + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(n)) +#endif +#if PY_MAJOR_VERSION >= 0x030900B1 +#define __Pyx_PyCFunction_CheckExact(func) PyCFunction_CheckExact(func) +#else +#define __Pyx_PyCFunction_CheckExact(func) PyCFunction_Check(func) +#endif +#define __Pyx_CyOrPyCFunction_Check(func) PyCFunction_Check(func) +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_CyOrPyCFunction_GET_FUNCTION(func) (((PyCFunctionObject*)(func))->m_ml->ml_meth) +#elif !CYTHON_COMPILING_IN_LIMITED_API +#define __Pyx_CyOrPyCFunction_GET_FUNCTION(func) PyCFunction_GET_FUNCTION(func) +#endif +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_CyOrPyCFunction_GET_FLAGS(func) (((PyCFunctionObject*)(func))->m_ml->ml_flags) +static CYTHON_INLINE PyObject* __Pyx_CyOrPyCFunction_GET_SELF(PyObject *func) { + return (__Pyx_CyOrPyCFunction_GET_FLAGS(func) & METH_STATIC) ? NULL : ((PyCFunctionObject*)func)->m_self; +} +#endif +static CYTHON_INLINE int __Pyx__IsSameCFunction(PyObject *func, void *cfunc) { +#if CYTHON_COMPILING_IN_LIMITED_API + return PyCFunction_Check(func) && PyCFunction_GetFunction(func) == (PyCFunction) cfunc; +#else + return PyCFunction_Check(func) && PyCFunction_GET_FUNCTION(func) == (PyCFunction) cfunc; +#endif +} +#define __Pyx_IsSameCFunction(func, cfunc) __Pyx__IsSameCFunction(func, cfunc) +#if __PYX_LIMITED_VERSION_HEX < 0x030900B1 + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) ((void)m, PyType_FromSpecWithBases(s, b)) + typedef PyObject *(*__Pyx_PyCMethod)(PyObject *, PyTypeObject *, PyObject *const *, size_t, PyObject *); +#else + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) PyType_FromModuleAndSpec(m, s, b) + #define __Pyx_PyCMethod PyCMethod +#endif +#ifndef METH_METHOD + #define METH_METHOD 0x200 +#endif +#if CYTHON_COMPILING_IN_PYPY && !defined(PyObject_Malloc) + #define PyObject_Malloc(s) PyMem_Malloc(s) + #define PyObject_Free(p) PyMem_Free(p) + #define PyObject_Realloc(p) PyMem_Realloc(p) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) +#else + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) (frame)->f_lineno = (lineno) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyThreadState_Current PyThreadState_Get() +#elif !CYTHON_FAST_THREAD_STATE + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#elif PY_VERSION_HEX >= 0x030d00A1 + #define __Pyx_PyThreadState_Current PyThreadState_GetUnchecked() +#elif PY_VERSION_HEX >= 0x03060000 + #define __Pyx_PyThreadState_Current _PyThreadState_UncheckedGet() +#elif PY_VERSION_HEX >= 0x03000000 + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#else + #define __Pyx_PyThreadState_Current _PyThreadState_Current +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE void *__Pyx_PyModule_GetState(PyObject *op) +{ + void *result; + result = PyModule_GetState(op); + if (!result) + Py_FatalError("Couldn't find the module state"); + return result; +} +#endif +#define __Pyx_PyObject_GetSlot(obj, name, func_ctype) __Pyx_PyType_GetSlot(Py_TYPE(obj), name, func_ctype) +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((func_ctype) PyType_GetSlot((type), Py_##name)) +#else + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((type)->name) +#endif +#if PY_VERSION_HEX < 0x030700A2 && !defined(PyThread_tss_create) && !defined(Py_tss_NEEDS_INIT) +#include "pythread.h" +#define Py_tss_NEEDS_INIT 0 +typedef int Py_tss_t; +static CYTHON_INLINE int PyThread_tss_create(Py_tss_t *key) { + *key = PyThread_create_key(); + return 0; +} +static CYTHON_INLINE Py_tss_t * PyThread_tss_alloc(void) { + Py_tss_t *key = (Py_tss_t *)PyObject_Malloc(sizeof(Py_tss_t)); + *key = Py_tss_NEEDS_INIT; + return key; +} +static CYTHON_INLINE void PyThread_tss_free(Py_tss_t *key) { + PyObject_Free(key); +} +static CYTHON_INLINE int PyThread_tss_is_created(Py_tss_t *key) { + return *key != Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE void PyThread_tss_delete(Py_tss_t *key) { + PyThread_delete_key(*key); + *key = Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE int PyThread_tss_set(Py_tss_t *key, void *value) { + return PyThread_set_key_value(*key, value); +} +static CYTHON_INLINE void * PyThread_tss_get(Py_tss_t *key) { + return PyThread_get_key_value(*key); +} +#endif +#if PY_MAJOR_VERSION < 3 + #if CYTHON_COMPILING_IN_PYPY + #if PYPY_VERSION_NUM < 0x07030600 + #if defined(__cplusplus) && __cplusplus >= 201402L + [[deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")]] + #elif defined(__GNUC__) || defined(__clang__) + __attribute__ ((__deprecated__("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6"))) + #elif defined(_MSC_VER) + __declspec(deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")) + #endif + static CYTHON_INLINE int PyGILState_Check(void) { + return 0; + } + #else // PYPY_VERSION_NUM < 0x07030600 + #endif // PYPY_VERSION_NUM < 0x07030600 + #else + static CYTHON_INLINE int PyGILState_Check(void) { + PyThreadState * tstate = _PyThreadState_Current; + return tstate && (tstate == PyGILState_GetThisThreadState()); + } + #endif +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030d0000 || defined(_PyDict_NewPresized) +#define __Pyx_PyDict_NewPresized(n) ((n <= 8) ? PyDict_New() : _PyDict_NewPresized(n)) +#else +#define __Pyx_PyDict_NewPresized(n) PyDict_New() +#endif +#if PY_MAJOR_VERSION >= 3 || CYTHON_FUTURE_DIVISION + #define __Pyx_PyNumber_Divide(x,y) PyNumber_TrueDivide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceTrueDivide(x,y) +#else + #define __Pyx_PyNumber_Divide(x,y) PyNumber_Divide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceDivide(x,y) +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX > 0x030600B4 && PY_VERSION_HEX < 0x030d0000 && CYTHON_USE_UNICODE_INTERNALS +#define __Pyx_PyDict_GetItemStrWithError(dict, name) _PyDict_GetItem_KnownHash(dict, name, ((PyASCIIObject *) name)->hash) +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStr(PyObject *dict, PyObject *name) { + PyObject *res = __Pyx_PyDict_GetItemStrWithError(dict, name); + if (res == NULL) PyErr_Clear(); + return res; +} +#elif PY_MAJOR_VERSION >= 3 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07020000) +#define __Pyx_PyDict_GetItemStrWithError PyDict_GetItemWithError +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#else +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStrWithError(PyObject *dict, PyObject *name) { +#if CYTHON_COMPILING_IN_PYPY + return PyDict_GetItem(dict, name); +#else + PyDictEntry *ep; + PyDictObject *mp = (PyDictObject*) dict; + long hash = ((PyStringObject *) name)->ob_shash; + assert(hash != -1); + ep = (mp->ma_lookup)(mp, name, hash); + if (ep == NULL) { + return NULL; + } + return ep->me_value; +#endif +} +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#endif +#if CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyType_GetFlags(tp) (((PyTypeObject *)tp)->tp_flags) + #define __Pyx_PyType_HasFeature(type, feature) ((__Pyx_PyType_GetFlags(type) & (feature)) != 0) + #define __Pyx_PyObject_GetIterNextFunc(obj) (Py_TYPE(obj)->tp_iternext) +#else + #define __Pyx_PyType_GetFlags(tp) (PyType_GetFlags((PyTypeObject *)tp)) + #define __Pyx_PyType_HasFeature(type, feature) PyType_HasFeature(type, feature) + #define __Pyx_PyObject_GetIterNextFunc(obj) PyIter_Next +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_SetItemOnTypeDict(tp, k, v) PyObject_GenericSetAttr((PyObject*)tp, k, v) +#else + #define __Pyx_SetItemOnTypeDict(tp, k, v) PyDict_SetItem(tp->tp_dict, k, v) +#endif +#if CYTHON_USE_TYPE_SPECS && PY_VERSION_HEX >= 0x03080000 +#define __Pyx_PyHeapTypeObject_GC_Del(obj) {\ + PyTypeObject *type = Py_TYPE((PyObject*)obj);\ + assert(__Pyx_PyType_HasFeature(type, Py_TPFLAGS_HEAPTYPE));\ + PyObject_GC_Del(obj);\ + Py_DECREF(type);\ +} +#else +#define __Pyx_PyHeapTypeObject_GC_Del(obj) PyObject_GC_Del(obj) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define CYTHON_PEP393_ENABLED 1 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GetLength(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_ReadChar(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((void)u, 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((void)u, (0)) + #define __Pyx_PyUnicode_DATA(u) ((void*)u) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)k, PyUnicode_ReadChar((PyObject*)(d), i)) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GetLength(u)) +#elif PY_VERSION_HEX > 0x03030000 && defined(PyUnicode_KIND) + #define CYTHON_PEP393_ENABLED 1 + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_READY(op) (0) + #else + #define __Pyx_PyUnicode_READY(op) (likely(PyUnicode_IS_READY(op)) ?\ + 0 : _PyUnicode_Ready((PyObject *)(op))) + #endif + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_LENGTH(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_READ_CHAR(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) PyUnicode_MAX_CHAR_VALUE(u) + #define __Pyx_PyUnicode_KIND(u) ((int)PyUnicode_KIND(u)) + #define __Pyx_PyUnicode_DATA(u) PyUnicode_DATA(u) + #define __Pyx_PyUnicode_READ(k, d, i) PyUnicode_READ(k, d, i) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) PyUnicode_WRITE(k, d, i, (Py_UCS4) ch) + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_LENGTH(u)) + #else + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x03090000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : ((PyCompactUnicodeObject *)(u))->wstr_length)) + #else + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : PyUnicode_GET_SIZE(u))) + #endif + #endif +#else + #define CYTHON_PEP393_ENABLED 0 + #define PyUnicode_1BYTE_KIND 1 + #define PyUnicode_2BYTE_KIND 2 + #define PyUnicode_4BYTE_KIND 4 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_SIZE(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) ((Py_UCS4)(PyUnicode_AS_UNICODE(u)[i])) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((sizeof(Py_UNICODE) == 2) ? 65535U : 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((int)sizeof(Py_UNICODE)) + #define __Pyx_PyUnicode_DATA(u) ((void*)PyUnicode_AS_UNICODE(u)) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)(k), (Py_UCS4)(((Py_UNICODE*)d)[i])) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) (((void)(k)), ((Py_UNICODE*)d)[i] = (Py_UNICODE) ch) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_SIZE(u)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyUnicode_Concat(a, b) PyNumber_Add(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) PyNumber_Add(a, b) +#else + #define __Pyx_PyUnicode_Concat(a, b) PyUnicode_Concat(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) ((unlikely((a) == Py_None) || unlikely((b) == Py_None)) ?\ + PyNumber_Add(a, b) : __Pyx_PyUnicode_Concat(a, b)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #if !defined(PyUnicode_DecodeUnicodeEscape) + #define PyUnicode_DecodeUnicodeEscape(s, size, errors) PyUnicode_Decode(s, size, "unicode_escape", errors) + #endif + #if !defined(PyUnicode_Contains) || (PY_MAJOR_VERSION == 2 && PYPY_VERSION_NUM < 0x07030500) + #undef PyUnicode_Contains + #define PyUnicode_Contains(u, s) PySequence_Contains(u, s) + #endif + #if !defined(PyByteArray_Check) + #define PyByteArray_Check(obj) PyObject_TypeCheck(obj, &PyByteArray_Type) + #endif + #if !defined(PyObject_Format) + #define PyObject_Format(obj, fmt) PyObject_CallMethod(obj, "__format__", "O", fmt) + #endif +#endif +#define __Pyx_PyString_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyString_Check(b) && !PyString_CheckExact(b)))) ? PyNumber_Remainder(a, b) : __Pyx_PyString_Format(a, b)) +#define __Pyx_PyUnicode_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyUnicode_Check(b) && !PyUnicode_CheckExact(b)))) ? PyNumber_Remainder(a, b) : PyUnicode_Format(a, b)) +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyString_Format(a, b) PyUnicode_Format(a, b) +#else + #define __Pyx_PyString_Format(a, b) PyString_Format(a, b) +#endif +#if PY_MAJOR_VERSION < 3 && !defined(PyObject_ASCII) + #define PyObject_ASCII(o) PyObject_Repr(o) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBaseString_Type PyUnicode_Type + #define PyStringObject PyUnicodeObject + #define PyString_Type PyUnicode_Type + #define PyString_Check PyUnicode_Check + #define PyString_CheckExact PyUnicode_CheckExact +#ifndef PyObject_Unicode + #define PyObject_Unicode PyObject_Str +#endif +#endif +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyBaseString_Check(obj) PyUnicode_Check(obj) + #define __Pyx_PyBaseString_CheckExact(obj) PyUnicode_CheckExact(obj) +#else + #define __Pyx_PyBaseString_Check(obj) (PyString_Check(obj) || PyUnicode_Check(obj)) + #define __Pyx_PyBaseString_CheckExact(obj) (PyString_CheckExact(obj) || PyUnicode_CheckExact(obj)) +#endif +#if CYTHON_COMPILING_IN_CPYTHON + #define __Pyx_PySequence_ListKeepNew(obj)\ + (likely(PyList_CheckExact(obj) && Py_REFCNT(obj) == 1) ? __Pyx_NewRef(obj) : PySequence_List(obj)) +#else + #define __Pyx_PySequence_ListKeepNew(obj) PySequence_List(obj) +#endif +#ifndef PySet_CheckExact + #define PySet_CheckExact(obj) __Pyx_IS_TYPE(obj, &PySet_Type) +#endif +#if PY_VERSION_HEX >= 0x030900A4 + #define __Pyx_SET_REFCNT(obj, refcnt) Py_SET_REFCNT(obj, refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SET_SIZE(obj, size) +#else + #define __Pyx_SET_REFCNT(obj, refcnt) Py_REFCNT(obj) = (refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SIZE(obj) = (size) +#endif +#if CYTHON_ASSUME_SAFE_MACROS + #define __Pyx_PySequence_ITEM(o, i) PySequence_ITEM(o, i) + #define __Pyx_PySequence_SIZE(seq) Py_SIZE(seq) + #define __Pyx_PyTuple_SET_ITEM(o, i, v) (PyTuple_SET_ITEM(o, i, v), (0)) + #define __Pyx_PyList_SET_ITEM(o, i, v) (PyList_SET_ITEM(o, i, v), (0)) + #define __Pyx_PyTuple_GET_SIZE(o) PyTuple_GET_SIZE(o) + #define __Pyx_PyList_GET_SIZE(o) PyList_GET_SIZE(o) + #define __Pyx_PySet_GET_SIZE(o) PySet_GET_SIZE(o) + #define __Pyx_PyBytes_GET_SIZE(o) PyBytes_GET_SIZE(o) + #define __Pyx_PyByteArray_GET_SIZE(o) PyByteArray_GET_SIZE(o) +#else + #define __Pyx_PySequence_ITEM(o, i) PySequence_GetItem(o, i) + #define __Pyx_PySequence_SIZE(seq) PySequence_Size(seq) + #define __Pyx_PyTuple_SET_ITEM(o, i, v) PyTuple_SetItem(o, i, v) + #define __Pyx_PyList_SET_ITEM(o, i, v) PyList_SetItem(o, i, v) + #define __Pyx_PyTuple_GET_SIZE(o) PyTuple_Size(o) + #define __Pyx_PyList_GET_SIZE(o) PyList_Size(o) + #define __Pyx_PySet_GET_SIZE(o) PySet_Size(o) + #define __Pyx_PyBytes_GET_SIZE(o) PyBytes_Size(o) + #define __Pyx_PyByteArray_GET_SIZE(o) PyByteArray_Size(o) +#endif +#if PY_VERSION_HEX >= 0x030d00A1 + #define __Pyx_PyImport_AddModuleRef(name) PyImport_AddModuleRef(name) +#else + static CYTHON_INLINE PyObject *__Pyx_PyImport_AddModuleRef(const char *name) { + PyObject *module = PyImport_AddModule(name); + Py_XINCREF(module); + return module; + } +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyIntObject PyLongObject + #define PyInt_Type PyLong_Type + #define PyInt_Check(op) PyLong_Check(op) + #define PyInt_CheckExact(op) PyLong_CheckExact(op) + #define __Pyx_Py3Int_Check(op) PyLong_Check(op) + #define __Pyx_Py3Int_CheckExact(op) PyLong_CheckExact(op) + #define PyInt_FromString PyLong_FromString + #define PyInt_FromUnicode PyLong_FromUnicode + #define PyInt_FromLong PyLong_FromLong + #define PyInt_FromSize_t PyLong_FromSize_t + #define PyInt_FromSsize_t PyLong_FromSsize_t + #define PyInt_AsLong PyLong_AsLong + #define PyInt_AS_LONG PyLong_AS_LONG + #define PyInt_AsSsize_t PyLong_AsSsize_t + #define PyInt_AsUnsignedLongMask PyLong_AsUnsignedLongMask + #define PyInt_AsUnsignedLongLongMask PyLong_AsUnsignedLongLongMask + #define PyNumber_Int PyNumber_Long +#else + #define __Pyx_Py3Int_Check(op) (PyLong_Check(op) || PyInt_Check(op)) + #define __Pyx_Py3Int_CheckExact(op) (PyLong_CheckExact(op) || PyInt_CheckExact(op)) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBoolObject PyLongObject +#endif +#if PY_MAJOR_VERSION >= 3 && CYTHON_COMPILING_IN_PYPY + #ifndef PyUnicode_InternFromString + #define PyUnicode_InternFromString(s) PyUnicode_FromString(s) + #endif +#endif +#if PY_VERSION_HEX < 0x030200A4 + typedef long Py_hash_t; + #define __Pyx_PyInt_FromHash_t PyInt_FromLong + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsHash_t +#else + #define __Pyx_PyInt_FromHash_t PyInt_FromSsize_t + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsSsize_t +#endif +#if CYTHON_USE_ASYNC_SLOTS + #if PY_VERSION_HEX >= 0x030500B1 + #define __Pyx_PyAsyncMethodsStruct PyAsyncMethods + #define __Pyx_PyType_AsAsync(obj) (Py_TYPE(obj)->tp_as_async) + #else + #define __Pyx_PyType_AsAsync(obj) ((__Pyx_PyAsyncMethodsStruct*) (Py_TYPE(obj)->tp_reserved)) + #endif +#else + #define __Pyx_PyType_AsAsync(obj) NULL +#endif +#ifndef __Pyx_PyAsyncMethodsStruct + typedef struct { + unaryfunc am_await; + unaryfunc am_aiter; + unaryfunc am_anext; + } __Pyx_PyAsyncMethodsStruct; +#endif + +#if defined(_WIN32) || defined(WIN32) || defined(MS_WINDOWS) + #if !defined(_USE_MATH_DEFINES) + #define _USE_MATH_DEFINES + #endif +#endif +#include +#ifdef NAN +#define __PYX_NAN() ((float) NAN) +#else +static CYTHON_INLINE float __PYX_NAN() { + float value; + memset(&value, 0xFF, sizeof(value)); + return value; +} +#endif +#if defined(__CYGWIN__) && defined(_LDBL_EQ_DBL) +#define __Pyx_truncl trunc +#else +#define __Pyx_truncl truncl +#endif + +#define __PYX_MARK_ERR_POS(f_index, lineno) \ + { __pyx_filename = __pyx_f[f_index]; (void)__pyx_filename; __pyx_lineno = lineno; (void)__pyx_lineno; __pyx_clineno = __LINE__; (void)__pyx_clineno; } +#define __PYX_ERR(f_index, lineno, Ln_error) \ + { __PYX_MARK_ERR_POS(f_index, lineno) goto Ln_error; } + +#ifdef CYTHON_EXTERN_C + #undef __PYX_EXTERN_C + #define __PYX_EXTERN_C CYTHON_EXTERN_C +#elif defined(__PYX_EXTERN_C) + #ifdef _MSC_VER + #pragma message ("Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead.") + #else + #warning Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead. + #endif +#else + #define __PYX_EXTERN_C extern "C++" +#endif + +#define __PYX_HAVE__cereal__visionipc__visionipc_pyx +#define __PYX_HAVE_API__cereal__visionipc__visionipc_pyx +/* Early includes */ +#include +#include +#include "ios" +#include "new" +#include "stdexcept" +#include "typeinfo" +#include +#include + + #if __cplusplus >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1600) + // move should be defined for these versions of MSVC, but __cplusplus isn't set usefully + #include + + namespace cython_std { + template typename std::remove_reference::type&& move(T& t) noexcept { return std::move(t); } + template typename std::remove_reference::type&& move(T&& t) noexcept { return std::move(t); } + } + + #endif + +#include +#include +#include "cereal/visionipc/visionbuf.h" +#include "cereal/visionipc/visionipc.h" +#include "cereal/visionipc/visionipc_server.h" +#include "cereal/visionipc/visionipc_client.h" +#include + + /* Using NumPy API declarations from "numpy/__init__.cython-30.pxd" */ + +#include "numpy/arrayobject.h" +#include "numpy/ndarrayobject.h" +#include "numpy/ndarraytypes.h" +#include "numpy/arrayscalars.h" +#include "numpy/ufuncobject.h" +#include "pythread.h" +#include +#ifdef _OPENMP +#include +#endif /* _OPENMP */ + +#if defined(PYREX_WITHOUT_ASSERTIONS) && !defined(CYTHON_WITHOUT_ASSERTIONS) +#define CYTHON_WITHOUT_ASSERTIONS +#endif + +typedef struct {PyObject **p; const char *s; const Py_ssize_t n; const char* encoding; + const char is_unicode; const char is_str; const char intern; } __Pyx_StringTabEntry; + +#define __PYX_DEFAULT_STRING_ENCODING_IS_ASCII 1 +#define __PYX_DEFAULT_STRING_ENCODING_IS_UTF8 0 +#define __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT (PY_MAJOR_VERSION >= 3 && __PYX_DEFAULT_STRING_ENCODING_IS_UTF8) +#define __PYX_DEFAULT_STRING_ENCODING "ascii" +#define __Pyx_PyObject_FromString __Pyx_PyBytes_FromString +#define __Pyx_PyObject_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#define __Pyx_uchar_cast(c) ((unsigned char)c) +#define __Pyx_long_cast(x) ((long)x) +#define __Pyx_fits_Py_ssize_t(v, type, is_signed) (\ + (sizeof(type) < sizeof(Py_ssize_t)) ||\ + (sizeof(type) > sizeof(Py_ssize_t) &&\ + likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX) &&\ + (!is_signed || likely(v > (type)PY_SSIZE_T_MIN ||\ + v == (type)PY_SSIZE_T_MIN))) ||\ + (sizeof(type) == sizeof(Py_ssize_t) &&\ + (is_signed || likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX))) ) +static CYTHON_INLINE int __Pyx_is_valid_index(Py_ssize_t i, Py_ssize_t limit) { + return (size_t) i < (size_t) limit; +} +#if defined (__cplusplus) && __cplusplus >= 201103L + #include + #define __Pyx_sst_abs(value) std::abs(value) +#elif SIZEOF_INT >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) abs(value) +#elif SIZEOF_LONG >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) labs(value) +#elif defined (_MSC_VER) + #define __Pyx_sst_abs(value) ((Py_ssize_t)_abs64(value)) +#elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define __Pyx_sst_abs(value) llabs(value) +#elif defined (__GNUC__) + #define __Pyx_sst_abs(value) __builtin_llabs(value) +#else + #define __Pyx_sst_abs(value) ((value<0) ? -value : value) +#endif +static CYTHON_INLINE Py_ssize_t __Pyx_ssize_strlen(const char *s); +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject*); +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject*, Py_ssize_t* length); +static CYTHON_INLINE PyObject* __Pyx_PyByteArray_FromString(const char*); +#define __Pyx_PyByteArray_FromStringAndSize(s, l) PyByteArray_FromStringAndSize((const char*)s, l) +#define __Pyx_PyBytes_FromString PyBytes_FromString +#define __Pyx_PyBytes_FromStringAndSize PyBytes_FromStringAndSize +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char*); +#if PY_MAJOR_VERSION < 3 + #define __Pyx_PyStr_FromString __Pyx_PyBytes_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#else + #define __Pyx_PyStr_FromString __Pyx_PyUnicode_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyUnicode_FromStringAndSize +#endif +#define __Pyx_PyBytes_AsWritableString(s) ((char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableSString(s) ((signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableUString(s) ((unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsString(s) ((const char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsSString(s) ((const signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsUString(s) ((const unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyObject_AsWritableString(s) ((char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableSString(s) ((signed char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableUString(s) ((unsigned char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsSString(s) ((const signed char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsUString(s) ((const unsigned char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_FromCString(s) __Pyx_PyObject_FromString((const char*)s) +#define __Pyx_PyBytes_FromCString(s) __Pyx_PyBytes_FromString((const char*)s) +#define __Pyx_PyByteArray_FromCString(s) __Pyx_PyByteArray_FromString((const char*)s) +#define __Pyx_PyStr_FromCString(s) __Pyx_PyStr_FromString((const char*)s) +#define __Pyx_PyUnicode_FromCString(s) __Pyx_PyUnicode_FromString((const char*)s) +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const wchar_t *u) +{ + const wchar_t *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#else +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const Py_UNICODE *u) +{ + const Py_UNICODE *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#endif +#define __Pyx_PyUnicode_FromOrdinal(o) PyUnicode_FromOrdinal((int)o) +#define __Pyx_PyUnicode_FromUnicode(u) PyUnicode_FromUnicode(u, __Pyx_Py_UNICODE_strlen(u)) +#define __Pyx_PyUnicode_FromUnicodeAndLength PyUnicode_FromUnicode +#define __Pyx_PyUnicode_AsUnicode PyUnicode_AsUnicode +#define __Pyx_NewRef(obj) (Py_INCREF(obj), obj) +#define __Pyx_Owned_Py_None(b) __Pyx_NewRef(Py_None) +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b); +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject*); +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject*); +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x); +#define __Pyx_PySequence_Tuple(obj)\ + (likely(PyTuple_CheckExact(obj)) ? __Pyx_NewRef(obj) : PySequence_Tuple(obj)) +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject*); +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t); +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject*); +#if CYTHON_ASSUME_SAFE_MACROS +#define __pyx_PyFloat_AsDouble(x) (PyFloat_CheckExact(x) ? PyFloat_AS_DOUBLE(x) : PyFloat_AsDouble(x)) +#else +#define __pyx_PyFloat_AsDouble(x) PyFloat_AsDouble(x) +#endif +#define __pyx_PyFloat_AsFloat(x) ((float) __pyx_PyFloat_AsDouble(x)) +#if PY_MAJOR_VERSION >= 3 +#define __Pyx_PyNumber_Int(x) (PyLong_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Long(x)) +#else +#define __Pyx_PyNumber_Int(x) (PyInt_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Int(x)) +#endif +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_VERSION_HEX >= 0x030C00A7 + #ifndef _PyLong_SIGN_MASK + #define _PyLong_SIGN_MASK 3 + #endif + #ifndef _PyLong_NON_SIZE_BITS + #define _PyLong_NON_SIZE_BITS 3 + #endif + #define __Pyx_PyLong_Sign(x) (((PyLongObject*)x)->long_value.lv_tag & _PyLong_SIGN_MASK) + #define __Pyx_PyLong_IsNeg(x) ((__Pyx_PyLong_Sign(x) & 2) != 0) + #define __Pyx_PyLong_IsNonNeg(x) (!__Pyx_PyLong_IsNeg(x)) + #define __Pyx_PyLong_IsZero(x) (__Pyx_PyLong_Sign(x) & 1) + #define __Pyx_PyLong_IsPos(x) (__Pyx_PyLong_Sign(x) == 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) (__Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) ((Py_ssize_t) (((PyLongObject*)x)->long_value.lv_tag >> _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_SignedDigitCount(x)\ + ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * __Pyx_PyLong_DigitCount(x)) + #if defined(PyUnstable_Long_IsCompact) && defined(PyUnstable_Long_CompactValue) + #define __Pyx_PyLong_IsCompact(x) PyUnstable_Long_IsCompact((PyLongObject*) x) + #define __Pyx_PyLong_CompactValue(x) PyUnstable_Long_CompactValue((PyLongObject*) x) + #else + #define __Pyx_PyLong_IsCompact(x) (((PyLongObject*)x)->long_value.lv_tag < (2 << _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_CompactValue(x) ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * (Py_ssize_t) __Pyx_PyLong_Digits(x)[0]) + #endif + typedef Py_ssize_t __Pyx_compact_pylong; + typedef size_t __Pyx_compact_upylong; + #else + #define __Pyx_PyLong_IsNeg(x) (Py_SIZE(x) < 0) + #define __Pyx_PyLong_IsNonNeg(x) (Py_SIZE(x) >= 0) + #define __Pyx_PyLong_IsZero(x) (Py_SIZE(x) == 0) + #define __Pyx_PyLong_IsPos(x) (Py_SIZE(x) > 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) ((Py_SIZE(x) == 0) ? 0 : __Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) __Pyx_sst_abs(Py_SIZE(x)) + #define __Pyx_PyLong_SignedDigitCount(x) Py_SIZE(x) + #define __Pyx_PyLong_IsCompact(x) (Py_SIZE(x) == 0 || Py_SIZE(x) == 1 || Py_SIZE(x) == -1) + #define __Pyx_PyLong_CompactValue(x)\ + ((Py_SIZE(x) == 0) ? (sdigit) 0 : ((Py_SIZE(x) < 0) ? -(sdigit)__Pyx_PyLong_Digits(x)[0] : (sdigit)__Pyx_PyLong_Digits(x)[0])) + typedef sdigit __Pyx_compact_pylong; + typedef digit __Pyx_compact_upylong; + #endif + #if PY_VERSION_HEX >= 0x030C00A5 + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->long_value.ob_digit) + #else + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->ob_digit) + #endif +#endif +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII +#include +static int __Pyx_sys_getdefaultencoding_not_ascii; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + PyObject* ascii_chars_u = NULL; + PyObject* ascii_chars_b = NULL; + const char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + if (strcmp(default_encoding_c, "ascii") == 0) { + __Pyx_sys_getdefaultencoding_not_ascii = 0; + } else { + char ascii_chars[128]; + int c; + for (c = 0; c < 128; c++) { + ascii_chars[c] = (char) c; + } + __Pyx_sys_getdefaultencoding_not_ascii = 1; + ascii_chars_u = PyUnicode_DecodeASCII(ascii_chars, 128, NULL); + if (!ascii_chars_u) goto bad; + ascii_chars_b = PyUnicode_AsEncodedString(ascii_chars_u, default_encoding_c, NULL); + if (!ascii_chars_b || !PyBytes_Check(ascii_chars_b) || memcmp(ascii_chars, PyBytes_AS_STRING(ascii_chars_b), 128) != 0) { + PyErr_Format( + PyExc_ValueError, + "This module compiled with c_string_encoding=ascii, but default encoding '%.200s' is not a superset of ascii.", + default_encoding_c); + goto bad; + } + Py_DECREF(ascii_chars_u); + Py_DECREF(ascii_chars_b); + } + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + Py_XDECREF(ascii_chars_u); + Py_XDECREF(ascii_chars_b); + return -1; +} +#endif +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT && PY_MAJOR_VERSION >= 3 +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_DecodeUTF8(c_str, size, NULL) +#else +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_Decode(c_str, size, __PYX_DEFAULT_STRING_ENCODING, NULL) +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +#include +static char* __PYX_DEFAULT_STRING_ENCODING; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) (const char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + __PYX_DEFAULT_STRING_ENCODING = (char*) malloc(strlen(default_encoding_c) + 1); + if (!__PYX_DEFAULT_STRING_ENCODING) goto bad; + strcpy(__PYX_DEFAULT_STRING_ENCODING, default_encoding_c); + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + return -1; +} +#endif +#endif + + +/* Test for GCC > 2.95 */ +#if defined(__GNUC__) && (__GNUC__ > 2 || (__GNUC__ == 2 && (__GNUC_MINOR__ > 95))) + #define likely(x) __builtin_expect(!!(x), 1) + #define unlikely(x) __builtin_expect(!!(x), 0) +#else /* !__GNUC__ or GCC < 2.95 */ + #define likely(x) (x) + #define unlikely(x) (x) +#endif /* __GNUC__ */ +static CYTHON_INLINE void __Pyx_pretend_to_initialize(void* ptr) { (void)ptr; } + +#if !CYTHON_USE_MODULE_STATE +static PyObject *__pyx_m = NULL; +#endif +static int __pyx_lineno; +static int __pyx_clineno = 0; +static const char * __pyx_cfilenm = __FILE__; +static const char *__pyx_filename; + +/* Header.proto */ +#if !defined(CYTHON_CCOMPLEX) + #if defined(__cplusplus) + #define CYTHON_CCOMPLEX 1 + #elif (defined(_Complex_I) && !defined(_MSC_VER)) || ((defined (__STDC_VERSION__) && __STDC_VERSION__ >= 201112L) && !defined(__STDC_NO_COMPLEX__) && !defined(_MSC_VER)) + #define CYTHON_CCOMPLEX 1 + #else + #define CYTHON_CCOMPLEX 0 + #endif +#endif +#if CYTHON_CCOMPLEX + #ifdef __cplusplus + #include + #else + #include + #endif +#endif +#if CYTHON_CCOMPLEX && !defined(__cplusplus) && defined(__sun__) && defined(__GNUC__) + #undef _Complex_I + #define _Complex_I 1.0fj +#endif + +/* #### Code section: filename_table ### */ + +static const char *__pyx_f[] = { + "cereal/visionipc/visionipc_pyx.pyx", + "", + "__init__.cython-30.pxd", + "cereal/visionipc/visionipc_pyx.pxd", + "type.pxd", +}; +/* #### Code section: utility_code_proto_before_types ### */ +/* ForceInitThreads.proto */ +#ifndef __PYX_FORCE_INIT_THREADS + #define __PYX_FORCE_INIT_THREADS 0 +#endif + +/* NoFastGil.proto */ +#define __Pyx_PyGILState_Ensure PyGILState_Ensure +#define __Pyx_PyGILState_Release PyGILState_Release +#define __Pyx_FastGIL_Remember() +#define __Pyx_FastGIL_Forget() +#define __Pyx_FastGilFuncInit() + +/* BufferFormatStructs.proto */ +struct __Pyx_StructField_; +#define __PYX_BUF_FLAGS_PACKED_STRUCT (1 << 0) +typedef struct { + const char* name; + struct __Pyx_StructField_* fields; + size_t size; + size_t arraysize[8]; + int ndim; + char typegroup; + char is_unsigned; + int flags; +} __Pyx_TypeInfo; +typedef struct __Pyx_StructField_ { + __Pyx_TypeInfo* type; + const char* name; + size_t offset; +} __Pyx_StructField; +typedef struct { + __Pyx_StructField* field; + size_t parent_offset; +} __Pyx_BufFmt_StackElem; +typedef struct { + __Pyx_StructField root; + __Pyx_BufFmt_StackElem* head; + size_t fmt_offset; + size_t new_count, enc_count; + size_t struct_alignment; + int is_complex; + char enc_type; + char new_packmode; + char enc_packmode; + char is_valid_array; +} __Pyx_BufFmt_Context; + +/* Atomics.proto */ +#include +#ifndef CYTHON_ATOMICS + #define CYTHON_ATOMICS 1 +#endif +#define __PYX_CYTHON_ATOMICS_ENABLED() CYTHON_ATOMICS +#define __pyx_atomic_int_type int +#define __pyx_nonatomic_int_type int +#if CYTHON_ATOMICS && (defined(__STDC_VERSION__) &&\ + (__STDC_VERSION__ >= 201112L) &&\ + !defined(__STDC_NO_ATOMICS__)) + #include +#elif CYTHON_ATOMICS && (defined(__cplusplus) && (\ + (__cplusplus >= 201103L) ||\ + (defined(_MSC_VER) && _MSC_VER >= 1700))) + #include +#endif +#if CYTHON_ATOMICS && (defined(__STDC_VERSION__) &&\ + (__STDC_VERSION__ >= 201112L) &&\ + !defined(__STDC_NO_ATOMICS__) &&\ + ATOMIC_INT_LOCK_FREE == 2) + #undef __pyx_atomic_int_type + #define __pyx_atomic_int_type atomic_int + #define __pyx_atomic_incr_aligned(value) atomic_fetch_add_explicit(value, 1, memory_order_relaxed) + #define __pyx_atomic_decr_aligned(value) atomic_fetch_sub_explicit(value, 1, memory_order_acq_rel) + #if defined(__PYX_DEBUG_ATOMICS) && defined(_MSC_VER) + #pragma message ("Using standard C atomics") + #elif defined(__PYX_DEBUG_ATOMICS) + #warning "Using standard C atomics" + #endif +#elif CYTHON_ATOMICS && (defined(__cplusplus) && (\ + (__cplusplus >= 201103L) ||\ +\ + (defined(_MSC_VER) && _MSC_VER >= 1700)) &&\ + ATOMIC_INT_LOCK_FREE == 2) + #undef __pyx_atomic_int_type + #define __pyx_atomic_int_type std::atomic_int + #define __pyx_atomic_incr_aligned(value) std::atomic_fetch_add_explicit(value, 1, std::memory_order_relaxed) + #define __pyx_atomic_decr_aligned(value) std::atomic_fetch_sub_explicit(value, 1, std::memory_order_acq_rel) + #if defined(__PYX_DEBUG_ATOMICS) && defined(_MSC_VER) + #pragma message ("Using standard C++ atomics") + #elif defined(__PYX_DEBUG_ATOMICS) + #warning "Using standard C++ atomics" + #endif +#elif CYTHON_ATOMICS && (__GNUC__ >= 5 || (__GNUC__ == 4 &&\ + (__GNUC_MINOR__ > 1 ||\ + (__GNUC_MINOR__ == 1 && __GNUC_PATCHLEVEL__ >= 2)))) + #define __pyx_atomic_incr_aligned(value) __sync_fetch_and_add(value, 1) + #define __pyx_atomic_decr_aligned(value) __sync_fetch_and_sub(value, 1) + #ifdef __PYX_DEBUG_ATOMICS + #warning "Using GNU atomics" + #endif +#elif CYTHON_ATOMICS && defined(_MSC_VER) + #include + #undef __pyx_atomic_int_type + #define __pyx_atomic_int_type long + #undef __pyx_nonatomic_int_type + #define __pyx_nonatomic_int_type long + #pragma intrinsic (_InterlockedExchangeAdd) + #define __pyx_atomic_incr_aligned(value) _InterlockedExchangeAdd(value, 1) + #define __pyx_atomic_decr_aligned(value) _InterlockedExchangeAdd(value, -1) + #ifdef __PYX_DEBUG_ATOMICS + #pragma message ("Using MSVC atomics") + #endif +#else + #undef CYTHON_ATOMICS + #define CYTHON_ATOMICS 0 + #ifdef __PYX_DEBUG_ATOMICS + #warning "Not using atomics" + #endif +#endif +#if CYTHON_ATOMICS + #define __pyx_add_acquisition_count(memview)\ + __pyx_atomic_incr_aligned(__pyx_get_slice_count_pointer(memview)) + #define __pyx_sub_acquisition_count(memview)\ + __pyx_atomic_decr_aligned(__pyx_get_slice_count_pointer(memview)) +#else + #define __pyx_add_acquisition_count(memview)\ + __pyx_add_acquisition_count_locked(__pyx_get_slice_count_pointer(memview), memview->lock) + #define __pyx_sub_acquisition_count(memview)\ + __pyx_sub_acquisition_count_locked(__pyx_get_slice_count_pointer(memview), memview->lock) +#endif + +/* MemviewSliceStruct.proto */ +struct __pyx_memoryview_obj; +typedef struct { + struct __pyx_memoryview_obj *memview; + char *data; + Py_ssize_t shape[8]; + Py_ssize_t strides[8]; + Py_ssize_t suboffsets[8]; +} __Pyx_memviewslice; +#define __Pyx_MemoryView_Len(m) (m.shape[0]) + +/* #### Code section: numeric_typedefs ### */ + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":730 + * # in Cython to enable them only on the right systems. + * + * ctypedef npy_int8 int8_t # <<<<<<<<<<<<<< + * ctypedef npy_int16 int16_t + * ctypedef npy_int32 int32_t + */ +typedef npy_int8 __pyx_t_5numpy_int8_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":731 + * + * ctypedef npy_int8 int8_t + * ctypedef npy_int16 int16_t # <<<<<<<<<<<<<< + * ctypedef npy_int32 int32_t + * ctypedef npy_int64 int64_t + */ +typedef npy_int16 __pyx_t_5numpy_int16_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":732 + * ctypedef npy_int8 int8_t + * ctypedef npy_int16 int16_t + * ctypedef npy_int32 int32_t # <<<<<<<<<<<<<< + * ctypedef npy_int64 int64_t + * #ctypedef npy_int96 int96_t + */ +typedef npy_int32 __pyx_t_5numpy_int32_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":733 + * ctypedef npy_int16 int16_t + * ctypedef npy_int32 int32_t + * ctypedef npy_int64 int64_t # <<<<<<<<<<<<<< + * #ctypedef npy_int96 int96_t + * #ctypedef npy_int128 int128_t + */ +typedef npy_int64 __pyx_t_5numpy_int64_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":737 + * #ctypedef npy_int128 int128_t + * + * ctypedef npy_uint8 uint8_t # <<<<<<<<<<<<<< + * ctypedef npy_uint16 uint16_t + * ctypedef npy_uint32 uint32_t + */ +typedef npy_uint8 __pyx_t_5numpy_uint8_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":738 + * + * ctypedef npy_uint8 uint8_t + * ctypedef npy_uint16 uint16_t # <<<<<<<<<<<<<< + * ctypedef npy_uint32 uint32_t + * ctypedef npy_uint64 uint64_t + */ +typedef npy_uint16 __pyx_t_5numpy_uint16_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":739 + * ctypedef npy_uint8 uint8_t + * ctypedef npy_uint16 uint16_t + * ctypedef npy_uint32 uint32_t # <<<<<<<<<<<<<< + * ctypedef npy_uint64 uint64_t + * #ctypedef npy_uint96 uint96_t + */ +typedef npy_uint32 __pyx_t_5numpy_uint32_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":740 + * ctypedef npy_uint16 uint16_t + * ctypedef npy_uint32 uint32_t + * ctypedef npy_uint64 uint64_t # <<<<<<<<<<<<<< + * #ctypedef npy_uint96 uint96_t + * #ctypedef npy_uint128 uint128_t + */ +typedef npy_uint64 __pyx_t_5numpy_uint64_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":744 + * #ctypedef npy_uint128 uint128_t + * + * ctypedef npy_float32 float32_t # <<<<<<<<<<<<<< + * ctypedef npy_float64 float64_t + * #ctypedef npy_float80 float80_t + */ +typedef npy_float32 __pyx_t_5numpy_float32_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":745 + * + * ctypedef npy_float32 float32_t + * ctypedef npy_float64 float64_t # <<<<<<<<<<<<<< + * #ctypedef npy_float80 float80_t + * #ctypedef npy_float128 float128_t + */ +typedef npy_float64 __pyx_t_5numpy_float64_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":754 + * # The int types are mapped a bit surprising -- + * # numpy.int corresponds to 'l' and numpy.long to 'q' + * ctypedef npy_long int_t # <<<<<<<<<<<<<< + * ctypedef npy_longlong longlong_t + * + */ +typedef npy_long __pyx_t_5numpy_int_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":755 + * # numpy.int corresponds to 'l' and numpy.long to 'q' + * ctypedef npy_long int_t + * ctypedef npy_longlong longlong_t # <<<<<<<<<<<<<< + * + * ctypedef npy_ulong uint_t + */ +typedef npy_longlong __pyx_t_5numpy_longlong_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":757 + * ctypedef npy_longlong longlong_t + * + * ctypedef npy_ulong uint_t # <<<<<<<<<<<<<< + * ctypedef npy_ulonglong ulonglong_t + * + */ +typedef npy_ulong __pyx_t_5numpy_uint_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":758 + * + * ctypedef npy_ulong uint_t + * ctypedef npy_ulonglong ulonglong_t # <<<<<<<<<<<<<< + * + * ctypedef npy_intp intp_t + */ +typedef npy_ulonglong __pyx_t_5numpy_ulonglong_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":760 + * ctypedef npy_ulonglong ulonglong_t + * + * ctypedef npy_intp intp_t # <<<<<<<<<<<<<< + * ctypedef npy_uintp uintp_t + * + */ +typedef npy_intp __pyx_t_5numpy_intp_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":761 + * + * ctypedef npy_intp intp_t + * ctypedef npy_uintp uintp_t # <<<<<<<<<<<<<< + * + * ctypedef npy_double float_t + */ +typedef npy_uintp __pyx_t_5numpy_uintp_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":763 + * ctypedef npy_uintp uintp_t + * + * ctypedef npy_double float_t # <<<<<<<<<<<<<< + * ctypedef npy_double double_t + * ctypedef npy_longdouble longdouble_t + */ +typedef npy_double __pyx_t_5numpy_float_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":764 + * + * ctypedef npy_double float_t + * ctypedef npy_double double_t # <<<<<<<<<<<<<< + * ctypedef npy_longdouble longdouble_t + * + */ +typedef npy_double __pyx_t_5numpy_double_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":765 + * ctypedef npy_double float_t + * ctypedef npy_double double_t + * ctypedef npy_longdouble longdouble_t # <<<<<<<<<<<<<< + * + * ctypedef npy_cfloat cfloat_t + */ +typedef npy_longdouble __pyx_t_5numpy_longdouble_t; +/* #### Code section: complex_type_declarations ### */ +/* Declarations.proto */ +#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #ifdef __cplusplus + typedef ::std::complex< float > __pyx_t_float_complex; + #else + typedef float _Complex __pyx_t_float_complex; + #endif +#else + typedef struct { float real, imag; } __pyx_t_float_complex; +#endif +static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float, float); + +/* Declarations.proto */ +#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #ifdef __cplusplus + typedef ::std::complex< double > __pyx_t_double_complex; + #else + typedef double _Complex __pyx_t_double_complex; + #endif +#else + typedef struct { double real, imag; } __pyx_t_double_complex; +#endif +static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double, double); + +/* #### Code section: type_declarations ### */ + +/*--- Type declarations ---*/ +struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_CLContext; +struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf; +struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer; +struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient; +struct __pyx_obj___Pyx_EnumMeta; +struct __pyx_array_obj; +struct __pyx_MemviewEnum_obj; +struct __pyx_memoryview_obj; +struct __pyx_memoryviewslice_obj; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":767 + * ctypedef npy_longdouble longdouble_t + * + * ctypedef npy_cfloat cfloat_t # <<<<<<<<<<<<<< + * ctypedef npy_cdouble cdouble_t + * ctypedef npy_clongdouble clongdouble_t + */ +typedef npy_cfloat __pyx_t_5numpy_cfloat_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":768 + * + * ctypedef npy_cfloat cfloat_t + * ctypedef npy_cdouble cdouble_t # <<<<<<<<<<<<<< + * ctypedef npy_clongdouble clongdouble_t + * + */ +typedef npy_cdouble __pyx_t_5numpy_cdouble_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":769 + * ctypedef npy_cfloat cfloat_t + * ctypedef npy_cdouble cdouble_t + * ctypedef npy_clongdouble clongdouble_t # <<<<<<<<<<<<<< + * + * ctypedef npy_cdouble complex_t + */ +typedef npy_clongdouble __pyx_t_5numpy_clongdouble_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":771 + * ctypedef npy_clongdouble clongdouble_t + * + * ctypedef npy_cdouble complex_t # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew1(a): + */ +typedef npy_cdouble __pyx_t_5numpy_complex_t; + +/* "cereal/visionipc/visionipc_pyx.pyx":24 + * + * + * cpdef enum VisionStreamType: # <<<<<<<<<<<<<< + * VISION_STREAM_ROAD + * VISION_STREAM_DRIVER + */ +enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType { + __pyx_e_6cereal_9visionipc_13visionipc_pyx_VISION_STREAM_ROAD, + __pyx_e_6cereal_9visionipc_13visionipc_pyx_VISION_STREAM_DRIVER, + __pyx_e_6cereal_9visionipc_13visionipc_pyx_VISION_STREAM_WIDE_ROAD, + __pyx_e_6cereal_9visionipc_13visionipc_pyx_VISION_STREAM_MAP +}; + +/* "cereal/visionipc/visionipc_pyx.pxd":7 + * from .visionipc cimport cl_device_id, cl_context + * + * cdef class CLContext: # <<<<<<<<<<<<<< + * cdef cl_device_id device_id + * cdef cl_context context + */ +struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_CLContext { + PyObject_HEAD + cl_device_id device_id; + cl_context context; +}; + + +/* "cereal/visionipc/visionipc_pyx.pxd":11 + * cdef cl_context context + * + * cdef class VisionBuf: # <<<<<<<<<<<<<< + * cdef cppVisionBuf * buf + * + */ +struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf { + PyObject_HEAD + struct __pyx_vtabstruct_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_vtab; + VisionBuf *buf; +}; + + +/* "cereal/visionipc/visionipc_pyx.pyx":63 + * + * + * cdef class VisionIpcServer: # <<<<<<<<<<<<<< + * cdef cppVisionIpcServer * server + * + */ +struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer { + PyObject_HEAD + VisionIpcServer *server; +}; + + +/* "cereal/visionipc/visionipc_pyx.pyx":97 + * + * + * cdef class VisionIpcClient: # <<<<<<<<<<<<<< + * cdef cppVisionIpcClient * client + * cdef VisionIpcBufExtra extra + */ +struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient { + PyObject_HEAD + VisionIpcClient *client; + struct VisionIpcBufExtra extra; +}; + + +/* "EnumBase":16 + * + * @cython.internal + * cdef class __Pyx_EnumMeta(type): # <<<<<<<<<<<<<< + * def __init__(cls, name, parents, dct): + * type.__init__(cls, name, parents, dct) + */ +struct __pyx_obj___Pyx_EnumMeta { + PyHeapTypeObject __pyx_base; +}; + + +/* "View.MemoryView":114 + * @cython.collection_type("sequence") + * @cname("__pyx_array") + * cdef class array: # <<<<<<<<<<<<<< + * + * cdef: + */ +struct __pyx_array_obj { + PyObject_HEAD + struct __pyx_vtabstruct_array *__pyx_vtab; + char *data; + Py_ssize_t len; + char *format; + int ndim; + Py_ssize_t *_shape; + Py_ssize_t *_strides; + Py_ssize_t itemsize; + PyObject *mode; + PyObject *_format; + void (*callback_free_data)(void *); + int free_data; + int dtype_is_object; +}; + + +/* "View.MemoryView":302 + * + * @cname('__pyx_MemviewEnum') + * cdef class Enum(object): # <<<<<<<<<<<<<< + * cdef object name + * def __init__(self, name): + */ +struct __pyx_MemviewEnum_obj { + PyObject_HEAD + PyObject *name; +}; + + +/* "View.MemoryView":337 + * + * @cname('__pyx_memoryview') + * cdef class memoryview: # <<<<<<<<<<<<<< + * + * cdef object obj + */ +struct __pyx_memoryview_obj { + PyObject_HEAD + struct __pyx_vtabstruct_memoryview *__pyx_vtab; + PyObject *obj; + PyObject *_size; + PyObject *_array_interface; + PyThread_type_lock lock; + __pyx_atomic_int_type acquisition_count; + Py_buffer view; + int flags; + int dtype_is_object; + __Pyx_TypeInfo *typeinfo; +}; + + +/* "View.MemoryView":952 + * @cython.collection_type("sequence") + * @cname('__pyx_memoryviewslice') + * cdef class _memoryviewslice(memoryview): # <<<<<<<<<<<<<< + * "Internal class for passing memoryview slices to Python" + * + */ +struct __pyx_memoryviewslice_obj { + struct __pyx_memoryview_obj __pyx_base; + __Pyx_memviewslice from_slice; + PyObject *from_object; + PyObject *(*to_object_func)(char *); + int (*to_dtype_func)(char *, PyObject *); +}; + + + +/* "View.MemoryView":114 + * @cython.collection_type("sequence") + * @cname("__pyx_array") + * cdef class array: # <<<<<<<<<<<<<< + * + * cdef: + */ + +struct __pyx_vtabstruct_array { + PyObject *(*get_memview)(struct __pyx_array_obj *); +}; +static struct __pyx_vtabstruct_array *__pyx_vtabptr_array; + + +/* "cereal/visionipc/visionipc_pyx.pyx":31 + * + * + * cdef class VisionBuf: # <<<<<<<<<<<<<< + * @staticmethod + * cdef create(cppVisionBuf * cbuf): + */ + +struct __pyx_vtabstruct_6cereal_9visionipc_13visionipc_pyx_VisionBuf { + PyObject *(*create)(VisionBuf *); +}; +static struct __pyx_vtabstruct_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_vtabptr_6cereal_9visionipc_13visionipc_pyx_VisionBuf; + + +/* "View.MemoryView":337 + * + * @cname('__pyx_memoryview') + * cdef class memoryview: # <<<<<<<<<<<<<< + * + * cdef object obj + */ + +struct __pyx_vtabstruct_memoryview { + char *(*get_item_pointer)(struct __pyx_memoryview_obj *, PyObject *); + PyObject *(*is_slice)(struct __pyx_memoryview_obj *, PyObject *); + PyObject *(*setitem_slice_assignment)(struct __pyx_memoryview_obj *, PyObject *, PyObject *); + PyObject *(*setitem_slice_assign_scalar)(struct __pyx_memoryview_obj *, struct __pyx_memoryview_obj *, PyObject *); + PyObject *(*setitem_indexed)(struct __pyx_memoryview_obj *, PyObject *, PyObject *); + PyObject *(*convert_item_to_object)(struct __pyx_memoryview_obj *, char *); + PyObject *(*assign_item_from_object)(struct __pyx_memoryview_obj *, char *, PyObject *); + PyObject *(*_get_base)(struct __pyx_memoryview_obj *); +}; +static struct __pyx_vtabstruct_memoryview *__pyx_vtabptr_memoryview; + + +/* "View.MemoryView":952 + * @cython.collection_type("sequence") + * @cname('__pyx_memoryviewslice') + * cdef class _memoryviewslice(memoryview): # <<<<<<<<<<<<<< + * "Internal class for passing memoryview slices to Python" + * + */ + +struct __pyx_vtabstruct__memoryviewslice { + struct __pyx_vtabstruct_memoryview __pyx_base; +}; +static struct __pyx_vtabstruct__memoryviewslice *__pyx_vtabptr__memoryviewslice; +/* #### Code section: utility_code_proto ### */ + +/* --- Runtime support code (head) --- */ +/* Refnanny.proto */ +#ifndef CYTHON_REFNANNY + #define CYTHON_REFNANNY 0 +#endif +#if CYTHON_REFNANNY + typedef struct { + void (*INCREF)(void*, PyObject*, Py_ssize_t); + void (*DECREF)(void*, PyObject*, Py_ssize_t); + void (*GOTREF)(void*, PyObject*, Py_ssize_t); + void (*GIVEREF)(void*, PyObject*, Py_ssize_t); + void* (*SetupContext)(const char*, Py_ssize_t, const char*); + void (*FinishContext)(void**); + } __Pyx_RefNannyAPIStruct; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNanny = NULL; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname); + #define __Pyx_RefNannyDeclarations void *__pyx_refnanny = NULL; +#ifdef WITH_THREAD + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + if (acquire_gil) {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + PyGILState_Release(__pyx_gilstate_save);\ + } else {\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + } + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } +#else + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__)) + #define __Pyx_RefNannyFinishContextNogil() __Pyx_RefNannyFinishContext() +#endif + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } + #define __Pyx_RefNannyFinishContext()\ + __Pyx_RefNanny->FinishContext(&__pyx_refnanny) + #define __Pyx_INCREF(r) __Pyx_RefNanny->INCREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_DECREF(r) __Pyx_RefNanny->DECREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GOTREF(r) __Pyx_RefNanny->GOTREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GIVEREF(r) __Pyx_RefNanny->GIVEREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_XINCREF(r) do { if((r) == NULL); else {__Pyx_INCREF(r); }} while(0) + #define __Pyx_XDECREF(r) do { if((r) == NULL); else {__Pyx_DECREF(r); }} while(0) + #define __Pyx_XGOTREF(r) do { if((r) == NULL); else {__Pyx_GOTREF(r); }} while(0) + #define __Pyx_XGIVEREF(r) do { if((r) == NULL); else {__Pyx_GIVEREF(r);}} while(0) +#else + #define __Pyx_RefNannyDeclarations + #define __Pyx_RefNannySetupContext(name, acquire_gil) + #define __Pyx_RefNannyFinishContextNogil() + #define __Pyx_RefNannyFinishContext() + #define __Pyx_INCREF(r) Py_INCREF(r) + #define __Pyx_DECREF(r) Py_DECREF(r) + #define __Pyx_GOTREF(r) + #define __Pyx_GIVEREF(r) + #define __Pyx_XINCREF(r) Py_XINCREF(r) + #define __Pyx_XDECREF(r) Py_XDECREF(r) + #define __Pyx_XGOTREF(r) + #define __Pyx_XGIVEREF(r) +#endif +#define __Pyx_Py_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; Py_XDECREF(tmp);\ + } while (0) +#define __Pyx_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_XDECREF(tmp);\ + } while (0) +#define __Pyx_DECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_DECREF(tmp);\ + } while (0) +#define __Pyx_CLEAR(r) do { PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);} while(0) +#define __Pyx_XCLEAR(r) do { if((r) != NULL) {PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);}} while(0) + +/* PyErrExceptionMatches.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_ExceptionMatches(err) __Pyx_PyErr_ExceptionMatchesInState(__pyx_tstate, err) +static CYTHON_INLINE int __Pyx_PyErr_ExceptionMatchesInState(PyThreadState* tstate, PyObject* err); +#else +#define __Pyx_PyErr_ExceptionMatches(err) PyErr_ExceptionMatches(err) +#endif + +/* PyThreadStateGet.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyThreadState_declare PyThreadState *__pyx_tstate; +#define __Pyx_PyThreadState_assign __pyx_tstate = __Pyx_PyThreadState_Current; +#if PY_VERSION_HEX >= 0x030C00A6 +#define __Pyx_PyErr_Occurred() (__pyx_tstate->current_exception != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->current_exception ? (PyObject*) Py_TYPE(__pyx_tstate->current_exception) : (PyObject*) NULL) +#else +#define __Pyx_PyErr_Occurred() (__pyx_tstate->curexc_type != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->curexc_type) +#endif +#else +#define __Pyx_PyThreadState_declare +#define __Pyx_PyThreadState_assign +#define __Pyx_PyErr_Occurred() (PyErr_Occurred() != NULL) +#define __Pyx_PyErr_CurrentExceptionType() PyErr_Occurred() +#endif + +/* PyErrFetchRestore.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_Clear() __Pyx_ErrRestore(NULL, NULL, NULL) +#define __Pyx_ErrRestoreWithState(type, value, tb) __Pyx_ErrRestoreInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) __Pyx_ErrFetchInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) __Pyx_ErrRestoreInState(__pyx_tstate, type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) __Pyx_ErrFetchInState(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb); +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A6 +#define __Pyx_PyErr_SetNone(exc) (Py_INCREF(exc), __Pyx_ErrRestore((exc), NULL, NULL)) +#else +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#endif +#else +#define __Pyx_PyErr_Clear() PyErr_Clear() +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#define __Pyx_ErrRestoreWithState(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestoreInState(tstate, type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchInState(tstate, type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) PyErr_Fetch(type, value, tb) +#endif + +/* PyObjectGetAttrStr.proto */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GetAttrStr(o,n) PyObject_GetAttr(o,n) +#endif + +/* PyObjectGetAttrStrNoError.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name); + +/* GetBuiltinName.proto */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name); + +/* TupleAndListFromArray.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n); +static CYTHON_INLINE PyObject* __Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n); +#endif + +/* IncludeStringH.proto */ +#include + +/* BytesEquals.proto */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals); + +/* UnicodeEquals.proto */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals); + +/* fastcall.proto */ +#if CYTHON_AVOID_BORROWED_REFS + #define __Pyx_Arg_VARARGS(args, i) PySequence_GetItem(args, i) +#elif CYTHON_ASSUME_SAFE_MACROS + #define __Pyx_Arg_VARARGS(args, i) PyTuple_GET_ITEM(args, i) +#else + #define __Pyx_Arg_VARARGS(args, i) PyTuple_GetItem(args, i) +#endif +#if CYTHON_AVOID_BORROWED_REFS + #define __Pyx_Arg_NewRef_VARARGS(arg) __Pyx_NewRef(arg) + #define __Pyx_Arg_XDECREF_VARARGS(arg) Py_XDECREF(arg) +#else + #define __Pyx_Arg_NewRef_VARARGS(arg) arg + #define __Pyx_Arg_XDECREF_VARARGS(arg) +#endif +#define __Pyx_NumKwargs_VARARGS(kwds) PyDict_Size(kwds) +#define __Pyx_KwValues_VARARGS(args, nargs) NULL +#define __Pyx_GetKwValue_VARARGS(kw, kwvalues, s) __Pyx_PyDict_GetItemStrWithError(kw, s) +#define __Pyx_KwargsAsDict_VARARGS(kw, kwvalues) PyDict_Copy(kw) +#if CYTHON_METH_FASTCALL + #define __Pyx_Arg_FASTCALL(args, i) args[i] + #define __Pyx_NumKwargs_FASTCALL(kwds) PyTuple_GET_SIZE(kwds) + #define __Pyx_KwValues_FASTCALL(args, nargs) ((args) + (nargs)) + static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 + CYTHON_UNUSED static PyObject *__Pyx_KwargsAsDict_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues); + #else + #define __Pyx_KwargsAsDict_FASTCALL(kw, kwvalues) _PyStack_AsDict(kwvalues, kw) + #endif + #define __Pyx_Arg_NewRef_FASTCALL(arg) arg /* no-op, __Pyx_Arg_FASTCALL is direct and this needs + to have the same reference counting */ + #define __Pyx_Arg_XDECREF_FASTCALL(arg) +#else + #define __Pyx_Arg_FASTCALL __Pyx_Arg_VARARGS + #define __Pyx_NumKwargs_FASTCALL __Pyx_NumKwargs_VARARGS + #define __Pyx_KwValues_FASTCALL __Pyx_KwValues_VARARGS + #define __Pyx_GetKwValue_FASTCALL __Pyx_GetKwValue_VARARGS + #define __Pyx_KwargsAsDict_FASTCALL __Pyx_KwargsAsDict_VARARGS + #define __Pyx_Arg_NewRef_FASTCALL(arg) __Pyx_Arg_NewRef_VARARGS(arg) + #define __Pyx_Arg_XDECREF_FASTCALL(arg) __Pyx_Arg_XDECREF_VARARGS(arg) +#endif +#if CYTHON_COMPILING_IN_CPYTHON && CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_VARARGS(args, start), stop - start) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_FASTCALL(args, start), stop - start) +#else +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) PyTuple_GetSlice(args, start, stop) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) PyTuple_GetSlice(args, start, stop) +#endif + +/* RaiseArgTupleInvalid.proto */ +static void __Pyx_RaiseArgtupleInvalid(const char* func_name, int exact, + Py_ssize_t num_min, Py_ssize_t num_max, Py_ssize_t num_found); + +/* RaiseDoubleKeywords.proto */ +static void __Pyx_RaiseDoubleKeywordsError(const char* func_name, PyObject* kw_name); + +/* ParseKeywords.proto */ +static int __Pyx_ParseOptionalKeywords(PyObject *kwds, PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, PyObject *values[], Py_ssize_t num_pos_args, + const char* function_name); + +/* PyFunctionFastCall.proto */ +#if CYTHON_FAST_PYCALL +#if !CYTHON_VECTORCALL +#define __Pyx_PyFunction_FastCall(func, args, nargs)\ + __Pyx_PyFunction_FastCallDict((func), (args), (nargs), NULL) +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs); +#endif +#define __Pyx_BUILD_ASSERT_EXPR(cond)\ + (sizeof(char [1 - 2*!(cond)]) - 1) +#ifndef Py_MEMBER_SIZE +#define Py_MEMBER_SIZE(type, member) sizeof(((type *)0)->member) +#endif +#if !CYTHON_VECTORCALL +#if PY_VERSION_HEX >= 0x03080000 + #include "frameobject.h" +#if PY_VERSION_HEX >= 0x030b00a6 && !CYTHON_COMPILING_IN_LIMITED_API + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif + #define __Pxy_PyFrame_Initialize_Offsets() + #define __Pyx_PyFrame_GetLocalsplus(frame) ((frame)->f_localsplus) +#else + static size_t __pyx_pyframe_localsplus_offset = 0; + #include "frameobject.h" + #define __Pxy_PyFrame_Initialize_Offsets()\ + ((void)__Pyx_BUILD_ASSERT_EXPR(sizeof(PyFrameObject) == offsetof(PyFrameObject, f_localsplus) + Py_MEMBER_SIZE(PyFrameObject, f_localsplus)),\ + (void)(__pyx_pyframe_localsplus_offset = ((size_t)PyFrame_Type.tp_basicsize) - Py_MEMBER_SIZE(PyFrameObject, f_localsplus))) + #define __Pyx_PyFrame_GetLocalsplus(frame)\ + (assert(__pyx_pyframe_localsplus_offset), (PyObject **)(((char *)(frame)) + __pyx_pyframe_localsplus_offset)) +#endif +#endif +#endif + +/* PyObjectCall.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw); +#else +#define __Pyx_PyObject_Call(func, arg, kw) PyObject_Call(func, arg, kw) +#endif + +/* PyObjectCallMethO.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg); +#endif + +/* PyObjectFastCall.proto */ +#define __Pyx_PyObject_FastCall(func, args, nargs) __Pyx_PyObject_FastCallDict(func, args, (size_t)(nargs), NULL) +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs); + +/* PyObjectSetAttrStr.proto */ +#if CYTHON_USE_TYPE_SLOTS +#define __Pyx_PyObject_DelAttrStr(o,n) __Pyx_PyObject_SetAttrStr(o, n, NULL) +static CYTHON_INLINE int __Pyx_PyObject_SetAttrStr(PyObject* obj, PyObject* attr_name, PyObject* value); +#else +#define __Pyx_PyObject_DelAttrStr(o,n) PyObject_DelAttr(o,n) +#define __Pyx_PyObject_SetAttrStr(o,n,v) PyObject_SetAttr(o,n,v) +#endif + +/* GetItemInt.proto */ +#define __Pyx_GetItemInt(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_Fast(o, (Py_ssize_t)i, is_list, wraparound, boundscheck) :\ + (is_list ? (PyErr_SetString(PyExc_IndexError, "list index out of range"), (PyObject*)NULL) :\ + __Pyx_GetItemInt_Generic(o, to_py_func(i)))) +#define __Pyx_GetItemInt_List(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_List_Fast(o, (Py_ssize_t)i, wraparound, boundscheck) :\ + (PyErr_SetString(PyExc_IndexError, "list index out of range"), (PyObject*)NULL)) +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_List_Fast(PyObject *o, Py_ssize_t i, + int wraparound, int boundscheck); +#define __Pyx_GetItemInt_Tuple(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_Tuple_Fast(o, (Py_ssize_t)i, wraparound, boundscheck) :\ + (PyErr_SetString(PyExc_IndexError, "tuple index out of range"), (PyObject*)NULL)) +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Tuple_Fast(PyObject *o, Py_ssize_t i, + int wraparound, int boundscheck); +static PyObject *__Pyx_GetItemInt_Generic(PyObject *o, PyObject* j); +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Fast(PyObject *o, Py_ssize_t i, + int is_list, int wraparound, int boundscheck); + +/* PyObjectCallOneArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg); + +/* ObjectGetItem.proto */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject *__Pyx_PyObject_GetItem(PyObject *obj, PyObject *key); +#else +#define __Pyx_PyObject_GetItem(obj, key) PyObject_GetItem(obj, key) +#endif + +/* KeywordStringCheck.proto */ +static int __Pyx_CheckKeywordStrings(PyObject *kw, const char* function_name, int kw_allowed); + +/* GetAttr3.proto */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr3(PyObject *, PyObject *, PyObject *); + +/* PyDictVersioning.proto */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +#define __PYX_DICT_VERSION_INIT ((PY_UINT64_T) -1) +#define __PYX_GET_DICT_VERSION(dict) (((PyDictObject*)(dict))->ma_version_tag) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var)\ + (version_var) = __PYX_GET_DICT_VERSION(dict);\ + (cache_var) = (value); +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + if (likely(__PYX_GET_DICT_VERSION(DICT) == __pyx_dict_version)) {\ + (VAR) = __pyx_dict_cached_value;\ + } else {\ + (VAR) = __pyx_dict_cached_value = (LOOKUP);\ + __pyx_dict_version = __PYX_GET_DICT_VERSION(DICT);\ + }\ +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj); +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj); +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version); +#else +#define __PYX_GET_DICT_VERSION(dict) (0) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var) +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) (VAR) = (LOOKUP); +#endif + +/* GetModuleGlobalName.proto */ +#if CYTHON_USE_DICT_VERSIONS +#define __Pyx_GetModuleGlobalName(var, name) do {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + (var) = (likely(__pyx_dict_version == __PYX_GET_DICT_VERSION(__pyx_d))) ?\ + (likely(__pyx_dict_cached_value) ? __Pyx_NewRef(__pyx_dict_cached_value) : __Pyx_GetBuiltinName(name)) :\ + __Pyx__GetModuleGlobalName(name, &__pyx_dict_version, &__pyx_dict_cached_value);\ +} while(0) +#define __Pyx_GetModuleGlobalNameUncached(var, name) do {\ + PY_UINT64_T __pyx_dict_version;\ + PyObject *__pyx_dict_cached_value;\ + (var) = __Pyx__GetModuleGlobalName(name, &__pyx_dict_version, &__pyx_dict_cached_value);\ +} while(0) +static PyObject *__Pyx__GetModuleGlobalName(PyObject *name, PY_UINT64_T *dict_version, PyObject **dict_cached_value); +#else +#define __Pyx_GetModuleGlobalName(var, name) (var) = __Pyx__GetModuleGlobalName(name) +#define __Pyx_GetModuleGlobalNameUncached(var, name) (var) = __Pyx__GetModuleGlobalName(name) +static CYTHON_INLINE PyObject *__Pyx__GetModuleGlobalName(PyObject *name); +#endif + +/* RaiseUnexpectedTypeError.proto */ +static int __Pyx_RaiseUnexpectedTypeError(const char *expected, PyObject *obj); + +/* RaiseException.proto */ +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause); + +/* PySequenceContains.proto */ +static CYTHON_INLINE int __Pyx_PySequence_ContainsTF(PyObject* item, PyObject* seq, int eq) { + int result = PySequence_Contains(seq, item); + return unlikely(result < 0) ? result : (result == (eq == Py_EQ)); +} + +/* Import.proto */ +static PyObject *__Pyx_Import(PyObject *name, PyObject *from_list, int level); + +/* ImportFrom.proto */ +static PyObject* __Pyx_ImportFrom(PyObject* module, PyObject* name); + +/* GetAttr.proto */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr(PyObject *, PyObject *); + +/* HasAttr.proto */ +#if __PYX_LIMITED_VERSION_HEX >= 0x030d00A1 +#define __Pyx_HasAttr(o, n) PyObject_HasAttrWithError(o, n) +#else +static CYTHON_INLINE int __Pyx_HasAttr(PyObject *, PyObject *); +#endif + +/* ArgTypeTest.proto */ +#define __Pyx_ArgTypeTest(obj, type, none_allowed, name, exact)\ + ((likely(__Pyx_IS_TYPE(obj, type) | (none_allowed && (obj == Py_None)))) ? 1 :\ + __Pyx__ArgTypeTest(obj, type, name, exact)) +static int __Pyx__ArgTypeTest(PyObject *obj, PyTypeObject *type, const char *name, int exact); + +/* GCCDiagnostics.proto */ +#if !defined(__INTEL_COMPILER) && defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 6)) +#define __Pyx_HAS_GCC_DIAGNOSTIC +#endif + +/* BuildPyUnicode.proto */ +static PyObject* __Pyx_PyUnicode_BuildFromAscii(Py_ssize_t ulength, char* chars, int clength, + int prepend_sign, char padding_char); + +/* CIntToPyUnicode.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_int(int value, Py_ssize_t width, char padding_char, char format_char); + +/* CIntToPyUnicode.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_Py_ssize_t(Py_ssize_t value, Py_ssize_t width, char padding_char, char format_char); + +/* JoinPyUnicode.proto */ +static PyObject* __Pyx_PyUnicode_Join(PyObject* value_tuple, Py_ssize_t value_count, Py_ssize_t result_ulength, + Py_UCS4 max_char); + +/* StrEquals.proto */ +#if PY_MAJOR_VERSION >= 3 +#define __Pyx_PyString_Equals __Pyx_PyUnicode_Equals +#else +#define __Pyx_PyString_Equals __Pyx_PyBytes_Equals +#endif + +/* PyObjectFormatSimple.proto */ +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + PyObject_Format(s, f)) +#elif PY_MAJOR_VERSION < 3 + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + likely(PyString_CheckExact(s)) ? PyUnicode_FromEncodedObject(s, NULL, "strict") :\ + PyObject_Format(s, f)) +#elif CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + likely(PyLong_CheckExact(s)) ? PyLong_Type.tp_repr(s) :\ + likely(PyFloat_CheckExact(s)) ? PyFloat_Type.tp_repr(s) :\ + PyObject_Format(s, f)) +#else + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + PyObject_Format(s, f)) +#endif + +CYTHON_UNUSED static int __pyx_array_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +static PyObject *__pyx_array_get_memview(struct __pyx_array_obj *); /*proto*/ +/* DivInt[Py_ssize_t].proto */ +static CYTHON_INLINE Py_ssize_t __Pyx_div_Py_ssize_t(Py_ssize_t, Py_ssize_t); + +/* UnaryNegOverflows.proto */ +#define __Pyx_UNARY_NEG_WOULD_OVERFLOW(x)\ + (((x) < 0) & ((unsigned long)(x) == 0-(unsigned long)(x))) + +/* AssertionsEnabled.proto */ +#if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX < 0x02070600 && !defined(Py_OptimizeFlag) + #define __Pyx_init_assertions_enabled() (0) + #define __pyx_assertions_enabled() (1) +#elif CYTHON_COMPILING_IN_LIMITED_API || (CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030C0000) + static int __pyx_assertions_enabled_flag; + #define __pyx_assertions_enabled() (__pyx_assertions_enabled_flag) + static int __Pyx_init_assertions_enabled(void) { + PyObject *builtins, *debug, *debug_str; + int flag; + builtins = PyEval_GetBuiltins(); + if (!builtins) goto bad; + debug_str = PyUnicode_FromStringAndSize("__debug__", 9); + if (!debug_str) goto bad; + debug = PyObject_GetItem(builtins, debug_str); + Py_DECREF(debug_str); + if (!debug) goto bad; + flag = PyObject_IsTrue(debug); + Py_DECREF(debug); + if (flag == -1) goto bad; + __pyx_assertions_enabled_flag = flag; + return 0; + bad: + __pyx_assertions_enabled_flag = 1; + return -1; + } +#else + #define __Pyx_init_assertions_enabled() (0) + #define __pyx_assertions_enabled() (!Py_OptimizeFlag) +#endif + +/* RaiseTooManyValuesToUnpack.proto */ +static CYTHON_INLINE void __Pyx_RaiseTooManyValuesError(Py_ssize_t expected); + +/* RaiseNeedMoreValuesToUnpack.proto */ +static CYTHON_INLINE void __Pyx_RaiseNeedMoreValuesError(Py_ssize_t index); + +/* RaiseNoneIterError.proto */ +static CYTHON_INLINE void __Pyx_RaiseNoneNotIterableError(void); + +/* ExtTypeTest.proto */ +static CYTHON_INLINE int __Pyx_TypeTest(PyObject *obj, PyTypeObject *type); + +/* GetTopmostException.proto */ +#if CYTHON_USE_EXC_INFO_STACK && CYTHON_FAST_THREAD_STATE +static _PyErr_StackItem * __Pyx_PyErr_GetTopmostException(PyThreadState *tstate); +#endif + +/* SaveResetException.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_ExceptionSave(type, value, tb) __Pyx__ExceptionSave(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx__ExceptionSave(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#define __Pyx_ExceptionReset(type, value, tb) __Pyx__ExceptionReset(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx__ExceptionReset(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb); +#else +#define __Pyx_ExceptionSave(type, value, tb) PyErr_GetExcInfo(type, value, tb) +#define __Pyx_ExceptionReset(type, value, tb) PyErr_SetExcInfo(type, value, tb) +#endif + +/* GetException.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_GetException(type, value, tb) __Pyx__GetException(__pyx_tstate, type, value, tb) +static int __Pyx__GetException(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#else +static int __Pyx_GetException(PyObject **type, PyObject **value, PyObject **tb); +#endif + +/* SwapException.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_ExceptionSwap(type, value, tb) __Pyx__ExceptionSwap(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx__ExceptionSwap(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#else +static CYTHON_INLINE void __Pyx_ExceptionSwap(PyObject **type, PyObject **value, PyObject **tb); +#endif + +/* ImportDottedModule.proto */ +static PyObject *__Pyx_ImportDottedModule(PyObject *name, PyObject *parts_tuple); +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_ImportDottedModule_WalkParts(PyObject *module, PyObject *name, PyObject *parts_tuple); +#endif + +/* FastTypeChecks.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_TypeCheck(obj, type) __Pyx_IsSubtype(Py_TYPE(obj), (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) __Pyx_IsAnySubtype2(Py_TYPE(obj), (PyTypeObject *)type1, (PyTypeObject *)type2) +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches(PyObject *err, PyObject *type); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches2(PyObject *err, PyObject *type1, PyObject *type2); +#else +#define __Pyx_TypeCheck(obj, type) PyObject_TypeCheck(obj, (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) (PyObject_TypeCheck(obj, (PyTypeObject *)type1) || PyObject_TypeCheck(obj, (PyTypeObject *)type2)) +#define __Pyx_PyErr_GivenExceptionMatches(err, type) PyErr_GivenExceptionMatches(err, type) +#define __Pyx_PyErr_GivenExceptionMatches2(err, type1, type2) (PyErr_GivenExceptionMatches(err, type1) || PyErr_GivenExceptionMatches(err, type2)) +#endif +#define __Pyx_PyErr_ExceptionMatches2(err1, err2) __Pyx_PyErr_GivenExceptionMatches2(__Pyx_PyErr_CurrentExceptionType(), err1, err2) +#define __Pyx_PyException_Check(obj) __Pyx_TypeCheck(obj, PyExc_Exception) + +CYTHON_UNUSED static int __pyx_memoryview_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +/* ListCompAppend.proto */ +#if CYTHON_USE_PYLIST_INTERNALS && CYTHON_ASSUME_SAFE_MACROS +static CYTHON_INLINE int __Pyx_ListComp_Append(PyObject* list, PyObject* x) { + PyListObject* L = (PyListObject*) list; + Py_ssize_t len = Py_SIZE(list); + if (likely(L->allocated > len)) { + Py_INCREF(x); + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 + L->ob_item[len] = x; + #else + PyList_SET_ITEM(list, len, x); + #endif + __Pyx_SET_SIZE(list, len + 1); + return 0; + } + return PyList_Append(list, x); +} +#else +#define __Pyx_ListComp_Append(L,x) PyList_Append(L,x) +#endif + +/* PySequenceMultiply.proto */ +#define __Pyx_PySequence_Multiply_Left(mul, seq) __Pyx_PySequence_Multiply(seq, mul) +static CYTHON_INLINE PyObject* __Pyx_PySequence_Multiply(PyObject *seq, Py_ssize_t mul); + +/* SetItemInt.proto */ +#define __Pyx_SetItemInt(o, i, v, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_SetItemInt_Fast(o, (Py_ssize_t)i, v, is_list, wraparound, boundscheck) :\ + (is_list ? (PyErr_SetString(PyExc_IndexError, "list assignment index out of range"), -1) :\ + __Pyx_SetItemInt_Generic(o, to_py_func(i), v))) +static int __Pyx_SetItemInt_Generic(PyObject *o, PyObject *j, PyObject *v); +static CYTHON_INLINE int __Pyx_SetItemInt_Fast(PyObject *o, Py_ssize_t i, PyObject *v, + int is_list, int wraparound, int boundscheck); + +/* RaiseUnboundLocalError.proto */ +static CYTHON_INLINE void __Pyx_RaiseUnboundLocalError(const char *varname); + +/* DivInt[long].proto */ +static CYTHON_INLINE long __Pyx_div_long(long, long); + +/* ListAppend.proto */ +#if CYTHON_USE_PYLIST_INTERNALS && CYTHON_ASSUME_SAFE_MACROS +static CYTHON_INLINE int __Pyx_PyList_Append(PyObject* list, PyObject* x) { + PyListObject* L = (PyListObject*) list; + Py_ssize_t len = Py_SIZE(list); + if (likely(L->allocated > len) & likely(len > (L->allocated >> 1))) { + Py_INCREF(x); + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 + L->ob_item[len] = x; + #else + PyList_SET_ITEM(list, len, x); + #endif + __Pyx_SET_SIZE(list, len + 1); + return 0; + } + return PyList_Append(list, x); +} +#else +#define __Pyx_PyList_Append(L,x) PyList_Append(L,x) +#endif + +/* PyObjectCall2Args.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call2Args(PyObject* function, PyObject* arg1, PyObject* arg2); + +/* PyObjectGetMethod.proto */ +static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method); + +/* PyObjectCallMethod1.proto */ +static PyObject* __Pyx_PyObject_CallMethod1(PyObject* obj, PyObject* method_name, PyObject* arg); + +/* StringJoin.proto */ +#if PY_MAJOR_VERSION < 3 +#define __Pyx_PyString_Join __Pyx_PyBytes_Join +#define __Pyx_PyBaseString_Join(s, v) (PyUnicode_CheckExact(s) ? PyUnicode_Join(s, v) : __Pyx_PyBytes_Join(s, v)) +#else +#define __Pyx_PyString_Join PyUnicode_Join +#define __Pyx_PyBaseString_Join PyUnicode_Join +#endif +static CYTHON_INLINE PyObject* __Pyx_PyBytes_Join(PyObject* sep, PyObject* values); + +/* CIntToPyUnicode.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_size_t(size_t value, Py_ssize_t width, char padding_char, char format_char); + +/* MoveIfSupported.proto */ +#if CYTHON_USE_CPP_STD_MOVE + #include + #define __PYX_STD_MOVE_IF_SUPPORTED(x) std::move(x) +#else + #define __PYX_STD_MOVE_IF_SUPPORTED(x) x +#endif + +/* IncludeCppStringH.proto */ +#include + +/* decode_c_string_utf16.proto */ +static CYTHON_INLINE PyObject *__Pyx_PyUnicode_DecodeUTF16(const char *s, Py_ssize_t size, const char *errors) { + int byteorder = 0; + return PyUnicode_DecodeUTF16(s, size, errors, &byteorder); +} +static CYTHON_INLINE PyObject *__Pyx_PyUnicode_DecodeUTF16LE(const char *s, Py_ssize_t size, const char *errors) { + int byteorder = -1; + return PyUnicode_DecodeUTF16(s, size, errors, &byteorder); +} +static CYTHON_INLINE PyObject *__Pyx_PyUnicode_DecodeUTF16BE(const char *s, Py_ssize_t size, const char *errors) { + int byteorder = 1; + return PyUnicode_DecodeUTF16(s, size, errors, &byteorder); +} + +/* decode_c_bytes.proto */ +static CYTHON_INLINE PyObject* __Pyx_decode_c_bytes( + const char* cstring, Py_ssize_t length, Py_ssize_t start, Py_ssize_t stop, + const char* encoding, const char* errors, + PyObject* (*decode_func)(const char *s, Py_ssize_t size, const char *errors)); + +/* decode_cpp_string.proto */ +static CYTHON_INLINE PyObject* __Pyx_decode_cpp_string( + std::string cppstring, Py_ssize_t start, Py_ssize_t stop, + const char* encoding, const char* errors, + PyObject* (*decode_func)(const char *s, Py_ssize_t size, const char *errors)) { + return __Pyx_decode_c_bytes( + cppstring.data(), cppstring.size(), start, stop, encoding, errors, decode_func); +} + +/* PyObjectCallNoArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func); + +/* BufferIndexError.proto */ +static void __Pyx_RaiseBufferIndexError(int axis); + +/* PyObject_GenericGetAttrNoDict.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttrNoDict PyObject_GenericGetAttr +#endif + +/* PyObject_GenericGetAttr.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttr PyObject_GenericGetAttr +#endif + +/* IncludeStructmemberH.proto */ +#include + +/* FixUpExtensionType.proto */ +#if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type); +#endif + +/* PyObjectCallMethod0.proto */ +static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name); + +/* ValidateBasesTuple.proto */ +#if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases); +#endif + +/* PyType_Ready.proto */ +CYTHON_UNUSED static int __Pyx_PyType_Ready(PyTypeObject *t); + +/* SetVTable.proto */ +static int __Pyx_SetVtable(PyTypeObject* typeptr , void* vtable); + +/* GetVTable.proto */ +static void* __Pyx_GetVtable(PyTypeObject *type); + +/* MergeVTables.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_MergeVtables(PyTypeObject *type); +#endif + +/* SetupReduce.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce(PyObject* type_obj); +#endif + +/* TypeImport.proto */ +#ifndef __PYX_HAVE_RT_ImportType_proto_3_0_8 +#define __PYX_HAVE_RT_ImportType_proto_3_0_8 +#if defined (__STDC_VERSION__) && __STDC_VERSION__ >= 201112L +#include +#endif +#if (defined (__STDC_VERSION__) && __STDC_VERSION__ >= 201112L) || __cplusplus >= 201103L +#define __PYX_GET_STRUCT_ALIGNMENT_3_0_8(s) alignof(s) +#else +#define __PYX_GET_STRUCT_ALIGNMENT_3_0_8(s) sizeof(void*) +#endif +enum __Pyx_ImportType_CheckSize_3_0_8 { + __Pyx_ImportType_CheckSize_Error_3_0_8 = 0, + __Pyx_ImportType_CheckSize_Warn_3_0_8 = 1, + __Pyx_ImportType_CheckSize_Ignore_3_0_8 = 2 +}; +static PyTypeObject *__Pyx_ImportType_3_0_8(PyObject* module, const char *module_name, const char *class_name, size_t size, size_t alignment, enum __Pyx_ImportType_CheckSize_3_0_8 check_size); +#endif + +/* FetchSharedCythonModule.proto */ +static PyObject *__Pyx_FetchSharedCythonABIModule(void); + +/* FetchCommonType.proto */ +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type); +#else +static PyTypeObject* __Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases); +#endif + +/* PyMethodNew.proto */ +#if CYTHON_COMPILING_IN_LIMITED_API +static PyObject *__Pyx_PyMethod_New(PyObject *func, PyObject *self, PyObject *typ) { + PyObject *typesModule=NULL, *methodType=NULL, *result=NULL; + CYTHON_UNUSED_VAR(typ); + if (!self) + return __Pyx_NewRef(func); + typesModule = PyImport_ImportModule("types"); + if (!typesModule) return NULL; + methodType = PyObject_GetAttrString(typesModule, "MethodType"); + Py_DECREF(typesModule); + if (!methodType) return NULL; + result = PyObject_CallFunctionObjArgs(methodType, func, self, NULL); + Py_DECREF(methodType); + return result; +} +#elif PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_PyMethod_New(PyObject *func, PyObject *self, PyObject *typ) { + CYTHON_UNUSED_VAR(typ); + if (!self) + return __Pyx_NewRef(func); + return PyMethod_New(func, self); +} +#else + #define __Pyx_PyMethod_New PyMethod_New +#endif + +/* PyVectorcallFastCallDict.proto */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw); +#endif + +/* CythonFunctionShared.proto */ +#define __Pyx_CyFunction_USED +#define __Pyx_CYFUNCTION_STATICMETHOD 0x01 +#define __Pyx_CYFUNCTION_CLASSMETHOD 0x02 +#define __Pyx_CYFUNCTION_CCLASS 0x04 +#define __Pyx_CYFUNCTION_COROUTINE 0x08 +#define __Pyx_CyFunction_GetClosure(f)\ + (((__pyx_CyFunctionObject *) (f))->func_closure) +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_CyFunction_GetClassObj(f)\ + (((__pyx_CyFunctionObject *) (f))->func_classobj) +#else + #define __Pyx_CyFunction_GetClassObj(f)\ + ((PyObject*) ((PyCMethodObject *) (f))->mm_class) +#endif +#define __Pyx_CyFunction_SetClassObj(f, classobj)\ + __Pyx__CyFunction_SetClassObj((__pyx_CyFunctionObject *) (f), (classobj)) +#define __Pyx_CyFunction_Defaults(type, f)\ + ((type *)(((__pyx_CyFunctionObject *) (f))->defaults)) +#define __Pyx_CyFunction_SetDefaultsGetter(f, g)\ + ((__pyx_CyFunctionObject *) (f))->defaults_getter = (g) +typedef struct { +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject_HEAD + PyObject *func; +#elif PY_VERSION_HEX < 0x030900B1 + PyCFunctionObject func; +#else + PyCMethodObject func; +#endif +#if CYTHON_BACKPORT_VECTORCALL + __pyx_vectorcallfunc func_vectorcall; +#endif +#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API + PyObject *func_weakreflist; +#endif + PyObject *func_dict; + PyObject *func_name; + PyObject *func_qualname; + PyObject *func_doc; + PyObject *func_globals; + PyObject *func_code; + PyObject *func_closure; +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + PyObject *func_classobj; +#endif + void *defaults; + int defaults_pyobjects; + size_t defaults_size; + int flags; + PyObject *defaults_tuple; + PyObject *defaults_kwdict; + PyObject *(*defaults_getter)(PyObject *); + PyObject *func_annotations; + PyObject *func_is_coroutine; +} __pyx_CyFunctionObject; +#undef __Pyx_CyOrPyCFunction_Check +#define __Pyx_CyFunction_Check(obj) __Pyx_TypeCheck(obj, __pyx_CyFunctionType) +#define __Pyx_CyOrPyCFunction_Check(obj) __Pyx_TypeCheck2(obj, __pyx_CyFunctionType, &PyCFunction_Type) +#define __Pyx_CyFunction_CheckExact(obj) __Pyx_IS_TYPE(obj, __pyx_CyFunctionType) +static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc); +#undef __Pyx_IsSameCFunction +#define __Pyx_IsSameCFunction(func, cfunc) __Pyx__IsSameCyOrCFunction(func, cfunc) +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject* op, PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj); +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *m, + size_t size, + int pyobjects); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *m, + PyObject *tuple); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *m, + PyObject *dict); +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *m, + PyObject *dict); +static int __pyx_CyFunction_init(PyObject *module); +#if CYTHON_METH_FASTCALL +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +#if CYTHON_BACKPORT_VECTORCALL +#define __Pyx_CyFunction_func_vectorcall(f) (((__pyx_CyFunctionObject*)f)->func_vectorcall) +#else +#define __Pyx_CyFunction_func_vectorcall(f) (((PyCFunctionObject*)f)->vectorcall) +#endif +#endif + +/* CythonFunction.proto */ +static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); + +/* Py3UpdateBases.proto */ +static PyObject* __Pyx_PEP560_update_bases(PyObject *bases); + +/* SetNameInClass.proto */ +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030500A1 && PY_VERSION_HEX < 0x030d0000 +#define __Pyx_SetNameInClass(ns, name, value)\ + (likely(PyDict_CheckExact(ns)) ? _PyDict_SetItem_KnownHash(ns, name, value, ((PyASCIIObject *) name)->hash) : PyObject_SetItem(ns, name, value)) +#elif CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_SetNameInClass(ns, name, value)\ + (likely(PyDict_CheckExact(ns)) ? PyDict_SetItem(ns, name, value) : PyObject_SetItem(ns, name, value)) +#else +#define __Pyx_SetNameInClass(ns, name, value) PyObject_SetItem(ns, name, value) +#endif + +/* SetNewInClass.proto */ +static int __Pyx_SetNewInClass(PyObject *ns, PyObject *name, PyObject *value); + +/* CalculateMetaclass.proto */ +static PyObject *__Pyx_CalculateMetaclass(PyTypeObject *metaclass, PyObject *bases); + +/* PyObjectLookupSpecial.proto */ +#if CYTHON_USE_PYTYPE_LOOKUP && CYTHON_USE_TYPE_SLOTS +#define __Pyx_PyObject_LookupSpecialNoError(obj, attr_name) __Pyx__PyObject_LookupSpecial(obj, attr_name, 0) +#define __Pyx_PyObject_LookupSpecial(obj, attr_name) __Pyx__PyObject_LookupSpecial(obj, attr_name, 1) +static CYTHON_INLINE PyObject* __Pyx__PyObject_LookupSpecial(PyObject* obj, PyObject* attr_name, int with_error); +#else +#define __Pyx_PyObject_LookupSpecialNoError(o,n) __Pyx_PyObject_GetAttrStrNoError(o,n) +#define __Pyx_PyObject_LookupSpecial(o,n) __Pyx_PyObject_GetAttrStr(o,n) +#endif + +/* Py3ClassCreate.proto */ +static PyObject *__Pyx_Py3MetaclassPrepare(PyObject *metaclass, PyObject *bases, PyObject *name, PyObject *qualname, + PyObject *mkw, PyObject *modname, PyObject *doc); +static PyObject *__Pyx_Py3ClassCreate(PyObject *metaclass, PyObject *name, PyObject *bases, PyObject *dict, + PyObject *mkw, int calculate_metaclass, int allow_py2_metaclass); + +/* Globals.proto */ +static PyObject* __Pyx_Globals(void); + +/* dict_getitem_default.proto */ +static PyObject* __Pyx_PyDict_GetItemDefault(PyObject* d, PyObject* key, PyObject* default_value); + +/* UnpackUnboundCMethod.proto */ +typedef struct { + PyObject *type; + PyObject **method_name; + PyCFunction func; + PyObject *method; + int flag; +} __Pyx_CachedCFunction; + +/* CallUnboundCMethod1.proto */ +static PyObject* __Pyx__CallUnboundCMethod1(__Pyx_CachedCFunction* cfunc, PyObject* self, PyObject* arg); +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_CallUnboundCMethod1(__Pyx_CachedCFunction* cfunc, PyObject* self, PyObject* arg); +#else +#define __Pyx_CallUnboundCMethod1(cfunc, self, arg) __Pyx__CallUnboundCMethod1(cfunc, self, arg) +#endif + +/* CallUnboundCMethod2.proto */ +static PyObject* __Pyx__CallUnboundCMethod2(__Pyx_CachedCFunction* cfunc, PyObject* self, PyObject* arg1, PyObject* arg2); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030600B1 +static CYTHON_INLINE PyObject *__Pyx_CallUnboundCMethod2(__Pyx_CachedCFunction *cfunc, PyObject *self, PyObject *arg1, PyObject *arg2); +#else +#define __Pyx_CallUnboundCMethod2(cfunc, self, arg1, arg2) __Pyx__CallUnboundCMethod2(cfunc, self, arg1, arg2) +#endif + +/* GetNameInClass.proto */ +#define __Pyx_GetNameInClass(var, nmspace, name) (var) = __Pyx__GetNameInClass(nmspace, name) +static PyObject *__Pyx__GetNameInClass(PyObject *nmspace, PyObject *name); + +/* CLineInTraceback.proto */ +#ifdef CYTHON_CLINE_IN_TRACEBACK +#define __Pyx_CLineForTraceback(tstate, c_line) (((CYTHON_CLINE_IN_TRACEBACK)) ? c_line : 0) +#else +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line); +#endif + +/* CodeObjectCache.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +typedef struct { + PyCodeObject* code_object; + int code_line; +} __Pyx_CodeObjectCacheEntry; +struct __Pyx_CodeObjectCache { + int count; + int max_count; + __Pyx_CodeObjectCacheEntry* entries; +}; +static struct __Pyx_CodeObjectCache __pyx_code_cache = {0,0,NULL}; +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line); +static PyCodeObject *__pyx_find_code_object(int code_line); +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object); +#endif + +/* AddTraceback.proto */ +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename); + +#if PY_MAJOR_VERSION < 3 + static int __Pyx_GetBuffer(PyObject *obj, Py_buffer *view, int flags); + static void __Pyx_ReleaseBuffer(Py_buffer *view); +#else + #define __Pyx_GetBuffer PyObject_GetBuffer + #define __Pyx_ReleaseBuffer PyBuffer_Release +#endif + + +/* BufferStructDeclare.proto */ +typedef struct { + Py_ssize_t shape, strides, suboffsets; +} __Pyx_Buf_DimInfo; +typedef struct { + size_t refcount; + Py_buffer pybuffer; +} __Pyx_Buffer; +typedef struct { + __Pyx_Buffer *rcbuffer; + char *data; + __Pyx_Buf_DimInfo diminfo[8]; +} __Pyx_LocalBuf_ND; + +/* MemviewSliceIsContig.proto */ +static int __pyx_memviewslice_is_contig(const __Pyx_memviewslice mvs, char order, int ndim); + +/* OverlappingSlices.proto */ +static int __pyx_slices_overlap(__Pyx_memviewslice *slice1, + __Pyx_memviewslice *slice2, + int ndim, size_t itemsize); + +/* None.proto */ +#include + +/* IsLittleEndian.proto */ +static CYTHON_INLINE int __Pyx_Is_Little_Endian(void); + +/* BufferFormatCheck.proto */ +static const char* __Pyx_BufFmt_CheckString(__Pyx_BufFmt_Context* ctx, const char* ts); +static void __Pyx_BufFmt_Init(__Pyx_BufFmt_Context* ctx, + __Pyx_BufFmt_StackElem* stack, + __Pyx_TypeInfo* type); + +/* TypeInfoCompare.proto */ +static int __pyx_typeinfo_cmp(__Pyx_TypeInfo *a, __Pyx_TypeInfo *b); + +/* MemviewSliceValidateAndInit.proto */ +static int __Pyx_ValidateAndInit_memviewslice( + int *axes_specs, + int c_or_f_flag, + int buf_flags, + int ndim, + __Pyx_TypeInfo *dtype, + __Pyx_BufFmt_StackElem stack[], + __Pyx_memviewslice *memviewslice, + PyObject *original_obj); + +/* ObjectToMemviewSlice.proto */ +static CYTHON_INLINE __Pyx_memviewslice __Pyx_PyObject_to_MemoryviewSlice_ds_unsigned_char__const__(PyObject *, int writable_flag); + +/* MemviewDtypeToObject.proto */ +static CYTHON_INLINE PyObject *__pyx_memview_get_nn___pyx_t_5numpy_uint8_t(const char *itemp); +static CYTHON_INLINE int __pyx_memview_set_nn___pyx_t_5numpy_uint8_t(const char *itemp, PyObject *obj); + +/* MemviewDtypeToObject.proto */ +static CYTHON_INLINE PyObject *__pyx_memview_get_unsigned_char__const__(const char *itemp); + +/* RealImag.proto */ +#if CYTHON_CCOMPLEX + #ifdef __cplusplus + #define __Pyx_CREAL(z) ((z).real()) + #define __Pyx_CIMAG(z) ((z).imag()) + #else + #define __Pyx_CREAL(z) (__real__(z)) + #define __Pyx_CIMAG(z) (__imag__(z)) + #endif +#else + #define __Pyx_CREAL(z) ((z).real) + #define __Pyx_CIMAG(z) ((z).imag) +#endif +#if defined(__cplusplus) && CYTHON_CCOMPLEX\ + && (defined(_WIN32) || defined(__clang__) || (defined(__GNUC__) && (__GNUC__ >= 5 || __GNUC__ == 4 && __GNUC_MINOR__ >= 4 )) || __cplusplus >= 201103) + #define __Pyx_SET_CREAL(z,x) ((z).real(x)) + #define __Pyx_SET_CIMAG(z,y) ((z).imag(y)) +#else + #define __Pyx_SET_CREAL(z,x) __Pyx_CREAL(z) = (x) + #define __Pyx_SET_CIMAG(z,y) __Pyx_CIMAG(z) = (y) +#endif + +/* Arithmetic.proto */ +#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #define __Pyx_c_eq_float(a, b) ((a)==(b)) + #define __Pyx_c_sum_float(a, b) ((a)+(b)) + #define __Pyx_c_diff_float(a, b) ((a)-(b)) + #define __Pyx_c_prod_float(a, b) ((a)*(b)) + #define __Pyx_c_quot_float(a, b) ((a)/(b)) + #define __Pyx_c_neg_float(a) (-(a)) + #ifdef __cplusplus + #define __Pyx_c_is_zero_float(z) ((z)==(float)0) + #define __Pyx_c_conj_float(z) (::std::conj(z)) + #if 1 + #define __Pyx_c_abs_float(z) (::std::abs(z)) + #define __Pyx_c_pow_float(a, b) (::std::pow(a, b)) + #endif + #else + #define __Pyx_c_is_zero_float(z) ((z)==0) + #define __Pyx_c_conj_float(z) (conjf(z)) + #if 1 + #define __Pyx_c_abs_float(z) (cabsf(z)) + #define __Pyx_c_pow_float(a, b) (cpowf(a, b)) + #endif + #endif +#else + static CYTHON_INLINE int __Pyx_c_eq_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_sum_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_diff_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_prod_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_quot_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_neg_float(__pyx_t_float_complex); + static CYTHON_INLINE int __Pyx_c_is_zero_float(__pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_conj_float(__pyx_t_float_complex); + #if 1 + static CYTHON_INLINE float __Pyx_c_abs_float(__pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_pow_float(__pyx_t_float_complex, __pyx_t_float_complex); + #endif +#endif + +/* Arithmetic.proto */ +#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #define __Pyx_c_eq_double(a, b) ((a)==(b)) + #define __Pyx_c_sum_double(a, b) ((a)+(b)) + #define __Pyx_c_diff_double(a, b) ((a)-(b)) + #define __Pyx_c_prod_double(a, b) ((a)*(b)) + #define __Pyx_c_quot_double(a, b) ((a)/(b)) + #define __Pyx_c_neg_double(a) (-(a)) + #ifdef __cplusplus + #define __Pyx_c_is_zero_double(z) ((z)==(double)0) + #define __Pyx_c_conj_double(z) (::std::conj(z)) + #if 1 + #define __Pyx_c_abs_double(z) (::std::abs(z)) + #define __Pyx_c_pow_double(a, b) (::std::pow(a, b)) + #endif + #else + #define __Pyx_c_is_zero_double(z) ((z)==0) + #define __Pyx_c_conj_double(z) (conj(z)) + #if 1 + #define __Pyx_c_abs_double(z) (cabs(z)) + #define __Pyx_c_pow_double(a, b) (cpow(a, b)) + #endif + #endif +#else + static CYTHON_INLINE int __Pyx_c_eq_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_sum_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_diff_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_prod_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_quot_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_neg_double(__pyx_t_double_complex); + static CYTHON_INLINE int __Pyx_c_is_zero_double(__pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_conj_double(__pyx_t_double_complex); + #if 1 + static CYTHON_INLINE double __Pyx_c_abs_double(__pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_pow_double(__pyx_t_double_complex, __pyx_t_double_complex); + #endif +#endif + +/* MemviewSliceCopyTemplate.proto */ +static __Pyx_memviewslice +__pyx_memoryview_copy_new_contig(const __Pyx_memviewslice *from_mvs, + const char *mode, int ndim, + size_t sizeof_dtype, int contig_flag, + int dtype_is_object); + +/* MemviewSliceInit.proto */ +#define __Pyx_BUF_MAX_NDIMS %(BUF_MAX_NDIMS)d +#define __Pyx_MEMVIEW_DIRECT 1 +#define __Pyx_MEMVIEW_PTR 2 +#define __Pyx_MEMVIEW_FULL 4 +#define __Pyx_MEMVIEW_CONTIG 8 +#define __Pyx_MEMVIEW_STRIDED 16 +#define __Pyx_MEMVIEW_FOLLOW 32 +#define __Pyx_IS_C_CONTIG 1 +#define __Pyx_IS_F_CONTIG 2 +static int __Pyx_init_memviewslice( + struct __pyx_memoryview_obj *memview, + int ndim, + __Pyx_memviewslice *memviewslice, + int memview_is_new_reference); +static CYTHON_INLINE int __pyx_add_acquisition_count_locked( + __pyx_atomic_int_type *acquisition_count, PyThread_type_lock lock); +static CYTHON_INLINE int __pyx_sub_acquisition_count_locked( + __pyx_atomic_int_type *acquisition_count, PyThread_type_lock lock); +#define __pyx_get_slice_count_pointer(memview) (&memview->acquisition_count) +#define __PYX_INC_MEMVIEW(slice, have_gil) __Pyx_INC_MEMVIEW(slice, have_gil, __LINE__) +#define __PYX_XCLEAR_MEMVIEW(slice, have_gil) __Pyx_XCLEAR_MEMVIEW(slice, have_gil, __LINE__) +static CYTHON_INLINE void __Pyx_INC_MEMVIEW(__Pyx_memviewslice *, int, int); +static CYTHON_INLINE void __Pyx_XCLEAR_MEMVIEW(__Pyx_memviewslice *, int, int); + +/* TypeInfoToFormat.proto */ +struct __pyx_typeinfo_string { + char string[3]; +}; +static struct __pyx_typeinfo_string __Pyx_TypeInfoToFormat(__Pyx_TypeInfo *type); + +/* CIntFromPy.proto */ +static CYTHON_INLINE enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType __Pyx_PyInt_As_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(PyObject *); + +/* CIntFromPy.proto */ +static CYTHON_INLINE size_t __Pyx_PyInt_As_size_t(PyObject *); + +/* CIntFromPy.proto */ +static CYTHON_INLINE uint32_t __Pyx_PyInt_As_uint32_t(PyObject *); + +/* CIntFromPy.proto */ +static CYTHON_INLINE uint64_t __Pyx_PyInt_As_uint64_t(PyObject *); + +/* CIntFromPy.proto */ +static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_npy_uint8(npy_uint8 value); + +/* CIntFromPy.proto */ +static CYTHON_INLINE npy_uint8 __Pyx_PyInt_As_npy_uint8(PyObject *); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_unsigned_char(unsigned char value); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_int(int value); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_uint32_t(uint32_t value); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_uint64_t(uint64_t value); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_enum__VisionStreamType(enum VisionStreamType value); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType value); + +/* CppExceptionConversion.proto */ +#ifndef __Pyx_CppExn2PyErr +#include +#include +#include +#include +static void __Pyx_CppExn2PyErr() { + try { + if (PyErr_Occurred()) + ; // let the latest Python exn pass through and ignore the current one + else + throw; + } catch (const std::bad_alloc& exn) { + PyErr_SetString(PyExc_MemoryError, exn.what()); + } catch (const std::bad_cast& exn) { + PyErr_SetString(PyExc_TypeError, exn.what()); + } catch (const std::bad_typeid& exn) { + PyErr_SetString(PyExc_TypeError, exn.what()); + } catch (const std::domain_error& exn) { + PyErr_SetString(PyExc_ValueError, exn.what()); + } catch (const std::invalid_argument& exn) { + PyErr_SetString(PyExc_ValueError, exn.what()); + } catch (const std::ios_base::failure& exn) { + PyErr_SetString(PyExc_IOError, exn.what()); + } catch (const std::out_of_range& exn) { + PyErr_SetString(PyExc_IndexError, exn.what()); + } catch (const std::overflow_error& exn) { + PyErr_SetString(PyExc_OverflowError, exn.what()); + } catch (const std::range_error& exn) { + PyErr_SetString(PyExc_ArithmeticError, exn.what()); + } catch (const std::underflow_error& exn) { + PyErr_SetString(PyExc_ArithmeticError, exn.what()); + } catch (const std::exception& exn) { + PyErr_SetString(PyExc_RuntimeError, exn.what()); + } + catch (...) + { + PyErr_SetString(PyExc_RuntimeError, "Unknown exception"); + } +} +#endif + +/* CIntFromPy.proto */ +static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value); + +/* CIntFromPy.proto */ +static CYTHON_INLINE char __Pyx_PyInt_As_char(PyObject *); + +/* FormatTypeName.proto */ +#if CYTHON_COMPILING_IN_LIMITED_API +typedef PyObject *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%U" +static __Pyx_TypeName __Pyx_PyType_GetName(PyTypeObject* tp); +#define __Pyx_DECREF_TypeName(obj) Py_XDECREF(obj) +#else +typedef const char *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%.200s" +#define __Pyx_PyType_GetName(tp) ((tp)->tp_name) +#define __Pyx_DECREF_TypeName(obj) +#endif + +/* CheckBinaryVersion.proto */ +static unsigned long __Pyx_get_runtime_version(void); +static int __Pyx_check_binary_version(unsigned long ct_version, unsigned long rt_version, int allow_newer); + +/* InitStrings.proto */ +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t); + +/* #### Code section: module_declarations ### */ +static PyObject *__pyx_array_get_memview(struct __pyx_array_obj *__pyx_v_self); /* proto*/ +static char *__pyx_memoryview_get_item_pointer(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index); /* proto*/ +static PyObject *__pyx_memoryview_is_slice(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj); /* proto*/ +static PyObject *__pyx_memoryview_setitem_slice_assignment(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_dst, PyObject *__pyx_v_src); /* proto*/ +static PyObject *__pyx_memoryview_setitem_slice_assign_scalar(struct __pyx_memoryview_obj *__pyx_v_self, struct __pyx_memoryview_obj *__pyx_v_dst, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryview_setitem_indexed(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryview_convert_item_to_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp); /* proto*/ +static PyObject *__pyx_memoryview_assign_item_from_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryview__get_base(struct __pyx_memoryview_obj *__pyx_v_self); /* proto*/ +static PyObject *__pyx_memoryviewslice_convert_item_to_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp); /* proto*/ +static PyObject *__pyx_memoryviewslice_assign_item_from_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryviewslice__get_base(struct __pyx_memoryviewslice_obj *__pyx_v_self); /* proto*/ +static CYTHON_INLINE PyObject *__pyx_f_5numpy_7ndarray_4base_base(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE PyArray_Descr *__pyx_f_5numpy_7ndarray_5descr_descr(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE int __pyx_f_5numpy_7ndarray_4ndim_ndim(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_5shape_shape(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_7strides_strides(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE npy_intp __pyx_f_5numpy_7ndarray_4size_size(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE char *__pyx_f_5numpy_7ndarray_4data_data(PyArrayObject *__pyx_v_self); /* proto*/ +static PyObject *__pyx_f_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_create(VisionBuf *__pyx_v_cbuf); /* proto*/ + +/* Module declarations from "libc.string" */ + +/* Module declarations from "libcpp.string" */ + +/* Module declarations from "libcpp.vector" */ + +/* Module declarations from "libcpp.utility" */ + +/* Module declarations from "libcpp.set" */ + +/* Module declarations from "libc.stdint" */ + +/* Module declarations from "libcpp" */ + +/* Module declarations from "cereal.visionipc.visionipc" */ + +/* Module declarations from "libc.stdio" */ + +/* Module declarations from "__builtin__" */ + +/* Module declarations from "cpython.type" */ + +/* Module declarations from "cpython" */ + +/* Module declarations from "cpython.object" */ + +/* Module declarations from "cpython.ref" */ + +/* Module declarations from "numpy" */ + +/* Module declarations from "numpy" */ + +/* Module declarations from "cython.view" */ +static struct __pyx_array_obj *__pyx_array_new(PyObject *, Py_ssize_t, char *, char *, char *); /*proto*/ + +/* Module declarations from "cereal.visionipc.visionipc_pyx" */ +static PyObject *__Pyx_OrderedDict = 0; +static PyObject *__Pyx_EnumBase = 0; +static PyObject *__Pyx_FlagBase = 0; +static PyObject *__pyx_collections_abc_Sequence = 0; +static PyObject *generic = 0; +static PyObject *strided = 0; +static PyObject *indirect = 0; +static PyObject *contiguous = 0; +static PyObject *indirect_contiguous = 0; +static int __pyx_memoryview_thread_locks_used; +static PyThread_type_lock __pyx_memoryview_thread_locks[8]; +static PyObject *__Pyx_globals = 0; +static std::string __pyx_convert_string_from_py_std__in_string(PyObject *); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyObject_string_to_py_std__in_string(std::string const &); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyUnicode_string_to_py_std__in_string(std::string const &); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyStr_string_to_py_std__in_string(std::string const &); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyBytes_string_to_py_std__in_string(std::string const &); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyByteArray_string_to_py_std__in_string(std::string const &); /*proto*/ +static PyObject *__pyx_convert_set_to_py_enum__VisionStreamType(std::set const &); /*proto*/ +static PyObject *__pyx_unpickle___Pyx_EnumMeta__set_state(struct __pyx_obj___Pyx_EnumMeta *, PyObject *); /*proto*/ +static int __pyx_array_allocate_buffer(struct __pyx_array_obj *); /*proto*/ +static struct __pyx_array_obj *__pyx_array_new(PyObject *, Py_ssize_t, char *, char *, char *); /*proto*/ +static PyObject *__pyx_memoryview_new(PyObject *, int, int, __Pyx_TypeInfo *); /*proto*/ +static CYTHON_INLINE int __pyx_memoryview_check(PyObject *); /*proto*/ +static PyObject *_unellipsify(PyObject *, int); /*proto*/ +static int assert_direct_dimensions(Py_ssize_t *, int); /*proto*/ +static struct __pyx_memoryview_obj *__pyx_memview_slice(struct __pyx_memoryview_obj *, PyObject *); /*proto*/ +static int __pyx_memoryview_slice_memviewslice(__Pyx_memviewslice *, Py_ssize_t, Py_ssize_t, Py_ssize_t, int, int, int *, Py_ssize_t, Py_ssize_t, Py_ssize_t, int, int, int, int); /*proto*/ +static char *__pyx_pybuffer_index(Py_buffer *, char *, Py_ssize_t, Py_ssize_t); /*proto*/ +static int __pyx_memslice_transpose(__Pyx_memviewslice *); /*proto*/ +static PyObject *__pyx_memoryview_fromslice(__Pyx_memviewslice, int, PyObject *(*)(char *), int (*)(char *, PyObject *), int); /*proto*/ +static __Pyx_memviewslice *__pyx_memoryview_get_slice_from_memoryview(struct __pyx_memoryview_obj *, __Pyx_memviewslice *); /*proto*/ +static void __pyx_memoryview_slice_copy(struct __pyx_memoryview_obj *, __Pyx_memviewslice *); /*proto*/ +static PyObject *__pyx_memoryview_copy_object(struct __pyx_memoryview_obj *); /*proto*/ +static PyObject *__pyx_memoryview_copy_object_from_slice(struct __pyx_memoryview_obj *, __Pyx_memviewslice *); /*proto*/ +static Py_ssize_t abs_py_ssize_t(Py_ssize_t); /*proto*/ +static char __pyx_get_best_slice_order(__Pyx_memviewslice *, int); /*proto*/ +static void _copy_strided_to_strided(char *, Py_ssize_t *, char *, Py_ssize_t *, Py_ssize_t *, Py_ssize_t *, int, size_t); /*proto*/ +static void copy_strided_to_strided(__Pyx_memviewslice *, __Pyx_memviewslice *, int, size_t); /*proto*/ +static Py_ssize_t __pyx_memoryview_slice_get_size(__Pyx_memviewslice *, int); /*proto*/ +static Py_ssize_t __pyx_fill_contig_strides_array(Py_ssize_t *, Py_ssize_t *, Py_ssize_t, int, char); /*proto*/ +static void *__pyx_memoryview_copy_data_to_temp(__Pyx_memviewslice *, __Pyx_memviewslice *, char, int); /*proto*/ +static int __pyx_memoryview_err_extents(int, Py_ssize_t, Py_ssize_t); /*proto*/ +static int __pyx_memoryview_err_dim(PyObject *, PyObject *, int); /*proto*/ +static int __pyx_memoryview_err(PyObject *, PyObject *); /*proto*/ +static int __pyx_memoryview_err_no_memory(void); /*proto*/ +static int __pyx_memoryview_copy_contents(__Pyx_memviewslice, __Pyx_memviewslice, int, int, int); /*proto*/ +static void __pyx_memoryview_broadcast_leading(__Pyx_memviewslice *, int, int); /*proto*/ +static void __pyx_memoryview_refcount_copying(__Pyx_memviewslice *, int, int, int); /*proto*/ +static void __pyx_memoryview_refcount_objects_in_slice_with_gil(char *, Py_ssize_t *, Py_ssize_t *, int, int); /*proto*/ +static void __pyx_memoryview_refcount_objects_in_slice(char *, Py_ssize_t *, Py_ssize_t *, int, int); /*proto*/ +static void __pyx_memoryview_slice_assign_scalar(__Pyx_memviewslice *, int, size_t, void *, int); /*proto*/ +static void __pyx_memoryview__slice_assign_scalar(char *, Py_ssize_t *, Py_ssize_t *, int, size_t, void *); /*proto*/ +static PyObject *__pyx_unpickle_Enum__set_state(struct __pyx_MemviewEnum_obj *, PyObject *); /*proto*/ +static PyObject *__pyx_format_from_typeinfo(__Pyx_TypeInfo *); /*proto*/ +/* #### Code section: typeinfo ### */ +static __Pyx_TypeInfo __Pyx_TypeInfo_nn___pyx_t_5numpy_uint8_t = { "uint8_t", NULL, sizeof(__pyx_t_5numpy_uint8_t), { 0 }, 0, __PYX_IS_UNSIGNED(__pyx_t_5numpy_uint8_t) ? 'U' : 'I', __PYX_IS_UNSIGNED(__pyx_t_5numpy_uint8_t), 0 }; +static __Pyx_TypeInfo __Pyx_TypeInfo_unsigned_char__const__ = { "const unsigned char", NULL, sizeof(unsigned char const ), { 0 }, 0, __PYX_IS_UNSIGNED(unsigned char const ) ? 'U' : 'I', __PYX_IS_UNSIGNED(unsigned char const ), 0 }; +/* #### Code section: before_global_var ### */ +#define __Pyx_MODULE_NAME "cereal.visionipc.visionipc_pyx" +extern int __pyx_module_is_main_cereal__visionipc__visionipc_pyx; +int __pyx_module_is_main_cereal__visionipc__visionipc_pyx = 0; + +/* Implementation of "cereal.visionipc.visionipc_pyx" */ +/* #### Code section: global_var ### */ +static PyObject *__pyx_builtin_staticmethod; +static PyObject *__pyx_builtin_TypeError; +static PyObject *__pyx_builtin_AssertionError; +static PyObject *__pyx_builtin_ValueError; +static PyObject *__pyx_builtin___import__; +static PyObject *__pyx_builtin_MemoryError; +static PyObject *__pyx_builtin_enumerate; +static PyObject *__pyx_builtin_range; +static PyObject *__pyx_builtin_Ellipsis; +static PyObject *__pyx_builtin_id; +static PyObject *__pyx_builtin_IndexError; +static PyObject *__pyx_builtin_ImportError; +/* #### Code section: string_decls ### */ +static const char __pyx_k_[] = ""; +static const char __pyx_k_O[] = "O"; +static const char __pyx_k_T[] = "T{"; + static const char __pyx_k_c[] = "c"; + static const char __pyx_k_v[] = "v"; + static const char __pyx_k__3[] = "."; + static const char __pyx_k__4[] = ": "; + static const char __pyx_k__5[] = "*"; + static const char __pyx_k__8[] = "'"; + static const char __pyx_k__9[] = ")"; + static const char __pyx_k_gc[] = "gc"; + static const char __pyx_k_id[] = "id"; + static const char __pyx_k_np[] = "np"; + static const char __pyx_k_tp[] = "tp"; + static const char __pyx_k__11[] = "^"; + static const char __pyx_k__12[] = ":"; +static const char __pyx_k__13[] = "}"; +static const char __pyx_k__14[] = "("; +static const char __pyx_k__15[] = ","; +static const char __pyx_k__67[] = "?"; +static const char __pyx_k_abc[] = "abc"; +static const char __pyx_k_and[] = " and "; +static const char __pyx_k_buf[] = "buf"; +static const char __pyx_k_cls[] = "cls"; +static const char __pyx_k_dct[] = "dct"; +static const char __pyx_k_doc[] = "__doc__"; +static const char __pyx_k_get[] = "get"; +static const char __pyx_k_got[] = " (got "; +static const char __pyx_k_new[] = "__new__"; +static const char __pyx_k_obj[] = "obj"; +static const char __pyx_k_res[] = "res"; +static const char __pyx_k_rgb[] = "rgb"; +static const char __pyx_k_s_s[] = "%s.%s"; +static const char __pyx_k_str[] = "__str__"; +static const char __pyx_k_sys[] = "sys"; +static const char __pyx_k_base[] = "base"; +static const char __pyx_k_data[] = "data"; +static const char __pyx_k_dict[] = "__dict__"; +static const char __pyx_k_enum[] = "enum"; +static const char __pyx_k_init[] = "__init__"; +static const char __pyx_k_join[] = "join"; +static const char __pyx_k_main[] = "__main__"; +static const char __pyx_k_mode[] = "mode"; +static const char __pyx_k_name[] = "name"; +static const char __pyx_k_ndim[] = "ndim"; +static const char __pyx_k_pack[] = "pack"; +static const char __pyx_k_recv[] = "recv"; +static const char __pyx_k_repr[] = "__repr__"; +static const char __pyx_k_self[] = "self"; +static const char __pyx_k_send[] = "send"; +static const char __pyx_k_size[] = "size"; +static const char __pyx_k_spec[] = "__spec__"; +static const char __pyx_k_step[] = "step"; +static const char __pyx_k_stop[] = "stop"; +static const char __pyx_k_test[] = "__test__"; +static const char __pyx_k_ASCII[] = "ASCII"; +static const char __pyx_k_block[] = "block"; +static const char __pyx_k_class[] = "__class__"; +static const char __pyx_k_count[] = "count"; +static const char __pyx_k_error[] = "error"; +static const char __pyx_k_extra[] = "extra"; +static const char __pyx_k_flags[] = "flags"; +static const char __pyx_k_index[] = "index"; +static const char __pyx_k_numpy[] = "numpy"; +static const char __pyx_k_range[] = "range"; +static const char __pyx_k_s_s_d[] = "<%s.%s: %d>"; +static const char __pyx_k_shape[] = "shape"; +static const char __pyx_k_start[] = "start"; +static const char __pyx_k_state[] = "state"; +static const char __pyx_k_super[] = "super"; +static const char __pyx_k_value[] = "value"; +static const char __pyx_k_width[] = "width"; +static const char __pyx_k_dict_2[] = "_dict"; +static const char __pyx_k_enable[] = "enable"; +static const char __pyx_k_encode[] = "encode"; +static const char __pyx_k_format[] = "format"; +static const char __pyx_k_height[] = "height"; +static const char __pyx_k_import[] = "__import__"; +static const char __pyx_k_module[] = "__module__"; +static const char __pyx_k_name_2[] = "__name__"; +static const char __pyx_k_pickle[] = "pickle"; +static const char __pyx_k_reduce[] = "__reduce__"; +static const char __pyx_k_stream[] = "stream"; +static const char __pyx_k_stride[] = "stride"; +static const char __pyx_k_struct[] = "struct"; +static const char __pyx_k_unpack[] = "unpack"; +static const char __pyx_k_update[] = "update"; +static const char __pyx_k_values[] = "values"; +static const char __pyx_k_IntEnum[] = "IntEnum"; +static const char __pyx_k_IntFlag[] = "IntFlag"; +static const char __pyx_k_asarray[] = "asarray"; +static const char __pyx_k_connect[] = "connect"; +static const char __pyx_k_context[] = "context"; +static const char __pyx_k_disable[] = "disable"; +static const char __pyx_k_fortran[] = "fortran"; +static const char __pyx_k_members[] = "__members__"; +static const char __pyx_k_memview[] = "memview"; +static const char __pyx_k_parents[] = "parents"; +static const char __pyx_k_prepare[] = "__prepare__"; +static const char __pyx_k_Ellipsis[] = "Ellipsis"; +static const char __pyx_k_EnumBase[] = "EnumBase"; +static const char __pyx_k_EnumType[] = "EnumType"; +static const char __pyx_k_Sequence[] = "Sequence"; +static const char __pyx_k_blocking[] = "blocking"; +static const char __pyx_k_conflate[] = "conflate"; +static const char __pyx_k_frame_id[] = "frame_id"; +static const char __pyx_k_getstate[] = "__getstate__"; +static const char __pyx_k_itemsize[] = "itemsize"; +static const char __pyx_k_module_2[] = "module"; +static const char __pyx_k_pyx_type[] = "__pyx_type"; +static const char __pyx_k_qualname[] = "__qualname__"; +static const char __pyx_k_register[] = "register"; +static const char __pyx_k_set_name[] = "__set_name__"; +static const char __pyx_k_setstate[] = "__setstate__"; +static const char __pyx_k_CLContext[] = "CLContext"; +static const char __pyx_k_TypeError[] = "TypeError"; +static const char __pyx_k_VisionBuf[] = "VisionBuf"; +static const char __pyx_k_enumerate[] = "enumerate"; +static const char __pyx_k_isenabled[] = "isenabled"; +static const char __pyx_k_metaclass[] = "__metaclass__"; +static const char __pyx_k_pyx_state[] = "__pyx_state"; +static const char __pyx_k_reduce_ex[] = "__reduce_ex__"; +static const char __pyx_k_uv_offset[] = "uv_offset"; +static const char __pyx_k_IndexError[] = "IndexError"; +static const char __pyx_k_ValueError[] = "ValueError"; +static const char __pyx_k_pyx_result[] = "__pyx_result"; +static const char __pyx_k_pyx_vtable[] = "__pyx_vtable__"; +static const char __pyx_k_timeout_ms[] = "timeout_ms"; +static const char __pyx_k_ImportError[] = "ImportError"; +static const char __pyx_k_MemoryError[] = "MemoryError"; +static const char __pyx_k_OrderedDict[] = "OrderedDict"; +static const char __pyx_k_PickleError[] = "PickleError"; +static const char __pyx_k_collections[] = "collections"; +static const char __pyx_k_mro_entries[] = "__mro_entries__"; +static const char __pyx_k_num_buffers[] = "num_buffers"; +static const char __pyx_k_Pyx_EnumBase[] = "__Pyx_EnumBase"; +static const char __pyx_k_Pyx_FlagBase[] = "__Pyx_FlagBase"; +static const char __pyx_k_initializing[] = "_initializing"; +static const char __pyx_k_is_connected[] = "is_connected"; +static const char __pyx_k_is_coroutine[] = "_is_coroutine"; +static const char __pyx_k_member_names[] = "_member_names_"; +static const char __pyx_k_pyx_checksum[] = "__pyx_checksum"; +static const char __pyx_k_staticmethod[] = "staticmethod"; +static const char __pyx_k_stringsource[] = ""; +static const char __pyx_k_use_setstate[] = "use_setstate"; +static const char __pyx_k_version_info[] = "version_info"; +static const char __pyx_k_class_getitem[] = "__class_getitem__"; +static const char __pyx_k_init_subclass[] = "__init_subclass__"; +static const char __pyx_k_reduce_cython[] = "__reduce_cython__"; +static const char __pyx_k_timestamp_eof[] = "timestamp_eof"; +static const char __pyx_k_timestamp_sof[] = "timestamp_sof"; +static const char __pyx_k_AssertionError[] = "AssertionError"; +static const char __pyx_k_create_buffers[] = "create_buffers"; +static const char __pyx_k_start_listener[] = "start_listener"; +static const char __pyx_k_View_MemoryView[] = "View.MemoryView"; +static const char __pyx_k_VisionIpcClient[] = "VisionIpcClient"; +static const char __pyx_k_VisionIpcServer[] = "VisionIpcServer"; +static const char __pyx_k_allocate_buffer[] = "allocate_buffer"; +static const char __pyx_k_collections_abc[] = "collections.abc"; +static const char __pyx_k_dtype_is_object[] = "dtype_is_object"; +static const char __pyx_k_pyx_PickleError[] = "__pyx_PickleError"; +static const char __pyx_k_setstate_cython[] = "__setstate_cython__"; +static const char __pyx_k_VisionStreamType[] = "VisionStreamType"; +static const char __pyx_k_VISION_STREAM_MAP[] = "VISION_STREAM_MAP"; +static const char __pyx_k_available_streams[] = "available_streams"; +static const char __pyx_k_get_endpoint_name[] = "get_endpoint_name"; +static const char __pyx_k_pyx_unpickle_Enum[] = "__pyx_unpickle_Enum"; +static const char __pyx_k_Pyx_EnumBase___new[] = "__Pyx_EnumBase.__new__"; +static const char __pyx_k_Pyx_EnumBase___str[] = "__Pyx_EnumBase.__str__"; +static const char __pyx_k_Pyx_FlagBase___new[] = "__Pyx_FlagBase.__new__"; +static const char __pyx_k_Pyx_FlagBase___str[] = "__Pyx_FlagBase.__str__"; +static const char __pyx_k_VISION_STREAM_ROAD[] = "VISION_STREAM_ROAD"; +static const char __pyx_k_asyncio_coroutines[] = "asyncio.coroutines"; +static const char __pyx_k_cline_in_traceback[] = "cline_in_traceback"; +static const char __pyx_k_strided_and_direct[] = ""; +static const char __pyx_k_Pyx_EnumBase___repr[] = "__Pyx_EnumBase.__repr__"; +static const char __pyx_k_Pyx_FlagBase___repr[] = "__Pyx_FlagBase.__repr__"; +static const char __pyx_k_Unknown_enum_value_s[] = "Unknown enum value: '%s'"; +static const char __pyx_k_VISION_STREAM_DRIVER[] = "VISION_STREAM_DRIVER"; +static const char __pyx_k_VisionIpcClient_recv[] = "VisionIpcClient.recv"; +static const char __pyx_k_VisionIpcServer_send[] = "VisionIpcServer.send"; +static const char __pyx_k_strided_and_indirect[] = ""; +static const char __pyx_k_Invalid_shape_in_axis[] = "Invalid shape in axis "; +static const char __pyx_k_contiguous_and_direct[] = ""; +static const char __pyx_k_Cannot_index_with_type[] = "Cannot index with type '"; +static const char __pyx_k_MemoryView_of_r_object[] = ""; +static const char __pyx_k_MemoryView_of_r_at_0x_x[] = ""; +static const char __pyx_k_VISION_STREAM_WIDE_ROAD[] = "VISION_STREAM_WIDE_ROAD"; +static const char __pyx_k_VisionIpcClient_connect[] = "VisionIpcClient.connect"; +static const char __pyx_k_contiguous_and_indirect[] = ""; +static const char __pyx_k_Dimension_d_is_not_direct[] = "Dimension %d is not direct"; +static const char __pyx_k_VisionBuf___reduce_cython[] = "VisionBuf.__reduce_cython__"; +static const char __pyx_k_create_buffers_with_sizes[] = "create_buffers_with_sizes"; +static const char __pyx_k_Index_out_of_bounds_axis_d[] = "Index out of bounds (axis %d)"; +static const char __pyx_k_Step_may_not_be_zero_axis_d[] = "Step may not be zero (axis %d)"; +static const char __pyx_k_VisionBuf___setstate_cython[] = "VisionBuf.__setstate_cython__"; +static const char __pyx_k_itemsize_0_for_cython_array[] = "itemsize <= 0 for cython.array"; +static const char __pyx_k_pyx_unpickle___Pyx_EnumMeta[] = "__pyx_unpickle___Pyx_EnumMeta"; +static const char __pyx_k_Pyx_EnumMeta___reduce_cython[] = "__Pyx_EnumMeta.__reduce_cython__"; +static const char __pyx_k_VisionIpcClient_is_connected[] = "VisionIpcClient.is_connected"; +static const char __pyx_k_unable_to_allocate_array_data[] = "unable to allocate array data."; +static const char __pyx_k_Pyx_EnumMeta___setstate_cython[] = "__Pyx_EnumMeta.__setstate_cython__"; +static const char __pyx_k_VisionIpcServer_create_buffers[] = "VisionIpcServer.create_buffers"; +static const char __pyx_k_VisionIpcServer_start_listener[] = "VisionIpcServer.start_listener"; +static const char __pyx_k_cereal_visionipc_visionipc_pyx[] = "cereal.visionipc.visionipc_pyx"; +static const char __pyx_k_strided_and_direct_or_indirect[] = ""; +static const char __pyx_k_VisionIpcClient___reduce_cython[] = "VisionIpcClient.__reduce_cython__"; +static const char __pyx_k_VisionIpcServer___reduce_cython[] = "VisionIpcServer.__reduce_cython__"; +static const char __pyx_k_numpy_core_multiarray_failed_to[] = "numpy.core.multiarray failed to import"; +static const char __pyx_k_self_buf_cannot_be_converted_to[] = "self.buf cannot be converted to a Python object for pickling"; +static const char __pyx_k_self_server_cannot_be_converted[] = "self.server cannot be converted to a Python object for pickling"; +static const char __pyx_k_All_dimensions_preceding_dimensi[] = "All dimensions preceding dimension %d must be indexed and not sliced"; +static const char __pyx_k_Buffer_view_does_not_expose_stri[] = "Buffer view does not expose strides"; +static const char __pyx_k_Can_only_create_a_buffer_that_is[] = "Can only create a buffer that is contiguous in memory."; +static const char __pyx_k_Cannot_assign_to_read_only_memor[] = "Cannot assign to read-only memoryview"; +static const char __pyx_k_Cannot_create_writable_memory_vi[] = "Cannot create writable memory view from read-only memoryview"; +static const char __pyx_k_Cannot_transpose_memoryview_with[] = "Cannot transpose memoryview with indirect dimensions"; +static const char __pyx_k_Empty_shape_tuple_for_cython_arr[] = "Empty shape tuple for cython.array"; +static const char __pyx_k_Incompatible_checksums_0x_x_vs_0[] = "Incompatible checksums (0x%x vs (0xe3b0c44, 0xda39a3e, 0xd41d8cd) = ())"; +static const char __pyx_k_Indirect_dimensions_not_supporte[] = "Indirect dimensions not supported"; +static const char __pyx_k_Invalid_mode_expected_c_or_fortr[] = "Invalid mode, expected 'c' or 'fortran', got "; +static const char __pyx_k_Out_of_bounds_on_buffer_access_a[] = "Out of bounds on buffer access (axis "; +static const char __pyx_k_Unable_to_convert_item_to_object[] = "Unable to convert item to object"; +static const char __pyx_k_VisionIpcClient___setstate_cytho[] = "VisionIpcClient.__setstate_cython__"; +static const char __pyx_k_VisionIpcClient_available_stream[] = "VisionIpcClient.available_streams"; +static const char __pyx_k_VisionIpcServer___setstate_cytho[] = "VisionIpcServer.__setstate_cython__"; +static const char __pyx_k_VisionIpcServer_create_buffers_w[] = "VisionIpcServer.create_buffers_with_sizes"; +static const char __pyx_k_cereal_visionipc_visionipc_pyx_p[] = "cereal/visionipc/visionipc_pyx.pyx"; +static const char __pyx_k_got_differing_extents_in_dimensi[] = "got differing extents in dimension "; +static const char __pyx_k_no_default___reduce___due_to_non[] = "no default __reduce__ due to non-trivial __cinit__"; +static const char __pyx_k_numpy_core_umath_failed_to_impor[] = "numpy.core.umath failed to import"; +static const char __pyx_k_unable_to_allocate_shape_and_str[] = "unable to allocate shape and strides."; +static const char __pyx_k_Incompatible_checksums_0x_x_vs_0_2[] = "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))"; +/* #### Code section: decls ### */ +static int __pyx_pf_8EnumBase_14__Pyx_EnumMeta___init__(struct __pyx_obj___Pyx_EnumMeta *__pyx_v_cls, PyObject *__pyx_v_name, PyObject *__pyx_v_parents, PyObject *__pyx_v_dct); /* proto */ +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumMeta_2__iter__(struct __pyx_obj___Pyx_EnumMeta *__pyx_v_cls); /* proto */ +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumMeta_4__getitem__(struct __pyx_obj___Pyx_EnumMeta *__pyx_v_cls, PyObject *__pyx_v_name); /* proto */ +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumMeta_6__reduce_cython__(struct __pyx_obj___Pyx_EnumMeta *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumMeta_8__setstate_cython__(struct __pyx_obj___Pyx_EnumMeta *__pyx_v_self, PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumBase___new__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_cls, PyObject *__pyx_v_value, PyObject *__pyx_v_name); /* proto */ +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumBase_2__repr__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumBase_4__str__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_8EnumBase_14__Pyx_FlagBase___new__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_cls, PyObject *__pyx_v_value, PyObject *__pyx_v_name); /* proto */ +static PyObject *__pyx_pf_8EnumBase_14__Pyx_FlagBase_2__repr__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_8EnumBase_14__Pyx_FlagBase_4__str__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_8EnumBase___pyx_unpickle___Pyx_EnumMeta(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v___pyx_type, long __pyx_v___pyx_checksum, PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array___cinit__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_shape, Py_ssize_t __pyx_v_itemsize, PyObject *__pyx_v_format, PyObject *__pyx_v_mode, int __pyx_v_allocate_buffer); /* proto */ +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_2__getbuffer__(struct __pyx_array_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /* proto */ +static void __pyx_array___pyx_pf_15View_dot_MemoryView_5array_4__dealloc__(struct __pyx_array_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_5array_7memview___get__(struct __pyx_array_obj *__pyx_v_self); /* proto */ +static Py_ssize_t __pyx_array___pyx_pf_15View_dot_MemoryView_5array_6__len__(struct __pyx_array_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_8__getattr__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_attr); /* proto */ +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_10__getitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item); /* proto */ +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_12__setitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value); /* proto */ +static PyObject *__pyx_pf___pyx_array___reduce_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_array_2__setstate_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum___init__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v_name); /* proto */ +static PyObject *__pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum_2__repr__(struct __pyx_MemviewEnum_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_MemviewEnum___reduce_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_MemviewEnum_2__setstate_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview___cinit__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj, int __pyx_v_flags, int __pyx_v_dtype_is_object); /* proto */ +static void __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_2__dealloc__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_4__getitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index); /* proto */ +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_6__setitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value); /* proto */ +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_8__getbuffer__(struct __pyx_memoryview_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_1T___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4base___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_5shape___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_7strides___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_10suboffsets___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4ndim___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_8itemsize___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_6nbytes___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4size___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static Py_ssize_t __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_10__len__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_12__repr__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_14__str__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_16is_c_contig(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_18is_f_contig(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_20copy(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_22copy_fortran(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryview___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryview_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static void __pyx_memoryviewslice___pyx_pf_15View_dot_MemoryView_16_memoryviewslice___dealloc__(struct __pyx_memoryviewslice_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryviewslice___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryviewslice_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView___pyx_unpickle_Enum(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v___pyx_type, long __pyx_v___pyx_checksum, PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_get_endpoint_name(CYTHON_UNUSED PyObject *__pyx_self, std::string __pyx_v_name, enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType __pyx_v_stream); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_4data___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_5width___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_6height___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_6stride___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_9uv_offset___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_3rgb___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf___reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_2__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer___init__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *__pyx_v_self, std::string __pyx_v_name); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_2create_buffers(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *__pyx_v_self, enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType __pyx_v_tp, size_t __pyx_v_num_buffers, bool __pyx_v_rgb, size_t __pyx_v_width, size_t __pyx_v_height); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_4create_buffers_with_sizes(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *__pyx_v_self, enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType __pyx_v_tp, size_t __pyx_v_num_buffers, bool __pyx_v_rgb, size_t __pyx_v_width, size_t __pyx_v_height, size_t __pyx_v_size, size_t __pyx_v_stride, size_t __pyx_v_uv_offset); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_6send(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *__pyx_v_self, enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType __pyx_v_tp, __Pyx_memviewslice __pyx_v_data, uint32_t __pyx_v_frame_id, uint64_t __pyx_v_timestamp_sof, uint64_t __pyx_v_timestamp_eof); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_8start_listener(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *__pyx_v_self); /* proto */ +static void __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_10__dealloc__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_12__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_14__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient___cinit__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self, std::string __pyx_v_name, enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType __pyx_v_stream, bool __pyx_v_conflate, struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_CLContext *__pyx_v_context); /* proto */ +static void __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_2__dealloc__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_5width___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_6height___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_6stride___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_9uv_offset___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_3rgb___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_10buffer_len___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_11num_buffers___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_8frame_id___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_13timestamp_sof___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_13timestamp_eof___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_5valid___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_4recv(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self, int __pyx_v_timeout_ms); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_6connect(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self, bool __pyx_v_blocking); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_8is_connected(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_10available_streams(std::string __pyx_v_name, bool __pyx_v_block); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_12__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_14__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_tp_new_6cereal_9visionipc_13visionipc_pyx_CLContext(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_6cereal_9visionipc_13visionipc_pyx_VisionBuf(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_array(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_Enum(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_memoryview(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new__memoryviewslice(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static __Pyx_CachedCFunction __pyx_umethod_PyDict_Type_get = {0, 0, 0, 0, 0}; +/* #### Code section: late_includes ### */ +/* #### Code section: module_state ### */ +typedef struct { + PyObject *__pyx_d; + PyObject *__pyx_b; + PyObject *__pyx_cython_runtime; + PyObject *__pyx_empty_tuple; + PyObject *__pyx_empty_bytes; + PyObject *__pyx_empty_unicode; + #ifdef __Pyx_CyFunction_USED + PyTypeObject *__pyx_CyFunctionType; + #endif + #ifdef __Pyx_FusedFunction_USED + PyTypeObject *__pyx_FusedFunctionType; + #endif + #ifdef __Pyx_Generator_USED + PyTypeObject *__pyx_GeneratorType; + #endif + #ifdef __Pyx_IterableCoroutine_USED + PyTypeObject *__pyx_IterableCoroutineType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineAwaitType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineType; + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + PyTypeObject *__pyx_ptype_7cpython_4type_type; + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + PyTypeObject *__pyx_ptype_5numpy_dtype; + PyTypeObject *__pyx_ptype_5numpy_flatiter; + PyTypeObject *__pyx_ptype_5numpy_broadcast; + PyTypeObject *__pyx_ptype_5numpy_ndarray; + PyTypeObject *__pyx_ptype_5numpy_generic; + PyTypeObject *__pyx_ptype_5numpy_number; + PyTypeObject *__pyx_ptype_5numpy_integer; + PyTypeObject *__pyx_ptype_5numpy_signedinteger; + PyTypeObject *__pyx_ptype_5numpy_unsignedinteger; + PyTypeObject *__pyx_ptype_5numpy_inexact; + PyTypeObject *__pyx_ptype_5numpy_floating; + PyTypeObject *__pyx_ptype_5numpy_complexfloating; + PyTypeObject *__pyx_ptype_5numpy_flexible; + PyTypeObject *__pyx_ptype_5numpy_character; + PyTypeObject *__pyx_ptype_5numpy_ufunc; + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + PyObject *__pyx_type_6cereal_9visionipc_13visionipc_pyx_CLContext; + PyObject *__pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionBuf; + PyObject *__pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer; + PyObject *__pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient; + PyObject *__Pyx_EnumMeta; + PyObject *__pyx_type___pyx_array; + PyObject *__pyx_type___pyx_MemviewEnum; + PyObject *__pyx_type___pyx_memoryview; + PyObject *__pyx_type___pyx_memoryviewslice; + #endif + PyTypeObject *__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext; + PyTypeObject *__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf; + PyTypeObject *__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer; + PyTypeObject *__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient; + PyTypeObject *__pyx_ptype___Pyx_EnumMeta; + PyTypeObject *__pyx_array_type; + PyTypeObject *__pyx_MemviewEnum_type; + PyTypeObject *__pyx_memoryview_type; + PyTypeObject *__pyx_memoryviewslice_type; + PyObject *__pyx_kp_b_; + PyObject *__pyx_kp_s_; + PyObject *__pyx_n_s_ASCII; + PyObject *__pyx_kp_s_All_dimensions_preceding_dimensi; + PyObject *__pyx_n_s_AssertionError; + PyObject *__pyx_kp_s_Buffer_view_does_not_expose_stri; + PyObject *__pyx_n_s_CLContext; + PyObject *__pyx_kp_s_Can_only_create_a_buffer_that_is; + PyObject *__pyx_kp_s_Cannot_assign_to_read_only_memor; + PyObject *__pyx_kp_s_Cannot_create_writable_memory_vi; + PyObject *__pyx_kp_u_Cannot_index_with_type; + PyObject *__pyx_kp_s_Cannot_transpose_memoryview_with; + PyObject *__pyx_kp_s_Dimension_d_is_not_direct; + PyObject *__pyx_n_s_Ellipsis; + PyObject *__pyx_kp_s_Empty_shape_tuple_for_cython_arr; + PyObject *__pyx_n_s_EnumBase; + PyObject *__pyx_n_s_EnumType; + PyObject *__pyx_n_s_ImportError; + PyObject *__pyx_kp_s_Incompatible_checksums_0x_x_vs_0; + PyObject *__pyx_kp_s_Incompatible_checksums_0x_x_vs_0_2; + PyObject *__pyx_n_s_IndexError; + PyObject *__pyx_kp_s_Index_out_of_bounds_axis_d; + PyObject *__pyx_kp_s_Indirect_dimensions_not_supporte; + PyObject *__pyx_n_s_IntEnum; + PyObject *__pyx_n_s_IntFlag; + PyObject *__pyx_kp_u_Invalid_mode_expected_c_or_fortr; + PyObject *__pyx_kp_u_Invalid_shape_in_axis; + PyObject *__pyx_n_s_MemoryError; + PyObject *__pyx_kp_s_MemoryView_of_r_at_0x_x; + PyObject *__pyx_kp_s_MemoryView_of_r_object; + PyObject *__pyx_n_b_O; + PyObject *__pyx_n_s_OrderedDict; + PyObject *__pyx_kp_u_Out_of_bounds_on_buffer_access_a; + PyObject *__pyx_n_s_PickleError; + PyObject *__pyx_n_s_Pyx_EnumBase; + PyObject *__pyx_n_s_Pyx_EnumBase___new; + PyObject *__pyx_n_s_Pyx_EnumBase___repr; + PyObject *__pyx_n_s_Pyx_EnumBase___str; + PyObject *__pyx_n_s_Pyx_EnumMeta___reduce_cython; + PyObject *__pyx_n_s_Pyx_EnumMeta___setstate_cython; + PyObject *__pyx_n_s_Pyx_FlagBase; + PyObject *__pyx_n_s_Pyx_FlagBase___new; + PyObject *__pyx_n_s_Pyx_FlagBase___repr; + PyObject *__pyx_n_s_Pyx_FlagBase___str; + PyObject *__pyx_n_s_Sequence; + PyObject *__pyx_kp_s_Step_may_not_be_zero_axis_d; + PyObject *__pyx_kp_b_T; + PyObject *__pyx_n_s_TypeError; + PyObject *__pyx_kp_s_Unable_to_convert_item_to_object; + PyObject *__pyx_kp_s_Unknown_enum_value_s; + PyObject *__pyx_n_s_VISION_STREAM_DRIVER; + PyObject *__pyx_n_s_VISION_STREAM_MAP; + PyObject *__pyx_n_s_VISION_STREAM_ROAD; + PyObject *__pyx_n_s_VISION_STREAM_WIDE_ROAD; + PyObject *__pyx_n_s_ValueError; + PyObject *__pyx_n_s_View_MemoryView; + PyObject *__pyx_n_s_VisionBuf; + PyObject *__pyx_n_s_VisionBuf___reduce_cython; + PyObject *__pyx_n_s_VisionBuf___setstate_cython; + PyObject *__pyx_n_s_VisionIpcClient; + PyObject *__pyx_n_s_VisionIpcClient___reduce_cython; + PyObject *__pyx_n_s_VisionIpcClient___setstate_cytho; + PyObject *__pyx_n_s_VisionIpcClient_available_stream; + PyObject *__pyx_n_s_VisionIpcClient_connect; + PyObject *__pyx_n_s_VisionIpcClient_is_connected; + PyObject *__pyx_n_s_VisionIpcClient_recv; + PyObject *__pyx_n_s_VisionIpcServer; + PyObject *__pyx_n_s_VisionIpcServer___reduce_cython; + PyObject *__pyx_n_s_VisionIpcServer___setstate_cytho; + PyObject *__pyx_n_s_VisionIpcServer_create_buffers; + PyObject *__pyx_n_s_VisionIpcServer_create_buffers_w; + PyObject *__pyx_n_s_VisionIpcServer_send; + PyObject *__pyx_n_s_VisionIpcServer_start_listener; + PyObject *__pyx_n_s_VisionStreamType; + PyObject *__pyx_kp_b__11; + PyObject *__pyx_kp_b__12; + PyObject *__pyx_kp_b__13; + PyObject *__pyx_kp_u__14; + PyObject *__pyx_kp_u__15; + PyObject *__pyx_kp_u__3; + PyObject *__pyx_kp_u__4; + PyObject *__pyx_n_s__5; + PyObject *__pyx_n_s__67; + PyObject *__pyx_kp_u__8; + PyObject *__pyx_kp_u__9; + PyObject *__pyx_n_s_abc; + PyObject *__pyx_n_s_allocate_buffer; + PyObject *__pyx_kp_u_and; + PyObject *__pyx_n_s_asarray; + PyObject *__pyx_n_s_asyncio_coroutines; + PyObject *__pyx_n_s_available_streams; + PyObject *__pyx_n_s_base; + PyObject *__pyx_n_s_block; + PyObject *__pyx_n_s_blocking; + PyObject *__pyx_n_s_buf; + PyObject *__pyx_n_s_c; + PyObject *__pyx_n_u_c; + PyObject *__pyx_kp_s_cereal_visionipc_visionipc_pyx; + PyObject *__pyx_kp_s_cereal_visionipc_visionipc_pyx_p; + PyObject *__pyx_n_s_class; + PyObject *__pyx_n_s_class_getitem; + PyObject *__pyx_n_s_cline_in_traceback; + PyObject *__pyx_n_s_cls; + PyObject *__pyx_n_s_collections; + PyObject *__pyx_kp_s_collections_abc; + PyObject *__pyx_n_s_conflate; + PyObject *__pyx_n_s_connect; + PyObject *__pyx_n_s_context; + PyObject *__pyx_kp_s_contiguous_and_direct; + PyObject *__pyx_kp_s_contiguous_and_indirect; + PyObject *__pyx_n_s_count; + PyObject *__pyx_n_s_create_buffers; + PyObject *__pyx_n_s_create_buffers_with_sizes; + PyObject *__pyx_n_s_data; + PyObject *__pyx_n_s_dct; + PyObject *__pyx_n_s_dict; + PyObject *__pyx_n_s_dict_2; + PyObject *__pyx_kp_u_disable; + PyObject *__pyx_n_s_doc; + PyObject *__pyx_n_s_dtype_is_object; + PyObject *__pyx_kp_u_enable; + PyObject *__pyx_n_s_encode; + PyObject *__pyx_n_s_enum; + PyObject *__pyx_n_s_enumerate; + PyObject *__pyx_n_s_error; + PyObject *__pyx_n_s_extra; + PyObject *__pyx_n_s_flags; + PyObject *__pyx_n_s_format; + PyObject *__pyx_n_s_fortran; + PyObject *__pyx_n_u_fortran; + PyObject *__pyx_n_s_frame_id; + PyObject *__pyx_kp_u_gc; + PyObject *__pyx_n_s_get; + PyObject *__pyx_n_s_get_endpoint_name; + PyObject *__pyx_n_s_getstate; + PyObject *__pyx_kp_u_got; + PyObject *__pyx_kp_u_got_differing_extents_in_dimensi; + PyObject *__pyx_n_s_height; + PyObject *__pyx_n_s_id; + PyObject *__pyx_n_s_import; + PyObject *__pyx_n_s_index; + PyObject *__pyx_n_s_init; + PyObject *__pyx_n_s_init_subclass; + PyObject *__pyx_n_s_initializing; + PyObject *__pyx_n_s_is_connected; + PyObject *__pyx_n_s_is_coroutine; + PyObject *__pyx_kp_u_isenabled; + PyObject *__pyx_n_s_itemsize; + PyObject *__pyx_kp_s_itemsize_0_for_cython_array; + PyObject *__pyx_n_s_join; + PyObject *__pyx_n_s_main; + PyObject *__pyx_n_s_member_names; + PyObject *__pyx_n_s_members; + PyObject *__pyx_n_s_memview; + PyObject *__pyx_n_s_metaclass; + PyObject *__pyx_n_s_mode; + PyObject *__pyx_n_s_module; + PyObject *__pyx_n_s_module_2; + PyObject *__pyx_n_s_mro_entries; + PyObject *__pyx_n_s_name; + PyObject *__pyx_n_s_name_2; + PyObject *__pyx_n_s_ndim; + PyObject *__pyx_n_s_new; + PyObject *__pyx_kp_s_no_default___reduce___due_to_non; + PyObject *__pyx_n_s_np; + PyObject *__pyx_n_s_num_buffers; + PyObject *__pyx_n_s_numpy; + PyObject *__pyx_kp_u_numpy_core_multiarray_failed_to; + PyObject *__pyx_kp_u_numpy_core_umath_failed_to_impor; + PyObject *__pyx_n_s_obj; + PyObject *__pyx_n_s_pack; + PyObject *__pyx_n_s_parents; + PyObject *__pyx_n_s_pickle; + PyObject *__pyx_n_s_prepare; + PyObject *__pyx_n_s_pyx_PickleError; + PyObject *__pyx_n_s_pyx_checksum; + PyObject *__pyx_n_s_pyx_result; + PyObject *__pyx_n_s_pyx_state; + PyObject *__pyx_n_s_pyx_type; + PyObject *__pyx_n_s_pyx_unpickle_Enum; + PyObject *__pyx_n_s_pyx_unpickle___Pyx_EnumMeta; + PyObject *__pyx_n_s_pyx_vtable; + PyObject *__pyx_n_s_qualname; + PyObject *__pyx_n_s_range; + PyObject *__pyx_n_s_recv; + PyObject *__pyx_n_s_reduce; + PyObject *__pyx_n_s_reduce_cython; + PyObject *__pyx_n_s_reduce_ex; + PyObject *__pyx_n_s_register; + PyObject *__pyx_n_s_repr; + PyObject *__pyx_n_s_res; + PyObject *__pyx_n_s_rgb; + PyObject *__pyx_kp_s_s_s; + PyObject *__pyx_kp_s_s_s_d; + PyObject *__pyx_n_s_self; + PyObject *__pyx_kp_s_self_buf_cannot_be_converted_to; + PyObject *__pyx_kp_s_self_server_cannot_be_converted; + PyObject *__pyx_n_s_send; + PyObject *__pyx_n_s_set_name; + PyObject *__pyx_n_s_setstate; + PyObject *__pyx_n_s_setstate_cython; + PyObject *__pyx_n_s_shape; + PyObject *__pyx_n_s_size; + PyObject *__pyx_n_s_spec; + PyObject *__pyx_n_s_start; + PyObject *__pyx_n_s_start_listener; + PyObject *__pyx_n_s_state; + PyObject *__pyx_n_s_staticmethod; + PyObject *__pyx_n_s_step; + PyObject *__pyx_n_s_stop; + PyObject *__pyx_n_s_str; + PyObject *__pyx_n_s_stream; + PyObject *__pyx_n_s_stride; + PyObject *__pyx_kp_s_strided_and_direct; + PyObject *__pyx_kp_s_strided_and_direct_or_indirect; + PyObject *__pyx_kp_s_strided_and_indirect; + PyObject *__pyx_kp_s_stringsource; + PyObject *__pyx_n_s_struct; + PyObject *__pyx_n_s_super; + PyObject *__pyx_n_s_sys; + PyObject *__pyx_n_s_test; + PyObject *__pyx_n_s_timeout_ms; + PyObject *__pyx_n_s_timestamp_eof; + PyObject *__pyx_n_s_timestamp_sof; + PyObject *__pyx_n_s_tp; + PyObject *__pyx_kp_s_unable_to_allocate_array_data; + PyObject *__pyx_kp_s_unable_to_allocate_shape_and_str; + PyObject *__pyx_n_s_unpack; + PyObject *__pyx_n_s_update; + PyObject *__pyx_n_s_use_setstate; + PyObject *__pyx_n_s_uv_offset; + PyObject *__pyx_n_s_v; + PyObject *__pyx_n_s_value; + PyObject *__pyx_n_s_values; + PyObject *__pyx_n_s_version_info; + PyObject *__pyx_n_s_width; + PyObject *__pyx_int_0; + PyObject *__pyx_int_1; + PyObject *__pyx_int_3; + PyObject *__pyx_int_100; + PyObject *__pyx_int_112105877; + PyObject *__pyx_int_136983863; + PyObject *__pyx_int_184977713; + PyObject *__pyx_int_222419149; + PyObject *__pyx_int_228825662; + PyObject *__pyx_int_238750788; + PyObject *__pyx_int_neg_1; + PyObject *__pyx_slice__7; + PyObject *__pyx_tuple__2; + PyObject *__pyx_tuple__6; + PyObject *__pyx_tuple__10; + PyObject *__pyx_tuple__16; + PyObject *__pyx_tuple__17; + PyObject *__pyx_tuple__18; + PyObject *__pyx_tuple__20; + PyObject *__pyx_tuple__22; + PyObject *__pyx_tuple__24; + PyObject *__pyx_tuple__25; + PyObject *__pyx_tuple__31; + PyObject *__pyx_tuple__33; + PyObject *__pyx_tuple__34; + PyObject *__pyx_tuple__35; + PyObject *__pyx_tuple__36; + PyObject *__pyx_tuple__37; + PyObject *__pyx_tuple__38; + PyObject *__pyx_tuple__39; + PyObject *__pyx_tuple__40; + PyObject *__pyx_tuple__41; + PyObject *__pyx_tuple__43; + PyObject *__pyx_tuple__47; + PyObject *__pyx_tuple__49; + PyObject *__pyx_tuple__51; + PyObject *__pyx_tuple__53; + PyObject *__pyx_tuple__57; + PyObject *__pyx_tuple__59; + PyObject *__pyx_tuple__60; + PyObject *__pyx_tuple__63; + PyObject *__pyx_codeobj__19; + PyObject *__pyx_codeobj__21; + PyObject *__pyx_codeobj__23; + PyObject *__pyx_codeobj__26; + PyObject *__pyx_codeobj__27; + PyObject *__pyx_codeobj__28; + PyObject *__pyx_codeobj__29; + PyObject *__pyx_codeobj__30; + PyObject *__pyx_codeobj__32; + PyObject *__pyx_codeobj__42; + PyObject *__pyx_codeobj__44; + PyObject *__pyx_codeobj__45; + PyObject *__pyx_codeobj__46; + PyObject *__pyx_codeobj__48; + PyObject *__pyx_codeobj__50; + PyObject *__pyx_codeobj__52; + PyObject *__pyx_codeobj__54; + PyObject *__pyx_codeobj__55; + PyObject *__pyx_codeobj__56; + PyObject *__pyx_codeobj__58; + PyObject *__pyx_codeobj__61; + PyObject *__pyx_codeobj__62; + PyObject *__pyx_codeobj__64; + PyObject *__pyx_codeobj__65; + PyObject *__pyx_codeobj__66; +} __pyx_mstate; + +#if CYTHON_USE_MODULE_STATE +#ifdef __cplusplus +namespace { + extern struct PyModuleDef __pyx_moduledef; +} /* anonymous namespace */ +#else +static struct PyModuleDef __pyx_moduledef; +#endif + +#define __pyx_mstate(o) ((__pyx_mstate *)__Pyx_PyModule_GetState(o)) + +#define __pyx_mstate_global (__pyx_mstate(PyState_FindModule(&__pyx_moduledef))) + +#define __pyx_m (PyState_FindModule(&__pyx_moduledef)) +#else +static __pyx_mstate __pyx_mstate_global_static = +#ifdef __cplusplus + {}; +#else + {0}; +#endif +static __pyx_mstate *__pyx_mstate_global = &__pyx_mstate_global_static; +#endif +/* #### Code section: module_state_clear ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_clear(PyObject *m) { + __pyx_mstate *clear_module_state = __pyx_mstate(m); + if (!clear_module_state) return 0; + Py_CLEAR(clear_module_state->__pyx_d); + Py_CLEAR(clear_module_state->__pyx_b); + Py_CLEAR(clear_module_state->__pyx_cython_runtime); + Py_CLEAR(clear_module_state->__pyx_empty_tuple); + Py_CLEAR(clear_module_state->__pyx_empty_bytes); + Py_CLEAR(clear_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_CLEAR(clear_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_CLEAR(clear_module_state->__pyx_FusedFunctionType); + #endif + Py_CLEAR(clear_module_state->__pyx_ptype_7cpython_4type_type); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_dtype); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_flatiter); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_broadcast); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_ndarray); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_generic); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_number); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_integer); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_signedinteger); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_unsignedinteger); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_inexact); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_floating); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_complexfloating); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_flexible); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_character); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_ufunc); + Py_CLEAR(clear_module_state->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext); + Py_CLEAR(clear_module_state->__pyx_type_6cereal_9visionipc_13visionipc_pyx_CLContext); + Py_CLEAR(clear_module_state->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf); + Py_CLEAR(clear_module_state->__pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionBuf); + Py_CLEAR(clear_module_state->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer); + Py_CLEAR(clear_module_state->__pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer); + Py_CLEAR(clear_module_state->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient); + Py_CLEAR(clear_module_state->__pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient); + Py_CLEAR(clear_module_state->__pyx_ptype___Pyx_EnumMeta); + Py_CLEAR(clear_module_state->__Pyx_EnumMeta); + Py_CLEAR(clear_module_state->__pyx_array_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_array); + Py_CLEAR(clear_module_state->__pyx_MemviewEnum_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_MemviewEnum); + Py_CLEAR(clear_module_state->__pyx_memoryview_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_memoryview); + Py_CLEAR(clear_module_state->__pyx_memoryviewslice_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_memoryviewslice); + Py_CLEAR(clear_module_state->__pyx_kp_b_); + Py_CLEAR(clear_module_state->__pyx_kp_s_); + Py_CLEAR(clear_module_state->__pyx_n_s_ASCII); + Py_CLEAR(clear_module_state->__pyx_kp_s_All_dimensions_preceding_dimensi); + Py_CLEAR(clear_module_state->__pyx_n_s_AssertionError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Buffer_view_does_not_expose_stri); + Py_CLEAR(clear_module_state->__pyx_n_s_CLContext); + Py_CLEAR(clear_module_state->__pyx_kp_s_Can_only_create_a_buffer_that_is); + Py_CLEAR(clear_module_state->__pyx_kp_s_Cannot_assign_to_read_only_memor); + Py_CLEAR(clear_module_state->__pyx_kp_s_Cannot_create_writable_memory_vi); + Py_CLEAR(clear_module_state->__pyx_kp_u_Cannot_index_with_type); + Py_CLEAR(clear_module_state->__pyx_kp_s_Cannot_transpose_memoryview_with); + Py_CLEAR(clear_module_state->__pyx_kp_s_Dimension_d_is_not_direct); + Py_CLEAR(clear_module_state->__pyx_n_s_Ellipsis); + Py_CLEAR(clear_module_state->__pyx_kp_s_Empty_shape_tuple_for_cython_arr); + Py_CLEAR(clear_module_state->__pyx_n_s_EnumBase); + Py_CLEAR(clear_module_state->__pyx_n_s_EnumType); + Py_CLEAR(clear_module_state->__pyx_n_s_ImportError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0); + Py_CLEAR(clear_module_state->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0_2); + Py_CLEAR(clear_module_state->__pyx_n_s_IndexError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Index_out_of_bounds_axis_d); + Py_CLEAR(clear_module_state->__pyx_kp_s_Indirect_dimensions_not_supporte); + Py_CLEAR(clear_module_state->__pyx_n_s_IntEnum); + Py_CLEAR(clear_module_state->__pyx_n_s_IntFlag); + Py_CLEAR(clear_module_state->__pyx_kp_u_Invalid_mode_expected_c_or_fortr); + Py_CLEAR(clear_module_state->__pyx_kp_u_Invalid_shape_in_axis); + Py_CLEAR(clear_module_state->__pyx_n_s_MemoryError); + Py_CLEAR(clear_module_state->__pyx_kp_s_MemoryView_of_r_at_0x_x); + Py_CLEAR(clear_module_state->__pyx_kp_s_MemoryView_of_r_object); + Py_CLEAR(clear_module_state->__pyx_n_b_O); + Py_CLEAR(clear_module_state->__pyx_n_s_OrderedDict); + Py_CLEAR(clear_module_state->__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + Py_CLEAR(clear_module_state->__pyx_n_s_PickleError); + Py_CLEAR(clear_module_state->__pyx_n_s_Pyx_EnumBase); + Py_CLEAR(clear_module_state->__pyx_n_s_Pyx_EnumBase___new); + Py_CLEAR(clear_module_state->__pyx_n_s_Pyx_EnumBase___repr); + Py_CLEAR(clear_module_state->__pyx_n_s_Pyx_EnumBase___str); + Py_CLEAR(clear_module_state->__pyx_n_s_Pyx_EnumMeta___reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_Pyx_EnumMeta___setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_Pyx_FlagBase); + Py_CLEAR(clear_module_state->__pyx_n_s_Pyx_FlagBase___new); + Py_CLEAR(clear_module_state->__pyx_n_s_Pyx_FlagBase___repr); + Py_CLEAR(clear_module_state->__pyx_n_s_Pyx_FlagBase___str); + Py_CLEAR(clear_module_state->__pyx_n_s_Sequence); + Py_CLEAR(clear_module_state->__pyx_kp_s_Step_may_not_be_zero_axis_d); + Py_CLEAR(clear_module_state->__pyx_kp_b_T); + Py_CLEAR(clear_module_state->__pyx_n_s_TypeError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Unable_to_convert_item_to_object); + Py_CLEAR(clear_module_state->__pyx_kp_s_Unknown_enum_value_s); + Py_CLEAR(clear_module_state->__pyx_n_s_VISION_STREAM_DRIVER); + Py_CLEAR(clear_module_state->__pyx_n_s_VISION_STREAM_MAP); + Py_CLEAR(clear_module_state->__pyx_n_s_VISION_STREAM_ROAD); + Py_CLEAR(clear_module_state->__pyx_n_s_VISION_STREAM_WIDE_ROAD); + Py_CLEAR(clear_module_state->__pyx_n_s_ValueError); + Py_CLEAR(clear_module_state->__pyx_n_s_View_MemoryView); + Py_CLEAR(clear_module_state->__pyx_n_s_VisionBuf); + Py_CLEAR(clear_module_state->__pyx_n_s_VisionBuf___reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_VisionBuf___setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_VisionIpcClient); + Py_CLEAR(clear_module_state->__pyx_n_s_VisionIpcClient___reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_VisionIpcClient___setstate_cytho); + Py_CLEAR(clear_module_state->__pyx_n_s_VisionIpcClient_available_stream); + Py_CLEAR(clear_module_state->__pyx_n_s_VisionIpcClient_connect); + Py_CLEAR(clear_module_state->__pyx_n_s_VisionIpcClient_is_connected); + Py_CLEAR(clear_module_state->__pyx_n_s_VisionIpcClient_recv); + Py_CLEAR(clear_module_state->__pyx_n_s_VisionIpcServer); + Py_CLEAR(clear_module_state->__pyx_n_s_VisionIpcServer___reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_VisionIpcServer___setstate_cytho); + Py_CLEAR(clear_module_state->__pyx_n_s_VisionIpcServer_create_buffers); + Py_CLEAR(clear_module_state->__pyx_n_s_VisionIpcServer_create_buffers_w); + Py_CLEAR(clear_module_state->__pyx_n_s_VisionIpcServer_send); + Py_CLEAR(clear_module_state->__pyx_n_s_VisionIpcServer_start_listener); + Py_CLEAR(clear_module_state->__pyx_n_s_VisionStreamType); + Py_CLEAR(clear_module_state->__pyx_kp_b__11); + Py_CLEAR(clear_module_state->__pyx_kp_b__12); + Py_CLEAR(clear_module_state->__pyx_kp_b__13); + Py_CLEAR(clear_module_state->__pyx_kp_u__14); + Py_CLEAR(clear_module_state->__pyx_kp_u__15); + Py_CLEAR(clear_module_state->__pyx_kp_u__3); + Py_CLEAR(clear_module_state->__pyx_kp_u__4); + Py_CLEAR(clear_module_state->__pyx_n_s__5); + Py_CLEAR(clear_module_state->__pyx_n_s__67); + Py_CLEAR(clear_module_state->__pyx_kp_u__8); + Py_CLEAR(clear_module_state->__pyx_kp_u__9); + Py_CLEAR(clear_module_state->__pyx_n_s_abc); + Py_CLEAR(clear_module_state->__pyx_n_s_allocate_buffer); + Py_CLEAR(clear_module_state->__pyx_kp_u_and); + Py_CLEAR(clear_module_state->__pyx_n_s_asarray); + Py_CLEAR(clear_module_state->__pyx_n_s_asyncio_coroutines); + Py_CLEAR(clear_module_state->__pyx_n_s_available_streams); + Py_CLEAR(clear_module_state->__pyx_n_s_base); + Py_CLEAR(clear_module_state->__pyx_n_s_block); + Py_CLEAR(clear_module_state->__pyx_n_s_blocking); + Py_CLEAR(clear_module_state->__pyx_n_s_buf); + Py_CLEAR(clear_module_state->__pyx_n_s_c); + Py_CLEAR(clear_module_state->__pyx_n_u_c); + Py_CLEAR(clear_module_state->__pyx_kp_s_cereal_visionipc_visionipc_pyx); + Py_CLEAR(clear_module_state->__pyx_kp_s_cereal_visionipc_visionipc_pyx_p); + Py_CLEAR(clear_module_state->__pyx_n_s_class); + Py_CLEAR(clear_module_state->__pyx_n_s_class_getitem); + Py_CLEAR(clear_module_state->__pyx_n_s_cline_in_traceback); + Py_CLEAR(clear_module_state->__pyx_n_s_cls); + Py_CLEAR(clear_module_state->__pyx_n_s_collections); + Py_CLEAR(clear_module_state->__pyx_kp_s_collections_abc); + Py_CLEAR(clear_module_state->__pyx_n_s_conflate); + Py_CLEAR(clear_module_state->__pyx_n_s_connect); + Py_CLEAR(clear_module_state->__pyx_n_s_context); + Py_CLEAR(clear_module_state->__pyx_kp_s_contiguous_and_direct); + Py_CLEAR(clear_module_state->__pyx_kp_s_contiguous_and_indirect); + Py_CLEAR(clear_module_state->__pyx_n_s_count); + Py_CLEAR(clear_module_state->__pyx_n_s_create_buffers); + Py_CLEAR(clear_module_state->__pyx_n_s_create_buffers_with_sizes); + Py_CLEAR(clear_module_state->__pyx_n_s_data); + Py_CLEAR(clear_module_state->__pyx_n_s_dct); + Py_CLEAR(clear_module_state->__pyx_n_s_dict); + Py_CLEAR(clear_module_state->__pyx_n_s_dict_2); + Py_CLEAR(clear_module_state->__pyx_kp_u_disable); + Py_CLEAR(clear_module_state->__pyx_n_s_doc); + Py_CLEAR(clear_module_state->__pyx_n_s_dtype_is_object); + Py_CLEAR(clear_module_state->__pyx_kp_u_enable); + Py_CLEAR(clear_module_state->__pyx_n_s_encode); + Py_CLEAR(clear_module_state->__pyx_n_s_enum); + Py_CLEAR(clear_module_state->__pyx_n_s_enumerate); + Py_CLEAR(clear_module_state->__pyx_n_s_error); + Py_CLEAR(clear_module_state->__pyx_n_s_extra); + Py_CLEAR(clear_module_state->__pyx_n_s_flags); + Py_CLEAR(clear_module_state->__pyx_n_s_format); + Py_CLEAR(clear_module_state->__pyx_n_s_fortran); + Py_CLEAR(clear_module_state->__pyx_n_u_fortran); + Py_CLEAR(clear_module_state->__pyx_n_s_frame_id); + Py_CLEAR(clear_module_state->__pyx_kp_u_gc); + Py_CLEAR(clear_module_state->__pyx_n_s_get); + Py_CLEAR(clear_module_state->__pyx_n_s_get_endpoint_name); + Py_CLEAR(clear_module_state->__pyx_n_s_getstate); + Py_CLEAR(clear_module_state->__pyx_kp_u_got); + Py_CLEAR(clear_module_state->__pyx_kp_u_got_differing_extents_in_dimensi); + Py_CLEAR(clear_module_state->__pyx_n_s_height); + Py_CLEAR(clear_module_state->__pyx_n_s_id); + Py_CLEAR(clear_module_state->__pyx_n_s_import); + Py_CLEAR(clear_module_state->__pyx_n_s_index); + Py_CLEAR(clear_module_state->__pyx_n_s_init); + Py_CLEAR(clear_module_state->__pyx_n_s_init_subclass); + Py_CLEAR(clear_module_state->__pyx_n_s_initializing); + Py_CLEAR(clear_module_state->__pyx_n_s_is_connected); + Py_CLEAR(clear_module_state->__pyx_n_s_is_coroutine); + Py_CLEAR(clear_module_state->__pyx_kp_u_isenabled); + Py_CLEAR(clear_module_state->__pyx_n_s_itemsize); + Py_CLEAR(clear_module_state->__pyx_kp_s_itemsize_0_for_cython_array); + Py_CLEAR(clear_module_state->__pyx_n_s_join); + Py_CLEAR(clear_module_state->__pyx_n_s_main); + Py_CLEAR(clear_module_state->__pyx_n_s_member_names); + Py_CLEAR(clear_module_state->__pyx_n_s_members); + Py_CLEAR(clear_module_state->__pyx_n_s_memview); + Py_CLEAR(clear_module_state->__pyx_n_s_metaclass); + Py_CLEAR(clear_module_state->__pyx_n_s_mode); + Py_CLEAR(clear_module_state->__pyx_n_s_module); + Py_CLEAR(clear_module_state->__pyx_n_s_module_2); + Py_CLEAR(clear_module_state->__pyx_n_s_mro_entries); + Py_CLEAR(clear_module_state->__pyx_n_s_name); + Py_CLEAR(clear_module_state->__pyx_n_s_name_2); + Py_CLEAR(clear_module_state->__pyx_n_s_ndim); + Py_CLEAR(clear_module_state->__pyx_n_s_new); + Py_CLEAR(clear_module_state->__pyx_kp_s_no_default___reduce___due_to_non); + Py_CLEAR(clear_module_state->__pyx_n_s_np); + Py_CLEAR(clear_module_state->__pyx_n_s_num_buffers); + Py_CLEAR(clear_module_state->__pyx_n_s_numpy); + Py_CLEAR(clear_module_state->__pyx_kp_u_numpy_core_multiarray_failed_to); + Py_CLEAR(clear_module_state->__pyx_kp_u_numpy_core_umath_failed_to_impor); + Py_CLEAR(clear_module_state->__pyx_n_s_obj); + Py_CLEAR(clear_module_state->__pyx_n_s_pack); + Py_CLEAR(clear_module_state->__pyx_n_s_parents); + Py_CLEAR(clear_module_state->__pyx_n_s_pickle); + Py_CLEAR(clear_module_state->__pyx_n_s_prepare); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_PickleError); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_checksum); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_result); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_state); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_type); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_unpickle_Enum); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_unpickle___Pyx_EnumMeta); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_vtable); + Py_CLEAR(clear_module_state->__pyx_n_s_qualname); + Py_CLEAR(clear_module_state->__pyx_n_s_range); + Py_CLEAR(clear_module_state->__pyx_n_s_recv); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_ex); + Py_CLEAR(clear_module_state->__pyx_n_s_register); + Py_CLEAR(clear_module_state->__pyx_n_s_repr); + Py_CLEAR(clear_module_state->__pyx_n_s_res); + Py_CLEAR(clear_module_state->__pyx_n_s_rgb); + Py_CLEAR(clear_module_state->__pyx_kp_s_s_s); + Py_CLEAR(clear_module_state->__pyx_kp_s_s_s_d); + Py_CLEAR(clear_module_state->__pyx_n_s_self); + Py_CLEAR(clear_module_state->__pyx_kp_s_self_buf_cannot_be_converted_to); + Py_CLEAR(clear_module_state->__pyx_kp_s_self_server_cannot_be_converted); + Py_CLEAR(clear_module_state->__pyx_n_s_send); + Py_CLEAR(clear_module_state->__pyx_n_s_set_name); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_shape); + Py_CLEAR(clear_module_state->__pyx_n_s_size); + Py_CLEAR(clear_module_state->__pyx_n_s_spec); + Py_CLEAR(clear_module_state->__pyx_n_s_start); + Py_CLEAR(clear_module_state->__pyx_n_s_start_listener); + Py_CLEAR(clear_module_state->__pyx_n_s_state); + Py_CLEAR(clear_module_state->__pyx_n_s_staticmethod); + Py_CLEAR(clear_module_state->__pyx_n_s_step); + Py_CLEAR(clear_module_state->__pyx_n_s_stop); + Py_CLEAR(clear_module_state->__pyx_n_s_str); + Py_CLEAR(clear_module_state->__pyx_n_s_stream); + Py_CLEAR(clear_module_state->__pyx_n_s_stride); + Py_CLEAR(clear_module_state->__pyx_kp_s_strided_and_direct); + Py_CLEAR(clear_module_state->__pyx_kp_s_strided_and_direct_or_indirect); + Py_CLEAR(clear_module_state->__pyx_kp_s_strided_and_indirect); + Py_CLEAR(clear_module_state->__pyx_kp_s_stringsource); + Py_CLEAR(clear_module_state->__pyx_n_s_struct); + Py_CLEAR(clear_module_state->__pyx_n_s_super); + Py_CLEAR(clear_module_state->__pyx_n_s_sys); + Py_CLEAR(clear_module_state->__pyx_n_s_test); + Py_CLEAR(clear_module_state->__pyx_n_s_timeout_ms); + Py_CLEAR(clear_module_state->__pyx_n_s_timestamp_eof); + Py_CLEAR(clear_module_state->__pyx_n_s_timestamp_sof); + Py_CLEAR(clear_module_state->__pyx_n_s_tp); + Py_CLEAR(clear_module_state->__pyx_kp_s_unable_to_allocate_array_data); + Py_CLEAR(clear_module_state->__pyx_kp_s_unable_to_allocate_shape_and_str); + Py_CLEAR(clear_module_state->__pyx_n_s_unpack); + Py_CLEAR(clear_module_state->__pyx_n_s_update); + Py_CLEAR(clear_module_state->__pyx_n_s_use_setstate); + Py_CLEAR(clear_module_state->__pyx_n_s_uv_offset); + Py_CLEAR(clear_module_state->__pyx_n_s_v); + Py_CLEAR(clear_module_state->__pyx_n_s_value); + Py_CLEAR(clear_module_state->__pyx_n_s_values); + Py_CLEAR(clear_module_state->__pyx_n_s_version_info); + Py_CLEAR(clear_module_state->__pyx_n_s_width); + Py_CLEAR(clear_module_state->__pyx_int_0); + Py_CLEAR(clear_module_state->__pyx_int_1); + Py_CLEAR(clear_module_state->__pyx_int_3); + Py_CLEAR(clear_module_state->__pyx_int_100); + Py_CLEAR(clear_module_state->__pyx_int_112105877); + Py_CLEAR(clear_module_state->__pyx_int_136983863); + Py_CLEAR(clear_module_state->__pyx_int_184977713); + Py_CLEAR(clear_module_state->__pyx_int_222419149); + Py_CLEAR(clear_module_state->__pyx_int_228825662); + Py_CLEAR(clear_module_state->__pyx_int_238750788); + Py_CLEAR(clear_module_state->__pyx_int_neg_1); + Py_CLEAR(clear_module_state->__pyx_slice__7); + Py_CLEAR(clear_module_state->__pyx_tuple__2); + Py_CLEAR(clear_module_state->__pyx_tuple__6); + Py_CLEAR(clear_module_state->__pyx_tuple__10); + Py_CLEAR(clear_module_state->__pyx_tuple__16); + Py_CLEAR(clear_module_state->__pyx_tuple__17); + Py_CLEAR(clear_module_state->__pyx_tuple__18); + Py_CLEAR(clear_module_state->__pyx_tuple__20); + Py_CLEAR(clear_module_state->__pyx_tuple__22); + Py_CLEAR(clear_module_state->__pyx_tuple__24); + Py_CLEAR(clear_module_state->__pyx_tuple__25); + Py_CLEAR(clear_module_state->__pyx_tuple__31); + Py_CLEAR(clear_module_state->__pyx_tuple__33); + Py_CLEAR(clear_module_state->__pyx_tuple__34); + Py_CLEAR(clear_module_state->__pyx_tuple__35); + Py_CLEAR(clear_module_state->__pyx_tuple__36); + Py_CLEAR(clear_module_state->__pyx_tuple__37); + Py_CLEAR(clear_module_state->__pyx_tuple__38); + Py_CLEAR(clear_module_state->__pyx_tuple__39); + Py_CLEAR(clear_module_state->__pyx_tuple__40); + Py_CLEAR(clear_module_state->__pyx_tuple__41); + Py_CLEAR(clear_module_state->__pyx_tuple__43); + Py_CLEAR(clear_module_state->__pyx_tuple__47); + Py_CLEAR(clear_module_state->__pyx_tuple__49); + Py_CLEAR(clear_module_state->__pyx_tuple__51); + Py_CLEAR(clear_module_state->__pyx_tuple__53); + Py_CLEAR(clear_module_state->__pyx_tuple__57); + Py_CLEAR(clear_module_state->__pyx_tuple__59); + Py_CLEAR(clear_module_state->__pyx_tuple__60); + Py_CLEAR(clear_module_state->__pyx_tuple__63); + Py_CLEAR(clear_module_state->__pyx_codeobj__19); + Py_CLEAR(clear_module_state->__pyx_codeobj__21); + Py_CLEAR(clear_module_state->__pyx_codeobj__23); + Py_CLEAR(clear_module_state->__pyx_codeobj__26); + Py_CLEAR(clear_module_state->__pyx_codeobj__27); + Py_CLEAR(clear_module_state->__pyx_codeobj__28); + Py_CLEAR(clear_module_state->__pyx_codeobj__29); + Py_CLEAR(clear_module_state->__pyx_codeobj__30); + Py_CLEAR(clear_module_state->__pyx_codeobj__32); + Py_CLEAR(clear_module_state->__pyx_codeobj__42); + Py_CLEAR(clear_module_state->__pyx_codeobj__44); + Py_CLEAR(clear_module_state->__pyx_codeobj__45); + Py_CLEAR(clear_module_state->__pyx_codeobj__46); + Py_CLEAR(clear_module_state->__pyx_codeobj__48); + Py_CLEAR(clear_module_state->__pyx_codeobj__50); + Py_CLEAR(clear_module_state->__pyx_codeobj__52); + Py_CLEAR(clear_module_state->__pyx_codeobj__54); + Py_CLEAR(clear_module_state->__pyx_codeobj__55); + Py_CLEAR(clear_module_state->__pyx_codeobj__56); + Py_CLEAR(clear_module_state->__pyx_codeobj__58); + Py_CLEAR(clear_module_state->__pyx_codeobj__61); + Py_CLEAR(clear_module_state->__pyx_codeobj__62); + Py_CLEAR(clear_module_state->__pyx_codeobj__64); + Py_CLEAR(clear_module_state->__pyx_codeobj__65); + Py_CLEAR(clear_module_state->__pyx_codeobj__66); + return 0; +} +#endif +/* #### Code section: module_state_traverse ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { + __pyx_mstate *traverse_module_state = __pyx_mstate(m); + if (!traverse_module_state) return 0; + Py_VISIT(traverse_module_state->__pyx_d); + Py_VISIT(traverse_module_state->__pyx_b); + Py_VISIT(traverse_module_state->__pyx_cython_runtime); + Py_VISIT(traverse_module_state->__pyx_empty_tuple); + Py_VISIT(traverse_module_state->__pyx_empty_bytes); + Py_VISIT(traverse_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_VISIT(traverse_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_VISIT(traverse_module_state->__pyx_FusedFunctionType); + #endif + Py_VISIT(traverse_module_state->__pyx_ptype_7cpython_4type_type); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_dtype); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_flatiter); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_broadcast); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_ndarray); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_generic); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_number); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_integer); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_signedinteger); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_unsignedinteger); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_inexact); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_floating); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_complexfloating); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_flexible); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_character); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_ufunc); + Py_VISIT(traverse_module_state->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext); + Py_VISIT(traverse_module_state->__pyx_type_6cereal_9visionipc_13visionipc_pyx_CLContext); + Py_VISIT(traverse_module_state->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf); + Py_VISIT(traverse_module_state->__pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionBuf); + Py_VISIT(traverse_module_state->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer); + Py_VISIT(traverse_module_state->__pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer); + Py_VISIT(traverse_module_state->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient); + Py_VISIT(traverse_module_state->__pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient); + Py_VISIT(traverse_module_state->__pyx_ptype___Pyx_EnumMeta); + Py_VISIT(traverse_module_state->__Pyx_EnumMeta); + Py_VISIT(traverse_module_state->__pyx_array_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_array); + Py_VISIT(traverse_module_state->__pyx_MemviewEnum_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_MemviewEnum); + Py_VISIT(traverse_module_state->__pyx_memoryview_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_memoryview); + Py_VISIT(traverse_module_state->__pyx_memoryviewslice_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_memoryviewslice); + Py_VISIT(traverse_module_state->__pyx_kp_b_); + Py_VISIT(traverse_module_state->__pyx_kp_s_); + Py_VISIT(traverse_module_state->__pyx_n_s_ASCII); + Py_VISIT(traverse_module_state->__pyx_kp_s_All_dimensions_preceding_dimensi); + Py_VISIT(traverse_module_state->__pyx_n_s_AssertionError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Buffer_view_does_not_expose_stri); + Py_VISIT(traverse_module_state->__pyx_n_s_CLContext); + Py_VISIT(traverse_module_state->__pyx_kp_s_Can_only_create_a_buffer_that_is); + Py_VISIT(traverse_module_state->__pyx_kp_s_Cannot_assign_to_read_only_memor); + Py_VISIT(traverse_module_state->__pyx_kp_s_Cannot_create_writable_memory_vi); + Py_VISIT(traverse_module_state->__pyx_kp_u_Cannot_index_with_type); + Py_VISIT(traverse_module_state->__pyx_kp_s_Cannot_transpose_memoryview_with); + Py_VISIT(traverse_module_state->__pyx_kp_s_Dimension_d_is_not_direct); + Py_VISIT(traverse_module_state->__pyx_n_s_Ellipsis); + Py_VISIT(traverse_module_state->__pyx_kp_s_Empty_shape_tuple_for_cython_arr); + Py_VISIT(traverse_module_state->__pyx_n_s_EnumBase); + Py_VISIT(traverse_module_state->__pyx_n_s_EnumType); + Py_VISIT(traverse_module_state->__pyx_n_s_ImportError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0); + Py_VISIT(traverse_module_state->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0_2); + Py_VISIT(traverse_module_state->__pyx_n_s_IndexError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Index_out_of_bounds_axis_d); + Py_VISIT(traverse_module_state->__pyx_kp_s_Indirect_dimensions_not_supporte); + Py_VISIT(traverse_module_state->__pyx_n_s_IntEnum); + Py_VISIT(traverse_module_state->__pyx_n_s_IntFlag); + Py_VISIT(traverse_module_state->__pyx_kp_u_Invalid_mode_expected_c_or_fortr); + Py_VISIT(traverse_module_state->__pyx_kp_u_Invalid_shape_in_axis); + Py_VISIT(traverse_module_state->__pyx_n_s_MemoryError); + Py_VISIT(traverse_module_state->__pyx_kp_s_MemoryView_of_r_at_0x_x); + Py_VISIT(traverse_module_state->__pyx_kp_s_MemoryView_of_r_object); + Py_VISIT(traverse_module_state->__pyx_n_b_O); + Py_VISIT(traverse_module_state->__pyx_n_s_OrderedDict); + Py_VISIT(traverse_module_state->__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + Py_VISIT(traverse_module_state->__pyx_n_s_PickleError); + Py_VISIT(traverse_module_state->__pyx_n_s_Pyx_EnumBase); + Py_VISIT(traverse_module_state->__pyx_n_s_Pyx_EnumBase___new); + Py_VISIT(traverse_module_state->__pyx_n_s_Pyx_EnumBase___repr); + Py_VISIT(traverse_module_state->__pyx_n_s_Pyx_EnumBase___str); + Py_VISIT(traverse_module_state->__pyx_n_s_Pyx_EnumMeta___reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_Pyx_EnumMeta___setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_Pyx_FlagBase); + Py_VISIT(traverse_module_state->__pyx_n_s_Pyx_FlagBase___new); + Py_VISIT(traverse_module_state->__pyx_n_s_Pyx_FlagBase___repr); + Py_VISIT(traverse_module_state->__pyx_n_s_Pyx_FlagBase___str); + Py_VISIT(traverse_module_state->__pyx_n_s_Sequence); + Py_VISIT(traverse_module_state->__pyx_kp_s_Step_may_not_be_zero_axis_d); + Py_VISIT(traverse_module_state->__pyx_kp_b_T); + Py_VISIT(traverse_module_state->__pyx_n_s_TypeError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Unable_to_convert_item_to_object); + Py_VISIT(traverse_module_state->__pyx_kp_s_Unknown_enum_value_s); + Py_VISIT(traverse_module_state->__pyx_n_s_VISION_STREAM_DRIVER); + Py_VISIT(traverse_module_state->__pyx_n_s_VISION_STREAM_MAP); + Py_VISIT(traverse_module_state->__pyx_n_s_VISION_STREAM_ROAD); + Py_VISIT(traverse_module_state->__pyx_n_s_VISION_STREAM_WIDE_ROAD); + Py_VISIT(traverse_module_state->__pyx_n_s_ValueError); + Py_VISIT(traverse_module_state->__pyx_n_s_View_MemoryView); + Py_VISIT(traverse_module_state->__pyx_n_s_VisionBuf); + Py_VISIT(traverse_module_state->__pyx_n_s_VisionBuf___reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_VisionBuf___setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_VisionIpcClient); + Py_VISIT(traverse_module_state->__pyx_n_s_VisionIpcClient___reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_VisionIpcClient___setstate_cytho); + Py_VISIT(traverse_module_state->__pyx_n_s_VisionIpcClient_available_stream); + Py_VISIT(traverse_module_state->__pyx_n_s_VisionIpcClient_connect); + Py_VISIT(traverse_module_state->__pyx_n_s_VisionIpcClient_is_connected); + Py_VISIT(traverse_module_state->__pyx_n_s_VisionIpcClient_recv); + Py_VISIT(traverse_module_state->__pyx_n_s_VisionIpcServer); + Py_VISIT(traverse_module_state->__pyx_n_s_VisionIpcServer___reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_VisionIpcServer___setstate_cytho); + Py_VISIT(traverse_module_state->__pyx_n_s_VisionIpcServer_create_buffers); + Py_VISIT(traverse_module_state->__pyx_n_s_VisionIpcServer_create_buffers_w); + Py_VISIT(traverse_module_state->__pyx_n_s_VisionIpcServer_send); + Py_VISIT(traverse_module_state->__pyx_n_s_VisionIpcServer_start_listener); + Py_VISIT(traverse_module_state->__pyx_n_s_VisionStreamType); + Py_VISIT(traverse_module_state->__pyx_kp_b__11); + Py_VISIT(traverse_module_state->__pyx_kp_b__12); + Py_VISIT(traverse_module_state->__pyx_kp_b__13); + Py_VISIT(traverse_module_state->__pyx_kp_u__14); + Py_VISIT(traverse_module_state->__pyx_kp_u__15); + Py_VISIT(traverse_module_state->__pyx_kp_u__3); + Py_VISIT(traverse_module_state->__pyx_kp_u__4); + Py_VISIT(traverse_module_state->__pyx_n_s__5); + Py_VISIT(traverse_module_state->__pyx_n_s__67); + Py_VISIT(traverse_module_state->__pyx_kp_u__8); + Py_VISIT(traverse_module_state->__pyx_kp_u__9); + Py_VISIT(traverse_module_state->__pyx_n_s_abc); + Py_VISIT(traverse_module_state->__pyx_n_s_allocate_buffer); + Py_VISIT(traverse_module_state->__pyx_kp_u_and); + Py_VISIT(traverse_module_state->__pyx_n_s_asarray); + Py_VISIT(traverse_module_state->__pyx_n_s_asyncio_coroutines); + Py_VISIT(traverse_module_state->__pyx_n_s_available_streams); + Py_VISIT(traverse_module_state->__pyx_n_s_base); + Py_VISIT(traverse_module_state->__pyx_n_s_block); + Py_VISIT(traverse_module_state->__pyx_n_s_blocking); + Py_VISIT(traverse_module_state->__pyx_n_s_buf); + Py_VISIT(traverse_module_state->__pyx_n_s_c); + Py_VISIT(traverse_module_state->__pyx_n_u_c); + Py_VISIT(traverse_module_state->__pyx_kp_s_cereal_visionipc_visionipc_pyx); + Py_VISIT(traverse_module_state->__pyx_kp_s_cereal_visionipc_visionipc_pyx_p); + Py_VISIT(traverse_module_state->__pyx_n_s_class); + Py_VISIT(traverse_module_state->__pyx_n_s_class_getitem); + Py_VISIT(traverse_module_state->__pyx_n_s_cline_in_traceback); + Py_VISIT(traverse_module_state->__pyx_n_s_cls); + Py_VISIT(traverse_module_state->__pyx_n_s_collections); + Py_VISIT(traverse_module_state->__pyx_kp_s_collections_abc); + Py_VISIT(traverse_module_state->__pyx_n_s_conflate); + Py_VISIT(traverse_module_state->__pyx_n_s_connect); + Py_VISIT(traverse_module_state->__pyx_n_s_context); + Py_VISIT(traverse_module_state->__pyx_kp_s_contiguous_and_direct); + Py_VISIT(traverse_module_state->__pyx_kp_s_contiguous_and_indirect); + Py_VISIT(traverse_module_state->__pyx_n_s_count); + Py_VISIT(traverse_module_state->__pyx_n_s_create_buffers); + Py_VISIT(traverse_module_state->__pyx_n_s_create_buffers_with_sizes); + Py_VISIT(traverse_module_state->__pyx_n_s_data); + Py_VISIT(traverse_module_state->__pyx_n_s_dct); + Py_VISIT(traverse_module_state->__pyx_n_s_dict); + Py_VISIT(traverse_module_state->__pyx_n_s_dict_2); + Py_VISIT(traverse_module_state->__pyx_kp_u_disable); + Py_VISIT(traverse_module_state->__pyx_n_s_doc); + Py_VISIT(traverse_module_state->__pyx_n_s_dtype_is_object); + Py_VISIT(traverse_module_state->__pyx_kp_u_enable); + Py_VISIT(traverse_module_state->__pyx_n_s_encode); + Py_VISIT(traverse_module_state->__pyx_n_s_enum); + Py_VISIT(traverse_module_state->__pyx_n_s_enumerate); + Py_VISIT(traverse_module_state->__pyx_n_s_error); + Py_VISIT(traverse_module_state->__pyx_n_s_extra); + Py_VISIT(traverse_module_state->__pyx_n_s_flags); + Py_VISIT(traverse_module_state->__pyx_n_s_format); + Py_VISIT(traverse_module_state->__pyx_n_s_fortran); + Py_VISIT(traverse_module_state->__pyx_n_u_fortran); + Py_VISIT(traverse_module_state->__pyx_n_s_frame_id); + Py_VISIT(traverse_module_state->__pyx_kp_u_gc); + Py_VISIT(traverse_module_state->__pyx_n_s_get); + Py_VISIT(traverse_module_state->__pyx_n_s_get_endpoint_name); + Py_VISIT(traverse_module_state->__pyx_n_s_getstate); + Py_VISIT(traverse_module_state->__pyx_kp_u_got); + Py_VISIT(traverse_module_state->__pyx_kp_u_got_differing_extents_in_dimensi); + Py_VISIT(traverse_module_state->__pyx_n_s_height); + Py_VISIT(traverse_module_state->__pyx_n_s_id); + Py_VISIT(traverse_module_state->__pyx_n_s_import); + Py_VISIT(traverse_module_state->__pyx_n_s_index); + Py_VISIT(traverse_module_state->__pyx_n_s_init); + Py_VISIT(traverse_module_state->__pyx_n_s_init_subclass); + Py_VISIT(traverse_module_state->__pyx_n_s_initializing); + Py_VISIT(traverse_module_state->__pyx_n_s_is_connected); + Py_VISIT(traverse_module_state->__pyx_n_s_is_coroutine); + Py_VISIT(traverse_module_state->__pyx_kp_u_isenabled); + Py_VISIT(traverse_module_state->__pyx_n_s_itemsize); + Py_VISIT(traverse_module_state->__pyx_kp_s_itemsize_0_for_cython_array); + Py_VISIT(traverse_module_state->__pyx_n_s_join); + Py_VISIT(traverse_module_state->__pyx_n_s_main); + Py_VISIT(traverse_module_state->__pyx_n_s_member_names); + Py_VISIT(traverse_module_state->__pyx_n_s_members); + Py_VISIT(traverse_module_state->__pyx_n_s_memview); + Py_VISIT(traverse_module_state->__pyx_n_s_metaclass); + Py_VISIT(traverse_module_state->__pyx_n_s_mode); + Py_VISIT(traverse_module_state->__pyx_n_s_module); + Py_VISIT(traverse_module_state->__pyx_n_s_module_2); + Py_VISIT(traverse_module_state->__pyx_n_s_mro_entries); + Py_VISIT(traverse_module_state->__pyx_n_s_name); + Py_VISIT(traverse_module_state->__pyx_n_s_name_2); + Py_VISIT(traverse_module_state->__pyx_n_s_ndim); + Py_VISIT(traverse_module_state->__pyx_n_s_new); + Py_VISIT(traverse_module_state->__pyx_kp_s_no_default___reduce___due_to_non); + Py_VISIT(traverse_module_state->__pyx_n_s_np); + Py_VISIT(traverse_module_state->__pyx_n_s_num_buffers); + Py_VISIT(traverse_module_state->__pyx_n_s_numpy); + Py_VISIT(traverse_module_state->__pyx_kp_u_numpy_core_multiarray_failed_to); + Py_VISIT(traverse_module_state->__pyx_kp_u_numpy_core_umath_failed_to_impor); + Py_VISIT(traverse_module_state->__pyx_n_s_obj); + Py_VISIT(traverse_module_state->__pyx_n_s_pack); + Py_VISIT(traverse_module_state->__pyx_n_s_parents); + Py_VISIT(traverse_module_state->__pyx_n_s_pickle); + Py_VISIT(traverse_module_state->__pyx_n_s_prepare); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_PickleError); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_checksum); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_result); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_state); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_type); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_unpickle_Enum); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_unpickle___Pyx_EnumMeta); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_vtable); + Py_VISIT(traverse_module_state->__pyx_n_s_qualname); + Py_VISIT(traverse_module_state->__pyx_n_s_range); + Py_VISIT(traverse_module_state->__pyx_n_s_recv); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_ex); + Py_VISIT(traverse_module_state->__pyx_n_s_register); + Py_VISIT(traverse_module_state->__pyx_n_s_repr); + Py_VISIT(traverse_module_state->__pyx_n_s_res); + Py_VISIT(traverse_module_state->__pyx_n_s_rgb); + Py_VISIT(traverse_module_state->__pyx_kp_s_s_s); + Py_VISIT(traverse_module_state->__pyx_kp_s_s_s_d); + Py_VISIT(traverse_module_state->__pyx_n_s_self); + Py_VISIT(traverse_module_state->__pyx_kp_s_self_buf_cannot_be_converted_to); + Py_VISIT(traverse_module_state->__pyx_kp_s_self_server_cannot_be_converted); + Py_VISIT(traverse_module_state->__pyx_n_s_send); + Py_VISIT(traverse_module_state->__pyx_n_s_set_name); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_shape); + Py_VISIT(traverse_module_state->__pyx_n_s_size); + Py_VISIT(traverse_module_state->__pyx_n_s_spec); + Py_VISIT(traverse_module_state->__pyx_n_s_start); + Py_VISIT(traverse_module_state->__pyx_n_s_start_listener); + Py_VISIT(traverse_module_state->__pyx_n_s_state); + Py_VISIT(traverse_module_state->__pyx_n_s_staticmethod); + Py_VISIT(traverse_module_state->__pyx_n_s_step); + Py_VISIT(traverse_module_state->__pyx_n_s_stop); + Py_VISIT(traverse_module_state->__pyx_n_s_str); + Py_VISIT(traverse_module_state->__pyx_n_s_stream); + Py_VISIT(traverse_module_state->__pyx_n_s_stride); + Py_VISIT(traverse_module_state->__pyx_kp_s_strided_and_direct); + Py_VISIT(traverse_module_state->__pyx_kp_s_strided_and_direct_or_indirect); + Py_VISIT(traverse_module_state->__pyx_kp_s_strided_and_indirect); + Py_VISIT(traverse_module_state->__pyx_kp_s_stringsource); + Py_VISIT(traverse_module_state->__pyx_n_s_struct); + Py_VISIT(traverse_module_state->__pyx_n_s_super); + Py_VISIT(traverse_module_state->__pyx_n_s_sys); + Py_VISIT(traverse_module_state->__pyx_n_s_test); + Py_VISIT(traverse_module_state->__pyx_n_s_timeout_ms); + Py_VISIT(traverse_module_state->__pyx_n_s_timestamp_eof); + Py_VISIT(traverse_module_state->__pyx_n_s_timestamp_sof); + Py_VISIT(traverse_module_state->__pyx_n_s_tp); + Py_VISIT(traverse_module_state->__pyx_kp_s_unable_to_allocate_array_data); + Py_VISIT(traverse_module_state->__pyx_kp_s_unable_to_allocate_shape_and_str); + Py_VISIT(traverse_module_state->__pyx_n_s_unpack); + Py_VISIT(traverse_module_state->__pyx_n_s_update); + Py_VISIT(traverse_module_state->__pyx_n_s_use_setstate); + Py_VISIT(traverse_module_state->__pyx_n_s_uv_offset); + Py_VISIT(traverse_module_state->__pyx_n_s_v); + Py_VISIT(traverse_module_state->__pyx_n_s_value); + Py_VISIT(traverse_module_state->__pyx_n_s_values); + Py_VISIT(traverse_module_state->__pyx_n_s_version_info); + Py_VISIT(traverse_module_state->__pyx_n_s_width); + Py_VISIT(traverse_module_state->__pyx_int_0); + Py_VISIT(traverse_module_state->__pyx_int_1); + Py_VISIT(traverse_module_state->__pyx_int_3); + Py_VISIT(traverse_module_state->__pyx_int_100); + Py_VISIT(traverse_module_state->__pyx_int_112105877); + Py_VISIT(traverse_module_state->__pyx_int_136983863); + Py_VISIT(traverse_module_state->__pyx_int_184977713); + Py_VISIT(traverse_module_state->__pyx_int_222419149); + Py_VISIT(traverse_module_state->__pyx_int_228825662); + Py_VISIT(traverse_module_state->__pyx_int_238750788); + Py_VISIT(traverse_module_state->__pyx_int_neg_1); + Py_VISIT(traverse_module_state->__pyx_slice__7); + Py_VISIT(traverse_module_state->__pyx_tuple__2); + Py_VISIT(traverse_module_state->__pyx_tuple__6); + Py_VISIT(traverse_module_state->__pyx_tuple__10); + Py_VISIT(traverse_module_state->__pyx_tuple__16); + Py_VISIT(traverse_module_state->__pyx_tuple__17); + Py_VISIT(traverse_module_state->__pyx_tuple__18); + Py_VISIT(traverse_module_state->__pyx_tuple__20); + Py_VISIT(traverse_module_state->__pyx_tuple__22); + Py_VISIT(traverse_module_state->__pyx_tuple__24); + Py_VISIT(traverse_module_state->__pyx_tuple__25); + Py_VISIT(traverse_module_state->__pyx_tuple__31); + Py_VISIT(traverse_module_state->__pyx_tuple__33); + Py_VISIT(traverse_module_state->__pyx_tuple__34); + Py_VISIT(traverse_module_state->__pyx_tuple__35); + Py_VISIT(traverse_module_state->__pyx_tuple__36); + Py_VISIT(traverse_module_state->__pyx_tuple__37); + Py_VISIT(traverse_module_state->__pyx_tuple__38); + Py_VISIT(traverse_module_state->__pyx_tuple__39); + Py_VISIT(traverse_module_state->__pyx_tuple__40); + Py_VISIT(traverse_module_state->__pyx_tuple__41); + Py_VISIT(traverse_module_state->__pyx_tuple__43); + Py_VISIT(traverse_module_state->__pyx_tuple__47); + Py_VISIT(traverse_module_state->__pyx_tuple__49); + Py_VISIT(traverse_module_state->__pyx_tuple__51); + Py_VISIT(traverse_module_state->__pyx_tuple__53); + Py_VISIT(traverse_module_state->__pyx_tuple__57); + Py_VISIT(traverse_module_state->__pyx_tuple__59); + Py_VISIT(traverse_module_state->__pyx_tuple__60); + Py_VISIT(traverse_module_state->__pyx_tuple__63); + Py_VISIT(traverse_module_state->__pyx_codeobj__19); + Py_VISIT(traverse_module_state->__pyx_codeobj__21); + Py_VISIT(traverse_module_state->__pyx_codeobj__23); + Py_VISIT(traverse_module_state->__pyx_codeobj__26); + Py_VISIT(traverse_module_state->__pyx_codeobj__27); + Py_VISIT(traverse_module_state->__pyx_codeobj__28); + Py_VISIT(traverse_module_state->__pyx_codeobj__29); + Py_VISIT(traverse_module_state->__pyx_codeobj__30); + Py_VISIT(traverse_module_state->__pyx_codeobj__32); + Py_VISIT(traverse_module_state->__pyx_codeobj__42); + Py_VISIT(traverse_module_state->__pyx_codeobj__44); + Py_VISIT(traverse_module_state->__pyx_codeobj__45); + Py_VISIT(traverse_module_state->__pyx_codeobj__46); + Py_VISIT(traverse_module_state->__pyx_codeobj__48); + Py_VISIT(traverse_module_state->__pyx_codeobj__50); + Py_VISIT(traverse_module_state->__pyx_codeobj__52); + Py_VISIT(traverse_module_state->__pyx_codeobj__54); + Py_VISIT(traverse_module_state->__pyx_codeobj__55); + Py_VISIT(traverse_module_state->__pyx_codeobj__56); + Py_VISIT(traverse_module_state->__pyx_codeobj__58); + Py_VISIT(traverse_module_state->__pyx_codeobj__61); + Py_VISIT(traverse_module_state->__pyx_codeobj__62); + Py_VISIT(traverse_module_state->__pyx_codeobj__64); + Py_VISIT(traverse_module_state->__pyx_codeobj__65); + Py_VISIT(traverse_module_state->__pyx_codeobj__66); + return 0; +} +#endif +/* #### Code section: module_state_defines ### */ +#define __pyx_d __pyx_mstate_global->__pyx_d +#define __pyx_b __pyx_mstate_global->__pyx_b +#define __pyx_cython_runtime __pyx_mstate_global->__pyx_cython_runtime +#define __pyx_empty_tuple __pyx_mstate_global->__pyx_empty_tuple +#define __pyx_empty_bytes __pyx_mstate_global->__pyx_empty_bytes +#define __pyx_empty_unicode __pyx_mstate_global->__pyx_empty_unicode +#ifdef __Pyx_CyFunction_USED +#define __pyx_CyFunctionType __pyx_mstate_global->__pyx_CyFunctionType +#endif +#ifdef __Pyx_FusedFunction_USED +#define __pyx_FusedFunctionType __pyx_mstate_global->__pyx_FusedFunctionType +#endif +#ifdef __Pyx_Generator_USED +#define __pyx_GeneratorType __pyx_mstate_global->__pyx_GeneratorType +#endif +#ifdef __Pyx_IterableCoroutine_USED +#define __pyx_IterableCoroutineType __pyx_mstate_global->__pyx_IterableCoroutineType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineAwaitType __pyx_mstate_global->__pyx_CoroutineAwaitType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineType __pyx_mstate_global->__pyx_CoroutineType +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#define __pyx_ptype_7cpython_4type_type __pyx_mstate_global->__pyx_ptype_7cpython_4type_type +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#define __pyx_ptype_5numpy_dtype __pyx_mstate_global->__pyx_ptype_5numpy_dtype +#define __pyx_ptype_5numpy_flatiter __pyx_mstate_global->__pyx_ptype_5numpy_flatiter +#define __pyx_ptype_5numpy_broadcast __pyx_mstate_global->__pyx_ptype_5numpy_broadcast +#define __pyx_ptype_5numpy_ndarray __pyx_mstate_global->__pyx_ptype_5numpy_ndarray +#define __pyx_ptype_5numpy_generic __pyx_mstate_global->__pyx_ptype_5numpy_generic +#define __pyx_ptype_5numpy_number __pyx_mstate_global->__pyx_ptype_5numpy_number +#define __pyx_ptype_5numpy_integer __pyx_mstate_global->__pyx_ptype_5numpy_integer +#define __pyx_ptype_5numpy_signedinteger __pyx_mstate_global->__pyx_ptype_5numpy_signedinteger +#define __pyx_ptype_5numpy_unsignedinteger __pyx_mstate_global->__pyx_ptype_5numpy_unsignedinteger +#define __pyx_ptype_5numpy_inexact __pyx_mstate_global->__pyx_ptype_5numpy_inexact +#define __pyx_ptype_5numpy_floating __pyx_mstate_global->__pyx_ptype_5numpy_floating +#define __pyx_ptype_5numpy_complexfloating __pyx_mstate_global->__pyx_ptype_5numpy_complexfloating +#define __pyx_ptype_5numpy_flexible __pyx_mstate_global->__pyx_ptype_5numpy_flexible +#define __pyx_ptype_5numpy_character __pyx_mstate_global->__pyx_ptype_5numpy_character +#define __pyx_ptype_5numpy_ufunc __pyx_mstate_global->__pyx_ptype_5numpy_ufunc +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#define __pyx_type_6cereal_9visionipc_13visionipc_pyx_CLContext __pyx_mstate_global->__pyx_type_6cereal_9visionipc_13visionipc_pyx_CLContext +#define __pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionBuf __pyx_mstate_global->__pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionBuf +#define __pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer __pyx_mstate_global->__pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer +#define __pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient __pyx_mstate_global->__pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient +#define __Pyx_EnumMeta __pyx_mstate_global->__Pyx_EnumMeta +#define __pyx_type___pyx_array __pyx_mstate_global->__pyx_type___pyx_array +#define __pyx_type___pyx_MemviewEnum __pyx_mstate_global->__pyx_type___pyx_MemviewEnum +#define __pyx_type___pyx_memoryview __pyx_mstate_global->__pyx_type___pyx_memoryview +#define __pyx_type___pyx_memoryviewslice __pyx_mstate_global->__pyx_type___pyx_memoryviewslice +#endif +#define __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext __pyx_mstate_global->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext +#define __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf __pyx_mstate_global->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf +#define __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer __pyx_mstate_global->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer +#define __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient __pyx_mstate_global->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient +#define __pyx_ptype___Pyx_EnumMeta __pyx_mstate_global->__pyx_ptype___Pyx_EnumMeta +#define __pyx_array_type __pyx_mstate_global->__pyx_array_type +#define __pyx_MemviewEnum_type __pyx_mstate_global->__pyx_MemviewEnum_type +#define __pyx_memoryview_type __pyx_mstate_global->__pyx_memoryview_type +#define __pyx_memoryviewslice_type __pyx_mstate_global->__pyx_memoryviewslice_type +#define __pyx_kp_b_ __pyx_mstate_global->__pyx_kp_b_ +#define __pyx_kp_s_ __pyx_mstate_global->__pyx_kp_s_ +#define __pyx_n_s_ASCII __pyx_mstate_global->__pyx_n_s_ASCII +#define __pyx_kp_s_All_dimensions_preceding_dimensi __pyx_mstate_global->__pyx_kp_s_All_dimensions_preceding_dimensi +#define __pyx_n_s_AssertionError __pyx_mstate_global->__pyx_n_s_AssertionError +#define __pyx_kp_s_Buffer_view_does_not_expose_stri __pyx_mstate_global->__pyx_kp_s_Buffer_view_does_not_expose_stri +#define __pyx_n_s_CLContext __pyx_mstate_global->__pyx_n_s_CLContext +#define __pyx_kp_s_Can_only_create_a_buffer_that_is __pyx_mstate_global->__pyx_kp_s_Can_only_create_a_buffer_that_is +#define __pyx_kp_s_Cannot_assign_to_read_only_memor __pyx_mstate_global->__pyx_kp_s_Cannot_assign_to_read_only_memor +#define __pyx_kp_s_Cannot_create_writable_memory_vi __pyx_mstate_global->__pyx_kp_s_Cannot_create_writable_memory_vi +#define __pyx_kp_u_Cannot_index_with_type __pyx_mstate_global->__pyx_kp_u_Cannot_index_with_type +#define __pyx_kp_s_Cannot_transpose_memoryview_with __pyx_mstate_global->__pyx_kp_s_Cannot_transpose_memoryview_with +#define __pyx_kp_s_Dimension_d_is_not_direct __pyx_mstate_global->__pyx_kp_s_Dimension_d_is_not_direct +#define __pyx_n_s_Ellipsis __pyx_mstate_global->__pyx_n_s_Ellipsis +#define __pyx_kp_s_Empty_shape_tuple_for_cython_arr __pyx_mstate_global->__pyx_kp_s_Empty_shape_tuple_for_cython_arr +#define __pyx_n_s_EnumBase __pyx_mstate_global->__pyx_n_s_EnumBase +#define __pyx_n_s_EnumType __pyx_mstate_global->__pyx_n_s_EnumType +#define __pyx_n_s_ImportError __pyx_mstate_global->__pyx_n_s_ImportError +#define __pyx_kp_s_Incompatible_checksums_0x_x_vs_0 __pyx_mstate_global->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0 +#define __pyx_kp_s_Incompatible_checksums_0x_x_vs_0_2 __pyx_mstate_global->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0_2 +#define __pyx_n_s_IndexError __pyx_mstate_global->__pyx_n_s_IndexError +#define __pyx_kp_s_Index_out_of_bounds_axis_d __pyx_mstate_global->__pyx_kp_s_Index_out_of_bounds_axis_d +#define __pyx_kp_s_Indirect_dimensions_not_supporte __pyx_mstate_global->__pyx_kp_s_Indirect_dimensions_not_supporte +#define __pyx_n_s_IntEnum __pyx_mstate_global->__pyx_n_s_IntEnum +#define __pyx_n_s_IntFlag __pyx_mstate_global->__pyx_n_s_IntFlag +#define __pyx_kp_u_Invalid_mode_expected_c_or_fortr __pyx_mstate_global->__pyx_kp_u_Invalid_mode_expected_c_or_fortr +#define __pyx_kp_u_Invalid_shape_in_axis __pyx_mstate_global->__pyx_kp_u_Invalid_shape_in_axis +#define __pyx_n_s_MemoryError __pyx_mstate_global->__pyx_n_s_MemoryError +#define __pyx_kp_s_MemoryView_of_r_at_0x_x __pyx_mstate_global->__pyx_kp_s_MemoryView_of_r_at_0x_x +#define __pyx_kp_s_MemoryView_of_r_object __pyx_mstate_global->__pyx_kp_s_MemoryView_of_r_object +#define __pyx_n_b_O __pyx_mstate_global->__pyx_n_b_O +#define __pyx_n_s_OrderedDict __pyx_mstate_global->__pyx_n_s_OrderedDict +#define __pyx_kp_u_Out_of_bounds_on_buffer_access_a __pyx_mstate_global->__pyx_kp_u_Out_of_bounds_on_buffer_access_a +#define __pyx_n_s_PickleError __pyx_mstate_global->__pyx_n_s_PickleError +#define __pyx_n_s_Pyx_EnumBase __pyx_mstate_global->__pyx_n_s_Pyx_EnumBase +#define __pyx_n_s_Pyx_EnumBase___new __pyx_mstate_global->__pyx_n_s_Pyx_EnumBase___new +#define __pyx_n_s_Pyx_EnumBase___repr __pyx_mstate_global->__pyx_n_s_Pyx_EnumBase___repr +#define __pyx_n_s_Pyx_EnumBase___str __pyx_mstate_global->__pyx_n_s_Pyx_EnumBase___str +#define __pyx_n_s_Pyx_EnumMeta___reduce_cython __pyx_mstate_global->__pyx_n_s_Pyx_EnumMeta___reduce_cython +#define __pyx_n_s_Pyx_EnumMeta___setstate_cython __pyx_mstate_global->__pyx_n_s_Pyx_EnumMeta___setstate_cython +#define __pyx_n_s_Pyx_FlagBase __pyx_mstate_global->__pyx_n_s_Pyx_FlagBase +#define __pyx_n_s_Pyx_FlagBase___new __pyx_mstate_global->__pyx_n_s_Pyx_FlagBase___new +#define __pyx_n_s_Pyx_FlagBase___repr __pyx_mstate_global->__pyx_n_s_Pyx_FlagBase___repr +#define __pyx_n_s_Pyx_FlagBase___str __pyx_mstate_global->__pyx_n_s_Pyx_FlagBase___str +#define __pyx_n_s_Sequence __pyx_mstate_global->__pyx_n_s_Sequence +#define __pyx_kp_s_Step_may_not_be_zero_axis_d __pyx_mstate_global->__pyx_kp_s_Step_may_not_be_zero_axis_d +#define __pyx_kp_b_T __pyx_mstate_global->__pyx_kp_b_T +#define __pyx_n_s_TypeError __pyx_mstate_global->__pyx_n_s_TypeError +#define __pyx_kp_s_Unable_to_convert_item_to_object __pyx_mstate_global->__pyx_kp_s_Unable_to_convert_item_to_object +#define __pyx_kp_s_Unknown_enum_value_s __pyx_mstate_global->__pyx_kp_s_Unknown_enum_value_s +#define __pyx_n_s_VISION_STREAM_DRIVER __pyx_mstate_global->__pyx_n_s_VISION_STREAM_DRIVER +#define __pyx_n_s_VISION_STREAM_MAP __pyx_mstate_global->__pyx_n_s_VISION_STREAM_MAP +#define __pyx_n_s_VISION_STREAM_ROAD __pyx_mstate_global->__pyx_n_s_VISION_STREAM_ROAD +#define __pyx_n_s_VISION_STREAM_WIDE_ROAD __pyx_mstate_global->__pyx_n_s_VISION_STREAM_WIDE_ROAD +#define __pyx_n_s_ValueError __pyx_mstate_global->__pyx_n_s_ValueError +#define __pyx_n_s_View_MemoryView __pyx_mstate_global->__pyx_n_s_View_MemoryView +#define __pyx_n_s_VisionBuf __pyx_mstate_global->__pyx_n_s_VisionBuf +#define __pyx_n_s_VisionBuf___reduce_cython __pyx_mstate_global->__pyx_n_s_VisionBuf___reduce_cython +#define __pyx_n_s_VisionBuf___setstate_cython __pyx_mstate_global->__pyx_n_s_VisionBuf___setstate_cython +#define __pyx_n_s_VisionIpcClient __pyx_mstate_global->__pyx_n_s_VisionIpcClient +#define __pyx_n_s_VisionIpcClient___reduce_cython __pyx_mstate_global->__pyx_n_s_VisionIpcClient___reduce_cython +#define __pyx_n_s_VisionIpcClient___setstate_cytho __pyx_mstate_global->__pyx_n_s_VisionIpcClient___setstate_cytho +#define __pyx_n_s_VisionIpcClient_available_stream __pyx_mstate_global->__pyx_n_s_VisionIpcClient_available_stream +#define __pyx_n_s_VisionIpcClient_connect __pyx_mstate_global->__pyx_n_s_VisionIpcClient_connect +#define __pyx_n_s_VisionIpcClient_is_connected __pyx_mstate_global->__pyx_n_s_VisionIpcClient_is_connected +#define __pyx_n_s_VisionIpcClient_recv __pyx_mstate_global->__pyx_n_s_VisionIpcClient_recv +#define __pyx_n_s_VisionIpcServer __pyx_mstate_global->__pyx_n_s_VisionIpcServer +#define __pyx_n_s_VisionIpcServer___reduce_cython __pyx_mstate_global->__pyx_n_s_VisionIpcServer___reduce_cython +#define __pyx_n_s_VisionIpcServer___setstate_cytho __pyx_mstate_global->__pyx_n_s_VisionIpcServer___setstate_cytho +#define __pyx_n_s_VisionIpcServer_create_buffers __pyx_mstate_global->__pyx_n_s_VisionIpcServer_create_buffers +#define __pyx_n_s_VisionIpcServer_create_buffers_w __pyx_mstate_global->__pyx_n_s_VisionIpcServer_create_buffers_w +#define __pyx_n_s_VisionIpcServer_send __pyx_mstate_global->__pyx_n_s_VisionIpcServer_send +#define __pyx_n_s_VisionIpcServer_start_listener __pyx_mstate_global->__pyx_n_s_VisionIpcServer_start_listener +#define __pyx_n_s_VisionStreamType __pyx_mstate_global->__pyx_n_s_VisionStreamType +#define __pyx_kp_b__11 __pyx_mstate_global->__pyx_kp_b__11 +#define __pyx_kp_b__12 __pyx_mstate_global->__pyx_kp_b__12 +#define __pyx_kp_b__13 __pyx_mstate_global->__pyx_kp_b__13 +#define __pyx_kp_u__14 __pyx_mstate_global->__pyx_kp_u__14 +#define __pyx_kp_u__15 __pyx_mstate_global->__pyx_kp_u__15 +#define __pyx_kp_u__3 __pyx_mstate_global->__pyx_kp_u__3 +#define __pyx_kp_u__4 __pyx_mstate_global->__pyx_kp_u__4 +#define __pyx_n_s__5 __pyx_mstate_global->__pyx_n_s__5 +#define __pyx_n_s__67 __pyx_mstate_global->__pyx_n_s__67 +#define __pyx_kp_u__8 __pyx_mstate_global->__pyx_kp_u__8 +#define __pyx_kp_u__9 __pyx_mstate_global->__pyx_kp_u__9 +#define __pyx_n_s_abc __pyx_mstate_global->__pyx_n_s_abc +#define __pyx_n_s_allocate_buffer __pyx_mstate_global->__pyx_n_s_allocate_buffer +#define __pyx_kp_u_and __pyx_mstate_global->__pyx_kp_u_and +#define __pyx_n_s_asarray __pyx_mstate_global->__pyx_n_s_asarray +#define __pyx_n_s_asyncio_coroutines __pyx_mstate_global->__pyx_n_s_asyncio_coroutines +#define __pyx_n_s_available_streams __pyx_mstate_global->__pyx_n_s_available_streams +#define __pyx_n_s_base __pyx_mstate_global->__pyx_n_s_base +#define __pyx_n_s_block __pyx_mstate_global->__pyx_n_s_block +#define __pyx_n_s_blocking __pyx_mstate_global->__pyx_n_s_blocking +#define __pyx_n_s_buf __pyx_mstate_global->__pyx_n_s_buf +#define __pyx_n_s_c __pyx_mstate_global->__pyx_n_s_c +#define __pyx_n_u_c __pyx_mstate_global->__pyx_n_u_c +#define __pyx_kp_s_cereal_visionipc_visionipc_pyx __pyx_mstate_global->__pyx_kp_s_cereal_visionipc_visionipc_pyx +#define __pyx_kp_s_cereal_visionipc_visionipc_pyx_p __pyx_mstate_global->__pyx_kp_s_cereal_visionipc_visionipc_pyx_p +#define __pyx_n_s_class __pyx_mstate_global->__pyx_n_s_class +#define __pyx_n_s_class_getitem __pyx_mstate_global->__pyx_n_s_class_getitem +#define __pyx_n_s_cline_in_traceback __pyx_mstate_global->__pyx_n_s_cline_in_traceback +#define __pyx_n_s_cls __pyx_mstate_global->__pyx_n_s_cls +#define __pyx_n_s_collections __pyx_mstate_global->__pyx_n_s_collections +#define __pyx_kp_s_collections_abc __pyx_mstate_global->__pyx_kp_s_collections_abc +#define __pyx_n_s_conflate __pyx_mstate_global->__pyx_n_s_conflate +#define __pyx_n_s_connect __pyx_mstate_global->__pyx_n_s_connect +#define __pyx_n_s_context __pyx_mstate_global->__pyx_n_s_context +#define __pyx_kp_s_contiguous_and_direct __pyx_mstate_global->__pyx_kp_s_contiguous_and_direct +#define __pyx_kp_s_contiguous_and_indirect __pyx_mstate_global->__pyx_kp_s_contiguous_and_indirect +#define __pyx_n_s_count __pyx_mstate_global->__pyx_n_s_count +#define __pyx_n_s_create_buffers __pyx_mstate_global->__pyx_n_s_create_buffers +#define __pyx_n_s_create_buffers_with_sizes __pyx_mstate_global->__pyx_n_s_create_buffers_with_sizes +#define __pyx_n_s_data __pyx_mstate_global->__pyx_n_s_data +#define __pyx_n_s_dct __pyx_mstate_global->__pyx_n_s_dct +#define __pyx_n_s_dict __pyx_mstate_global->__pyx_n_s_dict +#define __pyx_n_s_dict_2 __pyx_mstate_global->__pyx_n_s_dict_2 +#define __pyx_kp_u_disable __pyx_mstate_global->__pyx_kp_u_disable +#define __pyx_n_s_doc __pyx_mstate_global->__pyx_n_s_doc +#define __pyx_n_s_dtype_is_object __pyx_mstate_global->__pyx_n_s_dtype_is_object +#define __pyx_kp_u_enable __pyx_mstate_global->__pyx_kp_u_enable +#define __pyx_n_s_encode __pyx_mstate_global->__pyx_n_s_encode +#define __pyx_n_s_enum __pyx_mstate_global->__pyx_n_s_enum +#define __pyx_n_s_enumerate __pyx_mstate_global->__pyx_n_s_enumerate +#define __pyx_n_s_error __pyx_mstate_global->__pyx_n_s_error +#define __pyx_n_s_extra __pyx_mstate_global->__pyx_n_s_extra +#define __pyx_n_s_flags __pyx_mstate_global->__pyx_n_s_flags +#define __pyx_n_s_format __pyx_mstate_global->__pyx_n_s_format +#define __pyx_n_s_fortran __pyx_mstate_global->__pyx_n_s_fortran +#define __pyx_n_u_fortran __pyx_mstate_global->__pyx_n_u_fortran +#define __pyx_n_s_frame_id __pyx_mstate_global->__pyx_n_s_frame_id +#define __pyx_kp_u_gc __pyx_mstate_global->__pyx_kp_u_gc +#define __pyx_n_s_get __pyx_mstate_global->__pyx_n_s_get +#define __pyx_n_s_get_endpoint_name __pyx_mstate_global->__pyx_n_s_get_endpoint_name +#define __pyx_n_s_getstate __pyx_mstate_global->__pyx_n_s_getstate +#define __pyx_kp_u_got __pyx_mstate_global->__pyx_kp_u_got +#define __pyx_kp_u_got_differing_extents_in_dimensi __pyx_mstate_global->__pyx_kp_u_got_differing_extents_in_dimensi +#define __pyx_n_s_height __pyx_mstate_global->__pyx_n_s_height +#define __pyx_n_s_id __pyx_mstate_global->__pyx_n_s_id +#define __pyx_n_s_import __pyx_mstate_global->__pyx_n_s_import +#define __pyx_n_s_index __pyx_mstate_global->__pyx_n_s_index +#define __pyx_n_s_init __pyx_mstate_global->__pyx_n_s_init +#define __pyx_n_s_init_subclass __pyx_mstate_global->__pyx_n_s_init_subclass +#define __pyx_n_s_initializing __pyx_mstate_global->__pyx_n_s_initializing +#define __pyx_n_s_is_connected __pyx_mstate_global->__pyx_n_s_is_connected +#define __pyx_n_s_is_coroutine __pyx_mstate_global->__pyx_n_s_is_coroutine +#define __pyx_kp_u_isenabled __pyx_mstate_global->__pyx_kp_u_isenabled +#define __pyx_n_s_itemsize __pyx_mstate_global->__pyx_n_s_itemsize +#define __pyx_kp_s_itemsize_0_for_cython_array __pyx_mstate_global->__pyx_kp_s_itemsize_0_for_cython_array +#define __pyx_n_s_join __pyx_mstate_global->__pyx_n_s_join +#define __pyx_n_s_main __pyx_mstate_global->__pyx_n_s_main +#define __pyx_n_s_member_names __pyx_mstate_global->__pyx_n_s_member_names +#define __pyx_n_s_members __pyx_mstate_global->__pyx_n_s_members +#define __pyx_n_s_memview __pyx_mstate_global->__pyx_n_s_memview +#define __pyx_n_s_metaclass __pyx_mstate_global->__pyx_n_s_metaclass +#define __pyx_n_s_mode __pyx_mstate_global->__pyx_n_s_mode +#define __pyx_n_s_module __pyx_mstate_global->__pyx_n_s_module +#define __pyx_n_s_module_2 __pyx_mstate_global->__pyx_n_s_module_2 +#define __pyx_n_s_mro_entries __pyx_mstate_global->__pyx_n_s_mro_entries +#define __pyx_n_s_name __pyx_mstate_global->__pyx_n_s_name +#define __pyx_n_s_name_2 __pyx_mstate_global->__pyx_n_s_name_2 +#define __pyx_n_s_ndim __pyx_mstate_global->__pyx_n_s_ndim +#define __pyx_n_s_new __pyx_mstate_global->__pyx_n_s_new +#define __pyx_kp_s_no_default___reduce___due_to_non __pyx_mstate_global->__pyx_kp_s_no_default___reduce___due_to_non +#define __pyx_n_s_np __pyx_mstate_global->__pyx_n_s_np +#define __pyx_n_s_num_buffers __pyx_mstate_global->__pyx_n_s_num_buffers +#define __pyx_n_s_numpy __pyx_mstate_global->__pyx_n_s_numpy +#define __pyx_kp_u_numpy_core_multiarray_failed_to __pyx_mstate_global->__pyx_kp_u_numpy_core_multiarray_failed_to +#define __pyx_kp_u_numpy_core_umath_failed_to_impor __pyx_mstate_global->__pyx_kp_u_numpy_core_umath_failed_to_impor +#define __pyx_n_s_obj __pyx_mstate_global->__pyx_n_s_obj +#define __pyx_n_s_pack __pyx_mstate_global->__pyx_n_s_pack +#define __pyx_n_s_parents __pyx_mstate_global->__pyx_n_s_parents +#define __pyx_n_s_pickle __pyx_mstate_global->__pyx_n_s_pickle +#define __pyx_n_s_prepare __pyx_mstate_global->__pyx_n_s_prepare +#define __pyx_n_s_pyx_PickleError __pyx_mstate_global->__pyx_n_s_pyx_PickleError +#define __pyx_n_s_pyx_checksum __pyx_mstate_global->__pyx_n_s_pyx_checksum +#define __pyx_n_s_pyx_result __pyx_mstate_global->__pyx_n_s_pyx_result +#define __pyx_n_s_pyx_state __pyx_mstate_global->__pyx_n_s_pyx_state +#define __pyx_n_s_pyx_type __pyx_mstate_global->__pyx_n_s_pyx_type +#define __pyx_n_s_pyx_unpickle_Enum __pyx_mstate_global->__pyx_n_s_pyx_unpickle_Enum +#define __pyx_n_s_pyx_unpickle___Pyx_EnumMeta __pyx_mstate_global->__pyx_n_s_pyx_unpickle___Pyx_EnumMeta +#define __pyx_n_s_pyx_vtable __pyx_mstate_global->__pyx_n_s_pyx_vtable +#define __pyx_n_s_qualname __pyx_mstate_global->__pyx_n_s_qualname +#define __pyx_n_s_range __pyx_mstate_global->__pyx_n_s_range +#define __pyx_n_s_recv __pyx_mstate_global->__pyx_n_s_recv +#define __pyx_n_s_reduce __pyx_mstate_global->__pyx_n_s_reduce +#define __pyx_n_s_reduce_cython __pyx_mstate_global->__pyx_n_s_reduce_cython +#define __pyx_n_s_reduce_ex __pyx_mstate_global->__pyx_n_s_reduce_ex +#define __pyx_n_s_register __pyx_mstate_global->__pyx_n_s_register +#define __pyx_n_s_repr __pyx_mstate_global->__pyx_n_s_repr +#define __pyx_n_s_res __pyx_mstate_global->__pyx_n_s_res +#define __pyx_n_s_rgb __pyx_mstate_global->__pyx_n_s_rgb +#define __pyx_kp_s_s_s __pyx_mstate_global->__pyx_kp_s_s_s +#define __pyx_kp_s_s_s_d __pyx_mstate_global->__pyx_kp_s_s_s_d +#define __pyx_n_s_self __pyx_mstate_global->__pyx_n_s_self +#define __pyx_kp_s_self_buf_cannot_be_converted_to __pyx_mstate_global->__pyx_kp_s_self_buf_cannot_be_converted_to +#define __pyx_kp_s_self_server_cannot_be_converted __pyx_mstate_global->__pyx_kp_s_self_server_cannot_be_converted +#define __pyx_n_s_send __pyx_mstate_global->__pyx_n_s_send +#define __pyx_n_s_set_name __pyx_mstate_global->__pyx_n_s_set_name +#define __pyx_n_s_setstate __pyx_mstate_global->__pyx_n_s_setstate +#define __pyx_n_s_setstate_cython __pyx_mstate_global->__pyx_n_s_setstate_cython +#define __pyx_n_s_shape __pyx_mstate_global->__pyx_n_s_shape +#define __pyx_n_s_size __pyx_mstate_global->__pyx_n_s_size +#define __pyx_n_s_spec __pyx_mstate_global->__pyx_n_s_spec +#define __pyx_n_s_start __pyx_mstate_global->__pyx_n_s_start +#define __pyx_n_s_start_listener __pyx_mstate_global->__pyx_n_s_start_listener +#define __pyx_n_s_state __pyx_mstate_global->__pyx_n_s_state +#define __pyx_n_s_staticmethod __pyx_mstate_global->__pyx_n_s_staticmethod +#define __pyx_n_s_step __pyx_mstate_global->__pyx_n_s_step +#define __pyx_n_s_stop __pyx_mstate_global->__pyx_n_s_stop +#define __pyx_n_s_str __pyx_mstate_global->__pyx_n_s_str +#define __pyx_n_s_stream __pyx_mstate_global->__pyx_n_s_stream +#define __pyx_n_s_stride __pyx_mstate_global->__pyx_n_s_stride +#define __pyx_kp_s_strided_and_direct __pyx_mstate_global->__pyx_kp_s_strided_and_direct +#define __pyx_kp_s_strided_and_direct_or_indirect __pyx_mstate_global->__pyx_kp_s_strided_and_direct_or_indirect +#define __pyx_kp_s_strided_and_indirect __pyx_mstate_global->__pyx_kp_s_strided_and_indirect +#define __pyx_kp_s_stringsource __pyx_mstate_global->__pyx_kp_s_stringsource +#define __pyx_n_s_struct __pyx_mstate_global->__pyx_n_s_struct +#define __pyx_n_s_super __pyx_mstate_global->__pyx_n_s_super +#define __pyx_n_s_sys __pyx_mstate_global->__pyx_n_s_sys +#define __pyx_n_s_test __pyx_mstate_global->__pyx_n_s_test +#define __pyx_n_s_timeout_ms __pyx_mstate_global->__pyx_n_s_timeout_ms +#define __pyx_n_s_timestamp_eof __pyx_mstate_global->__pyx_n_s_timestamp_eof +#define __pyx_n_s_timestamp_sof __pyx_mstate_global->__pyx_n_s_timestamp_sof +#define __pyx_n_s_tp __pyx_mstate_global->__pyx_n_s_tp +#define __pyx_kp_s_unable_to_allocate_array_data __pyx_mstate_global->__pyx_kp_s_unable_to_allocate_array_data +#define __pyx_kp_s_unable_to_allocate_shape_and_str __pyx_mstate_global->__pyx_kp_s_unable_to_allocate_shape_and_str +#define __pyx_n_s_unpack __pyx_mstate_global->__pyx_n_s_unpack +#define __pyx_n_s_update __pyx_mstate_global->__pyx_n_s_update +#define __pyx_n_s_use_setstate __pyx_mstate_global->__pyx_n_s_use_setstate +#define __pyx_n_s_uv_offset __pyx_mstate_global->__pyx_n_s_uv_offset +#define __pyx_n_s_v __pyx_mstate_global->__pyx_n_s_v +#define __pyx_n_s_value __pyx_mstate_global->__pyx_n_s_value +#define __pyx_n_s_values __pyx_mstate_global->__pyx_n_s_values +#define __pyx_n_s_version_info __pyx_mstate_global->__pyx_n_s_version_info +#define __pyx_n_s_width __pyx_mstate_global->__pyx_n_s_width +#define __pyx_int_0 __pyx_mstate_global->__pyx_int_0 +#define __pyx_int_1 __pyx_mstate_global->__pyx_int_1 +#define __pyx_int_3 __pyx_mstate_global->__pyx_int_3 +#define __pyx_int_100 __pyx_mstate_global->__pyx_int_100 +#define __pyx_int_112105877 __pyx_mstate_global->__pyx_int_112105877 +#define __pyx_int_136983863 __pyx_mstate_global->__pyx_int_136983863 +#define __pyx_int_184977713 __pyx_mstate_global->__pyx_int_184977713 +#define __pyx_int_222419149 __pyx_mstate_global->__pyx_int_222419149 +#define __pyx_int_228825662 __pyx_mstate_global->__pyx_int_228825662 +#define __pyx_int_238750788 __pyx_mstate_global->__pyx_int_238750788 +#define __pyx_int_neg_1 __pyx_mstate_global->__pyx_int_neg_1 +#define __pyx_slice__7 __pyx_mstate_global->__pyx_slice__7 +#define __pyx_tuple__2 __pyx_mstate_global->__pyx_tuple__2 +#define __pyx_tuple__6 __pyx_mstate_global->__pyx_tuple__6 +#define __pyx_tuple__10 __pyx_mstate_global->__pyx_tuple__10 +#define __pyx_tuple__16 __pyx_mstate_global->__pyx_tuple__16 +#define __pyx_tuple__17 __pyx_mstate_global->__pyx_tuple__17 +#define __pyx_tuple__18 __pyx_mstate_global->__pyx_tuple__18 +#define __pyx_tuple__20 __pyx_mstate_global->__pyx_tuple__20 +#define __pyx_tuple__22 __pyx_mstate_global->__pyx_tuple__22 +#define __pyx_tuple__24 __pyx_mstate_global->__pyx_tuple__24 +#define __pyx_tuple__25 __pyx_mstate_global->__pyx_tuple__25 +#define __pyx_tuple__31 __pyx_mstate_global->__pyx_tuple__31 +#define __pyx_tuple__33 __pyx_mstate_global->__pyx_tuple__33 +#define __pyx_tuple__34 __pyx_mstate_global->__pyx_tuple__34 +#define __pyx_tuple__35 __pyx_mstate_global->__pyx_tuple__35 +#define __pyx_tuple__36 __pyx_mstate_global->__pyx_tuple__36 +#define __pyx_tuple__37 __pyx_mstate_global->__pyx_tuple__37 +#define __pyx_tuple__38 __pyx_mstate_global->__pyx_tuple__38 +#define __pyx_tuple__39 __pyx_mstate_global->__pyx_tuple__39 +#define __pyx_tuple__40 __pyx_mstate_global->__pyx_tuple__40 +#define __pyx_tuple__41 __pyx_mstate_global->__pyx_tuple__41 +#define __pyx_tuple__43 __pyx_mstate_global->__pyx_tuple__43 +#define __pyx_tuple__47 __pyx_mstate_global->__pyx_tuple__47 +#define __pyx_tuple__49 __pyx_mstate_global->__pyx_tuple__49 +#define __pyx_tuple__51 __pyx_mstate_global->__pyx_tuple__51 +#define __pyx_tuple__53 __pyx_mstate_global->__pyx_tuple__53 +#define __pyx_tuple__57 __pyx_mstate_global->__pyx_tuple__57 +#define __pyx_tuple__59 __pyx_mstate_global->__pyx_tuple__59 +#define __pyx_tuple__60 __pyx_mstate_global->__pyx_tuple__60 +#define __pyx_tuple__63 __pyx_mstate_global->__pyx_tuple__63 +#define __pyx_codeobj__19 __pyx_mstate_global->__pyx_codeobj__19 +#define __pyx_codeobj__21 __pyx_mstate_global->__pyx_codeobj__21 +#define __pyx_codeobj__23 __pyx_mstate_global->__pyx_codeobj__23 +#define __pyx_codeobj__26 __pyx_mstate_global->__pyx_codeobj__26 +#define __pyx_codeobj__27 __pyx_mstate_global->__pyx_codeobj__27 +#define __pyx_codeobj__28 __pyx_mstate_global->__pyx_codeobj__28 +#define __pyx_codeobj__29 __pyx_mstate_global->__pyx_codeobj__29 +#define __pyx_codeobj__30 __pyx_mstate_global->__pyx_codeobj__30 +#define __pyx_codeobj__32 __pyx_mstate_global->__pyx_codeobj__32 +#define __pyx_codeobj__42 __pyx_mstate_global->__pyx_codeobj__42 +#define __pyx_codeobj__44 __pyx_mstate_global->__pyx_codeobj__44 +#define __pyx_codeobj__45 __pyx_mstate_global->__pyx_codeobj__45 +#define __pyx_codeobj__46 __pyx_mstate_global->__pyx_codeobj__46 +#define __pyx_codeobj__48 __pyx_mstate_global->__pyx_codeobj__48 +#define __pyx_codeobj__50 __pyx_mstate_global->__pyx_codeobj__50 +#define __pyx_codeobj__52 __pyx_mstate_global->__pyx_codeobj__52 +#define __pyx_codeobj__54 __pyx_mstate_global->__pyx_codeobj__54 +#define __pyx_codeobj__55 __pyx_mstate_global->__pyx_codeobj__55 +#define __pyx_codeobj__56 __pyx_mstate_global->__pyx_codeobj__56 +#define __pyx_codeobj__58 __pyx_mstate_global->__pyx_codeobj__58 +#define __pyx_codeobj__61 __pyx_mstate_global->__pyx_codeobj__61 +#define __pyx_codeobj__62 __pyx_mstate_global->__pyx_codeobj__62 +#define __pyx_codeobj__64 __pyx_mstate_global->__pyx_codeobj__64 +#define __pyx_codeobj__65 __pyx_mstate_global->__pyx_codeobj__65 +#define __pyx_codeobj__66 __pyx_mstate_global->__pyx_codeobj__66 +/* #### Code section: module_code ### */ + +/* "string.from_py":13 + * + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: # <<<<<<<<<<<<<< + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + */ + +static std::string __pyx_convert_string_from_py_std__in_string(PyObject *__pyx_v_o) { + Py_ssize_t __pyx_v_length; + char const *__pyx_v_data; + std::string __pyx_r; + char const *__pyx_t_1; + std::string __pyx_t_2; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + + /* "string.from_py":14 + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: + * cdef Py_ssize_t length = 0 # <<<<<<<<<<<<<< + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + * return string(data, length) + */ + __pyx_v_length = 0; + + /* "string.from_py":15 + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) # <<<<<<<<<<<<<< + * return string(data, length) + * + */ + __pyx_t_1 = __Pyx_PyObject_AsStringAndSize(__pyx_v_o, (&__pyx_v_length)); if (unlikely(__pyx_t_1 == ((char const *)NULL))) __PYX_ERR(1, 15, __pyx_L1_error) + __pyx_v_data = __pyx_t_1; + + /* "string.from_py":16 + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + * return string(data, length) # <<<<<<<<<<<<<< + * + * + */ + try { + __pyx_t_2 = std::string(__pyx_v_data, __pyx_v_length); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(1, 16, __pyx_L1_error) + } + __pyx_r = __pyx_t_2; + goto __pyx_L0; + + /* "string.from_py":13 + * + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: # <<<<<<<<<<<<<< + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("string.from_py.__pyx_convert_string_from_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_pretend_to_initialize(&__pyx_r); + __pyx_L0:; + return __pyx_r; +} + +/* "string.to_py":31 + * + * @cname("__pyx_convert_PyObject_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyObject_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyObject_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyObject_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyObject_string_to_py_std__in_string", 1); + + /* "string.to_py":32 + * @cname("__pyx_convert_PyObject_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyObject_string_to_py_std__in_string(const string& s): + * return __Pyx_PyObject_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * cdef extern from *: + * cdef object __Pyx_PyUnicode_FromStringAndSize(const char*, size_t) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 32, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":31 + * + * @cname("__pyx_convert_PyObject_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyObject_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyObject_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyObject_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":37 + * + * @cname("__pyx_convert_PyUnicode_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyUnicode_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyUnicode_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyUnicode_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyUnicode_string_to_py_std__in_string", 1); + + /* "string.to_py":38 + * @cname("__pyx_convert_PyUnicode_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyUnicode_string_to_py_std__in_string(const string& s): + * return __Pyx_PyUnicode_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * cdef extern from *: + * cdef object __Pyx_PyStr_FromStringAndSize(const char*, size_t) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyUnicode_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 38, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":37 + * + * @cname("__pyx_convert_PyUnicode_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyUnicode_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyUnicode_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyUnicode_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":43 + * + * @cname("__pyx_convert_PyStr_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyStr_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyStr_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyStr_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyStr_string_to_py_std__in_string", 1); + + /* "string.to_py":44 + * @cname("__pyx_convert_PyStr_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyStr_string_to_py_std__in_string(const string& s): + * return __Pyx_PyStr_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * cdef extern from *: + * cdef object __Pyx_PyBytes_FromStringAndSize(const char*, size_t) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyStr_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 44, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":43 + * + * @cname("__pyx_convert_PyStr_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyStr_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyStr_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyStr_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":49 + * + * @cname("__pyx_convert_PyBytes_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyBytes_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyBytes_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyBytes_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyBytes_string_to_py_std__in_string", 1); + + /* "string.to_py":50 + * @cname("__pyx_convert_PyBytes_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyBytes_string_to_py_std__in_string(const string& s): + * return __Pyx_PyBytes_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * cdef extern from *: + * cdef object __Pyx_PyByteArray_FromStringAndSize(const char*, size_t) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyBytes_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 50, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":49 + * + * @cname("__pyx_convert_PyBytes_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyBytes_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyBytes_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyBytes_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":55 + * + * @cname("__pyx_convert_PyByteArray_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyByteArray_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyByteArray_FromStringAndSize(s.data(), s.size()) + * + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyByteArray_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyByteArray_string_to_py_std__in_string", 1); + + /* "string.to_py":56 + * @cname("__pyx_convert_PyByteArray_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyByteArray_string_to_py_std__in_string(const string& s): + * return __Pyx_PyByteArray_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyByteArray_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 56, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":55 + * + * @cname("__pyx_convert_PyByteArray_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyByteArray_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyByteArray_FromStringAndSize(s.data(), s.size()) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyByteArray_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "set.to_py":166 + * + * @cname("__pyx_convert_set_to_py_enum__VisionStreamType") + * cdef object __pyx_convert_set_to_py_enum__VisionStreamType(const cpp_set[X]& s): # <<<<<<<<<<<<<< + * return {v for v in s} + * + */ + +static PyObject *__pyx_convert_set_to_py_enum__VisionStreamType(std::set const &__pyx_v_s) { + enum VisionStreamType __pyx_7genexpr__pyx_v_v; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + std::set ::const_iterator __pyx_t_2; + enum VisionStreamType __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_set_to_py_enum__VisionStreamType", 1); + + /* "set.to_py":167 + * @cname("__pyx_convert_set_to_py_enum__VisionStreamType") + * cdef object __pyx_convert_set_to_py_enum__VisionStreamType(const cpp_set[X]& s): + * return {v for v in s} # <<<<<<<<<<<<<< + * + */ + __Pyx_XDECREF(__pyx_r); + { /* enter inner scope */ + __pyx_t_1 = PySet_New(NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 167, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_v_s.begin(); + for (;;) { + if (!(__pyx_t_2 != __pyx_v_s.end())) break; + __pyx_t_3 = *__pyx_t_2; + ++__pyx_t_2; + __pyx_7genexpr__pyx_v_v = __pyx_t_3; + __pyx_t_4 = __Pyx_PyInt_From_enum__VisionStreamType(__pyx_7genexpr__pyx_v_v); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 167, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (unlikely(PySet_Add(__pyx_t_1, (PyObject*)__pyx_t_4))) __PYX_ERR(1, 167, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + } /* exit inner scope */ + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "set.to_py":166 + * + * @cname("__pyx_convert_set_to_py_enum__VisionStreamType") + * cdef object __pyx_convert_set_to_py_enum__VisionStreamType(const cpp_set[X]& s): # <<<<<<<<<<<<<< + * return {v for v in s} + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("set.to_py.__pyx_convert_set_to_py_enum__VisionStreamType", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "EnumBase":17 + * @cython.internal + * cdef class __Pyx_EnumMeta(type): + * def __init__(cls, name, parents, dct): # <<<<<<<<<<<<<< + * type.__init__(cls, name, parents, dct) + * cls.__members__ = __Pyx_OrderedDict() + */ + +/* Python wrapper */ +static int __pyx_pw_8EnumBase_14__Pyx_EnumMeta_1__init__(PyObject *__pyx_v_cls, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_pw_8EnumBase_14__Pyx_EnumMeta_1__init__(PyObject *__pyx_v_cls, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_name = 0; + PyObject *__pyx_v_parents = 0; + PyObject *__pyx_v_dct = 0; + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__init__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_name,&__pyx_n_s_parents,&__pyx_n_s_dct,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_name)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 17, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_parents)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 17, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__init__", 1, 3, 3, 1); __PYX_ERR(1, 17, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_dct)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 17, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__init__", 1, 3, 3, 2); __PYX_ERR(1, 17, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__init__") < 0)) __PYX_ERR(1, 17, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + } + __pyx_v_name = values[0]; + __pyx_v_parents = values[1]; + __pyx_v_dct = values[2]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__init__", 1, 3, 3, __pyx_nargs); __PYX_ERR(1, 17, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("EnumBase.__Pyx_EnumMeta.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_8EnumBase_14__Pyx_EnumMeta___init__(((struct __pyx_obj___Pyx_EnumMeta *)__pyx_v_cls), __pyx_v_name, __pyx_v_parents, __pyx_v_dct); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_8EnumBase_14__Pyx_EnumMeta___init__(struct __pyx_obj___Pyx_EnumMeta *__pyx_v_cls, PyObject *__pyx_v_name, PyObject *__pyx_v_parents, PyObject *__pyx_v_dct) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__init__", 1); + + /* "EnumBase":18 + * cdef class __Pyx_EnumMeta(type): + * def __init__(cls, name, parents, dct): + * type.__init__(cls, name, parents, dct) # <<<<<<<<<<<<<< + * cls.__members__ = __Pyx_OrderedDict() + * def __iter__(cls): + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(((PyObject *)(&PyType_Type)), __pyx_n_s_init); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 18, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[5] = {__pyx_t_3, ((PyObject *)__pyx_v_cls), __pyx_v_name, __pyx_v_parents, __pyx_v_dct}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 4+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 18, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "EnumBase":19 + * def __init__(cls, name, parents, dct): + * type.__init__(cls, name, parents, dct) + * cls.__members__ = __Pyx_OrderedDict() # <<<<<<<<<<<<<< + * def __iter__(cls): + * return iter(cls.__members__.values()) + */ + __Pyx_INCREF(__Pyx_OrderedDict); + __pyx_t_2 = __Pyx_OrderedDict; __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (unlikely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, NULL}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 0+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 19, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + if (__Pyx_PyObject_SetAttrStr(((PyObject *)__pyx_v_cls), __pyx_n_s_members, __pyx_t_1) < 0) __PYX_ERR(1, 19, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "EnumBase":17 + * @cython.internal + * cdef class __Pyx_EnumMeta(type): + * def __init__(cls, name, parents, dct): # <<<<<<<<<<<<<< + * type.__init__(cls, name, parents, dct) + * cls.__members__ = __Pyx_OrderedDict() + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("EnumBase.__Pyx_EnumMeta.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "EnumBase":20 + * type.__init__(cls, name, parents, dct) + * cls.__members__ = __Pyx_OrderedDict() + * def __iter__(cls): # <<<<<<<<<<<<<< + * return iter(cls.__members__.values()) + * def __getitem__(cls, name): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumMeta_3__iter__(PyObject *__pyx_v_cls); /*proto*/ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumMeta_3__iter__(PyObject *__pyx_v_cls) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__iter__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_8EnumBase_14__Pyx_EnumMeta_2__iter__(((struct __pyx_obj___Pyx_EnumMeta *)__pyx_v_cls)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumMeta_2__iter__(struct __pyx_obj___Pyx_EnumMeta *__pyx_v_cls) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__iter__", 1); + + /* "EnumBase":21 + * cls.__members__ = __Pyx_OrderedDict() + * def __iter__(cls): + * return iter(cls.__members__.values()) # <<<<<<<<<<<<<< + * def __getitem__(cls, name): + * return cls.__members__[name] + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_cls), __pyx_n_s_members); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 21, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_values); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 21, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_2 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_2)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_2); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_2, NULL}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_4, 0+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 21, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_t_3 = PyObject_GetIter(__pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 21, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_3; + __pyx_t_3 = 0; + goto __pyx_L0; + + /* "EnumBase":20 + * type.__init__(cls, name, parents, dct) + * cls.__members__ = __Pyx_OrderedDict() + * def __iter__(cls): # <<<<<<<<<<<<<< + * return iter(cls.__members__.values()) + * def __getitem__(cls, name): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("EnumBase.__Pyx_EnumMeta.__iter__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "EnumBase":22 + * def __iter__(cls): + * return iter(cls.__members__.values()) + * def __getitem__(cls, name): # <<<<<<<<<<<<<< + * return cls.__members__[name] + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumMeta_5__getitem__(PyObject *__pyx_v_cls, PyObject *__pyx_v_name); /*proto*/ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumMeta_5__getitem__(PyObject *__pyx_v_cls, PyObject *__pyx_v_name) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getitem__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_8EnumBase_14__Pyx_EnumMeta_4__getitem__(((struct __pyx_obj___Pyx_EnumMeta *)__pyx_v_cls), ((PyObject *)__pyx_v_name)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumMeta_4__getitem__(struct __pyx_obj___Pyx_EnumMeta *__pyx_v_cls, PyObject *__pyx_v_name) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__getitem__", 1); + + /* "EnumBase":23 + * return iter(cls.__members__.values()) + * def __getitem__(cls, name): + * return cls.__members__[name] # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_cls), __pyx_n_s_members); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 23, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_t_1, __pyx_v_name); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 23, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "EnumBase":22 + * def __iter__(cls): + * return iter(cls.__members__.values()) + * def __getitem__(cls, name): # <<<<<<<<<<<<<< + * return cls.__members__[name] + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("EnumBase.__Pyx_EnumMeta.__getitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * cdef tuple state + * cdef object _dict + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumMeta_7__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_8EnumBase_14__Pyx_EnumMeta_7__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_8EnumBase_14__Pyx_EnumMeta_7__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumMeta_7__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_8EnumBase_14__Pyx_EnumMeta_6__reduce_cython__(((struct __pyx_obj___Pyx_EnumMeta *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumMeta_6__reduce_cython__(struct __pyx_obj___Pyx_EnumMeta *__pyx_v_self) { + PyObject *__pyx_v_state = 0; + PyObject *__pyx_v__dict = 0; + int __pyx_v_use_setstate; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":5 + * cdef object _dict + * cdef bint use_setstate + * state = () # <<<<<<<<<<<<<< + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: + */ + __Pyx_INCREF(__pyx_empty_tuple); + __pyx_v_state = __pyx_empty_tuple; + + /* "(tree fragment)":6 + * cdef bint use_setstate + * state = () + * _dict = getattr(self, '__dict__', None) # <<<<<<<<<<<<<< + * if _dict is not None: + * state += (_dict,) + */ + __pyx_t_1 = __Pyx_GetAttr3(((PyObject *)__pyx_v_self), __pyx_n_s_dict, Py_None); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v__dict = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":7 + * state = () + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: # <<<<<<<<<<<<<< + * state += (_dict,) + * use_setstate = True + */ + __pyx_t_2 = (__pyx_v__dict != Py_None); + if (__pyx_t_2) { + + /* "(tree fragment)":8 + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: + * state += (_dict,) # <<<<<<<<<<<<<< + * use_setstate = True + * else: + */ + __pyx_t_1 = PyTuple_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 8, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v__dict); + __Pyx_GIVEREF(__pyx_v__dict); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v__dict)) __PYX_ERR(1, 8, __pyx_L1_error); + __pyx_t_3 = PyNumber_InPlaceAdd(__pyx_v_state, __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 8, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF_SET(__pyx_v_state, ((PyObject*)__pyx_t_3)); + __pyx_t_3 = 0; + + /* "(tree fragment)":9 + * if _dict is not None: + * state += (_dict,) + * use_setstate = True # <<<<<<<<<<<<<< + * else: + * use_setstate = False + */ + __pyx_v_use_setstate = 1; + + /* "(tree fragment)":7 + * state = () + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: # <<<<<<<<<<<<<< + * state += (_dict,) + * use_setstate = True + */ + goto __pyx_L3; + } + + /* "(tree fragment)":11 + * use_setstate = True + * else: + * use_setstate = False # <<<<<<<<<<<<<< + * if use_setstate: + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, None), state + */ + /*else*/ { + __pyx_v_use_setstate = 0; + } + __pyx_L3:; + + /* "(tree fragment)":12 + * else: + * use_setstate = False + * if use_setstate: # <<<<<<<<<<<<<< + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, None), state + * else: + */ + if (__pyx_v_use_setstate) { + + /* "(tree fragment)":13 + * use_setstate = False + * if use_setstate: + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, None), state # <<<<<<<<<<<<<< + * else: + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, state) + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_pyx_unpickle___Pyx_EnumMeta); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = PyTuple_New(3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_GIVEREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, ((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self))))) __PYX_ERR(1, 13, __pyx_L1_error); + __Pyx_INCREF(__pyx_int_238750788); + __Pyx_GIVEREF(__pyx_int_238750788); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_int_238750788)) __PYX_ERR(1, 13, __pyx_L1_error); + __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(Py_None); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 2, Py_None)) __PYX_ERR(1, 13, __pyx_L1_error); + __pyx_t_4 = PyTuple_New(3); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_3)) __PYX_ERR(1, 13, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_t_1)) __PYX_ERR(1, 13, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_state); + __Pyx_GIVEREF(__pyx_v_state); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 2, __pyx_v_state)) __PYX_ERR(1, 13, __pyx_L1_error); + __pyx_t_3 = 0; + __pyx_t_1 = 0; + __pyx_r = __pyx_t_4; + __pyx_t_4 = 0; + goto __pyx_L0; + + /* "(tree fragment)":12 + * else: + * use_setstate = False + * if use_setstate: # <<<<<<<<<<<<<< + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, None), state + * else: + */ + } + + /* "(tree fragment)":15 + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, None), state + * else: + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, state) # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * __pyx_unpickle___Pyx_EnumMeta__set_state(self, __pyx_state) + */ + /*else*/ { + __Pyx_XDECREF(__pyx_r); + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_pyx_unpickle___Pyx_EnumMeta); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_1 = PyTuple_New(3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_GIVEREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, ((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self))))) __PYX_ERR(1, 15, __pyx_L1_error); + __Pyx_INCREF(__pyx_int_238750788); + __Pyx_GIVEREF(__pyx_int_238750788); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_int_238750788)) __PYX_ERR(1, 15, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_state); + __Pyx_GIVEREF(__pyx_v_state); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_v_state)) __PYX_ERR(1, 15, __pyx_L1_error); + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_4); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_4)) __PYX_ERR(1, 15, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1)) __PYX_ERR(1, 15, __pyx_L1_error); + __pyx_t_4 = 0; + __pyx_t_1 = 0; + __pyx_r = __pyx_t_3; + __pyx_t_3 = 0; + goto __pyx_L0; + } + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * cdef tuple state + * cdef object _dict + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("EnumBase.__Pyx_EnumMeta.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_state); + __Pyx_XDECREF(__pyx_v__dict); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":16 + * else: + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, state) + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * __pyx_unpickle___Pyx_EnumMeta__set_state(self, __pyx_state) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumMeta_9__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_8EnumBase_14__Pyx_EnumMeta_9__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_8EnumBase_14__Pyx_EnumMeta_9__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumMeta_9__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 16, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 16, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 16, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("EnumBase.__Pyx_EnumMeta.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_8EnumBase_14__Pyx_EnumMeta_8__setstate_cython__(((struct __pyx_obj___Pyx_EnumMeta *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumMeta_8__setstate_cython__(struct __pyx_obj___Pyx_EnumMeta *__pyx_v_self, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":17 + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, state) + * def __setstate_cython__(self, __pyx_state): + * __pyx_unpickle___Pyx_EnumMeta__set_state(self, __pyx_state) # <<<<<<<<<<<<<< + */ + if (!(likely(PyTuple_CheckExact(__pyx_v___pyx_state))||((__pyx_v___pyx_state) == Py_None) || __Pyx_RaiseUnexpectedTypeError("tuple", __pyx_v___pyx_state))) __PYX_ERR(1, 17, __pyx_L1_error) + __pyx_t_1 = __pyx_unpickle___Pyx_EnumMeta__set_state(__pyx_v_self, ((PyObject*)__pyx_v___pyx_state)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 17, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":16 + * else: + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, state) + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * __pyx_unpickle___Pyx_EnumMeta__set_state(self, __pyx_state) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("EnumBase.__Pyx_EnumMeta.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "EnumBase":28 + * cdef object __Pyx_EnumBase + * class __Pyx_EnumBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): # <<<<<<<<<<<<<< + * for v in cls: + * if v == value: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumBase_1__new__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_8EnumBase_14__Pyx_EnumBase_1__new__ = {"__new__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_8EnumBase_14__Pyx_EnumBase_1__new__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumBase_1__new__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_cls = 0; + PyObject *__pyx_v_value = 0; + PyObject *__pyx_v_name = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__new__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_cls,&__pyx_n_s_value,&__pyx_n_s_name,0}; + values[2] = __Pyx_Arg_NewRef_FASTCALL(((PyObject *)Py_None)); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_cls)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 28, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_value)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 28, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__new__", 0, 2, 3, 1); __PYX_ERR(1, 28, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_name); + if (value) { values[2] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 28, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__new__") < 0)) __PYX_ERR(1, 28, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_cls = values[0]; + __pyx_v_value = values[1]; + __pyx_v_name = values[2]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__new__", 0, 2, 3, __pyx_nargs); __PYX_ERR(1, 28, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("EnumBase.__Pyx_EnumBase.__new__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_8EnumBase_14__Pyx_EnumBase___new__(__pyx_self, __pyx_v_cls, __pyx_v_value, __pyx_v_name); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumBase___new__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_cls, PyObject *__pyx_v_value, PyObject *__pyx_v_name) { + PyObject *__pyx_v_v = NULL; + PyObject *__pyx_v_res = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + Py_ssize_t __pyx_t_2; + PyObject *(*__pyx_t_3)(PyObject *); + PyObject *__pyx_t_4 = NULL; + int __pyx_t_5; + PyObject *__pyx_t_6 = NULL; + int __pyx_t_7; + int __pyx_t_8; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__new__", 1); + + /* "EnumBase":29 + * class __Pyx_EnumBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): + * for v in cls: # <<<<<<<<<<<<<< + * if v == value: + * return v + */ + if (likely(PyList_CheckExact(__pyx_v_cls)) || PyTuple_CheckExact(__pyx_v_cls)) { + __pyx_t_1 = __pyx_v_cls; __Pyx_INCREF(__pyx_t_1); + __pyx_t_2 = 0; + __pyx_t_3 = NULL; + } else { + __pyx_t_2 = -1; __pyx_t_1 = PyObject_GetIter(__pyx_v_cls); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 29, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 29, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_3)) { + if (likely(PyList_CheckExact(__pyx_t_1))) { + { + Py_ssize_t __pyx_temp = __Pyx_PyList_GET_SIZE(__pyx_t_1); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 29, __pyx_L1_error) + #endif + if (__pyx_t_2 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyList_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(1, 29, __pyx_L1_error) + #else + __pyx_t_4 = __Pyx_PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 29, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } else { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_1); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 29, __pyx_L1_error) + #endif + if (__pyx_t_2 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyTuple_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(1, 29, __pyx_L1_error) + #else + __pyx_t_4 = __Pyx_PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 29, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } + } else { + __pyx_t_4 = __pyx_t_3(__pyx_t_1); + if (unlikely(!__pyx_t_4)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(1, 29, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_4); + } + __Pyx_XDECREF_SET(__pyx_v_v, __pyx_t_4); + __pyx_t_4 = 0; + + /* "EnumBase":30 + * def __new__(cls, value, name=None): + * for v in cls: + * if v == value: # <<<<<<<<<<<<<< + * return v + * if name is None: + */ + __pyx_t_4 = PyObject_RichCompare(__pyx_v_v, __pyx_v_value, Py_EQ); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 30, __pyx_L1_error) + __pyx_t_5 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_5 < 0))) __PYX_ERR(1, 30, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (__pyx_t_5) { + + /* "EnumBase":31 + * for v in cls: + * if v == value: + * return v # <<<<<<<<<<<<<< + * if name is None: + * raise ValueError("Unknown enum value: '%s'" % value) + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_v); + __pyx_r = __pyx_v_v; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + goto __pyx_L0; + + /* "EnumBase":30 + * def __new__(cls, value, name=None): + * for v in cls: + * if v == value: # <<<<<<<<<<<<<< + * return v + * if name is None: + */ + } + + /* "EnumBase":29 + * class __Pyx_EnumBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): + * for v in cls: # <<<<<<<<<<<<<< + * if v == value: + * return v + */ + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "EnumBase":32 + * if v == value: + * return v + * if name is None: # <<<<<<<<<<<<<< + * raise ValueError("Unknown enum value: '%s'" % value) + * res = int.__new__(cls, value) + */ + __pyx_t_5 = (__pyx_v_name == Py_None); + if (unlikely(__pyx_t_5)) { + + /* "EnumBase":33 + * return v + * if name is None: + * raise ValueError("Unknown enum value: '%s'" % value) # <<<<<<<<<<<<<< + * res = int.__new__(cls, value) + * res.name = name + */ + __pyx_t_1 = __Pyx_PyString_FormatSafe(__pyx_kp_s_Unknown_enum_value_s, __pyx_v_value); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 33, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_4 = __Pyx_PyObject_CallOneArg(__pyx_builtin_ValueError, __pyx_t_1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 33, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_t_4, 0, 0, 0); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __PYX_ERR(1, 33, __pyx_L1_error) + + /* "EnumBase":32 + * if v == value: + * return v + * if name is None: # <<<<<<<<<<<<<< + * raise ValueError("Unknown enum value: '%s'" % value) + * res = int.__new__(cls, value) + */ + } + + /* "EnumBase":34 + * if name is None: + * raise ValueError("Unknown enum value: '%s'" % value) + * res = int.__new__(cls, value) # <<<<<<<<<<<<<< + * res.name = name + * setattr(cls, name, res) + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)(&PyInt_Type)), __pyx_n_s_new); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 34, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_6 = NULL; + __pyx_t_7 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_6 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_6)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_6); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_7 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_6, __pyx_v_cls, __pyx_v_value}; + __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_7, 2+__pyx_t_7); + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 34, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_v_res = __pyx_t_4; + __pyx_t_4 = 0; + + /* "EnumBase":35 + * raise ValueError("Unknown enum value: '%s'" % value) + * res = int.__new__(cls, value) + * res.name = name # <<<<<<<<<<<<<< + * setattr(cls, name, res) + * cls.__members__[name] = res + */ + if (__Pyx_PyObject_SetAttrStr(__pyx_v_res, __pyx_n_s_name, __pyx_v_name) < 0) __PYX_ERR(1, 35, __pyx_L1_error) + + /* "EnumBase":36 + * res = int.__new__(cls, value) + * res.name = name + * setattr(cls, name, res) # <<<<<<<<<<<<<< + * cls.__members__[name] = res + * return res + */ + __pyx_t_8 = PyObject_SetAttr(__pyx_v_cls, __pyx_v_name, __pyx_v_res); if (unlikely(__pyx_t_8 == ((int)-1))) __PYX_ERR(1, 36, __pyx_L1_error) + + /* "EnumBase":37 + * res.name = name + * setattr(cls, name, res) + * cls.__members__[name] = res # <<<<<<<<<<<<<< + * return res + * def __repr__(self): + */ + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_v_cls, __pyx_n_s_members); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 37, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (unlikely((PyObject_SetItem(__pyx_t_4, __pyx_v_name, __pyx_v_res) < 0))) __PYX_ERR(1, 37, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "EnumBase":38 + * setattr(cls, name, res) + * cls.__members__[name] = res + * return res # <<<<<<<<<<<<<< + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_res); + __pyx_r = __pyx_v_res; + goto __pyx_L0; + + /* "EnumBase":28 + * cdef object __Pyx_EnumBase + * class __Pyx_EnumBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): # <<<<<<<<<<<<<< + * for v in cls: + * if v == value: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("EnumBase.__Pyx_EnumBase.__new__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_v); + __Pyx_XDECREF(__pyx_v_res); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "EnumBase":39 + * cls.__members__[name] = res + * return res + * def __repr__(self): # <<<<<<<<<<<<<< + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumBase_3__repr__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_8EnumBase_14__Pyx_EnumBase_3__repr__ = {"__repr__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_8EnumBase_14__Pyx_EnumBase_3__repr__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumBase_3__repr__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_self = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__repr__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_self,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_self)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 39, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__repr__") < 0)) __PYX_ERR(1, 39, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_self = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__repr__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 39, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("EnumBase.__Pyx_EnumBase.__repr__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_8EnumBase_14__Pyx_EnumBase_2__repr__(__pyx_self, __pyx_v_self); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumBase_2__repr__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__repr__", 1); + + /* "EnumBase":40 + * return res + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) # <<<<<<<<<<<<<< + * def __str__(self): + * return "%s.%s" % (self.__class__.__name__, self.name) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_self, __pyx_n_s_class); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_name_2); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_self, __pyx_n_s_name); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_2)) __PYX_ERR(1, 40, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1)) __PYX_ERR(1, 40, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_self); + __Pyx_GIVEREF(__pyx_v_self); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_v_self)) __PYX_ERR(1, 40, __pyx_L1_error); + __pyx_t_2 = 0; + __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_s_s_d, __pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "EnumBase":39 + * cls.__members__[name] = res + * return res + * def __repr__(self): # <<<<<<<<<<<<<< + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("EnumBase.__Pyx_EnumBase.__repr__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "EnumBase":41 + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): # <<<<<<<<<<<<<< + * return "%s.%s" % (self.__class__.__name__, self.name) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumBase_5__str__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_8EnumBase_14__Pyx_EnumBase_5__str__ = {"__str__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_8EnumBase_14__Pyx_EnumBase_5__str__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumBase_5__str__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_self = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__str__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_self,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_self)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 41, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__str__") < 0)) __PYX_ERR(1, 41, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_self = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__str__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 41, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("EnumBase.__Pyx_EnumBase.__str__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_8EnumBase_14__Pyx_EnumBase_4__str__(__pyx_self, __pyx_v_self); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumBase_4__str__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__str__", 1); + + /* "EnumBase":42 + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): + * return "%s.%s" % (self.__class__.__name__, self.name) # <<<<<<<<<<<<<< + * + * if PY_VERSION_HEX >= 0x03040000: + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_self, __pyx_n_s_class); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 42, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_name_2); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 42, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_self, __pyx_n_s_name); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 42, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 42, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_2)) __PYX_ERR(1, 42, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1)) __PYX_ERR(1, 42, __pyx_L1_error); + __pyx_t_2 = 0; + __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_s_s, __pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 42, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "EnumBase":41 + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): # <<<<<<<<<<<<<< + * return "%s.%s" % (self.__class__.__name__, self.name) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("EnumBase.__Pyx_EnumBase.__str__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "EnumBase":49 + * cdef object __Pyx_FlagBase + * class __Pyx_FlagBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): # <<<<<<<<<<<<<< + * for v in cls: + * if v == value: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_FlagBase_1__new__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_8EnumBase_14__Pyx_FlagBase_1__new__ = {"__new__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_8EnumBase_14__Pyx_FlagBase_1__new__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_8EnumBase_14__Pyx_FlagBase_1__new__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_cls = 0; + PyObject *__pyx_v_value = 0; + PyObject *__pyx_v_name = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__new__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_cls,&__pyx_n_s_value,&__pyx_n_s_name,0}; + values[2] = __Pyx_Arg_NewRef_FASTCALL(((PyObject *)Py_None)); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_cls)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 49, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_value)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 49, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__new__", 0, 2, 3, 1); __PYX_ERR(1, 49, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_name); + if (value) { values[2] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 49, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__new__") < 0)) __PYX_ERR(1, 49, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_cls = values[0]; + __pyx_v_value = values[1]; + __pyx_v_name = values[2]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__new__", 0, 2, 3, __pyx_nargs); __PYX_ERR(1, 49, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("EnumBase.__Pyx_FlagBase.__new__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_8EnumBase_14__Pyx_FlagBase___new__(__pyx_self, __pyx_v_cls, __pyx_v_value, __pyx_v_name); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_8EnumBase_14__Pyx_FlagBase___new__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_cls, PyObject *__pyx_v_value, PyObject *__pyx_v_name) { + PyObject *__pyx_v_v = NULL; + PyObject *__pyx_v_res = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + Py_ssize_t __pyx_t_2; + PyObject *(*__pyx_t_3)(PyObject *); + PyObject *__pyx_t_4 = NULL; + int __pyx_t_5; + PyObject *__pyx_t_6 = NULL; + int __pyx_t_7; + int __pyx_t_8; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__new__", 1); + + /* "EnumBase":50 + * class __Pyx_FlagBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): + * for v in cls: # <<<<<<<<<<<<<< + * if v == value: + * return v + */ + if (likely(PyList_CheckExact(__pyx_v_cls)) || PyTuple_CheckExact(__pyx_v_cls)) { + __pyx_t_1 = __pyx_v_cls; __Pyx_INCREF(__pyx_t_1); + __pyx_t_2 = 0; + __pyx_t_3 = NULL; + } else { + __pyx_t_2 = -1; __pyx_t_1 = PyObject_GetIter(__pyx_v_cls); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 50, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 50, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_3)) { + if (likely(PyList_CheckExact(__pyx_t_1))) { + { + Py_ssize_t __pyx_temp = __Pyx_PyList_GET_SIZE(__pyx_t_1); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 50, __pyx_L1_error) + #endif + if (__pyx_t_2 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyList_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(1, 50, __pyx_L1_error) + #else + __pyx_t_4 = __Pyx_PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 50, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } else { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_1); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 50, __pyx_L1_error) + #endif + if (__pyx_t_2 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyTuple_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(1, 50, __pyx_L1_error) + #else + __pyx_t_4 = __Pyx_PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 50, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } + } else { + __pyx_t_4 = __pyx_t_3(__pyx_t_1); + if (unlikely(!__pyx_t_4)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(1, 50, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_4); + } + __Pyx_XDECREF_SET(__pyx_v_v, __pyx_t_4); + __pyx_t_4 = 0; + + /* "EnumBase":51 + * def __new__(cls, value, name=None): + * for v in cls: + * if v == value: # <<<<<<<<<<<<<< + * return v + * res = int.__new__(cls, value) + */ + __pyx_t_4 = PyObject_RichCompare(__pyx_v_v, __pyx_v_value, Py_EQ); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 51, __pyx_L1_error) + __pyx_t_5 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_5 < 0))) __PYX_ERR(1, 51, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (__pyx_t_5) { + + /* "EnumBase":52 + * for v in cls: + * if v == value: + * return v # <<<<<<<<<<<<<< + * res = int.__new__(cls, value) + * if name is None: + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_v); + __pyx_r = __pyx_v_v; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + goto __pyx_L0; + + /* "EnumBase":51 + * def __new__(cls, value, name=None): + * for v in cls: + * if v == value: # <<<<<<<<<<<<<< + * return v + * res = int.__new__(cls, value) + */ + } + + /* "EnumBase":50 + * class __Pyx_FlagBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): + * for v in cls: # <<<<<<<<<<<<<< + * if v == value: + * return v + */ + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "EnumBase":53 + * if v == value: + * return v + * res = int.__new__(cls, value) # <<<<<<<<<<<<<< + * if name is None: + * + */ + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(((PyObject *)(&PyInt_Type)), __pyx_n_s_new); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 53, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_6 = NULL; + __pyx_t_7 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_4))) { + __pyx_t_6 = PyMethod_GET_SELF(__pyx_t_4); + if (likely(__pyx_t_6)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_4); + __Pyx_INCREF(__pyx_t_6); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_4, function); + __pyx_t_7 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_6, __pyx_v_cls, __pyx_v_value}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_7, 2+__pyx_t_7); + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 53, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + __pyx_v_res = __pyx_t_1; + __pyx_t_1 = 0; + + /* "EnumBase":54 + * return v + * res = int.__new__(cls, value) + * if name is None: # <<<<<<<<<<<<<< + * + * res.name = "" + */ + __pyx_t_5 = (__pyx_v_name == Py_None); + if (__pyx_t_5) { + + /* "EnumBase":56 + * if name is None: + * + * res.name = "" # <<<<<<<<<<<<<< + * else: + * res.name = name + */ + if (__Pyx_PyObject_SetAttrStr(__pyx_v_res, __pyx_n_s_name, __pyx_kp_s_) < 0) __PYX_ERR(1, 56, __pyx_L1_error) + + /* "EnumBase":54 + * return v + * res = int.__new__(cls, value) + * if name is None: # <<<<<<<<<<<<<< + * + * res.name = "" + */ + goto __pyx_L7; + } + + /* "EnumBase":58 + * res.name = "" + * else: + * res.name = name # <<<<<<<<<<<<<< + * setattr(cls, name, res) + * cls.__members__[name] = res + */ + /*else*/ { + if (__Pyx_PyObject_SetAttrStr(__pyx_v_res, __pyx_n_s_name, __pyx_v_name) < 0) __PYX_ERR(1, 58, __pyx_L1_error) + + /* "EnumBase":59 + * else: + * res.name = name + * setattr(cls, name, res) # <<<<<<<<<<<<<< + * cls.__members__[name] = res + * return res + */ + __pyx_t_8 = PyObject_SetAttr(__pyx_v_cls, __pyx_v_name, __pyx_v_res); if (unlikely(__pyx_t_8 == ((int)-1))) __PYX_ERR(1, 59, __pyx_L1_error) + + /* "EnumBase":60 + * res.name = name + * setattr(cls, name, res) + * cls.__members__[name] = res # <<<<<<<<<<<<<< + * return res + * def __repr__(self): + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_cls, __pyx_n_s_members); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 60, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyObject_SetItem(__pyx_t_1, __pyx_v_name, __pyx_v_res) < 0))) __PYX_ERR(1, 60, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_L7:; + + /* "EnumBase":61 + * setattr(cls, name, res) + * cls.__members__[name] = res + * return res # <<<<<<<<<<<<<< + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_res); + __pyx_r = __pyx_v_res; + goto __pyx_L0; + + /* "EnumBase":49 + * cdef object __Pyx_FlagBase + * class __Pyx_FlagBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): # <<<<<<<<<<<<<< + * for v in cls: + * if v == value: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("EnumBase.__Pyx_FlagBase.__new__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_v); + __Pyx_XDECREF(__pyx_v_res); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "EnumBase":62 + * cls.__members__[name] = res + * return res + * def __repr__(self): # <<<<<<<<<<<<<< + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_FlagBase_3__repr__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_8EnumBase_14__Pyx_FlagBase_3__repr__ = {"__repr__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_8EnumBase_14__Pyx_FlagBase_3__repr__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_8EnumBase_14__Pyx_FlagBase_3__repr__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_self = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__repr__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_self,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_self)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 62, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__repr__") < 0)) __PYX_ERR(1, 62, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_self = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__repr__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 62, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("EnumBase.__Pyx_FlagBase.__repr__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_8EnumBase_14__Pyx_FlagBase_2__repr__(__pyx_self, __pyx_v_self); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_8EnumBase_14__Pyx_FlagBase_2__repr__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__repr__", 1); + + /* "EnumBase":63 + * return res + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) # <<<<<<<<<<<<<< + * def __str__(self): + * return "%s.%s" % (self.__class__.__name__, self.name) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_self, __pyx_n_s_class); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 63, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_name_2); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 63, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_self, __pyx_n_s_name); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 63, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 63, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_2)) __PYX_ERR(1, 63, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1)) __PYX_ERR(1, 63, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_self); + __Pyx_GIVEREF(__pyx_v_self); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_v_self)) __PYX_ERR(1, 63, __pyx_L1_error); + __pyx_t_2 = 0; + __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_s_s_d, __pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 63, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "EnumBase":62 + * cls.__members__[name] = res + * return res + * def __repr__(self): # <<<<<<<<<<<<<< + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("EnumBase.__Pyx_FlagBase.__repr__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "EnumBase":64 + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): # <<<<<<<<<<<<<< + * return "%s.%s" % (self.__class__.__name__, self.name) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_FlagBase_5__str__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_8EnumBase_14__Pyx_FlagBase_5__str__ = {"__str__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_8EnumBase_14__Pyx_FlagBase_5__str__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_8EnumBase_14__Pyx_FlagBase_5__str__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_self = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__str__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_self,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_self)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 64, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__str__") < 0)) __PYX_ERR(1, 64, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_self = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__str__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 64, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("EnumBase.__Pyx_FlagBase.__str__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_8EnumBase_14__Pyx_FlagBase_4__str__(__pyx_self, __pyx_v_self); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_8EnumBase_14__Pyx_FlagBase_4__str__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__str__", 1); + + /* "EnumBase":65 + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): + * return "%s.%s" % (self.__class__.__name__, self.name) # <<<<<<<<<<<<<< + * + * if PY_VERSION_HEX >= 0x03060000: + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_self, __pyx_n_s_class); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 65, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_name_2); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 65, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_self, __pyx_n_s_name); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 65, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 65, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_2)) __PYX_ERR(1, 65, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1)) __PYX_ERR(1, 65, __pyx_L1_error); + __pyx_t_2 = 0; + __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_s_s, __pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 65, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "EnumBase":64 + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): # <<<<<<<<<<<<<< + * return "%s.%s" % (self.__class__.__name__, self.name) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("EnumBase.__Pyx_FlagBase.__str__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __pyx_unpickle___Pyx_EnumMeta(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_8EnumBase_1__pyx_unpickle___Pyx_EnumMeta(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_8EnumBase_1__pyx_unpickle___Pyx_EnumMeta = {"__pyx_unpickle___Pyx_EnumMeta", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_8EnumBase_1__pyx_unpickle___Pyx_EnumMeta, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_8EnumBase_1__pyx_unpickle___Pyx_EnumMeta(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v___pyx_type = 0; + long __pyx_v___pyx_checksum; + PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__pyx_unpickle___Pyx_EnumMeta (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_type,&__pyx_n_s_pyx_checksum,&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_type)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_checksum)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle___Pyx_EnumMeta", 1, 3, 3, 1); __PYX_ERR(1, 1, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle___Pyx_EnumMeta", 1, 3, 3, 2); __PYX_ERR(1, 1, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__pyx_unpickle___Pyx_EnumMeta") < 0)) __PYX_ERR(1, 1, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + } + __pyx_v___pyx_type = values[0]; + __pyx_v___pyx_checksum = __Pyx_PyInt_As_long(values[1]); if (unlikely((__pyx_v___pyx_checksum == (long)-1) && PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + __pyx_v___pyx_state = values[2]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle___Pyx_EnumMeta", 1, 3, 3, __pyx_nargs); __PYX_ERR(1, 1, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("EnumBase.__pyx_unpickle___Pyx_EnumMeta", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_8EnumBase___pyx_unpickle___Pyx_EnumMeta(__pyx_self, __pyx_v___pyx_type, __pyx_v___pyx_checksum, __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_8EnumBase___pyx_unpickle___Pyx_EnumMeta(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v___pyx_type, long __pyx_v___pyx_checksum, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_v___pyx_PickleError = 0; + PyObject *__pyx_v___pyx_result = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_unpickle___Pyx_EnumMeta", 1); + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0xe3b0c44, 0xda39a3e, 0xd41d8cd): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0xe3b0c44, 0xda39a3e, 0xd41d8cd) = ())" % __pyx_checksum + */ + __pyx_t_1 = __Pyx_PyInt_From_long(__pyx_v___pyx_checksum); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 4, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = (__Pyx_PySequence_ContainsTF(__pyx_t_1, __pyx_tuple__2, Py_NE)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(1, 4, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (__pyx_t_2) { + + /* "(tree fragment)":5 + * cdef object __pyx_result + * if __pyx_checksum not in (0xe3b0c44, 0xda39a3e, 0xd41d8cd): + * from pickle import PickleError as __pyx_PickleError # <<<<<<<<<<<<<< + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0xe3b0c44, 0xda39a3e, 0xd41d8cd) = ())" % __pyx_checksum + * __pyx_result = __Pyx_EnumMeta.__new__(__pyx_type) + */ + __pyx_t_1 = PyList_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_s_PickleError); + __Pyx_GIVEREF(__pyx_n_s_PickleError); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_s_PickleError)) __PYX_ERR(1, 5, __pyx_L1_error); + __pyx_t_3 = __Pyx_Import(__pyx_n_s_pickle, __pyx_t_1, 0); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_ImportFrom(__pyx_t_3, __pyx_n_s_PickleError); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_t_1); + __pyx_v___pyx_PickleError = __pyx_t_1; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "(tree fragment)":6 + * if __pyx_checksum not in (0xe3b0c44, 0xda39a3e, 0xd41d8cd): + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0xe3b0c44, 0xda39a3e, 0xd41d8cd) = ())" % __pyx_checksum # <<<<<<<<<<<<<< + * __pyx_result = __Pyx_EnumMeta.__new__(__pyx_type) + * if __pyx_state is not None: + */ + __pyx_t_3 = __Pyx_PyInt_From_long(__pyx_v___pyx_checksum); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_Incompatible_checksums_0x_x_vs_0, __pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_v___pyx_PickleError, __pyx_t_1, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(1, 6, __pyx_L1_error) + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0xe3b0c44, 0xda39a3e, 0xd41d8cd): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0xe3b0c44, 0xda39a3e, 0xd41d8cd) = ())" % __pyx_checksum + */ + } + + /* "(tree fragment)":7 + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0xe3b0c44, 0xda39a3e, 0xd41d8cd) = ())" % __pyx_checksum + * __pyx_result = __Pyx_EnumMeta.__new__(__pyx_type) # <<<<<<<<<<<<<< + * if __pyx_state is not None: + * __pyx_unpickle___Pyx_EnumMeta__set_state(<__Pyx_EnumMeta> __pyx_result, __pyx_state) + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_ptype___Pyx_EnumMeta), __pyx_n_s_new); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 7, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = NULL; + __pyx_t_5 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_5 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_4, __pyx_v___pyx_type}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_5, 1+__pyx_t_5); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 7, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_v___pyx_result = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":8 + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0xe3b0c44, 0xda39a3e, 0xd41d8cd) = ())" % __pyx_checksum + * __pyx_result = __Pyx_EnumMeta.__new__(__pyx_type) + * if __pyx_state is not None: # <<<<<<<<<<<<<< + * __pyx_unpickle___Pyx_EnumMeta__set_state(<__Pyx_EnumMeta> __pyx_result, __pyx_state) + * return __pyx_result + */ + __pyx_t_2 = (__pyx_v___pyx_state != Py_None); + if (__pyx_t_2) { + + /* "(tree fragment)":9 + * __pyx_result = __Pyx_EnumMeta.__new__(__pyx_type) + * if __pyx_state is not None: + * __pyx_unpickle___Pyx_EnumMeta__set_state(<__Pyx_EnumMeta> __pyx_result, __pyx_state) # <<<<<<<<<<<<<< + * return __pyx_result + * cdef __pyx_unpickle___Pyx_EnumMeta__set_state(__Pyx_EnumMeta __pyx_result, tuple __pyx_state): + */ + if (!(likely(PyTuple_CheckExact(__pyx_v___pyx_state))||((__pyx_v___pyx_state) == Py_None) || __Pyx_RaiseUnexpectedTypeError("tuple", __pyx_v___pyx_state))) __PYX_ERR(1, 9, __pyx_L1_error) + __pyx_t_1 = __pyx_unpickle___Pyx_EnumMeta__set_state(((struct __pyx_obj___Pyx_EnumMeta *)__pyx_v___pyx_result), ((PyObject*)__pyx_v___pyx_state)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 9, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":8 + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0xe3b0c44, 0xda39a3e, 0xd41d8cd) = ())" % __pyx_checksum + * __pyx_result = __Pyx_EnumMeta.__new__(__pyx_type) + * if __pyx_state is not None: # <<<<<<<<<<<<<< + * __pyx_unpickle___Pyx_EnumMeta__set_state(<__Pyx_EnumMeta> __pyx_result, __pyx_state) + * return __pyx_result + */ + } + + /* "(tree fragment)":10 + * if __pyx_state is not None: + * __pyx_unpickle___Pyx_EnumMeta__set_state(<__Pyx_EnumMeta> __pyx_result, __pyx_state) + * return __pyx_result # <<<<<<<<<<<<<< + * cdef __pyx_unpickle___Pyx_EnumMeta__set_state(__Pyx_EnumMeta __pyx_result, tuple __pyx_state): + * if len(__pyx_state) > 0 and hasattr(__pyx_result, '__dict__'): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v___pyx_result); + __pyx_r = __pyx_v___pyx_result; + goto __pyx_L0; + + /* "(tree fragment)":1 + * def __pyx_unpickle___Pyx_EnumMeta(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("EnumBase.__pyx_unpickle___Pyx_EnumMeta", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v___pyx_PickleError); + __Pyx_XDECREF(__pyx_v___pyx_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":11 + * __pyx_unpickle___Pyx_EnumMeta__set_state(<__Pyx_EnumMeta> __pyx_result, __pyx_state) + * return __pyx_result + * cdef __pyx_unpickle___Pyx_EnumMeta__set_state(__Pyx_EnumMeta __pyx_result, tuple __pyx_state): # <<<<<<<<<<<<<< + * if len(__pyx_state) > 0 and hasattr(__pyx_result, '__dict__'): + * __pyx_result.__dict__.update(__pyx_state[0]) + */ + +static PyObject *__pyx_unpickle___Pyx_EnumMeta__set_state(struct __pyx_obj___Pyx_EnumMeta *__pyx_v___pyx_result, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + Py_ssize_t __pyx_t_2; + int __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + int __pyx_t_8; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_unpickle___Pyx_EnumMeta__set_state", 1); + + /* "(tree fragment)":12 + * return __pyx_result + * cdef __pyx_unpickle___Pyx_EnumMeta__set_state(__Pyx_EnumMeta __pyx_result, tuple __pyx_state): + * if len(__pyx_state) > 0 and hasattr(__pyx_result, '__dict__'): # <<<<<<<<<<<<<< + * __pyx_result.__dict__.update(__pyx_state[0]) + */ + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); + __PYX_ERR(1, 12, __pyx_L1_error) + } + __pyx_t_2 = __Pyx_PyTuple_GET_SIZE(__pyx_v___pyx_state); if (unlikely(__pyx_t_2 == ((Py_ssize_t)-1))) __PYX_ERR(1, 12, __pyx_L1_error) + __pyx_t_3 = (__pyx_t_2 > 0); + if (__pyx_t_3) { + } else { + __pyx_t_1 = __pyx_t_3; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_3 = __Pyx_HasAttr(((PyObject *)__pyx_v___pyx_result), __pyx_n_s_dict); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 12, __pyx_L1_error) + __pyx_t_1 = __pyx_t_3; + __pyx_L4_bool_binop_done:; + if (__pyx_t_1) { + + /* "(tree fragment)":13 + * cdef __pyx_unpickle___Pyx_EnumMeta__set_state(__Pyx_EnumMeta __pyx_result, tuple __pyx_state): + * if len(__pyx_state) > 0 and hasattr(__pyx_result, '__dict__'): + * __pyx_result.__dict__.update(__pyx_state[0]) # <<<<<<<<<<<<<< + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v___pyx_result), __pyx_n_s_dict); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_update); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 13, __pyx_L1_error) + } + __pyx_t_5 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_7 = NULL; + __pyx_t_8 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_6))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_6); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_6); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_6, function); + __pyx_t_8 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_7, __pyx_t_5}; + __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_6, __pyx_callargs+1-__pyx_t_8, 1+__pyx_t_8); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "(tree fragment)":12 + * return __pyx_result + * cdef __pyx_unpickle___Pyx_EnumMeta__set_state(__Pyx_EnumMeta __pyx_result, tuple __pyx_state): + * if len(__pyx_state) > 0 and hasattr(__pyx_result, '__dict__'): # <<<<<<<<<<<<<< + * __pyx_result.__dict__.update(__pyx_state[0]) + */ + } + + /* "(tree fragment)":11 + * __pyx_unpickle___Pyx_EnumMeta__set_state(<__Pyx_EnumMeta> __pyx_result, __pyx_state) + * return __pyx_result + * cdef __pyx_unpickle___Pyx_EnumMeta__set_state(__Pyx_EnumMeta __pyx_result, tuple __pyx_state): # <<<<<<<<<<<<<< + * if len(__pyx_state) > 0 and hasattr(__pyx_result, '__dict__'): + * __pyx_result.__dict__.update(__pyx_state[0]) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("EnumBase.__pyx_unpickle___Pyx_EnumMeta__set_state", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":131 + * cdef bint dtype_is_object + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, # <<<<<<<<<<<<<< + * mode="c", bint allocate_buffer=True): + * + */ + +/* Python wrapper */ +static int __pyx_array___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_array___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_shape = 0; + Py_ssize_t __pyx_v_itemsize; + PyObject *__pyx_v_format = 0; + PyObject *__pyx_v_mode = 0; + int __pyx_v_allocate_buffer; + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[5] = {0,0,0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_shape,&__pyx_n_s_itemsize,&__pyx_n_s_format,&__pyx_n_s_mode,&__pyx_n_s_allocate_buffer,0}; + values[3] = __Pyx_Arg_NewRef_VARARGS(((PyObject *)__pyx_n_s_c)); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 5: values[4] = __Pyx_Arg_VARARGS(__pyx_args, 4); + CYTHON_FALLTHROUGH; + case 4: values[3] = __Pyx_Arg_VARARGS(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_shape)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_itemsize)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 3, 5, 1); __PYX_ERR(1, 131, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_format)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 3, 5, 2); __PYX_ERR(1, 131, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 3: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_mode); + if (value) { values[3] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 4: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_allocate_buffer); + if (value) { values[4] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(1, 131, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 5: values[4] = __Pyx_Arg_VARARGS(__pyx_args, 4); + CYTHON_FALLTHROUGH; + case 4: values[3] = __Pyx_Arg_VARARGS(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_shape = ((PyObject*)values[0]); + __pyx_v_itemsize = __Pyx_PyIndex_AsSsize_t(values[1]); if (unlikely((__pyx_v_itemsize == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + __pyx_v_format = values[2]; + __pyx_v_mode = values[3]; + if (values[4]) { + __pyx_v_allocate_buffer = __Pyx_PyObject_IsTrue(values[4]); if (unlikely((__pyx_v_allocate_buffer == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 132, __pyx_L3_error) + } else { + + /* "View.MemoryView":132 + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, + * mode="c", bint allocate_buffer=True): # <<<<<<<<<<<<<< + * + * cdef int idx + */ + __pyx_v_allocate_buffer = ((int)1); + } + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 3, 5, __pyx_nargs); __PYX_ERR(1, 131, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.array.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_shape), (&PyTuple_Type), 1, "shape", 1))) __PYX_ERR(1, 131, __pyx_L1_error) + if (unlikely(((PyObject *)__pyx_v_format) == Py_None)) { + PyErr_Format(PyExc_TypeError, "Argument '%.200s' must not be None", "format"); __PYX_ERR(1, 131, __pyx_L1_error) + } + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array___cinit__(((struct __pyx_array_obj *)__pyx_v_self), __pyx_v_shape, __pyx_v_itemsize, __pyx_v_format, __pyx_v_mode, __pyx_v_allocate_buffer); + + /* "View.MemoryView":131 + * cdef bint dtype_is_object + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, # <<<<<<<<<<<<<< + * mode="c", bint allocate_buffer=True): + * + */ + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = -1; + __pyx_L0:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array___cinit__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_shape, Py_ssize_t __pyx_v_itemsize, PyObject *__pyx_v_format, PyObject *__pyx_v_mode, int __pyx_v_allocate_buffer) { + int __pyx_v_idx; + Py_ssize_t __pyx_v_dim; + char __pyx_v_order; + int __pyx_r; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + int __pyx_t_7; + char *__pyx_t_8; + Py_ssize_t __pyx_t_9; + Py_UCS4 __pyx_t_10; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__cinit__", 0); + __Pyx_INCREF(__pyx_v_format); + + /* "View.MemoryView":137 + * cdef Py_ssize_t dim + * + * self.ndim = len(shape) # <<<<<<<<<<<<<< + * self.itemsize = itemsize + * + */ + if (unlikely(__pyx_v_shape == Py_None)) { + PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); + __PYX_ERR(1, 137, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_PyTuple_GET_SIZE(__pyx_v_shape); if (unlikely(__pyx_t_1 == ((Py_ssize_t)-1))) __PYX_ERR(1, 137, __pyx_L1_error) + __pyx_v_self->ndim = ((int)__pyx_t_1); + + /* "View.MemoryView":138 + * + * self.ndim = len(shape) + * self.itemsize = itemsize # <<<<<<<<<<<<<< + * + * if not self.ndim: + */ + __pyx_v_self->itemsize = __pyx_v_itemsize; + + /* "View.MemoryView":140 + * self.itemsize = itemsize + * + * if not self.ndim: # <<<<<<<<<<<<<< + * raise ValueError, "Empty shape tuple for cython.array" + * + */ + __pyx_t_2 = (!(__pyx_v_self->ndim != 0)); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":141 + * + * if not self.ndim: + * raise ValueError, "Empty shape tuple for cython.array" # <<<<<<<<<<<<<< + * + * if itemsize <= 0: + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Empty_shape_tuple_for_cython_arr, 0, 0); + __PYX_ERR(1, 141, __pyx_L1_error) + + /* "View.MemoryView":140 + * self.itemsize = itemsize + * + * if not self.ndim: # <<<<<<<<<<<<<< + * raise ValueError, "Empty shape tuple for cython.array" + * + */ + } + + /* "View.MemoryView":143 + * raise ValueError, "Empty shape tuple for cython.array" + * + * if itemsize <= 0: # <<<<<<<<<<<<<< + * raise ValueError, "itemsize <= 0 for cython.array" + * + */ + __pyx_t_2 = (__pyx_v_itemsize <= 0); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":144 + * + * if itemsize <= 0: + * raise ValueError, "itemsize <= 0 for cython.array" # <<<<<<<<<<<<<< + * + * if not isinstance(format, bytes): + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_itemsize_0_for_cython_array, 0, 0); + __PYX_ERR(1, 144, __pyx_L1_error) + + /* "View.MemoryView":143 + * raise ValueError, "Empty shape tuple for cython.array" + * + * if itemsize <= 0: # <<<<<<<<<<<<<< + * raise ValueError, "itemsize <= 0 for cython.array" + * + */ + } + + /* "View.MemoryView":146 + * raise ValueError, "itemsize <= 0 for cython.array" + * + * if not isinstance(format, bytes): # <<<<<<<<<<<<<< + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string + */ + __pyx_t_2 = PyBytes_Check(__pyx_v_format); + __pyx_t_3 = (!__pyx_t_2); + if (__pyx_t_3) { + + /* "View.MemoryView":147 + * + * if not isinstance(format, bytes): + * format = format.encode('ASCII') # <<<<<<<<<<<<<< + * self._format = format # keep a reference to the byte string + * self.format = self._format + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_format, __pyx_n_s_encode); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 147, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = NULL; + __pyx_t_7 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_6 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_6)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_6); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_7 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_6, __pyx_n_s_ASCII}; + __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_7, 1+__pyx_t_7); + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 147, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + __Pyx_DECREF_SET(__pyx_v_format, __pyx_t_4); + __pyx_t_4 = 0; + + /* "View.MemoryView":146 + * raise ValueError, "itemsize <= 0 for cython.array" + * + * if not isinstance(format, bytes): # <<<<<<<<<<<<<< + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string + */ + } + + /* "View.MemoryView":148 + * if not isinstance(format, bytes): + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string # <<<<<<<<<<<<<< + * self.format = self._format + * + */ + if (!(likely(PyBytes_CheckExact(__pyx_v_format))||((__pyx_v_format) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_v_format))) __PYX_ERR(1, 148, __pyx_L1_error) + __pyx_t_4 = __pyx_v_format; + __Pyx_INCREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + __Pyx_GOTREF(__pyx_v_self->_format); + __Pyx_DECREF(__pyx_v_self->_format); + __pyx_v_self->_format = ((PyObject*)__pyx_t_4); + __pyx_t_4 = 0; + + /* "View.MemoryView":149 + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string + * self.format = self._format # <<<<<<<<<<<<<< + * + * + */ + if (unlikely(__pyx_v_self->_format == Py_None)) { + PyErr_SetString(PyExc_TypeError, "expected bytes, NoneType found"); + __PYX_ERR(1, 149, __pyx_L1_error) + } + __pyx_t_8 = __Pyx_PyBytes_AsWritableString(__pyx_v_self->_format); if (unlikely((!__pyx_t_8) && PyErr_Occurred())) __PYX_ERR(1, 149, __pyx_L1_error) + __pyx_v_self->format = __pyx_t_8; + + /* "View.MemoryView":152 + * + * + * self._shape = PyObject_Malloc(sizeof(Py_ssize_t)*self.ndim*2) # <<<<<<<<<<<<<< + * self._strides = self._shape + self.ndim + * + */ + __pyx_v_self->_shape = ((Py_ssize_t *)PyObject_Malloc((((sizeof(Py_ssize_t)) * __pyx_v_self->ndim) * 2))); + + /* "View.MemoryView":153 + * + * self._shape = PyObject_Malloc(sizeof(Py_ssize_t)*self.ndim*2) + * self._strides = self._shape + self.ndim # <<<<<<<<<<<<<< + * + * if not self._shape: + */ + __pyx_v_self->_strides = (__pyx_v_self->_shape + __pyx_v_self->ndim); + + /* "View.MemoryView":155 + * self._strides = self._shape + self.ndim + * + * if not self._shape: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate shape and strides." + * + */ + __pyx_t_3 = (!(__pyx_v_self->_shape != 0)); + if (unlikely(__pyx_t_3)) { + + /* "View.MemoryView":156 + * + * if not self._shape: + * raise MemoryError, "unable to allocate shape and strides." # <<<<<<<<<<<<<< + * + * + */ + __Pyx_Raise(__pyx_builtin_MemoryError, __pyx_kp_s_unable_to_allocate_shape_and_str, 0, 0); + __PYX_ERR(1, 156, __pyx_L1_error) + + /* "View.MemoryView":155 + * self._strides = self._shape + self.ndim + * + * if not self._shape: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate shape and strides." + * + */ + } + + /* "View.MemoryView":159 + * + * + * for idx, dim in enumerate(shape): # <<<<<<<<<<<<<< + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + */ + __pyx_t_7 = 0; + __pyx_t_4 = __pyx_v_shape; __Pyx_INCREF(__pyx_t_4); + __pyx_t_1 = 0; + for (;;) { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_4); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 159, __pyx_L1_error) + #endif + if (__pyx_t_1 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_5 = PyTuple_GET_ITEM(__pyx_t_4, __pyx_t_1); __Pyx_INCREF(__pyx_t_5); __pyx_t_1++; if (unlikely((0 < 0))) __PYX_ERR(1, 159, __pyx_L1_error) + #else + __pyx_t_5 = __Pyx_PySequence_ITEM(__pyx_t_4, __pyx_t_1); __pyx_t_1++; if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 159, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + #endif + __pyx_t_9 = __Pyx_PyIndex_AsSsize_t(__pyx_t_5); if (unlikely((__pyx_t_9 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 159, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_v_dim = __pyx_t_9; + __pyx_v_idx = __pyx_t_7; + __pyx_t_7 = (__pyx_t_7 + 1); + + /* "View.MemoryView":160 + * + * for idx, dim in enumerate(shape): + * if dim <= 0: # <<<<<<<<<<<<<< + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + * self._shape[idx] = dim + */ + __pyx_t_3 = (__pyx_v_dim <= 0); + if (unlikely(__pyx_t_3)) { + + /* "View.MemoryView":161 + * for idx, dim in enumerate(shape): + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." # <<<<<<<<<<<<<< + * self._shape[idx] = dim + * + */ + __pyx_t_5 = PyTuple_New(5); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_9 = 0; + __pyx_t_10 = 127; + __Pyx_INCREF(__pyx_kp_u_Invalid_shape_in_axis); + __pyx_t_9 += 22; + __Pyx_GIVEREF(__pyx_kp_u_Invalid_shape_in_axis); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_kp_u_Invalid_shape_in_axis); + __pyx_t_6 = __Pyx_PyUnicode_From_int(__pyx_v_idx, 0, ' ', 'd'); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_9 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_6); + __Pyx_GIVEREF(__pyx_t_6); + PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_6); + __pyx_t_6 = 0; + __Pyx_INCREF(__pyx_kp_u__4); + __pyx_t_9 += 2; + __Pyx_GIVEREF(__pyx_kp_u__4); + PyTuple_SET_ITEM(__pyx_t_5, 2, __pyx_kp_u__4); + __pyx_t_6 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_dim, 0, ' ', 'd'); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_9 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_6); + __Pyx_GIVEREF(__pyx_t_6); + PyTuple_SET_ITEM(__pyx_t_5, 3, __pyx_t_6); + __pyx_t_6 = 0; + __Pyx_INCREF(__pyx_kp_u__3); + __pyx_t_9 += 1; + __Pyx_GIVEREF(__pyx_kp_u__3); + PyTuple_SET_ITEM(__pyx_t_5, 4, __pyx_kp_u__3); + __pyx_t_6 = __Pyx_PyUnicode_Join(__pyx_t_5, 5, __pyx_t_9, __pyx_t_10); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_t_6, 0, 0); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __PYX_ERR(1, 161, __pyx_L1_error) + + /* "View.MemoryView":160 + * + * for idx, dim in enumerate(shape): + * if dim <= 0: # <<<<<<<<<<<<<< + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + * self._shape[idx] = dim + */ + } + + /* "View.MemoryView":162 + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + * self._shape[idx] = dim # <<<<<<<<<<<<<< + * + * cdef char order + */ + (__pyx_v_self->_shape[__pyx_v_idx]) = __pyx_v_dim; + + /* "View.MemoryView":159 + * + * + * for idx, dim in enumerate(shape): # <<<<<<<<<<<<<< + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + */ + } + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "View.MemoryView":165 + * + * cdef char order + * if mode == 'c': # <<<<<<<<<<<<<< + * order = b'C' + * self.mode = u'c' + */ + __pyx_t_3 = (__Pyx_PyString_Equals(__pyx_v_mode, __pyx_n_s_c, Py_EQ)); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(1, 165, __pyx_L1_error) + if (__pyx_t_3) { + + /* "View.MemoryView":166 + * cdef char order + * if mode == 'c': + * order = b'C' # <<<<<<<<<<<<<< + * self.mode = u'c' + * elif mode == 'fortran': + */ + __pyx_v_order = 'C'; + + /* "View.MemoryView":167 + * if mode == 'c': + * order = b'C' + * self.mode = u'c' # <<<<<<<<<<<<<< + * elif mode == 'fortran': + * order = b'F' + */ + __Pyx_INCREF(__pyx_n_u_c); + __Pyx_GIVEREF(__pyx_n_u_c); + __Pyx_GOTREF(__pyx_v_self->mode); + __Pyx_DECREF(__pyx_v_self->mode); + __pyx_v_self->mode = __pyx_n_u_c; + + /* "View.MemoryView":165 + * + * cdef char order + * if mode == 'c': # <<<<<<<<<<<<<< + * order = b'C' + * self.mode = u'c' + */ + goto __pyx_L11; + } + + /* "View.MemoryView":168 + * order = b'C' + * self.mode = u'c' + * elif mode == 'fortran': # <<<<<<<<<<<<<< + * order = b'F' + * self.mode = u'fortran' + */ + __pyx_t_3 = (__Pyx_PyString_Equals(__pyx_v_mode, __pyx_n_s_fortran, Py_EQ)); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(1, 168, __pyx_L1_error) + if (likely(__pyx_t_3)) { + + /* "View.MemoryView":169 + * self.mode = u'c' + * elif mode == 'fortran': + * order = b'F' # <<<<<<<<<<<<<< + * self.mode = u'fortran' + * else: + */ + __pyx_v_order = 'F'; + + /* "View.MemoryView":170 + * elif mode == 'fortran': + * order = b'F' + * self.mode = u'fortran' # <<<<<<<<<<<<<< + * else: + * raise ValueError, f"Invalid mode, expected 'c' or 'fortran', got {mode}" + */ + __Pyx_INCREF(__pyx_n_u_fortran); + __Pyx_GIVEREF(__pyx_n_u_fortran); + __Pyx_GOTREF(__pyx_v_self->mode); + __Pyx_DECREF(__pyx_v_self->mode); + __pyx_v_self->mode = __pyx_n_u_fortran; + + /* "View.MemoryView":168 + * order = b'C' + * self.mode = u'c' + * elif mode == 'fortran': # <<<<<<<<<<<<<< + * order = b'F' + * self.mode = u'fortran' + */ + goto __pyx_L11; + } + + /* "View.MemoryView":172 + * self.mode = u'fortran' + * else: + * raise ValueError, f"Invalid mode, expected 'c' or 'fortran', got {mode}" # <<<<<<<<<<<<<< + * + * self.len = fill_contig_strides_array(self._shape, self._strides, itemsize, self.ndim, order) + */ + /*else*/ { + __pyx_t_4 = __Pyx_PyObject_FormatSimple(__pyx_v_mode, __pyx_empty_unicode); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 172, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_6 = __Pyx_PyUnicode_Concat(__pyx_kp_u_Invalid_mode_expected_c_or_fortr, __pyx_t_4); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 172, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_t_6, 0, 0); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __PYX_ERR(1, 172, __pyx_L1_error) + } + __pyx_L11:; + + /* "View.MemoryView":174 + * raise ValueError, f"Invalid mode, expected 'c' or 'fortran', got {mode}" + * + * self.len = fill_contig_strides_array(self._shape, self._strides, itemsize, self.ndim, order) # <<<<<<<<<<<<<< + * + * self.free_data = allocate_buffer + */ + __pyx_v_self->len = __pyx_fill_contig_strides_array(__pyx_v_self->_shape, __pyx_v_self->_strides, __pyx_v_itemsize, __pyx_v_self->ndim, __pyx_v_order); + + /* "View.MemoryView":176 + * self.len = fill_contig_strides_array(self._shape, self._strides, itemsize, self.ndim, order) + * + * self.free_data = allocate_buffer # <<<<<<<<<<<<<< + * self.dtype_is_object = format == b'O' + * + */ + __pyx_v_self->free_data = __pyx_v_allocate_buffer; + + /* "View.MemoryView":177 + * + * self.free_data = allocate_buffer + * self.dtype_is_object = format == b'O' # <<<<<<<<<<<<<< + * + * if allocate_buffer: + */ + __pyx_t_6 = PyObject_RichCompare(__pyx_v_format, __pyx_n_b_O, Py_EQ); __Pyx_XGOTREF(__pyx_t_6); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 177, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_IsTrue(__pyx_t_6); if (unlikely((__pyx_t_3 == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 177, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __pyx_v_self->dtype_is_object = __pyx_t_3; + + /* "View.MemoryView":179 + * self.dtype_is_object = format == b'O' + * + * if allocate_buffer: # <<<<<<<<<<<<<< + * _allocate_buffer(self) + * + */ + if (__pyx_v_allocate_buffer) { + + /* "View.MemoryView":180 + * + * if allocate_buffer: + * _allocate_buffer(self) # <<<<<<<<<<<<<< + * + * @cname('getbuffer') + */ + __pyx_t_7 = __pyx_array_allocate_buffer(__pyx_v_self); if (unlikely(__pyx_t_7 == ((int)-1))) __PYX_ERR(1, 180, __pyx_L1_error) + + /* "View.MemoryView":179 + * self.dtype_is_object = format == b'O' + * + * if allocate_buffer: # <<<<<<<<<<<<<< + * _allocate_buffer(self) + * + */ + } + + /* "View.MemoryView":131 + * cdef bint dtype_is_object + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, # <<<<<<<<<<<<<< + * mode="c", bint allocate_buffer=True): + * + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("View.MemoryView.array.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_format); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":182 + * _allocate_buffer(self) + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + */ + +/* Python wrapper */ +CYTHON_UNUSED static int __pyx_array_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +CYTHON_UNUSED static int __pyx_array_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getbuffer__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_2__getbuffer__(((struct __pyx_array_obj *)__pyx_v_self), ((Py_buffer *)__pyx_v_info), ((int)__pyx_v_flags)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_2__getbuffer__(struct __pyx_array_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + int __pyx_v_bufmode; + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + char *__pyx_t_2; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + Py_ssize_t *__pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + if (unlikely(__pyx_v_info == NULL)) { + PyErr_SetString(PyExc_BufferError, "PyObject_GetBuffer: view==NULL argument is obsolete"); + return -1; + } + __Pyx_RefNannySetupContext("__getbuffer__", 0); + __pyx_v_info->obj = Py_None; __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(__pyx_v_info->obj); + + /* "View.MemoryView":184 + * @cname('getbuffer') + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 # <<<<<<<<<<<<<< + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": + */ + __pyx_v_bufmode = -1; + + /* "View.MemoryView":185 + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): # <<<<<<<<<<<<<< + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + */ + __pyx_t_1 = ((__pyx_v_flags & ((PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS) | PyBUF_ANY_CONTIGUOUS)) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":186 + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": # <<<<<<<<<<<<<< + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": + */ + __pyx_t_1 = (__Pyx_PyUnicode_Equals(__pyx_v_self->mode, __pyx_n_u_c, Py_EQ)); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 186, __pyx_L1_error) + if (__pyx_t_1) { + + /* "View.MemoryView":187 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS # <<<<<<<<<<<<<< + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + */ + __pyx_v_bufmode = (PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS); + + /* "View.MemoryView":186 + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": # <<<<<<<<<<<<<< + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": + */ + goto __pyx_L4; + } + + /* "View.MemoryView":188 + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": # <<<<<<<<<<<<<< + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): + */ + __pyx_t_1 = (__Pyx_PyUnicode_Equals(__pyx_v_self->mode, __pyx_n_u_fortran, Py_EQ)); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 188, __pyx_L1_error) + if (__pyx_t_1) { + + /* "View.MemoryView":189 + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS # <<<<<<<<<<<<<< + * if not (flags & bufmode): + * raise ValueError, "Can only create a buffer that is contiguous in memory." + */ + __pyx_v_bufmode = (PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS); + + /* "View.MemoryView":188 + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": # <<<<<<<<<<<<<< + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): + */ + } + __pyx_L4:; + + /* "View.MemoryView":190 + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): # <<<<<<<<<<<<<< + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data + */ + __pyx_t_1 = (!((__pyx_v_flags & __pyx_v_bufmode) != 0)); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":191 + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): + * raise ValueError, "Can only create a buffer that is contiguous in memory." # <<<<<<<<<<<<<< + * info.buf = self.data + * info.len = self.len + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Can_only_create_a_buffer_that_is, 0, 0); + __PYX_ERR(1, 191, __pyx_L1_error) + + /* "View.MemoryView":190 + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): # <<<<<<<<<<<<<< + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data + */ + } + + /* "View.MemoryView":185 + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): # <<<<<<<<<<<<<< + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + */ + } + + /* "View.MemoryView":192 + * if not (flags & bufmode): + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data # <<<<<<<<<<<<<< + * info.len = self.len + * + */ + __pyx_t_2 = __pyx_v_self->data; + __pyx_v_info->buf = __pyx_t_2; + + /* "View.MemoryView":193 + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data + * info.len = self.len # <<<<<<<<<<<<<< + * + * if flags & PyBUF_STRIDES: + */ + __pyx_t_3 = __pyx_v_self->len; + __pyx_v_info->len = __pyx_t_3; + + /* "View.MemoryView":195 + * info.len = self.len + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.ndim = self.ndim + * info.shape = self._shape + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_STRIDES) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":196 + * + * if flags & PyBUF_STRIDES: + * info.ndim = self.ndim # <<<<<<<<<<<<<< + * info.shape = self._shape + * info.strides = self._strides + */ + __pyx_t_4 = __pyx_v_self->ndim; + __pyx_v_info->ndim = __pyx_t_4; + + /* "View.MemoryView":197 + * if flags & PyBUF_STRIDES: + * info.ndim = self.ndim + * info.shape = self._shape # <<<<<<<<<<<<<< + * info.strides = self._strides + * else: + */ + __pyx_t_5 = __pyx_v_self->_shape; + __pyx_v_info->shape = __pyx_t_5; + + /* "View.MemoryView":198 + * info.ndim = self.ndim + * info.shape = self._shape + * info.strides = self._strides # <<<<<<<<<<<<<< + * else: + * info.ndim = 1 + */ + __pyx_t_5 = __pyx_v_self->_strides; + __pyx_v_info->strides = __pyx_t_5; + + /* "View.MemoryView":195 + * info.len = self.len + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.ndim = self.ndim + * info.shape = self._shape + */ + goto __pyx_L6; + } + + /* "View.MemoryView":200 + * info.strides = self._strides + * else: + * info.ndim = 1 # <<<<<<<<<<<<<< + * info.shape = &self.len if flags & PyBUF_ND else NULL + * info.strides = NULL + */ + /*else*/ { + __pyx_v_info->ndim = 1; + + /* "View.MemoryView":201 + * else: + * info.ndim = 1 + * info.shape = &self.len if flags & PyBUF_ND else NULL # <<<<<<<<<<<<<< + * info.strides = NULL + * + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_ND) != 0); + if (__pyx_t_1) { + __pyx_t_5 = (&__pyx_v_self->len); + } else { + __pyx_t_5 = NULL; + } + __pyx_v_info->shape = __pyx_t_5; + + /* "View.MemoryView":202 + * info.ndim = 1 + * info.shape = &self.len if flags & PyBUF_ND else NULL + * info.strides = NULL # <<<<<<<<<<<<<< + * + * info.suboffsets = NULL + */ + __pyx_v_info->strides = NULL; + } + __pyx_L6:; + + /* "View.MemoryView":204 + * info.strides = NULL + * + * info.suboffsets = NULL # <<<<<<<<<<<<<< + * info.itemsize = self.itemsize + * info.readonly = 0 + */ + __pyx_v_info->suboffsets = NULL; + + /* "View.MemoryView":205 + * + * info.suboffsets = NULL + * info.itemsize = self.itemsize # <<<<<<<<<<<<<< + * info.readonly = 0 + * info.format = self.format if flags & PyBUF_FORMAT else NULL + */ + __pyx_t_3 = __pyx_v_self->itemsize; + __pyx_v_info->itemsize = __pyx_t_3; + + /* "View.MemoryView":206 + * info.suboffsets = NULL + * info.itemsize = self.itemsize + * info.readonly = 0 # <<<<<<<<<<<<<< + * info.format = self.format if flags & PyBUF_FORMAT else NULL + * info.obj = self + */ + __pyx_v_info->readonly = 0; + + /* "View.MemoryView":207 + * info.itemsize = self.itemsize + * info.readonly = 0 + * info.format = self.format if flags & PyBUF_FORMAT else NULL # <<<<<<<<<<<<<< + * info.obj = self + * + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_FORMAT) != 0); + if (__pyx_t_1) { + __pyx_t_2 = __pyx_v_self->format; + } else { + __pyx_t_2 = NULL; + } + __pyx_v_info->format = __pyx_t_2; + + /* "View.MemoryView":208 + * info.readonly = 0 + * info.format = self.format if flags & PyBUF_FORMAT else NULL + * info.obj = self # <<<<<<<<<<<<<< + * + * def __dealloc__(array self): + */ + __Pyx_INCREF((PyObject *)__pyx_v_self); + __Pyx_GIVEREF((PyObject *)__pyx_v_self); + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); + __pyx_v_info->obj = ((PyObject *)__pyx_v_self); + + /* "View.MemoryView":182 + * _allocate_buffer(self) + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.array.__getbuffer__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + if (__pyx_v_info->obj != NULL) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + goto __pyx_L2; + __pyx_L0:; + if (__pyx_v_info->obj == Py_None) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + __pyx_L2:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":210 + * info.obj = self + * + * def __dealloc__(array self): # <<<<<<<<<<<<<< + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + */ + +/* Python wrapper */ +static void __pyx_array___dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_array___dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_array___pyx_pf_15View_dot_MemoryView_5array_4__dealloc__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_array___pyx_pf_15View_dot_MemoryView_5array_4__dealloc__(struct __pyx_array_obj *__pyx_v_self) { + int __pyx_t_1; + int __pyx_t_2; + + /* "View.MemoryView":211 + * + * def __dealloc__(array self): + * if self.callback_free_data != NULL: # <<<<<<<<<<<<<< + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + */ + __pyx_t_1 = (__pyx_v_self->callback_free_data != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":212 + * def __dealloc__(array self): + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) # <<<<<<<<<<<<<< + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: + */ + __pyx_v_self->callback_free_data(__pyx_v_self->data); + + /* "View.MemoryView":211 + * + * def __dealloc__(array self): + * if self.callback_free_data != NULL: # <<<<<<<<<<<<<< + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":213 + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: # <<<<<<<<<<<<<< + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + */ + if (__pyx_v_self->free_data) { + } else { + __pyx_t_1 = __pyx_v_self->free_data; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_2 = (__pyx_v_self->data != NULL); + __pyx_t_1 = __pyx_t_2; + __pyx_L4_bool_binop_done:; + if (__pyx_t_1) { + + /* "View.MemoryView":214 + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) + */ + if (__pyx_v_self->dtype_is_object) { + + /* "View.MemoryView":215 + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) # <<<<<<<<<<<<<< + * free(self.data) + * PyObject_Free(self._shape) + */ + __pyx_memoryview_refcount_objects_in_slice(__pyx_v_self->data, __pyx_v_self->_shape, __pyx_v_self->_strides, __pyx_v_self->ndim, 0); + + /* "View.MemoryView":214 + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) + */ + } + + /* "View.MemoryView":216 + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) # <<<<<<<<<<<<<< + * PyObject_Free(self._shape) + * + */ + free(__pyx_v_self->data); + + /* "View.MemoryView":213 + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: # <<<<<<<<<<<<<< + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + */ + } + __pyx_L3:; + + /* "View.MemoryView":217 + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) + * PyObject_Free(self._shape) # <<<<<<<<<<<<<< + * + * @property + */ + PyObject_Free(__pyx_v_self->_shape); + + /* "View.MemoryView":210 + * info.obj = self + * + * def __dealloc__(array self): # <<<<<<<<<<<<<< + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + */ + + /* function exit code */ +} + +/* "View.MemoryView":219 + * PyObject_Free(self._shape) + * + * @property # <<<<<<<<<<<<<< + * def memview(self): + * return self.get_memview() + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_5array_7memview_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_5array_7memview_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_5array_7memview___get__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_5array_7memview___get__(struct __pyx_array_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":221 + * @property + * def memview(self): + * return self.get_memview() # <<<<<<<<<<<<<< + * + * @cname('get_memview') + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = ((struct __pyx_vtabstruct_array *)__pyx_v_self->__pyx_vtab)->get_memview(__pyx_v_self); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 221, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":219 + * PyObject_Free(self._shape) + * + * @property # <<<<<<<<<<<<<< + * def memview(self): + * return self.get_memview() + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.array.memview.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":224 + * + * @cname('get_memview') + * cdef get_memview(self): # <<<<<<<<<<<<<< + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE + * return memoryview(self, flags, self.dtype_is_object) + */ + +static PyObject *__pyx_array_get_memview(struct __pyx_array_obj *__pyx_v_self) { + int __pyx_v_flags; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_memview", 1); + + /* "View.MemoryView":225 + * @cname('get_memview') + * cdef get_memview(self): + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE # <<<<<<<<<<<<<< + * return memoryview(self, flags, self.dtype_is_object) + * + */ + __pyx_v_flags = ((PyBUF_ANY_CONTIGUOUS | PyBUF_FORMAT) | PyBUF_WRITABLE); + + /* "View.MemoryView":226 + * cdef get_memview(self): + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE + * return memoryview(self, flags, self.dtype_is_object) # <<<<<<<<<<<<<< + * + * def __len__(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_flags); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_v_self->dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF((PyObject *)__pyx_v_self); + __Pyx_GIVEREF((PyObject *)__pyx_v_self); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, ((PyObject *)__pyx_v_self))) __PYX_ERR(1, 226, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1)) __PYX_ERR(1, 226, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_t_2)) __PYX_ERR(1, 226, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_Call(((PyObject *)__pyx_memoryview_type), __pyx_t_3, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":224 + * + * @cname('get_memview') + * cdef get_memview(self): # <<<<<<<<<<<<<< + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE + * return memoryview(self, flags, self.dtype_is_object) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.array.get_memview", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":228 + * return memoryview(self, flags, self.dtype_is_object) + * + * def __len__(self): # <<<<<<<<<<<<<< + * return self._shape[0] + * + */ + +/* Python wrapper */ +static Py_ssize_t __pyx_array___len__(PyObject *__pyx_v_self); /*proto*/ +static Py_ssize_t __pyx_array___len__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + Py_ssize_t __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__len__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_6__len__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static Py_ssize_t __pyx_array___pyx_pf_15View_dot_MemoryView_5array_6__len__(struct __pyx_array_obj *__pyx_v_self) { + Py_ssize_t __pyx_r; + + /* "View.MemoryView":229 + * + * def __len__(self): + * return self._shape[0] # <<<<<<<<<<<<<< + * + * def __getattr__(self, attr): + */ + __pyx_r = (__pyx_v_self->_shape[0]); + goto __pyx_L0; + + /* "View.MemoryView":228 + * return memoryview(self, flags, self.dtype_is_object) + * + * def __len__(self): # <<<<<<<<<<<<<< + * return self._shape[0] + * + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":231 + * return self._shape[0] + * + * def __getattr__(self, attr): # <<<<<<<<<<<<<< + * return getattr(self.memview, attr) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_array___getattr__(PyObject *__pyx_v_self, PyObject *__pyx_v_attr); /*proto*/ +static PyObject *__pyx_array___getattr__(PyObject *__pyx_v_self, PyObject *__pyx_v_attr) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getattr__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_8__getattr__(((struct __pyx_array_obj *)__pyx_v_self), ((PyObject *)__pyx_v_attr)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_8__getattr__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_attr) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__getattr__", 1); + + /* "View.MemoryView":232 + * + * def __getattr__(self, attr): + * return getattr(self.memview, attr) # <<<<<<<<<<<<<< + * + * def __getitem__(self, item): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_memview); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 232, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_GetAttr(__pyx_t_1, __pyx_v_attr); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 232, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":231 + * return self._shape[0] + * + * def __getattr__(self, attr): # <<<<<<<<<<<<<< + * return getattr(self.memview, attr) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.array.__getattr__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":234 + * return getattr(self.memview, attr) + * + * def __getitem__(self, item): # <<<<<<<<<<<<<< + * return self.memview[item] + * + */ + +/* Python wrapper */ +static PyObject *__pyx_array___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item); /*proto*/ +static PyObject *__pyx_array___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getitem__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_10__getitem__(((struct __pyx_array_obj *)__pyx_v_self), ((PyObject *)__pyx_v_item)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_10__getitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__getitem__", 1); + + /* "View.MemoryView":235 + * + * def __getitem__(self, item): + * return self.memview[item] # <<<<<<<<<<<<<< + * + * def __setitem__(self, item, value): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_memview); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 235, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_t_1, __pyx_v_item); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 235, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":234 + * return getattr(self.memview, attr) + * + * def __getitem__(self, item): # <<<<<<<<<<<<<< + * return self.memview[item] + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.array.__getitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":237 + * return self.memview[item] + * + * def __setitem__(self, item, value): # <<<<<<<<<<<<<< + * self.memview[item] = value + * + */ + +/* Python wrapper */ +static int __pyx_array___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value); /*proto*/ +static int __pyx_array___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setitem__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_12__setitem__(((struct __pyx_array_obj *)__pyx_v_self), ((PyObject *)__pyx_v_item), ((PyObject *)__pyx_v_value)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_12__setitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setitem__", 1); + + /* "View.MemoryView":238 + * + * def __setitem__(self, item, value): + * self.memview[item] = value # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_memview); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 238, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyObject_SetItem(__pyx_t_1, __pyx_v_item, __pyx_v_value) < 0))) __PYX_ERR(1, 238, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "View.MemoryView":237 + * return self.memview[item] + * + * def __setitem__(self, item, value): # <<<<<<<<<<<<<< + * self.memview[item] = value + * + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.array.__setitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_array_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_array_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_array___reduce_cython__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_array___reduce_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.array.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_array_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_array_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.array.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_array_2__setstate_cython__(((struct __pyx_array_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_array_2__setstate_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.array.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":248 + * + * @cname("__pyx_array_allocate_buffer") + * cdef int _allocate_buffer(array self) except -1: # <<<<<<<<<<<<<< + * + * + */ + +static int __pyx_array_allocate_buffer(struct __pyx_array_obj *__pyx_v_self) { + Py_ssize_t __pyx_v_i; + PyObject **__pyx_v_p; + int __pyx_r; + int __pyx_t_1; + Py_ssize_t __pyx_t_2; + Py_ssize_t __pyx_t_3; + Py_ssize_t __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + + /* "View.MemoryView":254 + * cdef PyObject **p + * + * self.free_data = True # <<<<<<<<<<<<<< + * self.data = malloc(self.len) + * if not self.data: + */ + __pyx_v_self->free_data = 1; + + /* "View.MemoryView":255 + * + * self.free_data = True + * self.data = malloc(self.len) # <<<<<<<<<<<<<< + * if not self.data: + * raise MemoryError, "unable to allocate array data." + */ + __pyx_v_self->data = ((char *)malloc(__pyx_v_self->len)); + + /* "View.MemoryView":256 + * self.free_data = True + * self.data = malloc(self.len) + * if not self.data: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate array data." + * + */ + __pyx_t_1 = (!(__pyx_v_self->data != 0)); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":257 + * self.data = malloc(self.len) + * if not self.data: + * raise MemoryError, "unable to allocate array data." # <<<<<<<<<<<<<< + * + * if self.dtype_is_object: + */ + __Pyx_Raise(__pyx_builtin_MemoryError, __pyx_kp_s_unable_to_allocate_array_data, 0, 0); + __PYX_ERR(1, 257, __pyx_L1_error) + + /* "View.MemoryView":256 + * self.free_data = True + * self.data = malloc(self.len) + * if not self.data: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate array data." + * + */ + } + + /* "View.MemoryView":259 + * raise MemoryError, "unable to allocate array data." + * + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * p = self.data + * for i in range(self.len // self.itemsize): + */ + if (__pyx_v_self->dtype_is_object) { + + /* "View.MemoryView":260 + * + * if self.dtype_is_object: + * p = self.data # <<<<<<<<<<<<<< + * for i in range(self.len // self.itemsize): + * p[i] = Py_None + */ + __pyx_v_p = ((PyObject **)__pyx_v_self->data); + + /* "View.MemoryView":261 + * if self.dtype_is_object: + * p = self.data + * for i in range(self.len // self.itemsize): # <<<<<<<<<<<<<< + * p[i] = Py_None + * Py_INCREF(Py_None) + */ + if (unlikely(__pyx_v_self->itemsize == 0)) { + PyErr_SetString(PyExc_ZeroDivisionError, "integer division or modulo by zero"); + __PYX_ERR(1, 261, __pyx_L1_error) + } + else if (sizeof(Py_ssize_t) == sizeof(long) && (!(((Py_ssize_t)-1) > 0)) && unlikely(__pyx_v_self->itemsize == (Py_ssize_t)-1) && unlikely(__Pyx_UNARY_NEG_WOULD_OVERFLOW(__pyx_v_self->len))) { + PyErr_SetString(PyExc_OverflowError, "value too large to perform division"); + __PYX_ERR(1, 261, __pyx_L1_error) + } + __pyx_t_2 = __Pyx_div_Py_ssize_t(__pyx_v_self->len, __pyx_v_self->itemsize); + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":262 + * p = self.data + * for i in range(self.len // self.itemsize): + * p[i] = Py_None # <<<<<<<<<<<<<< + * Py_INCREF(Py_None) + * return 0 + */ + (__pyx_v_p[__pyx_v_i]) = Py_None; + + /* "View.MemoryView":263 + * for i in range(self.len // self.itemsize): + * p[i] = Py_None + * Py_INCREF(Py_None) # <<<<<<<<<<<<<< + * return 0 + * + */ + Py_INCREF(Py_None); + } + + /* "View.MemoryView":259 + * raise MemoryError, "unable to allocate array data." + * + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * p = self.data + * for i in range(self.len // self.itemsize): + */ + } + + /* "View.MemoryView":264 + * p[i] = Py_None + * Py_INCREF(Py_None) + * return 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":248 + * + * @cname("__pyx_array_allocate_buffer") + * cdef int _allocate_buffer(array self) except -1: # <<<<<<<<<<<<<< + * + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._allocate_buffer", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":268 + * + * @cname("__pyx_array_new") + * cdef array array_cwrapper(tuple shape, Py_ssize_t itemsize, char *format, char *c_mode, char *buf): # <<<<<<<<<<<<<< + * cdef array result + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + */ + +static struct __pyx_array_obj *__pyx_array_new(PyObject *__pyx_v_shape, Py_ssize_t __pyx_v_itemsize, char *__pyx_v_format, char *__pyx_v_c_mode, char *__pyx_v_buf) { + struct __pyx_array_obj *__pyx_v_result = 0; + PyObject *__pyx_v_mode = 0; + struct __pyx_array_obj *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("array_cwrapper", 1); + + /* "View.MemoryView":270 + * cdef array array_cwrapper(tuple shape, Py_ssize_t itemsize, char *format, char *c_mode, char *buf): + * cdef array result + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. # <<<<<<<<<<<<<< + * + * if buf is NULL: + */ + __pyx_t_2 = ((__pyx_v_c_mode[0]) == 'f'); + if (__pyx_t_2) { + __Pyx_INCREF(__pyx_n_s_fortran); + __pyx_t_1 = __pyx_n_s_fortran; + } else { + __Pyx_INCREF(__pyx_n_s_c); + __pyx_t_1 = __pyx_n_s_c; + } + __pyx_v_mode = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":272 + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + * + * if buf is NULL: # <<<<<<<<<<<<<< + * result = array.__new__(array, shape, itemsize, format, mode) + * else: + */ + __pyx_t_2 = (__pyx_v_buf == NULL); + if (__pyx_t_2) { + + /* "View.MemoryView":273 + * + * if buf is NULL: + * result = array.__new__(array, shape, itemsize, format, mode) # <<<<<<<<<<<<<< + * else: + * result = array.__new__(array, shape, itemsize, format, mode, allocate_buffer=False) + */ + __pyx_t_1 = PyInt_FromSsize_t(__pyx_v_itemsize); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 273, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyBytes_FromString(__pyx_v_format); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 273, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PyTuple_New(4); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 273, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_INCREF(__pyx_v_shape); + __Pyx_GIVEREF(__pyx_v_shape); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_v_shape)) __PYX_ERR(1, 273, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_t_1)) __PYX_ERR(1, 273, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 2, __pyx_t_3)) __PYX_ERR(1, 273, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_mode); + __Pyx_GIVEREF(__pyx_v_mode); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 3, __pyx_v_mode)) __PYX_ERR(1, 273, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_3 = 0; + __pyx_t_3 = ((PyObject *)__pyx_tp_new_array(((PyTypeObject *)__pyx_array_type), __pyx_t_4, NULL)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 273, __pyx_L1_error) + __Pyx_GOTREF((PyObject *)__pyx_t_3); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_v_result = ((struct __pyx_array_obj *)__pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":272 + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + * + * if buf is NULL: # <<<<<<<<<<<<<< + * result = array.__new__(array, shape, itemsize, format, mode) + * else: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":275 + * result = array.__new__(array, shape, itemsize, format, mode) + * else: + * result = array.__new__(array, shape, itemsize, format, mode, allocate_buffer=False) # <<<<<<<<<<<<<< + * result.data = buf + * + */ + /*else*/ { + __pyx_t_3 = PyInt_FromSsize_t(__pyx_v_itemsize); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = __Pyx_PyBytes_FromString(__pyx_v_format); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_1 = PyTuple_New(4); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v_shape); + __Pyx_GIVEREF(__pyx_v_shape); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v_shape)) __PYX_ERR(1, 275, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_t_3)) __PYX_ERR(1, 275, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_4); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_t_4)) __PYX_ERR(1, 275, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_mode); + __Pyx_GIVEREF(__pyx_v_mode); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 3, __pyx_v_mode)) __PYX_ERR(1, 275, __pyx_L1_error); + __pyx_t_3 = 0; + __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem(__pyx_t_4, __pyx_n_s_allocate_buffer, Py_False) < 0) __PYX_ERR(1, 275, __pyx_L1_error) + __pyx_t_3 = ((PyObject *)__pyx_tp_new_array(((PyTypeObject *)__pyx_array_type), __pyx_t_1, __pyx_t_4)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 275, __pyx_L1_error) + __Pyx_GOTREF((PyObject *)__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_v_result = ((struct __pyx_array_obj *)__pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":276 + * else: + * result = array.__new__(array, shape, itemsize, format, mode, allocate_buffer=False) + * result.data = buf # <<<<<<<<<<<<<< + * + * return result + */ + __pyx_v_result->data = __pyx_v_buf; + } + __pyx_L3:; + + /* "View.MemoryView":278 + * result.data = buf + * + * return result # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF((PyObject *)__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = __pyx_v_result; + goto __pyx_L0; + + /* "View.MemoryView":268 + * + * @cname("__pyx_array_new") + * cdef array array_cwrapper(tuple shape, Py_ssize_t itemsize, char *format, char *c_mode, char *buf): # <<<<<<<<<<<<<< + * cdef array result + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.array_cwrapper", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XDECREF(__pyx_v_mode); + __Pyx_XGIVEREF((PyObject *)__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":304 + * cdef class Enum(object): + * cdef object name + * def __init__(self, name): # <<<<<<<<<<<<<< + * self.name = name + * def __repr__(self): + */ + +/* Python wrapper */ +static int __pyx_MemviewEnum___init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_MemviewEnum___init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_name = 0; + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__init__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_name,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_name)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 304, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__init__") < 0)) __PYX_ERR(1, 304, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + } + __pyx_v_name = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__init__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 304, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.Enum.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum___init__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self), __pyx_v_name); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum___init__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v_name) { + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__init__", 1); + + /* "View.MemoryView":305 + * cdef object name + * def __init__(self, name): + * self.name = name # <<<<<<<<<<<<<< + * def __repr__(self): + * return self.name + */ + __Pyx_INCREF(__pyx_v_name); + __Pyx_GIVEREF(__pyx_v_name); + __Pyx_GOTREF(__pyx_v_self->name); + __Pyx_DECREF(__pyx_v_self->name); + __pyx_v_self->name = __pyx_v_name; + + /* "View.MemoryView":304 + * cdef class Enum(object): + * cdef object name + * def __init__(self, name): # <<<<<<<<<<<<<< + * self.name = name + * def __repr__(self): + */ + + /* function exit code */ + __pyx_r = 0; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":306 + * def __init__(self, name): + * self.name = name + * def __repr__(self): # <<<<<<<<<<<<<< + * return self.name + * + */ + +/* Python wrapper */ +static PyObject *__pyx_MemviewEnum___repr__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_MemviewEnum___repr__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__repr__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum_2__repr__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum_2__repr__(struct __pyx_MemviewEnum_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__repr__", 1); + + /* "View.MemoryView":307 + * self.name = name + * def __repr__(self): + * return self.name # <<<<<<<<<<<<<< + * + * cdef generic = Enum("") + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->name); + __pyx_r = __pyx_v_self->name; + goto __pyx_L0; + + /* "View.MemoryView":306 + * def __init__(self, name): + * self.name = name + * def __repr__(self): # <<<<<<<<<<<<<< + * return self.name + * + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * cdef tuple state + * cdef object _dict + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_MemviewEnum_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_MemviewEnum_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_MemviewEnum___reduce_cython__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_MemviewEnum___reduce_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self) { + PyObject *__pyx_v_state = 0; + PyObject *__pyx_v__dict = 0; + int __pyx_v_use_setstate; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":5 + * cdef object _dict + * cdef bint use_setstate + * state = (self.name,) # <<<<<<<<<<<<<< + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: + */ + __pyx_t_1 = PyTuple_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v_self->name); + __Pyx_GIVEREF(__pyx_v_self->name); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v_self->name)) __PYX_ERR(1, 5, __pyx_L1_error); + __pyx_v_state = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "(tree fragment)":6 + * cdef bint use_setstate + * state = (self.name,) + * _dict = getattr(self, '__dict__', None) # <<<<<<<<<<<<<< + * if _dict is not None: + * state += (_dict,) + */ + __pyx_t_1 = __Pyx_GetAttr3(((PyObject *)__pyx_v_self), __pyx_n_s_dict, Py_None); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v__dict = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":7 + * state = (self.name,) + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: # <<<<<<<<<<<<<< + * state += (_dict,) + * use_setstate = True + */ + __pyx_t_2 = (__pyx_v__dict != Py_None); + if (__pyx_t_2) { + + /* "(tree fragment)":8 + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: + * state += (_dict,) # <<<<<<<<<<<<<< + * use_setstate = True + * else: + */ + __pyx_t_1 = PyTuple_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 8, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v__dict); + __Pyx_GIVEREF(__pyx_v__dict); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v__dict)) __PYX_ERR(1, 8, __pyx_L1_error); + __pyx_t_3 = PyNumber_InPlaceAdd(__pyx_v_state, __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 8, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF_SET(__pyx_v_state, ((PyObject*)__pyx_t_3)); + __pyx_t_3 = 0; + + /* "(tree fragment)":9 + * if _dict is not None: + * state += (_dict,) + * use_setstate = True # <<<<<<<<<<<<<< + * else: + * use_setstate = self.name is not None + */ + __pyx_v_use_setstate = 1; + + /* "(tree fragment)":7 + * state = (self.name,) + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: # <<<<<<<<<<<<<< + * state += (_dict,) + * use_setstate = True + */ + goto __pyx_L3; + } + + /* "(tree fragment)":11 + * use_setstate = True + * else: + * use_setstate = self.name is not None # <<<<<<<<<<<<<< + * if use_setstate: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + */ + /*else*/ { + __pyx_t_2 = (__pyx_v_self->name != Py_None); + __pyx_v_use_setstate = __pyx_t_2; + } + __pyx_L3:; + + /* "(tree fragment)":12 + * else: + * use_setstate = self.name is not None + * if use_setstate: # <<<<<<<<<<<<<< + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + * else: + */ + if (__pyx_v_use_setstate) { + + /* "(tree fragment)":13 + * use_setstate = self.name is not None + * if use_setstate: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state # <<<<<<<<<<<<<< + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_pyx_unpickle_Enum); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = PyTuple_New(3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_GIVEREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, ((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self))))) __PYX_ERR(1, 13, __pyx_L1_error); + __Pyx_INCREF(__pyx_int_136983863); + __Pyx_GIVEREF(__pyx_int_136983863); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_int_136983863)) __PYX_ERR(1, 13, __pyx_L1_error); + __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(Py_None); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 2, Py_None)) __PYX_ERR(1, 13, __pyx_L1_error); + __pyx_t_4 = PyTuple_New(3); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_3)) __PYX_ERR(1, 13, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_t_1)) __PYX_ERR(1, 13, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_state); + __Pyx_GIVEREF(__pyx_v_state); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 2, __pyx_v_state)) __PYX_ERR(1, 13, __pyx_L1_error); + __pyx_t_3 = 0; + __pyx_t_1 = 0; + __pyx_r = __pyx_t_4; + __pyx_t_4 = 0; + goto __pyx_L0; + + /* "(tree fragment)":12 + * else: + * use_setstate = self.name is not None + * if use_setstate: # <<<<<<<<<<<<<< + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + * else: + */ + } + + /* "(tree fragment)":15 + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * __pyx_unpickle_Enum__set_state(self, __pyx_state) + */ + /*else*/ { + __Pyx_XDECREF(__pyx_r); + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_pyx_unpickle_Enum); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_1 = PyTuple_New(3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_GIVEREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, ((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self))))) __PYX_ERR(1, 15, __pyx_L1_error); + __Pyx_INCREF(__pyx_int_136983863); + __Pyx_GIVEREF(__pyx_int_136983863); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_int_136983863)) __PYX_ERR(1, 15, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_state); + __Pyx_GIVEREF(__pyx_v_state); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_v_state)) __PYX_ERR(1, 15, __pyx_L1_error); + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_4); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_4)) __PYX_ERR(1, 15, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1)) __PYX_ERR(1, 15, __pyx_L1_error); + __pyx_t_4 = 0; + __pyx_t_1 = 0; + __pyx_r = __pyx_t_3; + __pyx_t_3 = 0; + goto __pyx_L0; + } + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * cdef tuple state + * cdef object _dict + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.Enum.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_state); + __Pyx_XDECREF(__pyx_v__dict); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":16 + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state(self, __pyx_state) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_MemviewEnum_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_MemviewEnum_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 16, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 16, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 16, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.Enum.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_MemviewEnum_2__setstate_cython__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_MemviewEnum_2__setstate_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":17 + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + * def __setstate_cython__(self, __pyx_state): + * __pyx_unpickle_Enum__set_state(self, __pyx_state) # <<<<<<<<<<<<<< + */ + if (!(likely(PyTuple_CheckExact(__pyx_v___pyx_state))||((__pyx_v___pyx_state) == Py_None) || __Pyx_RaiseUnexpectedTypeError("tuple", __pyx_v___pyx_state))) __PYX_ERR(1, 17, __pyx_L1_error) + __pyx_t_1 = __pyx_unpickle_Enum__set_state(__pyx_v_self, ((PyObject*)__pyx_v___pyx_state)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 17, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":16 + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state(self, __pyx_state) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.Enum.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":349 + * cdef __Pyx_TypeInfo *typeinfo + * + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): # <<<<<<<<<<<<<< + * self.obj = obj + * self.flags = flags + */ + +/* Python wrapper */ +static int __pyx_memoryview___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_memoryview___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_obj = 0; + int __pyx_v_flags; + int __pyx_v_dtype_is_object; + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_obj,&__pyx_n_s_flags,&__pyx_n_s_dtype_is_object,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_obj)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_flags)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 2, 3, 1); __PYX_ERR(1, 349, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_dtype_is_object); + if (value) { values[2] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(1, 349, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_obj = values[0]; + __pyx_v_flags = __Pyx_PyInt_As_int(values[1]); if (unlikely((__pyx_v_flags == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) + if (values[2]) { + __pyx_v_dtype_is_object = __Pyx_PyObject_IsTrue(values[2]); if (unlikely((__pyx_v_dtype_is_object == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) + } else { + __pyx_v_dtype_is_object = ((int)0); + } + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 2, 3, __pyx_nargs); __PYX_ERR(1, 349, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.memoryview.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview___cinit__(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v_obj, __pyx_v_flags, __pyx_v_dtype_is_object); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview___cinit__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj, int __pyx_v_flags, int __pyx_v_dtype_is_object) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + Py_intptr_t __pyx_t_4; + size_t __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__cinit__", 1); + + /* "View.MemoryView":350 + * + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): + * self.obj = obj # <<<<<<<<<<<<<< + * self.flags = flags + * if type(self) is memoryview or obj is not None: + */ + __Pyx_INCREF(__pyx_v_obj); + __Pyx_GIVEREF(__pyx_v_obj); + __Pyx_GOTREF(__pyx_v_self->obj); + __Pyx_DECREF(__pyx_v_self->obj); + __pyx_v_self->obj = __pyx_v_obj; + + /* "View.MemoryView":351 + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): + * self.obj = obj + * self.flags = flags # <<<<<<<<<<<<<< + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) + */ + __pyx_v_self->flags = __pyx_v_flags; + + /* "View.MemoryView":352 + * self.obj = obj + * self.flags = flags + * if type(self) is memoryview or obj is not None: # <<<<<<<<<<<<<< + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: + */ + __pyx_t_2 = (((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self))) == ((PyObject *)__pyx_memoryview_type)); + if (!__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_2 = (__pyx_v_obj != Py_None); + __pyx_t_1 = __pyx_t_2; + __pyx_L4_bool_binop_done:; + if (__pyx_t_1) { + + /* "View.MemoryView":353 + * self.flags = flags + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) # <<<<<<<<<<<<<< + * if self.view.obj == NULL: + * (<__pyx_buffer *> &self.view).obj = Py_None + */ + __pyx_t_3 = __Pyx_GetBuffer(__pyx_v_obj, (&__pyx_v_self->view), __pyx_v_flags); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 353, __pyx_L1_error) + + /* "View.MemoryView":354 + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: # <<<<<<<<<<<<<< + * (<__pyx_buffer *> &self.view).obj = Py_None + * Py_INCREF(Py_None) + */ + __pyx_t_1 = (((PyObject *)__pyx_v_self->view.obj) == NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":355 + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: + * (<__pyx_buffer *> &self.view).obj = Py_None # <<<<<<<<<<<<<< + * Py_INCREF(Py_None) + * + */ + ((Py_buffer *)(&__pyx_v_self->view))->obj = Py_None; + + /* "View.MemoryView":356 + * if self.view.obj == NULL: + * (<__pyx_buffer *> &self.view).obj = Py_None + * Py_INCREF(Py_None) # <<<<<<<<<<<<<< + * + * if not __PYX_CYTHON_ATOMICS_ENABLED(): + */ + Py_INCREF(Py_None); + + /* "View.MemoryView":354 + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: # <<<<<<<<<<<<<< + * (<__pyx_buffer *> &self.view).obj = Py_None + * Py_INCREF(Py_None) + */ + } + + /* "View.MemoryView":352 + * self.obj = obj + * self.flags = flags + * if type(self) is memoryview or obj is not None: # <<<<<<<<<<<<<< + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: + */ + } + + /* "View.MemoryView":358 + * Py_INCREF(Py_None) + * + * if not __PYX_CYTHON_ATOMICS_ENABLED(): # <<<<<<<<<<<<<< + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: + */ + __pyx_t_1 = (!__PYX_CYTHON_ATOMICS_ENABLED()); + if (__pyx_t_1) { + + /* "View.MemoryView":360 + * if not __PYX_CYTHON_ATOMICS_ENABLED(): + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: # <<<<<<<<<<<<<< + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + */ + __pyx_t_1 = (__pyx_memoryview_thread_locks_used < 8); + if (__pyx_t_1) { + + /* "View.MemoryView":361 + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: + */ + __pyx_v_self->lock = (__pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used]); + + /* "View.MemoryView":362 + * if __pyx_memoryview_thread_locks_used < 8: + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 # <<<<<<<<<<<<<< + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() + */ + __pyx_memoryview_thread_locks_used = (__pyx_memoryview_thread_locks_used + 1); + + /* "View.MemoryView":360 + * if not __PYX_CYTHON_ATOMICS_ENABLED(): + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: # <<<<<<<<<<<<<< + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + */ + } + + /* "View.MemoryView":363 + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: # <<<<<<<<<<<<<< + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: + */ + __pyx_t_1 = (__pyx_v_self->lock == NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":364 + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() # <<<<<<<<<<<<<< + * if self.lock is NULL: + * raise MemoryError + */ + __pyx_v_self->lock = PyThread_allocate_lock(); + + /* "View.MemoryView":365 + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + __pyx_t_1 = (__pyx_v_self->lock == NULL); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":366 + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: + * raise MemoryError # <<<<<<<<<<<<<< + * + * if flags & PyBUF_FORMAT: + */ + PyErr_NoMemory(); __PYX_ERR(1, 366, __pyx_L1_error) + + /* "View.MemoryView":365 + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + } + + /* "View.MemoryView":363 + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: # <<<<<<<<<<<<<< + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: + */ + } + + /* "View.MemoryView":358 + * Py_INCREF(Py_None) + * + * if not __PYX_CYTHON_ATOMICS_ENABLED(): # <<<<<<<<<<<<<< + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: + */ + } + + /* "View.MemoryView":368 + * raise MemoryError + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_FORMAT) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":369 + * + * if flags & PyBUF_FORMAT: + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') # <<<<<<<<<<<<<< + * else: + * self.dtype_is_object = dtype_is_object + */ + __pyx_t_2 = ((__pyx_v_self->view.format[0]) == 'O'); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L12_bool_binop_done; + } + __pyx_t_2 = ((__pyx_v_self->view.format[1]) == '\x00'); + __pyx_t_1 = __pyx_t_2; + __pyx_L12_bool_binop_done:; + __pyx_v_self->dtype_is_object = __pyx_t_1; + + /* "View.MemoryView":368 + * raise MemoryError + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') + * else: + */ + goto __pyx_L11; + } + + /* "View.MemoryView":371 + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') + * else: + * self.dtype_is_object = dtype_is_object # <<<<<<<<<<<<<< + * + * assert (&self.acquisition_count) % sizeof(__pyx_atomic_int_type) == 0 + */ + /*else*/ { + __pyx_v_self->dtype_is_object = __pyx_v_dtype_is_object; + } + __pyx_L11:; + + /* "View.MemoryView":373 + * self.dtype_is_object = dtype_is_object + * + * assert (&self.acquisition_count) % sizeof(__pyx_atomic_int_type) == 0 # <<<<<<<<<<<<<< + * self.typeinfo = NULL + * + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_4 = ((Py_intptr_t)((void *)(&__pyx_v_self->acquisition_count))); + __pyx_t_5 = (sizeof(__pyx_atomic_int_type)); + if (unlikely(__pyx_t_5 == 0)) { + PyErr_SetString(PyExc_ZeroDivisionError, "integer division or modulo by zero"); + __PYX_ERR(1, 373, __pyx_L1_error) + } + __pyx_t_1 = ((__pyx_t_4 % __pyx_t_5) == 0); + if (unlikely(!__pyx_t_1)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(1, 373, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(1, 373, __pyx_L1_error) + #endif + + /* "View.MemoryView":374 + * + * assert (&self.acquisition_count) % sizeof(__pyx_atomic_int_type) == 0 + * self.typeinfo = NULL # <<<<<<<<<<<<<< + * + * def __dealloc__(memoryview self): + */ + __pyx_v_self->typeinfo = NULL; + + /* "View.MemoryView":349 + * cdef __Pyx_TypeInfo *typeinfo + * + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): # <<<<<<<<<<<<<< + * self.obj = obj + * self.flags = flags + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":376 + * self.typeinfo = NULL + * + * def __dealloc__(memoryview self): # <<<<<<<<<<<<<< + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + */ + +/* Python wrapper */ +static void __pyx_memoryview___dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_memoryview___dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_2__dealloc__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_2__dealloc__(struct __pyx_memoryview_obj *__pyx_v_self) { + int __pyx_v_i; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + PyThread_type_lock __pyx_t_5; + PyThread_type_lock __pyx_t_6; + + /* "View.MemoryView":377 + * + * def __dealloc__(memoryview self): + * if self.obj is not None: # <<<<<<<<<<<<<< + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + */ + __pyx_t_1 = (__pyx_v_self->obj != Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":378 + * def __dealloc__(memoryview self): + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) # <<<<<<<<<<<<<< + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + * + */ + __Pyx_ReleaseBuffer((&__pyx_v_self->view)); + + /* "View.MemoryView":377 + * + * def __dealloc__(memoryview self): + * if self.obj is not None: # <<<<<<<<<<<<<< + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":379 + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: # <<<<<<<<<<<<<< + * + * (<__pyx_buffer *> &self.view).obj = NULL + */ + __pyx_t_1 = (((Py_buffer *)(&__pyx_v_self->view))->obj == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":381 + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + * + * (<__pyx_buffer *> &self.view).obj = NULL # <<<<<<<<<<<<<< + * Py_DECREF(Py_None) + * + */ + ((Py_buffer *)(&__pyx_v_self->view))->obj = NULL; + + /* "View.MemoryView":382 + * + * (<__pyx_buffer *> &self.view).obj = NULL + * Py_DECREF(Py_None) # <<<<<<<<<<<<<< + * + * cdef int i + */ + Py_DECREF(Py_None); + + /* "View.MemoryView":379 + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: # <<<<<<<<<<<<<< + * + * (<__pyx_buffer *> &self.view).obj = NULL + */ + } + __pyx_L3:; + + /* "View.MemoryView":386 + * cdef int i + * global __pyx_memoryview_thread_locks_used + * if self.lock != NULL: # <<<<<<<<<<<<<< + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: + */ + __pyx_t_1 = (__pyx_v_self->lock != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":387 + * global __pyx_memoryview_thread_locks_used + * if self.lock != NULL: + * for i in range(__pyx_memoryview_thread_locks_used): # <<<<<<<<<<<<<< + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 + */ + __pyx_t_2 = __pyx_memoryview_thread_locks_used; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":388 + * if self.lock != NULL: + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: + */ + __pyx_t_1 = ((__pyx_memoryview_thread_locks[__pyx_v_i]) == __pyx_v_self->lock); + if (__pyx_t_1) { + + /* "View.MemoryView":389 + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 # <<<<<<<<<<<<<< + * if i != __pyx_memoryview_thread_locks_used: + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + */ + __pyx_memoryview_thread_locks_used = (__pyx_memoryview_thread_locks_used - 1); + + /* "View.MemoryView":390 + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + */ + __pyx_t_1 = (__pyx_v_i != __pyx_memoryview_thread_locks_used); + if (__pyx_t_1) { + + /* "View.MemoryView":392 + * if i != __pyx_memoryview_thread_locks_used: + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) # <<<<<<<<<<<<<< + * break + * else: + */ + __pyx_t_5 = (__pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used]); + __pyx_t_6 = (__pyx_memoryview_thread_locks[__pyx_v_i]); + + /* "View.MemoryView":391 + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + * break + */ + (__pyx_memoryview_thread_locks[__pyx_v_i]) = __pyx_t_5; + (__pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used]) = __pyx_t_6; + + /* "View.MemoryView":390 + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + */ + } + + /* "View.MemoryView":393 + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + * break # <<<<<<<<<<<<<< + * else: + * PyThread_free_lock(self.lock) + */ + goto __pyx_L6_break; + + /* "View.MemoryView":388 + * if self.lock != NULL: + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: + */ + } + } + /*else*/ { + + /* "View.MemoryView":395 + * break + * else: + * PyThread_free_lock(self.lock) # <<<<<<<<<<<<<< + * + * cdef char *get_item_pointer(memoryview self, object index) except NULL: + */ + PyThread_free_lock(__pyx_v_self->lock); + } + __pyx_L6_break:; + + /* "View.MemoryView":386 + * cdef int i + * global __pyx_memoryview_thread_locks_used + * if self.lock != NULL: # <<<<<<<<<<<<<< + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: + */ + } + + /* "View.MemoryView":376 + * self.typeinfo = NULL + * + * def __dealloc__(memoryview self): # <<<<<<<<<<<<<< + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + */ + + /* function exit code */ +} + +/* "View.MemoryView":397 + * PyThread_free_lock(self.lock) + * + * cdef char *get_item_pointer(memoryview self, object index) except NULL: # <<<<<<<<<<<<<< + * cdef Py_ssize_t dim + * cdef char *itemp = self.view.buf + */ + +static char *__pyx_memoryview_get_item_pointer(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index) { + Py_ssize_t __pyx_v_dim; + char *__pyx_v_itemp; + PyObject *__pyx_v_idx = NULL; + char *__pyx_r; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + Py_ssize_t __pyx_t_3; + PyObject *(*__pyx_t_4)(PyObject *); + PyObject *__pyx_t_5 = NULL; + Py_ssize_t __pyx_t_6; + char *__pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_item_pointer", 1); + + /* "View.MemoryView":399 + * cdef char *get_item_pointer(memoryview self, object index) except NULL: + * cdef Py_ssize_t dim + * cdef char *itemp = self.view.buf # <<<<<<<<<<<<<< + * + * for dim, idx in enumerate(index): + */ + __pyx_v_itemp = ((char *)__pyx_v_self->view.buf); + + /* "View.MemoryView":401 + * cdef char *itemp = self.view.buf + * + * for dim, idx in enumerate(index): # <<<<<<<<<<<<<< + * itemp = pybuffer_index(&self.view, itemp, idx, dim) + * + */ + __pyx_t_1 = 0; + if (likely(PyList_CheckExact(__pyx_v_index)) || PyTuple_CheckExact(__pyx_v_index)) { + __pyx_t_2 = __pyx_v_index; __Pyx_INCREF(__pyx_t_2); + __pyx_t_3 = 0; + __pyx_t_4 = NULL; + } else { + __pyx_t_3 = -1; __pyx_t_2 = PyObject_GetIter(__pyx_v_index); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 401, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_2); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 401, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_4)) { + if (likely(PyList_CheckExact(__pyx_t_2))) { + { + Py_ssize_t __pyx_temp = __Pyx_PyList_GET_SIZE(__pyx_t_2); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 401, __pyx_L1_error) + #endif + if (__pyx_t_3 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_5 = PyList_GET_ITEM(__pyx_t_2, __pyx_t_3); __Pyx_INCREF(__pyx_t_5); __pyx_t_3++; if (unlikely((0 < 0))) __PYX_ERR(1, 401, __pyx_L1_error) + #else + __pyx_t_5 = __Pyx_PySequence_ITEM(__pyx_t_2, __pyx_t_3); __pyx_t_3++; if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 401, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + #endif + } else { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_2); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 401, __pyx_L1_error) + #endif + if (__pyx_t_3 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_5 = PyTuple_GET_ITEM(__pyx_t_2, __pyx_t_3); __Pyx_INCREF(__pyx_t_5); __pyx_t_3++; if (unlikely((0 < 0))) __PYX_ERR(1, 401, __pyx_L1_error) + #else + __pyx_t_5 = __Pyx_PySequence_ITEM(__pyx_t_2, __pyx_t_3); __pyx_t_3++; if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 401, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + #endif + } + } else { + __pyx_t_5 = __pyx_t_4(__pyx_t_2); + if (unlikely(!__pyx_t_5)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(1, 401, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_5); + } + __Pyx_XDECREF_SET(__pyx_v_idx, __pyx_t_5); + __pyx_t_5 = 0; + __pyx_v_dim = __pyx_t_1; + __pyx_t_1 = (__pyx_t_1 + 1); + + /* "View.MemoryView":402 + * + * for dim, idx in enumerate(index): + * itemp = pybuffer_index(&self.view, itemp, idx, dim) # <<<<<<<<<<<<<< + * + * return itemp + */ + __pyx_t_6 = __Pyx_PyIndex_AsSsize_t(__pyx_v_idx); if (unlikely((__pyx_t_6 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 402, __pyx_L1_error) + __pyx_t_7 = __pyx_pybuffer_index((&__pyx_v_self->view), __pyx_v_itemp, __pyx_t_6, __pyx_v_dim); if (unlikely(__pyx_t_7 == ((char *)NULL))) __PYX_ERR(1, 402, __pyx_L1_error) + __pyx_v_itemp = __pyx_t_7; + + /* "View.MemoryView":401 + * cdef char *itemp = self.view.buf + * + * for dim, idx in enumerate(index): # <<<<<<<<<<<<<< + * itemp = pybuffer_index(&self.view, itemp, idx, dim) + * + */ + } + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":404 + * itemp = pybuffer_index(&self.view, itemp, idx, dim) + * + * return itemp # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = __pyx_v_itemp; + goto __pyx_L0; + + /* "View.MemoryView":397 + * PyThread_free_lock(self.lock) + * + * cdef char *get_item_pointer(memoryview self, object index) except NULL: # <<<<<<<<<<<<<< + * cdef Py_ssize_t dim + * cdef char *itemp = self.view.buf + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.memoryview.get_item_pointer", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_idx); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":407 + * + * + * def __getitem__(memoryview self, object index): # <<<<<<<<<<<<<< + * if index is Ellipsis: + * return self + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index); /*proto*/ +static PyObject *__pyx_memoryview___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getitem__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_4__getitem__(((struct __pyx_memoryview_obj *)__pyx_v_self), ((PyObject *)__pyx_v_index)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_4__getitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index) { + PyObject *__pyx_v_have_slices = NULL; + PyObject *__pyx_v_indices = NULL; + char *__pyx_v_itemp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + char *__pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__getitem__", 1); + + /* "View.MemoryView":408 + * + * def __getitem__(memoryview self, object index): + * if index is Ellipsis: # <<<<<<<<<<<<<< + * return self + * + */ + __pyx_t_1 = (__pyx_v_index == __pyx_builtin_Ellipsis); + if (__pyx_t_1) { + + /* "View.MemoryView":409 + * def __getitem__(memoryview self, object index): + * if index is Ellipsis: + * return self # <<<<<<<<<<<<<< + * + * have_slices, indices = _unellipsify(index, self.view.ndim) + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_self); + __pyx_r = ((PyObject *)__pyx_v_self); + goto __pyx_L0; + + /* "View.MemoryView":408 + * + * def __getitem__(memoryview self, object index): + * if index is Ellipsis: # <<<<<<<<<<<<<< + * return self + * + */ + } + + /* "View.MemoryView":411 + * return self + * + * have_slices, indices = _unellipsify(index, self.view.ndim) # <<<<<<<<<<<<<< + * + * cdef char *itemp + */ + __pyx_t_2 = _unellipsify(__pyx_v_index, __pyx_v_self->view.ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 411, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (likely(__pyx_t_2 != Py_None)) { + PyObject* sequence = __pyx_t_2; + Py_ssize_t size = __Pyx_PySequence_SIZE(sequence); + if (unlikely(size != 2)) { + if (size > 2) __Pyx_RaiseTooManyValuesError(2); + else if (size >= 0) __Pyx_RaiseNeedMoreValuesError(size); + __PYX_ERR(1, 411, __pyx_L1_error) + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_3 = PyTuple_GET_ITEM(sequence, 0); + __pyx_t_4 = PyTuple_GET_ITEM(sequence, 1); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(__pyx_t_4); + #else + __pyx_t_3 = PySequence_ITEM(sequence, 0); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 411, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PySequence_ITEM(sequence, 1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 411, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } else { + __Pyx_RaiseNoneNotIterableError(); __PYX_ERR(1, 411, __pyx_L1_error) + } + __pyx_v_have_slices = __pyx_t_3; + __pyx_t_3 = 0; + __pyx_v_indices = __pyx_t_4; + __pyx_t_4 = 0; + + /* "View.MemoryView":414 + * + * cdef char *itemp + * if have_slices: # <<<<<<<<<<<<<< + * return memview_slice(self, indices) + * else: + */ + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_v_have_slices); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 414, __pyx_L1_error) + if (__pyx_t_1) { + + /* "View.MemoryView":415 + * cdef char *itemp + * if have_slices: + * return memview_slice(self, indices) # <<<<<<<<<<<<<< + * else: + * itemp = self.get_item_pointer(indices) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = ((PyObject *)__pyx_memview_slice(__pyx_v_self, __pyx_v_indices)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 415, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":414 + * + * cdef char *itemp + * if have_slices: # <<<<<<<<<<<<<< + * return memview_slice(self, indices) + * else: + */ + } + + /* "View.MemoryView":417 + * return memview_slice(self, indices) + * else: + * itemp = self.get_item_pointer(indices) # <<<<<<<<<<<<<< + * return self.convert_item_to_object(itemp) + * + */ + /*else*/ { + __pyx_t_5 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->get_item_pointer(__pyx_v_self, __pyx_v_indices); if (unlikely(__pyx_t_5 == ((char *)NULL))) __PYX_ERR(1, 417, __pyx_L1_error) + __pyx_v_itemp = __pyx_t_5; + + /* "View.MemoryView":418 + * else: + * itemp = self.get_item_pointer(indices) + * return self.convert_item_to_object(itemp) # <<<<<<<<<<<<<< + * + * def __setitem__(memoryview self, object index, object value): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->convert_item_to_object(__pyx_v_self, __pyx_v_itemp); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 418, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + } + + /* "View.MemoryView":407 + * + * + * def __getitem__(memoryview self, object index): # <<<<<<<<<<<<<< + * if index is Ellipsis: + * return self + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.memoryview.__getitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_have_slices); + __Pyx_XDECREF(__pyx_v_indices); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":420 + * return self.convert_item_to_object(itemp) + * + * def __setitem__(memoryview self, object index, object value): # <<<<<<<<<<<<<< + * if self.view.readonly: + * raise TypeError, "Cannot assign to read-only memoryview" + */ + +/* Python wrapper */ +static int __pyx_memoryview___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value); /*proto*/ +static int __pyx_memoryview___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setitem__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_6__setitem__(((struct __pyx_memoryview_obj *)__pyx_v_self), ((PyObject *)__pyx_v_index), ((PyObject *)__pyx_v_value)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_6__setitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value) { + PyObject *__pyx_v_have_slices = NULL; + PyObject *__pyx_v_obj = NULL; + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setitem__", 0); + __Pyx_INCREF(__pyx_v_index); + + /* "View.MemoryView":421 + * + * def __setitem__(memoryview self, object index, object value): + * if self.view.readonly: # <<<<<<<<<<<<<< + * raise TypeError, "Cannot assign to read-only memoryview" + * + */ + if (unlikely(__pyx_v_self->view.readonly)) { + + /* "View.MemoryView":422 + * def __setitem__(memoryview self, object index, object value): + * if self.view.readonly: + * raise TypeError, "Cannot assign to read-only memoryview" # <<<<<<<<<<<<<< + * + * have_slices, index = _unellipsify(index, self.view.ndim) + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_Cannot_assign_to_read_only_memor, 0, 0); + __PYX_ERR(1, 422, __pyx_L1_error) + + /* "View.MemoryView":421 + * + * def __setitem__(memoryview self, object index, object value): + * if self.view.readonly: # <<<<<<<<<<<<<< + * raise TypeError, "Cannot assign to read-only memoryview" + * + */ + } + + /* "View.MemoryView":424 + * raise TypeError, "Cannot assign to read-only memoryview" + * + * have_slices, index = _unellipsify(index, self.view.ndim) # <<<<<<<<<<<<<< + * + * if have_slices: + */ + __pyx_t_1 = _unellipsify(__pyx_v_index, __pyx_v_self->view.ndim); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 424, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (likely(__pyx_t_1 != Py_None)) { + PyObject* sequence = __pyx_t_1; + Py_ssize_t size = __Pyx_PySequence_SIZE(sequence); + if (unlikely(size != 2)) { + if (size > 2) __Pyx_RaiseTooManyValuesError(2); + else if (size >= 0) __Pyx_RaiseNeedMoreValuesError(size); + __PYX_ERR(1, 424, __pyx_L1_error) + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_2 = PyTuple_GET_ITEM(sequence, 0); + __pyx_t_3 = PyTuple_GET_ITEM(sequence, 1); + __Pyx_INCREF(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + #else + __pyx_t_2 = PySequence_ITEM(sequence, 0); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 424, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PySequence_ITEM(sequence, 1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 424, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + #endif + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } else { + __Pyx_RaiseNoneNotIterableError(); __PYX_ERR(1, 424, __pyx_L1_error) + } + __pyx_v_have_slices = __pyx_t_2; + __pyx_t_2 = 0; + __Pyx_DECREF_SET(__pyx_v_index, __pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":426 + * have_slices, index = _unellipsify(index, self.view.ndim) + * + * if have_slices: # <<<<<<<<<<<<<< + * obj = self.is_slice(value) + * if obj: + */ + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_v_have_slices); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(1, 426, __pyx_L1_error) + if (__pyx_t_4) { + + /* "View.MemoryView":427 + * + * if have_slices: + * obj = self.is_slice(value) # <<<<<<<<<<<<<< + * if obj: + * self.setitem_slice_assignment(self[index], obj) + */ + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->is_slice(__pyx_v_self, __pyx_v_value); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 427, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_obj = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":428 + * if have_slices: + * obj = self.is_slice(value) + * if obj: # <<<<<<<<<<<<<< + * self.setitem_slice_assignment(self[index], obj) + * else: + */ + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_v_obj); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(1, 428, __pyx_L1_error) + if (__pyx_t_4) { + + /* "View.MemoryView":429 + * obj = self.is_slice(value) + * if obj: + * self.setitem_slice_assignment(self[index], obj) # <<<<<<<<<<<<<< + * else: + * self.setitem_slice_assign_scalar(self[index], value) + */ + __pyx_t_1 = __Pyx_PyObject_GetItem(((PyObject *)__pyx_v_self), __pyx_v_index); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 429, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->setitem_slice_assignment(__pyx_v_self, __pyx_t_1, __pyx_v_obj); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 429, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "View.MemoryView":428 + * if have_slices: + * obj = self.is_slice(value) + * if obj: # <<<<<<<<<<<<<< + * self.setitem_slice_assignment(self[index], obj) + * else: + */ + goto __pyx_L5; + } + + /* "View.MemoryView":431 + * self.setitem_slice_assignment(self[index], obj) + * else: + * self.setitem_slice_assign_scalar(self[index], value) # <<<<<<<<<<<<<< + * else: + * self.setitem_indexed(index, value) + */ + /*else*/ { + __pyx_t_3 = __Pyx_PyObject_GetItem(((PyObject *)__pyx_v_self), __pyx_v_index); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 431, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (!(likely(((__pyx_t_3) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_3, __pyx_memoryview_type))))) __PYX_ERR(1, 431, __pyx_L1_error) + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->setitem_slice_assign_scalar(__pyx_v_self, ((struct __pyx_memoryview_obj *)__pyx_t_3), __pyx_v_value); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 431, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_L5:; + + /* "View.MemoryView":426 + * have_slices, index = _unellipsify(index, self.view.ndim) + * + * if have_slices: # <<<<<<<<<<<<<< + * obj = self.is_slice(value) + * if obj: + */ + goto __pyx_L4; + } + + /* "View.MemoryView":433 + * self.setitem_slice_assign_scalar(self[index], value) + * else: + * self.setitem_indexed(index, value) # <<<<<<<<<<<<<< + * + * cdef is_slice(self, obj): + */ + /*else*/ { + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->setitem_indexed(__pyx_v_self, __pyx_v_index, __pyx_v_value); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 433, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_L4:; + + /* "View.MemoryView":420 + * return self.convert_item_to_object(itemp) + * + * def __setitem__(memoryview self, object index, object value): # <<<<<<<<<<<<<< + * if self.view.readonly: + * raise TypeError, "Cannot assign to read-only memoryview" + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.__setitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_have_slices); + __Pyx_XDECREF(__pyx_v_obj); + __Pyx_XDECREF(__pyx_v_index); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":435 + * self.setitem_indexed(index, value) + * + * cdef is_slice(self, obj): # <<<<<<<<<<<<<< + * if not isinstance(obj, memoryview): + * try: + */ + +static PyObject *__pyx_memoryview_is_slice(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("is_slice", 0); + __Pyx_INCREF(__pyx_v_obj); + + /* "View.MemoryView":436 + * + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): # <<<<<<<<<<<<<< + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + */ + __pyx_t_1 = __Pyx_TypeCheck(__pyx_v_obj, __pyx_memoryview_type); + __pyx_t_2 = (!__pyx_t_1); + if (__pyx_t_2) { + + /* "View.MemoryView":437 + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): + * try: # <<<<<<<<<<<<<< + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_3, &__pyx_t_4, &__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_4); + __Pyx_XGOTREF(__pyx_t_5); + /*try:*/ { + + /* "View.MemoryView":438 + * if not isinstance(obj, memoryview): + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, # <<<<<<<<<<<<<< + * self.dtype_is_object) + * except TypeError: + */ + __pyx_t_6 = __Pyx_PyInt_From_int(((__pyx_v_self->flags & (~PyBUF_WRITABLE)) | PyBUF_ANY_CONTIGUOUS)); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 438, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_6); + + /* "View.MemoryView":439 + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) # <<<<<<<<<<<<<< + * except TypeError: + * return None + */ + __pyx_t_7 = __Pyx_PyBool_FromLong(__pyx_v_self->dtype_is_object); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 439, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_7); + + /* "View.MemoryView":438 + * if not isinstance(obj, memoryview): + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, # <<<<<<<<<<<<<< + * self.dtype_is_object) + * except TypeError: + */ + __pyx_t_8 = PyTuple_New(3); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 438, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_INCREF(__pyx_v_obj); + __Pyx_GIVEREF(__pyx_v_obj); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_8, 0, __pyx_v_obj)) __PYX_ERR(1, 438, __pyx_L4_error); + __Pyx_GIVEREF(__pyx_t_6); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_8, 1, __pyx_t_6)) __PYX_ERR(1, 438, __pyx_L4_error); + __Pyx_GIVEREF(__pyx_t_7); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_8, 2, __pyx_t_7)) __PYX_ERR(1, 438, __pyx_L4_error); + __pyx_t_6 = 0; + __pyx_t_7 = 0; + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_memoryview_type), __pyx_t_8, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 438, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_DECREF_SET(__pyx_v_obj, __pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":437 + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): + * try: # <<<<<<<<<<<<<< + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + */ + } + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + goto __pyx_L9_try_end; + __pyx_L4_error:; + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + + /* "View.MemoryView":440 + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + * except TypeError: # <<<<<<<<<<<<<< + * return None + * + */ + __pyx_t_9 = __Pyx_PyErr_ExceptionMatches(__pyx_builtin_TypeError); + if (__pyx_t_9) { + __Pyx_AddTraceback("View.MemoryView.memoryview.is_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_7, &__pyx_t_8, &__pyx_t_6) < 0) __PYX_ERR(1, 440, __pyx_L6_except_error) + __Pyx_XGOTREF(__pyx_t_7); + __Pyx_XGOTREF(__pyx_t_8); + __Pyx_XGOTREF(__pyx_t_6); + + /* "View.MemoryView":441 + * self.dtype_is_object) + * except TypeError: + * return None # <<<<<<<<<<<<<< + * + * return obj + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L7_except_return; + } + goto __pyx_L6_except_error; + + /* "View.MemoryView":437 + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): + * try: # <<<<<<<<<<<<<< + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + */ + __pyx_L6_except_error:; + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_XGIVEREF(__pyx_t_5); + __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_4, __pyx_t_5); + goto __pyx_L1_error; + __pyx_L7_except_return:; + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_XGIVEREF(__pyx_t_5); + __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_4, __pyx_t_5); + goto __pyx_L0; + __pyx_L9_try_end:; + } + + /* "View.MemoryView":436 + * + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): # <<<<<<<<<<<<<< + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + */ + } + + /* "View.MemoryView":443 + * return None + * + * return obj # <<<<<<<<<<<<<< + * + * cdef setitem_slice_assignment(self, dst, src): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_obj); + __pyx_r = __pyx_v_obj; + goto __pyx_L0; + + /* "View.MemoryView":435 + * self.setitem_indexed(index, value) + * + * cdef is_slice(self, obj): # <<<<<<<<<<<<<< + * if not isinstance(obj, memoryview): + * try: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("View.MemoryView.memoryview.is_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_obj); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":445 + * return obj + * + * cdef setitem_slice_assignment(self, dst, src): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice dst_slice + * cdef __Pyx_memviewslice src_slice + */ + +static PyObject *__pyx_memoryview_setitem_slice_assignment(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_dst, PyObject *__pyx_v_src) { + __Pyx_memviewslice __pyx_v_dst_slice; + __Pyx_memviewslice __pyx_v_src_slice; + __Pyx_memviewslice __pyx_v_msrc; + __Pyx_memviewslice __pyx_v_mdst; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_t_3; + int __pyx_t_4; + int __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("setitem_slice_assignment", 1); + + /* "View.MemoryView":448 + * cdef __Pyx_memviewslice dst_slice + * cdef __Pyx_memviewslice src_slice + * cdef __Pyx_memviewslice msrc = get_slice_from_memview(src, &src_slice)[0] # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice mdst = get_slice_from_memview(dst, &dst_slice)[0] + * + */ + if (!(likely(((__pyx_v_src) == Py_None) || likely(__Pyx_TypeTest(__pyx_v_src, __pyx_memoryview_type))))) __PYX_ERR(1, 448, __pyx_L1_error) + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(((struct __pyx_memoryview_obj *)__pyx_v_src), (&__pyx_v_src_slice)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 448, __pyx_L1_error) + __pyx_v_msrc = (__pyx_t_1[0]); + + /* "View.MemoryView":449 + * cdef __Pyx_memviewslice src_slice + * cdef __Pyx_memviewslice msrc = get_slice_from_memview(src, &src_slice)[0] + * cdef __Pyx_memviewslice mdst = get_slice_from_memview(dst, &dst_slice)[0] # <<<<<<<<<<<<<< + * + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) + */ + if (!(likely(((__pyx_v_dst) == Py_None) || likely(__Pyx_TypeTest(__pyx_v_dst, __pyx_memoryview_type))))) __PYX_ERR(1, 449, __pyx_L1_error) + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(((struct __pyx_memoryview_obj *)__pyx_v_dst), (&__pyx_v_dst_slice)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 449, __pyx_L1_error) + __pyx_v_mdst = (__pyx_t_1[0]); + + /* "View.MemoryView":451 + * cdef __Pyx_memviewslice mdst = get_slice_from_memview(dst, &dst_slice)[0] + * + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) # <<<<<<<<<<<<<< + * + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_src, __pyx_n_s_ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 451, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_PyInt_As_int(__pyx_t_2); if (unlikely((__pyx_t_3 == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 451, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_dst, __pyx_n_s_ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 451, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __Pyx_PyInt_As_int(__pyx_t_2); if (unlikely((__pyx_t_4 == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 451, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_5 = __pyx_memoryview_copy_contents(__pyx_v_msrc, __pyx_v_mdst, __pyx_t_3, __pyx_t_4, __pyx_v_self->dtype_is_object); if (unlikely(__pyx_t_5 == ((int)-1))) __PYX_ERR(1, 451, __pyx_L1_error) + + /* "View.MemoryView":445 + * return obj + * + * cdef setitem_slice_assignment(self, dst, src): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice dst_slice + * cdef __Pyx_memviewslice src_slice + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.setitem_slice_assignment", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":453 + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) + * + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): # <<<<<<<<<<<<<< + * cdef int array[128] + * cdef void *tmp = NULL + */ + +static PyObject *__pyx_memoryview_setitem_slice_assign_scalar(struct __pyx_memoryview_obj *__pyx_v_self, struct __pyx_memoryview_obj *__pyx_v_dst, PyObject *__pyx_v_value) { + int __pyx_v_array[0x80]; + void *__pyx_v_tmp; + void *__pyx_v_item; + __Pyx_memviewslice *__pyx_v_dst_slice; + __Pyx_memviewslice __pyx_v_tmp_slice; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_t_5; + char const *__pyx_t_6; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + PyObject *__pyx_t_9 = NULL; + PyObject *__pyx_t_10 = NULL; + PyObject *__pyx_t_11 = NULL; + PyObject *__pyx_t_12 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("setitem_slice_assign_scalar", 1); + + /* "View.MemoryView":455 + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): + * cdef int array[128] + * cdef void *tmp = NULL # <<<<<<<<<<<<<< + * cdef void *item + * + */ + __pyx_v_tmp = NULL; + + /* "View.MemoryView":460 + * cdef __Pyx_memviewslice *dst_slice + * cdef __Pyx_memviewslice tmp_slice + * dst_slice = get_slice_from_memview(dst, &tmp_slice) # <<<<<<<<<<<<<< + * + * if self.view.itemsize > sizeof(array): + */ + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(__pyx_v_dst, (&__pyx_v_tmp_slice)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 460, __pyx_L1_error) + __pyx_v_dst_slice = __pyx_t_1; + + /* "View.MemoryView":462 + * dst_slice = get_slice_from_memview(dst, &tmp_slice) + * + * if self.view.itemsize > sizeof(array): # <<<<<<<<<<<<<< + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: + */ + __pyx_t_2 = (((size_t)__pyx_v_self->view.itemsize) > (sizeof(__pyx_v_array))); + if (__pyx_t_2) { + + /* "View.MemoryView":463 + * + * if self.view.itemsize > sizeof(array): + * tmp = PyMem_Malloc(self.view.itemsize) # <<<<<<<<<<<<<< + * if tmp == NULL: + * raise MemoryError + */ + __pyx_v_tmp = PyMem_Malloc(__pyx_v_self->view.itemsize); + + /* "View.MemoryView":464 + * if self.view.itemsize > sizeof(array): + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * item = tmp + */ + __pyx_t_2 = (__pyx_v_tmp == NULL); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":465 + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: + * raise MemoryError # <<<<<<<<<<<<<< + * item = tmp + * else: + */ + PyErr_NoMemory(); __PYX_ERR(1, 465, __pyx_L1_error) + + /* "View.MemoryView":464 + * if self.view.itemsize > sizeof(array): + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * item = tmp + */ + } + + /* "View.MemoryView":466 + * if tmp == NULL: + * raise MemoryError + * item = tmp # <<<<<<<<<<<<<< + * else: + * item = array + */ + __pyx_v_item = __pyx_v_tmp; + + /* "View.MemoryView":462 + * dst_slice = get_slice_from_memview(dst, &tmp_slice) + * + * if self.view.itemsize > sizeof(array): # <<<<<<<<<<<<<< + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":468 + * item = tmp + * else: + * item = array # <<<<<<<<<<<<<< + * + * try: + */ + /*else*/ { + __pyx_v_item = ((void *)__pyx_v_array); + } + __pyx_L3:; + + /* "View.MemoryView":470 + * item = array + * + * try: # <<<<<<<<<<<<<< + * if self.dtype_is_object: + * ( item)[0] = value + */ + /*try:*/ { + + /* "View.MemoryView":471 + * + * try: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * ( item)[0] = value + * else: + */ + if (__pyx_v_self->dtype_is_object) { + + /* "View.MemoryView":472 + * try: + * if self.dtype_is_object: + * ( item)[0] = value # <<<<<<<<<<<<<< + * else: + * self.assign_item_from_object( item, value) + */ + (((PyObject **)__pyx_v_item)[0]) = ((PyObject *)__pyx_v_value); + + /* "View.MemoryView":471 + * + * try: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * ( item)[0] = value + * else: + */ + goto __pyx_L8; + } + + /* "View.MemoryView":474 + * ( item)[0] = value + * else: + * self.assign_item_from_object( item, value) # <<<<<<<<<<<<<< + * + * + */ + /*else*/ { + __pyx_t_3 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->assign_item_from_object(__pyx_v_self, ((char *)__pyx_v_item), __pyx_v_value); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 474, __pyx_L6_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_L8:; + + /* "View.MemoryView":478 + * + * + * if self.view.suboffsets != NULL: # <<<<<<<<<<<<<< + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, + */ + __pyx_t_2 = (__pyx_v_self->view.suboffsets != NULL); + if (__pyx_t_2) { + + /* "View.MemoryView":479 + * + * if self.view.suboffsets != NULL: + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) # <<<<<<<<<<<<<< + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, + * item, self.dtype_is_object) + */ + __pyx_t_4 = assert_direct_dimensions(__pyx_v_self->view.suboffsets, __pyx_v_self->view.ndim); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(1, 479, __pyx_L6_error) + + /* "View.MemoryView":478 + * + * + * if self.view.suboffsets != NULL: # <<<<<<<<<<<<<< + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, + */ + } + + /* "View.MemoryView":480 + * if self.view.suboffsets != NULL: + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, # <<<<<<<<<<<<<< + * item, self.dtype_is_object) + * finally: + */ + __pyx_memoryview_slice_assign_scalar(__pyx_v_dst_slice, __pyx_v_dst->view.ndim, __pyx_v_self->view.itemsize, __pyx_v_item, __pyx_v_self->dtype_is_object); + } + + /* "View.MemoryView":483 + * item, self.dtype_is_object) + * finally: + * PyMem_Free(tmp) # <<<<<<<<<<<<<< + * + * cdef setitem_indexed(self, index, value): + */ + /*finally:*/ { + /*normal exit:*/{ + PyMem_Free(__pyx_v_tmp); + goto __pyx_L7; + } + __pyx_L6_error:; + /*exception exit:*/{ + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __pyx_t_7 = 0; __pyx_t_8 = 0; __pyx_t_9 = 0; __pyx_t_10 = 0; __pyx_t_11 = 0; __pyx_t_12 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (PY_MAJOR_VERSION >= 3) __Pyx_ExceptionSwap(&__pyx_t_10, &__pyx_t_11, &__pyx_t_12); + if ((PY_MAJOR_VERSION < 3) || unlikely(__Pyx_GetException(&__pyx_t_7, &__pyx_t_8, &__pyx_t_9) < 0)) __Pyx_ErrFetch(&__pyx_t_7, &__pyx_t_8, &__pyx_t_9); + __Pyx_XGOTREF(__pyx_t_7); + __Pyx_XGOTREF(__pyx_t_8); + __Pyx_XGOTREF(__pyx_t_9); + __Pyx_XGOTREF(__pyx_t_10); + __Pyx_XGOTREF(__pyx_t_11); + __Pyx_XGOTREF(__pyx_t_12); + __pyx_t_4 = __pyx_lineno; __pyx_t_5 = __pyx_clineno; __pyx_t_6 = __pyx_filename; + { + PyMem_Free(__pyx_v_tmp); + } + if (PY_MAJOR_VERSION >= 3) { + __Pyx_XGIVEREF(__pyx_t_10); + __Pyx_XGIVEREF(__pyx_t_11); + __Pyx_XGIVEREF(__pyx_t_12); + __Pyx_ExceptionReset(__pyx_t_10, __pyx_t_11, __pyx_t_12); + } + __Pyx_XGIVEREF(__pyx_t_7); + __Pyx_XGIVEREF(__pyx_t_8); + __Pyx_XGIVEREF(__pyx_t_9); + __Pyx_ErrRestore(__pyx_t_7, __pyx_t_8, __pyx_t_9); + __pyx_t_7 = 0; __pyx_t_8 = 0; __pyx_t_9 = 0; __pyx_t_10 = 0; __pyx_t_11 = 0; __pyx_t_12 = 0; + __pyx_lineno = __pyx_t_4; __pyx_clineno = __pyx_t_5; __pyx_filename = __pyx_t_6; + goto __pyx_L1_error; + } + __pyx_L7:; + } + + /* "View.MemoryView":453 + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) + * + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): # <<<<<<<<<<<<<< + * cdef int array[128] + * cdef void *tmp = NULL + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.setitem_slice_assign_scalar", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":485 + * PyMem_Free(tmp) + * + * cdef setitem_indexed(self, index, value): # <<<<<<<<<<<<<< + * cdef char *itemp = self.get_item_pointer(index) + * self.assign_item_from_object(itemp, value) + */ + +static PyObject *__pyx_memoryview_setitem_indexed(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value) { + char *__pyx_v_itemp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + char *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("setitem_indexed", 1); + + /* "View.MemoryView":486 + * + * cdef setitem_indexed(self, index, value): + * cdef char *itemp = self.get_item_pointer(index) # <<<<<<<<<<<<<< + * self.assign_item_from_object(itemp, value) + * + */ + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->get_item_pointer(__pyx_v_self, __pyx_v_index); if (unlikely(__pyx_t_1 == ((char *)NULL))) __PYX_ERR(1, 486, __pyx_L1_error) + __pyx_v_itemp = __pyx_t_1; + + /* "View.MemoryView":487 + * cdef setitem_indexed(self, index, value): + * cdef char *itemp = self.get_item_pointer(index) + * self.assign_item_from_object(itemp, value) # <<<<<<<<<<<<<< + * + * cdef convert_item_to_object(self, char *itemp): + */ + __pyx_t_2 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->assign_item_from_object(__pyx_v_self, __pyx_v_itemp, __pyx_v_value); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 487, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":485 + * PyMem_Free(tmp) + * + * cdef setitem_indexed(self, index, value): # <<<<<<<<<<<<<< + * cdef char *itemp = self.get_item_pointer(index) + * self.assign_item_from_object(itemp, value) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.setitem_indexed", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":489 + * self.assign_item_from_object(itemp, value) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + +static PyObject *__pyx_memoryview_convert_item_to_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp) { + PyObject *__pyx_v_struct = NULL; + PyObject *__pyx_v_bytesitem = 0; + PyObject *__pyx_v_result = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + int __pyx_t_8; + Py_ssize_t __pyx_t_9; + int __pyx_t_10; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("convert_item_to_object", 1); + + /* "View.MemoryView":492 + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + * import struct # <<<<<<<<<<<<<< + * cdef bytes bytesitem + * + */ + __pyx_t_1 = __Pyx_ImportDottedModule(__pyx_n_s_struct, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 492, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_struct = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":495 + * cdef bytes bytesitem + * + * bytesitem = itemp[:self.view.itemsize] # <<<<<<<<<<<<<< + * try: + * result = struct.unpack(self.view.format, bytesitem) + */ + __pyx_t_1 = __Pyx_PyBytes_FromStringAndSize(__pyx_v_itemp + 0, __pyx_v_self->view.itemsize - 0); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 495, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_bytesitem = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":496 + * + * bytesitem = itemp[:self.view.itemsize] + * try: # <<<<<<<<<<<<<< + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_2, &__pyx_t_3, &__pyx_t_4); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_4); + /*try:*/ { + + /* "View.MemoryView":497 + * bytesitem = itemp[:self.view.itemsize] + * try: + * result = struct.unpack(self.view.format, bytesitem) # <<<<<<<<<<<<<< + * except struct.error: + * raise ValueError, "Unable to convert item to object" + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_unpack); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 497, __pyx_L3_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = __Pyx_PyBytes_FromString(__pyx_v_self->view.format); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 497, __pyx_L3_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_7 = NULL; + __pyx_t_8 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_8 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_7, __pyx_t_6, __pyx_v_bytesitem}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_8, 2+__pyx_t_8); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 497, __pyx_L3_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + __pyx_v_result = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":496 + * + * bytesitem = itemp[:self.view.itemsize] + * try: # <<<<<<<<<<<<<< + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + */ + } + + /* "View.MemoryView":501 + * raise ValueError, "Unable to convert item to object" + * else: + * if len(self.view.format) == 1: # <<<<<<<<<<<<<< + * return result[0] + * return result + */ + /*else:*/ { + __pyx_t_9 = __Pyx_ssize_strlen(__pyx_v_self->view.format); if (unlikely(__pyx_t_9 == ((Py_ssize_t)-1))) __PYX_ERR(1, 501, __pyx_L5_except_error) + __pyx_t_10 = (__pyx_t_9 == 1); + if (__pyx_t_10) { + + /* "View.MemoryView":502 + * else: + * if len(self.view.format) == 1: + * return result[0] # <<<<<<<<<<<<<< + * return result + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_result, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 502, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L6_except_return; + + /* "View.MemoryView":501 + * raise ValueError, "Unable to convert item to object" + * else: + * if len(self.view.format) == 1: # <<<<<<<<<<<<<< + * return result[0] + * return result + */ + } + + /* "View.MemoryView":503 + * if len(self.view.format) == 1: + * return result[0] + * return result # <<<<<<<<<<<<<< + * + * cdef assign_item_from_object(self, char *itemp, object value): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_result); + __pyx_r = __pyx_v_result; + goto __pyx_L6_except_return; + } + __pyx_L3_error:; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":498 + * try: + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: # <<<<<<<<<<<<<< + * raise ValueError, "Unable to convert item to object" + * else: + */ + __Pyx_ErrFetch(&__pyx_t_1, &__pyx_t_5, &__pyx_t_6); + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_error); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 498, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_8 = __Pyx_PyErr_GivenExceptionMatches(__pyx_t_1, __pyx_t_7); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_ErrRestore(__pyx_t_1, __pyx_t_5, __pyx_t_6); + __pyx_t_1 = 0; __pyx_t_5 = 0; __pyx_t_6 = 0; + if (__pyx_t_8) { + __Pyx_AddTraceback("View.MemoryView.memoryview.convert_item_to_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_6, &__pyx_t_5, &__pyx_t_1) < 0) __PYX_ERR(1, 498, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_1); + + /* "View.MemoryView":499 + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + * raise ValueError, "Unable to convert item to object" # <<<<<<<<<<<<<< + * else: + * if len(self.view.format) == 1: + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Unable_to_convert_item_to_object, 0, 0); + __PYX_ERR(1, 499, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "View.MemoryView":496 + * + * bytesitem = itemp[:self.view.itemsize] + * try: # <<<<<<<<<<<<<< + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_ExceptionReset(__pyx_t_2, __pyx_t_3, __pyx_t_4); + goto __pyx_L1_error; + __pyx_L6_except_return:; + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_ExceptionReset(__pyx_t_2, __pyx_t_3, __pyx_t_4); + goto __pyx_L0; + } + + /* "View.MemoryView":489 + * self.assign_item_from_object(itemp, value) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("View.MemoryView.memoryview.convert_item_to_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_struct); + __Pyx_XDECREF(__pyx_v_bytesitem); + __Pyx_XDECREF(__pyx_v_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":505 + * return result + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + +static PyObject *__pyx_memoryview_assign_item_from_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value) { + PyObject *__pyx_v_struct = NULL; + char __pyx_v_c; + PyObject *__pyx_v_bytesvalue = 0; + Py_ssize_t __pyx_v_i; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + Py_ssize_t __pyx_t_7; + PyObject *__pyx_t_8 = NULL; + char *__pyx_t_9; + char *__pyx_t_10; + char *__pyx_t_11; + char *__pyx_t_12; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("assign_item_from_object", 1); + + /* "View.MemoryView":508 + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + * import struct # <<<<<<<<<<<<<< + * cdef char c + * cdef bytes bytesvalue + */ + __pyx_t_1 = __Pyx_ImportDottedModule(__pyx_n_s_struct, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 508, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_struct = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":513 + * cdef Py_ssize_t i + * + * if isinstance(value, tuple): # <<<<<<<<<<<<<< + * bytesvalue = struct.pack(self.view.format, *value) + * else: + */ + __pyx_t_2 = PyTuple_Check(__pyx_v_value); + if (__pyx_t_2) { + + /* "View.MemoryView":514 + * + * if isinstance(value, tuple): + * bytesvalue = struct.pack(self.view.format, *value) # <<<<<<<<<<<<<< + * else: + * bytesvalue = struct.pack(self.view.format, value) + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_pack); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyBytes_FromString(__pyx_v_self->view.format); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PyTuple_New(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_3)) __PYX_ERR(1, 514, __pyx_L1_error); + __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PySequence_Tuple(__pyx_v_value); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = PyNumber_Add(__pyx_t_4, __pyx_t_3); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PyObject_Call(__pyx_t_1, __pyx_t_5, NULL); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (!(likely(PyBytes_CheckExact(__pyx_t_3))||((__pyx_t_3) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_t_3))) __PYX_ERR(1, 514, __pyx_L1_error) + __pyx_v_bytesvalue = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":513 + * cdef Py_ssize_t i + * + * if isinstance(value, tuple): # <<<<<<<<<<<<<< + * bytesvalue = struct.pack(self.view.format, *value) + * else: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":516 + * bytesvalue = struct.pack(self.view.format, *value) + * else: + * bytesvalue = struct.pack(self.view.format, value) # <<<<<<<<<<<<<< + * + * for i, c in enumerate(bytesvalue): + */ + /*else*/ { + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_pack); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 516, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 = __Pyx_PyBytes_FromString(__pyx_v_self->view.format); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 516, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_4 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_4, __pyx_t_1, __pyx_v_value}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 516, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + if (!(likely(PyBytes_CheckExact(__pyx_t_3))||((__pyx_t_3) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_t_3))) __PYX_ERR(1, 516, __pyx_L1_error) + __pyx_v_bytesvalue = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; + } + __pyx_L3:; + + /* "View.MemoryView":518 + * bytesvalue = struct.pack(self.view.format, value) + * + * for i, c in enumerate(bytesvalue): # <<<<<<<<<<<<<< + * itemp[i] = c + * + */ + __pyx_t_7 = 0; + if (unlikely(__pyx_v_bytesvalue == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' is not iterable"); + __PYX_ERR(1, 518, __pyx_L1_error) + } + __Pyx_INCREF(__pyx_v_bytesvalue); + __pyx_t_8 = __pyx_v_bytesvalue; + __pyx_t_10 = PyBytes_AS_STRING(__pyx_t_8); + __pyx_t_11 = (__pyx_t_10 + PyBytes_GET_SIZE(__pyx_t_8)); + for (__pyx_t_12 = __pyx_t_10; __pyx_t_12 < __pyx_t_11; __pyx_t_12++) { + __pyx_t_9 = __pyx_t_12; + __pyx_v_c = (__pyx_t_9[0]); + + /* "View.MemoryView":519 + * + * for i, c in enumerate(bytesvalue): + * itemp[i] = c # <<<<<<<<<<<<<< + * + * @cname('getbuffer') + */ + __pyx_v_i = __pyx_t_7; + + /* "View.MemoryView":518 + * bytesvalue = struct.pack(self.view.format, value) + * + * for i, c in enumerate(bytesvalue): # <<<<<<<<<<<<<< + * itemp[i] = c + * + */ + __pyx_t_7 = (__pyx_t_7 + 1); + + /* "View.MemoryView":519 + * + * for i, c in enumerate(bytesvalue): + * itemp[i] = c # <<<<<<<<<<<<<< + * + * @cname('getbuffer') + */ + (__pyx_v_itemp[__pyx_v_i]) = __pyx_v_c; + } + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + + /* "View.MemoryView":505 + * return result + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("View.MemoryView.memoryview.assign_item_from_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_struct); + __Pyx_XDECREF(__pyx_v_bytesvalue); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":521 + * itemp[i] = c + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: + */ + +/* Python wrapper */ +CYTHON_UNUSED static int __pyx_memoryview_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +CYTHON_UNUSED static int __pyx_memoryview_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getbuffer__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_8__getbuffer__(((struct __pyx_memoryview_obj *)__pyx_v_self), ((Py_buffer *)__pyx_v_info), ((int)__pyx_v_flags)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_8__getbuffer__(struct __pyx_memoryview_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + Py_ssize_t *__pyx_t_3; + char *__pyx_t_4; + void *__pyx_t_5; + int __pyx_t_6; + Py_ssize_t __pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + if (unlikely(__pyx_v_info == NULL)) { + PyErr_SetString(PyExc_BufferError, "PyObject_GetBuffer: view==NULL argument is obsolete"); + return -1; + } + __Pyx_RefNannySetupContext("__getbuffer__", 0); + __pyx_v_info->obj = Py_None; __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(__pyx_v_info->obj); + + /* "View.MemoryView":523 + * @cname('getbuffer') + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: # <<<<<<<<<<<<<< + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + */ + __pyx_t_2 = ((__pyx_v_flags & PyBUF_WRITABLE) != 0); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_1 = __pyx_v_self->view.readonly; + __pyx_L4_bool_binop_done:; + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":524 + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: + * raise ValueError, "Cannot create writable memory view from read-only memoryview" # <<<<<<<<<<<<<< + * + * if flags & PyBUF_ND: + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Cannot_create_writable_memory_vi, 0, 0); + __PYX_ERR(1, 524, __pyx_L1_error) + + /* "View.MemoryView":523 + * @cname('getbuffer') + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: # <<<<<<<<<<<<<< + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + */ + } + + /* "View.MemoryView":526 + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + * if flags & PyBUF_ND: # <<<<<<<<<<<<<< + * info.shape = self.view.shape + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_ND) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":527 + * + * if flags & PyBUF_ND: + * info.shape = self.view.shape # <<<<<<<<<<<<<< + * else: + * info.shape = NULL + */ + __pyx_t_3 = __pyx_v_self->view.shape; + __pyx_v_info->shape = __pyx_t_3; + + /* "View.MemoryView":526 + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + * if flags & PyBUF_ND: # <<<<<<<<<<<<<< + * info.shape = self.view.shape + * else: + */ + goto __pyx_L6; + } + + /* "View.MemoryView":529 + * info.shape = self.view.shape + * else: + * info.shape = NULL # <<<<<<<<<<<<<< + * + * if flags & PyBUF_STRIDES: + */ + /*else*/ { + __pyx_v_info->shape = NULL; + } + __pyx_L6:; + + /* "View.MemoryView":531 + * info.shape = NULL + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.strides = self.view.strides + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_STRIDES) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":532 + * + * if flags & PyBUF_STRIDES: + * info.strides = self.view.strides # <<<<<<<<<<<<<< + * else: + * info.strides = NULL + */ + __pyx_t_3 = __pyx_v_self->view.strides; + __pyx_v_info->strides = __pyx_t_3; + + /* "View.MemoryView":531 + * info.shape = NULL + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.strides = self.view.strides + * else: + */ + goto __pyx_L7; + } + + /* "View.MemoryView":534 + * info.strides = self.view.strides + * else: + * info.strides = NULL # <<<<<<<<<<<<<< + * + * if flags & PyBUF_INDIRECT: + */ + /*else*/ { + __pyx_v_info->strides = NULL; + } + __pyx_L7:; + + /* "View.MemoryView":536 + * info.strides = NULL + * + * if flags & PyBUF_INDIRECT: # <<<<<<<<<<<<<< + * info.suboffsets = self.view.suboffsets + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_INDIRECT) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":537 + * + * if flags & PyBUF_INDIRECT: + * info.suboffsets = self.view.suboffsets # <<<<<<<<<<<<<< + * else: + * info.suboffsets = NULL + */ + __pyx_t_3 = __pyx_v_self->view.suboffsets; + __pyx_v_info->suboffsets = __pyx_t_3; + + /* "View.MemoryView":536 + * info.strides = NULL + * + * if flags & PyBUF_INDIRECT: # <<<<<<<<<<<<<< + * info.suboffsets = self.view.suboffsets + * else: + */ + goto __pyx_L8; + } + + /* "View.MemoryView":539 + * info.suboffsets = self.view.suboffsets + * else: + * info.suboffsets = NULL # <<<<<<<<<<<<<< + * + * if flags & PyBUF_FORMAT: + */ + /*else*/ { + __pyx_v_info->suboffsets = NULL; + } + __pyx_L8:; + + /* "View.MemoryView":541 + * info.suboffsets = NULL + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * info.format = self.view.format + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_FORMAT) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":542 + * + * if flags & PyBUF_FORMAT: + * info.format = self.view.format # <<<<<<<<<<<<<< + * else: + * info.format = NULL + */ + __pyx_t_4 = __pyx_v_self->view.format; + __pyx_v_info->format = __pyx_t_4; + + /* "View.MemoryView":541 + * info.suboffsets = NULL + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * info.format = self.view.format + * else: + */ + goto __pyx_L9; + } + + /* "View.MemoryView":544 + * info.format = self.view.format + * else: + * info.format = NULL # <<<<<<<<<<<<<< + * + * info.buf = self.view.buf + */ + /*else*/ { + __pyx_v_info->format = NULL; + } + __pyx_L9:; + + /* "View.MemoryView":546 + * info.format = NULL + * + * info.buf = self.view.buf # <<<<<<<<<<<<<< + * info.ndim = self.view.ndim + * info.itemsize = self.view.itemsize + */ + __pyx_t_5 = __pyx_v_self->view.buf; + __pyx_v_info->buf = __pyx_t_5; + + /* "View.MemoryView":547 + * + * info.buf = self.view.buf + * info.ndim = self.view.ndim # <<<<<<<<<<<<<< + * info.itemsize = self.view.itemsize + * info.len = self.view.len + */ + __pyx_t_6 = __pyx_v_self->view.ndim; + __pyx_v_info->ndim = __pyx_t_6; + + /* "View.MemoryView":548 + * info.buf = self.view.buf + * info.ndim = self.view.ndim + * info.itemsize = self.view.itemsize # <<<<<<<<<<<<<< + * info.len = self.view.len + * info.readonly = self.view.readonly + */ + __pyx_t_7 = __pyx_v_self->view.itemsize; + __pyx_v_info->itemsize = __pyx_t_7; + + /* "View.MemoryView":549 + * info.ndim = self.view.ndim + * info.itemsize = self.view.itemsize + * info.len = self.view.len # <<<<<<<<<<<<<< + * info.readonly = self.view.readonly + * info.obj = self + */ + __pyx_t_7 = __pyx_v_self->view.len; + __pyx_v_info->len = __pyx_t_7; + + /* "View.MemoryView":550 + * info.itemsize = self.view.itemsize + * info.len = self.view.len + * info.readonly = self.view.readonly # <<<<<<<<<<<<<< + * info.obj = self + * + */ + __pyx_t_1 = __pyx_v_self->view.readonly; + __pyx_v_info->readonly = __pyx_t_1; + + /* "View.MemoryView":551 + * info.len = self.view.len + * info.readonly = self.view.readonly + * info.obj = self # <<<<<<<<<<<<<< + * + * + */ + __Pyx_INCREF((PyObject *)__pyx_v_self); + __Pyx_GIVEREF((PyObject *)__pyx_v_self); + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); + __pyx_v_info->obj = ((PyObject *)__pyx_v_self); + + /* "View.MemoryView":521 + * itemp[i] = c + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__getbuffer__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + if (__pyx_v_info->obj != NULL) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + goto __pyx_L2; + __pyx_L0:; + if (__pyx_v_info->obj == Py_None) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + __pyx_L2:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":554 + * + * + * @property # <<<<<<<<<<<<<< + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_1T_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_1T_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_1T___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_1T___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + struct __pyx_memoryviewslice_obj *__pyx_v_result = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":556 + * @property + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) # <<<<<<<<<<<<<< + * transpose_memslice(&result.from_slice) + * return result + */ + __pyx_t_1 = __pyx_memoryview_copy_object(__pyx_v_self); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 556, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (!(likely(((__pyx_t_1) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_1, __pyx_memoryviewslice_type))))) __PYX_ERR(1, 556, __pyx_L1_error) + __pyx_v_result = ((struct __pyx_memoryviewslice_obj *)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":557 + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) + * transpose_memslice(&result.from_slice) # <<<<<<<<<<<<<< + * return result + * + */ + __pyx_t_2 = __pyx_memslice_transpose((&__pyx_v_result->from_slice)); if (unlikely(__pyx_t_2 == ((int)-1))) __PYX_ERR(1, 557, __pyx_L1_error) + + /* "View.MemoryView":558 + * cdef _memoryviewslice result = memoryview_copy(self) + * transpose_memslice(&result.from_slice) + * return result # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = ((PyObject *)__pyx_v_result); + goto __pyx_L0; + + /* "View.MemoryView":554 + * + * + * @property # <<<<<<<<<<<<<< + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.T.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":560 + * return result + * + * @property # <<<<<<<<<<<<<< + * def base(self): + * return self._get_base() + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4base_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4base_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_4base___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4base___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":562 + * @property + * def base(self): + * return self._get_base() # <<<<<<<<<<<<<< + * + * cdef _get_base(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->_get_base(__pyx_v_self); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 562, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":560 + * return result + * + * @property # <<<<<<<<<<<<<< + * def base(self): + * return self._get_base() + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.base.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":564 + * return self._get_base() + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.obj + * + */ + +static PyObject *__pyx_memoryview__get_base(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("_get_base", 1); + + /* "View.MemoryView":565 + * + * cdef _get_base(self): + * return self.obj # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->obj); + __pyx_r = __pyx_v_self->obj; + goto __pyx_L0; + + /* "View.MemoryView":564 + * return self._get_base() + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.obj + * + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":567 + * return self.obj + * + * @property # <<<<<<<<<<<<<< + * def shape(self): + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_5shape_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_5shape_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_5shape___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_5shape___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_7genexpr__pyx_v_length; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + PyObject *__pyx_t_5 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":569 + * @property + * def shape(self): + * return tuple([length for length in self.view.shape[:self.view.ndim]]) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + { /* enter inner scope */ + __pyx_t_1 = PyList_New(0); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 569, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = (__pyx_v_self->view.shape + __pyx_v_self->view.ndim); + for (__pyx_t_4 = __pyx_v_self->view.shape; __pyx_t_4 < __pyx_t_3; __pyx_t_4++) { + __pyx_t_2 = __pyx_t_4; + __pyx_7genexpr__pyx_v_length = (__pyx_t_2[0]); + __pyx_t_5 = PyInt_FromSsize_t(__pyx_7genexpr__pyx_v_length); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 569, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_1, (PyObject*)__pyx_t_5))) __PYX_ERR(1, 569, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + } /* exit inner scope */ + __pyx_t_5 = PyList_AsTuple(((PyObject*)__pyx_t_1)); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 569, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_5; + __pyx_t_5 = 0; + goto __pyx_L0; + + /* "View.MemoryView":567 + * return self.obj + * + * @property # <<<<<<<<<<<<<< + * def shape(self): + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.memoryview.shape.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":571 + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def strides(self): + * if self.view.strides == NULL: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_7strides_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_7strides_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_7strides___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_7strides___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_8genexpr1__pyx_v_stride; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + Py_ssize_t *__pyx_t_5; + PyObject *__pyx_t_6 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":573 + * @property + * def strides(self): + * if self.view.strides == NULL: # <<<<<<<<<<<<<< + * + * raise ValueError, "Buffer view does not expose strides" + */ + __pyx_t_1 = (__pyx_v_self->view.strides == NULL); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":575 + * if self.view.strides == NULL: + * + * raise ValueError, "Buffer view does not expose strides" # <<<<<<<<<<<<<< + * + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Buffer_view_does_not_expose_stri, 0, 0); + __PYX_ERR(1, 575, __pyx_L1_error) + + /* "View.MemoryView":573 + * @property + * def strides(self): + * if self.view.strides == NULL: # <<<<<<<<<<<<<< + * + * raise ValueError, "Buffer view does not expose strides" + */ + } + + /* "View.MemoryView":577 + * raise ValueError, "Buffer view does not expose strides" + * + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + { /* enter inner scope */ + __pyx_t_2 = PyList_New(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 577, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = (__pyx_v_self->view.strides + __pyx_v_self->view.ndim); + for (__pyx_t_5 = __pyx_v_self->view.strides; __pyx_t_5 < __pyx_t_4; __pyx_t_5++) { + __pyx_t_3 = __pyx_t_5; + __pyx_8genexpr1__pyx_v_stride = (__pyx_t_3[0]); + __pyx_t_6 = PyInt_FromSsize_t(__pyx_8genexpr1__pyx_v_stride); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 577, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_2, (PyObject*)__pyx_t_6))) __PYX_ERR(1, 577, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + } /* exit inner scope */ + __pyx_t_6 = PyList_AsTuple(((PyObject*)__pyx_t_2)); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 577, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_6; + __pyx_t_6 = 0; + goto __pyx_L0; + + /* "View.MemoryView":571 + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def strides(self): + * if self.view.strides == NULL: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("View.MemoryView.memoryview.strides.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":579 + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def suboffsets(self): + * if self.view.suboffsets == NULL: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_10suboffsets_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_10suboffsets_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_10suboffsets___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_10suboffsets___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_8genexpr2__pyx_v_suboffset; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + Py_ssize_t *__pyx_t_5; + PyObject *__pyx_t_6 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":581 + * @property + * def suboffsets(self): + * if self.view.suboffsets == NULL: # <<<<<<<<<<<<<< + * return (-1,) * self.view.ndim + * + */ + __pyx_t_1 = (__pyx_v_self->view.suboffsets == NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":582 + * def suboffsets(self): + * if self.view.suboffsets == NULL: + * return (-1,) * self.view.ndim # <<<<<<<<<<<<<< + * + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PySequence_Multiply(__pyx_tuple__6, __pyx_v_self->view.ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 582, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":581 + * @property + * def suboffsets(self): + * if self.view.suboffsets == NULL: # <<<<<<<<<<<<<< + * return (-1,) * self.view.ndim + * + */ + } + + /* "View.MemoryView":584 + * return (-1,) * self.view.ndim + * + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + { /* enter inner scope */ + __pyx_t_2 = PyList_New(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 584, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = (__pyx_v_self->view.suboffsets + __pyx_v_self->view.ndim); + for (__pyx_t_5 = __pyx_v_self->view.suboffsets; __pyx_t_5 < __pyx_t_4; __pyx_t_5++) { + __pyx_t_3 = __pyx_t_5; + __pyx_8genexpr2__pyx_v_suboffset = (__pyx_t_3[0]); + __pyx_t_6 = PyInt_FromSsize_t(__pyx_8genexpr2__pyx_v_suboffset); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 584, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_2, (PyObject*)__pyx_t_6))) __PYX_ERR(1, 584, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + } /* exit inner scope */ + __pyx_t_6 = PyList_AsTuple(((PyObject*)__pyx_t_2)); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 584, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_6; + __pyx_t_6 = 0; + goto __pyx_L0; + + /* "View.MemoryView":579 + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def suboffsets(self): + * if self.view.suboffsets == NULL: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("View.MemoryView.memoryview.suboffsets.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":586 + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def ndim(self): + * return self.view.ndim + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4ndim_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4ndim_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_4ndim___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4ndim___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":588 + * @property + * def ndim(self): + * return self.view.ndim # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_self->view.ndim); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 588, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":586 + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def ndim(self): + * return self.view.ndim + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.ndim.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":590 + * return self.view.ndim + * + * @property # <<<<<<<<<<<<<< + * def itemsize(self): + * return self.view.itemsize + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_8itemsize_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_8itemsize_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_8itemsize___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_8itemsize___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":592 + * @property + * def itemsize(self): + * return self.view.itemsize # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyInt_FromSsize_t(__pyx_v_self->view.itemsize); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 592, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":590 + * return self.view.ndim + * + * @property # <<<<<<<<<<<<<< + * def itemsize(self): + * return self.view.itemsize + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.itemsize.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":594 + * return self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def nbytes(self): + * return self.size * self.view.itemsize + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_6nbytes_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_6nbytes_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_6nbytes___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_6nbytes___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":596 + * @property + * def nbytes(self): + * return self.size * self.view.itemsize # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_size); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 596, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = PyInt_FromSsize_t(__pyx_v_self->view.itemsize); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 596, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyNumber_Multiply(__pyx_t_1, __pyx_t_2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 596, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_3; + __pyx_t_3 = 0; + goto __pyx_L0; + + /* "View.MemoryView":594 + * return self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def nbytes(self): + * return self.size * self.view.itemsize + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.nbytes.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":598 + * return self.size * self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def size(self): + * if self._size is None: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4size_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4size_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_4size___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4size___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_v_result = NULL; + PyObject *__pyx_v_length = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + PyObject *__pyx_t_5 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":600 + * @property + * def size(self): + * if self._size is None: # <<<<<<<<<<<<<< + * result = 1 + * + */ + __pyx_t_1 = (__pyx_v_self->_size == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":601 + * def size(self): + * if self._size is None: + * result = 1 # <<<<<<<<<<<<<< + * + * for length in self.view.shape[:self.view.ndim]: + */ + __Pyx_INCREF(__pyx_int_1); + __pyx_v_result = __pyx_int_1; + + /* "View.MemoryView":603 + * result = 1 + * + * for length in self.view.shape[:self.view.ndim]: # <<<<<<<<<<<<<< + * result *= length + * + */ + __pyx_t_3 = (__pyx_v_self->view.shape + __pyx_v_self->view.ndim); + for (__pyx_t_4 = __pyx_v_self->view.shape; __pyx_t_4 < __pyx_t_3; __pyx_t_4++) { + __pyx_t_2 = __pyx_t_4; + __pyx_t_5 = PyInt_FromSsize_t((__pyx_t_2[0])); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 603, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_XDECREF_SET(__pyx_v_length, __pyx_t_5); + __pyx_t_5 = 0; + + /* "View.MemoryView":604 + * + * for length in self.view.shape[:self.view.ndim]: + * result *= length # <<<<<<<<<<<<<< + * + * self._size = result + */ + __pyx_t_5 = PyNumber_InPlaceMultiply(__pyx_v_result, __pyx_v_length); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 604, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF_SET(__pyx_v_result, __pyx_t_5); + __pyx_t_5 = 0; + } + + /* "View.MemoryView":606 + * result *= length + * + * self._size = result # <<<<<<<<<<<<<< + * + * return self._size + */ + __Pyx_INCREF(__pyx_v_result); + __Pyx_GIVEREF(__pyx_v_result); + __Pyx_GOTREF(__pyx_v_self->_size); + __Pyx_DECREF(__pyx_v_self->_size); + __pyx_v_self->_size = __pyx_v_result; + + /* "View.MemoryView":600 + * @property + * def size(self): + * if self._size is None: # <<<<<<<<<<<<<< + * result = 1 + * + */ + } + + /* "View.MemoryView":608 + * self._size = result + * + * return self._size # <<<<<<<<<<<<<< + * + * def __len__(self): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->_size); + __pyx_r = __pyx_v_self->_size; + goto __pyx_L0; + + /* "View.MemoryView":598 + * return self.size * self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def size(self): + * if self._size is None: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.memoryview.size.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_result); + __Pyx_XDECREF(__pyx_v_length); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":610 + * return self._size + * + * def __len__(self): # <<<<<<<<<<<<<< + * if self.view.ndim >= 1: + * return self.view.shape[0] + */ + +/* Python wrapper */ +static Py_ssize_t __pyx_memoryview___len__(PyObject *__pyx_v_self); /*proto*/ +static Py_ssize_t __pyx_memoryview___len__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + Py_ssize_t __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__len__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_10__len__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static Py_ssize_t __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_10__len__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_r; + int __pyx_t_1; + + /* "View.MemoryView":611 + * + * def __len__(self): + * if self.view.ndim >= 1: # <<<<<<<<<<<<<< + * return self.view.shape[0] + * + */ + __pyx_t_1 = (__pyx_v_self->view.ndim >= 1); + if (__pyx_t_1) { + + /* "View.MemoryView":612 + * def __len__(self): + * if self.view.ndim >= 1: + * return self.view.shape[0] # <<<<<<<<<<<<<< + * + * return 0 + */ + __pyx_r = (__pyx_v_self->view.shape[0]); + goto __pyx_L0; + + /* "View.MemoryView":611 + * + * def __len__(self): + * if self.view.ndim >= 1: # <<<<<<<<<<<<<< + * return self.view.shape[0] + * + */ + } + + /* "View.MemoryView":614 + * return self.view.shape[0] + * + * return 0 # <<<<<<<<<<<<<< + * + * def __repr__(self): + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":610 + * return self._size + * + * def __len__(self): # <<<<<<<<<<<<<< + * if self.view.ndim >= 1: + * return self.view.shape[0] + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":616 + * return 0 + * + * def __repr__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__, + * id(self)) + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview___repr__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_memoryview___repr__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__repr__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_12__repr__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_12__repr__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__repr__", 1); + + /* "View.MemoryView":617 + * + * def __repr__(self): + * return "" % (self.base.__class__.__name__, # <<<<<<<<<<<<<< + * id(self)) + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_base); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_class); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_name_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":618 + * def __repr__(self): + * return "" % (self.base.__class__.__name__, + * id(self)) # <<<<<<<<<<<<<< + * + * def __str__(self): + */ + __pyx_t_2 = __Pyx_PyObject_CallOneArg(__pyx_builtin_id, ((PyObject *)__pyx_v_self)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 618, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + + /* "View.MemoryView":617 + * + * def __repr__(self): + * return "" % (self.base.__class__.__name__, # <<<<<<<<<<<<<< + * id(self)) + * + */ + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_1)) __PYX_ERR(1, 617, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_2)) __PYX_ERR(1, 617, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyString_Format(__pyx_kp_s_MemoryView_of_r_at_0x_x, __pyx_t_3); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":616 + * return 0 + * + * def __repr__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__, + * id(self)) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.__repr__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":620 + * id(self)) + * + * def __str__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__,) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview___str__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_memoryview___str__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__str__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_14__str__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_14__str__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__str__", 1); + + /* "View.MemoryView":621 + * + * def __str__(self): + * return "" % (self.base.__class__.__name__,) # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_base); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_class); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_name_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = PyTuple_New(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_t_1)) __PYX_ERR(1, 621, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_MemoryView_of_r_object, __pyx_t_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":620 + * id(self)) + * + * def __str__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__,) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.__str__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":624 + * + * + * def is_c_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_is_c_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_is_c_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("is_c_contig (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("is_c_contig", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "is_c_contig", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_16is_c_contig(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_16is_c_contig(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice *__pyx_v_mslice; + __Pyx_memviewslice __pyx_v_tmp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("is_c_contig", 1); + + /* "View.MemoryView":627 + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) # <<<<<<<<<<<<<< + * return slice_is_contig(mslice[0], 'C', self.view.ndim) + * + */ + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(__pyx_v_self, (&__pyx_v_tmp)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 627, __pyx_L1_error) + __pyx_v_mslice = __pyx_t_1; + + /* "View.MemoryView":628 + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) + * return slice_is_contig(mslice[0], 'C', self.view.ndim) # <<<<<<<<<<<<<< + * + * def is_f_contig(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_memviewslice_is_contig((__pyx_v_mslice[0]), 'C', __pyx_v_self->view.ndim)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 628, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":624 + * + * + * def is_c_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.is_c_contig", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":630 + * return slice_is_contig(mslice[0], 'C', self.view.ndim) + * + * def is_f_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_is_f_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_is_f_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("is_f_contig (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("is_f_contig", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "is_f_contig", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_18is_f_contig(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_18is_f_contig(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice *__pyx_v_mslice; + __Pyx_memviewslice __pyx_v_tmp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("is_f_contig", 1); + + /* "View.MemoryView":633 + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) # <<<<<<<<<<<<<< + * return slice_is_contig(mslice[0], 'F', self.view.ndim) + * + */ + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(__pyx_v_self, (&__pyx_v_tmp)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 633, __pyx_L1_error) + __pyx_v_mslice = __pyx_t_1; + + /* "View.MemoryView":634 + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) + * return slice_is_contig(mslice[0], 'F', self.view.ndim) # <<<<<<<<<<<<<< + * + * def copy(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_memviewslice_is_contig((__pyx_v_mslice[0]), 'F', __pyx_v_self->view.ndim)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 634, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":630 + * return slice_is_contig(mslice[0], 'C', self.view.ndim) + * + * def is_f_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.is_f_contig", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":636 + * return slice_is_contig(mslice[0], 'F', self.view.ndim) + * + * def copy(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice mslice + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_copy(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_copy(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("copy (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("copy", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "copy", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_20copy(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_20copy(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice __pyx_v_mslice; + int __pyx_v_flags; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("copy", 1); + + /* "View.MemoryView":638 + * def copy(self): + * cdef __Pyx_memviewslice mslice + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS # <<<<<<<<<<<<<< + * + * slice_copy(self, &mslice) + */ + __pyx_v_flags = (__pyx_v_self->flags & (~PyBUF_F_CONTIGUOUS)); + + /* "View.MemoryView":640 + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS + * + * slice_copy(self, &mslice) # <<<<<<<<<<<<<< + * mslice = slice_copy_contig(&mslice, "c", self.view.ndim, + * self.view.itemsize, + */ + __pyx_memoryview_slice_copy(__pyx_v_self, (&__pyx_v_mslice)); + + /* "View.MemoryView":641 + * + * slice_copy(self, &mslice) + * mslice = slice_copy_contig(&mslice, "c", self.view.ndim, # <<<<<<<<<<<<<< + * self.view.itemsize, + * flags|PyBUF_C_CONTIGUOUS, + */ + __pyx_t_1 = __pyx_memoryview_copy_new_contig((&__pyx_v_mslice), ((char *)"c"), __pyx_v_self->view.ndim, __pyx_v_self->view.itemsize, (__pyx_v_flags | PyBUF_C_CONTIGUOUS), __pyx_v_self->dtype_is_object); if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 641, __pyx_L1_error) + __pyx_v_mslice = __pyx_t_1; + + /* "View.MemoryView":646 + * self.dtype_is_object) + * + * return memoryview_copy_from_slice(self, &mslice) # <<<<<<<<<<<<<< + * + * def copy_fortran(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_memoryview_copy_object_from_slice(__pyx_v_self, (&__pyx_v_mslice)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 646, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":636 + * return slice_is_contig(mslice[0], 'F', self.view.ndim) + * + * def copy(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice mslice + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.copy", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":648 + * return memoryview_copy_from_slice(self, &mslice) + * + * def copy_fortran(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice src, dst + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_copy_fortran(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_copy_fortran(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("copy_fortran (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("copy_fortran", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "copy_fortran", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_22copy_fortran(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_22copy_fortran(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice __pyx_v_src; + __Pyx_memviewslice __pyx_v_dst; + int __pyx_v_flags; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("copy_fortran", 1); + + /* "View.MemoryView":650 + * def copy_fortran(self): + * cdef __Pyx_memviewslice src, dst + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS # <<<<<<<<<<<<<< + * + * slice_copy(self, &src) + */ + __pyx_v_flags = (__pyx_v_self->flags & (~PyBUF_C_CONTIGUOUS)); + + /* "View.MemoryView":652 + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS + * + * slice_copy(self, &src) # <<<<<<<<<<<<<< + * dst = slice_copy_contig(&src, "fortran", self.view.ndim, + * self.view.itemsize, + */ + __pyx_memoryview_slice_copy(__pyx_v_self, (&__pyx_v_src)); + + /* "View.MemoryView":653 + * + * slice_copy(self, &src) + * dst = slice_copy_contig(&src, "fortran", self.view.ndim, # <<<<<<<<<<<<<< + * self.view.itemsize, + * flags|PyBUF_F_CONTIGUOUS, + */ + __pyx_t_1 = __pyx_memoryview_copy_new_contig((&__pyx_v_src), ((char *)"fortran"), __pyx_v_self->view.ndim, __pyx_v_self->view.itemsize, (__pyx_v_flags | PyBUF_F_CONTIGUOUS), __pyx_v_self->dtype_is_object); if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 653, __pyx_L1_error) + __pyx_v_dst = __pyx_t_1; + + /* "View.MemoryView":658 + * self.dtype_is_object) + * + * return memoryview_copy_from_slice(self, &dst) # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_memoryview_copy_object_from_slice(__pyx_v_self, (&__pyx_v_dst)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 658, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":648 + * return memoryview_copy_from_slice(self, &mslice) + * + * def copy_fortran(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice src, dst + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.copy_fortran", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryview_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryview_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_memoryview___reduce_cython__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryview___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryview_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryview_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.memoryview.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_memoryview_2__setstate_cython__(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryview_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":662 + * + * @cname('__pyx_memoryview_new') + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): # <<<<<<<<<<<<<< + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo + */ + +static PyObject *__pyx_memoryview_new(PyObject *__pyx_v_o, int __pyx_v_flags, int __pyx_v_dtype_is_object, __Pyx_TypeInfo *__pyx_v_typeinfo) { + struct __pyx_memoryview_obj *__pyx_v_result = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_cwrapper", 1); + + /* "View.MemoryView":663 + * @cname('__pyx_memoryview_new') + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): + * cdef memoryview result = memoryview(o, flags, dtype_is_object) # <<<<<<<<<<<<<< + * result.typeinfo = typeinfo + * return result + */ + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_flags); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_v_dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_v_o); + __Pyx_GIVEREF(__pyx_v_o); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_v_o)) __PYX_ERR(1, 663, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1)) __PYX_ERR(1, 663, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_t_2)) __PYX_ERR(1, 663, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_Call(((PyObject *)__pyx_memoryview_type), __pyx_t_3, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_v_result = ((struct __pyx_memoryview_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":664 + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo # <<<<<<<<<<<<<< + * return result + * + */ + __pyx_v_result->typeinfo = __pyx_v_typeinfo; + + /* "View.MemoryView":665 + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo + * return result # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_check') + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = ((PyObject *)__pyx_v_result); + goto __pyx_L0; + + /* "View.MemoryView":662 + * + * @cname('__pyx_memoryview_new') + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): # <<<<<<<<<<<<<< + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview_cwrapper", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":668 + * + * @cname('__pyx_memoryview_check') + * cdef inline bint memoryview_check(object o) noexcept: # <<<<<<<<<<<<<< + * return isinstance(o, memoryview) + * + */ + +static CYTHON_INLINE int __pyx_memoryview_check(PyObject *__pyx_v_o) { + int __pyx_r; + int __pyx_t_1; + + /* "View.MemoryView":669 + * @cname('__pyx_memoryview_check') + * cdef inline bint memoryview_check(object o) noexcept: + * return isinstance(o, memoryview) # <<<<<<<<<<<<<< + * + * cdef tuple _unellipsify(object index, int ndim): + */ + __pyx_t_1 = __Pyx_TypeCheck(__pyx_v_o, __pyx_memoryview_type); + __pyx_r = __pyx_t_1; + goto __pyx_L0; + + /* "View.MemoryView":668 + * + * @cname('__pyx_memoryview_check') + * cdef inline bint memoryview_check(object o) noexcept: # <<<<<<<<<<<<<< + * return isinstance(o, memoryview) + * + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":671 + * return isinstance(o, memoryview) + * + * cdef tuple _unellipsify(object index, int ndim): # <<<<<<<<<<<<<< + * """ + * Replace all ellipses with full slices and fill incomplete indices with + */ + +static PyObject *_unellipsify(PyObject *__pyx_v_index, int __pyx_v_ndim) { + Py_ssize_t __pyx_v_idx; + PyObject *__pyx_v_tup = NULL; + PyObject *__pyx_v_result = NULL; + int __pyx_v_have_slices; + int __pyx_v_seen_ellipsis; + PyObject *__pyx_v_item = NULL; + Py_ssize_t __pyx_v_nslices; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + Py_ssize_t __pyx_t_4; + Py_ssize_t __pyx_t_5; + Py_UCS4 __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("_unellipsify", 1); + + /* "View.MemoryView":677 + * """ + * cdef Py_ssize_t idx + * tup = index if isinstance(index, tuple) else (index,) # <<<<<<<<<<<<<< + * + * result = [slice(None)] * ndim + */ + __pyx_t_2 = PyTuple_Check(__pyx_v_index); + if (__pyx_t_2) { + __Pyx_INCREF(((PyObject*)__pyx_v_index)); + __pyx_t_1 = __pyx_v_index; + } else { + __pyx_t_3 = PyTuple_New(1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 677, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_v_index); + __Pyx_GIVEREF(__pyx_v_index); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_v_index)) __PYX_ERR(1, 677, __pyx_L1_error); + __pyx_t_1 = __pyx_t_3; + __pyx_t_3 = 0; + } + __pyx_v_tup = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":679 + * tup = index if isinstance(index, tuple) else (index,) + * + * result = [slice(None)] * ndim # <<<<<<<<<<<<<< + * have_slices = False + * seen_ellipsis = False + */ + __pyx_t_1 = PyList_New(1 * ((__pyx_v_ndim<0) ? 0:__pyx_v_ndim)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 679, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + { Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < __pyx_v_ndim; __pyx_temp++) { + __Pyx_INCREF(__pyx_slice__7); + __Pyx_GIVEREF(__pyx_slice__7); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, __pyx_temp, __pyx_slice__7)) __PYX_ERR(1, 679, __pyx_L1_error); + } + } + __pyx_v_result = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":680 + * + * result = [slice(None)] * ndim + * have_slices = False # <<<<<<<<<<<<<< + * seen_ellipsis = False + * idx = 0 + */ + __pyx_v_have_slices = 0; + + /* "View.MemoryView":681 + * result = [slice(None)] * ndim + * have_slices = False + * seen_ellipsis = False # <<<<<<<<<<<<<< + * idx = 0 + * for item in tup: + */ + __pyx_v_seen_ellipsis = 0; + + /* "View.MemoryView":682 + * have_slices = False + * seen_ellipsis = False + * idx = 0 # <<<<<<<<<<<<<< + * for item in tup: + * if item is Ellipsis: + */ + __pyx_v_idx = 0; + + /* "View.MemoryView":683 + * seen_ellipsis = False + * idx = 0 + * for item in tup: # <<<<<<<<<<<<<< + * if item is Ellipsis: + * if not seen_ellipsis: + */ + if (unlikely(__pyx_v_tup == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not iterable"); + __PYX_ERR(1, 683, __pyx_L1_error) + } + __pyx_t_1 = __pyx_v_tup; __Pyx_INCREF(__pyx_t_1); + __pyx_t_4 = 0; + for (;;) { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_1); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 683, __pyx_L1_error) + #endif + if (__pyx_t_4 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_3 = PyTuple_GET_ITEM(__pyx_t_1, __pyx_t_4); __Pyx_INCREF(__pyx_t_3); __pyx_t_4++; if (unlikely((0 < 0))) __PYX_ERR(1, 683, __pyx_L1_error) + #else + __pyx_t_3 = __Pyx_PySequence_ITEM(__pyx_t_1, __pyx_t_4); __pyx_t_4++; if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 683, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + #endif + __Pyx_XDECREF_SET(__pyx_v_item, __pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":684 + * idx = 0 + * for item in tup: + * if item is Ellipsis: # <<<<<<<<<<<<<< + * if not seen_ellipsis: + * idx += ndim - len(tup) + */ + __pyx_t_2 = (__pyx_v_item == __pyx_builtin_Ellipsis); + if (__pyx_t_2) { + + /* "View.MemoryView":685 + * for item in tup: + * if item is Ellipsis: + * if not seen_ellipsis: # <<<<<<<<<<<<<< + * idx += ndim - len(tup) + * seen_ellipsis = True + */ + __pyx_t_2 = (!__pyx_v_seen_ellipsis); + if (__pyx_t_2) { + + /* "View.MemoryView":686 + * if item is Ellipsis: + * if not seen_ellipsis: + * idx += ndim - len(tup) # <<<<<<<<<<<<<< + * seen_ellipsis = True + * have_slices = True + */ + if (unlikely(__pyx_v_tup == Py_None)) { + PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); + __PYX_ERR(1, 686, __pyx_L1_error) + } + __pyx_t_5 = __Pyx_PyTuple_GET_SIZE(__pyx_v_tup); if (unlikely(__pyx_t_5 == ((Py_ssize_t)-1))) __PYX_ERR(1, 686, __pyx_L1_error) + __pyx_v_idx = (__pyx_v_idx + (__pyx_v_ndim - __pyx_t_5)); + + /* "View.MemoryView":687 + * if not seen_ellipsis: + * idx += ndim - len(tup) + * seen_ellipsis = True # <<<<<<<<<<<<<< + * have_slices = True + * else: + */ + __pyx_v_seen_ellipsis = 1; + + /* "View.MemoryView":685 + * for item in tup: + * if item is Ellipsis: + * if not seen_ellipsis: # <<<<<<<<<<<<<< + * idx += ndim - len(tup) + * seen_ellipsis = True + */ + } + + /* "View.MemoryView":688 + * idx += ndim - len(tup) + * seen_ellipsis = True + * have_slices = True # <<<<<<<<<<<<<< + * else: + * if isinstance(item, slice): + */ + __pyx_v_have_slices = 1; + + /* "View.MemoryView":684 + * idx = 0 + * for item in tup: + * if item is Ellipsis: # <<<<<<<<<<<<<< + * if not seen_ellipsis: + * idx += ndim - len(tup) + */ + goto __pyx_L5; + } + + /* "View.MemoryView":690 + * have_slices = True + * else: + * if isinstance(item, slice): # <<<<<<<<<<<<<< + * have_slices = True + * elif not PyIndex_Check(item): + */ + /*else*/ { + __pyx_t_2 = PySlice_Check(__pyx_v_item); + if (__pyx_t_2) { + + /* "View.MemoryView":691 + * else: + * if isinstance(item, slice): + * have_slices = True # <<<<<<<<<<<<<< + * elif not PyIndex_Check(item): + * raise TypeError, f"Cannot index with type '{type(item)}'" + */ + __pyx_v_have_slices = 1; + + /* "View.MemoryView":690 + * have_slices = True + * else: + * if isinstance(item, slice): # <<<<<<<<<<<<<< + * have_slices = True + * elif not PyIndex_Check(item): + */ + goto __pyx_L7; + } + + /* "View.MemoryView":692 + * if isinstance(item, slice): + * have_slices = True + * elif not PyIndex_Check(item): # <<<<<<<<<<<<<< + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item + */ + __pyx_t_2 = (!(PyIndex_Check(__pyx_v_item) != 0)); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":693 + * have_slices = True + * elif not PyIndex_Check(item): + * raise TypeError, f"Cannot index with type '{type(item)}'" # <<<<<<<<<<<<<< + * result[idx] = item + * idx += 1 + */ + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 693, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = 0; + __pyx_t_6 = 127; + __Pyx_INCREF(__pyx_kp_u_Cannot_index_with_type); + __pyx_t_5 += 24; + __Pyx_GIVEREF(__pyx_kp_u_Cannot_index_with_type); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_kp_u_Cannot_index_with_type); + __pyx_t_7 = __Pyx_PyObject_FormatSimple(((PyObject *)Py_TYPE(__pyx_v_item)), __pyx_empty_unicode); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 693, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_7) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_7) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_7); + __pyx_t_7 = 0; + __Pyx_INCREF(__pyx_kp_u__8); + __pyx_t_5 += 1; + __Pyx_GIVEREF(__pyx_kp_u__8); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_kp_u__8); + __pyx_t_7 = __Pyx_PyUnicode_Join(__pyx_t_3, 3, __pyx_t_5, __pyx_t_6); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 693, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_t_7, 0, 0); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __PYX_ERR(1, 693, __pyx_L1_error) + + /* "View.MemoryView":692 + * if isinstance(item, slice): + * have_slices = True + * elif not PyIndex_Check(item): # <<<<<<<<<<<<<< + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item + */ + } + __pyx_L7:; + + /* "View.MemoryView":694 + * elif not PyIndex_Check(item): + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item # <<<<<<<<<<<<<< + * idx += 1 + * + */ + if (unlikely((__Pyx_SetItemInt(__pyx_v_result, __pyx_v_idx, __pyx_v_item, Py_ssize_t, 1, PyInt_FromSsize_t, 1, 1, 1) < 0))) __PYX_ERR(1, 694, __pyx_L1_error) + } + __pyx_L5:; + + /* "View.MemoryView":695 + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item + * idx += 1 # <<<<<<<<<<<<<< + * + * nslices = ndim - idx + */ + __pyx_v_idx = (__pyx_v_idx + 1); + + /* "View.MemoryView":683 + * seen_ellipsis = False + * idx = 0 + * for item in tup: # <<<<<<<<<<<<<< + * if item is Ellipsis: + * if not seen_ellipsis: + */ + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "View.MemoryView":697 + * idx += 1 + * + * nslices = ndim - idx # <<<<<<<<<<<<<< + * return have_slices or nslices, tuple(result) + * + */ + __pyx_v_nslices = (__pyx_v_ndim - __pyx_v_idx); + + /* "View.MemoryView":698 + * + * nslices = ndim - idx + * return have_slices or nslices, tuple(result) # <<<<<<<<<<<<<< + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + */ + __Pyx_XDECREF(__pyx_r); + if (!__pyx_v_have_slices) { + } else { + __pyx_t_7 = __Pyx_PyBool_FromLong(__pyx_v_have_slices); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_1 = __pyx_t_7; + __pyx_t_7 = 0; + goto __pyx_L9_bool_binop_done; + } + __pyx_t_7 = PyInt_FromSsize_t(__pyx_v_nslices); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_1 = __pyx_t_7; + __pyx_t_7 = 0; + __pyx_L9_bool_binop_done:; + __pyx_t_7 = PyList_AsTuple(__pyx_v_result); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_1)) __PYX_ERR(1, 698, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_7); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_7)) __PYX_ERR(1, 698, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_7 = 0; + __pyx_r = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; + goto __pyx_L0; + + /* "View.MemoryView":671 + * return isinstance(o, memoryview) + * + * cdef tuple _unellipsify(object index, int ndim): # <<<<<<<<<<<<<< + * """ + * Replace all ellipses with full slices and fill incomplete indices with + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("View.MemoryView._unellipsify", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_tup); + __Pyx_XDECREF(__pyx_v_result); + __Pyx_XDECREF(__pyx_v_item); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":700 + * return have_slices or nslices, tuple(result) + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: # <<<<<<<<<<<<<< + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: + */ + +static int assert_direct_dimensions(Py_ssize_t *__pyx_v_suboffsets, int __pyx_v_ndim) { + Py_ssize_t __pyx_v_suboffset; + int __pyx_r; + Py_ssize_t *__pyx_t_1; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + int __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + + /* "View.MemoryView":701 + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + * for suboffset in suboffsets[:ndim]: # <<<<<<<<<<<<<< + * if suboffset >= 0: + * raise ValueError, "Indirect dimensions not supported" + */ + __pyx_t_2 = (__pyx_v_suboffsets + __pyx_v_ndim); + for (__pyx_t_3 = __pyx_v_suboffsets; __pyx_t_3 < __pyx_t_2; __pyx_t_3++) { + __pyx_t_1 = __pyx_t_3; + __pyx_v_suboffset = (__pyx_t_1[0]); + + /* "View.MemoryView":702 + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * raise ValueError, "Indirect dimensions not supported" + * return 0 # return type just used as an error flag + */ + __pyx_t_4 = (__pyx_v_suboffset >= 0); + if (unlikely(__pyx_t_4)) { + + /* "View.MemoryView":703 + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: + * raise ValueError, "Indirect dimensions not supported" # <<<<<<<<<<<<<< + * return 0 # return type just used as an error flag + * + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Indirect_dimensions_not_supporte, 0, 0); + __PYX_ERR(1, 703, __pyx_L1_error) + + /* "View.MemoryView":702 + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * raise ValueError, "Indirect dimensions not supported" + * return 0 # return type just used as an error flag + */ + } + } + + /* "View.MemoryView":704 + * if suboffset >= 0: + * raise ValueError, "Indirect dimensions not supported" + * return 0 # return type just used as an error flag # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":700 + * return have_slices or nslices, tuple(result) + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: # <<<<<<<<<<<<<< + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.assert_direct_dimensions", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":711 + * + * @cname('__pyx_memview_slice') + * cdef memoryview memview_slice(memoryview memview, object indices): # <<<<<<<<<<<<<< + * cdef int new_ndim = 0, suboffset_dim = -1, dim + * cdef bint negative_step + */ + +static struct __pyx_memoryview_obj *__pyx_memview_slice(struct __pyx_memoryview_obj *__pyx_v_memview, PyObject *__pyx_v_indices) { + int __pyx_v_new_ndim; + int __pyx_v_suboffset_dim; + int __pyx_v_dim; + __Pyx_memviewslice __pyx_v_src; + __Pyx_memviewslice __pyx_v_dst; + __Pyx_memviewslice *__pyx_v_p_src; + struct __pyx_memoryviewslice_obj *__pyx_v_memviewsliceobj = 0; + __Pyx_memviewslice *__pyx_v_p_dst; + int *__pyx_v_p_suboffset_dim; + Py_ssize_t __pyx_v_start; + Py_ssize_t __pyx_v_stop; + Py_ssize_t __pyx_v_step; + Py_ssize_t __pyx_v_cindex; + int __pyx_v_have_start; + int __pyx_v_have_stop; + int __pyx_v_have_step; + PyObject *__pyx_v_index = NULL; + struct __pyx_memoryview_obj *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + struct __pyx_memoryview_obj *__pyx_t_3; + char *__pyx_t_4; + int __pyx_t_5; + Py_ssize_t __pyx_t_6; + PyObject *(*__pyx_t_7)(PyObject *); + PyObject *__pyx_t_8 = NULL; + Py_ssize_t __pyx_t_9; + int __pyx_t_10; + Py_ssize_t __pyx_t_11; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memview_slice", 1); + + /* "View.MemoryView":712 + * @cname('__pyx_memview_slice') + * cdef memoryview memview_slice(memoryview memview, object indices): + * cdef int new_ndim = 0, suboffset_dim = -1, dim # <<<<<<<<<<<<<< + * cdef bint negative_step + * cdef __Pyx_memviewslice src, dst + */ + __pyx_v_new_ndim = 0; + __pyx_v_suboffset_dim = -1; + + /* "View.MemoryView":719 + * + * + * memset(&dst, 0, sizeof(dst)) # <<<<<<<<<<<<<< + * + * cdef _memoryviewslice memviewsliceobj + */ + (void)(memset((&__pyx_v_dst), 0, (sizeof(__pyx_v_dst)))); + + /* "View.MemoryView":723 + * cdef _memoryviewslice memviewsliceobj + * + * assert memview.view.ndim > 0 # <<<<<<<<<<<<<< + * + * if isinstance(memview, _memoryviewslice): + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_1 = (__pyx_v_memview->view.ndim > 0); + if (unlikely(!__pyx_t_1)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(1, 723, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(1, 723, __pyx_L1_error) + #endif + + /* "View.MemoryView":725 + * assert memview.view.ndim > 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * memviewsliceobj = memview + * p_src = &memviewsliceobj.from_slice + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":726 + * + * if isinstance(memview, _memoryviewslice): + * memviewsliceobj = memview # <<<<<<<<<<<<<< + * p_src = &memviewsliceobj.from_slice + * else: + */ + if (!(likely(((((PyObject *)__pyx_v_memview)) == Py_None) || likely(__Pyx_TypeTest(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type))))) __PYX_ERR(1, 726, __pyx_L1_error) + __pyx_t_2 = ((PyObject *)__pyx_v_memview); + __Pyx_INCREF(__pyx_t_2); + __pyx_v_memviewsliceobj = ((struct __pyx_memoryviewslice_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":727 + * if isinstance(memview, _memoryviewslice): + * memviewsliceobj = memview + * p_src = &memviewsliceobj.from_slice # <<<<<<<<<<<<<< + * else: + * slice_copy(memview, &src) + */ + __pyx_v_p_src = (&__pyx_v_memviewsliceobj->from_slice); + + /* "View.MemoryView":725 + * assert memview.view.ndim > 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * memviewsliceobj = memview + * p_src = &memviewsliceobj.from_slice + */ + goto __pyx_L3; + } + + /* "View.MemoryView":729 + * p_src = &memviewsliceobj.from_slice + * else: + * slice_copy(memview, &src) # <<<<<<<<<<<<<< + * p_src = &src + * + */ + /*else*/ { + __pyx_memoryview_slice_copy(__pyx_v_memview, (&__pyx_v_src)); + + /* "View.MemoryView":730 + * else: + * slice_copy(memview, &src) + * p_src = &src # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_p_src = (&__pyx_v_src); + } + __pyx_L3:; + + /* "View.MemoryView":736 + * + * + * dst.memview = p_src.memview # <<<<<<<<<<<<<< + * dst.data = p_src.data + * + */ + __pyx_t_3 = __pyx_v_p_src->memview; + __pyx_v_dst.memview = __pyx_t_3; + + /* "View.MemoryView":737 + * + * dst.memview = p_src.memview + * dst.data = p_src.data # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_4 = __pyx_v_p_src->data; + __pyx_v_dst.data = __pyx_t_4; + + /* "View.MemoryView":742 + * + * + * cdef __Pyx_memviewslice *p_dst = &dst # <<<<<<<<<<<<<< + * cdef int *p_suboffset_dim = &suboffset_dim + * cdef Py_ssize_t start, stop, step, cindex + */ + __pyx_v_p_dst = (&__pyx_v_dst); + + /* "View.MemoryView":743 + * + * cdef __Pyx_memviewslice *p_dst = &dst + * cdef int *p_suboffset_dim = &suboffset_dim # <<<<<<<<<<<<<< + * cdef Py_ssize_t start, stop, step, cindex + * cdef bint have_start, have_stop, have_step + */ + __pyx_v_p_suboffset_dim = (&__pyx_v_suboffset_dim); + + /* "View.MemoryView":747 + * cdef bint have_start, have_stop, have_step + * + * for dim, index in enumerate(indices): # <<<<<<<<<<<<<< + * if PyIndex_Check(index): + * cindex = index + */ + __pyx_t_5 = 0; + if (likely(PyList_CheckExact(__pyx_v_indices)) || PyTuple_CheckExact(__pyx_v_indices)) { + __pyx_t_2 = __pyx_v_indices; __Pyx_INCREF(__pyx_t_2); + __pyx_t_6 = 0; + __pyx_t_7 = NULL; + } else { + __pyx_t_6 = -1; __pyx_t_2 = PyObject_GetIter(__pyx_v_indices); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 747, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_7 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_2); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 747, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_7)) { + if (likely(PyList_CheckExact(__pyx_t_2))) { + { + Py_ssize_t __pyx_temp = __Pyx_PyList_GET_SIZE(__pyx_t_2); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 747, __pyx_L1_error) + #endif + if (__pyx_t_6 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_8 = PyList_GET_ITEM(__pyx_t_2, __pyx_t_6); __Pyx_INCREF(__pyx_t_8); __pyx_t_6++; if (unlikely((0 < 0))) __PYX_ERR(1, 747, __pyx_L1_error) + #else + __pyx_t_8 = __Pyx_PySequence_ITEM(__pyx_t_2, __pyx_t_6); __pyx_t_6++; if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 747, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + #endif + } else { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_2); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 747, __pyx_L1_error) + #endif + if (__pyx_t_6 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_8 = PyTuple_GET_ITEM(__pyx_t_2, __pyx_t_6); __Pyx_INCREF(__pyx_t_8); __pyx_t_6++; if (unlikely((0 < 0))) __PYX_ERR(1, 747, __pyx_L1_error) + #else + __pyx_t_8 = __Pyx_PySequence_ITEM(__pyx_t_2, __pyx_t_6); __pyx_t_6++; if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 747, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + #endif + } + } else { + __pyx_t_8 = __pyx_t_7(__pyx_t_2); + if (unlikely(!__pyx_t_8)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(1, 747, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_8); + } + __Pyx_XDECREF_SET(__pyx_v_index, __pyx_t_8); + __pyx_t_8 = 0; + __pyx_v_dim = __pyx_t_5; + __pyx_t_5 = (__pyx_t_5 + 1); + + /* "View.MemoryView":748 + * + * for dim, index in enumerate(indices): + * if PyIndex_Check(index): # <<<<<<<<<<<<<< + * cindex = index + * slice_memviewslice( + */ + __pyx_t_1 = (PyIndex_Check(__pyx_v_index) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":749 + * for dim, index in enumerate(indices): + * if PyIndex_Check(index): + * cindex = index # <<<<<<<<<<<<<< + * slice_memviewslice( + * p_dst, p_src.shape[dim], p_src.strides[dim], p_src.suboffsets[dim], + */ + __pyx_t_9 = __Pyx_PyIndex_AsSsize_t(__pyx_v_index); if (unlikely((__pyx_t_9 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 749, __pyx_L1_error) + __pyx_v_cindex = __pyx_t_9; + + /* "View.MemoryView":750 + * if PyIndex_Check(index): + * cindex = index + * slice_memviewslice( # <<<<<<<<<<<<<< + * p_dst, p_src.shape[dim], p_src.strides[dim], p_src.suboffsets[dim], + * dim, new_ndim, p_suboffset_dim, + */ + __pyx_t_10 = __pyx_memoryview_slice_memviewslice(__pyx_v_p_dst, (__pyx_v_p_src->shape[__pyx_v_dim]), (__pyx_v_p_src->strides[__pyx_v_dim]), (__pyx_v_p_src->suboffsets[__pyx_v_dim]), __pyx_v_dim, __pyx_v_new_ndim, __pyx_v_p_suboffset_dim, __pyx_v_cindex, 0, 0, 0, 0, 0, 0); if (unlikely(__pyx_t_10 == ((int)-1))) __PYX_ERR(1, 750, __pyx_L1_error) + + /* "View.MemoryView":748 + * + * for dim, index in enumerate(indices): + * if PyIndex_Check(index): # <<<<<<<<<<<<<< + * cindex = index + * slice_memviewslice( + */ + goto __pyx_L6; + } + + /* "View.MemoryView":756 + * 0, 0, 0, # have_{start,stop,step} + * False) + * elif index is None: # <<<<<<<<<<<<<< + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 + */ + __pyx_t_1 = (__pyx_v_index == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":757 + * False) + * elif index is None: + * p_dst.shape[new_ndim] = 1 # <<<<<<<<<<<<<< + * p_dst.strides[new_ndim] = 0 + * p_dst.suboffsets[new_ndim] = -1 + */ + (__pyx_v_p_dst->shape[__pyx_v_new_ndim]) = 1; + + /* "View.MemoryView":758 + * elif index is None: + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 # <<<<<<<<<<<<<< + * p_dst.suboffsets[new_ndim] = -1 + * new_ndim += 1 + */ + (__pyx_v_p_dst->strides[__pyx_v_new_ndim]) = 0; + + /* "View.MemoryView":759 + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 + * p_dst.suboffsets[new_ndim] = -1 # <<<<<<<<<<<<<< + * new_ndim += 1 + * else: + */ + (__pyx_v_p_dst->suboffsets[__pyx_v_new_ndim]) = -1L; + + /* "View.MemoryView":760 + * p_dst.strides[new_ndim] = 0 + * p_dst.suboffsets[new_ndim] = -1 + * new_ndim += 1 # <<<<<<<<<<<<<< + * else: + * start = index.start or 0 + */ + __pyx_v_new_ndim = (__pyx_v_new_ndim + 1); + + /* "View.MemoryView":756 + * 0, 0, 0, # have_{start,stop,step} + * False) + * elif index is None: # <<<<<<<<<<<<<< + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 + */ + goto __pyx_L6; + } + + /* "View.MemoryView":762 + * new_ndim += 1 + * else: + * start = index.start or 0 # <<<<<<<<<<<<<< + * stop = index.stop or 0 + * step = index.step or 0 + */ + /*else*/ { + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_start); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 762, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_t_8); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 762, __pyx_L1_error) + if (!__pyx_t_1) { + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } else { + __pyx_t_11 = __Pyx_PyIndex_AsSsize_t(__pyx_t_8); if (unlikely((__pyx_t_11 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 762, __pyx_L1_error) + __pyx_t_9 = __pyx_t_11; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L7_bool_binop_done; + } + __pyx_t_9 = 0; + __pyx_L7_bool_binop_done:; + __pyx_v_start = __pyx_t_9; + + /* "View.MemoryView":763 + * else: + * start = index.start or 0 + * stop = index.stop or 0 # <<<<<<<<<<<<<< + * step = index.step or 0 + * + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_stop); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 763, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_t_8); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 763, __pyx_L1_error) + if (!__pyx_t_1) { + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } else { + __pyx_t_11 = __Pyx_PyIndex_AsSsize_t(__pyx_t_8); if (unlikely((__pyx_t_11 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 763, __pyx_L1_error) + __pyx_t_9 = __pyx_t_11; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L9_bool_binop_done; + } + __pyx_t_9 = 0; + __pyx_L9_bool_binop_done:; + __pyx_v_stop = __pyx_t_9; + + /* "View.MemoryView":764 + * start = index.start or 0 + * stop = index.stop or 0 + * step = index.step or 0 # <<<<<<<<<<<<<< + * + * have_start = index.start is not None + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_step); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 764, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_t_8); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 764, __pyx_L1_error) + if (!__pyx_t_1) { + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } else { + __pyx_t_11 = __Pyx_PyIndex_AsSsize_t(__pyx_t_8); if (unlikely((__pyx_t_11 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 764, __pyx_L1_error) + __pyx_t_9 = __pyx_t_11; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L11_bool_binop_done; + } + __pyx_t_9 = 0; + __pyx_L11_bool_binop_done:; + __pyx_v_step = __pyx_t_9; + + /* "View.MemoryView":766 + * step = index.step or 0 + * + * have_start = index.start is not None # <<<<<<<<<<<<<< + * have_stop = index.stop is not None + * have_step = index.step is not None + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_start); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 766, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = (__pyx_t_8 != Py_None); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_v_have_start = __pyx_t_1; + + /* "View.MemoryView":767 + * + * have_start = index.start is not None + * have_stop = index.stop is not None # <<<<<<<<<<<<<< + * have_step = index.step is not None + * + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_stop); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 767, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = (__pyx_t_8 != Py_None); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_v_have_stop = __pyx_t_1; + + /* "View.MemoryView":768 + * have_start = index.start is not None + * have_stop = index.stop is not None + * have_step = index.step is not None # <<<<<<<<<<<<<< + * + * slice_memviewslice( + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_step); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 768, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = (__pyx_t_8 != Py_None); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_v_have_step = __pyx_t_1; + + /* "View.MemoryView":770 + * have_step = index.step is not None + * + * slice_memviewslice( # <<<<<<<<<<<<<< + * p_dst, p_src.shape[dim], p_src.strides[dim], p_src.suboffsets[dim], + * dim, new_ndim, p_suboffset_dim, + */ + __pyx_t_10 = __pyx_memoryview_slice_memviewslice(__pyx_v_p_dst, (__pyx_v_p_src->shape[__pyx_v_dim]), (__pyx_v_p_src->strides[__pyx_v_dim]), (__pyx_v_p_src->suboffsets[__pyx_v_dim]), __pyx_v_dim, __pyx_v_new_ndim, __pyx_v_p_suboffset_dim, __pyx_v_start, __pyx_v_stop, __pyx_v_step, __pyx_v_have_start, __pyx_v_have_stop, __pyx_v_have_step, 1); if (unlikely(__pyx_t_10 == ((int)-1))) __PYX_ERR(1, 770, __pyx_L1_error) + + /* "View.MemoryView":776 + * have_start, have_stop, have_step, + * True) + * new_ndim += 1 # <<<<<<<<<<<<<< + * + * if isinstance(memview, _memoryviewslice): + */ + __pyx_v_new_ndim = (__pyx_v_new_ndim + 1); + } + __pyx_L6:; + + /* "View.MemoryView":747 + * cdef bint have_start, have_stop, have_step + * + * for dim, index in enumerate(indices): # <<<<<<<<<<<<<< + * if PyIndex_Check(index): + * cindex = index + */ + } + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":778 + * new_ndim += 1 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":779 + * + * if isinstance(memview, _memoryviewslice): + * return memoryview_fromslice(dst, new_ndim, # <<<<<<<<<<<<<< + * memviewsliceobj.to_object_func, + * memviewsliceobj.to_dtype_func, + */ + __Pyx_XDECREF((PyObject *)__pyx_r); + + /* "View.MemoryView":780 + * if isinstance(memview, _memoryviewslice): + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, # <<<<<<<<<<<<<< + * memviewsliceobj.to_dtype_func, + * memview.dtype_is_object) + */ + if (unlikely(!__pyx_v_memviewsliceobj)) { __Pyx_RaiseUnboundLocalError("memviewsliceobj"); __PYX_ERR(1, 780, __pyx_L1_error) } + + /* "View.MemoryView":781 + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, + * memviewsliceobj.to_dtype_func, # <<<<<<<<<<<<<< + * memview.dtype_is_object) + * else: + */ + if (unlikely(!__pyx_v_memviewsliceobj)) { __Pyx_RaiseUnboundLocalError("memviewsliceobj"); __PYX_ERR(1, 781, __pyx_L1_error) } + + /* "View.MemoryView":779 + * + * if isinstance(memview, _memoryviewslice): + * return memoryview_fromslice(dst, new_ndim, # <<<<<<<<<<<<<< + * memviewsliceobj.to_object_func, + * memviewsliceobj.to_dtype_func, + */ + __pyx_t_2 = __pyx_memoryview_fromslice(__pyx_v_dst, __pyx_v_new_ndim, __pyx_v_memviewsliceobj->to_object_func, __pyx_v_memviewsliceobj->to_dtype_func, __pyx_v_memview->dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 779, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (!(likely(((__pyx_t_2) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_2, __pyx_memoryview_type))))) __PYX_ERR(1, 779, __pyx_L1_error) + __pyx_r = ((struct __pyx_memoryview_obj *)__pyx_t_2); + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":778 + * new_ndim += 1 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, + */ + } + + /* "View.MemoryView":784 + * memview.dtype_is_object) + * else: + * return memoryview_fromslice(dst, new_ndim, NULL, NULL, # <<<<<<<<<<<<<< + * memview.dtype_is_object) + * + */ + /*else*/ { + __Pyx_XDECREF((PyObject *)__pyx_r); + + /* "View.MemoryView":785 + * else: + * return memoryview_fromslice(dst, new_ndim, NULL, NULL, + * memview.dtype_is_object) # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = __pyx_memoryview_fromslice(__pyx_v_dst, __pyx_v_new_ndim, NULL, NULL, __pyx_v_memview->dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 784, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + + /* "View.MemoryView":784 + * memview.dtype_is_object) + * else: + * return memoryview_fromslice(dst, new_ndim, NULL, NULL, # <<<<<<<<<<<<<< + * memview.dtype_is_object) + * + */ + if (!(likely(((__pyx_t_2) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_2, __pyx_memoryview_type))))) __PYX_ERR(1, 784, __pyx_L1_error) + __pyx_r = ((struct __pyx_memoryview_obj *)__pyx_t_2); + __pyx_t_2 = 0; + goto __pyx_L0; + } + + /* "View.MemoryView":711 + * + * @cname('__pyx_memview_slice') + * cdef memoryview memview_slice(memoryview memview, object indices): # <<<<<<<<<<<<<< + * cdef int new_ndim = 0, suboffset_dim = -1, dim + * cdef bint negative_step + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("View.MemoryView.memview_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_memviewsliceobj); + __Pyx_XDECREF(__pyx_v_index); + __Pyx_XGIVEREF((PyObject *)__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":793 + * + * @cname('__pyx_memoryview_slice_memviewslice') + * cdef int slice_memviewslice( # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * Py_ssize_t shape, Py_ssize_t stride, Py_ssize_t suboffset, + */ + +static int __pyx_memoryview_slice_memviewslice(__Pyx_memviewslice *__pyx_v_dst, Py_ssize_t __pyx_v_shape, Py_ssize_t __pyx_v_stride, Py_ssize_t __pyx_v_suboffset, int __pyx_v_dim, int __pyx_v_new_ndim, int *__pyx_v_suboffset_dim, Py_ssize_t __pyx_v_start, Py_ssize_t __pyx_v_stop, Py_ssize_t __pyx_v_step, int __pyx_v_have_start, int __pyx_v_have_stop, int __pyx_v_have_step, int __pyx_v_is_slice) { + Py_ssize_t __pyx_v_new_shape; + int __pyx_v_negative_step; + int __pyx_r; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":813 + * cdef bint negative_step + * + * if not is_slice: # <<<<<<<<<<<<<< + * + * if start < 0: + */ + __pyx_t_1 = (!__pyx_v_is_slice); + if (__pyx_t_1) { + + /* "View.MemoryView":815 + * if not is_slice: + * + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if not 0 <= start < shape: + */ + __pyx_t_1 = (__pyx_v_start < 0); + if (__pyx_t_1) { + + /* "View.MemoryView":816 + * + * if start < 0: + * start += shape # <<<<<<<<<<<<<< + * if not 0 <= start < shape: + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) + */ + __pyx_v_start = (__pyx_v_start + __pyx_v_shape); + + /* "View.MemoryView":815 + * if not is_slice: + * + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if not 0 <= start < shape: + */ + } + + /* "View.MemoryView":817 + * if start < 0: + * start += shape + * if not 0 <= start < shape: # <<<<<<<<<<<<<< + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) + * else: + */ + __pyx_t_1 = (0 <= __pyx_v_start); + if (__pyx_t_1) { + __pyx_t_1 = (__pyx_v_start < __pyx_v_shape); + } + __pyx_t_2 = (!__pyx_t_1); + if (__pyx_t_2) { + + /* "View.MemoryView":818 + * start += shape + * if not 0 <= start < shape: + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) # <<<<<<<<<<<<<< + * else: + * + */ + __pyx_t_3 = __pyx_memoryview_err_dim(PyExc_IndexError, __pyx_kp_s_Index_out_of_bounds_axis_d, __pyx_v_dim); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 818, __pyx_L1_error) + + /* "View.MemoryView":817 + * if start < 0: + * start += shape + * if not 0 <= start < shape: # <<<<<<<<<<<<<< + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) + * else: + */ + } + + /* "View.MemoryView":813 + * cdef bint negative_step + * + * if not is_slice: # <<<<<<<<<<<<<< + * + * if start < 0: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":821 + * else: + * + * if have_step: # <<<<<<<<<<<<<< + * negative_step = step < 0 + * if step == 0: + */ + /*else*/ { + __pyx_t_2 = (__pyx_v_have_step != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":822 + * + * if have_step: + * negative_step = step < 0 # <<<<<<<<<<<<<< + * if step == 0: + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + */ + __pyx_v_negative_step = (__pyx_v_step < 0); + + /* "View.MemoryView":823 + * if have_step: + * negative_step = step < 0 + * if step == 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + * else: + */ + __pyx_t_2 = (__pyx_v_step == 0); + if (__pyx_t_2) { + + /* "View.MemoryView":824 + * negative_step = step < 0 + * if step == 0: + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) # <<<<<<<<<<<<<< + * else: + * negative_step = False + */ + __pyx_t_3 = __pyx_memoryview_err_dim(PyExc_ValueError, __pyx_kp_s_Step_may_not_be_zero_axis_d, __pyx_v_dim); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 824, __pyx_L1_error) + + /* "View.MemoryView":823 + * if have_step: + * negative_step = step < 0 + * if step == 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + * else: + */ + } + + /* "View.MemoryView":821 + * else: + * + * if have_step: # <<<<<<<<<<<<<< + * negative_step = step < 0 + * if step == 0: + */ + goto __pyx_L6; + } + + /* "View.MemoryView":826 + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + * else: + * negative_step = False # <<<<<<<<<<<<<< + * step = 1 + * + */ + /*else*/ { + __pyx_v_negative_step = 0; + + /* "View.MemoryView":827 + * else: + * negative_step = False + * step = 1 # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_step = 1; + } + __pyx_L6:; + + /* "View.MemoryView":830 + * + * + * if have_start: # <<<<<<<<<<<<<< + * if start < 0: + * start += shape + */ + __pyx_t_2 = (__pyx_v_have_start != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":831 + * + * if have_start: + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if start < 0: + */ + __pyx_t_2 = (__pyx_v_start < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":832 + * if have_start: + * if start < 0: + * start += shape # <<<<<<<<<<<<<< + * if start < 0: + * start = 0 + */ + __pyx_v_start = (__pyx_v_start + __pyx_v_shape); + + /* "View.MemoryView":833 + * if start < 0: + * start += shape + * if start < 0: # <<<<<<<<<<<<<< + * start = 0 + * elif start >= shape: + */ + __pyx_t_2 = (__pyx_v_start < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":834 + * start += shape + * if start < 0: + * start = 0 # <<<<<<<<<<<<<< + * elif start >= shape: + * if negative_step: + */ + __pyx_v_start = 0; + + /* "View.MemoryView":833 + * if start < 0: + * start += shape + * if start < 0: # <<<<<<<<<<<<<< + * start = 0 + * elif start >= shape: + */ + } + + /* "View.MemoryView":831 + * + * if have_start: + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if start < 0: + */ + goto __pyx_L9; + } + + /* "View.MemoryView":835 + * if start < 0: + * start = 0 + * elif start >= shape: # <<<<<<<<<<<<<< + * if negative_step: + * start = shape - 1 + */ + __pyx_t_2 = (__pyx_v_start >= __pyx_v_shape); + if (__pyx_t_2) { + + /* "View.MemoryView":836 + * start = 0 + * elif start >= shape: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + if (__pyx_v_negative_step) { + + /* "View.MemoryView":837 + * elif start >= shape: + * if negative_step: + * start = shape - 1 # <<<<<<<<<<<<<< + * else: + * start = shape + */ + __pyx_v_start = (__pyx_v_shape - 1); + + /* "View.MemoryView":836 + * start = 0 + * elif start >= shape: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + goto __pyx_L11; + } + + /* "View.MemoryView":839 + * start = shape - 1 + * else: + * start = shape # <<<<<<<<<<<<<< + * else: + * if negative_step: + */ + /*else*/ { + __pyx_v_start = __pyx_v_shape; + } + __pyx_L11:; + + /* "View.MemoryView":835 + * if start < 0: + * start = 0 + * elif start >= shape: # <<<<<<<<<<<<<< + * if negative_step: + * start = shape - 1 + */ + } + __pyx_L9:; + + /* "View.MemoryView":830 + * + * + * if have_start: # <<<<<<<<<<<<<< + * if start < 0: + * start += shape + */ + goto __pyx_L8; + } + + /* "View.MemoryView":841 + * start = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + /*else*/ { + if (__pyx_v_negative_step) { + + /* "View.MemoryView":842 + * else: + * if negative_step: + * start = shape - 1 # <<<<<<<<<<<<<< + * else: + * start = 0 + */ + __pyx_v_start = (__pyx_v_shape - 1); + + /* "View.MemoryView":841 + * start = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + goto __pyx_L12; + } + + /* "View.MemoryView":844 + * start = shape - 1 + * else: + * start = 0 # <<<<<<<<<<<<<< + * + * if have_stop: + */ + /*else*/ { + __pyx_v_start = 0; + } + __pyx_L12:; + } + __pyx_L8:; + + /* "View.MemoryView":846 + * start = 0 + * + * if have_stop: # <<<<<<<<<<<<<< + * if stop < 0: + * stop += shape + */ + __pyx_t_2 = (__pyx_v_have_stop != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":847 + * + * if have_stop: + * if stop < 0: # <<<<<<<<<<<<<< + * stop += shape + * if stop < 0: + */ + __pyx_t_2 = (__pyx_v_stop < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":848 + * if have_stop: + * if stop < 0: + * stop += shape # <<<<<<<<<<<<<< + * if stop < 0: + * stop = 0 + */ + __pyx_v_stop = (__pyx_v_stop + __pyx_v_shape); + + /* "View.MemoryView":849 + * if stop < 0: + * stop += shape + * if stop < 0: # <<<<<<<<<<<<<< + * stop = 0 + * elif stop > shape: + */ + __pyx_t_2 = (__pyx_v_stop < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":850 + * stop += shape + * if stop < 0: + * stop = 0 # <<<<<<<<<<<<<< + * elif stop > shape: + * stop = shape + */ + __pyx_v_stop = 0; + + /* "View.MemoryView":849 + * if stop < 0: + * stop += shape + * if stop < 0: # <<<<<<<<<<<<<< + * stop = 0 + * elif stop > shape: + */ + } + + /* "View.MemoryView":847 + * + * if have_stop: + * if stop < 0: # <<<<<<<<<<<<<< + * stop += shape + * if stop < 0: + */ + goto __pyx_L14; + } + + /* "View.MemoryView":851 + * if stop < 0: + * stop = 0 + * elif stop > shape: # <<<<<<<<<<<<<< + * stop = shape + * else: + */ + __pyx_t_2 = (__pyx_v_stop > __pyx_v_shape); + if (__pyx_t_2) { + + /* "View.MemoryView":852 + * stop = 0 + * elif stop > shape: + * stop = shape # <<<<<<<<<<<<<< + * else: + * if negative_step: + */ + __pyx_v_stop = __pyx_v_shape; + + /* "View.MemoryView":851 + * if stop < 0: + * stop = 0 + * elif stop > shape: # <<<<<<<<<<<<<< + * stop = shape + * else: + */ + } + __pyx_L14:; + + /* "View.MemoryView":846 + * start = 0 + * + * if have_stop: # <<<<<<<<<<<<<< + * if stop < 0: + * stop += shape + */ + goto __pyx_L13; + } + + /* "View.MemoryView":854 + * stop = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * stop = -1 + * else: + */ + /*else*/ { + if (__pyx_v_negative_step) { + + /* "View.MemoryView":855 + * else: + * if negative_step: + * stop = -1 # <<<<<<<<<<<<<< + * else: + * stop = shape + */ + __pyx_v_stop = -1L; + + /* "View.MemoryView":854 + * stop = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * stop = -1 + * else: + */ + goto __pyx_L16; + } + + /* "View.MemoryView":857 + * stop = -1 + * else: + * stop = shape # <<<<<<<<<<<<<< + * + * + */ + /*else*/ { + __pyx_v_stop = __pyx_v_shape; + } + __pyx_L16:; + } + __pyx_L13:; + + /* "View.MemoryView":861 + * + * with cython.cdivision(True): + * new_shape = (stop - start) // step # <<<<<<<<<<<<<< + * + * if (stop - start) - step * new_shape: + */ + __pyx_v_new_shape = ((__pyx_v_stop - __pyx_v_start) / __pyx_v_step); + + /* "View.MemoryView":863 + * new_shape = (stop - start) // step + * + * if (stop - start) - step * new_shape: # <<<<<<<<<<<<<< + * new_shape += 1 + * + */ + __pyx_t_2 = (((__pyx_v_stop - __pyx_v_start) - (__pyx_v_step * __pyx_v_new_shape)) != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":864 + * + * if (stop - start) - step * new_shape: + * new_shape += 1 # <<<<<<<<<<<<<< + * + * if new_shape < 0: + */ + __pyx_v_new_shape = (__pyx_v_new_shape + 1); + + /* "View.MemoryView":863 + * new_shape = (stop - start) // step + * + * if (stop - start) - step * new_shape: # <<<<<<<<<<<<<< + * new_shape += 1 + * + */ + } + + /* "View.MemoryView":866 + * new_shape += 1 + * + * if new_shape < 0: # <<<<<<<<<<<<<< + * new_shape = 0 + * + */ + __pyx_t_2 = (__pyx_v_new_shape < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":867 + * + * if new_shape < 0: + * new_shape = 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_new_shape = 0; + + /* "View.MemoryView":866 + * new_shape += 1 + * + * if new_shape < 0: # <<<<<<<<<<<<<< + * new_shape = 0 + * + */ + } + + /* "View.MemoryView":870 + * + * + * dst.strides[new_ndim] = stride * step # <<<<<<<<<<<<<< + * dst.shape[new_ndim] = new_shape + * dst.suboffsets[new_ndim] = suboffset + */ + (__pyx_v_dst->strides[__pyx_v_new_ndim]) = (__pyx_v_stride * __pyx_v_step); + + /* "View.MemoryView":871 + * + * dst.strides[new_ndim] = stride * step + * dst.shape[new_ndim] = new_shape # <<<<<<<<<<<<<< + * dst.suboffsets[new_ndim] = suboffset + * + */ + (__pyx_v_dst->shape[__pyx_v_new_ndim]) = __pyx_v_new_shape; + + /* "View.MemoryView":872 + * dst.strides[new_ndim] = stride * step + * dst.shape[new_ndim] = new_shape + * dst.suboffsets[new_ndim] = suboffset # <<<<<<<<<<<<<< + * + * + */ + (__pyx_v_dst->suboffsets[__pyx_v_new_ndim]) = __pyx_v_suboffset; + } + __pyx_L3:; + + /* "View.MemoryView":875 + * + * + * if suboffset_dim[0] < 0: # <<<<<<<<<<<<<< + * dst.data += start * stride + * else: + */ + __pyx_t_2 = ((__pyx_v_suboffset_dim[0]) < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":876 + * + * if suboffset_dim[0] < 0: + * dst.data += start * stride # <<<<<<<<<<<<<< + * else: + * dst.suboffsets[suboffset_dim[0]] += start * stride + */ + __pyx_v_dst->data = (__pyx_v_dst->data + (__pyx_v_start * __pyx_v_stride)); + + /* "View.MemoryView":875 + * + * + * if suboffset_dim[0] < 0: # <<<<<<<<<<<<<< + * dst.data += start * stride + * else: + */ + goto __pyx_L19; + } + + /* "View.MemoryView":878 + * dst.data += start * stride + * else: + * dst.suboffsets[suboffset_dim[0]] += start * stride # <<<<<<<<<<<<<< + * + * if suboffset >= 0: + */ + /*else*/ { + __pyx_t_3 = (__pyx_v_suboffset_dim[0]); + (__pyx_v_dst->suboffsets[__pyx_t_3]) = ((__pyx_v_dst->suboffsets[__pyx_t_3]) + (__pyx_v_start * __pyx_v_stride)); + } + __pyx_L19:; + + /* "View.MemoryView":880 + * dst.suboffsets[suboffset_dim[0]] += start * stride + * + * if suboffset >= 0: # <<<<<<<<<<<<<< + * if not is_slice: + * if new_ndim == 0: + */ + __pyx_t_2 = (__pyx_v_suboffset >= 0); + if (__pyx_t_2) { + + /* "View.MemoryView":881 + * + * if suboffset >= 0: + * if not is_slice: # <<<<<<<<<<<<<< + * if new_ndim == 0: + * dst.data = ( dst.data)[0] + suboffset + */ + __pyx_t_2 = (!__pyx_v_is_slice); + if (__pyx_t_2) { + + /* "View.MemoryView":882 + * if suboffset >= 0: + * if not is_slice: + * if new_ndim == 0: # <<<<<<<<<<<<<< + * dst.data = ( dst.data)[0] + suboffset + * else: + */ + __pyx_t_2 = (__pyx_v_new_ndim == 0); + if (__pyx_t_2) { + + /* "View.MemoryView":883 + * if not is_slice: + * if new_ndim == 0: + * dst.data = ( dst.data)[0] + suboffset # <<<<<<<<<<<<<< + * else: + * _err_dim(PyExc_IndexError, "All dimensions preceding dimension %d " + */ + __pyx_v_dst->data = ((((char **)__pyx_v_dst->data)[0]) + __pyx_v_suboffset); + + /* "View.MemoryView":882 + * if suboffset >= 0: + * if not is_slice: + * if new_ndim == 0: # <<<<<<<<<<<<<< + * dst.data = ( dst.data)[0] + suboffset + * else: + */ + goto __pyx_L22; + } + + /* "View.MemoryView":885 + * dst.data = ( dst.data)[0] + suboffset + * else: + * _err_dim(PyExc_IndexError, "All dimensions preceding dimension %d " # <<<<<<<<<<<<<< + * "must be indexed and not sliced", dim) + * else: + */ + /*else*/ { + + /* "View.MemoryView":886 + * else: + * _err_dim(PyExc_IndexError, "All dimensions preceding dimension %d " + * "must be indexed and not sliced", dim) # <<<<<<<<<<<<<< + * else: + * suboffset_dim[0] = new_ndim + */ + __pyx_t_3 = __pyx_memoryview_err_dim(PyExc_IndexError, __pyx_kp_s_All_dimensions_preceding_dimensi, __pyx_v_dim); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 885, __pyx_L1_error) + } + __pyx_L22:; + + /* "View.MemoryView":881 + * + * if suboffset >= 0: + * if not is_slice: # <<<<<<<<<<<<<< + * if new_ndim == 0: + * dst.data = ( dst.data)[0] + suboffset + */ + goto __pyx_L21; + } + + /* "View.MemoryView":888 + * "must be indexed and not sliced", dim) + * else: + * suboffset_dim[0] = new_ndim # <<<<<<<<<<<<<< + * + * return 0 + */ + /*else*/ { + (__pyx_v_suboffset_dim[0]) = __pyx_v_new_ndim; + } + __pyx_L21:; + + /* "View.MemoryView":880 + * dst.suboffsets[suboffset_dim[0]] += start * stride + * + * if suboffset >= 0: # <<<<<<<<<<<<<< + * if not is_slice: + * if new_ndim == 0: + */ + } + + /* "View.MemoryView":890 + * suboffset_dim[0] = new_ndim + * + * return 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":793 + * + * @cname('__pyx_memoryview_slice_memviewslice') + * cdef int slice_memviewslice( # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * Py_ssize_t shape, Py_ssize_t stride, Py_ssize_t suboffset, + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.slice_memviewslice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":896 + * + * @cname('__pyx_pybuffer_index') + * cdef char *pybuffer_index(Py_buffer *view, char *bufp, Py_ssize_t index, # <<<<<<<<<<<<<< + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 + */ + +static char *__pyx_pybuffer_index(Py_buffer *__pyx_v_view, char *__pyx_v_bufp, Py_ssize_t __pyx_v_index, Py_ssize_t __pyx_v_dim) { + Py_ssize_t __pyx_v_shape; + Py_ssize_t __pyx_v_stride; + Py_ssize_t __pyx_v_suboffset; + Py_ssize_t __pyx_v_itemsize; + char *__pyx_v_resultp; + char *__pyx_r; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + Py_UCS4 __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("pybuffer_index", 1); + + /* "View.MemoryView":898 + * cdef char *pybuffer_index(Py_buffer *view, char *bufp, Py_ssize_t index, + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 # <<<<<<<<<<<<<< + * cdef Py_ssize_t itemsize = view.itemsize + * cdef char *resultp + */ + __pyx_v_suboffset = -1L; + + /* "View.MemoryView":899 + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 + * cdef Py_ssize_t itemsize = view.itemsize # <<<<<<<<<<<<<< + * cdef char *resultp + * + */ + __pyx_t_1 = __pyx_v_view->itemsize; + __pyx_v_itemsize = __pyx_t_1; + + /* "View.MemoryView":902 + * cdef char *resultp + * + * if view.ndim == 0: # <<<<<<<<<<<<<< + * shape = view.len // itemsize + * stride = itemsize + */ + __pyx_t_2 = (__pyx_v_view->ndim == 0); + if (__pyx_t_2) { + + /* "View.MemoryView":903 + * + * if view.ndim == 0: + * shape = view.len // itemsize # <<<<<<<<<<<<<< + * stride = itemsize + * else: + */ + if (unlikely(__pyx_v_itemsize == 0)) { + PyErr_SetString(PyExc_ZeroDivisionError, "integer division or modulo by zero"); + __PYX_ERR(1, 903, __pyx_L1_error) + } + else if (sizeof(Py_ssize_t) == sizeof(long) && (!(((Py_ssize_t)-1) > 0)) && unlikely(__pyx_v_itemsize == (Py_ssize_t)-1) && unlikely(__Pyx_UNARY_NEG_WOULD_OVERFLOW(__pyx_v_view->len))) { + PyErr_SetString(PyExc_OverflowError, "value too large to perform division"); + __PYX_ERR(1, 903, __pyx_L1_error) + } + __pyx_v_shape = __Pyx_div_Py_ssize_t(__pyx_v_view->len, __pyx_v_itemsize); + + /* "View.MemoryView":904 + * if view.ndim == 0: + * shape = view.len // itemsize + * stride = itemsize # <<<<<<<<<<<<<< + * else: + * shape = view.shape[dim] + */ + __pyx_v_stride = __pyx_v_itemsize; + + /* "View.MemoryView":902 + * cdef char *resultp + * + * if view.ndim == 0: # <<<<<<<<<<<<<< + * shape = view.len // itemsize + * stride = itemsize + */ + goto __pyx_L3; + } + + /* "View.MemoryView":906 + * stride = itemsize + * else: + * shape = view.shape[dim] # <<<<<<<<<<<<<< + * stride = view.strides[dim] + * if view.suboffsets != NULL: + */ + /*else*/ { + __pyx_v_shape = (__pyx_v_view->shape[__pyx_v_dim]); + + /* "View.MemoryView":907 + * else: + * shape = view.shape[dim] + * stride = view.strides[dim] # <<<<<<<<<<<<<< + * if view.suboffsets != NULL: + * suboffset = view.suboffsets[dim] + */ + __pyx_v_stride = (__pyx_v_view->strides[__pyx_v_dim]); + + /* "View.MemoryView":908 + * shape = view.shape[dim] + * stride = view.strides[dim] + * if view.suboffsets != NULL: # <<<<<<<<<<<<<< + * suboffset = view.suboffsets[dim] + * + */ + __pyx_t_2 = (__pyx_v_view->suboffsets != NULL); + if (__pyx_t_2) { + + /* "View.MemoryView":909 + * stride = view.strides[dim] + * if view.suboffsets != NULL: + * suboffset = view.suboffsets[dim] # <<<<<<<<<<<<<< + * + * if index < 0: + */ + __pyx_v_suboffset = (__pyx_v_view->suboffsets[__pyx_v_dim]); + + /* "View.MemoryView":908 + * shape = view.shape[dim] + * stride = view.strides[dim] + * if view.suboffsets != NULL: # <<<<<<<<<<<<<< + * suboffset = view.suboffsets[dim] + * + */ + } + } + __pyx_L3:; + + /* "View.MemoryView":911 + * suboffset = view.suboffsets[dim] + * + * if index < 0: # <<<<<<<<<<<<<< + * index += view.shape[dim] + * if index < 0: + */ + __pyx_t_2 = (__pyx_v_index < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":912 + * + * if index < 0: + * index += view.shape[dim] # <<<<<<<<<<<<<< + * if index < 0: + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + */ + __pyx_v_index = (__pyx_v_index + (__pyx_v_view->shape[__pyx_v_dim])); + + /* "View.MemoryView":913 + * if index < 0: + * index += view.shape[dim] + * if index < 0: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + __pyx_t_2 = (__pyx_v_index < 0); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":914 + * index += view.shape[dim] + * if index < 0: + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" # <<<<<<<<<<<<<< + * + * if index >= shape: + */ + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 914, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = 0; + __pyx_t_4 = 127; + __Pyx_INCREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_1 += 37; + __Pyx_GIVEREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_5 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_dim, 0, ' ', 'd'); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 914, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_5); + __Pyx_GIVEREF(__pyx_t_5); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_5); + __pyx_t_5 = 0; + __Pyx_INCREF(__pyx_kp_u__9); + __pyx_t_1 += 1; + __Pyx_GIVEREF(__pyx_kp_u__9); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_kp_u__9); + __pyx_t_5 = __Pyx_PyUnicode_Join(__pyx_t_3, 3, __pyx_t_1, __pyx_t_4); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 914, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_builtin_IndexError, __pyx_t_5, 0, 0); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __PYX_ERR(1, 914, __pyx_L1_error) + + /* "View.MemoryView":913 + * if index < 0: + * index += view.shape[dim] + * if index < 0: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + } + + /* "View.MemoryView":911 + * suboffset = view.suboffsets[dim] + * + * if index < 0: # <<<<<<<<<<<<<< + * index += view.shape[dim] + * if index < 0: + */ + } + + /* "View.MemoryView":916 + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + * if index >= shape: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + __pyx_t_2 = (__pyx_v_index >= __pyx_v_shape); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":917 + * + * if index >= shape: + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" # <<<<<<<<<<<<<< + * + * resultp = bufp + index * stride + */ + __pyx_t_5 = PyTuple_New(3); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 917, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 = 0; + __pyx_t_4 = 127; + __Pyx_INCREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_1 += 37; + __Pyx_GIVEREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_3 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_dim, 0, ' ', 'd'); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 917, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_3); + PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_3); + __pyx_t_3 = 0; + __Pyx_INCREF(__pyx_kp_u__9); + __pyx_t_1 += 1; + __Pyx_GIVEREF(__pyx_kp_u__9); + PyTuple_SET_ITEM(__pyx_t_5, 2, __pyx_kp_u__9); + __pyx_t_3 = __Pyx_PyUnicode_Join(__pyx_t_5, 3, __pyx_t_1, __pyx_t_4); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 917, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_Raise(__pyx_builtin_IndexError, __pyx_t_3, 0, 0); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __PYX_ERR(1, 917, __pyx_L1_error) + + /* "View.MemoryView":916 + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + * if index >= shape: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + } + + /* "View.MemoryView":919 + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + * resultp = bufp + index * stride # <<<<<<<<<<<<<< + * if suboffset >= 0: + * resultp = ( resultp)[0] + suboffset + */ + __pyx_v_resultp = (__pyx_v_bufp + (__pyx_v_index * __pyx_v_stride)); + + /* "View.MemoryView":920 + * + * resultp = bufp + index * stride + * if suboffset >= 0: # <<<<<<<<<<<<<< + * resultp = ( resultp)[0] + suboffset + * + */ + __pyx_t_2 = (__pyx_v_suboffset >= 0); + if (__pyx_t_2) { + + /* "View.MemoryView":921 + * resultp = bufp + index * stride + * if suboffset >= 0: + * resultp = ( resultp)[0] + suboffset # <<<<<<<<<<<<<< + * + * return resultp + */ + __pyx_v_resultp = ((((char **)__pyx_v_resultp)[0]) + __pyx_v_suboffset); + + /* "View.MemoryView":920 + * + * resultp = bufp + index * stride + * if suboffset >= 0: # <<<<<<<<<<<<<< + * resultp = ( resultp)[0] + suboffset + * + */ + } + + /* "View.MemoryView":923 + * resultp = ( resultp)[0] + suboffset + * + * return resultp # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = __pyx_v_resultp; + goto __pyx_L0; + + /* "View.MemoryView":896 + * + * @cname('__pyx_pybuffer_index') + * cdef char *pybuffer_index(Py_buffer *view, char *bufp, Py_ssize_t index, # <<<<<<<<<<<<<< + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.pybuffer_index", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":929 + * + * @cname('__pyx_memslice_transpose') + * cdef int transpose_memslice(__Pyx_memviewslice *memslice) except -1 nogil: # <<<<<<<<<<<<<< + * cdef int ndim = memslice.memview.view.ndim + * + */ + +static int __pyx_memslice_transpose(__Pyx_memviewslice *__pyx_v_memslice) { + int __pyx_v_ndim; + Py_ssize_t *__pyx_v_shape; + Py_ssize_t *__pyx_v_strides; + int __pyx_v_i; + int __pyx_v_j; + int __pyx_r; + int __pyx_t_1; + Py_ssize_t *__pyx_t_2; + long __pyx_t_3; + long __pyx_t_4; + Py_ssize_t __pyx_t_5; + Py_ssize_t __pyx_t_6; + int __pyx_t_7; + int __pyx_t_8; + int __pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":930 + * @cname('__pyx_memslice_transpose') + * cdef int transpose_memslice(__Pyx_memviewslice *memslice) except -1 nogil: + * cdef int ndim = memslice.memview.view.ndim # <<<<<<<<<<<<<< + * + * cdef Py_ssize_t *shape = memslice.shape + */ + __pyx_t_1 = __pyx_v_memslice->memview->view.ndim; + __pyx_v_ndim = __pyx_t_1; + + /* "View.MemoryView":932 + * cdef int ndim = memslice.memview.view.ndim + * + * cdef Py_ssize_t *shape = memslice.shape # <<<<<<<<<<<<<< + * cdef Py_ssize_t *strides = memslice.strides + * + */ + __pyx_t_2 = __pyx_v_memslice->shape; + __pyx_v_shape = __pyx_t_2; + + /* "View.MemoryView":933 + * + * cdef Py_ssize_t *shape = memslice.shape + * cdef Py_ssize_t *strides = memslice.strides # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = __pyx_v_memslice->strides; + __pyx_v_strides = __pyx_t_2; + + /* "View.MemoryView":937 + * + * cdef int i, j + * for i in range(ndim // 2): # <<<<<<<<<<<<<< + * j = ndim - 1 - i + * strides[i], strides[j] = strides[j], strides[i] + */ + __pyx_t_3 = __Pyx_div_long(__pyx_v_ndim, 2); + __pyx_t_4 = __pyx_t_3; + for (__pyx_t_1 = 0; __pyx_t_1 < __pyx_t_4; __pyx_t_1+=1) { + __pyx_v_i = __pyx_t_1; + + /* "View.MemoryView":938 + * cdef int i, j + * for i in range(ndim // 2): + * j = ndim - 1 - i # <<<<<<<<<<<<<< + * strides[i], strides[j] = strides[j], strides[i] + * shape[i], shape[j] = shape[j], shape[i] + */ + __pyx_v_j = ((__pyx_v_ndim - 1) - __pyx_v_i); + + /* "View.MemoryView":939 + * for i in range(ndim // 2): + * j = ndim - 1 - i + * strides[i], strides[j] = strides[j], strides[i] # <<<<<<<<<<<<<< + * shape[i], shape[j] = shape[j], shape[i] + * + */ + __pyx_t_5 = (__pyx_v_strides[__pyx_v_j]); + __pyx_t_6 = (__pyx_v_strides[__pyx_v_i]); + (__pyx_v_strides[__pyx_v_i]) = __pyx_t_5; + (__pyx_v_strides[__pyx_v_j]) = __pyx_t_6; + + /* "View.MemoryView":940 + * j = ndim - 1 - i + * strides[i], strides[j] = strides[j], strides[i] + * shape[i], shape[j] = shape[j], shape[i] # <<<<<<<<<<<<<< + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: + */ + __pyx_t_6 = (__pyx_v_shape[__pyx_v_j]); + __pyx_t_5 = (__pyx_v_shape[__pyx_v_i]); + (__pyx_v_shape[__pyx_v_i]) = __pyx_t_6; + (__pyx_v_shape[__pyx_v_j]) = __pyx_t_5; + + /* "View.MemoryView":942 + * shape[i], shape[j] = shape[j], shape[i] + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: # <<<<<<<<<<<<<< + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") + * + */ + __pyx_t_8 = ((__pyx_v_memslice->suboffsets[__pyx_v_i]) >= 0); + if (!__pyx_t_8) { + } else { + __pyx_t_7 = __pyx_t_8; + goto __pyx_L6_bool_binop_done; + } + __pyx_t_8 = ((__pyx_v_memslice->suboffsets[__pyx_v_j]) >= 0); + __pyx_t_7 = __pyx_t_8; + __pyx_L6_bool_binop_done:; + if (__pyx_t_7) { + + /* "View.MemoryView":943 + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") # <<<<<<<<<<<<<< + * + * return 0 + */ + __pyx_t_9 = __pyx_memoryview_err(PyExc_ValueError, __pyx_kp_s_Cannot_transpose_memoryview_with); if (unlikely(__pyx_t_9 == ((int)-1))) __PYX_ERR(1, 943, __pyx_L1_error) + + /* "View.MemoryView":942 + * shape[i], shape[j] = shape[j], shape[i] + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: # <<<<<<<<<<<<<< + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") + * + */ + } + } + + /* "View.MemoryView":945 + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") + * + * return 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":929 + * + * @cname('__pyx_memslice_transpose') + * cdef int transpose_memslice(__Pyx_memviewslice *memslice) except -1 nogil: # <<<<<<<<<<<<<< + * cdef int ndim = memslice.memview.view.ndim + * + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.transpose_memslice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":963 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + */ + +/* Python wrapper */ +static void __pyx_memoryviewslice___dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_memoryviewslice___dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_memoryviewslice___pyx_pf_15View_dot_MemoryView_16_memoryviewslice___dealloc__(((struct __pyx_memoryviewslice_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_memoryviewslice___pyx_pf_15View_dot_MemoryView_16_memoryviewslice___dealloc__(struct __pyx_memoryviewslice_obj *__pyx_v_self) { + + /* "View.MemoryView":964 + * + * def __dealloc__(self): + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) # <<<<<<<<<<<<<< + * + * cdef convert_item_to_object(self, char *itemp): + */ + __PYX_XCLEAR_MEMVIEW((&__pyx_v_self->from_slice), 1); + + /* "View.MemoryView":963 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + */ + + /* function exit code */ +} + +/* "View.MemoryView":966 + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * if self.to_object_func != NULL: + * return self.to_object_func(itemp) + */ + +static PyObject *__pyx_memoryviewslice_convert_item_to_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("convert_item_to_object", 1); + + /* "View.MemoryView":967 + * + * cdef convert_item_to_object(self, char *itemp): + * if self.to_object_func != NULL: # <<<<<<<<<<<<<< + * return self.to_object_func(itemp) + * else: + */ + __pyx_t_1 = (__pyx_v_self->to_object_func != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":968 + * cdef convert_item_to_object(self, char *itemp): + * if self.to_object_func != NULL: + * return self.to_object_func(itemp) # <<<<<<<<<<<<<< + * else: + * return memoryview.convert_item_to_object(self, itemp) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_v_self->to_object_func(__pyx_v_itemp); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 968, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":967 + * + * cdef convert_item_to_object(self, char *itemp): + * if self.to_object_func != NULL: # <<<<<<<<<<<<<< + * return self.to_object_func(itemp) + * else: + */ + } + + /* "View.MemoryView":970 + * return self.to_object_func(itemp) + * else: + * return memoryview.convert_item_to_object(self, itemp) # <<<<<<<<<<<<<< + * + * cdef assign_item_from_object(self, char *itemp, object value): + */ + /*else*/ { + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_memoryview_convert_item_to_object(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v_itemp); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 970, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + } + + /* "View.MemoryView":966 + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * if self.to_object_func != NULL: + * return self.to_object_func(itemp) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.convert_item_to_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":972 + * return memoryview.convert_item_to_object(self, itemp) + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * if self.to_dtype_func != NULL: + * self.to_dtype_func(itemp, value) + */ + +static PyObject *__pyx_memoryviewslice_assign_item_from_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("assign_item_from_object", 1); + + /* "View.MemoryView":973 + * + * cdef assign_item_from_object(self, char *itemp, object value): + * if self.to_dtype_func != NULL: # <<<<<<<<<<<<<< + * self.to_dtype_func(itemp, value) + * else: + */ + __pyx_t_1 = (__pyx_v_self->to_dtype_func != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":974 + * cdef assign_item_from_object(self, char *itemp, object value): + * if self.to_dtype_func != NULL: + * self.to_dtype_func(itemp, value) # <<<<<<<<<<<<<< + * else: + * memoryview.assign_item_from_object(self, itemp, value) + */ + __pyx_t_2 = __pyx_v_self->to_dtype_func(__pyx_v_itemp, __pyx_v_value); if (unlikely(__pyx_t_2 == ((int)0))) __PYX_ERR(1, 974, __pyx_L1_error) + + /* "View.MemoryView":973 + * + * cdef assign_item_from_object(self, char *itemp, object value): + * if self.to_dtype_func != NULL: # <<<<<<<<<<<<<< + * self.to_dtype_func(itemp, value) + * else: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":976 + * self.to_dtype_func(itemp, value) + * else: + * memoryview.assign_item_from_object(self, itemp, value) # <<<<<<<<<<<<<< + * + * cdef _get_base(self): + */ + /*else*/ { + __pyx_t_3 = __pyx_memoryview_assign_item_from_object(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v_itemp, __pyx_v_value); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 976, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_L3:; + + /* "View.MemoryView":972 + * return memoryview.convert_item_to_object(self, itemp) + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * if self.to_dtype_func != NULL: + * self.to_dtype_func(itemp, value) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.assign_item_from_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":978 + * memoryview.assign_item_from_object(self, itemp, value) + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.from_object + * + */ + +static PyObject *__pyx_memoryviewslice__get_base(struct __pyx_memoryviewslice_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("_get_base", 1); + + /* "View.MemoryView":979 + * + * cdef _get_base(self): + * return self.from_object # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->from_object); + __pyx_r = __pyx_v_self->from_object; + goto __pyx_L0; + + /* "View.MemoryView":978 + * memoryview.assign_item_from_object(self, itemp, value) + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.from_object + * + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryviewslice_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryviewslice_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_memoryviewslice___reduce_cython__(((struct __pyx_memoryviewslice_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryviewslice___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryviewslice_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryviewslice_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_memoryviewslice_2__setstate_cython__(((struct __pyx_memoryviewslice_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryviewslice_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":999 + * + * @cname('__pyx_memoryview_fromslice') + * cdef memoryview_fromslice(__Pyx_memviewslice memviewslice, # <<<<<<<<<<<<<< + * int ndim, + * object (*to_object_func)(char *), + */ + +static PyObject *__pyx_memoryview_fromslice(__Pyx_memviewslice __pyx_v_memviewslice, int __pyx_v_ndim, PyObject *(*__pyx_v_to_object_func)(char *), int (*__pyx_v_to_dtype_func)(char *, PyObject *), int __pyx_v_dtype_is_object) { + struct __pyx_memoryviewslice_obj *__pyx_v_result = 0; + Py_ssize_t __pyx_v_suboffset; + PyObject *__pyx_v_length = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + __Pyx_TypeInfo *__pyx_t_4; + Py_buffer __pyx_t_5; + Py_ssize_t *__pyx_t_6; + Py_ssize_t *__pyx_t_7; + Py_ssize_t *__pyx_t_8; + Py_ssize_t __pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_fromslice", 1); + + /* "View.MemoryView":1007 + * cdef _memoryviewslice result + * + * if memviewslice.memview == Py_None: # <<<<<<<<<<<<<< + * return None + * + */ + __pyx_t_1 = (((PyObject *)__pyx_v_memviewslice.memview) == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":1008 + * + * if memviewslice.memview == Py_None: + * return None # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "View.MemoryView":1007 + * cdef _memoryviewslice result + * + * if memviewslice.memview == Py_None: # <<<<<<<<<<<<<< + * return None + * + */ + } + + /* "View.MemoryView":1013 + * + * + * result = _memoryviewslice.__new__(_memoryviewslice, None, 0, dtype_is_object) # <<<<<<<<<<<<<< + * + * result.from_slice = memviewslice + */ + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_v_dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1013, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 1013, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(Py_None); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, Py_None)) __PYX_ERR(1, 1013, __pyx_L1_error); + __Pyx_INCREF(__pyx_int_0); + __Pyx_GIVEREF(__pyx_int_0); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_int_0)) __PYX_ERR(1, 1013, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_t_2)) __PYX_ERR(1, 1013, __pyx_L1_error); + __pyx_t_2 = 0; + __pyx_t_2 = ((PyObject *)__pyx_tp_new__memoryviewslice(((PyTypeObject *)__pyx_memoryviewslice_type), __pyx_t_3, NULL)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1013, __pyx_L1_error) + __Pyx_GOTREF((PyObject *)__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_v_result = ((struct __pyx_memoryviewslice_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":1015 + * result = _memoryviewslice.__new__(_memoryviewslice, None, 0, dtype_is_object) + * + * result.from_slice = memviewslice # <<<<<<<<<<<<<< + * __PYX_INC_MEMVIEW(&memviewslice, 1) + * + */ + __pyx_v_result->from_slice = __pyx_v_memviewslice; + + /* "View.MemoryView":1016 + * + * result.from_slice = memviewslice + * __PYX_INC_MEMVIEW(&memviewslice, 1) # <<<<<<<<<<<<<< + * + * result.from_object = ( memviewslice.memview)._get_base() + */ + __PYX_INC_MEMVIEW((&__pyx_v_memviewslice), 1); + + /* "View.MemoryView":1018 + * __PYX_INC_MEMVIEW(&memviewslice, 1) + * + * result.from_object = ( memviewslice.memview)._get_base() # <<<<<<<<<<<<<< + * result.typeinfo = memviewslice.memview.typeinfo + * + */ + __pyx_t_2 = ((struct __pyx_vtabstruct_memoryview *)((struct __pyx_memoryview_obj *)__pyx_v_memviewslice.memview)->__pyx_vtab)->_get_base(((struct __pyx_memoryview_obj *)__pyx_v_memviewslice.memview)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1018, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + __Pyx_GOTREF(__pyx_v_result->from_object); + __Pyx_DECREF(__pyx_v_result->from_object); + __pyx_v_result->from_object = __pyx_t_2; + __pyx_t_2 = 0; + + /* "View.MemoryView":1019 + * + * result.from_object = ( memviewslice.memview)._get_base() + * result.typeinfo = memviewslice.memview.typeinfo # <<<<<<<<<<<<<< + * + * result.view = memviewslice.memview.view + */ + __pyx_t_4 = __pyx_v_memviewslice.memview->typeinfo; + __pyx_v_result->__pyx_base.typeinfo = __pyx_t_4; + + /* "View.MemoryView":1021 + * result.typeinfo = memviewslice.memview.typeinfo + * + * result.view = memviewslice.memview.view # <<<<<<<<<<<<<< + * result.view.buf = memviewslice.data + * result.view.ndim = ndim + */ + __pyx_t_5 = __pyx_v_memviewslice.memview->view; + __pyx_v_result->__pyx_base.view = __pyx_t_5; + + /* "View.MemoryView":1022 + * + * result.view = memviewslice.memview.view + * result.view.buf = memviewslice.data # <<<<<<<<<<<<<< + * result.view.ndim = ndim + * (<__pyx_buffer *> &result.view).obj = Py_None + */ + __pyx_v_result->__pyx_base.view.buf = ((void *)__pyx_v_memviewslice.data); + + /* "View.MemoryView":1023 + * result.view = memviewslice.memview.view + * result.view.buf = memviewslice.data + * result.view.ndim = ndim # <<<<<<<<<<<<<< + * (<__pyx_buffer *> &result.view).obj = Py_None + * Py_INCREF(Py_None) + */ + __pyx_v_result->__pyx_base.view.ndim = __pyx_v_ndim; + + /* "View.MemoryView":1024 + * result.view.buf = memviewslice.data + * result.view.ndim = ndim + * (<__pyx_buffer *> &result.view).obj = Py_None # <<<<<<<<<<<<<< + * Py_INCREF(Py_None) + * + */ + ((Py_buffer *)(&__pyx_v_result->__pyx_base.view))->obj = Py_None; + + /* "View.MemoryView":1025 + * result.view.ndim = ndim + * (<__pyx_buffer *> &result.view).obj = Py_None + * Py_INCREF(Py_None) # <<<<<<<<<<<<<< + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: + */ + Py_INCREF(Py_None); + + /* "View.MemoryView":1027 + * Py_INCREF(Py_None) + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: # <<<<<<<<<<<<<< + * result.flags = PyBUF_RECORDS + * else: + */ + __pyx_t_1 = ((((struct __pyx_memoryview_obj *)__pyx_v_memviewslice.memview)->flags & PyBUF_WRITABLE) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":1028 + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: + * result.flags = PyBUF_RECORDS # <<<<<<<<<<<<<< + * else: + * result.flags = PyBUF_RECORDS_RO + */ + __pyx_v_result->__pyx_base.flags = PyBUF_RECORDS; + + /* "View.MemoryView":1027 + * Py_INCREF(Py_None) + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: # <<<<<<<<<<<<<< + * result.flags = PyBUF_RECORDS + * else: + */ + goto __pyx_L4; + } + + /* "View.MemoryView":1030 + * result.flags = PyBUF_RECORDS + * else: + * result.flags = PyBUF_RECORDS_RO # <<<<<<<<<<<<<< + * + * result.view.shape = result.from_slice.shape + */ + /*else*/ { + __pyx_v_result->__pyx_base.flags = PyBUF_RECORDS_RO; + } + __pyx_L4:; + + /* "View.MemoryView":1032 + * result.flags = PyBUF_RECORDS_RO + * + * result.view.shape = result.from_slice.shape # <<<<<<<<<<<<<< + * result.view.strides = result.from_slice.strides + * + */ + __pyx_v_result->__pyx_base.view.shape = ((Py_ssize_t *)__pyx_v_result->from_slice.shape); + + /* "View.MemoryView":1033 + * + * result.view.shape = result.from_slice.shape + * result.view.strides = result.from_slice.strides # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_result->__pyx_base.view.strides = ((Py_ssize_t *)__pyx_v_result->from_slice.strides); + + /* "View.MemoryView":1036 + * + * + * result.view.suboffsets = NULL # <<<<<<<<<<<<<< + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: + */ + __pyx_v_result->__pyx_base.view.suboffsets = NULL; + + /* "View.MemoryView":1037 + * + * result.view.suboffsets = NULL + * for suboffset in result.from_slice.suboffsets[:ndim]: # <<<<<<<<<<<<<< + * if suboffset >= 0: + * result.view.suboffsets = result.from_slice.suboffsets + */ + __pyx_t_7 = (__pyx_v_result->from_slice.suboffsets + __pyx_v_ndim); + for (__pyx_t_8 = __pyx_v_result->from_slice.suboffsets; __pyx_t_8 < __pyx_t_7; __pyx_t_8++) { + __pyx_t_6 = __pyx_t_8; + __pyx_v_suboffset = (__pyx_t_6[0]); + + /* "View.MemoryView":1038 + * result.view.suboffsets = NULL + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * result.view.suboffsets = result.from_slice.suboffsets + * break + */ + __pyx_t_1 = (__pyx_v_suboffset >= 0); + if (__pyx_t_1) { + + /* "View.MemoryView":1039 + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: + * result.view.suboffsets = result.from_slice.suboffsets # <<<<<<<<<<<<<< + * break + * + */ + __pyx_v_result->__pyx_base.view.suboffsets = ((Py_ssize_t *)__pyx_v_result->from_slice.suboffsets); + + /* "View.MemoryView":1040 + * if suboffset >= 0: + * result.view.suboffsets = result.from_slice.suboffsets + * break # <<<<<<<<<<<<<< + * + * result.view.len = result.view.itemsize + */ + goto __pyx_L6_break; + + /* "View.MemoryView":1038 + * result.view.suboffsets = NULL + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * result.view.suboffsets = result.from_slice.suboffsets + * break + */ + } + } + __pyx_L6_break:; + + /* "View.MemoryView":1042 + * break + * + * result.view.len = result.view.itemsize # <<<<<<<<<<<<<< + * for length in result.view.shape[:ndim]: + * result.view.len *= length + */ + __pyx_t_9 = __pyx_v_result->__pyx_base.view.itemsize; + __pyx_v_result->__pyx_base.view.len = __pyx_t_9; + + /* "View.MemoryView":1043 + * + * result.view.len = result.view.itemsize + * for length in result.view.shape[:ndim]: # <<<<<<<<<<<<<< + * result.view.len *= length + * + */ + __pyx_t_7 = (__pyx_v_result->__pyx_base.view.shape + __pyx_v_ndim); + for (__pyx_t_8 = __pyx_v_result->__pyx_base.view.shape; __pyx_t_8 < __pyx_t_7; __pyx_t_8++) { + __pyx_t_6 = __pyx_t_8; + __pyx_t_2 = PyInt_FromSsize_t((__pyx_t_6[0])); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1043, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_XDECREF_SET(__pyx_v_length, __pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":1044 + * result.view.len = result.view.itemsize + * for length in result.view.shape[:ndim]: + * result.view.len *= length # <<<<<<<<<<<<<< + * + * result.to_object_func = to_object_func + */ + __pyx_t_2 = PyInt_FromSsize_t(__pyx_v_result->__pyx_base.view.len); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1044, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyNumber_InPlaceMultiply(__pyx_t_2, __pyx_v_length); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 1044, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_9 = __Pyx_PyIndex_AsSsize_t(__pyx_t_3); if (unlikely((__pyx_t_9 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 1044, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_v_result->__pyx_base.view.len = __pyx_t_9; + } + + /* "View.MemoryView":1046 + * result.view.len *= length + * + * result.to_object_func = to_object_func # <<<<<<<<<<<<<< + * result.to_dtype_func = to_dtype_func + * + */ + __pyx_v_result->to_object_func = __pyx_v_to_object_func; + + /* "View.MemoryView":1047 + * + * result.to_object_func = to_object_func + * result.to_dtype_func = to_dtype_func # <<<<<<<<<<<<<< + * + * return result + */ + __pyx_v_result->to_dtype_func = __pyx_v_to_dtype_func; + + /* "View.MemoryView":1049 + * result.to_dtype_func = to_dtype_func + * + * return result # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_get_slice_from_memoryview') + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = ((PyObject *)__pyx_v_result); + goto __pyx_L0; + + /* "View.MemoryView":999 + * + * @cname('__pyx_memoryview_fromslice') + * cdef memoryview_fromslice(__Pyx_memviewslice memviewslice, # <<<<<<<<<<<<<< + * int ndim, + * object (*to_object_func)(char *), + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview_fromslice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XDECREF(__pyx_v_length); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1052 + * + * @cname('__pyx_memoryview_get_slice_from_memoryview') + * cdef __Pyx_memviewslice *get_slice_from_memview(memoryview memview, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + */ + +static __Pyx_memviewslice *__pyx_memoryview_get_slice_from_memoryview(struct __pyx_memoryview_obj *__pyx_v_memview, __Pyx_memviewslice *__pyx_v_mslice) { + struct __pyx_memoryviewslice_obj *__pyx_v_obj = 0; + __Pyx_memviewslice *__pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_slice_from_memview", 1); + + /* "View.MemoryView":1055 + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * obj = memview + * return &obj.from_slice + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":1056 + * cdef _memoryviewslice obj + * if isinstance(memview, _memoryviewslice): + * obj = memview # <<<<<<<<<<<<<< + * return &obj.from_slice + * else: + */ + if (!(likely(((((PyObject *)__pyx_v_memview)) == Py_None) || likely(__Pyx_TypeTest(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type))))) __PYX_ERR(1, 1056, __pyx_L1_error) + __pyx_t_2 = ((PyObject *)__pyx_v_memview); + __Pyx_INCREF(__pyx_t_2); + __pyx_v_obj = ((struct __pyx_memoryviewslice_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":1057 + * if isinstance(memview, _memoryviewslice): + * obj = memview + * return &obj.from_slice # <<<<<<<<<<<<<< + * else: + * slice_copy(memview, mslice) + */ + __pyx_r = (&__pyx_v_obj->from_slice); + goto __pyx_L0; + + /* "View.MemoryView":1055 + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * obj = memview + * return &obj.from_slice + */ + } + + /* "View.MemoryView":1059 + * return &obj.from_slice + * else: + * slice_copy(memview, mslice) # <<<<<<<<<<<<<< + * return mslice + * + */ + /*else*/ { + __pyx_memoryview_slice_copy(__pyx_v_memview, __pyx_v_mslice); + + /* "View.MemoryView":1060 + * else: + * slice_copy(memview, mslice) + * return mslice # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_slice_copy') + */ + __pyx_r = __pyx_v_mslice; + goto __pyx_L0; + } + + /* "View.MemoryView":1052 + * + * @cname('__pyx_memoryview_get_slice_from_memoryview') + * cdef __Pyx_memviewslice *get_slice_from_memview(memoryview memview, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.get_slice_from_memview", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_obj); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1063 + * + * @cname('__pyx_memoryview_slice_copy') + * cdef void slice_copy(memoryview memview, __Pyx_memviewslice *dst) noexcept: # <<<<<<<<<<<<<< + * cdef int dim + * cdef (Py_ssize_t*) shape, strides, suboffsets + */ + +static void __pyx_memoryview_slice_copy(struct __pyx_memoryview_obj *__pyx_v_memview, __Pyx_memviewslice *__pyx_v_dst) { + int __pyx_v_dim; + Py_ssize_t *__pyx_v_shape; + Py_ssize_t *__pyx_v_strides; + Py_ssize_t *__pyx_v_suboffsets; + Py_ssize_t *__pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + Py_ssize_t __pyx_t_5; + int __pyx_t_6; + + /* "View.MemoryView":1067 + * cdef (Py_ssize_t*) shape, strides, suboffsets + * + * shape = memview.view.shape # <<<<<<<<<<<<<< + * strides = memview.view.strides + * suboffsets = memview.view.suboffsets + */ + __pyx_t_1 = __pyx_v_memview->view.shape; + __pyx_v_shape = __pyx_t_1; + + /* "View.MemoryView":1068 + * + * shape = memview.view.shape + * strides = memview.view.strides # <<<<<<<<<<<<<< + * suboffsets = memview.view.suboffsets + * + */ + __pyx_t_1 = __pyx_v_memview->view.strides; + __pyx_v_strides = __pyx_t_1; + + /* "View.MemoryView":1069 + * shape = memview.view.shape + * strides = memview.view.strides + * suboffsets = memview.view.suboffsets # <<<<<<<<<<<<<< + * + * dst.memview = <__pyx_memoryview *> memview + */ + __pyx_t_1 = __pyx_v_memview->view.suboffsets; + __pyx_v_suboffsets = __pyx_t_1; + + /* "View.MemoryView":1071 + * suboffsets = memview.view.suboffsets + * + * dst.memview = <__pyx_memoryview *> memview # <<<<<<<<<<<<<< + * dst.data = memview.view.buf + * + */ + __pyx_v_dst->memview = ((struct __pyx_memoryview_obj *)__pyx_v_memview); + + /* "View.MemoryView":1072 + * + * dst.memview = <__pyx_memoryview *> memview + * dst.data = memview.view.buf # <<<<<<<<<<<<<< + * + * for dim in range(memview.view.ndim): + */ + __pyx_v_dst->data = ((char *)__pyx_v_memview->view.buf); + + /* "View.MemoryView":1074 + * dst.data = memview.view.buf + * + * for dim in range(memview.view.ndim): # <<<<<<<<<<<<<< + * dst.shape[dim] = shape[dim] + * dst.strides[dim] = strides[dim] + */ + __pyx_t_2 = __pyx_v_memview->view.ndim; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_dim = __pyx_t_4; + + /* "View.MemoryView":1075 + * + * for dim in range(memview.view.ndim): + * dst.shape[dim] = shape[dim] # <<<<<<<<<<<<<< + * dst.strides[dim] = strides[dim] + * dst.suboffsets[dim] = suboffsets[dim] if suboffsets else -1 + */ + (__pyx_v_dst->shape[__pyx_v_dim]) = (__pyx_v_shape[__pyx_v_dim]); + + /* "View.MemoryView":1076 + * for dim in range(memview.view.ndim): + * dst.shape[dim] = shape[dim] + * dst.strides[dim] = strides[dim] # <<<<<<<<<<<<<< + * dst.suboffsets[dim] = suboffsets[dim] if suboffsets else -1 + * + */ + (__pyx_v_dst->strides[__pyx_v_dim]) = (__pyx_v_strides[__pyx_v_dim]); + + /* "View.MemoryView":1077 + * dst.shape[dim] = shape[dim] + * dst.strides[dim] = strides[dim] + * dst.suboffsets[dim] = suboffsets[dim] if suboffsets else -1 # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_copy_object') + */ + __pyx_t_6 = (__pyx_v_suboffsets != 0); + if (__pyx_t_6) { + __pyx_t_5 = (__pyx_v_suboffsets[__pyx_v_dim]); + } else { + __pyx_t_5 = -1L; + } + (__pyx_v_dst->suboffsets[__pyx_v_dim]) = __pyx_t_5; + } + + /* "View.MemoryView":1063 + * + * @cname('__pyx_memoryview_slice_copy') + * cdef void slice_copy(memoryview memview, __Pyx_memviewslice *dst) noexcept: # <<<<<<<<<<<<<< + * cdef int dim + * cdef (Py_ssize_t*) shape, strides, suboffsets + */ + + /* function exit code */ +} + +/* "View.MemoryView":1080 + * + * @cname('__pyx_memoryview_copy_object') + * cdef memoryview_copy(memoryview memview): # <<<<<<<<<<<<<< + * "Create a new memoryview object" + * cdef __Pyx_memviewslice memviewslice + */ + +static PyObject *__pyx_memoryview_copy_object(struct __pyx_memoryview_obj *__pyx_v_memview) { + __Pyx_memviewslice __pyx_v_memviewslice; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_copy", 1); + + /* "View.MemoryView":1083 + * "Create a new memoryview object" + * cdef __Pyx_memviewslice memviewslice + * slice_copy(memview, &memviewslice) # <<<<<<<<<<<<<< + * return memoryview_copy_from_slice(memview, &memviewslice) + * + */ + __pyx_memoryview_slice_copy(__pyx_v_memview, (&__pyx_v_memviewslice)); + + /* "View.MemoryView":1084 + * cdef __Pyx_memviewslice memviewslice + * slice_copy(memview, &memviewslice) + * return memoryview_copy_from_slice(memview, &memviewslice) # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_copy_object_from_slice') + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __pyx_memoryview_copy_object_from_slice(__pyx_v_memview, (&__pyx_v_memviewslice)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 1084, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":1080 + * + * @cname('__pyx_memoryview_copy_object') + * cdef memoryview_copy(memoryview memview): # <<<<<<<<<<<<<< + * "Create a new memoryview object" + * cdef __Pyx_memviewslice memviewslice + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview_copy", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1087 + * + * @cname('__pyx_memoryview_copy_object_from_slice') + * cdef memoryview_copy_from_slice(memoryview memview, __Pyx_memviewslice *memviewslice): # <<<<<<<<<<<<<< + * """ + * Create a new memoryview object from a given memoryview object and slice. + */ + +static PyObject *__pyx_memoryview_copy_object_from_slice(struct __pyx_memoryview_obj *__pyx_v_memview, __Pyx_memviewslice *__pyx_v_memviewslice) { + PyObject *(*__pyx_v_to_object_func)(char *); + int (*__pyx_v_to_dtype_func)(char *, PyObject *); + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *(*__pyx_t_2)(char *); + int (*__pyx_t_3)(char *, PyObject *); + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_copy_from_slice", 1); + + /* "View.MemoryView":1094 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * to_object_func = (<_memoryviewslice> memview).to_object_func + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":1095 + * + * if isinstance(memview, _memoryviewslice): + * to_object_func = (<_memoryviewslice> memview).to_object_func # <<<<<<<<<<<<<< + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + * else: + */ + __pyx_t_2 = ((struct __pyx_memoryviewslice_obj *)__pyx_v_memview)->to_object_func; + __pyx_v_to_object_func = __pyx_t_2; + + /* "View.MemoryView":1096 + * if isinstance(memview, _memoryviewslice): + * to_object_func = (<_memoryviewslice> memview).to_object_func + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func # <<<<<<<<<<<<<< + * else: + * to_object_func = NULL + */ + __pyx_t_3 = ((struct __pyx_memoryviewslice_obj *)__pyx_v_memview)->to_dtype_func; + __pyx_v_to_dtype_func = __pyx_t_3; + + /* "View.MemoryView":1094 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * to_object_func = (<_memoryviewslice> memview).to_object_func + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1098 + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + * else: + * to_object_func = NULL # <<<<<<<<<<<<<< + * to_dtype_func = NULL + * + */ + /*else*/ { + __pyx_v_to_object_func = NULL; + + /* "View.MemoryView":1099 + * else: + * to_object_func = NULL + * to_dtype_func = NULL # <<<<<<<<<<<<<< + * + * return memoryview_fromslice(memviewslice[0], memview.view.ndim, + */ + __pyx_v_to_dtype_func = NULL; + } + __pyx_L3:; + + /* "View.MemoryView":1101 + * to_dtype_func = NULL + * + * return memoryview_fromslice(memviewslice[0], memview.view.ndim, # <<<<<<<<<<<<<< + * to_object_func, to_dtype_func, + * memview.dtype_is_object) + */ + __Pyx_XDECREF(__pyx_r); + + /* "View.MemoryView":1103 + * return memoryview_fromslice(memviewslice[0], memview.view.ndim, + * to_object_func, to_dtype_func, + * memview.dtype_is_object) # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_4 = __pyx_memoryview_fromslice((__pyx_v_memviewslice[0]), __pyx_v_memview->view.ndim, __pyx_v_to_object_func, __pyx_v_to_dtype_func, __pyx_v_memview->dtype_is_object); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1101, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_r = __pyx_t_4; + __pyx_t_4 = 0; + goto __pyx_L0; + + /* "View.MemoryView":1087 + * + * @cname('__pyx_memoryview_copy_object_from_slice') + * cdef memoryview_copy_from_slice(memoryview memview, __Pyx_memviewslice *memviewslice): # <<<<<<<<<<<<<< + * """ + * Create a new memoryview object from a given memoryview object and slice. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.memoryview_copy_from_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1109 + * + * + * cdef Py_ssize_t abs_py_ssize_t(Py_ssize_t arg) noexcept nogil: # <<<<<<<<<<<<<< + * return -arg if arg < 0 else arg + * + */ + +static Py_ssize_t abs_py_ssize_t(Py_ssize_t __pyx_v_arg) { + Py_ssize_t __pyx_r; + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + + /* "View.MemoryView":1110 + * + * cdef Py_ssize_t abs_py_ssize_t(Py_ssize_t arg) noexcept nogil: + * return -arg if arg < 0 else arg # <<<<<<<<<<<<<< + * + * @cname('__pyx_get_best_slice_order') + */ + __pyx_t_2 = (__pyx_v_arg < 0); + if (__pyx_t_2) { + __pyx_t_1 = (-__pyx_v_arg); + } else { + __pyx_t_1 = __pyx_v_arg; + } + __pyx_r = __pyx_t_1; + goto __pyx_L0; + + /* "View.MemoryView":1109 + * + * + * cdef Py_ssize_t abs_py_ssize_t(Py_ssize_t arg) noexcept nogil: # <<<<<<<<<<<<<< + * return -arg if arg < 0 else arg + * + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1113 + * + * @cname('__pyx_get_best_slice_order') + * cdef char get_best_order(__Pyx_memviewslice *mslice, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * """ + * Figure out the best memory access order for a given slice. + */ + +static char __pyx_get_best_slice_order(__Pyx_memviewslice *__pyx_v_mslice, int __pyx_v_ndim) { + int __pyx_v_i; + Py_ssize_t __pyx_v_c_stride; + Py_ssize_t __pyx_v_f_stride; + char __pyx_r; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + + /* "View.MemoryView":1118 + * """ + * cdef int i + * cdef Py_ssize_t c_stride = 0 # <<<<<<<<<<<<<< + * cdef Py_ssize_t f_stride = 0 + * + */ + __pyx_v_c_stride = 0; + + /* "View.MemoryView":1119 + * cdef int i + * cdef Py_ssize_t c_stride = 0 + * cdef Py_ssize_t f_stride = 0 # <<<<<<<<<<<<<< + * + * for i in range(ndim - 1, -1, -1): + */ + __pyx_v_f_stride = 0; + + /* "View.MemoryView":1121 + * cdef Py_ssize_t f_stride = 0 + * + * for i in range(ndim - 1, -1, -1): # <<<<<<<<<<<<<< + * if mslice.shape[i] > 1: + * c_stride = mslice.strides[i] + */ + for (__pyx_t_1 = (__pyx_v_ndim - 1); __pyx_t_1 > -1; __pyx_t_1-=1) { + __pyx_v_i = __pyx_t_1; + + /* "View.MemoryView":1122 + * + * for i in range(ndim - 1, -1, -1): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * c_stride = mslice.strides[i] + * break + */ + __pyx_t_2 = ((__pyx_v_mslice->shape[__pyx_v_i]) > 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1123 + * for i in range(ndim - 1, -1, -1): + * if mslice.shape[i] > 1: + * c_stride = mslice.strides[i] # <<<<<<<<<<<<<< + * break + * + */ + __pyx_v_c_stride = (__pyx_v_mslice->strides[__pyx_v_i]); + + /* "View.MemoryView":1124 + * if mslice.shape[i] > 1: + * c_stride = mslice.strides[i] + * break # <<<<<<<<<<<<<< + * + * for i in range(ndim): + */ + goto __pyx_L4_break; + + /* "View.MemoryView":1122 + * + * for i in range(ndim - 1, -1, -1): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * c_stride = mslice.strides[i] + * break + */ + } + } + __pyx_L4_break:; + + /* "View.MemoryView":1126 + * break + * + * for i in range(ndim): # <<<<<<<<<<<<<< + * if mslice.shape[i] > 1: + * f_stride = mslice.strides[i] + */ + __pyx_t_1 = __pyx_v_ndim; + __pyx_t_3 = __pyx_t_1; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1127 + * + * for i in range(ndim): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * f_stride = mslice.strides[i] + * break + */ + __pyx_t_2 = ((__pyx_v_mslice->shape[__pyx_v_i]) > 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1128 + * for i in range(ndim): + * if mslice.shape[i] > 1: + * f_stride = mslice.strides[i] # <<<<<<<<<<<<<< + * break + * + */ + __pyx_v_f_stride = (__pyx_v_mslice->strides[__pyx_v_i]); + + /* "View.MemoryView":1129 + * if mslice.shape[i] > 1: + * f_stride = mslice.strides[i] + * break # <<<<<<<<<<<<<< + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): + */ + goto __pyx_L7_break; + + /* "View.MemoryView":1127 + * + * for i in range(ndim): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * f_stride = mslice.strides[i] + * break + */ + } + } + __pyx_L7_break:; + + /* "View.MemoryView":1131 + * break + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): # <<<<<<<<<<<<<< + * return 'C' + * else: + */ + __pyx_t_2 = (abs_py_ssize_t(__pyx_v_c_stride) <= abs_py_ssize_t(__pyx_v_f_stride)); + if (__pyx_t_2) { + + /* "View.MemoryView":1132 + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): + * return 'C' # <<<<<<<<<<<<<< + * else: + * return 'F' + */ + __pyx_r = 'C'; + goto __pyx_L0; + + /* "View.MemoryView":1131 + * break + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): # <<<<<<<<<<<<<< + * return 'C' + * else: + */ + } + + /* "View.MemoryView":1134 + * return 'C' + * else: + * return 'F' # <<<<<<<<<<<<<< + * + * @cython.cdivision(True) + */ + /*else*/ { + __pyx_r = 'F'; + goto __pyx_L0; + } + + /* "View.MemoryView":1113 + * + * @cname('__pyx_get_best_slice_order') + * cdef char get_best_order(__Pyx_memviewslice *mslice, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * """ + * Figure out the best memory access order for a given slice. + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1137 + * + * @cython.cdivision(True) + * cdef void _copy_strided_to_strided(char *src_data, Py_ssize_t *src_strides, # <<<<<<<<<<<<<< + * char *dst_data, Py_ssize_t *dst_strides, + * Py_ssize_t *src_shape, Py_ssize_t *dst_shape, + */ + +static void _copy_strided_to_strided(char *__pyx_v_src_data, Py_ssize_t *__pyx_v_src_strides, char *__pyx_v_dst_data, Py_ssize_t *__pyx_v_dst_strides, Py_ssize_t *__pyx_v_src_shape, Py_ssize_t *__pyx_v_dst_shape, int __pyx_v_ndim, size_t __pyx_v_itemsize) { + CYTHON_UNUSED Py_ssize_t __pyx_v_i; + CYTHON_UNUSED Py_ssize_t __pyx_v_src_extent; + Py_ssize_t __pyx_v_dst_extent; + Py_ssize_t __pyx_v_src_stride; + Py_ssize_t __pyx_v_dst_stride; + int __pyx_t_1; + int __pyx_t_2; + Py_ssize_t __pyx_t_3; + Py_ssize_t __pyx_t_4; + Py_ssize_t __pyx_t_5; + + /* "View.MemoryView":1144 + * + * cdef Py_ssize_t i + * cdef Py_ssize_t src_extent = src_shape[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t dst_extent = dst_shape[0] + * cdef Py_ssize_t src_stride = src_strides[0] + */ + __pyx_v_src_extent = (__pyx_v_src_shape[0]); + + /* "View.MemoryView":1145 + * cdef Py_ssize_t i + * cdef Py_ssize_t src_extent = src_shape[0] + * cdef Py_ssize_t dst_extent = dst_shape[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t src_stride = src_strides[0] + * cdef Py_ssize_t dst_stride = dst_strides[0] + */ + __pyx_v_dst_extent = (__pyx_v_dst_shape[0]); + + /* "View.MemoryView":1146 + * cdef Py_ssize_t src_extent = src_shape[0] + * cdef Py_ssize_t dst_extent = dst_shape[0] + * cdef Py_ssize_t src_stride = src_strides[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t dst_stride = dst_strides[0] + * + */ + __pyx_v_src_stride = (__pyx_v_src_strides[0]); + + /* "View.MemoryView":1147 + * cdef Py_ssize_t dst_extent = dst_shape[0] + * cdef Py_ssize_t src_stride = src_strides[0] + * cdef Py_ssize_t dst_stride = dst_strides[0] # <<<<<<<<<<<<<< + * + * if ndim == 1: + */ + __pyx_v_dst_stride = (__pyx_v_dst_strides[0]); + + /* "View.MemoryView":1149 + * cdef Py_ssize_t dst_stride = dst_strides[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): + */ + __pyx_t_1 = (__pyx_v_ndim == 1); + if (__pyx_t_1) { + + /* "View.MemoryView":1150 + * + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and # <<<<<<<<<<<<<< + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) + */ + __pyx_t_2 = (__pyx_v_src_stride > 0); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L5_bool_binop_done; + } + __pyx_t_2 = (__pyx_v_dst_stride > 0); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L5_bool_binop_done; + } + + /* "View.MemoryView":1151 + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): # <<<<<<<<<<<<<< + * memcpy(dst_data, src_data, itemsize * dst_extent) + * else: + */ + __pyx_t_2 = (((size_t)__pyx_v_src_stride) == __pyx_v_itemsize); + if (__pyx_t_2) { + __pyx_t_2 = (__pyx_v_itemsize == ((size_t)__pyx_v_dst_stride)); + } + __pyx_t_1 = __pyx_t_2; + __pyx_L5_bool_binop_done:; + + /* "View.MemoryView":1150 + * + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and # <<<<<<<<<<<<<< + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) + */ + if (__pyx_t_1) { + + /* "View.MemoryView":1152 + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) # <<<<<<<<<<<<<< + * else: + * for i in range(dst_extent): + */ + (void)(memcpy(__pyx_v_dst_data, __pyx_v_src_data, (__pyx_v_itemsize * __pyx_v_dst_extent))); + + /* "View.MemoryView":1150 + * + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and # <<<<<<<<<<<<<< + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) + */ + goto __pyx_L4; + } + + /* "View.MemoryView":1154 + * memcpy(dst_data, src_data, itemsize * dst_extent) + * else: + * for i in range(dst_extent): # <<<<<<<<<<<<<< + * memcpy(dst_data, src_data, itemsize) + * src_data += src_stride + */ + /*else*/ { + __pyx_t_3 = __pyx_v_dst_extent; + __pyx_t_4 = __pyx_t_3; + for (__pyx_t_5 = 0; __pyx_t_5 < __pyx_t_4; __pyx_t_5+=1) { + __pyx_v_i = __pyx_t_5; + + /* "View.MemoryView":1155 + * else: + * for i in range(dst_extent): + * memcpy(dst_data, src_data, itemsize) # <<<<<<<<<<<<<< + * src_data += src_stride + * dst_data += dst_stride + */ + (void)(memcpy(__pyx_v_dst_data, __pyx_v_src_data, __pyx_v_itemsize)); + + /* "View.MemoryView":1156 + * for i in range(dst_extent): + * memcpy(dst_data, src_data, itemsize) + * src_data += src_stride # <<<<<<<<<<<<<< + * dst_data += dst_stride + * else: + */ + __pyx_v_src_data = (__pyx_v_src_data + __pyx_v_src_stride); + + /* "View.MemoryView":1157 + * memcpy(dst_data, src_data, itemsize) + * src_data += src_stride + * dst_data += dst_stride # <<<<<<<<<<<<<< + * else: + * for i in range(dst_extent): + */ + __pyx_v_dst_data = (__pyx_v_dst_data + __pyx_v_dst_stride); + } + } + __pyx_L4:; + + /* "View.MemoryView":1149 + * cdef Py_ssize_t dst_stride = dst_strides[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1159 + * dst_data += dst_stride + * else: + * for i in range(dst_extent): # <<<<<<<<<<<<<< + * _copy_strided_to_strided(src_data, src_strides + 1, + * dst_data, dst_strides + 1, + */ + /*else*/ { + __pyx_t_3 = __pyx_v_dst_extent; + __pyx_t_4 = __pyx_t_3; + for (__pyx_t_5 = 0; __pyx_t_5 < __pyx_t_4; __pyx_t_5+=1) { + __pyx_v_i = __pyx_t_5; + + /* "View.MemoryView":1160 + * else: + * for i in range(dst_extent): + * _copy_strided_to_strided(src_data, src_strides + 1, # <<<<<<<<<<<<<< + * dst_data, dst_strides + 1, + * src_shape + 1, dst_shape + 1, + */ + _copy_strided_to_strided(__pyx_v_src_data, (__pyx_v_src_strides + 1), __pyx_v_dst_data, (__pyx_v_dst_strides + 1), (__pyx_v_src_shape + 1), (__pyx_v_dst_shape + 1), (__pyx_v_ndim - 1), __pyx_v_itemsize); + + /* "View.MemoryView":1164 + * src_shape + 1, dst_shape + 1, + * ndim - 1, itemsize) + * src_data += src_stride # <<<<<<<<<<<<<< + * dst_data += dst_stride + * + */ + __pyx_v_src_data = (__pyx_v_src_data + __pyx_v_src_stride); + + /* "View.MemoryView":1165 + * ndim - 1, itemsize) + * src_data += src_stride + * dst_data += dst_stride # <<<<<<<<<<<<<< + * + * cdef void copy_strided_to_strided(__Pyx_memviewslice *src, + */ + __pyx_v_dst_data = (__pyx_v_dst_data + __pyx_v_dst_stride); + } + } + __pyx_L3:; + + /* "View.MemoryView":1137 + * + * @cython.cdivision(True) + * cdef void _copy_strided_to_strided(char *src_data, Py_ssize_t *src_strides, # <<<<<<<<<<<<<< + * char *dst_data, Py_ssize_t *dst_strides, + * Py_ssize_t *src_shape, Py_ssize_t *dst_shape, + */ + + /* function exit code */ +} + +/* "View.MemoryView":1167 + * dst_data += dst_stride + * + * cdef void copy_strided_to_strided(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * int ndim, size_t itemsize) noexcept nogil: + */ + +static void copy_strided_to_strided(__Pyx_memviewslice *__pyx_v_src, __Pyx_memviewslice *__pyx_v_dst, int __pyx_v_ndim, size_t __pyx_v_itemsize) { + + /* "View.MemoryView":1170 + * __Pyx_memviewslice *dst, + * int ndim, size_t itemsize) noexcept nogil: + * _copy_strided_to_strided(src.data, src.strides, dst.data, dst.strides, # <<<<<<<<<<<<<< + * src.shape, dst.shape, ndim, itemsize) + * + */ + _copy_strided_to_strided(__pyx_v_src->data, __pyx_v_src->strides, __pyx_v_dst->data, __pyx_v_dst->strides, __pyx_v_src->shape, __pyx_v_dst->shape, __pyx_v_ndim, __pyx_v_itemsize); + + /* "View.MemoryView":1167 + * dst_data += dst_stride + * + * cdef void copy_strided_to_strided(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * int ndim, size_t itemsize) noexcept nogil: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1174 + * + * @cname('__pyx_memoryview_slice_get_size') + * cdef Py_ssize_t slice_get_size(__Pyx_memviewslice *src, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * "Return the size of the memory occupied by the slice in number of bytes" + * cdef Py_ssize_t shape, size = src.memview.view.itemsize + */ + +static Py_ssize_t __pyx_memoryview_slice_get_size(__Pyx_memviewslice *__pyx_v_src, int __pyx_v_ndim) { + Py_ssize_t __pyx_v_shape; + Py_ssize_t __pyx_v_size; + Py_ssize_t __pyx_r; + Py_ssize_t __pyx_t_1; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + + /* "View.MemoryView":1176 + * cdef Py_ssize_t slice_get_size(__Pyx_memviewslice *src, int ndim) noexcept nogil: + * "Return the size of the memory occupied by the slice in number of bytes" + * cdef Py_ssize_t shape, size = src.memview.view.itemsize # <<<<<<<<<<<<<< + * + * for shape in src.shape[:ndim]: + */ + __pyx_t_1 = __pyx_v_src->memview->view.itemsize; + __pyx_v_size = __pyx_t_1; + + /* "View.MemoryView":1178 + * cdef Py_ssize_t shape, size = src.memview.view.itemsize + * + * for shape in src.shape[:ndim]: # <<<<<<<<<<<<<< + * size *= shape + * + */ + __pyx_t_3 = (__pyx_v_src->shape + __pyx_v_ndim); + for (__pyx_t_4 = __pyx_v_src->shape; __pyx_t_4 < __pyx_t_3; __pyx_t_4++) { + __pyx_t_2 = __pyx_t_4; + __pyx_v_shape = (__pyx_t_2[0]); + + /* "View.MemoryView":1179 + * + * for shape in src.shape[:ndim]: + * size *= shape # <<<<<<<<<<<<<< + * + * return size + */ + __pyx_v_size = (__pyx_v_size * __pyx_v_shape); + } + + /* "View.MemoryView":1181 + * size *= shape + * + * return size # <<<<<<<<<<<<<< + * + * @cname('__pyx_fill_contig_strides_array') + */ + __pyx_r = __pyx_v_size; + goto __pyx_L0; + + /* "View.MemoryView":1174 + * + * @cname('__pyx_memoryview_slice_get_size') + * cdef Py_ssize_t slice_get_size(__Pyx_memviewslice *src, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * "Return the size of the memory occupied by the slice in number of bytes" + * cdef Py_ssize_t shape, size = src.memview.view.itemsize + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1184 + * + * @cname('__pyx_fill_contig_strides_array') + * cdef Py_ssize_t fill_contig_strides_array( # <<<<<<<<<<<<<< + * Py_ssize_t *shape, Py_ssize_t *strides, Py_ssize_t stride, + * int ndim, char order) noexcept nogil: + */ + +static Py_ssize_t __pyx_fill_contig_strides_array(Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, Py_ssize_t __pyx_v_stride, int __pyx_v_ndim, char __pyx_v_order) { + int __pyx_v_idx; + Py_ssize_t __pyx_r; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + + /* "View.MemoryView":1193 + * cdef int idx + * + * if order == 'F': # <<<<<<<<<<<<<< + * for idx in range(ndim): + * strides[idx] = stride + */ + __pyx_t_1 = (__pyx_v_order == 'F'); + if (__pyx_t_1) { + + /* "View.MemoryView":1194 + * + * if order == 'F': + * for idx in range(ndim): # <<<<<<<<<<<<<< + * strides[idx] = stride + * stride *= shape[idx] + */ + __pyx_t_2 = __pyx_v_ndim; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_idx = __pyx_t_4; + + /* "View.MemoryView":1195 + * if order == 'F': + * for idx in range(ndim): + * strides[idx] = stride # <<<<<<<<<<<<<< + * stride *= shape[idx] + * else: + */ + (__pyx_v_strides[__pyx_v_idx]) = __pyx_v_stride; + + /* "View.MemoryView":1196 + * for idx in range(ndim): + * strides[idx] = stride + * stride *= shape[idx] # <<<<<<<<<<<<<< + * else: + * for idx in range(ndim - 1, -1, -1): + */ + __pyx_v_stride = (__pyx_v_stride * (__pyx_v_shape[__pyx_v_idx])); + } + + /* "View.MemoryView":1193 + * cdef int idx + * + * if order == 'F': # <<<<<<<<<<<<<< + * for idx in range(ndim): + * strides[idx] = stride + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1198 + * stride *= shape[idx] + * else: + * for idx in range(ndim - 1, -1, -1): # <<<<<<<<<<<<<< + * strides[idx] = stride + * stride *= shape[idx] + */ + /*else*/ { + for (__pyx_t_2 = (__pyx_v_ndim - 1); __pyx_t_2 > -1; __pyx_t_2-=1) { + __pyx_v_idx = __pyx_t_2; + + /* "View.MemoryView":1199 + * else: + * for idx in range(ndim - 1, -1, -1): + * strides[idx] = stride # <<<<<<<<<<<<<< + * stride *= shape[idx] + * + */ + (__pyx_v_strides[__pyx_v_idx]) = __pyx_v_stride; + + /* "View.MemoryView":1200 + * for idx in range(ndim - 1, -1, -1): + * strides[idx] = stride + * stride *= shape[idx] # <<<<<<<<<<<<<< + * + * return stride + */ + __pyx_v_stride = (__pyx_v_stride * (__pyx_v_shape[__pyx_v_idx])); + } + } + __pyx_L3:; + + /* "View.MemoryView":1202 + * stride *= shape[idx] + * + * return stride # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_copy_data_to_temp') + */ + __pyx_r = __pyx_v_stride; + goto __pyx_L0; + + /* "View.MemoryView":1184 + * + * @cname('__pyx_fill_contig_strides_array') + * cdef Py_ssize_t fill_contig_strides_array( # <<<<<<<<<<<<<< + * Py_ssize_t *shape, Py_ssize_t *strides, Py_ssize_t stride, + * int ndim, char order) noexcept nogil: + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1205 + * + * @cname('__pyx_memoryview_copy_data_to_temp') + * cdef void *copy_data_to_temp(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *tmpslice, + * char order, + */ + +static void *__pyx_memoryview_copy_data_to_temp(__Pyx_memviewslice *__pyx_v_src, __Pyx_memviewslice *__pyx_v_tmpslice, char __pyx_v_order, int __pyx_v_ndim) { + int __pyx_v_i; + void *__pyx_v_result; + size_t __pyx_v_itemsize; + size_t __pyx_v_size; + void *__pyx_r; + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + struct __pyx_memoryview_obj *__pyx_t_4; + int __pyx_t_5; + int __pyx_t_6; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":1216 + * cdef void *result + * + * cdef size_t itemsize = src.memview.view.itemsize # <<<<<<<<<<<<<< + * cdef size_t size = slice_get_size(src, ndim) + * + */ + __pyx_t_1 = __pyx_v_src->memview->view.itemsize; + __pyx_v_itemsize = __pyx_t_1; + + /* "View.MemoryView":1217 + * + * cdef size_t itemsize = src.memview.view.itemsize + * cdef size_t size = slice_get_size(src, ndim) # <<<<<<<<<<<<<< + * + * result = malloc(size) + */ + __pyx_v_size = __pyx_memoryview_slice_get_size(__pyx_v_src, __pyx_v_ndim); + + /* "View.MemoryView":1219 + * cdef size_t size = slice_get_size(src, ndim) + * + * result = malloc(size) # <<<<<<<<<<<<<< + * if not result: + * _err_no_memory() + */ + __pyx_v_result = malloc(__pyx_v_size); + + /* "View.MemoryView":1220 + * + * result = malloc(size) + * if not result: # <<<<<<<<<<<<<< + * _err_no_memory() + * + */ + __pyx_t_2 = (!(__pyx_v_result != 0)); + if (__pyx_t_2) { + + /* "View.MemoryView":1221 + * result = malloc(size) + * if not result: + * _err_no_memory() # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_3 = __pyx_memoryview_err_no_memory(); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 1221, __pyx_L1_error) + + /* "View.MemoryView":1220 + * + * result = malloc(size) + * if not result: # <<<<<<<<<<<<<< + * _err_no_memory() + * + */ + } + + /* "View.MemoryView":1224 + * + * + * tmpslice.data = result # <<<<<<<<<<<<<< + * tmpslice.memview = src.memview + * for i in range(ndim): + */ + __pyx_v_tmpslice->data = ((char *)__pyx_v_result); + + /* "View.MemoryView":1225 + * + * tmpslice.data = result + * tmpslice.memview = src.memview # <<<<<<<<<<<<<< + * for i in range(ndim): + * tmpslice.shape[i] = src.shape[i] + */ + __pyx_t_4 = __pyx_v_src->memview; + __pyx_v_tmpslice->memview = __pyx_t_4; + + /* "View.MemoryView":1226 + * tmpslice.data = result + * tmpslice.memview = src.memview + * for i in range(ndim): # <<<<<<<<<<<<<< + * tmpslice.shape[i] = src.shape[i] + * tmpslice.suboffsets[i] = -1 + */ + __pyx_t_3 = __pyx_v_ndim; + __pyx_t_5 = __pyx_t_3; + for (__pyx_t_6 = 0; __pyx_t_6 < __pyx_t_5; __pyx_t_6+=1) { + __pyx_v_i = __pyx_t_6; + + /* "View.MemoryView":1227 + * tmpslice.memview = src.memview + * for i in range(ndim): + * tmpslice.shape[i] = src.shape[i] # <<<<<<<<<<<<<< + * tmpslice.suboffsets[i] = -1 + * + */ + (__pyx_v_tmpslice->shape[__pyx_v_i]) = (__pyx_v_src->shape[__pyx_v_i]); + + /* "View.MemoryView":1228 + * for i in range(ndim): + * tmpslice.shape[i] = src.shape[i] + * tmpslice.suboffsets[i] = -1 # <<<<<<<<<<<<<< + * + * fill_contig_strides_array(&tmpslice.shape[0], &tmpslice.strides[0], itemsize, ndim, order) + */ + (__pyx_v_tmpslice->suboffsets[__pyx_v_i]) = -1L; + } + + /* "View.MemoryView":1230 + * tmpslice.suboffsets[i] = -1 + * + * fill_contig_strides_array(&tmpslice.shape[0], &tmpslice.strides[0], itemsize, ndim, order) # <<<<<<<<<<<<<< + * + * + */ + (void)(__pyx_fill_contig_strides_array((&(__pyx_v_tmpslice->shape[0])), (&(__pyx_v_tmpslice->strides[0])), __pyx_v_itemsize, __pyx_v_ndim, __pyx_v_order)); + + /* "View.MemoryView":1233 + * + * + * for i in range(ndim): # <<<<<<<<<<<<<< + * if tmpslice.shape[i] == 1: + * tmpslice.strides[i] = 0 + */ + __pyx_t_3 = __pyx_v_ndim; + __pyx_t_5 = __pyx_t_3; + for (__pyx_t_6 = 0; __pyx_t_6 < __pyx_t_5; __pyx_t_6+=1) { + __pyx_v_i = __pyx_t_6; + + /* "View.MemoryView":1234 + * + * for i in range(ndim): + * if tmpslice.shape[i] == 1: # <<<<<<<<<<<<<< + * tmpslice.strides[i] = 0 + * + */ + __pyx_t_2 = ((__pyx_v_tmpslice->shape[__pyx_v_i]) == 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1235 + * for i in range(ndim): + * if tmpslice.shape[i] == 1: + * tmpslice.strides[i] = 0 # <<<<<<<<<<<<<< + * + * if slice_is_contig(src[0], order, ndim): + */ + (__pyx_v_tmpslice->strides[__pyx_v_i]) = 0; + + /* "View.MemoryView":1234 + * + * for i in range(ndim): + * if tmpslice.shape[i] == 1: # <<<<<<<<<<<<<< + * tmpslice.strides[i] = 0 + * + */ + } + } + + /* "View.MemoryView":1237 + * tmpslice.strides[i] = 0 + * + * if slice_is_contig(src[0], order, ndim): # <<<<<<<<<<<<<< + * memcpy(result, src.data, size) + * else: + */ + __pyx_t_2 = __pyx_memviewslice_is_contig((__pyx_v_src[0]), __pyx_v_order, __pyx_v_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1238 + * + * if slice_is_contig(src[0], order, ndim): + * memcpy(result, src.data, size) # <<<<<<<<<<<<<< + * else: + * copy_strided_to_strided(src, tmpslice, ndim, itemsize) + */ + (void)(memcpy(__pyx_v_result, __pyx_v_src->data, __pyx_v_size)); + + /* "View.MemoryView":1237 + * tmpslice.strides[i] = 0 + * + * if slice_is_contig(src[0], order, ndim): # <<<<<<<<<<<<<< + * memcpy(result, src.data, size) + * else: + */ + goto __pyx_L9; + } + + /* "View.MemoryView":1240 + * memcpy(result, src.data, size) + * else: + * copy_strided_to_strided(src, tmpslice, ndim, itemsize) # <<<<<<<<<<<<<< + * + * return result + */ + /*else*/ { + copy_strided_to_strided(__pyx_v_src, __pyx_v_tmpslice, __pyx_v_ndim, __pyx_v_itemsize); + } + __pyx_L9:; + + /* "View.MemoryView":1242 + * copy_strided_to_strided(src, tmpslice, ndim, itemsize) + * + * return result # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = __pyx_v_result; + goto __pyx_L0; + + /* "View.MemoryView":1205 + * + * @cname('__pyx_memoryview_copy_data_to_temp') + * cdef void *copy_data_to_temp(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *tmpslice, + * char order, + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.copy_data_to_temp", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1247 + * + * @cname('__pyx_memoryview_err_extents') + * cdef int _err_extents(int i, Py_ssize_t extent1, # <<<<<<<<<<<<<< + * Py_ssize_t extent2) except -1 with gil: + * raise ValueError, f"got differing extents in dimension {i} (got {extent1} and {extent2})" + */ + +static int __pyx_memoryview_err_extents(int __pyx_v_i, Py_ssize_t __pyx_v_extent1, Py_ssize_t __pyx_v_extent2) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + Py_ssize_t __pyx_t_2; + Py_UCS4 __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_RefNannySetupContext("_err_extents", 0); + + /* "View.MemoryView":1249 + * cdef int _err_extents(int i, Py_ssize_t extent1, + * Py_ssize_t extent2) except -1 with gil: + * raise ValueError, f"got differing extents in dimension {i} (got {extent1} and {extent2})" # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_err_dim') + */ + __pyx_t_1 = PyTuple_New(7); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = 0; + __pyx_t_3 = 127; + __Pyx_INCREF(__pyx_kp_u_got_differing_extents_in_dimensi); + __pyx_t_2 += 35; + __Pyx_GIVEREF(__pyx_kp_u_got_differing_extents_in_dimensi); + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_kp_u_got_differing_extents_in_dimensi); + __pyx_t_4 = __Pyx_PyUnicode_From_int(__pyx_v_i, 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_2 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_t_4); + __pyx_t_4 = 0; + __Pyx_INCREF(__pyx_kp_u_got); + __pyx_t_2 += 6; + __Pyx_GIVEREF(__pyx_kp_u_got); + PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_kp_u_got); + __pyx_t_4 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_extent1, 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_2 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_1, 3, __pyx_t_4); + __pyx_t_4 = 0; + __Pyx_INCREF(__pyx_kp_u_and); + __pyx_t_2 += 5; + __Pyx_GIVEREF(__pyx_kp_u_and); + PyTuple_SET_ITEM(__pyx_t_1, 4, __pyx_kp_u_and); + __pyx_t_4 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_extent2, 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_2 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_1, 5, __pyx_t_4); + __pyx_t_4 = 0; + __Pyx_INCREF(__pyx_kp_u__9); + __pyx_t_2 += 1; + __Pyx_GIVEREF(__pyx_kp_u__9); + PyTuple_SET_ITEM(__pyx_t_1, 6, __pyx_kp_u__9); + __pyx_t_4 = __Pyx_PyUnicode_Join(__pyx_t_1, 7, __pyx_t_2, __pyx_t_3); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_t_4, 0, 0); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __PYX_ERR(1, 1249, __pyx_L1_error) + + /* "View.MemoryView":1247 + * + * @cname('__pyx_memoryview_err_extents') + * cdef int _err_extents(int i, Py_ssize_t extent1, # <<<<<<<<<<<<<< + * Py_ssize_t extent2) except -1 with gil: + * raise ValueError, f"got differing extents in dimension {i} (got {extent1} and {extent2})" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView._err_extents", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __Pyx_RefNannyFinishContext(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1252 + * + * @cname('__pyx_memoryview_err_dim') + * cdef int _err_dim(PyObject *error, str msg, int dim) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg % dim + * + */ + +static int __pyx_memoryview_err_dim(PyObject *__pyx_v_error, PyObject *__pyx_v_msg, int __pyx_v_dim) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_RefNannySetupContext("_err_dim", 0); + __Pyx_INCREF(__pyx_v_msg); + + /* "View.MemoryView":1253 + * @cname('__pyx_memoryview_err_dim') + * cdef int _err_dim(PyObject *error, str msg, int dim) except -1 with gil: + * raise error, msg % dim # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_err') + */ + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_dim); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 1253, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyString_FormatSafe(__pyx_v_msg, __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1253, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(((PyObject *)__pyx_v_error), __pyx_t_2, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(1, 1253, __pyx_L1_error) + + /* "View.MemoryView":1252 + * + * @cname('__pyx_memoryview_err_dim') + * cdef int _err_dim(PyObject *error, str msg, int dim) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg % dim + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView._err_dim", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __Pyx_XDECREF(__pyx_v_msg); + __Pyx_RefNannyFinishContext(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1256 + * + * @cname('__pyx_memoryview_err') + * cdef int _err(PyObject *error, str msg) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg + * + */ + +static int __pyx_memoryview_err(PyObject *__pyx_v_error, PyObject *__pyx_v_msg) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_RefNannySetupContext("_err", 0); + __Pyx_INCREF(__pyx_v_msg); + + /* "View.MemoryView":1257 + * @cname('__pyx_memoryview_err') + * cdef int _err(PyObject *error, str msg) except -1 with gil: + * raise error, msg # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_err_no_memory') + */ + __Pyx_Raise(((PyObject *)__pyx_v_error), __pyx_v_msg, 0, 0); + __PYX_ERR(1, 1257, __pyx_L1_error) + + /* "View.MemoryView":1256 + * + * @cname('__pyx_memoryview_err') + * cdef int _err(PyObject *error, str msg) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._err", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __Pyx_XDECREF(__pyx_v_msg); + __Pyx_RefNannyFinishContext(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1260 + * + * @cname('__pyx_memoryview_err_no_memory') + * cdef int _err_no_memory() except -1 with gil: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + +static int __pyx_memoryview_err_no_memory(void) { + int __pyx_r; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + + /* "View.MemoryView":1261 + * @cname('__pyx_memoryview_err_no_memory') + * cdef int _err_no_memory() except -1 with gil: + * raise MemoryError # <<<<<<<<<<<<<< + * + * + */ + PyErr_NoMemory(); __PYX_ERR(1, 1261, __pyx_L1_error) + + /* "View.MemoryView":1260 + * + * @cname('__pyx_memoryview_err_no_memory') + * cdef int _err_no_memory() except -1 with gil: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._err_no_memory", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1265 + * + * @cname('__pyx_memoryview_copy_contents') + * cdef int memoryview_copy_contents(__Pyx_memviewslice src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice dst, + * int src_ndim, int dst_ndim, + */ + +static int __pyx_memoryview_copy_contents(__Pyx_memviewslice __pyx_v_src, __Pyx_memviewslice __pyx_v_dst, int __pyx_v_src_ndim, int __pyx_v_dst_ndim, int __pyx_v_dtype_is_object) { + void *__pyx_v_tmpdata; + size_t __pyx_v_itemsize; + int __pyx_v_i; + char __pyx_v_order; + int __pyx_v_broadcasting; + int __pyx_v_direct_copy; + __Pyx_memviewslice __pyx_v_tmp; + int __pyx_v_ndim; + int __pyx_r; + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + int __pyx_t_5; + int __pyx_t_6; + void *__pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":1273 + * Check for overlapping memory and verify the shapes. + * """ + * cdef void *tmpdata = NULL # <<<<<<<<<<<<<< + * cdef size_t itemsize = src.memview.view.itemsize + * cdef int i + */ + __pyx_v_tmpdata = NULL; + + /* "View.MemoryView":1274 + * """ + * cdef void *tmpdata = NULL + * cdef size_t itemsize = src.memview.view.itemsize # <<<<<<<<<<<<<< + * cdef int i + * cdef char order = get_best_order(&src, src_ndim) + */ + __pyx_t_1 = __pyx_v_src.memview->view.itemsize; + __pyx_v_itemsize = __pyx_t_1; + + /* "View.MemoryView":1276 + * cdef size_t itemsize = src.memview.view.itemsize + * cdef int i + * cdef char order = get_best_order(&src, src_ndim) # <<<<<<<<<<<<<< + * cdef bint broadcasting = False + * cdef bint direct_copy = False + */ + __pyx_v_order = __pyx_get_best_slice_order((&__pyx_v_src), __pyx_v_src_ndim); + + /* "View.MemoryView":1277 + * cdef int i + * cdef char order = get_best_order(&src, src_ndim) + * cdef bint broadcasting = False # <<<<<<<<<<<<<< + * cdef bint direct_copy = False + * cdef __Pyx_memviewslice tmp + */ + __pyx_v_broadcasting = 0; + + /* "View.MemoryView":1278 + * cdef char order = get_best_order(&src, src_ndim) + * cdef bint broadcasting = False + * cdef bint direct_copy = False # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice tmp + * + */ + __pyx_v_direct_copy = 0; + + /* "View.MemoryView":1281 + * cdef __Pyx_memviewslice tmp + * + * if src_ndim < dst_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: + */ + __pyx_t_2 = (__pyx_v_src_ndim < __pyx_v_dst_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1282 + * + * if src_ndim < dst_ndim: + * broadcast_leading(&src, src_ndim, dst_ndim) # <<<<<<<<<<<<<< + * elif dst_ndim < src_ndim: + * broadcast_leading(&dst, dst_ndim, src_ndim) + */ + __pyx_memoryview_broadcast_leading((&__pyx_v_src), __pyx_v_src_ndim, __pyx_v_dst_ndim); + + /* "View.MemoryView":1281 + * cdef __Pyx_memviewslice tmp + * + * if src_ndim < dst_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1283 + * if src_ndim < dst_ndim: + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&dst, dst_ndim, src_ndim) + * + */ + __pyx_t_2 = (__pyx_v_dst_ndim < __pyx_v_src_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1284 + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: + * broadcast_leading(&dst, dst_ndim, src_ndim) # <<<<<<<<<<<<<< + * + * cdef int ndim = max(src_ndim, dst_ndim) + */ + __pyx_memoryview_broadcast_leading((&__pyx_v_dst), __pyx_v_dst_ndim, __pyx_v_src_ndim); + + /* "View.MemoryView":1283 + * if src_ndim < dst_ndim: + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&dst, dst_ndim, src_ndim) + * + */ + } + __pyx_L3:; + + /* "View.MemoryView":1286 + * broadcast_leading(&dst, dst_ndim, src_ndim) + * + * cdef int ndim = max(src_ndim, dst_ndim) # <<<<<<<<<<<<<< + * + * for i in range(ndim): + */ + __pyx_t_3 = __pyx_v_dst_ndim; + __pyx_t_4 = __pyx_v_src_ndim; + __pyx_t_2 = (__pyx_t_3 > __pyx_t_4); + if (__pyx_t_2) { + __pyx_t_5 = __pyx_t_3; + } else { + __pyx_t_5 = __pyx_t_4; + } + __pyx_v_ndim = __pyx_t_5; + + /* "View.MemoryView":1288 + * cdef int ndim = max(src_ndim, dst_ndim) + * + * for i in range(ndim): # <<<<<<<<<<<<<< + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: + */ + __pyx_t_5 = __pyx_v_ndim; + __pyx_t_3 = __pyx_t_5; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1289 + * + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: # <<<<<<<<<<<<<< + * if src.shape[i] == 1: + * broadcasting = True + */ + __pyx_t_2 = ((__pyx_v_src.shape[__pyx_v_i]) != (__pyx_v_dst.shape[__pyx_v_i])); + if (__pyx_t_2) { + + /* "View.MemoryView":1290 + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: # <<<<<<<<<<<<<< + * broadcasting = True + * src.strides[i] = 0 + */ + __pyx_t_2 = ((__pyx_v_src.shape[__pyx_v_i]) == 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1291 + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: + * broadcasting = True # <<<<<<<<<<<<<< + * src.strides[i] = 0 + * else: + */ + __pyx_v_broadcasting = 1; + + /* "View.MemoryView":1292 + * if src.shape[i] == 1: + * broadcasting = True + * src.strides[i] = 0 # <<<<<<<<<<<<<< + * else: + * _err_extents(i, dst.shape[i], src.shape[i]) + */ + (__pyx_v_src.strides[__pyx_v_i]) = 0; + + /* "View.MemoryView":1290 + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: # <<<<<<<<<<<<<< + * broadcasting = True + * src.strides[i] = 0 + */ + goto __pyx_L7; + } + + /* "View.MemoryView":1294 + * src.strides[i] = 0 + * else: + * _err_extents(i, dst.shape[i], src.shape[i]) # <<<<<<<<<<<<<< + * + * if src.suboffsets[i] >= 0: + */ + /*else*/ { + __pyx_t_6 = __pyx_memoryview_err_extents(__pyx_v_i, (__pyx_v_dst.shape[__pyx_v_i]), (__pyx_v_src.shape[__pyx_v_i])); if (unlikely(__pyx_t_6 == ((int)-1))) __PYX_ERR(1, 1294, __pyx_L1_error) + } + __pyx_L7:; + + /* "View.MemoryView":1289 + * + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: # <<<<<<<<<<<<<< + * if src.shape[i] == 1: + * broadcasting = True + */ + } + + /* "View.MemoryView":1296 + * _err_extents(i, dst.shape[i], src.shape[i]) + * + * if src.suboffsets[i] >= 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + */ + __pyx_t_2 = ((__pyx_v_src.suboffsets[__pyx_v_i]) >= 0); + if (__pyx_t_2) { + + /* "View.MemoryView":1297 + * + * if src.suboffsets[i] >= 0: + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) # <<<<<<<<<<<<<< + * + * if slices_overlap(&src, &dst, ndim, itemsize): + */ + __pyx_t_6 = __pyx_memoryview_err_dim(PyExc_ValueError, __pyx_kp_s_Dimension_d_is_not_direct, __pyx_v_i); if (unlikely(__pyx_t_6 == ((int)-1))) __PYX_ERR(1, 1297, __pyx_L1_error) + + /* "View.MemoryView":1296 + * _err_extents(i, dst.shape[i], src.shape[i]) + * + * if src.suboffsets[i] >= 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + */ + } + } + + /* "View.MemoryView":1299 + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + * if slices_overlap(&src, &dst, ndim, itemsize): # <<<<<<<<<<<<<< + * + * if not slice_is_contig(src, order, ndim): + */ + __pyx_t_2 = __pyx_slices_overlap((&__pyx_v_src), (&__pyx_v_dst), __pyx_v_ndim, __pyx_v_itemsize); + if (__pyx_t_2) { + + /* "View.MemoryView":1301 + * if slices_overlap(&src, &dst, ndim, itemsize): + * + * if not slice_is_contig(src, order, ndim): # <<<<<<<<<<<<<< + * order = get_best_order(&dst, ndim) + * + */ + __pyx_t_2 = (!__pyx_memviewslice_is_contig(__pyx_v_src, __pyx_v_order, __pyx_v_ndim)); + if (__pyx_t_2) { + + /* "View.MemoryView":1302 + * + * if not slice_is_contig(src, order, ndim): + * order = get_best_order(&dst, ndim) # <<<<<<<<<<<<<< + * + * tmpdata = copy_data_to_temp(&src, &tmp, order, ndim) + */ + __pyx_v_order = __pyx_get_best_slice_order((&__pyx_v_dst), __pyx_v_ndim); + + /* "View.MemoryView":1301 + * if slices_overlap(&src, &dst, ndim, itemsize): + * + * if not slice_is_contig(src, order, ndim): # <<<<<<<<<<<<<< + * order = get_best_order(&dst, ndim) + * + */ + } + + /* "View.MemoryView":1304 + * order = get_best_order(&dst, ndim) + * + * tmpdata = copy_data_to_temp(&src, &tmp, order, ndim) # <<<<<<<<<<<<<< + * src = tmp + * + */ + __pyx_t_7 = __pyx_memoryview_copy_data_to_temp((&__pyx_v_src), (&__pyx_v_tmp), __pyx_v_order, __pyx_v_ndim); if (unlikely(__pyx_t_7 == ((void *)NULL))) __PYX_ERR(1, 1304, __pyx_L1_error) + __pyx_v_tmpdata = __pyx_t_7; + + /* "View.MemoryView":1305 + * + * tmpdata = copy_data_to_temp(&src, &tmp, order, ndim) + * src = tmp # <<<<<<<<<<<<<< + * + * if not broadcasting: + */ + __pyx_v_src = __pyx_v_tmp; + + /* "View.MemoryView":1299 + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + * if slices_overlap(&src, &dst, ndim, itemsize): # <<<<<<<<<<<<<< + * + * if not slice_is_contig(src, order, ndim): + */ + } + + /* "View.MemoryView":1307 + * src = tmp + * + * if not broadcasting: # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = (!__pyx_v_broadcasting); + if (__pyx_t_2) { + + /* "View.MemoryView":1310 + * + * + * if slice_is_contig(src, 'C', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): + */ + __pyx_t_2 = __pyx_memviewslice_is_contig(__pyx_v_src, 'C', __pyx_v_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1311 + * + * if slice_is_contig(src, 'C', ndim): + * direct_copy = slice_is_contig(dst, 'C', ndim) # <<<<<<<<<<<<<< + * elif slice_is_contig(src, 'F', ndim): + * direct_copy = slice_is_contig(dst, 'F', ndim) + */ + __pyx_v_direct_copy = __pyx_memviewslice_is_contig(__pyx_v_dst, 'C', __pyx_v_ndim); + + /* "View.MemoryView":1310 + * + * + * if slice_is_contig(src, 'C', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): + */ + goto __pyx_L12; + } + + /* "View.MemoryView":1312 + * if slice_is_contig(src, 'C', ndim): + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + */ + __pyx_t_2 = __pyx_memviewslice_is_contig(__pyx_v_src, 'F', __pyx_v_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1313 + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): + * direct_copy = slice_is_contig(dst, 'F', ndim) # <<<<<<<<<<<<<< + * + * if direct_copy: + */ + __pyx_v_direct_copy = __pyx_memviewslice_is_contig(__pyx_v_dst, 'F', __pyx_v_ndim); + + /* "View.MemoryView":1312 + * if slice_is_contig(src, 'C', ndim): + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + */ + } + __pyx_L12:; + + /* "View.MemoryView":1315 + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + * if direct_copy: # <<<<<<<<<<<<<< + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + */ + if (__pyx_v_direct_copy) { + + /* "View.MemoryView":1317 + * if direct_copy: + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) # <<<<<<<<<<<<<< + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 0); + + /* "View.MemoryView":1318 + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) # <<<<<<<<<<<<<< + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * free(tmpdata) + */ + (void)(memcpy(__pyx_v_dst.data, __pyx_v_src.data, __pyx_memoryview_slice_get_size((&__pyx_v_src), __pyx_v_ndim))); + + /* "View.MemoryView":1319 + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) # <<<<<<<<<<<<<< + * free(tmpdata) + * return 0 + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 1); + + /* "View.MemoryView":1320 + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * free(tmpdata) # <<<<<<<<<<<<<< + * return 0 + * + */ + free(__pyx_v_tmpdata); + + /* "View.MemoryView":1321 + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * free(tmpdata) + * return 0 # <<<<<<<<<<<<<< + * + * if order == 'F' == get_best_order(&dst, ndim): + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":1315 + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + * if direct_copy: # <<<<<<<<<<<<<< + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + */ + } + + /* "View.MemoryView":1307 + * src = tmp + * + * if not broadcasting: # <<<<<<<<<<<<<< + * + * + */ + } + + /* "View.MemoryView":1323 + * return 0 + * + * if order == 'F' == get_best_order(&dst, ndim): # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = (__pyx_v_order == 'F'); + if (__pyx_t_2) { + __pyx_t_2 = ('F' == __pyx_get_best_slice_order((&__pyx_v_dst), __pyx_v_ndim)); + } + if (__pyx_t_2) { + + /* "View.MemoryView":1326 + * + * + * transpose_memslice(&src) # <<<<<<<<<<<<<< + * transpose_memslice(&dst) + * + */ + __pyx_t_5 = __pyx_memslice_transpose((&__pyx_v_src)); if (unlikely(__pyx_t_5 == ((int)-1))) __PYX_ERR(1, 1326, __pyx_L1_error) + + /* "View.MemoryView":1327 + * + * transpose_memslice(&src) + * transpose_memslice(&dst) # <<<<<<<<<<<<<< + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + */ + __pyx_t_5 = __pyx_memslice_transpose((&__pyx_v_dst)); if (unlikely(__pyx_t_5 == ((int)-1))) __PYX_ERR(1, 1327, __pyx_L1_error) + + /* "View.MemoryView":1323 + * return 0 + * + * if order == 'F' == get_best_order(&dst, ndim): # <<<<<<<<<<<<<< + * + * + */ + } + + /* "View.MemoryView":1329 + * transpose_memslice(&dst) + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) # <<<<<<<<<<<<<< + * copy_strided_to_strided(&src, &dst, ndim, itemsize) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 0); + + /* "View.MemoryView":1330 + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * copy_strided_to_strided(&src, &dst, ndim, itemsize) # <<<<<<<<<<<<<< + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * + */ + copy_strided_to_strided((&__pyx_v_src), (&__pyx_v_dst), __pyx_v_ndim, __pyx_v_itemsize); + + /* "View.MemoryView":1331 + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * copy_strided_to_strided(&src, &dst, ndim, itemsize) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) # <<<<<<<<<<<<<< + * + * free(tmpdata) + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 1); + + /* "View.MemoryView":1333 + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * + * free(tmpdata) # <<<<<<<<<<<<<< + * return 0 + * + */ + free(__pyx_v_tmpdata); + + /* "View.MemoryView":1334 + * + * free(tmpdata) + * return 0 # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_broadcast_leading') + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":1265 + * + * @cname('__pyx_memoryview_copy_contents') + * cdef int memoryview_copy_contents(__Pyx_memviewslice src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice dst, + * int src_ndim, int dst_ndim, + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.memoryview_copy_contents", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1337 + * + * @cname('__pyx_memoryview_broadcast_leading') + * cdef void broadcast_leading(__Pyx_memviewslice *mslice, # <<<<<<<<<<<<<< + * int ndim, + * int ndim_other) noexcept nogil: + */ + +static void __pyx_memoryview_broadcast_leading(__Pyx_memviewslice *__pyx_v_mslice, int __pyx_v_ndim, int __pyx_v_ndim_other) { + int __pyx_v_i; + int __pyx_v_offset; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + + /* "View.MemoryView":1341 + * int ndim_other) noexcept nogil: + * cdef int i + * cdef int offset = ndim_other - ndim # <<<<<<<<<<<<<< + * + * for i in range(ndim - 1, -1, -1): + */ + __pyx_v_offset = (__pyx_v_ndim_other - __pyx_v_ndim); + + /* "View.MemoryView":1343 + * cdef int offset = ndim_other - ndim + * + * for i in range(ndim - 1, -1, -1): # <<<<<<<<<<<<<< + * mslice.shape[i + offset] = mslice.shape[i] + * mslice.strides[i + offset] = mslice.strides[i] + */ + for (__pyx_t_1 = (__pyx_v_ndim - 1); __pyx_t_1 > -1; __pyx_t_1-=1) { + __pyx_v_i = __pyx_t_1; + + /* "View.MemoryView":1344 + * + * for i in range(ndim - 1, -1, -1): + * mslice.shape[i + offset] = mslice.shape[i] # <<<<<<<<<<<<<< + * mslice.strides[i + offset] = mslice.strides[i] + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] + */ + (__pyx_v_mslice->shape[(__pyx_v_i + __pyx_v_offset)]) = (__pyx_v_mslice->shape[__pyx_v_i]); + + /* "View.MemoryView":1345 + * for i in range(ndim - 1, -1, -1): + * mslice.shape[i + offset] = mslice.shape[i] + * mslice.strides[i + offset] = mslice.strides[i] # <<<<<<<<<<<<<< + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] + * + */ + (__pyx_v_mslice->strides[(__pyx_v_i + __pyx_v_offset)]) = (__pyx_v_mslice->strides[__pyx_v_i]); + + /* "View.MemoryView":1346 + * mslice.shape[i + offset] = mslice.shape[i] + * mslice.strides[i + offset] = mslice.strides[i] + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] # <<<<<<<<<<<<<< + * + * for i in range(offset): + */ + (__pyx_v_mslice->suboffsets[(__pyx_v_i + __pyx_v_offset)]) = (__pyx_v_mslice->suboffsets[__pyx_v_i]); + } + + /* "View.MemoryView":1348 + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] + * + * for i in range(offset): # <<<<<<<<<<<<<< + * mslice.shape[i] = 1 + * mslice.strides[i] = mslice.strides[0] + */ + __pyx_t_1 = __pyx_v_offset; + __pyx_t_2 = __pyx_t_1; + for (__pyx_t_3 = 0; __pyx_t_3 < __pyx_t_2; __pyx_t_3+=1) { + __pyx_v_i = __pyx_t_3; + + /* "View.MemoryView":1349 + * + * for i in range(offset): + * mslice.shape[i] = 1 # <<<<<<<<<<<<<< + * mslice.strides[i] = mslice.strides[0] + * mslice.suboffsets[i] = -1 + */ + (__pyx_v_mslice->shape[__pyx_v_i]) = 1; + + /* "View.MemoryView":1350 + * for i in range(offset): + * mslice.shape[i] = 1 + * mslice.strides[i] = mslice.strides[0] # <<<<<<<<<<<<<< + * mslice.suboffsets[i] = -1 + * + */ + (__pyx_v_mslice->strides[__pyx_v_i]) = (__pyx_v_mslice->strides[0]); + + /* "View.MemoryView":1351 + * mslice.shape[i] = 1 + * mslice.strides[i] = mslice.strides[0] + * mslice.suboffsets[i] = -1 # <<<<<<<<<<<<<< + * + * + */ + (__pyx_v_mslice->suboffsets[__pyx_v_i]) = -1L; + } + + /* "View.MemoryView":1337 + * + * @cname('__pyx_memoryview_broadcast_leading') + * cdef void broadcast_leading(__Pyx_memviewslice *mslice, # <<<<<<<<<<<<<< + * int ndim, + * int ndim_other) noexcept nogil: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1359 + * + * @cname('__pyx_memoryview_refcount_copying') + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: # <<<<<<<<<<<<<< + * + * if dtype_is_object: + */ + +static void __pyx_memoryview_refcount_copying(__Pyx_memviewslice *__pyx_v_dst, int __pyx_v_dtype_is_object, int __pyx_v_ndim, int __pyx_v_inc) { + + /* "View.MemoryView":1361 + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: + * + * if dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice_with_gil(dst.data, dst.shape, dst.strides, ndim, inc) + * + */ + if (__pyx_v_dtype_is_object) { + + /* "View.MemoryView":1362 + * + * if dtype_is_object: + * refcount_objects_in_slice_with_gil(dst.data, dst.shape, dst.strides, ndim, inc) # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_refcount_objects_in_slice_with_gil') + */ + __pyx_memoryview_refcount_objects_in_slice_with_gil(__pyx_v_dst->data, __pyx_v_dst->shape, __pyx_v_dst->strides, __pyx_v_ndim, __pyx_v_inc); + + /* "View.MemoryView":1361 + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: + * + * if dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice_with_gil(dst.data, dst.shape, dst.strides, ndim, inc) + * + */ + } + + /* "View.MemoryView":1359 + * + * @cname('__pyx_memoryview_refcount_copying') + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: # <<<<<<<<<<<<<< + * + * if dtype_is_object: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1365 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice_with_gil') + * cdef void refcount_objects_in_slice_with_gil(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * bint inc) noexcept with gil: + */ + +static void __pyx_memoryview_refcount_objects_in_slice_with_gil(char *__pyx_v_data, Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, int __pyx_v_ndim, int __pyx_v_inc) { + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + + /* "View.MemoryView":1368 + * Py_ssize_t *strides, int ndim, + * bint inc) noexcept with gil: + * refcount_objects_in_slice(data, shape, strides, ndim, inc) # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_refcount_objects_in_slice') + */ + __pyx_memoryview_refcount_objects_in_slice(__pyx_v_data, __pyx_v_shape, __pyx_v_strides, __pyx_v_ndim, __pyx_v_inc); + + /* "View.MemoryView":1365 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice_with_gil') + * cdef void refcount_objects_in_slice_with_gil(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * bint inc) noexcept with gil: + */ + + /* function exit code */ + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif +} + +/* "View.MemoryView":1371 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice') + * cdef void refcount_objects_in_slice(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, bint inc) noexcept: + * cdef Py_ssize_t i + */ + +static void __pyx_memoryview_refcount_objects_in_slice(char *__pyx_v_data, Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, int __pyx_v_ndim, int __pyx_v_inc) { + CYTHON_UNUSED Py_ssize_t __pyx_v_i; + Py_ssize_t __pyx_v_stride; + Py_ssize_t __pyx_t_1; + Py_ssize_t __pyx_t_2; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + + /* "View.MemoryView":1374 + * Py_ssize_t *strides, int ndim, bint inc) noexcept: + * cdef Py_ssize_t i + * cdef Py_ssize_t stride = strides[0] # <<<<<<<<<<<<<< + * + * for i in range(shape[0]): + */ + __pyx_v_stride = (__pyx_v_strides[0]); + + /* "View.MemoryView":1376 + * cdef Py_ssize_t stride = strides[0] + * + * for i in range(shape[0]): # <<<<<<<<<<<<<< + * if ndim == 1: + * if inc: + */ + __pyx_t_1 = (__pyx_v_shape[0]); + __pyx_t_2 = __pyx_t_1; + for (__pyx_t_3 = 0; __pyx_t_3 < __pyx_t_2; __pyx_t_3+=1) { + __pyx_v_i = __pyx_t_3; + + /* "View.MemoryView":1377 + * + * for i in range(shape[0]): + * if ndim == 1: # <<<<<<<<<<<<<< + * if inc: + * Py_INCREF(( data)[0]) + */ + __pyx_t_4 = (__pyx_v_ndim == 1); + if (__pyx_t_4) { + + /* "View.MemoryView":1378 + * for i in range(shape[0]): + * if ndim == 1: + * if inc: # <<<<<<<<<<<<<< + * Py_INCREF(( data)[0]) + * else: + */ + if (__pyx_v_inc) { + + /* "View.MemoryView":1379 + * if ndim == 1: + * if inc: + * Py_INCREF(( data)[0]) # <<<<<<<<<<<<<< + * else: + * Py_DECREF(( data)[0]) + */ + Py_INCREF((((PyObject **)__pyx_v_data)[0])); + + /* "View.MemoryView":1378 + * for i in range(shape[0]): + * if ndim == 1: + * if inc: # <<<<<<<<<<<<<< + * Py_INCREF(( data)[0]) + * else: + */ + goto __pyx_L6; + } + + /* "View.MemoryView":1381 + * Py_INCREF(( data)[0]) + * else: + * Py_DECREF(( data)[0]) # <<<<<<<<<<<<<< + * else: + * refcount_objects_in_slice(data, shape + 1, strides + 1, ndim - 1, inc) + */ + /*else*/ { + Py_DECREF((((PyObject **)__pyx_v_data)[0])); + } + __pyx_L6:; + + /* "View.MemoryView":1377 + * + * for i in range(shape[0]): + * if ndim == 1: # <<<<<<<<<<<<<< + * if inc: + * Py_INCREF(( data)[0]) + */ + goto __pyx_L5; + } + + /* "View.MemoryView":1383 + * Py_DECREF(( data)[0]) + * else: + * refcount_objects_in_slice(data, shape + 1, strides + 1, ndim - 1, inc) # <<<<<<<<<<<<<< + * + * data += stride + */ + /*else*/ { + __pyx_memoryview_refcount_objects_in_slice(__pyx_v_data, (__pyx_v_shape + 1), (__pyx_v_strides + 1), (__pyx_v_ndim - 1), __pyx_v_inc); + } + __pyx_L5:; + + /* "View.MemoryView":1385 + * refcount_objects_in_slice(data, shape + 1, strides + 1, ndim - 1, inc) + * + * data += stride # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_data = (__pyx_v_data + __pyx_v_stride); + } + + /* "View.MemoryView":1371 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice') + * cdef void refcount_objects_in_slice(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, bint inc) noexcept: + * cdef Py_ssize_t i + */ + + /* function exit code */ +} + +/* "View.MemoryView":1391 + * + * @cname('__pyx_memoryview_slice_assign_scalar') + * cdef void slice_assign_scalar(__Pyx_memviewslice *dst, int ndim, # <<<<<<<<<<<<<< + * size_t itemsize, void *item, + * bint dtype_is_object) noexcept nogil: + */ + +static void __pyx_memoryview_slice_assign_scalar(__Pyx_memviewslice *__pyx_v_dst, int __pyx_v_ndim, size_t __pyx_v_itemsize, void *__pyx_v_item, int __pyx_v_dtype_is_object) { + + /* "View.MemoryView":1394 + * size_t itemsize, void *item, + * bint dtype_is_object) noexcept nogil: + * refcount_copying(dst, dtype_is_object, ndim, inc=False) # <<<<<<<<<<<<<< + * _slice_assign_scalar(dst.data, dst.shape, dst.strides, ndim, itemsize, item) + * refcount_copying(dst, dtype_is_object, ndim, inc=True) + */ + __pyx_memoryview_refcount_copying(__pyx_v_dst, __pyx_v_dtype_is_object, __pyx_v_ndim, 0); + + /* "View.MemoryView":1395 + * bint dtype_is_object) noexcept nogil: + * refcount_copying(dst, dtype_is_object, ndim, inc=False) + * _slice_assign_scalar(dst.data, dst.shape, dst.strides, ndim, itemsize, item) # <<<<<<<<<<<<<< + * refcount_copying(dst, dtype_is_object, ndim, inc=True) + * + */ + __pyx_memoryview__slice_assign_scalar(__pyx_v_dst->data, __pyx_v_dst->shape, __pyx_v_dst->strides, __pyx_v_ndim, __pyx_v_itemsize, __pyx_v_item); + + /* "View.MemoryView":1396 + * refcount_copying(dst, dtype_is_object, ndim, inc=False) + * _slice_assign_scalar(dst.data, dst.shape, dst.strides, ndim, itemsize, item) + * refcount_copying(dst, dtype_is_object, ndim, inc=True) # <<<<<<<<<<<<<< + * + * + */ + __pyx_memoryview_refcount_copying(__pyx_v_dst, __pyx_v_dtype_is_object, __pyx_v_ndim, 1); + + /* "View.MemoryView":1391 + * + * @cname('__pyx_memoryview_slice_assign_scalar') + * cdef void slice_assign_scalar(__Pyx_memviewslice *dst, int ndim, # <<<<<<<<<<<<<< + * size_t itemsize, void *item, + * bint dtype_is_object) noexcept nogil: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1400 + * + * @cname('__pyx_memoryview__slice_assign_scalar') + * cdef void _slice_assign_scalar(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * size_t itemsize, void *item) noexcept nogil: + */ + +static void __pyx_memoryview__slice_assign_scalar(char *__pyx_v_data, Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, int __pyx_v_ndim, size_t __pyx_v_itemsize, void *__pyx_v_item) { + CYTHON_UNUSED Py_ssize_t __pyx_v_i; + Py_ssize_t __pyx_v_stride; + Py_ssize_t __pyx_v_extent; + int __pyx_t_1; + Py_ssize_t __pyx_t_2; + Py_ssize_t __pyx_t_3; + Py_ssize_t __pyx_t_4; + + /* "View.MemoryView":1404 + * size_t itemsize, void *item) noexcept nogil: + * cdef Py_ssize_t i + * cdef Py_ssize_t stride = strides[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t extent = shape[0] + * + */ + __pyx_v_stride = (__pyx_v_strides[0]); + + /* "View.MemoryView":1405 + * cdef Py_ssize_t i + * cdef Py_ssize_t stride = strides[0] + * cdef Py_ssize_t extent = shape[0] # <<<<<<<<<<<<<< + * + * if ndim == 1: + */ + __pyx_v_extent = (__pyx_v_shape[0]); + + /* "View.MemoryView":1407 + * cdef Py_ssize_t extent = shape[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * for i in range(extent): + * memcpy(data, item, itemsize) + */ + __pyx_t_1 = (__pyx_v_ndim == 1); + if (__pyx_t_1) { + + /* "View.MemoryView":1408 + * + * if ndim == 1: + * for i in range(extent): # <<<<<<<<<<<<<< + * memcpy(data, item, itemsize) + * data += stride + */ + __pyx_t_2 = __pyx_v_extent; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1409 + * if ndim == 1: + * for i in range(extent): + * memcpy(data, item, itemsize) # <<<<<<<<<<<<<< + * data += stride + * else: + */ + (void)(memcpy(__pyx_v_data, __pyx_v_item, __pyx_v_itemsize)); + + /* "View.MemoryView":1410 + * for i in range(extent): + * memcpy(data, item, itemsize) + * data += stride # <<<<<<<<<<<<<< + * else: + * for i in range(extent): + */ + __pyx_v_data = (__pyx_v_data + __pyx_v_stride); + } + + /* "View.MemoryView":1407 + * cdef Py_ssize_t extent = shape[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * for i in range(extent): + * memcpy(data, item, itemsize) + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1412 + * data += stride + * else: + * for i in range(extent): # <<<<<<<<<<<<<< + * _slice_assign_scalar(data, shape + 1, strides + 1, ndim - 1, itemsize, item) + * data += stride + */ + /*else*/ { + __pyx_t_2 = __pyx_v_extent; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1413 + * else: + * for i in range(extent): + * _slice_assign_scalar(data, shape + 1, strides + 1, ndim - 1, itemsize, item) # <<<<<<<<<<<<<< + * data += stride + * + */ + __pyx_memoryview__slice_assign_scalar(__pyx_v_data, (__pyx_v_shape + 1), (__pyx_v_strides + 1), (__pyx_v_ndim - 1), __pyx_v_itemsize, __pyx_v_item); + + /* "View.MemoryView":1414 + * for i in range(extent): + * _slice_assign_scalar(data, shape + 1, strides + 1, ndim - 1, itemsize, item) + * data += stride # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_data = (__pyx_v_data + __pyx_v_stride); + } + } + __pyx_L3:; + + /* "View.MemoryView":1400 + * + * @cname('__pyx_memoryview__slice_assign_scalar') + * cdef void _slice_assign_scalar(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * size_t itemsize, void *item) noexcept nogil: + */ + + /* function exit code */ +} + +/* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_1__pyx_unpickle_Enum(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_15View_dot_MemoryView_1__pyx_unpickle_Enum = {"__pyx_unpickle_Enum", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15View_dot_MemoryView_1__pyx_unpickle_Enum, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15View_dot_MemoryView_1__pyx_unpickle_Enum(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v___pyx_type = 0; + long __pyx_v___pyx_checksum; + PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__pyx_unpickle_Enum (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_type,&__pyx_n_s_pyx_checksum,&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_type)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_checksum)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle_Enum", 1, 3, 3, 1); __PYX_ERR(1, 1, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle_Enum", 1, 3, 3, 2); __PYX_ERR(1, 1, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__pyx_unpickle_Enum") < 0)) __PYX_ERR(1, 1, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + } + __pyx_v___pyx_type = values[0]; + __pyx_v___pyx_checksum = __Pyx_PyInt_As_long(values[1]); if (unlikely((__pyx_v___pyx_checksum == (long)-1) && PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + __pyx_v___pyx_state = values[2]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle_Enum", 1, 3, 3, __pyx_nargs); __PYX_ERR(1, 1, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.__pyx_unpickle_Enum", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15View_dot_MemoryView___pyx_unpickle_Enum(__pyx_self, __pyx_v___pyx_type, __pyx_v___pyx_checksum, __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView___pyx_unpickle_Enum(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v___pyx_type, long __pyx_v___pyx_checksum, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_v___pyx_PickleError = 0; + PyObject *__pyx_v___pyx_result = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_unpickle_Enum", 1); + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + */ + __pyx_t_1 = __Pyx_PyInt_From_long(__pyx_v___pyx_checksum); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 4, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = (__Pyx_PySequence_ContainsTF(__pyx_t_1, __pyx_tuple__10, Py_NE)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(1, 4, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (__pyx_t_2) { + + /* "(tree fragment)":5 + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): + * from pickle import PickleError as __pyx_PickleError # <<<<<<<<<<<<<< + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) + */ + __pyx_t_1 = PyList_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_s_PickleError); + __Pyx_GIVEREF(__pyx_n_s_PickleError); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_s_PickleError)) __PYX_ERR(1, 5, __pyx_L1_error); + __pyx_t_3 = __Pyx_Import(__pyx_n_s_pickle, __pyx_t_1, 0); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_ImportFrom(__pyx_t_3, __pyx_n_s_PickleError); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_t_1); + __pyx_v___pyx_PickleError = __pyx_t_1; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "(tree fragment)":6 + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum # <<<<<<<<<<<<<< + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: + */ + __pyx_t_3 = __Pyx_PyInt_From_long(__pyx_v___pyx_checksum); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_Incompatible_checksums_0x_x_vs_0_2, __pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_v___pyx_PickleError, __pyx_t_1, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(1, 6, __pyx_L1_error) + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + */ + } + + /* "(tree fragment)":7 + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) # <<<<<<<<<<<<<< + * if __pyx_state is not None: + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_MemviewEnum_type), __pyx_n_s_new); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 7, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = NULL; + __pyx_t_5 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_5 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_4, __pyx_v___pyx_type}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_5, 1+__pyx_t_5); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 7, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_v___pyx_result = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":8 + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + */ + __pyx_t_2 = (__pyx_v___pyx_state != Py_None); + if (__pyx_t_2) { + + /* "(tree fragment)":9 + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) # <<<<<<<<<<<<<< + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + */ + if (!(likely(PyTuple_CheckExact(__pyx_v___pyx_state))||((__pyx_v___pyx_state) == Py_None) || __Pyx_RaiseUnexpectedTypeError("tuple", __pyx_v___pyx_state))) __PYX_ERR(1, 9, __pyx_L1_error) + __pyx_t_1 = __pyx_unpickle_Enum__set_state(((struct __pyx_MemviewEnum_obj *)__pyx_v___pyx_result), ((PyObject*)__pyx_v___pyx_state)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 9, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":8 + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + */ + } + + /* "(tree fragment)":10 + * if __pyx_state is not None: + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result # <<<<<<<<<<<<<< + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v___pyx_result); + __pyx_r = __pyx_v___pyx_result; + goto __pyx_L0; + + /* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.__pyx_unpickle_Enum", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v___pyx_PickleError); + __Pyx_XDECREF(__pyx_v___pyx_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":11 + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): # <<<<<<<<<<<<<< + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + */ + +static PyObject *__pyx_unpickle_Enum__set_state(struct __pyx_MemviewEnum_obj *__pyx_v___pyx_result, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + int __pyx_t_8; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_unpickle_Enum__set_state", 1); + + /* "(tree fragment)":12 + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] # <<<<<<<<<<<<<< + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + * __pyx_result.__dict__.update(__pyx_state[1]) + */ + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 12, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 12, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + __Pyx_GOTREF(__pyx_v___pyx_result->name); + __Pyx_DECREF(__pyx_v___pyx_result->name); + __pyx_v___pyx_result->name = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":13 + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): # <<<<<<<<<<<<<< + * __pyx_result.__dict__.update(__pyx_state[1]) + */ + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); + __PYX_ERR(1, 13, __pyx_L1_error) + } + __pyx_t_3 = __Pyx_PyTuple_GET_SIZE(__pyx_v___pyx_state); if (unlikely(__pyx_t_3 == ((Py_ssize_t)-1))) __PYX_ERR(1, 13, __pyx_L1_error) + __pyx_t_4 = (__pyx_t_3 > 1); + if (__pyx_t_4) { + } else { + __pyx_t_2 = __pyx_t_4; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_4 = __Pyx_HasAttr(((PyObject *)__pyx_v___pyx_result), __pyx_n_s_dict); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(1, 13, __pyx_L1_error) + __pyx_t_2 = __pyx_t_4; + __pyx_L4_bool_binop_done:; + if (__pyx_t_2) { + + /* "(tree fragment)":14 + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + * __pyx_result.__dict__.update(__pyx_state[1]) # <<<<<<<<<<<<<< + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v___pyx_result), __pyx_n_s_dict); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_update); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 14, __pyx_L1_error) + } + __pyx_t_5 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_7 = NULL; + __pyx_t_8 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_6))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_6); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_6); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_6, function); + __pyx_t_8 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_7, __pyx_t_5}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_6, __pyx_callargs+1-__pyx_t_8, 1+__pyx_t_8); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":13 + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): # <<<<<<<<<<<<<< + * __pyx_result.__dict__.update(__pyx_state[1]) + */ + } + + /* "(tree fragment)":11 + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): # <<<<<<<<<<<<<< + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("View.MemoryView.__pyx_unpickle_Enum__set_state", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "BufferFormatFromTypeInfo":1450 + * + * @cname('__pyx_format_from_typeinfo') + * cdef bytes format_from_typeinfo(__Pyx_TypeInfo *type): # <<<<<<<<<<<<<< + * cdef __Pyx_StructField *field + * cdef __pyx_typeinfo_string fmt + */ + +static PyObject *__pyx_format_from_typeinfo(__Pyx_TypeInfo *__pyx_v_type) { + __Pyx_StructField *__pyx_v_field; + struct __pyx_typeinfo_string __pyx_v_fmt; + PyObject *__pyx_v_part = 0; + PyObject *__pyx_v_result = 0; + PyObject *__pyx_v_alignment = NULL; + PyObject *__pyx_v_parts = NULL; + PyObject *__pyx_v_extents = NULL; + Py_ssize_t __pyx_7genexpr__pyx_v_i; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + __Pyx_StructField *__pyx_t_3; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + int __pyx_t_7; + int __pyx_t_8; + Py_ssize_t __pyx_t_9; + Py_UCS4 __pyx_t_10; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("format_from_typeinfo", 1); + + /* "BufferFormatFromTypeInfo":1456 + * cdef Py_ssize_t i + * + * if type.typegroup == 'S': # <<<<<<<<<<<<<< + * assert type.fields != NULL + * assert type.fields.type != NULL + */ + __pyx_t_1 = (__pyx_v_type->typegroup == 'S'); + if (__pyx_t_1) { + + /* "BufferFormatFromTypeInfo":1457 + * + * if type.typegroup == 'S': + * assert type.fields != NULL # <<<<<<<<<<<<<< + * assert type.fields.type != NULL + * + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_1 = (__pyx_v_type->fields != NULL); + if (unlikely(!__pyx_t_1)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(1, 1457, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(1, 1457, __pyx_L1_error) + #endif + + /* "BufferFormatFromTypeInfo":1458 + * if type.typegroup == 'S': + * assert type.fields != NULL + * assert type.fields.type != NULL # <<<<<<<<<<<<<< + * + * if type.flags & __PYX_BUF_FLAGS_PACKED_STRUCT: + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_1 = (__pyx_v_type->fields->type != NULL); + if (unlikely(!__pyx_t_1)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(1, 1458, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(1, 1458, __pyx_L1_error) + #endif + + /* "BufferFormatFromTypeInfo":1460 + * assert type.fields.type != NULL + * + * if type.flags & __PYX_BUF_FLAGS_PACKED_STRUCT: # <<<<<<<<<<<<<< + * alignment = b'^' + * else: + */ + __pyx_t_1 = ((__pyx_v_type->flags & __PYX_BUF_FLAGS_PACKED_STRUCT) != 0); + if (__pyx_t_1) { + + /* "BufferFormatFromTypeInfo":1461 + * + * if type.flags & __PYX_BUF_FLAGS_PACKED_STRUCT: + * alignment = b'^' # <<<<<<<<<<<<<< + * else: + * alignment = b'' + */ + __Pyx_INCREF(__pyx_kp_b__11); + __pyx_v_alignment = __pyx_kp_b__11; + + /* "BufferFormatFromTypeInfo":1460 + * assert type.fields.type != NULL + * + * if type.flags & __PYX_BUF_FLAGS_PACKED_STRUCT: # <<<<<<<<<<<<<< + * alignment = b'^' + * else: + */ + goto __pyx_L4; + } + + /* "BufferFormatFromTypeInfo":1463 + * alignment = b'^' + * else: + * alignment = b'' # <<<<<<<<<<<<<< + * + * parts = [b"T{"] + */ + /*else*/ { + __Pyx_INCREF(__pyx_kp_b_); + __pyx_v_alignment = __pyx_kp_b_; + } + __pyx_L4:; + + /* "BufferFormatFromTypeInfo":1465 + * alignment = b'' + * + * parts = [b"T{"] # <<<<<<<<<<<<<< + * field = type.fields + * + */ + __pyx_t_2 = PyList_New(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1465, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_INCREF(__pyx_kp_b_T); + __Pyx_GIVEREF(__pyx_kp_b_T); + if (__Pyx_PyList_SET_ITEM(__pyx_t_2, 0, __pyx_kp_b_T)) __PYX_ERR(1, 1465, __pyx_L1_error); + __pyx_v_parts = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; + + /* "BufferFormatFromTypeInfo":1466 + * + * parts = [b"T{"] + * field = type.fields # <<<<<<<<<<<<<< + * + * while field.type: + */ + __pyx_t_3 = __pyx_v_type->fields; + __pyx_v_field = __pyx_t_3; + + /* "BufferFormatFromTypeInfo":1468 + * field = type.fields + * + * while field.type: # <<<<<<<<<<<<<< + * part = format_from_typeinfo(field.type) + * parts.append(part + b':' + field.name + b':') + */ + while (1) { + __pyx_t_1 = (__pyx_v_field->type != 0); + if (!__pyx_t_1) break; + + /* "BufferFormatFromTypeInfo":1469 + * + * while field.type: + * part = format_from_typeinfo(field.type) # <<<<<<<<<<<<<< + * parts.append(part + b':' + field.name + b':') + * field += 1 + */ + __pyx_t_2 = __pyx_format_from_typeinfo(__pyx_v_field->type); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1469, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_XDECREF_SET(__pyx_v_part, ((PyObject*)__pyx_t_2)); + __pyx_t_2 = 0; + + /* "BufferFormatFromTypeInfo":1470 + * while field.type: + * part = format_from_typeinfo(field.type) + * parts.append(part + b':' + field.name + b':') # <<<<<<<<<<<<<< + * field += 1 + * + */ + __pyx_t_2 = PyNumber_Add(__pyx_v_part, __pyx_kp_b__12); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1470, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __Pyx_PyBytes_FromString(__pyx_v_field->name); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1470, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = PyNumber_Add(__pyx_t_2, __pyx_t_4); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 1470, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = PyNumber_Add(__pyx_t_5, __pyx_kp_b__12); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1470, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_6 = __Pyx_PyList_Append(__pyx_v_parts, __pyx_t_4); if (unlikely(__pyx_t_6 == ((int)-1))) __PYX_ERR(1, 1470, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "BufferFormatFromTypeInfo":1471 + * part = format_from_typeinfo(field.type) + * parts.append(part + b':' + field.name + b':') + * field += 1 # <<<<<<<<<<<<<< + * + * result = alignment.join(parts) + b'}' + */ + __pyx_v_field = (__pyx_v_field + 1); + } + + /* "BufferFormatFromTypeInfo":1473 + * field += 1 + * + * result = alignment.join(parts) + b'}' # <<<<<<<<<<<<<< + * else: + * fmt = __Pyx_TypeInfoToFormat(type) + */ + __pyx_t_4 = __Pyx_PyBytes_Join(__pyx_v_alignment, __pyx_v_parts); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1473, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = PyNumber_Add(__pyx_t_4, __pyx_kp_b__13); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 1473, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (!(likely(PyBytes_CheckExact(__pyx_t_5))||((__pyx_t_5) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_t_5))) __PYX_ERR(1, 1473, __pyx_L1_error) + __pyx_v_result = ((PyObject*)__pyx_t_5); + __pyx_t_5 = 0; + + /* "BufferFormatFromTypeInfo":1456 + * cdef Py_ssize_t i + * + * if type.typegroup == 'S': # <<<<<<<<<<<<<< + * assert type.fields != NULL + * assert type.fields.type != NULL + */ + goto __pyx_L3; + } + + /* "BufferFormatFromTypeInfo":1475 + * result = alignment.join(parts) + b'}' + * else: + * fmt = __Pyx_TypeInfoToFormat(type) # <<<<<<<<<<<<<< + * result = fmt.string + * if type.arraysize[0]: + */ + /*else*/ { + __pyx_v_fmt = __Pyx_TypeInfoToFormat(__pyx_v_type); + + /* "BufferFormatFromTypeInfo":1476 + * else: + * fmt = __Pyx_TypeInfoToFormat(type) + * result = fmt.string # <<<<<<<<<<<<<< + * if type.arraysize[0]: + * extents = [f"{type.arraysize[i]}" for i in range(type.ndim)] + */ + __pyx_t_5 = __Pyx_PyObject_FromString(__pyx_v_fmt.string); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 1476, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_v_result = ((PyObject*)__pyx_t_5); + __pyx_t_5 = 0; + + /* "BufferFormatFromTypeInfo":1477 + * fmt = __Pyx_TypeInfoToFormat(type) + * result = fmt.string + * if type.arraysize[0]: # <<<<<<<<<<<<<< + * extents = [f"{type.arraysize[i]}" for i in range(type.ndim)] + * result = f"({u','.join(extents)})".encode('ascii') + result + */ + __pyx_t_1 = ((__pyx_v_type->arraysize[0]) != 0); + if (__pyx_t_1) { + + /* "BufferFormatFromTypeInfo":1478 + * result = fmt.string + * if type.arraysize[0]: + * extents = [f"{type.arraysize[i]}" for i in range(type.ndim)] # <<<<<<<<<<<<<< + * result = f"({u','.join(extents)})".encode('ascii') + result + * + */ + { /* enter inner scope */ + __pyx_t_5 = PyList_New(0); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 1478, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_7 = __pyx_v_type->ndim; + __pyx_t_8 = __pyx_t_7; + for (__pyx_t_9 = 0; __pyx_t_9 < __pyx_t_8; __pyx_t_9+=1) { + __pyx_7genexpr__pyx_v_i = __pyx_t_9; + __pyx_t_4 = __Pyx_PyUnicode_From_size_t((__pyx_v_type->arraysize[__pyx_7genexpr__pyx_v_i]), 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1478, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_5, (PyObject*)__pyx_t_4))) __PYX_ERR(1, 1478, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + } /* exit inner scope */ + __pyx_v_extents = ((PyObject*)__pyx_t_5); + __pyx_t_5 = 0; + + /* "BufferFormatFromTypeInfo":1479 + * if type.arraysize[0]: + * extents = [f"{type.arraysize[i]}" for i in range(type.ndim)] + * result = f"({u','.join(extents)})".encode('ascii') + result # <<<<<<<<<<<<<< + * + * return result + */ + __pyx_t_5 = PyTuple_New(3); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 1479, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_9 = 0; + __pyx_t_10 = 127; + __Pyx_INCREF(__pyx_kp_u__14); + __pyx_t_9 += 1; + __Pyx_GIVEREF(__pyx_kp_u__14); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_kp_u__14); + __pyx_t_4 = PyUnicode_Join(__pyx_kp_u__15, __pyx_v_extents); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1479, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_10 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_4) > __pyx_t_10) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_4) : __pyx_t_10; + __pyx_t_9 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_4); + __pyx_t_4 = 0; + __Pyx_INCREF(__pyx_kp_u__9); + __pyx_t_9 += 1; + __Pyx_GIVEREF(__pyx_kp_u__9); + PyTuple_SET_ITEM(__pyx_t_5, 2, __pyx_kp_u__9); + __pyx_t_4 = __Pyx_PyUnicode_Join(__pyx_t_5, 3, __pyx_t_9, __pyx_t_10); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1479, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_5 = PyUnicode_AsASCIIString(((PyObject*)__pyx_t_4)); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 1479, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = PyNumber_Add(__pyx_t_5, __pyx_v_result); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1479, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (!(likely(PyBytes_CheckExact(__pyx_t_4)) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_t_4))) __PYX_ERR(1, 1479, __pyx_L1_error) + __Pyx_DECREF_SET(__pyx_v_result, ((PyObject*)__pyx_t_4)); + __pyx_t_4 = 0; + + /* "BufferFormatFromTypeInfo":1477 + * fmt = __Pyx_TypeInfoToFormat(type) + * result = fmt.string + * if type.arraysize[0]: # <<<<<<<<<<<<<< + * extents = [f"{type.arraysize[i]}" for i in range(type.ndim)] + * result = f"({u','.join(extents)})".encode('ascii') + result + */ + } + } + __pyx_L3:; + + /* "BufferFormatFromTypeInfo":1481 + * result = f"({u','.join(extents)})".encode('ascii') + result + * + * return result # <<<<<<<<<<<<<< + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_result); + __pyx_r = __pyx_v_result; + goto __pyx_L0; + + /* "BufferFormatFromTypeInfo":1450 + * + * @cname('__pyx_format_from_typeinfo') + * cdef bytes format_from_typeinfo(__Pyx_TypeInfo *type): # <<<<<<<<<<<<<< + * cdef __Pyx_StructField *field + * cdef __pyx_typeinfo_string fmt + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("BufferFormatFromTypeInfo.format_from_typeinfo", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_part); + __Pyx_XDECREF(__pyx_v_result); + __Pyx_XDECREF(__pyx_v_alignment); + __Pyx_XDECREF(__pyx_v_parts); + __Pyx_XDECREF(__pyx_v_extents); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":245 + * + * @property + * cdef inline PyObject* base(self) nogil: # <<<<<<<<<<<<<< + * """Returns a borrowed reference to the object owning the data/memory. + * """ + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_7ndarray_4base_base(PyArrayObject *__pyx_v_self) { + PyObject *__pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":248 + * """Returns a borrowed reference to the object owning the data/memory. + * """ + * return PyArray_BASE(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_BASE(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":245 + * + * @property + * cdef inline PyObject* base(self) nogil: # <<<<<<<<<<<<<< + * """Returns a borrowed reference to the object owning the data/memory. + * """ + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":251 + * + * @property + * cdef inline dtype descr(self): # <<<<<<<<<<<<<< + * """Returns an owned reference to the dtype of the array. + * """ + */ + +static CYTHON_INLINE PyArray_Descr *__pyx_f_5numpy_7ndarray_5descr_descr(PyArrayObject *__pyx_v_self) { + PyArray_Descr *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyArray_Descr *__pyx_t_1; + __Pyx_RefNannySetupContext("descr", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":254 + * """Returns an owned reference to the dtype of the array. + * """ + * return PyArray_DESCR(self) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF((PyObject *)__pyx_r); + __pyx_t_1 = PyArray_DESCR(__pyx_v_self); + __Pyx_INCREF((PyObject *)((PyArray_Descr *)__pyx_t_1)); + __pyx_r = ((PyArray_Descr *)__pyx_t_1); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":251 + * + * @property + * cdef inline dtype descr(self): # <<<<<<<<<<<<<< + * """Returns an owned reference to the dtype of the array. + * """ + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF((PyObject *)__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":257 + * + * @property + * cdef inline int ndim(self) nogil: # <<<<<<<<<<<<<< + * """Returns the number of dimensions in the array. + * """ + */ + +static CYTHON_INLINE int __pyx_f_5numpy_7ndarray_4ndim_ndim(PyArrayObject *__pyx_v_self) { + int __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":260 + * """Returns the number of dimensions in the array. + * """ + * return PyArray_NDIM(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_NDIM(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":257 + * + * @property + * cdef inline int ndim(self) nogil: # <<<<<<<<<<<<<< + * """Returns the number of dimensions in the array. + * """ + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":263 + * + * @property + * cdef inline npy_intp *shape(self) nogil: # <<<<<<<<<<<<<< + * """Returns a pointer to the dimensions/shape of the array. + * The number of elements matches the number of dimensions of the array (ndim). + */ + +static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_5shape_shape(PyArrayObject *__pyx_v_self) { + npy_intp *__pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":268 + * Can return NULL for 0-dimensional arrays. + * """ + * return PyArray_DIMS(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_DIMS(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":263 + * + * @property + * cdef inline npy_intp *shape(self) nogil: # <<<<<<<<<<<<<< + * """Returns a pointer to the dimensions/shape of the array. + * The number of elements matches the number of dimensions of the array (ndim). + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":271 + * + * @property + * cdef inline npy_intp *strides(self) nogil: # <<<<<<<<<<<<<< + * """Returns a pointer to the strides of the array. + * The number of elements matches the number of dimensions of the array (ndim). + */ + +static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_7strides_strides(PyArrayObject *__pyx_v_self) { + npy_intp *__pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":275 + * The number of elements matches the number of dimensions of the array (ndim). + * """ + * return PyArray_STRIDES(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_STRIDES(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":271 + * + * @property + * cdef inline npy_intp *strides(self) nogil: # <<<<<<<<<<<<<< + * """Returns a pointer to the strides of the array. + * The number of elements matches the number of dimensions of the array (ndim). + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":278 + * + * @property + * cdef inline npy_intp size(self) nogil: # <<<<<<<<<<<<<< + * """Returns the total size (in number of elements) of the array. + * """ + */ + +static CYTHON_INLINE npy_intp __pyx_f_5numpy_7ndarray_4size_size(PyArrayObject *__pyx_v_self) { + npy_intp __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":281 + * """Returns the total size (in number of elements) of the array. + * """ + * return PyArray_SIZE(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_SIZE(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":278 + * + * @property + * cdef inline npy_intp size(self) nogil: # <<<<<<<<<<<<<< + * """Returns the total size (in number of elements) of the array. + * """ + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":284 + * + * @property + * cdef inline char* data(self) nogil: # <<<<<<<<<<<<<< + * """The pointer to the data buffer as a char*. + * This is provided for legacy reasons to avoid direct struct field access. + */ + +static CYTHON_INLINE char *__pyx_f_5numpy_7ndarray_4data_data(PyArrayObject *__pyx_v_self) { + char *__pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":290 + * of `PyArray_DATA()` instead, which returns a 'void*'. + * """ + * return PyArray_BYTES(self) # <<<<<<<<<<<<<< + * + * ctypedef unsigned char npy_bool + */ + __pyx_r = PyArray_BYTES(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":284 + * + * @property + * cdef inline char* data(self) nogil: # <<<<<<<<<<<<<< + * """The pointer to the data buffer as a char*. + * This is provided for legacy reasons to avoid direct struct field access. + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":773 + * ctypedef npy_cdouble complex_t + * + * cdef inline object PyArray_MultiIterNew1(a): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(1, a) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew1(PyObject *__pyx_v_a) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew1", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":774 + * + * cdef inline object PyArray_MultiIterNew1(a): + * return PyArray_MultiIterNew(1, a) # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew2(a, b): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(1, ((void *)__pyx_v_a)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 774, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":773 + * ctypedef npy_cdouble complex_t + * + * cdef inline object PyArray_MultiIterNew1(a): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(1, a) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew1", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":776 + * return PyArray_MultiIterNew(1, a) + * + * cdef inline object PyArray_MultiIterNew2(a, b): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(2, a, b) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew2(PyObject *__pyx_v_a, PyObject *__pyx_v_b) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew2", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":777 + * + * cdef inline object PyArray_MultiIterNew2(a, b): + * return PyArray_MultiIterNew(2, a, b) # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew3(a, b, c): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(2, ((void *)__pyx_v_a), ((void *)__pyx_v_b)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 777, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":776 + * return PyArray_MultiIterNew(1, a) + * + * cdef inline object PyArray_MultiIterNew2(a, b): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(2, a, b) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew2", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":779 + * return PyArray_MultiIterNew(2, a, b) + * + * cdef inline object PyArray_MultiIterNew3(a, b, c): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(3, a, b, c) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew3(PyObject *__pyx_v_a, PyObject *__pyx_v_b, PyObject *__pyx_v_c) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew3", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":780 + * + * cdef inline object PyArray_MultiIterNew3(a, b, c): + * return PyArray_MultiIterNew(3, a, b, c) # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew4(a, b, c, d): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(3, ((void *)__pyx_v_a), ((void *)__pyx_v_b), ((void *)__pyx_v_c)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 780, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":779 + * return PyArray_MultiIterNew(2, a, b) + * + * cdef inline object PyArray_MultiIterNew3(a, b, c): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(3, a, b, c) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew3", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":782 + * return PyArray_MultiIterNew(3, a, b, c) + * + * cdef inline object PyArray_MultiIterNew4(a, b, c, d): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(4, a, b, c, d) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew4(PyObject *__pyx_v_a, PyObject *__pyx_v_b, PyObject *__pyx_v_c, PyObject *__pyx_v_d) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew4", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":783 + * + * cdef inline object PyArray_MultiIterNew4(a, b, c, d): + * return PyArray_MultiIterNew(4, a, b, c, d) # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(4, ((void *)__pyx_v_a), ((void *)__pyx_v_b), ((void *)__pyx_v_c), ((void *)__pyx_v_d)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 783, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":782 + * return PyArray_MultiIterNew(3, a, b, c) + * + * cdef inline object PyArray_MultiIterNew4(a, b, c, d): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(4, a, b, c, d) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew4", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":785 + * return PyArray_MultiIterNew(4, a, b, c, d) + * + * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(5, a, b, c, d, e) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew5(PyObject *__pyx_v_a, PyObject *__pyx_v_b, PyObject *__pyx_v_c, PyObject *__pyx_v_d, PyObject *__pyx_v_e) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew5", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":786 + * + * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): + * return PyArray_MultiIterNew(5, a, b, c, d, e) # <<<<<<<<<<<<<< + * + * cdef inline tuple PyDataType_SHAPE(dtype d): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(5, ((void *)__pyx_v_a), ((void *)__pyx_v_b), ((void *)__pyx_v_c), ((void *)__pyx_v_d), ((void *)__pyx_v_e)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 786, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":785 + * return PyArray_MultiIterNew(4, a, b, c, d) + * + * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(5, a, b, c, d, e) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew5", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":788 + * return PyArray_MultiIterNew(5, a, b, c, d, e) + * + * cdef inline tuple PyDataType_SHAPE(dtype d): # <<<<<<<<<<<<<< + * if PyDataType_HASSUBARRAY(d): + * return d.subarray.shape + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyDataType_SHAPE(PyArray_Descr *__pyx_v_d) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + __Pyx_RefNannySetupContext("PyDataType_SHAPE", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":789 + * + * cdef inline tuple PyDataType_SHAPE(dtype d): + * if PyDataType_HASSUBARRAY(d): # <<<<<<<<<<<<<< + * return d.subarray.shape + * else: + */ + __pyx_t_1 = PyDataType_HASSUBARRAY(__pyx_v_d); + if (__pyx_t_1) { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":790 + * cdef inline tuple PyDataType_SHAPE(dtype d): + * if PyDataType_HASSUBARRAY(d): + * return d.subarray.shape # <<<<<<<<<<<<<< + * else: + * return () + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(((PyObject*)__pyx_v_d->subarray->shape)); + __pyx_r = ((PyObject*)__pyx_v_d->subarray->shape); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":789 + * + * cdef inline tuple PyDataType_SHAPE(dtype d): + * if PyDataType_HASSUBARRAY(d): # <<<<<<<<<<<<<< + * return d.subarray.shape + * else: + */ + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":792 + * return d.subarray.shape + * else: + * return () # <<<<<<<<<<<<<< + * + * + */ + /*else*/ { + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_empty_tuple); + __pyx_r = __pyx_empty_tuple; + goto __pyx_L0; + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":788 + * return PyArray_MultiIterNew(5, a, b, c, d, e) + * + * cdef inline tuple PyDataType_SHAPE(dtype d): # <<<<<<<<<<<<<< + * if PyDataType_HASSUBARRAY(d): + * return d.subarray.shape + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":968 + * int _import_umath() except -1 + * + * cdef inline void set_array_base(ndarray arr, object base): # <<<<<<<<<<<<<< + * Py_INCREF(base) # important to do this before stealing the reference below! + * PyArray_SetBaseObject(arr, base) + */ + +static CYTHON_INLINE void __pyx_f_5numpy_set_array_base(PyArrayObject *__pyx_v_arr, PyObject *__pyx_v_base) { + int __pyx_t_1; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":969 + * + * cdef inline void set_array_base(ndarray arr, object base): + * Py_INCREF(base) # important to do this before stealing the reference below! # <<<<<<<<<<<<<< + * PyArray_SetBaseObject(arr, base) + * + */ + Py_INCREF(__pyx_v_base); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":970 + * cdef inline void set_array_base(ndarray arr, object base): + * Py_INCREF(base) # important to do this before stealing the reference below! + * PyArray_SetBaseObject(arr, base) # <<<<<<<<<<<<<< + * + * cdef inline object get_array_base(ndarray arr): + */ + __pyx_t_1 = PyArray_SetBaseObject(__pyx_v_arr, __pyx_v_base); if (unlikely(__pyx_t_1 == ((int)-1))) __PYX_ERR(2, 970, __pyx_L1_error) + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":968 + * int _import_umath() except -1 + * + * cdef inline void set_array_base(ndarray arr, object base): # <<<<<<<<<<<<<< + * Py_INCREF(base) # important to do this before stealing the reference below! + * PyArray_SetBaseObject(arr, base) + */ + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("numpy.set_array_base", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_L0:; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":972 + * PyArray_SetBaseObject(arr, base) + * + * cdef inline object get_array_base(ndarray arr): # <<<<<<<<<<<<<< + * base = PyArray_BASE(arr) + * if base is NULL: + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_get_array_base(PyArrayObject *__pyx_v_arr) { + PyObject *__pyx_v_base; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + __Pyx_RefNannySetupContext("get_array_base", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":973 + * + * cdef inline object get_array_base(ndarray arr): + * base = PyArray_BASE(arr) # <<<<<<<<<<<<<< + * if base is NULL: + * return None + */ + __pyx_v_base = PyArray_BASE(__pyx_v_arr); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":974 + * cdef inline object get_array_base(ndarray arr): + * base = PyArray_BASE(arr) + * if base is NULL: # <<<<<<<<<<<<<< + * return None + * return base + */ + __pyx_t_1 = (__pyx_v_base == NULL); + if (__pyx_t_1) { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":975 + * base = PyArray_BASE(arr) + * if base is NULL: + * return None # <<<<<<<<<<<<<< + * return base + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":974 + * cdef inline object get_array_base(ndarray arr): + * base = PyArray_BASE(arr) + * if base is NULL: # <<<<<<<<<<<<<< + * return None + * return base + */ + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":976 + * if base is NULL: + * return None + * return base # <<<<<<<<<<<<<< + * + * # Versions of the import_* functions which are more suitable for + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(((PyObject *)__pyx_v_base)); + __pyx_r = ((PyObject *)__pyx_v_base); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":972 + * PyArray_SetBaseObject(arr, base) + * + * cdef inline object get_array_base(ndarray arr): # <<<<<<<<<<<<<< + * base = PyArray_BASE(arr) + * if base is NULL: + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":980 + * # Versions of the import_* functions which are more suitable for + * # Cython code. + * cdef inline int import_array() except -1: # <<<<<<<<<<<<<< + * try: + * __pyx_import_array() + */ + +static CYTHON_INLINE int __pyx_f_5numpy_import_array(void) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("import_array", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":981 + * # Cython code. + * cdef inline int import_array() except -1: + * try: # <<<<<<<<<<<<<< + * __pyx_import_array() + * except Exception: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":982 + * cdef inline int import_array() except -1: + * try: + * __pyx_import_array() # <<<<<<<<<<<<<< + * except Exception: + * raise ImportError("numpy.core.multiarray failed to import") + */ + __pyx_t_4 = _import_array(); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(2, 982, __pyx_L3_error) + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":981 + * # Cython code. + * cdef inline int import_array() except -1: + * try: # <<<<<<<<<<<<<< + * __pyx_import_array() + * except Exception: + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L8_try_end; + __pyx_L3_error:; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":983 + * try: + * __pyx_import_array() + * except Exception: # <<<<<<<<<<<<<< + * raise ImportError("numpy.core.multiarray failed to import") + * + */ + __pyx_t_4 = __Pyx_PyErr_ExceptionMatches(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0]))); + if (__pyx_t_4) { + __Pyx_AddTraceback("numpy.import_array", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_6, &__pyx_t_7) < 0) __PYX_ERR(2, 983, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_7); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":984 + * __pyx_import_array() + * except Exception: + * raise ImportError("numpy.core.multiarray failed to import") # <<<<<<<<<<<<<< + * + * cdef inline int import_umath() except -1: + */ + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_builtin_ImportError, __pyx_tuple__16, NULL); if (unlikely(!__pyx_t_8)) __PYX_ERR(2, 984, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_Raise(__pyx_t_8, 0, 0, 0); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __PYX_ERR(2, 984, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":981 + * # Cython code. + * cdef inline int import_array() except -1: + * try: # <<<<<<<<<<<<<< + * __pyx_import_array() + * except Exception: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + goto __pyx_L1_error; + __pyx_L8_try_end:; + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":980 + * # Versions of the import_* functions which are more suitable for + * # Cython code. + * cdef inline int import_array() except -1: # <<<<<<<<<<<<<< + * try: + * __pyx_import_array() + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("numpy.import_array", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":986 + * raise ImportError("numpy.core.multiarray failed to import") + * + * cdef inline int import_umath() except -1: # <<<<<<<<<<<<<< + * try: + * _import_umath() + */ + +static CYTHON_INLINE int __pyx_f_5numpy_import_umath(void) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("import_umath", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":987 + * + * cdef inline int import_umath() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":988 + * cdef inline int import_umath() except -1: + * try: + * _import_umath() # <<<<<<<<<<<<<< + * except Exception: + * raise ImportError("numpy.core.umath failed to import") + */ + __pyx_t_4 = _import_umath(); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(2, 988, __pyx_L3_error) + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":987 + * + * cdef inline int import_umath() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L8_try_end; + __pyx_L3_error:; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":989 + * try: + * _import_umath() + * except Exception: # <<<<<<<<<<<<<< + * raise ImportError("numpy.core.umath failed to import") + * + */ + __pyx_t_4 = __Pyx_PyErr_ExceptionMatches(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0]))); + if (__pyx_t_4) { + __Pyx_AddTraceback("numpy.import_umath", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_6, &__pyx_t_7) < 0) __PYX_ERR(2, 989, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_7); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":990 + * _import_umath() + * except Exception: + * raise ImportError("numpy.core.umath failed to import") # <<<<<<<<<<<<<< + * + * cdef inline int import_ufunc() except -1: + */ + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_builtin_ImportError, __pyx_tuple__17, NULL); if (unlikely(!__pyx_t_8)) __PYX_ERR(2, 990, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_Raise(__pyx_t_8, 0, 0, 0); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __PYX_ERR(2, 990, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":987 + * + * cdef inline int import_umath() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + goto __pyx_L1_error; + __pyx_L8_try_end:; + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":986 + * raise ImportError("numpy.core.multiarray failed to import") + * + * cdef inline int import_umath() except -1: # <<<<<<<<<<<<<< + * try: + * _import_umath() + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("numpy.import_umath", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":992 + * raise ImportError("numpy.core.umath failed to import") + * + * cdef inline int import_ufunc() except -1: # <<<<<<<<<<<<<< + * try: + * _import_umath() + */ + +static CYTHON_INLINE int __pyx_f_5numpy_import_ufunc(void) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("import_ufunc", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":993 + * + * cdef inline int import_ufunc() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":994 + * cdef inline int import_ufunc() except -1: + * try: + * _import_umath() # <<<<<<<<<<<<<< + * except Exception: + * raise ImportError("numpy.core.umath failed to import") + */ + __pyx_t_4 = _import_umath(); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(2, 994, __pyx_L3_error) + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":993 + * + * cdef inline int import_ufunc() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L8_try_end; + __pyx_L3_error:; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":995 + * try: + * _import_umath() + * except Exception: # <<<<<<<<<<<<<< + * raise ImportError("numpy.core.umath failed to import") + * + */ + __pyx_t_4 = __Pyx_PyErr_ExceptionMatches(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0]))); + if (__pyx_t_4) { + __Pyx_AddTraceback("numpy.import_ufunc", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_6, &__pyx_t_7) < 0) __PYX_ERR(2, 995, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_7); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":996 + * _import_umath() + * except Exception: + * raise ImportError("numpy.core.umath failed to import") # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_builtin_ImportError, __pyx_tuple__17, NULL); if (unlikely(!__pyx_t_8)) __PYX_ERR(2, 996, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_Raise(__pyx_t_8, 0, 0, 0); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __PYX_ERR(2, 996, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":993 + * + * cdef inline int import_ufunc() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + goto __pyx_L1_error; + __pyx_L8_try_end:; + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":992 + * raise ImportError("numpy.core.umath failed to import") + * + * cdef inline int import_ufunc() except -1: # <<<<<<<<<<<<<< + * try: + * _import_umath() + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("numpy.import_ufunc", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":999 + * + * + * cdef inline bint is_timedelta64_object(object obj): # <<<<<<<<<<<<<< + * """ + * Cython equivalent of `isinstance(obj, np.timedelta64)` + */ + +static CYTHON_INLINE int __pyx_f_5numpy_is_timedelta64_object(PyObject *__pyx_v_obj) { + int __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1011 + * bool + * """ + * return PyObject_TypeCheck(obj, &PyTimedeltaArrType_Type) # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = PyObject_TypeCheck(__pyx_v_obj, (&PyTimedeltaArrType_Type)); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":999 + * + * + * cdef inline bint is_timedelta64_object(object obj): # <<<<<<<<<<<<<< + * """ + * Cython equivalent of `isinstance(obj, np.timedelta64)` + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1014 + * + * + * cdef inline bint is_datetime64_object(object obj): # <<<<<<<<<<<<<< + * """ + * Cython equivalent of `isinstance(obj, np.datetime64)` + */ + +static CYTHON_INLINE int __pyx_f_5numpy_is_datetime64_object(PyObject *__pyx_v_obj) { + int __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1026 + * bool + * """ + * return PyObject_TypeCheck(obj, &PyDatetimeArrType_Type) # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = PyObject_TypeCheck(__pyx_v_obj, (&PyDatetimeArrType_Type)); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1014 + * + * + * cdef inline bint is_datetime64_object(object obj): # <<<<<<<<<<<<<< + * """ + * Cython equivalent of `isinstance(obj, np.datetime64)` + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1029 + * + * + * cdef inline npy_datetime get_datetime64_value(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the int64 value underlying scalar numpy datetime64 object + */ + +static CYTHON_INLINE npy_datetime __pyx_f_5numpy_get_datetime64_value(PyObject *__pyx_v_obj) { + npy_datetime __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1036 + * also needed. That can be found using `get_datetime64_unit`. + * """ + * return (obj).obval # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = ((PyDatetimeScalarObject *)__pyx_v_obj)->obval; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1029 + * + * + * cdef inline npy_datetime get_datetime64_value(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the int64 value underlying scalar numpy datetime64 object + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1039 + * + * + * cdef inline npy_timedelta get_timedelta64_value(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the int64 value underlying scalar numpy timedelta64 object + */ + +static CYTHON_INLINE npy_timedelta __pyx_f_5numpy_get_timedelta64_value(PyObject *__pyx_v_obj) { + npy_timedelta __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1043 + * returns the int64 value underlying scalar numpy timedelta64 object + * """ + * return (obj).obval # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = ((PyTimedeltaScalarObject *)__pyx_v_obj)->obval; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1039 + * + * + * cdef inline npy_timedelta get_timedelta64_value(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the int64 value underlying scalar numpy timedelta64 object + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1046 + * + * + * cdef inline NPY_DATETIMEUNIT get_datetime64_unit(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the unit part of the dtype for a numpy datetime64 object. + */ + +static CYTHON_INLINE NPY_DATETIMEUNIT __pyx_f_5numpy_get_datetime64_unit(PyObject *__pyx_v_obj) { + NPY_DATETIMEUNIT __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1050 + * returns the unit part of the dtype for a numpy datetime64 object. + * """ + * return (obj).obmeta.base # <<<<<<<<<<<<<< + */ + __pyx_r = ((NPY_DATETIMEUNIT)((PyDatetimeScalarObject *)__pyx_v_obj)->obmeta.base); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1046 + * + * + * cdef inline NPY_DATETIMEUNIT get_datetime64_unit(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the unit part of the dtype for a numpy datetime64 object. + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":20 + * + * + * def get_endpoint_name(string name, VisionStreamType stream): # <<<<<<<<<<<<<< + * return cpp_get_endpoint_name(name, stream).decode('utf-8') + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_1get_endpoint_name(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9visionipc_13visionipc_pyx_1get_endpoint_name = {"get_endpoint_name", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_1get_endpoint_name, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_1get_endpoint_name(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + std::string __pyx_v_name; + enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType __pyx_v_stream; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[2] = {0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("get_endpoint_name (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_name,&__pyx_n_s_stream,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_name)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 20, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stream)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 20, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("get_endpoint_name", 1, 2, 2, 1); __PYX_ERR(0, 20, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "get_endpoint_name") < 0)) __PYX_ERR(0, 20, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 2)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + } + __pyx_v_name = __pyx_convert_string_from_py_std__in_string(values[0]); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 20, __pyx_L3_error) + __pyx_v_stream = ((enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)__Pyx_PyInt_As_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(values[1])); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 20, __pyx_L3_error) + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("get_endpoint_name", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 20, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.get_endpoint_name", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_get_endpoint_name(__pyx_self, __PYX_STD_MOVE_IF_SUPPORTED(__pyx_v_name), __pyx_v_stream); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_get_endpoint_name(CYTHON_UNUSED PyObject *__pyx_self, std::string __pyx_v_name, enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType __pyx_v_stream) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_endpoint_name", 1); + + /* "cereal/visionipc/visionipc_pyx.pyx":21 + * + * def get_endpoint_name(string name, VisionStreamType stream): + * return cpp_get_endpoint_name(name, stream).decode('utf-8') # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_decode_cpp_string(get_endpoint_name(__pyx_v_name, ((enum VisionStreamType)__pyx_v_stream)), 0, PY_SSIZE_T_MAX, NULL, NULL, PyUnicode_DecodeUTF8); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 21, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":20 + * + * + * def get_endpoint_name(string name, VisionStreamType stream): # <<<<<<<<<<<<<< + * return cpp_get_endpoint_name(name, stream).decode('utf-8') + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.get_endpoint_name", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":33 + * cdef class VisionBuf: + * @staticmethod + * cdef create(cppVisionBuf * cbuf): # <<<<<<<<<<<<<< + * buf = VisionBuf() + * buf.buf = cbuf + */ + +static PyObject *__pyx_f_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_create(VisionBuf *__pyx_v_cbuf) { + struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_v_buf = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("create", 1); + + /* "cereal/visionipc/visionipc_pyx.pyx":34 + * @staticmethod + * cdef create(cppVisionBuf * cbuf): + * buf = VisionBuf() # <<<<<<<<<<<<<< + * buf.buf = cbuf + * return buf + */ + __pyx_t_1 = __Pyx_PyObject_CallNoArg(((PyObject *)__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 34, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_buf = ((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *)__pyx_t_1); + __pyx_t_1 = 0; + + /* "cereal/visionipc/visionipc_pyx.pyx":35 + * cdef create(cppVisionBuf * cbuf): + * buf = VisionBuf() + * buf.buf = cbuf # <<<<<<<<<<<<<< + * return buf + * + */ + __pyx_v_buf->buf = __pyx_v_cbuf; + + /* "cereal/visionipc/visionipc_pyx.pyx":36 + * buf = VisionBuf() + * buf.buf = cbuf + * return buf # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_buf); + __pyx_r = ((PyObject *)__pyx_v_buf); + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":33 + * cdef class VisionBuf: + * @staticmethod + * cdef create(cppVisionBuf * cbuf): # <<<<<<<<<<<<<< + * buf = VisionBuf() + * buf.buf = cbuf + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionBuf.create", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_buf); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":38 + * return buf + * + * @property # <<<<<<<<<<<<<< + * def data(self): + * return np.asarray( self.buf.addr) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_4data_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_4data_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_4data___get__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_4data___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + void *__pyx_t_4; + struct __pyx_array_obj *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + int __pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "cereal/visionipc/visionipc_pyx.pyx":40 + * @property + * def data(self): + * return np.asarray( self.buf.addr) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_np); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_asarray); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_4 = __pyx_v_self->buf->addr; + if (!__pyx_t_4) { + PyErr_SetString(PyExc_ValueError,"Cannot create cython.array from NULL pointer"); + __PYX_ERR(0, 40, __pyx_L1_error) + } + __pyx_t_6 = __pyx_format_from_typeinfo(&__Pyx_TypeInfo_nn___pyx_t_5numpy_uint8_t); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_2 = Py_BuildValue((char*) "(" __PYX_BUILD_PY_SSIZE_T ")", ((Py_ssize_t)__pyx_v_self->buf->len)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_5 = __pyx_array_new(__pyx_t_2, sizeof(__pyx_t_5numpy_uint8_t), PyBytes_AS_STRING(__pyx_t_6), (char *) "c", (char *) __pyx_t_4); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 40, __pyx_L1_error) + __Pyx_GOTREF((PyObject *)__pyx_t_5); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __pyx_t_6 = NULL; + __pyx_t_7 = 0; + #if CYTHON_UNPACK_METHODS + if (unlikely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_6 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_6)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_6); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_7 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_6, ((PyObject *)__pyx_t_5)}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_7, 1+__pyx_t_7); + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF((PyObject *)__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":38 + * return buf + * + * @property # <<<<<<<<<<<<<< + * def data(self): + * return np.asarray( self.buf.addr) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF((PyObject *)__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionBuf.data.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":42 + * return np.asarray( self.buf.addr) + * + * @property # <<<<<<<<<<<<<< + * def width(self): + * return self.buf.width + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_5width_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_5width_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_5width___get__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_5width___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "cereal/visionipc/visionipc_pyx.pyx":44 + * @property + * def width(self): + * return self.buf.width # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_FromSize_t(__pyx_v_self->buf->width); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 44, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":42 + * return np.asarray( self.buf.addr) + * + * @property # <<<<<<<<<<<<<< + * def width(self): + * return self.buf.width + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionBuf.width.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":46 + * return self.buf.width + * + * @property # <<<<<<<<<<<<<< + * def height(self): + * return self.buf.height + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_6height_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_6height_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_6height___get__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_6height___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "cereal/visionipc/visionipc_pyx.pyx":48 + * @property + * def height(self): + * return self.buf.height # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_FromSize_t(__pyx_v_self->buf->height); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 48, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":46 + * return self.buf.width + * + * @property # <<<<<<<<<<<<<< + * def height(self): + * return self.buf.height + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionBuf.height.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":50 + * return self.buf.height + * + * @property # <<<<<<<<<<<<<< + * def stride(self): + * return self.buf.stride + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_6stride_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_6stride_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_6stride___get__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_6stride___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "cereal/visionipc/visionipc_pyx.pyx":52 + * @property + * def stride(self): + * return self.buf.stride # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_FromSize_t(__pyx_v_self->buf->stride); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 52, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":50 + * return self.buf.height + * + * @property # <<<<<<<<<<<<<< + * def stride(self): + * return self.buf.stride + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionBuf.stride.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":54 + * return self.buf.stride + * + * @property # <<<<<<<<<<<<<< + * def uv_offset(self): + * return self.buf.uv_offset + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_9uv_offset_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_9uv_offset_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_9uv_offset___get__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_9uv_offset___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "cereal/visionipc/visionipc_pyx.pyx":56 + * @property + * def uv_offset(self): + * return self.buf.uv_offset # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_FromSize_t(__pyx_v_self->buf->uv_offset); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 56, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":54 + * return self.buf.stride + * + * @property # <<<<<<<<<<<<<< + * def uv_offset(self): + * return self.buf.uv_offset + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionBuf.uv_offset.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":58 + * return self.buf.uv_offset + * + * @property # <<<<<<<<<<<<<< + * def rgb(self): + * return self.buf.rgb + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_3rgb_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_3rgb_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_3rgb___get__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_3rgb___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "cereal/visionipc/visionipc_pyx.pyx":60 + * @property + * def rgb(self): + * return self.buf.rgb # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyBool_FromLong(__pyx_v_self->buf->rgb); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 60, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":58 + * return self.buf.uv_offset + * + * @property # <<<<<<<<<<<<<< + * def rgb(self): + * return self.buf.rgb + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionBuf.rgb.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.buf cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_1__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf___reduce_cython__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf___reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "self.buf cannot be converted to a Python object for pickling" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "self.buf cannot be converted to a Python object for pickling" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_self_buf_cannot_be_converted_to, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.buf cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionBuf.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.buf cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.buf cannot be converted to a Python object for pickling" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_3__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionBuf.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_2__setstate_cython__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_2__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "self.buf cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "self.buf cannot be converted to a Python object for pickling" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_self_buf_cannot_be_converted_to, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.buf cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.buf cannot be converted to a Python object for pickling" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionBuf.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":66 + * cdef cppVisionIpcServer * server + * + * def __init__(self, string name): # <<<<<<<<<<<<<< + * self.server = new cppVisionIpcServer(name, NULL, NULL) + * + */ + +/* Python wrapper */ +static int __pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_1__init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_1__init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + std::string __pyx_v_name; + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__init__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_name,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_name)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 66, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__init__") < 0)) __PYX_ERR(0, 66, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + } + __pyx_v_name = __pyx_convert_string_from_py_std__in_string(values[0]); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 66, __pyx_L3_error) + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__init__", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 66, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcServer.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer___init__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *)__pyx_v_self), __PYX_STD_MOVE_IF_SUPPORTED(__pyx_v_name)); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer___init__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *__pyx_v_self, std::string __pyx_v_name) { + int __pyx_r; + + /* "cereal/visionipc/visionipc_pyx.pyx":67 + * + * def __init__(self, string name): + * self.server = new cppVisionIpcServer(name, NULL, NULL) # <<<<<<<<<<<<<< + * + * def create_buffers(self, VisionStreamType tp, size_t num_buffers, bool rgb, size_t width, size_t height): + */ + __pyx_v_self->server = new VisionIpcServer(__pyx_v_name, NULL, NULL); + + /* "cereal/visionipc/visionipc_pyx.pyx":66 + * cdef cppVisionIpcServer * server + * + * def __init__(self, string name): # <<<<<<<<<<<<<< + * self.server = new cppVisionIpcServer(name, NULL, NULL) + * + */ + + /* function exit code */ + __pyx_r = 0; + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":69 + * self.server = new cppVisionIpcServer(name, NULL, NULL) + * + * def create_buffers(self, VisionStreamType tp, size_t num_buffers, bool rgb, size_t width, size_t height): # <<<<<<<<<<<<<< + * self.server.create_buffers(tp, num_buffers, rgb, width, height) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_3create_buffers(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_3create_buffers = {"create_buffers", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_3create_buffers, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_3create_buffers(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType __pyx_v_tp; + size_t __pyx_v_num_buffers; + bool __pyx_v_rgb; + size_t __pyx_v_width; + size_t __pyx_v_height; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[5] = {0,0,0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("create_buffers (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_tp,&__pyx_n_s_num_buffers,&__pyx_n_s_rgb,&__pyx_n_s_width,&__pyx_n_s_height,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 5: values[4] = __Pyx_Arg_FASTCALL(__pyx_args, 4); + CYTHON_FALLTHROUGH; + case 4: values[3] = __Pyx_Arg_FASTCALL(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_tp)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 69, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_num_buffers)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 69, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("create_buffers", 1, 5, 5, 1); __PYX_ERR(0, 69, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_rgb)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 69, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("create_buffers", 1, 5, 5, 2); __PYX_ERR(0, 69, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 3: + if (likely((values[3] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_width)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[3]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 69, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("create_buffers", 1, 5, 5, 3); __PYX_ERR(0, 69, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 4: + if (likely((values[4] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_height)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[4]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 69, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("create_buffers", 1, 5, 5, 4); __PYX_ERR(0, 69, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "create_buffers") < 0)) __PYX_ERR(0, 69, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 5)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + values[3] = __Pyx_Arg_FASTCALL(__pyx_args, 3); + values[4] = __Pyx_Arg_FASTCALL(__pyx_args, 4); + } + __pyx_v_tp = ((enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)__Pyx_PyInt_As_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(values[0])); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 69, __pyx_L3_error) + __pyx_v_num_buffers = __Pyx_PyInt_As_size_t(values[1]); if (unlikely((__pyx_v_num_buffers == (size_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 69, __pyx_L3_error) + __pyx_v_rgb = __Pyx_PyObject_IsTrue(values[2]); if (unlikely((__pyx_v_rgb == ((bool)-1)) && PyErr_Occurred())) __PYX_ERR(0, 69, __pyx_L3_error) + __pyx_v_width = __Pyx_PyInt_As_size_t(values[3]); if (unlikely((__pyx_v_width == (size_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 69, __pyx_L3_error) + __pyx_v_height = __Pyx_PyInt_As_size_t(values[4]); if (unlikely((__pyx_v_height == (size_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 69, __pyx_L3_error) + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("create_buffers", 1, 5, 5, __pyx_nargs); __PYX_ERR(0, 69, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcServer.create_buffers", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_2create_buffers(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *)__pyx_v_self), __pyx_v_tp, __pyx_v_num_buffers, __pyx_v_rgb, __pyx_v_width, __pyx_v_height); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_2create_buffers(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *__pyx_v_self, enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType __pyx_v_tp, size_t __pyx_v_num_buffers, bool __pyx_v_rgb, size_t __pyx_v_width, size_t __pyx_v_height) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("create_buffers", 1); + + /* "cereal/visionipc/visionipc_pyx.pyx":70 + * + * def create_buffers(self, VisionStreamType tp, size_t num_buffers, bool rgb, size_t width, size_t height): + * self.server.create_buffers(tp, num_buffers, rgb, width, height) # <<<<<<<<<<<<<< + * + * def create_buffers_with_sizes(self, VisionStreamType tp, size_t num_buffers, bool rgb, size_t width, size_t height, size_t size, size_t stride, size_t uv_offset): + */ + __pyx_v_self->server->create_buffers(((enum VisionStreamType)__pyx_v_tp), __pyx_v_num_buffers, __pyx_v_rgb, __pyx_v_width, __pyx_v_height); + + /* "cereal/visionipc/visionipc_pyx.pyx":69 + * self.server = new cppVisionIpcServer(name, NULL, NULL) + * + * def create_buffers(self, VisionStreamType tp, size_t num_buffers, bool rgb, size_t width, size_t height): # <<<<<<<<<<<<<< + * self.server.create_buffers(tp, num_buffers, rgb, width, height) + * + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":72 + * self.server.create_buffers(tp, num_buffers, rgb, width, height) + * + * def create_buffers_with_sizes(self, VisionStreamType tp, size_t num_buffers, bool rgb, size_t width, size_t height, size_t size, size_t stride, size_t uv_offset): # <<<<<<<<<<<<<< + * self.server.create_buffers_with_sizes(tp, num_buffers, rgb, width, height, size, stride, uv_offset) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_5create_buffers_with_sizes(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_5create_buffers_with_sizes = {"create_buffers_with_sizes", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_5create_buffers_with_sizes, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_5create_buffers_with_sizes(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType __pyx_v_tp; + size_t __pyx_v_num_buffers; + bool __pyx_v_rgb; + size_t __pyx_v_width; + size_t __pyx_v_height; + size_t __pyx_v_size; + size_t __pyx_v_stride; + size_t __pyx_v_uv_offset; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[8] = {0,0,0,0,0,0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("create_buffers_with_sizes (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_tp,&__pyx_n_s_num_buffers,&__pyx_n_s_rgb,&__pyx_n_s_width,&__pyx_n_s_height,&__pyx_n_s_size,&__pyx_n_s_stride,&__pyx_n_s_uv_offset,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 8: values[7] = __Pyx_Arg_FASTCALL(__pyx_args, 7); + CYTHON_FALLTHROUGH; + case 7: values[6] = __Pyx_Arg_FASTCALL(__pyx_args, 6); + CYTHON_FALLTHROUGH; + case 6: values[5] = __Pyx_Arg_FASTCALL(__pyx_args, 5); + CYTHON_FALLTHROUGH; + case 5: values[4] = __Pyx_Arg_FASTCALL(__pyx_args, 4); + CYTHON_FALLTHROUGH; + case 4: values[3] = __Pyx_Arg_FASTCALL(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_tp)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 72, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_num_buffers)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 72, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("create_buffers_with_sizes", 1, 8, 8, 1); __PYX_ERR(0, 72, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_rgb)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 72, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("create_buffers_with_sizes", 1, 8, 8, 2); __PYX_ERR(0, 72, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 3: + if (likely((values[3] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_width)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[3]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 72, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("create_buffers_with_sizes", 1, 8, 8, 3); __PYX_ERR(0, 72, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 4: + if (likely((values[4] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_height)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[4]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 72, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("create_buffers_with_sizes", 1, 8, 8, 4); __PYX_ERR(0, 72, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 5: + if (likely((values[5] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_size)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[5]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 72, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("create_buffers_with_sizes", 1, 8, 8, 5); __PYX_ERR(0, 72, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 6: + if (likely((values[6] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stride)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[6]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 72, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("create_buffers_with_sizes", 1, 8, 8, 6); __PYX_ERR(0, 72, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 7: + if (likely((values[7] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_uv_offset)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[7]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 72, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("create_buffers_with_sizes", 1, 8, 8, 7); __PYX_ERR(0, 72, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "create_buffers_with_sizes") < 0)) __PYX_ERR(0, 72, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 8)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + values[3] = __Pyx_Arg_FASTCALL(__pyx_args, 3); + values[4] = __Pyx_Arg_FASTCALL(__pyx_args, 4); + values[5] = __Pyx_Arg_FASTCALL(__pyx_args, 5); + values[6] = __Pyx_Arg_FASTCALL(__pyx_args, 6); + values[7] = __Pyx_Arg_FASTCALL(__pyx_args, 7); + } + __pyx_v_tp = ((enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)__Pyx_PyInt_As_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(values[0])); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 72, __pyx_L3_error) + __pyx_v_num_buffers = __Pyx_PyInt_As_size_t(values[1]); if (unlikely((__pyx_v_num_buffers == (size_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 72, __pyx_L3_error) + __pyx_v_rgb = __Pyx_PyObject_IsTrue(values[2]); if (unlikely((__pyx_v_rgb == ((bool)-1)) && PyErr_Occurred())) __PYX_ERR(0, 72, __pyx_L3_error) + __pyx_v_width = __Pyx_PyInt_As_size_t(values[3]); if (unlikely((__pyx_v_width == (size_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 72, __pyx_L3_error) + __pyx_v_height = __Pyx_PyInt_As_size_t(values[4]); if (unlikely((__pyx_v_height == (size_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 72, __pyx_L3_error) + __pyx_v_size = __Pyx_PyInt_As_size_t(values[5]); if (unlikely((__pyx_v_size == (size_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 72, __pyx_L3_error) + __pyx_v_stride = __Pyx_PyInt_As_size_t(values[6]); if (unlikely((__pyx_v_stride == (size_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 72, __pyx_L3_error) + __pyx_v_uv_offset = __Pyx_PyInt_As_size_t(values[7]); if (unlikely((__pyx_v_uv_offset == (size_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 72, __pyx_L3_error) + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("create_buffers_with_sizes", 1, 8, 8, __pyx_nargs); __PYX_ERR(0, 72, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcServer.create_buffers_with_sizes", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_4create_buffers_with_sizes(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *)__pyx_v_self), __pyx_v_tp, __pyx_v_num_buffers, __pyx_v_rgb, __pyx_v_width, __pyx_v_height, __pyx_v_size, __pyx_v_stride, __pyx_v_uv_offset); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_4create_buffers_with_sizes(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *__pyx_v_self, enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType __pyx_v_tp, size_t __pyx_v_num_buffers, bool __pyx_v_rgb, size_t __pyx_v_width, size_t __pyx_v_height, size_t __pyx_v_size, size_t __pyx_v_stride, size_t __pyx_v_uv_offset) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("create_buffers_with_sizes", 1); + + /* "cereal/visionipc/visionipc_pyx.pyx":73 + * + * def create_buffers_with_sizes(self, VisionStreamType tp, size_t num_buffers, bool rgb, size_t width, size_t height, size_t size, size_t stride, size_t uv_offset): + * self.server.create_buffers_with_sizes(tp, num_buffers, rgb, width, height, size, stride, uv_offset) # <<<<<<<<<<<<<< + * + * def send(self, VisionStreamType tp, const unsigned char[:] data, uint32_t frame_id=0, uint64_t timestamp_sof=0, uint64_t timestamp_eof=0): + */ + __pyx_v_self->server->create_buffers_with_sizes(((enum VisionStreamType)__pyx_v_tp), __pyx_v_num_buffers, __pyx_v_rgb, __pyx_v_width, __pyx_v_height, __pyx_v_size, __pyx_v_stride, __pyx_v_uv_offset); + + /* "cereal/visionipc/visionipc_pyx.pyx":72 + * self.server.create_buffers(tp, num_buffers, rgb, width, height) + * + * def create_buffers_with_sizes(self, VisionStreamType tp, size_t num_buffers, bool rgb, size_t width, size_t height, size_t size, size_t stride, size_t uv_offset): # <<<<<<<<<<<<<< + * self.server.create_buffers_with_sizes(tp, num_buffers, rgb, width, height, size, stride, uv_offset) + * + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":75 + * self.server.create_buffers_with_sizes(tp, num_buffers, rgb, width, height, size, stride, uv_offset) + * + * def send(self, VisionStreamType tp, const unsigned char[:] data, uint32_t frame_id=0, uint64_t timestamp_sof=0, uint64_t timestamp_eof=0): # <<<<<<<<<<<<<< + * cdef cppVisionBuf * buf = self.server.get_buffer(tp) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_7send(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_7send = {"send", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_7send, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_7send(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType __pyx_v_tp; + __Pyx_memviewslice __pyx_v_data = { 0, 0, { 0 }, { 0 }, { 0 } }; + uint32_t __pyx_v_frame_id; + uint64_t __pyx_v_timestamp_sof; + uint64_t __pyx_v_timestamp_eof; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[5] = {0,0,0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("send (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_tp,&__pyx_n_s_data,&__pyx_n_s_frame_id,&__pyx_n_s_timestamp_sof,&__pyx_n_s_timestamp_eof,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 5: values[4] = __Pyx_Arg_FASTCALL(__pyx_args, 4); + CYTHON_FALLTHROUGH; + case 4: values[3] = __Pyx_Arg_FASTCALL(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_tp)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 75, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_data)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 75, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("send", 0, 2, 5, 1); __PYX_ERR(0, 75, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_frame_id); + if (value) { values[2] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 75, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 3: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_timestamp_sof); + if (value) { values[3] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 75, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 4: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_timestamp_eof); + if (value) { values[4] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 75, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "send") < 0)) __PYX_ERR(0, 75, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 5: values[4] = __Pyx_Arg_FASTCALL(__pyx_args, 4); + CYTHON_FALLTHROUGH; + case 4: values[3] = __Pyx_Arg_FASTCALL(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_tp = ((enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)__Pyx_PyInt_As_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(values[0])); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 75, __pyx_L3_error) + __pyx_v_data = __Pyx_PyObject_to_MemoryviewSlice_ds_unsigned_char__const__(values[1], 0); if (unlikely(!__pyx_v_data.memview)) __PYX_ERR(0, 75, __pyx_L3_error) + if (values[2]) { + __pyx_v_frame_id = __Pyx_PyInt_As_uint32_t(values[2]); if (unlikely((__pyx_v_frame_id == ((uint32_t)-1)) && PyErr_Occurred())) __PYX_ERR(0, 75, __pyx_L3_error) + } else { + __pyx_v_frame_id = ((uint32_t)0); + } + if (values[3]) { + __pyx_v_timestamp_sof = __Pyx_PyInt_As_uint64_t(values[3]); if (unlikely((__pyx_v_timestamp_sof == ((uint64_t)-1)) && PyErr_Occurred())) __PYX_ERR(0, 75, __pyx_L3_error) + } else { + __pyx_v_timestamp_sof = ((uint64_t)0); + } + if (values[4]) { + __pyx_v_timestamp_eof = __Pyx_PyInt_As_uint64_t(values[4]); if (unlikely((__pyx_v_timestamp_eof == ((uint64_t)-1)) && PyErr_Occurred())) __PYX_ERR(0, 75, __pyx_L3_error) + } else { + __pyx_v_timestamp_eof = ((uint64_t)0); + } + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("send", 0, 2, 5, __pyx_nargs); __PYX_ERR(0, 75, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __PYX_XCLEAR_MEMVIEW(&__pyx_v_data, 1); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcServer.send", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_6send(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *)__pyx_v_self), __pyx_v_tp, __pyx_v_data, __pyx_v_frame_id, __pyx_v_timestamp_sof, __pyx_v_timestamp_eof); + + /* function exit code */ + __PYX_XCLEAR_MEMVIEW(&__pyx_v_data, 1); + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_6send(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *__pyx_v_self, enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType __pyx_v_tp, __Pyx_memviewslice __pyx_v_data, uint32_t __pyx_v_frame_id, uint64_t __pyx_v_timestamp_sof, uint64_t __pyx_v_timestamp_eof) { + VisionBuf *__pyx_v_buf; + struct VisionIpcBufExtra __pyx_v_extra; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("send", 1); + + /* "cereal/visionipc/visionipc_pyx.pyx":76 + * + * def send(self, VisionStreamType tp, const unsigned char[:] data, uint32_t frame_id=0, uint64_t timestamp_sof=0, uint64_t timestamp_eof=0): + * cdef cppVisionBuf * buf = self.server.get_buffer(tp) # <<<<<<<<<<<<<< + * + * # Populate buffer + */ + __pyx_v_buf = __pyx_v_self->server->get_buffer(((enum VisionStreamType)__pyx_v_tp)); + + /* "cereal/visionipc/visionipc_pyx.pyx":79 + * + * # Populate buffer + * assert buf.len == len(data) # <<<<<<<<<<<<<< + * memcpy(buf.addr, &data[0], len(data)) + * buf.set_frame_id(frame_id) + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_1 = __Pyx_MemoryView_Len(__pyx_v_data); + __pyx_t_2 = (__pyx_v_buf->len == __pyx_t_1); + if (unlikely(!__pyx_t_2)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(0, 79, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(0, 79, __pyx_L1_error) + #endif + + /* "cereal/visionipc/visionipc_pyx.pyx":80 + * # Populate buffer + * assert buf.len == len(data) + * memcpy(buf.addr, &data[0], len(data)) # <<<<<<<<<<<<<< + * buf.set_frame_id(frame_id) + * + */ + __pyx_t_3 = 0; + __pyx_t_4 = -1; + if (__pyx_t_3 < 0) { + __pyx_t_3 += __pyx_v_data.shape[0]; + if (unlikely(__pyx_t_3 < 0)) __pyx_t_4 = 0; + } else if (unlikely(__pyx_t_3 >= __pyx_v_data.shape[0])) __pyx_t_4 = 0; + if (unlikely(__pyx_t_4 != -1)) { + __Pyx_RaiseBufferIndexError(__pyx_t_4); + __PYX_ERR(0, 80, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_MemoryView_Len(__pyx_v_data); + (void)(memcpy(__pyx_v_buf->addr, (&(*((unsigned char const *) ( /* dim=0 */ (__pyx_v_data.data + __pyx_t_3 * __pyx_v_data.strides[0]) )))), __pyx_t_1)); + + /* "cereal/visionipc/visionipc_pyx.pyx":81 + * assert buf.len == len(data) + * memcpy(buf.addr, &data[0], len(data)) + * buf.set_frame_id(frame_id) # <<<<<<<<<<<<<< + * + * cdef VisionIpcBufExtra extra + */ + __pyx_v_buf->set_frame_id(__pyx_v_frame_id); + + /* "cereal/visionipc/visionipc_pyx.pyx":84 + * + * cdef VisionIpcBufExtra extra + * extra.frame_id = frame_id # <<<<<<<<<<<<<< + * extra.timestamp_sof = timestamp_sof + * extra.timestamp_eof = timestamp_eof + */ + __pyx_v_extra.frame_id = __pyx_v_frame_id; + + /* "cereal/visionipc/visionipc_pyx.pyx":85 + * cdef VisionIpcBufExtra extra + * extra.frame_id = frame_id + * extra.timestamp_sof = timestamp_sof # <<<<<<<<<<<<<< + * extra.timestamp_eof = timestamp_eof + * + */ + __pyx_v_extra.timestamp_sof = __pyx_v_timestamp_sof; + + /* "cereal/visionipc/visionipc_pyx.pyx":86 + * extra.frame_id = frame_id + * extra.timestamp_sof = timestamp_sof + * extra.timestamp_eof = timestamp_eof # <<<<<<<<<<<<<< + * + * self.server.send(buf, &extra, False) + */ + __pyx_v_extra.timestamp_eof = __pyx_v_timestamp_eof; + + /* "cereal/visionipc/visionipc_pyx.pyx":88 + * extra.timestamp_eof = timestamp_eof + * + * self.server.send(buf, &extra, False) # <<<<<<<<<<<<<< + * + * def start_listener(self): + */ + __pyx_v_self->server->send(__pyx_v_buf, (&__pyx_v_extra), 0); + + /* "cereal/visionipc/visionipc_pyx.pyx":75 + * self.server.create_buffers_with_sizes(tp, num_buffers, rgb, width, height, size, stride, uv_offset) + * + * def send(self, VisionStreamType tp, const unsigned char[:] data, uint32_t frame_id=0, uint64_t timestamp_sof=0, uint64_t timestamp_eof=0): # <<<<<<<<<<<<<< + * cdef cppVisionBuf * buf = self.server.get_buffer(tp) + * + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcServer.send", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":90 + * self.server.send(buf, &extra, False) + * + * def start_listener(self): # <<<<<<<<<<<<<< + * self.server.start_listener() + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_9start_listener(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_9start_listener = {"start_listener", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_9start_listener, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_9start_listener(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("start_listener (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("start_listener", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "start_listener", 0))) return NULL; + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_8start_listener(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_8start_listener(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("start_listener", 1); + + /* "cereal/visionipc/visionipc_pyx.pyx":91 + * + * def start_listener(self): + * self.server.start_listener() # <<<<<<<<<<<<<< + * + * def __dealloc__(self): + */ + __pyx_v_self->server->start_listener(); + + /* "cereal/visionipc/visionipc_pyx.pyx":90 + * self.server.send(buf, &extra, False) + * + * def start_listener(self): # <<<<<<<<<<<<<< + * self.server.start_listener() + * + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":93 + * self.server.start_listener() + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * del self.server + * + */ + +/* Python wrapper */ +static void __pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_11__dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_11__dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_10__dealloc__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_10__dealloc__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *__pyx_v_self) { + + /* "cereal/visionipc/visionipc_pyx.pyx":94 + * + * def __dealloc__(self): + * del self.server # <<<<<<<<<<<<<< + * + * + */ + delete __pyx_v_self->server; + + /* "cereal/visionipc/visionipc_pyx.pyx":93 + * self.server.start_listener() + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * del self.server + * + */ + + /* function exit code */ +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.server cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_13__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_13__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_13__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_13__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_12__reduce_cython__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_12__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "self.server cannot be converted to a Python object for pickling" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "self.server cannot be converted to a Python object for pickling" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_self_server_cannot_be_converted, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.server cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcServer.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.server cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.server cannot be converted to a Python object for pickling" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_15__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_15__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_15__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_15__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcServer.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_14__setstate_cython__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_14__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "self.server cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "self.server cannot be converted to a Python object for pickling" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_self_server_cannot_be_converted, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.server cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.server cannot be converted to a Python object for pickling" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcServer.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":101 + * cdef VisionIpcBufExtra extra + * + * def __cinit__(self, string name, VisionStreamType stream, bool conflate, CLContext context = None): # <<<<<<<<<<<<<< + * if context: + * self.client = new cppVisionIpcClient(name, stream, conflate, context.device_id, context.context) + */ + +/* Python wrapper */ +static int __pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + std::string __pyx_v_name; + enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType __pyx_v_stream; + bool __pyx_v_conflate; + struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_CLContext *__pyx_v_context = 0; + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[4] = {0,0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_name,&__pyx_n_s_stream,&__pyx_n_s_conflate,&__pyx_n_s_context,0}; + values[3] = __Pyx_Arg_NewRef_VARARGS((PyObject *)((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_CLContext *)Py_None)); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 4: values[3] = __Pyx_Arg_VARARGS(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_name)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 101, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stream)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 101, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 3, 4, 1); __PYX_ERR(0, 101, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_conflate)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 101, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 3, 4, 2); __PYX_ERR(0, 101, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 3: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_context); + if (value) { values[3] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 101, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(0, 101, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 4: values[3] = __Pyx_Arg_VARARGS(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_name = __pyx_convert_string_from_py_std__in_string(values[0]); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 101, __pyx_L3_error) + __pyx_v_stream = ((enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)__Pyx_PyInt_As_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(values[1])); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 101, __pyx_L3_error) + __pyx_v_conflate = __Pyx_PyObject_IsTrue(values[2]); if (unlikely((__pyx_v_conflate == ((bool)-1)) && PyErr_Occurred())) __PYX_ERR(0, 101, __pyx_L3_error) + __pyx_v_context = ((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_CLContext *)values[3]); + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 3, 4, __pyx_nargs); __PYX_ERR(0, 101, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_context), __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext, 1, "context", 0))) __PYX_ERR(0, 101, __pyx_L1_error) + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient___cinit__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *)__pyx_v_self), __PYX_STD_MOVE_IF_SUPPORTED(__pyx_v_name), __pyx_v_stream, __pyx_v_conflate, __pyx_v_context); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = -1; + __pyx_L0:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient___cinit__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self, std::string __pyx_v_name, enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType __pyx_v_stream, bool __pyx_v_conflate, struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_CLContext *__pyx_v_context) { + int __pyx_r; + int __pyx_t_1; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + + /* "cereal/visionipc/visionipc_pyx.pyx":102 + * + * def __cinit__(self, string name, VisionStreamType stream, bool conflate, CLContext context = None): + * if context: # <<<<<<<<<<<<<< + * self.client = new cppVisionIpcClient(name, stream, conflate, context.device_id, context.context) + * else: + */ + __pyx_t_1 = __Pyx_PyObject_IsTrue(((PyObject *)__pyx_v_context)); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(0, 102, __pyx_L1_error) + if (__pyx_t_1) { + + /* "cereal/visionipc/visionipc_pyx.pyx":103 + * def __cinit__(self, string name, VisionStreamType stream, bool conflate, CLContext context = None): + * if context: + * self.client = new cppVisionIpcClient(name, stream, conflate, context.device_id, context.context) # <<<<<<<<<<<<<< + * else: + * self.client = new cppVisionIpcClient(name, stream, conflate, NULL, NULL) + */ + __pyx_v_self->client = new VisionIpcClient(__pyx_v_name, ((enum VisionStreamType)__pyx_v_stream), __pyx_v_conflate, __pyx_v_context->device_id, __pyx_v_context->context); + + /* "cereal/visionipc/visionipc_pyx.pyx":102 + * + * def __cinit__(self, string name, VisionStreamType stream, bool conflate, CLContext context = None): + * if context: # <<<<<<<<<<<<<< + * self.client = new cppVisionIpcClient(name, stream, conflate, context.device_id, context.context) + * else: + */ + goto __pyx_L3; + } + + /* "cereal/visionipc/visionipc_pyx.pyx":105 + * self.client = new cppVisionIpcClient(name, stream, conflate, context.device_id, context.context) + * else: + * self.client = new cppVisionIpcClient(name, stream, conflate, NULL, NULL) # <<<<<<<<<<<<<< + * + * def __dealloc__(self): + */ + /*else*/ { + __pyx_v_self->client = new VisionIpcClient(__pyx_v_name, ((enum VisionStreamType)__pyx_v_stream), __pyx_v_conflate, NULL, NULL); + } + __pyx_L3:; + + /* "cereal/visionipc/visionipc_pyx.pyx":101 + * cdef VisionIpcBufExtra extra + * + * def __cinit__(self, string name, VisionStreamType stream, bool conflate, CLContext context = None): # <<<<<<<<<<<<<< + * if context: + * self.client = new cppVisionIpcClient(name, stream, conflate, context.device_id, context.context) + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":107 + * self.client = new cppVisionIpcClient(name, stream, conflate, NULL, NULL) + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * del self.client + * + */ + +/* Python wrapper */ +static void __pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_3__dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_3__dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_2__dealloc__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_2__dealloc__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self) { + + /* "cereal/visionipc/visionipc_pyx.pyx":108 + * + * def __dealloc__(self): + * del self.client # <<<<<<<<<<<<<< + * + * @property + */ + delete __pyx_v_self->client; + + /* "cereal/visionipc/visionipc_pyx.pyx":107 + * self.client = new cppVisionIpcClient(name, stream, conflate, NULL, NULL) + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * del self.client + * + */ + + /* function exit code */ +} + +/* "cereal/visionipc/visionipc_pyx.pyx":110 + * del self.client + * + * @property # <<<<<<<<<<<<<< + * def width(self): + * return self.client.buffers[0].width if self.client.num_buffers else None + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_5width_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_5width_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_5width___get__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_5width___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "cereal/visionipc/visionipc_pyx.pyx":112 + * @property + * def width(self): + * return self.client.buffers[0].width if self.client.num_buffers else None # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = (__pyx_v_self->client->num_buffers != 0); + if (__pyx_t_2) { + __pyx_t_3 = __Pyx_PyInt_FromSize_t((__pyx_v_self->client->buffers[0]).width); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 112, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = __pyx_t_3; + __pyx_t_3 = 0; + } else { + __Pyx_INCREF(Py_None); + __pyx_t_1 = Py_None; + } + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":110 + * del self.client + * + * @property # <<<<<<<<<<<<<< + * def width(self): + * return self.client.buffers[0].width if self.client.num_buffers else None + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.width.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":114 + * return self.client.buffers[0].width if self.client.num_buffers else None + * + * @property # <<<<<<<<<<<<<< + * def height(self): + * return self.client.buffers[0].height if self.client.num_buffers else None + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_6height_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_6height_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_6height___get__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_6height___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "cereal/visionipc/visionipc_pyx.pyx":116 + * @property + * def height(self): + * return self.client.buffers[0].height if self.client.num_buffers else None # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = (__pyx_v_self->client->num_buffers != 0); + if (__pyx_t_2) { + __pyx_t_3 = __Pyx_PyInt_FromSize_t((__pyx_v_self->client->buffers[0]).height); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 116, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = __pyx_t_3; + __pyx_t_3 = 0; + } else { + __Pyx_INCREF(Py_None); + __pyx_t_1 = Py_None; + } + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":114 + * return self.client.buffers[0].width if self.client.num_buffers else None + * + * @property # <<<<<<<<<<<<<< + * def height(self): + * return self.client.buffers[0].height if self.client.num_buffers else None + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.height.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":118 + * return self.client.buffers[0].height if self.client.num_buffers else None + * + * @property # <<<<<<<<<<<<<< + * def stride(self): + * return self.client.buffers[0].stride if self.client.num_buffers else None + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_6stride_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_6stride_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_6stride___get__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_6stride___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "cereal/visionipc/visionipc_pyx.pyx":120 + * @property + * def stride(self): + * return self.client.buffers[0].stride if self.client.num_buffers else None # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = (__pyx_v_self->client->num_buffers != 0); + if (__pyx_t_2) { + __pyx_t_3 = __Pyx_PyInt_FromSize_t((__pyx_v_self->client->buffers[0]).stride); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 120, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = __pyx_t_3; + __pyx_t_3 = 0; + } else { + __Pyx_INCREF(Py_None); + __pyx_t_1 = Py_None; + } + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":118 + * return self.client.buffers[0].height if self.client.num_buffers else None + * + * @property # <<<<<<<<<<<<<< + * def stride(self): + * return self.client.buffers[0].stride if self.client.num_buffers else None + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.stride.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":122 + * return self.client.buffers[0].stride if self.client.num_buffers else None + * + * @property # <<<<<<<<<<<<<< + * def uv_offset(self): + * return self.client.buffers[0].uv_offset if self.client.num_buffers else None + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_9uv_offset_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_9uv_offset_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_9uv_offset___get__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_9uv_offset___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "cereal/visionipc/visionipc_pyx.pyx":124 + * @property + * def uv_offset(self): + * return self.client.buffers[0].uv_offset if self.client.num_buffers else None # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = (__pyx_v_self->client->num_buffers != 0); + if (__pyx_t_2) { + __pyx_t_3 = __Pyx_PyInt_FromSize_t((__pyx_v_self->client->buffers[0]).uv_offset); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 124, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = __pyx_t_3; + __pyx_t_3 = 0; + } else { + __Pyx_INCREF(Py_None); + __pyx_t_1 = Py_None; + } + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":122 + * return self.client.buffers[0].stride if self.client.num_buffers else None + * + * @property # <<<<<<<<<<<<<< + * def uv_offset(self): + * return self.client.buffers[0].uv_offset if self.client.num_buffers else None + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.uv_offset.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":126 + * return self.client.buffers[0].uv_offset if self.client.num_buffers else None + * + * @property # <<<<<<<<<<<<<< + * def rgb(self): + * return self.client.buffers[0].rgb if self.client.num_buffers else None + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_3rgb_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_3rgb_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_3rgb___get__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_3rgb___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "cereal/visionipc/visionipc_pyx.pyx":128 + * @property + * def rgb(self): + * return self.client.buffers[0].rgb if self.client.num_buffers else None # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = (__pyx_v_self->client->num_buffers != 0); + if (__pyx_t_2) { + __pyx_t_3 = __Pyx_PyBool_FromLong((__pyx_v_self->client->buffers[0]).rgb); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 128, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = __pyx_t_3; + __pyx_t_3 = 0; + } else { + __Pyx_INCREF(Py_None); + __pyx_t_1 = Py_None; + } + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":126 + * return self.client.buffers[0].uv_offset if self.client.num_buffers else None + * + * @property # <<<<<<<<<<<<<< + * def rgb(self): + * return self.client.buffers[0].rgb if self.client.num_buffers else None + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.rgb.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":130 + * return self.client.buffers[0].rgb if self.client.num_buffers else None + * + * @property # <<<<<<<<<<<<<< + * def buffer_len(self): + * return self.client.buffers[0].len if self.client.num_buffers else None + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_10buffer_len_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_10buffer_len_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_10buffer_len___get__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_10buffer_len___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "cereal/visionipc/visionipc_pyx.pyx":132 + * @property + * def buffer_len(self): + * return self.client.buffers[0].len if self.client.num_buffers else None # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = (__pyx_v_self->client->num_buffers != 0); + if (__pyx_t_2) { + __pyx_t_3 = __Pyx_PyInt_FromSize_t((__pyx_v_self->client->buffers[0]).len); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 132, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = __pyx_t_3; + __pyx_t_3 = 0; + } else { + __Pyx_INCREF(Py_None); + __pyx_t_1 = Py_None; + } + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":130 + * return self.client.buffers[0].rgb if self.client.num_buffers else None + * + * @property # <<<<<<<<<<<<<< + * def buffer_len(self): + * return self.client.buffers[0].len if self.client.num_buffers else None + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.buffer_len.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":134 + * return self.client.buffers[0].len if self.client.num_buffers else None + * + * @property # <<<<<<<<<<<<<< + * def num_buffers(self): + * return self.client.num_buffers + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_11num_buffers_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_11num_buffers_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_11num_buffers___get__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_11num_buffers___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "cereal/visionipc/visionipc_pyx.pyx":136 + * @property + * def num_buffers(self): + * return self.client.num_buffers # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_self->client->num_buffers); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 136, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":134 + * return self.client.buffers[0].len if self.client.num_buffers else None + * + * @property # <<<<<<<<<<<<<< + * def num_buffers(self): + * return self.client.num_buffers + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.num_buffers.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":138 + * return self.client.num_buffers + * + * @property # <<<<<<<<<<<<<< + * def frame_id(self): + * return self.extra.frame_id + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_8frame_id_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_8frame_id_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_8frame_id___get__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_8frame_id___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "cereal/visionipc/visionipc_pyx.pyx":140 + * @property + * def frame_id(self): + * return self.extra.frame_id # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_uint32_t(__pyx_v_self->extra.frame_id); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 140, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":138 + * return self.client.num_buffers + * + * @property # <<<<<<<<<<<<<< + * def frame_id(self): + * return self.extra.frame_id + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.frame_id.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":142 + * return self.extra.frame_id + * + * @property # <<<<<<<<<<<<<< + * def timestamp_sof(self): + * return self.extra.timestamp_sof + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_13timestamp_sof_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_13timestamp_sof_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_13timestamp_sof___get__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_13timestamp_sof___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "cereal/visionipc/visionipc_pyx.pyx":144 + * @property + * def timestamp_sof(self): + * return self.extra.timestamp_sof # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_uint64_t(__pyx_v_self->extra.timestamp_sof); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 144, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":142 + * return self.extra.frame_id + * + * @property # <<<<<<<<<<<<<< + * def timestamp_sof(self): + * return self.extra.timestamp_sof + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.timestamp_sof.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":146 + * return self.extra.timestamp_sof + * + * @property # <<<<<<<<<<<<<< + * def timestamp_eof(self): + * return self.extra.timestamp_eof + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_13timestamp_eof_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_13timestamp_eof_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_13timestamp_eof___get__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_13timestamp_eof___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "cereal/visionipc/visionipc_pyx.pyx":148 + * @property + * def timestamp_eof(self): + * return self.extra.timestamp_eof # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_uint64_t(__pyx_v_self->extra.timestamp_eof); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 148, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":146 + * return self.extra.timestamp_sof + * + * @property # <<<<<<<<<<<<<< + * def timestamp_eof(self): + * return self.extra.timestamp_eof + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.timestamp_eof.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":150 + * return self.extra.timestamp_eof + * + * @property # <<<<<<<<<<<<<< + * def valid(self): + * return self.extra.valid + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_5valid_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_5valid_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_5valid___get__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_5valid___get__(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "cereal/visionipc/visionipc_pyx.pyx":152 + * @property + * def valid(self): + * return self.extra.valid # <<<<<<<<<<<<<< + * + * def recv(self, int timeout_ms=100): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyBool_FromLong(__pyx_v_self->extra.valid); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 152, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":150 + * return self.extra.timestamp_eof + * + * @property # <<<<<<<<<<<<<< + * def valid(self): + * return self.extra.valid + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.valid.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":154 + * return self.extra.valid + * + * def recv(self, int timeout_ms=100): # <<<<<<<<<<<<<< + * buf = self.client.recv(&self.extra, timeout_ms) + * if not buf: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_5recv(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_5recv = {"recv", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_5recv, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_5recv(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + int __pyx_v_timeout_ms; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("recv (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_timeout_ms,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_timeout_ms); + if (value) { values[0] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 154, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "recv") < 0)) __PYX_ERR(0, 154, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + } + if (values[0]) { + __pyx_v_timeout_ms = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_timeout_ms == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 154, __pyx_L3_error) + } else { + __pyx_v_timeout_ms = ((int)0x64); + } + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("recv", 0, 0, 1, __pyx_nargs); __PYX_ERR(0, 154, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.recv", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_4recv(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *)__pyx_v_self), __pyx_v_timeout_ms); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_4recv(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self, int __pyx_v_timeout_ms) { + VisionBuf *__pyx_v_buf; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("recv", 1); + + /* "cereal/visionipc/visionipc_pyx.pyx":155 + * + * def recv(self, int timeout_ms=100): + * buf = self.client.recv(&self.extra, timeout_ms) # <<<<<<<<<<<<<< + * if not buf: + * return None + */ + __pyx_v_buf = __pyx_v_self->client->recv((&__pyx_v_self->extra), __pyx_v_timeout_ms); + + /* "cereal/visionipc/visionipc_pyx.pyx":156 + * def recv(self, int timeout_ms=100): + * buf = self.client.recv(&self.extra, timeout_ms) + * if not buf: # <<<<<<<<<<<<<< + * return None + * return VisionBuf.create(buf) + */ + __pyx_t_1 = (!(__pyx_v_buf != 0)); + if (__pyx_t_1) { + + /* "cereal/visionipc/visionipc_pyx.pyx":157 + * buf = self.client.recv(&self.extra, timeout_ms) + * if not buf: + * return None # <<<<<<<<<<<<<< + * return VisionBuf.create(buf) + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":156 + * def recv(self, int timeout_ms=100): + * buf = self.client.recv(&self.extra, timeout_ms) + * if not buf: # <<<<<<<<<<<<<< + * return None + * return VisionBuf.create(buf) + */ + } + + /* "cereal/visionipc/visionipc_pyx.pyx":158 + * if not buf: + * return None + * return VisionBuf.create(buf) # <<<<<<<<<<<<<< + * + * def connect(self, bool blocking): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_f_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_create(__pyx_v_buf); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 158, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":154 + * return self.extra.valid + * + * def recv(self, int timeout_ms=100): # <<<<<<<<<<<<<< + * buf = self.client.recv(&self.extra, timeout_ms) + * if not buf: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.recv", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":160 + * return VisionBuf.create(buf) + * + * def connect(self, bool blocking): # <<<<<<<<<<<<<< + * return self.client.connect(blocking) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_7connect(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_7connect = {"connect", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_7connect, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_7connect(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + bool __pyx_v_blocking; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("connect (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_blocking,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_blocking)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 160, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "connect") < 0)) __PYX_ERR(0, 160, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_blocking = __Pyx_PyObject_IsTrue(values[0]); if (unlikely((__pyx_v_blocking == ((bool)-1)) && PyErr_Occurred())) __PYX_ERR(0, 160, __pyx_L3_error) + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("connect", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 160, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.connect", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_6connect(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *)__pyx_v_self), __pyx_v_blocking); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_6connect(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self, bool __pyx_v_blocking) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("connect", 1); + + /* "cereal/visionipc/visionipc_pyx.pyx":161 + * + * def connect(self, bool blocking): + * return self.client.connect(blocking) # <<<<<<<<<<<<<< + * + * def is_connected(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyBool_FromLong(__pyx_v_self->client->connect(__pyx_v_blocking)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":160 + * return VisionBuf.create(buf) + * + * def connect(self, bool blocking): # <<<<<<<<<<<<<< + * return self.client.connect(blocking) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.connect", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":163 + * return self.client.connect(blocking) + * + * def is_connected(self): # <<<<<<<<<<<<<< + * return self.client.is_connected() + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_9is_connected(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_9is_connected = {"is_connected", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_9is_connected, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_9is_connected(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("is_connected (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("is_connected", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "is_connected", 0))) return NULL; + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_8is_connected(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_8is_connected(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("is_connected", 1); + + /* "cereal/visionipc/visionipc_pyx.pyx":164 + * + * def is_connected(self): + * return self.client.is_connected() # <<<<<<<<<<<<<< + * + * @staticmethod + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyBool_FromLong(__pyx_v_self->client->is_connected()); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 164, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":163 + * return self.client.connect(blocking) + * + * def is_connected(self): # <<<<<<<<<<<<<< + * return self.client.is_connected() + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.is_connected", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "cereal/visionipc/visionipc_pyx.pyx":166 + * return self.client.is_connected() + * + * @staticmethod # <<<<<<<<<<<<<< + * def available_streams(string name, bool block): + * return cppVisionIpcClient.getAvailableStreams(name, block) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_11available_streams(CYTHON_UNUSED PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_11available_streams = {"available_streams", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_11available_streams, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_11available_streams(CYTHON_UNUSED PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + std::string __pyx_v_name; + bool __pyx_v_block; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[2] = {0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("available_streams (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_name,&__pyx_n_s_block,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_name)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 166, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_block)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 166, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("available_streams", 1, 2, 2, 1); __PYX_ERR(0, 166, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "available_streams") < 0)) __PYX_ERR(0, 166, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 2)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + } + __pyx_v_name = __pyx_convert_string_from_py_std__in_string(values[0]); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 167, __pyx_L3_error) + __pyx_v_block = __Pyx_PyObject_IsTrue(values[1]); if (unlikely((__pyx_v_block == ((bool)-1)) && PyErr_Occurred())) __PYX_ERR(0, 167, __pyx_L3_error) + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("available_streams", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 166, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.available_streams", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_10available_streams(__PYX_STD_MOVE_IF_SUPPORTED(__pyx_v_name), __pyx_v_block); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_10available_streams(std::string __pyx_v_name, bool __pyx_v_block) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("available_streams", 1); + + /* "cereal/visionipc/visionipc_pyx.pyx":168 + * @staticmethod + * def available_streams(string name, bool block): + * return cppVisionIpcClient.getAvailableStreams(name, block) # <<<<<<<<<<<<<< + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __pyx_convert_set_to_py_enum__VisionStreamType(VisionIpcClient::getAvailableStreams(__pyx_v_name, __pyx_v_block)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 168, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "cereal/visionipc/visionipc_pyx.pyx":166 + * return self.client.is_connected() + * + * @staticmethod # <<<<<<<<<<<<<< + * def available_streams(string name, bool block): + * return cppVisionIpcClient.getAvailableStreams(name, block) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.available_streams", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_13__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_13__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_13__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_13__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_12__reduce_cython__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_12__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_15__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_15__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_15__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_15__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_14__setstate_cython__(((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_14__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("cereal.visionipc.visionipc_pyx.VisionIpcClient.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_tp_new_6cereal_9visionipc_13visionipc_pyx_CLContext(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + return o; +} + +static void __pyx_tp_dealloc_6cereal_9visionipc_13visionipc_pyx_CLContext(PyObject *o) { + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_6cereal_9visionipc_13visionipc_pyx_CLContext) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_6cereal_9visionipc_13visionipc_pyx_CLContext_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_6cereal_9visionipc_13visionipc_pyx_CLContext}, + {Py_tp_new, (void *)__pyx_tp_new_6cereal_9visionipc_13visionipc_pyx_CLContext}, + {0, 0}, +}; +static PyType_Spec __pyx_type_6cereal_9visionipc_13visionipc_pyx_CLContext_spec = { + "cereal.visionipc.visionipc_pyx.CLContext", + sizeof(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_CLContext), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_FINALIZE, + __pyx_type_6cereal_9visionipc_13visionipc_pyx_CLContext_slots, +}; +#else + +static PyTypeObject __pyx_type_6cereal_9visionipc_13visionipc_pyx_CLContext = { + PyVarObject_HEAD_INIT(0, 0) + "cereal.visionipc.visionipc_pyx.""CLContext", /*tp_name*/ + sizeof(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_CLContext), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_6cereal_9visionipc_13visionipc_pyx_CLContext, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_FINALIZE, /*tp_flags*/ + 0, /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + 0, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_6cereal_9visionipc_13visionipc_pyx_CLContext, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif +static struct __pyx_vtabstruct_6cereal_9visionipc_13visionipc_pyx_VisionBuf __pyx_vtable_6cereal_9visionipc_13visionipc_pyx_VisionBuf; + +static PyObject *__pyx_tp_new_6cereal_9visionipc_13visionipc_pyx_VisionBuf(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { + struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *)o); + p->__pyx_vtab = __pyx_vtabptr_6cereal_9visionipc_13visionipc_pyx_VisionBuf; + return o; +} + +static void __pyx_tp_dealloc_6cereal_9visionipc_13visionipc_pyx_VisionBuf(PyObject *o) { + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_6cereal_9visionipc_13visionipc_pyx_VisionBuf) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} + +static PyObject *__pyx_getprop_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_data(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_4data_1__get__(o); +} + +static PyObject *__pyx_getprop_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_width(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_5width_1__get__(o); +} + +static PyObject *__pyx_getprop_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_height(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_6height_1__get__(o); +} + +static PyObject *__pyx_getprop_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_stride(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_6stride_1__get__(o); +} + +static PyObject *__pyx_getprop_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_uv_offset(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_9uv_offset_1__get__(o); +} + +static PyObject *__pyx_getprop_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_rgb(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_3rgb_1__get__(o); +} + +static PyMethodDef __pyx_methods_6cereal_9visionipc_13visionipc_pyx_VisionBuf[] = { + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; + +static struct PyGetSetDef __pyx_getsets_6cereal_9visionipc_13visionipc_pyx_VisionBuf[] = { + {(char *)"data", __pyx_getprop_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_data, 0, (char *)0, 0}, + {(char *)"width", __pyx_getprop_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_width, 0, (char *)0, 0}, + {(char *)"height", __pyx_getprop_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_height, 0, (char *)0, 0}, + {(char *)"stride", __pyx_getprop_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_stride, 0, (char *)0, 0}, + {(char *)"uv_offset", __pyx_getprop_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_uv_offset, 0, (char *)0, 0}, + {(char *)"rgb", __pyx_getprop_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_rgb, 0, (char *)0, 0}, + {0, 0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionBuf_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_6cereal_9visionipc_13visionipc_pyx_VisionBuf}, + {Py_tp_methods, (void *)__pyx_methods_6cereal_9visionipc_13visionipc_pyx_VisionBuf}, + {Py_tp_getset, (void *)__pyx_getsets_6cereal_9visionipc_13visionipc_pyx_VisionBuf}, + {Py_tp_new, (void *)__pyx_tp_new_6cereal_9visionipc_13visionipc_pyx_VisionBuf}, + {0, 0}, +}; +static PyType_Spec __pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionBuf_spec = { + "cereal.visionipc.visionipc_pyx.VisionBuf", + sizeof(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, + __pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionBuf_slots, +}; +#else + +static PyTypeObject __pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionBuf = { + PyVarObject_HEAD_INIT(0, 0) + "cereal.visionipc.visionipc_pyx.""VisionBuf", /*tp_name*/ + sizeof(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_6cereal_9visionipc_13visionipc_pyx_VisionBuf, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, /*tp_flags*/ + 0, /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_6cereal_9visionipc_13visionipc_pyx_VisionBuf, /*tp_methods*/ + 0, /*tp_members*/ + __pyx_getsets_6cereal_9visionipc_13visionipc_pyx_VisionBuf, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_6cereal_9visionipc_13visionipc_pyx_VisionBuf, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyObject *__pyx_tp_new_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + return o; +} + +static void __pyx_tp_dealloc_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer(PyObject *o) { + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_11__dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} + +static PyMethodDef __pyx_methods_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer[] = { + {"create_buffers", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_3create_buffers, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"create_buffers_with_sizes", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_5create_buffers_with_sizes, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"send", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_7send, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"start_listener", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_9start_listener, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_13__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_15__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer}, + {Py_tp_methods, (void *)__pyx_methods_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer}, + {Py_tp_init, (void *)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_1__init__}, + {Py_tp_new, (void *)__pyx_tp_new_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer}, + {0, 0}, +}; +static PyType_Spec __pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer_spec = { + "cereal.visionipc.visionipc_pyx.VisionIpcServer", + sizeof(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, + __pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer_slots, +}; +#else + +static PyTypeObject __pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer = { + PyVarObject_HEAD_INIT(0, 0) + "cereal.visionipc.visionipc_pyx.""VisionIpcServer", /*tp_name*/ + sizeof(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, /*tp_flags*/ + 0, /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + __pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_1__init__, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyObject *__pyx_tp_new_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient(PyTypeObject *t, PyObject *a, PyObject *k) { + struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *)o); + new((void*)&(p->extra)) struct VisionIpcBufExtra(); + if (unlikely(__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_1__cinit__(o, a, k) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static void __pyx_tp_dealloc_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient(PyObject *o) { + struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *p = (struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_3__dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + __Pyx_call_destructor(p->extra); + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} + +static PyObject *__pyx_getprop_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_width(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_5width_1__get__(o); +} + +static PyObject *__pyx_getprop_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_height(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_6height_1__get__(o); +} + +static PyObject *__pyx_getprop_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_stride(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_6stride_1__get__(o); +} + +static PyObject *__pyx_getprop_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_uv_offset(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_9uv_offset_1__get__(o); +} + +static PyObject *__pyx_getprop_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_rgb(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_3rgb_1__get__(o); +} + +static PyObject *__pyx_getprop_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_buffer_len(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_10buffer_len_1__get__(o); +} + +static PyObject *__pyx_getprop_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_num_buffers(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_11num_buffers_1__get__(o); +} + +static PyObject *__pyx_getprop_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_frame_id(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_8frame_id_1__get__(o); +} + +static PyObject *__pyx_getprop_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_timestamp_sof(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_13timestamp_sof_1__get__(o); +} + +static PyObject *__pyx_getprop_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_timestamp_eof(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_13timestamp_eof_1__get__(o); +} + +static PyObject *__pyx_getprop_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_valid(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_5valid_1__get__(o); +} + +static PyMethodDef __pyx_methods_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient[] = { + {"recv", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_5recv, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"connect", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_7connect, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"is_connected", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_9is_connected, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"available_streams", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_11available_streams, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_13__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_15__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; + +static struct PyGetSetDef __pyx_getsets_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient[] = { + {(char *)"width", __pyx_getprop_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_width, 0, (char *)0, 0}, + {(char *)"height", __pyx_getprop_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_height, 0, (char *)0, 0}, + {(char *)"stride", __pyx_getprop_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_stride, 0, (char *)0, 0}, + {(char *)"uv_offset", __pyx_getprop_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_uv_offset, 0, (char *)0, 0}, + {(char *)"rgb", __pyx_getprop_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_rgb, 0, (char *)0, 0}, + {(char *)"buffer_len", __pyx_getprop_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_buffer_len, 0, (char *)0, 0}, + {(char *)"num_buffers", __pyx_getprop_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_num_buffers, 0, (char *)0, 0}, + {(char *)"frame_id", __pyx_getprop_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_frame_id, 0, (char *)0, 0}, + {(char *)"timestamp_sof", __pyx_getprop_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_timestamp_sof, 0, (char *)0, 0}, + {(char *)"timestamp_eof", __pyx_getprop_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_timestamp_eof, 0, (char *)0, 0}, + {(char *)"valid", __pyx_getprop_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_valid, 0, (char *)0, 0}, + {0, 0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient}, + {Py_tp_methods, (void *)__pyx_methods_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient}, + {Py_tp_getset, (void *)__pyx_getsets_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient}, + {Py_tp_new, (void *)__pyx_tp_new_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient}, + {0, 0}, +}; +static PyType_Spec __pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient_spec = { + "cereal.visionipc.visionipc_pyx.VisionIpcClient", + sizeof(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, + __pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient_slots, +}; +#else + +static PyTypeObject __pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient = { + PyVarObject_HEAD_INIT(0, 0) + "cereal.visionipc.visionipc_pyx.""VisionIpcClient", /*tp_name*/ + sizeof(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, /*tp_flags*/ + 0, /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient, /*tp_methods*/ + 0, /*tp_members*/ + __pyx_getsets_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static int __pyx_tp_traverse___Pyx_EnumMeta(PyObject *o, visitproc v, void *a) { + int e; + if (!(&PyType_Type)->tp_traverse); else { e = (&PyType_Type)->tp_traverse(o,v,a); if (e) return e; } + return 0; +} + +static int __pyx_tp_clear___Pyx_EnumMeta(PyObject *o) { + if (!(&PyType_Type)->tp_clear); else (&PyType_Type)->tp_clear(o); + return 0; +} +static PyObject *__pyx_sq_item___Pyx_EnumMeta(PyObject *o, Py_ssize_t i) { + PyObject *r; + PyObject *x = PyInt_FromSsize_t(i); if(!x) return 0; + r = Py_TYPE(o)->tp_as_mapping->mp_subscript(o, x); + Py_DECREF(x); + return r; +} + +static PyMethodDef __pyx_methods___Pyx_EnumMeta[] = { + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_8EnumBase_14__Pyx_EnumMeta_7__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_8EnumBase_14__Pyx_EnumMeta_9__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __Pyx_EnumMeta_slots[] = { + {Py_sq_item, (void *)__pyx_sq_item___Pyx_EnumMeta}, + {Py_mp_subscript, (void *)__pyx_pw_8EnumBase_14__Pyx_EnumMeta_5__getitem__}, + {Py_tp_traverse, (void *)__pyx_tp_traverse___Pyx_EnumMeta}, + {Py_tp_clear, (void *)__pyx_tp_clear___Pyx_EnumMeta}, + {Py_tp_iter, (void *)__pyx_pw_8EnumBase_14__Pyx_EnumMeta_3__iter__}, + {Py_tp_methods, (void *)__pyx_methods___Pyx_EnumMeta}, + {Py_tp_init, (void *)__pyx_pw_8EnumBase_14__Pyx_EnumMeta_1__init__}, + {0, 0}, +}; +static PyType_Spec __Pyx_EnumMeta_spec = { + "cereal.visionipc.visionipc_pyx.__Pyx_EnumMeta", + sizeof(struct __pyx_obj___Pyx_EnumMeta), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_HAVE_FINALIZE, + __Pyx_EnumMeta_slots, +}; +#else + +static PySequenceMethods __pyx_tp_as_sequence___Pyx_EnumMeta = { + 0, /*sq_length*/ + 0, /*sq_concat*/ + 0, /*sq_repeat*/ + __pyx_sq_item___Pyx_EnumMeta, /*sq_item*/ + 0, /*sq_slice*/ + 0, /*sq_ass_item*/ + 0, /*sq_ass_slice*/ + 0, /*sq_contains*/ + 0, /*sq_inplace_concat*/ + 0, /*sq_inplace_repeat*/ +}; + +static PyMappingMethods __pyx_tp_as_mapping___Pyx_EnumMeta = { + 0, /*mp_length*/ + __pyx_pw_8EnumBase_14__Pyx_EnumMeta_5__getitem__, /*mp_subscript*/ + 0, /*mp_ass_subscript*/ +}; + +static PyTypeObject __Pyx_EnumMeta = { + PyVarObject_HEAD_INIT(0, 0) + "cereal.visionipc.visionipc_pyx.""__Pyx_EnumMeta", /*tp_name*/ + sizeof(struct __pyx_obj___Pyx_EnumMeta), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + 0, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + &__pyx_tp_as_sequence___Pyx_EnumMeta, /*tp_as_sequence*/ + &__pyx_tp_as_mapping___Pyx_EnumMeta, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_HAVE_FINALIZE, /*tp_flags*/ + 0, /*tp_doc*/ + __pyx_tp_traverse___Pyx_EnumMeta, /*tp_traverse*/ + __pyx_tp_clear___Pyx_EnumMeta, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + __pyx_pw_8EnumBase_14__Pyx_EnumMeta_3__iter__, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods___Pyx_EnumMeta, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + __pyx_pw_8EnumBase_14__Pyx_EnumMeta_1__init__, /*tp_init*/ + 0, /*tp_alloc*/ + 0, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif +static struct __pyx_vtabstruct_array __pyx_vtable_array; + +static PyObject *__pyx_tp_new_array(PyTypeObject *t, PyObject *a, PyObject *k) { + struct __pyx_array_obj *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_array_obj *)o); + p->__pyx_vtab = __pyx_vtabptr_array; + p->mode = ((PyObject*)Py_None); Py_INCREF(Py_None); + p->_format = ((PyObject*)Py_None); Py_INCREF(Py_None); + if (unlikely(__pyx_array___cinit__(o, a, k) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static void __pyx_tp_dealloc_array(PyObject *o) { + struct __pyx_array_obj *p = (struct __pyx_array_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_array) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_array___dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + Py_CLEAR(p->mode); + Py_CLEAR(p->_format); + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} +static PyObject *__pyx_sq_item_array(PyObject *o, Py_ssize_t i) { + PyObject *r; + PyObject *x = PyInt_FromSsize_t(i); if(!x) return 0; + r = Py_TYPE(o)->tp_as_mapping->mp_subscript(o, x); + Py_DECREF(x); + return r; +} + +static int __pyx_mp_ass_subscript_array(PyObject *o, PyObject *i, PyObject *v) { + if (v) { + return __pyx_array___setitem__(o, i, v); + } + else { + __Pyx_TypeName o_type_name; + o_type_name = __Pyx_PyType_GetName(Py_TYPE(o)); + PyErr_Format(PyExc_NotImplementedError, + "Subscript deletion not supported by " __Pyx_FMT_TYPENAME, o_type_name); + __Pyx_DECREF_TypeName(o_type_name); + return -1; + } +} + +static PyObject *__pyx_tp_getattro_array(PyObject *o, PyObject *n) { + PyObject *v = __Pyx_PyObject_GenericGetAttr(o, n); + if (!v && PyErr_ExceptionMatches(PyExc_AttributeError)) { + PyErr_Clear(); + v = __pyx_array___getattr__(o, n); + } + return v; +} + +static PyObject *__pyx_getprop___pyx_array_memview(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_5array_7memview_1__get__(o); +} + +static PyMethodDef __pyx_methods_array[] = { + {"__getattr__", (PyCFunction)__pyx_array___getattr__, METH_O|METH_COEXIST, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_array_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_array_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; + +static struct PyGetSetDef __pyx_getsets_array[] = { + {(char *)"memview", __pyx_getprop___pyx_array_memview, 0, (char *)0, 0}, + {0, 0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +#if !CYTHON_COMPILING_IN_LIMITED_API + +static PyBufferProcs __pyx_tp_as_buffer_array = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_array_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; +#endif +static PyType_Slot __pyx_type___pyx_array_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_array}, + {Py_sq_length, (void *)__pyx_array___len__}, + {Py_sq_item, (void *)__pyx_sq_item_array}, + {Py_mp_length, (void *)__pyx_array___len__}, + {Py_mp_subscript, (void *)__pyx_array___getitem__}, + {Py_mp_ass_subscript, (void *)__pyx_mp_ass_subscript_array}, + {Py_tp_getattro, (void *)__pyx_tp_getattro_array}, + #if defined(Py_bf_getbuffer) + {Py_bf_getbuffer, (void *)__pyx_array_getbuffer}, + #endif + {Py_tp_methods, (void *)__pyx_methods_array}, + {Py_tp_getset, (void *)__pyx_getsets_array}, + {Py_tp_new, (void *)__pyx_tp_new_array}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_array_spec = { + "cereal.visionipc.visionipc_pyx.array", + sizeof(struct __pyx_array_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_SEQUENCE, + __pyx_type___pyx_array_slots, +}; +#else + +static PySequenceMethods __pyx_tp_as_sequence_array = { + __pyx_array___len__, /*sq_length*/ + 0, /*sq_concat*/ + 0, /*sq_repeat*/ + __pyx_sq_item_array, /*sq_item*/ + 0, /*sq_slice*/ + 0, /*sq_ass_item*/ + 0, /*sq_ass_slice*/ + 0, /*sq_contains*/ + 0, /*sq_inplace_concat*/ + 0, /*sq_inplace_repeat*/ +}; + +static PyMappingMethods __pyx_tp_as_mapping_array = { + __pyx_array___len__, /*mp_length*/ + __pyx_array___getitem__, /*mp_subscript*/ + __pyx_mp_ass_subscript_array, /*mp_ass_subscript*/ +}; + +static PyBufferProcs __pyx_tp_as_buffer_array = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_array_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; + +static PyTypeObject __pyx_type___pyx_array = { + PyVarObject_HEAD_INIT(0, 0) + "cereal.visionipc.visionipc_pyx.""array", /*tp_name*/ + sizeof(struct __pyx_array_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_array, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + &__pyx_tp_as_sequence_array, /*tp_as_sequence*/ + &__pyx_tp_as_mapping_array, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + __pyx_tp_getattro_array, /*tp_getattro*/ + 0, /*tp_setattro*/ + &__pyx_tp_as_buffer_array, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_SEQUENCE, /*tp_flags*/ + 0, /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_array, /*tp_methods*/ + 0, /*tp_members*/ + __pyx_getsets_array, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_array, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyObject *__pyx_tp_new_Enum(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { + struct __pyx_MemviewEnum_obj *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_MemviewEnum_obj *)o); + p->name = Py_None; Py_INCREF(Py_None); + return o; +} + +static void __pyx_tp_dealloc_Enum(PyObject *o) { + struct __pyx_MemviewEnum_obj *p = (struct __pyx_MemviewEnum_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_Enum) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + Py_CLEAR(p->name); + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} + +static int __pyx_tp_traverse_Enum(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_MemviewEnum_obj *p = (struct __pyx_MemviewEnum_obj *)o; + if (p->name) { + e = (*v)(p->name, a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear_Enum(PyObject *o) { + PyObject* tmp; + struct __pyx_MemviewEnum_obj *p = (struct __pyx_MemviewEnum_obj *)o; + tmp = ((PyObject*)p->name); + p->name = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + return 0; +} + +static PyObject *__pyx_specialmethod___pyx_MemviewEnum___repr__(PyObject *self, CYTHON_UNUSED PyObject *arg) { + return __pyx_MemviewEnum___repr__(self); +} + +static PyMethodDef __pyx_methods_Enum[] = { + {"__repr__", (PyCFunction)__pyx_specialmethod___pyx_MemviewEnum___repr__, METH_NOARGS|METH_COEXIST, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_MemviewEnum_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_MemviewEnum_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type___pyx_MemviewEnum_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_Enum}, + {Py_tp_repr, (void *)__pyx_MemviewEnum___repr__}, + {Py_tp_traverse, (void *)__pyx_tp_traverse_Enum}, + {Py_tp_clear, (void *)__pyx_tp_clear_Enum}, + {Py_tp_methods, (void *)__pyx_methods_Enum}, + {Py_tp_init, (void *)__pyx_MemviewEnum___init__}, + {Py_tp_new, (void *)__pyx_tp_new_Enum}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_MemviewEnum_spec = { + "cereal.visionipc.visionipc_pyx.Enum", + sizeof(struct __pyx_MemviewEnum_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, + __pyx_type___pyx_MemviewEnum_slots, +}; +#else + +static PyTypeObject __pyx_type___pyx_MemviewEnum = { + PyVarObject_HEAD_INIT(0, 0) + "cereal.visionipc.visionipc_pyx.""Enum", /*tp_name*/ + sizeof(struct __pyx_MemviewEnum_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_Enum, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + __pyx_MemviewEnum___repr__, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, /*tp_flags*/ + 0, /*tp_doc*/ + __pyx_tp_traverse_Enum, /*tp_traverse*/ + __pyx_tp_clear_Enum, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_Enum, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + __pyx_MemviewEnum___init__, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_Enum, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif +static struct __pyx_vtabstruct_memoryview __pyx_vtable_memoryview; + +static PyObject *__pyx_tp_new_memoryview(PyTypeObject *t, PyObject *a, PyObject *k) { + struct __pyx_memoryview_obj *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_memoryview_obj *)o); + p->__pyx_vtab = __pyx_vtabptr_memoryview; + p->obj = Py_None; Py_INCREF(Py_None); + p->_size = Py_None; Py_INCREF(Py_None); + p->_array_interface = Py_None; Py_INCREF(Py_None); + p->view.obj = NULL; + if (unlikely(__pyx_memoryview___cinit__(o, a, k) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static void __pyx_tp_dealloc_memoryview(PyObject *o) { + struct __pyx_memoryview_obj *p = (struct __pyx_memoryview_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_memoryview) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_memoryview___dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + Py_CLEAR(p->obj); + Py_CLEAR(p->_size); + Py_CLEAR(p->_array_interface); + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} + +static int __pyx_tp_traverse_memoryview(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_memoryview_obj *p = (struct __pyx_memoryview_obj *)o; + if (p->obj) { + e = (*v)(p->obj, a); if (e) return e; + } + if (p->_size) { + e = (*v)(p->_size, a); if (e) return e; + } + if (p->_array_interface) { + e = (*v)(p->_array_interface, a); if (e) return e; + } + if (p->view.obj) { + e = (*v)(p->view.obj, a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear_memoryview(PyObject *o) { + PyObject* tmp; + struct __pyx_memoryview_obj *p = (struct __pyx_memoryview_obj *)o; + tmp = ((PyObject*)p->obj); + p->obj = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + tmp = ((PyObject*)p->_size); + p->_size = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + tmp = ((PyObject*)p->_array_interface); + p->_array_interface = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + Py_CLEAR(p->view.obj); + return 0; +} +static PyObject *__pyx_sq_item_memoryview(PyObject *o, Py_ssize_t i) { + PyObject *r; + PyObject *x = PyInt_FromSsize_t(i); if(!x) return 0; + r = Py_TYPE(o)->tp_as_mapping->mp_subscript(o, x); + Py_DECREF(x); + return r; +} + +static int __pyx_mp_ass_subscript_memoryview(PyObject *o, PyObject *i, PyObject *v) { + if (v) { + return __pyx_memoryview___setitem__(o, i, v); + } + else { + __Pyx_TypeName o_type_name; + o_type_name = __Pyx_PyType_GetName(Py_TYPE(o)); + PyErr_Format(PyExc_NotImplementedError, + "Subscript deletion not supported by " __Pyx_FMT_TYPENAME, o_type_name); + __Pyx_DECREF_TypeName(o_type_name); + return -1; + } +} + +static PyObject *__pyx_getprop___pyx_memoryview_T(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_1T_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_base(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_4base_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_shape(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_5shape_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_strides(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_7strides_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_suboffsets(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_10suboffsets_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_ndim(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_4ndim_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_itemsize(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_8itemsize_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_nbytes(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_6nbytes_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_size(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_4size_1__get__(o); +} + +static PyObject *__pyx_specialmethod___pyx_memoryview___repr__(PyObject *self, CYTHON_UNUSED PyObject *arg) { + return __pyx_memoryview___repr__(self); +} + +static PyMethodDef __pyx_methods_memoryview[] = { + {"__repr__", (PyCFunction)__pyx_specialmethod___pyx_memoryview___repr__, METH_NOARGS|METH_COEXIST, 0}, + {"is_c_contig", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_is_c_contig, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"is_f_contig", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_is_f_contig, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"copy", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_copy, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"copy_fortran", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_copy_fortran, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryview_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryview_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; + +static struct PyGetSetDef __pyx_getsets_memoryview[] = { + {(char *)"T", __pyx_getprop___pyx_memoryview_T, 0, (char *)0, 0}, + {(char *)"base", __pyx_getprop___pyx_memoryview_base, 0, (char *)0, 0}, + {(char *)"shape", __pyx_getprop___pyx_memoryview_shape, 0, (char *)0, 0}, + {(char *)"strides", __pyx_getprop___pyx_memoryview_strides, 0, (char *)0, 0}, + {(char *)"suboffsets", __pyx_getprop___pyx_memoryview_suboffsets, 0, (char *)0, 0}, + {(char *)"ndim", __pyx_getprop___pyx_memoryview_ndim, 0, (char *)0, 0}, + {(char *)"itemsize", __pyx_getprop___pyx_memoryview_itemsize, 0, (char *)0, 0}, + {(char *)"nbytes", __pyx_getprop___pyx_memoryview_nbytes, 0, (char *)0, 0}, + {(char *)"size", __pyx_getprop___pyx_memoryview_size, 0, (char *)0, 0}, + {0, 0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +#if !CYTHON_COMPILING_IN_LIMITED_API + +static PyBufferProcs __pyx_tp_as_buffer_memoryview = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_memoryview_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; +#endif +static PyType_Slot __pyx_type___pyx_memoryview_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_memoryview}, + {Py_tp_repr, (void *)__pyx_memoryview___repr__}, + {Py_sq_length, (void *)__pyx_memoryview___len__}, + {Py_sq_item, (void *)__pyx_sq_item_memoryview}, + {Py_mp_length, (void *)__pyx_memoryview___len__}, + {Py_mp_subscript, (void *)__pyx_memoryview___getitem__}, + {Py_mp_ass_subscript, (void *)__pyx_mp_ass_subscript_memoryview}, + {Py_tp_str, (void *)__pyx_memoryview___str__}, + #if defined(Py_bf_getbuffer) + {Py_bf_getbuffer, (void *)__pyx_memoryview_getbuffer}, + #endif + {Py_tp_traverse, (void *)__pyx_tp_traverse_memoryview}, + {Py_tp_clear, (void *)__pyx_tp_clear_memoryview}, + {Py_tp_methods, (void *)__pyx_methods_memoryview}, + {Py_tp_getset, (void *)__pyx_getsets_memoryview}, + {Py_tp_new, (void *)__pyx_tp_new_memoryview}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_memoryview_spec = { + "cereal.visionipc.visionipc_pyx.memoryview", + sizeof(struct __pyx_memoryview_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, + __pyx_type___pyx_memoryview_slots, +}; +#else + +static PySequenceMethods __pyx_tp_as_sequence_memoryview = { + __pyx_memoryview___len__, /*sq_length*/ + 0, /*sq_concat*/ + 0, /*sq_repeat*/ + __pyx_sq_item_memoryview, /*sq_item*/ + 0, /*sq_slice*/ + 0, /*sq_ass_item*/ + 0, /*sq_ass_slice*/ + 0, /*sq_contains*/ + 0, /*sq_inplace_concat*/ + 0, /*sq_inplace_repeat*/ +}; + +static PyMappingMethods __pyx_tp_as_mapping_memoryview = { + __pyx_memoryview___len__, /*mp_length*/ + __pyx_memoryview___getitem__, /*mp_subscript*/ + __pyx_mp_ass_subscript_memoryview, /*mp_ass_subscript*/ +}; + +static PyBufferProcs __pyx_tp_as_buffer_memoryview = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_memoryview_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; + +static PyTypeObject __pyx_type___pyx_memoryview = { + PyVarObject_HEAD_INIT(0, 0) + "cereal.visionipc.visionipc_pyx.""memoryview", /*tp_name*/ + sizeof(struct __pyx_memoryview_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_memoryview, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + __pyx_memoryview___repr__, /*tp_repr*/ + 0, /*tp_as_number*/ + &__pyx_tp_as_sequence_memoryview, /*tp_as_sequence*/ + &__pyx_tp_as_mapping_memoryview, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + __pyx_memoryview___str__, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + &__pyx_tp_as_buffer_memoryview, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, /*tp_flags*/ + 0, /*tp_doc*/ + __pyx_tp_traverse_memoryview, /*tp_traverse*/ + __pyx_tp_clear_memoryview, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_memoryview, /*tp_methods*/ + 0, /*tp_members*/ + __pyx_getsets_memoryview, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_memoryview, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif +static struct __pyx_vtabstruct__memoryviewslice __pyx_vtable__memoryviewslice; + +static PyObject *__pyx_tp_new__memoryviewslice(PyTypeObject *t, PyObject *a, PyObject *k) { + struct __pyx_memoryviewslice_obj *p; + PyObject *o = __pyx_tp_new_memoryview(t, a, k); + if (unlikely(!o)) return 0; + p = ((struct __pyx_memoryviewslice_obj *)o); + p->__pyx_base.__pyx_vtab = (struct __pyx_vtabstruct_memoryview*)__pyx_vtabptr__memoryviewslice; + new((void*)&(p->from_slice)) __Pyx_memviewslice(); + p->from_object = Py_None; Py_INCREF(Py_None); + p->from_slice.memview = NULL; + return o; +} + +static void __pyx_tp_dealloc__memoryviewslice(PyObject *o) { + struct __pyx_memoryviewslice_obj *p = (struct __pyx_memoryviewslice_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc__memoryviewslice) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_memoryviewslice___dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + __Pyx_call_destructor(p->from_slice); + Py_CLEAR(p->from_object); + PyObject_GC_Track(o); + __pyx_tp_dealloc_memoryview(o); +} + +static int __pyx_tp_traverse__memoryviewslice(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_memoryviewslice_obj *p = (struct __pyx_memoryviewslice_obj *)o; + e = __pyx_tp_traverse_memoryview(o, v, a); if (e) return e; + if (p->from_object) { + e = (*v)(p->from_object, a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear__memoryviewslice(PyObject *o) { + PyObject* tmp; + struct __pyx_memoryviewslice_obj *p = (struct __pyx_memoryviewslice_obj *)o; + __pyx_tp_clear_memoryview(o); + tmp = ((PyObject*)p->from_object); + p->from_object = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + __PYX_XCLEAR_MEMVIEW(&p->from_slice, 1); + return 0; +} + +static PyMethodDef __pyx_methods__memoryviewslice[] = { + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryviewslice_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryviewslice_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type___pyx_memoryviewslice_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc__memoryviewslice}, + {Py_tp_doc, (void *)PyDoc_STR("Internal class for passing memoryview slices to Python")}, + {Py_tp_traverse, (void *)__pyx_tp_traverse__memoryviewslice}, + {Py_tp_clear, (void *)__pyx_tp_clear__memoryviewslice}, + {Py_tp_methods, (void *)__pyx_methods__memoryviewslice}, + {Py_tp_new, (void *)__pyx_tp_new__memoryviewslice}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_memoryviewslice_spec = { + "cereal.visionipc.visionipc_pyx._memoryviewslice", + sizeof(struct __pyx_memoryviewslice_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_SEQUENCE, + __pyx_type___pyx_memoryviewslice_slots, +}; +#else + +static PyTypeObject __pyx_type___pyx_memoryviewslice = { + PyVarObject_HEAD_INIT(0, 0) + "cereal.visionipc.visionipc_pyx.""_memoryviewslice", /*tp_name*/ + sizeof(struct __pyx_memoryviewslice_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc__memoryviewslice, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + #if CYTHON_COMPILING_IN_PYPY || 0 + __pyx_memoryview___repr__, /*tp_repr*/ + #else + 0, /*tp_repr*/ + #endif + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + #if CYTHON_COMPILING_IN_PYPY || 0 + __pyx_memoryview___str__, /*tp_str*/ + #else + 0, /*tp_str*/ + #endif + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_SEQUENCE, /*tp_flags*/ + PyDoc_STR("Internal class for passing memoryview slices to Python"), /*tp_doc*/ + __pyx_tp_traverse__memoryviewslice, /*tp_traverse*/ + __pyx_tp_clear__memoryviewslice, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods__memoryviewslice, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new__memoryviewslice, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyMethodDef __pyx_methods[] = { + {0, 0, 0, 0} +}; +#ifndef CYTHON_SMALL_CODE +#if defined(__clang__) + #define CYTHON_SMALL_CODE +#elif defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 3)) + #define CYTHON_SMALL_CODE __attribute__((cold)) +#else + #define CYTHON_SMALL_CODE +#endif +#endif +/* #### Code section: pystring_table ### */ + +static int __Pyx_CreateStringTabAndInitStrings(void) { + __Pyx_StringTabEntry __pyx_string_tab[] = { + {&__pyx_kp_b_, __pyx_k_, sizeof(__pyx_k_), 0, 0, 0, 0}, + {&__pyx_kp_s_, __pyx_k_, sizeof(__pyx_k_), 0, 0, 1, 0}, + {&__pyx_n_s_ASCII, __pyx_k_ASCII, sizeof(__pyx_k_ASCII), 0, 0, 1, 1}, + {&__pyx_kp_s_All_dimensions_preceding_dimensi, __pyx_k_All_dimensions_preceding_dimensi, sizeof(__pyx_k_All_dimensions_preceding_dimensi), 0, 0, 1, 0}, + {&__pyx_n_s_AssertionError, __pyx_k_AssertionError, sizeof(__pyx_k_AssertionError), 0, 0, 1, 1}, + {&__pyx_kp_s_Buffer_view_does_not_expose_stri, __pyx_k_Buffer_view_does_not_expose_stri, sizeof(__pyx_k_Buffer_view_does_not_expose_stri), 0, 0, 1, 0}, + {&__pyx_n_s_CLContext, __pyx_k_CLContext, sizeof(__pyx_k_CLContext), 0, 0, 1, 1}, + {&__pyx_kp_s_Can_only_create_a_buffer_that_is, __pyx_k_Can_only_create_a_buffer_that_is, sizeof(__pyx_k_Can_only_create_a_buffer_that_is), 0, 0, 1, 0}, + {&__pyx_kp_s_Cannot_assign_to_read_only_memor, __pyx_k_Cannot_assign_to_read_only_memor, sizeof(__pyx_k_Cannot_assign_to_read_only_memor), 0, 0, 1, 0}, + {&__pyx_kp_s_Cannot_create_writable_memory_vi, __pyx_k_Cannot_create_writable_memory_vi, sizeof(__pyx_k_Cannot_create_writable_memory_vi), 0, 0, 1, 0}, + {&__pyx_kp_u_Cannot_index_with_type, __pyx_k_Cannot_index_with_type, sizeof(__pyx_k_Cannot_index_with_type), 0, 1, 0, 0}, + {&__pyx_kp_s_Cannot_transpose_memoryview_with, __pyx_k_Cannot_transpose_memoryview_with, sizeof(__pyx_k_Cannot_transpose_memoryview_with), 0, 0, 1, 0}, + {&__pyx_kp_s_Dimension_d_is_not_direct, __pyx_k_Dimension_d_is_not_direct, sizeof(__pyx_k_Dimension_d_is_not_direct), 0, 0, 1, 0}, + {&__pyx_n_s_Ellipsis, __pyx_k_Ellipsis, sizeof(__pyx_k_Ellipsis), 0, 0, 1, 1}, + {&__pyx_kp_s_Empty_shape_tuple_for_cython_arr, __pyx_k_Empty_shape_tuple_for_cython_arr, sizeof(__pyx_k_Empty_shape_tuple_for_cython_arr), 0, 0, 1, 0}, + {&__pyx_n_s_EnumBase, __pyx_k_EnumBase, sizeof(__pyx_k_EnumBase), 0, 0, 1, 1}, + {&__pyx_n_s_EnumType, __pyx_k_EnumType, sizeof(__pyx_k_EnumType), 0, 0, 1, 1}, + {&__pyx_n_s_ImportError, __pyx_k_ImportError, sizeof(__pyx_k_ImportError), 0, 0, 1, 1}, + {&__pyx_kp_s_Incompatible_checksums_0x_x_vs_0, __pyx_k_Incompatible_checksums_0x_x_vs_0, sizeof(__pyx_k_Incompatible_checksums_0x_x_vs_0), 0, 0, 1, 0}, + {&__pyx_kp_s_Incompatible_checksums_0x_x_vs_0_2, __pyx_k_Incompatible_checksums_0x_x_vs_0_2, sizeof(__pyx_k_Incompatible_checksums_0x_x_vs_0_2), 0, 0, 1, 0}, + {&__pyx_n_s_IndexError, __pyx_k_IndexError, sizeof(__pyx_k_IndexError), 0, 0, 1, 1}, + {&__pyx_kp_s_Index_out_of_bounds_axis_d, __pyx_k_Index_out_of_bounds_axis_d, sizeof(__pyx_k_Index_out_of_bounds_axis_d), 0, 0, 1, 0}, + {&__pyx_kp_s_Indirect_dimensions_not_supporte, __pyx_k_Indirect_dimensions_not_supporte, sizeof(__pyx_k_Indirect_dimensions_not_supporte), 0, 0, 1, 0}, + {&__pyx_n_s_IntEnum, __pyx_k_IntEnum, sizeof(__pyx_k_IntEnum), 0, 0, 1, 1}, + {&__pyx_n_s_IntFlag, __pyx_k_IntFlag, sizeof(__pyx_k_IntFlag), 0, 0, 1, 1}, + {&__pyx_kp_u_Invalid_mode_expected_c_or_fortr, __pyx_k_Invalid_mode_expected_c_or_fortr, sizeof(__pyx_k_Invalid_mode_expected_c_or_fortr), 0, 1, 0, 0}, + {&__pyx_kp_u_Invalid_shape_in_axis, __pyx_k_Invalid_shape_in_axis, sizeof(__pyx_k_Invalid_shape_in_axis), 0, 1, 0, 0}, + {&__pyx_n_s_MemoryError, __pyx_k_MemoryError, sizeof(__pyx_k_MemoryError), 0, 0, 1, 1}, + {&__pyx_kp_s_MemoryView_of_r_at_0x_x, __pyx_k_MemoryView_of_r_at_0x_x, sizeof(__pyx_k_MemoryView_of_r_at_0x_x), 0, 0, 1, 0}, + {&__pyx_kp_s_MemoryView_of_r_object, __pyx_k_MemoryView_of_r_object, sizeof(__pyx_k_MemoryView_of_r_object), 0, 0, 1, 0}, + {&__pyx_n_b_O, __pyx_k_O, sizeof(__pyx_k_O), 0, 0, 0, 1}, + {&__pyx_n_s_OrderedDict, __pyx_k_OrderedDict, sizeof(__pyx_k_OrderedDict), 0, 0, 1, 1}, + {&__pyx_kp_u_Out_of_bounds_on_buffer_access_a, __pyx_k_Out_of_bounds_on_buffer_access_a, sizeof(__pyx_k_Out_of_bounds_on_buffer_access_a), 0, 1, 0, 0}, + {&__pyx_n_s_PickleError, __pyx_k_PickleError, sizeof(__pyx_k_PickleError), 0, 0, 1, 1}, + {&__pyx_n_s_Pyx_EnumBase, __pyx_k_Pyx_EnumBase, sizeof(__pyx_k_Pyx_EnumBase), 0, 0, 1, 1}, + {&__pyx_n_s_Pyx_EnumBase___new, __pyx_k_Pyx_EnumBase___new, sizeof(__pyx_k_Pyx_EnumBase___new), 0, 0, 1, 1}, + {&__pyx_n_s_Pyx_EnumBase___repr, __pyx_k_Pyx_EnumBase___repr, sizeof(__pyx_k_Pyx_EnumBase___repr), 0, 0, 1, 1}, + {&__pyx_n_s_Pyx_EnumBase___str, __pyx_k_Pyx_EnumBase___str, sizeof(__pyx_k_Pyx_EnumBase___str), 0, 0, 1, 1}, + {&__pyx_n_s_Pyx_EnumMeta___reduce_cython, __pyx_k_Pyx_EnumMeta___reduce_cython, sizeof(__pyx_k_Pyx_EnumMeta___reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_Pyx_EnumMeta___setstate_cython, __pyx_k_Pyx_EnumMeta___setstate_cython, sizeof(__pyx_k_Pyx_EnumMeta___setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_Pyx_FlagBase, __pyx_k_Pyx_FlagBase, sizeof(__pyx_k_Pyx_FlagBase), 0, 0, 1, 1}, + {&__pyx_n_s_Pyx_FlagBase___new, __pyx_k_Pyx_FlagBase___new, sizeof(__pyx_k_Pyx_FlagBase___new), 0, 0, 1, 1}, + {&__pyx_n_s_Pyx_FlagBase___repr, __pyx_k_Pyx_FlagBase___repr, sizeof(__pyx_k_Pyx_FlagBase___repr), 0, 0, 1, 1}, + {&__pyx_n_s_Pyx_FlagBase___str, __pyx_k_Pyx_FlagBase___str, sizeof(__pyx_k_Pyx_FlagBase___str), 0, 0, 1, 1}, + {&__pyx_n_s_Sequence, __pyx_k_Sequence, sizeof(__pyx_k_Sequence), 0, 0, 1, 1}, + {&__pyx_kp_s_Step_may_not_be_zero_axis_d, __pyx_k_Step_may_not_be_zero_axis_d, sizeof(__pyx_k_Step_may_not_be_zero_axis_d), 0, 0, 1, 0}, + {&__pyx_kp_b_T, __pyx_k_T, sizeof(__pyx_k_T), 0, 0, 0, 0}, + {&__pyx_n_s_TypeError, __pyx_k_TypeError, sizeof(__pyx_k_TypeError), 0, 0, 1, 1}, + {&__pyx_kp_s_Unable_to_convert_item_to_object, __pyx_k_Unable_to_convert_item_to_object, sizeof(__pyx_k_Unable_to_convert_item_to_object), 0, 0, 1, 0}, + {&__pyx_kp_s_Unknown_enum_value_s, __pyx_k_Unknown_enum_value_s, sizeof(__pyx_k_Unknown_enum_value_s), 0, 0, 1, 0}, + {&__pyx_n_s_VISION_STREAM_DRIVER, __pyx_k_VISION_STREAM_DRIVER, sizeof(__pyx_k_VISION_STREAM_DRIVER), 0, 0, 1, 1}, + {&__pyx_n_s_VISION_STREAM_MAP, __pyx_k_VISION_STREAM_MAP, sizeof(__pyx_k_VISION_STREAM_MAP), 0, 0, 1, 1}, + {&__pyx_n_s_VISION_STREAM_ROAD, __pyx_k_VISION_STREAM_ROAD, sizeof(__pyx_k_VISION_STREAM_ROAD), 0, 0, 1, 1}, + {&__pyx_n_s_VISION_STREAM_WIDE_ROAD, __pyx_k_VISION_STREAM_WIDE_ROAD, sizeof(__pyx_k_VISION_STREAM_WIDE_ROAD), 0, 0, 1, 1}, + {&__pyx_n_s_ValueError, __pyx_k_ValueError, sizeof(__pyx_k_ValueError), 0, 0, 1, 1}, + {&__pyx_n_s_View_MemoryView, __pyx_k_View_MemoryView, sizeof(__pyx_k_View_MemoryView), 0, 0, 1, 1}, + {&__pyx_n_s_VisionBuf, __pyx_k_VisionBuf, sizeof(__pyx_k_VisionBuf), 0, 0, 1, 1}, + {&__pyx_n_s_VisionBuf___reduce_cython, __pyx_k_VisionBuf___reduce_cython, sizeof(__pyx_k_VisionBuf___reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_VisionBuf___setstate_cython, __pyx_k_VisionBuf___setstate_cython, sizeof(__pyx_k_VisionBuf___setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_VisionIpcClient, __pyx_k_VisionIpcClient, sizeof(__pyx_k_VisionIpcClient), 0, 0, 1, 1}, + {&__pyx_n_s_VisionIpcClient___reduce_cython, __pyx_k_VisionIpcClient___reduce_cython, sizeof(__pyx_k_VisionIpcClient___reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_VisionIpcClient___setstate_cytho, __pyx_k_VisionIpcClient___setstate_cytho, sizeof(__pyx_k_VisionIpcClient___setstate_cytho), 0, 0, 1, 1}, + {&__pyx_n_s_VisionIpcClient_available_stream, __pyx_k_VisionIpcClient_available_stream, sizeof(__pyx_k_VisionIpcClient_available_stream), 0, 0, 1, 1}, + {&__pyx_n_s_VisionIpcClient_connect, __pyx_k_VisionIpcClient_connect, sizeof(__pyx_k_VisionIpcClient_connect), 0, 0, 1, 1}, + {&__pyx_n_s_VisionIpcClient_is_connected, __pyx_k_VisionIpcClient_is_connected, sizeof(__pyx_k_VisionIpcClient_is_connected), 0, 0, 1, 1}, + {&__pyx_n_s_VisionIpcClient_recv, __pyx_k_VisionIpcClient_recv, sizeof(__pyx_k_VisionIpcClient_recv), 0, 0, 1, 1}, + {&__pyx_n_s_VisionIpcServer, __pyx_k_VisionIpcServer, sizeof(__pyx_k_VisionIpcServer), 0, 0, 1, 1}, + {&__pyx_n_s_VisionIpcServer___reduce_cython, __pyx_k_VisionIpcServer___reduce_cython, sizeof(__pyx_k_VisionIpcServer___reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_VisionIpcServer___setstate_cytho, __pyx_k_VisionIpcServer___setstate_cytho, sizeof(__pyx_k_VisionIpcServer___setstate_cytho), 0, 0, 1, 1}, + {&__pyx_n_s_VisionIpcServer_create_buffers, __pyx_k_VisionIpcServer_create_buffers, sizeof(__pyx_k_VisionIpcServer_create_buffers), 0, 0, 1, 1}, + {&__pyx_n_s_VisionIpcServer_create_buffers_w, __pyx_k_VisionIpcServer_create_buffers_w, sizeof(__pyx_k_VisionIpcServer_create_buffers_w), 0, 0, 1, 1}, + {&__pyx_n_s_VisionIpcServer_send, __pyx_k_VisionIpcServer_send, sizeof(__pyx_k_VisionIpcServer_send), 0, 0, 1, 1}, + {&__pyx_n_s_VisionIpcServer_start_listener, __pyx_k_VisionIpcServer_start_listener, sizeof(__pyx_k_VisionIpcServer_start_listener), 0, 0, 1, 1}, + {&__pyx_n_s_VisionStreamType, __pyx_k_VisionStreamType, sizeof(__pyx_k_VisionStreamType), 0, 0, 1, 1}, + {&__pyx_kp_b__11, __pyx_k__11, sizeof(__pyx_k__11), 0, 0, 0, 0}, + {&__pyx_kp_b__12, __pyx_k__12, sizeof(__pyx_k__12), 0, 0, 0, 0}, + {&__pyx_kp_b__13, __pyx_k__13, sizeof(__pyx_k__13), 0, 0, 0, 0}, + {&__pyx_kp_u__14, __pyx_k__14, sizeof(__pyx_k__14), 0, 1, 0, 0}, + {&__pyx_kp_u__15, __pyx_k__15, sizeof(__pyx_k__15), 0, 1, 0, 0}, + {&__pyx_kp_u__3, __pyx_k__3, sizeof(__pyx_k__3), 0, 1, 0, 0}, + {&__pyx_kp_u__4, __pyx_k__4, sizeof(__pyx_k__4), 0, 1, 0, 0}, + {&__pyx_n_s__5, __pyx_k__5, sizeof(__pyx_k__5), 0, 0, 1, 1}, + {&__pyx_n_s__67, __pyx_k__67, sizeof(__pyx_k__67), 0, 0, 1, 1}, + {&__pyx_kp_u__8, __pyx_k__8, sizeof(__pyx_k__8), 0, 1, 0, 0}, + {&__pyx_kp_u__9, __pyx_k__9, sizeof(__pyx_k__9), 0, 1, 0, 0}, + {&__pyx_n_s_abc, __pyx_k_abc, sizeof(__pyx_k_abc), 0, 0, 1, 1}, + {&__pyx_n_s_allocate_buffer, __pyx_k_allocate_buffer, sizeof(__pyx_k_allocate_buffer), 0, 0, 1, 1}, + {&__pyx_kp_u_and, __pyx_k_and, sizeof(__pyx_k_and), 0, 1, 0, 0}, + {&__pyx_n_s_asarray, __pyx_k_asarray, sizeof(__pyx_k_asarray), 0, 0, 1, 1}, + {&__pyx_n_s_asyncio_coroutines, __pyx_k_asyncio_coroutines, sizeof(__pyx_k_asyncio_coroutines), 0, 0, 1, 1}, + {&__pyx_n_s_available_streams, __pyx_k_available_streams, sizeof(__pyx_k_available_streams), 0, 0, 1, 1}, + {&__pyx_n_s_base, __pyx_k_base, sizeof(__pyx_k_base), 0, 0, 1, 1}, + {&__pyx_n_s_block, __pyx_k_block, sizeof(__pyx_k_block), 0, 0, 1, 1}, + {&__pyx_n_s_blocking, __pyx_k_blocking, sizeof(__pyx_k_blocking), 0, 0, 1, 1}, + {&__pyx_n_s_buf, __pyx_k_buf, sizeof(__pyx_k_buf), 0, 0, 1, 1}, + {&__pyx_n_s_c, __pyx_k_c, sizeof(__pyx_k_c), 0, 0, 1, 1}, + {&__pyx_n_u_c, __pyx_k_c, sizeof(__pyx_k_c), 0, 1, 0, 1}, + {&__pyx_kp_s_cereal_visionipc_visionipc_pyx, __pyx_k_cereal_visionipc_visionipc_pyx, sizeof(__pyx_k_cereal_visionipc_visionipc_pyx), 0, 0, 1, 0}, + {&__pyx_kp_s_cereal_visionipc_visionipc_pyx_p, __pyx_k_cereal_visionipc_visionipc_pyx_p, sizeof(__pyx_k_cereal_visionipc_visionipc_pyx_p), 0, 0, 1, 0}, + {&__pyx_n_s_class, __pyx_k_class, sizeof(__pyx_k_class), 0, 0, 1, 1}, + {&__pyx_n_s_class_getitem, __pyx_k_class_getitem, sizeof(__pyx_k_class_getitem), 0, 0, 1, 1}, + {&__pyx_n_s_cline_in_traceback, __pyx_k_cline_in_traceback, sizeof(__pyx_k_cline_in_traceback), 0, 0, 1, 1}, + {&__pyx_n_s_cls, __pyx_k_cls, sizeof(__pyx_k_cls), 0, 0, 1, 1}, + {&__pyx_n_s_collections, __pyx_k_collections, sizeof(__pyx_k_collections), 0, 0, 1, 1}, + {&__pyx_kp_s_collections_abc, __pyx_k_collections_abc, sizeof(__pyx_k_collections_abc), 0, 0, 1, 0}, + {&__pyx_n_s_conflate, __pyx_k_conflate, sizeof(__pyx_k_conflate), 0, 0, 1, 1}, + {&__pyx_n_s_connect, __pyx_k_connect, sizeof(__pyx_k_connect), 0, 0, 1, 1}, + {&__pyx_n_s_context, __pyx_k_context, sizeof(__pyx_k_context), 0, 0, 1, 1}, + {&__pyx_kp_s_contiguous_and_direct, __pyx_k_contiguous_and_direct, sizeof(__pyx_k_contiguous_and_direct), 0, 0, 1, 0}, + {&__pyx_kp_s_contiguous_and_indirect, __pyx_k_contiguous_and_indirect, sizeof(__pyx_k_contiguous_and_indirect), 0, 0, 1, 0}, + {&__pyx_n_s_count, __pyx_k_count, sizeof(__pyx_k_count), 0, 0, 1, 1}, + {&__pyx_n_s_create_buffers, __pyx_k_create_buffers, sizeof(__pyx_k_create_buffers), 0, 0, 1, 1}, + {&__pyx_n_s_create_buffers_with_sizes, __pyx_k_create_buffers_with_sizes, sizeof(__pyx_k_create_buffers_with_sizes), 0, 0, 1, 1}, + {&__pyx_n_s_data, __pyx_k_data, sizeof(__pyx_k_data), 0, 0, 1, 1}, + {&__pyx_n_s_dct, __pyx_k_dct, sizeof(__pyx_k_dct), 0, 0, 1, 1}, + {&__pyx_n_s_dict, __pyx_k_dict, sizeof(__pyx_k_dict), 0, 0, 1, 1}, + {&__pyx_n_s_dict_2, __pyx_k_dict_2, sizeof(__pyx_k_dict_2), 0, 0, 1, 1}, + {&__pyx_kp_u_disable, __pyx_k_disable, sizeof(__pyx_k_disable), 0, 1, 0, 0}, + {&__pyx_n_s_doc, __pyx_k_doc, sizeof(__pyx_k_doc), 0, 0, 1, 1}, + {&__pyx_n_s_dtype_is_object, __pyx_k_dtype_is_object, sizeof(__pyx_k_dtype_is_object), 0, 0, 1, 1}, + {&__pyx_kp_u_enable, __pyx_k_enable, sizeof(__pyx_k_enable), 0, 1, 0, 0}, + {&__pyx_n_s_encode, __pyx_k_encode, sizeof(__pyx_k_encode), 0, 0, 1, 1}, + {&__pyx_n_s_enum, __pyx_k_enum, sizeof(__pyx_k_enum), 0, 0, 1, 1}, + {&__pyx_n_s_enumerate, __pyx_k_enumerate, sizeof(__pyx_k_enumerate), 0, 0, 1, 1}, + {&__pyx_n_s_error, __pyx_k_error, sizeof(__pyx_k_error), 0, 0, 1, 1}, + {&__pyx_n_s_extra, __pyx_k_extra, sizeof(__pyx_k_extra), 0, 0, 1, 1}, + {&__pyx_n_s_flags, __pyx_k_flags, sizeof(__pyx_k_flags), 0, 0, 1, 1}, + {&__pyx_n_s_format, __pyx_k_format, sizeof(__pyx_k_format), 0, 0, 1, 1}, + {&__pyx_n_s_fortran, __pyx_k_fortran, sizeof(__pyx_k_fortran), 0, 0, 1, 1}, + {&__pyx_n_u_fortran, __pyx_k_fortran, sizeof(__pyx_k_fortran), 0, 1, 0, 1}, + {&__pyx_n_s_frame_id, __pyx_k_frame_id, sizeof(__pyx_k_frame_id), 0, 0, 1, 1}, + {&__pyx_kp_u_gc, __pyx_k_gc, sizeof(__pyx_k_gc), 0, 1, 0, 0}, + {&__pyx_n_s_get, __pyx_k_get, sizeof(__pyx_k_get), 0, 0, 1, 1}, + {&__pyx_n_s_get_endpoint_name, __pyx_k_get_endpoint_name, sizeof(__pyx_k_get_endpoint_name), 0, 0, 1, 1}, + {&__pyx_n_s_getstate, __pyx_k_getstate, sizeof(__pyx_k_getstate), 0, 0, 1, 1}, + {&__pyx_kp_u_got, __pyx_k_got, sizeof(__pyx_k_got), 0, 1, 0, 0}, + {&__pyx_kp_u_got_differing_extents_in_dimensi, __pyx_k_got_differing_extents_in_dimensi, sizeof(__pyx_k_got_differing_extents_in_dimensi), 0, 1, 0, 0}, + {&__pyx_n_s_height, __pyx_k_height, sizeof(__pyx_k_height), 0, 0, 1, 1}, + {&__pyx_n_s_id, __pyx_k_id, sizeof(__pyx_k_id), 0, 0, 1, 1}, + {&__pyx_n_s_import, __pyx_k_import, sizeof(__pyx_k_import), 0, 0, 1, 1}, + {&__pyx_n_s_index, __pyx_k_index, sizeof(__pyx_k_index), 0, 0, 1, 1}, + {&__pyx_n_s_init, __pyx_k_init, sizeof(__pyx_k_init), 0, 0, 1, 1}, + {&__pyx_n_s_init_subclass, __pyx_k_init_subclass, sizeof(__pyx_k_init_subclass), 0, 0, 1, 1}, + {&__pyx_n_s_initializing, __pyx_k_initializing, sizeof(__pyx_k_initializing), 0, 0, 1, 1}, + {&__pyx_n_s_is_connected, __pyx_k_is_connected, sizeof(__pyx_k_is_connected), 0, 0, 1, 1}, + {&__pyx_n_s_is_coroutine, __pyx_k_is_coroutine, sizeof(__pyx_k_is_coroutine), 0, 0, 1, 1}, + {&__pyx_kp_u_isenabled, __pyx_k_isenabled, sizeof(__pyx_k_isenabled), 0, 1, 0, 0}, + {&__pyx_n_s_itemsize, __pyx_k_itemsize, sizeof(__pyx_k_itemsize), 0, 0, 1, 1}, + {&__pyx_kp_s_itemsize_0_for_cython_array, __pyx_k_itemsize_0_for_cython_array, sizeof(__pyx_k_itemsize_0_for_cython_array), 0, 0, 1, 0}, + {&__pyx_n_s_join, __pyx_k_join, sizeof(__pyx_k_join), 0, 0, 1, 1}, + {&__pyx_n_s_main, __pyx_k_main, sizeof(__pyx_k_main), 0, 0, 1, 1}, + {&__pyx_n_s_member_names, __pyx_k_member_names, sizeof(__pyx_k_member_names), 0, 0, 1, 1}, + {&__pyx_n_s_members, __pyx_k_members, sizeof(__pyx_k_members), 0, 0, 1, 1}, + {&__pyx_n_s_memview, __pyx_k_memview, sizeof(__pyx_k_memview), 0, 0, 1, 1}, + {&__pyx_n_s_metaclass, __pyx_k_metaclass, sizeof(__pyx_k_metaclass), 0, 0, 1, 1}, + {&__pyx_n_s_mode, __pyx_k_mode, sizeof(__pyx_k_mode), 0, 0, 1, 1}, + {&__pyx_n_s_module, __pyx_k_module, sizeof(__pyx_k_module), 0, 0, 1, 1}, + {&__pyx_n_s_module_2, __pyx_k_module_2, sizeof(__pyx_k_module_2), 0, 0, 1, 1}, + {&__pyx_n_s_mro_entries, __pyx_k_mro_entries, sizeof(__pyx_k_mro_entries), 0, 0, 1, 1}, + {&__pyx_n_s_name, __pyx_k_name, sizeof(__pyx_k_name), 0, 0, 1, 1}, + {&__pyx_n_s_name_2, __pyx_k_name_2, sizeof(__pyx_k_name_2), 0, 0, 1, 1}, + {&__pyx_n_s_ndim, __pyx_k_ndim, sizeof(__pyx_k_ndim), 0, 0, 1, 1}, + {&__pyx_n_s_new, __pyx_k_new, sizeof(__pyx_k_new), 0, 0, 1, 1}, + {&__pyx_kp_s_no_default___reduce___due_to_non, __pyx_k_no_default___reduce___due_to_non, sizeof(__pyx_k_no_default___reduce___due_to_non), 0, 0, 1, 0}, + {&__pyx_n_s_np, __pyx_k_np, sizeof(__pyx_k_np), 0, 0, 1, 1}, + {&__pyx_n_s_num_buffers, __pyx_k_num_buffers, sizeof(__pyx_k_num_buffers), 0, 0, 1, 1}, + {&__pyx_n_s_numpy, __pyx_k_numpy, sizeof(__pyx_k_numpy), 0, 0, 1, 1}, + {&__pyx_kp_u_numpy_core_multiarray_failed_to, __pyx_k_numpy_core_multiarray_failed_to, sizeof(__pyx_k_numpy_core_multiarray_failed_to), 0, 1, 0, 0}, + {&__pyx_kp_u_numpy_core_umath_failed_to_impor, __pyx_k_numpy_core_umath_failed_to_impor, sizeof(__pyx_k_numpy_core_umath_failed_to_impor), 0, 1, 0, 0}, + {&__pyx_n_s_obj, __pyx_k_obj, sizeof(__pyx_k_obj), 0, 0, 1, 1}, + {&__pyx_n_s_pack, __pyx_k_pack, sizeof(__pyx_k_pack), 0, 0, 1, 1}, + {&__pyx_n_s_parents, __pyx_k_parents, sizeof(__pyx_k_parents), 0, 0, 1, 1}, + {&__pyx_n_s_pickle, __pyx_k_pickle, sizeof(__pyx_k_pickle), 0, 0, 1, 1}, + {&__pyx_n_s_prepare, __pyx_k_prepare, sizeof(__pyx_k_prepare), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_PickleError, __pyx_k_pyx_PickleError, sizeof(__pyx_k_pyx_PickleError), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_checksum, __pyx_k_pyx_checksum, sizeof(__pyx_k_pyx_checksum), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_result, __pyx_k_pyx_result, sizeof(__pyx_k_pyx_result), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_state, __pyx_k_pyx_state, sizeof(__pyx_k_pyx_state), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_type, __pyx_k_pyx_type, sizeof(__pyx_k_pyx_type), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_unpickle_Enum, __pyx_k_pyx_unpickle_Enum, sizeof(__pyx_k_pyx_unpickle_Enum), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_unpickle___Pyx_EnumMeta, __pyx_k_pyx_unpickle___Pyx_EnumMeta, sizeof(__pyx_k_pyx_unpickle___Pyx_EnumMeta), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_vtable, __pyx_k_pyx_vtable, sizeof(__pyx_k_pyx_vtable), 0, 0, 1, 1}, + {&__pyx_n_s_qualname, __pyx_k_qualname, sizeof(__pyx_k_qualname), 0, 0, 1, 1}, + {&__pyx_n_s_range, __pyx_k_range, sizeof(__pyx_k_range), 0, 0, 1, 1}, + {&__pyx_n_s_recv, __pyx_k_recv, sizeof(__pyx_k_recv), 0, 0, 1, 1}, + {&__pyx_n_s_reduce, __pyx_k_reduce, sizeof(__pyx_k_reduce), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_cython, __pyx_k_reduce_cython, sizeof(__pyx_k_reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_ex, __pyx_k_reduce_ex, sizeof(__pyx_k_reduce_ex), 0, 0, 1, 1}, + {&__pyx_n_s_register, __pyx_k_register, sizeof(__pyx_k_register), 0, 0, 1, 1}, + {&__pyx_n_s_repr, __pyx_k_repr, sizeof(__pyx_k_repr), 0, 0, 1, 1}, + {&__pyx_n_s_res, __pyx_k_res, sizeof(__pyx_k_res), 0, 0, 1, 1}, + {&__pyx_n_s_rgb, __pyx_k_rgb, sizeof(__pyx_k_rgb), 0, 0, 1, 1}, + {&__pyx_kp_s_s_s, __pyx_k_s_s, sizeof(__pyx_k_s_s), 0, 0, 1, 0}, + {&__pyx_kp_s_s_s_d, __pyx_k_s_s_d, sizeof(__pyx_k_s_s_d), 0, 0, 1, 0}, + {&__pyx_n_s_self, __pyx_k_self, sizeof(__pyx_k_self), 0, 0, 1, 1}, + {&__pyx_kp_s_self_buf_cannot_be_converted_to, __pyx_k_self_buf_cannot_be_converted_to, sizeof(__pyx_k_self_buf_cannot_be_converted_to), 0, 0, 1, 0}, + {&__pyx_kp_s_self_server_cannot_be_converted, __pyx_k_self_server_cannot_be_converted, sizeof(__pyx_k_self_server_cannot_be_converted), 0, 0, 1, 0}, + {&__pyx_n_s_send, __pyx_k_send, sizeof(__pyx_k_send), 0, 0, 1, 1}, + {&__pyx_n_s_set_name, __pyx_k_set_name, sizeof(__pyx_k_set_name), 0, 0, 1, 1}, + {&__pyx_n_s_setstate, __pyx_k_setstate, sizeof(__pyx_k_setstate), 0, 0, 1, 1}, + {&__pyx_n_s_setstate_cython, __pyx_k_setstate_cython, sizeof(__pyx_k_setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_shape, __pyx_k_shape, sizeof(__pyx_k_shape), 0, 0, 1, 1}, + {&__pyx_n_s_size, __pyx_k_size, sizeof(__pyx_k_size), 0, 0, 1, 1}, + {&__pyx_n_s_spec, __pyx_k_spec, sizeof(__pyx_k_spec), 0, 0, 1, 1}, + {&__pyx_n_s_start, __pyx_k_start, sizeof(__pyx_k_start), 0, 0, 1, 1}, + {&__pyx_n_s_start_listener, __pyx_k_start_listener, sizeof(__pyx_k_start_listener), 0, 0, 1, 1}, + {&__pyx_n_s_state, __pyx_k_state, sizeof(__pyx_k_state), 0, 0, 1, 1}, + {&__pyx_n_s_staticmethod, __pyx_k_staticmethod, sizeof(__pyx_k_staticmethod), 0, 0, 1, 1}, + {&__pyx_n_s_step, __pyx_k_step, sizeof(__pyx_k_step), 0, 0, 1, 1}, + {&__pyx_n_s_stop, __pyx_k_stop, sizeof(__pyx_k_stop), 0, 0, 1, 1}, + {&__pyx_n_s_str, __pyx_k_str, sizeof(__pyx_k_str), 0, 0, 1, 1}, + {&__pyx_n_s_stream, __pyx_k_stream, sizeof(__pyx_k_stream), 0, 0, 1, 1}, + {&__pyx_n_s_stride, __pyx_k_stride, sizeof(__pyx_k_stride), 0, 0, 1, 1}, + {&__pyx_kp_s_strided_and_direct, __pyx_k_strided_and_direct, sizeof(__pyx_k_strided_and_direct), 0, 0, 1, 0}, + {&__pyx_kp_s_strided_and_direct_or_indirect, __pyx_k_strided_and_direct_or_indirect, sizeof(__pyx_k_strided_and_direct_or_indirect), 0, 0, 1, 0}, + {&__pyx_kp_s_strided_and_indirect, __pyx_k_strided_and_indirect, sizeof(__pyx_k_strided_and_indirect), 0, 0, 1, 0}, + {&__pyx_kp_s_stringsource, __pyx_k_stringsource, sizeof(__pyx_k_stringsource), 0, 0, 1, 0}, + {&__pyx_n_s_struct, __pyx_k_struct, sizeof(__pyx_k_struct), 0, 0, 1, 1}, + {&__pyx_n_s_super, __pyx_k_super, sizeof(__pyx_k_super), 0, 0, 1, 1}, + {&__pyx_n_s_sys, __pyx_k_sys, sizeof(__pyx_k_sys), 0, 0, 1, 1}, + {&__pyx_n_s_test, __pyx_k_test, sizeof(__pyx_k_test), 0, 0, 1, 1}, + {&__pyx_n_s_timeout_ms, __pyx_k_timeout_ms, sizeof(__pyx_k_timeout_ms), 0, 0, 1, 1}, + {&__pyx_n_s_timestamp_eof, __pyx_k_timestamp_eof, sizeof(__pyx_k_timestamp_eof), 0, 0, 1, 1}, + {&__pyx_n_s_timestamp_sof, __pyx_k_timestamp_sof, sizeof(__pyx_k_timestamp_sof), 0, 0, 1, 1}, + {&__pyx_n_s_tp, __pyx_k_tp, sizeof(__pyx_k_tp), 0, 0, 1, 1}, + {&__pyx_kp_s_unable_to_allocate_array_data, __pyx_k_unable_to_allocate_array_data, sizeof(__pyx_k_unable_to_allocate_array_data), 0, 0, 1, 0}, + {&__pyx_kp_s_unable_to_allocate_shape_and_str, __pyx_k_unable_to_allocate_shape_and_str, sizeof(__pyx_k_unable_to_allocate_shape_and_str), 0, 0, 1, 0}, + {&__pyx_n_s_unpack, __pyx_k_unpack, sizeof(__pyx_k_unpack), 0, 0, 1, 1}, + {&__pyx_n_s_update, __pyx_k_update, sizeof(__pyx_k_update), 0, 0, 1, 1}, + {&__pyx_n_s_use_setstate, __pyx_k_use_setstate, sizeof(__pyx_k_use_setstate), 0, 0, 1, 1}, + {&__pyx_n_s_uv_offset, __pyx_k_uv_offset, sizeof(__pyx_k_uv_offset), 0, 0, 1, 1}, + {&__pyx_n_s_v, __pyx_k_v, sizeof(__pyx_k_v), 0, 0, 1, 1}, + {&__pyx_n_s_value, __pyx_k_value, sizeof(__pyx_k_value), 0, 0, 1, 1}, + {&__pyx_n_s_values, __pyx_k_values, sizeof(__pyx_k_values), 0, 0, 1, 1}, + {&__pyx_n_s_version_info, __pyx_k_version_info, sizeof(__pyx_k_version_info), 0, 0, 1, 1}, + {&__pyx_n_s_width, __pyx_k_width, sizeof(__pyx_k_width), 0, 0, 1, 1}, + {0, 0, 0, 0, 0, 0, 0} + }; + return __Pyx_InitStrings(__pyx_string_tab); +} +/* #### Code section: cached_builtins ### */ +static CYTHON_SMALL_CODE int __Pyx_InitCachedBuiltins(void) { + __pyx_builtin_staticmethod = __Pyx_GetBuiltinName(__pyx_n_s_staticmethod); if (!__pyx_builtin_staticmethod) __PYX_ERR(0, 166, __pyx_L1_error) + __pyx_builtin_TypeError = __Pyx_GetBuiltinName(__pyx_n_s_TypeError); if (!__pyx_builtin_TypeError) __PYX_ERR(1, 2, __pyx_L1_error) + __pyx_builtin_AssertionError = __Pyx_GetBuiltinName(__pyx_n_s_AssertionError); if (!__pyx_builtin_AssertionError) __PYX_ERR(0, 79, __pyx_L1_error) + __pyx_builtin_ValueError = __Pyx_GetBuiltinName(__pyx_n_s_ValueError); if (!__pyx_builtin_ValueError) __PYX_ERR(1, 33, __pyx_L1_error) + __pyx_builtin___import__ = __Pyx_GetBuiltinName(__pyx_n_s_import); if (!__pyx_builtin___import__) __PYX_ERR(1, 100, __pyx_L1_error) + __pyx_builtin_MemoryError = __Pyx_GetBuiltinName(__pyx_n_s_MemoryError); if (!__pyx_builtin_MemoryError) __PYX_ERR(1, 156, __pyx_L1_error) + __pyx_builtin_enumerate = __Pyx_GetBuiltinName(__pyx_n_s_enumerate); if (!__pyx_builtin_enumerate) __PYX_ERR(1, 159, __pyx_L1_error) + __pyx_builtin_range = __Pyx_GetBuiltinName(__pyx_n_s_range); if (!__pyx_builtin_range) __PYX_ERR(1, 261, __pyx_L1_error) + __pyx_builtin_Ellipsis = __Pyx_GetBuiltinName(__pyx_n_s_Ellipsis); if (!__pyx_builtin_Ellipsis) __PYX_ERR(1, 408, __pyx_L1_error) + __pyx_builtin_id = __Pyx_GetBuiltinName(__pyx_n_s_id); if (!__pyx_builtin_id) __PYX_ERR(1, 618, __pyx_L1_error) + __pyx_builtin_IndexError = __Pyx_GetBuiltinName(__pyx_n_s_IndexError); if (!__pyx_builtin_IndexError) __PYX_ERR(1, 914, __pyx_L1_error) + __pyx_builtin_ImportError = __Pyx_GetBuiltinName(__pyx_n_s_ImportError); if (!__pyx_builtin_ImportError) __PYX_ERR(2, 984, __pyx_L1_error) + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: cached_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_InitCachedConstants", 0); + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0xe3b0c44, 0xda39a3e, 0xd41d8cd): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0xe3b0c44, 0xda39a3e, 0xd41d8cd) = ())" % __pyx_checksum + */ + __pyx_tuple__2 = PyTuple_Pack(3, __pyx_int_238750788, __pyx_int_228825662, __pyx_int_222419149); if (unlikely(!__pyx_tuple__2)) __PYX_ERR(1, 4, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__2); + __Pyx_GIVEREF(__pyx_tuple__2); + + /* "View.MemoryView":582 + * def suboffsets(self): + * if self.view.suboffsets == NULL: + * return (-1,) * self.view.ndim # <<<<<<<<<<<<<< + * + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + */ + __pyx_tuple__6 = PyTuple_New(1); if (unlikely(!__pyx_tuple__6)) __PYX_ERR(1, 582, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__6); + __Pyx_INCREF(__pyx_int_neg_1); + __Pyx_GIVEREF(__pyx_int_neg_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_tuple__6, 0, __pyx_int_neg_1)) __PYX_ERR(1, 582, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_tuple__6); + + /* "View.MemoryView":679 + * tup = index if isinstance(index, tuple) else (index,) + * + * result = [slice(None)] * ndim # <<<<<<<<<<<<<< + * have_slices = False + * seen_ellipsis = False + */ + __pyx_slice__7 = PySlice_New(Py_None, Py_None, Py_None); if (unlikely(!__pyx_slice__7)) __PYX_ERR(1, 679, __pyx_L1_error) + __Pyx_GOTREF(__pyx_slice__7); + __Pyx_GIVEREF(__pyx_slice__7); + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + */ + __pyx_tuple__10 = PyTuple_Pack(3, __pyx_int_136983863, __pyx_int_112105877, __pyx_int_184977713); if (unlikely(!__pyx_tuple__10)) __PYX_ERR(1, 4, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__10); + __Pyx_GIVEREF(__pyx_tuple__10); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":984 + * __pyx_import_array() + * except Exception: + * raise ImportError("numpy.core.multiarray failed to import") # <<<<<<<<<<<<<< + * + * cdef inline int import_umath() except -1: + */ + __pyx_tuple__16 = PyTuple_Pack(1, __pyx_kp_u_numpy_core_multiarray_failed_to); if (unlikely(!__pyx_tuple__16)) __PYX_ERR(2, 984, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__16); + __Pyx_GIVEREF(__pyx_tuple__16); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":990 + * _import_umath() + * except Exception: + * raise ImportError("numpy.core.umath failed to import") # <<<<<<<<<<<<<< + * + * cdef inline int import_ufunc() except -1: + */ + __pyx_tuple__17 = PyTuple_Pack(1, __pyx_kp_u_numpy_core_umath_failed_to_impor); if (unlikely(!__pyx_tuple__17)) __PYX_ERR(2, 990, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__17); + __Pyx_GIVEREF(__pyx_tuple__17); + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * cdef tuple state + * cdef object _dict + */ + __pyx_tuple__18 = PyTuple_Pack(4, __pyx_n_s_self, __pyx_n_s_state, __pyx_n_s_dict_2, __pyx_n_s_use_setstate); if (unlikely(!__pyx_tuple__18)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__18); + __Pyx_GIVEREF(__pyx_tuple__18); + __pyx_codeobj__19 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 4, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__18, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__19)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "(tree fragment)":16 + * else: + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, state) + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * __pyx_unpickle___Pyx_EnumMeta__set_state(self, __pyx_state) + */ + __pyx_tuple__20 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_pyx_state); if (unlikely(!__pyx_tuple__20)) __PYX_ERR(1, 16, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__20); + __Pyx_GIVEREF(__pyx_tuple__20); + __pyx_codeobj__21 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__20, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 16, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__21)) __PYX_ERR(1, 16, __pyx_L1_error) + + /* "EnumBase":28 + * cdef object __Pyx_EnumBase + * class __Pyx_EnumBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): # <<<<<<<<<<<<<< + * for v in cls: + * if v == value: + */ + __pyx_tuple__22 = PyTuple_Pack(5, __pyx_n_s_cls, __pyx_n_s_value, __pyx_n_s_name, __pyx_n_s_v, __pyx_n_s_res); if (unlikely(!__pyx_tuple__22)) __PYX_ERR(1, 28, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__22); + __Pyx_GIVEREF(__pyx_tuple__22); + __pyx_codeobj__23 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__22, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_new, 28, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__23)) __PYX_ERR(1, 28, __pyx_L1_error) + __pyx_tuple__24 = PyTuple_Pack(1, Py_None); if (unlikely(!__pyx_tuple__24)) __PYX_ERR(1, 28, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__24); + __Pyx_GIVEREF(__pyx_tuple__24); + + /* "EnumBase":39 + * cls.__members__[name] = res + * return res + * def __repr__(self): # <<<<<<<<<<<<<< + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): + */ + __pyx_tuple__25 = PyTuple_Pack(1, __pyx_n_s_self); if (unlikely(!__pyx_tuple__25)) __PYX_ERR(1, 39, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__25); + __Pyx_GIVEREF(__pyx_tuple__25); + __pyx_codeobj__26 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__25, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_repr, 39, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__26)) __PYX_ERR(1, 39, __pyx_L1_error) + + /* "EnumBase":41 + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): # <<<<<<<<<<<<<< + * return "%s.%s" % (self.__class__.__name__, self.name) + * + */ + __pyx_codeobj__27 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__25, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_str, 41, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__27)) __PYX_ERR(1, 41, __pyx_L1_error) + + /* "EnumBase":49 + * cdef object __Pyx_FlagBase + * class __Pyx_FlagBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): # <<<<<<<<<<<<<< + * for v in cls: + * if v == value: + */ + __pyx_codeobj__28 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__22, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_new, 49, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__28)) __PYX_ERR(1, 49, __pyx_L1_error) + + /* "EnumBase":62 + * cls.__members__[name] = res + * return res + * def __repr__(self): # <<<<<<<<<<<<<< + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): + */ + __pyx_codeobj__29 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__25, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_repr, 62, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__29)) __PYX_ERR(1, 62, __pyx_L1_error) + + /* "EnumBase":64 + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): # <<<<<<<<<<<<<< + * return "%s.%s" % (self.__class__.__name__, self.name) + * + */ + __pyx_codeobj__30 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__25, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_str, 64, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__30)) __PYX_ERR(1, 64, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __pyx_unpickle___Pyx_EnumMeta(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + __pyx_tuple__31 = PyTuple_Pack(5, __pyx_n_s_pyx_type, __pyx_n_s_pyx_checksum, __pyx_n_s_pyx_state, __pyx_n_s_pyx_PickleError, __pyx_n_s_pyx_result); if (unlikely(!__pyx_tuple__31)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__31); + __Pyx_GIVEREF(__pyx_tuple__31); + __pyx_codeobj__32 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__31, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_pyx_unpickle___Pyx_EnumMeta, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__32)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "View.MemoryView":100 + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: + * if __import__("sys").version_info >= (3, 3): # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + */ + __pyx_tuple__33 = PyTuple_Pack(1, __pyx_n_s_sys); if (unlikely(!__pyx_tuple__33)) __PYX_ERR(1, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__33); + __Pyx_GIVEREF(__pyx_tuple__33); + __pyx_tuple__34 = PyTuple_Pack(2, __pyx_int_3, __pyx_int_3); if (unlikely(!__pyx_tuple__34)) __PYX_ERR(1, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__34); + __Pyx_GIVEREF(__pyx_tuple__34); + + /* "View.MemoryView":101 + * try: + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence # <<<<<<<<<<<<<< + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence + */ + __pyx_tuple__35 = PyTuple_Pack(1, __pyx_kp_s_collections_abc); if (unlikely(!__pyx_tuple__35)) __PYX_ERR(1, 101, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__35); + __Pyx_GIVEREF(__pyx_tuple__35); + + /* "View.MemoryView":103 + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence # <<<<<<<<<<<<<< + * except: + * + */ + __pyx_tuple__36 = PyTuple_Pack(1, __pyx_n_s_collections); if (unlikely(!__pyx_tuple__36)) __PYX_ERR(1, 103, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__36); + __Pyx_GIVEREF(__pyx_tuple__36); + + /* "View.MemoryView":309 + * return self.name + * + * cdef generic = Enum("") # <<<<<<<<<<<<<< + * cdef strided = Enum("") # default + * cdef indirect = Enum("") + */ + __pyx_tuple__37 = PyTuple_Pack(1, __pyx_kp_s_strided_and_direct_or_indirect); if (unlikely(!__pyx_tuple__37)) __PYX_ERR(1, 309, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__37); + __Pyx_GIVEREF(__pyx_tuple__37); + + /* "View.MemoryView":310 + * + * cdef generic = Enum("") + * cdef strided = Enum("") # default # <<<<<<<<<<<<<< + * cdef indirect = Enum("") + * + */ + __pyx_tuple__38 = PyTuple_Pack(1, __pyx_kp_s_strided_and_direct); if (unlikely(!__pyx_tuple__38)) __PYX_ERR(1, 310, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__38); + __Pyx_GIVEREF(__pyx_tuple__38); + + /* "View.MemoryView":311 + * cdef generic = Enum("") + * cdef strided = Enum("") # default + * cdef indirect = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_tuple__39 = PyTuple_Pack(1, __pyx_kp_s_strided_and_indirect); if (unlikely(!__pyx_tuple__39)) __PYX_ERR(1, 311, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__39); + __Pyx_GIVEREF(__pyx_tuple__39); + + /* "View.MemoryView":314 + * + * + * cdef contiguous = Enum("") # <<<<<<<<<<<<<< + * cdef indirect_contiguous = Enum("") + * + */ + __pyx_tuple__40 = PyTuple_Pack(1, __pyx_kp_s_contiguous_and_direct); if (unlikely(!__pyx_tuple__40)) __PYX_ERR(1, 314, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__40); + __Pyx_GIVEREF(__pyx_tuple__40); + + /* "View.MemoryView":315 + * + * cdef contiguous = Enum("") + * cdef indirect_contiguous = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_tuple__41 = PyTuple_Pack(1, __pyx_kp_s_contiguous_and_indirect); if (unlikely(!__pyx_tuple__41)) __PYX_ERR(1, 315, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__41); + __Pyx_GIVEREF(__pyx_tuple__41); + + /* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + __pyx_codeobj__42 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__31, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_pyx_unpickle_Enum, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__42)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "cereal/visionipc/visionipc_pyx.pyx":20 + * + * + * def get_endpoint_name(string name, VisionStreamType stream): # <<<<<<<<<<<<<< + * return cpp_get_endpoint_name(name, stream).decode('utf-8') + * + */ + __pyx_tuple__43 = PyTuple_Pack(2, __pyx_n_s_name, __pyx_n_s_stream); if (unlikely(!__pyx_tuple__43)) __PYX_ERR(0, 20, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__43); + __Pyx_GIVEREF(__pyx_tuple__43); + __pyx_codeobj__44 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__43, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_visionipc_visionipc_pyx_p, __pyx_n_s_get_endpoint_name, 20, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__44)) __PYX_ERR(0, 20, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.buf cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_codeobj__45 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__25, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__45)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.buf cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.buf cannot be converted to a Python object for pickling" + */ + __pyx_codeobj__46 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__20, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__46)) __PYX_ERR(1, 3, __pyx_L1_error) + + /* "cereal/visionipc/visionipc_pyx.pyx":69 + * self.server = new cppVisionIpcServer(name, NULL, NULL) + * + * def create_buffers(self, VisionStreamType tp, size_t num_buffers, bool rgb, size_t width, size_t height): # <<<<<<<<<<<<<< + * self.server.create_buffers(tp, num_buffers, rgb, width, height) + * + */ + __pyx_tuple__47 = PyTuple_Pack(6, __pyx_n_s_self, __pyx_n_s_tp, __pyx_n_s_num_buffers, __pyx_n_s_rgb, __pyx_n_s_width, __pyx_n_s_height); if (unlikely(!__pyx_tuple__47)) __PYX_ERR(0, 69, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__47); + __Pyx_GIVEREF(__pyx_tuple__47); + __pyx_codeobj__48 = (PyObject*)__Pyx_PyCode_New(6, 0, 0, 6, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__47, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_visionipc_visionipc_pyx_p, __pyx_n_s_create_buffers, 69, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__48)) __PYX_ERR(0, 69, __pyx_L1_error) + + /* "cereal/visionipc/visionipc_pyx.pyx":72 + * self.server.create_buffers(tp, num_buffers, rgb, width, height) + * + * def create_buffers_with_sizes(self, VisionStreamType tp, size_t num_buffers, bool rgb, size_t width, size_t height, size_t size, size_t stride, size_t uv_offset): # <<<<<<<<<<<<<< + * self.server.create_buffers_with_sizes(tp, num_buffers, rgb, width, height, size, stride, uv_offset) + * + */ + __pyx_tuple__49 = PyTuple_Pack(9, __pyx_n_s_self, __pyx_n_s_tp, __pyx_n_s_num_buffers, __pyx_n_s_rgb, __pyx_n_s_width, __pyx_n_s_height, __pyx_n_s_size, __pyx_n_s_stride, __pyx_n_s_uv_offset); if (unlikely(!__pyx_tuple__49)) __PYX_ERR(0, 72, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__49); + __Pyx_GIVEREF(__pyx_tuple__49); + __pyx_codeobj__50 = (PyObject*)__Pyx_PyCode_New(9, 0, 0, 9, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__49, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_visionipc_visionipc_pyx_p, __pyx_n_s_create_buffers_with_sizes, 72, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__50)) __PYX_ERR(0, 72, __pyx_L1_error) + + /* "cereal/visionipc/visionipc_pyx.pyx":75 + * self.server.create_buffers_with_sizes(tp, num_buffers, rgb, width, height, size, stride, uv_offset) + * + * def send(self, VisionStreamType tp, const unsigned char[:] data, uint32_t frame_id=0, uint64_t timestamp_sof=0, uint64_t timestamp_eof=0): # <<<<<<<<<<<<<< + * cdef cppVisionBuf * buf = self.server.get_buffer(tp) + * + */ + __pyx_tuple__51 = PyTuple_Pack(8, __pyx_n_s_self, __pyx_n_s_tp, __pyx_n_s_data, __pyx_n_s_frame_id, __pyx_n_s_timestamp_sof, __pyx_n_s_timestamp_eof, __pyx_n_s_buf, __pyx_n_s_extra); if (unlikely(!__pyx_tuple__51)) __PYX_ERR(0, 75, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__51); + __Pyx_GIVEREF(__pyx_tuple__51); + __pyx_codeobj__52 = (PyObject*)__Pyx_PyCode_New(6, 0, 0, 8, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__51, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_visionipc_visionipc_pyx_p, __pyx_n_s_send, 75, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__52)) __PYX_ERR(0, 75, __pyx_L1_error) + __pyx_tuple__53 = PyTuple_Pack(3, __pyx_int_0, __pyx_int_0, __pyx_int_0); if (unlikely(!__pyx_tuple__53)) __PYX_ERR(0, 75, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__53); + __Pyx_GIVEREF(__pyx_tuple__53); + + /* "cereal/visionipc/visionipc_pyx.pyx":90 + * self.server.send(buf, &extra, False) + * + * def start_listener(self): # <<<<<<<<<<<<<< + * self.server.start_listener() + * + */ + __pyx_codeobj__54 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__25, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_visionipc_visionipc_pyx_p, __pyx_n_s_start_listener, 90, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__54)) __PYX_ERR(0, 90, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.server cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_codeobj__55 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__25, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__55)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.server cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.server cannot be converted to a Python object for pickling" + */ + __pyx_codeobj__56 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__20, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__56)) __PYX_ERR(1, 3, __pyx_L1_error) + + /* "cereal/visionipc/visionipc_pyx.pyx":154 + * return self.extra.valid + * + * def recv(self, int timeout_ms=100): # <<<<<<<<<<<<<< + * buf = self.client.recv(&self.extra, timeout_ms) + * if not buf: + */ + __pyx_tuple__57 = PyTuple_Pack(3, __pyx_n_s_self, __pyx_n_s_timeout_ms, __pyx_n_s_buf); if (unlikely(!__pyx_tuple__57)) __PYX_ERR(0, 154, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__57); + __Pyx_GIVEREF(__pyx_tuple__57); + __pyx_codeobj__58 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__57, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_visionipc_visionipc_pyx_p, __pyx_n_s_recv, 154, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__58)) __PYX_ERR(0, 154, __pyx_L1_error) + __pyx_tuple__59 = PyTuple_Pack(1, __pyx_int_100); if (unlikely(!__pyx_tuple__59)) __PYX_ERR(0, 154, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__59); + __Pyx_GIVEREF(__pyx_tuple__59); + + /* "cereal/visionipc/visionipc_pyx.pyx":160 + * return VisionBuf.create(buf) + * + * def connect(self, bool blocking): # <<<<<<<<<<<<<< + * return self.client.connect(blocking) + * + */ + __pyx_tuple__60 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_blocking); if (unlikely(!__pyx_tuple__60)) __PYX_ERR(0, 160, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__60); + __Pyx_GIVEREF(__pyx_tuple__60); + __pyx_codeobj__61 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__60, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_visionipc_visionipc_pyx_p, __pyx_n_s_connect, 160, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__61)) __PYX_ERR(0, 160, __pyx_L1_error) + + /* "cereal/visionipc/visionipc_pyx.pyx":163 + * return self.client.connect(blocking) + * + * def is_connected(self): # <<<<<<<<<<<<<< + * return self.client.is_connected() + * + */ + __pyx_codeobj__62 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__25, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_visionipc_visionipc_pyx_p, __pyx_n_s_is_connected, 163, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__62)) __PYX_ERR(0, 163, __pyx_L1_error) + + /* "cereal/visionipc/visionipc_pyx.pyx":166 + * return self.client.is_connected() + * + * @staticmethod # <<<<<<<<<<<<<< + * def available_streams(string name, bool block): + * return cppVisionIpcClient.getAvailableStreams(name, block) + */ + __pyx_tuple__63 = PyTuple_Pack(2, __pyx_n_s_name, __pyx_n_s_block); if (unlikely(!__pyx_tuple__63)) __PYX_ERR(0, 166, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__63); + __Pyx_GIVEREF(__pyx_tuple__63); + __pyx_codeobj__64 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__63, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_cereal_visionipc_visionipc_pyx_p, __pyx_n_s_available_streams, 166, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__64)) __PYX_ERR(0, 166, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_codeobj__65 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__25, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__65)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_codeobj__66 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__20, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__66)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_RefNannyFinishContext(); + return -1; +} +/* #### Code section: init_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitConstants(void) { + __pyx_umethod_PyDict_Type_get.type = (PyObject*)&PyDict_Type; + __pyx_umethod_PyDict_Type_get.method_name = &__pyx_n_s_get; + if (__Pyx_CreateStringTabAndInitStrings() < 0) __PYX_ERR(0, 1, __pyx_L1_error); + __pyx_int_0 = PyInt_FromLong(0); if (unlikely(!__pyx_int_0)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_1 = PyInt_FromLong(1); if (unlikely(!__pyx_int_1)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_3 = PyInt_FromLong(3); if (unlikely(!__pyx_int_3)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_100 = PyInt_FromLong(100); if (unlikely(!__pyx_int_100)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_112105877 = PyInt_FromLong(112105877L); if (unlikely(!__pyx_int_112105877)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_136983863 = PyInt_FromLong(136983863L); if (unlikely(!__pyx_int_136983863)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_184977713 = PyInt_FromLong(184977713L); if (unlikely(!__pyx_int_184977713)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_222419149 = PyInt_FromLong(222419149L); if (unlikely(!__pyx_int_222419149)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_228825662 = PyInt_FromLong(228825662L); if (unlikely(!__pyx_int_228825662)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_238750788 = PyInt_FromLong(238750788L); if (unlikely(!__pyx_int_238750788)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_neg_1 = PyInt_FromLong(-1); if (unlikely(!__pyx_int_neg_1)) __PYX_ERR(0, 1, __pyx_L1_error) + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: init_globals ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitGlobals(void) { + /* AssertionsEnabled.init */ + if (likely(__Pyx_init_assertions_enabled() == 0)); else + +if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 1, __pyx_L1_error) + + /* NumpyImportArray.init */ + /* + * Cython has automatically inserted a call to _import_array since + * you didn't include one when you cimported numpy. To disable this + * add the line + * numpy._import_array + */ +#ifdef NPY_FEATURE_VERSION +#ifndef NO_IMPORT_ARRAY +if (unlikely(_import_array() == -1)) { + PyErr_SetString(PyExc_ImportError, "numpy.core.multiarray failed to import " + "(auto-generated because you didn't call 'numpy.import_array()' after cimporting numpy; " + "use 'numpy._import_array' to disable if you are certain you don't need it)."); +} +#endif +#endif + +if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 1, __pyx_L1_error) + + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: init_module ### */ + +static CYTHON_SMALL_CODE int __Pyx_modinit_global_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_import_code(void); /*proto*/ + +static int __Pyx_modinit_global_init_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_global_init_code", 0); + /*--- Global init code ---*/ + __Pyx_OrderedDict = Py_None; Py_INCREF(Py_None); + __Pyx_EnumBase = Py_None; Py_INCREF(Py_None); + __Pyx_FlagBase = Py_None; Py_INCREF(Py_None); + __pyx_collections_abc_Sequence = Py_None; Py_INCREF(Py_None); + generic = Py_None; Py_INCREF(Py_None); + strided = Py_None; Py_INCREF(Py_None); + indirect = Py_None; Py_INCREF(Py_None); + contiguous = Py_None; Py_INCREF(Py_None); + indirect_contiguous = Py_None; Py_INCREF(Py_None); + __Pyx_globals = ((PyObject*)Py_None); Py_INCREF(Py_None); + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_variable_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_export_code", 0); + /*--- Variable export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_export_code", 0); + /*--- Function export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_type_init_code(void) { + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_modinit_type_init_code", 0); + /*--- Type init code ---*/ + #if CYTHON_USE_TYPE_SPECS + __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_6cereal_9visionipc_13visionipc_pyx_CLContext_spec, NULL); if (unlikely(!__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext)) __PYX_ERR(3, 7, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_6cereal_9visionipc_13visionipc_pyx_CLContext_spec, __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext) < 0) __PYX_ERR(3, 7, __pyx_L1_error) + #else + __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext = &__pyx_type_6cereal_9visionipc_13visionipc_pyx_CLContext; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext) < 0) __PYX_ERR(3, 7, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext->tp_dictoffset && __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_CLContext, (PyObject *) __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext) < 0) __PYX_ERR(3, 7, __pyx_L1_error) + __pyx_vtabptr_6cereal_9visionipc_13visionipc_pyx_VisionBuf = &__pyx_vtable_6cereal_9visionipc_13visionipc_pyx_VisionBuf; + __pyx_vtable_6cereal_9visionipc_13visionipc_pyx_VisionBuf.create = (PyObject *(*)(VisionBuf *))__pyx_f_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_create; + #if CYTHON_USE_TYPE_SPECS + __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionBuf_spec, NULL); if (unlikely(!__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf)) __PYX_ERR(0, 31, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionBuf_spec, __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf) < 0) __PYX_ERR(0, 31, __pyx_L1_error) + #else + __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf = &__pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionBuf; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf) < 0) __PYX_ERR(0, 31, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf->tp_dictoffset && __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (__Pyx_SetVtable(__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf, __pyx_vtabptr_6cereal_9visionipc_13visionipc_pyx_VisionBuf) < 0) __PYX_ERR(0, 31, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf) < 0) __PYX_ERR(0, 31, __pyx_L1_error) + #endif + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_VisionBuf, (PyObject *) __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf) < 0) __PYX_ERR(0, 31, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf) < 0) __PYX_ERR(0, 31, __pyx_L1_error) + #endif + #if CYTHON_USE_TYPE_SPECS + __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer_spec, NULL); if (unlikely(!__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer)) __PYX_ERR(0, 63, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer_spec, __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer) < 0) __PYX_ERR(0, 63, __pyx_L1_error) + #else + __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer = &__pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer) < 0) __PYX_ERR(0, 63, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer->tp_dictoffset && __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_VisionIpcServer, (PyObject *) __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer) < 0) __PYX_ERR(0, 63, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer) < 0) __PYX_ERR(0, 63, __pyx_L1_error) + #endif + #if CYTHON_USE_TYPE_SPECS + __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient_spec, NULL); if (unlikely(!__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient)) __PYX_ERR(0, 97, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient_spec, __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient) < 0) __PYX_ERR(0, 97, __pyx_L1_error) + #else + __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient = &__pyx_type_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient) < 0) __PYX_ERR(0, 97, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient->tp_dictoffset && __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_VisionIpcClient, (PyObject *) __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient) < 0) __PYX_ERR(0, 97, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient) < 0) __PYX_ERR(0, 97, __pyx_L1_error) + #endif + #if CYTHON_USE_TYPE_SPECS + __pyx_t_1 = PyTuple_Pack(1, (PyObject *)(&PyType_Type)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 16, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_ptype___Pyx_EnumMeta = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__Pyx_EnumMeta_spec, __pyx_t_1); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_ptype___Pyx_EnumMeta)) __PYX_ERR(1, 16, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__Pyx_EnumMeta_spec, __pyx_ptype___Pyx_EnumMeta) < 0) __PYX_ERR(1, 16, __pyx_L1_error) + #else + __pyx_ptype___Pyx_EnumMeta = &__Pyx_EnumMeta; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + __pyx_ptype___Pyx_EnumMeta->tp_dealloc = (&PyType_Type)->tp_dealloc; + __pyx_ptype___Pyx_EnumMeta->tp_base = (&PyType_Type); + __pyx_ptype___Pyx_EnumMeta->tp_new = (&PyType_Type)->tp_new; + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype___Pyx_EnumMeta) < 0) __PYX_ERR(1, 16, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype___Pyx_EnumMeta->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype___Pyx_EnumMeta->tp_dictoffset && __pyx_ptype___Pyx_EnumMeta->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype___Pyx_EnumMeta->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype___Pyx_EnumMeta) < 0) __PYX_ERR(1, 16, __pyx_L1_error) + #endif + __pyx_vtabptr_array = &__pyx_vtable_array; + __pyx_vtable_array.get_memview = (PyObject *(*)(struct __pyx_array_obj *))__pyx_array_get_memview; + #if CYTHON_USE_TYPE_SPECS + __pyx_array_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_array_spec, NULL); if (unlikely(!__pyx_array_type)) __PYX_ERR(1, 114, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + __pyx_array_type->tp_as_buffer = &__pyx_tp_as_buffer_array; + if (!__pyx_array_type->tp_as_buffer->bf_releasebuffer && __pyx_array_type->tp_base->tp_as_buffer && __pyx_array_type->tp_base->tp_as_buffer->bf_releasebuffer) { + __pyx_array_type->tp_as_buffer->bf_releasebuffer = __pyx_array_type->tp_base->tp_as_buffer->bf_releasebuffer; + } + #elif defined(Py_bf_getbuffer) && defined(Py_bf_releasebuffer) + /* PY_VERSION_HEX >= 0x03090000 || Py_LIMITED_API >= 0x030B0000 */ + #elif defined(_MSC_VER) + #pragma message ("The buffer protocol is not supported in the Limited C-API < 3.11.") + #else + #warning "The buffer protocol is not supported in the Limited C-API < 3.11." + #endif + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_array_spec, __pyx_array_type) < 0) __PYX_ERR(1, 114, __pyx_L1_error) + #else + __pyx_array_type = &__pyx_type___pyx_array; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_array_type) < 0) __PYX_ERR(1, 114, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_array_type->tp_print = 0; + #endif + if (__Pyx_SetVtable(__pyx_array_type, __pyx_vtabptr_array) < 0) __PYX_ERR(1, 114, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_array_type) < 0) __PYX_ERR(1, 114, __pyx_L1_error) + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_array_type) < 0) __PYX_ERR(1, 114, __pyx_L1_error) + #endif + #if CYTHON_USE_TYPE_SPECS + __pyx_MemviewEnum_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_MemviewEnum_spec, NULL); if (unlikely(!__pyx_MemviewEnum_type)) __PYX_ERR(1, 302, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_MemviewEnum_spec, __pyx_MemviewEnum_type) < 0) __PYX_ERR(1, 302, __pyx_L1_error) + #else + __pyx_MemviewEnum_type = &__pyx_type___pyx_MemviewEnum; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_MemviewEnum_type) < 0) __PYX_ERR(1, 302, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_MemviewEnum_type->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_MemviewEnum_type->tp_dictoffset && __pyx_MemviewEnum_type->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_MemviewEnum_type->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_MemviewEnum_type) < 0) __PYX_ERR(1, 302, __pyx_L1_error) + #endif + __pyx_vtabptr_memoryview = &__pyx_vtable_memoryview; + __pyx_vtable_memoryview.get_item_pointer = (char *(*)(struct __pyx_memoryview_obj *, PyObject *))__pyx_memoryview_get_item_pointer; + __pyx_vtable_memoryview.is_slice = (PyObject *(*)(struct __pyx_memoryview_obj *, PyObject *))__pyx_memoryview_is_slice; + __pyx_vtable_memoryview.setitem_slice_assignment = (PyObject *(*)(struct __pyx_memoryview_obj *, PyObject *, PyObject *))__pyx_memoryview_setitem_slice_assignment; + __pyx_vtable_memoryview.setitem_slice_assign_scalar = (PyObject *(*)(struct __pyx_memoryview_obj *, struct __pyx_memoryview_obj *, PyObject *))__pyx_memoryview_setitem_slice_assign_scalar; + __pyx_vtable_memoryview.setitem_indexed = (PyObject *(*)(struct __pyx_memoryview_obj *, PyObject *, PyObject *))__pyx_memoryview_setitem_indexed; + __pyx_vtable_memoryview.convert_item_to_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *))__pyx_memoryview_convert_item_to_object; + __pyx_vtable_memoryview.assign_item_from_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *, PyObject *))__pyx_memoryview_assign_item_from_object; + __pyx_vtable_memoryview._get_base = (PyObject *(*)(struct __pyx_memoryview_obj *))__pyx_memoryview__get_base; + #if CYTHON_USE_TYPE_SPECS + __pyx_memoryview_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_memoryview_spec, NULL); if (unlikely(!__pyx_memoryview_type)) __PYX_ERR(1, 337, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + __pyx_memoryview_type->tp_as_buffer = &__pyx_tp_as_buffer_memoryview; + if (!__pyx_memoryview_type->tp_as_buffer->bf_releasebuffer && __pyx_memoryview_type->tp_base->tp_as_buffer && __pyx_memoryview_type->tp_base->tp_as_buffer->bf_releasebuffer) { + __pyx_memoryview_type->tp_as_buffer->bf_releasebuffer = __pyx_memoryview_type->tp_base->tp_as_buffer->bf_releasebuffer; + } + #elif defined(Py_bf_getbuffer) && defined(Py_bf_releasebuffer) + /* PY_VERSION_HEX >= 0x03090000 || Py_LIMITED_API >= 0x030B0000 */ + #elif defined(_MSC_VER) + #pragma message ("The buffer protocol is not supported in the Limited C-API < 3.11.") + #else + #warning "The buffer protocol is not supported in the Limited C-API < 3.11." + #endif + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_memoryview_spec, __pyx_memoryview_type) < 0) __PYX_ERR(1, 337, __pyx_L1_error) + #else + __pyx_memoryview_type = &__pyx_type___pyx_memoryview; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_memoryview_type) < 0) __PYX_ERR(1, 337, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_memoryview_type->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_memoryview_type->tp_dictoffset && __pyx_memoryview_type->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_memoryview_type->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (__Pyx_SetVtable(__pyx_memoryview_type, __pyx_vtabptr_memoryview) < 0) __PYX_ERR(1, 337, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_memoryview_type) < 0) __PYX_ERR(1, 337, __pyx_L1_error) + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_memoryview_type) < 0) __PYX_ERR(1, 337, __pyx_L1_error) + #endif + __pyx_vtabptr__memoryviewslice = &__pyx_vtable__memoryviewslice; + __pyx_vtable__memoryviewslice.__pyx_base = *__pyx_vtabptr_memoryview; + __pyx_vtable__memoryviewslice.__pyx_base.convert_item_to_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *))__pyx_memoryviewslice_convert_item_to_object; + __pyx_vtable__memoryviewslice.__pyx_base.assign_item_from_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *, PyObject *))__pyx_memoryviewslice_assign_item_from_object; + __pyx_vtable__memoryviewslice.__pyx_base._get_base = (PyObject *(*)(struct __pyx_memoryview_obj *))__pyx_memoryviewslice__get_base; + #if CYTHON_USE_TYPE_SPECS + __pyx_t_1 = PyTuple_Pack(1, (PyObject *)__pyx_memoryview_type); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 952, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_memoryviewslice_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_memoryviewslice_spec, __pyx_t_1); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_memoryviewslice_type)) __PYX_ERR(1, 952, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_memoryviewslice_spec, __pyx_memoryviewslice_type) < 0) __PYX_ERR(1, 952, __pyx_L1_error) + #else + __pyx_memoryviewslice_type = &__pyx_type___pyx_memoryviewslice; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + __pyx_memoryviewslice_type->tp_base = __pyx_memoryview_type; + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_memoryviewslice_type) < 0) __PYX_ERR(1, 952, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_memoryviewslice_type->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_memoryviewslice_type->tp_dictoffset && __pyx_memoryviewslice_type->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_memoryviewslice_type->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (__Pyx_SetVtable(__pyx_memoryviewslice_type, __pyx_vtabptr__memoryviewslice) < 0) __PYX_ERR(1, 952, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_memoryviewslice_type) < 0) __PYX_ERR(1, 952, __pyx_L1_error) + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_memoryviewslice_type) < 0) __PYX_ERR(1, 952, __pyx_L1_error) + #endif + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_RefNannyFinishContext(); + return -1; +} + +static int __Pyx_modinit_type_import_code(void) { + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_modinit_type_import_code", 0); + /*--- Type import code ---*/ + __pyx_t_1 = PyImport_ImportModule(__Pyx_BUILTIN_MODULE_NAME); if (unlikely(!__pyx_t_1)) __PYX_ERR(4, 9, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_ptype_7cpython_4type_type = __Pyx_ImportType_3_0_8(__pyx_t_1, __Pyx_BUILTIN_MODULE_NAME, "type", + #if defined(PYPY_VERSION_NUM) && PYPY_VERSION_NUM < 0x050B0000 + sizeof(PyTypeObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyTypeObject), + #elif CYTHON_COMPILING_IN_LIMITED_API + sizeof(PyTypeObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyTypeObject), + #else + sizeof(PyHeapTypeObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyHeapTypeObject), + #endif + __Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_7cpython_4type_type) __PYX_ERR(4, 9, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = PyImport_ImportModule("numpy"); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 202, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_ptype_5numpy_dtype = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "dtype", sizeof(PyArray_Descr), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyArray_Descr),__Pyx_ImportType_CheckSize_Ignore_3_0_8); if (!__pyx_ptype_5numpy_dtype) __PYX_ERR(2, 202, __pyx_L1_error) + __pyx_ptype_5numpy_flatiter = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "flatiter", sizeof(PyArrayIterObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyArrayIterObject),__Pyx_ImportType_CheckSize_Ignore_3_0_8); if (!__pyx_ptype_5numpy_flatiter) __PYX_ERR(2, 225, __pyx_L1_error) + __pyx_ptype_5numpy_broadcast = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "broadcast", sizeof(PyArrayMultiIterObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyArrayMultiIterObject),__Pyx_ImportType_CheckSize_Ignore_3_0_8); if (!__pyx_ptype_5numpy_broadcast) __PYX_ERR(2, 229, __pyx_L1_error) + __pyx_ptype_5numpy_ndarray = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "ndarray", sizeof(PyArrayObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyArrayObject),__Pyx_ImportType_CheckSize_Ignore_3_0_8); if (!__pyx_ptype_5numpy_ndarray) __PYX_ERR(2, 238, __pyx_L1_error) + __pyx_ptype_5numpy_generic = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "generic", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_generic) __PYX_ERR(2, 809, __pyx_L1_error) + __pyx_ptype_5numpy_number = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "number", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_number) __PYX_ERR(2, 811, __pyx_L1_error) + __pyx_ptype_5numpy_integer = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "integer", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_integer) __PYX_ERR(2, 813, __pyx_L1_error) + __pyx_ptype_5numpy_signedinteger = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "signedinteger", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_signedinteger) __PYX_ERR(2, 815, __pyx_L1_error) + __pyx_ptype_5numpy_unsignedinteger = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "unsignedinteger", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_unsignedinteger) __PYX_ERR(2, 817, __pyx_L1_error) + __pyx_ptype_5numpy_inexact = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "inexact", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_inexact) __PYX_ERR(2, 819, __pyx_L1_error) + __pyx_ptype_5numpy_floating = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "floating", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_floating) __PYX_ERR(2, 821, __pyx_L1_error) + __pyx_ptype_5numpy_complexfloating = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "complexfloating", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_complexfloating) __PYX_ERR(2, 823, __pyx_L1_error) + __pyx_ptype_5numpy_flexible = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "flexible", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_flexible) __PYX_ERR(2, 825, __pyx_L1_error) + __pyx_ptype_5numpy_character = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "character", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_character) __PYX_ERR(2, 827, __pyx_L1_error) + __pyx_ptype_5numpy_ufunc = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "ufunc", sizeof(PyUFuncObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyUFuncObject),__Pyx_ImportType_CheckSize_Ignore_3_0_8); if (!__pyx_ptype_5numpy_ufunc) __PYX_ERR(2, 866, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_RefNannyFinishContext(); + return -1; +} + +static int __Pyx_modinit_variable_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_import_code", 0); + /*--- Variable import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_import_code", 0); + /*--- Function import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + + +#if PY_MAJOR_VERSION >= 3 +#if CYTHON_PEP489_MULTI_PHASE_INIT +static PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def); /*proto*/ +static int __pyx_pymod_exec_visionipc_pyx(PyObject* module); /*proto*/ +static PyModuleDef_Slot __pyx_moduledef_slots[] = { + {Py_mod_create, (void*)__pyx_pymod_create}, + {Py_mod_exec, (void*)__pyx_pymod_exec_visionipc_pyx}, + {0, NULL} +}; +#endif + +#ifdef __cplusplus +namespace { + struct PyModuleDef __pyx_moduledef = + #else + static struct PyModuleDef __pyx_moduledef = + #endif + { + PyModuleDef_HEAD_INIT, + "visionipc_pyx", + 0, /* m_doc */ + #if CYTHON_PEP489_MULTI_PHASE_INIT + 0, /* m_size */ + #elif CYTHON_USE_MODULE_STATE + sizeof(__pyx_mstate), /* m_size */ + #else + -1, /* m_size */ + #endif + __pyx_methods /* m_methods */, + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_moduledef_slots, /* m_slots */ + #else + NULL, /* m_reload */ + #endif + #if CYTHON_USE_MODULE_STATE + __pyx_m_traverse, /* m_traverse */ + __pyx_m_clear, /* m_clear */ + NULL /* m_free */ + #else + NULL, /* m_traverse */ + NULL, /* m_clear */ + NULL /* m_free */ + #endif + }; + #ifdef __cplusplus +} /* anonymous namespace */ +#endif +#endif + +#ifndef CYTHON_NO_PYINIT_EXPORT +#define __Pyx_PyMODINIT_FUNC PyMODINIT_FUNC +#elif PY_MAJOR_VERSION < 3 +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" void +#else +#define __Pyx_PyMODINIT_FUNC void +#endif +#else +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" PyObject * +#else +#define __Pyx_PyMODINIT_FUNC PyObject * +#endif +#endif + + +#if PY_MAJOR_VERSION < 3 +__Pyx_PyMODINIT_FUNC initvisionipc_pyx(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC initvisionipc_pyx(void) +#else +__Pyx_PyMODINIT_FUNC PyInit_visionipc_pyx(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC PyInit_visionipc_pyx(void) +#if CYTHON_PEP489_MULTI_PHASE_INIT +{ + return PyModuleDef_Init(&__pyx_moduledef); +} +static CYTHON_SMALL_CODE int __Pyx_check_single_interpreter(void) { + #if PY_VERSION_HEX >= 0x030700A1 + static PY_INT64_T main_interpreter_id = -1; + PY_INT64_T current_id = PyInterpreterState_GetID(PyThreadState_Get()->interp); + if (main_interpreter_id == -1) { + main_interpreter_id = current_id; + return (unlikely(current_id == -1)) ? -1 : 0; + } else if (unlikely(main_interpreter_id != current_id)) + #else + static PyInterpreterState *main_interpreter = NULL; + PyInterpreterState *current_interpreter = PyThreadState_Get()->interp; + if (!main_interpreter) { + main_interpreter = current_interpreter; + } else if (unlikely(main_interpreter != current_interpreter)) + #endif + { + PyErr_SetString( + PyExc_ImportError, + "Interpreter change detected - this module can only be loaded into one interpreter per process."); + return -1; + } + return 0; +} +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *module, const char* from_name, const char* to_name, int allow_none) +#else +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *moddict, const char* from_name, const char* to_name, int allow_none) +#endif +{ + PyObject *value = PyObject_GetAttrString(spec, from_name); + int result = 0; + if (likely(value)) { + if (allow_none || value != Py_None) { +#if CYTHON_COMPILING_IN_LIMITED_API + result = PyModule_AddObject(module, to_name, value); +#else + result = PyDict_SetItemString(moddict, to_name, value); +#endif + } + Py_DECREF(value); + } else if (PyErr_ExceptionMatches(PyExc_AttributeError)) { + PyErr_Clear(); + } else { + result = -1; + } + return result; +} +static CYTHON_SMALL_CODE PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def) { + PyObject *module = NULL, *moddict, *modname; + CYTHON_UNUSED_VAR(def); + if (__Pyx_check_single_interpreter()) + return NULL; + if (__pyx_m) + return __Pyx_NewRef(__pyx_m); + modname = PyObject_GetAttrString(spec, "name"); + if (unlikely(!modname)) goto bad; + module = PyModule_NewObject(modname); + Py_DECREF(modname); + if (unlikely(!module)) goto bad; +#if CYTHON_COMPILING_IN_LIMITED_API + moddict = module; +#else + moddict = PyModule_GetDict(module); + if (unlikely(!moddict)) goto bad; +#endif + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "loader", "__loader__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "origin", "__file__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "parent", "__package__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "submodule_search_locations", "__path__", 0) < 0)) goto bad; + return module; +bad: + Py_XDECREF(module); + return NULL; +} + + +static CYTHON_SMALL_CODE int __pyx_pymod_exec_visionipc_pyx(PyObject *__pyx_pyinit_module) +#endif +#endif +{ + int stringtab_initialized = 0; + #if CYTHON_USE_MODULE_STATE + int pystate_addmodule_run = 0; + #endif + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + static PyThread_type_lock __pyx_t_9[8]; + PyObject *__pyx_t_10 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannyDeclarations + #if CYTHON_PEP489_MULTI_PHASE_INIT + if (__pyx_m) { + if (__pyx_m == __pyx_pyinit_module) return 0; + PyErr_SetString(PyExc_RuntimeError, "Module 'visionipc_pyx' has already been imported. Re-initialisation is not supported."); + return -1; + } + #elif PY_MAJOR_VERSION >= 3 + if (__pyx_m) return __Pyx_NewRef(__pyx_m); + #endif + /*--- Module creation code ---*/ + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_m = __pyx_pyinit_module; + Py_INCREF(__pyx_m); + #else + #if PY_MAJOR_VERSION < 3 + __pyx_m = Py_InitModule4("visionipc_pyx", __pyx_methods, 0, 0, PYTHON_API_VERSION); Py_XINCREF(__pyx_m); + if (unlikely(!__pyx_m)) __PYX_ERR(0, 1, __pyx_L1_error) + #elif CYTHON_USE_MODULE_STATE + __pyx_t_1 = PyModule_Create(&__pyx_moduledef); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 1, __pyx_L1_error) + { + int add_module_result = PyState_AddModule(__pyx_t_1, &__pyx_moduledef); + __pyx_t_1 = 0; /* transfer ownership from __pyx_t_1 to "visionipc_pyx" pseudovariable */ + if (unlikely((add_module_result < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + pystate_addmodule_run = 1; + } + #else + __pyx_m = PyModule_Create(&__pyx_moduledef); + if (unlikely(!__pyx_m)) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #endif + CYTHON_UNUSED_VAR(__pyx_t_1); + __pyx_d = PyModule_GetDict(__pyx_m); if (unlikely(!__pyx_d)) __PYX_ERR(0, 1, __pyx_L1_error) + Py_INCREF(__pyx_d); + __pyx_b = __Pyx_PyImport_AddModuleRef(__Pyx_BUILTIN_MODULE_NAME); if (unlikely(!__pyx_b)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_cython_runtime = __Pyx_PyImport_AddModuleRef((const char *) "cython_runtime"); if (unlikely(!__pyx_cython_runtime)) __PYX_ERR(0, 1, __pyx_L1_error) + if (PyObject_SetAttrString(__pyx_m, "__builtins__", __pyx_b) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #if CYTHON_REFNANNY +__Pyx_RefNanny = __Pyx_RefNannyImportAPI("refnanny"); +if (!__Pyx_RefNanny) { + PyErr_Clear(); + __Pyx_RefNanny = __Pyx_RefNannyImportAPI("Cython.Runtime.refnanny"); + if (!__Pyx_RefNanny) + Py_FatalError("failed to import 'refnanny' module"); +} +#endif + __Pyx_RefNannySetupContext("__Pyx_PyMODINIT_FUNC PyInit_visionipc_pyx(void)", 0); + if (__Pyx_check_binary_version(__PYX_LIMITED_VERSION_HEX, __Pyx_get_runtime_version(), CYTHON_COMPILING_IN_LIMITED_API) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #ifdef __Pxy_PyFrame_Initialize_Offsets + __Pxy_PyFrame_Initialize_Offsets(); + #endif + __pyx_empty_tuple = PyTuple_New(0); if (unlikely(!__pyx_empty_tuple)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_empty_bytes = PyBytes_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_bytes)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_empty_unicode = PyUnicode_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_unicode)) __PYX_ERR(0, 1, __pyx_L1_error) + #ifdef __Pyx_CyFunction_USED + if (__pyx_CyFunction_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_FusedFunction_USED + if (__pyx_FusedFunction_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Coroutine_USED + if (__pyx_Coroutine_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Generator_USED + if (__pyx_Generator_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_AsyncGen_USED + if (__pyx_AsyncGen_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_StopAsyncIteration_USED + if (__pyx_StopAsyncIteration_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + /*--- Library function declarations ---*/ + /*--- Threads initialization code ---*/ + #if defined(WITH_THREAD) && PY_VERSION_HEX < 0x030700F0 && defined(__PYX_FORCE_INIT_THREADS) && __PYX_FORCE_INIT_THREADS + PyEval_InitThreads(); + #endif + /*--- Initialize various global constants etc. ---*/ + if (__Pyx_InitConstants() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + stringtab_initialized = 1; + if (__Pyx_InitGlobals() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #if PY_MAJOR_VERSION < 3 && (__PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT) + if (__Pyx_init_sys_getdefaultencoding_params() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + if (__pyx_module_is_main_cereal__visionipc__visionipc_pyx) { + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_name_2, __pyx_n_s_main) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + } + #if PY_MAJOR_VERSION >= 3 + { + PyObject *modules = PyImport_GetModuleDict(); if (unlikely(!modules)) __PYX_ERR(0, 1, __pyx_L1_error) + if (!PyDict_GetItemString(modules, "cereal.visionipc.visionipc_pyx")) { + if (unlikely((PyDict_SetItemString(modules, "cereal.visionipc.visionipc_pyx", __pyx_m) < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + } + } + #endif + /*--- Builtin init code ---*/ + if (__Pyx_InitCachedBuiltins() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + /*--- Constants init code ---*/ + if (__Pyx_InitCachedConstants() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + /*--- Global type/function init code ---*/ + (void)__Pyx_modinit_global_init_code(); + (void)__Pyx_modinit_variable_export_code(); + (void)__Pyx_modinit_function_export_code(); + if (unlikely((__Pyx_modinit_type_init_code() < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + if (unlikely((__Pyx_modinit_type_import_code() < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + (void)__Pyx_modinit_variable_import_code(); + (void)__Pyx_modinit_function_import_code(); + /*--- Execution code ---*/ + #if defined(__Pyx_Generator_USED) || defined(__Pyx_Coroutine_USED) + if (__Pyx_patch_abc() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + + /* "EnumBase":10 + * cdef object __Pyx_OrderedDict + * + * if PY_VERSION_HEX >= 0x03060000: # <<<<<<<<<<<<<< + * __Pyx_OrderedDict = dict + * else: + */ + __pyx_t_2 = (PY_VERSION_HEX >= 0x03060000); + if (__pyx_t_2) { + + /* "EnumBase":11 + * + * if PY_VERSION_HEX >= 0x03060000: + * __Pyx_OrderedDict = dict # <<<<<<<<<<<<<< + * else: + * from collections import OrderedDict as __Pyx_OrderedDict + */ + __Pyx_INCREF((PyObject *)(&PyDict_Type)); + __Pyx_XGOTREF(__Pyx_OrderedDict); + __Pyx_DECREF_SET(__Pyx_OrderedDict, ((PyObject *)(&PyDict_Type))); + __Pyx_GIVEREF((PyObject *)(&PyDict_Type)); + + /* "EnumBase":10 + * cdef object __Pyx_OrderedDict + * + * if PY_VERSION_HEX >= 0x03060000: # <<<<<<<<<<<<<< + * __Pyx_OrderedDict = dict + * else: + */ + goto __pyx_L2; + } + + /* "EnumBase":13 + * __Pyx_OrderedDict = dict + * else: + * from collections import OrderedDict as __Pyx_OrderedDict # <<<<<<<<<<<<<< + * + * @cython.internal + */ + /*else*/ { + __pyx_t_3 = PyList_New(1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_n_s_OrderedDict); + __Pyx_GIVEREF(__pyx_n_s_OrderedDict); + if (__Pyx_PyList_SET_ITEM(__pyx_t_3, 0, __pyx_n_s_OrderedDict)) __PYX_ERR(1, 13, __pyx_L1_error); + __pyx_t_4 = __Pyx_Import(__pyx_n_s_collections, __pyx_t_3, 0); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_ImportFrom(__pyx_t_4, __pyx_n_s_OrderedDict); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_t_3); + __Pyx_XGOTREF(__Pyx_OrderedDict); + __Pyx_DECREF_SET(__Pyx_OrderedDict, __pyx_t_3); + __Pyx_GIVEREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + __pyx_L2:; + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * cdef tuple state + * cdef object _dict + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_8EnumBase_14__Pyx_EnumMeta_7__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Pyx_EnumMeta___reduce_cython, NULL, __pyx_n_s_EnumBase, __pyx_d, ((PyObject *)__pyx_codeobj__19)); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype___Pyx_EnumMeta, __pyx_n_s_reduce_cython, __pyx_t_4) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + PyType_Modified(__pyx_ptype___Pyx_EnumMeta); + + /* "(tree fragment)":16 + * else: + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, state) + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * __pyx_unpickle___Pyx_EnumMeta__set_state(self, __pyx_state) + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_8EnumBase_14__Pyx_EnumMeta_9__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Pyx_EnumMeta___setstate_cython, NULL, __pyx_n_s_EnumBase, __pyx_d, ((PyObject *)__pyx_codeobj__21)); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 16, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype___Pyx_EnumMeta, __pyx_n_s_setstate_cython, __pyx_t_4) < 0) __PYX_ERR(1, 16, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + PyType_Modified(__pyx_ptype___Pyx_EnumMeta); + + /* "EnumBase":27 + * + * cdef object __Pyx_EnumBase + * class __Pyx_EnumBase(int, metaclass=__Pyx_EnumMeta): # <<<<<<<<<<<<<< + * def __new__(cls, value, name=None): + * for v in cls: + */ + __pyx_t_4 = PyTuple_New(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 27, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_INCREF((PyObject *)(&PyInt_Type)); + __Pyx_GIVEREF((PyObject *)(&PyInt_Type)); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, ((PyObject *)(&PyInt_Type)))) __PYX_ERR(1, 27, __pyx_L1_error); + __pyx_t_3 = __Pyx_PEP560_update_bases(__pyx_t_4); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 27, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 27, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = __Pyx_Py3MetaclassPrepare(((PyObject *)__pyx_ptype___Pyx_EnumMeta), __pyx_t_3, __pyx_n_s_Pyx_EnumBase, __pyx_n_s_Pyx_EnumBase, __pyx_t_5, __pyx_n_s_EnumBase, (PyObject *) NULL); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 27, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (__pyx_t_3 != __pyx_t_4) { + if (unlikely((PyDict_SetItemString(__pyx_t_6, "__orig_bases__", __pyx_t_4) < 0))) __PYX_ERR(1, 27, __pyx_L1_error) + } + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "EnumBase":28 + * cdef object __Pyx_EnumBase + * class __Pyx_EnumBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): # <<<<<<<<<<<<<< + * for v in cls: + * if v == value: + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_8EnumBase_14__Pyx_EnumBase_1__new__, __Pyx_CYFUNCTION_STATICMETHOD, __pyx_n_s_Pyx_EnumBase___new, NULL, __pyx_n_s_EnumBase, __pyx_d, ((PyObject *)__pyx_codeobj__23)); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 28, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_4, __pyx_tuple__24); + if (__Pyx_SetNewInClass(__pyx_t_6, __pyx_n_s_new, __pyx_t_4) < 0) __PYX_ERR(1, 28, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "EnumBase":39 + * cls.__members__[name] = res + * return res + * def __repr__(self): # <<<<<<<<<<<<<< + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_8EnumBase_14__Pyx_EnumBase_3__repr__, 0, __pyx_n_s_Pyx_EnumBase___repr, NULL, __pyx_n_s_EnumBase, __pyx_d, ((PyObject *)__pyx_codeobj__26)); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 39, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (__Pyx_SetNameInClass(__pyx_t_6, __pyx_n_s_repr, __pyx_t_4) < 0) __PYX_ERR(1, 39, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "EnumBase":41 + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): # <<<<<<<<<<<<<< + * return "%s.%s" % (self.__class__.__name__, self.name) + * + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_8EnumBase_14__Pyx_EnumBase_5__str__, 0, __pyx_n_s_Pyx_EnumBase___str, NULL, __pyx_n_s_EnumBase, __pyx_d, ((PyObject *)__pyx_codeobj__27)); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 41, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (__Pyx_SetNameInClass(__pyx_t_6, __pyx_n_s_str, __pyx_t_4) < 0) __PYX_ERR(1, 41, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "EnumBase":27 + * + * cdef object __Pyx_EnumBase + * class __Pyx_EnumBase(int, metaclass=__Pyx_EnumMeta): # <<<<<<<<<<<<<< + * def __new__(cls, value, name=None): + * for v in cls: + */ + __pyx_t_4 = __Pyx_Py3ClassCreate(((PyObject *)__pyx_ptype___Pyx_EnumMeta), __pyx_n_s_Pyx_EnumBase, __pyx_t_3, __pyx_t_6, __pyx_t_5, 1, 0); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 27, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_XGOTREF(__Pyx_EnumBase); + __Pyx_DECREF_SET(__Pyx_EnumBase, __pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "EnumBase":44 + * return "%s.%s" % (self.__class__.__name__, self.name) + * + * if PY_VERSION_HEX >= 0x03040000: # <<<<<<<<<<<<<< + * from enum import IntEnum as __Pyx_EnumBase + * + */ + __pyx_t_2 = (PY_VERSION_HEX >= 0x03040000); + if (__pyx_t_2) { + + /* "EnumBase":45 + * + * if PY_VERSION_HEX >= 0x03040000: + * from enum import IntEnum as __Pyx_EnumBase # <<<<<<<<<<<<<< + * + * cdef object __Pyx_FlagBase + */ + __pyx_t_3 = PyList_New(1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 45, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_n_s_IntEnum); + __Pyx_GIVEREF(__pyx_n_s_IntEnum); + if (__Pyx_PyList_SET_ITEM(__pyx_t_3, 0, __pyx_n_s_IntEnum)) __PYX_ERR(1, 45, __pyx_L1_error); + __pyx_t_5 = __Pyx_Import(__pyx_n_s_enum, __pyx_t_3, 0); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 45, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_ImportFrom(__pyx_t_5, __pyx_n_s_IntEnum); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 45, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_t_3); + __Pyx_XGOTREF(__Pyx_EnumBase); + __Pyx_DECREF_SET(__Pyx_EnumBase, __pyx_t_3); + __Pyx_GIVEREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "EnumBase":44 + * return "%s.%s" % (self.__class__.__name__, self.name) + * + * if PY_VERSION_HEX >= 0x03040000: # <<<<<<<<<<<<<< + * from enum import IntEnum as __Pyx_EnumBase + * + */ + } + + /* "EnumBase":48 + * + * cdef object __Pyx_FlagBase + * class __Pyx_FlagBase(int, metaclass=__Pyx_EnumMeta): # <<<<<<<<<<<<<< + * def __new__(cls, value, name=None): + * for v in cls: + */ + __pyx_t_5 = PyTuple_New(1); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 48, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_INCREF((PyObject *)(&PyInt_Type)); + __Pyx_GIVEREF((PyObject *)(&PyInt_Type)); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_5, 0, ((PyObject *)(&PyInt_Type)))) __PYX_ERR(1, 48, __pyx_L1_error); + __pyx_t_3 = __Pyx_PEP560_update_bases(__pyx_t_5); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 48, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_6 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 48, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_4 = __Pyx_Py3MetaclassPrepare(((PyObject *)__pyx_ptype___Pyx_EnumMeta), __pyx_t_3, __pyx_n_s_Pyx_FlagBase, __pyx_n_s_Pyx_FlagBase, __pyx_t_6, __pyx_n_s_EnumBase, (PyObject *) NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 48, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (__pyx_t_3 != __pyx_t_5) { + if (unlikely((PyDict_SetItemString(__pyx_t_4, "__orig_bases__", __pyx_t_5) < 0))) __PYX_ERR(1, 48, __pyx_L1_error) + } + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "EnumBase":49 + * cdef object __Pyx_FlagBase + * class __Pyx_FlagBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): # <<<<<<<<<<<<<< + * for v in cls: + * if v == value: + */ + __pyx_t_5 = __Pyx_CyFunction_New(&__pyx_mdef_8EnumBase_14__Pyx_FlagBase_1__new__, __Pyx_CYFUNCTION_STATICMETHOD, __pyx_n_s_Pyx_FlagBase___new, NULL, __pyx_n_s_EnumBase, __pyx_d, ((PyObject *)__pyx_codeobj__28)); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 49, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_5, __pyx_tuple__24); + if (__Pyx_SetNewInClass(__pyx_t_4, __pyx_n_s_new, __pyx_t_5) < 0) __PYX_ERR(1, 49, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "EnumBase":62 + * cls.__members__[name] = res + * return res + * def __repr__(self): # <<<<<<<<<<<<<< + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): + */ + __pyx_t_5 = __Pyx_CyFunction_New(&__pyx_mdef_8EnumBase_14__Pyx_FlagBase_3__repr__, 0, __pyx_n_s_Pyx_FlagBase___repr, NULL, __pyx_n_s_EnumBase, __pyx_d, ((PyObject *)__pyx_codeobj__29)); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 62, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + if (__Pyx_SetNameInClass(__pyx_t_4, __pyx_n_s_repr, __pyx_t_5) < 0) __PYX_ERR(1, 62, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "EnumBase":64 + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): # <<<<<<<<<<<<<< + * return "%s.%s" % (self.__class__.__name__, self.name) + * + */ + __pyx_t_5 = __Pyx_CyFunction_New(&__pyx_mdef_8EnumBase_14__Pyx_FlagBase_5__str__, 0, __pyx_n_s_Pyx_FlagBase___str, NULL, __pyx_n_s_EnumBase, __pyx_d, ((PyObject *)__pyx_codeobj__30)); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 64, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + if (__Pyx_SetNameInClass(__pyx_t_4, __pyx_n_s_str, __pyx_t_5) < 0) __PYX_ERR(1, 64, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "EnumBase":48 + * + * cdef object __Pyx_FlagBase + * class __Pyx_FlagBase(int, metaclass=__Pyx_EnumMeta): # <<<<<<<<<<<<<< + * def __new__(cls, value, name=None): + * for v in cls: + */ + __pyx_t_5 = __Pyx_Py3ClassCreate(((PyObject *)__pyx_ptype___Pyx_EnumMeta), __pyx_n_s_Pyx_FlagBase, __pyx_t_3, __pyx_t_4, __pyx_t_6, 1, 0); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 48, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_XGOTREF(__Pyx_FlagBase); + __Pyx_DECREF_SET(__Pyx_FlagBase, __pyx_t_5); + __Pyx_GIVEREF(__pyx_t_5); + __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "EnumBase":67 + * return "%s.%s" % (self.__class__.__name__, self.name) + * + * if PY_VERSION_HEX >= 0x03060000: # <<<<<<<<<<<<<< + * from enum import IntFlag as __Pyx_FlagBase + * + */ + __pyx_t_2 = (PY_VERSION_HEX >= 0x03060000); + if (__pyx_t_2) { + + /* "EnumBase":68 + * + * if PY_VERSION_HEX >= 0x03060000: + * from enum import IntFlag as __Pyx_FlagBase # <<<<<<<<<<<<<< + * + */ + __pyx_t_3 = PyList_New(1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 68, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_n_s_IntFlag); + __Pyx_GIVEREF(__pyx_n_s_IntFlag); + if (__Pyx_PyList_SET_ITEM(__pyx_t_3, 0, __pyx_n_s_IntFlag)) __PYX_ERR(1, 68, __pyx_L1_error); + __pyx_t_6 = __Pyx_Import(__pyx_n_s_enum, __pyx_t_3, 0); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 68, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_ImportFrom(__pyx_t_6, __pyx_n_s_IntFlag); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 68, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_t_3); + __Pyx_XGOTREF(__Pyx_FlagBase); + __Pyx_DECREF_SET(__Pyx_FlagBase, __pyx_t_3); + __Pyx_GIVEREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + + /* "EnumBase":67 + * return "%s.%s" % (self.__class__.__name__, self.name) + * + * if PY_VERSION_HEX >= 0x03060000: # <<<<<<<<<<<<<< + * from enum import IntFlag as __Pyx_FlagBase + * + */ + } + + /* "(tree fragment)":1 + * def __pyx_unpickle___Pyx_EnumMeta(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + __pyx_t_6 = __Pyx_CyFunction_New(&__pyx_mdef_8EnumBase_1__pyx_unpickle___Pyx_EnumMeta, 0, __pyx_n_s_pyx_unpickle___Pyx_EnumMeta, NULL, __pyx_n_s_EnumBase, __pyx_d, ((PyObject *)__pyx_codeobj__32)); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_pyx_unpickle___Pyx_EnumMeta, __pyx_t_6) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + + /* "View.MemoryView":99 + * + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: # <<<<<<<<<<<<<< + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_7, &__pyx_t_8); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_7); + __Pyx_XGOTREF(__pyx_t_8); + /*try:*/ { + + /* "View.MemoryView":100 + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: + * if __import__("sys").version_info >= (3, 3): # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + */ + __pyx_t_6 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__33, NULL); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 100, __pyx_L5_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_6, __pyx_n_s_version_info); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 100, __pyx_L5_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __pyx_t_6 = PyObject_RichCompare(__pyx_t_3, __pyx_tuple__34, Py_GE); __Pyx_XGOTREF(__pyx_t_6); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 100, __pyx_L5_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_t_6); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(1, 100, __pyx_L5_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + if (__pyx_t_2) { + + /* "View.MemoryView":101 + * try: + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence # <<<<<<<<<<<<<< + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence + */ + __pyx_t_6 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__35, NULL); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 101, __pyx_L5_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_6, __pyx_n_s_abc); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 101, __pyx_L5_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_Sequence); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 101, __pyx_L5_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XGOTREF(__pyx_collections_abc_Sequence); + __Pyx_DECREF_SET(__pyx_collections_abc_Sequence, __pyx_t_6); + __Pyx_GIVEREF(__pyx_t_6); + __pyx_t_6 = 0; + + /* "View.MemoryView":100 + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: + * if __import__("sys").version_info >= (3, 3): # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + */ + goto __pyx_L11; + } + + /* "View.MemoryView":103 + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence # <<<<<<<<<<<<<< + * except: + * + */ + /*else*/ { + __pyx_t_6 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__36, NULL); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 103, __pyx_L5_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_6, __pyx_n_s_Sequence); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 103, __pyx_L5_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_XGOTREF(__pyx_collections_abc_Sequence); + __Pyx_DECREF_SET(__pyx_collections_abc_Sequence, __pyx_t_3); + __Pyx_GIVEREF(__pyx_t_3); + __pyx_t_3 = 0; + } + __pyx_L11:; + + /* "View.MemoryView":99 + * + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: # <<<<<<<<<<<<<< + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L10_try_end; + __pyx_L5_error:; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + + /* "View.MemoryView":104 + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence + * except: # <<<<<<<<<<<<<< + * + * __pyx_collections_abc_Sequence = None + */ + /*except:*/ { + __Pyx_AddTraceback("View.MemoryView", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_3, &__pyx_t_6, &__pyx_t_4) < 0) __PYX_ERR(1, 104, __pyx_L7_except_error) + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_4); + + /* "View.MemoryView":106 + * except: + * + * __pyx_collections_abc_Sequence = None # <<<<<<<<<<<<<< + * + * + */ + __Pyx_INCREF(Py_None); + __Pyx_XGOTREF(__pyx_collections_abc_Sequence); + __Pyx_DECREF_SET(__pyx_collections_abc_Sequence, Py_None); + __Pyx_GIVEREF(Py_None); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + goto __pyx_L6_exception_handled; + } + + /* "View.MemoryView":99 + * + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: # <<<<<<<<<<<<<< + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + */ + __pyx_L7_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_7); + __Pyx_XGIVEREF(__pyx_t_8); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_7, __pyx_t_8); + goto __pyx_L1_error; + __pyx_L6_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_7); + __Pyx_XGIVEREF(__pyx_t_8); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_7, __pyx_t_8); + __pyx_L10_try_end:; + } + + /* "View.MemoryView":241 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_8, &__pyx_t_7, &__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_8); + __Pyx_XGOTREF(__pyx_t_7); + __Pyx_XGOTREF(__pyx_t_1); + /*try:*/ { + + /* "View.MemoryView":242 + * + * try: + * count = __pyx_collections_abc_Sequence.count # <<<<<<<<<<<<<< + * index = __pyx_collections_abc_Sequence.index + * except: + */ + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_count); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 242, __pyx_L14_error) + __Pyx_GOTREF(__pyx_t_4); + if (__Pyx_SetItemOnTypeDict(__pyx_array_type, __pyx_n_s_count, __pyx_t_4) < 0) __PYX_ERR(1, 242, __pyx_L14_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + PyType_Modified(__pyx_array_type); + + /* "View.MemoryView":243 + * try: + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index # <<<<<<<<<<<<<< + * except: + * pass + */ + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_index); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 243, __pyx_L14_error) + __Pyx_GOTREF(__pyx_t_4); + if (__Pyx_SetItemOnTypeDict(__pyx_array_type, __pyx_n_s_index, __pyx_t_4) < 0) __PYX_ERR(1, 243, __pyx_L14_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + PyType_Modified(__pyx_array_type); + + /* "View.MemoryView":241 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + } + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + goto __pyx_L19_try_end; + __pyx_L14_error:; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + + /* "View.MemoryView":244 + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + * except: # <<<<<<<<<<<<<< + * pass + * + */ + /*except:*/ { + __Pyx_ErrRestore(0,0,0); + goto __pyx_L15_exception_handled; + } + __pyx_L15_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_8); + __Pyx_XGIVEREF(__pyx_t_7); + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_ExceptionReset(__pyx_t_8, __pyx_t_7, __pyx_t_1); + __pyx_L19_try_end:; + } + + /* "View.MemoryView":309 + * return self.name + * + * cdef generic = Enum("") # <<<<<<<<<<<<<< + * cdef strided = Enum("") # default + * cdef indirect = Enum("") + */ + __pyx_t_4 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__37, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 309, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_XGOTREF(generic); + __Pyx_DECREF_SET(generic, __pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + __pyx_t_4 = 0; + + /* "View.MemoryView":310 + * + * cdef generic = Enum("") + * cdef strided = Enum("") # default # <<<<<<<<<<<<<< + * cdef indirect = Enum("") + * + */ + __pyx_t_4 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__38, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 310, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_XGOTREF(strided); + __Pyx_DECREF_SET(strided, __pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + __pyx_t_4 = 0; + + /* "View.MemoryView":311 + * cdef generic = Enum("") + * cdef strided = Enum("") # default + * cdef indirect = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_4 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__39, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 311, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_XGOTREF(indirect); + __Pyx_DECREF_SET(indirect, __pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + __pyx_t_4 = 0; + + /* "View.MemoryView":314 + * + * + * cdef contiguous = Enum("") # <<<<<<<<<<<<<< + * cdef indirect_contiguous = Enum("") + * + */ + __pyx_t_4 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__40, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 314, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_XGOTREF(contiguous); + __Pyx_DECREF_SET(contiguous, __pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + __pyx_t_4 = 0; + + /* "View.MemoryView":315 + * + * cdef contiguous = Enum("") + * cdef indirect_contiguous = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_4 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__41, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 315, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_XGOTREF(indirect_contiguous); + __Pyx_DECREF_SET(indirect_contiguous, __pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + __pyx_t_4 = 0; + + /* "View.MemoryView":323 + * + * + * cdef int __pyx_memoryview_thread_locks_used = 0 # <<<<<<<<<<<<<< + * cdef PyThread_type_lock[8] __pyx_memoryview_thread_locks = [ + * PyThread_allocate_lock(), + */ + __pyx_memoryview_thread_locks_used = 0; + + /* "View.MemoryView":324 + * + * cdef int __pyx_memoryview_thread_locks_used = 0 + * cdef PyThread_type_lock[8] __pyx_memoryview_thread_locks = [ # <<<<<<<<<<<<<< + * PyThread_allocate_lock(), + * PyThread_allocate_lock(), + */ + __pyx_t_9[0] = PyThread_allocate_lock(); + __pyx_t_9[1] = PyThread_allocate_lock(); + __pyx_t_9[2] = PyThread_allocate_lock(); + __pyx_t_9[3] = PyThread_allocate_lock(); + __pyx_t_9[4] = PyThread_allocate_lock(); + __pyx_t_9[5] = PyThread_allocate_lock(); + __pyx_t_9[6] = PyThread_allocate_lock(); + __pyx_t_9[7] = PyThread_allocate_lock(); + memcpy(&(__pyx_memoryview_thread_locks[0]), __pyx_t_9, sizeof(__pyx_memoryview_thread_locks[0]) * (8)); + + /* "View.MemoryView":982 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_7, &__pyx_t_8); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_7); + __Pyx_XGOTREF(__pyx_t_8); + /*try:*/ { + + /* "View.MemoryView":983 + * + * try: + * count = __pyx_collections_abc_Sequence.count # <<<<<<<<<<<<<< + * index = __pyx_collections_abc_Sequence.index + * except: + */ + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_count); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 983, __pyx_L20_error) + __Pyx_GOTREF(__pyx_t_4); + if (__Pyx_SetItemOnTypeDict(__pyx_memoryviewslice_type, __pyx_n_s_count, __pyx_t_4) < 0) __PYX_ERR(1, 983, __pyx_L20_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + PyType_Modified(__pyx_memoryviewslice_type); + + /* "View.MemoryView":984 + * try: + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index # <<<<<<<<<<<<<< + * except: + * pass + */ + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_index); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 984, __pyx_L20_error) + __Pyx_GOTREF(__pyx_t_4); + if (__Pyx_SetItemOnTypeDict(__pyx_memoryviewslice_type, __pyx_n_s_index, __pyx_t_4) < 0) __PYX_ERR(1, 984, __pyx_L20_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + PyType_Modified(__pyx_memoryviewslice_type); + + /* "View.MemoryView":982 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L25_try_end; + __pyx_L20_error:; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + + /* "View.MemoryView":985 + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + * except: # <<<<<<<<<<<<<< + * pass + * + */ + /*except:*/ { + __Pyx_ErrRestore(0,0,0); + goto __pyx_L21_exception_handled; + } + __pyx_L21_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_7); + __Pyx_XGIVEREF(__pyx_t_8); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_7, __pyx_t_8); + __pyx_L25_try_end:; + } + + /* "View.MemoryView":988 + * pass + * + * try: # <<<<<<<<<<<<<< + * if __pyx_collections_abc_Sequence: + * + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_8, &__pyx_t_7, &__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_8); + __Pyx_XGOTREF(__pyx_t_7); + __Pyx_XGOTREF(__pyx_t_1); + /*try:*/ { + + /* "View.MemoryView":989 + * + * try: + * if __pyx_collections_abc_Sequence: # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_collections_abc_Sequence); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(1, 989, __pyx_L26_error) + if (__pyx_t_2) { + + /* "View.MemoryView":993 + * + * + * __pyx_collections_abc_Sequence.register(_memoryviewslice) # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence.register(array) + * except: + */ + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_register); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 993, __pyx_L26_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_6 = __Pyx_PyObject_CallOneArg(__pyx_t_4, ((PyObject *)__pyx_memoryviewslice_type)); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 993, __pyx_L26_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + + /* "View.MemoryView":994 + * + * __pyx_collections_abc_Sequence.register(_memoryviewslice) + * __pyx_collections_abc_Sequence.register(array) # <<<<<<<<<<<<<< + * except: + * pass # ignore failure, it's a minor issue + */ + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_register); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 994, __pyx_L26_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_4 = __Pyx_PyObject_CallOneArg(__pyx_t_6, ((PyObject *)__pyx_array_type)); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 994, __pyx_L26_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "View.MemoryView":989 + * + * try: + * if __pyx_collections_abc_Sequence: # <<<<<<<<<<<<<< + * + * + */ + } + + /* "View.MemoryView":988 + * pass + * + * try: # <<<<<<<<<<<<<< + * if __pyx_collections_abc_Sequence: + * + */ + } + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + goto __pyx_L31_try_end; + __pyx_L26_error:; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + + /* "View.MemoryView":995 + * __pyx_collections_abc_Sequence.register(_memoryviewslice) + * __pyx_collections_abc_Sequence.register(array) + * except: # <<<<<<<<<<<<<< + * pass # ignore failure, it's a minor issue + * + */ + /*except:*/ { + __Pyx_ErrRestore(0,0,0); + goto __pyx_L27_exception_handled; + } + __pyx_L27_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_8); + __Pyx_XGIVEREF(__pyx_t_7); + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_ExceptionReset(__pyx_t_8, __pyx_t_7, __pyx_t_1); + __pyx_L31_try_end:; + } + + /* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + __pyx_t_4 = PyCFunction_NewEx(&__pyx_mdef_15View_dot_MemoryView_1__pyx_unpickle_Enum, NULL, __pyx_n_s_View_MemoryView); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_pyx_unpickle_Enum, __pyx_t_4) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "EnumType":76 + * object __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VisionStreamType value) + * + * cdef dict __Pyx_globals = globals() # <<<<<<<<<<<<<< + * if PY_VERSION_HEX >= 0x03060000: + * + */ + __pyx_t_4 = __Pyx_Globals(); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 76, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (!(likely(PyDict_CheckExact(__pyx_t_4))||((__pyx_t_4) == Py_None) || __Pyx_RaiseUnexpectedTypeError("dict", __pyx_t_4))) __PYX_ERR(1, 76, __pyx_L1_error) + __Pyx_XGOTREF(__Pyx_globals); + __Pyx_DECREF_SET(__Pyx_globals, ((PyObject*)__pyx_t_4)); + __Pyx_GIVEREF(__pyx_t_4); + __pyx_t_4 = 0; + + /* "EnumType":77 + * + * cdef dict __Pyx_globals = globals() + * if PY_VERSION_HEX >= 0x03060000: # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = (PY_VERSION_HEX >= 0x03060000); + if (__pyx_t_2) { + + /* "EnumType":81 + * + * VisionStreamType = __Pyx_FlagBase('VisionStreamType', [ + * ('VISION_STREAM_ROAD', __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_ROAD)), # <<<<<<<<<<<<<< + * ('VISION_STREAM_DRIVER', __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_DRIVER)), + * ('VISION_STREAM_WIDE_ROAD', __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_WIDE_ROAD)), + */ + __pyx_t_4 = __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(__pyx_e_6cereal_9visionipc_13visionipc_pyx_VISION_STREAM_ROAD); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 81, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_6 = PyTuple_New(2); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 81, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_INCREF(__pyx_n_s_VISION_STREAM_ROAD); + __Pyx_GIVEREF(__pyx_n_s_VISION_STREAM_ROAD); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_6, 0, __pyx_n_s_VISION_STREAM_ROAD)) __PYX_ERR(1, 81, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_4); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_6, 1, __pyx_t_4)) __PYX_ERR(1, 81, __pyx_L1_error); + __pyx_t_4 = 0; + + /* "EnumType":82 + * VisionStreamType = __Pyx_FlagBase('VisionStreamType', [ + * ('VISION_STREAM_ROAD', __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_ROAD)), + * ('VISION_STREAM_DRIVER', __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_DRIVER)), # <<<<<<<<<<<<<< + * ('VISION_STREAM_WIDE_ROAD', __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_WIDE_ROAD)), + * ('VISION_STREAM_MAP', __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_MAP)), + */ + __pyx_t_4 = __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(__pyx_e_6cereal_9visionipc_13visionipc_pyx_VISION_STREAM_DRIVER); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 82, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 82, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_n_s_VISION_STREAM_DRIVER); + __Pyx_GIVEREF(__pyx_n_s_VISION_STREAM_DRIVER); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_n_s_VISION_STREAM_DRIVER)) __PYX_ERR(1, 82, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_4); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_4)) __PYX_ERR(1, 82, __pyx_L1_error); + __pyx_t_4 = 0; + + /* "EnumType":83 + * ('VISION_STREAM_ROAD', __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_ROAD)), + * ('VISION_STREAM_DRIVER', __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_DRIVER)), + * ('VISION_STREAM_WIDE_ROAD', __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_WIDE_ROAD)), # <<<<<<<<<<<<<< + * ('VISION_STREAM_MAP', __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_MAP)), + * + */ + __pyx_t_4 = __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(__pyx_e_6cereal_9visionipc_13visionipc_pyx_VISION_STREAM_WIDE_ROAD); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 83, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = PyTuple_New(2); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 83, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_INCREF(__pyx_n_s_VISION_STREAM_WIDE_ROAD); + __Pyx_GIVEREF(__pyx_n_s_VISION_STREAM_WIDE_ROAD); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_n_s_VISION_STREAM_WIDE_ROAD)) __PYX_ERR(1, 83, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_4); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_4)) __PYX_ERR(1, 83, __pyx_L1_error); + __pyx_t_4 = 0; + + /* "EnumType":84 + * ('VISION_STREAM_DRIVER', __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_DRIVER)), + * ('VISION_STREAM_WIDE_ROAD', __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_WIDE_ROAD)), + * ('VISION_STREAM_MAP', __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_MAP)), # <<<<<<<<<<<<<< + * + * ], module=__Pyx_globals.get("__module__", 'cereal.visionipc.visionipc_pyx')) + */ + __pyx_t_4 = __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(__pyx_e_6cereal_9visionipc_13visionipc_pyx_VISION_STREAM_MAP); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 84, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_10 = PyTuple_New(2); if (unlikely(!__pyx_t_10)) __PYX_ERR(1, 84, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __Pyx_INCREF(__pyx_n_s_VISION_STREAM_MAP); + __Pyx_GIVEREF(__pyx_n_s_VISION_STREAM_MAP); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_10, 0, __pyx_n_s_VISION_STREAM_MAP)) __PYX_ERR(1, 84, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_4); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_10, 1, __pyx_t_4)) __PYX_ERR(1, 84, __pyx_L1_error); + __pyx_t_4 = 0; + + /* "EnumType":80 + * + * + * VisionStreamType = __Pyx_FlagBase('VisionStreamType', [ # <<<<<<<<<<<<<< + * ('VISION_STREAM_ROAD', __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_ROAD)), + * ('VISION_STREAM_DRIVER', __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_DRIVER)), + */ + __pyx_t_4 = PyList_New(4); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 80, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_6); + if (__Pyx_PyList_SET_ITEM(__pyx_t_4, 0, __pyx_t_6)) __PYX_ERR(1, 80, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyList_SET_ITEM(__pyx_t_4, 1, __pyx_t_3)) __PYX_ERR(1, 80, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_5); + if (__Pyx_PyList_SET_ITEM(__pyx_t_4, 2, __pyx_t_5)) __PYX_ERR(1, 80, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_10); + if (__Pyx_PyList_SET_ITEM(__pyx_t_4, 3, __pyx_t_10)) __PYX_ERR(1, 80, __pyx_L1_error); + __pyx_t_6 = 0; + __pyx_t_3 = 0; + __pyx_t_5 = 0; + __pyx_t_10 = 0; + __pyx_t_10 = PyTuple_New(2); if (unlikely(!__pyx_t_10)) __PYX_ERR(1, 80, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __Pyx_INCREF(__pyx_n_s_VisionStreamType); + __Pyx_GIVEREF(__pyx_n_s_VisionStreamType); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_10, 0, __pyx_n_s_VisionStreamType)) __PYX_ERR(1, 80, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_4); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_10, 1, __pyx_t_4)) __PYX_ERR(1, 80, __pyx_L1_error); + __pyx_t_4 = 0; + + /* "EnumType":86 + * ('VISION_STREAM_MAP', __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_MAP)), + * + * ], module=__Pyx_globals.get("__module__", 'cereal.visionipc.visionipc_pyx')) # <<<<<<<<<<<<<< + * + * if PY_VERSION_HEX >= 0x030B0000: + */ + __pyx_t_4 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 86, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (unlikely(__Pyx_globals == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "get"); + __PYX_ERR(1, 86, __pyx_L1_error) + } + __pyx_t_5 = __Pyx_PyDict_GetItemDefault(__Pyx_globals, __pyx_n_s_module, __pyx_kp_s_cereal_visionipc_visionipc_pyx); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 86, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + if (PyDict_SetItem(__pyx_t_4, __pyx_n_s_module_2, __pyx_t_5) < 0) __PYX_ERR(1, 86, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "EnumType":80 + * + * + * VisionStreamType = __Pyx_FlagBase('VisionStreamType', [ # <<<<<<<<<<<<<< + * ('VISION_STREAM_ROAD', __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_ROAD)), + * ('VISION_STREAM_DRIVER', __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_DRIVER)), + */ + __pyx_t_5 = __Pyx_PyObject_Call(__Pyx_FlagBase, __pyx_t_10, __pyx_t_4); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 80, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (PyDict_SetItem(__pyx_d, __pyx_n_s_VisionStreamType, __pyx_t_5) < 0) __PYX_ERR(1, 80, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "EnumType":88 + * ], module=__Pyx_globals.get("__module__", 'cereal.visionipc.visionipc_pyx')) + * + * if PY_VERSION_HEX >= 0x030B0000: # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = (PY_VERSION_HEX >= 0x030B0000); + if (__pyx_t_2) { + + /* "EnumType":93 + * + * + * VisionStreamType._member_names_ = list(VisionStreamType.__members__) # <<<<<<<<<<<<<< + * + * __Pyx_globals['VISION_STREAM_ROAD'] = VisionStreamType.VISION_STREAM_ROAD + */ + __Pyx_GetModuleGlobalName(__pyx_t_5, __pyx_n_s_VisionStreamType); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 93, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_members); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 93, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_5 = __Pyx_PySequence_ListKeepNew(__pyx_t_4); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 93, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_VisionStreamType); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 93, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (__Pyx_PyObject_SetAttrStr(__pyx_t_4, __pyx_n_s_member_names, __pyx_t_5) < 0) __PYX_ERR(1, 93, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "EnumType":88 + * ], module=__Pyx_globals.get("__module__", 'cereal.visionipc.visionipc_pyx')) + * + * if PY_VERSION_HEX >= 0x030B0000: # <<<<<<<<<<<<<< + * + * + */ + } + + /* "EnumType":95 + * VisionStreamType._member_names_ = list(VisionStreamType.__members__) + * + * __Pyx_globals['VISION_STREAM_ROAD'] = VisionStreamType.VISION_STREAM_ROAD # <<<<<<<<<<<<<< + * __Pyx_globals['VISION_STREAM_DRIVER'] = VisionStreamType.VISION_STREAM_DRIVER + * __Pyx_globals['VISION_STREAM_WIDE_ROAD'] = VisionStreamType.VISION_STREAM_WIDE_ROAD + */ + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_VisionStreamType); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 95, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_VISION_STREAM_ROAD); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 95, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(__Pyx_globals == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 95, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__Pyx_globals, __pyx_n_s_VISION_STREAM_ROAD, __pyx_t_5) < 0))) __PYX_ERR(1, 95, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "EnumType":96 + * + * __Pyx_globals['VISION_STREAM_ROAD'] = VisionStreamType.VISION_STREAM_ROAD + * __Pyx_globals['VISION_STREAM_DRIVER'] = VisionStreamType.VISION_STREAM_DRIVER # <<<<<<<<<<<<<< + * __Pyx_globals['VISION_STREAM_WIDE_ROAD'] = VisionStreamType.VISION_STREAM_WIDE_ROAD + * __Pyx_globals['VISION_STREAM_MAP'] = VisionStreamType.VISION_STREAM_MAP + */ + __Pyx_GetModuleGlobalName(__pyx_t_5, __pyx_n_s_VisionStreamType); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 96, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_VISION_STREAM_DRIVER); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 96, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(__Pyx_globals == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 96, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__Pyx_globals, __pyx_n_s_VISION_STREAM_DRIVER, __pyx_t_4) < 0))) __PYX_ERR(1, 96, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "EnumType":97 + * __Pyx_globals['VISION_STREAM_ROAD'] = VisionStreamType.VISION_STREAM_ROAD + * __Pyx_globals['VISION_STREAM_DRIVER'] = VisionStreamType.VISION_STREAM_DRIVER + * __Pyx_globals['VISION_STREAM_WIDE_ROAD'] = VisionStreamType.VISION_STREAM_WIDE_ROAD # <<<<<<<<<<<<<< + * __Pyx_globals['VISION_STREAM_MAP'] = VisionStreamType.VISION_STREAM_MAP + * else: + */ + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_VisionStreamType); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 97, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_VISION_STREAM_WIDE_ROAD); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 97, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(__Pyx_globals == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 97, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__Pyx_globals, __pyx_n_s_VISION_STREAM_WIDE_ROAD, __pyx_t_5) < 0))) __PYX_ERR(1, 97, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "EnumType":98 + * __Pyx_globals['VISION_STREAM_DRIVER'] = VisionStreamType.VISION_STREAM_DRIVER + * __Pyx_globals['VISION_STREAM_WIDE_ROAD'] = VisionStreamType.VISION_STREAM_WIDE_ROAD + * __Pyx_globals['VISION_STREAM_MAP'] = VisionStreamType.VISION_STREAM_MAP # <<<<<<<<<<<<<< + * else: + * class VisionStreamType(__Pyx_FlagBase): + */ + __Pyx_GetModuleGlobalName(__pyx_t_5, __pyx_n_s_VisionStreamType); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 98, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_VISION_STREAM_MAP); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 98, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(__Pyx_globals == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 98, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__Pyx_globals, __pyx_n_s_VISION_STREAM_MAP, __pyx_t_4) < 0))) __PYX_ERR(1, 98, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "EnumType":77 + * + * cdef dict __Pyx_globals = globals() + * if PY_VERSION_HEX >= 0x03060000: # <<<<<<<<<<<<<< + * + * + */ + goto __pyx_L33; + } + + /* "EnumType":100 + * __Pyx_globals['VISION_STREAM_MAP'] = VisionStreamType.VISION_STREAM_MAP + * else: + * class VisionStreamType(__Pyx_FlagBase): # <<<<<<<<<<<<<< + * pass + * __Pyx_globals['VISION_STREAM_ROAD'] = VisionStreamType(__Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_ROAD), 'VISION_STREAM_ROAD') + */ + /*else*/ { + __pyx_t_4 = PyTuple_New(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_INCREF(__Pyx_FlagBase); + __Pyx_GIVEREF(__Pyx_FlagBase); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, __Pyx_FlagBase)) __PYX_ERR(1, 100, __pyx_L1_error); + __pyx_t_5 = __Pyx_PEP560_update_bases(__pyx_t_4); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_10 = __Pyx_CalculateMetaclass(NULL, __pyx_t_5); if (unlikely(!__pyx_t_10)) __PYX_ERR(1, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __pyx_t_3 = __Pyx_Py3MetaclassPrepare(__pyx_t_10, __pyx_t_5, __pyx_n_s_VisionStreamType, __pyx_n_s_VisionStreamType, (PyObject *) NULL, __pyx_n_s_EnumType, (PyObject *) NULL); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (__pyx_t_5 != __pyx_t_4) { + if (unlikely((PyDict_SetItemString(__pyx_t_3, "__orig_bases__", __pyx_t_4) < 0))) __PYX_ERR(1, 100, __pyx_L1_error) + } + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_Py3ClassCreate(__pyx_t_10, __pyx_n_s_VisionStreamType, __pyx_t_5, __pyx_t_3, NULL, 0, 0); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_VisionStreamType, __pyx_t_4) < 0) __PYX_ERR(1, 100, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "EnumType":102 + * class VisionStreamType(__Pyx_FlagBase): + * pass + * __Pyx_globals['VISION_STREAM_ROAD'] = VisionStreamType(__Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_ROAD), 'VISION_STREAM_ROAD') # <<<<<<<<<<<<<< + * __Pyx_globals['VISION_STREAM_DRIVER'] = VisionStreamType(__Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_DRIVER), 'VISION_STREAM_DRIVER') + * __Pyx_globals['VISION_STREAM_WIDE_ROAD'] = VisionStreamType(__Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_WIDE_ROAD), 'VISION_STREAM_WIDE_ROAD') + */ + __Pyx_GetModuleGlobalName(__pyx_t_5, __pyx_n_s_VisionStreamType); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 102, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_10 = __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(__pyx_e_6cereal_9visionipc_13visionipc_pyx_VISION_STREAM_ROAD); if (unlikely(!__pyx_t_10)) __PYX_ERR(1, 102, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 102, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_10); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_10)) __PYX_ERR(1, 102, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_s_VISION_STREAM_ROAD); + __Pyx_GIVEREF(__pyx_n_s_VISION_STREAM_ROAD); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_n_s_VISION_STREAM_ROAD)) __PYX_ERR(1, 102, __pyx_L1_error); + __pyx_t_10 = 0; + __pyx_t_10 = __Pyx_PyObject_Call(__pyx_t_5, __pyx_t_3, NULL); if (unlikely(!__pyx_t_10)) __PYX_ERR(1, 102, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(__Pyx_globals == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 102, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__Pyx_globals, __pyx_n_s_VISION_STREAM_ROAD, __pyx_t_10) < 0))) __PYX_ERR(1, 102, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + + /* "EnumType":103 + * pass + * __Pyx_globals['VISION_STREAM_ROAD'] = VisionStreamType(__Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_ROAD), 'VISION_STREAM_ROAD') + * __Pyx_globals['VISION_STREAM_DRIVER'] = VisionStreamType(__Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_DRIVER), 'VISION_STREAM_DRIVER') # <<<<<<<<<<<<<< + * __Pyx_globals['VISION_STREAM_WIDE_ROAD'] = VisionStreamType(__Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_WIDE_ROAD), 'VISION_STREAM_WIDE_ROAD') + * __Pyx_globals['VISION_STREAM_MAP'] = VisionStreamType(__Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_MAP), 'VISION_STREAM_MAP') + */ + __Pyx_GetModuleGlobalName(__pyx_t_10, __pyx_n_s_VisionStreamType); if (unlikely(!__pyx_t_10)) __PYX_ERR(1, 103, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __pyx_t_3 = __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(__pyx_e_6cereal_9visionipc_13visionipc_pyx_VISION_STREAM_DRIVER); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 103, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = PyTuple_New(2); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 103, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_t_3)) __PYX_ERR(1, 103, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_s_VISION_STREAM_DRIVER); + __Pyx_GIVEREF(__pyx_n_s_VISION_STREAM_DRIVER); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_n_s_VISION_STREAM_DRIVER)) __PYX_ERR(1, 103, __pyx_L1_error); + __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PyObject_Call(__pyx_t_10, __pyx_t_5, NULL); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 103, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(__Pyx_globals == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 103, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__Pyx_globals, __pyx_n_s_VISION_STREAM_DRIVER, __pyx_t_3) < 0))) __PYX_ERR(1, 103, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "EnumType":104 + * __Pyx_globals['VISION_STREAM_ROAD'] = VisionStreamType(__Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_ROAD), 'VISION_STREAM_ROAD') + * __Pyx_globals['VISION_STREAM_DRIVER'] = VisionStreamType(__Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_DRIVER), 'VISION_STREAM_DRIVER') + * __Pyx_globals['VISION_STREAM_WIDE_ROAD'] = VisionStreamType(__Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_WIDE_ROAD), 'VISION_STREAM_WIDE_ROAD') # <<<<<<<<<<<<<< + * __Pyx_globals['VISION_STREAM_MAP'] = VisionStreamType(__Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_MAP), 'VISION_STREAM_MAP') + * + */ + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_VisionStreamType); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 104, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(__pyx_e_6cereal_9visionipc_13visionipc_pyx_VISION_STREAM_WIDE_ROAD); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 104, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_10 = PyTuple_New(2); if (unlikely(!__pyx_t_10)) __PYX_ERR(1, 104, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __Pyx_GIVEREF(__pyx_t_5); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_10, 0, __pyx_t_5)) __PYX_ERR(1, 104, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_s_VISION_STREAM_WIDE_ROAD); + __Pyx_GIVEREF(__pyx_n_s_VISION_STREAM_WIDE_ROAD); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_10, 1, __pyx_n_s_VISION_STREAM_WIDE_ROAD)) __PYX_ERR(1, 104, __pyx_L1_error); + __pyx_t_5 = 0; + __pyx_t_5 = __Pyx_PyObject_Call(__pyx_t_3, __pyx_t_10, NULL); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 104, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + if (unlikely(__Pyx_globals == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 104, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__Pyx_globals, __pyx_n_s_VISION_STREAM_WIDE_ROAD, __pyx_t_5) < 0))) __PYX_ERR(1, 104, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "EnumType":105 + * __Pyx_globals['VISION_STREAM_DRIVER'] = VisionStreamType(__Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_DRIVER), 'VISION_STREAM_DRIVER') + * __Pyx_globals['VISION_STREAM_WIDE_ROAD'] = VisionStreamType(__Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_WIDE_ROAD), 'VISION_STREAM_WIDE_ROAD') + * __Pyx_globals['VISION_STREAM_MAP'] = VisionStreamType(__Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(VISION_STREAM_MAP), 'VISION_STREAM_MAP') # <<<<<<<<<<<<<< + * + */ + __Pyx_GetModuleGlobalName(__pyx_t_5, __pyx_n_s_VisionStreamType); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 105, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_10 = __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(__pyx_e_6cereal_9visionipc_13visionipc_pyx_VISION_STREAM_MAP); if (unlikely(!__pyx_t_10)) __PYX_ERR(1, 105, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 105, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_10); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_10)) __PYX_ERR(1, 105, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_s_VISION_STREAM_MAP); + __Pyx_GIVEREF(__pyx_n_s_VISION_STREAM_MAP); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_n_s_VISION_STREAM_MAP)) __PYX_ERR(1, 105, __pyx_L1_error); + __pyx_t_10 = 0; + __pyx_t_10 = __Pyx_PyObject_Call(__pyx_t_5, __pyx_t_3, NULL); if (unlikely(!__pyx_t_10)) __PYX_ERR(1, 105, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(__Pyx_globals == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 105, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__Pyx_globals, __pyx_n_s_VISION_STREAM_MAP, __pyx_t_10) < 0))) __PYX_ERR(1, 105, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + } + __pyx_L33:; + + /* "cereal/visionipc/visionipc_pyx.pyx":4 + * # cython: c_string_encoding=ascii, language_level=3 + * + * import sys # <<<<<<<<<<<<<< + * import numpy as np + * cimport numpy as cnp + */ + __pyx_t_10 = __Pyx_ImportDottedModule(__pyx_n_s_sys, NULL); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 4, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_sys, __pyx_t_10) < 0) __PYX_ERR(0, 4, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + + /* "cereal/visionipc/visionipc_pyx.pyx":5 + * + * import sys + * import numpy as np # <<<<<<<<<<<<<< + * cimport numpy as cnp + * from cython.view cimport array + */ + __pyx_t_10 = __Pyx_ImportDottedModule(__pyx_n_s_numpy, NULL); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_np, __pyx_t_10) < 0) __PYX_ERR(0, 5, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + + /* "cereal/visionipc/visionipc_pyx.pyx":20 + * + * + * def get_endpoint_name(string name, VisionStreamType stream): # <<<<<<<<<<<<<< + * return cpp_get_endpoint_name(name, stream).decode('utf-8') + * + */ + __pyx_t_10 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9visionipc_13visionipc_pyx_1get_endpoint_name, 0, __pyx_n_s_get_endpoint_name, NULL, __pyx_kp_s_cereal_visionipc_visionipc_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__44)); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 20, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_get_endpoint_name, __pyx_t_10) < 0) __PYX_ERR(0, 20, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.buf cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_t_10 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_1__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_VisionBuf___reduce_cython, NULL, __pyx_kp_s_cereal_visionipc_visionipc_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__45)); if (unlikely(!__pyx_t_10)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_10) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.buf cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.buf cannot be converted to a Python object for pickling" + */ + __pyx_t_10 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9visionipc_13visionipc_pyx_9VisionBuf_3__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_VisionBuf___setstate_cython, NULL, __pyx_kp_s_cereal_visionipc_visionipc_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__46)); if (unlikely(!__pyx_t_10)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_10) < 0) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + + /* "cereal/visionipc/visionipc_pyx.pyx":69 + * self.server = new cppVisionIpcServer(name, NULL, NULL) + * + * def create_buffers(self, VisionStreamType tp, size_t num_buffers, bool rgb, size_t width, size_t height): # <<<<<<<<<<<<<< + * self.server.create_buffers(tp, num_buffers, rgb, width, height) + * + */ + __pyx_t_10 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_3create_buffers, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_VisionIpcServer_create_buffers, NULL, __pyx_kp_s_cereal_visionipc_visionipc_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__48)); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 69, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer, __pyx_n_s_create_buffers, __pyx_t_10) < 0) __PYX_ERR(0, 69, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + PyType_Modified(__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer); + + /* "cereal/visionipc/visionipc_pyx.pyx":72 + * self.server.create_buffers(tp, num_buffers, rgb, width, height) + * + * def create_buffers_with_sizes(self, VisionStreamType tp, size_t num_buffers, bool rgb, size_t width, size_t height, size_t size, size_t stride, size_t uv_offset): # <<<<<<<<<<<<<< + * self.server.create_buffers_with_sizes(tp, num_buffers, rgb, width, height, size, stride, uv_offset) + * + */ + __pyx_t_10 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_5create_buffers_with_sizes, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_VisionIpcServer_create_buffers_w, NULL, __pyx_kp_s_cereal_visionipc_visionipc_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__50)); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 72, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer, __pyx_n_s_create_buffers_with_sizes, __pyx_t_10) < 0) __PYX_ERR(0, 72, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + PyType_Modified(__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer); + + /* "cereal/visionipc/visionipc_pyx.pyx":75 + * self.server.create_buffers_with_sizes(tp, num_buffers, rgb, width, height, size, stride, uv_offset) + * + * def send(self, VisionStreamType tp, const unsigned char[:] data, uint32_t frame_id=0, uint64_t timestamp_sof=0, uint64_t timestamp_eof=0): # <<<<<<<<<<<<<< + * cdef cppVisionBuf * buf = self.server.get_buffer(tp) + * + */ + __pyx_t_10 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_7send, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_VisionIpcServer_send, NULL, __pyx_kp_s_cereal_visionipc_visionipc_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__52)); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 75, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_10, __pyx_tuple__53); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer, __pyx_n_s_send, __pyx_t_10) < 0) __PYX_ERR(0, 75, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + PyType_Modified(__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer); + + /* "cereal/visionipc/visionipc_pyx.pyx":90 + * self.server.send(buf, &extra, False) + * + * def start_listener(self): # <<<<<<<<<<<<<< + * self.server.start_listener() + * + */ + __pyx_t_10 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_9start_listener, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_VisionIpcServer_start_listener, NULL, __pyx_kp_s_cereal_visionipc_visionipc_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__54)); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 90, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer, __pyx_n_s_start_listener, __pyx_t_10) < 0) __PYX_ERR(0, 90, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + PyType_Modified(__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcServer); + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.server cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_t_10 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_13__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_VisionIpcServer___reduce_cython, NULL, __pyx_kp_s_cereal_visionipc_visionipc_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__55)); if (unlikely(!__pyx_t_10)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_10) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.server cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.server cannot be converted to a Python object for pickling" + */ + __pyx_t_10 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcServer_15__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_VisionIpcServer___setstate_cytho, NULL, __pyx_kp_s_cereal_visionipc_visionipc_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__56)); if (unlikely(!__pyx_t_10)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_10) < 0) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + + /* "cereal/visionipc/visionipc_pyx.pyx":154 + * return self.extra.valid + * + * def recv(self, int timeout_ms=100): # <<<<<<<<<<<<<< + * buf = self.client.recv(&self.extra, timeout_ms) + * if not buf: + */ + __pyx_t_10 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_5recv, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_VisionIpcClient_recv, NULL, __pyx_kp_s_cereal_visionipc_visionipc_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__58)); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 154, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_10, __pyx_tuple__59); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient, __pyx_n_s_recv, __pyx_t_10) < 0) __PYX_ERR(0, 154, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + PyType_Modified(__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient); + + /* "cereal/visionipc/visionipc_pyx.pyx":160 + * return VisionBuf.create(buf) + * + * def connect(self, bool blocking): # <<<<<<<<<<<<<< + * return self.client.connect(blocking) + * + */ + __pyx_t_10 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_7connect, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_VisionIpcClient_connect, NULL, __pyx_kp_s_cereal_visionipc_visionipc_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__61)); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 160, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient, __pyx_n_s_connect, __pyx_t_10) < 0) __PYX_ERR(0, 160, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + PyType_Modified(__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient); + + /* "cereal/visionipc/visionipc_pyx.pyx":163 + * return self.client.connect(blocking) + * + * def is_connected(self): # <<<<<<<<<<<<<< + * return self.client.is_connected() + * + */ + __pyx_t_10 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_9is_connected, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_VisionIpcClient_is_connected, NULL, __pyx_kp_s_cereal_visionipc_visionipc_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__62)); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 163, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient, __pyx_n_s_is_connected, __pyx_t_10) < 0) __PYX_ERR(0, 163, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + PyType_Modified(__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient); + + /* "cereal/visionipc/visionipc_pyx.pyx":166 + * return self.client.is_connected() + * + * @staticmethod # <<<<<<<<<<<<<< + * def available_streams(string name, bool block): + * return cppVisionIpcClient.getAvailableStreams(name, block) + */ + __pyx_t_10 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_11available_streams, __Pyx_CYFUNCTION_STATICMETHOD | __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_VisionIpcClient_available_stream, NULL, __pyx_kp_s_cereal_visionipc_visionipc_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__64)); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 166, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient, __pyx_n_s_available_streams, __pyx_t_10) < 0) __PYX_ERR(0, 166, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + PyType_Modified(__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient); + __Pyx_GetNameInClass(__pyx_t_10, (PyObject *)__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient, __pyx_n_s_available_streams); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 166, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __pyx_t_3 = __Pyx_PyObject_CallOneArg(__pyx_builtin_staticmethod, __pyx_t_10); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 166, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient, __pyx_n_s_available_streams, __pyx_t_3) < 0) __PYX_ERR(0, 166, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + PyType_Modified(__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionIpcClient); + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_13__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_VisionIpcClient___reduce_cython, NULL, __pyx_kp_s_cereal_visionipc_visionipc_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__65)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_3) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6cereal_9visionipc_13visionipc_pyx_15VisionIpcClient_15__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_VisionIpcClient___setstate_cytho, NULL, __pyx_kp_s_cereal_visionipc_visionipc_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__66)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_3) < 0) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "cereal/visionipc/visionipc_pyx.pyx":1 + * # distutils: language = c++ # <<<<<<<<<<<<<< + * # cython: c_string_encoding=ascii, language_level=3 + * + */ + __pyx_t_3 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_test, __pyx_t_3) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /*--- Wrapped vars code ---*/ + + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_10); + if (__pyx_m) { + if (__pyx_d && stringtab_initialized) { + __Pyx_AddTraceback("init cereal.visionipc.visionipc_pyx", __pyx_clineno, __pyx_lineno, __pyx_filename); + } + #if !CYTHON_USE_MODULE_STATE + Py_CLEAR(__pyx_m); + #else + Py_DECREF(__pyx_m); + if (pystate_addmodule_run) { + PyObject *tp, *value, *tb; + PyErr_Fetch(&tp, &value, &tb); + PyState_RemoveModule(&__pyx_moduledef); + PyErr_Restore(tp, value, tb); + } + #endif + } else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_ImportError, "init cereal.visionipc.visionipc_pyx"); + } + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + #if CYTHON_PEP489_MULTI_PHASE_INIT + return (__pyx_m != NULL) ? 0 : -1; + #elif PY_MAJOR_VERSION >= 3 + return __pyx_m; + #else + return; + #endif +} +/* #### Code section: cleanup_globals ### */ +/* #### Code section: cleanup_module ### */ +/* #### Code section: main_method ### */ +/* #### Code section: utility_code_pragmas ### */ +#ifdef _MSC_VER +#pragma warning( push ) +/* Warning 4127: conditional expression is constant + * Cython uses constant conditional expressions to allow in inline functions to be optimized at + * compile-time, so this warning is not useful + */ +#pragma warning( disable : 4127 ) +#endif + + + +/* #### Code section: utility_code_def ### */ + +/* --- Runtime support code --- */ +/* Refnanny */ +#if CYTHON_REFNANNY +static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname) { + PyObject *m = NULL, *p = NULL; + void *r = NULL; + m = PyImport_ImportModule(modname); + if (!m) goto end; + p = PyObject_GetAttrString(m, "RefNannyAPI"); + if (!p) goto end; + r = PyLong_AsVoidPtr(p); +end: + Py_XDECREF(p); + Py_XDECREF(m); + return (__Pyx_RefNannyAPIStruct *)r; +} +#endif + +/* PyErrExceptionMatches */ +#if CYTHON_FAST_THREAD_STATE +static int __Pyx_PyErr_ExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; i= 0x030C00A6 + PyObject *current_exception = tstate->current_exception; + if (unlikely(!current_exception)) return 0; + exc_type = (PyObject*) Py_TYPE(current_exception); + if (exc_type == err) return 1; +#else + exc_type = tstate->curexc_type; + if (exc_type == err) return 1; + if (unlikely(!exc_type)) return 0; +#endif + #if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(exc_type); + #endif + if (unlikely(PyTuple_Check(err))) { + result = __Pyx_PyErr_ExceptionMatchesTuple(exc_type, err); + } else { + result = __Pyx_PyErr_GivenExceptionMatches(exc_type, err); + } + #if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(exc_type); + #endif + return result; +} +#endif + +/* PyErrFetchRestore */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject *tmp_value; + assert(type == NULL || (value != NULL && type == (PyObject*) Py_TYPE(value))); + if (value) { + #if CYTHON_COMPILING_IN_CPYTHON + if (unlikely(((PyBaseExceptionObject*) value)->traceback != tb)) + #endif + PyException_SetTraceback(value, tb); + } + tmp_value = tstate->current_exception; + tstate->current_exception = value; + Py_XDECREF(tmp_value); + Py_XDECREF(type); + Py_XDECREF(tb); +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + tmp_type = tstate->curexc_type; + tmp_value = tstate->curexc_value; + tmp_tb = tstate->curexc_traceback; + tstate->curexc_type = type; + tstate->curexc_value = value; + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); +#endif +} +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject* exc_value; + exc_value = tstate->current_exception; + tstate->current_exception = 0; + *value = exc_value; + *type = NULL; + *tb = NULL; + if (exc_value) { + *type = (PyObject*) Py_TYPE(exc_value); + Py_INCREF(*type); + #if CYTHON_COMPILING_IN_CPYTHON + *tb = ((PyBaseExceptionObject*) exc_value)->traceback; + Py_XINCREF(*tb); + #else + *tb = PyException_GetTraceback(exc_value); + #endif + } +#else + *type = tstate->curexc_type; + *value = tstate->curexc_value; + *tb = tstate->curexc_traceback; + tstate->curexc_type = 0; + tstate->curexc_value = 0; + tstate->curexc_traceback = 0; +#endif +} +#endif + +/* PyObjectGetAttrStr */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name) { + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro)) + return tp->tp_getattro(obj, attr_name); +#if PY_MAJOR_VERSION < 3 + if (likely(tp->tp_getattr)) + return tp->tp_getattr(obj, PyString_AS_STRING(attr_name)); +#endif + return PyObject_GetAttr(obj, attr_name); +} +#endif + +/* PyObjectGetAttrStrNoError */ +#if __PYX_LIMITED_VERSION_HEX < 0x030d00A1 +static void __Pyx_PyObject_GetAttrStr_ClearAttributeError(void) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + if (likely(__Pyx_PyErr_ExceptionMatches(PyExc_AttributeError))) + __Pyx_PyErr_Clear(); +} +#endif +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name) { + PyObject *result; +#if __PYX_LIMITED_VERSION_HEX >= 0x030d00A1 + (void) PyObject_GetOptionalAttr(obj, attr_name, &result); + return result; +#else +#if CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_TYPE_SLOTS && PY_VERSION_HEX >= 0x030700B1 + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro == PyObject_GenericGetAttr)) { + return _PyObject_GenericGetAttrWithDict(obj, attr_name, NULL, 1); + } +#endif + result = __Pyx_PyObject_GetAttrStr(obj, attr_name); + if (unlikely(!result)) { + __Pyx_PyObject_GetAttrStr_ClearAttributeError(); + } + return result; +#endif +} + +/* GetBuiltinName */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name) { + PyObject* result = __Pyx_PyObject_GetAttrStrNoError(__pyx_b, name); + if (unlikely(!result) && !PyErr_Occurred()) { + PyErr_Format(PyExc_NameError, +#if PY_MAJOR_VERSION >= 3 + "name '%U' is not defined", name); +#else + "name '%.200s' is not defined", PyString_AS_STRING(name)); +#endif + } + return result; +} + +/* TupleAndListFromArray */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE void __Pyx_copy_object_array(PyObject *const *CYTHON_RESTRICT src, PyObject** CYTHON_RESTRICT dest, Py_ssize_t length) { + PyObject *v; + Py_ssize_t i; + for (i = 0; i < length; i++) { + v = dest[i] = src[i]; + Py_INCREF(v); + } +} +static CYTHON_INLINE PyObject * +__Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + Py_INCREF(__pyx_empty_tuple); + return __pyx_empty_tuple; + } + res = PyTuple_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyTupleObject*)res)->ob_item, n); + return res; +} +static CYTHON_INLINE PyObject * +__Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + return PyList_New(0); + } + res = PyList_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyListObject*)res)->ob_item, n); + return res; +} +#endif + +/* BytesEquals */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else + if (s1 == s2) { + return (equals == Py_EQ); + } else if (PyBytes_CheckExact(s1) & PyBytes_CheckExact(s2)) { + const char *ps1, *ps2; + Py_ssize_t length = PyBytes_GET_SIZE(s1); + if (length != PyBytes_GET_SIZE(s2)) + return (equals == Py_NE); + ps1 = PyBytes_AS_STRING(s1); + ps2 = PyBytes_AS_STRING(s2); + if (ps1[0] != ps2[0]) { + return (equals == Py_NE); + } else if (length == 1) { + return (equals == Py_EQ); + } else { + int result; +#if CYTHON_USE_UNICODE_INTERNALS && (PY_VERSION_HEX < 0x030B0000) + Py_hash_t hash1, hash2; + hash1 = ((PyBytesObject*)s1)->ob_shash; + hash2 = ((PyBytesObject*)s2)->ob_shash; + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + return (equals == Py_NE); + } +#endif + result = memcmp(ps1, ps2, (size_t)length); + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & PyBytes_CheckExact(s2)) { + return (equals == Py_NE); + } else if ((s2 == Py_None) & PyBytes_CheckExact(s1)) { + return (equals == Py_NE); + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +#endif +} + +/* UnicodeEquals */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else +#if PY_MAJOR_VERSION < 3 + PyObject* owned_ref = NULL; +#endif + int s1_is_unicode, s2_is_unicode; + if (s1 == s2) { + goto return_eq; + } + s1_is_unicode = PyUnicode_CheckExact(s1); + s2_is_unicode = PyUnicode_CheckExact(s2); +#if PY_MAJOR_VERSION < 3 + if ((s1_is_unicode & (!s2_is_unicode)) && PyString_CheckExact(s2)) { + owned_ref = PyUnicode_FromObject(s2); + if (unlikely(!owned_ref)) + return -1; + s2 = owned_ref; + s2_is_unicode = 1; + } else if ((s2_is_unicode & (!s1_is_unicode)) && PyString_CheckExact(s1)) { + owned_ref = PyUnicode_FromObject(s1); + if (unlikely(!owned_ref)) + return -1; + s1 = owned_ref; + s1_is_unicode = 1; + } else if (((!s2_is_unicode) & (!s1_is_unicode))) { + return __Pyx_PyBytes_Equals(s1, s2, equals); + } +#endif + if (s1_is_unicode & s2_is_unicode) { + Py_ssize_t length; + int kind; + void *data1, *data2; + if (unlikely(__Pyx_PyUnicode_READY(s1) < 0) || unlikely(__Pyx_PyUnicode_READY(s2) < 0)) + return -1; + length = __Pyx_PyUnicode_GET_LENGTH(s1); + if (length != __Pyx_PyUnicode_GET_LENGTH(s2)) { + goto return_ne; + } +#if CYTHON_USE_UNICODE_INTERNALS + { + Py_hash_t hash1, hash2; + #if CYTHON_PEP393_ENABLED + hash1 = ((PyASCIIObject*)s1)->hash; + hash2 = ((PyASCIIObject*)s2)->hash; + #else + hash1 = ((PyUnicodeObject*)s1)->hash; + hash2 = ((PyUnicodeObject*)s2)->hash; + #endif + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + goto return_ne; + } + } +#endif + kind = __Pyx_PyUnicode_KIND(s1); + if (kind != __Pyx_PyUnicode_KIND(s2)) { + goto return_ne; + } + data1 = __Pyx_PyUnicode_DATA(s1); + data2 = __Pyx_PyUnicode_DATA(s2); + if (__Pyx_PyUnicode_READ(kind, data1, 0) != __Pyx_PyUnicode_READ(kind, data2, 0)) { + goto return_ne; + } else if (length == 1) { + goto return_eq; + } else { + int result = memcmp(data1, data2, (size_t)(length * kind)); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & s2_is_unicode) { + goto return_ne; + } else if ((s2 == Py_None) & s1_is_unicode) { + goto return_ne; + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +return_eq: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ); +return_ne: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_NE); +#endif +} + +/* fastcall */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s) +{ + Py_ssize_t i, n = PyTuple_GET_SIZE(kwnames); + for (i = 0; i < n; i++) + { + if (s == PyTuple_GET_ITEM(kwnames, i)) return kwvalues[i]; + } + for (i = 0; i < n; i++) + { + int eq = __Pyx_PyUnicode_Equals(s, PyTuple_GET_ITEM(kwnames, i), Py_EQ); + if (unlikely(eq != 0)) { + if (unlikely(eq < 0)) return NULL; + return kwvalues[i]; + } + } + return NULL; +} +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 +CYTHON_UNUSED static PyObject *__Pyx_KwargsAsDict_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues) { + Py_ssize_t i, nkwargs = PyTuple_GET_SIZE(kwnames); + PyObject *dict; + dict = PyDict_New(); + if (unlikely(!dict)) + return NULL; + for (i=0; i= 3 + "%s() got multiple values for keyword argument '%U'", func_name, kw_name); + #else + "%s() got multiple values for keyword argument '%s'", func_name, + PyString_AsString(kw_name)); + #endif +} + +/* ParseKeywords */ +static int __Pyx_ParseOptionalKeywords( + PyObject *kwds, + PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, + PyObject *values[], + Py_ssize_t num_pos_args, + const char* function_name) +{ + PyObject *key = 0, *value = 0; + Py_ssize_t pos = 0; + PyObject*** name; + PyObject*** first_kw_arg = argnames + num_pos_args; + int kwds_is_tuple = CYTHON_METH_FASTCALL && likely(PyTuple_Check(kwds)); + while (1) { + Py_XDECREF(key); key = NULL; + Py_XDECREF(value); value = NULL; + if (kwds_is_tuple) { + Py_ssize_t size; +#if CYTHON_ASSUME_SAFE_MACROS + size = PyTuple_GET_SIZE(kwds); +#else + size = PyTuple_Size(kwds); + if (size < 0) goto bad; +#endif + if (pos >= size) break; +#if CYTHON_AVOID_BORROWED_REFS + key = __Pyx_PySequence_ITEM(kwds, pos); + if (!key) goto bad; +#elif CYTHON_ASSUME_SAFE_MACROS + key = PyTuple_GET_ITEM(kwds, pos); +#else + key = PyTuple_GetItem(kwds, pos); + if (!key) goto bad; +#endif + value = kwvalues[pos]; + pos++; + } + else + { + if (!PyDict_Next(kwds, &pos, &key, &value)) break; +#if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(key); +#endif + } + name = first_kw_arg; + while (*name && (**name != key)) name++; + if (*name) { + values[name-argnames] = value; +#if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(value); + Py_DECREF(key); +#endif + key = NULL; + value = NULL; + continue; + } +#if !CYTHON_AVOID_BORROWED_REFS + Py_INCREF(key); +#endif + Py_INCREF(value); + name = first_kw_arg; + #if PY_MAJOR_VERSION < 3 + if (likely(PyString_Check(key))) { + while (*name) { + if ((CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**name) == PyString_GET_SIZE(key)) + && _PyString_Eq(**name, key)) { + values[name-argnames] = value; +#if CYTHON_AVOID_BORROWED_REFS + value = NULL; +#endif + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + if ((**argname == key) || ( + (CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**argname) == PyString_GET_SIZE(key)) + && _PyString_Eq(**argname, key))) { + goto arg_passed_twice; + } + argname++; + } + } + } else + #endif + if (likely(PyUnicode_Check(key))) { + while (*name) { + int cmp = ( + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**name) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**name, key) + ); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) { + values[name-argnames] = value; +#if CYTHON_AVOID_BORROWED_REFS + value = NULL; +#endif + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + int cmp = (**argname == key) ? 0 : + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**argname) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**argname, key); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) goto arg_passed_twice; + argname++; + } + } + } else + goto invalid_keyword_type; + if (kwds2) { + if (unlikely(PyDict_SetItem(kwds2, key, value))) goto bad; + } else { + goto invalid_keyword; + } + } + Py_XDECREF(key); + Py_XDECREF(value); + return 0; +arg_passed_twice: + __Pyx_RaiseDoubleKeywordsError(function_name, key); + goto bad; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + goto bad; +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif +bad: + Py_XDECREF(key); + Py_XDECREF(value); + return -1; +} + +/* PyFunctionFastCall */ +#if CYTHON_FAST_PYCALL && !CYTHON_VECTORCALL +static PyObject* __Pyx_PyFunction_FastCallNoKw(PyCodeObject *co, PyObject **args, Py_ssize_t na, + PyObject *globals) { + PyFrameObject *f; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject **fastlocals; + Py_ssize_t i; + PyObject *result; + assert(globals != NULL); + /* XXX Perhaps we should create a specialized + PyFrame_New() that doesn't take locals, but does + take builtins without sanity checking them. + */ + assert(tstate != NULL); + f = PyFrame_New(tstate, co, globals, NULL); + if (f == NULL) { + return NULL; + } + fastlocals = __Pyx_PyFrame_GetLocalsplus(f); + for (i = 0; i < na; i++) { + Py_INCREF(*args); + fastlocals[i] = *args++; + } + result = PyEval_EvalFrameEx(f,0); + ++tstate->recursion_depth; + Py_DECREF(f); + --tstate->recursion_depth; + return result; +} +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs) { + PyCodeObject *co = (PyCodeObject *)PyFunction_GET_CODE(func); + PyObject *globals = PyFunction_GET_GLOBALS(func); + PyObject *argdefs = PyFunction_GET_DEFAULTS(func); + PyObject *closure; +#if PY_MAJOR_VERSION >= 3 + PyObject *kwdefs; +#endif + PyObject *kwtuple, **k; + PyObject **d; + Py_ssize_t nd; + Py_ssize_t nk; + PyObject *result; + assert(kwargs == NULL || PyDict_Check(kwargs)); + nk = kwargs ? PyDict_Size(kwargs) : 0; + #if PY_MAJOR_VERSION < 3 + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) { + return NULL; + } + #else + if (unlikely(Py_EnterRecursiveCall(" while calling a Python object"))) { + return NULL; + } + #endif + if ( +#if PY_MAJOR_VERSION >= 3 + co->co_kwonlyargcount == 0 && +#endif + likely(kwargs == NULL || nk == 0) && + co->co_flags == (CO_OPTIMIZED | CO_NEWLOCALS | CO_NOFREE)) { + if (argdefs == NULL && co->co_argcount == nargs) { + result = __Pyx_PyFunction_FastCallNoKw(co, args, nargs, globals); + goto done; + } + else if (nargs == 0 && argdefs != NULL + && co->co_argcount == Py_SIZE(argdefs)) { + /* function called with no arguments, but all parameters have + a default value: use default values as arguments .*/ + args = &PyTuple_GET_ITEM(argdefs, 0); + result =__Pyx_PyFunction_FastCallNoKw(co, args, Py_SIZE(argdefs), globals); + goto done; + } + } + if (kwargs != NULL) { + Py_ssize_t pos, i; + kwtuple = PyTuple_New(2 * nk); + if (kwtuple == NULL) { + result = NULL; + goto done; + } + k = &PyTuple_GET_ITEM(kwtuple, 0); + pos = i = 0; + while (PyDict_Next(kwargs, &pos, &k[i], &k[i+1])) { + Py_INCREF(k[i]); + Py_INCREF(k[i+1]); + i += 2; + } + nk = i / 2; + } + else { + kwtuple = NULL; + k = NULL; + } + closure = PyFunction_GET_CLOSURE(func); +#if PY_MAJOR_VERSION >= 3 + kwdefs = PyFunction_GET_KW_DEFAULTS(func); +#endif + if (argdefs != NULL) { + d = &PyTuple_GET_ITEM(argdefs, 0); + nd = Py_SIZE(argdefs); + } + else { + d = NULL; + nd = 0; + } +#if PY_MAJOR_VERSION >= 3 + result = PyEval_EvalCodeEx((PyObject*)co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, kwdefs, closure); +#else + result = PyEval_EvalCodeEx(co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, closure); +#endif + Py_XDECREF(kwtuple); +done: + Py_LeaveRecursiveCall(); + return result; +} +#endif + +/* PyObjectCall */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw) { + PyObject *result; + ternaryfunc call = Py_TYPE(func)->tp_call; + if (unlikely(!call)) + return PyObject_Call(func, arg, kw); + #if PY_MAJOR_VERSION < 3 + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + #else + if (unlikely(Py_EnterRecursiveCall(" while calling a Python object"))) + return NULL; + #endif + result = (*call)(func, arg, kw); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* PyObjectCallMethO */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg) { + PyObject *self, *result; + PyCFunction cfunc; + cfunc = __Pyx_CyOrPyCFunction_GET_FUNCTION(func); + self = __Pyx_CyOrPyCFunction_GET_SELF(func); + #if PY_MAJOR_VERSION < 3 + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + #else + if (unlikely(Py_EnterRecursiveCall(" while calling a Python object"))) + return NULL; + #endif + result = cfunc(self, arg); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* PyObjectFastCall */ +#if PY_VERSION_HEX < 0x03090000 || CYTHON_COMPILING_IN_LIMITED_API +static PyObject* __Pyx_PyObject_FastCall_fallback(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs) { + PyObject *argstuple; + PyObject *result = 0; + size_t i; + argstuple = PyTuple_New((Py_ssize_t)nargs); + if (unlikely(!argstuple)) return NULL; + for (i = 0; i < nargs; i++) { + Py_INCREF(args[i]); + if (__Pyx_PyTuple_SET_ITEM(argstuple, (Py_ssize_t)i, args[i]) < 0) goto bad; + } + result = __Pyx_PyObject_Call(func, argstuple, kwargs); + bad: + Py_DECREF(argstuple); + return result; +} +#endif +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t _nargs, PyObject *kwargs) { + Py_ssize_t nargs = __Pyx_PyVectorcall_NARGS(_nargs); +#if CYTHON_COMPILING_IN_CPYTHON + if (nargs == 0 && kwargs == NULL) { + if (__Pyx_CyOrPyCFunction_Check(func) && likely( __Pyx_CyOrPyCFunction_GET_FLAGS(func) & METH_NOARGS)) + return __Pyx_PyObject_CallMethO(func, NULL); + } + else if (nargs == 1 && kwargs == NULL) { + if (__Pyx_CyOrPyCFunction_Check(func) && likely( __Pyx_CyOrPyCFunction_GET_FLAGS(func) & METH_O)) + return __Pyx_PyObject_CallMethO(func, args[0]); + } +#endif + #if PY_VERSION_HEX < 0x030800B1 + #if CYTHON_FAST_PYCCALL + if (PyCFunction_Check(func)) { + if (kwargs) { + return _PyCFunction_FastCallDict(func, args, nargs, kwargs); + } else { + return _PyCFunction_FastCallKeywords(func, args, nargs, NULL); + } + } + #if PY_VERSION_HEX >= 0x030700A1 + if (!kwargs && __Pyx_IS_TYPE(func, &PyMethodDescr_Type)) { + return _PyMethodDescr_FastCallKeywords(func, args, nargs, NULL); + } + #endif + #endif + #if CYTHON_FAST_PYCALL + if (PyFunction_Check(func)) { + return __Pyx_PyFunction_FastCallDict(func, args, nargs, kwargs); + } + #endif + #endif + if (kwargs == NULL) { + #if CYTHON_VECTORCALL + #if PY_VERSION_HEX < 0x03090000 + vectorcallfunc f = _PyVectorcall_Function(func); + #else + vectorcallfunc f = PyVectorcall_Function(func); + #endif + if (f) { + return f(func, args, (size_t)nargs, NULL); + } + #elif defined(__Pyx_CyFunction_USED) && CYTHON_BACKPORT_VECTORCALL + if (__Pyx_CyFunction_CheckExact(func)) { + __pyx_vectorcallfunc f = __Pyx_CyFunction_func_vectorcall(func); + if (f) return f(func, args, (size_t)nargs, NULL); + } + #endif + } + if (nargs == 0) { + return __Pyx_PyObject_Call(func, __pyx_empty_tuple, kwargs); + } + #if PY_VERSION_HEX >= 0x03090000 && !CYTHON_COMPILING_IN_LIMITED_API + return PyObject_VectorcallDict(func, args, (size_t)nargs, kwargs); + #else + return __Pyx_PyObject_FastCall_fallback(func, args, (size_t)nargs, kwargs); + #endif +} + +/* PyObjectSetAttrStr */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE int __Pyx_PyObject_SetAttrStr(PyObject* obj, PyObject* attr_name, PyObject* value) { + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_setattro)) + return tp->tp_setattro(obj, attr_name, value); +#if PY_MAJOR_VERSION < 3 + if (likely(tp->tp_setattr)) + return tp->tp_setattr(obj, PyString_AS_STRING(attr_name), value); +#endif + return PyObject_SetAttr(obj, attr_name, value); +} +#endif + +/* GetItemInt */ +static PyObject *__Pyx_GetItemInt_Generic(PyObject *o, PyObject* j) { + PyObject *r; + if (unlikely(!j)) return NULL; + r = PyObject_GetItem(o, j); + Py_DECREF(j); + return r; +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_List_Fast(PyObject *o, Py_ssize_t i, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + Py_ssize_t wrapped_i = i; + if (wraparound & unlikely(i < 0)) { + wrapped_i += PyList_GET_SIZE(o); + } + if ((!boundscheck) || likely(__Pyx_is_valid_index(wrapped_i, PyList_GET_SIZE(o)))) { + PyObject *r = PyList_GET_ITEM(o, wrapped_i); + Py_INCREF(r); + return r; + } + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +#else + return PySequence_GetItem(o, i); +#endif +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Tuple_Fast(PyObject *o, Py_ssize_t i, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + Py_ssize_t wrapped_i = i; + if (wraparound & unlikely(i < 0)) { + wrapped_i += PyTuple_GET_SIZE(o); + } + if ((!boundscheck) || likely(__Pyx_is_valid_index(wrapped_i, PyTuple_GET_SIZE(o)))) { + PyObject *r = PyTuple_GET_ITEM(o, wrapped_i); + Py_INCREF(r); + return r; + } + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +#else + return PySequence_GetItem(o, i); +#endif +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Fast(PyObject *o, Py_ssize_t i, int is_list, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS && CYTHON_USE_TYPE_SLOTS + if (is_list || PyList_CheckExact(o)) { + Py_ssize_t n = ((!wraparound) | likely(i >= 0)) ? i : i + PyList_GET_SIZE(o); + if ((!boundscheck) || (likely(__Pyx_is_valid_index(n, PyList_GET_SIZE(o))))) { + PyObject *r = PyList_GET_ITEM(o, n); + Py_INCREF(r); + return r; + } + } + else if (PyTuple_CheckExact(o)) { + Py_ssize_t n = ((!wraparound) | likely(i >= 0)) ? i : i + PyTuple_GET_SIZE(o); + if ((!boundscheck) || likely(__Pyx_is_valid_index(n, PyTuple_GET_SIZE(o)))) { + PyObject *r = PyTuple_GET_ITEM(o, n); + Py_INCREF(r); + return r; + } + } else { + PyMappingMethods *mm = Py_TYPE(o)->tp_as_mapping; + PySequenceMethods *sm = Py_TYPE(o)->tp_as_sequence; + if (mm && mm->mp_subscript) { + PyObject *r, *key = PyInt_FromSsize_t(i); + if (unlikely(!key)) return NULL; + r = mm->mp_subscript(o, key); + Py_DECREF(key); + return r; + } + if (likely(sm && sm->sq_item)) { + if (wraparound && unlikely(i < 0) && likely(sm->sq_length)) { + Py_ssize_t l = sm->sq_length(o); + if (likely(l >= 0)) { + i += l; + } else { + if (!PyErr_ExceptionMatches(PyExc_OverflowError)) + return NULL; + PyErr_Clear(); + } + } + return sm->sq_item(o, i); + } + } +#else + if (is_list || !PyMapping_Check(o)) { + return PySequence_GetItem(o, i); + } +#endif + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +} + +/* PyObjectCallOneArg */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg) { + PyObject *args[2] = {NULL, arg}; + return __Pyx_PyObject_FastCall(func, args+1, 1 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* ObjectGetItem */ +#if CYTHON_USE_TYPE_SLOTS +static PyObject *__Pyx_PyObject_GetIndex(PyObject *obj, PyObject *index) { + PyObject *runerr = NULL; + Py_ssize_t key_value; + key_value = __Pyx_PyIndex_AsSsize_t(index); + if (likely(key_value != -1 || !(runerr = PyErr_Occurred()))) { + return __Pyx_GetItemInt_Fast(obj, key_value, 0, 1, 1); + } + if (PyErr_GivenExceptionMatches(runerr, PyExc_OverflowError)) { + __Pyx_TypeName index_type_name = __Pyx_PyType_GetName(Py_TYPE(index)); + PyErr_Clear(); + PyErr_Format(PyExc_IndexError, + "cannot fit '" __Pyx_FMT_TYPENAME "' into an index-sized integer", index_type_name); + __Pyx_DECREF_TypeName(index_type_name); + } + return NULL; +} +static PyObject *__Pyx_PyObject_GetItem_Slow(PyObject *obj, PyObject *key) { + __Pyx_TypeName obj_type_name; + if (likely(PyType_Check(obj))) { + PyObject *meth = __Pyx_PyObject_GetAttrStrNoError(obj, __pyx_n_s_class_getitem); + if (!meth) { + PyErr_Clear(); + } else { + PyObject *result = __Pyx_PyObject_CallOneArg(meth, key); + Py_DECREF(meth); + return result; + } + } + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "'" __Pyx_FMT_TYPENAME "' object is not subscriptable", obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return NULL; +} +static PyObject *__Pyx_PyObject_GetItem(PyObject *obj, PyObject *key) { + PyTypeObject *tp = Py_TYPE(obj); + PyMappingMethods *mm = tp->tp_as_mapping; + PySequenceMethods *sm = tp->tp_as_sequence; + if (likely(mm && mm->mp_subscript)) { + return mm->mp_subscript(obj, key); + } + if (likely(sm && sm->sq_item)) { + return __Pyx_PyObject_GetIndex(obj, key); + } + return __Pyx_PyObject_GetItem_Slow(obj, key); +} +#endif + +/* KeywordStringCheck */ +static int __Pyx_CheckKeywordStrings( + PyObject *kw, + const char* function_name, + int kw_allowed) +{ + PyObject* key = 0; + Py_ssize_t pos = 0; +#if CYTHON_COMPILING_IN_PYPY + if (!kw_allowed && PyDict_Next(kw, &pos, &key, 0)) + goto invalid_keyword; + return 1; +#else + if (CYTHON_METH_FASTCALL && likely(PyTuple_Check(kw))) { + Py_ssize_t kwsize; +#if CYTHON_ASSUME_SAFE_MACROS + kwsize = PyTuple_GET_SIZE(kw); +#else + kwsize = PyTuple_Size(kw); + if (kwsize < 0) return 0; +#endif + if (unlikely(kwsize == 0)) + return 1; + if (!kw_allowed) { +#if CYTHON_ASSUME_SAFE_MACROS + key = PyTuple_GET_ITEM(kw, 0); +#else + key = PyTuple_GetItem(kw, pos); + if (!key) return 0; +#endif + goto invalid_keyword; + } +#if PY_VERSION_HEX < 0x03090000 + for (pos = 0; pos < kwsize; pos++) { +#if CYTHON_ASSUME_SAFE_MACROS + key = PyTuple_GET_ITEM(kw, pos); +#else + key = PyTuple_GetItem(kw, pos); + if (!key) return 0; +#endif + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } +#endif + return 1; + } + while (PyDict_Next(kw, &pos, &key, 0)) { + #if PY_MAJOR_VERSION < 3 + if (unlikely(!PyString_Check(key))) + #endif + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } + if (!kw_allowed && unlikely(key)) + goto invalid_keyword; + return 1; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + return 0; +#endif +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif + return 0; +} + +/* GetAttr3 */ +#if __PYX_LIMITED_VERSION_HEX < 0x030d00A1 +static PyObject *__Pyx_GetAttr3Default(PyObject *d) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + if (unlikely(!__Pyx_PyErr_ExceptionMatches(PyExc_AttributeError))) + return NULL; + __Pyx_PyErr_Clear(); + Py_INCREF(d); + return d; +} +#endif +static CYTHON_INLINE PyObject *__Pyx_GetAttr3(PyObject *o, PyObject *n, PyObject *d) { + PyObject *r; +#if __PYX_LIMITED_VERSION_HEX >= 0x030d00A1 + int res = PyObject_GetOptionalAttr(o, n, &r); + return (res != 0) ? r : __Pyx_NewRef(d); +#else + #if CYTHON_USE_TYPE_SLOTS + if (likely(PyString_Check(n))) { + r = __Pyx_PyObject_GetAttrStrNoError(o, n); + if (unlikely(!r) && likely(!PyErr_Occurred())) { + r = __Pyx_NewRef(d); + } + return r; + } + #endif + r = PyObject_GetAttr(o, n); + return (likely(r)) ? r : __Pyx_GetAttr3Default(d); +#endif +} + +/* PyDictVersioning */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + return likely(dict) ? __PYX_GET_DICT_VERSION(dict) : 0; +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj) { + PyObject **dictptr = NULL; + Py_ssize_t offset = Py_TYPE(obj)->tp_dictoffset; + if (offset) { +#if CYTHON_COMPILING_IN_CPYTHON + dictptr = (likely(offset > 0)) ? (PyObject **) ((char *)obj + offset) : _PyObject_GetDictPtr(obj); +#else + dictptr = _PyObject_GetDictPtr(obj); +#endif + } + return (dictptr && *dictptr) ? __PYX_GET_DICT_VERSION(*dictptr) : 0; +} +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + if (unlikely(!dict) || unlikely(tp_dict_version != __PYX_GET_DICT_VERSION(dict))) + return 0; + return obj_dict_version == __Pyx_get_object_dict_version(obj); +} +#endif + +/* GetModuleGlobalName */ +#if CYTHON_USE_DICT_VERSIONS +static PyObject *__Pyx__GetModuleGlobalName(PyObject *name, PY_UINT64_T *dict_version, PyObject **dict_cached_value) +#else +static CYTHON_INLINE PyObject *__Pyx__GetModuleGlobalName(PyObject *name) +#endif +{ + PyObject *result; +#if !CYTHON_AVOID_BORROWED_REFS +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030500A1 && PY_VERSION_HEX < 0x030d0000 + result = _PyDict_GetItem_KnownHash(__pyx_d, name, ((PyASCIIObject *) name)->hash); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } else if (unlikely(PyErr_Occurred())) { + return NULL; + } +#elif CYTHON_COMPILING_IN_LIMITED_API + if (unlikely(!__pyx_m)) { + return NULL; + } + result = PyObject_GetAttr(__pyx_m, name); + if (likely(result)) { + return result; + } +#else + result = PyDict_GetItem(__pyx_d, name); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } +#endif +#else + result = PyObject_GetItem(__pyx_d, name); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } + PyErr_Clear(); +#endif + return __Pyx_GetBuiltinName(name); +} + +/* RaiseUnexpectedTypeError */ +static int +__Pyx_RaiseUnexpectedTypeError(const char *expected, PyObject *obj) +{ + __Pyx_TypeName obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, "Expected %s, got " __Pyx_FMT_TYPENAME, + expected, obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return 0; +} + +/* RaiseException */ +#if PY_MAJOR_VERSION < 3 +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + __Pyx_PyThreadState_declare + CYTHON_UNUSED_VAR(cause); + Py_XINCREF(type); + if (!value || value == Py_None) + value = NULL; + else + Py_INCREF(value); + if (!tb || tb == Py_None) + tb = NULL; + else { + Py_INCREF(tb); + if (!PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto raise_error; + } + } + if (PyType_Check(type)) { +#if CYTHON_COMPILING_IN_PYPY + if (!value) { + Py_INCREF(Py_None); + value = Py_None; + } +#endif + PyErr_NormalizeException(&type, &value, &tb); + } else { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto raise_error; + } + value = type; + type = (PyObject*) Py_TYPE(type); + Py_INCREF(type); + if (!PyType_IsSubtype((PyTypeObject *)type, (PyTypeObject *)PyExc_BaseException)) { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto raise_error; + } + } + __Pyx_PyThreadState_assign + __Pyx_ErrRestore(type, value, tb); + return; +raise_error: + Py_XDECREF(value); + Py_XDECREF(type); + Py_XDECREF(tb); + return; +} +#else +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + PyObject* owned_instance = NULL; + if (tb == Py_None) { + tb = 0; + } else if (tb && !PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto bad; + } + if (value == Py_None) + value = 0; + if (PyExceptionInstance_Check(type)) { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto bad; + } + value = type; + type = (PyObject*) Py_TYPE(value); + } else if (PyExceptionClass_Check(type)) { + PyObject *instance_class = NULL; + if (value && PyExceptionInstance_Check(value)) { + instance_class = (PyObject*) Py_TYPE(value); + if (instance_class != type) { + int is_subclass = PyObject_IsSubclass(instance_class, type); + if (!is_subclass) { + instance_class = NULL; + } else if (unlikely(is_subclass == -1)) { + goto bad; + } else { + type = instance_class; + } + } + } + if (!instance_class) { + PyObject *args; + if (!value) + args = PyTuple_New(0); + else if (PyTuple_Check(value)) { + Py_INCREF(value); + args = value; + } else + args = PyTuple_Pack(1, value); + if (!args) + goto bad; + owned_instance = PyObject_Call(type, args, NULL); + Py_DECREF(args); + if (!owned_instance) + goto bad; + value = owned_instance; + if (!PyExceptionInstance_Check(value)) { + PyErr_Format(PyExc_TypeError, + "calling %R should have returned an instance of " + "BaseException, not %R", + type, Py_TYPE(value)); + goto bad; + } + } + } else { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto bad; + } + if (cause) { + PyObject *fixed_cause; + if (cause == Py_None) { + fixed_cause = NULL; + } else if (PyExceptionClass_Check(cause)) { + fixed_cause = PyObject_CallObject(cause, NULL); + if (fixed_cause == NULL) + goto bad; + } else if (PyExceptionInstance_Check(cause)) { + fixed_cause = cause; + Py_INCREF(fixed_cause); + } else { + PyErr_SetString(PyExc_TypeError, + "exception causes must derive from " + "BaseException"); + goto bad; + } + PyException_SetCause(value, fixed_cause); + } + PyErr_SetObject(type, value); + if (tb) { + #if PY_VERSION_HEX >= 0x030C00A6 + PyException_SetTraceback(value, tb); + #elif CYTHON_FAST_THREAD_STATE + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject* tmp_tb = tstate->curexc_traceback; + if (tb != tmp_tb) { + Py_INCREF(tb); + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_tb); + } +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + PyErr_Fetch(&tmp_type, &tmp_value, &tmp_tb); + Py_INCREF(tb); + PyErr_Restore(tmp_type, tmp_value, tb); + Py_XDECREF(tmp_tb); +#endif + } +bad: + Py_XDECREF(owned_instance); + return; +} +#endif + +/* Import */ +static PyObject *__Pyx_Import(PyObject *name, PyObject *from_list, int level) { + PyObject *module = 0; + PyObject *empty_dict = 0; + PyObject *empty_list = 0; + #if PY_MAJOR_VERSION < 3 + PyObject *py_import; + py_import = __Pyx_PyObject_GetAttrStr(__pyx_b, __pyx_n_s_import); + if (unlikely(!py_import)) + goto bad; + if (!from_list) { + empty_list = PyList_New(0); + if (unlikely(!empty_list)) + goto bad; + from_list = empty_list; + } + #endif + empty_dict = PyDict_New(); + if (unlikely(!empty_dict)) + goto bad; + { + #if PY_MAJOR_VERSION >= 3 + if (level == -1) { + if (strchr(__Pyx_MODULE_NAME, '.') != NULL) { + module = PyImport_ImportModuleLevelObject( + name, __pyx_d, empty_dict, from_list, 1); + if (unlikely(!module)) { + if (unlikely(!PyErr_ExceptionMatches(PyExc_ImportError))) + goto bad; + PyErr_Clear(); + } + } + level = 0; + } + #endif + if (!module) { + #if PY_MAJOR_VERSION < 3 + PyObject *py_level = PyInt_FromLong(level); + if (unlikely(!py_level)) + goto bad; + module = PyObject_CallFunctionObjArgs(py_import, + name, __pyx_d, empty_dict, from_list, py_level, (PyObject *)NULL); + Py_DECREF(py_level); + #else + module = PyImport_ImportModuleLevelObject( + name, __pyx_d, empty_dict, from_list, level); + #endif + } + } +bad: + Py_XDECREF(empty_dict); + Py_XDECREF(empty_list); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_import); + #endif + return module; +} + +/* ImportFrom */ +static PyObject* __Pyx_ImportFrom(PyObject* module, PyObject* name) { + PyObject* value = __Pyx_PyObject_GetAttrStr(module, name); + if (unlikely(!value) && PyErr_ExceptionMatches(PyExc_AttributeError)) { + const char* module_name_str = 0; + PyObject* module_name = 0; + PyObject* module_dot = 0; + PyObject* full_name = 0; + PyErr_Clear(); + module_name_str = PyModule_GetName(module); + if (unlikely(!module_name_str)) { goto modbad; } + module_name = PyUnicode_FromString(module_name_str); + if (unlikely(!module_name)) { goto modbad; } + module_dot = PyUnicode_Concat(module_name, __pyx_kp_u__3); + if (unlikely(!module_dot)) { goto modbad; } + full_name = PyUnicode_Concat(module_dot, name); + if (unlikely(!full_name)) { goto modbad; } + #if PY_VERSION_HEX < 0x030700A1 || (CYTHON_COMPILING_IN_PYPY && PYPY_VERSION_NUM < 0x07030400) + { + PyObject *modules = PyImport_GetModuleDict(); + if (unlikely(!modules)) + goto modbad; + value = PyObject_GetItem(modules, full_name); + } + #else + value = PyImport_GetModule(full_name); + #endif + modbad: + Py_XDECREF(full_name); + Py_XDECREF(module_dot); + Py_XDECREF(module_name); + } + if (unlikely(!value)) { + PyErr_Format(PyExc_ImportError, + #if PY_MAJOR_VERSION < 3 + "cannot import name %.230s", PyString_AS_STRING(name)); + #else + "cannot import name %S", name); + #endif + } + return value; +} + +/* GetAttr */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr(PyObject *o, PyObject *n) { +#if CYTHON_USE_TYPE_SLOTS +#if PY_MAJOR_VERSION >= 3 + if (likely(PyUnicode_Check(n))) +#else + if (likely(PyString_Check(n))) +#endif + return __Pyx_PyObject_GetAttrStr(o, n); +#endif + return PyObject_GetAttr(o, n); +} + +/* HasAttr */ +#if __PYX_LIMITED_VERSION_HEX < 0x030d00A1 +static CYTHON_INLINE int __Pyx_HasAttr(PyObject *o, PyObject *n) { + PyObject *r; + if (unlikely(!__Pyx_PyBaseString_Check(n))) { + PyErr_SetString(PyExc_TypeError, + "hasattr(): attribute name must be string"); + return -1; + } + r = __Pyx_GetAttr(o, n); + if (!r) { + PyErr_Clear(); + return 0; + } else { + Py_DECREF(r); + return 1; + } +} +#endif + +/* ArgTypeTest */ +static int __Pyx__ArgTypeTest(PyObject *obj, PyTypeObject *type, const char *name, int exact) +{ + __Pyx_TypeName type_name; + __Pyx_TypeName obj_type_name; + if (unlikely(!type)) { + PyErr_SetString(PyExc_SystemError, "Missing type object"); + return 0; + } + else if (exact) { + #if PY_MAJOR_VERSION == 2 + if ((type == &PyBaseString_Type) && likely(__Pyx_PyBaseString_CheckExact(obj))) return 1; + #endif + } + else { + if (likely(__Pyx_TypeCheck(obj, type))) return 1; + } + type_name = __Pyx_PyType_GetName(type); + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "Argument '%.200s' has incorrect type (expected " __Pyx_FMT_TYPENAME + ", got " __Pyx_FMT_TYPENAME ")", name, type_name, obj_type_name); + __Pyx_DECREF_TypeName(type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return 0; +} + +/* CIntToDigits */ +static const char DIGIT_PAIRS_10[2*10*10+1] = { + "00010203040506070809" + "10111213141516171819" + "20212223242526272829" + "30313233343536373839" + "40414243444546474849" + "50515253545556575859" + "60616263646566676869" + "70717273747576777879" + "80818283848586878889" + "90919293949596979899" +}; +static const char DIGIT_PAIRS_8[2*8*8+1] = { + "0001020304050607" + "1011121314151617" + "2021222324252627" + "3031323334353637" + "4041424344454647" + "5051525354555657" + "6061626364656667" + "7071727374757677" +}; +static const char DIGITS_HEX[2*16+1] = { + "0123456789abcdef" + "0123456789ABCDEF" +}; + +/* BuildPyUnicode */ +static PyObject* __Pyx_PyUnicode_BuildFromAscii(Py_ssize_t ulength, char* chars, int clength, + int prepend_sign, char padding_char) { + PyObject *uval; + Py_ssize_t uoffset = ulength - clength; +#if CYTHON_USE_UNICODE_INTERNALS + Py_ssize_t i; +#if CYTHON_PEP393_ENABLED + void *udata; + uval = PyUnicode_New(ulength, 127); + if (unlikely(!uval)) return NULL; + udata = PyUnicode_DATA(uval); +#else + Py_UNICODE *udata; + uval = PyUnicode_FromUnicode(NULL, ulength); + if (unlikely(!uval)) return NULL; + udata = PyUnicode_AS_UNICODE(uval); +#endif + if (uoffset > 0) { + i = 0; + if (prepend_sign) { + __Pyx_PyUnicode_WRITE(PyUnicode_1BYTE_KIND, udata, 0, '-'); + i++; + } + for (; i < uoffset; i++) { + __Pyx_PyUnicode_WRITE(PyUnicode_1BYTE_KIND, udata, i, padding_char); + } + } + for (i=0; i < clength; i++) { + __Pyx_PyUnicode_WRITE(PyUnicode_1BYTE_KIND, udata, uoffset+i, chars[i]); + } +#else + { + PyObject *sign = NULL, *padding = NULL; + uval = NULL; + if (uoffset > 0) { + prepend_sign = !!prepend_sign; + if (uoffset > prepend_sign) { + padding = PyUnicode_FromOrdinal(padding_char); + if (likely(padding) && uoffset > prepend_sign + 1) { + PyObject *tmp; + PyObject *repeat = PyInt_FromSsize_t(uoffset - prepend_sign); + if (unlikely(!repeat)) goto done_or_error; + tmp = PyNumber_Multiply(padding, repeat); + Py_DECREF(repeat); + Py_DECREF(padding); + padding = tmp; + } + if (unlikely(!padding)) goto done_or_error; + } + if (prepend_sign) { + sign = PyUnicode_FromOrdinal('-'); + if (unlikely(!sign)) goto done_or_error; + } + } + uval = PyUnicode_DecodeASCII(chars, clength, NULL); + if (likely(uval) && padding) { + PyObject *tmp = PyNumber_Add(padding, uval); + Py_DECREF(uval); + uval = tmp; + } + if (likely(uval) && sign) { + PyObject *tmp = PyNumber_Add(sign, uval); + Py_DECREF(uval); + uval = tmp; + } +done_or_error: + Py_XDECREF(padding); + Py_XDECREF(sign); + } +#endif + return uval; +} + +/* CIntToPyUnicode */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_int(int value, Py_ssize_t width, char padding_char, char format_char) { + char digits[sizeof(int)*3+2]; + char *dpos, *end = digits + sizeof(int)*3+2; + const char *hex_digits = DIGITS_HEX; + Py_ssize_t length, ulength; + int prepend_sign, last_one_off; + int remaining; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (format_char == 'X') { + hex_digits += 16; + format_char = 'x'; + } + remaining = value; + last_one_off = 0; + dpos = end; + do { + int digit_pos; + switch (format_char) { + case 'o': + digit_pos = abs((int)(remaining % (8*8))); + remaining = (int) (remaining / (8*8)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_8 + digit_pos * 2, 2); + last_one_off = (digit_pos < 8); + break; + case 'd': + digit_pos = abs((int)(remaining % (10*10))); + remaining = (int) (remaining / (10*10)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_10 + digit_pos * 2, 2); + last_one_off = (digit_pos < 10); + break; + case 'x': + *(--dpos) = hex_digits[abs((int)(remaining % 16))]; + remaining = (int) (remaining / 16); + break; + default: + assert(0); + break; + } + } while (unlikely(remaining != 0)); + assert(!last_one_off || *dpos == '0'); + dpos += last_one_off; + length = end - dpos; + ulength = length; + prepend_sign = 0; + if (!is_unsigned && value <= neg_one) { + if (padding_char == ' ' || width <= length + 1) { + *(--dpos) = '-'; + ++length; + } else { + prepend_sign = 1; + } + ++ulength; + } + if (width > ulength) { + ulength = width; + } + if (ulength == 1) { + return PyUnicode_FromOrdinal(*dpos); + } + return __Pyx_PyUnicode_BuildFromAscii(ulength, dpos, (int) length, prepend_sign, padding_char); +} + +/* CIntToPyUnicode */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_Py_ssize_t(Py_ssize_t value, Py_ssize_t width, char padding_char, char format_char) { + char digits[sizeof(Py_ssize_t)*3+2]; + char *dpos, *end = digits + sizeof(Py_ssize_t)*3+2; + const char *hex_digits = DIGITS_HEX; + Py_ssize_t length, ulength; + int prepend_sign, last_one_off; + Py_ssize_t remaining; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const Py_ssize_t neg_one = (Py_ssize_t) -1, const_zero = (Py_ssize_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (format_char == 'X') { + hex_digits += 16; + format_char = 'x'; + } + remaining = value; + last_one_off = 0; + dpos = end; + do { + int digit_pos; + switch (format_char) { + case 'o': + digit_pos = abs((int)(remaining % (8*8))); + remaining = (Py_ssize_t) (remaining / (8*8)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_8 + digit_pos * 2, 2); + last_one_off = (digit_pos < 8); + break; + case 'd': + digit_pos = abs((int)(remaining % (10*10))); + remaining = (Py_ssize_t) (remaining / (10*10)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_10 + digit_pos * 2, 2); + last_one_off = (digit_pos < 10); + break; + case 'x': + *(--dpos) = hex_digits[abs((int)(remaining % 16))]; + remaining = (Py_ssize_t) (remaining / 16); + break; + default: + assert(0); + break; + } + } while (unlikely(remaining != 0)); + assert(!last_one_off || *dpos == '0'); + dpos += last_one_off; + length = end - dpos; + ulength = length; + prepend_sign = 0; + if (!is_unsigned && value <= neg_one) { + if (padding_char == ' ' || width <= length + 1) { + *(--dpos) = '-'; + ++length; + } else { + prepend_sign = 1; + } + ++ulength; + } + if (width > ulength) { + ulength = width; + } + if (ulength == 1) { + return PyUnicode_FromOrdinal(*dpos); + } + return __Pyx_PyUnicode_BuildFromAscii(ulength, dpos, (int) length, prepend_sign, padding_char); +} + +/* JoinPyUnicode */ +static PyObject* __Pyx_PyUnicode_Join(PyObject* value_tuple, Py_ssize_t value_count, Py_ssize_t result_ulength, + Py_UCS4 max_char) { +#if CYTHON_USE_UNICODE_INTERNALS && CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + PyObject *result_uval; + int result_ukind, kind_shift; + Py_ssize_t i, char_pos; + void *result_udata; + CYTHON_MAYBE_UNUSED_VAR(max_char); +#if CYTHON_PEP393_ENABLED + result_uval = PyUnicode_New(result_ulength, max_char); + if (unlikely(!result_uval)) return NULL; + result_ukind = (max_char <= 255) ? PyUnicode_1BYTE_KIND : (max_char <= 65535) ? PyUnicode_2BYTE_KIND : PyUnicode_4BYTE_KIND; + kind_shift = (result_ukind == PyUnicode_4BYTE_KIND) ? 2 : result_ukind - 1; + result_udata = PyUnicode_DATA(result_uval); +#else + result_uval = PyUnicode_FromUnicode(NULL, result_ulength); + if (unlikely(!result_uval)) return NULL; + result_ukind = sizeof(Py_UNICODE); + kind_shift = (result_ukind == 4) ? 2 : result_ukind - 1; + result_udata = PyUnicode_AS_UNICODE(result_uval); +#endif + assert(kind_shift == 2 || kind_shift == 1 || kind_shift == 0); + char_pos = 0; + for (i=0; i < value_count; i++) { + int ukind; + Py_ssize_t ulength; + void *udata; + PyObject *uval = PyTuple_GET_ITEM(value_tuple, i); + if (unlikely(__Pyx_PyUnicode_READY(uval))) + goto bad; + ulength = __Pyx_PyUnicode_GET_LENGTH(uval); + if (unlikely(!ulength)) + continue; + if (unlikely((PY_SSIZE_T_MAX >> kind_shift) - ulength < char_pos)) + goto overflow; + ukind = __Pyx_PyUnicode_KIND(uval); + udata = __Pyx_PyUnicode_DATA(uval); + if (!CYTHON_PEP393_ENABLED || ukind == result_ukind) { + memcpy((char *)result_udata + (char_pos << kind_shift), udata, (size_t) (ulength << kind_shift)); + } else { + #if PY_VERSION_HEX >= 0x030d0000 + if (unlikely(PyUnicode_CopyCharacters(result_uval, char_pos, uval, 0, ulength) < 0)) goto bad; + #elif CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030300F0 || defined(_PyUnicode_FastCopyCharacters) + _PyUnicode_FastCopyCharacters(result_uval, char_pos, uval, 0, ulength); + #else + Py_ssize_t j; + for (j=0; j < ulength; j++) { + Py_UCS4 uchar = __Pyx_PyUnicode_READ(ukind, udata, j); + __Pyx_PyUnicode_WRITE(result_ukind, result_udata, char_pos+j, uchar); + } + #endif + } + char_pos += ulength; + } + return result_uval; +overflow: + PyErr_SetString(PyExc_OverflowError, "join() result is too long for a Python string"); +bad: + Py_DECREF(result_uval); + return NULL; +#else + CYTHON_UNUSED_VAR(max_char); + CYTHON_UNUSED_VAR(result_ulength); + CYTHON_UNUSED_VAR(value_count); + return PyUnicode_Join(__pyx_empty_unicode, value_tuple); +#endif +} + +/* DivInt[Py_ssize_t] */ +static CYTHON_INLINE Py_ssize_t __Pyx_div_Py_ssize_t(Py_ssize_t a, Py_ssize_t b) { + Py_ssize_t q = a / b; + Py_ssize_t r = a - q*b; + q -= ((r != 0) & ((r ^ b) < 0)); + return q; +} + +/* RaiseTooManyValuesToUnpack */ +static CYTHON_INLINE void __Pyx_RaiseTooManyValuesError(Py_ssize_t expected) { + PyErr_Format(PyExc_ValueError, + "too many values to unpack (expected %" CYTHON_FORMAT_SSIZE_T "d)", expected); +} + +/* RaiseNeedMoreValuesToUnpack */ +static CYTHON_INLINE void __Pyx_RaiseNeedMoreValuesError(Py_ssize_t index) { + PyErr_Format(PyExc_ValueError, + "need more than %" CYTHON_FORMAT_SSIZE_T "d value%.1s to unpack", + index, (index == 1) ? "" : "s"); +} + +/* RaiseNoneIterError */ +static CYTHON_INLINE void __Pyx_RaiseNoneNotIterableError(void) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not iterable"); +} + +/* ExtTypeTest */ +static CYTHON_INLINE int __Pyx_TypeTest(PyObject *obj, PyTypeObject *type) { + __Pyx_TypeName obj_type_name; + __Pyx_TypeName type_name; + if (unlikely(!type)) { + PyErr_SetString(PyExc_SystemError, "Missing type object"); + return 0; + } + if (likely(__Pyx_TypeCheck(obj, type))) + return 1; + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + type_name = __Pyx_PyType_GetName(type); + PyErr_Format(PyExc_TypeError, + "Cannot convert " __Pyx_FMT_TYPENAME " to " __Pyx_FMT_TYPENAME, + obj_type_name, type_name); + __Pyx_DECREF_TypeName(obj_type_name); + __Pyx_DECREF_TypeName(type_name); + return 0; +} + +/* GetTopmostException */ +#if CYTHON_USE_EXC_INFO_STACK && CYTHON_FAST_THREAD_STATE +static _PyErr_StackItem * +__Pyx_PyErr_GetTopmostException(PyThreadState *tstate) +{ + _PyErr_StackItem *exc_info = tstate->exc_info; + while ((exc_info->exc_value == NULL || exc_info->exc_value == Py_None) && + exc_info->previous_item != NULL) + { + exc_info = exc_info->previous_item; + } + return exc_info; +} +#endif + +/* SaveResetException */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx__ExceptionSave(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { + #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 + _PyErr_StackItem *exc_info = __Pyx_PyErr_GetTopmostException(tstate); + PyObject *exc_value = exc_info->exc_value; + if (exc_value == NULL || exc_value == Py_None) { + *value = NULL; + *type = NULL; + *tb = NULL; + } else { + *value = exc_value; + Py_INCREF(*value); + *type = (PyObject*) Py_TYPE(exc_value); + Py_INCREF(*type); + *tb = PyException_GetTraceback(exc_value); + } + #elif CYTHON_USE_EXC_INFO_STACK + _PyErr_StackItem *exc_info = __Pyx_PyErr_GetTopmostException(tstate); + *type = exc_info->exc_type; + *value = exc_info->exc_value; + *tb = exc_info->exc_traceback; + Py_XINCREF(*type); + Py_XINCREF(*value); + Py_XINCREF(*tb); + #else + *type = tstate->exc_type; + *value = tstate->exc_value; + *tb = tstate->exc_traceback; + Py_XINCREF(*type); + Py_XINCREF(*value); + Py_XINCREF(*tb); + #endif +} +static CYTHON_INLINE void __Pyx__ExceptionReset(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb) { + #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 + _PyErr_StackItem *exc_info = tstate->exc_info; + PyObject *tmp_value = exc_info->exc_value; + exc_info->exc_value = value; + Py_XDECREF(tmp_value); + Py_XDECREF(type); + Py_XDECREF(tb); + #else + PyObject *tmp_type, *tmp_value, *tmp_tb; + #if CYTHON_USE_EXC_INFO_STACK + _PyErr_StackItem *exc_info = tstate->exc_info; + tmp_type = exc_info->exc_type; + tmp_value = exc_info->exc_value; + tmp_tb = exc_info->exc_traceback; + exc_info->exc_type = type; + exc_info->exc_value = value; + exc_info->exc_traceback = tb; + #else + tmp_type = tstate->exc_type; + tmp_value = tstate->exc_value; + tmp_tb = tstate->exc_traceback; + tstate->exc_type = type; + tstate->exc_value = value; + tstate->exc_traceback = tb; + #endif + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); + #endif +} +#endif + +/* GetException */ +#if CYTHON_FAST_THREAD_STATE +static int __Pyx__GetException(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) +#else +static int __Pyx_GetException(PyObject **type, PyObject **value, PyObject **tb) +#endif +{ + PyObject *local_type = NULL, *local_value, *local_tb = NULL; +#if CYTHON_FAST_THREAD_STATE + PyObject *tmp_type, *tmp_value, *tmp_tb; + #if PY_VERSION_HEX >= 0x030C00A6 + local_value = tstate->current_exception; + tstate->current_exception = 0; + if (likely(local_value)) { + local_type = (PyObject*) Py_TYPE(local_value); + Py_INCREF(local_type); + local_tb = PyException_GetTraceback(local_value); + } + #else + local_type = tstate->curexc_type; + local_value = tstate->curexc_value; + local_tb = tstate->curexc_traceback; + tstate->curexc_type = 0; + tstate->curexc_value = 0; + tstate->curexc_traceback = 0; + #endif +#else + PyErr_Fetch(&local_type, &local_value, &local_tb); +#endif + PyErr_NormalizeException(&local_type, &local_value, &local_tb); +#if CYTHON_FAST_THREAD_STATE && PY_VERSION_HEX >= 0x030C00A6 + if (unlikely(tstate->current_exception)) +#elif CYTHON_FAST_THREAD_STATE + if (unlikely(tstate->curexc_type)) +#else + if (unlikely(PyErr_Occurred())) +#endif + goto bad; + #if PY_MAJOR_VERSION >= 3 + if (local_tb) { + if (unlikely(PyException_SetTraceback(local_value, local_tb) < 0)) + goto bad; + } + #endif + Py_XINCREF(local_tb); + Py_XINCREF(local_type); + Py_XINCREF(local_value); + *type = local_type; + *value = local_value; + *tb = local_tb; +#if CYTHON_FAST_THREAD_STATE + #if CYTHON_USE_EXC_INFO_STACK + { + _PyErr_StackItem *exc_info = tstate->exc_info; + #if PY_VERSION_HEX >= 0x030B00a4 + tmp_value = exc_info->exc_value; + exc_info->exc_value = local_value; + tmp_type = NULL; + tmp_tb = NULL; + Py_XDECREF(local_type); + Py_XDECREF(local_tb); + #else + tmp_type = exc_info->exc_type; + tmp_value = exc_info->exc_value; + tmp_tb = exc_info->exc_traceback; + exc_info->exc_type = local_type; + exc_info->exc_value = local_value; + exc_info->exc_traceback = local_tb; + #endif + } + #else + tmp_type = tstate->exc_type; + tmp_value = tstate->exc_value; + tmp_tb = tstate->exc_traceback; + tstate->exc_type = local_type; + tstate->exc_value = local_value; + tstate->exc_traceback = local_tb; + #endif + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); +#else + PyErr_SetExcInfo(local_type, local_value, local_tb); +#endif + return 0; +bad: + *type = 0; + *value = 0; + *tb = 0; + Py_XDECREF(local_type); + Py_XDECREF(local_value); + Py_XDECREF(local_tb); + return -1; +} + +/* SwapException */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx__ExceptionSwap(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { + PyObject *tmp_type, *tmp_value, *tmp_tb; + #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 + _PyErr_StackItem *exc_info = tstate->exc_info; + tmp_value = exc_info->exc_value; + exc_info->exc_value = *value; + if (tmp_value == NULL || tmp_value == Py_None) { + Py_XDECREF(tmp_value); + tmp_value = NULL; + tmp_type = NULL; + tmp_tb = NULL; + } else { + tmp_type = (PyObject*) Py_TYPE(tmp_value); + Py_INCREF(tmp_type); + #if CYTHON_COMPILING_IN_CPYTHON + tmp_tb = ((PyBaseExceptionObject*) tmp_value)->traceback; + Py_XINCREF(tmp_tb); + #else + tmp_tb = PyException_GetTraceback(tmp_value); + #endif + } + #elif CYTHON_USE_EXC_INFO_STACK + _PyErr_StackItem *exc_info = tstate->exc_info; + tmp_type = exc_info->exc_type; + tmp_value = exc_info->exc_value; + tmp_tb = exc_info->exc_traceback; + exc_info->exc_type = *type; + exc_info->exc_value = *value; + exc_info->exc_traceback = *tb; + #else + tmp_type = tstate->exc_type; + tmp_value = tstate->exc_value; + tmp_tb = tstate->exc_traceback; + tstate->exc_type = *type; + tstate->exc_value = *value; + tstate->exc_traceback = *tb; + #endif + *type = tmp_type; + *value = tmp_value; + *tb = tmp_tb; +} +#else +static CYTHON_INLINE void __Pyx_ExceptionSwap(PyObject **type, PyObject **value, PyObject **tb) { + PyObject *tmp_type, *tmp_value, *tmp_tb; + PyErr_GetExcInfo(&tmp_type, &tmp_value, &tmp_tb); + PyErr_SetExcInfo(*type, *value, *tb); + *type = tmp_type; + *value = tmp_value; + *tb = tmp_tb; +} +#endif + +/* ImportDottedModule */ +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx__ImportDottedModule_Error(PyObject *name, PyObject *parts_tuple, Py_ssize_t count) { + PyObject *partial_name = NULL, *slice = NULL, *sep = NULL; + if (unlikely(PyErr_Occurred())) { + PyErr_Clear(); + } + if (likely(PyTuple_GET_SIZE(parts_tuple) == count)) { + partial_name = name; + } else { + slice = PySequence_GetSlice(parts_tuple, 0, count); + if (unlikely(!slice)) + goto bad; + sep = PyUnicode_FromStringAndSize(".", 1); + if (unlikely(!sep)) + goto bad; + partial_name = PyUnicode_Join(sep, slice); + } + PyErr_Format( +#if PY_MAJOR_VERSION < 3 + PyExc_ImportError, + "No module named '%s'", PyString_AS_STRING(partial_name)); +#else +#if PY_VERSION_HEX >= 0x030600B1 + PyExc_ModuleNotFoundError, +#else + PyExc_ImportError, +#endif + "No module named '%U'", partial_name); +#endif +bad: + Py_XDECREF(sep); + Py_XDECREF(slice); + Py_XDECREF(partial_name); + return NULL; +} +#endif +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx__ImportDottedModule_Lookup(PyObject *name) { + PyObject *imported_module; +#if PY_VERSION_HEX < 0x030700A1 || (CYTHON_COMPILING_IN_PYPY && PYPY_VERSION_NUM < 0x07030400) + PyObject *modules = PyImport_GetModuleDict(); + if (unlikely(!modules)) + return NULL; + imported_module = __Pyx_PyDict_GetItemStr(modules, name); + Py_XINCREF(imported_module); +#else + imported_module = PyImport_GetModule(name); +#endif + return imported_module; +} +#endif +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_ImportDottedModule_WalkParts(PyObject *module, PyObject *name, PyObject *parts_tuple) { + Py_ssize_t i, nparts; + nparts = PyTuple_GET_SIZE(parts_tuple); + for (i=1; i < nparts && module; i++) { + PyObject *part, *submodule; +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + part = PyTuple_GET_ITEM(parts_tuple, i); +#else + part = PySequence_ITEM(parts_tuple, i); +#endif + submodule = __Pyx_PyObject_GetAttrStrNoError(module, part); +#if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(part); +#endif + Py_DECREF(module); + module = submodule; + } + if (unlikely(!module)) { + return __Pyx__ImportDottedModule_Error(name, parts_tuple, i); + } + return module; +} +#endif +static PyObject *__Pyx__ImportDottedModule(PyObject *name, PyObject *parts_tuple) { +#if PY_MAJOR_VERSION < 3 + PyObject *module, *from_list, *star = __pyx_n_s__5; + CYTHON_UNUSED_VAR(parts_tuple); + from_list = PyList_New(1); + if (unlikely(!from_list)) + return NULL; + Py_INCREF(star); + PyList_SET_ITEM(from_list, 0, star); + module = __Pyx_Import(name, from_list, 0); + Py_DECREF(from_list); + return module; +#else + PyObject *imported_module; + PyObject *module = __Pyx_Import(name, NULL, 0); + if (!parts_tuple || unlikely(!module)) + return module; + imported_module = __Pyx__ImportDottedModule_Lookup(name); + if (likely(imported_module)) { + Py_DECREF(module); + return imported_module; + } + PyErr_Clear(); + return __Pyx_ImportDottedModule_WalkParts(module, name, parts_tuple); +#endif +} +static PyObject *__Pyx_ImportDottedModule(PyObject *name, PyObject *parts_tuple) { +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030400B1 + PyObject *module = __Pyx__ImportDottedModule_Lookup(name); + if (likely(module)) { + PyObject *spec = __Pyx_PyObject_GetAttrStrNoError(module, __pyx_n_s_spec); + if (likely(spec)) { + PyObject *unsafe = __Pyx_PyObject_GetAttrStrNoError(spec, __pyx_n_s_initializing); + if (likely(!unsafe || !__Pyx_PyObject_IsTrue(unsafe))) { + Py_DECREF(spec); + spec = NULL; + } + Py_XDECREF(unsafe); + } + if (likely(!spec)) { + PyErr_Clear(); + return module; + } + Py_DECREF(spec); + Py_DECREF(module); + } else if (PyErr_Occurred()) { + PyErr_Clear(); + } +#endif + return __Pyx__ImportDottedModule(name, parts_tuple); +} + +/* FastTypeChecks */ +#if CYTHON_COMPILING_IN_CPYTHON +static int __Pyx_InBases(PyTypeObject *a, PyTypeObject *b) { + while (a) { + a = __Pyx_PyType_GetSlot(a, tp_base, PyTypeObject*); + if (a == b) + return 1; + } + return b == &PyBaseObject_Type; +} +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (a == b) return 1; + mro = a->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + if (PyTuple_GET_ITEM(mro, i) == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(a, b); +} +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (cls == a || cls == b) return 1; + mro = cls->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + PyObject *base = PyTuple_GET_ITEM(mro, i); + if (base == (PyObject *)a || base == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(cls, a) || __Pyx_InBases(cls, b); +} +#if PY_MAJOR_VERSION == 2 +static int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject* exc_type2) { + PyObject *exception, *value, *tb; + int res; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&exception, &value, &tb); + res = exc_type1 ? PyObject_IsSubclass(err, exc_type1) : 0; + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + if (!res) { + res = PyObject_IsSubclass(err, exc_type2); + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + } + __Pyx_ErrRestore(exception, value, tb); + return res; +} +#else +static CYTHON_INLINE int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject *exc_type2) { + if (exc_type1) { + return __Pyx_IsAnySubtype2((PyTypeObject*)err, (PyTypeObject*)exc_type1, (PyTypeObject*)exc_type2); + } else { + return __Pyx_IsSubtype((PyTypeObject*)err, (PyTypeObject*)exc_type2); + } +} +#endif +static int __Pyx_PyErr_GivenExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + assert(PyExceptionClass_Check(exc_type)); + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; itp_as_sequence && type->tp_as_sequence->sq_repeat)) { + return type->tp_as_sequence->sq_repeat(seq, mul); + } else +#endif + { + return __Pyx_PySequence_Multiply_Generic(seq, mul); + } +} + +/* SetItemInt */ +static int __Pyx_SetItemInt_Generic(PyObject *o, PyObject *j, PyObject *v) { + int r; + if (unlikely(!j)) return -1; + r = PyObject_SetItem(o, j, v); + Py_DECREF(j); + return r; +} +static CYTHON_INLINE int __Pyx_SetItemInt_Fast(PyObject *o, Py_ssize_t i, PyObject *v, int is_list, + CYTHON_NCP_UNUSED int wraparound, CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS && CYTHON_USE_TYPE_SLOTS + if (is_list || PyList_CheckExact(o)) { + Py_ssize_t n = (!wraparound) ? i : ((likely(i >= 0)) ? i : i + PyList_GET_SIZE(o)); + if ((!boundscheck) || likely(__Pyx_is_valid_index(n, PyList_GET_SIZE(o)))) { + PyObject* old = PyList_GET_ITEM(o, n); + Py_INCREF(v); + PyList_SET_ITEM(o, n, v); + Py_DECREF(old); + return 1; + } + } else { + PyMappingMethods *mm = Py_TYPE(o)->tp_as_mapping; + PySequenceMethods *sm = Py_TYPE(o)->tp_as_sequence; + if (mm && mm->mp_ass_subscript) { + int r; + PyObject *key = PyInt_FromSsize_t(i); + if (unlikely(!key)) return -1; + r = mm->mp_ass_subscript(o, key, v); + Py_DECREF(key); + return r; + } + if (likely(sm && sm->sq_ass_item)) { + if (wraparound && unlikely(i < 0) && likely(sm->sq_length)) { + Py_ssize_t l = sm->sq_length(o); + if (likely(l >= 0)) { + i += l; + } else { + if (!PyErr_ExceptionMatches(PyExc_OverflowError)) + return -1; + PyErr_Clear(); + } + } + return sm->sq_ass_item(o, i, v); + } + } +#else + if (is_list || !PyMapping_Check(o)) + { + return PySequence_SetItem(o, i, v); + } +#endif + return __Pyx_SetItemInt_Generic(o, PyInt_FromSsize_t(i), v); +} + +/* RaiseUnboundLocalError */ +static CYTHON_INLINE void __Pyx_RaiseUnboundLocalError(const char *varname) { + PyErr_Format(PyExc_UnboundLocalError, "local variable '%s' referenced before assignment", varname); +} + +/* DivInt[long] */ +static CYTHON_INLINE long __Pyx_div_long(long a, long b) { + long q = a / b; + long r = a - q*b; + q -= ((r != 0) & ((r ^ b) < 0)); + return q; +} + +/* PyObjectCall2Args */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call2Args(PyObject* function, PyObject* arg1, PyObject* arg2) { + PyObject *args[3] = {NULL, arg1, arg2}; + return __Pyx_PyObject_FastCall(function, args+1, 2 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* PyObjectGetMethod */ +static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method) { + PyObject *attr; +#if CYTHON_UNPACK_METHODS && CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_PYTYPE_LOOKUP + __Pyx_TypeName type_name; + PyTypeObject *tp = Py_TYPE(obj); + PyObject *descr; + descrgetfunc f = NULL; + PyObject **dictptr, *dict; + int meth_found = 0; + assert (*method == NULL); + if (unlikely(tp->tp_getattro != PyObject_GenericGetAttr)) { + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; + } + if (unlikely(tp->tp_dict == NULL) && unlikely(PyType_Ready(tp) < 0)) { + return 0; + } + descr = _PyType_Lookup(tp, name); + if (likely(descr != NULL)) { + Py_INCREF(descr); +#if defined(Py_TPFLAGS_METHOD_DESCRIPTOR) && Py_TPFLAGS_METHOD_DESCRIPTOR + if (__Pyx_PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_METHOD_DESCRIPTOR)) +#elif PY_MAJOR_VERSION >= 3 + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type))) + #endif +#else + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr))) + #endif +#endif + { + meth_found = 1; + } else { + f = Py_TYPE(descr)->tp_descr_get; + if (f != NULL && PyDescr_IsData(descr)) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + } + } + dictptr = _PyObject_GetDictPtr(obj); + if (dictptr != NULL && (dict = *dictptr) != NULL) { + Py_INCREF(dict); + attr = __Pyx_PyDict_GetItemStr(dict, name); + if (attr != NULL) { + Py_INCREF(attr); + Py_DECREF(dict); + Py_XDECREF(descr); + goto try_unpack; + } + Py_DECREF(dict); + } + if (meth_found) { + *method = descr; + return 1; + } + if (f != NULL) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + if (likely(descr != NULL)) { + *method = descr; + return 0; + } + type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return 0; +#else + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; +#endif +try_unpack: +#if CYTHON_UNPACK_METHODS + if (likely(attr) && PyMethod_Check(attr) && likely(PyMethod_GET_SELF(attr) == obj)) { + PyObject *function = PyMethod_GET_FUNCTION(attr); + Py_INCREF(function); + Py_DECREF(attr); + *method = function; + return 1; + } +#endif + *method = attr; + return 0; +} + +/* PyObjectCallMethod1 */ +#if !(CYTHON_VECTORCALL && __PYX_LIMITED_VERSION_HEX >= 0x030C00A2) +static PyObject* __Pyx__PyObject_CallMethod1(PyObject* method, PyObject* arg) { + PyObject *result = __Pyx_PyObject_CallOneArg(method, arg); + Py_DECREF(method); + return result; +} +#endif +static PyObject* __Pyx_PyObject_CallMethod1(PyObject* obj, PyObject* method_name, PyObject* arg) { +#if CYTHON_VECTORCALL && __PYX_LIMITED_VERSION_HEX >= 0x030C00A2 + PyObject *args[2] = {obj, arg}; + (void) __Pyx_PyObject_GetMethod; + (void) __Pyx_PyObject_CallOneArg; + (void) __Pyx_PyObject_Call2Args; + return PyObject_VectorcallMethod(method_name, args, 2 | PY_VECTORCALL_ARGUMENTS_OFFSET, NULL); +#else + PyObject *method = NULL, *result; + int is_method = __Pyx_PyObject_GetMethod(obj, method_name, &method); + if (likely(is_method)) { + result = __Pyx_PyObject_Call2Args(method, obj, arg); + Py_DECREF(method); + return result; + } + if (unlikely(!method)) return NULL; + return __Pyx__PyObject_CallMethod1(method, arg); +#endif +} + +/* StringJoin */ +static CYTHON_INLINE PyObject* __Pyx_PyBytes_Join(PyObject* sep, PyObject* values) { + (void) __Pyx_PyObject_CallMethod1; +#if CYTHON_COMPILING_IN_CPYTHON && PY_MAJOR_VERSION < 3 + return _PyString_Join(sep, values); +#elif CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030d0000 + return _PyBytes_Join(sep, values); +#else + return __Pyx_PyObject_CallMethod1(sep, __pyx_n_s_join, values); +#endif +} + +/* CIntToPyUnicode */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_size_t(size_t value, Py_ssize_t width, char padding_char, char format_char) { + char digits[sizeof(size_t)*3+2]; + char *dpos, *end = digits + sizeof(size_t)*3+2; + const char *hex_digits = DIGITS_HEX; + Py_ssize_t length, ulength; + int prepend_sign, last_one_off; + size_t remaining; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const size_t neg_one = (size_t) -1, const_zero = (size_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (format_char == 'X') { + hex_digits += 16; + format_char = 'x'; + } + remaining = value; + last_one_off = 0; + dpos = end; + do { + int digit_pos; + switch (format_char) { + case 'o': + digit_pos = abs((int)(remaining % (8*8))); + remaining = (size_t) (remaining / (8*8)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_8 + digit_pos * 2, 2); + last_one_off = (digit_pos < 8); + break; + case 'd': + digit_pos = abs((int)(remaining % (10*10))); + remaining = (size_t) (remaining / (10*10)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_10 + digit_pos * 2, 2); + last_one_off = (digit_pos < 10); + break; + case 'x': + *(--dpos) = hex_digits[abs((int)(remaining % 16))]; + remaining = (size_t) (remaining / 16); + break; + default: + assert(0); + break; + } + } while (unlikely(remaining != 0)); + assert(!last_one_off || *dpos == '0'); + dpos += last_one_off; + length = end - dpos; + ulength = length; + prepend_sign = 0; + if (!is_unsigned && value <= neg_one) { + if (padding_char == ' ' || width <= length + 1) { + *(--dpos) = '-'; + ++length; + } else { + prepend_sign = 1; + } + ++ulength; + } + if (width > ulength) { + ulength = width; + } + if (ulength == 1) { + return PyUnicode_FromOrdinal(*dpos); + } + return __Pyx_PyUnicode_BuildFromAscii(ulength, dpos, (int) length, prepend_sign, padding_char); +} + +/* decode_c_bytes */ +static CYTHON_INLINE PyObject* __Pyx_decode_c_bytes( + const char* cstring, Py_ssize_t length, Py_ssize_t start, Py_ssize_t stop, + const char* encoding, const char* errors, + PyObject* (*decode_func)(const char *s, Py_ssize_t size, const char *errors)) { + if (unlikely((start < 0) | (stop < 0))) { + if (start < 0) { + start += length; + if (start < 0) + start = 0; + } + if (stop < 0) + stop += length; + } + if (stop > length) + stop = length; + if (unlikely(stop <= start)) + return __Pyx_NewRef(__pyx_empty_unicode); + length = stop - start; + cstring += start; + if (decode_func) { + return decode_func(cstring, length, errors); + } else { + return PyUnicode_Decode(cstring, length, encoding, errors); + } +} + +/* PyObjectCallNoArg */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func) { + PyObject *arg[2] = {NULL, NULL}; + return __Pyx_PyObject_FastCall(func, arg + 1, 0 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* BufferIndexError */ +static void __Pyx_RaiseBufferIndexError(int axis) { + PyErr_Format(PyExc_IndexError, + "Out of bounds on buffer access (axis %d)", axis); +} + +/* PyObject_GenericGetAttrNoDict */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject *__Pyx_RaiseGenericGetAttributeError(PyTypeObject *tp, PyObject *attr_name) { + __Pyx_TypeName type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, attr_name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(attr_name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name) { + PyObject *descr; + PyTypeObject *tp = Py_TYPE(obj); + if (unlikely(!PyString_Check(attr_name))) { + return PyObject_GenericGetAttr(obj, attr_name); + } + assert(!tp->tp_dictoffset); + descr = _PyType_Lookup(tp, attr_name); + if (unlikely(!descr)) { + return __Pyx_RaiseGenericGetAttributeError(tp, attr_name); + } + Py_INCREF(descr); + #if PY_MAJOR_VERSION < 3 + if (likely(PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_HAVE_CLASS))) + #endif + { + descrgetfunc f = Py_TYPE(descr)->tp_descr_get; + if (unlikely(f)) { + PyObject *res = f(descr, obj, (PyObject *)tp); + Py_DECREF(descr); + return res; + } + } + return descr; +} +#endif + +/* PyObject_GenericGetAttr */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name) { + if (unlikely(Py_TYPE(obj)->tp_dictoffset)) { + return PyObject_GenericGetAttr(obj, attr_name); + } + return __Pyx_PyObject_GenericGetAttrNoDict(obj, attr_name); +} +#endif + +/* FixUpExtensionType */ +#if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type) { +#if PY_VERSION_HEX > 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + CYTHON_UNUSED_VAR(spec); + CYTHON_UNUSED_VAR(type); +#else + const PyType_Slot *slot = spec->slots; + while (slot && slot->slot && slot->slot != Py_tp_members) + slot++; + if (slot && slot->slot == Py_tp_members) { + int changed = 0; +#if !(PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON) + const +#endif + PyMemberDef *memb = (PyMemberDef*) slot->pfunc; + while (memb && memb->name) { + if (memb->name[0] == '_' && memb->name[1] == '_') { +#if PY_VERSION_HEX < 0x030900b1 + if (strcmp(memb->name, "__weaklistoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_weaklistoffset = memb->offset; + changed = 1; + } + else if (strcmp(memb->name, "__dictoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_dictoffset = memb->offset; + changed = 1; + } +#if CYTHON_METH_FASTCALL + else if (strcmp(memb->name, "__vectorcalloffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); +#if PY_VERSION_HEX >= 0x030800b4 + type->tp_vectorcall_offset = memb->offset; +#else + type->tp_print = (printfunc) memb->offset; +#endif + changed = 1; + } +#endif +#else + if ((0)); +#endif +#if PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON + else if (strcmp(memb->name, "__module__") == 0) { + PyObject *descr; + assert(memb->type == T_OBJECT); + assert(memb->flags == 0 || memb->flags == READONLY); + descr = PyDescr_NewMember(type, memb); + if (unlikely(!descr)) + return -1; + if (unlikely(PyDict_SetItem(type->tp_dict, PyDescr_NAME(descr), descr) < 0)) { + Py_DECREF(descr); + return -1; + } + Py_DECREF(descr); + changed = 1; + } +#endif + } + memb++; + } + if (changed) + PyType_Modified(type); + } +#endif + return 0; +} +#endif + +/* PyObjectCallMethod0 */ +static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name) { + PyObject *method = NULL, *result = NULL; + int is_method = __Pyx_PyObject_GetMethod(obj, method_name, &method); + if (likely(is_method)) { + result = __Pyx_PyObject_CallOneArg(method, obj); + Py_DECREF(method); + return result; + } + if (unlikely(!method)) goto bad; + result = __Pyx_PyObject_CallNoArg(method); + Py_DECREF(method); +bad: + return result; +} + +/* ValidateBasesTuple */ +#if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases) { + Py_ssize_t i, n; +#if CYTHON_ASSUME_SAFE_MACROS + n = PyTuple_GET_SIZE(bases); +#else + n = PyTuple_Size(bases); + if (n < 0) return -1; +#endif + for (i = 1; i < n; i++) + { +#if CYTHON_AVOID_BORROWED_REFS + PyObject *b0 = PySequence_GetItem(bases, i); + if (!b0) return -1; +#elif CYTHON_ASSUME_SAFE_MACROS + PyObject *b0 = PyTuple_GET_ITEM(bases, i); +#else + PyObject *b0 = PyTuple_GetItem(bases, i); + if (!b0) return -1; +#endif + PyTypeObject *b; +#if PY_MAJOR_VERSION < 3 + if (PyClass_Check(b0)) + { + PyErr_Format(PyExc_TypeError, "base class '%.200s' is an old-style class", + PyString_AS_STRING(((PyClassObject*)b0)->cl_name)); +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + return -1; + } +#endif + b = (PyTypeObject*) b0; + if (!__Pyx_PyType_HasFeature(b, Py_TPFLAGS_HEAPTYPE)) + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "base class '" __Pyx_FMT_TYPENAME "' is not a heap type", b_name); + __Pyx_DECREF_TypeName(b_name); +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + return -1; + } + if (dictoffset == 0) + { + Py_ssize_t b_dictoffset = 0; +#if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + b_dictoffset = b->tp_dictoffset; +#else + PyObject *py_b_dictoffset = PyObject_GetAttrString((PyObject*)b, "__dictoffset__"); + if (!py_b_dictoffset) goto dictoffset_return; + b_dictoffset = PyLong_AsSsize_t(py_b_dictoffset); + Py_DECREF(py_b_dictoffset); + if (b_dictoffset == -1 && PyErr_Occurred()) goto dictoffset_return; +#endif + if (b_dictoffset) { + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "extension type '%.200s' has no __dict__ slot, " + "but base type '" __Pyx_FMT_TYPENAME "' has: " + "either add 'cdef dict __dict__' to the extension type " + "or add '__slots__ = [...]' to the base type", + type_name, b_name); + __Pyx_DECREF_TypeName(b_name); + } +#if !(CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY) + dictoffset_return: +#endif +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + return -1; + } + } +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + } + return 0; +} +#endif + +/* PyType_Ready */ +static int __Pyx_PyType_Ready(PyTypeObject *t) { +#if CYTHON_USE_TYPE_SPECS || !(CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API) || defined(PYSTON_MAJOR_VERSION) + (void)__Pyx_PyObject_CallMethod0; +#if CYTHON_USE_TYPE_SPECS + (void)__Pyx_validate_bases_tuple; +#endif + return PyType_Ready(t); +#else + int r; + PyObject *bases = __Pyx_PyType_GetSlot(t, tp_bases, PyObject*); + if (bases && unlikely(__Pyx_validate_bases_tuple(t->tp_name, t->tp_dictoffset, bases) == -1)) + return -1; +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + { + int gc_was_enabled; + #if PY_VERSION_HEX >= 0x030A00b1 + gc_was_enabled = PyGC_Disable(); + (void)__Pyx_PyObject_CallMethod0; + #else + PyObject *ret, *py_status; + PyObject *gc = NULL; + #if PY_VERSION_HEX >= 0x030700a1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM+0 >= 0x07030400) + gc = PyImport_GetModule(__pyx_kp_u_gc); + #endif + if (unlikely(!gc)) gc = PyImport_Import(__pyx_kp_u_gc); + if (unlikely(!gc)) return -1; + py_status = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_isenabled); + if (unlikely(!py_status)) { + Py_DECREF(gc); + return -1; + } + gc_was_enabled = __Pyx_PyObject_IsTrue(py_status); + Py_DECREF(py_status); + if (gc_was_enabled > 0) { + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_disable); + if (unlikely(!ret)) { + Py_DECREF(gc); + return -1; + } + Py_DECREF(ret); + } else if (unlikely(gc_was_enabled == -1)) { + Py_DECREF(gc); + return -1; + } + #endif + t->tp_flags |= Py_TPFLAGS_HEAPTYPE; +#if PY_VERSION_HEX >= 0x030A0000 + t->tp_flags |= Py_TPFLAGS_IMMUTABLETYPE; +#endif +#else + (void)__Pyx_PyObject_CallMethod0; +#endif + r = PyType_Ready(t); +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + t->tp_flags &= ~Py_TPFLAGS_HEAPTYPE; + #if PY_VERSION_HEX >= 0x030A00b1 + if (gc_was_enabled) + PyGC_Enable(); + #else + if (gc_was_enabled) { + PyObject *tp, *v, *tb; + PyErr_Fetch(&tp, &v, &tb); + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_enable); + if (likely(ret || r == -1)) { + Py_XDECREF(ret); + PyErr_Restore(tp, v, tb); + } else { + Py_XDECREF(tp); + Py_XDECREF(v); + Py_XDECREF(tb); + r = -1; + } + } + Py_DECREF(gc); + #endif + } +#endif + return r; +#endif +} + +/* SetVTable */ +static int __Pyx_SetVtable(PyTypeObject *type, void *vtable) { + PyObject *ob = PyCapsule_New(vtable, 0, 0); + if (unlikely(!ob)) + goto bad; +#if CYTHON_COMPILING_IN_LIMITED_API + if (unlikely(PyObject_SetAttr((PyObject *) type, __pyx_n_s_pyx_vtable, ob) < 0)) +#else + if (unlikely(PyDict_SetItem(type->tp_dict, __pyx_n_s_pyx_vtable, ob) < 0)) +#endif + goto bad; + Py_DECREF(ob); + return 0; +bad: + Py_XDECREF(ob); + return -1; +} + +/* GetVTable */ +static void* __Pyx_GetVtable(PyTypeObject *type) { + void* ptr; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *ob = PyObject_GetAttr((PyObject *)type, __pyx_n_s_pyx_vtable); +#else + PyObject *ob = PyObject_GetItem(type->tp_dict, __pyx_n_s_pyx_vtable); +#endif + if (!ob) + goto bad; + ptr = PyCapsule_GetPointer(ob, 0); + if (!ptr && !PyErr_Occurred()) + PyErr_SetString(PyExc_RuntimeError, "invalid vtable found for imported type"); + Py_DECREF(ob); + return ptr; +bad: + Py_XDECREF(ob); + return NULL; +} + +/* MergeVTables */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_MergeVtables(PyTypeObject *type) { + int i; + void** base_vtables; + __Pyx_TypeName tp_base_name; + __Pyx_TypeName base_name; + void* unknown = (void*)-1; + PyObject* bases = type->tp_bases; + int base_depth = 0; + { + PyTypeObject* base = type->tp_base; + while (base) { + base_depth += 1; + base = base->tp_base; + } + } + base_vtables = (void**) malloc(sizeof(void*) * (size_t)(base_depth + 1)); + base_vtables[0] = unknown; + for (i = 1; i < PyTuple_GET_SIZE(bases); i++) { + void* base_vtable = __Pyx_GetVtable(((PyTypeObject*)PyTuple_GET_ITEM(bases, i))); + if (base_vtable != NULL) { + int j; + PyTypeObject* base = type->tp_base; + for (j = 0; j < base_depth; j++) { + if (base_vtables[j] == unknown) { + base_vtables[j] = __Pyx_GetVtable(base); + base_vtables[j + 1] = unknown; + } + if (base_vtables[j] == base_vtable) { + break; + } else if (base_vtables[j] == NULL) { + goto bad; + } + base = base->tp_base; + } + } + } + PyErr_Clear(); + free(base_vtables); + return 0; +bad: + tp_base_name = __Pyx_PyType_GetName(type->tp_base); + base_name = __Pyx_PyType_GetName((PyTypeObject*)PyTuple_GET_ITEM(bases, i)); + PyErr_Format(PyExc_TypeError, + "multiple bases have vtable conflict: '" __Pyx_FMT_TYPENAME "' and '" __Pyx_FMT_TYPENAME "'", tp_base_name, base_name); + __Pyx_DECREF_TypeName(tp_base_name); + __Pyx_DECREF_TypeName(base_name); + free(base_vtables); + return -1; +} +#endif + +/* SetupReduce */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce_is_named(PyObject* meth, PyObject* name) { + int ret; + PyObject *name_attr; + name_attr = __Pyx_PyObject_GetAttrStrNoError(meth, __pyx_n_s_name_2); + if (likely(name_attr)) { + ret = PyObject_RichCompareBool(name_attr, name, Py_EQ); + } else { + ret = -1; + } + if (unlikely(ret < 0)) { + PyErr_Clear(); + ret = 0; + } + Py_XDECREF(name_attr); + return ret; +} +static int __Pyx_setup_reduce(PyObject* type_obj) { + int ret = 0; + PyObject *object_reduce = NULL; + PyObject *object_getstate = NULL; + PyObject *object_reduce_ex = NULL; + PyObject *reduce = NULL; + PyObject *reduce_ex = NULL; + PyObject *reduce_cython = NULL; + PyObject *setstate = NULL; + PyObject *setstate_cython = NULL; + PyObject *getstate = NULL; +#if CYTHON_USE_PYTYPE_LOOKUP + getstate = _PyType_Lookup((PyTypeObject*)type_obj, __pyx_n_s_getstate); +#else + getstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_getstate); + if (!getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (getstate) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_getstate = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_getstate); +#else + object_getstate = __Pyx_PyObject_GetAttrStrNoError((PyObject*)&PyBaseObject_Type, __pyx_n_s_getstate); + if (!object_getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (object_getstate != getstate) { + goto __PYX_GOOD; + } + } +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce_ex = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#else + object_reduce_ex = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#endif + reduce_ex = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce_ex); if (unlikely(!reduce_ex)) goto __PYX_BAD; + if (reduce_ex == object_reduce_ex) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#else + object_reduce = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#endif + reduce = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce); if (unlikely(!reduce)) goto __PYX_BAD; + if (reduce == object_reduce || __Pyx_setup_reduce_is_named(reduce, __pyx_n_s_reduce_cython)) { + reduce_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_reduce_cython); + if (likely(reduce_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce, reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (reduce == object_reduce || PyErr_Occurred()) { + goto __PYX_BAD; + } + setstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate); + if (!setstate) PyErr_Clear(); + if (!setstate || __Pyx_setup_reduce_is_named(setstate, __pyx_n_s_setstate_cython)) { + setstate_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate_cython); + if (likely(setstate_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate, setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (!setstate || PyErr_Occurred()) { + goto __PYX_BAD; + } + } + PyType_Modified((PyTypeObject*)type_obj); + } + } + goto __PYX_GOOD; +__PYX_BAD: + if (!PyErr_Occurred()) { + __Pyx_TypeName type_obj_name = + __Pyx_PyType_GetName((PyTypeObject*)type_obj); + PyErr_Format(PyExc_RuntimeError, + "Unable to initialize pickling for " __Pyx_FMT_TYPENAME, type_obj_name); + __Pyx_DECREF_TypeName(type_obj_name); + } + ret = -1; +__PYX_GOOD: +#if !CYTHON_USE_PYTYPE_LOOKUP + Py_XDECREF(object_reduce); + Py_XDECREF(object_reduce_ex); + Py_XDECREF(object_getstate); + Py_XDECREF(getstate); +#endif + Py_XDECREF(reduce); + Py_XDECREF(reduce_ex); + Py_XDECREF(reduce_cython); + Py_XDECREF(setstate); + Py_XDECREF(setstate_cython); + return ret; +} +#endif + +/* TypeImport */ +#ifndef __PYX_HAVE_RT_ImportType_3_0_8 +#define __PYX_HAVE_RT_ImportType_3_0_8 +static PyTypeObject *__Pyx_ImportType_3_0_8(PyObject *module, const char *module_name, const char *class_name, + size_t size, size_t alignment, enum __Pyx_ImportType_CheckSize_3_0_8 check_size) +{ + PyObject *result = 0; + char warning[200]; + Py_ssize_t basicsize; + Py_ssize_t itemsize; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *py_basicsize; + PyObject *py_itemsize; +#endif + result = PyObject_GetAttrString(module, class_name); + if (!result) + goto bad; + if (!PyType_Check(result)) { + PyErr_Format(PyExc_TypeError, + "%.200s.%.200s is not a type object", + module_name, class_name); + goto bad; + } +#if !CYTHON_COMPILING_IN_LIMITED_API + basicsize = ((PyTypeObject *)result)->tp_basicsize; + itemsize = ((PyTypeObject *)result)->tp_itemsize; +#else + py_basicsize = PyObject_GetAttrString(result, "__basicsize__"); + if (!py_basicsize) + goto bad; + basicsize = PyLong_AsSsize_t(py_basicsize); + Py_DECREF(py_basicsize); + py_basicsize = 0; + if (basicsize == (Py_ssize_t)-1 && PyErr_Occurred()) + goto bad; + py_itemsize = PyObject_GetAttrString(result, "__itemsize__"); + if (!py_itemsize) + goto bad; + itemsize = PyLong_AsSsize_t(py_itemsize); + Py_DECREF(py_itemsize); + py_itemsize = 0; + if (itemsize == (Py_ssize_t)-1 && PyErr_Occurred()) + goto bad; +#endif + if (itemsize) { + if (size % alignment) { + alignment = size % alignment; + } + if (itemsize < (Py_ssize_t)alignment) + itemsize = (Py_ssize_t)alignment; + } + if ((size_t)(basicsize + itemsize) < size) { + PyErr_Format(PyExc_ValueError, + "%.200s.%.200s size changed, may indicate binary incompatibility. " + "Expected %zd from C header, got %zd from PyObject", + module_name, class_name, size, basicsize+itemsize); + goto bad; + } + if (check_size == __Pyx_ImportType_CheckSize_Error_3_0_8 && + ((size_t)basicsize > size || (size_t)(basicsize + itemsize) < size)) { + PyErr_Format(PyExc_ValueError, + "%.200s.%.200s size changed, may indicate binary incompatibility. " + "Expected %zd from C header, got %zd-%zd from PyObject", + module_name, class_name, size, basicsize, basicsize+itemsize); + goto bad; + } + else if (check_size == __Pyx_ImportType_CheckSize_Warn_3_0_8 && (size_t)basicsize > size) { + PyOS_snprintf(warning, sizeof(warning), + "%s.%s size changed, may indicate binary incompatibility. " + "Expected %zd from C header, got %zd from PyObject", + module_name, class_name, size, basicsize); + if (PyErr_WarnEx(NULL, warning, 0) < 0) goto bad; + } + return (PyTypeObject *)result; +bad: + Py_XDECREF(result); + return NULL; +} +#endif + +/* FetchSharedCythonModule */ +static PyObject *__Pyx_FetchSharedCythonABIModule(void) { + return __Pyx_PyImport_AddModuleRef((char*) __PYX_ABI_MODULE_NAME); +} + +/* FetchCommonType */ +static int __Pyx_VerifyCachedType(PyObject *cached_type, + const char *name, + Py_ssize_t basicsize, + Py_ssize_t expected_basicsize) { + if (!PyType_Check(cached_type)) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s is not a type object", name); + return -1; + } + if (basicsize != expected_basicsize) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s has the wrong size, try recompiling", + name); + return -1; + } + return 0; +} +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type) { + PyObject* abi_module; + const char* object_name; + PyTypeObject *cached_type = NULL; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + object_name = strrchr(type->tp_name, '.'); + object_name = object_name ? object_name+1 : type->tp_name; + cached_type = (PyTypeObject*) PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + if (__Pyx_VerifyCachedType( + (PyObject *)cached_type, + object_name, + cached_type->tp_basicsize, + type->tp_basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + if (PyType_Ready(type) < 0) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, (PyObject *)type) < 0) + goto bad; + Py_INCREF(type); + cached_type = type; +done: + Py_DECREF(abi_module); + return cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#else +static PyTypeObject *__Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases) { + PyObject *abi_module, *cached_type = NULL; + const char* object_name = strrchr(spec->name, '.'); + object_name = object_name ? object_name+1 : spec->name; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + cached_type = PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + Py_ssize_t basicsize; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *py_basicsize; + py_basicsize = PyObject_GetAttrString(cached_type, "__basicsize__"); + if (unlikely(!py_basicsize)) goto bad; + basicsize = PyLong_AsSsize_t(py_basicsize); + Py_DECREF(py_basicsize); + py_basicsize = 0; + if (unlikely(basicsize == (Py_ssize_t)-1) && PyErr_Occurred()) goto bad; +#else + basicsize = likely(PyType_Check(cached_type)) ? ((PyTypeObject*) cached_type)->tp_basicsize : -1; +#endif + if (__Pyx_VerifyCachedType( + cached_type, + object_name, + basicsize, + spec->basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + CYTHON_UNUSED_VAR(module); + cached_type = __Pyx_PyType_FromModuleAndSpec(abi_module, spec, bases); + if (unlikely(!cached_type)) goto bad; + if (unlikely(__Pyx_fix_up_extension_type_from_spec(spec, (PyTypeObject *) cached_type) < 0)) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, cached_type) < 0) goto bad; +done: + Py_DECREF(abi_module); + assert(cached_type == NULL || PyType_Check(cached_type)); + return (PyTypeObject *) cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#endif + +/* PyVectorcallFastCallDict */ +#if CYTHON_METH_FASTCALL +static PyObject *__Pyx_PyVectorcall_FastCallDict_kw(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + PyObject *res = NULL; + PyObject *kwnames; + PyObject **newargs; + PyObject **kwvalues; + Py_ssize_t i, pos; + size_t j; + PyObject *key, *value; + unsigned long keys_are_strings; + Py_ssize_t nkw = PyDict_GET_SIZE(kw); + newargs = (PyObject **)PyMem_Malloc((nargs + (size_t)nkw) * sizeof(args[0])); + if (unlikely(newargs == NULL)) { + PyErr_NoMemory(); + return NULL; + } + for (j = 0; j < nargs; j++) newargs[j] = args[j]; + kwnames = PyTuple_New(nkw); + if (unlikely(kwnames == NULL)) { + PyMem_Free(newargs); + return NULL; + } + kwvalues = newargs + nargs; + pos = i = 0; + keys_are_strings = Py_TPFLAGS_UNICODE_SUBCLASS; + while (PyDict_Next(kw, &pos, &key, &value)) { + keys_are_strings &= Py_TYPE(key)->tp_flags; + Py_INCREF(key); + Py_INCREF(value); + PyTuple_SET_ITEM(kwnames, i, key); + kwvalues[i] = value; + i++; + } + if (unlikely(!keys_are_strings)) { + PyErr_SetString(PyExc_TypeError, "keywords must be strings"); + goto cleanup; + } + res = vc(func, newargs, nargs, kwnames); +cleanup: + Py_DECREF(kwnames); + for (i = 0; i < nkw; i++) + Py_DECREF(kwvalues[i]); + PyMem_Free(newargs); + return res; +} +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + if (likely(kw == NULL) || PyDict_GET_SIZE(kw) == 0) { + return vc(func, args, nargs, NULL); + } + return __Pyx_PyVectorcall_FastCallDict_kw(func, vc, args, nargs, kw); +} +#endif + +/* CythonFunctionShared */ +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc) { + if (__Pyx_CyFunction_Check(func)) { + return PyCFunction_GetFunction(((__pyx_CyFunctionObject*)func)->func) == (PyCFunction) cfunc; + } else if (PyCFunction_Check(func)) { + return PyCFunction_GetFunction(func) == (PyCFunction) cfunc; + } + return 0; +} +#else +static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc) { + return __Pyx_CyOrPyCFunction_Check(func) && __Pyx_CyOrPyCFunction_GET_FUNCTION(func) == (PyCFunction) cfunc; +} +#endif +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj) { +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + __Pyx_Py_XDECREF_SET( + __Pyx_CyFunction_GetClassObj(f), + ((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#else + __Pyx_Py_XDECREF_SET( + ((PyCMethodObject *) (f))->mm_class, + (PyTypeObject*)((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#endif +} +static PyObject * +__Pyx_CyFunction_get_doc(__pyx_CyFunctionObject *op, void *closure) +{ + CYTHON_UNUSED_VAR(closure); + if (unlikely(op->func_doc == NULL)) { +#if CYTHON_COMPILING_IN_LIMITED_API + op->func_doc = PyObject_GetAttrString(op->func, "__doc__"); + if (unlikely(!op->func_doc)) return NULL; +#else + if (((PyCFunctionObject*)op)->m_ml->ml_doc) { +#if PY_MAJOR_VERSION >= 3 + op->func_doc = PyUnicode_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#else + op->func_doc = PyString_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#endif + if (unlikely(op->func_doc == NULL)) + return NULL; + } else { + Py_INCREF(Py_None); + return Py_None; + } +#endif + } + Py_INCREF(op->func_doc); + return op->func_doc; +} +static int +__Pyx_CyFunction_set_doc(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (value == NULL) { + value = Py_None; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_doc, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_name(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_name == NULL)) { +#if CYTHON_COMPILING_IN_LIMITED_API + op->func_name = PyObject_GetAttrString(op->func, "__name__"); +#elif PY_MAJOR_VERSION >= 3 + op->func_name = PyUnicode_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#else + op->func_name = PyString_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#endif + if (unlikely(op->func_name == NULL)) + return NULL; + } + Py_INCREF(op->func_name); + return op->func_name; +} +static int +__Pyx_CyFunction_set_name(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__name__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_name, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_qualname(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_qualname); + return op->func_qualname; +} +static int +__Pyx_CyFunction_set_qualname(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__qualname__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_qualname, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_dict(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_dict == NULL)) { + op->func_dict = PyDict_New(); + if (unlikely(op->func_dict == NULL)) + return NULL; + } + Py_INCREF(op->func_dict); + return op->func_dict; +} +static int +__Pyx_CyFunction_set_dict(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(value == NULL)) { + PyErr_SetString(PyExc_TypeError, + "function's dictionary may not be deleted"); + return -1; + } + if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "setting function's dictionary to a non-dict"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_dict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_globals(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_globals); + return op->func_globals; +} +static PyObject * +__Pyx_CyFunction_get_closure(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(op); + CYTHON_UNUSED_VAR(context); + Py_INCREF(Py_None); + return Py_None; +} +static PyObject * +__Pyx_CyFunction_get_code(__pyx_CyFunctionObject *op, void *context) +{ + PyObject* result = (op->func_code) ? op->func_code : Py_None; + CYTHON_UNUSED_VAR(context); + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_init_defaults(__pyx_CyFunctionObject *op) { + int result = 0; + PyObject *res = op->defaults_getter((PyObject *) op); + if (unlikely(!res)) + return -1; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + op->defaults_tuple = PyTuple_GET_ITEM(res, 0); + Py_INCREF(op->defaults_tuple); + op->defaults_kwdict = PyTuple_GET_ITEM(res, 1); + Py_INCREF(op->defaults_kwdict); + #else + op->defaults_tuple = __Pyx_PySequence_ITEM(res, 0); + if (unlikely(!op->defaults_tuple)) result = -1; + else { + op->defaults_kwdict = __Pyx_PySequence_ITEM(res, 1); + if (unlikely(!op->defaults_kwdict)) result = -1; + } + #endif + Py_DECREF(res); + return result; +} +static int +__Pyx_CyFunction_set_defaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyTuple_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__defaults__ must be set to a tuple object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__defaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_tuple, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_defaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_tuple; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_tuple; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_kwdefaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__kwdefaults__ must be set to a dict object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__kwdefaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_kwdict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_kwdefaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_kwdict; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_kwdict; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_annotations(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value || value == Py_None) { + value = NULL; + } else if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__annotations__ must be set to a dict object"); + return -1; + } + Py_XINCREF(value); + __Pyx_Py_XDECREF_SET(op->func_annotations, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_annotations(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->func_annotations; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + result = PyDict_New(); + if (unlikely(!result)) return NULL; + op->func_annotations = result; + } + Py_INCREF(result); + return result; +} +static PyObject * +__Pyx_CyFunction_get_is_coroutine(__pyx_CyFunctionObject *op, void *context) { + int is_coroutine; + CYTHON_UNUSED_VAR(context); + if (op->func_is_coroutine) { + return __Pyx_NewRef(op->func_is_coroutine); + } + is_coroutine = op->flags & __Pyx_CYFUNCTION_COROUTINE; +#if PY_VERSION_HEX >= 0x03050000 + if (is_coroutine) { + PyObject *module, *fromlist, *marker = __pyx_n_s_is_coroutine; + fromlist = PyList_New(1); + if (unlikely(!fromlist)) return NULL; + Py_INCREF(marker); +#if CYTHON_ASSUME_SAFE_MACROS + PyList_SET_ITEM(fromlist, 0, marker); +#else + if (unlikely(PyList_SetItem(fromlist, 0, marker) < 0)) { + Py_DECREF(marker); + Py_DECREF(fromlist); + return NULL; + } +#endif + module = PyImport_ImportModuleLevelObject(__pyx_n_s_asyncio_coroutines, NULL, NULL, fromlist, 0); + Py_DECREF(fromlist); + if (unlikely(!module)) goto ignore; + op->func_is_coroutine = __Pyx_PyObject_GetAttrStr(module, marker); + Py_DECREF(module); + if (likely(op->func_is_coroutine)) { + return __Pyx_NewRef(op->func_is_coroutine); + } +ignore: + PyErr_Clear(); + } +#endif + op->func_is_coroutine = __Pyx_PyBool_FromLong(is_coroutine); + return __Pyx_NewRef(op->func_is_coroutine); +} +#if CYTHON_COMPILING_IN_LIMITED_API +static PyObject * +__Pyx_CyFunction_get_module(__pyx_CyFunctionObject *op, void *context) { + CYTHON_UNUSED_VAR(context); + return PyObject_GetAttrString(op->func, "__module__"); +} +static int +__Pyx_CyFunction_set_module(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + return PyObject_SetAttrString(op->func, "__module__", value); +} +#endif +static PyGetSetDef __pyx_CyFunction_getsets[] = { + {(char *) "func_doc", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "__doc__", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "func_name", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__name__", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__qualname__", (getter)__Pyx_CyFunction_get_qualname, (setter)__Pyx_CyFunction_set_qualname, 0, 0}, + {(char *) "func_dict", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "__dict__", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "func_globals", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "__globals__", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "func_closure", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "__closure__", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "func_code", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "__code__", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "func_defaults", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__defaults__", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__kwdefaults__", (getter)__Pyx_CyFunction_get_kwdefaults, (setter)__Pyx_CyFunction_set_kwdefaults, 0, 0}, + {(char *) "__annotations__", (getter)__Pyx_CyFunction_get_annotations, (setter)__Pyx_CyFunction_set_annotations, 0, 0}, + {(char *) "_is_coroutine", (getter)__Pyx_CyFunction_get_is_coroutine, 0, 0, 0}, +#if CYTHON_COMPILING_IN_LIMITED_API + {"__module__", (getter)__Pyx_CyFunction_get_module, (setter)__Pyx_CyFunction_set_module, 0, 0}, +#endif + {0, 0, 0, 0, 0} +}; +static PyMemberDef __pyx_CyFunction_members[] = { +#if !CYTHON_COMPILING_IN_LIMITED_API + {(char *) "__module__", T_OBJECT, offsetof(PyCFunctionObject, m_module), 0, 0}, +#endif +#if CYTHON_USE_TYPE_SPECS + {(char *) "__dictoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_dict), READONLY, 0}, +#if CYTHON_METH_FASTCALL +#if CYTHON_BACKPORT_VECTORCALL + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_vectorcall), READONLY, 0}, +#else +#if !CYTHON_COMPILING_IN_LIMITED_API + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(PyCFunctionObject, vectorcall), READONLY, 0}, +#endif +#endif +#endif +#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_weakreflist), READONLY, 0}, +#else + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(PyCFunctionObject, m_weakreflist), READONLY, 0}, +#endif +#endif + {0, 0, 0, 0, 0} +}; +static PyObject * +__Pyx_CyFunction_reduce(__pyx_CyFunctionObject *m, PyObject *args) +{ + CYTHON_UNUSED_VAR(args); +#if PY_MAJOR_VERSION >= 3 + Py_INCREF(m->func_qualname); + return m->func_qualname; +#else + return PyString_FromString(((PyCFunctionObject*)m)->m_ml->ml_name); +#endif +} +static PyMethodDef __pyx_CyFunction_methods[] = { + {"__reduce__", (PyCFunction)__Pyx_CyFunction_reduce, METH_VARARGS, 0}, + {0, 0, 0, 0} +}; +#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API +#define __Pyx_CyFunction_weakreflist(cyfunc) ((cyfunc)->func_weakreflist) +#else +#define __Pyx_CyFunction_weakreflist(cyfunc) (((PyCFunctionObject*)cyfunc)->m_weakreflist) +#endif +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject *op, PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { +#if !CYTHON_COMPILING_IN_LIMITED_API + PyCFunctionObject *cf = (PyCFunctionObject*) op; +#endif + if (unlikely(op == NULL)) + return NULL; +#if CYTHON_COMPILING_IN_LIMITED_API + op->func = PyCFunction_NewEx(ml, (PyObject*)op, module); + if (unlikely(!op->func)) return NULL; +#endif + op->flags = flags; + __Pyx_CyFunction_weakreflist(op) = NULL; +#if !CYTHON_COMPILING_IN_LIMITED_API + cf->m_ml = ml; + cf->m_self = (PyObject *) op; +#endif + Py_XINCREF(closure); + op->func_closure = closure; +#if !CYTHON_COMPILING_IN_LIMITED_API + Py_XINCREF(module); + cf->m_module = module; +#endif + op->func_dict = NULL; + op->func_name = NULL; + Py_INCREF(qualname); + op->func_qualname = qualname; + op->func_doc = NULL; +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + op->func_classobj = NULL; +#else + ((PyCMethodObject*)op)->mm_class = NULL; +#endif + op->func_globals = globals; + Py_INCREF(op->func_globals); + Py_XINCREF(code); + op->func_code = code; + op->defaults_pyobjects = 0; + op->defaults_size = 0; + op->defaults = NULL; + op->defaults_tuple = NULL; + op->defaults_kwdict = NULL; + op->defaults_getter = NULL; + op->func_annotations = NULL; + op->func_is_coroutine = NULL; +#if CYTHON_METH_FASTCALL + switch (ml->ml_flags & (METH_VARARGS | METH_FASTCALL | METH_NOARGS | METH_O | METH_KEYWORDS | METH_METHOD)) { + case METH_NOARGS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_NOARGS; + break; + case METH_O: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_O; + break; + case METH_METHOD | METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD; + break; + case METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS; + break; + case METH_VARARGS | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = NULL; + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + Py_DECREF(op); + return NULL; + } +#endif + return (PyObject *) op; +} +static int +__Pyx_CyFunction_clear(__pyx_CyFunctionObject *m) +{ + Py_CLEAR(m->func_closure); +#if CYTHON_COMPILING_IN_LIMITED_API + Py_CLEAR(m->func); +#else + Py_CLEAR(((PyCFunctionObject*)m)->m_module); +#endif + Py_CLEAR(m->func_dict); + Py_CLEAR(m->func_name); + Py_CLEAR(m->func_qualname); + Py_CLEAR(m->func_doc); + Py_CLEAR(m->func_globals); + Py_CLEAR(m->func_code); +#if !CYTHON_COMPILING_IN_LIMITED_API +#if PY_VERSION_HEX < 0x030900B1 + Py_CLEAR(__Pyx_CyFunction_GetClassObj(m)); +#else + { + PyObject *cls = (PyObject*) ((PyCMethodObject *) (m))->mm_class; + ((PyCMethodObject *) (m))->mm_class = NULL; + Py_XDECREF(cls); + } +#endif +#endif + Py_CLEAR(m->defaults_tuple); + Py_CLEAR(m->defaults_kwdict); + Py_CLEAR(m->func_annotations); + Py_CLEAR(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_XDECREF(pydefaults[i]); + PyObject_Free(m->defaults); + m->defaults = NULL; + } + return 0; +} +static void __Pyx__CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + if (__Pyx_CyFunction_weakreflist(m) != NULL) + PyObject_ClearWeakRefs((PyObject *) m); + __Pyx_CyFunction_clear(m); + __Pyx_PyHeapTypeObject_GC_Del(m); +} +static void __Pyx_CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + PyObject_GC_UnTrack(m); + __Pyx__CyFunction_dealloc(m); +} +static int __Pyx_CyFunction_traverse(__pyx_CyFunctionObject *m, visitproc visit, void *arg) +{ + Py_VISIT(m->func_closure); +#if CYTHON_COMPILING_IN_LIMITED_API + Py_VISIT(m->func); +#else + Py_VISIT(((PyCFunctionObject*)m)->m_module); +#endif + Py_VISIT(m->func_dict); + Py_VISIT(m->func_name); + Py_VISIT(m->func_qualname); + Py_VISIT(m->func_doc); + Py_VISIT(m->func_globals); + Py_VISIT(m->func_code); +#if !CYTHON_COMPILING_IN_LIMITED_API + Py_VISIT(__Pyx_CyFunction_GetClassObj(m)); +#endif + Py_VISIT(m->defaults_tuple); + Py_VISIT(m->defaults_kwdict); + Py_VISIT(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_VISIT(pydefaults[i]); + } + return 0; +} +static PyObject* +__Pyx_CyFunction_repr(__pyx_CyFunctionObject *op) +{ +#if PY_MAJOR_VERSION >= 3 + return PyUnicode_FromFormat("", + op->func_qualname, (void *)op); +#else + return PyString_FromFormat("", + PyString_AsString(op->func_qualname), (void *)op); +#endif +} +static PyObject * __Pyx_CyFunction_CallMethod(PyObject *func, PyObject *self, PyObject *arg, PyObject *kw) { +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *f = ((__pyx_CyFunctionObject*)func)->func; + PyObject *py_name = NULL; + PyCFunction meth; + int flags; + meth = PyCFunction_GetFunction(f); + if (unlikely(!meth)) return NULL; + flags = PyCFunction_GetFlags(f); + if (unlikely(flags < 0)) return NULL; +#else + PyCFunctionObject* f = (PyCFunctionObject*)func; + PyCFunction meth = f->m_ml->ml_meth; + int flags = f->m_ml->ml_flags; +#endif + Py_ssize_t size; + switch (flags & (METH_VARARGS | METH_KEYWORDS | METH_NOARGS | METH_O)) { + case METH_VARARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) + return (*meth)(self, arg); + break; + case METH_VARARGS | METH_KEYWORDS: + return (*(PyCFunctionWithKeywords)(void*)meth)(self, arg, kw); + case METH_NOARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { +#if CYTHON_ASSUME_SAFE_MACROS + size = PyTuple_GET_SIZE(arg); +#else + size = PyTuple_Size(arg); + if (unlikely(size < 0)) return NULL; +#endif + if (likely(size == 0)) + return (*meth)(self, NULL); +#if CYTHON_COMPILING_IN_LIMITED_API + py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); + if (!py_name) return NULL; + PyErr_Format(PyExc_TypeError, + "%.200S() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + py_name, size); + Py_DECREF(py_name); +#else + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); +#endif + return NULL; + } + break; + case METH_O: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { +#if CYTHON_ASSUME_SAFE_MACROS + size = PyTuple_GET_SIZE(arg); +#else + size = PyTuple_Size(arg); + if (unlikely(size < 0)) return NULL; +#endif + if (likely(size == 1)) { + PyObject *result, *arg0; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + arg0 = PyTuple_GET_ITEM(arg, 0); + #else + arg0 = __Pyx_PySequence_ITEM(arg, 0); if (unlikely(!arg0)) return NULL; + #endif + result = (*meth)(self, arg0); + #if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(arg0); + #endif + return result; + } +#if CYTHON_COMPILING_IN_LIMITED_API + py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); + if (!py_name) return NULL; + PyErr_Format(PyExc_TypeError, + "%.200S() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + py_name, size); + Py_DECREF(py_name); +#else + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); +#endif + return NULL; + } + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + return NULL; + } +#if CYTHON_COMPILING_IN_LIMITED_API + py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); + if (!py_name) return NULL; + PyErr_Format(PyExc_TypeError, "%.200S() takes no keyword arguments", + py_name); + Py_DECREF(py_name); +#else + PyErr_Format(PyExc_TypeError, "%.200s() takes no keyword arguments", + f->m_ml->ml_name); +#endif + return NULL; +} +static CYTHON_INLINE PyObject *__Pyx_CyFunction_Call(PyObject *func, PyObject *arg, PyObject *kw) { + PyObject *self, *result; +#if CYTHON_COMPILING_IN_LIMITED_API + self = PyCFunction_GetSelf(((__pyx_CyFunctionObject*)func)->func); + if (unlikely(!self) && PyErr_Occurred()) return NULL; +#else + self = ((PyCFunctionObject*)func)->m_self; +#endif + result = __Pyx_CyFunction_CallMethod(func, self, arg, kw); + return result; +} +static PyObject *__Pyx_CyFunction_CallAsMethod(PyObject *func, PyObject *args, PyObject *kw) { + PyObject *result; + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *) func; +#if CYTHON_METH_FASTCALL + __pyx_vectorcallfunc vc = __Pyx_CyFunction_func_vectorcall(cyfunc); + if (vc) { +#if CYTHON_ASSUME_SAFE_MACROS + return __Pyx_PyVectorcall_FastCallDict(func, vc, &PyTuple_GET_ITEM(args, 0), (size_t)PyTuple_GET_SIZE(args), kw); +#else + (void) &__Pyx_PyVectorcall_FastCallDict; + return PyVectorcall_Call(func, args, kw); +#endif + } +#endif + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + Py_ssize_t argc; + PyObject *new_args; + PyObject *self; +#if CYTHON_ASSUME_SAFE_MACROS + argc = PyTuple_GET_SIZE(args); +#else + argc = PyTuple_Size(args); + if (unlikely(!argc) < 0) return NULL; +#endif + new_args = PyTuple_GetSlice(args, 1, argc); + if (unlikely(!new_args)) + return NULL; + self = PyTuple_GetItem(args, 0); + if (unlikely(!self)) { + Py_DECREF(new_args); +#if PY_MAJOR_VERSION > 2 + PyErr_Format(PyExc_TypeError, + "unbound method %.200S() needs an argument", + cyfunc->func_qualname); +#else + PyErr_SetString(PyExc_TypeError, + "unbound method needs an argument"); +#endif + return NULL; + } + result = __Pyx_CyFunction_CallMethod(func, self, new_args, kw); + Py_DECREF(new_args); + } else { + result = __Pyx_CyFunction_Call(func, args, kw); + } + return result; +} +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE int __Pyx_CyFunction_Vectorcall_CheckArgs(__pyx_CyFunctionObject *cyfunc, Py_ssize_t nargs, PyObject *kwnames) +{ + int ret = 0; + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + if (unlikely(nargs < 1)) { + PyErr_Format(PyExc_TypeError, "%.200s() needs an argument", + ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + ret = 1; + } + if (unlikely(kwnames) && unlikely(PyTuple_GET_SIZE(kwnames))) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no keyword arguments", ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + return ret; +} +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 0)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, NULL); +} +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 1)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, args[0]); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((_PyCFunctionFastWithKeywords)(void(*)(void))def->ml_meth)(self, args, nargs, kwnames); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; + PyTypeObject *cls = (PyTypeObject *) __Pyx_CyFunction_GetClassObj(cyfunc); +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((__Pyx_PyCMethod)(void(*)(void))def->ml_meth)(self, cls, args, (size_t)nargs, kwnames); +} +#endif +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_CyFunctionType_slots[] = { + {Py_tp_dealloc, (void *)__Pyx_CyFunction_dealloc}, + {Py_tp_repr, (void *)__Pyx_CyFunction_repr}, + {Py_tp_call, (void *)__Pyx_CyFunction_CallAsMethod}, + {Py_tp_traverse, (void *)__Pyx_CyFunction_traverse}, + {Py_tp_clear, (void *)__Pyx_CyFunction_clear}, + {Py_tp_methods, (void *)__pyx_CyFunction_methods}, + {Py_tp_members, (void *)__pyx_CyFunction_members}, + {Py_tp_getset, (void *)__pyx_CyFunction_getsets}, + {Py_tp_descr_get, (void *)__Pyx_PyMethod_New}, + {0, 0}, +}; +static PyType_Spec __pyx_CyFunctionType_spec = { + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#if (defined(_Py_TPFLAGS_HAVE_VECTORCALL) && CYTHON_METH_FASTCALL) + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + __pyx_CyFunctionType_slots +}; +#else +static PyTypeObject __pyx_CyFunctionType_type = { + PyVarObject_HEAD_INIT(0, 0) + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, + (destructor) __Pyx_CyFunction_dealloc, +#if !CYTHON_METH_FASTCALL + 0, +#elif CYTHON_BACKPORT_VECTORCALL + (printfunc)offsetof(__pyx_CyFunctionObject, func_vectorcall), +#else + offsetof(PyCFunctionObject, vectorcall), +#endif + 0, + 0, +#if PY_MAJOR_VERSION < 3 + 0, +#else + 0, +#endif + (reprfunc) __Pyx_CyFunction_repr, + 0, + 0, + 0, + 0, + __Pyx_CyFunction_CallAsMethod, + 0, + 0, + 0, + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#if defined(_Py_TPFLAGS_HAVE_VECTORCALL) && CYTHON_METH_FASTCALL + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + 0, + (traverseproc) __Pyx_CyFunction_traverse, + (inquiry) __Pyx_CyFunction_clear, + 0, +#if PY_VERSION_HEX < 0x030500A0 + offsetof(__pyx_CyFunctionObject, func_weakreflist), +#else + offsetof(PyCFunctionObject, m_weakreflist), +#endif + 0, + 0, + __pyx_CyFunction_methods, + __pyx_CyFunction_members, + __pyx_CyFunction_getsets, + 0, + 0, + __Pyx_PyMethod_New, + 0, + offsetof(__pyx_CyFunctionObject, func_dict), + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, +#if PY_VERSION_HEX >= 0x030400a1 + 0, +#endif +#if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, +#endif +#if __PYX_NEED_TP_PRINT_SLOT + 0, +#endif +#if PY_VERSION_HEX >= 0x030C0000 + 0, +#endif +#if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, +#endif +}; +#endif +static int __pyx_CyFunction_init(PyObject *module) { +#if CYTHON_USE_TYPE_SPECS + __pyx_CyFunctionType = __Pyx_FetchCommonTypeFromSpec(module, &__pyx_CyFunctionType_spec, NULL); +#else + CYTHON_UNUSED_VAR(module); + __pyx_CyFunctionType = __Pyx_FetchCommonType(&__pyx_CyFunctionType_type); +#endif + if (unlikely(__pyx_CyFunctionType == NULL)) { + return -1; + } + return 0; +} +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *func, size_t size, int pyobjects) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults = PyObject_Malloc(size); + if (unlikely(!m->defaults)) + return PyErr_NoMemory(); + memset(m->defaults, 0, size); + m->defaults_pyobjects = pyobjects; + m->defaults_size = size; + return m->defaults; +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *func, PyObject *tuple) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_tuple = tuple; + Py_INCREF(tuple); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_kwdict = dict; + Py_INCREF(dict); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->func_annotations = dict; + Py_INCREF(dict); +} + +/* CythonFunction */ +static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { + PyObject *op = __Pyx_CyFunction_Init( + PyObject_GC_New(__pyx_CyFunctionObject, __pyx_CyFunctionType), + ml, flags, qualname, closure, module, globals, code + ); + if (likely(op)) { + PyObject_GC_Track(op); + } + return op; +} + +/* Py3UpdateBases */ +static PyObject* +__Pyx_PEP560_update_bases(PyObject *bases) +{ + Py_ssize_t i, j, size_bases; + PyObject *base, *meth, *new_base, *result, *new_bases = NULL; + size_bases = PyTuple_GET_SIZE(bases); + for (i = 0; i < size_bases; i++) { + base = PyTuple_GET_ITEM(bases, i); + if (PyType_Check(base)) { + if (new_bases) { + if (PyList_Append(new_bases, base) < 0) { + goto error; + } + } + continue; + } + meth = __Pyx_PyObject_GetAttrStrNoError(base, __pyx_n_s_mro_entries); + if (!meth && PyErr_Occurred()) { + goto error; + } + if (!meth) { + if (new_bases) { + if (PyList_Append(new_bases, base) < 0) { + goto error; + } + } + continue; + } + new_base = __Pyx_PyObject_CallOneArg(meth, bases); + Py_DECREF(meth); + if (!new_base) { + goto error; + } + if (!PyTuple_Check(new_base)) { + PyErr_SetString(PyExc_TypeError, + "__mro_entries__ must return a tuple"); + Py_DECREF(new_base); + goto error; + } + if (!new_bases) { + if (!(new_bases = PyList_New(i))) { + goto error; + } + for (j = 0; j < i; j++) { + base = PyTuple_GET_ITEM(bases, j); + PyList_SET_ITEM(new_bases, j, base); + Py_INCREF(base); + } + } + j = PyList_GET_SIZE(new_bases); + if (PyList_SetSlice(new_bases, j, j, new_base) < 0) { + goto error; + } + Py_DECREF(new_base); + } + if (!new_bases) { + Py_INCREF(bases); + return bases; + } + result = PyList_AsTuple(new_bases); + Py_DECREF(new_bases); + return result; +error: + Py_XDECREF(new_bases); + return NULL; +} + +/* SetNewInClass */ +static int __Pyx_SetNewInClass(PyObject *ns, PyObject *name, PyObject *value) { +#ifdef __Pyx_CyFunction_USED + int ret; + if (__Pyx_CyFunction_Check(value)) { + PyObject *staticnew = PyStaticMethod_New(value); + if (unlikely(!staticnew)) return -1; + ret = __Pyx_SetNameInClass(ns, name, staticnew); + Py_DECREF(staticnew); + return ret; + } +#endif + return __Pyx_SetNameInClass(ns, name, value); +} + +/* CalculateMetaclass */ +static PyObject *__Pyx_CalculateMetaclass(PyTypeObject *metaclass, PyObject *bases) { + Py_ssize_t i, nbases; +#if CYTHON_ASSUME_SAFE_MACROS + nbases = PyTuple_GET_SIZE(bases); +#else + nbases = PyTuple_Size(bases); + if (nbases < 0) return NULL; +#endif + for (i=0; i < nbases; i++) { + PyTypeObject *tmptype; +#if CYTHON_ASSUME_SAFE_MACROS + PyObject *tmp = PyTuple_GET_ITEM(bases, i); +#else + PyObject *tmp = PyTuple_GetItem(bases, i); + if (!tmp) return NULL; +#endif + tmptype = Py_TYPE(tmp); +#if PY_MAJOR_VERSION < 3 + if (tmptype == &PyClass_Type) + continue; +#endif + if (!metaclass) { + metaclass = tmptype; + continue; + } + if (PyType_IsSubtype(metaclass, tmptype)) + continue; + if (PyType_IsSubtype(tmptype, metaclass)) { + metaclass = tmptype; + continue; + } + PyErr_SetString(PyExc_TypeError, + "metaclass conflict: " + "the metaclass of a derived class " + "must be a (non-strict) subclass " + "of the metaclasses of all its bases"); + return NULL; + } + if (!metaclass) { +#if PY_MAJOR_VERSION < 3 + metaclass = &PyClass_Type; +#else + metaclass = &PyType_Type; +#endif + } + Py_INCREF((PyObject*) metaclass); + return (PyObject*) metaclass; +} + +/* PyObjectLookupSpecial */ +#if CYTHON_USE_PYTYPE_LOOKUP && CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx__PyObject_LookupSpecial(PyObject* obj, PyObject* attr_name, int with_error) { + PyObject *res; + PyTypeObject *tp = Py_TYPE(obj); +#if PY_MAJOR_VERSION < 3 + if (unlikely(PyInstance_Check(obj))) + return with_error ? __Pyx_PyObject_GetAttrStr(obj, attr_name) : __Pyx_PyObject_GetAttrStrNoError(obj, attr_name); +#endif + res = _PyType_Lookup(tp, attr_name); + if (likely(res)) { + descrgetfunc f = Py_TYPE(res)->tp_descr_get; + if (!f) { + Py_INCREF(res); + } else { + res = f(res, obj, (PyObject *)tp); + } + } else if (with_error) { + PyErr_SetObject(PyExc_AttributeError, attr_name); + } + return res; +} +#endif + +/* Py3ClassCreate */ +static PyObject *__Pyx_Py3MetaclassPrepare(PyObject *metaclass, PyObject *bases, PyObject *name, + PyObject *qualname, PyObject *mkw, PyObject *modname, PyObject *doc) { + PyObject *ns; + if (metaclass) { + PyObject *prep = __Pyx_PyObject_GetAttrStrNoError(metaclass, __pyx_n_s_prepare); + if (prep) { + PyObject *pargs[3] = {NULL, name, bases}; + ns = __Pyx_PyObject_FastCallDict(prep, pargs+1, 2 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET, mkw); + Py_DECREF(prep); + } else { + if (unlikely(PyErr_Occurred())) + return NULL; + ns = PyDict_New(); + } + } else { + ns = PyDict_New(); + } + if (unlikely(!ns)) + return NULL; + if (unlikely(PyObject_SetItem(ns, __pyx_n_s_module, modname) < 0)) goto bad; +#if PY_VERSION_HEX >= 0x03030000 + if (unlikely(PyObject_SetItem(ns, __pyx_n_s_qualname, qualname) < 0)) goto bad; +#else + CYTHON_MAYBE_UNUSED_VAR(qualname); +#endif + if (unlikely(doc && PyObject_SetItem(ns, __pyx_n_s_doc, doc) < 0)) goto bad; + return ns; +bad: + Py_DECREF(ns); + return NULL; +} +#if PY_VERSION_HEX < 0x030600A4 && CYTHON_PEP487_INIT_SUBCLASS +static int __Pyx_SetNamesPEP487(PyObject *type_obj) { + PyTypeObject *type = (PyTypeObject*) type_obj; + PyObject *names_to_set, *key, *value, *set_name, *tmp; + Py_ssize_t i = 0; +#if CYTHON_USE_TYPE_SLOTS + names_to_set = PyDict_Copy(type->tp_dict); +#else + { + PyObject *d = PyObject_GetAttr(type_obj, __pyx_n_s_dict); + names_to_set = NULL; + if (likely(d)) { + PyObject *names_to_set = PyDict_New(); + int ret = likely(names_to_set) ? PyDict_Update(names_to_set, d) : -1; + Py_DECREF(d); + if (unlikely(ret < 0)) + Py_CLEAR(names_to_set); + } + } +#endif + if (unlikely(names_to_set == NULL)) + goto bad; + while (PyDict_Next(names_to_set, &i, &key, &value)) { + set_name = __Pyx_PyObject_LookupSpecialNoError(value, __pyx_n_s_set_name); + if (unlikely(set_name != NULL)) { + tmp = __Pyx_PyObject_Call2Args(set_name, type_obj, key); + Py_DECREF(set_name); + if (unlikely(tmp == NULL)) { + __Pyx_TypeName value_type_name = + __Pyx_PyType_GetName(Py_TYPE(value)); + __Pyx_TypeName type_name = __Pyx_PyType_GetName(type); + PyErr_Format(PyExc_RuntimeError, +#if PY_MAJOR_VERSION >= 3 + "Error calling __set_name__ on '" __Pyx_FMT_TYPENAME "' instance %R " "in '" __Pyx_FMT_TYPENAME "'", + value_type_name, key, type_name); +#else + "Error calling __set_name__ on '" __Pyx_FMT_TYPENAME "' instance %.100s in '" __Pyx_FMT_TYPENAME "'", + value_type_name, + PyString_Check(key) ? PyString_AS_STRING(key) : "?", + type_name); +#endif + goto bad; + } else { + Py_DECREF(tmp); + } + } + else if (unlikely(PyErr_Occurred())) { + goto bad; + } + } + Py_DECREF(names_to_set); + return 0; +bad: + Py_XDECREF(names_to_set); + return -1; +} +static PyObject *__Pyx_InitSubclassPEP487(PyObject *type_obj, PyObject *mkw) { +#if CYTHON_USE_TYPE_SLOTS && CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + PyTypeObject *type = (PyTypeObject*) type_obj; + PyObject *mro = type->tp_mro; + Py_ssize_t i, nbases; + if (unlikely(!mro)) goto done; + (void) &__Pyx_GetBuiltinName; + Py_INCREF(mro); + nbases = PyTuple_GET_SIZE(mro); + assert(PyTuple_GET_ITEM(mro, 0) == type_obj); + for (i = 1; i < nbases-1; i++) { + PyObject *base, *dict, *meth; + base = PyTuple_GET_ITEM(mro, i); + dict = ((PyTypeObject *)base)->tp_dict; + meth = __Pyx_PyDict_GetItemStrWithError(dict, __pyx_n_s_init_subclass); + if (unlikely(meth)) { + descrgetfunc f = Py_TYPE(meth)->tp_descr_get; + PyObject *res; + Py_INCREF(meth); + if (likely(f)) { + res = f(meth, NULL, type_obj); + Py_DECREF(meth); + if (unlikely(!res)) goto bad; + meth = res; + } + res = __Pyx_PyObject_FastCallDict(meth, NULL, 0, mkw); + Py_DECREF(meth); + if (unlikely(!res)) goto bad; + Py_DECREF(res); + goto done; + } else if (unlikely(PyErr_Occurred())) { + goto bad; + } + } +done: + Py_XDECREF(mro); + return type_obj; +bad: + Py_XDECREF(mro); + Py_DECREF(type_obj); + return NULL; +#else + PyObject *super_type, *super, *func, *res; +#if CYTHON_COMPILING_IN_PYPY && !defined(PySuper_Type) + super_type = __Pyx_GetBuiltinName(__pyx_n_s_super); +#else + super_type = (PyObject*) &PySuper_Type; + (void) &__Pyx_GetBuiltinName; +#endif + super = likely(super_type) ? __Pyx_PyObject_Call2Args(super_type, type_obj, type_obj) : NULL; +#if CYTHON_COMPILING_IN_PYPY && !defined(PySuper_Type) + Py_XDECREF(super_type); +#endif + if (unlikely(!super)) { + Py_CLEAR(type_obj); + goto done; + } + func = __Pyx_PyObject_GetAttrStrNoError(super, __pyx_n_s_init_subclass); + Py_DECREF(super); + if (likely(!func)) { + if (unlikely(PyErr_Occurred())) + Py_CLEAR(type_obj); + goto done; + } + res = __Pyx_PyObject_FastCallDict(func, NULL, 0, mkw); + Py_DECREF(func); + if (unlikely(!res)) + Py_CLEAR(type_obj); + Py_XDECREF(res); +done: + return type_obj; +#endif +} +#endif +static PyObject *__Pyx_Py3ClassCreate(PyObject *metaclass, PyObject *name, PyObject *bases, + PyObject *dict, PyObject *mkw, + int calculate_metaclass, int allow_py2_metaclass) { + PyObject *result; + PyObject *owned_metaclass = NULL; + PyObject *margs[4] = {NULL, name, bases, dict}; + if (allow_py2_metaclass) { + owned_metaclass = PyObject_GetItem(dict, __pyx_n_s_metaclass); + if (owned_metaclass) { + metaclass = owned_metaclass; + } else if (likely(PyErr_ExceptionMatches(PyExc_KeyError))) { + PyErr_Clear(); + } else { + return NULL; + } + } + if (calculate_metaclass && (!metaclass || PyType_Check(metaclass))) { + metaclass = __Pyx_CalculateMetaclass((PyTypeObject*) metaclass, bases); + Py_XDECREF(owned_metaclass); + if (unlikely(!metaclass)) + return NULL; + owned_metaclass = metaclass; + } + result = __Pyx_PyObject_FastCallDict(metaclass, margs+1, 3 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET, +#if PY_VERSION_HEX < 0x030600A4 + (metaclass == (PyObject*)&PyType_Type) ? NULL : mkw +#else + mkw +#endif + ); + Py_XDECREF(owned_metaclass); +#if PY_VERSION_HEX < 0x030600A4 && CYTHON_PEP487_INIT_SUBCLASS + if (likely(result) && likely(PyType_Check(result))) { + if (unlikely(__Pyx_SetNamesPEP487(result) < 0)) { + Py_CLEAR(result); + } else { + result = __Pyx_InitSubclassPEP487(result, mkw); + } + } +#else + (void) &__Pyx_GetBuiltinName; +#endif + return result; +} + +/* Globals */ +static PyObject* __Pyx_Globals(void) { + return __Pyx_NewRef(__pyx_d); +} + +/* UnpackUnboundCMethod */ +static PyObject *__Pyx_SelflessCall(PyObject *method, PyObject *args, PyObject *kwargs) { + PyObject *result; + PyObject *selfless_args = PyTuple_GetSlice(args, 1, PyTuple_Size(args)); + if (unlikely(!selfless_args)) return NULL; + result = PyObject_Call(method, selfless_args, kwargs); + Py_DECREF(selfless_args); + return result; +} +static PyMethodDef __Pyx_UnboundCMethod_Def = { + "CythonUnboundCMethod", + __PYX_REINTERPRET_FUNCION(PyCFunction, __Pyx_SelflessCall), + METH_VARARGS | METH_KEYWORDS, + NULL +}; +static int __Pyx_TryUnpackUnboundCMethod(__Pyx_CachedCFunction* target) { + PyObject *method; + method = __Pyx_PyObject_GetAttrStr(target->type, *target->method_name); + if (unlikely(!method)) + return -1; + target->method = method; +#if CYTHON_COMPILING_IN_CPYTHON + #if PY_MAJOR_VERSION >= 3 + if (likely(__Pyx_TypeCheck(method, &PyMethodDescr_Type))) + #else + if (likely(!__Pyx_CyOrPyCFunction_Check(method))) + #endif + { + PyMethodDescrObject *descr = (PyMethodDescrObject*) method; + target->func = descr->d_method->ml_meth; + target->flag = descr->d_method->ml_flags & ~(METH_CLASS | METH_STATIC | METH_COEXIST | METH_STACKLESS); + } else +#endif +#if CYTHON_COMPILING_IN_PYPY +#else + if (PyCFunction_Check(method)) +#endif + { + PyObject *self; + int self_found; +#if CYTHON_COMPILING_IN_LIMITED_API || CYTHON_COMPILING_IN_PYPY + self = PyObject_GetAttrString(method, "__self__"); + if (!self) { + PyErr_Clear(); + } +#else + self = PyCFunction_GET_SELF(method); +#endif + self_found = (self && self != Py_None); +#if CYTHON_COMPILING_IN_LIMITED_API || CYTHON_COMPILING_IN_PYPY + Py_XDECREF(self); +#endif + if (self_found) { + PyObject *unbound_method = PyCFunction_New(&__Pyx_UnboundCMethod_Def, method); + if (unlikely(!unbound_method)) return -1; + Py_DECREF(method); + target->method = unbound_method; + } + } + return 0; +} + +/* CallUnboundCMethod1 */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_CallUnboundCMethod1(__Pyx_CachedCFunction* cfunc, PyObject* self, PyObject* arg) { + if (likely(cfunc->func)) { + int flag = cfunc->flag; + if (flag == METH_O) { + return (*(cfunc->func))(self, arg); + } else if ((PY_VERSION_HEX >= 0x030600B1) && flag == METH_FASTCALL) { + #if PY_VERSION_HEX >= 0x030700A0 + return (*(__Pyx_PyCFunctionFast)(void*)(PyCFunction)cfunc->func)(self, &arg, 1); + #else + return (*(__Pyx_PyCFunctionFastWithKeywords)(void*)(PyCFunction)cfunc->func)(self, &arg, 1, NULL); + #endif + } else if ((PY_VERSION_HEX >= 0x030700A0) && flag == (METH_FASTCALL | METH_KEYWORDS)) { + return (*(__Pyx_PyCFunctionFastWithKeywords)(void*)(PyCFunction)cfunc->func)(self, &arg, 1, NULL); + } + } + return __Pyx__CallUnboundCMethod1(cfunc, self, arg); +} +#endif +static PyObject* __Pyx__CallUnboundCMethod1(__Pyx_CachedCFunction* cfunc, PyObject* self, PyObject* arg){ + PyObject *args, *result = NULL; + if (unlikely(!cfunc->func && !cfunc->method) && unlikely(__Pyx_TryUnpackUnboundCMethod(cfunc) < 0)) return NULL; +#if CYTHON_COMPILING_IN_CPYTHON + if (cfunc->func && (cfunc->flag & METH_VARARGS)) { + args = PyTuple_New(1); + if (unlikely(!args)) goto bad; + Py_INCREF(arg); + PyTuple_SET_ITEM(args, 0, arg); + if (cfunc->flag & METH_KEYWORDS) + result = (*(PyCFunctionWithKeywords)(void*)(PyCFunction)cfunc->func)(self, args, NULL); + else + result = (*cfunc->func)(self, args); + } else { + args = PyTuple_New(2); + if (unlikely(!args)) goto bad; + Py_INCREF(self); + PyTuple_SET_ITEM(args, 0, self); + Py_INCREF(arg); + PyTuple_SET_ITEM(args, 1, arg); + result = __Pyx_PyObject_Call(cfunc->method, args, NULL); + } +#else + args = PyTuple_Pack(2, self, arg); + if (unlikely(!args)) goto bad; + result = __Pyx_PyObject_Call(cfunc->method, args, NULL); +#endif +bad: + Py_XDECREF(args); + return result; +} + +/* CallUnboundCMethod2 */ +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030600B1 +static CYTHON_INLINE PyObject *__Pyx_CallUnboundCMethod2(__Pyx_CachedCFunction *cfunc, PyObject *self, PyObject *arg1, PyObject *arg2) { + if (likely(cfunc->func)) { + PyObject *args[2] = {arg1, arg2}; + if (cfunc->flag == METH_FASTCALL) { + #if PY_VERSION_HEX >= 0x030700A0 + return (*(__Pyx_PyCFunctionFast)(void*)(PyCFunction)cfunc->func)(self, args, 2); + #else + return (*(__Pyx_PyCFunctionFastWithKeywords)(void*)(PyCFunction)cfunc->func)(self, args, 2, NULL); + #endif + } + #if PY_VERSION_HEX >= 0x030700A0 + if (cfunc->flag == (METH_FASTCALL | METH_KEYWORDS)) + return (*(__Pyx_PyCFunctionFastWithKeywords)(void*)(PyCFunction)cfunc->func)(self, args, 2, NULL); + #endif + } + return __Pyx__CallUnboundCMethod2(cfunc, self, arg1, arg2); +} +#endif +static PyObject* __Pyx__CallUnboundCMethod2(__Pyx_CachedCFunction* cfunc, PyObject* self, PyObject* arg1, PyObject* arg2){ + PyObject *args, *result = NULL; + if (unlikely(!cfunc->func && !cfunc->method) && unlikely(__Pyx_TryUnpackUnboundCMethod(cfunc) < 0)) return NULL; +#if CYTHON_COMPILING_IN_CPYTHON + if (cfunc->func && (cfunc->flag & METH_VARARGS)) { + args = PyTuple_New(2); + if (unlikely(!args)) goto bad; + Py_INCREF(arg1); + PyTuple_SET_ITEM(args, 0, arg1); + Py_INCREF(arg2); + PyTuple_SET_ITEM(args, 1, arg2); + if (cfunc->flag & METH_KEYWORDS) + result = (*(PyCFunctionWithKeywords)(void*)(PyCFunction)cfunc->func)(self, args, NULL); + else + result = (*cfunc->func)(self, args); + } else { + args = PyTuple_New(3); + if (unlikely(!args)) goto bad; + Py_INCREF(self); + PyTuple_SET_ITEM(args, 0, self); + Py_INCREF(arg1); + PyTuple_SET_ITEM(args, 1, arg1); + Py_INCREF(arg2); + PyTuple_SET_ITEM(args, 2, arg2); + result = __Pyx_PyObject_Call(cfunc->method, args, NULL); + } +#else + args = PyTuple_Pack(3, self, arg1, arg2); + if (unlikely(!args)) goto bad; + result = __Pyx_PyObject_Call(cfunc->method, args, NULL); +#endif +bad: + Py_XDECREF(args); + return result; +} + +/* dict_getitem_default */ +static PyObject* __Pyx_PyDict_GetItemDefault(PyObject* d, PyObject* key, PyObject* default_value) { + PyObject* value; +#if PY_MAJOR_VERSION >= 3 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07020000) + value = PyDict_GetItemWithError(d, key); + if (unlikely(!value)) { + if (unlikely(PyErr_Occurred())) + return NULL; + value = default_value; + } + Py_INCREF(value); + if ((1)); +#else + if (PyString_CheckExact(key) || PyUnicode_CheckExact(key) || PyInt_CheckExact(key)) { + value = PyDict_GetItem(d, key); + if (unlikely(!value)) { + value = default_value; + } + Py_INCREF(value); + } +#endif + else { + if (default_value == Py_None) + value = __Pyx_CallUnboundCMethod1(&__pyx_umethod_PyDict_Type_get, d, key); + else + value = __Pyx_CallUnboundCMethod2(&__pyx_umethod_PyDict_Type_get, d, key, default_value); + } + return value; +} + +/* GetNameInClass */ +static PyObject *__Pyx__GetNameInClass(PyObject *nmspace, PyObject *name) { + PyObject *result; + PyObject *dict; + assert(PyType_Check(nmspace)); +#if CYTHON_USE_TYPE_SLOTS + dict = ((PyTypeObject*)nmspace)->tp_dict; + Py_XINCREF(dict); +#else + dict = PyObject_GetAttr(nmspace, __pyx_n_s_dict); +#endif + if (likely(dict)) { + result = PyObject_GetItem(dict, name); + Py_DECREF(dict); + if (result) { + return result; + } + } + PyErr_Clear(); + __Pyx_GetModuleGlobalNameUncached(result, name); + return result; +} + +/* CLineInTraceback */ +#ifndef CYTHON_CLINE_IN_TRACEBACK +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line) { + PyObject *use_cline; + PyObject *ptype, *pvalue, *ptraceback; +#if CYTHON_COMPILING_IN_CPYTHON + PyObject **cython_runtime_dict; +#endif + CYTHON_MAYBE_UNUSED_VAR(tstate); + if (unlikely(!__pyx_cython_runtime)) { + return c_line; + } + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); +#if CYTHON_COMPILING_IN_CPYTHON + cython_runtime_dict = _PyObject_GetDictPtr(__pyx_cython_runtime); + if (likely(cython_runtime_dict)) { + __PYX_PY_DICT_LOOKUP_IF_MODIFIED( + use_cline, *cython_runtime_dict, + __Pyx_PyDict_GetItemStr(*cython_runtime_dict, __pyx_n_s_cline_in_traceback)) + } else +#endif + { + PyObject *use_cline_obj = __Pyx_PyObject_GetAttrStrNoError(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback); + if (use_cline_obj) { + use_cline = PyObject_Not(use_cline_obj) ? Py_False : Py_True; + Py_DECREF(use_cline_obj); + } else { + PyErr_Clear(); + use_cline = NULL; + } + } + if (!use_cline) { + c_line = 0; + (void) PyObject_SetAttr(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback, Py_False); + } + else if (use_cline == Py_False || (use_cline != Py_True && PyObject_Not(use_cline) != 0)) { + c_line = 0; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + return c_line; +} +#endif + +/* CodeObjectCache */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line) { + int start = 0, mid = 0, end = count - 1; + if (end >= 0 && code_line > entries[end].code_line) { + return count; + } + while (start < end) { + mid = start + (end - start) / 2; + if (code_line < entries[mid].code_line) { + end = mid; + } else if (code_line > entries[mid].code_line) { + start = mid + 1; + } else { + return mid; + } + } + if (code_line <= entries[mid].code_line) { + return mid; + } else { + return mid + 1; + } +} +static PyCodeObject *__pyx_find_code_object(int code_line) { + PyCodeObject* code_object; + int pos; + if (unlikely(!code_line) || unlikely(!__pyx_code_cache.entries)) { + return NULL; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if (unlikely(pos >= __pyx_code_cache.count) || unlikely(__pyx_code_cache.entries[pos].code_line != code_line)) { + return NULL; + } + code_object = __pyx_code_cache.entries[pos].code_object; + Py_INCREF(code_object); + return code_object; +} +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object) { + int pos, i; + __Pyx_CodeObjectCacheEntry* entries = __pyx_code_cache.entries; + if (unlikely(!code_line)) { + return; + } + if (unlikely(!entries)) { + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Malloc(64*sizeof(__Pyx_CodeObjectCacheEntry)); + if (likely(entries)) { + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = 64; + __pyx_code_cache.count = 1; + entries[0].code_line = code_line; + entries[0].code_object = code_object; + Py_INCREF(code_object); + } + return; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if ((pos < __pyx_code_cache.count) && unlikely(__pyx_code_cache.entries[pos].code_line == code_line)) { + PyCodeObject* tmp = entries[pos].code_object; + entries[pos].code_object = code_object; + Py_DECREF(tmp); + return; + } + if (__pyx_code_cache.count == __pyx_code_cache.max_count) { + int new_max = __pyx_code_cache.max_count + 64; + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Realloc( + __pyx_code_cache.entries, ((size_t)new_max) * sizeof(__Pyx_CodeObjectCacheEntry)); + if (unlikely(!entries)) { + return; + } + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = new_max; + } + for (i=__pyx_code_cache.count; i>pos; i--) { + entries[i] = entries[i-1]; + } + entries[pos].code_line = code_line; + entries[pos].code_object = code_object; + __pyx_code_cache.count++; + Py_INCREF(code_object); +} +#endif + +/* AddTraceback */ +#include "compile.h" +#include "frameobject.h" +#include "traceback.h" +#if PY_VERSION_HEX >= 0x030b00a6 && !CYTHON_COMPILING_IN_LIMITED_API + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static PyObject *__Pyx_PyCode_Replace_For_AddTraceback(PyObject *code, PyObject *scratch_dict, + PyObject *firstlineno, PyObject *name) { + PyObject *replace = NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "co_firstlineno", firstlineno))) return NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "co_name", name))) return NULL; + replace = PyObject_GetAttrString(code, "replace"); + if (likely(replace)) { + PyObject *result; + result = PyObject_Call(replace, __pyx_empty_tuple, scratch_dict); + Py_DECREF(replace); + return result; + } + PyErr_Clear(); + #if __PYX_LIMITED_VERSION_HEX < 0x030780000 + { + PyObject *compiled = NULL, *result = NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "code", code))) return NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "type", (PyObject*)(&PyType_Type)))) return NULL; + compiled = Py_CompileString( + "out = type(code)(\n" + " code.co_argcount, code.co_kwonlyargcount, code.co_nlocals, code.co_stacksize,\n" + " code.co_flags, code.co_code, code.co_consts, code.co_names,\n" + " code.co_varnames, code.co_filename, co_name, co_firstlineno,\n" + " code.co_lnotab)\n", "", Py_file_input); + if (!compiled) return NULL; + result = PyEval_EvalCode(compiled, scratch_dict, scratch_dict); + Py_DECREF(compiled); + if (!result) PyErr_Print(); + Py_DECREF(result); + result = PyDict_GetItemString(scratch_dict, "out"); + if (result) Py_INCREF(result); + return result; + } + #else + return NULL; + #endif +} +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + PyObject *code_object = NULL, *py_py_line = NULL, *py_funcname = NULL, *dict = NULL; + PyObject *replace = NULL, *getframe = NULL, *frame = NULL; + PyObject *exc_type, *exc_value, *exc_traceback; + int success = 0; + if (c_line) { + (void) __pyx_cfilenm; + (void) __Pyx_CLineForTraceback(__Pyx_PyThreadState_Current, c_line); + } + PyErr_Fetch(&exc_type, &exc_value, &exc_traceback); + code_object = Py_CompileString("_getframe()", filename, Py_eval_input); + if (unlikely(!code_object)) goto bad; + py_py_line = PyLong_FromLong(py_line); + if (unlikely(!py_py_line)) goto bad; + py_funcname = PyUnicode_FromString(funcname); + if (unlikely(!py_funcname)) goto bad; + dict = PyDict_New(); + if (unlikely(!dict)) goto bad; + { + PyObject *old_code_object = code_object; + code_object = __Pyx_PyCode_Replace_For_AddTraceback(code_object, dict, py_py_line, py_funcname); + Py_DECREF(old_code_object); + } + if (unlikely(!code_object)) goto bad; + getframe = PySys_GetObject("_getframe"); + if (unlikely(!getframe)) goto bad; + if (unlikely(PyDict_SetItemString(dict, "_getframe", getframe))) goto bad; + frame = PyEval_EvalCode(code_object, dict, dict); + if (unlikely(!frame) || frame == Py_None) goto bad; + success = 1; + bad: + PyErr_Restore(exc_type, exc_value, exc_traceback); + Py_XDECREF(code_object); + Py_XDECREF(py_py_line); + Py_XDECREF(py_funcname); + Py_XDECREF(dict); + Py_XDECREF(replace); + if (success) { + PyTraceBack_Here( + (struct _frame*)frame); + } + Py_XDECREF(frame); +} +#else +static PyCodeObject* __Pyx_CreateCodeObjectForTraceback( + const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = NULL; + PyObject *py_funcname = NULL; + #if PY_MAJOR_VERSION < 3 + PyObject *py_srcfile = NULL; + py_srcfile = PyString_FromString(filename); + if (!py_srcfile) goto bad; + #endif + if (c_line) { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + #else + py_funcname = PyUnicode_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + funcname = PyUnicode_AsUTF8(py_funcname); + if (!funcname) goto bad; + #endif + } + else { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromString(funcname); + if (!py_funcname) goto bad; + #endif + } + #if PY_MAJOR_VERSION < 3 + py_code = __Pyx_PyCode_New( + 0, + 0, + 0, + 0, + 0, + 0, + __pyx_empty_bytes, /*PyObject *code,*/ + __pyx_empty_tuple, /*PyObject *consts,*/ + __pyx_empty_tuple, /*PyObject *names,*/ + __pyx_empty_tuple, /*PyObject *varnames,*/ + __pyx_empty_tuple, /*PyObject *freevars,*/ + __pyx_empty_tuple, /*PyObject *cellvars,*/ + py_srcfile, /*PyObject *filename,*/ + py_funcname, /*PyObject *name,*/ + py_line, + __pyx_empty_bytes /*PyObject *lnotab*/ + ); + Py_DECREF(py_srcfile); + #else + py_code = PyCode_NewEmpty(filename, funcname, py_line); + #endif + Py_XDECREF(py_funcname); + return py_code; +bad: + Py_XDECREF(py_funcname); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_srcfile); + #endif + return NULL; +} +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = 0; + PyFrameObject *py_frame = 0; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject *ptype, *pvalue, *ptraceback; + if (c_line) { + c_line = __Pyx_CLineForTraceback(tstate, c_line); + } + py_code = __pyx_find_code_object(c_line ? -c_line : py_line); + if (!py_code) { + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); + py_code = __Pyx_CreateCodeObjectForTraceback( + funcname, c_line, py_line, filename); + if (!py_code) { + /* If the code object creation fails, then we should clear the + fetched exception references and propagate the new exception */ + Py_XDECREF(ptype); + Py_XDECREF(pvalue); + Py_XDECREF(ptraceback); + goto bad; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + __pyx_insert_code_object(c_line ? -c_line : py_line, py_code); + } + py_frame = PyFrame_New( + tstate, /*PyThreadState *tstate,*/ + py_code, /*PyCodeObject *code,*/ + __pyx_d, /*PyObject *globals,*/ + 0 /*PyObject *locals*/ + ); + if (!py_frame) goto bad; + __Pyx_PyFrame_SetLineNumber(py_frame, py_line); + PyTraceBack_Here(py_frame); +bad: + Py_XDECREF(py_code); + Py_XDECREF(py_frame); +} +#endif + +#if PY_MAJOR_VERSION < 3 +static int __Pyx_GetBuffer(PyObject *obj, Py_buffer *view, int flags) { + __Pyx_TypeName obj_type_name; + if (PyObject_CheckBuffer(obj)) return PyObject_GetBuffer(obj, view, flags); + if (__Pyx_TypeCheck(obj, __pyx_array_type)) return __pyx_array_getbuffer(obj, view, flags); + if (__Pyx_TypeCheck(obj, __pyx_memoryview_type)) return __pyx_memoryview_getbuffer(obj, view, flags); + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "'" __Pyx_FMT_TYPENAME "' does not have the buffer interface", + obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return -1; +} +static void __Pyx_ReleaseBuffer(Py_buffer *view) { + PyObject *obj = view->obj; + if (!obj) return; + if (PyObject_CheckBuffer(obj)) { + PyBuffer_Release(view); + return; + } + if ((0)) {} + view->obj = NULL; + Py_DECREF(obj); +} +#endif + + +/* MemviewSliceIsContig */ +static int +__pyx_memviewslice_is_contig(const __Pyx_memviewslice mvs, char order, int ndim) +{ + int i, index, step, start; + Py_ssize_t itemsize = mvs.memview->view.itemsize; + if (order == 'F') { + step = 1; + start = 0; + } else { + step = -1; + start = ndim - 1; + } + for (i = 0; i < ndim; i++) { + index = start + step * i; + if (mvs.suboffsets[index] >= 0 || mvs.strides[index] != itemsize) + return 0; + itemsize *= mvs.shape[index]; + } + return 1; +} + +/* OverlappingSlices */ +static void +__pyx_get_array_memory_extents(__Pyx_memviewslice *slice, + void **out_start, void **out_end, + int ndim, size_t itemsize) +{ + char *start, *end; + int i; + start = end = slice->data; + for (i = 0; i < ndim; i++) { + Py_ssize_t stride = slice->strides[i]; + Py_ssize_t extent = slice->shape[i]; + if (extent == 0) { + *out_start = *out_end = start; + return; + } else { + if (stride > 0) + end += stride * (extent - 1); + else + start += stride * (extent - 1); + } + } + *out_start = start; + *out_end = end + itemsize; +} +static int +__pyx_slices_overlap(__Pyx_memviewslice *slice1, + __Pyx_memviewslice *slice2, + int ndim, size_t itemsize) +{ + void *start1, *end1, *start2, *end2; + __pyx_get_array_memory_extents(slice1, &start1, &end1, ndim, itemsize); + __pyx_get_array_memory_extents(slice2, &start2, &end2, ndim, itemsize); + return (start1 < end2) && (start2 < end1); +} + +/* CIntFromPyVerify */ +#define __PYX_VERIFY_RETURN_INT(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 0) +#define __PYX_VERIFY_RETURN_INT_EXC(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 1) +#define __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, exc)\ + {\ + func_type value = func_value;\ + if (sizeof(target_type) < sizeof(func_type)) {\ + if (unlikely(value != (func_type) (target_type) value)) {\ + func_type zero = 0;\ + if (exc && unlikely(value == (func_type)-1 && PyErr_Occurred()))\ + return (target_type) -1;\ + if (is_unsigned && unlikely(value < zero))\ + goto raise_neg_overflow;\ + else\ + goto raise_overflow;\ + }\ + }\ + return (target_type) value;\ + } + +/* IsLittleEndian */ +static CYTHON_INLINE int __Pyx_Is_Little_Endian(void) +{ + union { + uint32_t u32; + uint8_t u8[4]; + } S; + S.u32 = 0x01020304; + return S.u8[0] == 4; +} + +/* BufferFormatCheck */ +static void __Pyx_BufFmt_Init(__Pyx_BufFmt_Context* ctx, + __Pyx_BufFmt_StackElem* stack, + __Pyx_TypeInfo* type) { + stack[0].field = &ctx->root; + stack[0].parent_offset = 0; + ctx->root.type = type; + ctx->root.name = "buffer dtype"; + ctx->root.offset = 0; + ctx->head = stack; + ctx->head->field = &ctx->root; + ctx->fmt_offset = 0; + ctx->head->parent_offset = 0; + ctx->new_packmode = '@'; + ctx->enc_packmode = '@'; + ctx->new_count = 1; + ctx->enc_count = 0; + ctx->enc_type = 0; + ctx->is_complex = 0; + ctx->is_valid_array = 0; + ctx->struct_alignment = 0; + while (type->typegroup == 'S') { + ++ctx->head; + ctx->head->field = type->fields; + ctx->head->parent_offset = 0; + type = type->fields->type; + } +} +static int __Pyx_BufFmt_ParseNumber(const char** ts) { + int count; + const char* t = *ts; + if (*t < '0' || *t > '9') { + return -1; + } else { + count = *t++ - '0'; + while (*t >= '0' && *t <= '9') { + count *= 10; + count += *t++ - '0'; + } + } + *ts = t; + return count; +} +static int __Pyx_BufFmt_ExpectNumber(const char **ts) { + int number = __Pyx_BufFmt_ParseNumber(ts); + if (number == -1) + PyErr_Format(PyExc_ValueError,\ + "Does not understand character buffer dtype format string ('%c')", **ts); + return number; +} +static void __Pyx_BufFmt_RaiseUnexpectedChar(char ch) { + PyErr_Format(PyExc_ValueError, + "Unexpected format string character: '%c'", ch); +} +static const char* __Pyx_BufFmt_DescribeTypeChar(char ch, int is_complex) { + switch (ch) { + case '?': return "'bool'"; + case 'c': return "'char'"; + case 'b': return "'signed char'"; + case 'B': return "'unsigned char'"; + case 'h': return "'short'"; + case 'H': return "'unsigned short'"; + case 'i': return "'int'"; + case 'I': return "'unsigned int'"; + case 'l': return "'long'"; + case 'L': return "'unsigned long'"; + case 'q': return "'long long'"; + case 'Q': return "'unsigned long long'"; + case 'f': return (is_complex ? "'complex float'" : "'float'"); + case 'd': return (is_complex ? "'complex double'" : "'double'"); + case 'g': return (is_complex ? "'complex long double'" : "'long double'"); + case 'T': return "a struct"; + case 'O': return "Python object"; + case 'P': return "a pointer"; + case 's': case 'p': return "a string"; + case 0: return "end"; + default: return "unparsable format string"; + } +} +static size_t __Pyx_BufFmt_TypeCharToStandardSize(char ch, int is_complex) { + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return 2; + case 'i': case 'I': case 'l': case 'L': return 4; + case 'q': case 'Q': return 8; + case 'f': return (is_complex ? 8 : 4); + case 'd': return (is_complex ? 16 : 8); + case 'g': { + PyErr_SetString(PyExc_ValueError, "Python does not define a standard format string size for long double ('g').."); + return 0; + } + case 'O': case 'P': return sizeof(void*); + default: + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } +} +static size_t __Pyx_BufFmt_TypeCharToNativeSize(char ch, int is_complex) { + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return sizeof(short); + case 'i': case 'I': return sizeof(int); + case 'l': case 'L': return sizeof(long); + #ifdef HAVE_LONG_LONG + case 'q': case 'Q': return sizeof(PY_LONG_LONG); + #endif + case 'f': return sizeof(float) * (is_complex ? 2 : 1); + case 'd': return sizeof(double) * (is_complex ? 2 : 1); + case 'g': return sizeof(long double) * (is_complex ? 2 : 1); + case 'O': case 'P': return sizeof(void*); + default: { + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } + } +} +typedef struct { char c; short x; } __Pyx_st_short; +typedef struct { char c; int x; } __Pyx_st_int; +typedef struct { char c; long x; } __Pyx_st_long; +typedef struct { char c; float x; } __Pyx_st_float; +typedef struct { char c; double x; } __Pyx_st_double; +typedef struct { char c; long double x; } __Pyx_st_longdouble; +typedef struct { char c; void *x; } __Pyx_st_void_p; +#ifdef HAVE_LONG_LONG +typedef struct { char c; PY_LONG_LONG x; } __Pyx_st_longlong; +#endif +static size_t __Pyx_BufFmt_TypeCharToAlignment(char ch, int is_complex) { + CYTHON_UNUSED_VAR(is_complex); + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return sizeof(__Pyx_st_short) - sizeof(short); + case 'i': case 'I': return sizeof(__Pyx_st_int) - sizeof(int); + case 'l': case 'L': return sizeof(__Pyx_st_long) - sizeof(long); +#ifdef HAVE_LONG_LONG + case 'q': case 'Q': return sizeof(__Pyx_st_longlong) - sizeof(PY_LONG_LONG); +#endif + case 'f': return sizeof(__Pyx_st_float) - sizeof(float); + case 'd': return sizeof(__Pyx_st_double) - sizeof(double); + case 'g': return sizeof(__Pyx_st_longdouble) - sizeof(long double); + case 'P': case 'O': return sizeof(__Pyx_st_void_p) - sizeof(void*); + default: + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } +} +/* These are for computing the padding at the end of the struct to align + on the first member of the struct. This will probably the same as above, + but we don't have any guarantees. + */ +typedef struct { short x; char c; } __Pyx_pad_short; +typedef struct { int x; char c; } __Pyx_pad_int; +typedef struct { long x; char c; } __Pyx_pad_long; +typedef struct { float x; char c; } __Pyx_pad_float; +typedef struct { double x; char c; } __Pyx_pad_double; +typedef struct { long double x; char c; } __Pyx_pad_longdouble; +typedef struct { void *x; char c; } __Pyx_pad_void_p; +#ifdef HAVE_LONG_LONG +typedef struct { PY_LONG_LONG x; char c; } __Pyx_pad_longlong; +#endif +static size_t __Pyx_BufFmt_TypeCharToPadding(char ch, int is_complex) { + CYTHON_UNUSED_VAR(is_complex); + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return sizeof(__Pyx_pad_short) - sizeof(short); + case 'i': case 'I': return sizeof(__Pyx_pad_int) - sizeof(int); + case 'l': case 'L': return sizeof(__Pyx_pad_long) - sizeof(long); +#ifdef HAVE_LONG_LONG + case 'q': case 'Q': return sizeof(__Pyx_pad_longlong) - sizeof(PY_LONG_LONG); +#endif + case 'f': return sizeof(__Pyx_pad_float) - sizeof(float); + case 'd': return sizeof(__Pyx_pad_double) - sizeof(double); + case 'g': return sizeof(__Pyx_pad_longdouble) - sizeof(long double); + case 'P': case 'O': return sizeof(__Pyx_pad_void_p) - sizeof(void*); + default: + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } +} +static char __Pyx_BufFmt_TypeCharToGroup(char ch, int is_complex) { + switch (ch) { + case 'c': + return 'H'; + case 'b': case 'h': case 'i': + case 'l': case 'q': case 's': case 'p': + return 'I'; + case '?': case 'B': case 'H': case 'I': case 'L': case 'Q': + return 'U'; + case 'f': case 'd': case 'g': + return (is_complex ? 'C' : 'R'); + case 'O': + return 'O'; + case 'P': + return 'P'; + default: { + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } + } +} +static void __Pyx_BufFmt_RaiseExpected(__Pyx_BufFmt_Context* ctx) { + if (ctx->head == NULL || ctx->head->field == &ctx->root) { + const char* expected; + const char* quote; + if (ctx->head == NULL) { + expected = "end"; + quote = ""; + } else { + expected = ctx->head->field->type->name; + quote = "'"; + } + PyErr_Format(PyExc_ValueError, + "Buffer dtype mismatch, expected %s%s%s but got %s", + quote, expected, quote, + __Pyx_BufFmt_DescribeTypeChar(ctx->enc_type, ctx->is_complex)); + } else { + __Pyx_StructField* field = ctx->head->field; + __Pyx_StructField* parent = (ctx->head - 1)->field; + PyErr_Format(PyExc_ValueError, + "Buffer dtype mismatch, expected '%s' but got %s in '%s.%s'", + field->type->name, __Pyx_BufFmt_DescribeTypeChar(ctx->enc_type, ctx->is_complex), + parent->type->name, field->name); + } +} +static int __Pyx_BufFmt_ProcessTypeChunk(__Pyx_BufFmt_Context* ctx) { + char group; + size_t size, offset, arraysize = 1; + if (ctx->enc_type == 0) return 0; + if (ctx->head->field->type->arraysize[0]) { + int i, ndim = 0; + if (ctx->enc_type == 's' || ctx->enc_type == 'p') { + ctx->is_valid_array = ctx->head->field->type->ndim == 1; + ndim = 1; + if (ctx->enc_count != ctx->head->field->type->arraysize[0]) { + PyErr_Format(PyExc_ValueError, + "Expected a dimension of size %zu, got %zu", + ctx->head->field->type->arraysize[0], ctx->enc_count); + return -1; + } + } + if (!ctx->is_valid_array) { + PyErr_Format(PyExc_ValueError, "Expected %d dimensions, got %d", + ctx->head->field->type->ndim, ndim); + return -1; + } + for (i = 0; i < ctx->head->field->type->ndim; i++) { + arraysize *= ctx->head->field->type->arraysize[i]; + } + ctx->is_valid_array = 0; + ctx->enc_count = 1; + } + group = __Pyx_BufFmt_TypeCharToGroup(ctx->enc_type, ctx->is_complex); + do { + __Pyx_StructField* field = ctx->head->field; + __Pyx_TypeInfo* type = field->type; + if (ctx->enc_packmode == '@' || ctx->enc_packmode == '^') { + size = __Pyx_BufFmt_TypeCharToNativeSize(ctx->enc_type, ctx->is_complex); + } else { + size = __Pyx_BufFmt_TypeCharToStandardSize(ctx->enc_type, ctx->is_complex); + } + if (ctx->enc_packmode == '@') { + size_t align_at = __Pyx_BufFmt_TypeCharToAlignment(ctx->enc_type, ctx->is_complex); + size_t align_mod_offset; + if (align_at == 0) return -1; + align_mod_offset = ctx->fmt_offset % align_at; + if (align_mod_offset > 0) ctx->fmt_offset += align_at - align_mod_offset; + if (ctx->struct_alignment == 0) + ctx->struct_alignment = __Pyx_BufFmt_TypeCharToPadding(ctx->enc_type, + ctx->is_complex); + } + if (type->size != size || type->typegroup != group) { + if (type->typegroup == 'C' && type->fields != NULL) { + size_t parent_offset = ctx->head->parent_offset + field->offset; + ++ctx->head; + ctx->head->field = type->fields; + ctx->head->parent_offset = parent_offset; + continue; + } + if ((type->typegroup == 'H' || group == 'H') && type->size == size) { + } else { + __Pyx_BufFmt_RaiseExpected(ctx); + return -1; + } + } + offset = ctx->head->parent_offset + field->offset; + if (ctx->fmt_offset != offset) { + PyErr_Format(PyExc_ValueError, + "Buffer dtype mismatch; next field is at offset %" CYTHON_FORMAT_SSIZE_T "d but %" CYTHON_FORMAT_SSIZE_T "d expected", + (Py_ssize_t)ctx->fmt_offset, (Py_ssize_t)offset); + return -1; + } + ctx->fmt_offset += size; + if (arraysize) + ctx->fmt_offset += (arraysize - 1) * size; + --ctx->enc_count; + while (1) { + if (field == &ctx->root) { + ctx->head = NULL; + if (ctx->enc_count != 0) { + __Pyx_BufFmt_RaiseExpected(ctx); + return -1; + } + break; + } + ctx->head->field = ++field; + if (field->type == NULL) { + --ctx->head; + field = ctx->head->field; + continue; + } else if (field->type->typegroup == 'S') { + size_t parent_offset = ctx->head->parent_offset + field->offset; + if (field->type->fields->type == NULL) continue; + field = field->type->fields; + ++ctx->head; + ctx->head->field = field; + ctx->head->parent_offset = parent_offset; + break; + } else { + break; + } + } + } while (ctx->enc_count); + ctx->enc_type = 0; + ctx->is_complex = 0; + return 0; +} +static int +__pyx_buffmt_parse_array(__Pyx_BufFmt_Context* ctx, const char** tsp) +{ + const char *ts = *tsp; + int i = 0, number, ndim; + ++ts; + if (ctx->new_count != 1) { + PyErr_SetString(PyExc_ValueError, + "Cannot handle repeated arrays in format string"); + return -1; + } + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return -1; + ndim = ctx->head->field->type->ndim; + while (*ts && *ts != ')') { + switch (*ts) { + case ' ': case '\f': case '\r': case '\n': case '\t': case '\v': continue; + default: break; + } + number = __Pyx_BufFmt_ExpectNumber(&ts); + if (number == -1) return -1; + if (i < ndim && (size_t) number != ctx->head->field->type->arraysize[i]) { + PyErr_Format(PyExc_ValueError, + "Expected a dimension of size %zu, got %d", + ctx->head->field->type->arraysize[i], number); + return -1; + } + if (*ts != ',' && *ts != ')') { + PyErr_Format(PyExc_ValueError, + "Expected a comma in format string, got '%c'", *ts); + return -1; + } + if (*ts == ',') ts++; + i++; + } + if (i != ndim) { + PyErr_Format(PyExc_ValueError, "Expected %d dimension(s), got %d", + ctx->head->field->type->ndim, i); + return -1; + } + if (!*ts) { + PyErr_SetString(PyExc_ValueError, + "Unexpected end of format string, expected ')'"); + return -1; + } + ctx->is_valid_array = 1; + ctx->new_count = 1; + *tsp = ++ts; + return 0; +} +static const char* __Pyx_BufFmt_CheckString(__Pyx_BufFmt_Context* ctx, const char* ts) { + int got_Z = 0; + while (1) { + switch(*ts) { + case 0: + if (ctx->enc_type != 0 && ctx->head == NULL) { + __Pyx_BufFmt_RaiseExpected(ctx); + return NULL; + } + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + if (ctx->head != NULL) { + __Pyx_BufFmt_RaiseExpected(ctx); + return NULL; + } + return ts; + case ' ': + case '\r': + case '\n': + ++ts; + break; + case '<': + if (!__Pyx_Is_Little_Endian()) { + PyErr_SetString(PyExc_ValueError, "Little-endian buffer not supported on big-endian compiler"); + return NULL; + } + ctx->new_packmode = '='; + ++ts; + break; + case '>': + case '!': + if (__Pyx_Is_Little_Endian()) { + PyErr_SetString(PyExc_ValueError, "Big-endian buffer not supported on little-endian compiler"); + return NULL; + } + ctx->new_packmode = '='; + ++ts; + break; + case '=': + case '@': + case '^': + ctx->new_packmode = *ts++; + break; + case 'T': + { + const char* ts_after_sub; + size_t i, struct_count = ctx->new_count; + size_t struct_alignment = ctx->struct_alignment; + ctx->new_count = 1; + ++ts; + if (*ts != '{') { + PyErr_SetString(PyExc_ValueError, "Buffer acquisition: Expected '{' after 'T'"); + return NULL; + } + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->enc_type = 0; + ctx->enc_count = 0; + ctx->struct_alignment = 0; + ++ts; + ts_after_sub = ts; + for (i = 0; i != struct_count; ++i) { + ts_after_sub = __Pyx_BufFmt_CheckString(ctx, ts); + if (!ts_after_sub) return NULL; + } + ts = ts_after_sub; + if (struct_alignment) ctx->struct_alignment = struct_alignment; + } + break; + case '}': + { + size_t alignment = ctx->struct_alignment; + ++ts; + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->enc_type = 0; + if (alignment && ctx->fmt_offset % alignment) { + ctx->fmt_offset += alignment - (ctx->fmt_offset % alignment); + } + } + return ts; + case 'x': + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->fmt_offset += ctx->new_count; + ctx->new_count = 1; + ctx->enc_count = 0; + ctx->enc_type = 0; + ctx->enc_packmode = ctx->new_packmode; + ++ts; + break; + case 'Z': + got_Z = 1; + ++ts; + if (*ts != 'f' && *ts != 'd' && *ts != 'g') { + __Pyx_BufFmt_RaiseUnexpectedChar('Z'); + return NULL; + } + CYTHON_FALLTHROUGH; + case '?': case 'c': case 'b': case 'B': case 'h': case 'H': case 'i': case 'I': + case 'l': case 'L': case 'q': case 'Q': + case 'f': case 'd': case 'g': + case 'O': case 'p': + if ((ctx->enc_type == *ts) && (got_Z == ctx->is_complex) && + (ctx->enc_packmode == ctx->new_packmode) && (!ctx->is_valid_array)) { + ctx->enc_count += ctx->new_count; + ctx->new_count = 1; + got_Z = 0; + ++ts; + break; + } + CYTHON_FALLTHROUGH; + case 's': + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->enc_count = ctx->new_count; + ctx->enc_packmode = ctx->new_packmode; + ctx->enc_type = *ts; + ctx->is_complex = got_Z; + ++ts; + ctx->new_count = 1; + got_Z = 0; + break; + case ':': + ++ts; + while(*ts != ':') ++ts; + ++ts; + break; + case '(': + if (__pyx_buffmt_parse_array(ctx, &ts) < 0) return NULL; + break; + default: + { + int number = __Pyx_BufFmt_ExpectNumber(&ts); + if (number == -1) return NULL; + ctx->new_count = (size_t)number; + } + } + } +} + +/* TypeInfoCompare */ + static int +__pyx_typeinfo_cmp(__Pyx_TypeInfo *a, __Pyx_TypeInfo *b) +{ + int i; + if (!a || !b) + return 0; + if (a == b) + return 1; + if (a->size != b->size || a->typegroup != b->typegroup || + a->is_unsigned != b->is_unsigned || a->ndim != b->ndim) { + if (a->typegroup == 'H' || b->typegroup == 'H') { + return a->size == b->size; + } else { + return 0; + } + } + if (a->ndim) { + for (i = 0; i < a->ndim; i++) + if (a->arraysize[i] != b->arraysize[i]) + return 0; + } + if (a->typegroup == 'S') { + if (a->flags != b->flags) + return 0; + if (a->fields || b->fields) { + if (!(a->fields && b->fields)) + return 0; + for (i = 0; a->fields[i].type && b->fields[i].type; i++) { + __Pyx_StructField *field_a = a->fields + i; + __Pyx_StructField *field_b = b->fields + i; + if (field_a->offset != field_b->offset || + !__pyx_typeinfo_cmp(field_a->type, field_b->type)) + return 0; + } + return !a->fields[i].type && !b->fields[i].type; + } + } + return 1; +} + +/* MemviewSliceValidateAndInit */ + static int +__pyx_check_strides(Py_buffer *buf, int dim, int ndim, int spec) +{ + if (buf->shape[dim] <= 1) + return 1; + if (buf->strides) { + if (spec & __Pyx_MEMVIEW_CONTIG) { + if (spec & (__Pyx_MEMVIEW_PTR|__Pyx_MEMVIEW_FULL)) { + if (unlikely(buf->strides[dim] != sizeof(void *))) { + PyErr_Format(PyExc_ValueError, + "Buffer is not indirectly contiguous " + "in dimension %d.", dim); + goto fail; + } + } else if (unlikely(buf->strides[dim] != buf->itemsize)) { + PyErr_SetString(PyExc_ValueError, + "Buffer and memoryview are not contiguous " + "in the same dimension."); + goto fail; + } + } + if (spec & __Pyx_MEMVIEW_FOLLOW) { + Py_ssize_t stride = buf->strides[dim]; + if (stride < 0) + stride = -stride; + if (unlikely(stride < buf->itemsize)) { + PyErr_SetString(PyExc_ValueError, + "Buffer and memoryview are not contiguous " + "in the same dimension."); + goto fail; + } + } + } else { + if (unlikely(spec & __Pyx_MEMVIEW_CONTIG && dim != ndim - 1)) { + PyErr_Format(PyExc_ValueError, + "C-contiguous buffer is not contiguous in " + "dimension %d", dim); + goto fail; + } else if (unlikely(spec & (__Pyx_MEMVIEW_PTR))) { + PyErr_Format(PyExc_ValueError, + "C-contiguous buffer is not indirect in " + "dimension %d", dim); + goto fail; + } else if (unlikely(buf->suboffsets)) { + PyErr_SetString(PyExc_ValueError, + "Buffer exposes suboffsets but no strides"); + goto fail; + } + } + return 1; +fail: + return 0; +} +static int +__pyx_check_suboffsets(Py_buffer *buf, int dim, int ndim, int spec) +{ + CYTHON_UNUSED_VAR(ndim); + if (spec & __Pyx_MEMVIEW_DIRECT) { + if (unlikely(buf->suboffsets && buf->suboffsets[dim] >= 0)) { + PyErr_Format(PyExc_ValueError, + "Buffer not compatible with direct access " + "in dimension %d.", dim); + goto fail; + } + } + if (spec & __Pyx_MEMVIEW_PTR) { + if (unlikely(!buf->suboffsets || (buf->suboffsets[dim] < 0))) { + PyErr_Format(PyExc_ValueError, + "Buffer is not indirectly accessible " + "in dimension %d.", dim); + goto fail; + } + } + return 1; +fail: + return 0; +} +static int +__pyx_verify_contig(Py_buffer *buf, int ndim, int c_or_f_flag) +{ + int i; + if (c_or_f_flag & __Pyx_IS_F_CONTIG) { + Py_ssize_t stride = 1; + for (i = 0; i < ndim; i++) { + if (unlikely(stride * buf->itemsize != buf->strides[i] && buf->shape[i] > 1)) { + PyErr_SetString(PyExc_ValueError, + "Buffer not fortran contiguous."); + goto fail; + } + stride = stride * buf->shape[i]; + } + } else if (c_or_f_flag & __Pyx_IS_C_CONTIG) { + Py_ssize_t stride = 1; + for (i = ndim - 1; i >- 1; i--) { + if (unlikely(stride * buf->itemsize != buf->strides[i] && buf->shape[i] > 1)) { + PyErr_SetString(PyExc_ValueError, + "Buffer not C contiguous."); + goto fail; + } + stride = stride * buf->shape[i]; + } + } + return 1; +fail: + return 0; +} +static int __Pyx_ValidateAndInit_memviewslice( + int *axes_specs, + int c_or_f_flag, + int buf_flags, + int ndim, + __Pyx_TypeInfo *dtype, + __Pyx_BufFmt_StackElem stack[], + __Pyx_memviewslice *memviewslice, + PyObject *original_obj) +{ + struct __pyx_memoryview_obj *memview, *new_memview; + __Pyx_RefNannyDeclarations + Py_buffer *buf; + int i, spec = 0, retval = -1; + __Pyx_BufFmt_Context ctx; + int from_memoryview = __pyx_memoryview_check(original_obj); + __Pyx_RefNannySetupContext("ValidateAndInit_memviewslice", 0); + if (from_memoryview && __pyx_typeinfo_cmp(dtype, ((struct __pyx_memoryview_obj *) + original_obj)->typeinfo)) { + memview = (struct __pyx_memoryview_obj *) original_obj; + new_memview = NULL; + } else { + memview = (struct __pyx_memoryview_obj *) __pyx_memoryview_new( + original_obj, buf_flags, 0, dtype); + new_memview = memview; + if (unlikely(!memview)) + goto fail; + } + buf = &memview->view; + if (unlikely(buf->ndim != ndim)) { + PyErr_Format(PyExc_ValueError, + "Buffer has wrong number of dimensions (expected %d, got %d)", + ndim, buf->ndim); + goto fail; + } + if (new_memview) { + __Pyx_BufFmt_Init(&ctx, stack, dtype); + if (unlikely(!__Pyx_BufFmt_CheckString(&ctx, buf->format))) goto fail; + } + if (unlikely((unsigned) buf->itemsize != dtype->size)) { + PyErr_Format(PyExc_ValueError, + "Item size of buffer (%" CYTHON_FORMAT_SSIZE_T "u byte%s) " + "does not match size of '%s' (%" CYTHON_FORMAT_SSIZE_T "u byte%s)", + buf->itemsize, + (buf->itemsize > 1) ? "s" : "", + dtype->name, + dtype->size, + (dtype->size > 1) ? "s" : ""); + goto fail; + } + if (buf->len > 0) { + for (i = 0; i < ndim; i++) { + spec = axes_specs[i]; + if (unlikely(!__pyx_check_strides(buf, i, ndim, spec))) + goto fail; + if (unlikely(!__pyx_check_suboffsets(buf, i, ndim, spec))) + goto fail; + } + if (unlikely(buf->strides && !__pyx_verify_contig(buf, ndim, c_or_f_flag))) + goto fail; + } + if (unlikely(__Pyx_init_memviewslice(memview, ndim, memviewslice, + new_memview != NULL) == -1)) { + goto fail; + } + retval = 0; + goto no_fail; +fail: + Py_XDECREF(new_memview); + retval = -1; +no_fail: + __Pyx_RefNannyFinishContext(); + return retval; +} + +/* ObjectToMemviewSlice */ + static CYTHON_INLINE __Pyx_memviewslice __Pyx_PyObject_to_MemoryviewSlice_ds_unsigned_char__const__(PyObject *obj, int writable_flag) { + __Pyx_memviewslice result = { 0, 0, { 0 }, { 0 }, { 0 } }; + __Pyx_BufFmt_StackElem stack[1]; + int axes_specs[] = { (__Pyx_MEMVIEW_DIRECT | __Pyx_MEMVIEW_STRIDED) }; + int retcode; + if (obj == Py_None) { + result.memview = (struct __pyx_memoryview_obj *) Py_None; + return result; + } + retcode = __Pyx_ValidateAndInit_memviewslice(axes_specs, 0, + PyBUF_RECORDS_RO | writable_flag, 1, + &__Pyx_TypeInfo_unsigned_char__const__, stack, + &result, obj); + if (unlikely(retcode == -1)) + goto __pyx_fail; + return result; +__pyx_fail: + result.memview = NULL; + result.data = NULL; + return result; +} + +/* MemviewDtypeToObject */ + static CYTHON_INLINE PyObject *__pyx_memview_get_nn___pyx_t_5numpy_uint8_t(const char *itemp) { + return (PyObject *) __Pyx_PyInt_From_npy_uint8(*(__pyx_t_5numpy_uint8_t *) itemp); +} +static CYTHON_INLINE int __pyx_memview_set_nn___pyx_t_5numpy_uint8_t(const char *itemp, PyObject *obj) { + __pyx_t_5numpy_uint8_t value = __Pyx_PyInt_As_npy_uint8(obj); + if (unlikely((value == ((npy_uint8)-1)) && PyErr_Occurred())) + return 0; + *(__pyx_t_5numpy_uint8_t *) itemp = value; + return 1; +} + +/* MemviewDtypeToObject */ + static CYTHON_INLINE PyObject *__pyx_memview_get_unsigned_char__const__(const char *itemp) { + return (PyObject *) __Pyx_PyInt_From_unsigned_char(*(unsigned char const *) itemp); +} + +/* Declarations */ + #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #ifdef __cplusplus + static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float x, float y) { + return ::std::complex< float >(x, y); + } + #else + static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float x, float y) { + return x + y*(__pyx_t_float_complex)_Complex_I; + } + #endif +#else + static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float x, float y) { + __pyx_t_float_complex z; + z.real = x; + z.imag = y; + return z; + } +#endif + +/* Arithmetic */ + #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) +#else + static CYTHON_INLINE int __Pyx_c_eq_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + return (a.real == b.real) && (a.imag == b.imag); + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_sum_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + __pyx_t_float_complex z; + z.real = a.real + b.real; + z.imag = a.imag + b.imag; + return z; + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_diff_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + __pyx_t_float_complex z; + z.real = a.real - b.real; + z.imag = a.imag - b.imag; + return z; + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_prod_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + __pyx_t_float_complex z; + z.real = a.real * b.real - a.imag * b.imag; + z.imag = a.real * b.imag + a.imag * b.real; + return z; + } + #if 1 + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_quot_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + if (b.imag == 0) { + return __pyx_t_float_complex_from_parts(a.real / b.real, a.imag / b.real); + } else if (fabsf(b.real) >= fabsf(b.imag)) { + if (b.real == 0 && b.imag == 0) { + return __pyx_t_float_complex_from_parts(a.real / b.real, a.imag / b.imag); + } else { + float r = b.imag / b.real; + float s = (float)(1.0) / (b.real + b.imag * r); + return __pyx_t_float_complex_from_parts( + (a.real + a.imag * r) * s, (a.imag - a.real * r) * s); + } + } else { + float r = b.real / b.imag; + float s = (float)(1.0) / (b.imag + b.real * r); + return __pyx_t_float_complex_from_parts( + (a.real * r + a.imag) * s, (a.imag * r - a.real) * s); + } + } + #else + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_quot_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + if (b.imag == 0) { + return __pyx_t_float_complex_from_parts(a.real / b.real, a.imag / b.real); + } else { + float denom = b.real * b.real + b.imag * b.imag; + return __pyx_t_float_complex_from_parts( + (a.real * b.real + a.imag * b.imag) / denom, + (a.imag * b.real - a.real * b.imag) / denom); + } + } + #endif + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_neg_float(__pyx_t_float_complex a) { + __pyx_t_float_complex z; + z.real = -a.real; + z.imag = -a.imag; + return z; + } + static CYTHON_INLINE int __Pyx_c_is_zero_float(__pyx_t_float_complex a) { + return (a.real == 0) && (a.imag == 0); + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_conj_float(__pyx_t_float_complex a) { + __pyx_t_float_complex z; + z.real = a.real; + z.imag = -a.imag; + return z; + } + #if 1 + static CYTHON_INLINE float __Pyx_c_abs_float(__pyx_t_float_complex z) { + #if !defined(HAVE_HYPOT) || defined(_MSC_VER) + return sqrtf(z.real*z.real + z.imag*z.imag); + #else + return hypotf(z.real, z.imag); + #endif + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_pow_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + __pyx_t_float_complex z; + float r, lnr, theta, z_r, z_theta; + if (b.imag == 0 && b.real == (int)b.real) { + if (b.real < 0) { + float denom = a.real * a.real + a.imag * a.imag; + a.real = a.real / denom; + a.imag = -a.imag / denom; + b.real = -b.real; + } + switch ((int)b.real) { + case 0: + z.real = 1; + z.imag = 0; + return z; + case 1: + return a; + case 2: + return __Pyx_c_prod_float(a, a); + case 3: + z = __Pyx_c_prod_float(a, a); + return __Pyx_c_prod_float(z, a); + case 4: + z = __Pyx_c_prod_float(a, a); + return __Pyx_c_prod_float(z, z); + } + } + if (a.imag == 0) { + if (a.real == 0) { + return a; + } else if ((b.imag == 0) && (a.real >= 0)) { + z.real = powf(a.real, b.real); + z.imag = 0; + return z; + } else if (a.real > 0) { + r = a.real; + theta = 0; + } else { + r = -a.real; + theta = atan2f(0.0, -1.0); + } + } else { + r = __Pyx_c_abs_float(a); + theta = atan2f(a.imag, a.real); + } + lnr = logf(r); + z_r = expf(lnr * b.real - theta * b.imag); + z_theta = theta * b.real + lnr * b.imag; + z.real = z_r * cosf(z_theta); + z.imag = z_r * sinf(z_theta); + return z; + } + #endif +#endif + +/* Declarations */ + #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #ifdef __cplusplus + static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double x, double y) { + return ::std::complex< double >(x, y); + } + #else + static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double x, double y) { + return x + y*(__pyx_t_double_complex)_Complex_I; + } + #endif +#else + static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double x, double y) { + __pyx_t_double_complex z; + z.real = x; + z.imag = y; + return z; + } +#endif + +/* Arithmetic */ + #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) +#else + static CYTHON_INLINE int __Pyx_c_eq_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + return (a.real == b.real) && (a.imag == b.imag); + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_sum_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + __pyx_t_double_complex z; + z.real = a.real + b.real; + z.imag = a.imag + b.imag; + return z; + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_diff_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + __pyx_t_double_complex z; + z.real = a.real - b.real; + z.imag = a.imag - b.imag; + return z; + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_prod_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + __pyx_t_double_complex z; + z.real = a.real * b.real - a.imag * b.imag; + z.imag = a.real * b.imag + a.imag * b.real; + return z; + } + #if 1 + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_quot_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + if (b.imag == 0) { + return __pyx_t_double_complex_from_parts(a.real / b.real, a.imag / b.real); + } else if (fabs(b.real) >= fabs(b.imag)) { + if (b.real == 0 && b.imag == 0) { + return __pyx_t_double_complex_from_parts(a.real / b.real, a.imag / b.imag); + } else { + double r = b.imag / b.real; + double s = (double)(1.0) / (b.real + b.imag * r); + return __pyx_t_double_complex_from_parts( + (a.real + a.imag * r) * s, (a.imag - a.real * r) * s); + } + } else { + double r = b.real / b.imag; + double s = (double)(1.0) / (b.imag + b.real * r); + return __pyx_t_double_complex_from_parts( + (a.real * r + a.imag) * s, (a.imag * r - a.real) * s); + } + } + #else + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_quot_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + if (b.imag == 0) { + return __pyx_t_double_complex_from_parts(a.real / b.real, a.imag / b.real); + } else { + double denom = b.real * b.real + b.imag * b.imag; + return __pyx_t_double_complex_from_parts( + (a.real * b.real + a.imag * b.imag) / denom, + (a.imag * b.real - a.real * b.imag) / denom); + } + } + #endif + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_neg_double(__pyx_t_double_complex a) { + __pyx_t_double_complex z; + z.real = -a.real; + z.imag = -a.imag; + return z; + } + static CYTHON_INLINE int __Pyx_c_is_zero_double(__pyx_t_double_complex a) { + return (a.real == 0) && (a.imag == 0); + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_conj_double(__pyx_t_double_complex a) { + __pyx_t_double_complex z; + z.real = a.real; + z.imag = -a.imag; + return z; + } + #if 1 + static CYTHON_INLINE double __Pyx_c_abs_double(__pyx_t_double_complex z) { + #if !defined(HAVE_HYPOT) || defined(_MSC_VER) + return sqrt(z.real*z.real + z.imag*z.imag); + #else + return hypot(z.real, z.imag); + #endif + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_pow_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + __pyx_t_double_complex z; + double r, lnr, theta, z_r, z_theta; + if (b.imag == 0 && b.real == (int)b.real) { + if (b.real < 0) { + double denom = a.real * a.real + a.imag * a.imag; + a.real = a.real / denom; + a.imag = -a.imag / denom; + b.real = -b.real; + } + switch ((int)b.real) { + case 0: + z.real = 1; + z.imag = 0; + return z; + case 1: + return a; + case 2: + return __Pyx_c_prod_double(a, a); + case 3: + z = __Pyx_c_prod_double(a, a); + return __Pyx_c_prod_double(z, a); + case 4: + z = __Pyx_c_prod_double(a, a); + return __Pyx_c_prod_double(z, z); + } + } + if (a.imag == 0) { + if (a.real == 0) { + return a; + } else if ((b.imag == 0) && (a.real >= 0)) { + z.real = pow(a.real, b.real); + z.imag = 0; + return z; + } else if (a.real > 0) { + r = a.real; + theta = 0; + } else { + r = -a.real; + theta = atan2(0.0, -1.0); + } + } else { + r = __Pyx_c_abs_double(a); + theta = atan2(a.imag, a.real); + } + lnr = log(r); + z_r = exp(lnr * b.real - theta * b.imag); + z_theta = theta * b.real + lnr * b.imag; + z.real = z_r * cos(z_theta); + z.imag = z_r * sin(z_theta); + return z; + } + #endif +#endif + +/* MemviewSliceCopyTemplate */ + static __Pyx_memviewslice +__pyx_memoryview_copy_new_contig(const __Pyx_memviewslice *from_mvs, + const char *mode, int ndim, + size_t sizeof_dtype, int contig_flag, + int dtype_is_object) +{ + __Pyx_RefNannyDeclarations + int i; + __Pyx_memviewslice new_mvs = { 0, 0, { 0 }, { 0 }, { 0 } }; + struct __pyx_memoryview_obj *from_memview = from_mvs->memview; + Py_buffer *buf = &from_memview->view; + PyObject *shape_tuple = NULL; + PyObject *temp_int = NULL; + struct __pyx_array_obj *array_obj = NULL; + struct __pyx_memoryview_obj *memview_obj = NULL; + __Pyx_RefNannySetupContext("__pyx_memoryview_copy_new_contig", 0); + for (i = 0; i < ndim; i++) { + if (unlikely(from_mvs->suboffsets[i] >= 0)) { + PyErr_Format(PyExc_ValueError, "Cannot copy memoryview slice with " + "indirect dimensions (axis %d)", i); + goto fail; + } + } + shape_tuple = PyTuple_New(ndim); + if (unlikely(!shape_tuple)) { + goto fail; + } + __Pyx_GOTREF(shape_tuple); + for(i = 0; i < ndim; i++) { + temp_int = PyInt_FromSsize_t(from_mvs->shape[i]); + if(unlikely(!temp_int)) { + goto fail; + } else { + PyTuple_SET_ITEM(shape_tuple, i, temp_int); + temp_int = NULL; + } + } + array_obj = __pyx_array_new(shape_tuple, sizeof_dtype, buf->format, (char *) mode, NULL); + if (unlikely(!array_obj)) { + goto fail; + } + __Pyx_GOTREF(array_obj); + memview_obj = (struct __pyx_memoryview_obj *) __pyx_memoryview_new( + (PyObject *) array_obj, contig_flag, + dtype_is_object, + from_mvs->memview->typeinfo); + if (unlikely(!memview_obj)) + goto fail; + if (unlikely(__Pyx_init_memviewslice(memview_obj, ndim, &new_mvs, 1) < 0)) + goto fail; + if (unlikely(__pyx_memoryview_copy_contents(*from_mvs, new_mvs, ndim, ndim, + dtype_is_object) < 0)) + goto fail; + goto no_fail; +fail: + __Pyx_XDECREF(new_mvs.memview); + new_mvs.memview = NULL; + new_mvs.data = NULL; +no_fail: + __Pyx_XDECREF(shape_tuple); + __Pyx_XDECREF(temp_int); + __Pyx_XDECREF(array_obj); + __Pyx_RefNannyFinishContext(); + return new_mvs; +} + +/* MemviewSliceInit */ + static int +__Pyx_init_memviewslice(struct __pyx_memoryview_obj *memview, + int ndim, + __Pyx_memviewslice *memviewslice, + int memview_is_new_reference) +{ + __Pyx_RefNannyDeclarations + int i, retval=-1; + Py_buffer *buf = &memview->view; + __Pyx_RefNannySetupContext("init_memviewslice", 0); + if (unlikely(memviewslice->memview || memviewslice->data)) { + PyErr_SetString(PyExc_ValueError, + "memviewslice is already initialized!"); + goto fail; + } + if (buf->strides) { + for (i = 0; i < ndim; i++) { + memviewslice->strides[i] = buf->strides[i]; + } + } else { + Py_ssize_t stride = buf->itemsize; + for (i = ndim - 1; i >= 0; i--) { + memviewslice->strides[i] = stride; + stride *= buf->shape[i]; + } + } + for (i = 0; i < ndim; i++) { + memviewslice->shape[i] = buf->shape[i]; + if (buf->suboffsets) { + memviewslice->suboffsets[i] = buf->suboffsets[i]; + } else { + memviewslice->suboffsets[i] = -1; + } + } + memviewslice->memview = memview; + memviewslice->data = (char *)buf->buf; + if (__pyx_add_acquisition_count(memview) == 0 && !memview_is_new_reference) { + Py_INCREF(memview); + } + retval = 0; + goto no_fail; +fail: + memviewslice->memview = 0; + memviewslice->data = 0; + retval = -1; +no_fail: + __Pyx_RefNannyFinishContext(); + return retval; +} +#ifndef Py_NO_RETURN +#define Py_NO_RETURN +#endif +static void __pyx_fatalerror(const char *fmt, ...) Py_NO_RETURN { + va_list vargs; + char msg[200]; +#if PY_VERSION_HEX >= 0x030A0000 || defined(HAVE_STDARG_PROTOTYPES) + va_start(vargs, fmt); +#else + va_start(vargs); +#endif + vsnprintf(msg, 200, fmt, vargs); + va_end(vargs); + Py_FatalError(msg); +} +static CYTHON_INLINE int +__pyx_add_acquisition_count_locked(__pyx_atomic_int_type *acquisition_count, + PyThread_type_lock lock) +{ + int result; + PyThread_acquire_lock(lock, 1); + result = (*acquisition_count)++; + PyThread_release_lock(lock); + return result; +} +static CYTHON_INLINE int +__pyx_sub_acquisition_count_locked(__pyx_atomic_int_type *acquisition_count, + PyThread_type_lock lock) +{ + int result; + PyThread_acquire_lock(lock, 1); + result = (*acquisition_count)--; + PyThread_release_lock(lock); + return result; +} +static CYTHON_INLINE void +__Pyx_INC_MEMVIEW(__Pyx_memviewslice *memslice, int have_gil, int lineno) +{ + __pyx_nonatomic_int_type old_acquisition_count; + struct __pyx_memoryview_obj *memview = memslice->memview; + if (unlikely(!memview || (PyObject *) memview == Py_None)) { + return; + } + old_acquisition_count = __pyx_add_acquisition_count(memview); + if (unlikely(old_acquisition_count <= 0)) { + if (likely(old_acquisition_count == 0)) { + if (have_gil) { + Py_INCREF((PyObject *) memview); + } else { + PyGILState_STATE _gilstate = PyGILState_Ensure(); + Py_INCREF((PyObject *) memview); + PyGILState_Release(_gilstate); + } + } else { + __pyx_fatalerror("Acquisition count is %d (line %d)", + old_acquisition_count+1, lineno); + } + } +} +static CYTHON_INLINE void __Pyx_XCLEAR_MEMVIEW(__Pyx_memviewslice *memslice, + int have_gil, int lineno) { + __pyx_nonatomic_int_type old_acquisition_count; + struct __pyx_memoryview_obj *memview = memslice->memview; + if (unlikely(!memview || (PyObject *) memview == Py_None)) { + memslice->memview = NULL; + return; + } + old_acquisition_count = __pyx_sub_acquisition_count(memview); + memslice->data = NULL; + if (likely(old_acquisition_count > 1)) { + memslice->memview = NULL; + } else if (likely(old_acquisition_count == 1)) { + if (have_gil) { + Py_CLEAR(memslice->memview); + } else { + PyGILState_STATE _gilstate = PyGILState_Ensure(); + Py_CLEAR(memslice->memview); + PyGILState_Release(_gilstate); + } + } else { + __pyx_fatalerror("Acquisition count is %d (line %d)", + old_acquisition_count-1, lineno); + } +} + +/* TypeInfoToFormat */ + static struct __pyx_typeinfo_string __Pyx_TypeInfoToFormat(__Pyx_TypeInfo *type) { + struct __pyx_typeinfo_string result = { {0} }; + char *buf = (char *) result.string; + size_t size = type->size; + switch (type->typegroup) { + case 'H': + *buf = 'c'; + break; + case 'I': + case 'U': + if (size == 1) + *buf = (type->is_unsigned) ? 'B' : 'b'; + else if (size == 2) + *buf = (type->is_unsigned) ? 'H' : 'h'; + else if (size == 4) + *buf = (type->is_unsigned) ? 'I' : 'i'; + else if (size == 8) + *buf = (type->is_unsigned) ? 'Q' : 'q'; + break; + case 'P': + *buf = 'P'; + break; + case 'C': + { + __Pyx_TypeInfo complex_type = *type; + complex_type.typegroup = 'R'; + complex_type.size /= 2; + *buf++ = 'Z'; + *buf = __Pyx_TypeInfoToFormat(&complex_type).string[0]; + break; + } + case 'R': + if (size == 4) + *buf = 'f'; + else if (size == 8) + *buf = 'd'; + else + *buf = 'g'; + break; + } + return result; +} + +/* CIntFromPy */ + static CYTHON_INLINE enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType __Pyx_PyInt_As_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType neg_one = (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) -1, const_zero = (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) >= 2 * PyLong_SHIFT)) { + return (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) (((((enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[1]) << PyLong_SHIFT) | (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) >= 3 * PyLong_SHIFT)) { + return (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) (((((((enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[2]) << PyLong_SHIFT) | (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[1]) << PyLong_SHIFT) | (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) >= 4 * PyLong_SHIFT)) { + return (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) (((((((((enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[3]) << PyLong_SHIFT) | (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[2]) << PyLong_SHIFT) | (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[1]) << PyLong_SHIFT) | (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) - 1 > 2 * PyLong_SHIFT)) { + return (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) (((enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)-1)*(((((enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[1]) << PyLong_SHIFT) | (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) - 1 > 2 * PyLong_SHIFT)) { + return (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) ((((((enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[1]) << PyLong_SHIFT) | (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) - 1 > 3 * PyLong_SHIFT)) { + return (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) (((enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)-1)*(((((((enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[2]) << PyLong_SHIFT) | (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[1]) << PyLong_SHIFT) | (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) - 1 > 3 * PyLong_SHIFT)) { + return (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) ((((((((enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[2]) << PyLong_SHIFT) | (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[1]) << PyLong_SHIFT) | (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) - 1 > 4 * PyLong_SHIFT)) { + return (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) (((enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)-1)*(((((((((enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[3]) << PyLong_SHIFT) | (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[2]) << PyLong_SHIFT) | (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[1]) << PyLong_SHIFT) | (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) - 1 > 4 * PyLong_SHIFT)) { + return (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) ((((((((((enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[3]) << PyLong_SHIFT) | (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[2]) << PyLong_SHIFT) | (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[1]) << PyLong_SHIFT) | (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + PyErr_SetString(PyExc_RuntimeError, + "_PyLong_AsByteArray() not available, cannot convert large enums"); + return (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) -1; + } else { + enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) -1; + val = __Pyx_PyInt_As_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType"); + return (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType"); + return (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) -1; +} + +/* CIntFromPy */ + static CYTHON_INLINE size_t __Pyx_PyInt_As_size_t(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const size_t neg_one = (size_t) -1, const_zero = (size_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(size_t) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(size_t, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (size_t) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(size_t, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(size_t) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) >= 2 * PyLong_SHIFT)) { + return (size_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(size_t) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) >= 3 * PyLong_SHIFT)) { + return (size_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(size_t) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) >= 4 * PyLong_SHIFT)) { + return (size_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (size_t) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(size_t) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(size_t) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(size_t, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(size_t) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 2 * PyLong_SHIFT)) { + return (size_t) (((size_t)-1)*(((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(size_t) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 2 * PyLong_SHIFT)) { + return (size_t) ((((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(size_t) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 3 * PyLong_SHIFT)) { + return (size_t) (((size_t)-1)*(((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(size_t) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 3 * PyLong_SHIFT)) { + return (size_t) ((((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(size_t) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 4 * PyLong_SHIFT)) { + return (size_t) (((size_t)-1)*(((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(size_t) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 4 * PyLong_SHIFT)) { + return (size_t) ((((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(size_t) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(size_t) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + size_t val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (size_t) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (size_t) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (size_t) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (size_t) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (size_t) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(size_t) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((size_t) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(size_t) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((size_t) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((size_t) 1) << (sizeof(size_t) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (size_t) -1; + } + } else { + size_t val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (size_t) -1; + val = __Pyx_PyInt_As_size_t(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to size_t"); + return (size_t) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to size_t"); + return (size_t) -1; +} + +/* CIntFromPy */ + static CYTHON_INLINE uint32_t __Pyx_PyInt_As_uint32_t(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const uint32_t neg_one = (uint32_t) -1, const_zero = (uint32_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(uint32_t) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(uint32_t, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (uint32_t) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(uint32_t, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(uint32_t) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) >= 2 * PyLong_SHIFT)) { + return (uint32_t) (((((uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(uint32_t) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) >= 3 * PyLong_SHIFT)) { + return (uint32_t) (((((((uint32_t)digits[2]) << PyLong_SHIFT) | (uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(uint32_t) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) >= 4 * PyLong_SHIFT)) { + return (uint32_t) (((((((((uint32_t)digits[3]) << PyLong_SHIFT) | (uint32_t)digits[2]) << PyLong_SHIFT) | (uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (uint32_t) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(uint32_t) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(uint32_t, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(uint32_t) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(uint32_t, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(uint32_t, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(uint32_t) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) - 1 > 2 * PyLong_SHIFT)) { + return (uint32_t) (((uint32_t)-1)*(((((uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(uint32_t) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) - 1 > 2 * PyLong_SHIFT)) { + return (uint32_t) ((((((uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(uint32_t) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) - 1 > 3 * PyLong_SHIFT)) { + return (uint32_t) (((uint32_t)-1)*(((((((uint32_t)digits[2]) << PyLong_SHIFT) | (uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(uint32_t) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) - 1 > 3 * PyLong_SHIFT)) { + return (uint32_t) ((((((((uint32_t)digits[2]) << PyLong_SHIFT) | (uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(uint32_t) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) - 1 > 4 * PyLong_SHIFT)) { + return (uint32_t) (((uint32_t)-1)*(((((((((uint32_t)digits[3]) << PyLong_SHIFT) | (uint32_t)digits[2]) << PyLong_SHIFT) | (uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(uint32_t) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) - 1 > 4 * PyLong_SHIFT)) { + return (uint32_t) ((((((((((uint32_t)digits[3]) << PyLong_SHIFT) | (uint32_t)digits[2]) << PyLong_SHIFT) | (uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(uint32_t) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(uint32_t, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(uint32_t) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(uint32_t, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + uint32_t val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (uint32_t) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (uint32_t) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (uint32_t) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (uint32_t) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (uint32_t) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(uint32_t) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((uint32_t) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(uint32_t) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((uint32_t) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((uint32_t) 1) << (sizeof(uint32_t) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (uint32_t) -1; + } + } else { + uint32_t val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (uint32_t) -1; + val = __Pyx_PyInt_As_uint32_t(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to uint32_t"); + return (uint32_t) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to uint32_t"); + return (uint32_t) -1; +} + +/* CIntFromPy */ + static CYTHON_INLINE uint64_t __Pyx_PyInt_As_uint64_t(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const uint64_t neg_one = (uint64_t) -1, const_zero = (uint64_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(uint64_t) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(uint64_t, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (uint64_t) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(uint64_t, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(uint64_t) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint64_t, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint64_t) >= 2 * PyLong_SHIFT)) { + return (uint64_t) (((((uint64_t)digits[1]) << PyLong_SHIFT) | (uint64_t)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(uint64_t) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint64_t, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint64_t) >= 3 * PyLong_SHIFT)) { + return (uint64_t) (((((((uint64_t)digits[2]) << PyLong_SHIFT) | (uint64_t)digits[1]) << PyLong_SHIFT) | (uint64_t)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(uint64_t) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint64_t, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint64_t) >= 4 * PyLong_SHIFT)) { + return (uint64_t) (((((((((uint64_t)digits[3]) << PyLong_SHIFT) | (uint64_t)digits[2]) << PyLong_SHIFT) | (uint64_t)digits[1]) << PyLong_SHIFT) | (uint64_t)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (uint64_t) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(uint64_t) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(uint64_t, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(uint64_t) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(uint64_t, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(uint64_t, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(uint64_t) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint64_t, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint64_t) - 1 > 2 * PyLong_SHIFT)) { + return (uint64_t) (((uint64_t)-1)*(((((uint64_t)digits[1]) << PyLong_SHIFT) | (uint64_t)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(uint64_t) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint64_t, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint64_t) - 1 > 2 * PyLong_SHIFT)) { + return (uint64_t) ((((((uint64_t)digits[1]) << PyLong_SHIFT) | (uint64_t)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(uint64_t) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint64_t, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint64_t) - 1 > 3 * PyLong_SHIFT)) { + return (uint64_t) (((uint64_t)-1)*(((((((uint64_t)digits[2]) << PyLong_SHIFT) | (uint64_t)digits[1]) << PyLong_SHIFT) | (uint64_t)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(uint64_t) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint64_t, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint64_t) - 1 > 3 * PyLong_SHIFT)) { + return (uint64_t) ((((((((uint64_t)digits[2]) << PyLong_SHIFT) | (uint64_t)digits[1]) << PyLong_SHIFT) | (uint64_t)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(uint64_t) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint64_t, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint64_t) - 1 > 4 * PyLong_SHIFT)) { + return (uint64_t) (((uint64_t)-1)*(((((((((uint64_t)digits[3]) << PyLong_SHIFT) | (uint64_t)digits[2]) << PyLong_SHIFT) | (uint64_t)digits[1]) << PyLong_SHIFT) | (uint64_t)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(uint64_t) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint64_t, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint64_t) - 1 > 4 * PyLong_SHIFT)) { + return (uint64_t) ((((((((((uint64_t)digits[3]) << PyLong_SHIFT) | (uint64_t)digits[2]) << PyLong_SHIFT) | (uint64_t)digits[1]) << PyLong_SHIFT) | (uint64_t)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(uint64_t) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(uint64_t, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(uint64_t) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(uint64_t, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + uint64_t val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (uint64_t) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (uint64_t) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (uint64_t) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (uint64_t) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (uint64_t) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(uint64_t) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((uint64_t) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(uint64_t) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((uint64_t) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((uint64_t) 1) << (sizeof(uint64_t) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (uint64_t) -1; + } + } else { + uint64_t val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (uint64_t) -1; + val = __Pyx_PyInt_As_uint64_t(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to uint64_t"); + return (uint64_t) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to uint64_t"); + return (uint64_t) -1; +} + +/* CIntFromPy */ + static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(int) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(int, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (int) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 2 * PyLong_SHIFT)) { + return (int) (((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 3 * PyLong_SHIFT)) { + return (int) (((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 4 * PyLong_SHIFT)) { + return (int) (((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(int) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(int) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) ((((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) ((((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) ((((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(int) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + int val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (int) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (int) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (int) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (int) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(int) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(int) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((int) 1) << (sizeof(int) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (int) -1; + } + } else { + int val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (int) -1; + val = __Pyx_PyInt_As_int(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to int"); + return (int) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to int"); + return (int) -1; +} + +/* CIntToPy */ + static CYTHON_INLINE PyObject* __Pyx_PyInt_From_npy_uint8(npy_uint8 value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const npy_uint8 neg_one = (npy_uint8) -1, const_zero = (npy_uint8) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(npy_uint8) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(npy_uint8) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(npy_uint8) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(npy_uint8) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(npy_uint8) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; +#if !CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030d0000 + return _PyLong_FromByteArray(bytes, sizeof(npy_uint8), + little, !is_unsigned); +#else + PyObject *from_bytes, *result = NULL; + PyObject *py_bytes = NULL, *arg_tuple = NULL, *kwds = NULL, *order_str = NULL; + from_bytes = PyObject_GetAttrString((PyObject*)&PyLong_Type, "from_bytes"); + if (!from_bytes) return NULL; + py_bytes = PyBytes_FromStringAndSize((char*)bytes, sizeof(npy_uint8)); + if (!py_bytes) goto limited_bad; + order_str = PyUnicode_FromString(little ? "little" : "big"); + if (!order_str) goto limited_bad; + arg_tuple = PyTuple_Pack(2, py_bytes, order_str); + if (!arg_tuple) goto limited_bad; + if (!is_unsigned) { + kwds = PyDict_New(); + if (!kwds) goto limited_bad; + if (PyDict_SetItemString(kwds, "signed", __Pyx_NewRef(Py_True))) goto limited_bad; + } + result = PyObject_Call(from_bytes, arg_tuple, kwds); + limited_bad: + Py_XDECREF(kwds); + Py_XDECREF(arg_tuple); + Py_XDECREF(order_str); + Py_XDECREF(py_bytes); + Py_XDECREF(from_bytes); + return result; +#endif + } +} + +/* CIntFromPy */ + static CYTHON_INLINE npy_uint8 __Pyx_PyInt_As_npy_uint8(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const npy_uint8 neg_one = (npy_uint8) -1, const_zero = (npy_uint8) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(npy_uint8) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(npy_uint8, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (npy_uint8) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(npy_uint8, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(npy_uint8) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(npy_uint8, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(npy_uint8) >= 2 * PyLong_SHIFT)) { + return (npy_uint8) (((((npy_uint8)digits[1]) << PyLong_SHIFT) | (npy_uint8)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(npy_uint8) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(npy_uint8, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(npy_uint8) >= 3 * PyLong_SHIFT)) { + return (npy_uint8) (((((((npy_uint8)digits[2]) << PyLong_SHIFT) | (npy_uint8)digits[1]) << PyLong_SHIFT) | (npy_uint8)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(npy_uint8) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(npy_uint8, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(npy_uint8) >= 4 * PyLong_SHIFT)) { + return (npy_uint8) (((((((((npy_uint8)digits[3]) << PyLong_SHIFT) | (npy_uint8)digits[2]) << PyLong_SHIFT) | (npy_uint8)digits[1]) << PyLong_SHIFT) | (npy_uint8)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (npy_uint8) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(npy_uint8) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(npy_uint8, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(npy_uint8) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(npy_uint8, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(npy_uint8, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(npy_uint8) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(npy_uint8, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(npy_uint8) - 1 > 2 * PyLong_SHIFT)) { + return (npy_uint8) (((npy_uint8)-1)*(((((npy_uint8)digits[1]) << PyLong_SHIFT) | (npy_uint8)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(npy_uint8) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(npy_uint8, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(npy_uint8) - 1 > 2 * PyLong_SHIFT)) { + return (npy_uint8) ((((((npy_uint8)digits[1]) << PyLong_SHIFT) | (npy_uint8)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(npy_uint8) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(npy_uint8, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(npy_uint8) - 1 > 3 * PyLong_SHIFT)) { + return (npy_uint8) (((npy_uint8)-1)*(((((((npy_uint8)digits[2]) << PyLong_SHIFT) | (npy_uint8)digits[1]) << PyLong_SHIFT) | (npy_uint8)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(npy_uint8) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(npy_uint8, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(npy_uint8) - 1 > 3 * PyLong_SHIFT)) { + return (npy_uint8) ((((((((npy_uint8)digits[2]) << PyLong_SHIFT) | (npy_uint8)digits[1]) << PyLong_SHIFT) | (npy_uint8)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(npy_uint8) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(npy_uint8, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(npy_uint8) - 1 > 4 * PyLong_SHIFT)) { + return (npy_uint8) (((npy_uint8)-1)*(((((((((npy_uint8)digits[3]) << PyLong_SHIFT) | (npy_uint8)digits[2]) << PyLong_SHIFT) | (npy_uint8)digits[1]) << PyLong_SHIFT) | (npy_uint8)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(npy_uint8) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(npy_uint8, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(npy_uint8) - 1 > 4 * PyLong_SHIFT)) { + return (npy_uint8) ((((((((((npy_uint8)digits[3]) << PyLong_SHIFT) | (npy_uint8)digits[2]) << PyLong_SHIFT) | (npy_uint8)digits[1]) << PyLong_SHIFT) | (npy_uint8)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(npy_uint8) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(npy_uint8, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(npy_uint8) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(npy_uint8, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + npy_uint8 val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (npy_uint8) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (npy_uint8) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (npy_uint8) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (npy_uint8) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (npy_uint8) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(npy_uint8) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((npy_uint8) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(npy_uint8) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((npy_uint8) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((npy_uint8) 1) << (sizeof(npy_uint8) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (npy_uint8) -1; + } + } else { + npy_uint8 val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (npy_uint8) -1; + val = __Pyx_PyInt_As_npy_uint8(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to npy_uint8"); + return (npy_uint8) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to npy_uint8"); + return (npy_uint8) -1; +} + +/* CIntToPy */ + static CYTHON_INLINE PyObject* __Pyx_PyInt_From_unsigned_char(unsigned char value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const unsigned char neg_one = (unsigned char) -1, const_zero = (unsigned char) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(unsigned char) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(unsigned char) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(unsigned char) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(unsigned char) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(unsigned char) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; +#if !CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030d0000 + return _PyLong_FromByteArray(bytes, sizeof(unsigned char), + little, !is_unsigned); +#else + PyObject *from_bytes, *result = NULL; + PyObject *py_bytes = NULL, *arg_tuple = NULL, *kwds = NULL, *order_str = NULL; + from_bytes = PyObject_GetAttrString((PyObject*)&PyLong_Type, "from_bytes"); + if (!from_bytes) return NULL; + py_bytes = PyBytes_FromStringAndSize((char*)bytes, sizeof(unsigned char)); + if (!py_bytes) goto limited_bad; + order_str = PyUnicode_FromString(little ? "little" : "big"); + if (!order_str) goto limited_bad; + arg_tuple = PyTuple_Pack(2, py_bytes, order_str); + if (!arg_tuple) goto limited_bad; + if (!is_unsigned) { + kwds = PyDict_New(); + if (!kwds) goto limited_bad; + if (PyDict_SetItemString(kwds, "signed", __Pyx_NewRef(Py_True))) goto limited_bad; + } + result = PyObject_Call(from_bytes, arg_tuple, kwds); + limited_bad: + Py_XDECREF(kwds); + Py_XDECREF(arg_tuple); + Py_XDECREF(order_str); + Py_XDECREF(py_bytes); + Py_XDECREF(from_bytes); + return result; +#endif + } +} + +/* CIntToPy */ + static CYTHON_INLINE PyObject* __Pyx_PyInt_From_int(int value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(int) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(int) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(int) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(int) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(int) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; +#if !CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030d0000 + return _PyLong_FromByteArray(bytes, sizeof(int), + little, !is_unsigned); +#else + PyObject *from_bytes, *result = NULL; + PyObject *py_bytes = NULL, *arg_tuple = NULL, *kwds = NULL, *order_str = NULL; + from_bytes = PyObject_GetAttrString((PyObject*)&PyLong_Type, "from_bytes"); + if (!from_bytes) return NULL; + py_bytes = PyBytes_FromStringAndSize((char*)bytes, sizeof(int)); + if (!py_bytes) goto limited_bad; + order_str = PyUnicode_FromString(little ? "little" : "big"); + if (!order_str) goto limited_bad; + arg_tuple = PyTuple_Pack(2, py_bytes, order_str); + if (!arg_tuple) goto limited_bad; + if (!is_unsigned) { + kwds = PyDict_New(); + if (!kwds) goto limited_bad; + if (PyDict_SetItemString(kwds, "signed", __Pyx_NewRef(Py_True))) goto limited_bad; + } + result = PyObject_Call(from_bytes, arg_tuple, kwds); + limited_bad: + Py_XDECREF(kwds); + Py_XDECREF(arg_tuple); + Py_XDECREF(order_str); + Py_XDECREF(py_bytes); + Py_XDECREF(from_bytes); + return result; +#endif + } +} + +/* CIntToPy */ + static CYTHON_INLINE PyObject* __Pyx_PyInt_From_uint32_t(uint32_t value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const uint32_t neg_one = (uint32_t) -1, const_zero = (uint32_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(uint32_t) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(uint32_t) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(uint32_t) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(uint32_t) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(uint32_t) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; +#if !CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030d0000 + return _PyLong_FromByteArray(bytes, sizeof(uint32_t), + little, !is_unsigned); +#else + PyObject *from_bytes, *result = NULL; + PyObject *py_bytes = NULL, *arg_tuple = NULL, *kwds = NULL, *order_str = NULL; + from_bytes = PyObject_GetAttrString((PyObject*)&PyLong_Type, "from_bytes"); + if (!from_bytes) return NULL; + py_bytes = PyBytes_FromStringAndSize((char*)bytes, sizeof(uint32_t)); + if (!py_bytes) goto limited_bad; + order_str = PyUnicode_FromString(little ? "little" : "big"); + if (!order_str) goto limited_bad; + arg_tuple = PyTuple_Pack(2, py_bytes, order_str); + if (!arg_tuple) goto limited_bad; + if (!is_unsigned) { + kwds = PyDict_New(); + if (!kwds) goto limited_bad; + if (PyDict_SetItemString(kwds, "signed", __Pyx_NewRef(Py_True))) goto limited_bad; + } + result = PyObject_Call(from_bytes, arg_tuple, kwds); + limited_bad: + Py_XDECREF(kwds); + Py_XDECREF(arg_tuple); + Py_XDECREF(order_str); + Py_XDECREF(py_bytes); + Py_XDECREF(from_bytes); + return result; +#endif + } +} + +/* CIntToPy */ + static CYTHON_INLINE PyObject* __Pyx_PyInt_From_uint64_t(uint64_t value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const uint64_t neg_one = (uint64_t) -1, const_zero = (uint64_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(uint64_t) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(uint64_t) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(uint64_t) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(uint64_t) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(uint64_t) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; +#if !CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030d0000 + return _PyLong_FromByteArray(bytes, sizeof(uint64_t), + little, !is_unsigned); +#else + PyObject *from_bytes, *result = NULL; + PyObject *py_bytes = NULL, *arg_tuple = NULL, *kwds = NULL, *order_str = NULL; + from_bytes = PyObject_GetAttrString((PyObject*)&PyLong_Type, "from_bytes"); + if (!from_bytes) return NULL; + py_bytes = PyBytes_FromStringAndSize((char*)bytes, sizeof(uint64_t)); + if (!py_bytes) goto limited_bad; + order_str = PyUnicode_FromString(little ? "little" : "big"); + if (!order_str) goto limited_bad; + arg_tuple = PyTuple_Pack(2, py_bytes, order_str); + if (!arg_tuple) goto limited_bad; + if (!is_unsigned) { + kwds = PyDict_New(); + if (!kwds) goto limited_bad; + if (PyDict_SetItemString(kwds, "signed", __Pyx_NewRef(Py_True))) goto limited_bad; + } + result = PyObject_Call(from_bytes, arg_tuple, kwds); + limited_bad: + Py_XDECREF(kwds); + Py_XDECREF(arg_tuple); + Py_XDECREF(order_str); + Py_XDECREF(py_bytes); + Py_XDECREF(from_bytes); + return result; +#endif + } +} + +/* CIntToPy */ + static CYTHON_INLINE PyObject* __Pyx_PyInt_From_enum__VisionStreamType(enum VisionStreamType value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const enum VisionStreamType neg_one = (enum VisionStreamType) -1, const_zero = (enum VisionStreamType) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(enum VisionStreamType) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(enum VisionStreamType) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(enum VisionStreamType) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(enum VisionStreamType) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(enum VisionStreamType) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; +#if !CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030d0000 + return _PyLong_FromByteArray(bytes, sizeof(enum VisionStreamType), + little, !is_unsigned); +#else + PyObject *from_bytes, *result = NULL; + PyObject *py_bytes = NULL, *arg_tuple = NULL, *kwds = NULL, *order_str = NULL; + from_bytes = PyObject_GetAttrString((PyObject*)&PyLong_Type, "from_bytes"); + if (!from_bytes) return NULL; + py_bytes = PyBytes_FromStringAndSize((char*)bytes, sizeof(enum VisionStreamType)); + if (!py_bytes) goto limited_bad; + order_str = PyUnicode_FromString(little ? "little" : "big"); + if (!order_str) goto limited_bad; + arg_tuple = PyTuple_Pack(2, py_bytes, order_str); + if (!arg_tuple) goto limited_bad; + if (!is_unsigned) { + kwds = PyDict_New(); + if (!kwds) goto limited_bad; + if (PyDict_SetItemString(kwds, "signed", __Pyx_NewRef(Py_True))) goto limited_bad; + } + result = PyObject_Call(from_bytes, arg_tuple, kwds); + limited_bad: + Py_XDECREF(kwds); + Py_XDECREF(arg_tuple); + Py_XDECREF(order_str); + Py_XDECREF(py_bytes); + Py_XDECREF(from_bytes); + return result; +#endif + } +} + +/* CIntToPy */ + static CYTHON_INLINE PyObject* __Pyx_PyInt_From_enum____pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType neg_one = (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) -1, const_zero = (enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; +#if !CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030d0000 + return _PyLong_FromByteArray(bytes, sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType), + little, !is_unsigned); +#else + PyObject *from_bytes, *result = NULL; + PyObject *py_bytes = NULL, *arg_tuple = NULL, *kwds = NULL, *order_str = NULL; + from_bytes = PyObject_GetAttrString((PyObject*)&PyLong_Type, "from_bytes"); + if (!from_bytes) return NULL; + py_bytes = PyBytes_FromStringAndSize((char*)bytes, sizeof(enum __pyx_t_6cereal_9visionipc_13visionipc_pyx_VisionStreamType)); + if (!py_bytes) goto limited_bad; + order_str = PyUnicode_FromString(little ? "little" : "big"); + if (!order_str) goto limited_bad; + arg_tuple = PyTuple_Pack(2, py_bytes, order_str); + if (!arg_tuple) goto limited_bad; + if (!is_unsigned) { + kwds = PyDict_New(); + if (!kwds) goto limited_bad; + if (PyDict_SetItemString(kwds, "signed", __Pyx_NewRef(Py_True))) goto limited_bad; + } + result = PyObject_Call(from_bytes, arg_tuple, kwds); + limited_bad: + Py_XDECREF(kwds); + Py_XDECREF(arg_tuple); + Py_XDECREF(order_str); + Py_XDECREF(py_bytes); + Py_XDECREF(from_bytes); + return result; +#endif + } +} + +/* CIntFromPy */ + static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(long) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(long, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (long) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 2 * PyLong_SHIFT)) { + return (long) (((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 3 * PyLong_SHIFT)) { + return (long) (((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 4 * PyLong_SHIFT)) { + return (long) (((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(long) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(long) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) ((((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) ((((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) ((((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(long) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + long val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (long) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (long) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (long) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (long) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(long) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(long) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((long) 1) << (sizeof(long) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (long) -1; + } + } else { + long val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (long) -1; + val = __Pyx_PyInt_As_long(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to long"); + return (long) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to long"); + return (long) -1; +} + +/* CIntToPy */ + static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(long) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(long) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(long) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; +#if !CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030d0000 + return _PyLong_FromByteArray(bytes, sizeof(long), + little, !is_unsigned); +#else + PyObject *from_bytes, *result = NULL; + PyObject *py_bytes = NULL, *arg_tuple = NULL, *kwds = NULL, *order_str = NULL; + from_bytes = PyObject_GetAttrString((PyObject*)&PyLong_Type, "from_bytes"); + if (!from_bytes) return NULL; + py_bytes = PyBytes_FromStringAndSize((char*)bytes, sizeof(long)); + if (!py_bytes) goto limited_bad; + order_str = PyUnicode_FromString(little ? "little" : "big"); + if (!order_str) goto limited_bad; + arg_tuple = PyTuple_Pack(2, py_bytes, order_str); + if (!arg_tuple) goto limited_bad; + if (!is_unsigned) { + kwds = PyDict_New(); + if (!kwds) goto limited_bad; + if (PyDict_SetItemString(kwds, "signed", __Pyx_NewRef(Py_True))) goto limited_bad; + } + result = PyObject_Call(from_bytes, arg_tuple, kwds); + limited_bad: + Py_XDECREF(kwds); + Py_XDECREF(arg_tuple); + Py_XDECREF(order_str); + Py_XDECREF(py_bytes); + Py_XDECREF(from_bytes); + return result; +#endif + } +} + +/* CIntFromPy */ + static CYTHON_INLINE char __Pyx_PyInt_As_char(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const char neg_one = (char) -1, const_zero = (char) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(char) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(char, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (char) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(char, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(char) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) >= 2 * PyLong_SHIFT)) { + return (char) (((((char)digits[1]) << PyLong_SHIFT) | (char)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(char) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) >= 3 * PyLong_SHIFT)) { + return (char) (((((((char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(char) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) >= 4 * PyLong_SHIFT)) { + return (char) (((((((((char)digits[3]) << PyLong_SHIFT) | (char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (char) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(char) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(char, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(char) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(char, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(char, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(char) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 2 * PyLong_SHIFT)) { + return (char) (((char)-1)*(((((char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(char) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 2 * PyLong_SHIFT)) { + return (char) ((((((char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(char) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 3 * PyLong_SHIFT)) { + return (char) (((char)-1)*(((((((char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(char) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 3 * PyLong_SHIFT)) { + return (char) ((((((((char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(char) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 4 * PyLong_SHIFT)) { + return (char) (((char)-1)*(((((((((char)digits[3]) << PyLong_SHIFT) | (char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(char) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 4 * PyLong_SHIFT)) { + return (char) ((((((((((char)digits[3]) << PyLong_SHIFT) | (char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(char) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(char, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(char) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(char, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + char val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (char) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (char) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (char) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (char) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (char) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(char) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((char) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(char) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((char) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((char) 1) << (sizeof(char) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (char) -1; + } + } else { + char val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (char) -1; + val = __Pyx_PyInt_As_char(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to char"); + return (char) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to char"); + return (char) -1; +} + +/* FormatTypeName */ + #if CYTHON_COMPILING_IN_LIMITED_API +static __Pyx_TypeName +__Pyx_PyType_GetName(PyTypeObject* tp) +{ + PyObject *name = __Pyx_PyObject_GetAttrStr((PyObject *)tp, + __pyx_n_s_name_2); + if (unlikely(name == NULL) || unlikely(!PyUnicode_Check(name))) { + PyErr_Clear(); + Py_XDECREF(name); + name = __Pyx_NewRef(__pyx_n_s__67); + } + return name; +} +#endif + +/* CheckBinaryVersion */ + static unsigned long __Pyx_get_runtime_version(void) { +#if __PYX_LIMITED_VERSION_HEX >= 0x030B00A4 + return Py_Version & ~0xFFUL; +#else + const char* rt_version = Py_GetVersion(); + unsigned long version = 0; + unsigned long factor = 0x01000000UL; + unsigned int digit = 0; + int i = 0; + while (factor) { + while ('0' <= rt_version[i] && rt_version[i] <= '9') { + digit = digit * 10 + (unsigned int) (rt_version[i] - '0'); + ++i; + } + version += factor * digit; + if (rt_version[i] != '.') + break; + digit = 0; + factor >>= 8; + ++i; + } + return version; +#endif +} +static int __Pyx_check_binary_version(unsigned long ct_version, unsigned long rt_version, int allow_newer) { + const unsigned long MAJOR_MINOR = 0xFFFF0000UL; + if ((rt_version & MAJOR_MINOR) == (ct_version & MAJOR_MINOR)) + return 0; + if (likely(allow_newer && (rt_version & MAJOR_MINOR) > (ct_version & MAJOR_MINOR))) + return 1; + { + char message[200]; + PyOS_snprintf(message, sizeof(message), + "compile time Python version %d.%d " + "of module '%.100s' " + "%s " + "runtime version %d.%d", + (int) (ct_version >> 24), (int) ((ct_version >> 16) & 0xFF), + __Pyx_MODULE_NAME, + (allow_newer) ? "was newer than" : "does not match", + (int) (rt_version >> 24), (int) ((rt_version >> 16) & 0xFF) + ); + return PyErr_WarnEx(NULL, message, 1); + } +} + +/* InitStrings */ + #if PY_MAJOR_VERSION >= 3 +static int __Pyx_InitString(__Pyx_StringTabEntry t, PyObject **str) { + if (t.is_unicode | t.is_str) { + if (t.intern) { + *str = PyUnicode_InternFromString(t.s); + } else if (t.encoding) { + *str = PyUnicode_Decode(t.s, t.n - 1, t.encoding, NULL); + } else { + *str = PyUnicode_FromStringAndSize(t.s, t.n - 1); + } + } else { + *str = PyBytes_FromStringAndSize(t.s, t.n - 1); + } + if (!*str) + return -1; + if (PyObject_Hash(*str) == -1) + return -1; + return 0; +} +#endif +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t) { + while (t->p) { + #if PY_MAJOR_VERSION >= 3 + __Pyx_InitString(*t, t->p); + #else + if (t->is_unicode) { + *t->p = PyUnicode_DecodeUTF8(t->s, t->n - 1, NULL); + } else if (t->intern) { + *t->p = PyString_InternFromString(t->s); + } else { + *t->p = PyString_FromStringAndSize(t->s, t->n - 1); + } + if (!*t->p) + return -1; + if (PyObject_Hash(*t->p) == -1) + return -1; + #endif + ++t; + } + return 0; +} + +#include +static CYTHON_INLINE Py_ssize_t __Pyx_ssize_strlen(const char *s) { + size_t len = strlen(s); + if (unlikely(len > (size_t) PY_SSIZE_T_MAX)) { + PyErr_SetString(PyExc_OverflowError, "byte string is too long"); + return -1; + } + return (Py_ssize_t) len; +} +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char* c_str) { + Py_ssize_t len = __Pyx_ssize_strlen(c_str); + if (unlikely(len < 0)) return NULL; + return __Pyx_PyUnicode_FromStringAndSize(c_str, len); +} +static CYTHON_INLINE PyObject* __Pyx_PyByteArray_FromString(const char* c_str) { + Py_ssize_t len = __Pyx_ssize_strlen(c_str); + if (unlikely(len < 0)) return NULL; + return PyByteArray_FromStringAndSize(c_str, len); +} +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject* o) { + Py_ssize_t ignore; + return __Pyx_PyObject_AsStringAndSize(o, &ignore); +} +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +#if !CYTHON_PEP393_ENABLED +static const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + char* defenc_c; + PyObject* defenc = _PyUnicode_AsDefaultEncodedString(o, NULL); + if (!defenc) return NULL; + defenc_c = PyBytes_AS_STRING(defenc); +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + { + char* end = defenc_c + PyBytes_GET_SIZE(defenc); + char* c; + for (c = defenc_c; c < end; c++) { + if ((unsigned char) (*c) >= 128) { + PyUnicode_AsASCIIString(o); + return NULL; + } + } + } +#endif + *length = PyBytes_GET_SIZE(defenc); + return defenc_c; +} +#else +static CYTHON_INLINE const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + if (unlikely(__Pyx_PyUnicode_READY(o) == -1)) return NULL; +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + if (likely(PyUnicode_IS_ASCII(o))) { + *length = PyUnicode_GET_LENGTH(o); + return PyUnicode_AsUTF8(o); + } else { + PyUnicode_AsASCIIString(o); + return NULL; + } +#else + return PyUnicode_AsUTF8AndSize(o, length); +#endif +} +#endif +#endif +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject* o, Py_ssize_t *length) { +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT + if ( +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + __Pyx_sys_getdefaultencoding_not_ascii && +#endif + PyUnicode_Check(o)) { + return __Pyx_PyUnicode_AsStringAndSize(o, length); + } else +#endif +#if (!CYTHON_COMPILING_IN_PYPY && !CYTHON_COMPILING_IN_LIMITED_API) || (defined(PyByteArray_AS_STRING) && defined(PyByteArray_GET_SIZE)) + if (PyByteArray_Check(o)) { + *length = PyByteArray_GET_SIZE(o); + return PyByteArray_AS_STRING(o); + } else +#endif + { + char* result; + int r = PyBytes_AsStringAndSize(o, &result, length); + if (unlikely(r < 0)) { + return NULL; + } else { + return result; + } + } +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject* x) { + int is_true = x == Py_True; + if (is_true | (x == Py_False) | (x == Py_None)) return is_true; + else return PyObject_IsTrue(x); +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject* x) { + int retval; + if (unlikely(!x)) return -1; + retval = __Pyx_PyObject_IsTrue(x); + Py_DECREF(x); + return retval; +} +static PyObject* __Pyx_PyNumber_IntOrLongWrongResultType(PyObject* result, const char* type_name) { + __Pyx_TypeName result_type_name = __Pyx_PyType_GetName(Py_TYPE(result)); +#if PY_MAJOR_VERSION >= 3 + if (PyLong_Check(result)) { + if (PyErr_WarnFormat(PyExc_DeprecationWarning, 1, + "__int__ returned non-int (type " __Pyx_FMT_TYPENAME "). " + "The ability to return an instance of a strict subclass of int is deprecated, " + "and may be removed in a future version of Python.", + result_type_name)) { + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; + } + __Pyx_DECREF_TypeName(result_type_name); + return result; + } +#endif + PyErr_Format(PyExc_TypeError, + "__%.4s__ returned non-%.4s (type " __Pyx_FMT_TYPENAME ")", + type_name, type_name, result_type_name); + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x) { +#if CYTHON_USE_TYPE_SLOTS + PyNumberMethods *m; +#endif + const char *name = NULL; + PyObject *res = NULL; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x) || PyLong_Check(x))) +#else + if (likely(PyLong_Check(x))) +#endif + return __Pyx_NewRef(x); +#if CYTHON_USE_TYPE_SLOTS + m = Py_TYPE(x)->tp_as_number; + #if PY_MAJOR_VERSION < 3 + if (m && m->nb_int) { + name = "int"; + res = m->nb_int(x); + } + else if (m && m->nb_long) { + name = "long"; + res = m->nb_long(x); + } + #else + if (likely(m && m->nb_int)) { + name = "int"; + res = m->nb_int(x); + } + #endif +#else + if (!PyBytes_CheckExact(x) && !PyUnicode_CheckExact(x)) { + res = PyNumber_Int(x); + } +#endif + if (likely(res)) { +#if PY_MAJOR_VERSION < 3 + if (unlikely(!PyInt_Check(res) && !PyLong_Check(res))) { +#else + if (unlikely(!PyLong_CheckExact(res))) { +#endif + return __Pyx_PyNumber_IntOrLongWrongResultType(res, name); + } + } + else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_TypeError, + "an integer is required"); + } + return res; +} +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject* b) { + Py_ssize_t ival; + PyObject *x; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_CheckExact(b))) { + if (sizeof(Py_ssize_t) >= sizeof(long)) + return PyInt_AS_LONG(b); + else + return PyInt_AsSsize_t(b); + } +#endif + if (likely(PyLong_CheckExact(b))) { + #if CYTHON_USE_PYLONG_INTERNALS + if (likely(__Pyx_PyLong_IsCompact(b))) { + return __Pyx_PyLong_CompactValue(b); + } else { + const digit* digits = __Pyx_PyLong_Digits(b); + const Py_ssize_t size = __Pyx_PyLong_SignedDigitCount(b); + switch (size) { + case 2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return (Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + } + } + #endif + return PyLong_AsSsize_t(b); + } + x = PyNumber_Index(b); + if (!x) return -1; + ival = PyInt_AsSsize_t(x); + Py_DECREF(x); + return ival; +} +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject* o) { + if (sizeof(Py_hash_t) == sizeof(Py_ssize_t)) { + return (Py_hash_t) __Pyx_PyIndex_AsSsize_t(o); +#if PY_MAJOR_VERSION < 3 + } else if (likely(PyInt_CheckExact(o))) { + return PyInt_AS_LONG(o); +#endif + } else { + Py_ssize_t ival; + PyObject *x; + x = PyNumber_Index(o); + if (!x) return -1; + ival = PyInt_AsLong(x); + Py_DECREF(x); + return ival; + } +} +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b) { + return b ? __Pyx_NewRef(Py_True) : __Pyx_NewRef(Py_False); +} +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t ival) { + return PyInt_FromSize_t(ival); +} + + +/* #### Code section: utility_code_pragmas_end ### */ +#ifdef _MSC_VER +#pragma warning( pop ) +#endif + + + +/* #### Code section: end ### */ +#endif /* Py_PYTHON_H */ diff --git a/cereal/visionipc/visionipc_pyx.so b/cereal/visionipc/visionipc_pyx.so new file mode 100755 index 0000000..53c5034 Binary files /dev/null and b/cereal/visionipc/visionipc_pyx.so differ diff --git a/cereal/visionipc/visionipc_server.cc b/cereal/visionipc/visionipc_server.cc deleted file mode 100644 index da9d11f..0000000 --- a/cereal/visionipc/visionipc_server.cc +++ /dev/null @@ -1,214 +0,0 @@ -#include -#include -#include -#include -#include - -#include -#include -#include - -#include "cereal/messaging/messaging.h" -#include "cereal/visionipc/ipc.h" -#include "cereal/visionipc/visionipc_server.h" -#include "cereal/logger/logger.h" - -std::string get_endpoint_name(std::string name, VisionStreamType type){ - if (messaging_use_zmq()){ - assert(name == "camerad" || name == "navd"); - return std::to_string(9000 + static_cast(type)); - } else { - return "visionipc_" + name + "_" + std::to_string(type); - } -} - -std::string get_ipc_path(const std::string& name) { - std::string path = "/tmp/"; - if (char* prefix = std::getenv("OPENPILOT_PREFIX")) { - path += std::string(prefix) + "_"; - } - return path + "visionipc_" + name; -} - -VisionIpcServer::VisionIpcServer(std::string name, cl_device_id device_id, cl_context ctx) : name(name), device_id(device_id), ctx(ctx) { - msg_ctx = Context::create(); - - std::random_device rd("/dev/urandom"); - std::uniform_int_distribution distribution(0, std::numeric_limits::max()); - server_id = distribution(rd); -} - -void VisionIpcServer::create_buffers(VisionStreamType type, size_t num_buffers, bool rgb, size_t width, size_t height){ - // TODO: assert that this type is not created yet - assert(num_buffers < VISIONIPC_MAX_FDS); - int aligned_w = 0, aligned_h = 0; - - size_t size = 0; - size_t stride = 0; - size_t uv_offset = 0; - - if (rgb) { - visionbuf_compute_aligned_width_and_height(width, height, &aligned_w, &aligned_h); - size = (size_t)aligned_w * (size_t)aligned_h * 3; - stride = aligned_w * 3; - } else { - size = width * height * 3 / 2; - stride = width; - uv_offset = width * height; - } - - create_buffers_with_sizes(type, num_buffers, rgb, width, height, size, stride, uv_offset); -} - -void VisionIpcServer::create_buffers_with_sizes(VisionStreamType type, size_t num_buffers, bool rgb, size_t width, size_t height, size_t size, size_t stride, size_t uv_offset) { - // Create map + alloc requested buffers - for (size_t i = 0; i < num_buffers; i++){ - VisionBuf* buf = new VisionBuf(); - buf->allocate(size); - buf->idx = i; - buf->type = type; - - if (device_id) buf->init_cl(device_id, ctx); - - rgb ? buf->init_rgb(width, height, stride) : buf->init_yuv(width, height, stride, uv_offset); - - buffers[type].push_back(buf); - } - - cur_idx[type] = 0; - - // Create msgq publisher for each of the `name` + type combos - // TODO: compute port number directly if using zmq - sockets[type] = PubSocket::create(msg_ctx, get_endpoint_name(name, type), false); -} - - -void VisionIpcServer::start_listener(){ - listener_thread = std::thread(&VisionIpcServer::listener, this); -} - - -void VisionIpcServer::listener(){ - std::cout << "Starting listener for: " << name << std::endl; - - const std::string ipc_path = get_ipc_path(name); - int sock = ipc_bind(ipc_path.c_str()); - assert(sock >= 0); - - while (!should_exit){ - // Wait for incoming connection - struct pollfd polls[1] = {{0}}; - polls[0].fd = sock; - polls[0].events = POLLIN; - - int ret = poll(polls, 1, 100); - if (ret < 0) { - if (errno == EINTR || errno == EAGAIN) continue; - std::cout << "poll failed, stopping listener" << std::endl; - break; - } - - if (should_exit) break; - if (!polls[0].revents) { - continue; - } - - // Handle incoming request - int fd = accept(sock, NULL, NULL); - assert(fd >= 0); - - VisionStreamType type = VisionStreamType::VISION_STREAM_MAX; - int r = ipc_sendrecv_with_fds(false, fd, &type, sizeof(type), nullptr, 0, nullptr); - assert(r == sizeof(type)); - - // send available stream types - if (type == VisionStreamType::VISION_STREAM_MAX) { - std::vector available_stream_types; - for (auto& [stream_type, _] : buffers) { - available_stream_types.push_back(stream_type); - } - r = ipc_sendrecv_with_fds(true, fd, available_stream_types.data(), available_stream_types.size() * sizeof(VisionStreamType), nullptr, 0, nullptr); - assert(r == available_stream_types.size() * sizeof(VisionStreamType)); - close(fd); - continue; - } - - if (buffers.count(type) <= 0) { - std::cout << "got request for invalid buffer type: " << type << std::endl; - close(fd); - continue; - } - - int fds[VISIONIPC_MAX_FDS]; - int num_fds = buffers[type].size(); - VisionBuf bufs[VISIONIPC_MAX_FDS]; - - for (int i = 0; i < num_fds; i++){ - fds[i] = buffers[type][i]->fd; - bufs[i] = *buffers[type][i]; - - // Remove some private openCL/ion metadata - bufs[i].buf_cl = 0; - bufs[i].copy_q = 0; - bufs[i].handle = 0; - - bufs[i].server_id = server_id; - } - - r = ipc_sendrecv_with_fds(true, fd, &bufs, sizeof(VisionBuf) * num_fds, fds, num_fds, nullptr); - - close(fd); - } - - std::cout << "Stopping listener for: " << name << std::endl; - close(sock); - unlink(ipc_path.c_str()); -} - - - -VisionBuf * VisionIpcServer::get_buffer(VisionStreamType type){ - // Do we want to keep track if the buffer has been sent out yet and warn user? - assert(buffers.count(type)); - auto b = buffers[type]; - return b[cur_idx[type]++ % b.size()]; -} - -void VisionIpcServer::send(VisionBuf * buf, VisionIpcBufExtra * extra, bool sync){ - if (sync) { - if (buf->sync(VISIONBUF_SYNC_FROM_DEVICE) != 0) { - LOGE("Failed to sync buffer"); - } - } - assert(buffers.count(buf->type)); - assert(buf->idx < buffers[buf->type].size()); - - // Send over correct msgq socket - VisionIpcPacket packet = {0}; - packet.server_id = server_id; - packet.idx = buf->idx; - packet.extra = *extra; - - sockets[buf->type]->send((char*)&packet, sizeof(packet)); -} - -VisionIpcServer::~VisionIpcServer(){ - should_exit = true; - listener_thread.join(); - - // VisionBuf cleanup - for (auto const& [type, buf] : buffers) { - for (VisionBuf* b : buf){ - if (b->free() != 0) { - LOGE("Failed to free buffer"); - } - delete b; - } - } - - // Messaging cleanup - for (auto const& [type, sock] : sockets) { - delete sock; - } - delete msg_ctx; -} diff --git a/cereal/visionipc/visionipc_server.h b/cereal/visionipc/visionipc_server.h deleted file mode 100644 index c494b1f..0000000 --- a/cereal/visionipc/visionipc_server.h +++ /dev/null @@ -1,42 +0,0 @@ -#pragma once -#include -#include -#include -#include -#include - -#include "cereal/messaging/messaging.h" -#include "cereal/visionipc/visionbuf.h" - -std::string get_endpoint_name(std::string name, VisionStreamType type); -std::string get_ipc_path(const std::string &name); - -class VisionIpcServer { - private: - cl_device_id device_id = nullptr; - cl_context ctx = nullptr; - uint64_t server_id; - - std::atomic should_exit = false; - std::string name; - std::thread listener_thread; - - std::map > cur_idx; - std::map > buffers; - - Context * msg_ctx; - std::map sockets; - - void listener(void); - - public: - VisionIpcServer(std::string name, cl_device_id device_id=nullptr, cl_context ctx=nullptr); - ~VisionIpcServer(); - - VisionBuf * get_buffer(VisionStreamType type); - - void create_buffers(VisionStreamType type, size_t num_buffers, bool rgb, size_t width, size_t height); - void create_buffers_with_sizes(VisionStreamType type, size_t num_buffers, bool rgb, size_t width, size_t height, size_t size, size_t stride, size_t uv_offset); - void send(VisionBuf * buf, VisionIpcBufExtra * extra, bool sync=true); - void start_listener(); -}; diff --git a/cereal/visionipc/visionipc_tests.cc b/cereal/visionipc/visionipc_tests.cc deleted file mode 100644 index 4a081df..0000000 --- a/cereal/visionipc/visionipc_tests.cc +++ /dev/null @@ -1,148 +0,0 @@ -#include -#include - -#include "catch2/catch.hpp" -#include "cereal/visionipc/visionipc_server.h" -#include "cereal/visionipc/visionipc_client.h" - -static void zmq_sleep(int milliseconds=1000){ - if (messaging_use_zmq()){ - std::this_thread::sleep_for(std::chrono::milliseconds(milliseconds)); - } -} - -TEST_CASE("Connecting"){ - VisionIpcServer server("camerad"); - server.create_buffers(VISION_STREAM_ROAD, 1, false, 100, 100); - server.start_listener(); - - VisionIpcClient client = VisionIpcClient("camerad", VISION_STREAM_ROAD, false); - REQUIRE(client.connect()); - - REQUIRE(client.connected); -} - -TEST_CASE("getAvailableStreams"){ - VisionIpcServer server("camerad"); - server.create_buffers(VISION_STREAM_ROAD, 1, false, 100, 100); - server.create_buffers(VISION_STREAM_WIDE_ROAD, 1, false, 100, 100); - server.start_listener(); - auto available_streams = VisionIpcClient::getAvailableStreams("camerad"); - REQUIRE(available_streams.size() == 2); - REQUIRE(available_streams.count(VISION_STREAM_ROAD) == 1); - REQUIRE(available_streams.count(VISION_STREAM_WIDE_ROAD) == 1); -} - -TEST_CASE("Check buffers"){ - size_t width = 100, height = 200, num_buffers = 5; - VisionIpcServer server("camerad"); - server.create_buffers(VISION_STREAM_ROAD, num_buffers, false, width, height); - server.start_listener(); - - VisionIpcClient client = VisionIpcClient("camerad", VISION_STREAM_ROAD, false); - REQUIRE(client.connect()); - - REQUIRE(client.buffers[0].width == width); - REQUIRE(client.buffers[0].height == height); - REQUIRE(client.buffers[0].len); - REQUIRE(client.num_buffers == num_buffers); -} - -TEST_CASE("Check yuv/rgb"){ - VisionIpcServer server("camerad"); - server.create_buffers(VISION_STREAM_ROAD, 1, false, 100, 100); - server.create_buffers(VISION_STREAM_MAP, 1, true, 100, 100); - server.start_listener(); - - VisionIpcClient client_yuv = VisionIpcClient("camerad", VISION_STREAM_ROAD, false); - VisionIpcClient client_rgb = VisionIpcClient("camerad", VISION_STREAM_MAP, false); - client_yuv.connect(); - client_rgb.connect(); - - REQUIRE(client_rgb.buffers[0].rgb == true); - REQUIRE(client_yuv.buffers[0].rgb == false); -} - -TEST_CASE("Send single buffer"){ - VisionIpcServer server("camerad"); - server.create_buffers(VISION_STREAM_ROAD, 1, true, 100, 100); - server.start_listener(); - - VisionIpcClient client = VisionIpcClient("camerad", VISION_STREAM_ROAD, false); - REQUIRE(client.connect()); - zmq_sleep(); - - VisionBuf * buf = server.get_buffer(VISION_STREAM_ROAD); - REQUIRE(buf != nullptr); - - *((uint64_t*)buf->addr) = 1234; - - VisionIpcBufExtra extra = {0}; - extra.frame_id = 1337; - buf->set_frame_id(extra.frame_id); - - server.send(buf, &extra); - - VisionIpcBufExtra extra_recv = {0}; - VisionBuf * recv_buf = client.recv(&extra_recv); - REQUIRE(recv_buf != nullptr); - REQUIRE(*(uint64_t*)recv_buf->addr == 1234); - REQUIRE(extra_recv.frame_id == extra.frame_id); - REQUIRE(recv_buf->get_frame_id() == extra.frame_id); -} - - -TEST_CASE("Test no conflate"){ - VisionIpcServer server("camerad"); - server.create_buffers(VISION_STREAM_ROAD, 1, true, 100, 100); - server.start_listener(); - - VisionIpcClient client = VisionIpcClient("camerad", VISION_STREAM_ROAD, false); - REQUIRE(client.connect()); - zmq_sleep(); - - VisionBuf * buf = server.get_buffer(VISION_STREAM_ROAD); - REQUIRE(buf != nullptr); - - VisionIpcBufExtra extra = {0}; - extra.frame_id = 1; - server.send(buf, &extra); - extra.frame_id = 2; - server.send(buf, &extra); - - VisionIpcBufExtra extra_recv = {0}; - VisionBuf * recv_buf = client.recv(&extra_recv); - REQUIRE(recv_buf != nullptr); - REQUIRE(extra_recv.frame_id == 1); - - recv_buf = client.recv(&extra_recv); - REQUIRE(recv_buf != nullptr); - REQUIRE(extra_recv.frame_id == 2); -} - -TEST_CASE("Test conflate"){ - VisionIpcServer server("camerad"); - server.create_buffers(VISION_STREAM_ROAD, 1, true, 100, 100); - server.start_listener(); - - VisionIpcClient client = VisionIpcClient("camerad", VISION_STREAM_ROAD, true); - REQUIRE(client.connect()); - zmq_sleep(); - - VisionBuf * buf = server.get_buffer(VISION_STREAM_ROAD); - REQUIRE(buf != nullptr); - - VisionIpcBufExtra extra = {0}; - extra.frame_id = 1; - server.send(buf, &extra); - extra.frame_id = 2; - server.send(buf, &extra); - - VisionIpcBufExtra extra_recv = {0}; - VisionBuf * recv_buf = client.recv(&extra_recv); - REQUIRE(recv_buf != nullptr); - REQUIRE(extra_recv.frame_id == 2); - - recv_buf = client.recv(&extra_recv); - REQUIRE(recv_buf == nullptr); -} diff --git a/common/SConscript b/common/SConscript deleted file mode 100644 index 829db6e..0000000 --- a/common/SConscript +++ /dev/null @@ -1,39 +0,0 @@ -Import('env', 'envCython', 'arch') - -common_libs = [ - 'params.cc', - 'swaglog.cc', - 'util.cc', - 'i2c.cc', - 'watchdog.cc', - 'ratekeeper.cc' -] - -if arch != "Darwin": - common_libs.append('gpio.cc') - -_common = env.Library('common', common_libs, LIBS="json11") - -files = [ - 'clutil.cc', -] - -_gpucommon = env.Library('gpucommon', files) -Export('_common', '_gpucommon') - -if GetOption('extras'): - env.Program('tests/test_common', - ['tests/test_runner.cc', 'tests/test_params.cc', 'tests/test_util.cc', 'tests/test_swaglog.cc'], - LIBS=[_common, 'json11', 'zmq', 'pthread']) - -# Cython bindings -params_python = envCython.Program('params_pyx.so', 'params_pyx.pyx', LIBS=envCython['LIBS'] + [_common, 'zmq', 'json11']) - -SConscript([ - 'transformations/SConscript', -]) - -Import('transformations_python') -common_python = [params_python, transformations_python] - -Export('common_python') diff --git a/common/clutil.cc b/common/clutil.cc deleted file mode 100644 index 4f2a783..0000000 --- a/common/clutil.cc +++ /dev/null @@ -1,200 +0,0 @@ -#include "common/clutil.h" - -#include -#include -#include - -#include "common/util.h" -#include "common/swaglog.h" - -namespace { // helper functions - -template -std::string get_info(Func get_info_func, Id id, Name param_name) { - size_t size = 0; - CL_CHECK(get_info_func(id, param_name, 0, NULL, &size)); - std::string info(size, '\0'); - CL_CHECK(get_info_func(id, param_name, size, info.data(), NULL)); - return info; -} -inline std::string get_platform_info(cl_platform_id id, cl_platform_info name) { return get_info(&clGetPlatformInfo, id, name); } -inline std::string get_device_info(cl_device_id id, cl_device_info name) { return get_info(&clGetDeviceInfo, id, name); } - -void cl_print_info(cl_platform_id platform, cl_device_id device) { - size_t work_group_size = 0; - cl_device_type device_type = 0; - clGetDeviceInfo(device, CL_DEVICE_MAX_WORK_GROUP_SIZE, sizeof(work_group_size), &work_group_size, NULL); - clGetDeviceInfo(device, CL_DEVICE_TYPE, sizeof(device_type), &device_type, NULL); - const char *type_str = "Other..."; - switch (device_type) { - case CL_DEVICE_TYPE_CPU: type_str ="CL_DEVICE_TYPE_CPU"; break; - case CL_DEVICE_TYPE_GPU: type_str = "CL_DEVICE_TYPE_GPU"; break; - case CL_DEVICE_TYPE_ACCELERATOR: type_str = "CL_DEVICE_TYPE_ACCELERATOR"; break; - } - - LOGD("vendor: %s", get_platform_info(platform, CL_PLATFORM_VENDOR).c_str()); - LOGD("platform version: %s", get_platform_info(platform, CL_PLATFORM_VERSION).c_str()); - LOGD("profile: %s", get_platform_info(platform, CL_PLATFORM_PROFILE).c_str()); - LOGD("extensions: %s", get_platform_info(platform, CL_PLATFORM_EXTENSIONS).c_str()); - LOGD("name: %s", get_device_info(device, CL_DEVICE_NAME).c_str()); - LOGD("device version: %s", get_device_info(device, CL_DEVICE_VERSION).c_str()); - LOGD("max work group size: %zu", work_group_size); - LOGD("type = %d, %s", (int)device_type, type_str); -} - -void cl_print_build_errors(cl_program program, cl_device_id device) { - cl_build_status status; - clGetProgramBuildInfo(program, device, CL_PROGRAM_BUILD_STATUS, sizeof(status), &status, NULL); - size_t log_size; - clGetProgramBuildInfo(program, device, CL_PROGRAM_BUILD_LOG, 0, NULL, &log_size); - std::string log(log_size, '\0'); - clGetProgramBuildInfo(program, device, CL_PROGRAM_BUILD_LOG, log_size, &log[0], NULL); - - LOGE("build failed; status=%d, log: %s", status, log.c_str()); -} - -} // namespace - -cl_device_id cl_get_device_id(cl_device_type device_type) { - cl_uint num_platforms = 0; - CL_CHECK(clGetPlatformIDs(0, NULL, &num_platforms)); - std::unique_ptr platform_ids = std::make_unique(num_platforms); - CL_CHECK(clGetPlatformIDs(num_platforms, &platform_ids[0], NULL)); - - for (size_t i = 0; i < num_platforms; ++i) { - LOGD("platform[%zu] CL_PLATFORM_NAME: %s", i, get_platform_info(platform_ids[i], CL_PLATFORM_NAME).c_str()); - - // Get first device - if (cl_device_id device_id = NULL; clGetDeviceIDs(platform_ids[i], device_type, 1, &device_id, NULL) == 0 && device_id) { - cl_print_info(platform_ids[i], device_id); - return device_id; - } - } - LOGE("No valid openCL platform found"); - assert(0); - return nullptr; -} - -cl_context cl_create_context(cl_device_id device_id) { - return CL_CHECK_ERR(clCreateContext(NULL, 1, &device_id, NULL, NULL, &err)); -} - -cl_program cl_program_from_file(cl_context ctx, cl_device_id device_id, const char* path, const char* args) { - return cl_program_from_source(ctx, device_id, util::read_file(path), args); -} - -cl_program cl_program_from_source(cl_context ctx, cl_device_id device_id, const std::string& src, const char* args) { - const char *csrc = src.c_str(); - cl_program prg = CL_CHECK_ERR(clCreateProgramWithSource(ctx, 1, &csrc, NULL, &err)); - if (int err = clBuildProgram(prg, 1, &device_id, args, NULL, NULL); err != 0) { - cl_print_build_errors(prg, device_id); - assert(0); - } - return prg; -} - -cl_program cl_program_from_binary(cl_context ctx, cl_device_id device_id, const uint8_t* binary, size_t length, const char* args) { - cl_program prg = CL_CHECK_ERR(clCreateProgramWithBinary(ctx, 1, &device_id, &length, &binary, NULL, &err)); - if (int err = clBuildProgram(prg, 1, &device_id, args, NULL, NULL); err != 0) { - cl_print_build_errors(prg, device_id); - assert(0); - } - return prg; -} - -// Given a cl code and return a string representation -#define CL_ERR_TO_STR(err) case err: return #err -const char* cl_get_error_string(int err) { - switch (err) { - CL_ERR_TO_STR(CL_SUCCESS); - CL_ERR_TO_STR(CL_DEVICE_NOT_FOUND); - CL_ERR_TO_STR(CL_DEVICE_NOT_AVAILABLE); - CL_ERR_TO_STR(CL_COMPILER_NOT_AVAILABLE); - CL_ERR_TO_STR(CL_MEM_OBJECT_ALLOCATION_FAILURE); - CL_ERR_TO_STR(CL_OUT_OF_RESOURCES); - CL_ERR_TO_STR(CL_OUT_OF_HOST_MEMORY); - CL_ERR_TO_STR(CL_PROFILING_INFO_NOT_AVAILABLE); - CL_ERR_TO_STR(CL_MEM_COPY_OVERLAP); - CL_ERR_TO_STR(CL_IMAGE_FORMAT_MISMATCH); - CL_ERR_TO_STR(CL_IMAGE_FORMAT_NOT_SUPPORTED); - CL_ERR_TO_STR(CL_MAP_FAILURE); - CL_ERR_TO_STR(CL_MISALIGNED_SUB_BUFFER_OFFSET); - CL_ERR_TO_STR(CL_EXEC_STATUS_ERROR_FOR_EVENTS_IN_WAIT_LIST); - CL_ERR_TO_STR(CL_COMPILE_PROGRAM_FAILURE); - CL_ERR_TO_STR(CL_LINKER_NOT_AVAILABLE); - CL_ERR_TO_STR(CL_LINK_PROGRAM_FAILURE); - CL_ERR_TO_STR(CL_DEVICE_PARTITION_FAILED); - CL_ERR_TO_STR(CL_KERNEL_ARG_INFO_NOT_AVAILABLE); - CL_ERR_TO_STR(CL_INVALID_VALUE); - CL_ERR_TO_STR(CL_INVALID_DEVICE_TYPE); - CL_ERR_TO_STR(CL_INVALID_PLATFORM); - CL_ERR_TO_STR(CL_INVALID_DEVICE); - CL_ERR_TO_STR(CL_INVALID_CONTEXT); - CL_ERR_TO_STR(CL_INVALID_QUEUE_PROPERTIES); - CL_ERR_TO_STR(CL_INVALID_COMMAND_QUEUE); - CL_ERR_TO_STR(CL_INVALID_HOST_PTR); - CL_ERR_TO_STR(CL_INVALID_MEM_OBJECT); - CL_ERR_TO_STR(CL_INVALID_IMAGE_FORMAT_DESCRIPTOR); - CL_ERR_TO_STR(CL_INVALID_IMAGE_SIZE); - CL_ERR_TO_STR(CL_INVALID_SAMPLER); - CL_ERR_TO_STR(CL_INVALID_BINARY); - CL_ERR_TO_STR(CL_INVALID_BUILD_OPTIONS); - CL_ERR_TO_STR(CL_INVALID_PROGRAM); - CL_ERR_TO_STR(CL_INVALID_PROGRAM_EXECUTABLE); - CL_ERR_TO_STR(CL_INVALID_KERNEL_NAME); - CL_ERR_TO_STR(CL_INVALID_KERNEL_DEFINITION); - CL_ERR_TO_STR(CL_INVALID_KERNEL); - CL_ERR_TO_STR(CL_INVALID_ARG_INDEX); - CL_ERR_TO_STR(CL_INVALID_ARG_VALUE); - CL_ERR_TO_STR(CL_INVALID_ARG_SIZE); - CL_ERR_TO_STR(CL_INVALID_KERNEL_ARGS); - CL_ERR_TO_STR(CL_INVALID_WORK_DIMENSION); - CL_ERR_TO_STR(CL_INVALID_WORK_GROUP_SIZE); - CL_ERR_TO_STR(CL_INVALID_WORK_ITEM_SIZE); - CL_ERR_TO_STR(CL_INVALID_GLOBAL_OFFSET); - CL_ERR_TO_STR(CL_INVALID_EVENT_WAIT_LIST); - CL_ERR_TO_STR(CL_INVALID_EVENT); - CL_ERR_TO_STR(CL_INVALID_OPERATION); - CL_ERR_TO_STR(CL_INVALID_GL_OBJECT); - CL_ERR_TO_STR(CL_INVALID_BUFFER_SIZE); - CL_ERR_TO_STR(CL_INVALID_MIP_LEVEL); - CL_ERR_TO_STR(CL_INVALID_GLOBAL_WORK_SIZE); - CL_ERR_TO_STR(CL_INVALID_PROPERTY); - CL_ERR_TO_STR(CL_INVALID_IMAGE_DESCRIPTOR); - CL_ERR_TO_STR(CL_INVALID_COMPILER_OPTIONS); - CL_ERR_TO_STR(CL_INVALID_LINKER_OPTIONS); - CL_ERR_TO_STR(CL_INVALID_DEVICE_PARTITION_COUNT); - case -69: return "CL_INVALID_PIPE_SIZE"; - case -70: return "CL_INVALID_DEVICE_QUEUE"; - case -71: return "CL_INVALID_SPEC_ID"; - case -72: return "CL_MAX_SIZE_RESTRICTION_EXCEEDED"; - case -1002: return "CL_INVALID_D3D10_DEVICE_KHR"; - case -1003: return "CL_INVALID_D3D10_RESOURCE_KHR"; - case -1004: return "CL_D3D10_RESOURCE_ALREADY_ACQUIRED_KHR"; - case -1005: return "CL_D3D10_RESOURCE_NOT_ACQUIRED_KHR"; - case -1006: return "CL_INVALID_D3D11_DEVICE_KHR"; - case -1007: return "CL_INVALID_D3D11_RESOURCE_KHR"; - case -1008: return "CL_D3D11_RESOURCE_ALREADY_ACQUIRED_KHR"; - case -1009: return "CL_D3D11_RESOURCE_NOT_ACQUIRED_KHR"; - case -1010: return "CL_INVALID_DX9_MEDIA_ADAPTER_KHR"; - case -1011: return "CL_INVALID_DX9_MEDIA_SURFACE_KHR"; - case -1012: return "CL_DX9_MEDIA_SURFACE_ALREADY_ACQUIRED_KHR"; - case -1013: return "CL_DX9_MEDIA_SURFACE_NOT_ACQUIRED_KHR"; - case -1093: return "CL_INVALID_EGL_OBJECT_KHR"; - case -1092: return "CL_EGL_RESOURCE_NOT_ACQUIRED_KHR"; - case -1001: return "CL_PLATFORM_NOT_FOUND_KHR"; - case -1057: return "CL_DEVICE_PARTITION_FAILED_EXT"; - case -1058: return "CL_INVALID_PARTITION_COUNT_EXT"; - case -1059: return "CL_INVALID_PARTITION_NAME_EXT"; - case -1094: return "CL_INVALID_ACCELERATOR_INTEL"; - case -1095: return "CL_INVALID_ACCELERATOR_TYPE_INTEL"; - case -1096: return "CL_INVALID_ACCELERATOR_DESCRIPTOR_INTEL"; - case -1097: return "CL_ACCELERATOR_TYPE_NOT_SUPPORTED_INTEL"; - case -1000: return "CL_INVALID_GL_SHAREGROUP_REFERENCE_KHR"; - case -1098: return "CL_INVALID_VA_API_MEDIA_ADAPTER_INTEL"; - case -1099: return "CL_INVALID_VA_API_MEDIA_SURFACE_INTEL"; - case -1100: return "CL_VA_API_MEDIA_SURFACE_ALREADY_ACQUIRED_INTEL"; - case -1101: return "CL_VA_API_MEDIA_SURFACE_NOT_ACQUIRED_INTEL"; - default: return "CL_UNKNOWN_ERROR"; - } -} diff --git a/common/clutil.h b/common/clutil.h deleted file mode 100644 index af986d6..0000000 --- a/common/clutil.h +++ /dev/null @@ -1,29 +0,0 @@ -#pragma once - -#ifdef __APPLE__ -#include -#else -#include -#endif - -#include - -#define CL_CHECK(_expr) \ - do { \ - assert(CL_SUCCESS == (_expr)); \ - } while (0) - -#define CL_CHECK_ERR(_expr) \ - ({ \ - cl_int err = CL_INVALID_VALUE; \ - __typeof__(_expr) _ret = _expr; \ - assert(_ret&& err == CL_SUCCESS); \ - _ret; \ - }) - -cl_device_id cl_get_device_id(cl_device_type device_type); -cl_context cl_create_context(cl_device_id device_id); -cl_program cl_program_from_source(cl_context ctx, cl_device_id device_id, const std::string& src, const char* args = nullptr); -cl_program cl_program_from_binary(cl_context ctx, cl_device_id device_id, const uint8_t* binary, size_t length, const char* args = nullptr); -cl_program cl_program_from_file(cl_context ctx, cl_device_id device_id, const char* path, const char* args); -const char* cl_get_error_string(int err); diff --git a/common/gpio.cc b/common/gpio.cc deleted file mode 100644 index dd7ba34..0000000 --- a/common/gpio.cc +++ /dev/null @@ -1,84 +0,0 @@ -#include "common/gpio.h" - -#include - -#ifdef __APPLE__ -int gpio_init(int pin_nr, bool output) { - return 0; -} - -int gpio_set(int pin_nr, bool high) { - return 0; -} - -int gpiochip_get_ro_value_fd(const char* consumer_label, int gpiochiop_id, int pin_nr) { - return 0; -} - -#else - -#include -#include - -#include -#include -#include - -#include "common/util.h" -#include "common/swaglog.h" - -int gpio_init(int pin_nr, bool output) { - char pin_dir_path[50]; - int pin_dir_path_len = snprintf(pin_dir_path, sizeof(pin_dir_path), - "/sys/class/gpio/gpio%d/direction", pin_nr); - if (pin_dir_path_len <= 0) { - return -1; - } - const char *value = output ? "out" : "in"; - return util::write_file(pin_dir_path, (void*)value, strlen(value)); -} - -int gpio_set(int pin_nr, bool high) { - char pin_val_path[50]; - int pin_val_path_len = snprintf(pin_val_path, sizeof(pin_val_path), - "/sys/class/gpio/gpio%d/value", pin_nr); - if (pin_val_path_len <= 0) { - return -1; - } - return util::write_file(pin_val_path, (void*)(high ? "1" : "0"), 1); -} - -int gpiochip_get_ro_value_fd(const char* consumer_label, int gpiochiop_id, int pin_nr) { - - // Assumed that all interrupt pins are unexported and rights are given to - // read from gpiochip0. - std::string gpiochip_path = "/dev/gpiochip" + std::to_string(gpiochiop_id); - int fd = open(gpiochip_path.c_str(), O_RDONLY); - if (fd < 0) { - LOGE("Error opening gpiochip0 fd"); - return -1; - } - - // Setup event - struct gpioevent_request rq; - rq.lineoffset = pin_nr; - rq.handleflags = GPIOHANDLE_REQUEST_INPUT; - - /* Requesting both edges as the data ready pulse from the lsm6ds sensor is - very short(75us) and is mostly detected as falling edge instead of rising. - So if it is detected as rising the following falling edge is skipped. */ - rq.eventflags = GPIOEVENT_REQUEST_BOTH_EDGES; - - strncpy(rq.consumer_label, consumer_label, std::size(rq.consumer_label) - 1); - int ret = util::safe_ioctl(fd, GPIO_GET_LINEEVENT_IOCTL, &rq); - if (ret == -1) { - LOGE("Unable to get line event from ioctl : %s", strerror(errno)); - close(fd); - return -1; - } - - close(fd); - return rq.fd; -} - -#endif diff --git a/common/gpio.h b/common/gpio.h deleted file mode 100644 index 89cdedd..0000000 --- a/common/gpio.h +++ /dev/null @@ -1,33 +0,0 @@ -#pragma once - -// Pin definitions -#ifdef QCOM2 - #define GPIO_HUB_RST_N 30 - #define GPIO_UBLOX_RST_N 32 - #define GPIO_UBLOX_SAFEBOOT_N 33 - #define GPIO_GNSS_PWR_EN 34 /* SCHEMATIC LABEL: GPIO_UBLOX_PWR_EN */ - #define GPIO_STM_RST_N 124 - #define GPIO_STM_BOOT0 134 - #define GPIO_BMX_ACCEL_INT 21 - #define GPIO_BMX_GYRO_INT 23 - #define GPIO_BMX_MAGN_INT 87 - #define GPIO_LSM_INT 84 - #define GPIOCHIP_INT 0 -#else - #define GPIO_HUB_RST_N 0 - #define GPIO_UBLOX_RST_N 0 - #define GPIO_UBLOX_SAFEBOOT_N 0 - #define GPIO_GNSS_PWR_EN 0 /* SCHEMATIC LABEL: GPIO_UBLOX_PWR_EN */ - #define GPIO_STM_RST_N 0 - #define GPIO_STM_BOOT0 0 - #define GPIO_BMX_ACCEL_INT 0 - #define GPIO_BMX_GYRO_INT 0 - #define GPIO_BMX_MAGN_INT 0 - #define GPIO_LSM_INT 0 - #define GPIOCHIP_INT 0 -#endif - -int gpio_init(int pin_nr, bool output); -int gpio_set(int pin_nr, bool high); - -int gpiochip_get_ro_value_fd(const char* consumer_label, int gpiochiop_id, int pin_nr); diff --git a/common/i2c.cc b/common/i2c.cc deleted file mode 100644 index 3d6c79e..0000000 --- a/common/i2c.cc +++ /dev/null @@ -1,92 +0,0 @@ -#include "common/i2c.h" - -#include -#include -#include - -#include -#include -#include - -#include "common/swaglog.h" -#include "common/util.h" - -#define UNUSED(x) (void)(x) - -#ifdef QCOM2 -// TODO: decide if we want to install libi2c-dev everywhere -extern "C" { - #include - #include -} - -I2CBus::I2CBus(uint8_t bus_id) { - char bus_name[20]; - snprintf(bus_name, 20, "/dev/i2c-%d", bus_id); - - i2c_fd = HANDLE_EINTR(open(bus_name, O_RDWR)); - if (i2c_fd < 0) { - throw std::runtime_error("Failed to open I2C bus"); - } -} - -I2CBus::~I2CBus() { - if (i2c_fd >= 0) { - close(i2c_fd); - } -} - -int I2CBus::read_register(uint8_t device_address, uint register_address, uint8_t *buffer, uint8_t len) { - std::lock_guard lk(m); - - int ret = 0; - - ret = HANDLE_EINTR(ioctl(i2c_fd, I2C_SLAVE, device_address)); - if (ret < 0) { goto fail; } - - ret = i2c_smbus_read_i2c_block_data(i2c_fd, register_address, len, buffer); - if ((ret < 0) || (ret != len)) { goto fail; } - -fail: - return ret; -} - -int I2CBus::set_register(uint8_t device_address, uint register_address, uint8_t data) { - std::lock_guard lk(m); - - int ret = 0; - - ret = HANDLE_EINTR(ioctl(i2c_fd, I2C_SLAVE, device_address)); - if (ret < 0) { goto fail; } - - ret = i2c_smbus_write_byte_data(i2c_fd, register_address, data); - if (ret < 0) { goto fail; } - -fail: - return ret; -} - -#else - -I2CBus::I2CBus(uint8_t bus_id) { - UNUSED(bus_id); - i2c_fd = -1; -} - -I2CBus::~I2CBus() {} - -int I2CBus::read_register(uint8_t device_address, uint register_address, uint8_t *buffer, uint8_t len) { - UNUSED(device_address); - UNUSED(register_address); - UNUSED(buffer); - UNUSED(len); - return -1; -} - -int I2CBus::set_register(uint8_t device_address, uint register_address, uint8_t data) { - UNUSED(device_address); - UNUSED(register_address); - UNUSED(data); - return -1; -} -#endif diff --git a/common/i2c.h b/common/i2c.h deleted file mode 100644 index ca0d463..0000000 --- a/common/i2c.h +++ /dev/null @@ -1,19 +0,0 @@ -#pragma once - -#include -#include - -#include - -class I2CBus { - private: - int i2c_fd; - std::mutex m; - - public: - I2CBus(uint8_t bus_id); - ~I2CBus(); - - int read_register(uint8_t device_address, uint register_address, uint8_t *buffer, uint8_t len); - int set_register(uint8_t device_address, uint register_address, uint8_t data); -}; diff --git a/common/mat.h b/common/mat.h deleted file mode 100644 index 8e10d61..0000000 --- a/common/mat.h +++ /dev/null @@ -1,85 +0,0 @@ -#pragma once - -typedef struct vec3 { - float v[3]; -} vec3; - -typedef struct vec4 { - float v[4]; -} vec4; - -typedef struct mat3 { - float v[3*3]; -} mat3; - -typedef struct mat4 { - float v[4*4]; -} mat4; - -static inline mat3 matmul3(const mat3 &a, const mat3 &b) { - mat3 ret = {{0.0}}; - for (int r=0; r<3; r++) { - for (int c=0; c<3; c++) { - float v = 0.0; - for (int k=0; k<3; k++) { - v += a.v[r*3+k] * b.v[k*3+c]; - } - ret.v[r*3+c] = v; - } - } - return ret; -} - -static inline vec3 matvecmul3(const mat3 &a, const vec3 &b) { - vec3 ret = {{0.0}}; - for (int r=0; r<3; r++) { - for (int c=0; c<3; c++) { - ret.v[r] += a.v[r*3+c] * b.v[c]; - } - } - return ret; -} - -static inline mat4 matmul(const mat4 &a, const mat4 &b) { - mat4 ret = {{0.0}}; - for (int r=0; r<4; r++) { - for (int c=0; c<4; c++) { - float v = 0.0; - for (int k=0; k<4; k++) { - v += a.v[r*4+k] * b.v[k*4+c]; - } - ret.v[r*4+c] = v; - } - } - return ret; -} - -static inline vec4 matvecmul(const mat4 &a, const vec4 &b) { - vec4 ret = {{0.0}}; - for (int r=0; r<4; r++) { - for (int c=0; c<4; c++) { - ret.v[r] += a.v[r*4+c] * b.v[c]; - } - } - return ret; -} - -// scales the input and output space of a transformation matrix -// that assumes pixel-center origin. -static inline mat3 transform_scale_buffer(const mat3 &in, float s) { - // in_pt = ( transform(out_pt/s + 0.5) - 0.5) * s - - mat3 transform_out = {{ - 1.0f/s, 0.0f, 0.5f, - 0.0f, 1.0f/s, 0.5f, - 0.0f, 0.0f, 1.0f, - }}; - - mat3 transform_in = {{ - s, 0.0f, -0.5f*s, - 0.0f, s, -0.5f*s, - 0.0f, 0.0f, 1.0f, - }}; - - return matmul3(transform_in, matmul3(in, transform_out)); -} diff --git a/common/params.cc b/common/params.cc deleted file mode 100644 index ee12627..0000000 --- a/common/params.cc +++ /dev/null @@ -1,581 +0,0 @@ -#include "common/params.h" - -#include -#include - -#include -#include -#include -#include - -#include "common/queue.h" -#include "common/swaglog.h" -#include "common/util.h" -#include "system/hardware/hw.h" - -namespace { - -volatile sig_atomic_t params_do_exit = 0; -void params_sig_handler(int signal) { - params_do_exit = 1; -} - -int fsync_dir(const std::string &path) { - int result = -1; - int fd = HANDLE_EINTR(open(path.c_str(), O_RDONLY, 0755)); - if (fd >= 0) { - result = fsync(fd); - close(fd); - } - return result; -} - -bool create_params_path(const std::string ¶m_path, const std::string &key_path) { - // Make sure params path exists - if (!util::file_exists(param_path) && !util::create_directories(param_path, 0775)) { - return false; - } - - // See if the symlink exists, otherwise create it - if (!util::file_exists(key_path)) { - // 1) Create temp folder - // 2) Symlink it to temp link - // 3) Move symlink to /d - - std::string tmp_path = param_path + "/.tmp_XXXXXX"; - // this should be OK since mkdtemp just replaces characters in place - char *tmp_dir = mkdtemp((char *)tmp_path.c_str()); - if (tmp_dir == NULL) { - return false; - } - - std::string link_path = std::string(tmp_dir) + ".link"; - if (symlink(tmp_dir, link_path.c_str()) != 0) { - return false; - } - - // don't return false if it has been created by other - if (rename(link_path.c_str(), key_path.c_str()) != 0 && errno != EEXIST) { - return false; - } - } - - return true; -} - -std::string ensure_params_path(const std::string &prefix, const std::string &path = {}) { - std::string params_path = path.empty() ? Path::params() : path; - if (!create_params_path(params_path, params_path + prefix)) { - throw std::runtime_error(util::string_format( - "Failed to ensure params path, errno=%d, path=%s, param_prefix=%s", - errno, params_path.c_str(), prefix.c_str())); - } - return params_path; -} - -class FileLock { -public: - FileLock(const std::string &fn) { - fd_ = HANDLE_EINTR(open(fn.c_str(), O_CREAT, 0775)); - if (fd_ < 0 || HANDLE_EINTR(flock(fd_, LOCK_EX)) < 0) { - LOGE("Failed to lock file %s, errno=%d", fn.c_str(), errno); - } - } - ~FileLock() { close(fd_); } - -private: - int fd_ = -1; -}; - -std::unordered_map keys = { - {"AccessToken", CLEAR_ON_MANAGER_START | DONT_LOG}, - {"ApiCache_Device", PERSISTENT}, - {"ApiCache_NavDestinations", PERSISTENT}, - {"AssistNowToken", PERSISTENT}, - {"AthenadPid", PERSISTENT}, - {"AthenadUploadQueue", PERSISTENT}, - {"AthenadRecentlyViewedRoutes", PERSISTENT}, - {"BootCount", PERSISTENT}, - {"CalibrationParams", PERSISTENT}, - {"CameraDebugExpGain", CLEAR_ON_MANAGER_START}, - {"CameraDebugExpTime", CLEAR_ON_MANAGER_START}, - {"CarBatteryCapacity", PERSISTENT}, - {"CarParams", CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION}, - {"CarParamsCache", CLEAR_ON_MANAGER_START}, - {"CarParamsPersistent", PERSISTENT}, - {"CarParamsPrevRoute", PERSISTENT}, - {"CarVin", CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION}, - {"CompletedTrainingVersion", PERSISTENT}, - {"ControlsReady", CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION}, - {"CurrentBootlog", PERSISTENT}, - {"CurrentRoute", CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION}, - {"DisableLogging", CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION}, - {"DisablePowerDown", PERSISTENT}, - {"DisableUpdates", PERSISTENT}, - {"DisengageOnAccelerator", PERSISTENT}, - {"DmModelInitialized", CLEAR_ON_ONROAD_TRANSITION}, - {"DongleId", PERSISTENT}, - {"DoReboot", CLEAR_ON_MANAGER_START}, - {"DoShutdown", CLEAR_ON_MANAGER_START}, - {"DoUninstall", CLEAR_ON_MANAGER_START}, - {"ExperimentalLongitudinalEnabled", PERSISTENT | DEVELOPMENT_ONLY}, - {"ExperimentalMode", PERSISTENT}, - {"ExperimentalModeConfirmed", PERSISTENT}, - {"FirmwareQueryDone", CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION}, - {"ForcePowerDown", PERSISTENT}, - {"GitBranch", PERSISTENT}, - {"GitCommit", PERSISTENT}, - {"GitCommitDate", PERSISTENT}, - {"GitDiff", PERSISTENT}, - {"GithubSshKeys", PERSISTENT}, - {"GithubUsername", PERSISTENT}, - {"GitRemote", PERSISTENT}, - {"GsmApn", PERSISTENT}, - {"GsmMetered", PERSISTENT}, - {"GsmRoaming", PERSISTENT}, - {"HardwareSerial", PERSISTENT}, - {"HasAcceptedTerms", PERSISTENT}, - {"IMEI", PERSISTENT}, - {"InstallDate", PERSISTENT}, - {"IsDriverViewEnabled", CLEAR_ON_MANAGER_START}, - {"IsEngaged", PERSISTENT}, - {"IsLdwEnabled", PERSISTENT}, - {"IsMetric", PERSISTENT}, - {"IsOffroad", CLEAR_ON_MANAGER_START}, - {"IsOnroad", PERSISTENT}, - {"IsRhdDetected", PERSISTENT}, - {"IsReleaseBranch", CLEAR_ON_MANAGER_START}, - {"IsTakingSnapshot", CLEAR_ON_MANAGER_START}, - {"IsTestedBranch", CLEAR_ON_MANAGER_START}, - {"JoystickDebugMode", CLEAR_ON_MANAGER_START | CLEAR_ON_OFFROAD_TRANSITION}, - {"LanguageSetting", PERSISTENT}, - {"LastAthenaPingTime", CLEAR_ON_MANAGER_START}, - {"LastGPSPosition", PERSISTENT}, - {"LastManagerExitReason", CLEAR_ON_MANAGER_START}, - {"LastOffroadStatusPacket", CLEAR_ON_MANAGER_START | CLEAR_ON_OFFROAD_TRANSITION}, - {"LastPowerDropDetected", CLEAR_ON_MANAGER_START}, - {"LastUpdateException", CLEAR_ON_MANAGER_START}, - {"LastUpdateTime", PERSISTENT}, - {"LiveParameters", PERSISTENT}, - {"LiveTorqueParameters", PERSISTENT | DONT_LOG}, - {"LongitudinalPersonality", PERSISTENT}, - {"NavDestination", CLEAR_ON_MANAGER_START | CLEAR_ON_OFFROAD_TRANSITION}, - {"NavDestinationWaypoints", CLEAR_ON_MANAGER_START | CLEAR_ON_OFFROAD_TRANSITION}, - {"NavPastDestinations", PERSISTENT}, - {"NavSettingLeftSide", PERSISTENT}, - {"NavSettingTime24h", PERSISTENT}, - {"NetworkMetered", PERSISTENT}, - {"ObdMultiplexingChanged", CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION}, - {"ObdMultiplexingEnabled", CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION}, - {"Offroad_BadNvme", CLEAR_ON_MANAGER_START}, - {"Offroad_CarUnrecognized", CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION}, - {"Offroad_ConnectivityNeeded", CLEAR_ON_MANAGER_START}, - {"Offroad_ConnectivityNeededPrompt", CLEAR_ON_MANAGER_START}, - {"Offroad_InvalidTime", CLEAR_ON_MANAGER_START}, - {"Offroad_IsTakingSnapshot", CLEAR_ON_MANAGER_START}, - {"Offroad_NeosUpdate", CLEAR_ON_MANAGER_START}, - {"Offroad_NoFirmware", CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION}, - {"Offroad_Recalibration", CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION}, - {"Offroad_StorageMissing", CLEAR_ON_MANAGER_START}, - {"Offroad_TemperatureTooHigh", CLEAR_ON_MANAGER_START}, - {"Offroad_UnofficialHardware", CLEAR_ON_MANAGER_START}, - {"Offroad_UpdateFailed", CLEAR_ON_MANAGER_START}, - {"OpenpilotEnabledToggle", PERSISTENT}, - {"PandaHeartbeatLost", CLEAR_ON_MANAGER_START | CLEAR_ON_OFFROAD_TRANSITION}, - {"PandaSomResetTriggered", CLEAR_ON_MANAGER_START | CLEAR_ON_OFFROAD_TRANSITION}, - {"PandaSignatures", CLEAR_ON_MANAGER_START}, - {"PrimeType", PERSISTENT}, - {"RecordFront", PERSISTENT}, - {"RecordFrontLock", PERSISTENT}, // for the internal fleet - {"ReplayControlsState", CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION}, - {"SnoozeUpdate", CLEAR_ON_MANAGER_START | CLEAR_ON_OFFROAD_TRANSITION}, - {"SshEnabled", PERSISTENT}, - {"TermsVersion", PERSISTENT}, - {"Timezone", PERSISTENT}, - {"TrainingVersion", PERSISTENT}, - {"UbloxAvailable", PERSISTENT}, - {"UpdateAvailable", CLEAR_ON_MANAGER_START | CLEAR_ON_ONROAD_TRANSITION}, - {"UpdateFailedCount", CLEAR_ON_MANAGER_START}, - {"UpdaterAvailableBranches", PERSISTENT}, - {"UpdaterCurrentDescription", CLEAR_ON_MANAGER_START}, - {"UpdaterCurrentReleaseNotes", CLEAR_ON_MANAGER_START}, - {"UpdaterFetchAvailable", CLEAR_ON_MANAGER_START}, - {"UpdaterNewDescription", CLEAR_ON_MANAGER_START}, - {"UpdaterNewReleaseNotes", CLEAR_ON_MANAGER_START}, - {"UpdaterState", CLEAR_ON_MANAGER_START}, - {"UpdaterTargetBranch", CLEAR_ON_MANAGER_START}, - {"UpdaterLastFetchTime", PERSISTENT}, - {"Version", PERSISTENT}, - {"VisionRadarToggle", PERSISTENT}, - - // FrogPilot parameters - {"AccelerationPath", PERSISTENT}, - {"AccelerationProfile", PERSISTENT}, - {"AdjacentPath", PERSISTENT}, - {"AdjacentPathMetrics", PERSISTENT}, - {"AdjustablePersonalities", PERSISTENT}, - {"AggressiveAcceleration", PERSISTENT}, - {"AggressiveFollow", PERSISTENT}, - {"AggressiveJerk", PERSISTENT}, - {"AlertVolumeControl", PERSISTENT}, - {"AlwaysOnLateral", PERSISTENT}, - {"AlwaysOnLateralMain", PERSISTENT}, - {"AMapKey1", PERSISTENT}, - {"AMapKey2", PERSISTENT}, - {"ApiCache_DriveStats", PERSISTENT}, - {"BlindSpotPath", PERSISTENT}, - {"CameraFPS", PERSISTENT}, - {"CameraView", PERSISTENT}, - {"CarMake", PERSISTENT}, - {"CarModel", PERSISTENT}, - {"CarSpeedLimit", PERSISTENT}, - {"CECurves", PERSISTENT}, - {"CECurvesLead", PERSISTENT}, - {"CENavigation", PERSISTENT}, - {"CENavigationIntersections", PERSISTENT}, - {"CENavigationLead", PERSISTENT}, - {"CENavigationTurns", PERSISTENT}, - {"CESignal", PERSISTENT}, - {"CESlowerLead", PERSISTENT}, - {"CESpeed", PERSISTENT}, - {"CESpeedLead", PERSISTENT}, - {"CEStatus", PERSISTENT}, - {"CEStopLights", PERSISTENT}, - {"CEStopLightsLead", PERSISTENT}, - {"Compass", PERSISTENT}, - {"ConditionalExperimental", PERSISTENT}, - {"CrosstrekTorque", PERSISTENT}, - {"CurrentHolidayTheme", PERSISTENT}, - {"CurrentRandomEvent", PERSISTENT}, - {"CurveSensitivity", PERSISTENT}, - {"CustomAlerts", PERSISTENT}, - {"CustomColors", PERSISTENT}, - {"CustomIcons", PERSISTENT}, - {"CustomPersonalities", PERSISTENT}, - {"CustomUI", PERSISTENT}, - {"CustomSignals", PERSISTENT}, - {"CustomSounds", PERSISTENT}, - {"CustomTheme", PERSISTENT}, - {"CydiaTune", PERSISTENT}, - {"DecelerationProfile", PERSISTENT}, - {"DeviceShutdown", PERSISTENT}, - {"DisableMTSCSmoothing", PERSISTENT}, - {"DisableOnroadUploads", PERSISTENT}, - {"DisableOpenpilotLongitudinal", PERSISTENT}, - {"DisableVTSCSmoothing", PERSISTENT}, - {"DisengageVolume", PERSISTENT}, - {"DoSoftReboot", CLEAR_ON_MANAGER_START}, - {"DragonPilotTune", PERSISTENT}, - {"DriverCamera", PERSISTENT}, - {"DriveStats", PERSISTENT}, - {"DynamicPathWidth", PERSISTENT}, - {"EngageVolume", PERSISTENT}, - {"EVTable", PERSISTENT}, - {"ExperimentalModeActivation", PERSISTENT}, - {"ExperimentalModeViaDistance", PERSISTENT}, - {"ExperimentalModeViaLKAS", PERSISTENT}, - {"ExperimentalModeViaScreen", PERSISTENT}, - {"Fahrenheit", PERSISTENT}, - {"FireTheBabysitter", PERSISTENT}, - {"ForceAutoTune", PERSISTENT}, - {"ForceFingerprint", PERSISTENT}, - {"ForceMPHDashboard", PERSISTENT}, - {"FPSCounter", PERSISTENT}, - {"FrogPilotDrives", PERSISTENT}, - {"FrogPilotKilometers", PERSISTENT}, - {"FrogPilotMinutes", PERSISTENT}, - {"FrogPilotTogglesUpdated", PERSISTENT}, - {"FrogsGoMoo", PERSISTENT}, - {"FrogsGoMooTune", PERSISTENT}, - {"FullMap", PERSISTENT}, - {"GasRegenCmd", PERSISTENT}, - {"GMapKey", PERSISTENT}, - {"GoatScream", PERSISTENT}, - {"GreenLightAlert", PERSISTENT}, - {"HideAlerts", PERSISTENT}, - {"HideAOLStatusBar", PERSISTENT}, - {"HideCEMStatusBar", PERSISTENT}, - {"HideLeadMarker", PERSISTENT}, - {"HideMapIcon", PERSISTENT}, - {"HideMaxSpeed", PERSISTENT}, - {"HideSpeed", PERSISTENT}, - {"HideSpeedUI", PERSISTENT}, - {"HideUIElements", PERSISTENT}, - {"HigherBitrate", PERSISTENT}, - {"HolidayThemes", PERSISTENT}, - {"LaneChangeTime", PERSISTENT}, - {"LaneDetection", PERSISTENT}, - {"LaneDetectionWidth", PERSISTENT}, - {"LaneLinesWidth", PERSISTENT}, - {"LastMapsUpdate", PERSISTENT}, - {"LateralTune", PERSISTENT}, - {"LeadDepartingAlert", PERSISTENT}, - {"LeadDetectionThreshold", PERSISTENT}, - {"LeadInfo", PERSISTENT}, - {"LockDoors", PERSISTENT}, - {"LongitudinalTune", PERSISTENT}, - {"LongPitch", PERSISTENT}, - {"LoudBlindspotAlert", PERSISTENT}, - {"LowerVolt", PERSISTENT}, - {"ManualUpdateInitiated", CLEAR_ON_MANAGER_START}, - {"MapboxPublicKey", PERSISTENT}, - {"MapboxSecretKey", PERSISTENT}, - {"MapsSelected", PERSISTENT}, - {"MapSpeedLimit", PERSISTENT}, - {"MapSpeedLimitControl", PERSISTENT}, - {"MapStyle", PERSISTENT}, - {"MapTargetLatA", PERSISTENT}, - {"MapTargetVelocities", PERSISTENT}, - {"Model", PERSISTENT}, - {"ModelUI", PERSISTENT}, - {"MTSCAggressiveness", PERSISTENT}, - {"MTSCCurvatureCheck", PERSISTENT}, - {"MTSCEnabled", PERSISTENT}, - {"MTSCLimit", PERSISTENT}, - {"MuteOverheated", PERSISTENT}, - {"NavChill", PERSISTENT}, - {"NavEnable", PERSISTENT}, - {"NavSpeedLimit", PERSISTENT}, - {"NavSpeedLimitControl", PERSISTENT}, - {"NNFF", PERSISTENT}, - {"NNFFModelFuzzyMatch", PERSISTENT}, - {"NNFFModelName", PERSISTENT}, - {"NoLogging", PERSISTENT}, - {"NoUploads", PERSISTENT}, - {"NudgelessLaneChange", PERSISTENT}, - {"NumericalTemp", PERSISTENT}, - {"OfflineMode", PERSISTENT}, - {"Offset1", PERSISTENT}, - {"Offset2", PERSISTENT}, - {"Offset3", PERSISTENT}, - {"Offset4", PERSISTENT}, - {"OneLaneChange", PERSISTENT}, - {"OSMDownloadLocations", PERSISTENT}, - {"OSMDownloadProgress", CLEAR_ON_MANAGER_START}, - {"PathEdgeWidth", PERSISTENT}, - {"PathWidth", PERSISTENT}, - {"PauseLateralOnSignal", PERSISTENT}, - {"PedalsOnUI", PERSISTENT}, - {"PersonalitiesViaScreen", PERSISTENT}, - {"PersonalitiesViaWheel", PERSISTENT}, - {"PersonalityChangedViaUI", PERSISTENT}, - {"PersonalityChangedViaWheel", PERSISTENT}, - {"PreferredSchedule", PERSISTENT}, - {"PreviousSpeedLimit", PERSISTENT}, - {"PromptVolume", PERSISTENT}, - {"PromptDistractedVolume", PERSISTENT}, - {"QOLControls", PERSISTENT}, - {"QOLVisuals", PERSISTENT}, - {"RandomEvents", PERSISTENT}, - {"RefuseVolume", PERSISTENT}, - {"RelaxedFollow", PERSISTENT}, - {"RelaxedJerk", PERSISTENT}, - {"ReverseCruise", PERSISTENT}, - {"ReverseCruiseUI", PERSISTENT}, - {"RoadEdgesWidth", PERSISTENT}, - {"RoadName", PERSISTENT}, - {"RoadNameUI", PERSISTENT}, - {"RotatingWheel", PERSISTENT}, - {"SchedulePending", PERSISTENT}, - {"ScreenBrightness", PERSISTENT}, - {"ScreenBrightnessOnroad", PERSISTENT}, - {"ScreenManagement", PERSISTENT}, - {"ScreenRecorder", PERSISTENT}, - {"ScreenTimeout", PERSISTENT}, - {"ScreenTimeoutOnroad", PERSISTENT}, - {"SearchInput", PERSISTENT}, - {"SetSpeedLimit", PERSISTENT}, - {"SetSpeedOffset", PERSISTENT}, - {"SilentMode", PERSISTENT}, - {"ShowCPU", PERSISTENT}, - {"ShowGPU", PERSISTENT}, - {"ShowIP", PERSISTENT}, - {"ShowMemoryUsage", PERSISTENT}, - {"ShowSLCOffset", PERSISTENT}, - {"ShowSLCOffsetUI", PERSISTENT}, - {"ShowStorageLeft", PERSISTENT}, - {"ShowStorageUsed", PERSISTENT}, - {"Sidebar", PERSISTENT}, - {"SLCConfirmation", PERSISTENT}, - {"SLCConfirmationLower", PERSISTENT}, - {"SLCConfirmationHigher", PERSISTENT}, - {"SLCConfirmed", PERSISTENT}, - {"SLCConfirmedPressed", PERSISTENT}, - {"SLCFallback", PERSISTENT}, - {"SLCOverride", PERSISTENT}, - {"SLCPriority", PERSISTENT}, - {"SLCPriority1", PERSISTENT}, - {"SLCPriority2", PERSISTENT}, - {"SLCPriority3", PERSISTENT}, - {"SmoothBraking", PERSISTENT}, - {"SNGHack", PERSISTENT}, - {"SpeedLimitController", PERSISTENT}, - {"SpeedLimitChangedAlert", PERSISTENT}, - {"StandardFollow", PERSISTENT}, - {"StandardJerk", PERSISTENT}, - {"StandbyMode", PERSISTENT}, - {"SteerRatio", PERSISTENT}, - {"SteerRatioStock", PERSISTENT}, - {"StockTune", PERSISTENT}, - {"StoppingDistance", PERSISTENT}, - {"TetheringEnabled", PERSISTENT}, - {"TrafficMode", PERSISTENT}, - {"TrafficModeActive", PERSISTENT}, - {"TurnAggressiveness", PERSISTENT}, - {"TurnDesires", PERSISTENT}, - {"UnlimitedLength", PERSISTENT}, - {"Updated", PERSISTENT}, - {"UpdateSchedule", PERSISTENT}, - {"UpdateTime", PERSISTENT}, - {"UseLateralJerk", PERSISTENT}, - {"UseSI", PERSISTENT}, - {"UseVienna", PERSISTENT}, - {"VisionTurnControl", PERSISTENT}, - {"WarningSoftVolume", PERSISTENT}, - {"WarningImmediateVolume", PERSISTENT}, - {"WheelIcon", PERSISTENT}, - {"WheelSpeed", PERSISTENT}, -}; - -} // namespace - - -Params::Params(const std::string &path) { - params_prefix = "/" + util::getenv("OPENPILOT_PREFIX", "d"); - params_path = ensure_params_path(params_prefix, path); -} - -Params::~Params() { - if (future.valid()) { - future.wait(); - } - assert(queue.empty()); -} - -std::vector Params::allKeys() const { - std::vector ret; - for (auto &p : keys) { - ret.push_back(p.first); - } - return ret; -} - -bool Params::checkKey(const std::string &key) { - return keys.find(key) != keys.end(); -} - -ParamKeyType Params::getKeyType(const std::string &key) { - return static_cast(keys[key]); -} - -int Params::put(const char* key, const char* value, size_t value_size) { - // Information about safely and atomically writing a file: https://lwn.net/Articles/457667/ - // 1) Create temp file - // 2) Write data to temp file - // 3) fsync() the temp file - // 4) rename the temp file to the real name - // 5) fsync() the containing directory - std::string tmp_path = params_path + "/.tmp_value_XXXXXX"; - int tmp_fd = mkstemp((char*)tmp_path.c_str()); - if (tmp_fd < 0) return -1; - - int result = -1; - do { - // Write value to temp. - ssize_t bytes_written = HANDLE_EINTR(write(tmp_fd, value, value_size)); - if (bytes_written < 0 || (size_t)bytes_written != value_size) { - result = -20; - break; - } - - // fsync to force persist the changes. - if ((result = fsync(tmp_fd)) < 0) break; - - FileLock file_lock(params_path + "/.lock"); - - // Move temp into place. - if ((result = rename(tmp_path.c_str(), getParamPath(key).c_str())) < 0) break; - - // fsync parent directory - result = fsync_dir(getParamPath()); - } while (false); - - close(tmp_fd); - ::unlink(tmp_path.c_str()); - return result; -} - -int Params::remove(const std::string &key) { - FileLock file_lock(params_path + "/.lock"); - int result = unlink(getParamPath(key).c_str()); - if (result != 0) { - return result; - } - return fsync_dir(getParamPath()); -} - -std::string Params::get(const std::string &key, bool block) { - if (!block) { - return util::read_file(getParamPath(key)); - } else { - // blocking read until successful - params_do_exit = 0; - void (*prev_handler_sigint)(int) = std::signal(SIGINT, params_sig_handler); - void (*prev_handler_sigterm)(int) = std::signal(SIGTERM, params_sig_handler); - - std::string value; - while (!params_do_exit) { - if (value = util::read_file(getParamPath(key)); !value.empty()) { - break; - } - util::sleep_for(100); // 0.1 s - } - - std::signal(SIGINT, prev_handler_sigint); - std::signal(SIGTERM, prev_handler_sigterm); - return value; - } -} - -std::map Params::readAll() { - FileLock file_lock(params_path + "/.lock"); - return util::read_files_in_dir(getParamPath()); -} - -void Params::clearAll(ParamKeyType key_type) { - FileLock file_lock(params_path + "/.lock"); - - // 1) delete params of key_type - // 2) delete files that are not defined in the keys. - if (DIR *d = opendir(getParamPath().c_str())) { - struct dirent *de = NULL; - while ((de = readdir(d))) { - if (de->d_type != DT_DIR) { - auto it = keys.find(de->d_name); - if (it == keys.end() || (it->second & key_type)) { - unlink(getParamPath(de->d_name).c_str()); - } - } - } - closedir(d); - } - - fsync_dir(getParamPath()); -} - -void Params::putNonBlocking(const std::string &key, const std::string &val) { - queue.push(std::make_pair(key, val)); - // start thread on demand - if (!future.valid() || future.wait_for(std::chrono::milliseconds(0)) == std::future_status::ready) { - future = std::async(std::launch::async, &Params::asyncWriteThread, this); - } -} - -void Params::asyncWriteThread() { - // TODO: write the latest one if a key has multiple values in the queue. - std::pair p; - while (queue.try_pop(p, 0)) { - // Params::put is Thread-Safe - put(p.first, p.second); - } -} diff --git a/common/params.h b/common/params.h deleted file mode 100644 index 9c8af82..0000000 --- a/common/params.h +++ /dev/null @@ -1,92 +0,0 @@ -#pragma once - -#include -#include -#include -#include -#include -#include - -#include "common/queue.h" - -enum ParamKeyType { - PERSISTENT = 0x02, - CLEAR_ON_MANAGER_START = 0x04, - CLEAR_ON_ONROAD_TRANSITION = 0x08, - CLEAR_ON_OFFROAD_TRANSITION = 0x10, - DONT_LOG = 0x20, - DEVELOPMENT_ONLY = 0x40, - ALL = 0xFFFFFFFF -}; - -class Params { -public: - explicit Params(const std::string &path = {}); - ~Params(); - // Not copyable. - Params(const Params&) = delete; - Params& operator=(const Params&) = delete; - - std::vector allKeys() const; - bool checkKey(const std::string &key); - ParamKeyType getKeyType(const std::string &key); - inline std::string getParamPath(const std::string &key = {}) { - return params_path + params_prefix + (key.empty() ? "" : "/" + key); - } - - // Delete a value - int remove(const std::string &key); - void clearAll(ParamKeyType type); - - // helpers for reading values - std::string get(const std::string &key, bool block = false); - inline bool getBool(const std::string &key, bool block = false) { - return get(key, block) == "1"; - } - inline int getInt(const std::string &key, bool block = false) { - std::string value = get(key, block); - return value.empty() ? 0 : std::stoi(value); - } - inline float getFloat(const std::string &key, bool block = false) { - std::string value = get(key, block); - return value.empty() ? 0.0 : std::stof(value); - } - std::map readAll(); - - // helpers for writing values - int put(const char *key, const char *val, size_t value_size); - inline int put(const std::string &key, const std::string &val) { - return put(key.c_str(), val.data(), val.size()); - } - inline int putBool(const std::string &key, bool val) { - return put(key.c_str(), val ? "1" : "0", 1); - } - inline int putInt(const std::string &key, int val) { - return put(key.c_str(), std::to_string(val).c_str(), std::to_string(val).size()); - } - inline int putFloat(const std::string &key, float val) { - return put(key.c_str(), std::to_string(val).c_str(), std::to_string(val).size()); - } - void putNonBlocking(const std::string &key, const std::string &val); - inline void putBoolNonBlocking(const std::string &key, bool val) { - putNonBlocking(key, val ? "1" : "0"); - } - void putIntNonBlocking(const std::string &key, const std::string &val); - inline void putIntNonBlocking(const std::string &key, int val) { - putNonBlocking(key, std::to_string(val)); - } - void putFloatNonBlocking(const std::string &key, const std::string &val); - inline void putFloatNonBlocking(const std::string &key, float val) { - putNonBlocking(key, std::to_string(val)); - } - -private: - void asyncWriteThread(); - - std::string params_path; - std::string params_prefix; - - // for nonblocking write - std::future future; - SafeQueue> queue; -}; diff --git a/common/params_pyx.cpp b/common/params_pyx.cpp new file mode 100644 index 0000000..6e28104 --- /dev/null +++ b/common/params_pyx.cpp @@ -0,0 +1,19684 @@ +/* Generated by Cython 3.0.8 */ + +/* BEGIN: Cython Metadata +{ + "distutils": { + "depends": [ + "common/params.h" + ], + "language": "c++", + "name": "common.params_pyx", + "sources": [ + "/data/openpilot/common/params_pyx.pyx" + ] + }, + "module_name": "common.params_pyx" +} +END: Cython Metadata */ + +#ifndef PY_SSIZE_T_CLEAN +#define PY_SSIZE_T_CLEAN +#endif /* PY_SSIZE_T_CLEAN */ +#if defined(CYTHON_LIMITED_API) && 0 + #ifndef Py_LIMITED_API + #if CYTHON_LIMITED_API+0 > 0x03030000 + #define Py_LIMITED_API CYTHON_LIMITED_API + #else + #define Py_LIMITED_API 0x03030000 + #endif + #endif +#endif + +#include "Python.h" +#ifndef Py_PYTHON_H + #error Python headers needed to compile C extensions, please install development version of Python. +#elif PY_VERSION_HEX < 0x02070000 || (0x03000000 <= PY_VERSION_HEX && PY_VERSION_HEX < 0x03030000) + #error Cython requires Python 2.7+ or Python 3.3+. +#else +#if defined(CYTHON_LIMITED_API) && CYTHON_LIMITED_API +#define __PYX_EXTRA_ABI_MODULE_NAME "limited" +#else +#define __PYX_EXTRA_ABI_MODULE_NAME "" +#endif +#define CYTHON_ABI "3_0_8" __PYX_EXTRA_ABI_MODULE_NAME +#define __PYX_ABI_MODULE_NAME "_cython_" CYTHON_ABI +#define __PYX_TYPE_MODULE_PREFIX __PYX_ABI_MODULE_NAME "." +#define CYTHON_HEX_VERSION 0x030008F0 +#define CYTHON_FUTURE_DIVISION 1 +#include +#ifndef offsetof + #define offsetof(type, member) ( (size_t) & ((type*)0) -> member ) +#endif +#if !defined(_WIN32) && !defined(WIN32) && !defined(MS_WINDOWS) + #ifndef __stdcall + #define __stdcall + #endif + #ifndef __cdecl + #define __cdecl + #endif + #ifndef __fastcall + #define __fastcall + #endif +#endif +#ifndef DL_IMPORT + #define DL_IMPORT(t) t +#endif +#ifndef DL_EXPORT + #define DL_EXPORT(t) t +#endif +#define __PYX_COMMA , +#ifndef HAVE_LONG_LONG + #define HAVE_LONG_LONG +#endif +#ifndef PY_LONG_LONG + #define PY_LONG_LONG LONG_LONG +#endif +#ifndef Py_HUGE_VAL + #define Py_HUGE_VAL HUGE_VAL +#endif +#define __PYX_LIMITED_VERSION_HEX PY_VERSION_HEX +#if defined(GRAALVM_PYTHON) + /* For very preliminary testing purposes. Most variables are set the same as PyPy. + The existence of this section does not imply that anything works or is even tested */ + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 1 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(PYPY_VERSION) + #define CYTHON_COMPILING_IN_PYPY 1 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #ifndef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #endif + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #if PY_VERSION_HEX < 0x03090000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE (PY_VERSION_HEX >= 0x030400a1 && PYPY_VERSION_NUM >= 0x07030C00) + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(CYTHON_LIMITED_API) + #ifdef Py_LIMITED_API + #undef __PYX_LIMITED_VERSION_HEX + #define __PYX_LIMITED_VERSION_HEX Py_LIMITED_API + #endif + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 1 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_CLINE_IN_TRACEBACK + #define CYTHON_CLINE_IN_TRACEBACK 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 1 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #endif + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 1 + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(Py_GIL_DISABLED) || defined(Py_NOGIL) + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 1 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #ifndef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 +#else + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 1 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #ifndef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #endif + #ifndef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 1 + #endif + #if PY_MAJOR_VERSION < 3 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #ifndef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 1 + #endif + #ifndef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 1 + #endif + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #if PY_VERSION_HEX < 0x030300F0 || PY_VERSION_HEX >= 0x030B00A2 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #elif !defined(CYTHON_USE_UNICODE_WRITER) + #define CYTHON_USE_UNICODE_WRITER 1 + #endif + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #ifndef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 1 + #endif + #ifndef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL (PY_MAJOR_VERSION < 3 || PY_VERSION_HEX >= 0x03060000 && PY_VERSION_HEX < 0x030C00A6) + #endif + #ifndef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL (PY_VERSION_HEX >= 0x030700A1) + #endif + #ifndef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 1 + #endif + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #endif + #if PY_VERSION_HEX < 0x030400a1 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #elif !defined(CYTHON_USE_TP_FINALIZE) + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #if PY_VERSION_HEX < 0x030600B1 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #elif !defined(CYTHON_USE_DICT_VERSIONS) + #define CYTHON_USE_DICT_VERSIONS (PY_VERSION_HEX < 0x030C00A5) + #endif + #if PY_VERSION_HEX < 0x030700A3 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #elif !defined(CYTHON_USE_EXC_INFO_STACK) + #define CYTHON_USE_EXC_INFO_STACK 1 + #endif + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 1 + #endif +#endif +#if !defined(CYTHON_FAST_PYCCALL) +#define CYTHON_FAST_PYCCALL (CYTHON_FAST_PYCALL && PY_VERSION_HEX >= 0x030600B1) +#endif +#if !defined(CYTHON_VECTORCALL) +#define CYTHON_VECTORCALL (CYTHON_FAST_PYCCALL && PY_VERSION_HEX >= 0x030800B1) +#endif +#define CYTHON_BACKPORT_VECTORCALL (CYTHON_METH_FASTCALL && PY_VERSION_HEX < 0x030800B1) +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_MAJOR_VERSION < 3 + #include "longintrepr.h" + #endif + #undef SHIFT + #undef BASE + #undef MASK + #ifdef SIZEOF_VOID_P + enum { __pyx_check_sizeof_voidp = 1 / (int)(SIZEOF_VOID_P == sizeof(void*)) }; + #endif +#endif +#ifndef __has_attribute + #define __has_attribute(x) 0 +#endif +#ifndef __has_cpp_attribute + #define __has_cpp_attribute(x) 0 +#endif +#ifndef CYTHON_RESTRICT + #if defined(__GNUC__) + #define CYTHON_RESTRICT __restrict__ + #elif defined(_MSC_VER) && _MSC_VER >= 1400 + #define CYTHON_RESTRICT __restrict + #elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define CYTHON_RESTRICT restrict + #else + #define CYTHON_RESTRICT + #endif +#endif +#ifndef CYTHON_UNUSED + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(maybe_unused) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(maybe_unused) + #define CYTHON_UNUSED [[maybe_unused]] + #endif + #endif + #endif +#endif +#ifndef CYTHON_UNUSED +# if defined(__GNUC__) +# if !(defined(__cplusplus)) || (__GNUC__ > 3 || (__GNUC__ == 3 && __GNUC_MINOR__ >= 4)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +# elif defined(__ICC) || (defined(__INTEL_COMPILER) && !defined(_MSC_VER)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +#endif +#ifndef CYTHON_UNUSED_VAR +# if defined(__cplusplus) + template void CYTHON_UNUSED_VAR( const T& ) { } +# else +# define CYTHON_UNUSED_VAR(x) (void)(x) +# endif +#endif +#ifndef CYTHON_MAYBE_UNUSED_VAR + #define CYTHON_MAYBE_UNUSED_VAR(x) CYTHON_UNUSED_VAR(x) +#endif +#ifndef CYTHON_NCP_UNUSED +# if CYTHON_COMPILING_IN_CPYTHON +# define CYTHON_NCP_UNUSED +# else +# define CYTHON_NCP_UNUSED CYTHON_UNUSED +# endif +#endif +#ifndef CYTHON_USE_CPP_STD_MOVE + #if defined(__cplusplus) && (\ + __cplusplus >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1600)) + #define CYTHON_USE_CPP_STD_MOVE 1 + #else + #define CYTHON_USE_CPP_STD_MOVE 0 + #endif +#endif +#define __Pyx_void_to_None(void_result) ((void)(void_result), Py_INCREF(Py_None), Py_None) +#ifdef _MSC_VER + #ifndef _MSC_STDINT_H_ + #if _MSC_VER < 1300 + typedef unsigned char uint8_t; + typedef unsigned short uint16_t; + typedef unsigned int uint32_t; + #else + typedef unsigned __int8 uint8_t; + typedef unsigned __int16 uint16_t; + typedef unsigned __int32 uint32_t; + #endif + #endif + #if _MSC_VER < 1300 + #ifdef _WIN64 + typedef unsigned long long __pyx_uintptr_t; + #else + typedef unsigned int __pyx_uintptr_t; + #endif + #else + #ifdef _WIN64 + typedef unsigned __int64 __pyx_uintptr_t; + #else + typedef unsigned __int32 __pyx_uintptr_t; + #endif + #endif +#else + #include + typedef uintptr_t __pyx_uintptr_t; +#endif +#ifndef CYTHON_FALLTHROUGH + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(fallthrough) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(fallthrough) + #define CYTHON_FALLTHROUGH [[fallthrough]] + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_cpp_attribute(clang::fallthrough) + #define CYTHON_FALLTHROUGH [[clang::fallthrough]] + #elif __has_cpp_attribute(gnu::fallthrough) + #define CYTHON_FALLTHROUGH [[gnu::fallthrough]] + #endif + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_attribute(fallthrough) + #define CYTHON_FALLTHROUGH __attribute__((fallthrough)) + #else + #define CYTHON_FALLTHROUGH + #endif + #endif + #if defined(__clang__) && defined(__apple_build_version__) + #if __apple_build_version__ < 7000000 + #undef CYTHON_FALLTHROUGH + #define CYTHON_FALLTHROUGH + #endif + #endif +#endif +#ifdef __cplusplus + template + struct __PYX_IS_UNSIGNED_IMPL {static const bool value = T(0) < T(-1);}; + #define __PYX_IS_UNSIGNED(type) (__PYX_IS_UNSIGNED_IMPL::value) +#else + #define __PYX_IS_UNSIGNED(type) (((type)-1) > 0) +#endif +#if CYTHON_COMPILING_IN_PYPY == 1 + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x030A0000) +#else + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x03090000) +#endif +#define __PYX_REINTERPRET_FUNCION(func_pointer, other_pointer) ((func_pointer)(void(*)(void))(other_pointer)) + +#ifndef __cplusplus + #error "Cython files generated with the C++ option must be compiled with a C++ compiler." +#endif +#ifndef CYTHON_INLINE + #if defined(__clang__) + #define CYTHON_INLINE __inline__ __attribute__ ((__unused__)) + #else + #define CYTHON_INLINE inline + #endif +#endif +template +void __Pyx_call_destructor(T& x) { + x.~T(); +} +template +class __Pyx_FakeReference { + public: + __Pyx_FakeReference() : ptr(NULL) { } + __Pyx_FakeReference(const T& ref) : ptr(const_cast(&ref)) { } + T *operator->() { return ptr; } + T *operator&() { return ptr; } + operator T&() { return *ptr; } + template bool operator ==(const U& other) const { return *ptr == other; } + template bool operator !=(const U& other) const { return *ptr != other; } + template bool operator==(const __Pyx_FakeReference& other) const { return *ptr == *other.ptr; } + template bool operator!=(const __Pyx_FakeReference& other) const { return *ptr != *other.ptr; } + private: + T *ptr; +}; + +#define __PYX_BUILD_PY_SSIZE_T "n" +#define CYTHON_FORMAT_SSIZE_T "z" +#if PY_MAJOR_VERSION < 3 + #define __Pyx_BUILTIN_MODULE_NAME "__builtin__" + #define __Pyx_DefaultClassType PyClass_Type + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a+k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_BUILTIN_MODULE_NAME "builtins" + #define __Pyx_DefaultClassType PyType_Type +#if CYTHON_COMPILING_IN_LIMITED_API + static CYTHON_INLINE PyObject* __Pyx_PyCode_New(int a, int p, int k, int l, int s, int f, + PyObject *code, PyObject *c, PyObject* n, PyObject *v, + PyObject *fv, PyObject *cell, PyObject* fn, + PyObject *name, int fline, PyObject *lnos) { + PyObject *exception_table = NULL; + PyObject *types_module=NULL, *code_type=NULL, *result=NULL; + #if __PYX_LIMITED_VERSION_HEX < 0x030B0000 + PyObject *version_info; + PyObject *py_minor_version = NULL; + #endif + long minor_version = 0; + PyObject *type, *value, *traceback; + PyErr_Fetch(&type, &value, &traceback); + #if __PYX_LIMITED_VERSION_HEX >= 0x030B0000 + minor_version = 11; + #else + if (!(version_info = PySys_GetObject("version_info"))) goto end; + if (!(py_minor_version = PySequence_GetItem(version_info, 1))) goto end; + minor_version = PyLong_AsLong(py_minor_version); + Py_DECREF(py_minor_version); + if (minor_version == -1 && PyErr_Occurred()) goto end; + #endif + if (!(types_module = PyImport_ImportModule("types"))) goto end; + if (!(code_type = PyObject_GetAttrString(types_module, "CodeType"))) goto end; + if (minor_version <= 7) { + (void)p; + result = PyObject_CallFunction(code_type, "iiiiiOOOOOOiOO", a, k, l, s, f, code, + c, n, v, fn, name, fline, lnos, fv, cell); + } else if (minor_version <= 10) { + result = PyObject_CallFunction(code_type, "iiiiiiOOOOOOiOO", a,p, k, l, s, f, code, + c, n, v, fn, name, fline, lnos, fv, cell); + } else { + if (!(exception_table = PyBytes_FromStringAndSize(NULL, 0))) goto end; + result = PyObject_CallFunction(code_type, "iiiiiiOOOOOOOiOO", a,p, k, l, s, f, code, + c, n, v, fn, name, name, fline, lnos, exception_table, fv, cell); + } + end: + Py_XDECREF(code_type); + Py_XDECREF(exception_table); + Py_XDECREF(types_module); + if (type) { + PyErr_Restore(type, value, traceback); + } + return result; + } + #ifndef CO_OPTIMIZED + #define CO_OPTIMIZED 0x0001 + #endif + #ifndef CO_NEWLOCALS + #define CO_NEWLOCALS 0x0002 + #endif + #ifndef CO_VARARGS + #define CO_VARARGS 0x0004 + #endif + #ifndef CO_VARKEYWORDS + #define CO_VARKEYWORDS 0x0008 + #endif + #ifndef CO_ASYNC_GENERATOR + #define CO_ASYNC_GENERATOR 0x0200 + #endif + #ifndef CO_GENERATOR + #define CO_GENERATOR 0x0020 + #endif + #ifndef CO_COROUTINE + #define CO_COROUTINE 0x0080 + #endif +#elif PY_VERSION_HEX >= 0x030B0000 + static CYTHON_INLINE PyCodeObject* __Pyx_PyCode_New(int a, int p, int k, int l, int s, int f, + PyObject *code, PyObject *c, PyObject* n, PyObject *v, + PyObject *fv, PyObject *cell, PyObject* fn, + PyObject *name, int fline, PyObject *lnos) { + PyCodeObject *result; + PyObject *empty_bytes = PyBytes_FromStringAndSize("", 0); + if (!empty_bytes) return NULL; + result = + #if PY_VERSION_HEX >= 0x030C0000 + PyUnstable_Code_NewWithPosOnlyArgs + #else + PyCode_NewWithPosOnlyArgs + #endif + (a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, name, fline, lnos, empty_bytes); + Py_DECREF(empty_bytes); + return result; + } +#elif PY_VERSION_HEX >= 0x030800B2 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_NewWithPosOnlyArgs(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#endif +#endif +#if PY_VERSION_HEX >= 0x030900A4 || defined(Py_IS_TYPE) + #define __Pyx_IS_TYPE(ob, type) Py_IS_TYPE(ob, type) +#else + #define __Pyx_IS_TYPE(ob, type) (((const PyObject*)ob)->ob_type == (type)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_Is) + #define __Pyx_Py_Is(x, y) Py_Is(x, y) +#else + #define __Pyx_Py_Is(x, y) ((x) == (y)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsNone) + #define __Pyx_Py_IsNone(ob) Py_IsNone(ob) +#else + #define __Pyx_Py_IsNone(ob) __Pyx_Py_Is((ob), Py_None) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsTrue) + #define __Pyx_Py_IsTrue(ob) Py_IsTrue(ob) +#else + #define __Pyx_Py_IsTrue(ob) __Pyx_Py_Is((ob), Py_True) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsFalse) + #define __Pyx_Py_IsFalse(ob) Py_IsFalse(ob) +#else + #define __Pyx_Py_IsFalse(ob) __Pyx_Py_Is((ob), Py_False) +#endif +#define __Pyx_NoneAsNull(obj) (__Pyx_Py_IsNone(obj) ? NULL : (obj)) +#if PY_VERSION_HEX >= 0x030900F0 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_GC_IsFinalized(o) PyObject_GC_IsFinalized(o) +#else + #define __Pyx_PyObject_GC_IsFinalized(o) _PyGC_FINALIZED(o) +#endif +#ifndef CO_COROUTINE + #define CO_COROUTINE 0x80 +#endif +#ifndef CO_ASYNC_GENERATOR + #define CO_ASYNC_GENERATOR 0x200 +#endif +#ifndef Py_TPFLAGS_CHECKTYPES + #define Py_TPFLAGS_CHECKTYPES 0 +#endif +#ifndef Py_TPFLAGS_HAVE_INDEX + #define Py_TPFLAGS_HAVE_INDEX 0 +#endif +#ifndef Py_TPFLAGS_HAVE_NEWBUFFER + #define Py_TPFLAGS_HAVE_NEWBUFFER 0 +#endif +#ifndef Py_TPFLAGS_HAVE_FINALIZE + #define Py_TPFLAGS_HAVE_FINALIZE 0 +#endif +#ifndef Py_TPFLAGS_SEQUENCE + #define Py_TPFLAGS_SEQUENCE 0 +#endif +#ifndef Py_TPFLAGS_MAPPING + #define Py_TPFLAGS_MAPPING 0 +#endif +#ifndef METH_STACKLESS + #define METH_STACKLESS 0 +#endif +#if PY_VERSION_HEX <= 0x030700A3 || !defined(METH_FASTCALL) + #ifndef METH_FASTCALL + #define METH_FASTCALL 0x80 + #endif + typedef PyObject *(*__Pyx_PyCFunctionFast) (PyObject *self, PyObject *const *args, Py_ssize_t nargs); + typedef PyObject *(*__Pyx_PyCFunctionFastWithKeywords) (PyObject *self, PyObject *const *args, + Py_ssize_t nargs, PyObject *kwnames); +#else + #define __Pyx_PyCFunctionFast _PyCFunctionFast + #define __Pyx_PyCFunctionFastWithKeywords _PyCFunctionFastWithKeywords +#endif +#if CYTHON_METH_FASTCALL + #define __Pyx_METH_FASTCALL METH_FASTCALL + #define __Pyx_PyCFunction_FastCall __Pyx_PyCFunctionFast + #define __Pyx_PyCFunction_FastCallWithKeywords __Pyx_PyCFunctionFastWithKeywords +#else + #define __Pyx_METH_FASTCALL METH_VARARGS + #define __Pyx_PyCFunction_FastCall PyCFunction + #define __Pyx_PyCFunction_FastCallWithKeywords PyCFunctionWithKeywords +#endif +#if CYTHON_VECTORCALL + #define __pyx_vectorcallfunc vectorcallfunc + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET PY_VECTORCALL_ARGUMENTS_OFFSET + #define __Pyx_PyVectorcall_NARGS(n) PyVectorcall_NARGS((size_t)(n)) +#elif CYTHON_BACKPORT_VECTORCALL + typedef PyObject *(*__pyx_vectorcallfunc)(PyObject *callable, PyObject *const *args, + size_t nargsf, PyObject *kwnames); + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET ((size_t)1 << (8 * sizeof(size_t) - 1)) + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(((size_t)(n)) & ~__Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET)) +#else + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET 0 + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(n)) +#endif +#if PY_MAJOR_VERSION >= 0x030900B1 +#define __Pyx_PyCFunction_CheckExact(func) PyCFunction_CheckExact(func) +#else +#define __Pyx_PyCFunction_CheckExact(func) PyCFunction_Check(func) +#endif +#define __Pyx_CyOrPyCFunction_Check(func) PyCFunction_Check(func) +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_CyOrPyCFunction_GET_FUNCTION(func) (((PyCFunctionObject*)(func))->m_ml->ml_meth) +#elif !CYTHON_COMPILING_IN_LIMITED_API +#define __Pyx_CyOrPyCFunction_GET_FUNCTION(func) PyCFunction_GET_FUNCTION(func) +#endif +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_CyOrPyCFunction_GET_FLAGS(func) (((PyCFunctionObject*)(func))->m_ml->ml_flags) +static CYTHON_INLINE PyObject* __Pyx_CyOrPyCFunction_GET_SELF(PyObject *func) { + return (__Pyx_CyOrPyCFunction_GET_FLAGS(func) & METH_STATIC) ? NULL : ((PyCFunctionObject*)func)->m_self; +} +#endif +static CYTHON_INLINE int __Pyx__IsSameCFunction(PyObject *func, void *cfunc) { +#if CYTHON_COMPILING_IN_LIMITED_API + return PyCFunction_Check(func) && PyCFunction_GetFunction(func) == (PyCFunction) cfunc; +#else + return PyCFunction_Check(func) && PyCFunction_GET_FUNCTION(func) == (PyCFunction) cfunc; +#endif +} +#define __Pyx_IsSameCFunction(func, cfunc) __Pyx__IsSameCFunction(func, cfunc) +#if __PYX_LIMITED_VERSION_HEX < 0x030900B1 + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) ((void)m, PyType_FromSpecWithBases(s, b)) + typedef PyObject *(*__Pyx_PyCMethod)(PyObject *, PyTypeObject *, PyObject *const *, size_t, PyObject *); +#else + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) PyType_FromModuleAndSpec(m, s, b) + #define __Pyx_PyCMethod PyCMethod +#endif +#ifndef METH_METHOD + #define METH_METHOD 0x200 +#endif +#if CYTHON_COMPILING_IN_PYPY && !defined(PyObject_Malloc) + #define PyObject_Malloc(s) PyMem_Malloc(s) + #define PyObject_Free(p) PyMem_Free(p) + #define PyObject_Realloc(p) PyMem_Realloc(p) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) +#else + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) (frame)->f_lineno = (lineno) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyThreadState_Current PyThreadState_Get() +#elif !CYTHON_FAST_THREAD_STATE + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#elif PY_VERSION_HEX >= 0x030d00A1 + #define __Pyx_PyThreadState_Current PyThreadState_GetUnchecked() +#elif PY_VERSION_HEX >= 0x03060000 + #define __Pyx_PyThreadState_Current _PyThreadState_UncheckedGet() +#elif PY_VERSION_HEX >= 0x03000000 + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#else + #define __Pyx_PyThreadState_Current _PyThreadState_Current +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE void *__Pyx_PyModule_GetState(PyObject *op) +{ + void *result; + result = PyModule_GetState(op); + if (!result) + Py_FatalError("Couldn't find the module state"); + return result; +} +#endif +#define __Pyx_PyObject_GetSlot(obj, name, func_ctype) __Pyx_PyType_GetSlot(Py_TYPE(obj), name, func_ctype) +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((func_ctype) PyType_GetSlot((type), Py_##name)) +#else + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((type)->name) +#endif +#if PY_VERSION_HEX < 0x030700A2 && !defined(PyThread_tss_create) && !defined(Py_tss_NEEDS_INIT) +#include "pythread.h" +#define Py_tss_NEEDS_INIT 0 +typedef int Py_tss_t; +static CYTHON_INLINE int PyThread_tss_create(Py_tss_t *key) { + *key = PyThread_create_key(); + return 0; +} +static CYTHON_INLINE Py_tss_t * PyThread_tss_alloc(void) { + Py_tss_t *key = (Py_tss_t *)PyObject_Malloc(sizeof(Py_tss_t)); + *key = Py_tss_NEEDS_INIT; + return key; +} +static CYTHON_INLINE void PyThread_tss_free(Py_tss_t *key) { + PyObject_Free(key); +} +static CYTHON_INLINE int PyThread_tss_is_created(Py_tss_t *key) { + return *key != Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE void PyThread_tss_delete(Py_tss_t *key) { + PyThread_delete_key(*key); + *key = Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE int PyThread_tss_set(Py_tss_t *key, void *value) { + return PyThread_set_key_value(*key, value); +} +static CYTHON_INLINE void * PyThread_tss_get(Py_tss_t *key) { + return PyThread_get_key_value(*key); +} +#endif +#if PY_MAJOR_VERSION < 3 + #if CYTHON_COMPILING_IN_PYPY + #if PYPY_VERSION_NUM < 0x07030600 + #if defined(__cplusplus) && __cplusplus >= 201402L + [[deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")]] + #elif defined(__GNUC__) || defined(__clang__) + __attribute__ ((__deprecated__("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6"))) + #elif defined(_MSC_VER) + __declspec(deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")) + #endif + static CYTHON_INLINE int PyGILState_Check(void) { + return 0; + } + #else // PYPY_VERSION_NUM < 0x07030600 + #endif // PYPY_VERSION_NUM < 0x07030600 + #else + static CYTHON_INLINE int PyGILState_Check(void) { + PyThreadState * tstate = _PyThreadState_Current; + return tstate && (tstate == PyGILState_GetThisThreadState()); + } + #endif +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030d0000 || defined(_PyDict_NewPresized) +#define __Pyx_PyDict_NewPresized(n) ((n <= 8) ? PyDict_New() : _PyDict_NewPresized(n)) +#else +#define __Pyx_PyDict_NewPresized(n) PyDict_New() +#endif +#if PY_MAJOR_VERSION >= 3 || CYTHON_FUTURE_DIVISION + #define __Pyx_PyNumber_Divide(x,y) PyNumber_TrueDivide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceTrueDivide(x,y) +#else + #define __Pyx_PyNumber_Divide(x,y) PyNumber_Divide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceDivide(x,y) +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX > 0x030600B4 && PY_VERSION_HEX < 0x030d0000 && CYTHON_USE_UNICODE_INTERNALS +#define __Pyx_PyDict_GetItemStrWithError(dict, name) _PyDict_GetItem_KnownHash(dict, name, ((PyASCIIObject *) name)->hash) +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStr(PyObject *dict, PyObject *name) { + PyObject *res = __Pyx_PyDict_GetItemStrWithError(dict, name); + if (res == NULL) PyErr_Clear(); + return res; +} +#elif PY_MAJOR_VERSION >= 3 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07020000) +#define __Pyx_PyDict_GetItemStrWithError PyDict_GetItemWithError +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#else +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStrWithError(PyObject *dict, PyObject *name) { +#if CYTHON_COMPILING_IN_PYPY + return PyDict_GetItem(dict, name); +#else + PyDictEntry *ep; + PyDictObject *mp = (PyDictObject*) dict; + long hash = ((PyStringObject *) name)->ob_shash; + assert(hash != -1); + ep = (mp->ma_lookup)(mp, name, hash); + if (ep == NULL) { + return NULL; + } + return ep->me_value; +#endif +} +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#endif +#if CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyType_GetFlags(tp) (((PyTypeObject *)tp)->tp_flags) + #define __Pyx_PyType_HasFeature(type, feature) ((__Pyx_PyType_GetFlags(type) & (feature)) != 0) + #define __Pyx_PyObject_GetIterNextFunc(obj) (Py_TYPE(obj)->tp_iternext) +#else + #define __Pyx_PyType_GetFlags(tp) (PyType_GetFlags((PyTypeObject *)tp)) + #define __Pyx_PyType_HasFeature(type, feature) PyType_HasFeature(type, feature) + #define __Pyx_PyObject_GetIterNextFunc(obj) PyIter_Next +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_SetItemOnTypeDict(tp, k, v) PyObject_GenericSetAttr((PyObject*)tp, k, v) +#else + #define __Pyx_SetItemOnTypeDict(tp, k, v) PyDict_SetItem(tp->tp_dict, k, v) +#endif +#if CYTHON_USE_TYPE_SPECS && PY_VERSION_HEX >= 0x03080000 +#define __Pyx_PyHeapTypeObject_GC_Del(obj) {\ + PyTypeObject *type = Py_TYPE((PyObject*)obj);\ + assert(__Pyx_PyType_HasFeature(type, Py_TPFLAGS_HEAPTYPE));\ + PyObject_GC_Del(obj);\ + Py_DECREF(type);\ +} +#else +#define __Pyx_PyHeapTypeObject_GC_Del(obj) PyObject_GC_Del(obj) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define CYTHON_PEP393_ENABLED 1 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GetLength(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_ReadChar(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((void)u, 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((void)u, (0)) + #define __Pyx_PyUnicode_DATA(u) ((void*)u) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)k, PyUnicode_ReadChar((PyObject*)(d), i)) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GetLength(u)) +#elif PY_VERSION_HEX > 0x03030000 && defined(PyUnicode_KIND) + #define CYTHON_PEP393_ENABLED 1 + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_READY(op) (0) + #else + #define __Pyx_PyUnicode_READY(op) (likely(PyUnicode_IS_READY(op)) ?\ + 0 : _PyUnicode_Ready((PyObject *)(op))) + #endif + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_LENGTH(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_READ_CHAR(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) PyUnicode_MAX_CHAR_VALUE(u) + #define __Pyx_PyUnicode_KIND(u) ((int)PyUnicode_KIND(u)) + #define __Pyx_PyUnicode_DATA(u) PyUnicode_DATA(u) + #define __Pyx_PyUnicode_READ(k, d, i) PyUnicode_READ(k, d, i) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) PyUnicode_WRITE(k, d, i, (Py_UCS4) ch) + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_LENGTH(u)) + #else + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x03090000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : ((PyCompactUnicodeObject *)(u))->wstr_length)) + #else + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : PyUnicode_GET_SIZE(u))) + #endif + #endif +#else + #define CYTHON_PEP393_ENABLED 0 + #define PyUnicode_1BYTE_KIND 1 + #define PyUnicode_2BYTE_KIND 2 + #define PyUnicode_4BYTE_KIND 4 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_SIZE(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) ((Py_UCS4)(PyUnicode_AS_UNICODE(u)[i])) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((sizeof(Py_UNICODE) == 2) ? 65535U : 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((int)sizeof(Py_UNICODE)) + #define __Pyx_PyUnicode_DATA(u) ((void*)PyUnicode_AS_UNICODE(u)) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)(k), (Py_UCS4)(((Py_UNICODE*)d)[i])) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) (((void)(k)), ((Py_UNICODE*)d)[i] = (Py_UNICODE) ch) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_SIZE(u)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyUnicode_Concat(a, b) PyNumber_Add(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) PyNumber_Add(a, b) +#else + #define __Pyx_PyUnicode_Concat(a, b) PyUnicode_Concat(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) ((unlikely((a) == Py_None) || unlikely((b) == Py_None)) ?\ + PyNumber_Add(a, b) : __Pyx_PyUnicode_Concat(a, b)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #if !defined(PyUnicode_DecodeUnicodeEscape) + #define PyUnicode_DecodeUnicodeEscape(s, size, errors) PyUnicode_Decode(s, size, "unicode_escape", errors) + #endif + #if !defined(PyUnicode_Contains) || (PY_MAJOR_VERSION == 2 && PYPY_VERSION_NUM < 0x07030500) + #undef PyUnicode_Contains + #define PyUnicode_Contains(u, s) PySequence_Contains(u, s) + #endif + #if !defined(PyByteArray_Check) + #define PyByteArray_Check(obj) PyObject_TypeCheck(obj, &PyByteArray_Type) + #endif + #if !defined(PyObject_Format) + #define PyObject_Format(obj, fmt) PyObject_CallMethod(obj, "__format__", "O", fmt) + #endif +#endif +#define __Pyx_PyString_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyString_Check(b) && !PyString_CheckExact(b)))) ? PyNumber_Remainder(a, b) : __Pyx_PyString_Format(a, b)) +#define __Pyx_PyUnicode_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyUnicode_Check(b) && !PyUnicode_CheckExact(b)))) ? PyNumber_Remainder(a, b) : PyUnicode_Format(a, b)) +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyString_Format(a, b) PyUnicode_Format(a, b) +#else + #define __Pyx_PyString_Format(a, b) PyString_Format(a, b) +#endif +#if PY_MAJOR_VERSION < 3 && !defined(PyObject_ASCII) + #define PyObject_ASCII(o) PyObject_Repr(o) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBaseString_Type PyUnicode_Type + #define PyStringObject PyUnicodeObject + #define PyString_Type PyUnicode_Type + #define PyString_Check PyUnicode_Check + #define PyString_CheckExact PyUnicode_CheckExact +#ifndef PyObject_Unicode + #define PyObject_Unicode PyObject_Str +#endif +#endif +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyBaseString_Check(obj) PyUnicode_Check(obj) + #define __Pyx_PyBaseString_CheckExact(obj) PyUnicode_CheckExact(obj) +#else + #define __Pyx_PyBaseString_Check(obj) (PyString_Check(obj) || PyUnicode_Check(obj)) + #define __Pyx_PyBaseString_CheckExact(obj) (PyString_CheckExact(obj) || PyUnicode_CheckExact(obj)) +#endif +#if CYTHON_COMPILING_IN_CPYTHON + #define __Pyx_PySequence_ListKeepNew(obj)\ + (likely(PyList_CheckExact(obj) && Py_REFCNT(obj) == 1) ? __Pyx_NewRef(obj) : PySequence_List(obj)) +#else + #define __Pyx_PySequence_ListKeepNew(obj) PySequence_List(obj) +#endif +#ifndef PySet_CheckExact + #define PySet_CheckExact(obj) __Pyx_IS_TYPE(obj, &PySet_Type) +#endif +#if PY_VERSION_HEX >= 0x030900A4 + #define __Pyx_SET_REFCNT(obj, refcnt) Py_SET_REFCNT(obj, refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SET_SIZE(obj, size) +#else + #define __Pyx_SET_REFCNT(obj, refcnt) Py_REFCNT(obj) = (refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SIZE(obj) = (size) +#endif +#if CYTHON_ASSUME_SAFE_MACROS + #define __Pyx_PySequence_ITEM(o, i) PySequence_ITEM(o, i) + #define __Pyx_PySequence_SIZE(seq) Py_SIZE(seq) + #define __Pyx_PyTuple_SET_ITEM(o, i, v) (PyTuple_SET_ITEM(o, i, v), (0)) + #define __Pyx_PyList_SET_ITEM(o, i, v) (PyList_SET_ITEM(o, i, v), (0)) + #define __Pyx_PyTuple_GET_SIZE(o) PyTuple_GET_SIZE(o) + #define __Pyx_PyList_GET_SIZE(o) PyList_GET_SIZE(o) + #define __Pyx_PySet_GET_SIZE(o) PySet_GET_SIZE(o) + #define __Pyx_PyBytes_GET_SIZE(o) PyBytes_GET_SIZE(o) + #define __Pyx_PyByteArray_GET_SIZE(o) PyByteArray_GET_SIZE(o) +#else + #define __Pyx_PySequence_ITEM(o, i) PySequence_GetItem(o, i) + #define __Pyx_PySequence_SIZE(seq) PySequence_Size(seq) + #define __Pyx_PyTuple_SET_ITEM(o, i, v) PyTuple_SetItem(o, i, v) + #define __Pyx_PyList_SET_ITEM(o, i, v) PyList_SetItem(o, i, v) + #define __Pyx_PyTuple_GET_SIZE(o) PyTuple_Size(o) + #define __Pyx_PyList_GET_SIZE(o) PyList_Size(o) + #define __Pyx_PySet_GET_SIZE(o) PySet_Size(o) + #define __Pyx_PyBytes_GET_SIZE(o) PyBytes_Size(o) + #define __Pyx_PyByteArray_GET_SIZE(o) PyByteArray_Size(o) +#endif +#if PY_VERSION_HEX >= 0x030d00A1 + #define __Pyx_PyImport_AddModuleRef(name) PyImport_AddModuleRef(name) +#else + static CYTHON_INLINE PyObject *__Pyx_PyImport_AddModuleRef(const char *name) { + PyObject *module = PyImport_AddModule(name); + Py_XINCREF(module); + return module; + } +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyIntObject PyLongObject + #define PyInt_Type PyLong_Type + #define PyInt_Check(op) PyLong_Check(op) + #define PyInt_CheckExact(op) PyLong_CheckExact(op) + #define __Pyx_Py3Int_Check(op) PyLong_Check(op) + #define __Pyx_Py3Int_CheckExact(op) PyLong_CheckExact(op) + #define PyInt_FromString PyLong_FromString + #define PyInt_FromUnicode PyLong_FromUnicode + #define PyInt_FromLong PyLong_FromLong + #define PyInt_FromSize_t PyLong_FromSize_t + #define PyInt_FromSsize_t PyLong_FromSsize_t + #define PyInt_AsLong PyLong_AsLong + #define PyInt_AS_LONG PyLong_AS_LONG + #define PyInt_AsSsize_t PyLong_AsSsize_t + #define PyInt_AsUnsignedLongMask PyLong_AsUnsignedLongMask + #define PyInt_AsUnsignedLongLongMask PyLong_AsUnsignedLongLongMask + #define PyNumber_Int PyNumber_Long +#else + #define __Pyx_Py3Int_Check(op) (PyLong_Check(op) || PyInt_Check(op)) + #define __Pyx_Py3Int_CheckExact(op) (PyLong_CheckExact(op) || PyInt_CheckExact(op)) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBoolObject PyLongObject +#endif +#if PY_MAJOR_VERSION >= 3 && CYTHON_COMPILING_IN_PYPY + #ifndef PyUnicode_InternFromString + #define PyUnicode_InternFromString(s) PyUnicode_FromString(s) + #endif +#endif +#if PY_VERSION_HEX < 0x030200A4 + typedef long Py_hash_t; + #define __Pyx_PyInt_FromHash_t PyInt_FromLong + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsHash_t +#else + #define __Pyx_PyInt_FromHash_t PyInt_FromSsize_t + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsSsize_t +#endif +#if CYTHON_USE_ASYNC_SLOTS + #if PY_VERSION_HEX >= 0x030500B1 + #define __Pyx_PyAsyncMethodsStruct PyAsyncMethods + #define __Pyx_PyType_AsAsync(obj) (Py_TYPE(obj)->tp_as_async) + #else + #define __Pyx_PyType_AsAsync(obj) ((__Pyx_PyAsyncMethodsStruct*) (Py_TYPE(obj)->tp_reserved)) + #endif +#else + #define __Pyx_PyType_AsAsync(obj) NULL +#endif +#ifndef __Pyx_PyAsyncMethodsStruct + typedef struct { + unaryfunc am_await; + unaryfunc am_aiter; + unaryfunc am_anext; + } __Pyx_PyAsyncMethodsStruct; +#endif + +#if defined(_WIN32) || defined(WIN32) || defined(MS_WINDOWS) + #if !defined(_USE_MATH_DEFINES) + #define _USE_MATH_DEFINES + #endif +#endif +#include +#ifdef NAN +#define __PYX_NAN() ((float) NAN) +#else +static CYTHON_INLINE float __PYX_NAN() { + float value; + memset(&value, 0xFF, sizeof(value)); + return value; +} +#endif +#if defined(__CYGWIN__) && defined(_LDBL_EQ_DBL) +#define __Pyx_truncl trunc +#else +#define __Pyx_truncl truncl +#endif + +#define __PYX_MARK_ERR_POS(f_index, lineno) \ + { __pyx_filename = __pyx_f[f_index]; (void)__pyx_filename; __pyx_lineno = lineno; (void)__pyx_lineno; __pyx_clineno = __LINE__; (void)__pyx_clineno; } +#define __PYX_ERR(f_index, lineno, Ln_error) \ + { __PYX_MARK_ERR_POS(f_index, lineno) goto Ln_error; } + +#ifdef CYTHON_EXTERN_C + #undef __PYX_EXTERN_C + #define __PYX_EXTERN_C CYTHON_EXTERN_C +#elif defined(__PYX_EXTERN_C) + #ifdef _MSC_VER + #pragma message ("Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead.") + #else + #warning Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead. + #endif +#else + #define __PYX_EXTERN_C extern "C++" +#endif + +#define __PYX_HAVE__common__params_pyx +#define __PYX_HAVE_API__common__params_pyx +/* Early includes */ +#include +#include +#include "ios" +#include "new" +#include "stdexcept" +#include "typeinfo" +#include +#include "common/params.h" +#ifdef _OPENMP +#include +#endif /* _OPENMP */ + +#if defined(PYREX_WITHOUT_ASSERTIONS) && !defined(CYTHON_WITHOUT_ASSERTIONS) +#define CYTHON_WITHOUT_ASSERTIONS +#endif + +typedef struct {PyObject **p; const char *s; const Py_ssize_t n; const char* encoding; + const char is_unicode; const char is_str; const char intern; } __Pyx_StringTabEntry; + +#define __PYX_DEFAULT_STRING_ENCODING_IS_ASCII 0 +#define __PYX_DEFAULT_STRING_ENCODING_IS_UTF8 0 +#define __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT (PY_MAJOR_VERSION >= 3 && __PYX_DEFAULT_STRING_ENCODING_IS_UTF8) +#define __PYX_DEFAULT_STRING_ENCODING "" +#define __Pyx_PyObject_FromString __Pyx_PyBytes_FromString +#define __Pyx_PyObject_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#define __Pyx_uchar_cast(c) ((unsigned char)c) +#define __Pyx_long_cast(x) ((long)x) +#define __Pyx_fits_Py_ssize_t(v, type, is_signed) (\ + (sizeof(type) < sizeof(Py_ssize_t)) ||\ + (sizeof(type) > sizeof(Py_ssize_t) &&\ + likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX) &&\ + (!is_signed || likely(v > (type)PY_SSIZE_T_MIN ||\ + v == (type)PY_SSIZE_T_MIN))) ||\ + (sizeof(type) == sizeof(Py_ssize_t) &&\ + (is_signed || likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX))) ) +static CYTHON_INLINE int __Pyx_is_valid_index(Py_ssize_t i, Py_ssize_t limit) { + return (size_t) i < (size_t) limit; +} +#if defined (__cplusplus) && __cplusplus >= 201103L + #include + #define __Pyx_sst_abs(value) std::abs(value) +#elif SIZEOF_INT >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) abs(value) +#elif SIZEOF_LONG >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) labs(value) +#elif defined (_MSC_VER) + #define __Pyx_sst_abs(value) ((Py_ssize_t)_abs64(value)) +#elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define __Pyx_sst_abs(value) llabs(value) +#elif defined (__GNUC__) + #define __Pyx_sst_abs(value) __builtin_llabs(value) +#else + #define __Pyx_sst_abs(value) ((value<0) ? -value : value) +#endif +static CYTHON_INLINE Py_ssize_t __Pyx_ssize_strlen(const char *s); +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject*); +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject*, Py_ssize_t* length); +static CYTHON_INLINE PyObject* __Pyx_PyByteArray_FromString(const char*); +#define __Pyx_PyByteArray_FromStringAndSize(s, l) PyByteArray_FromStringAndSize((const char*)s, l) +#define __Pyx_PyBytes_FromString PyBytes_FromString +#define __Pyx_PyBytes_FromStringAndSize PyBytes_FromStringAndSize +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char*); +#if PY_MAJOR_VERSION < 3 + #define __Pyx_PyStr_FromString __Pyx_PyBytes_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#else + #define __Pyx_PyStr_FromString __Pyx_PyUnicode_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyUnicode_FromStringAndSize +#endif +#define __Pyx_PyBytes_AsWritableString(s) ((char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableSString(s) ((signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableUString(s) ((unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsString(s) ((const char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsSString(s) ((const signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsUString(s) ((const unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyObject_AsWritableString(s) ((char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableSString(s) ((signed char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableUString(s) ((unsigned char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsSString(s) ((const signed char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsUString(s) ((const unsigned char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_FromCString(s) __Pyx_PyObject_FromString((const char*)s) +#define __Pyx_PyBytes_FromCString(s) __Pyx_PyBytes_FromString((const char*)s) +#define __Pyx_PyByteArray_FromCString(s) __Pyx_PyByteArray_FromString((const char*)s) +#define __Pyx_PyStr_FromCString(s) __Pyx_PyStr_FromString((const char*)s) +#define __Pyx_PyUnicode_FromCString(s) __Pyx_PyUnicode_FromString((const char*)s) +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const wchar_t *u) +{ + const wchar_t *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#else +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const Py_UNICODE *u) +{ + const Py_UNICODE *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#endif +#define __Pyx_PyUnicode_FromOrdinal(o) PyUnicode_FromOrdinal((int)o) +#define __Pyx_PyUnicode_FromUnicode(u) PyUnicode_FromUnicode(u, __Pyx_Py_UNICODE_strlen(u)) +#define __Pyx_PyUnicode_FromUnicodeAndLength PyUnicode_FromUnicode +#define __Pyx_PyUnicode_AsUnicode PyUnicode_AsUnicode +#define __Pyx_NewRef(obj) (Py_INCREF(obj), obj) +#define __Pyx_Owned_Py_None(b) __Pyx_NewRef(Py_None) +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b); +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject*); +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject*); +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x); +#define __Pyx_PySequence_Tuple(obj)\ + (likely(PyTuple_CheckExact(obj)) ? __Pyx_NewRef(obj) : PySequence_Tuple(obj)) +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject*); +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t); +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject*); +#if CYTHON_ASSUME_SAFE_MACROS +#define __pyx_PyFloat_AsDouble(x) (PyFloat_CheckExact(x) ? PyFloat_AS_DOUBLE(x) : PyFloat_AsDouble(x)) +#else +#define __pyx_PyFloat_AsDouble(x) PyFloat_AsDouble(x) +#endif +#define __pyx_PyFloat_AsFloat(x) ((float) __pyx_PyFloat_AsDouble(x)) +#if PY_MAJOR_VERSION >= 3 +#define __Pyx_PyNumber_Int(x) (PyLong_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Long(x)) +#else +#define __Pyx_PyNumber_Int(x) (PyInt_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Int(x)) +#endif +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_VERSION_HEX >= 0x030C00A7 + #ifndef _PyLong_SIGN_MASK + #define _PyLong_SIGN_MASK 3 + #endif + #ifndef _PyLong_NON_SIZE_BITS + #define _PyLong_NON_SIZE_BITS 3 + #endif + #define __Pyx_PyLong_Sign(x) (((PyLongObject*)x)->long_value.lv_tag & _PyLong_SIGN_MASK) + #define __Pyx_PyLong_IsNeg(x) ((__Pyx_PyLong_Sign(x) & 2) != 0) + #define __Pyx_PyLong_IsNonNeg(x) (!__Pyx_PyLong_IsNeg(x)) + #define __Pyx_PyLong_IsZero(x) (__Pyx_PyLong_Sign(x) & 1) + #define __Pyx_PyLong_IsPos(x) (__Pyx_PyLong_Sign(x) == 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) (__Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) ((Py_ssize_t) (((PyLongObject*)x)->long_value.lv_tag >> _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_SignedDigitCount(x)\ + ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * __Pyx_PyLong_DigitCount(x)) + #if defined(PyUnstable_Long_IsCompact) && defined(PyUnstable_Long_CompactValue) + #define __Pyx_PyLong_IsCompact(x) PyUnstable_Long_IsCompact((PyLongObject*) x) + #define __Pyx_PyLong_CompactValue(x) PyUnstable_Long_CompactValue((PyLongObject*) x) + #else + #define __Pyx_PyLong_IsCompact(x) (((PyLongObject*)x)->long_value.lv_tag < (2 << _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_CompactValue(x) ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * (Py_ssize_t) __Pyx_PyLong_Digits(x)[0]) + #endif + typedef Py_ssize_t __Pyx_compact_pylong; + typedef size_t __Pyx_compact_upylong; + #else + #define __Pyx_PyLong_IsNeg(x) (Py_SIZE(x) < 0) + #define __Pyx_PyLong_IsNonNeg(x) (Py_SIZE(x) >= 0) + #define __Pyx_PyLong_IsZero(x) (Py_SIZE(x) == 0) + #define __Pyx_PyLong_IsPos(x) (Py_SIZE(x) > 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) ((Py_SIZE(x) == 0) ? 0 : __Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) __Pyx_sst_abs(Py_SIZE(x)) + #define __Pyx_PyLong_SignedDigitCount(x) Py_SIZE(x) + #define __Pyx_PyLong_IsCompact(x) (Py_SIZE(x) == 0 || Py_SIZE(x) == 1 || Py_SIZE(x) == -1) + #define __Pyx_PyLong_CompactValue(x)\ + ((Py_SIZE(x) == 0) ? (sdigit) 0 : ((Py_SIZE(x) < 0) ? -(sdigit)__Pyx_PyLong_Digits(x)[0] : (sdigit)__Pyx_PyLong_Digits(x)[0])) + typedef sdigit __Pyx_compact_pylong; + typedef digit __Pyx_compact_upylong; + #endif + #if PY_VERSION_HEX >= 0x030C00A5 + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->long_value.ob_digit) + #else + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->ob_digit) + #endif +#endif +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII +#include +static int __Pyx_sys_getdefaultencoding_not_ascii; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + PyObject* ascii_chars_u = NULL; + PyObject* ascii_chars_b = NULL; + const char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + if (strcmp(default_encoding_c, "ascii") == 0) { + __Pyx_sys_getdefaultencoding_not_ascii = 0; + } else { + char ascii_chars[128]; + int c; + for (c = 0; c < 128; c++) { + ascii_chars[c] = (char) c; + } + __Pyx_sys_getdefaultencoding_not_ascii = 1; + ascii_chars_u = PyUnicode_DecodeASCII(ascii_chars, 128, NULL); + if (!ascii_chars_u) goto bad; + ascii_chars_b = PyUnicode_AsEncodedString(ascii_chars_u, default_encoding_c, NULL); + if (!ascii_chars_b || !PyBytes_Check(ascii_chars_b) || memcmp(ascii_chars, PyBytes_AS_STRING(ascii_chars_b), 128) != 0) { + PyErr_Format( + PyExc_ValueError, + "This module compiled with c_string_encoding=ascii, but default encoding '%.200s' is not a superset of ascii.", + default_encoding_c); + goto bad; + } + Py_DECREF(ascii_chars_u); + Py_DECREF(ascii_chars_b); + } + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + Py_XDECREF(ascii_chars_u); + Py_XDECREF(ascii_chars_b); + return -1; +} +#endif +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT && PY_MAJOR_VERSION >= 3 +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_DecodeUTF8(c_str, size, NULL) +#else +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_Decode(c_str, size, __PYX_DEFAULT_STRING_ENCODING, NULL) +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +#include +static char* __PYX_DEFAULT_STRING_ENCODING; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) (const char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + __PYX_DEFAULT_STRING_ENCODING = (char*) malloc(strlen(default_encoding_c) + 1); + if (!__PYX_DEFAULT_STRING_ENCODING) goto bad; + strcpy(__PYX_DEFAULT_STRING_ENCODING, default_encoding_c); + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + return -1; +} +#endif +#endif + + +/* Test for GCC > 2.95 */ +#if defined(__GNUC__) && (__GNUC__ > 2 || (__GNUC__ == 2 && (__GNUC_MINOR__ > 95))) + #define likely(x) __builtin_expect(!!(x), 1) + #define unlikely(x) __builtin_expect(!!(x), 0) +#else /* !__GNUC__ or GCC < 2.95 */ + #define likely(x) (x) + #define unlikely(x) (x) +#endif /* __GNUC__ */ +static CYTHON_INLINE void __Pyx_pretend_to_initialize(void* ptr) { (void)ptr; } + +#if !CYTHON_USE_MODULE_STATE +static PyObject *__pyx_m = NULL; +#endif +static int __pyx_lineno; +static int __pyx_clineno = 0; +static const char * __pyx_cfilenm = __FILE__; +static const char *__pyx_filename; + +/* #### Code section: filename_table ### */ + +static const char *__pyx_f[] = { + "common/params_pyx.pyx", + "", +}; +/* #### Code section: utility_code_proto_before_types ### */ +/* ForceInitThreads.proto */ +#ifndef __PYX_FORCE_INIT_THREADS + #define __PYX_FORCE_INIT_THREADS 0 +#endif + +/* NoFastGil.proto */ +#define __Pyx_PyGILState_Ensure PyGILState_Ensure +#define __Pyx_PyGILState_Release PyGILState_Release +#define __Pyx_FastGIL_Remember() +#define __Pyx_FastGIL_Forget() +#define __Pyx_FastGilFuncInit() + +/* #### Code section: numeric_typedefs ### */ +/* #### Code section: complex_type_declarations ### */ +/* #### Code section: type_declarations ### */ + +/*--- Type declarations ---*/ +struct __pyx_obj_6common_10params_pyx_Params; +struct __pyx_obj___Pyx_EnumMeta; + +/* "common/params_pyx.pyx":43 + * pass + * + * cdef class Params: # <<<<<<<<<<<<<< + * cdef c_Params* p + * + */ +struct __pyx_obj_6common_10params_pyx_Params { + PyObject_HEAD + Params *p; +}; + + +/* "EnumBase":16 + * + * @cython.internal + * cdef class __Pyx_EnumMeta(type): # <<<<<<<<<<<<<< + * def __init__(cls, name, parents, dct): + * type.__init__(cls, name, parents, dct) + */ +struct __pyx_obj___Pyx_EnumMeta { + PyHeapTypeObject __pyx_base; +}; + +/* #### Code section: utility_code_proto ### */ + +/* --- Runtime support code (head) --- */ +/* Refnanny.proto */ +#ifndef CYTHON_REFNANNY + #define CYTHON_REFNANNY 0 +#endif +#if CYTHON_REFNANNY + typedef struct { + void (*INCREF)(void*, PyObject*, Py_ssize_t); + void (*DECREF)(void*, PyObject*, Py_ssize_t); + void (*GOTREF)(void*, PyObject*, Py_ssize_t); + void (*GIVEREF)(void*, PyObject*, Py_ssize_t); + void* (*SetupContext)(const char*, Py_ssize_t, const char*); + void (*FinishContext)(void**); + } __Pyx_RefNannyAPIStruct; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNanny = NULL; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname); + #define __Pyx_RefNannyDeclarations void *__pyx_refnanny = NULL; +#ifdef WITH_THREAD + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + if (acquire_gil) {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + PyGILState_Release(__pyx_gilstate_save);\ + } else {\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + } + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } +#else + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__)) + #define __Pyx_RefNannyFinishContextNogil() __Pyx_RefNannyFinishContext() +#endif + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } + #define __Pyx_RefNannyFinishContext()\ + __Pyx_RefNanny->FinishContext(&__pyx_refnanny) + #define __Pyx_INCREF(r) __Pyx_RefNanny->INCREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_DECREF(r) __Pyx_RefNanny->DECREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GOTREF(r) __Pyx_RefNanny->GOTREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GIVEREF(r) __Pyx_RefNanny->GIVEREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_XINCREF(r) do { if((r) == NULL); else {__Pyx_INCREF(r); }} while(0) + #define __Pyx_XDECREF(r) do { if((r) == NULL); else {__Pyx_DECREF(r); }} while(0) + #define __Pyx_XGOTREF(r) do { if((r) == NULL); else {__Pyx_GOTREF(r); }} while(0) + #define __Pyx_XGIVEREF(r) do { if((r) == NULL); else {__Pyx_GIVEREF(r);}} while(0) +#else + #define __Pyx_RefNannyDeclarations + #define __Pyx_RefNannySetupContext(name, acquire_gil) + #define __Pyx_RefNannyFinishContextNogil() + #define __Pyx_RefNannyFinishContext() + #define __Pyx_INCREF(r) Py_INCREF(r) + #define __Pyx_DECREF(r) Py_DECREF(r) + #define __Pyx_GOTREF(r) + #define __Pyx_GIVEREF(r) + #define __Pyx_XINCREF(r) Py_XINCREF(r) + #define __Pyx_XDECREF(r) Py_XDECREF(r) + #define __Pyx_XGOTREF(r) + #define __Pyx_XGIVEREF(r) +#endif +#define __Pyx_Py_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; Py_XDECREF(tmp);\ + } while (0) +#define __Pyx_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_XDECREF(tmp);\ + } while (0) +#define __Pyx_DECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_DECREF(tmp);\ + } while (0) +#define __Pyx_CLEAR(r) do { PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);} while(0) +#define __Pyx_XCLEAR(r) do { if((r) != NULL) {PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);}} while(0) + +/* PyErrExceptionMatches.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_ExceptionMatches(err) __Pyx_PyErr_ExceptionMatchesInState(__pyx_tstate, err) +static CYTHON_INLINE int __Pyx_PyErr_ExceptionMatchesInState(PyThreadState* tstate, PyObject* err); +#else +#define __Pyx_PyErr_ExceptionMatches(err) PyErr_ExceptionMatches(err) +#endif + +/* PyThreadStateGet.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyThreadState_declare PyThreadState *__pyx_tstate; +#define __Pyx_PyThreadState_assign __pyx_tstate = __Pyx_PyThreadState_Current; +#if PY_VERSION_HEX >= 0x030C00A6 +#define __Pyx_PyErr_Occurred() (__pyx_tstate->current_exception != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->current_exception ? (PyObject*) Py_TYPE(__pyx_tstate->current_exception) : (PyObject*) NULL) +#else +#define __Pyx_PyErr_Occurred() (__pyx_tstate->curexc_type != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->curexc_type) +#endif +#else +#define __Pyx_PyThreadState_declare +#define __Pyx_PyThreadState_assign +#define __Pyx_PyErr_Occurred() (PyErr_Occurred() != NULL) +#define __Pyx_PyErr_CurrentExceptionType() PyErr_Occurred() +#endif + +/* PyErrFetchRestore.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_Clear() __Pyx_ErrRestore(NULL, NULL, NULL) +#define __Pyx_ErrRestoreWithState(type, value, tb) __Pyx_ErrRestoreInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) __Pyx_ErrFetchInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) __Pyx_ErrRestoreInState(__pyx_tstate, type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) __Pyx_ErrFetchInState(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb); +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A6 +#define __Pyx_PyErr_SetNone(exc) (Py_INCREF(exc), __Pyx_ErrRestore((exc), NULL, NULL)) +#else +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#endif +#else +#define __Pyx_PyErr_Clear() PyErr_Clear() +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#define __Pyx_ErrRestoreWithState(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestoreInState(tstate, type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchInState(tstate, type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) PyErr_Fetch(type, value, tb) +#endif + +/* PyObjectGetAttrStr.proto */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GetAttrStr(o,n) PyObject_GetAttr(o,n) +#endif + +/* PyObjectGetAttrStrNoError.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name); + +/* GetBuiltinName.proto */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name); + +/* PyDictVersioning.proto */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +#define __PYX_DICT_VERSION_INIT ((PY_UINT64_T) -1) +#define __PYX_GET_DICT_VERSION(dict) (((PyDictObject*)(dict))->ma_version_tag) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var)\ + (version_var) = __PYX_GET_DICT_VERSION(dict);\ + (cache_var) = (value); +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + if (likely(__PYX_GET_DICT_VERSION(DICT) == __pyx_dict_version)) {\ + (VAR) = __pyx_dict_cached_value;\ + } else {\ + (VAR) = __pyx_dict_cached_value = (LOOKUP);\ + __pyx_dict_version = __PYX_GET_DICT_VERSION(DICT);\ + }\ +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj); +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj); +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version); +#else +#define __PYX_GET_DICT_VERSION(dict) (0) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var) +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) (VAR) = (LOOKUP); +#endif + +/* GetModuleGlobalName.proto */ +#if CYTHON_USE_DICT_VERSIONS +#define __Pyx_GetModuleGlobalName(var, name) do {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + (var) = (likely(__pyx_dict_version == __PYX_GET_DICT_VERSION(__pyx_d))) ?\ + (likely(__pyx_dict_cached_value) ? __Pyx_NewRef(__pyx_dict_cached_value) : __Pyx_GetBuiltinName(name)) :\ + __Pyx__GetModuleGlobalName(name, &__pyx_dict_version, &__pyx_dict_cached_value);\ +} while(0) +#define __Pyx_GetModuleGlobalNameUncached(var, name) do {\ + PY_UINT64_T __pyx_dict_version;\ + PyObject *__pyx_dict_cached_value;\ + (var) = __Pyx__GetModuleGlobalName(name, &__pyx_dict_version, &__pyx_dict_cached_value);\ +} while(0) +static PyObject *__Pyx__GetModuleGlobalName(PyObject *name, PY_UINT64_T *dict_version, PyObject **dict_cached_value); +#else +#define __Pyx_GetModuleGlobalName(var, name) (var) = __Pyx__GetModuleGlobalName(name) +#define __Pyx_GetModuleGlobalNameUncached(var, name) (var) = __Pyx__GetModuleGlobalName(name) +static CYTHON_INLINE PyObject *__Pyx__GetModuleGlobalName(PyObject *name); +#endif + +/* PyFunctionFastCall.proto */ +#if CYTHON_FAST_PYCALL +#if !CYTHON_VECTORCALL +#define __Pyx_PyFunction_FastCall(func, args, nargs)\ + __Pyx_PyFunction_FastCallDict((func), (args), (nargs), NULL) +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs); +#endif +#define __Pyx_BUILD_ASSERT_EXPR(cond)\ + (sizeof(char [1 - 2*!(cond)]) - 1) +#ifndef Py_MEMBER_SIZE +#define Py_MEMBER_SIZE(type, member) sizeof(((type *)0)->member) +#endif +#if !CYTHON_VECTORCALL +#if PY_VERSION_HEX >= 0x03080000 + #include "frameobject.h" +#if PY_VERSION_HEX >= 0x030b00a6 && !CYTHON_COMPILING_IN_LIMITED_API + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif + #define __Pxy_PyFrame_Initialize_Offsets() + #define __Pyx_PyFrame_GetLocalsplus(frame) ((frame)->f_localsplus) +#else + static size_t __pyx_pyframe_localsplus_offset = 0; + #include "frameobject.h" + #define __Pxy_PyFrame_Initialize_Offsets()\ + ((void)__Pyx_BUILD_ASSERT_EXPR(sizeof(PyFrameObject) == offsetof(PyFrameObject, f_localsplus) + Py_MEMBER_SIZE(PyFrameObject, f_localsplus)),\ + (void)(__pyx_pyframe_localsplus_offset = ((size_t)PyFrame_Type.tp_basicsize) - Py_MEMBER_SIZE(PyFrameObject, f_localsplus))) + #define __Pyx_PyFrame_GetLocalsplus(frame)\ + (assert(__pyx_pyframe_localsplus_offset), (PyObject **)(((char *)(frame)) + __pyx_pyframe_localsplus_offset)) +#endif +#endif +#endif + +/* PyObjectCall.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw); +#else +#define __Pyx_PyObject_Call(func, arg, kw) PyObject_Call(func, arg, kw) +#endif + +/* PyObjectCallMethO.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg); +#endif + +/* PyObjectFastCall.proto */ +#define __Pyx_PyObject_FastCall(func, args, nargs) __Pyx_PyObject_FastCallDict(func, args, (size_t)(nargs), NULL) +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs); + +/* TupleAndListFromArray.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n); +static CYTHON_INLINE PyObject* __Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n); +#endif + +/* IncludeStringH.proto */ +#include + +/* BytesEquals.proto */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals); + +/* UnicodeEquals.proto */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals); + +/* fastcall.proto */ +#if CYTHON_AVOID_BORROWED_REFS + #define __Pyx_Arg_VARARGS(args, i) PySequence_GetItem(args, i) +#elif CYTHON_ASSUME_SAFE_MACROS + #define __Pyx_Arg_VARARGS(args, i) PyTuple_GET_ITEM(args, i) +#else + #define __Pyx_Arg_VARARGS(args, i) PyTuple_GetItem(args, i) +#endif +#if CYTHON_AVOID_BORROWED_REFS + #define __Pyx_Arg_NewRef_VARARGS(arg) __Pyx_NewRef(arg) + #define __Pyx_Arg_XDECREF_VARARGS(arg) Py_XDECREF(arg) +#else + #define __Pyx_Arg_NewRef_VARARGS(arg) arg + #define __Pyx_Arg_XDECREF_VARARGS(arg) +#endif +#define __Pyx_NumKwargs_VARARGS(kwds) PyDict_Size(kwds) +#define __Pyx_KwValues_VARARGS(args, nargs) NULL +#define __Pyx_GetKwValue_VARARGS(kw, kwvalues, s) __Pyx_PyDict_GetItemStrWithError(kw, s) +#define __Pyx_KwargsAsDict_VARARGS(kw, kwvalues) PyDict_Copy(kw) +#if CYTHON_METH_FASTCALL + #define __Pyx_Arg_FASTCALL(args, i) args[i] + #define __Pyx_NumKwargs_FASTCALL(kwds) PyTuple_GET_SIZE(kwds) + #define __Pyx_KwValues_FASTCALL(args, nargs) ((args) + (nargs)) + static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 + CYTHON_UNUSED static PyObject *__Pyx_KwargsAsDict_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues); + #else + #define __Pyx_KwargsAsDict_FASTCALL(kw, kwvalues) _PyStack_AsDict(kwvalues, kw) + #endif + #define __Pyx_Arg_NewRef_FASTCALL(arg) arg /* no-op, __Pyx_Arg_FASTCALL is direct and this needs + to have the same reference counting */ + #define __Pyx_Arg_XDECREF_FASTCALL(arg) +#else + #define __Pyx_Arg_FASTCALL __Pyx_Arg_VARARGS + #define __Pyx_NumKwargs_FASTCALL __Pyx_NumKwargs_VARARGS + #define __Pyx_KwValues_FASTCALL __Pyx_KwValues_VARARGS + #define __Pyx_GetKwValue_FASTCALL __Pyx_GetKwValue_VARARGS + #define __Pyx_KwargsAsDict_FASTCALL __Pyx_KwargsAsDict_VARARGS + #define __Pyx_Arg_NewRef_FASTCALL(arg) __Pyx_Arg_NewRef_VARARGS(arg) + #define __Pyx_Arg_XDECREF_FASTCALL(arg) __Pyx_Arg_XDECREF_VARARGS(arg) +#endif +#if CYTHON_COMPILING_IN_CPYTHON && CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_VARARGS(args, start), stop - start) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_FASTCALL(args, start), stop - start) +#else +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) PyTuple_GetSlice(args, start, stop) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) PyTuple_GetSlice(args, start, stop) +#endif + +/* RaiseArgTupleInvalid.proto */ +static void __Pyx_RaiseArgtupleInvalid(const char* func_name, int exact, + Py_ssize_t num_min, Py_ssize_t num_max, Py_ssize_t num_found); + +/* RaiseDoubleKeywords.proto */ +static void __Pyx_RaiseDoubleKeywordsError(const char* func_name, PyObject* kw_name); + +/* ParseKeywords.proto */ +static int __Pyx_ParseOptionalKeywords(PyObject *kwds, PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, PyObject *values[], Py_ssize_t num_pos_args, + const char* function_name); + +/* PyObjectSetAttrStr.proto */ +#if CYTHON_USE_TYPE_SLOTS +#define __Pyx_PyObject_DelAttrStr(o,n) __Pyx_PyObject_SetAttrStr(o, n, NULL) +static CYTHON_INLINE int __Pyx_PyObject_SetAttrStr(PyObject* obj, PyObject* attr_name, PyObject* value); +#else +#define __Pyx_PyObject_DelAttrStr(o,n) PyObject_DelAttr(o,n) +#define __Pyx_PyObject_SetAttrStr(o,n,v) PyObject_SetAttr(o,n,v) +#endif + +/* GetItemInt.proto */ +#define __Pyx_GetItemInt(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_Fast(o, (Py_ssize_t)i, is_list, wraparound, boundscheck) :\ + (is_list ? (PyErr_SetString(PyExc_IndexError, "list index out of range"), (PyObject*)NULL) :\ + __Pyx_GetItemInt_Generic(o, to_py_func(i)))) +#define __Pyx_GetItemInt_List(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_List_Fast(o, (Py_ssize_t)i, wraparound, boundscheck) :\ + (PyErr_SetString(PyExc_IndexError, "list index out of range"), (PyObject*)NULL)) +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_List_Fast(PyObject *o, Py_ssize_t i, + int wraparound, int boundscheck); +#define __Pyx_GetItemInt_Tuple(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_Tuple_Fast(o, (Py_ssize_t)i, wraparound, boundscheck) :\ + (PyErr_SetString(PyExc_IndexError, "tuple index out of range"), (PyObject*)NULL)) +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Tuple_Fast(PyObject *o, Py_ssize_t i, + int wraparound, int boundscheck); +static PyObject *__Pyx_GetItemInt_Generic(PyObject *o, PyObject* j); +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Fast(PyObject *o, Py_ssize_t i, + int is_list, int wraparound, int boundscheck); + +/* PyObjectCallOneArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg); + +/* ObjectGetItem.proto */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject *__Pyx_PyObject_GetItem(PyObject *obj, PyObject *key); +#else +#define __Pyx_PyObject_GetItem(obj, key) PyObject_GetItem(obj, key) +#endif + +/* KeywordStringCheck.proto */ +static int __Pyx_CheckKeywordStrings(PyObject *kw, const char* function_name, int kw_allowed); + +/* GetAttr3.proto */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr3(PyObject *, PyObject *, PyObject *); + +/* RaiseUnexpectedTypeError.proto */ +static int __Pyx_RaiseUnexpectedTypeError(const char *expected, PyObject *obj); + +/* RaiseException.proto */ +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause); + +/* PySequenceContains.proto */ +static CYTHON_INLINE int __Pyx_PySequence_ContainsTF(PyObject* item, PyObject* seq, int eq) { + int result = PySequence_Contains(seq, item); + return unlikely(result < 0) ? result : (result == (eq == Py_EQ)); +} + +/* Import.proto */ +static PyObject *__Pyx_Import(PyObject *name, PyObject *from_list, int level); + +/* ImportFrom.proto */ +static PyObject* __Pyx_ImportFrom(PyObject* module, PyObject* name); + +/* GetAttr.proto */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr(PyObject *, PyObject *); + +/* HasAttr.proto */ +#if __PYX_LIMITED_VERSION_HEX >= 0x030d00A1 +#define __Pyx_HasAttr(o, n) PyObject_HasAttrWithError(o, n) +#else +static CYTHON_INLINE int __Pyx_HasAttr(PyObject *, PyObject *); +#endif + +/* MoveIfSupported.proto */ +#if CYTHON_USE_CPP_STD_MOVE + #include + #define __PYX_STD_MOVE_IF_SUPPORTED(x) std::move(x) +#else + #define __PYX_STD_MOVE_IF_SUPPORTED(x) x +#endif + +/* IncludeCppStringH.proto */ +#include + +/* decode_c_string_utf16.proto */ +static CYTHON_INLINE PyObject *__Pyx_PyUnicode_DecodeUTF16(const char *s, Py_ssize_t size, const char *errors) { + int byteorder = 0; + return PyUnicode_DecodeUTF16(s, size, errors, &byteorder); +} +static CYTHON_INLINE PyObject *__Pyx_PyUnicode_DecodeUTF16LE(const char *s, Py_ssize_t size, const char *errors) { + int byteorder = -1; + return PyUnicode_DecodeUTF16(s, size, errors, &byteorder); +} +static CYTHON_INLINE PyObject *__Pyx_PyUnicode_DecodeUTF16BE(const char *s, Py_ssize_t size, const char *errors) { + int byteorder = 1; + return PyUnicode_DecodeUTF16(s, size, errors, &byteorder); +} + +/* decode_c_bytes.proto */ +static CYTHON_INLINE PyObject* __Pyx_decode_c_bytes( + const char* cstring, Py_ssize_t length, Py_ssize_t start, Py_ssize_t stop, + const char* encoding, const char* errors, + PyObject* (*decode_func)(const char *s, Py_ssize_t size, const char *errors)); + +/* decode_cpp_string.proto */ +static CYTHON_INLINE PyObject* __Pyx_decode_cpp_string( + std::string cppstring, Py_ssize_t start, Py_ssize_t stop, + const char* encoding, const char* errors, + PyObject* (*decode_func)(const char *s, Py_ssize_t size, const char *errors)) { + return __Pyx_decode_c_bytes( + cppstring.data(), cppstring.size(), start, stop, encoding, errors, decode_func); +} + +/* IncludeStructmemberH.proto */ +#include + +/* FixUpExtensionType.proto */ +#if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type); +#endif + +/* PyObjectCallNoArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func); + +/* PyObjectGetMethod.proto */ +static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method); + +/* PyObjectCallMethod0.proto */ +static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name); + +/* ValidateBasesTuple.proto */ +#if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases); +#endif + +/* PyType_Ready.proto */ +CYTHON_UNUSED static int __Pyx_PyType_Ready(PyTypeObject *t); + +/* PyObject_GenericGetAttrNoDict.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttrNoDict PyObject_GenericGetAttr +#endif + +/* PyObject_GenericGetAttr.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttr PyObject_GenericGetAttr +#endif + +/* SetupReduce.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce(PyObject* type_obj); +#endif + +/* FetchSharedCythonModule.proto */ +static PyObject *__Pyx_FetchSharedCythonABIModule(void); + +/* FetchCommonType.proto */ +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type); +#else +static PyTypeObject* __Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases); +#endif + +/* PyMethodNew.proto */ +#if CYTHON_COMPILING_IN_LIMITED_API +static PyObject *__Pyx_PyMethod_New(PyObject *func, PyObject *self, PyObject *typ) { + PyObject *typesModule=NULL, *methodType=NULL, *result=NULL; + CYTHON_UNUSED_VAR(typ); + if (!self) + return __Pyx_NewRef(func); + typesModule = PyImport_ImportModule("types"); + if (!typesModule) return NULL; + methodType = PyObject_GetAttrString(typesModule, "MethodType"); + Py_DECREF(typesModule); + if (!methodType) return NULL; + result = PyObject_CallFunctionObjArgs(methodType, func, self, NULL); + Py_DECREF(methodType); + return result; +} +#elif PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_PyMethod_New(PyObject *func, PyObject *self, PyObject *typ) { + CYTHON_UNUSED_VAR(typ); + if (!self) + return __Pyx_NewRef(func); + return PyMethod_New(func, self); +} +#else + #define __Pyx_PyMethod_New PyMethod_New +#endif + +/* PyVectorcallFastCallDict.proto */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw); +#endif + +/* CythonFunctionShared.proto */ +#define __Pyx_CyFunction_USED +#define __Pyx_CYFUNCTION_STATICMETHOD 0x01 +#define __Pyx_CYFUNCTION_CLASSMETHOD 0x02 +#define __Pyx_CYFUNCTION_CCLASS 0x04 +#define __Pyx_CYFUNCTION_COROUTINE 0x08 +#define __Pyx_CyFunction_GetClosure(f)\ + (((__pyx_CyFunctionObject *) (f))->func_closure) +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_CyFunction_GetClassObj(f)\ + (((__pyx_CyFunctionObject *) (f))->func_classobj) +#else + #define __Pyx_CyFunction_GetClassObj(f)\ + ((PyObject*) ((PyCMethodObject *) (f))->mm_class) +#endif +#define __Pyx_CyFunction_SetClassObj(f, classobj)\ + __Pyx__CyFunction_SetClassObj((__pyx_CyFunctionObject *) (f), (classobj)) +#define __Pyx_CyFunction_Defaults(type, f)\ + ((type *)(((__pyx_CyFunctionObject *) (f))->defaults)) +#define __Pyx_CyFunction_SetDefaultsGetter(f, g)\ + ((__pyx_CyFunctionObject *) (f))->defaults_getter = (g) +typedef struct { +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject_HEAD + PyObject *func; +#elif PY_VERSION_HEX < 0x030900B1 + PyCFunctionObject func; +#else + PyCMethodObject func; +#endif +#if CYTHON_BACKPORT_VECTORCALL + __pyx_vectorcallfunc func_vectorcall; +#endif +#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API + PyObject *func_weakreflist; +#endif + PyObject *func_dict; + PyObject *func_name; + PyObject *func_qualname; + PyObject *func_doc; + PyObject *func_globals; + PyObject *func_code; + PyObject *func_closure; +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + PyObject *func_classobj; +#endif + void *defaults; + int defaults_pyobjects; + size_t defaults_size; + int flags; + PyObject *defaults_tuple; + PyObject *defaults_kwdict; + PyObject *(*defaults_getter)(PyObject *); + PyObject *func_annotations; + PyObject *func_is_coroutine; +} __pyx_CyFunctionObject; +#undef __Pyx_CyOrPyCFunction_Check +#define __Pyx_CyFunction_Check(obj) __Pyx_TypeCheck(obj, __pyx_CyFunctionType) +#define __Pyx_CyOrPyCFunction_Check(obj) __Pyx_TypeCheck2(obj, __pyx_CyFunctionType, &PyCFunction_Type) +#define __Pyx_CyFunction_CheckExact(obj) __Pyx_IS_TYPE(obj, __pyx_CyFunctionType) +static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc); +#undef __Pyx_IsSameCFunction +#define __Pyx_IsSameCFunction(func, cfunc) __Pyx__IsSameCyOrCFunction(func, cfunc) +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject* op, PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj); +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *m, + size_t size, + int pyobjects); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *m, + PyObject *tuple); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *m, + PyObject *dict); +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *m, + PyObject *dict); +static int __pyx_CyFunction_init(PyObject *module); +#if CYTHON_METH_FASTCALL +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +#if CYTHON_BACKPORT_VECTORCALL +#define __Pyx_CyFunction_func_vectorcall(f) (((__pyx_CyFunctionObject*)f)->func_vectorcall) +#else +#define __Pyx_CyFunction_func_vectorcall(f) (((PyCFunctionObject*)f)->vectorcall) +#endif +#endif + +/* CythonFunction.proto */ +static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); + +/* Py3UpdateBases.proto */ +static PyObject* __Pyx_PEP560_update_bases(PyObject *bases); + +/* SetNameInClass.proto */ +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030500A1 && PY_VERSION_HEX < 0x030d0000 +#define __Pyx_SetNameInClass(ns, name, value)\ + (likely(PyDict_CheckExact(ns)) ? _PyDict_SetItem_KnownHash(ns, name, value, ((PyASCIIObject *) name)->hash) : PyObject_SetItem(ns, name, value)) +#elif CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_SetNameInClass(ns, name, value)\ + (likely(PyDict_CheckExact(ns)) ? PyDict_SetItem(ns, name, value) : PyObject_SetItem(ns, name, value)) +#else +#define __Pyx_SetNameInClass(ns, name, value) PyObject_SetItem(ns, name, value) +#endif + +/* SetNewInClass.proto */ +static int __Pyx_SetNewInClass(PyObject *ns, PyObject *name, PyObject *value); + +/* CalculateMetaclass.proto */ +static PyObject *__Pyx_CalculateMetaclass(PyTypeObject *metaclass, PyObject *bases); + +/* PyObjectCall2Args.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call2Args(PyObject* function, PyObject* arg1, PyObject* arg2); + +/* PyObjectLookupSpecial.proto */ +#if CYTHON_USE_PYTYPE_LOOKUP && CYTHON_USE_TYPE_SLOTS +#define __Pyx_PyObject_LookupSpecialNoError(obj, attr_name) __Pyx__PyObject_LookupSpecial(obj, attr_name, 0) +#define __Pyx_PyObject_LookupSpecial(obj, attr_name) __Pyx__PyObject_LookupSpecial(obj, attr_name, 1) +static CYTHON_INLINE PyObject* __Pyx__PyObject_LookupSpecial(PyObject* obj, PyObject* attr_name, int with_error); +#else +#define __Pyx_PyObject_LookupSpecialNoError(o,n) __Pyx_PyObject_GetAttrStrNoError(o,n) +#define __Pyx_PyObject_LookupSpecial(o,n) __Pyx_PyObject_GetAttrStr(o,n) +#endif + +/* Py3ClassCreate.proto */ +static PyObject *__Pyx_Py3MetaclassPrepare(PyObject *metaclass, PyObject *bases, PyObject *name, PyObject *qualname, + PyObject *mkw, PyObject *modname, PyObject *doc); +static PyObject *__Pyx_Py3ClassCreate(PyObject *metaclass, PyObject *name, PyObject *bases, PyObject *dict, + PyObject *mkw, int calculate_metaclass, int allow_py2_metaclass); + +/* Globals.proto */ +static PyObject* __Pyx_Globals(void); + +/* dict_getitem_default.proto */ +static PyObject* __Pyx_PyDict_GetItemDefault(PyObject* d, PyObject* key, PyObject* default_value); + +/* UnpackUnboundCMethod.proto */ +typedef struct { + PyObject *type; + PyObject **method_name; + PyCFunction func; + PyObject *method; + int flag; +} __Pyx_CachedCFunction; + +/* CallUnboundCMethod1.proto */ +static PyObject* __Pyx__CallUnboundCMethod1(__Pyx_CachedCFunction* cfunc, PyObject* self, PyObject* arg); +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_CallUnboundCMethod1(__Pyx_CachedCFunction* cfunc, PyObject* self, PyObject* arg); +#else +#define __Pyx_CallUnboundCMethod1(cfunc, self, arg) __Pyx__CallUnboundCMethod1(cfunc, self, arg) +#endif + +/* CallUnboundCMethod2.proto */ +static PyObject* __Pyx__CallUnboundCMethod2(__Pyx_CachedCFunction* cfunc, PyObject* self, PyObject* arg1, PyObject* arg2); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030600B1 +static CYTHON_INLINE PyObject *__Pyx_CallUnboundCMethod2(__Pyx_CachedCFunction *cfunc, PyObject *self, PyObject *arg1, PyObject *arg2); +#else +#define __Pyx_CallUnboundCMethod2(cfunc, self, arg1, arg2) __Pyx__CallUnboundCMethod2(cfunc, self, arg1, arg2) +#endif + +/* CLineInTraceback.proto */ +#ifdef CYTHON_CLINE_IN_TRACEBACK +#define __Pyx_CLineForTraceback(tstate, c_line) (((CYTHON_CLINE_IN_TRACEBACK)) ? c_line : 0) +#else +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line); +#endif + +/* CodeObjectCache.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +typedef struct { + PyCodeObject* code_object; + int code_line; +} __Pyx_CodeObjectCacheEntry; +struct __Pyx_CodeObjectCache { + int count; + int max_count; + __Pyx_CodeObjectCacheEntry* entries; +}; +static struct __Pyx_CodeObjectCache __pyx_code_cache = {0,0,NULL}; +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line); +static PyCodeObject *__pyx_find_code_object(int code_line); +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object); +#endif + +/* AddTraceback.proto */ +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename); + +/* GCCDiagnostics.proto */ +#if !defined(__INTEL_COMPILER) && defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 6)) +#define __Pyx_HAS_GCC_DIAGNOSTIC +#endif + +/* CppExceptionConversion.proto */ +#ifndef __Pyx_CppExn2PyErr +#include +#include +#include +#include +static void __Pyx_CppExn2PyErr() { + try { + if (PyErr_Occurred()) + ; // let the latest Python exn pass through and ignore the current one + else + throw; + } catch (const std::bad_alloc& exn) { + PyErr_SetString(PyExc_MemoryError, exn.what()); + } catch (const std::bad_cast& exn) { + PyErr_SetString(PyExc_TypeError, exn.what()); + } catch (const std::bad_typeid& exn) { + PyErr_SetString(PyExc_TypeError, exn.what()); + } catch (const std::domain_error& exn) { + PyErr_SetString(PyExc_ValueError, exn.what()); + } catch (const std::invalid_argument& exn) { + PyErr_SetString(PyExc_ValueError, exn.what()); + } catch (const std::ios_base::failure& exn) { + PyErr_SetString(PyExc_IOError, exn.what()); + } catch (const std::out_of_range& exn) { + PyErr_SetString(PyExc_IndexError, exn.what()); + } catch (const std::overflow_error& exn) { + PyErr_SetString(PyExc_OverflowError, exn.what()); + } catch (const std::range_error& exn) { + PyErr_SetString(PyExc_ArithmeticError, exn.what()); + } catch (const std::underflow_error& exn) { + PyErr_SetString(PyExc_ArithmeticError, exn.what()); + } catch (const std::exception& exn) { + PyErr_SetString(PyExc_RuntimeError, exn.what()); + } + catch (...) + { + PyErr_SetString(PyExc_RuntimeError, "Unknown exception"); + } +} +#endif + +/* CIntFromPy.proto */ +static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *); + +/* CIntFromPy.proto */ +static CYTHON_INLINE enum ParamKeyType __Pyx_PyInt_As_enum__ParamKeyType(PyObject *); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_int(int value); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_enum__ParamKeyType(enum ParamKeyType value); + +/* CIntFromPy.proto */ +static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value); + +/* FormatTypeName.proto */ +#if CYTHON_COMPILING_IN_LIMITED_API +typedef PyObject *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%U" +static __Pyx_TypeName __Pyx_PyType_GetName(PyTypeObject* tp); +#define __Pyx_DECREF_TypeName(obj) Py_XDECREF(obj) +#else +typedef const char *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%.200s" +#define __Pyx_PyType_GetName(tp) ((tp)->tp_name) +#define __Pyx_DECREF_TypeName(obj) +#endif + +/* FastTypeChecks.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_TypeCheck(obj, type) __Pyx_IsSubtype(Py_TYPE(obj), (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) __Pyx_IsAnySubtype2(Py_TYPE(obj), (PyTypeObject *)type1, (PyTypeObject *)type2) +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches(PyObject *err, PyObject *type); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches2(PyObject *err, PyObject *type1, PyObject *type2); +#else +#define __Pyx_TypeCheck(obj, type) PyObject_TypeCheck(obj, (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) (PyObject_TypeCheck(obj, (PyTypeObject *)type1) || PyObject_TypeCheck(obj, (PyTypeObject *)type2)) +#define __Pyx_PyErr_GivenExceptionMatches(err, type) PyErr_GivenExceptionMatches(err, type) +#define __Pyx_PyErr_GivenExceptionMatches2(err, type1, type2) (PyErr_GivenExceptionMatches(err, type1) || PyErr_GivenExceptionMatches(err, type2)) +#endif +#define __Pyx_PyErr_ExceptionMatches2(err1, err2) __Pyx_PyErr_GivenExceptionMatches2(__Pyx_PyErr_CurrentExceptionType(), err1, err2) +#define __Pyx_PyException_Check(obj) __Pyx_TypeCheck(obj, PyExc_Exception) + +/* CheckBinaryVersion.proto */ +static unsigned long __Pyx_get_runtime_version(void); +static int __Pyx_check_binary_version(unsigned long ct_version, unsigned long rt_version, int allow_newer); + +/* InitStrings.proto */ +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t); + +/* #### Code section: module_declarations ### */ + +/* Module declarations from "libcpp" */ + +/* Module declarations from "libc.string" */ + +/* Module declarations from "libcpp.string" */ + +/* Module declarations from "libcpp.vector" */ + +/* Module declarations from "common.params_pyx" */ +static PyObject *__Pyx_OrderedDict = 0; +static PyObject *__Pyx_EnumBase = 0; +static PyObject *__Pyx_FlagBase = 0; +static PyObject *__Pyx_globals = 0; +static PyObject *__Pyx_Enum_enum__space_ParamKeyType_to_py(enum ParamKeyType); /*proto*/ +static std::string __pyx_convert_string_from_py_std__in_string(PyObject *); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyObject_string_to_py_std__in_string(std::string const &); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyUnicode_string_to_py_std__in_string(std::string const &); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyStr_string_to_py_std__in_string(std::string const &); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyBytes_string_to_py_std__in_string(std::string const &); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyByteArray_string_to_py_std__in_string(std::string const &); /*proto*/ +static PyObject *__pyx_convert_vector_to_py_std_3a__3a_string(std::vector const &); /*proto*/ +static PyObject *__pyx_unpickle___Pyx_EnumMeta__set_state(struct __pyx_obj___Pyx_EnumMeta *, PyObject *); /*proto*/ +/* #### Code section: typeinfo ### */ +/* #### Code section: before_global_var ### */ +#define __Pyx_MODULE_NAME "common.params_pyx" +extern int __pyx_module_is_main_common__params_pyx; +int __pyx_module_is_main_common__params_pyx = 0; + +/* Implementation of "common.params_pyx" */ +/* #### Code section: global_var ### */ +static PyObject *__pyx_builtin_KeyboardInterrupt; +static PyObject *__pyx_builtin_TypeError; +static PyObject *__pyx_builtin_MemoryError; +static PyObject *__pyx_builtin_range; +static PyObject *__pyx_builtin_ValueError; +/* #### Code section: string_decls ### */ +static const char __pyx_k_[] = ""; +static const char __pyx_k_d[] = "d"; +static const char __pyx_k_k[] = "k"; +static const char __pyx_k_r[] = "r"; +static const char __pyx_k_v[] = "v"; +static const char __pyx_k__3[] = "."; +static const char __pyx_k_gc[] = "gc"; +static const char __pyx_k_ALL[] = "ALL"; +static const char __pyx_k__52[] = "?"; +static const char __pyx_k_cls[] = "cls"; +static const char __pyx_k_dat[] = "dat"; +static const char __pyx_k_dct[] = "dct"; +static const char __pyx_k_doc[] = "__doc__"; +static const char __pyx_k_get[] = "get"; +static const char __pyx_k_key[] = "key"; +static const char __pyx_k_new[] = "__new__"; +static const char __pyx_k_put[] = "put"; +static const char __pyx_k_res[] = "res"; +static const char __pyx_k_s_s[] = "%s.%s"; +static const char __pyx_k_str[] = "__str__"; +static const char __pyx_k_val[] = "val"; +static const char __pyx_k_dict[] = "__dict__"; +static const char __pyx_k_enum[] = "enum"; +static const char __pyx_k_init[] = "__init__"; +static const char __pyx_k_main[] = "__main__"; +static const char __pyx_k_name[] = "name"; +static const char __pyx_k_repr[] = "__repr__"; +static const char __pyx_k_self[] = "self"; +static const char __pyx_k_test[] = "__test__"; +static const char __pyx_k_block[] = "block"; +static const char __pyx_k_class[] = "__class__"; +static const char __pyx_k_range[] = "range"; +static const char __pyx_k_s_s_d[] = "<%s.%s: %d>"; +static const char __pyx_k_state[] = "state"; +static const char __pyx_k_super[] = "super"; +static const char __pyx_k_value[] = "value"; +static const char __pyx_k_Params[] = "Params"; +static const char __pyx_k_decode[] = "decode"; +static const char __pyx_k_dict_2[] = "_dict"; +static const char __pyx_k_enable[] = "enable"; +static const char __pyx_k_encode[] = "encode"; +static const char __pyx_k_import[] = "__import__"; +static const char __pyx_k_module[] = "__module__"; +static const char __pyx_k_name_2[] = "__name__"; +static const char __pyx_k_pickle[] = "pickle"; +static const char __pyx_k_reduce[] = "__reduce__"; +static const char __pyx_k_remove[] = "remove"; +static const char __pyx_k_update[] = "update"; +static const char __pyx_k_values[] = "values"; +static const char __pyx_k_IntEnum[] = "IntEnum"; +static const char __pyx_k_IntFlag[] = "IntFlag"; +static const char __pyx_k_disable[] = "disable"; +static const char __pyx_k_get_int[] = "get_int"; +static const char __pyx_k_members[] = "__members__"; +static const char __pyx_k_parents[] = "parents"; +static const char __pyx_k_prepare[] = "__prepare__"; +static const char __pyx_k_put_int[] = "put_int"; +static const char __pyx_k_tx_type[] = "tx_type"; +static const char __pyx_k_EnumBase[] = "EnumBase"; +static const char __pyx_k_EnumType[] = "EnumType"; +static const char __pyx_k_all_keys[] = "all_keys"; +static const char __pyx_k_encoding[] = "encoding"; +static const char __pyx_k_get_bool[] = "get_bool"; +static const char __pyx_k_getstate[] = "__getstate__"; +static const char __pyx_k_module_2[] = "module"; +static const char __pyx_k_put_bool[] = "put_bool"; +static const char __pyx_k_pyx_type[] = "__pyx_type"; +static const char __pyx_k_qualname[] = "__qualname__"; +static const char __pyx_k_set_name[] = "__set_name__"; +static const char __pyx_k_setstate[] = "__setstate__"; +static const char __pyx_k_TypeError[] = "TypeError"; +static const char __pyx_k_check_key[] = "check_key"; +static const char __pyx_k_clear_all[] = "clear_all"; +static const char __pyx_k_dat_bytes[] = "dat_bytes"; +static const char __pyx_k_get_float[] = "get_float"; +static const char __pyx_k_isenabled[] = "isenabled"; +static const char __pyx_k_key_bytes[] = "key_bytes"; +static const char __pyx_k_metaclass[] = "__metaclass__"; +static const char __pyx_k_put_float[] = "put_float"; +static const char __pyx_k_pyx_state[] = "__pyx_state"; +static const char __pyx_k_reduce_ex[] = "__reduce_ex__"; +static const char __pyx_k_PERSISTENT[] = "PERSISTENT"; +static const char __pyx_k_Params_get[] = "Params.get"; +static const char __pyx_k_Params_put[] = "Params.put"; +static const char __pyx_k_ValueError[] = "ValueError"; +static const char __pyx_k_pyx_result[] = "__pyx_result"; +static const char __pyx_k_MemoryError[] = "MemoryError"; +static const char __pyx_k_OrderedDict[] = "OrderedDict"; +static const char __pyx_k_PickleError[] = "PickleError"; +static const char __pyx_k_collections[] = "collections"; +static const char __pyx_k_mro_entries[] = "__mro_entries__"; +static const char __pyx_k_ParamKeyType[] = "ParamKeyType"; +static const char __pyx_k_Pyx_EnumBase[] = "__Pyx_EnumBase"; +static const char __pyx_k_Pyx_FlagBase[] = "__Pyx_FlagBase"; +static const char __pyx_k_ensure_bytes[] = "ensure_bytes"; +static const char __pyx_k_is_coroutine[] = "_is_coroutine"; +static const char __pyx_k_member_names[] = "_member_names_"; +static const char __pyx_k_pyx_checksum[] = "__pyx_checksum"; +static const char __pyx_k_stringsource[] = ""; +static const char __pyx_k_use_setstate[] = "use_setstate"; +static const char __pyx_k_Params_remove[] = "Params.remove"; +static const char __pyx_k_class_getitem[] = "__class_getitem__"; +static const char __pyx_k_init_subclass[] = "__init_subclass__"; +static const char __pyx_k_reduce_cython[] = "__reduce_cython__"; +static const char __pyx_k_Params_get_int[] = "Params.get_int"; +static const char __pyx_k_Params_put_int[] = "Params.put_int"; +static const char __pyx_k_UnknownKeyName[] = "UnknownKeyName"; +static const char __pyx_k_get_param_path[] = "get_param_path"; +static const char __pyx_k_Params_all_keys[] = "Params.all_keys"; +static const char __pyx_k_Params_get_bool[] = "Params.get_bool"; +static const char __pyx_k_Params_put_bool[] = "Params.put_bool"; +static const char __pyx_k_put_nonblocking[] = "put_nonblocking"; +static const char __pyx_k_pyx_PickleError[] = "__pyx_PickleError"; +static const char __pyx_k_setstate_cython[] = "__setstate_cython__"; +static const char __pyx_k_DEVELOPMENT_ONLY[] = "DEVELOPMENT_ONLY"; +static const char __pyx_k_Params_check_key[] = "Params.check_key"; +static const char __pyx_k_Params_clear_all[] = "Params.clear_all"; +static const char __pyx_k_Params_get_float[] = "Params.get_float"; +static const char __pyx_k_Params_put_float[] = "Params.put_float"; +static const char __pyx_k_KeyboardInterrupt[] = "KeyboardInterrupt"; +static const char __pyx_k_common_params_pyx[] = "common.params_pyx"; +static const char __pyx_k_Pyx_EnumBase___new[] = "__Pyx_EnumBase.__new__"; +static const char __pyx_k_Pyx_EnumBase___str[] = "__Pyx_EnumBase.__str__"; +static const char __pyx_k_Pyx_FlagBase___new[] = "__Pyx_FlagBase.__new__"; +static const char __pyx_k_Pyx_FlagBase___str[] = "__Pyx_FlagBase.__str__"; +static const char __pyx_k_asyncio_coroutines[] = "asyncio.coroutines"; +static const char __pyx_k_cline_in_traceback[] = "cline_in_traceback"; +static const char __pyx_k_Pyx_EnumBase___repr[] = "__Pyx_EnumBase.__repr__"; +static const char __pyx_k_Pyx_FlagBase___repr[] = "__Pyx_FlagBase.__repr__"; +static const char __pyx_k_put_int_nonblocking[] = "put_int_nonblocking"; +static const char __pyx_k_Unknown_enum_value_s[] = "Unknown enum value: '%s'"; +static const char __pyx_k_put_bool_nonblocking[] = "put_bool_nonblocking"; +static const char __pyx_k_Params_get_param_path[] = "Params.get_param_path"; +static const char __pyx_k_common_params_pyx_pyx[] = "common/params_pyx.pyx"; +static const char __pyx_k_put_float_nonblocking[] = "put_float_nonblocking"; +static const char __pyx_k_CLEAR_ON_MANAGER_START[] = "CLEAR_ON_MANAGER_START"; +static const char __pyx_k_Params___reduce_cython[] = "Params.__reduce_cython__"; +static const char __pyx_k_Params_put_nonblocking[] = "Params.put_nonblocking"; +static const char __pyx_k_Params___setstate_cython[] = "Params.__setstate_cython__"; +static const char __pyx_k_CLEAR_ON_ONROAD_TRANSITION[] = "CLEAR_ON_ONROAD_TRANSITION"; +static const char __pyx_k_Params_put_int_nonblocking[] = "Params.put_int_nonblocking"; +static const char __pyx_k_CLEAR_ON_OFFROAD_TRANSITION[] = "CLEAR_ON_OFFROAD_TRANSITION"; +static const char __pyx_k_Params_put_bool_nonblocking[] = "Params.put_bool_nonblocking"; +static const char __pyx_k_pyx_unpickle___Pyx_EnumMeta[] = "__pyx_unpickle___Pyx_EnumMeta"; +static const char __pyx_k_Params_put_float_nonblocking[] = "Params.put_float_nonblocking"; +static const char __pyx_k_Pyx_EnumMeta___reduce_cython[] = "__Pyx_EnumMeta.__reduce_cython__"; +static const char __pyx_k_Pyx_EnumMeta___setstate_cython[] = "__Pyx_EnumMeta.__setstate_cython__"; +static const char __pyx_k_Incompatible_checksums_0x_x_vs_0[] = "Incompatible checksums (0x%x vs (0xe3b0c44, 0xda39a3e, 0xd41d8cd) = ())"; +static const char __pyx_k_no_default___reduce___due_to_non[] = "no default __reduce__ due to non-trivial __cinit__"; +/* #### Code section: decls ### */ +static int __pyx_pf_8EnumBase_14__Pyx_EnumMeta___init__(struct __pyx_obj___Pyx_EnumMeta *__pyx_v_cls, PyObject *__pyx_v_name, PyObject *__pyx_v_parents, PyObject *__pyx_v_dct); /* proto */ +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumMeta_2__iter__(struct __pyx_obj___Pyx_EnumMeta *__pyx_v_cls); /* proto */ +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumMeta_4__getitem__(struct __pyx_obj___Pyx_EnumMeta *__pyx_v_cls, PyObject *__pyx_v_name); /* proto */ +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumMeta_6__reduce_cython__(struct __pyx_obj___Pyx_EnumMeta *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumMeta_8__setstate_cython__(struct __pyx_obj___Pyx_EnumMeta *__pyx_v_self, PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumBase___new__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_cls, PyObject *__pyx_v_value, PyObject *__pyx_v_name); /* proto */ +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumBase_2__repr__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumBase_4__str__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_8EnumBase_14__Pyx_FlagBase___new__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_cls, PyObject *__pyx_v_value, PyObject *__pyx_v_name); /* proto */ +static PyObject *__pyx_pf_8EnumBase_14__Pyx_FlagBase_2__repr__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_8EnumBase_14__Pyx_FlagBase_4__str__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_8EnumBase___pyx_unpickle___Pyx_EnumMeta(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v___pyx_type, long __pyx_v___pyx_checksum, PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_pf_6common_10params_pyx_ensure_bytes(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_v); /* proto */ +static int __pyx_pf_6common_10params_pyx_6Params___cinit__(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_d); /* proto */ +static void __pyx_pf_6common_10params_pyx_6Params_2__dealloc__(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6common_10params_pyx_6Params_4clear_all(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_tx_type); /* proto */ +static PyObject *__pyx_pf_6common_10params_pyx_6Params_6check_key(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key); /* proto */ +static PyObject *__pyx_pf_6common_10params_pyx_6Params_8get(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key, bool __pyx_v_block, PyObject *__pyx_v_encoding); /* proto */ +static PyObject *__pyx_pf_6common_10params_pyx_6Params_10get_bool(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key, bool __pyx_v_block); /* proto */ +static PyObject *__pyx_pf_6common_10params_pyx_6Params_12get_int(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key, bool __pyx_v_block); /* proto */ +static PyObject *__pyx_pf_6common_10params_pyx_6Params_14get_float(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key, bool __pyx_v_block); /* proto */ +static PyObject *__pyx_pf_6common_10params_pyx_6Params_16put(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key, PyObject *__pyx_v_dat); /* proto */ +static PyObject *__pyx_pf_6common_10params_pyx_6Params_18put_bool(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key, bool __pyx_v_val); /* proto */ +static PyObject *__pyx_pf_6common_10params_pyx_6Params_20put_int(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key, int __pyx_v_val); /* proto */ +static PyObject *__pyx_pf_6common_10params_pyx_6Params_22put_float(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key, float __pyx_v_val); /* proto */ +static PyObject *__pyx_pf_6common_10params_pyx_6Params_24put_nonblocking(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key, PyObject *__pyx_v_dat); /* proto */ +static PyObject *__pyx_pf_6common_10params_pyx_6Params_26put_bool_nonblocking(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key, bool __pyx_v_val); /* proto */ +static PyObject *__pyx_pf_6common_10params_pyx_6Params_28put_int_nonblocking(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key, int __pyx_v_val); /* proto */ +static PyObject *__pyx_pf_6common_10params_pyx_6Params_30put_float_nonblocking(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key, float __pyx_v_val); /* proto */ +static PyObject *__pyx_pf_6common_10params_pyx_6Params_32remove(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key); /* proto */ +static PyObject *__pyx_pf_6common_10params_pyx_6Params_34get_param_path(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key); /* proto */ +static PyObject *__pyx_pf_6common_10params_pyx_6Params_36all_keys(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6common_10params_pyx_6Params_38__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6common_10params_pyx_6Params_40__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_tp_new_6common_10params_pyx_Params(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static __Pyx_CachedCFunction __pyx_umethod_PyDict_Type_get = {0, 0, 0, 0, 0}; +/* #### Code section: late_includes ### */ +/* #### Code section: module_state ### */ +typedef struct { + PyObject *__pyx_d; + PyObject *__pyx_b; + PyObject *__pyx_cython_runtime; + PyObject *__pyx_empty_tuple; + PyObject *__pyx_empty_bytes; + PyObject *__pyx_empty_unicode; + #ifdef __Pyx_CyFunction_USED + PyTypeObject *__pyx_CyFunctionType; + #endif + #ifdef __Pyx_FusedFunction_USED + PyTypeObject *__pyx_FusedFunctionType; + #endif + #ifdef __Pyx_Generator_USED + PyTypeObject *__pyx_GeneratorType; + #endif + #ifdef __Pyx_IterableCoroutine_USED + PyTypeObject *__pyx_IterableCoroutineType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineAwaitType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineType; + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + PyObject *__pyx_type_6common_10params_pyx_Params; + PyObject *__Pyx_EnumMeta; + #endif + PyTypeObject *__pyx_ptype_6common_10params_pyx_Params; + PyTypeObject *__pyx_ptype___Pyx_EnumMeta; + PyObject *__pyx_kp_s_; + PyObject *__pyx_kp_u_; + PyObject *__pyx_n_s_ALL; + PyObject *__pyx_n_s_CLEAR_ON_MANAGER_START; + PyObject *__pyx_n_s_CLEAR_ON_OFFROAD_TRANSITION; + PyObject *__pyx_n_s_CLEAR_ON_ONROAD_TRANSITION; + PyObject *__pyx_n_s_DEVELOPMENT_ONLY; + PyObject *__pyx_n_s_EnumBase; + PyObject *__pyx_n_s_EnumType; + PyObject *__pyx_kp_s_Incompatible_checksums_0x_x_vs_0; + PyObject *__pyx_n_s_IntEnum; + PyObject *__pyx_n_s_IntFlag; + PyObject *__pyx_n_s_KeyboardInterrupt; + PyObject *__pyx_n_s_MemoryError; + PyObject *__pyx_n_s_OrderedDict; + PyObject *__pyx_n_s_PERSISTENT; + PyObject *__pyx_n_s_ParamKeyType; + PyObject *__pyx_n_s_Params; + PyObject *__pyx_n_s_Params___reduce_cython; + PyObject *__pyx_n_s_Params___setstate_cython; + PyObject *__pyx_n_s_Params_all_keys; + PyObject *__pyx_n_s_Params_check_key; + PyObject *__pyx_n_s_Params_clear_all; + PyObject *__pyx_n_s_Params_get; + PyObject *__pyx_n_s_Params_get_bool; + PyObject *__pyx_n_s_Params_get_float; + PyObject *__pyx_n_s_Params_get_int; + PyObject *__pyx_n_s_Params_get_param_path; + PyObject *__pyx_n_s_Params_put; + PyObject *__pyx_n_s_Params_put_bool; + PyObject *__pyx_n_s_Params_put_bool_nonblocking; + PyObject *__pyx_n_s_Params_put_float; + PyObject *__pyx_n_s_Params_put_float_nonblocking; + PyObject *__pyx_n_s_Params_put_int; + PyObject *__pyx_n_s_Params_put_int_nonblocking; + PyObject *__pyx_n_s_Params_put_nonblocking; + PyObject *__pyx_n_s_Params_remove; + PyObject *__pyx_n_s_PickleError; + PyObject *__pyx_n_s_Pyx_EnumBase; + PyObject *__pyx_n_s_Pyx_EnumBase___new; + PyObject *__pyx_n_s_Pyx_EnumBase___repr; + PyObject *__pyx_n_s_Pyx_EnumBase___str; + PyObject *__pyx_n_s_Pyx_EnumMeta___reduce_cython; + PyObject *__pyx_n_s_Pyx_EnumMeta___setstate_cython; + PyObject *__pyx_n_s_Pyx_FlagBase; + PyObject *__pyx_n_s_Pyx_FlagBase___new; + PyObject *__pyx_n_s_Pyx_FlagBase___repr; + PyObject *__pyx_n_s_Pyx_FlagBase___str; + PyObject *__pyx_n_s_TypeError; + PyObject *__pyx_n_s_UnknownKeyName; + PyObject *__pyx_kp_s_Unknown_enum_value_s; + PyObject *__pyx_n_s_ValueError; + PyObject *__pyx_kp_u__3; + PyObject *__pyx_n_s__52; + PyObject *__pyx_n_s_all_keys; + PyObject *__pyx_n_s_asyncio_coroutines; + PyObject *__pyx_n_s_block; + PyObject *__pyx_n_s_check_key; + PyObject *__pyx_n_s_class; + PyObject *__pyx_n_s_class_getitem; + PyObject *__pyx_n_s_clear_all; + PyObject *__pyx_n_s_cline_in_traceback; + PyObject *__pyx_n_s_cls; + PyObject *__pyx_n_s_collections; + PyObject *__pyx_kp_s_common_params_pyx; + PyObject *__pyx_kp_s_common_params_pyx_pyx; + PyObject *__pyx_n_s_d; + PyObject *__pyx_n_s_dat; + PyObject *__pyx_n_s_dat_bytes; + PyObject *__pyx_n_s_dct; + PyObject *__pyx_n_s_decode; + PyObject *__pyx_n_s_dict; + PyObject *__pyx_n_s_dict_2; + PyObject *__pyx_kp_u_disable; + PyObject *__pyx_n_s_doc; + PyObject *__pyx_kp_u_enable; + PyObject *__pyx_n_s_encode; + PyObject *__pyx_n_s_encoding; + PyObject *__pyx_n_s_ensure_bytes; + PyObject *__pyx_n_s_enum; + PyObject *__pyx_kp_u_gc; + PyObject *__pyx_n_s_get; + PyObject *__pyx_n_s_get_bool; + PyObject *__pyx_n_s_get_float; + PyObject *__pyx_n_s_get_int; + PyObject *__pyx_n_s_get_param_path; + PyObject *__pyx_n_s_getstate; + PyObject *__pyx_n_s_import; + PyObject *__pyx_n_s_init; + PyObject *__pyx_n_s_init_subclass; + PyObject *__pyx_n_s_is_coroutine; + PyObject *__pyx_kp_u_isenabled; + PyObject *__pyx_n_s_k; + PyObject *__pyx_n_s_key; + PyObject *__pyx_n_s_key_bytes; + PyObject *__pyx_n_s_main; + PyObject *__pyx_n_s_member_names; + PyObject *__pyx_n_s_members; + PyObject *__pyx_n_s_metaclass; + PyObject *__pyx_n_s_module; + PyObject *__pyx_n_s_module_2; + PyObject *__pyx_n_s_mro_entries; + PyObject *__pyx_n_s_name; + PyObject *__pyx_n_s_name_2; + PyObject *__pyx_n_s_new; + PyObject *__pyx_kp_s_no_default___reduce___due_to_non; + PyObject *__pyx_n_s_parents; + PyObject *__pyx_n_s_pickle; + PyObject *__pyx_n_s_prepare; + PyObject *__pyx_n_s_put; + PyObject *__pyx_n_s_put_bool; + PyObject *__pyx_n_s_put_bool_nonblocking; + PyObject *__pyx_n_s_put_float; + PyObject *__pyx_n_s_put_float_nonblocking; + PyObject *__pyx_n_s_put_int; + PyObject *__pyx_n_s_put_int_nonblocking; + PyObject *__pyx_n_s_put_nonblocking; + PyObject *__pyx_n_s_pyx_PickleError; + PyObject *__pyx_n_s_pyx_checksum; + PyObject *__pyx_n_s_pyx_result; + PyObject *__pyx_n_s_pyx_state; + PyObject *__pyx_n_s_pyx_type; + PyObject *__pyx_n_s_pyx_unpickle___Pyx_EnumMeta; + PyObject *__pyx_n_s_qualname; + PyObject *__pyx_n_s_r; + PyObject *__pyx_n_s_range; + PyObject *__pyx_n_s_reduce; + PyObject *__pyx_n_s_reduce_cython; + PyObject *__pyx_n_s_reduce_ex; + PyObject *__pyx_n_s_remove; + PyObject *__pyx_n_s_repr; + PyObject *__pyx_n_s_res; + PyObject *__pyx_kp_s_s_s; + PyObject *__pyx_kp_s_s_s_d; + PyObject *__pyx_n_s_self; + PyObject *__pyx_n_s_set_name; + PyObject *__pyx_n_s_setstate; + PyObject *__pyx_n_s_setstate_cython; + PyObject *__pyx_n_s_state; + PyObject *__pyx_n_s_str; + PyObject *__pyx_kp_s_stringsource; + PyObject *__pyx_n_s_super; + PyObject *__pyx_n_s_test; + PyObject *__pyx_n_s_tx_type; + PyObject *__pyx_n_s_update; + PyObject *__pyx_n_s_use_setstate; + PyObject *__pyx_n_s_v; + PyObject *__pyx_n_s_val; + PyObject *__pyx_n_s_value; + PyObject *__pyx_n_s_values; + PyObject *__pyx_int_222419149; + PyObject *__pyx_int_228825662; + PyObject *__pyx_int_238750788; + PyObject *__pyx_k__4; + PyObject *__pyx_tuple__2; + PyObject *__pyx_tuple__5; + PyObject *__pyx_tuple__7; + PyObject *__pyx_tuple__9; + PyObject *__pyx_tuple__11; + PyObject *__pyx_tuple__12; + PyObject *__pyx_tuple__18; + PyObject *__pyx_tuple__20; + PyObject *__pyx_tuple__22; + PyObject *__pyx_tuple__24; + PyObject *__pyx_tuple__26; + PyObject *__pyx_tuple__28; + PyObject *__pyx_tuple__29; + PyObject *__pyx_tuple__31; + PyObject *__pyx_tuple__34; + PyObject *__pyx_tuple__36; + PyObject *__pyx_tuple__44; + PyObject *__pyx_tuple__46; + PyObject *__pyx_tuple__48; + PyObject *__pyx_codeobj__6; + PyObject *__pyx_codeobj__8; + PyObject *__pyx_codeobj__10; + PyObject *__pyx_codeobj__13; + PyObject *__pyx_codeobj__14; + PyObject *__pyx_codeobj__15; + PyObject *__pyx_codeobj__16; + PyObject *__pyx_codeobj__17; + PyObject *__pyx_codeobj__19; + PyObject *__pyx_codeobj__21; + PyObject *__pyx_codeobj__23; + PyObject *__pyx_codeobj__25; + PyObject *__pyx_codeobj__27; + PyObject *__pyx_codeobj__30; + PyObject *__pyx_codeobj__32; + PyObject *__pyx_codeobj__33; + PyObject *__pyx_codeobj__35; + PyObject *__pyx_codeobj__37; + PyObject *__pyx_codeobj__38; + PyObject *__pyx_codeobj__39; + PyObject *__pyx_codeobj__40; + PyObject *__pyx_codeobj__41; + PyObject *__pyx_codeobj__42; + PyObject *__pyx_codeobj__43; + PyObject *__pyx_codeobj__45; + PyObject *__pyx_codeobj__47; + PyObject *__pyx_codeobj__49; + PyObject *__pyx_codeobj__50; + PyObject *__pyx_codeobj__51; +} __pyx_mstate; + +#if CYTHON_USE_MODULE_STATE +#ifdef __cplusplus +namespace { + extern struct PyModuleDef __pyx_moduledef; +} /* anonymous namespace */ +#else +static struct PyModuleDef __pyx_moduledef; +#endif + +#define __pyx_mstate(o) ((__pyx_mstate *)__Pyx_PyModule_GetState(o)) + +#define __pyx_mstate_global (__pyx_mstate(PyState_FindModule(&__pyx_moduledef))) + +#define __pyx_m (PyState_FindModule(&__pyx_moduledef)) +#else +static __pyx_mstate __pyx_mstate_global_static = +#ifdef __cplusplus + {}; +#else + {0}; +#endif +static __pyx_mstate *__pyx_mstate_global = &__pyx_mstate_global_static; +#endif +/* #### Code section: module_state_clear ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_clear(PyObject *m) { + __pyx_mstate *clear_module_state = __pyx_mstate(m); + if (!clear_module_state) return 0; + Py_CLEAR(clear_module_state->__pyx_d); + Py_CLEAR(clear_module_state->__pyx_b); + Py_CLEAR(clear_module_state->__pyx_cython_runtime); + Py_CLEAR(clear_module_state->__pyx_empty_tuple); + Py_CLEAR(clear_module_state->__pyx_empty_bytes); + Py_CLEAR(clear_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_CLEAR(clear_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_CLEAR(clear_module_state->__pyx_FusedFunctionType); + #endif + Py_CLEAR(clear_module_state->__pyx_ptype_6common_10params_pyx_Params); + Py_CLEAR(clear_module_state->__pyx_type_6common_10params_pyx_Params); + Py_CLEAR(clear_module_state->__pyx_ptype___Pyx_EnumMeta); + Py_CLEAR(clear_module_state->__Pyx_EnumMeta); + Py_CLEAR(clear_module_state->__pyx_kp_s_); + Py_CLEAR(clear_module_state->__pyx_kp_u_); + Py_CLEAR(clear_module_state->__pyx_n_s_ALL); + Py_CLEAR(clear_module_state->__pyx_n_s_CLEAR_ON_MANAGER_START); + Py_CLEAR(clear_module_state->__pyx_n_s_CLEAR_ON_OFFROAD_TRANSITION); + Py_CLEAR(clear_module_state->__pyx_n_s_CLEAR_ON_ONROAD_TRANSITION); + Py_CLEAR(clear_module_state->__pyx_n_s_DEVELOPMENT_ONLY); + Py_CLEAR(clear_module_state->__pyx_n_s_EnumBase); + Py_CLEAR(clear_module_state->__pyx_n_s_EnumType); + Py_CLEAR(clear_module_state->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0); + Py_CLEAR(clear_module_state->__pyx_n_s_IntEnum); + Py_CLEAR(clear_module_state->__pyx_n_s_IntFlag); + Py_CLEAR(clear_module_state->__pyx_n_s_KeyboardInterrupt); + Py_CLEAR(clear_module_state->__pyx_n_s_MemoryError); + Py_CLEAR(clear_module_state->__pyx_n_s_OrderedDict); + Py_CLEAR(clear_module_state->__pyx_n_s_PERSISTENT); + Py_CLEAR(clear_module_state->__pyx_n_s_ParamKeyType); + Py_CLEAR(clear_module_state->__pyx_n_s_Params); + Py_CLEAR(clear_module_state->__pyx_n_s_Params___reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_Params___setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_Params_all_keys); + Py_CLEAR(clear_module_state->__pyx_n_s_Params_check_key); + Py_CLEAR(clear_module_state->__pyx_n_s_Params_clear_all); + Py_CLEAR(clear_module_state->__pyx_n_s_Params_get); + Py_CLEAR(clear_module_state->__pyx_n_s_Params_get_bool); + Py_CLEAR(clear_module_state->__pyx_n_s_Params_get_float); + Py_CLEAR(clear_module_state->__pyx_n_s_Params_get_int); + Py_CLEAR(clear_module_state->__pyx_n_s_Params_get_param_path); + Py_CLEAR(clear_module_state->__pyx_n_s_Params_put); + Py_CLEAR(clear_module_state->__pyx_n_s_Params_put_bool); + Py_CLEAR(clear_module_state->__pyx_n_s_Params_put_bool_nonblocking); + Py_CLEAR(clear_module_state->__pyx_n_s_Params_put_float); + Py_CLEAR(clear_module_state->__pyx_n_s_Params_put_float_nonblocking); + Py_CLEAR(clear_module_state->__pyx_n_s_Params_put_int); + Py_CLEAR(clear_module_state->__pyx_n_s_Params_put_int_nonblocking); + Py_CLEAR(clear_module_state->__pyx_n_s_Params_put_nonblocking); + Py_CLEAR(clear_module_state->__pyx_n_s_Params_remove); + Py_CLEAR(clear_module_state->__pyx_n_s_PickleError); + Py_CLEAR(clear_module_state->__pyx_n_s_Pyx_EnumBase); + Py_CLEAR(clear_module_state->__pyx_n_s_Pyx_EnumBase___new); + Py_CLEAR(clear_module_state->__pyx_n_s_Pyx_EnumBase___repr); + Py_CLEAR(clear_module_state->__pyx_n_s_Pyx_EnumBase___str); + Py_CLEAR(clear_module_state->__pyx_n_s_Pyx_EnumMeta___reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_Pyx_EnumMeta___setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_Pyx_FlagBase); + Py_CLEAR(clear_module_state->__pyx_n_s_Pyx_FlagBase___new); + Py_CLEAR(clear_module_state->__pyx_n_s_Pyx_FlagBase___repr); + Py_CLEAR(clear_module_state->__pyx_n_s_Pyx_FlagBase___str); + Py_CLEAR(clear_module_state->__pyx_n_s_TypeError); + Py_CLEAR(clear_module_state->__pyx_n_s_UnknownKeyName); + Py_CLEAR(clear_module_state->__pyx_kp_s_Unknown_enum_value_s); + Py_CLEAR(clear_module_state->__pyx_n_s_ValueError); + Py_CLEAR(clear_module_state->__pyx_kp_u__3); + Py_CLEAR(clear_module_state->__pyx_n_s__52); + Py_CLEAR(clear_module_state->__pyx_n_s_all_keys); + Py_CLEAR(clear_module_state->__pyx_n_s_asyncio_coroutines); + Py_CLEAR(clear_module_state->__pyx_n_s_block); + Py_CLEAR(clear_module_state->__pyx_n_s_check_key); + Py_CLEAR(clear_module_state->__pyx_n_s_class); + Py_CLEAR(clear_module_state->__pyx_n_s_class_getitem); + Py_CLEAR(clear_module_state->__pyx_n_s_clear_all); + Py_CLEAR(clear_module_state->__pyx_n_s_cline_in_traceback); + Py_CLEAR(clear_module_state->__pyx_n_s_cls); + Py_CLEAR(clear_module_state->__pyx_n_s_collections); + Py_CLEAR(clear_module_state->__pyx_kp_s_common_params_pyx); + Py_CLEAR(clear_module_state->__pyx_kp_s_common_params_pyx_pyx); + Py_CLEAR(clear_module_state->__pyx_n_s_d); + Py_CLEAR(clear_module_state->__pyx_n_s_dat); + Py_CLEAR(clear_module_state->__pyx_n_s_dat_bytes); + Py_CLEAR(clear_module_state->__pyx_n_s_dct); + Py_CLEAR(clear_module_state->__pyx_n_s_decode); + Py_CLEAR(clear_module_state->__pyx_n_s_dict); + Py_CLEAR(clear_module_state->__pyx_n_s_dict_2); + Py_CLEAR(clear_module_state->__pyx_kp_u_disable); + Py_CLEAR(clear_module_state->__pyx_n_s_doc); + Py_CLEAR(clear_module_state->__pyx_kp_u_enable); + Py_CLEAR(clear_module_state->__pyx_n_s_encode); + Py_CLEAR(clear_module_state->__pyx_n_s_encoding); + Py_CLEAR(clear_module_state->__pyx_n_s_ensure_bytes); + Py_CLEAR(clear_module_state->__pyx_n_s_enum); + Py_CLEAR(clear_module_state->__pyx_kp_u_gc); + Py_CLEAR(clear_module_state->__pyx_n_s_get); + Py_CLEAR(clear_module_state->__pyx_n_s_get_bool); + Py_CLEAR(clear_module_state->__pyx_n_s_get_float); + Py_CLEAR(clear_module_state->__pyx_n_s_get_int); + Py_CLEAR(clear_module_state->__pyx_n_s_get_param_path); + Py_CLEAR(clear_module_state->__pyx_n_s_getstate); + Py_CLEAR(clear_module_state->__pyx_n_s_import); + Py_CLEAR(clear_module_state->__pyx_n_s_init); + Py_CLEAR(clear_module_state->__pyx_n_s_init_subclass); + Py_CLEAR(clear_module_state->__pyx_n_s_is_coroutine); + Py_CLEAR(clear_module_state->__pyx_kp_u_isenabled); + Py_CLEAR(clear_module_state->__pyx_n_s_k); + Py_CLEAR(clear_module_state->__pyx_n_s_key); + Py_CLEAR(clear_module_state->__pyx_n_s_key_bytes); + Py_CLEAR(clear_module_state->__pyx_n_s_main); + Py_CLEAR(clear_module_state->__pyx_n_s_member_names); + Py_CLEAR(clear_module_state->__pyx_n_s_members); + Py_CLEAR(clear_module_state->__pyx_n_s_metaclass); + Py_CLEAR(clear_module_state->__pyx_n_s_module); + Py_CLEAR(clear_module_state->__pyx_n_s_module_2); + Py_CLEAR(clear_module_state->__pyx_n_s_mro_entries); + Py_CLEAR(clear_module_state->__pyx_n_s_name); + Py_CLEAR(clear_module_state->__pyx_n_s_name_2); + Py_CLEAR(clear_module_state->__pyx_n_s_new); + Py_CLEAR(clear_module_state->__pyx_kp_s_no_default___reduce___due_to_non); + Py_CLEAR(clear_module_state->__pyx_n_s_parents); + Py_CLEAR(clear_module_state->__pyx_n_s_pickle); + Py_CLEAR(clear_module_state->__pyx_n_s_prepare); + Py_CLEAR(clear_module_state->__pyx_n_s_put); + Py_CLEAR(clear_module_state->__pyx_n_s_put_bool); + Py_CLEAR(clear_module_state->__pyx_n_s_put_bool_nonblocking); + Py_CLEAR(clear_module_state->__pyx_n_s_put_float); + Py_CLEAR(clear_module_state->__pyx_n_s_put_float_nonblocking); + Py_CLEAR(clear_module_state->__pyx_n_s_put_int); + Py_CLEAR(clear_module_state->__pyx_n_s_put_int_nonblocking); + Py_CLEAR(clear_module_state->__pyx_n_s_put_nonblocking); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_PickleError); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_checksum); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_result); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_state); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_type); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_unpickle___Pyx_EnumMeta); + Py_CLEAR(clear_module_state->__pyx_n_s_qualname); + Py_CLEAR(clear_module_state->__pyx_n_s_r); + Py_CLEAR(clear_module_state->__pyx_n_s_range); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_ex); + Py_CLEAR(clear_module_state->__pyx_n_s_remove); + Py_CLEAR(clear_module_state->__pyx_n_s_repr); + Py_CLEAR(clear_module_state->__pyx_n_s_res); + Py_CLEAR(clear_module_state->__pyx_kp_s_s_s); + Py_CLEAR(clear_module_state->__pyx_kp_s_s_s_d); + Py_CLEAR(clear_module_state->__pyx_n_s_self); + Py_CLEAR(clear_module_state->__pyx_n_s_set_name); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_state); + Py_CLEAR(clear_module_state->__pyx_n_s_str); + Py_CLEAR(clear_module_state->__pyx_kp_s_stringsource); + Py_CLEAR(clear_module_state->__pyx_n_s_super); + Py_CLEAR(clear_module_state->__pyx_n_s_test); + Py_CLEAR(clear_module_state->__pyx_n_s_tx_type); + Py_CLEAR(clear_module_state->__pyx_n_s_update); + Py_CLEAR(clear_module_state->__pyx_n_s_use_setstate); + Py_CLEAR(clear_module_state->__pyx_n_s_v); + Py_CLEAR(clear_module_state->__pyx_n_s_val); + Py_CLEAR(clear_module_state->__pyx_n_s_value); + Py_CLEAR(clear_module_state->__pyx_n_s_values); + Py_CLEAR(clear_module_state->__pyx_int_222419149); + Py_CLEAR(clear_module_state->__pyx_int_228825662); + Py_CLEAR(clear_module_state->__pyx_int_238750788); + Py_CLEAR(clear_module_state->__pyx_k__4); + Py_CLEAR(clear_module_state->__pyx_tuple__2); + Py_CLEAR(clear_module_state->__pyx_tuple__5); + Py_CLEAR(clear_module_state->__pyx_tuple__7); + Py_CLEAR(clear_module_state->__pyx_tuple__9); + Py_CLEAR(clear_module_state->__pyx_tuple__11); + Py_CLEAR(clear_module_state->__pyx_tuple__12); + Py_CLEAR(clear_module_state->__pyx_tuple__18); + Py_CLEAR(clear_module_state->__pyx_tuple__20); + Py_CLEAR(clear_module_state->__pyx_tuple__22); + Py_CLEAR(clear_module_state->__pyx_tuple__24); + Py_CLEAR(clear_module_state->__pyx_tuple__26); + Py_CLEAR(clear_module_state->__pyx_tuple__28); + Py_CLEAR(clear_module_state->__pyx_tuple__29); + Py_CLEAR(clear_module_state->__pyx_tuple__31); + Py_CLEAR(clear_module_state->__pyx_tuple__34); + Py_CLEAR(clear_module_state->__pyx_tuple__36); + Py_CLEAR(clear_module_state->__pyx_tuple__44); + Py_CLEAR(clear_module_state->__pyx_tuple__46); + Py_CLEAR(clear_module_state->__pyx_tuple__48); + Py_CLEAR(clear_module_state->__pyx_codeobj__6); + Py_CLEAR(clear_module_state->__pyx_codeobj__8); + Py_CLEAR(clear_module_state->__pyx_codeobj__10); + Py_CLEAR(clear_module_state->__pyx_codeobj__13); + Py_CLEAR(clear_module_state->__pyx_codeobj__14); + Py_CLEAR(clear_module_state->__pyx_codeobj__15); + Py_CLEAR(clear_module_state->__pyx_codeobj__16); + Py_CLEAR(clear_module_state->__pyx_codeobj__17); + Py_CLEAR(clear_module_state->__pyx_codeobj__19); + Py_CLEAR(clear_module_state->__pyx_codeobj__21); + Py_CLEAR(clear_module_state->__pyx_codeobj__23); + Py_CLEAR(clear_module_state->__pyx_codeobj__25); + Py_CLEAR(clear_module_state->__pyx_codeobj__27); + Py_CLEAR(clear_module_state->__pyx_codeobj__30); + Py_CLEAR(clear_module_state->__pyx_codeobj__32); + Py_CLEAR(clear_module_state->__pyx_codeobj__33); + Py_CLEAR(clear_module_state->__pyx_codeobj__35); + Py_CLEAR(clear_module_state->__pyx_codeobj__37); + Py_CLEAR(clear_module_state->__pyx_codeobj__38); + Py_CLEAR(clear_module_state->__pyx_codeobj__39); + Py_CLEAR(clear_module_state->__pyx_codeobj__40); + Py_CLEAR(clear_module_state->__pyx_codeobj__41); + Py_CLEAR(clear_module_state->__pyx_codeobj__42); + Py_CLEAR(clear_module_state->__pyx_codeobj__43); + Py_CLEAR(clear_module_state->__pyx_codeobj__45); + Py_CLEAR(clear_module_state->__pyx_codeobj__47); + Py_CLEAR(clear_module_state->__pyx_codeobj__49); + Py_CLEAR(clear_module_state->__pyx_codeobj__50); + Py_CLEAR(clear_module_state->__pyx_codeobj__51); + return 0; +} +#endif +/* #### Code section: module_state_traverse ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { + __pyx_mstate *traverse_module_state = __pyx_mstate(m); + if (!traverse_module_state) return 0; + Py_VISIT(traverse_module_state->__pyx_d); + Py_VISIT(traverse_module_state->__pyx_b); + Py_VISIT(traverse_module_state->__pyx_cython_runtime); + Py_VISIT(traverse_module_state->__pyx_empty_tuple); + Py_VISIT(traverse_module_state->__pyx_empty_bytes); + Py_VISIT(traverse_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_VISIT(traverse_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_VISIT(traverse_module_state->__pyx_FusedFunctionType); + #endif + Py_VISIT(traverse_module_state->__pyx_ptype_6common_10params_pyx_Params); + Py_VISIT(traverse_module_state->__pyx_type_6common_10params_pyx_Params); + Py_VISIT(traverse_module_state->__pyx_ptype___Pyx_EnumMeta); + Py_VISIT(traverse_module_state->__Pyx_EnumMeta); + Py_VISIT(traverse_module_state->__pyx_kp_s_); + Py_VISIT(traverse_module_state->__pyx_kp_u_); + Py_VISIT(traverse_module_state->__pyx_n_s_ALL); + Py_VISIT(traverse_module_state->__pyx_n_s_CLEAR_ON_MANAGER_START); + Py_VISIT(traverse_module_state->__pyx_n_s_CLEAR_ON_OFFROAD_TRANSITION); + Py_VISIT(traverse_module_state->__pyx_n_s_CLEAR_ON_ONROAD_TRANSITION); + Py_VISIT(traverse_module_state->__pyx_n_s_DEVELOPMENT_ONLY); + Py_VISIT(traverse_module_state->__pyx_n_s_EnumBase); + Py_VISIT(traverse_module_state->__pyx_n_s_EnumType); + Py_VISIT(traverse_module_state->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0); + Py_VISIT(traverse_module_state->__pyx_n_s_IntEnum); + Py_VISIT(traverse_module_state->__pyx_n_s_IntFlag); + Py_VISIT(traverse_module_state->__pyx_n_s_KeyboardInterrupt); + Py_VISIT(traverse_module_state->__pyx_n_s_MemoryError); + Py_VISIT(traverse_module_state->__pyx_n_s_OrderedDict); + Py_VISIT(traverse_module_state->__pyx_n_s_PERSISTENT); + Py_VISIT(traverse_module_state->__pyx_n_s_ParamKeyType); + Py_VISIT(traverse_module_state->__pyx_n_s_Params); + Py_VISIT(traverse_module_state->__pyx_n_s_Params___reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_Params___setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_Params_all_keys); + Py_VISIT(traverse_module_state->__pyx_n_s_Params_check_key); + Py_VISIT(traverse_module_state->__pyx_n_s_Params_clear_all); + Py_VISIT(traverse_module_state->__pyx_n_s_Params_get); + Py_VISIT(traverse_module_state->__pyx_n_s_Params_get_bool); + Py_VISIT(traverse_module_state->__pyx_n_s_Params_get_float); + Py_VISIT(traverse_module_state->__pyx_n_s_Params_get_int); + Py_VISIT(traverse_module_state->__pyx_n_s_Params_get_param_path); + Py_VISIT(traverse_module_state->__pyx_n_s_Params_put); + Py_VISIT(traverse_module_state->__pyx_n_s_Params_put_bool); + Py_VISIT(traverse_module_state->__pyx_n_s_Params_put_bool_nonblocking); + Py_VISIT(traverse_module_state->__pyx_n_s_Params_put_float); + Py_VISIT(traverse_module_state->__pyx_n_s_Params_put_float_nonblocking); + Py_VISIT(traverse_module_state->__pyx_n_s_Params_put_int); + Py_VISIT(traverse_module_state->__pyx_n_s_Params_put_int_nonblocking); + Py_VISIT(traverse_module_state->__pyx_n_s_Params_put_nonblocking); + Py_VISIT(traverse_module_state->__pyx_n_s_Params_remove); + Py_VISIT(traverse_module_state->__pyx_n_s_PickleError); + Py_VISIT(traverse_module_state->__pyx_n_s_Pyx_EnumBase); + Py_VISIT(traverse_module_state->__pyx_n_s_Pyx_EnumBase___new); + Py_VISIT(traverse_module_state->__pyx_n_s_Pyx_EnumBase___repr); + Py_VISIT(traverse_module_state->__pyx_n_s_Pyx_EnumBase___str); + Py_VISIT(traverse_module_state->__pyx_n_s_Pyx_EnumMeta___reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_Pyx_EnumMeta___setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_Pyx_FlagBase); + Py_VISIT(traverse_module_state->__pyx_n_s_Pyx_FlagBase___new); + Py_VISIT(traverse_module_state->__pyx_n_s_Pyx_FlagBase___repr); + Py_VISIT(traverse_module_state->__pyx_n_s_Pyx_FlagBase___str); + Py_VISIT(traverse_module_state->__pyx_n_s_TypeError); + Py_VISIT(traverse_module_state->__pyx_n_s_UnknownKeyName); + Py_VISIT(traverse_module_state->__pyx_kp_s_Unknown_enum_value_s); + Py_VISIT(traverse_module_state->__pyx_n_s_ValueError); + Py_VISIT(traverse_module_state->__pyx_kp_u__3); + Py_VISIT(traverse_module_state->__pyx_n_s__52); + Py_VISIT(traverse_module_state->__pyx_n_s_all_keys); + Py_VISIT(traverse_module_state->__pyx_n_s_asyncio_coroutines); + Py_VISIT(traverse_module_state->__pyx_n_s_block); + Py_VISIT(traverse_module_state->__pyx_n_s_check_key); + Py_VISIT(traverse_module_state->__pyx_n_s_class); + Py_VISIT(traverse_module_state->__pyx_n_s_class_getitem); + Py_VISIT(traverse_module_state->__pyx_n_s_clear_all); + Py_VISIT(traverse_module_state->__pyx_n_s_cline_in_traceback); + Py_VISIT(traverse_module_state->__pyx_n_s_cls); + Py_VISIT(traverse_module_state->__pyx_n_s_collections); + Py_VISIT(traverse_module_state->__pyx_kp_s_common_params_pyx); + Py_VISIT(traverse_module_state->__pyx_kp_s_common_params_pyx_pyx); + Py_VISIT(traverse_module_state->__pyx_n_s_d); + Py_VISIT(traverse_module_state->__pyx_n_s_dat); + Py_VISIT(traverse_module_state->__pyx_n_s_dat_bytes); + Py_VISIT(traverse_module_state->__pyx_n_s_dct); + Py_VISIT(traverse_module_state->__pyx_n_s_decode); + Py_VISIT(traverse_module_state->__pyx_n_s_dict); + Py_VISIT(traverse_module_state->__pyx_n_s_dict_2); + Py_VISIT(traverse_module_state->__pyx_kp_u_disable); + Py_VISIT(traverse_module_state->__pyx_n_s_doc); + Py_VISIT(traverse_module_state->__pyx_kp_u_enable); + Py_VISIT(traverse_module_state->__pyx_n_s_encode); + Py_VISIT(traverse_module_state->__pyx_n_s_encoding); + Py_VISIT(traverse_module_state->__pyx_n_s_ensure_bytes); + Py_VISIT(traverse_module_state->__pyx_n_s_enum); + Py_VISIT(traverse_module_state->__pyx_kp_u_gc); + Py_VISIT(traverse_module_state->__pyx_n_s_get); + Py_VISIT(traverse_module_state->__pyx_n_s_get_bool); + Py_VISIT(traverse_module_state->__pyx_n_s_get_float); + Py_VISIT(traverse_module_state->__pyx_n_s_get_int); + Py_VISIT(traverse_module_state->__pyx_n_s_get_param_path); + Py_VISIT(traverse_module_state->__pyx_n_s_getstate); + Py_VISIT(traverse_module_state->__pyx_n_s_import); + Py_VISIT(traverse_module_state->__pyx_n_s_init); + Py_VISIT(traverse_module_state->__pyx_n_s_init_subclass); + Py_VISIT(traverse_module_state->__pyx_n_s_is_coroutine); + Py_VISIT(traverse_module_state->__pyx_kp_u_isenabled); + Py_VISIT(traverse_module_state->__pyx_n_s_k); + Py_VISIT(traverse_module_state->__pyx_n_s_key); + Py_VISIT(traverse_module_state->__pyx_n_s_key_bytes); + Py_VISIT(traverse_module_state->__pyx_n_s_main); + Py_VISIT(traverse_module_state->__pyx_n_s_member_names); + Py_VISIT(traverse_module_state->__pyx_n_s_members); + Py_VISIT(traverse_module_state->__pyx_n_s_metaclass); + Py_VISIT(traverse_module_state->__pyx_n_s_module); + Py_VISIT(traverse_module_state->__pyx_n_s_module_2); + Py_VISIT(traverse_module_state->__pyx_n_s_mro_entries); + Py_VISIT(traverse_module_state->__pyx_n_s_name); + Py_VISIT(traverse_module_state->__pyx_n_s_name_2); + Py_VISIT(traverse_module_state->__pyx_n_s_new); + Py_VISIT(traverse_module_state->__pyx_kp_s_no_default___reduce___due_to_non); + Py_VISIT(traverse_module_state->__pyx_n_s_parents); + Py_VISIT(traverse_module_state->__pyx_n_s_pickle); + Py_VISIT(traverse_module_state->__pyx_n_s_prepare); + Py_VISIT(traverse_module_state->__pyx_n_s_put); + Py_VISIT(traverse_module_state->__pyx_n_s_put_bool); + Py_VISIT(traverse_module_state->__pyx_n_s_put_bool_nonblocking); + Py_VISIT(traverse_module_state->__pyx_n_s_put_float); + Py_VISIT(traverse_module_state->__pyx_n_s_put_float_nonblocking); + Py_VISIT(traverse_module_state->__pyx_n_s_put_int); + Py_VISIT(traverse_module_state->__pyx_n_s_put_int_nonblocking); + Py_VISIT(traverse_module_state->__pyx_n_s_put_nonblocking); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_PickleError); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_checksum); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_result); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_state); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_type); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_unpickle___Pyx_EnumMeta); + Py_VISIT(traverse_module_state->__pyx_n_s_qualname); + Py_VISIT(traverse_module_state->__pyx_n_s_r); + Py_VISIT(traverse_module_state->__pyx_n_s_range); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_ex); + Py_VISIT(traverse_module_state->__pyx_n_s_remove); + Py_VISIT(traverse_module_state->__pyx_n_s_repr); + Py_VISIT(traverse_module_state->__pyx_n_s_res); + Py_VISIT(traverse_module_state->__pyx_kp_s_s_s); + Py_VISIT(traverse_module_state->__pyx_kp_s_s_s_d); + Py_VISIT(traverse_module_state->__pyx_n_s_self); + Py_VISIT(traverse_module_state->__pyx_n_s_set_name); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_state); + Py_VISIT(traverse_module_state->__pyx_n_s_str); + Py_VISIT(traverse_module_state->__pyx_kp_s_stringsource); + Py_VISIT(traverse_module_state->__pyx_n_s_super); + Py_VISIT(traverse_module_state->__pyx_n_s_test); + Py_VISIT(traverse_module_state->__pyx_n_s_tx_type); + Py_VISIT(traverse_module_state->__pyx_n_s_update); + Py_VISIT(traverse_module_state->__pyx_n_s_use_setstate); + Py_VISIT(traverse_module_state->__pyx_n_s_v); + Py_VISIT(traverse_module_state->__pyx_n_s_val); + Py_VISIT(traverse_module_state->__pyx_n_s_value); + Py_VISIT(traverse_module_state->__pyx_n_s_values); + Py_VISIT(traverse_module_state->__pyx_int_222419149); + Py_VISIT(traverse_module_state->__pyx_int_228825662); + Py_VISIT(traverse_module_state->__pyx_int_238750788); + Py_VISIT(traverse_module_state->__pyx_k__4); + Py_VISIT(traverse_module_state->__pyx_tuple__2); + Py_VISIT(traverse_module_state->__pyx_tuple__5); + Py_VISIT(traverse_module_state->__pyx_tuple__7); + Py_VISIT(traverse_module_state->__pyx_tuple__9); + Py_VISIT(traverse_module_state->__pyx_tuple__11); + Py_VISIT(traverse_module_state->__pyx_tuple__12); + Py_VISIT(traverse_module_state->__pyx_tuple__18); + Py_VISIT(traverse_module_state->__pyx_tuple__20); + Py_VISIT(traverse_module_state->__pyx_tuple__22); + Py_VISIT(traverse_module_state->__pyx_tuple__24); + Py_VISIT(traverse_module_state->__pyx_tuple__26); + Py_VISIT(traverse_module_state->__pyx_tuple__28); + Py_VISIT(traverse_module_state->__pyx_tuple__29); + Py_VISIT(traverse_module_state->__pyx_tuple__31); + Py_VISIT(traverse_module_state->__pyx_tuple__34); + Py_VISIT(traverse_module_state->__pyx_tuple__36); + Py_VISIT(traverse_module_state->__pyx_tuple__44); + Py_VISIT(traverse_module_state->__pyx_tuple__46); + Py_VISIT(traverse_module_state->__pyx_tuple__48); + Py_VISIT(traverse_module_state->__pyx_codeobj__6); + Py_VISIT(traverse_module_state->__pyx_codeobj__8); + Py_VISIT(traverse_module_state->__pyx_codeobj__10); + Py_VISIT(traverse_module_state->__pyx_codeobj__13); + Py_VISIT(traverse_module_state->__pyx_codeobj__14); + Py_VISIT(traverse_module_state->__pyx_codeobj__15); + Py_VISIT(traverse_module_state->__pyx_codeobj__16); + Py_VISIT(traverse_module_state->__pyx_codeobj__17); + Py_VISIT(traverse_module_state->__pyx_codeobj__19); + Py_VISIT(traverse_module_state->__pyx_codeobj__21); + Py_VISIT(traverse_module_state->__pyx_codeobj__23); + Py_VISIT(traverse_module_state->__pyx_codeobj__25); + Py_VISIT(traverse_module_state->__pyx_codeobj__27); + Py_VISIT(traverse_module_state->__pyx_codeobj__30); + Py_VISIT(traverse_module_state->__pyx_codeobj__32); + Py_VISIT(traverse_module_state->__pyx_codeobj__33); + Py_VISIT(traverse_module_state->__pyx_codeobj__35); + Py_VISIT(traverse_module_state->__pyx_codeobj__37); + Py_VISIT(traverse_module_state->__pyx_codeobj__38); + Py_VISIT(traverse_module_state->__pyx_codeobj__39); + Py_VISIT(traverse_module_state->__pyx_codeobj__40); + Py_VISIT(traverse_module_state->__pyx_codeobj__41); + Py_VISIT(traverse_module_state->__pyx_codeobj__42); + Py_VISIT(traverse_module_state->__pyx_codeobj__43); + Py_VISIT(traverse_module_state->__pyx_codeobj__45); + Py_VISIT(traverse_module_state->__pyx_codeobj__47); + Py_VISIT(traverse_module_state->__pyx_codeobj__49); + Py_VISIT(traverse_module_state->__pyx_codeobj__50); + Py_VISIT(traverse_module_state->__pyx_codeobj__51); + return 0; +} +#endif +/* #### Code section: module_state_defines ### */ +#define __pyx_d __pyx_mstate_global->__pyx_d +#define __pyx_b __pyx_mstate_global->__pyx_b +#define __pyx_cython_runtime __pyx_mstate_global->__pyx_cython_runtime +#define __pyx_empty_tuple __pyx_mstate_global->__pyx_empty_tuple +#define __pyx_empty_bytes __pyx_mstate_global->__pyx_empty_bytes +#define __pyx_empty_unicode __pyx_mstate_global->__pyx_empty_unicode +#ifdef __Pyx_CyFunction_USED +#define __pyx_CyFunctionType __pyx_mstate_global->__pyx_CyFunctionType +#endif +#ifdef __Pyx_FusedFunction_USED +#define __pyx_FusedFunctionType __pyx_mstate_global->__pyx_FusedFunctionType +#endif +#ifdef __Pyx_Generator_USED +#define __pyx_GeneratorType __pyx_mstate_global->__pyx_GeneratorType +#endif +#ifdef __Pyx_IterableCoroutine_USED +#define __pyx_IterableCoroutineType __pyx_mstate_global->__pyx_IterableCoroutineType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineAwaitType __pyx_mstate_global->__pyx_CoroutineAwaitType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineType __pyx_mstate_global->__pyx_CoroutineType +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#define __pyx_type_6common_10params_pyx_Params __pyx_mstate_global->__pyx_type_6common_10params_pyx_Params +#define __Pyx_EnumMeta __pyx_mstate_global->__Pyx_EnumMeta +#endif +#define __pyx_ptype_6common_10params_pyx_Params __pyx_mstate_global->__pyx_ptype_6common_10params_pyx_Params +#define __pyx_ptype___Pyx_EnumMeta __pyx_mstate_global->__pyx_ptype___Pyx_EnumMeta +#define __pyx_kp_s_ __pyx_mstate_global->__pyx_kp_s_ +#define __pyx_kp_u_ __pyx_mstate_global->__pyx_kp_u_ +#define __pyx_n_s_ALL __pyx_mstate_global->__pyx_n_s_ALL +#define __pyx_n_s_CLEAR_ON_MANAGER_START __pyx_mstate_global->__pyx_n_s_CLEAR_ON_MANAGER_START +#define __pyx_n_s_CLEAR_ON_OFFROAD_TRANSITION __pyx_mstate_global->__pyx_n_s_CLEAR_ON_OFFROAD_TRANSITION +#define __pyx_n_s_CLEAR_ON_ONROAD_TRANSITION __pyx_mstate_global->__pyx_n_s_CLEAR_ON_ONROAD_TRANSITION +#define __pyx_n_s_DEVELOPMENT_ONLY __pyx_mstate_global->__pyx_n_s_DEVELOPMENT_ONLY +#define __pyx_n_s_EnumBase __pyx_mstate_global->__pyx_n_s_EnumBase +#define __pyx_n_s_EnumType __pyx_mstate_global->__pyx_n_s_EnumType +#define __pyx_kp_s_Incompatible_checksums_0x_x_vs_0 __pyx_mstate_global->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0 +#define __pyx_n_s_IntEnum __pyx_mstate_global->__pyx_n_s_IntEnum +#define __pyx_n_s_IntFlag __pyx_mstate_global->__pyx_n_s_IntFlag +#define __pyx_n_s_KeyboardInterrupt __pyx_mstate_global->__pyx_n_s_KeyboardInterrupt +#define __pyx_n_s_MemoryError __pyx_mstate_global->__pyx_n_s_MemoryError +#define __pyx_n_s_OrderedDict __pyx_mstate_global->__pyx_n_s_OrderedDict +#define __pyx_n_s_PERSISTENT __pyx_mstate_global->__pyx_n_s_PERSISTENT +#define __pyx_n_s_ParamKeyType __pyx_mstate_global->__pyx_n_s_ParamKeyType +#define __pyx_n_s_Params __pyx_mstate_global->__pyx_n_s_Params +#define __pyx_n_s_Params___reduce_cython __pyx_mstate_global->__pyx_n_s_Params___reduce_cython +#define __pyx_n_s_Params___setstate_cython __pyx_mstate_global->__pyx_n_s_Params___setstate_cython +#define __pyx_n_s_Params_all_keys __pyx_mstate_global->__pyx_n_s_Params_all_keys +#define __pyx_n_s_Params_check_key __pyx_mstate_global->__pyx_n_s_Params_check_key +#define __pyx_n_s_Params_clear_all __pyx_mstate_global->__pyx_n_s_Params_clear_all +#define __pyx_n_s_Params_get __pyx_mstate_global->__pyx_n_s_Params_get +#define __pyx_n_s_Params_get_bool __pyx_mstate_global->__pyx_n_s_Params_get_bool +#define __pyx_n_s_Params_get_float __pyx_mstate_global->__pyx_n_s_Params_get_float +#define __pyx_n_s_Params_get_int __pyx_mstate_global->__pyx_n_s_Params_get_int +#define __pyx_n_s_Params_get_param_path __pyx_mstate_global->__pyx_n_s_Params_get_param_path +#define __pyx_n_s_Params_put __pyx_mstate_global->__pyx_n_s_Params_put +#define __pyx_n_s_Params_put_bool __pyx_mstate_global->__pyx_n_s_Params_put_bool +#define __pyx_n_s_Params_put_bool_nonblocking __pyx_mstate_global->__pyx_n_s_Params_put_bool_nonblocking +#define __pyx_n_s_Params_put_float __pyx_mstate_global->__pyx_n_s_Params_put_float +#define __pyx_n_s_Params_put_float_nonblocking __pyx_mstate_global->__pyx_n_s_Params_put_float_nonblocking +#define __pyx_n_s_Params_put_int __pyx_mstate_global->__pyx_n_s_Params_put_int +#define __pyx_n_s_Params_put_int_nonblocking __pyx_mstate_global->__pyx_n_s_Params_put_int_nonblocking +#define __pyx_n_s_Params_put_nonblocking __pyx_mstate_global->__pyx_n_s_Params_put_nonblocking +#define __pyx_n_s_Params_remove __pyx_mstate_global->__pyx_n_s_Params_remove +#define __pyx_n_s_PickleError __pyx_mstate_global->__pyx_n_s_PickleError +#define __pyx_n_s_Pyx_EnumBase __pyx_mstate_global->__pyx_n_s_Pyx_EnumBase +#define __pyx_n_s_Pyx_EnumBase___new __pyx_mstate_global->__pyx_n_s_Pyx_EnumBase___new +#define __pyx_n_s_Pyx_EnumBase___repr __pyx_mstate_global->__pyx_n_s_Pyx_EnumBase___repr +#define __pyx_n_s_Pyx_EnumBase___str __pyx_mstate_global->__pyx_n_s_Pyx_EnumBase___str +#define __pyx_n_s_Pyx_EnumMeta___reduce_cython __pyx_mstate_global->__pyx_n_s_Pyx_EnumMeta___reduce_cython +#define __pyx_n_s_Pyx_EnumMeta___setstate_cython __pyx_mstate_global->__pyx_n_s_Pyx_EnumMeta___setstate_cython +#define __pyx_n_s_Pyx_FlagBase __pyx_mstate_global->__pyx_n_s_Pyx_FlagBase +#define __pyx_n_s_Pyx_FlagBase___new __pyx_mstate_global->__pyx_n_s_Pyx_FlagBase___new +#define __pyx_n_s_Pyx_FlagBase___repr __pyx_mstate_global->__pyx_n_s_Pyx_FlagBase___repr +#define __pyx_n_s_Pyx_FlagBase___str __pyx_mstate_global->__pyx_n_s_Pyx_FlagBase___str +#define __pyx_n_s_TypeError __pyx_mstate_global->__pyx_n_s_TypeError +#define __pyx_n_s_UnknownKeyName __pyx_mstate_global->__pyx_n_s_UnknownKeyName +#define __pyx_kp_s_Unknown_enum_value_s __pyx_mstate_global->__pyx_kp_s_Unknown_enum_value_s +#define __pyx_n_s_ValueError __pyx_mstate_global->__pyx_n_s_ValueError +#define __pyx_kp_u__3 __pyx_mstate_global->__pyx_kp_u__3 +#define __pyx_n_s__52 __pyx_mstate_global->__pyx_n_s__52 +#define __pyx_n_s_all_keys __pyx_mstate_global->__pyx_n_s_all_keys +#define __pyx_n_s_asyncio_coroutines __pyx_mstate_global->__pyx_n_s_asyncio_coroutines +#define __pyx_n_s_block __pyx_mstate_global->__pyx_n_s_block +#define __pyx_n_s_check_key __pyx_mstate_global->__pyx_n_s_check_key +#define __pyx_n_s_class __pyx_mstate_global->__pyx_n_s_class +#define __pyx_n_s_class_getitem __pyx_mstate_global->__pyx_n_s_class_getitem +#define __pyx_n_s_clear_all __pyx_mstate_global->__pyx_n_s_clear_all +#define __pyx_n_s_cline_in_traceback __pyx_mstate_global->__pyx_n_s_cline_in_traceback +#define __pyx_n_s_cls __pyx_mstate_global->__pyx_n_s_cls +#define __pyx_n_s_collections __pyx_mstate_global->__pyx_n_s_collections +#define __pyx_kp_s_common_params_pyx __pyx_mstate_global->__pyx_kp_s_common_params_pyx +#define __pyx_kp_s_common_params_pyx_pyx __pyx_mstate_global->__pyx_kp_s_common_params_pyx_pyx +#define __pyx_n_s_d __pyx_mstate_global->__pyx_n_s_d +#define __pyx_n_s_dat __pyx_mstate_global->__pyx_n_s_dat +#define __pyx_n_s_dat_bytes __pyx_mstate_global->__pyx_n_s_dat_bytes +#define __pyx_n_s_dct __pyx_mstate_global->__pyx_n_s_dct +#define __pyx_n_s_decode __pyx_mstate_global->__pyx_n_s_decode +#define __pyx_n_s_dict __pyx_mstate_global->__pyx_n_s_dict +#define __pyx_n_s_dict_2 __pyx_mstate_global->__pyx_n_s_dict_2 +#define __pyx_kp_u_disable __pyx_mstate_global->__pyx_kp_u_disable +#define __pyx_n_s_doc __pyx_mstate_global->__pyx_n_s_doc +#define __pyx_kp_u_enable __pyx_mstate_global->__pyx_kp_u_enable +#define __pyx_n_s_encode __pyx_mstate_global->__pyx_n_s_encode +#define __pyx_n_s_encoding __pyx_mstate_global->__pyx_n_s_encoding +#define __pyx_n_s_ensure_bytes __pyx_mstate_global->__pyx_n_s_ensure_bytes +#define __pyx_n_s_enum __pyx_mstate_global->__pyx_n_s_enum +#define __pyx_kp_u_gc __pyx_mstate_global->__pyx_kp_u_gc +#define __pyx_n_s_get __pyx_mstate_global->__pyx_n_s_get +#define __pyx_n_s_get_bool __pyx_mstate_global->__pyx_n_s_get_bool +#define __pyx_n_s_get_float __pyx_mstate_global->__pyx_n_s_get_float +#define __pyx_n_s_get_int __pyx_mstate_global->__pyx_n_s_get_int +#define __pyx_n_s_get_param_path __pyx_mstate_global->__pyx_n_s_get_param_path +#define __pyx_n_s_getstate __pyx_mstate_global->__pyx_n_s_getstate +#define __pyx_n_s_import __pyx_mstate_global->__pyx_n_s_import +#define __pyx_n_s_init __pyx_mstate_global->__pyx_n_s_init +#define __pyx_n_s_init_subclass __pyx_mstate_global->__pyx_n_s_init_subclass +#define __pyx_n_s_is_coroutine __pyx_mstate_global->__pyx_n_s_is_coroutine +#define __pyx_kp_u_isenabled __pyx_mstate_global->__pyx_kp_u_isenabled +#define __pyx_n_s_k __pyx_mstate_global->__pyx_n_s_k +#define __pyx_n_s_key __pyx_mstate_global->__pyx_n_s_key +#define __pyx_n_s_key_bytes __pyx_mstate_global->__pyx_n_s_key_bytes +#define __pyx_n_s_main __pyx_mstate_global->__pyx_n_s_main +#define __pyx_n_s_member_names __pyx_mstate_global->__pyx_n_s_member_names +#define __pyx_n_s_members __pyx_mstate_global->__pyx_n_s_members +#define __pyx_n_s_metaclass __pyx_mstate_global->__pyx_n_s_metaclass +#define __pyx_n_s_module __pyx_mstate_global->__pyx_n_s_module +#define __pyx_n_s_module_2 __pyx_mstate_global->__pyx_n_s_module_2 +#define __pyx_n_s_mro_entries __pyx_mstate_global->__pyx_n_s_mro_entries +#define __pyx_n_s_name __pyx_mstate_global->__pyx_n_s_name +#define __pyx_n_s_name_2 __pyx_mstate_global->__pyx_n_s_name_2 +#define __pyx_n_s_new __pyx_mstate_global->__pyx_n_s_new +#define __pyx_kp_s_no_default___reduce___due_to_non __pyx_mstate_global->__pyx_kp_s_no_default___reduce___due_to_non +#define __pyx_n_s_parents __pyx_mstate_global->__pyx_n_s_parents +#define __pyx_n_s_pickle __pyx_mstate_global->__pyx_n_s_pickle +#define __pyx_n_s_prepare __pyx_mstate_global->__pyx_n_s_prepare +#define __pyx_n_s_put __pyx_mstate_global->__pyx_n_s_put +#define __pyx_n_s_put_bool __pyx_mstate_global->__pyx_n_s_put_bool +#define __pyx_n_s_put_bool_nonblocking __pyx_mstate_global->__pyx_n_s_put_bool_nonblocking +#define __pyx_n_s_put_float __pyx_mstate_global->__pyx_n_s_put_float +#define __pyx_n_s_put_float_nonblocking __pyx_mstate_global->__pyx_n_s_put_float_nonblocking +#define __pyx_n_s_put_int __pyx_mstate_global->__pyx_n_s_put_int +#define __pyx_n_s_put_int_nonblocking __pyx_mstate_global->__pyx_n_s_put_int_nonblocking +#define __pyx_n_s_put_nonblocking __pyx_mstate_global->__pyx_n_s_put_nonblocking +#define __pyx_n_s_pyx_PickleError __pyx_mstate_global->__pyx_n_s_pyx_PickleError +#define __pyx_n_s_pyx_checksum __pyx_mstate_global->__pyx_n_s_pyx_checksum +#define __pyx_n_s_pyx_result __pyx_mstate_global->__pyx_n_s_pyx_result +#define __pyx_n_s_pyx_state __pyx_mstate_global->__pyx_n_s_pyx_state +#define __pyx_n_s_pyx_type __pyx_mstate_global->__pyx_n_s_pyx_type +#define __pyx_n_s_pyx_unpickle___Pyx_EnumMeta __pyx_mstate_global->__pyx_n_s_pyx_unpickle___Pyx_EnumMeta +#define __pyx_n_s_qualname __pyx_mstate_global->__pyx_n_s_qualname +#define __pyx_n_s_r __pyx_mstate_global->__pyx_n_s_r +#define __pyx_n_s_range __pyx_mstate_global->__pyx_n_s_range +#define __pyx_n_s_reduce __pyx_mstate_global->__pyx_n_s_reduce +#define __pyx_n_s_reduce_cython __pyx_mstate_global->__pyx_n_s_reduce_cython +#define __pyx_n_s_reduce_ex __pyx_mstate_global->__pyx_n_s_reduce_ex +#define __pyx_n_s_remove __pyx_mstate_global->__pyx_n_s_remove +#define __pyx_n_s_repr __pyx_mstate_global->__pyx_n_s_repr +#define __pyx_n_s_res __pyx_mstate_global->__pyx_n_s_res +#define __pyx_kp_s_s_s __pyx_mstate_global->__pyx_kp_s_s_s +#define __pyx_kp_s_s_s_d __pyx_mstate_global->__pyx_kp_s_s_s_d +#define __pyx_n_s_self __pyx_mstate_global->__pyx_n_s_self +#define __pyx_n_s_set_name __pyx_mstate_global->__pyx_n_s_set_name +#define __pyx_n_s_setstate __pyx_mstate_global->__pyx_n_s_setstate +#define __pyx_n_s_setstate_cython __pyx_mstate_global->__pyx_n_s_setstate_cython +#define __pyx_n_s_state __pyx_mstate_global->__pyx_n_s_state +#define __pyx_n_s_str __pyx_mstate_global->__pyx_n_s_str +#define __pyx_kp_s_stringsource __pyx_mstate_global->__pyx_kp_s_stringsource +#define __pyx_n_s_super __pyx_mstate_global->__pyx_n_s_super +#define __pyx_n_s_test __pyx_mstate_global->__pyx_n_s_test +#define __pyx_n_s_tx_type __pyx_mstate_global->__pyx_n_s_tx_type +#define __pyx_n_s_update __pyx_mstate_global->__pyx_n_s_update +#define __pyx_n_s_use_setstate __pyx_mstate_global->__pyx_n_s_use_setstate +#define __pyx_n_s_v __pyx_mstate_global->__pyx_n_s_v +#define __pyx_n_s_val __pyx_mstate_global->__pyx_n_s_val +#define __pyx_n_s_value __pyx_mstate_global->__pyx_n_s_value +#define __pyx_n_s_values __pyx_mstate_global->__pyx_n_s_values +#define __pyx_int_222419149 __pyx_mstate_global->__pyx_int_222419149 +#define __pyx_int_228825662 __pyx_mstate_global->__pyx_int_228825662 +#define __pyx_int_238750788 __pyx_mstate_global->__pyx_int_238750788 +#define __pyx_k__4 __pyx_mstate_global->__pyx_k__4 +#define __pyx_tuple__2 __pyx_mstate_global->__pyx_tuple__2 +#define __pyx_tuple__5 __pyx_mstate_global->__pyx_tuple__5 +#define __pyx_tuple__7 __pyx_mstate_global->__pyx_tuple__7 +#define __pyx_tuple__9 __pyx_mstate_global->__pyx_tuple__9 +#define __pyx_tuple__11 __pyx_mstate_global->__pyx_tuple__11 +#define __pyx_tuple__12 __pyx_mstate_global->__pyx_tuple__12 +#define __pyx_tuple__18 __pyx_mstate_global->__pyx_tuple__18 +#define __pyx_tuple__20 __pyx_mstate_global->__pyx_tuple__20 +#define __pyx_tuple__22 __pyx_mstate_global->__pyx_tuple__22 +#define __pyx_tuple__24 __pyx_mstate_global->__pyx_tuple__24 +#define __pyx_tuple__26 __pyx_mstate_global->__pyx_tuple__26 +#define __pyx_tuple__28 __pyx_mstate_global->__pyx_tuple__28 +#define __pyx_tuple__29 __pyx_mstate_global->__pyx_tuple__29 +#define __pyx_tuple__31 __pyx_mstate_global->__pyx_tuple__31 +#define __pyx_tuple__34 __pyx_mstate_global->__pyx_tuple__34 +#define __pyx_tuple__36 __pyx_mstate_global->__pyx_tuple__36 +#define __pyx_tuple__44 __pyx_mstate_global->__pyx_tuple__44 +#define __pyx_tuple__46 __pyx_mstate_global->__pyx_tuple__46 +#define __pyx_tuple__48 __pyx_mstate_global->__pyx_tuple__48 +#define __pyx_codeobj__6 __pyx_mstate_global->__pyx_codeobj__6 +#define __pyx_codeobj__8 __pyx_mstate_global->__pyx_codeobj__8 +#define __pyx_codeobj__10 __pyx_mstate_global->__pyx_codeobj__10 +#define __pyx_codeobj__13 __pyx_mstate_global->__pyx_codeobj__13 +#define __pyx_codeobj__14 __pyx_mstate_global->__pyx_codeobj__14 +#define __pyx_codeobj__15 __pyx_mstate_global->__pyx_codeobj__15 +#define __pyx_codeobj__16 __pyx_mstate_global->__pyx_codeobj__16 +#define __pyx_codeobj__17 __pyx_mstate_global->__pyx_codeobj__17 +#define __pyx_codeobj__19 __pyx_mstate_global->__pyx_codeobj__19 +#define __pyx_codeobj__21 __pyx_mstate_global->__pyx_codeobj__21 +#define __pyx_codeobj__23 __pyx_mstate_global->__pyx_codeobj__23 +#define __pyx_codeobj__25 __pyx_mstate_global->__pyx_codeobj__25 +#define __pyx_codeobj__27 __pyx_mstate_global->__pyx_codeobj__27 +#define __pyx_codeobj__30 __pyx_mstate_global->__pyx_codeobj__30 +#define __pyx_codeobj__32 __pyx_mstate_global->__pyx_codeobj__32 +#define __pyx_codeobj__33 __pyx_mstate_global->__pyx_codeobj__33 +#define __pyx_codeobj__35 __pyx_mstate_global->__pyx_codeobj__35 +#define __pyx_codeobj__37 __pyx_mstate_global->__pyx_codeobj__37 +#define __pyx_codeobj__38 __pyx_mstate_global->__pyx_codeobj__38 +#define __pyx_codeobj__39 __pyx_mstate_global->__pyx_codeobj__39 +#define __pyx_codeobj__40 __pyx_mstate_global->__pyx_codeobj__40 +#define __pyx_codeobj__41 __pyx_mstate_global->__pyx_codeobj__41 +#define __pyx_codeobj__42 __pyx_mstate_global->__pyx_codeobj__42 +#define __pyx_codeobj__43 __pyx_mstate_global->__pyx_codeobj__43 +#define __pyx_codeobj__45 __pyx_mstate_global->__pyx_codeobj__45 +#define __pyx_codeobj__47 __pyx_mstate_global->__pyx_codeobj__47 +#define __pyx_codeobj__49 __pyx_mstate_global->__pyx_codeobj__49 +#define __pyx_codeobj__50 __pyx_mstate_global->__pyx_codeobj__50 +#define __pyx_codeobj__51 __pyx_mstate_global->__pyx_codeobj__51 +/* #### Code section: module_code ### */ + +/* "EnumTypeToPy":132 + * + * @cname("__Pyx_Enum_enum__space_ParamKeyType_to_py") + * cdef __Pyx_Enum_enum__space_ParamKeyType_to_py(ParamKeyType c_val): # <<<<<<<<<<<<<< + * cdef object __pyx_enum + * + */ + +static PyObject *__Pyx_Enum_enum__space_ParamKeyType_to_py(enum ParamKeyType __pyx_v_c_val) { + PyObject *__pyx_v___pyx_enum = 0; + int __pyx_v_underlying_c_val; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_Enum_enum__space_ParamKeyType_to_py", 1); + + /* "EnumTypeToPy":137 + * + * + * __pyx_enum = ParamKeyType # <<<<<<<<<<<<<< + * + * if 0: + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_ParamKeyType); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 137, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v___pyx_enum = __pyx_t_1; + __pyx_t_1 = 0; + + /* "EnumTypeToPy":141 + * if 0: + * pass + * elif c_val == ParamKeyType.PERSISTENT: # <<<<<<<<<<<<<< + * return __pyx_enum.PERSISTENT + * elif c_val == ParamKeyType.CLEAR_ON_MANAGER_START: + */ + __pyx_t_2 = (__pyx_v_c_val == PERSISTENT); + if (__pyx_t_2) { + + /* "EnumTypeToPy":142 + * pass + * elif c_val == ParamKeyType.PERSISTENT: + * return __pyx_enum.PERSISTENT # <<<<<<<<<<<<<< + * elif c_val == ParamKeyType.CLEAR_ON_MANAGER_START: + * return __pyx_enum.CLEAR_ON_MANAGER_START + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v___pyx_enum, __pyx_n_s_PERSISTENT); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 142, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "EnumTypeToPy":141 + * if 0: + * pass + * elif c_val == ParamKeyType.PERSISTENT: # <<<<<<<<<<<<<< + * return __pyx_enum.PERSISTENT + * elif c_val == ParamKeyType.CLEAR_ON_MANAGER_START: + */ + } + + /* "EnumTypeToPy":143 + * elif c_val == ParamKeyType.PERSISTENT: + * return __pyx_enum.PERSISTENT + * elif c_val == ParamKeyType.CLEAR_ON_MANAGER_START: # <<<<<<<<<<<<<< + * return __pyx_enum.CLEAR_ON_MANAGER_START + * elif c_val == ParamKeyType.CLEAR_ON_ONROAD_TRANSITION: + */ + __pyx_t_2 = (__pyx_v_c_val == CLEAR_ON_MANAGER_START); + if (__pyx_t_2) { + + /* "EnumTypeToPy":144 + * return __pyx_enum.PERSISTENT + * elif c_val == ParamKeyType.CLEAR_ON_MANAGER_START: + * return __pyx_enum.CLEAR_ON_MANAGER_START # <<<<<<<<<<<<<< + * elif c_val == ParamKeyType.CLEAR_ON_ONROAD_TRANSITION: + * return __pyx_enum.CLEAR_ON_ONROAD_TRANSITION + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v___pyx_enum, __pyx_n_s_CLEAR_ON_MANAGER_START); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 144, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "EnumTypeToPy":143 + * elif c_val == ParamKeyType.PERSISTENT: + * return __pyx_enum.PERSISTENT + * elif c_val == ParamKeyType.CLEAR_ON_MANAGER_START: # <<<<<<<<<<<<<< + * return __pyx_enum.CLEAR_ON_MANAGER_START + * elif c_val == ParamKeyType.CLEAR_ON_ONROAD_TRANSITION: + */ + } + + /* "EnumTypeToPy":145 + * elif c_val == ParamKeyType.CLEAR_ON_MANAGER_START: + * return __pyx_enum.CLEAR_ON_MANAGER_START + * elif c_val == ParamKeyType.CLEAR_ON_ONROAD_TRANSITION: # <<<<<<<<<<<<<< + * return __pyx_enum.CLEAR_ON_ONROAD_TRANSITION + * elif c_val == ParamKeyType.CLEAR_ON_OFFROAD_TRANSITION: + */ + __pyx_t_2 = (__pyx_v_c_val == CLEAR_ON_ONROAD_TRANSITION); + if (__pyx_t_2) { + + /* "EnumTypeToPy":146 + * return __pyx_enum.CLEAR_ON_MANAGER_START + * elif c_val == ParamKeyType.CLEAR_ON_ONROAD_TRANSITION: + * return __pyx_enum.CLEAR_ON_ONROAD_TRANSITION # <<<<<<<<<<<<<< + * elif c_val == ParamKeyType.CLEAR_ON_OFFROAD_TRANSITION: + * return __pyx_enum.CLEAR_ON_OFFROAD_TRANSITION + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v___pyx_enum, __pyx_n_s_CLEAR_ON_ONROAD_TRANSITION); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 146, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "EnumTypeToPy":145 + * elif c_val == ParamKeyType.CLEAR_ON_MANAGER_START: + * return __pyx_enum.CLEAR_ON_MANAGER_START + * elif c_val == ParamKeyType.CLEAR_ON_ONROAD_TRANSITION: # <<<<<<<<<<<<<< + * return __pyx_enum.CLEAR_ON_ONROAD_TRANSITION + * elif c_val == ParamKeyType.CLEAR_ON_OFFROAD_TRANSITION: + */ + } + + /* "EnumTypeToPy":147 + * elif c_val == ParamKeyType.CLEAR_ON_ONROAD_TRANSITION: + * return __pyx_enum.CLEAR_ON_ONROAD_TRANSITION + * elif c_val == ParamKeyType.CLEAR_ON_OFFROAD_TRANSITION: # <<<<<<<<<<<<<< + * return __pyx_enum.CLEAR_ON_OFFROAD_TRANSITION + * elif c_val == ParamKeyType.DEVELOPMENT_ONLY: + */ + __pyx_t_2 = (__pyx_v_c_val == CLEAR_ON_OFFROAD_TRANSITION); + if (__pyx_t_2) { + + /* "EnumTypeToPy":148 + * return __pyx_enum.CLEAR_ON_ONROAD_TRANSITION + * elif c_val == ParamKeyType.CLEAR_ON_OFFROAD_TRANSITION: + * return __pyx_enum.CLEAR_ON_OFFROAD_TRANSITION # <<<<<<<<<<<<<< + * elif c_val == ParamKeyType.DEVELOPMENT_ONLY: + * return __pyx_enum.DEVELOPMENT_ONLY + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v___pyx_enum, __pyx_n_s_CLEAR_ON_OFFROAD_TRANSITION); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 148, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "EnumTypeToPy":147 + * elif c_val == ParamKeyType.CLEAR_ON_ONROAD_TRANSITION: + * return __pyx_enum.CLEAR_ON_ONROAD_TRANSITION + * elif c_val == ParamKeyType.CLEAR_ON_OFFROAD_TRANSITION: # <<<<<<<<<<<<<< + * return __pyx_enum.CLEAR_ON_OFFROAD_TRANSITION + * elif c_val == ParamKeyType.DEVELOPMENT_ONLY: + */ + } + + /* "EnumTypeToPy":149 + * elif c_val == ParamKeyType.CLEAR_ON_OFFROAD_TRANSITION: + * return __pyx_enum.CLEAR_ON_OFFROAD_TRANSITION + * elif c_val == ParamKeyType.DEVELOPMENT_ONLY: # <<<<<<<<<<<<<< + * return __pyx_enum.DEVELOPMENT_ONLY + * elif c_val == ParamKeyType.ALL: + */ + __pyx_t_2 = (__pyx_v_c_val == DEVELOPMENT_ONLY); + if (__pyx_t_2) { + + /* "EnumTypeToPy":150 + * return __pyx_enum.CLEAR_ON_OFFROAD_TRANSITION + * elif c_val == ParamKeyType.DEVELOPMENT_ONLY: + * return __pyx_enum.DEVELOPMENT_ONLY # <<<<<<<<<<<<<< + * elif c_val == ParamKeyType.ALL: + * return __pyx_enum.ALL + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v___pyx_enum, __pyx_n_s_DEVELOPMENT_ONLY); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 150, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "EnumTypeToPy":149 + * elif c_val == ParamKeyType.CLEAR_ON_OFFROAD_TRANSITION: + * return __pyx_enum.CLEAR_ON_OFFROAD_TRANSITION + * elif c_val == ParamKeyType.DEVELOPMENT_ONLY: # <<<<<<<<<<<<<< + * return __pyx_enum.DEVELOPMENT_ONLY + * elif c_val == ParamKeyType.ALL: + */ + } + + /* "EnumTypeToPy":151 + * elif c_val == ParamKeyType.DEVELOPMENT_ONLY: + * return __pyx_enum.DEVELOPMENT_ONLY + * elif c_val == ParamKeyType.ALL: # <<<<<<<<<<<<<< + * return __pyx_enum.ALL + * else: + */ + __pyx_t_2 = (__pyx_v_c_val == ALL); + if (__pyx_t_2) { + + /* "EnumTypeToPy":152 + * return __pyx_enum.DEVELOPMENT_ONLY + * elif c_val == ParamKeyType.ALL: + * return __pyx_enum.ALL # <<<<<<<<<<<<<< + * else: + * underlying_c_val = c_val + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v___pyx_enum, __pyx_n_s_ALL); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 152, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "EnumTypeToPy":151 + * elif c_val == ParamKeyType.DEVELOPMENT_ONLY: + * return __pyx_enum.DEVELOPMENT_ONLY + * elif c_val == ParamKeyType.ALL: # <<<<<<<<<<<<<< + * return __pyx_enum.ALL + * else: + */ + } + + /* "EnumTypeToPy":154 + * return __pyx_enum.ALL + * else: + * underlying_c_val = c_val # <<<<<<<<<<<<<< + * return __pyx_enum(underlying_c_val) + * + */ + /*else*/ { + __pyx_v_underlying_c_val = ((int)__pyx_v_c_val); + + /* "EnumTypeToPy":155 + * else: + * underlying_c_val = c_val + * return __pyx_enum(underlying_c_val) # <<<<<<<<<<<<<< + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_3 = __Pyx_PyInt_From_int(__pyx_v_underlying_c_val); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 155, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_v___pyx_enum); + __pyx_t_4 = __pyx_v___pyx_enum; __pyx_t_5 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (unlikely(PyMethod_Check(__pyx_t_4))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_4); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_4); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_4, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_5, __pyx_t_3}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_6, 1+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 155, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + } + + /* "EnumTypeToPy":132 + * + * @cname("__Pyx_Enum_enum__space_ParamKeyType_to_py") + * cdef __Pyx_Enum_enum__space_ParamKeyType_to_py(ParamKeyType c_val): # <<<<<<<<<<<<<< + * cdef object __pyx_enum + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("EnumTypeToPy.__Pyx_Enum_enum__space_ParamKeyType_to_py", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v___pyx_enum); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.from_py":13 + * + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: # <<<<<<<<<<<<<< + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + */ + +static std::string __pyx_convert_string_from_py_std__in_string(PyObject *__pyx_v_o) { + Py_ssize_t __pyx_v_length; + char const *__pyx_v_data; + std::string __pyx_r; + char const *__pyx_t_1; + std::string __pyx_t_2; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + + /* "string.from_py":14 + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: + * cdef Py_ssize_t length = 0 # <<<<<<<<<<<<<< + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + * return string(data, length) + */ + __pyx_v_length = 0; + + /* "string.from_py":15 + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) # <<<<<<<<<<<<<< + * return string(data, length) + * + */ + __pyx_t_1 = __Pyx_PyObject_AsStringAndSize(__pyx_v_o, (&__pyx_v_length)); if (unlikely(__pyx_t_1 == ((char const *)NULL))) __PYX_ERR(1, 15, __pyx_L1_error) + __pyx_v_data = __pyx_t_1; + + /* "string.from_py":16 + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + * return string(data, length) # <<<<<<<<<<<<<< + * + * + */ + try { + __pyx_t_2 = std::string(__pyx_v_data, __pyx_v_length); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(1, 16, __pyx_L1_error) + } + __pyx_r = __pyx_t_2; + goto __pyx_L0; + + /* "string.from_py":13 + * + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: # <<<<<<<<<<<<<< + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("string.from_py.__pyx_convert_string_from_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_pretend_to_initialize(&__pyx_r); + __pyx_L0:; + return __pyx_r; +} + +/* "string.to_py":31 + * + * @cname("__pyx_convert_PyObject_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyObject_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyObject_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyObject_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyObject_string_to_py_std__in_string", 1); + + /* "string.to_py":32 + * @cname("__pyx_convert_PyObject_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyObject_string_to_py_std__in_string(const string& s): + * return __Pyx_PyObject_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * cdef extern from *: + * cdef object __Pyx_PyUnicode_FromStringAndSize(const char*, size_t) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 32, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":31 + * + * @cname("__pyx_convert_PyObject_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyObject_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyObject_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyObject_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":37 + * + * @cname("__pyx_convert_PyUnicode_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyUnicode_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyUnicode_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyUnicode_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyUnicode_string_to_py_std__in_string", 1); + + /* "string.to_py":38 + * @cname("__pyx_convert_PyUnicode_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyUnicode_string_to_py_std__in_string(const string& s): + * return __Pyx_PyUnicode_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * cdef extern from *: + * cdef object __Pyx_PyStr_FromStringAndSize(const char*, size_t) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyUnicode_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 38, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":37 + * + * @cname("__pyx_convert_PyUnicode_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyUnicode_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyUnicode_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyUnicode_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":43 + * + * @cname("__pyx_convert_PyStr_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyStr_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyStr_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyStr_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyStr_string_to_py_std__in_string", 1); + + /* "string.to_py":44 + * @cname("__pyx_convert_PyStr_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyStr_string_to_py_std__in_string(const string& s): + * return __Pyx_PyStr_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * cdef extern from *: + * cdef object __Pyx_PyBytes_FromStringAndSize(const char*, size_t) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyStr_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 44, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":43 + * + * @cname("__pyx_convert_PyStr_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyStr_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyStr_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyStr_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":49 + * + * @cname("__pyx_convert_PyBytes_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyBytes_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyBytes_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyBytes_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyBytes_string_to_py_std__in_string", 1); + + /* "string.to_py":50 + * @cname("__pyx_convert_PyBytes_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyBytes_string_to_py_std__in_string(const string& s): + * return __Pyx_PyBytes_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * cdef extern from *: + * cdef object __Pyx_PyByteArray_FromStringAndSize(const char*, size_t) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyBytes_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 50, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":49 + * + * @cname("__pyx_convert_PyBytes_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyBytes_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyBytes_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyBytes_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":55 + * + * @cname("__pyx_convert_PyByteArray_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyByteArray_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyByteArray_FromStringAndSize(s.data(), s.size()) + * + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyByteArray_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyByteArray_string_to_py_std__in_string", 1); + + /* "string.to_py":56 + * @cname("__pyx_convert_PyByteArray_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyByteArray_string_to_py_std__in_string(const string& s): + * return __Pyx_PyByteArray_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyByteArray_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 56, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":55 + * + * @cname("__pyx_convert_PyByteArray_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyByteArray_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyByteArray_FromStringAndSize(s.data(), s.size()) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyByteArray_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "vector.to_py":66 + * + * @cname("__pyx_convert_vector_to_py_std_3a__3a_string") + * cdef object __pyx_convert_vector_to_py_std_3a__3a_string(const vector[X]& v): # <<<<<<<<<<<<<< + * if v.size() > PY_SSIZE_T_MAX: + * raise MemoryError() + */ + +static PyObject *__pyx_convert_vector_to_py_std_3a__3a_string(std::vector const &__pyx_v_v) { + Py_ssize_t __pyx_v_v_size_signed; + PyObject *__pyx_v_o = NULL; + Py_ssize_t __pyx_v_i; + PyObject *__pyx_v_item = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + Py_ssize_t __pyx_t_3; + Py_ssize_t __pyx_t_4; + Py_ssize_t __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_vector_to_py_std_3a__3a_string", 1); + + /* "vector.to_py":67 + * @cname("__pyx_convert_vector_to_py_std_3a__3a_string") + * cdef object __pyx_convert_vector_to_py_std_3a__3a_string(const vector[X]& v): + * if v.size() > PY_SSIZE_T_MAX: # <<<<<<<<<<<<<< + * raise MemoryError() + * v_size_signed = v.size() + */ + __pyx_t_1 = (__pyx_v_v.size() > ((size_t)PY_SSIZE_T_MAX)); + if (unlikely(__pyx_t_1)) { + + /* "vector.to_py":68 + * cdef object __pyx_convert_vector_to_py_std_3a__3a_string(const vector[X]& v): + * if v.size() > PY_SSIZE_T_MAX: + * raise MemoryError() # <<<<<<<<<<<<<< + * v_size_signed = v.size() + * + */ + PyErr_NoMemory(); __PYX_ERR(1, 68, __pyx_L1_error) + + /* "vector.to_py":67 + * @cname("__pyx_convert_vector_to_py_std_3a__3a_string") + * cdef object __pyx_convert_vector_to_py_std_3a__3a_string(const vector[X]& v): + * if v.size() > PY_SSIZE_T_MAX: # <<<<<<<<<<<<<< + * raise MemoryError() + * v_size_signed = v.size() + */ + } + + /* "vector.to_py":69 + * if v.size() > PY_SSIZE_T_MAX: + * raise MemoryError() + * v_size_signed = v.size() # <<<<<<<<<<<<<< + * + * o = PyList_New(v_size_signed) + */ + __pyx_v_v_size_signed = ((Py_ssize_t)__pyx_v_v.size()); + + /* "vector.to_py":71 + * v_size_signed = v.size() + * + * o = PyList_New(v_size_signed) # <<<<<<<<<<<<<< + * + * cdef Py_ssize_t i + */ + __pyx_t_2 = PyList_New(__pyx_v_v_size_signed); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 71, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_v_o = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; + + /* "vector.to_py":76 + * cdef object item + * + * for i in range(v_size_signed): # <<<<<<<<<<<<<< + * item = v[i] + * Py_INCREF(item) + */ + __pyx_t_3 = __pyx_v_v_size_signed; + __pyx_t_4 = __pyx_t_3; + for (__pyx_t_5 = 0; __pyx_t_5 < __pyx_t_4; __pyx_t_5+=1) { + __pyx_v_i = __pyx_t_5; + + /* "vector.to_py":77 + * + * for i in range(v_size_signed): + * item = v[i] # <<<<<<<<<<<<<< + * Py_INCREF(item) + * PyList_SET_ITEM(o, i, item) + */ + __pyx_t_2 = __pyx_convert_PyBytes_string_to_py_std__in_string((__pyx_v_v[__pyx_v_i])); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 77, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_XDECREF_SET(__pyx_v_item, __pyx_t_2); + __pyx_t_2 = 0; + + /* "vector.to_py":78 + * for i in range(v_size_signed): + * item = v[i] + * Py_INCREF(item) # <<<<<<<<<<<<<< + * PyList_SET_ITEM(o, i, item) + * + */ + Py_INCREF(__pyx_v_item); + + /* "vector.to_py":79 + * item = v[i] + * Py_INCREF(item) + * PyList_SET_ITEM(o, i, item) # <<<<<<<<<<<<<< + * + * return o + */ + PyList_SET_ITEM(__pyx_v_o, __pyx_v_i, __pyx_v_item); + } + + /* "vector.to_py":81 + * PyList_SET_ITEM(o, i, item) + * + * return o # <<<<<<<<<<<<<< + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_o); + __pyx_r = __pyx_v_o; + goto __pyx_L0; + + /* "vector.to_py":66 + * + * @cname("__pyx_convert_vector_to_py_std_3a__3a_string") + * cdef object __pyx_convert_vector_to_py_std_3a__3a_string(const vector[X]& v): # <<<<<<<<<<<<<< + * if v.size() > PY_SSIZE_T_MAX: + * raise MemoryError() + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("vector.to_py.__pyx_convert_vector_to_py_std_3a__3a_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_o); + __Pyx_XDECREF(__pyx_v_item); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "EnumBase":17 + * @cython.internal + * cdef class __Pyx_EnumMeta(type): + * def __init__(cls, name, parents, dct): # <<<<<<<<<<<<<< + * type.__init__(cls, name, parents, dct) + * cls.__members__ = __Pyx_OrderedDict() + */ + +/* Python wrapper */ +static int __pyx_pw_8EnumBase_14__Pyx_EnumMeta_1__init__(PyObject *__pyx_v_cls, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_pw_8EnumBase_14__Pyx_EnumMeta_1__init__(PyObject *__pyx_v_cls, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_name = 0; + PyObject *__pyx_v_parents = 0; + PyObject *__pyx_v_dct = 0; + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__init__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_name,&__pyx_n_s_parents,&__pyx_n_s_dct,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_name)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 17, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_parents)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 17, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__init__", 1, 3, 3, 1); __PYX_ERR(1, 17, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_dct)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 17, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__init__", 1, 3, 3, 2); __PYX_ERR(1, 17, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__init__") < 0)) __PYX_ERR(1, 17, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + } + __pyx_v_name = values[0]; + __pyx_v_parents = values[1]; + __pyx_v_dct = values[2]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__init__", 1, 3, 3, __pyx_nargs); __PYX_ERR(1, 17, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("EnumBase.__Pyx_EnumMeta.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_8EnumBase_14__Pyx_EnumMeta___init__(((struct __pyx_obj___Pyx_EnumMeta *)__pyx_v_cls), __pyx_v_name, __pyx_v_parents, __pyx_v_dct); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_8EnumBase_14__Pyx_EnumMeta___init__(struct __pyx_obj___Pyx_EnumMeta *__pyx_v_cls, PyObject *__pyx_v_name, PyObject *__pyx_v_parents, PyObject *__pyx_v_dct) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__init__", 1); + + /* "EnumBase":18 + * cdef class __Pyx_EnumMeta(type): + * def __init__(cls, name, parents, dct): + * type.__init__(cls, name, parents, dct) # <<<<<<<<<<<<<< + * cls.__members__ = __Pyx_OrderedDict() + * def __iter__(cls): + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(((PyObject *)(&PyType_Type)), __pyx_n_s_init); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 18, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[5] = {__pyx_t_3, ((PyObject *)__pyx_v_cls), __pyx_v_name, __pyx_v_parents, __pyx_v_dct}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 4+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 18, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "EnumBase":19 + * def __init__(cls, name, parents, dct): + * type.__init__(cls, name, parents, dct) + * cls.__members__ = __Pyx_OrderedDict() # <<<<<<<<<<<<<< + * def __iter__(cls): + * return iter(cls.__members__.values()) + */ + __Pyx_INCREF(__Pyx_OrderedDict); + __pyx_t_2 = __Pyx_OrderedDict; __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (unlikely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, NULL}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 0+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 19, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + if (__Pyx_PyObject_SetAttrStr(((PyObject *)__pyx_v_cls), __pyx_n_s_members, __pyx_t_1) < 0) __PYX_ERR(1, 19, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "EnumBase":17 + * @cython.internal + * cdef class __Pyx_EnumMeta(type): + * def __init__(cls, name, parents, dct): # <<<<<<<<<<<<<< + * type.__init__(cls, name, parents, dct) + * cls.__members__ = __Pyx_OrderedDict() + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("EnumBase.__Pyx_EnumMeta.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "EnumBase":20 + * type.__init__(cls, name, parents, dct) + * cls.__members__ = __Pyx_OrderedDict() + * def __iter__(cls): # <<<<<<<<<<<<<< + * return iter(cls.__members__.values()) + * def __getitem__(cls, name): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumMeta_3__iter__(PyObject *__pyx_v_cls); /*proto*/ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumMeta_3__iter__(PyObject *__pyx_v_cls) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__iter__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_8EnumBase_14__Pyx_EnumMeta_2__iter__(((struct __pyx_obj___Pyx_EnumMeta *)__pyx_v_cls)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumMeta_2__iter__(struct __pyx_obj___Pyx_EnumMeta *__pyx_v_cls) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__iter__", 1); + + /* "EnumBase":21 + * cls.__members__ = __Pyx_OrderedDict() + * def __iter__(cls): + * return iter(cls.__members__.values()) # <<<<<<<<<<<<<< + * def __getitem__(cls, name): + * return cls.__members__[name] + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_cls), __pyx_n_s_members); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 21, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_values); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 21, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_2 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_2)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_2); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_2, NULL}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_4, 0+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 21, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_t_3 = PyObject_GetIter(__pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 21, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_3; + __pyx_t_3 = 0; + goto __pyx_L0; + + /* "EnumBase":20 + * type.__init__(cls, name, parents, dct) + * cls.__members__ = __Pyx_OrderedDict() + * def __iter__(cls): # <<<<<<<<<<<<<< + * return iter(cls.__members__.values()) + * def __getitem__(cls, name): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("EnumBase.__Pyx_EnumMeta.__iter__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "EnumBase":22 + * def __iter__(cls): + * return iter(cls.__members__.values()) + * def __getitem__(cls, name): # <<<<<<<<<<<<<< + * return cls.__members__[name] + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumMeta_5__getitem__(PyObject *__pyx_v_cls, PyObject *__pyx_v_name); /*proto*/ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumMeta_5__getitem__(PyObject *__pyx_v_cls, PyObject *__pyx_v_name) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getitem__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_8EnumBase_14__Pyx_EnumMeta_4__getitem__(((struct __pyx_obj___Pyx_EnumMeta *)__pyx_v_cls), ((PyObject *)__pyx_v_name)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumMeta_4__getitem__(struct __pyx_obj___Pyx_EnumMeta *__pyx_v_cls, PyObject *__pyx_v_name) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__getitem__", 1); + + /* "EnumBase":23 + * return iter(cls.__members__.values()) + * def __getitem__(cls, name): + * return cls.__members__[name] # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_cls), __pyx_n_s_members); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 23, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_t_1, __pyx_v_name); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 23, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "EnumBase":22 + * def __iter__(cls): + * return iter(cls.__members__.values()) + * def __getitem__(cls, name): # <<<<<<<<<<<<<< + * return cls.__members__[name] + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("EnumBase.__Pyx_EnumMeta.__getitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * cdef tuple state + * cdef object _dict + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumMeta_7__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_8EnumBase_14__Pyx_EnumMeta_7__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_8EnumBase_14__Pyx_EnumMeta_7__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumMeta_7__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_8EnumBase_14__Pyx_EnumMeta_6__reduce_cython__(((struct __pyx_obj___Pyx_EnumMeta *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumMeta_6__reduce_cython__(struct __pyx_obj___Pyx_EnumMeta *__pyx_v_self) { + PyObject *__pyx_v_state = 0; + PyObject *__pyx_v__dict = 0; + int __pyx_v_use_setstate; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":5 + * cdef object _dict + * cdef bint use_setstate + * state = () # <<<<<<<<<<<<<< + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: + */ + __Pyx_INCREF(__pyx_empty_tuple); + __pyx_v_state = __pyx_empty_tuple; + + /* "(tree fragment)":6 + * cdef bint use_setstate + * state = () + * _dict = getattr(self, '__dict__', None) # <<<<<<<<<<<<<< + * if _dict is not None: + * state += (_dict,) + */ + __pyx_t_1 = __Pyx_GetAttr3(((PyObject *)__pyx_v_self), __pyx_n_s_dict, Py_None); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v__dict = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":7 + * state = () + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: # <<<<<<<<<<<<<< + * state += (_dict,) + * use_setstate = True + */ + __pyx_t_2 = (__pyx_v__dict != Py_None); + if (__pyx_t_2) { + + /* "(tree fragment)":8 + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: + * state += (_dict,) # <<<<<<<<<<<<<< + * use_setstate = True + * else: + */ + __pyx_t_1 = PyTuple_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 8, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v__dict); + __Pyx_GIVEREF(__pyx_v__dict); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v__dict)) __PYX_ERR(1, 8, __pyx_L1_error); + __pyx_t_3 = PyNumber_InPlaceAdd(__pyx_v_state, __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 8, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF_SET(__pyx_v_state, ((PyObject*)__pyx_t_3)); + __pyx_t_3 = 0; + + /* "(tree fragment)":9 + * if _dict is not None: + * state += (_dict,) + * use_setstate = True # <<<<<<<<<<<<<< + * else: + * use_setstate = False + */ + __pyx_v_use_setstate = 1; + + /* "(tree fragment)":7 + * state = () + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: # <<<<<<<<<<<<<< + * state += (_dict,) + * use_setstate = True + */ + goto __pyx_L3; + } + + /* "(tree fragment)":11 + * use_setstate = True + * else: + * use_setstate = False # <<<<<<<<<<<<<< + * if use_setstate: + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, None), state + */ + /*else*/ { + __pyx_v_use_setstate = 0; + } + __pyx_L3:; + + /* "(tree fragment)":12 + * else: + * use_setstate = False + * if use_setstate: # <<<<<<<<<<<<<< + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, None), state + * else: + */ + if (__pyx_v_use_setstate) { + + /* "(tree fragment)":13 + * use_setstate = False + * if use_setstate: + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, None), state # <<<<<<<<<<<<<< + * else: + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, state) + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_pyx_unpickle___Pyx_EnumMeta); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = PyTuple_New(3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_GIVEREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, ((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self))))) __PYX_ERR(1, 13, __pyx_L1_error); + __Pyx_INCREF(__pyx_int_238750788); + __Pyx_GIVEREF(__pyx_int_238750788); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_int_238750788)) __PYX_ERR(1, 13, __pyx_L1_error); + __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(Py_None); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 2, Py_None)) __PYX_ERR(1, 13, __pyx_L1_error); + __pyx_t_4 = PyTuple_New(3); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_3)) __PYX_ERR(1, 13, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_t_1)) __PYX_ERR(1, 13, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_state); + __Pyx_GIVEREF(__pyx_v_state); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 2, __pyx_v_state)) __PYX_ERR(1, 13, __pyx_L1_error); + __pyx_t_3 = 0; + __pyx_t_1 = 0; + __pyx_r = __pyx_t_4; + __pyx_t_4 = 0; + goto __pyx_L0; + + /* "(tree fragment)":12 + * else: + * use_setstate = False + * if use_setstate: # <<<<<<<<<<<<<< + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, None), state + * else: + */ + } + + /* "(tree fragment)":15 + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, None), state + * else: + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, state) # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * __pyx_unpickle___Pyx_EnumMeta__set_state(self, __pyx_state) + */ + /*else*/ { + __Pyx_XDECREF(__pyx_r); + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_pyx_unpickle___Pyx_EnumMeta); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_1 = PyTuple_New(3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_GIVEREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, ((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self))))) __PYX_ERR(1, 15, __pyx_L1_error); + __Pyx_INCREF(__pyx_int_238750788); + __Pyx_GIVEREF(__pyx_int_238750788); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_int_238750788)) __PYX_ERR(1, 15, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_state); + __Pyx_GIVEREF(__pyx_v_state); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_v_state)) __PYX_ERR(1, 15, __pyx_L1_error); + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_4); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_4)) __PYX_ERR(1, 15, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1)) __PYX_ERR(1, 15, __pyx_L1_error); + __pyx_t_4 = 0; + __pyx_t_1 = 0; + __pyx_r = __pyx_t_3; + __pyx_t_3 = 0; + goto __pyx_L0; + } + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * cdef tuple state + * cdef object _dict + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("EnumBase.__Pyx_EnumMeta.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_state); + __Pyx_XDECREF(__pyx_v__dict); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":16 + * else: + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, state) + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * __pyx_unpickle___Pyx_EnumMeta__set_state(self, __pyx_state) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumMeta_9__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_8EnumBase_14__Pyx_EnumMeta_9__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_8EnumBase_14__Pyx_EnumMeta_9__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumMeta_9__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 16, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 16, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 16, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("EnumBase.__Pyx_EnumMeta.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_8EnumBase_14__Pyx_EnumMeta_8__setstate_cython__(((struct __pyx_obj___Pyx_EnumMeta *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumMeta_8__setstate_cython__(struct __pyx_obj___Pyx_EnumMeta *__pyx_v_self, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":17 + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, state) + * def __setstate_cython__(self, __pyx_state): + * __pyx_unpickle___Pyx_EnumMeta__set_state(self, __pyx_state) # <<<<<<<<<<<<<< + */ + if (!(likely(PyTuple_CheckExact(__pyx_v___pyx_state))||((__pyx_v___pyx_state) == Py_None) || __Pyx_RaiseUnexpectedTypeError("tuple", __pyx_v___pyx_state))) __PYX_ERR(1, 17, __pyx_L1_error) + __pyx_t_1 = __pyx_unpickle___Pyx_EnumMeta__set_state(__pyx_v_self, ((PyObject*)__pyx_v___pyx_state)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 17, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":16 + * else: + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, state) + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * __pyx_unpickle___Pyx_EnumMeta__set_state(self, __pyx_state) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("EnumBase.__Pyx_EnumMeta.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "EnumBase":28 + * cdef object __Pyx_EnumBase + * class __Pyx_EnumBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): # <<<<<<<<<<<<<< + * for v in cls: + * if v == value: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumBase_1__new__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_8EnumBase_14__Pyx_EnumBase_1__new__ = {"__new__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_8EnumBase_14__Pyx_EnumBase_1__new__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumBase_1__new__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_cls = 0; + PyObject *__pyx_v_value = 0; + PyObject *__pyx_v_name = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__new__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_cls,&__pyx_n_s_value,&__pyx_n_s_name,0}; + values[2] = __Pyx_Arg_NewRef_FASTCALL(((PyObject *)Py_None)); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_cls)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 28, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_value)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 28, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__new__", 0, 2, 3, 1); __PYX_ERR(1, 28, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_name); + if (value) { values[2] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 28, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__new__") < 0)) __PYX_ERR(1, 28, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_cls = values[0]; + __pyx_v_value = values[1]; + __pyx_v_name = values[2]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__new__", 0, 2, 3, __pyx_nargs); __PYX_ERR(1, 28, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("EnumBase.__Pyx_EnumBase.__new__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_8EnumBase_14__Pyx_EnumBase___new__(__pyx_self, __pyx_v_cls, __pyx_v_value, __pyx_v_name); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumBase___new__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_cls, PyObject *__pyx_v_value, PyObject *__pyx_v_name) { + PyObject *__pyx_v_v = NULL; + PyObject *__pyx_v_res = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + Py_ssize_t __pyx_t_2; + PyObject *(*__pyx_t_3)(PyObject *); + PyObject *__pyx_t_4 = NULL; + int __pyx_t_5; + PyObject *__pyx_t_6 = NULL; + int __pyx_t_7; + int __pyx_t_8; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__new__", 1); + + /* "EnumBase":29 + * class __Pyx_EnumBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): + * for v in cls: # <<<<<<<<<<<<<< + * if v == value: + * return v + */ + if (likely(PyList_CheckExact(__pyx_v_cls)) || PyTuple_CheckExact(__pyx_v_cls)) { + __pyx_t_1 = __pyx_v_cls; __Pyx_INCREF(__pyx_t_1); + __pyx_t_2 = 0; + __pyx_t_3 = NULL; + } else { + __pyx_t_2 = -1; __pyx_t_1 = PyObject_GetIter(__pyx_v_cls); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 29, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 29, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_3)) { + if (likely(PyList_CheckExact(__pyx_t_1))) { + { + Py_ssize_t __pyx_temp = __Pyx_PyList_GET_SIZE(__pyx_t_1); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 29, __pyx_L1_error) + #endif + if (__pyx_t_2 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyList_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(1, 29, __pyx_L1_error) + #else + __pyx_t_4 = __Pyx_PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 29, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } else { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_1); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 29, __pyx_L1_error) + #endif + if (__pyx_t_2 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyTuple_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(1, 29, __pyx_L1_error) + #else + __pyx_t_4 = __Pyx_PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 29, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } + } else { + __pyx_t_4 = __pyx_t_3(__pyx_t_1); + if (unlikely(!__pyx_t_4)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(1, 29, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_4); + } + __Pyx_XDECREF_SET(__pyx_v_v, __pyx_t_4); + __pyx_t_4 = 0; + + /* "EnumBase":30 + * def __new__(cls, value, name=None): + * for v in cls: + * if v == value: # <<<<<<<<<<<<<< + * return v + * if name is None: + */ + __pyx_t_4 = PyObject_RichCompare(__pyx_v_v, __pyx_v_value, Py_EQ); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 30, __pyx_L1_error) + __pyx_t_5 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_5 < 0))) __PYX_ERR(1, 30, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (__pyx_t_5) { + + /* "EnumBase":31 + * for v in cls: + * if v == value: + * return v # <<<<<<<<<<<<<< + * if name is None: + * raise ValueError("Unknown enum value: '%s'" % value) + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_v); + __pyx_r = __pyx_v_v; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + goto __pyx_L0; + + /* "EnumBase":30 + * def __new__(cls, value, name=None): + * for v in cls: + * if v == value: # <<<<<<<<<<<<<< + * return v + * if name is None: + */ + } + + /* "EnumBase":29 + * class __Pyx_EnumBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): + * for v in cls: # <<<<<<<<<<<<<< + * if v == value: + * return v + */ + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "EnumBase":32 + * if v == value: + * return v + * if name is None: # <<<<<<<<<<<<<< + * raise ValueError("Unknown enum value: '%s'" % value) + * res = int.__new__(cls, value) + */ + __pyx_t_5 = (__pyx_v_name == Py_None); + if (unlikely(__pyx_t_5)) { + + /* "EnumBase":33 + * return v + * if name is None: + * raise ValueError("Unknown enum value: '%s'" % value) # <<<<<<<<<<<<<< + * res = int.__new__(cls, value) + * res.name = name + */ + __pyx_t_1 = __Pyx_PyString_FormatSafe(__pyx_kp_s_Unknown_enum_value_s, __pyx_v_value); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 33, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_4 = __Pyx_PyObject_CallOneArg(__pyx_builtin_ValueError, __pyx_t_1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 33, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_t_4, 0, 0, 0); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __PYX_ERR(1, 33, __pyx_L1_error) + + /* "EnumBase":32 + * if v == value: + * return v + * if name is None: # <<<<<<<<<<<<<< + * raise ValueError("Unknown enum value: '%s'" % value) + * res = int.__new__(cls, value) + */ + } + + /* "EnumBase":34 + * if name is None: + * raise ValueError("Unknown enum value: '%s'" % value) + * res = int.__new__(cls, value) # <<<<<<<<<<<<<< + * res.name = name + * setattr(cls, name, res) + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)(&PyInt_Type)), __pyx_n_s_new); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 34, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_6 = NULL; + __pyx_t_7 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_6 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_6)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_6); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_7 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_6, __pyx_v_cls, __pyx_v_value}; + __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_7, 2+__pyx_t_7); + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 34, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_v_res = __pyx_t_4; + __pyx_t_4 = 0; + + /* "EnumBase":35 + * raise ValueError("Unknown enum value: '%s'" % value) + * res = int.__new__(cls, value) + * res.name = name # <<<<<<<<<<<<<< + * setattr(cls, name, res) + * cls.__members__[name] = res + */ + if (__Pyx_PyObject_SetAttrStr(__pyx_v_res, __pyx_n_s_name, __pyx_v_name) < 0) __PYX_ERR(1, 35, __pyx_L1_error) + + /* "EnumBase":36 + * res = int.__new__(cls, value) + * res.name = name + * setattr(cls, name, res) # <<<<<<<<<<<<<< + * cls.__members__[name] = res + * return res + */ + __pyx_t_8 = PyObject_SetAttr(__pyx_v_cls, __pyx_v_name, __pyx_v_res); if (unlikely(__pyx_t_8 == ((int)-1))) __PYX_ERR(1, 36, __pyx_L1_error) + + /* "EnumBase":37 + * res.name = name + * setattr(cls, name, res) + * cls.__members__[name] = res # <<<<<<<<<<<<<< + * return res + * def __repr__(self): + */ + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_v_cls, __pyx_n_s_members); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 37, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (unlikely((PyObject_SetItem(__pyx_t_4, __pyx_v_name, __pyx_v_res) < 0))) __PYX_ERR(1, 37, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "EnumBase":38 + * setattr(cls, name, res) + * cls.__members__[name] = res + * return res # <<<<<<<<<<<<<< + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_res); + __pyx_r = __pyx_v_res; + goto __pyx_L0; + + /* "EnumBase":28 + * cdef object __Pyx_EnumBase + * class __Pyx_EnumBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): # <<<<<<<<<<<<<< + * for v in cls: + * if v == value: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("EnumBase.__Pyx_EnumBase.__new__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_v); + __Pyx_XDECREF(__pyx_v_res); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "EnumBase":39 + * cls.__members__[name] = res + * return res + * def __repr__(self): # <<<<<<<<<<<<<< + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumBase_3__repr__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_8EnumBase_14__Pyx_EnumBase_3__repr__ = {"__repr__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_8EnumBase_14__Pyx_EnumBase_3__repr__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumBase_3__repr__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_self = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__repr__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_self,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_self)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 39, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__repr__") < 0)) __PYX_ERR(1, 39, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_self = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__repr__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 39, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("EnumBase.__Pyx_EnumBase.__repr__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_8EnumBase_14__Pyx_EnumBase_2__repr__(__pyx_self, __pyx_v_self); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumBase_2__repr__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__repr__", 1); + + /* "EnumBase":40 + * return res + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) # <<<<<<<<<<<<<< + * def __str__(self): + * return "%s.%s" % (self.__class__.__name__, self.name) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_self, __pyx_n_s_class); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_name_2); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_self, __pyx_n_s_name); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_2)) __PYX_ERR(1, 40, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1)) __PYX_ERR(1, 40, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_self); + __Pyx_GIVEREF(__pyx_v_self); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_v_self)) __PYX_ERR(1, 40, __pyx_L1_error); + __pyx_t_2 = 0; + __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_s_s_d, __pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "EnumBase":39 + * cls.__members__[name] = res + * return res + * def __repr__(self): # <<<<<<<<<<<<<< + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("EnumBase.__Pyx_EnumBase.__repr__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "EnumBase":41 + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): # <<<<<<<<<<<<<< + * return "%s.%s" % (self.__class__.__name__, self.name) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumBase_5__str__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_8EnumBase_14__Pyx_EnumBase_5__str__ = {"__str__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_8EnumBase_14__Pyx_EnumBase_5__str__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_8EnumBase_14__Pyx_EnumBase_5__str__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_self = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__str__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_self,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_self)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 41, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__str__") < 0)) __PYX_ERR(1, 41, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_self = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__str__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 41, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("EnumBase.__Pyx_EnumBase.__str__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_8EnumBase_14__Pyx_EnumBase_4__str__(__pyx_self, __pyx_v_self); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_8EnumBase_14__Pyx_EnumBase_4__str__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__str__", 1); + + /* "EnumBase":42 + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): + * return "%s.%s" % (self.__class__.__name__, self.name) # <<<<<<<<<<<<<< + * + * if PY_VERSION_HEX >= 0x03040000: + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_self, __pyx_n_s_class); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 42, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_name_2); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 42, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_self, __pyx_n_s_name); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 42, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 42, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_2)) __PYX_ERR(1, 42, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1)) __PYX_ERR(1, 42, __pyx_L1_error); + __pyx_t_2 = 0; + __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_s_s, __pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 42, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "EnumBase":41 + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): # <<<<<<<<<<<<<< + * return "%s.%s" % (self.__class__.__name__, self.name) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("EnumBase.__Pyx_EnumBase.__str__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "EnumBase":49 + * cdef object __Pyx_FlagBase + * class __Pyx_FlagBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): # <<<<<<<<<<<<<< + * for v in cls: + * if v == value: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_FlagBase_1__new__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_8EnumBase_14__Pyx_FlagBase_1__new__ = {"__new__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_8EnumBase_14__Pyx_FlagBase_1__new__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_8EnumBase_14__Pyx_FlagBase_1__new__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_cls = 0; + PyObject *__pyx_v_value = 0; + PyObject *__pyx_v_name = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__new__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_cls,&__pyx_n_s_value,&__pyx_n_s_name,0}; + values[2] = __Pyx_Arg_NewRef_FASTCALL(((PyObject *)Py_None)); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_cls)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 49, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_value)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 49, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__new__", 0, 2, 3, 1); __PYX_ERR(1, 49, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_name); + if (value) { values[2] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 49, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__new__") < 0)) __PYX_ERR(1, 49, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_cls = values[0]; + __pyx_v_value = values[1]; + __pyx_v_name = values[2]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__new__", 0, 2, 3, __pyx_nargs); __PYX_ERR(1, 49, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("EnumBase.__Pyx_FlagBase.__new__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_8EnumBase_14__Pyx_FlagBase___new__(__pyx_self, __pyx_v_cls, __pyx_v_value, __pyx_v_name); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_8EnumBase_14__Pyx_FlagBase___new__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_cls, PyObject *__pyx_v_value, PyObject *__pyx_v_name) { + PyObject *__pyx_v_v = NULL; + PyObject *__pyx_v_res = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + Py_ssize_t __pyx_t_2; + PyObject *(*__pyx_t_3)(PyObject *); + PyObject *__pyx_t_4 = NULL; + int __pyx_t_5; + PyObject *__pyx_t_6 = NULL; + int __pyx_t_7; + int __pyx_t_8; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__new__", 1); + + /* "EnumBase":50 + * class __Pyx_FlagBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): + * for v in cls: # <<<<<<<<<<<<<< + * if v == value: + * return v + */ + if (likely(PyList_CheckExact(__pyx_v_cls)) || PyTuple_CheckExact(__pyx_v_cls)) { + __pyx_t_1 = __pyx_v_cls; __Pyx_INCREF(__pyx_t_1); + __pyx_t_2 = 0; + __pyx_t_3 = NULL; + } else { + __pyx_t_2 = -1; __pyx_t_1 = PyObject_GetIter(__pyx_v_cls); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 50, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 50, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_3)) { + if (likely(PyList_CheckExact(__pyx_t_1))) { + { + Py_ssize_t __pyx_temp = __Pyx_PyList_GET_SIZE(__pyx_t_1); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 50, __pyx_L1_error) + #endif + if (__pyx_t_2 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyList_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(1, 50, __pyx_L1_error) + #else + __pyx_t_4 = __Pyx_PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 50, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } else { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_1); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 50, __pyx_L1_error) + #endif + if (__pyx_t_2 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyTuple_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(1, 50, __pyx_L1_error) + #else + __pyx_t_4 = __Pyx_PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 50, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } + } else { + __pyx_t_4 = __pyx_t_3(__pyx_t_1); + if (unlikely(!__pyx_t_4)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(1, 50, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_4); + } + __Pyx_XDECREF_SET(__pyx_v_v, __pyx_t_4); + __pyx_t_4 = 0; + + /* "EnumBase":51 + * def __new__(cls, value, name=None): + * for v in cls: + * if v == value: # <<<<<<<<<<<<<< + * return v + * res = int.__new__(cls, value) + */ + __pyx_t_4 = PyObject_RichCompare(__pyx_v_v, __pyx_v_value, Py_EQ); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 51, __pyx_L1_error) + __pyx_t_5 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_5 < 0))) __PYX_ERR(1, 51, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (__pyx_t_5) { + + /* "EnumBase":52 + * for v in cls: + * if v == value: + * return v # <<<<<<<<<<<<<< + * res = int.__new__(cls, value) + * if name is None: + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_v); + __pyx_r = __pyx_v_v; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + goto __pyx_L0; + + /* "EnumBase":51 + * def __new__(cls, value, name=None): + * for v in cls: + * if v == value: # <<<<<<<<<<<<<< + * return v + * res = int.__new__(cls, value) + */ + } + + /* "EnumBase":50 + * class __Pyx_FlagBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): + * for v in cls: # <<<<<<<<<<<<<< + * if v == value: + * return v + */ + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "EnumBase":53 + * if v == value: + * return v + * res = int.__new__(cls, value) # <<<<<<<<<<<<<< + * if name is None: + * + */ + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(((PyObject *)(&PyInt_Type)), __pyx_n_s_new); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 53, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_6 = NULL; + __pyx_t_7 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_4))) { + __pyx_t_6 = PyMethod_GET_SELF(__pyx_t_4); + if (likely(__pyx_t_6)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_4); + __Pyx_INCREF(__pyx_t_6); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_4, function); + __pyx_t_7 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_6, __pyx_v_cls, __pyx_v_value}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_7, 2+__pyx_t_7); + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 53, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + __pyx_v_res = __pyx_t_1; + __pyx_t_1 = 0; + + /* "EnumBase":54 + * return v + * res = int.__new__(cls, value) + * if name is None: # <<<<<<<<<<<<<< + * + * res.name = "" + */ + __pyx_t_5 = (__pyx_v_name == Py_None); + if (__pyx_t_5) { + + /* "EnumBase":56 + * if name is None: + * + * res.name = "" # <<<<<<<<<<<<<< + * else: + * res.name = name + */ + if (__Pyx_PyObject_SetAttrStr(__pyx_v_res, __pyx_n_s_name, __pyx_kp_s_) < 0) __PYX_ERR(1, 56, __pyx_L1_error) + + /* "EnumBase":54 + * return v + * res = int.__new__(cls, value) + * if name is None: # <<<<<<<<<<<<<< + * + * res.name = "" + */ + goto __pyx_L7; + } + + /* "EnumBase":58 + * res.name = "" + * else: + * res.name = name # <<<<<<<<<<<<<< + * setattr(cls, name, res) + * cls.__members__[name] = res + */ + /*else*/ { + if (__Pyx_PyObject_SetAttrStr(__pyx_v_res, __pyx_n_s_name, __pyx_v_name) < 0) __PYX_ERR(1, 58, __pyx_L1_error) + + /* "EnumBase":59 + * else: + * res.name = name + * setattr(cls, name, res) # <<<<<<<<<<<<<< + * cls.__members__[name] = res + * return res + */ + __pyx_t_8 = PyObject_SetAttr(__pyx_v_cls, __pyx_v_name, __pyx_v_res); if (unlikely(__pyx_t_8 == ((int)-1))) __PYX_ERR(1, 59, __pyx_L1_error) + + /* "EnumBase":60 + * res.name = name + * setattr(cls, name, res) + * cls.__members__[name] = res # <<<<<<<<<<<<<< + * return res + * def __repr__(self): + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_cls, __pyx_n_s_members); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 60, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyObject_SetItem(__pyx_t_1, __pyx_v_name, __pyx_v_res) < 0))) __PYX_ERR(1, 60, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_L7:; + + /* "EnumBase":61 + * setattr(cls, name, res) + * cls.__members__[name] = res + * return res # <<<<<<<<<<<<<< + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_res); + __pyx_r = __pyx_v_res; + goto __pyx_L0; + + /* "EnumBase":49 + * cdef object __Pyx_FlagBase + * class __Pyx_FlagBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): # <<<<<<<<<<<<<< + * for v in cls: + * if v == value: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("EnumBase.__Pyx_FlagBase.__new__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_v); + __Pyx_XDECREF(__pyx_v_res); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "EnumBase":62 + * cls.__members__[name] = res + * return res + * def __repr__(self): # <<<<<<<<<<<<<< + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_FlagBase_3__repr__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_8EnumBase_14__Pyx_FlagBase_3__repr__ = {"__repr__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_8EnumBase_14__Pyx_FlagBase_3__repr__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_8EnumBase_14__Pyx_FlagBase_3__repr__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_self = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__repr__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_self,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_self)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 62, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__repr__") < 0)) __PYX_ERR(1, 62, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_self = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__repr__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 62, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("EnumBase.__Pyx_FlagBase.__repr__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_8EnumBase_14__Pyx_FlagBase_2__repr__(__pyx_self, __pyx_v_self); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_8EnumBase_14__Pyx_FlagBase_2__repr__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__repr__", 1); + + /* "EnumBase":63 + * return res + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) # <<<<<<<<<<<<<< + * def __str__(self): + * return "%s.%s" % (self.__class__.__name__, self.name) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_self, __pyx_n_s_class); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 63, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_name_2); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 63, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_self, __pyx_n_s_name); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 63, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 63, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_2)) __PYX_ERR(1, 63, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1)) __PYX_ERR(1, 63, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_self); + __Pyx_GIVEREF(__pyx_v_self); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_v_self)) __PYX_ERR(1, 63, __pyx_L1_error); + __pyx_t_2 = 0; + __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_s_s_d, __pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 63, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "EnumBase":62 + * cls.__members__[name] = res + * return res + * def __repr__(self): # <<<<<<<<<<<<<< + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("EnumBase.__Pyx_FlagBase.__repr__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "EnumBase":64 + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): # <<<<<<<<<<<<<< + * return "%s.%s" % (self.__class__.__name__, self.name) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_8EnumBase_14__Pyx_FlagBase_5__str__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_8EnumBase_14__Pyx_FlagBase_5__str__ = {"__str__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_8EnumBase_14__Pyx_FlagBase_5__str__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_8EnumBase_14__Pyx_FlagBase_5__str__(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_self = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__str__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_self,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_self)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 64, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__str__") < 0)) __PYX_ERR(1, 64, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_self = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__str__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 64, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("EnumBase.__Pyx_FlagBase.__str__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_8EnumBase_14__Pyx_FlagBase_4__str__(__pyx_self, __pyx_v_self); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_8EnumBase_14__Pyx_FlagBase_4__str__(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__str__", 1); + + /* "EnumBase":65 + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): + * return "%s.%s" % (self.__class__.__name__, self.name) # <<<<<<<<<<<<<< + * + * if PY_VERSION_HEX >= 0x03060000: + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_self, __pyx_n_s_class); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 65, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_name_2); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 65, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_self, __pyx_n_s_name); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 65, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 65, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_2)) __PYX_ERR(1, 65, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1)) __PYX_ERR(1, 65, __pyx_L1_error); + __pyx_t_2 = 0; + __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_s_s, __pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 65, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "EnumBase":64 + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): # <<<<<<<<<<<<<< + * return "%s.%s" % (self.__class__.__name__, self.name) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("EnumBase.__Pyx_FlagBase.__str__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __pyx_unpickle___Pyx_EnumMeta(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_8EnumBase_1__pyx_unpickle___Pyx_EnumMeta(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_8EnumBase_1__pyx_unpickle___Pyx_EnumMeta = {"__pyx_unpickle___Pyx_EnumMeta", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_8EnumBase_1__pyx_unpickle___Pyx_EnumMeta, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_8EnumBase_1__pyx_unpickle___Pyx_EnumMeta(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v___pyx_type = 0; + long __pyx_v___pyx_checksum; + PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__pyx_unpickle___Pyx_EnumMeta (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_type,&__pyx_n_s_pyx_checksum,&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_type)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_checksum)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle___Pyx_EnumMeta", 1, 3, 3, 1); __PYX_ERR(1, 1, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle___Pyx_EnumMeta", 1, 3, 3, 2); __PYX_ERR(1, 1, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__pyx_unpickle___Pyx_EnumMeta") < 0)) __PYX_ERR(1, 1, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + } + __pyx_v___pyx_type = values[0]; + __pyx_v___pyx_checksum = __Pyx_PyInt_As_long(values[1]); if (unlikely((__pyx_v___pyx_checksum == (long)-1) && PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + __pyx_v___pyx_state = values[2]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle___Pyx_EnumMeta", 1, 3, 3, __pyx_nargs); __PYX_ERR(1, 1, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("EnumBase.__pyx_unpickle___Pyx_EnumMeta", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_8EnumBase___pyx_unpickle___Pyx_EnumMeta(__pyx_self, __pyx_v___pyx_type, __pyx_v___pyx_checksum, __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_8EnumBase___pyx_unpickle___Pyx_EnumMeta(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v___pyx_type, long __pyx_v___pyx_checksum, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_v___pyx_PickleError = 0; + PyObject *__pyx_v___pyx_result = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_unpickle___Pyx_EnumMeta", 1); + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0xe3b0c44, 0xda39a3e, 0xd41d8cd): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0xe3b0c44, 0xda39a3e, 0xd41d8cd) = ())" % __pyx_checksum + */ + __pyx_t_1 = __Pyx_PyInt_From_long(__pyx_v___pyx_checksum); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 4, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = (__Pyx_PySequence_ContainsTF(__pyx_t_1, __pyx_tuple__2, Py_NE)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(1, 4, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (__pyx_t_2) { + + /* "(tree fragment)":5 + * cdef object __pyx_result + * if __pyx_checksum not in (0xe3b0c44, 0xda39a3e, 0xd41d8cd): + * from pickle import PickleError as __pyx_PickleError # <<<<<<<<<<<<<< + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0xe3b0c44, 0xda39a3e, 0xd41d8cd) = ())" % __pyx_checksum + * __pyx_result = __Pyx_EnumMeta.__new__(__pyx_type) + */ + __pyx_t_1 = PyList_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_s_PickleError); + __Pyx_GIVEREF(__pyx_n_s_PickleError); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_s_PickleError)) __PYX_ERR(1, 5, __pyx_L1_error); + __pyx_t_3 = __Pyx_Import(__pyx_n_s_pickle, __pyx_t_1, 0); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_ImportFrom(__pyx_t_3, __pyx_n_s_PickleError); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_t_1); + __pyx_v___pyx_PickleError = __pyx_t_1; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "(tree fragment)":6 + * if __pyx_checksum not in (0xe3b0c44, 0xda39a3e, 0xd41d8cd): + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0xe3b0c44, 0xda39a3e, 0xd41d8cd) = ())" % __pyx_checksum # <<<<<<<<<<<<<< + * __pyx_result = __Pyx_EnumMeta.__new__(__pyx_type) + * if __pyx_state is not None: + */ + __pyx_t_3 = __Pyx_PyInt_From_long(__pyx_v___pyx_checksum); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_Incompatible_checksums_0x_x_vs_0, __pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_v___pyx_PickleError, __pyx_t_1, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(1, 6, __pyx_L1_error) + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0xe3b0c44, 0xda39a3e, 0xd41d8cd): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0xe3b0c44, 0xda39a3e, 0xd41d8cd) = ())" % __pyx_checksum + */ + } + + /* "(tree fragment)":7 + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0xe3b0c44, 0xda39a3e, 0xd41d8cd) = ())" % __pyx_checksum + * __pyx_result = __Pyx_EnumMeta.__new__(__pyx_type) # <<<<<<<<<<<<<< + * if __pyx_state is not None: + * __pyx_unpickle___Pyx_EnumMeta__set_state(<__Pyx_EnumMeta> __pyx_result, __pyx_state) + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_ptype___Pyx_EnumMeta), __pyx_n_s_new); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 7, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = NULL; + __pyx_t_5 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_5 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_4, __pyx_v___pyx_type}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_5, 1+__pyx_t_5); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 7, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_v___pyx_result = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":8 + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0xe3b0c44, 0xda39a3e, 0xd41d8cd) = ())" % __pyx_checksum + * __pyx_result = __Pyx_EnumMeta.__new__(__pyx_type) + * if __pyx_state is not None: # <<<<<<<<<<<<<< + * __pyx_unpickle___Pyx_EnumMeta__set_state(<__Pyx_EnumMeta> __pyx_result, __pyx_state) + * return __pyx_result + */ + __pyx_t_2 = (__pyx_v___pyx_state != Py_None); + if (__pyx_t_2) { + + /* "(tree fragment)":9 + * __pyx_result = __Pyx_EnumMeta.__new__(__pyx_type) + * if __pyx_state is not None: + * __pyx_unpickle___Pyx_EnumMeta__set_state(<__Pyx_EnumMeta> __pyx_result, __pyx_state) # <<<<<<<<<<<<<< + * return __pyx_result + * cdef __pyx_unpickle___Pyx_EnumMeta__set_state(__Pyx_EnumMeta __pyx_result, tuple __pyx_state): + */ + if (!(likely(PyTuple_CheckExact(__pyx_v___pyx_state))||((__pyx_v___pyx_state) == Py_None) || __Pyx_RaiseUnexpectedTypeError("tuple", __pyx_v___pyx_state))) __PYX_ERR(1, 9, __pyx_L1_error) + __pyx_t_1 = __pyx_unpickle___Pyx_EnumMeta__set_state(((struct __pyx_obj___Pyx_EnumMeta *)__pyx_v___pyx_result), ((PyObject*)__pyx_v___pyx_state)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 9, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":8 + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0xe3b0c44, 0xda39a3e, 0xd41d8cd) = ())" % __pyx_checksum + * __pyx_result = __Pyx_EnumMeta.__new__(__pyx_type) + * if __pyx_state is not None: # <<<<<<<<<<<<<< + * __pyx_unpickle___Pyx_EnumMeta__set_state(<__Pyx_EnumMeta> __pyx_result, __pyx_state) + * return __pyx_result + */ + } + + /* "(tree fragment)":10 + * if __pyx_state is not None: + * __pyx_unpickle___Pyx_EnumMeta__set_state(<__Pyx_EnumMeta> __pyx_result, __pyx_state) + * return __pyx_result # <<<<<<<<<<<<<< + * cdef __pyx_unpickle___Pyx_EnumMeta__set_state(__Pyx_EnumMeta __pyx_result, tuple __pyx_state): + * if len(__pyx_state) > 0 and hasattr(__pyx_result, '__dict__'): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v___pyx_result); + __pyx_r = __pyx_v___pyx_result; + goto __pyx_L0; + + /* "(tree fragment)":1 + * def __pyx_unpickle___Pyx_EnumMeta(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("EnumBase.__pyx_unpickle___Pyx_EnumMeta", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v___pyx_PickleError); + __Pyx_XDECREF(__pyx_v___pyx_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":11 + * __pyx_unpickle___Pyx_EnumMeta__set_state(<__Pyx_EnumMeta> __pyx_result, __pyx_state) + * return __pyx_result + * cdef __pyx_unpickle___Pyx_EnumMeta__set_state(__Pyx_EnumMeta __pyx_result, tuple __pyx_state): # <<<<<<<<<<<<<< + * if len(__pyx_state) > 0 and hasattr(__pyx_result, '__dict__'): + * __pyx_result.__dict__.update(__pyx_state[0]) + */ + +static PyObject *__pyx_unpickle___Pyx_EnumMeta__set_state(struct __pyx_obj___Pyx_EnumMeta *__pyx_v___pyx_result, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + Py_ssize_t __pyx_t_2; + int __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + int __pyx_t_8; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_unpickle___Pyx_EnumMeta__set_state", 1); + + /* "(tree fragment)":12 + * return __pyx_result + * cdef __pyx_unpickle___Pyx_EnumMeta__set_state(__Pyx_EnumMeta __pyx_result, tuple __pyx_state): + * if len(__pyx_state) > 0 and hasattr(__pyx_result, '__dict__'): # <<<<<<<<<<<<<< + * __pyx_result.__dict__.update(__pyx_state[0]) + */ + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); + __PYX_ERR(1, 12, __pyx_L1_error) + } + __pyx_t_2 = __Pyx_PyTuple_GET_SIZE(__pyx_v___pyx_state); if (unlikely(__pyx_t_2 == ((Py_ssize_t)-1))) __PYX_ERR(1, 12, __pyx_L1_error) + __pyx_t_3 = (__pyx_t_2 > 0); + if (__pyx_t_3) { + } else { + __pyx_t_1 = __pyx_t_3; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_3 = __Pyx_HasAttr(((PyObject *)__pyx_v___pyx_result), __pyx_n_s_dict); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 12, __pyx_L1_error) + __pyx_t_1 = __pyx_t_3; + __pyx_L4_bool_binop_done:; + if (__pyx_t_1) { + + /* "(tree fragment)":13 + * cdef __pyx_unpickle___Pyx_EnumMeta__set_state(__Pyx_EnumMeta __pyx_result, tuple __pyx_state): + * if len(__pyx_state) > 0 and hasattr(__pyx_result, '__dict__'): + * __pyx_result.__dict__.update(__pyx_state[0]) # <<<<<<<<<<<<<< + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v___pyx_result), __pyx_n_s_dict); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_update); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 13, __pyx_L1_error) + } + __pyx_t_5 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_7 = NULL; + __pyx_t_8 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_6))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_6); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_6); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_6, function); + __pyx_t_8 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_7, __pyx_t_5}; + __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_6, __pyx_callargs+1-__pyx_t_8, 1+__pyx_t_8); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "(tree fragment)":12 + * return __pyx_result + * cdef __pyx_unpickle___Pyx_EnumMeta__set_state(__Pyx_EnumMeta __pyx_result, tuple __pyx_state): + * if len(__pyx_state) > 0 and hasattr(__pyx_result, '__dict__'): # <<<<<<<<<<<<<< + * __pyx_result.__dict__.update(__pyx_state[0]) + */ + } + + /* "(tree fragment)":11 + * __pyx_unpickle___Pyx_EnumMeta__set_state(<__Pyx_EnumMeta> __pyx_result, __pyx_state) + * return __pyx_result + * cdef __pyx_unpickle___Pyx_EnumMeta__set_state(__Pyx_EnumMeta __pyx_result, tuple __pyx_state): # <<<<<<<<<<<<<< + * if len(__pyx_state) > 0 and hasattr(__pyx_result, '__dict__'): + * __pyx_result.__dict__.update(__pyx_state[0]) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("EnumBase.__pyx_unpickle___Pyx_EnumMeta__set_state", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/params_pyx.pyx":37 + * + * + * def ensure_bytes(v): # <<<<<<<<<<<<<< + * return v.encode() if isinstance(v, str) else v + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_10params_pyx_1ensure_bytes(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_10params_pyx_1ensure_bytes = {"ensure_bytes", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_1ensure_bytes, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_10params_pyx_1ensure_bytes(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_v = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("ensure_bytes (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_v,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_v)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 37, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "ensure_bytes") < 0)) __PYX_ERR(0, 37, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_v = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("ensure_bytes", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 37, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("common.params_pyx.ensure_bytes", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_10params_pyx_ensure_bytes(__pyx_self, __pyx_v_v); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_10params_pyx_ensure_bytes(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_v) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("ensure_bytes", 1); + + /* "common/params_pyx.pyx":38 + * + * def ensure_bytes(v): + * return v.encode() if isinstance(v, str) else v # <<<<<<<<<<<<<< + * + * class UnknownKeyName(Exception): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = PyUnicode_Check(__pyx_v_v); + if (__pyx_t_2) { + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_v_v, __pyx_n_s_encode); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 38, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_4))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_4); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_4); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_4, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_5, NULL}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_6, 0+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 38, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + __pyx_t_1 = __pyx_t_3; + __pyx_t_3 = 0; + } else { + __Pyx_INCREF(__pyx_v_v); + __pyx_t_1 = __pyx_v_v; + } + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "common/params_pyx.pyx":37 + * + * + * def ensure_bytes(v): # <<<<<<<<<<<<<< + * return v.encode() if isinstance(v, str) else v + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("common.params_pyx.ensure_bytes", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/params_pyx.pyx":46 + * cdef c_Params* p + * + * def __cinit__(self, d=""): # <<<<<<<<<<<<<< + * cdef string path = d.encode() + * with nogil: + */ + +/* Python wrapper */ +static int __pyx_pw_6common_10params_pyx_6Params_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_pw_6common_10params_pyx_6Params_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_d = 0; + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_d,0}; + values[0] = __Pyx_Arg_NewRef_VARARGS(((PyObject *)__pyx_kp_u_)); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_d); + if (value) { values[0] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 46, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(0, 46, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_d = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 0, 1, __pyx_nargs); __PYX_ERR(0, 46, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("common.params_pyx.Params.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_10params_pyx_6Params___cinit__(((struct __pyx_obj_6common_10params_pyx_Params *)__pyx_v_self), __pyx_v_d); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_6common_10params_pyx_6Params___cinit__(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_d) { + std::string __pyx_v_path; + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + std::string __pyx_t_5; + Params *__pyx_t_6; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__cinit__", 1); + + /* "common/params_pyx.pyx":47 + * + * def __cinit__(self, d=""): + * cdef string path = d.encode() # <<<<<<<<<<<<<< + * with nogil: + * self.p = new c_Params(path) + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_d, __pyx_n_s_encode); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 47, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, NULL}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 0+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 47, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_t_5 = __pyx_convert_string_from_py_std__in_string(__pyx_t_1); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 47, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_path = ((std::string)__pyx_t_5); + + /* "common/params_pyx.pyx":48 + * def __cinit__(self, d=""): + * cdef string path = d.encode() + * with nogil: # <<<<<<<<<<<<<< + * self.p = new c_Params(path) + * + */ + { + #ifdef WITH_THREAD + PyThreadState *_save; + _save = NULL; + Py_UNBLOCK_THREADS + __Pyx_FastGIL_Remember(); + #endif + /*try:*/ { + + /* "common/params_pyx.pyx":49 + * cdef string path = d.encode() + * with nogil: + * self.p = new c_Params(path) # <<<<<<<<<<<<<< + * + * def __dealloc__(self): + */ + try { + __pyx_t_6 = new Params(__pyx_v_path); + } catch(...) { + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_CppExn2PyErr(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __PYX_ERR(0, 49, __pyx_L4_error) + } + __pyx_v_self->p = __pyx_t_6; + } + + /* "common/params_pyx.pyx":48 + * def __cinit__(self, d=""): + * cdef string path = d.encode() + * with nogil: # <<<<<<<<<<<<<< + * self.p = new c_Params(path) + * + */ + /*finally:*/ { + /*normal exit:*/{ + #ifdef WITH_THREAD + __Pyx_FastGIL_Forget(); + Py_BLOCK_THREADS + #endif + goto __pyx_L5; + } + __pyx_L4_error: { + #ifdef WITH_THREAD + __Pyx_FastGIL_Forget(); + Py_BLOCK_THREADS + #endif + goto __pyx_L1_error; + } + __pyx_L5:; + } + } + + /* "common/params_pyx.pyx":46 + * cdef c_Params* p + * + * def __cinit__(self, d=""): # <<<<<<<<<<<<<< + * cdef string path = d.encode() + * with nogil: + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("common.params_pyx.Params.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/params_pyx.pyx":51 + * self.p = new c_Params(path) + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * del self.p + * + */ + +/* Python wrapper */ +static void __pyx_pw_6common_10params_pyx_6Params_3__dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_pw_6common_10params_pyx_6Params_3__dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_pf_6common_10params_pyx_6Params_2__dealloc__(((struct __pyx_obj_6common_10params_pyx_Params *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_pf_6common_10params_pyx_6Params_2__dealloc__(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self) { + + /* "common/params_pyx.pyx":52 + * + * def __dealloc__(self): + * del self.p # <<<<<<<<<<<<<< + * + * def clear_all(self, tx_type=ParamKeyType.ALL): + */ + delete __pyx_v_self->p; + + /* "common/params_pyx.pyx":51 + * self.p = new c_Params(path) + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * del self.p + * + */ + + /* function exit code */ +} + +/* "common/params_pyx.pyx":54 + * del self.p + * + * def clear_all(self, tx_type=ParamKeyType.ALL): # <<<<<<<<<<<<<< + * self.p.clearAll(tx_type) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_10params_pyx_6Params_5clear_all(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_10params_pyx_6Params_5clear_all = {"clear_all", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_5clear_all, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_10params_pyx_6Params_5clear_all(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_tx_type = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("clear_all (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_tx_type,0}; + values[0] = __Pyx_Arg_NewRef_FASTCALL(__pyx_k__4); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_tx_type); + if (value) { values[0] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 54, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "clear_all") < 0)) __PYX_ERR(0, 54, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_tx_type = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("clear_all", 0, 0, 1, __pyx_nargs); __PYX_ERR(0, 54, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("common.params_pyx.Params.clear_all", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_10params_pyx_6Params_4clear_all(((struct __pyx_obj_6common_10params_pyx_Params *)__pyx_v_self), __pyx_v_tx_type); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_10params_pyx_6Params_4clear_all(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_tx_type) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + enum ParamKeyType __pyx_t_1; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("clear_all", 1); + + /* "common/params_pyx.pyx":55 + * + * def clear_all(self, tx_type=ParamKeyType.ALL): + * self.p.clearAll(tx_type) # <<<<<<<<<<<<<< + * + * def check_key(self, key): + */ + __pyx_t_1 = ((enum ParamKeyType)__Pyx_PyInt_As_enum__ParamKeyType(__pyx_v_tx_type)); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 55, __pyx_L1_error) + __pyx_v_self->p->clearAll(__pyx_t_1); + + /* "common/params_pyx.pyx":54 + * del self.p + * + * def clear_all(self, tx_type=ParamKeyType.ALL): # <<<<<<<<<<<<<< + * self.p.clearAll(tx_type) + * + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("common.params_pyx.Params.clear_all", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/params_pyx.pyx":57 + * self.p.clearAll(tx_type) + * + * def check_key(self, key): # <<<<<<<<<<<<<< + * key = ensure_bytes(key) + * if not self.p.checkKey(key): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_10params_pyx_6Params_7check_key(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_10params_pyx_6Params_7check_key = {"check_key", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_7check_key, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_10params_pyx_6Params_7check_key(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_key = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("check_key (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_key,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_key)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 57, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "check_key") < 0)) __PYX_ERR(0, 57, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_key = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("check_key", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 57, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("common.params_pyx.Params.check_key", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_10params_pyx_6Params_6check_key(((struct __pyx_obj_6common_10params_pyx_Params *)__pyx_v_self), __pyx_v_key); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_10params_pyx_6Params_6check_key(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + std::string __pyx_t_5; + int __pyx_t_6; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("check_key", 0); + __Pyx_INCREF(__pyx_v_key); + + /* "common/params_pyx.pyx":58 + * + * def check_key(self, key): + * key = ensure_bytes(key) # <<<<<<<<<<<<<< + * if not self.p.checkKey(key): + * raise UnknownKeyName(key) + */ + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_ensure_bytes); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 58, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (unlikely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_key}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 58, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __Pyx_DECREF_SET(__pyx_v_key, __pyx_t_1); + __pyx_t_1 = 0; + + /* "common/params_pyx.pyx":59 + * def check_key(self, key): + * key = ensure_bytes(key) + * if not self.p.checkKey(key): # <<<<<<<<<<<<<< + * raise UnknownKeyName(key) + * return key + */ + __pyx_t_5 = __pyx_convert_string_from_py_std__in_string(__pyx_v_key); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 59, __pyx_L1_error) + __pyx_t_6 = (!(__pyx_v_self->p->checkKey(__PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_5)) != 0)); + if (unlikely(__pyx_t_6)) { + + /* "common/params_pyx.pyx":60 + * key = ensure_bytes(key) + * if not self.p.checkKey(key): + * raise UnknownKeyName(key) # <<<<<<<<<<<<<< + * return key + * + */ + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_UnknownKeyName); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 60, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (unlikely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_key}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 60, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 60, __pyx_L1_error) + + /* "common/params_pyx.pyx":59 + * def check_key(self, key): + * key = ensure_bytes(key) + * if not self.p.checkKey(key): # <<<<<<<<<<<<<< + * raise UnknownKeyName(key) + * return key + */ + } + + /* "common/params_pyx.pyx":61 + * if not self.p.checkKey(key): + * raise UnknownKeyName(key) + * return key # <<<<<<<<<<<<<< + * + * def get(self, key, bool block=False, encoding=None): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_key); + __pyx_r = __pyx_v_key; + goto __pyx_L0; + + /* "common/params_pyx.pyx":57 + * self.p.clearAll(tx_type) + * + * def check_key(self, key): # <<<<<<<<<<<<<< + * key = ensure_bytes(key) + * if not self.p.checkKey(key): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("common.params_pyx.Params.check_key", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_key); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/params_pyx.pyx":63 + * return key + * + * def get(self, key, bool block=False, encoding=None): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * cdef string val + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_10params_pyx_6Params_9get(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_10params_pyx_6Params_9get = {"get", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_9get, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_10params_pyx_6Params_9get(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_key = 0; + bool __pyx_v_block; + PyObject *__pyx_v_encoding = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("get (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_key,&__pyx_n_s_block,&__pyx_n_s_encoding,0}; + values[2] = __Pyx_Arg_NewRef_FASTCALL(((PyObject *)Py_None)); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_key)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 63, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_block); + if (value) { values[1] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 63, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_encoding); + if (value) { values[2] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 63, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "get") < 0)) __PYX_ERR(0, 63, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_key = values[0]; + if (values[1]) { + __pyx_v_block = __Pyx_PyObject_IsTrue(values[1]); if (unlikely((__pyx_v_block == ((bool)-1)) && PyErr_Occurred())) __PYX_ERR(0, 63, __pyx_L3_error) + } else { + __pyx_v_block = ((bool)0); + } + __pyx_v_encoding = values[2]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("get", 0, 1, 3, __pyx_nargs); __PYX_ERR(0, 63, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("common.params_pyx.Params.get", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_10params_pyx_6Params_8get(((struct __pyx_obj_6common_10params_pyx_Params *)__pyx_v_self), __pyx_v_key, __pyx_v_block, __pyx_v_encoding); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_10params_pyx_6Params_8get(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key, bool __pyx_v_block, PyObject *__pyx_v_encoding) { + std::string __pyx_v_k; + std::string __pyx_v_val; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + std::string __pyx_t_5; + int __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get", 1); + + /* "common/params_pyx.pyx":64 + * + * def get(self, key, bool block=False, encoding=None): + * cdef string k = self.check_key(key) # <<<<<<<<<<<<<< + * cdef string val + * with nogil: + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_check_key); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 64, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_key}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 64, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_t_5 = __pyx_convert_string_from_py_std__in_string(__pyx_t_1); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 64, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_k = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_5); + + /* "common/params_pyx.pyx":66 + * cdef string k = self.check_key(key) + * cdef string val + * with nogil: # <<<<<<<<<<<<<< + * val = self.p.get(k, block) + * + */ + { + #ifdef WITH_THREAD + PyThreadState *_save; + _save = NULL; + Py_UNBLOCK_THREADS + __Pyx_FastGIL_Remember(); + #endif + /*try:*/ { + + /* "common/params_pyx.pyx":67 + * cdef string val + * with nogil: + * val = self.p.get(k, block) # <<<<<<<<<<<<<< + * + * if val == b"": + */ + __pyx_v_val = __pyx_v_self->p->get(__pyx_v_k, __pyx_v_block); + } + + /* "common/params_pyx.pyx":66 + * cdef string k = self.check_key(key) + * cdef string val + * with nogil: # <<<<<<<<<<<<<< + * val = self.p.get(k, block) + * + */ + /*finally:*/ { + /*normal exit:*/{ + #ifdef WITH_THREAD + __Pyx_FastGIL_Forget(); + Py_BLOCK_THREADS + #endif + goto __pyx_L5; + } + __pyx_L5:; + } + } + + /* "common/params_pyx.pyx":69 + * val = self.p.get(k, block) + * + * if val == b"": # <<<<<<<<<<<<<< + * if block: + * # If we got no value while running in blocked mode + */ + __pyx_t_6 = (__pyx_v_val == ((char const *)"")); + if (__pyx_t_6) { + + /* "common/params_pyx.pyx":70 + * + * if val == b"": + * if block: # <<<<<<<<<<<<<< + * # If we got no value while running in blocked mode + * # it means we got an interrupt while waiting + */ + __pyx_t_6 = (__pyx_v_block != 0); + if (unlikely(__pyx_t_6)) { + + /* "common/params_pyx.pyx":73 + * # If we got no value while running in blocked mode + * # it means we got an interrupt while waiting + * raise KeyboardInterrupt # <<<<<<<<<<<<<< + * else: + * return None + */ + __Pyx_Raise(__pyx_builtin_KeyboardInterrupt, 0, 0, 0); + __PYX_ERR(0, 73, __pyx_L1_error) + + /* "common/params_pyx.pyx":70 + * + * if val == b"": + * if block: # <<<<<<<<<<<<<< + * # If we got no value while running in blocked mode + * # it means we got an interrupt while waiting + */ + } + + /* "common/params_pyx.pyx":75 + * raise KeyboardInterrupt + * else: + * return None # <<<<<<<<<<<<<< + * + * return val if encoding is None else val.decode(encoding) + */ + /*else*/ { + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + } + + /* "common/params_pyx.pyx":69 + * val = self.p.get(k, block) + * + * if val == b"": # <<<<<<<<<<<<<< + * if block: + * # If we got no value while running in blocked mode + */ + } + + /* "common/params_pyx.pyx":77 + * return None + * + * return val if encoding is None else val.decode(encoding) # <<<<<<<<<<<<<< + * + * def get_bool(self, key, bool block=False): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_6 = (__pyx_v_encoding == Py_None); + if (__pyx_t_6) { + __pyx_t_2 = __pyx_convert_PyBytes_string_to_py_std__in_string(__pyx_v_val); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 77, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_1 = __pyx_t_2; + __pyx_t_2 = 0; + } else { + __pyx_t_3 = __pyx_convert_PyBytes_string_to_py_std__in_string(__pyx_v_val); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 77, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_decode); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 77, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_7))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_7); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_7); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_7, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_encoding}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_7, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 77, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + } + __pyx_t_1 = __pyx_t_2; + __pyx_t_2 = 0; + } + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "common/params_pyx.pyx":63 + * return key + * + * def get(self, key, bool block=False, encoding=None): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * cdef string val + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("common.params_pyx.Params.get", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/params_pyx.pyx":79 + * return val if encoding is None else val.decode(encoding) + * + * def get_bool(self, key, bool block=False): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * cdef bool r + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_10params_pyx_6Params_11get_bool(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_10params_pyx_6Params_11get_bool = {"get_bool", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_11get_bool, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_10params_pyx_6Params_11get_bool(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_key = 0; + bool __pyx_v_block; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[2] = {0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("get_bool (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_key,&__pyx_n_s_block,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_key)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 79, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_block); + if (value) { values[1] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 79, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "get_bool") < 0)) __PYX_ERR(0, 79, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_key = values[0]; + if (values[1]) { + __pyx_v_block = __Pyx_PyObject_IsTrue(values[1]); if (unlikely((__pyx_v_block == ((bool)-1)) && PyErr_Occurred())) __PYX_ERR(0, 79, __pyx_L3_error) + } else { + __pyx_v_block = ((bool)0); + } + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("get_bool", 0, 1, 2, __pyx_nargs); __PYX_ERR(0, 79, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("common.params_pyx.Params.get_bool", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_10params_pyx_6Params_10get_bool(((struct __pyx_obj_6common_10params_pyx_Params *)__pyx_v_self), __pyx_v_key, __pyx_v_block); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_10params_pyx_6Params_10get_bool(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key, bool __pyx_v_block) { + std::string __pyx_v_k; + bool __pyx_v_r; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + std::string __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_bool", 1); + + /* "common/params_pyx.pyx":80 + * + * def get_bool(self, key, bool block=False): + * cdef string k = self.check_key(key) # <<<<<<<<<<<<<< + * cdef bool r + * with nogil: + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_check_key); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 80, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_key}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 80, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_t_5 = __pyx_convert_string_from_py_std__in_string(__pyx_t_1); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 80, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_k = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_5); + + /* "common/params_pyx.pyx":82 + * cdef string k = self.check_key(key) + * cdef bool r + * with nogil: # <<<<<<<<<<<<<< + * r = self.p.getBool(k, block) + * return r + */ + { + #ifdef WITH_THREAD + PyThreadState *_save; + _save = NULL; + Py_UNBLOCK_THREADS + __Pyx_FastGIL_Remember(); + #endif + /*try:*/ { + + /* "common/params_pyx.pyx":83 + * cdef bool r + * with nogil: + * r = self.p.getBool(k, block) # <<<<<<<<<<<<<< + * return r + * + */ + __pyx_v_r = __pyx_v_self->p->getBool(__pyx_v_k, __pyx_v_block); + } + + /* "common/params_pyx.pyx":82 + * cdef string k = self.check_key(key) + * cdef bool r + * with nogil: # <<<<<<<<<<<<<< + * r = self.p.getBool(k, block) + * return r + */ + /*finally:*/ { + /*normal exit:*/{ + #ifdef WITH_THREAD + __Pyx_FastGIL_Forget(); + Py_BLOCK_THREADS + #endif + goto __pyx_L5; + } + __pyx_L5:; + } + } + + /* "common/params_pyx.pyx":84 + * with nogil: + * r = self.p.getBool(k, block) + * return r # <<<<<<<<<<<<<< + * + * def get_int(self, key, bool block=False): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyBool_FromLong(__pyx_v_r); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 84, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "common/params_pyx.pyx":79 + * return val if encoding is None else val.decode(encoding) + * + * def get_bool(self, key, bool block=False): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * cdef bool r + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("common.params_pyx.Params.get_bool", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/params_pyx.pyx":86 + * return r + * + * def get_int(self, key, bool block=False): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * cdef int r + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_10params_pyx_6Params_13get_int(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_10params_pyx_6Params_13get_int = {"get_int", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_13get_int, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_10params_pyx_6Params_13get_int(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_key = 0; + bool __pyx_v_block; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[2] = {0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("get_int (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_key,&__pyx_n_s_block,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_key)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 86, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_block); + if (value) { values[1] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 86, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "get_int") < 0)) __PYX_ERR(0, 86, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_key = values[0]; + if (values[1]) { + __pyx_v_block = __Pyx_PyObject_IsTrue(values[1]); if (unlikely((__pyx_v_block == ((bool)-1)) && PyErr_Occurred())) __PYX_ERR(0, 86, __pyx_L3_error) + } else { + __pyx_v_block = ((bool)0); + } + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("get_int", 0, 1, 2, __pyx_nargs); __PYX_ERR(0, 86, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("common.params_pyx.Params.get_int", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_10params_pyx_6Params_12get_int(((struct __pyx_obj_6common_10params_pyx_Params *)__pyx_v_self), __pyx_v_key, __pyx_v_block); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_10params_pyx_6Params_12get_int(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key, bool __pyx_v_block) { + std::string __pyx_v_k; + int __pyx_v_r; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + std::string __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_int", 1); + + /* "common/params_pyx.pyx":87 + * + * def get_int(self, key, bool block=False): + * cdef string k = self.check_key(key) # <<<<<<<<<<<<<< + * cdef int r + * with nogil: + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_check_key); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 87, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_key}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 87, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_t_5 = __pyx_convert_string_from_py_std__in_string(__pyx_t_1); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 87, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_k = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_5); + + /* "common/params_pyx.pyx":89 + * cdef string k = self.check_key(key) + * cdef int r + * with nogil: # <<<<<<<<<<<<<< + * r = self.p.getInt(k, block) + * return r + */ + { + #ifdef WITH_THREAD + PyThreadState *_save; + _save = NULL; + Py_UNBLOCK_THREADS + __Pyx_FastGIL_Remember(); + #endif + /*try:*/ { + + /* "common/params_pyx.pyx":90 + * cdef int r + * with nogil: + * r = self.p.getInt(k, block) # <<<<<<<<<<<<<< + * return r + * + */ + __pyx_v_r = __pyx_v_self->p->getInt(__pyx_v_k, __pyx_v_block); + } + + /* "common/params_pyx.pyx":89 + * cdef string k = self.check_key(key) + * cdef int r + * with nogil: # <<<<<<<<<<<<<< + * r = self.p.getInt(k, block) + * return r + */ + /*finally:*/ { + /*normal exit:*/{ + #ifdef WITH_THREAD + __Pyx_FastGIL_Forget(); + Py_BLOCK_THREADS + #endif + goto __pyx_L5; + } + __pyx_L5:; + } + } + + /* "common/params_pyx.pyx":91 + * with nogil: + * r = self.p.getInt(k, block) + * return r # <<<<<<<<<<<<<< + * + * def get_float(self, key, bool block=False): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_r); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 91, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "common/params_pyx.pyx":86 + * return r + * + * def get_int(self, key, bool block=False): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * cdef int r + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("common.params_pyx.Params.get_int", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/params_pyx.pyx":93 + * return r + * + * def get_float(self, key, bool block=False): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * cdef float r + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_10params_pyx_6Params_15get_float(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_10params_pyx_6Params_15get_float = {"get_float", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_15get_float, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_10params_pyx_6Params_15get_float(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_key = 0; + bool __pyx_v_block; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[2] = {0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("get_float (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_key,&__pyx_n_s_block,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_key)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 93, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_block); + if (value) { values[1] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 93, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "get_float") < 0)) __PYX_ERR(0, 93, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_key = values[0]; + if (values[1]) { + __pyx_v_block = __Pyx_PyObject_IsTrue(values[1]); if (unlikely((__pyx_v_block == ((bool)-1)) && PyErr_Occurred())) __PYX_ERR(0, 93, __pyx_L3_error) + } else { + __pyx_v_block = ((bool)0); + } + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("get_float", 0, 1, 2, __pyx_nargs); __PYX_ERR(0, 93, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("common.params_pyx.Params.get_float", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_10params_pyx_6Params_14get_float(((struct __pyx_obj_6common_10params_pyx_Params *)__pyx_v_self), __pyx_v_key, __pyx_v_block); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_10params_pyx_6Params_14get_float(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key, bool __pyx_v_block) { + std::string __pyx_v_k; + float __pyx_v_r; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + std::string __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_float", 1); + + /* "common/params_pyx.pyx":94 + * + * def get_float(self, key, bool block=False): + * cdef string k = self.check_key(key) # <<<<<<<<<<<<<< + * cdef float r + * with nogil: + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_check_key); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 94, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_key}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 94, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_t_5 = __pyx_convert_string_from_py_std__in_string(__pyx_t_1); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 94, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_k = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_5); + + /* "common/params_pyx.pyx":96 + * cdef string k = self.check_key(key) + * cdef float r + * with nogil: # <<<<<<<<<<<<<< + * r = self.p.getFloat(k, block) + * return r + */ + { + #ifdef WITH_THREAD + PyThreadState *_save; + _save = NULL; + Py_UNBLOCK_THREADS + __Pyx_FastGIL_Remember(); + #endif + /*try:*/ { + + /* "common/params_pyx.pyx":97 + * cdef float r + * with nogil: + * r = self.p.getFloat(k, block) # <<<<<<<<<<<<<< + * return r + * + */ + __pyx_v_r = __pyx_v_self->p->getFloat(__pyx_v_k, __pyx_v_block); + } + + /* "common/params_pyx.pyx":96 + * cdef string k = self.check_key(key) + * cdef float r + * with nogil: # <<<<<<<<<<<<<< + * r = self.p.getFloat(k, block) + * return r + */ + /*finally:*/ { + /*normal exit:*/{ + #ifdef WITH_THREAD + __Pyx_FastGIL_Forget(); + Py_BLOCK_THREADS + #endif + goto __pyx_L5; + } + __pyx_L5:; + } + } + + /* "common/params_pyx.pyx":98 + * with nogil: + * r = self.p.getFloat(k, block) + * return r # <<<<<<<<<<<<<< + * + * def put(self, key, dat): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyFloat_FromDouble(__pyx_v_r); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 98, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "common/params_pyx.pyx":93 + * return r + * + * def get_float(self, key, bool block=False): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * cdef float r + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("common.params_pyx.Params.get_float", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/params_pyx.pyx":100 + * return r + * + * def put(self, key, dat): # <<<<<<<<<<<<<< + * """ + * Warning: This function blocks until the param is written to disk! + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_10params_pyx_6Params_17put(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_6common_10params_pyx_6Params_16put, "\n Warning: This function blocks until the param is written to disk!\n In very rare cases this can take over a second, and your code will hang.\n Use the put_nonblocking, put_bool_nonblocking in time sensitive code, but\n in general try to avoid writing params as much as possible.\n "); +static PyMethodDef __pyx_mdef_6common_10params_pyx_6Params_17put = {"put", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_17put, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_6common_10params_pyx_6Params_16put}; +static PyObject *__pyx_pw_6common_10params_pyx_6Params_17put(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_key = 0; + PyObject *__pyx_v_dat = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[2] = {0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("put (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_key,&__pyx_n_s_dat,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_key)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 100, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_dat)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 100, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("put", 1, 2, 2, 1); __PYX_ERR(0, 100, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "put") < 0)) __PYX_ERR(0, 100, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 2)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + } + __pyx_v_key = values[0]; + __pyx_v_dat = values[1]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("put", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 100, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("common.params_pyx.Params.put", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_10params_pyx_6Params_16put(((struct __pyx_obj_6common_10params_pyx_Params *)__pyx_v_self), __pyx_v_key, __pyx_v_dat); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_10params_pyx_6Params_16put(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key, PyObject *__pyx_v_dat) { + std::string __pyx_v_k; + std::string __pyx_v_dat_bytes; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + std::string __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("put", 1); + + /* "common/params_pyx.pyx":107 + * in general try to avoid writing params as much as possible. + * """ + * cdef string k = self.check_key(key) # <<<<<<<<<<<<<< + * cdef string dat_bytes = ensure_bytes(dat) + * with nogil: + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_check_key); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 107, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_key}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 107, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_t_5 = __pyx_convert_string_from_py_std__in_string(__pyx_t_1); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 107, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_k = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_5); + + /* "common/params_pyx.pyx":108 + * """ + * cdef string k = self.check_key(key) + * cdef string dat_bytes = ensure_bytes(dat) # <<<<<<<<<<<<<< + * with nogil: + * self.p.put(k, dat_bytes) + */ + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_ensure_bytes); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 108, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (unlikely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_dat}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 108, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_t_5 = __pyx_convert_string_from_py_std__in_string(__pyx_t_1); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 108, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_dat_bytes = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_5); + + /* "common/params_pyx.pyx":109 + * cdef string k = self.check_key(key) + * cdef string dat_bytes = ensure_bytes(dat) + * with nogil: # <<<<<<<<<<<<<< + * self.p.put(k, dat_bytes) + * + */ + { + #ifdef WITH_THREAD + PyThreadState *_save; + _save = NULL; + Py_UNBLOCK_THREADS + __Pyx_FastGIL_Remember(); + #endif + /*try:*/ { + + /* "common/params_pyx.pyx":110 + * cdef string dat_bytes = ensure_bytes(dat) + * with nogil: + * self.p.put(k, dat_bytes) # <<<<<<<<<<<<<< + * + * def put_bool(self, key, bool val): + */ + (void)(__pyx_v_self->p->put(__pyx_v_k, __pyx_v_dat_bytes)); + } + + /* "common/params_pyx.pyx":109 + * cdef string k = self.check_key(key) + * cdef string dat_bytes = ensure_bytes(dat) + * with nogil: # <<<<<<<<<<<<<< + * self.p.put(k, dat_bytes) + * + */ + /*finally:*/ { + /*normal exit:*/{ + #ifdef WITH_THREAD + __Pyx_FastGIL_Forget(); + Py_BLOCK_THREADS + #endif + goto __pyx_L5; + } + __pyx_L5:; + } + } + + /* "common/params_pyx.pyx":100 + * return r + * + * def put(self, key, dat): # <<<<<<<<<<<<<< + * """ + * Warning: This function blocks until the param is written to disk! + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("common.params_pyx.Params.put", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/params_pyx.pyx":112 + * self.p.put(k, dat_bytes) + * + * def put_bool(self, key, bool val): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * with nogil: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_10params_pyx_6Params_19put_bool(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_10params_pyx_6Params_19put_bool = {"put_bool", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_19put_bool, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_10params_pyx_6Params_19put_bool(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_key = 0; + bool __pyx_v_val; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[2] = {0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("put_bool (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_key,&__pyx_n_s_val,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_key)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 112, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_val)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 112, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("put_bool", 1, 2, 2, 1); __PYX_ERR(0, 112, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "put_bool") < 0)) __PYX_ERR(0, 112, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 2)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + } + __pyx_v_key = values[0]; + __pyx_v_val = __Pyx_PyObject_IsTrue(values[1]); if (unlikely((__pyx_v_val == ((bool)-1)) && PyErr_Occurred())) __PYX_ERR(0, 112, __pyx_L3_error) + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("put_bool", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 112, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("common.params_pyx.Params.put_bool", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_10params_pyx_6Params_18put_bool(((struct __pyx_obj_6common_10params_pyx_Params *)__pyx_v_self), __pyx_v_key, __pyx_v_val); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_10params_pyx_6Params_18put_bool(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key, bool __pyx_v_val) { + std::string __pyx_v_k; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + std::string __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("put_bool", 1); + + /* "common/params_pyx.pyx":113 + * + * def put_bool(self, key, bool val): + * cdef string k = self.check_key(key) # <<<<<<<<<<<<<< + * with nogil: + * self.p.putBool(k, val) + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_check_key); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 113, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_key}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 113, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_t_5 = __pyx_convert_string_from_py_std__in_string(__pyx_t_1); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 113, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_k = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_5); + + /* "common/params_pyx.pyx":114 + * def put_bool(self, key, bool val): + * cdef string k = self.check_key(key) + * with nogil: # <<<<<<<<<<<<<< + * self.p.putBool(k, val) + * + */ + { + #ifdef WITH_THREAD + PyThreadState *_save; + _save = NULL; + Py_UNBLOCK_THREADS + __Pyx_FastGIL_Remember(); + #endif + /*try:*/ { + + /* "common/params_pyx.pyx":115 + * cdef string k = self.check_key(key) + * with nogil: + * self.p.putBool(k, val) # <<<<<<<<<<<<<< + * + * def put_int(self, key, int val): + */ + (void)(__pyx_v_self->p->putBool(__pyx_v_k, __pyx_v_val)); + } + + /* "common/params_pyx.pyx":114 + * def put_bool(self, key, bool val): + * cdef string k = self.check_key(key) + * with nogil: # <<<<<<<<<<<<<< + * self.p.putBool(k, val) + * + */ + /*finally:*/ { + /*normal exit:*/{ + #ifdef WITH_THREAD + __Pyx_FastGIL_Forget(); + Py_BLOCK_THREADS + #endif + goto __pyx_L5; + } + __pyx_L5:; + } + } + + /* "common/params_pyx.pyx":112 + * self.p.put(k, dat_bytes) + * + * def put_bool(self, key, bool val): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * with nogil: + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("common.params_pyx.Params.put_bool", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/params_pyx.pyx":117 + * self.p.putBool(k, val) + * + * def put_int(self, key, int val): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * with nogil: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_10params_pyx_6Params_21put_int(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_10params_pyx_6Params_21put_int = {"put_int", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_21put_int, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_10params_pyx_6Params_21put_int(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_key = 0; + int __pyx_v_val; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[2] = {0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("put_int (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_key,&__pyx_n_s_val,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_key)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 117, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_val)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 117, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("put_int", 1, 2, 2, 1); __PYX_ERR(0, 117, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "put_int") < 0)) __PYX_ERR(0, 117, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 2)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + } + __pyx_v_key = values[0]; + __pyx_v_val = __Pyx_PyInt_As_int(values[1]); if (unlikely((__pyx_v_val == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 117, __pyx_L3_error) + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("put_int", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 117, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("common.params_pyx.Params.put_int", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_10params_pyx_6Params_20put_int(((struct __pyx_obj_6common_10params_pyx_Params *)__pyx_v_self), __pyx_v_key, __pyx_v_val); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_10params_pyx_6Params_20put_int(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key, int __pyx_v_val) { + std::string __pyx_v_k; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + std::string __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("put_int", 1); + + /* "common/params_pyx.pyx":118 + * + * def put_int(self, key, int val): + * cdef string k = self.check_key(key) # <<<<<<<<<<<<<< + * with nogil: + * self.p.putInt(k, val) + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_check_key); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 118, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_key}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 118, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_t_5 = __pyx_convert_string_from_py_std__in_string(__pyx_t_1); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 118, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_k = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_5); + + /* "common/params_pyx.pyx":119 + * def put_int(self, key, int val): + * cdef string k = self.check_key(key) + * with nogil: # <<<<<<<<<<<<<< + * self.p.putInt(k, val) + * + */ + { + #ifdef WITH_THREAD + PyThreadState *_save; + _save = NULL; + Py_UNBLOCK_THREADS + __Pyx_FastGIL_Remember(); + #endif + /*try:*/ { + + /* "common/params_pyx.pyx":120 + * cdef string k = self.check_key(key) + * with nogil: + * self.p.putInt(k, val) # <<<<<<<<<<<<<< + * + * def put_float(self, key, float val): + */ + (void)(__pyx_v_self->p->putInt(__pyx_v_k, __pyx_v_val)); + } + + /* "common/params_pyx.pyx":119 + * def put_int(self, key, int val): + * cdef string k = self.check_key(key) + * with nogil: # <<<<<<<<<<<<<< + * self.p.putInt(k, val) + * + */ + /*finally:*/ { + /*normal exit:*/{ + #ifdef WITH_THREAD + __Pyx_FastGIL_Forget(); + Py_BLOCK_THREADS + #endif + goto __pyx_L5; + } + __pyx_L5:; + } + } + + /* "common/params_pyx.pyx":117 + * self.p.putBool(k, val) + * + * def put_int(self, key, int val): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * with nogil: + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("common.params_pyx.Params.put_int", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/params_pyx.pyx":122 + * self.p.putInt(k, val) + * + * def put_float(self, key, float val): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * with nogil: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_10params_pyx_6Params_23put_float(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_10params_pyx_6Params_23put_float = {"put_float", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_23put_float, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_10params_pyx_6Params_23put_float(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_key = 0; + float __pyx_v_val; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[2] = {0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("put_float (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_key,&__pyx_n_s_val,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_key)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 122, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_val)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 122, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("put_float", 1, 2, 2, 1); __PYX_ERR(0, 122, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "put_float") < 0)) __PYX_ERR(0, 122, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 2)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + } + __pyx_v_key = values[0]; + __pyx_v_val = __pyx_PyFloat_AsFloat(values[1]); if (unlikely((__pyx_v_val == (float)-1) && PyErr_Occurred())) __PYX_ERR(0, 122, __pyx_L3_error) + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("put_float", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 122, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("common.params_pyx.Params.put_float", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_10params_pyx_6Params_22put_float(((struct __pyx_obj_6common_10params_pyx_Params *)__pyx_v_self), __pyx_v_key, __pyx_v_val); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_10params_pyx_6Params_22put_float(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key, float __pyx_v_val) { + std::string __pyx_v_k; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + std::string __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("put_float", 1); + + /* "common/params_pyx.pyx":123 + * + * def put_float(self, key, float val): + * cdef string k = self.check_key(key) # <<<<<<<<<<<<<< + * with nogil: + * self.p.putFloat(k, val) + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_check_key); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 123, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_key}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 123, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_t_5 = __pyx_convert_string_from_py_std__in_string(__pyx_t_1); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 123, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_k = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_5); + + /* "common/params_pyx.pyx":124 + * def put_float(self, key, float val): + * cdef string k = self.check_key(key) + * with nogil: # <<<<<<<<<<<<<< + * self.p.putFloat(k, val) + * + */ + { + #ifdef WITH_THREAD + PyThreadState *_save; + _save = NULL; + Py_UNBLOCK_THREADS + __Pyx_FastGIL_Remember(); + #endif + /*try:*/ { + + /* "common/params_pyx.pyx":125 + * cdef string k = self.check_key(key) + * with nogil: + * self.p.putFloat(k, val) # <<<<<<<<<<<<<< + * + * def put_nonblocking(self, key, dat): + */ + (void)(__pyx_v_self->p->putFloat(__pyx_v_k, __pyx_v_val)); + } + + /* "common/params_pyx.pyx":124 + * def put_float(self, key, float val): + * cdef string k = self.check_key(key) + * with nogil: # <<<<<<<<<<<<<< + * self.p.putFloat(k, val) + * + */ + /*finally:*/ { + /*normal exit:*/{ + #ifdef WITH_THREAD + __Pyx_FastGIL_Forget(); + Py_BLOCK_THREADS + #endif + goto __pyx_L5; + } + __pyx_L5:; + } + } + + /* "common/params_pyx.pyx":122 + * self.p.putInt(k, val) + * + * def put_float(self, key, float val): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * with nogil: + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("common.params_pyx.Params.put_float", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/params_pyx.pyx":127 + * self.p.putFloat(k, val) + * + * def put_nonblocking(self, key, dat): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * cdef string dat_bytes = ensure_bytes(dat) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_10params_pyx_6Params_25put_nonblocking(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_10params_pyx_6Params_25put_nonblocking = {"put_nonblocking", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_25put_nonblocking, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_10params_pyx_6Params_25put_nonblocking(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_key = 0; + PyObject *__pyx_v_dat = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[2] = {0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("put_nonblocking (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_key,&__pyx_n_s_dat,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_key)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 127, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_dat)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 127, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("put_nonblocking", 1, 2, 2, 1); __PYX_ERR(0, 127, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "put_nonblocking") < 0)) __PYX_ERR(0, 127, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 2)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + } + __pyx_v_key = values[0]; + __pyx_v_dat = values[1]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("put_nonblocking", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 127, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("common.params_pyx.Params.put_nonblocking", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_10params_pyx_6Params_24put_nonblocking(((struct __pyx_obj_6common_10params_pyx_Params *)__pyx_v_self), __pyx_v_key, __pyx_v_dat); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_10params_pyx_6Params_24put_nonblocking(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key, PyObject *__pyx_v_dat) { + std::string __pyx_v_k; + std::string __pyx_v_dat_bytes; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + std::string __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("put_nonblocking", 1); + + /* "common/params_pyx.pyx":128 + * + * def put_nonblocking(self, key, dat): + * cdef string k = self.check_key(key) # <<<<<<<<<<<<<< + * cdef string dat_bytes = ensure_bytes(dat) + * with nogil: + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_check_key); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 128, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_key}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 128, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_t_5 = __pyx_convert_string_from_py_std__in_string(__pyx_t_1); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 128, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_k = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_5); + + /* "common/params_pyx.pyx":129 + * def put_nonblocking(self, key, dat): + * cdef string k = self.check_key(key) + * cdef string dat_bytes = ensure_bytes(dat) # <<<<<<<<<<<<<< + * with nogil: + * self.p.putNonBlocking(k, dat_bytes) + */ + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_ensure_bytes); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 129, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (unlikely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_dat}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 129, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_t_5 = __pyx_convert_string_from_py_std__in_string(__pyx_t_1); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 129, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_dat_bytes = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_5); + + /* "common/params_pyx.pyx":130 + * cdef string k = self.check_key(key) + * cdef string dat_bytes = ensure_bytes(dat) + * with nogil: # <<<<<<<<<<<<<< + * self.p.putNonBlocking(k, dat_bytes) + * + */ + { + #ifdef WITH_THREAD + PyThreadState *_save; + _save = NULL; + Py_UNBLOCK_THREADS + __Pyx_FastGIL_Remember(); + #endif + /*try:*/ { + + /* "common/params_pyx.pyx":131 + * cdef string dat_bytes = ensure_bytes(dat) + * with nogil: + * self.p.putNonBlocking(k, dat_bytes) # <<<<<<<<<<<<<< + * + * def put_bool_nonblocking(self, key, bool val): + */ + __pyx_v_self->p->putNonBlocking(__pyx_v_k, __pyx_v_dat_bytes); + } + + /* "common/params_pyx.pyx":130 + * cdef string k = self.check_key(key) + * cdef string dat_bytes = ensure_bytes(dat) + * with nogil: # <<<<<<<<<<<<<< + * self.p.putNonBlocking(k, dat_bytes) + * + */ + /*finally:*/ { + /*normal exit:*/{ + #ifdef WITH_THREAD + __Pyx_FastGIL_Forget(); + Py_BLOCK_THREADS + #endif + goto __pyx_L5; + } + __pyx_L5:; + } + } + + /* "common/params_pyx.pyx":127 + * self.p.putFloat(k, val) + * + * def put_nonblocking(self, key, dat): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * cdef string dat_bytes = ensure_bytes(dat) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("common.params_pyx.Params.put_nonblocking", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/params_pyx.pyx":133 + * self.p.putNonBlocking(k, dat_bytes) + * + * def put_bool_nonblocking(self, key, bool val): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * with nogil: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_10params_pyx_6Params_27put_bool_nonblocking(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_10params_pyx_6Params_27put_bool_nonblocking = {"put_bool_nonblocking", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_27put_bool_nonblocking, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_10params_pyx_6Params_27put_bool_nonblocking(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_key = 0; + bool __pyx_v_val; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[2] = {0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("put_bool_nonblocking (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_key,&__pyx_n_s_val,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_key)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 133, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_val)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 133, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("put_bool_nonblocking", 1, 2, 2, 1); __PYX_ERR(0, 133, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "put_bool_nonblocking") < 0)) __PYX_ERR(0, 133, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 2)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + } + __pyx_v_key = values[0]; + __pyx_v_val = __Pyx_PyObject_IsTrue(values[1]); if (unlikely((__pyx_v_val == ((bool)-1)) && PyErr_Occurred())) __PYX_ERR(0, 133, __pyx_L3_error) + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("put_bool_nonblocking", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 133, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("common.params_pyx.Params.put_bool_nonblocking", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_10params_pyx_6Params_26put_bool_nonblocking(((struct __pyx_obj_6common_10params_pyx_Params *)__pyx_v_self), __pyx_v_key, __pyx_v_val); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_10params_pyx_6Params_26put_bool_nonblocking(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key, bool __pyx_v_val) { + std::string __pyx_v_k; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + std::string __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("put_bool_nonblocking", 1); + + /* "common/params_pyx.pyx":134 + * + * def put_bool_nonblocking(self, key, bool val): + * cdef string k = self.check_key(key) # <<<<<<<<<<<<<< + * with nogil: + * self.p.putBoolNonBlocking(k, val) + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_check_key); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 134, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_key}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 134, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_t_5 = __pyx_convert_string_from_py_std__in_string(__pyx_t_1); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 134, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_k = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_5); + + /* "common/params_pyx.pyx":135 + * def put_bool_nonblocking(self, key, bool val): + * cdef string k = self.check_key(key) + * with nogil: # <<<<<<<<<<<<<< + * self.p.putBoolNonBlocking(k, val) + * + */ + { + #ifdef WITH_THREAD + PyThreadState *_save; + _save = NULL; + Py_UNBLOCK_THREADS + __Pyx_FastGIL_Remember(); + #endif + /*try:*/ { + + /* "common/params_pyx.pyx":136 + * cdef string k = self.check_key(key) + * with nogil: + * self.p.putBoolNonBlocking(k, val) # <<<<<<<<<<<<<< + * + * def put_int_nonblocking(self, key, int val): + */ + __pyx_v_self->p->putBoolNonBlocking(__pyx_v_k, __pyx_v_val); + } + + /* "common/params_pyx.pyx":135 + * def put_bool_nonblocking(self, key, bool val): + * cdef string k = self.check_key(key) + * with nogil: # <<<<<<<<<<<<<< + * self.p.putBoolNonBlocking(k, val) + * + */ + /*finally:*/ { + /*normal exit:*/{ + #ifdef WITH_THREAD + __Pyx_FastGIL_Forget(); + Py_BLOCK_THREADS + #endif + goto __pyx_L5; + } + __pyx_L5:; + } + } + + /* "common/params_pyx.pyx":133 + * self.p.putNonBlocking(k, dat_bytes) + * + * def put_bool_nonblocking(self, key, bool val): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * with nogil: + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("common.params_pyx.Params.put_bool_nonblocking", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/params_pyx.pyx":138 + * self.p.putBoolNonBlocking(k, val) + * + * def put_int_nonblocking(self, key, int val): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * with nogil: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_10params_pyx_6Params_29put_int_nonblocking(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_10params_pyx_6Params_29put_int_nonblocking = {"put_int_nonblocking", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_29put_int_nonblocking, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_10params_pyx_6Params_29put_int_nonblocking(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_key = 0; + int __pyx_v_val; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[2] = {0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("put_int_nonblocking (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_key,&__pyx_n_s_val,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_key)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 138, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_val)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 138, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("put_int_nonblocking", 1, 2, 2, 1); __PYX_ERR(0, 138, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "put_int_nonblocking") < 0)) __PYX_ERR(0, 138, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 2)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + } + __pyx_v_key = values[0]; + __pyx_v_val = __Pyx_PyInt_As_int(values[1]); if (unlikely((__pyx_v_val == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 138, __pyx_L3_error) + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("put_int_nonblocking", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 138, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("common.params_pyx.Params.put_int_nonblocking", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_10params_pyx_6Params_28put_int_nonblocking(((struct __pyx_obj_6common_10params_pyx_Params *)__pyx_v_self), __pyx_v_key, __pyx_v_val); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_10params_pyx_6Params_28put_int_nonblocking(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key, int __pyx_v_val) { + std::string __pyx_v_k; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + std::string __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("put_int_nonblocking", 1); + + /* "common/params_pyx.pyx":139 + * + * def put_int_nonblocking(self, key, int val): + * cdef string k = self.check_key(key) # <<<<<<<<<<<<<< + * with nogil: + * self.p.putIntNonBlocking(k, val) + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_check_key); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 139, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_key}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 139, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_t_5 = __pyx_convert_string_from_py_std__in_string(__pyx_t_1); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 139, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_k = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_5); + + /* "common/params_pyx.pyx":140 + * def put_int_nonblocking(self, key, int val): + * cdef string k = self.check_key(key) + * with nogil: # <<<<<<<<<<<<<< + * self.p.putIntNonBlocking(k, val) + * + */ + { + #ifdef WITH_THREAD + PyThreadState *_save; + _save = NULL; + Py_UNBLOCK_THREADS + __Pyx_FastGIL_Remember(); + #endif + /*try:*/ { + + /* "common/params_pyx.pyx":141 + * cdef string k = self.check_key(key) + * with nogil: + * self.p.putIntNonBlocking(k, val) # <<<<<<<<<<<<<< + * + * def put_float_nonblocking(self, key, float val): + */ + __pyx_v_self->p->putIntNonBlocking(__pyx_v_k, __pyx_v_val); + } + + /* "common/params_pyx.pyx":140 + * def put_int_nonblocking(self, key, int val): + * cdef string k = self.check_key(key) + * with nogil: # <<<<<<<<<<<<<< + * self.p.putIntNonBlocking(k, val) + * + */ + /*finally:*/ { + /*normal exit:*/{ + #ifdef WITH_THREAD + __Pyx_FastGIL_Forget(); + Py_BLOCK_THREADS + #endif + goto __pyx_L5; + } + __pyx_L5:; + } + } + + /* "common/params_pyx.pyx":138 + * self.p.putBoolNonBlocking(k, val) + * + * def put_int_nonblocking(self, key, int val): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * with nogil: + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("common.params_pyx.Params.put_int_nonblocking", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/params_pyx.pyx":143 + * self.p.putIntNonBlocking(k, val) + * + * def put_float_nonblocking(self, key, float val): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * with nogil: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_10params_pyx_6Params_31put_float_nonblocking(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_10params_pyx_6Params_31put_float_nonblocking = {"put_float_nonblocking", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_31put_float_nonblocking, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_10params_pyx_6Params_31put_float_nonblocking(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_key = 0; + float __pyx_v_val; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[2] = {0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("put_float_nonblocking (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_key,&__pyx_n_s_val,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_key)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 143, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_val)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 143, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("put_float_nonblocking", 1, 2, 2, 1); __PYX_ERR(0, 143, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "put_float_nonblocking") < 0)) __PYX_ERR(0, 143, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 2)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + } + __pyx_v_key = values[0]; + __pyx_v_val = __pyx_PyFloat_AsFloat(values[1]); if (unlikely((__pyx_v_val == (float)-1) && PyErr_Occurred())) __PYX_ERR(0, 143, __pyx_L3_error) + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("put_float_nonblocking", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 143, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("common.params_pyx.Params.put_float_nonblocking", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_10params_pyx_6Params_30put_float_nonblocking(((struct __pyx_obj_6common_10params_pyx_Params *)__pyx_v_self), __pyx_v_key, __pyx_v_val); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_10params_pyx_6Params_30put_float_nonblocking(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key, float __pyx_v_val) { + std::string __pyx_v_k; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + std::string __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("put_float_nonblocking", 1); + + /* "common/params_pyx.pyx":144 + * + * def put_float_nonblocking(self, key, float val): + * cdef string k = self.check_key(key) # <<<<<<<<<<<<<< + * with nogil: + * self.p.putFloatNonBlocking(k, val) + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_check_key); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 144, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_key}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 144, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_t_5 = __pyx_convert_string_from_py_std__in_string(__pyx_t_1); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 144, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_k = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_5); + + /* "common/params_pyx.pyx":145 + * def put_float_nonblocking(self, key, float val): + * cdef string k = self.check_key(key) + * with nogil: # <<<<<<<<<<<<<< + * self.p.putFloatNonBlocking(k, val) + * + */ + { + #ifdef WITH_THREAD + PyThreadState *_save; + _save = NULL; + Py_UNBLOCK_THREADS + __Pyx_FastGIL_Remember(); + #endif + /*try:*/ { + + /* "common/params_pyx.pyx":146 + * cdef string k = self.check_key(key) + * with nogil: + * self.p.putFloatNonBlocking(k, val) # <<<<<<<<<<<<<< + * + * def remove(self, key): + */ + __pyx_v_self->p->putFloatNonBlocking(__pyx_v_k, __pyx_v_val); + } + + /* "common/params_pyx.pyx":145 + * def put_float_nonblocking(self, key, float val): + * cdef string k = self.check_key(key) + * with nogil: # <<<<<<<<<<<<<< + * self.p.putFloatNonBlocking(k, val) + * + */ + /*finally:*/ { + /*normal exit:*/{ + #ifdef WITH_THREAD + __Pyx_FastGIL_Forget(); + Py_BLOCK_THREADS + #endif + goto __pyx_L5; + } + __pyx_L5:; + } + } + + /* "common/params_pyx.pyx":143 + * self.p.putIntNonBlocking(k, val) + * + * def put_float_nonblocking(self, key, float val): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * with nogil: + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("common.params_pyx.Params.put_float_nonblocking", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/params_pyx.pyx":148 + * self.p.putFloatNonBlocking(k, val) + * + * def remove(self, key): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * with nogil: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_10params_pyx_6Params_33remove(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_10params_pyx_6Params_33remove = {"remove", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_33remove, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_10params_pyx_6Params_33remove(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_key = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("remove (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_key,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_key)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 148, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "remove") < 0)) __PYX_ERR(0, 148, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_key = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("remove", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 148, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("common.params_pyx.Params.remove", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_10params_pyx_6Params_32remove(((struct __pyx_obj_6common_10params_pyx_Params *)__pyx_v_self), __pyx_v_key); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_10params_pyx_6Params_32remove(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key) { + std::string __pyx_v_k; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + std::string __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("remove", 1); + + /* "common/params_pyx.pyx":149 + * + * def remove(self, key): + * cdef string k = self.check_key(key) # <<<<<<<<<<<<<< + * with nogil: + * self.p.remove(k) + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_check_key); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 149, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_key}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 149, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_t_5 = __pyx_convert_string_from_py_std__in_string(__pyx_t_1); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 149, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_k = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_5); + + /* "common/params_pyx.pyx":150 + * def remove(self, key): + * cdef string k = self.check_key(key) + * with nogil: # <<<<<<<<<<<<<< + * self.p.remove(k) + * + */ + { + #ifdef WITH_THREAD + PyThreadState *_save; + _save = NULL; + Py_UNBLOCK_THREADS + __Pyx_FastGIL_Remember(); + #endif + /*try:*/ { + + /* "common/params_pyx.pyx":151 + * cdef string k = self.check_key(key) + * with nogil: + * self.p.remove(k) # <<<<<<<<<<<<<< + * + * def get_param_path(self, key=""): + */ + (void)(__pyx_v_self->p->remove(__pyx_v_k)); + } + + /* "common/params_pyx.pyx":150 + * def remove(self, key): + * cdef string k = self.check_key(key) + * with nogil: # <<<<<<<<<<<<<< + * self.p.remove(k) + * + */ + /*finally:*/ { + /*normal exit:*/{ + #ifdef WITH_THREAD + __Pyx_FastGIL_Forget(); + Py_BLOCK_THREADS + #endif + goto __pyx_L5; + } + __pyx_L5:; + } + } + + /* "common/params_pyx.pyx":148 + * self.p.putFloatNonBlocking(k, val) + * + * def remove(self, key): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * with nogil: + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("common.params_pyx.Params.remove", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/params_pyx.pyx":153 + * self.p.remove(k) + * + * def get_param_path(self, key=""): # <<<<<<<<<<<<<< + * cdef string key_bytes = ensure_bytes(key) + * return self.p.getParamPath(key_bytes).decode("utf-8") + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_10params_pyx_6Params_35get_param_path(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_10params_pyx_6Params_35get_param_path = {"get_param_path", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_35get_param_path, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_10params_pyx_6Params_35get_param_path(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_key = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("get_param_path (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_key,0}; + values[0] = __Pyx_Arg_NewRef_FASTCALL(((PyObject *)__pyx_kp_u_)); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_key); + if (value) { values[0] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 153, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "get_param_path") < 0)) __PYX_ERR(0, 153, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_key = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("get_param_path", 0, 0, 1, __pyx_nargs); __PYX_ERR(0, 153, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("common.params_pyx.Params.get_param_path", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_10params_pyx_6Params_34get_param_path(((struct __pyx_obj_6common_10params_pyx_Params *)__pyx_v_self), __pyx_v_key); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_10params_pyx_6Params_34get_param_path(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, PyObject *__pyx_v_key) { + std::string __pyx_v_key_bytes; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + std::string __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_param_path", 1); + + /* "common/params_pyx.pyx":154 + * + * def get_param_path(self, key=""): + * cdef string key_bytes = ensure_bytes(key) # <<<<<<<<<<<<<< + * return self.p.getParamPath(key_bytes).decode("utf-8") + * + */ + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_ensure_bytes); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 154, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (unlikely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_key}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 154, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_t_5 = __pyx_convert_string_from_py_std__in_string(__pyx_t_1); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 154, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_key_bytes = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_5); + + /* "common/params_pyx.pyx":155 + * def get_param_path(self, key=""): + * cdef string key_bytes = ensure_bytes(key) + * return self.p.getParamPath(key_bytes).decode("utf-8") # <<<<<<<<<<<<<< + * + * def all_keys(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_decode_cpp_string(__pyx_v_self->p->getParamPath(__pyx_v_key_bytes), 0, PY_SSIZE_T_MAX, NULL, NULL, PyUnicode_DecodeUTF8); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 155, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "common/params_pyx.pyx":153 + * self.p.remove(k) + * + * def get_param_path(self, key=""): # <<<<<<<<<<<<<< + * cdef string key_bytes = ensure_bytes(key) + * return self.p.getParamPath(key_bytes).decode("utf-8") + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("common.params_pyx.Params.get_param_path", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/params_pyx.pyx":157 + * return self.p.getParamPath(key_bytes).decode("utf-8") + * + * def all_keys(self): # <<<<<<<<<<<<<< + * return self.p.allKeys() + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_10params_pyx_6Params_37all_keys(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_10params_pyx_6Params_37all_keys = {"all_keys", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_37all_keys, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_10params_pyx_6Params_37all_keys(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("all_keys (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("all_keys", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "all_keys", 0))) return NULL; + __pyx_r = __pyx_pf_6common_10params_pyx_6Params_36all_keys(((struct __pyx_obj_6common_10params_pyx_Params *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_10params_pyx_6Params_36all_keys(struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("all_keys", 1); + + /* "common/params_pyx.pyx":158 + * + * def all_keys(self): + * return self.p.allKeys() # <<<<<<<<<<<<<< + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __pyx_convert_vector_to_py_std_3a__3a_string(__pyx_v_self->p->allKeys()); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 158, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "common/params_pyx.pyx":157 + * return self.p.getParamPath(key_bytes).decode("utf-8") + * + * def all_keys(self): # <<<<<<<<<<<<<< + * return self.p.allKeys() + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("common.params_pyx.Params.all_keys", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_10params_pyx_6Params_39__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_10params_pyx_6Params_39__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_39__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_10params_pyx_6Params_39__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_6common_10params_pyx_6Params_38__reduce_cython__(((struct __pyx_obj_6common_10params_pyx_Params *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_10params_pyx_6Params_38__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("common.params_pyx.Params.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_10params_pyx_6Params_41__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_10params_pyx_6Params_41__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_41__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_10params_pyx_6Params_41__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("common.params_pyx.Params.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_10params_pyx_6Params_40__setstate_cython__(((struct __pyx_obj_6common_10params_pyx_Params *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_10params_pyx_6Params_40__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6common_10params_pyx_Params *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("common.params_pyx.Params.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_tp_new_6common_10params_pyx_Params(PyTypeObject *t, PyObject *a, PyObject *k) { + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + if (unlikely(__pyx_pw_6common_10params_pyx_6Params_1__cinit__(o, a, k) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static void __pyx_tp_dealloc_6common_10params_pyx_Params(PyObject *o) { + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_6common_10params_pyx_Params) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_pw_6common_10params_pyx_6Params_3__dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} + +static PyMethodDef __pyx_methods_6common_10params_pyx_Params[] = { + {"clear_all", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_5clear_all, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"check_key", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_7check_key, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"get", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_9get, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"get_bool", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_11get_bool, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"get_int", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_13get_int, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"get_float", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_15get_float, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"put", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_17put, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_6common_10params_pyx_6Params_16put}, + {"put_bool", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_19put_bool, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"put_int", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_21put_int, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"put_float", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_23put_float, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"put_nonblocking", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_25put_nonblocking, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"put_bool_nonblocking", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_27put_bool_nonblocking, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"put_int_nonblocking", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_29put_int_nonblocking, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"put_float_nonblocking", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_31put_float_nonblocking, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"remove", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_33remove, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"get_param_path", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_35get_param_path, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"all_keys", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_37all_keys, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_39__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_10params_pyx_6Params_41__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_6common_10params_pyx_Params_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_6common_10params_pyx_Params}, + {Py_tp_methods, (void *)__pyx_methods_6common_10params_pyx_Params}, + {Py_tp_new, (void *)__pyx_tp_new_6common_10params_pyx_Params}, + {0, 0}, +}; +static PyType_Spec __pyx_type_6common_10params_pyx_Params_spec = { + "common.params_pyx.Params", + sizeof(struct __pyx_obj_6common_10params_pyx_Params), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, + __pyx_type_6common_10params_pyx_Params_slots, +}; +#else + +static PyTypeObject __pyx_type_6common_10params_pyx_Params = { + PyVarObject_HEAD_INIT(0, 0) + "common.params_pyx.""Params", /*tp_name*/ + sizeof(struct __pyx_obj_6common_10params_pyx_Params), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_6common_10params_pyx_Params, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, /*tp_flags*/ + 0, /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_6common_10params_pyx_Params, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_6common_10params_pyx_Params, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static int __pyx_tp_traverse___Pyx_EnumMeta(PyObject *o, visitproc v, void *a) { + int e; + if (!(&PyType_Type)->tp_traverse); else { e = (&PyType_Type)->tp_traverse(o,v,a); if (e) return e; } + return 0; +} + +static int __pyx_tp_clear___Pyx_EnumMeta(PyObject *o) { + if (!(&PyType_Type)->tp_clear); else (&PyType_Type)->tp_clear(o); + return 0; +} +static PyObject *__pyx_sq_item___Pyx_EnumMeta(PyObject *o, Py_ssize_t i) { + PyObject *r; + PyObject *x = PyInt_FromSsize_t(i); if(!x) return 0; + r = Py_TYPE(o)->tp_as_mapping->mp_subscript(o, x); + Py_DECREF(x); + return r; +} + +static PyMethodDef __pyx_methods___Pyx_EnumMeta[] = { + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_8EnumBase_14__Pyx_EnumMeta_7__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_8EnumBase_14__Pyx_EnumMeta_9__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __Pyx_EnumMeta_slots[] = { + {Py_sq_item, (void *)__pyx_sq_item___Pyx_EnumMeta}, + {Py_mp_subscript, (void *)__pyx_pw_8EnumBase_14__Pyx_EnumMeta_5__getitem__}, + {Py_tp_traverse, (void *)__pyx_tp_traverse___Pyx_EnumMeta}, + {Py_tp_clear, (void *)__pyx_tp_clear___Pyx_EnumMeta}, + {Py_tp_iter, (void *)__pyx_pw_8EnumBase_14__Pyx_EnumMeta_3__iter__}, + {Py_tp_methods, (void *)__pyx_methods___Pyx_EnumMeta}, + {Py_tp_init, (void *)__pyx_pw_8EnumBase_14__Pyx_EnumMeta_1__init__}, + {0, 0}, +}; +static PyType_Spec __Pyx_EnumMeta_spec = { + "common.params_pyx.__Pyx_EnumMeta", + sizeof(struct __pyx_obj___Pyx_EnumMeta), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_HAVE_FINALIZE, + __Pyx_EnumMeta_slots, +}; +#else + +static PySequenceMethods __pyx_tp_as_sequence___Pyx_EnumMeta = { + 0, /*sq_length*/ + 0, /*sq_concat*/ + 0, /*sq_repeat*/ + __pyx_sq_item___Pyx_EnumMeta, /*sq_item*/ + 0, /*sq_slice*/ + 0, /*sq_ass_item*/ + 0, /*sq_ass_slice*/ + 0, /*sq_contains*/ + 0, /*sq_inplace_concat*/ + 0, /*sq_inplace_repeat*/ +}; + +static PyMappingMethods __pyx_tp_as_mapping___Pyx_EnumMeta = { + 0, /*mp_length*/ + __pyx_pw_8EnumBase_14__Pyx_EnumMeta_5__getitem__, /*mp_subscript*/ + 0, /*mp_ass_subscript*/ +}; + +static PyTypeObject __Pyx_EnumMeta = { + PyVarObject_HEAD_INIT(0, 0) + "common.params_pyx.""__Pyx_EnumMeta", /*tp_name*/ + sizeof(struct __pyx_obj___Pyx_EnumMeta), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + 0, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + &__pyx_tp_as_sequence___Pyx_EnumMeta, /*tp_as_sequence*/ + &__pyx_tp_as_mapping___Pyx_EnumMeta, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_HAVE_FINALIZE, /*tp_flags*/ + 0, /*tp_doc*/ + __pyx_tp_traverse___Pyx_EnumMeta, /*tp_traverse*/ + __pyx_tp_clear___Pyx_EnumMeta, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + __pyx_pw_8EnumBase_14__Pyx_EnumMeta_3__iter__, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods___Pyx_EnumMeta, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + __pyx_pw_8EnumBase_14__Pyx_EnumMeta_1__init__, /*tp_init*/ + 0, /*tp_alloc*/ + 0, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyMethodDef __pyx_methods[] = { + {0, 0, 0, 0} +}; +#ifndef CYTHON_SMALL_CODE +#if defined(__clang__) + #define CYTHON_SMALL_CODE +#elif defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 3)) + #define CYTHON_SMALL_CODE __attribute__((cold)) +#else + #define CYTHON_SMALL_CODE +#endif +#endif +/* #### Code section: pystring_table ### */ + +static int __Pyx_CreateStringTabAndInitStrings(void) { + __Pyx_StringTabEntry __pyx_string_tab[] = { + {&__pyx_kp_s_, __pyx_k_, sizeof(__pyx_k_), 0, 0, 1, 0}, + {&__pyx_kp_u_, __pyx_k_, sizeof(__pyx_k_), 0, 1, 0, 0}, + {&__pyx_n_s_ALL, __pyx_k_ALL, sizeof(__pyx_k_ALL), 0, 0, 1, 1}, + {&__pyx_n_s_CLEAR_ON_MANAGER_START, __pyx_k_CLEAR_ON_MANAGER_START, sizeof(__pyx_k_CLEAR_ON_MANAGER_START), 0, 0, 1, 1}, + {&__pyx_n_s_CLEAR_ON_OFFROAD_TRANSITION, __pyx_k_CLEAR_ON_OFFROAD_TRANSITION, sizeof(__pyx_k_CLEAR_ON_OFFROAD_TRANSITION), 0, 0, 1, 1}, + {&__pyx_n_s_CLEAR_ON_ONROAD_TRANSITION, __pyx_k_CLEAR_ON_ONROAD_TRANSITION, sizeof(__pyx_k_CLEAR_ON_ONROAD_TRANSITION), 0, 0, 1, 1}, + {&__pyx_n_s_DEVELOPMENT_ONLY, __pyx_k_DEVELOPMENT_ONLY, sizeof(__pyx_k_DEVELOPMENT_ONLY), 0, 0, 1, 1}, + {&__pyx_n_s_EnumBase, __pyx_k_EnumBase, sizeof(__pyx_k_EnumBase), 0, 0, 1, 1}, + {&__pyx_n_s_EnumType, __pyx_k_EnumType, sizeof(__pyx_k_EnumType), 0, 0, 1, 1}, + {&__pyx_kp_s_Incompatible_checksums_0x_x_vs_0, __pyx_k_Incompatible_checksums_0x_x_vs_0, sizeof(__pyx_k_Incompatible_checksums_0x_x_vs_0), 0, 0, 1, 0}, + {&__pyx_n_s_IntEnum, __pyx_k_IntEnum, sizeof(__pyx_k_IntEnum), 0, 0, 1, 1}, + {&__pyx_n_s_IntFlag, __pyx_k_IntFlag, sizeof(__pyx_k_IntFlag), 0, 0, 1, 1}, + {&__pyx_n_s_KeyboardInterrupt, __pyx_k_KeyboardInterrupt, sizeof(__pyx_k_KeyboardInterrupt), 0, 0, 1, 1}, + {&__pyx_n_s_MemoryError, __pyx_k_MemoryError, sizeof(__pyx_k_MemoryError), 0, 0, 1, 1}, + {&__pyx_n_s_OrderedDict, __pyx_k_OrderedDict, sizeof(__pyx_k_OrderedDict), 0, 0, 1, 1}, + {&__pyx_n_s_PERSISTENT, __pyx_k_PERSISTENT, sizeof(__pyx_k_PERSISTENT), 0, 0, 1, 1}, + {&__pyx_n_s_ParamKeyType, __pyx_k_ParamKeyType, sizeof(__pyx_k_ParamKeyType), 0, 0, 1, 1}, + {&__pyx_n_s_Params, __pyx_k_Params, sizeof(__pyx_k_Params), 0, 0, 1, 1}, + {&__pyx_n_s_Params___reduce_cython, __pyx_k_Params___reduce_cython, sizeof(__pyx_k_Params___reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_Params___setstate_cython, __pyx_k_Params___setstate_cython, sizeof(__pyx_k_Params___setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_Params_all_keys, __pyx_k_Params_all_keys, sizeof(__pyx_k_Params_all_keys), 0, 0, 1, 1}, + {&__pyx_n_s_Params_check_key, __pyx_k_Params_check_key, sizeof(__pyx_k_Params_check_key), 0, 0, 1, 1}, + {&__pyx_n_s_Params_clear_all, __pyx_k_Params_clear_all, sizeof(__pyx_k_Params_clear_all), 0, 0, 1, 1}, + {&__pyx_n_s_Params_get, __pyx_k_Params_get, sizeof(__pyx_k_Params_get), 0, 0, 1, 1}, + {&__pyx_n_s_Params_get_bool, __pyx_k_Params_get_bool, sizeof(__pyx_k_Params_get_bool), 0, 0, 1, 1}, + {&__pyx_n_s_Params_get_float, __pyx_k_Params_get_float, sizeof(__pyx_k_Params_get_float), 0, 0, 1, 1}, + {&__pyx_n_s_Params_get_int, __pyx_k_Params_get_int, sizeof(__pyx_k_Params_get_int), 0, 0, 1, 1}, + {&__pyx_n_s_Params_get_param_path, __pyx_k_Params_get_param_path, sizeof(__pyx_k_Params_get_param_path), 0, 0, 1, 1}, + {&__pyx_n_s_Params_put, __pyx_k_Params_put, sizeof(__pyx_k_Params_put), 0, 0, 1, 1}, + {&__pyx_n_s_Params_put_bool, __pyx_k_Params_put_bool, sizeof(__pyx_k_Params_put_bool), 0, 0, 1, 1}, + {&__pyx_n_s_Params_put_bool_nonblocking, __pyx_k_Params_put_bool_nonblocking, sizeof(__pyx_k_Params_put_bool_nonblocking), 0, 0, 1, 1}, + {&__pyx_n_s_Params_put_float, __pyx_k_Params_put_float, sizeof(__pyx_k_Params_put_float), 0, 0, 1, 1}, + {&__pyx_n_s_Params_put_float_nonblocking, __pyx_k_Params_put_float_nonblocking, sizeof(__pyx_k_Params_put_float_nonblocking), 0, 0, 1, 1}, + {&__pyx_n_s_Params_put_int, __pyx_k_Params_put_int, sizeof(__pyx_k_Params_put_int), 0, 0, 1, 1}, + {&__pyx_n_s_Params_put_int_nonblocking, __pyx_k_Params_put_int_nonblocking, sizeof(__pyx_k_Params_put_int_nonblocking), 0, 0, 1, 1}, + {&__pyx_n_s_Params_put_nonblocking, __pyx_k_Params_put_nonblocking, sizeof(__pyx_k_Params_put_nonblocking), 0, 0, 1, 1}, + {&__pyx_n_s_Params_remove, __pyx_k_Params_remove, sizeof(__pyx_k_Params_remove), 0, 0, 1, 1}, + {&__pyx_n_s_PickleError, __pyx_k_PickleError, sizeof(__pyx_k_PickleError), 0, 0, 1, 1}, + {&__pyx_n_s_Pyx_EnumBase, __pyx_k_Pyx_EnumBase, sizeof(__pyx_k_Pyx_EnumBase), 0, 0, 1, 1}, + {&__pyx_n_s_Pyx_EnumBase___new, __pyx_k_Pyx_EnumBase___new, sizeof(__pyx_k_Pyx_EnumBase___new), 0, 0, 1, 1}, + {&__pyx_n_s_Pyx_EnumBase___repr, __pyx_k_Pyx_EnumBase___repr, sizeof(__pyx_k_Pyx_EnumBase___repr), 0, 0, 1, 1}, + {&__pyx_n_s_Pyx_EnumBase___str, __pyx_k_Pyx_EnumBase___str, sizeof(__pyx_k_Pyx_EnumBase___str), 0, 0, 1, 1}, + {&__pyx_n_s_Pyx_EnumMeta___reduce_cython, __pyx_k_Pyx_EnumMeta___reduce_cython, sizeof(__pyx_k_Pyx_EnumMeta___reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_Pyx_EnumMeta___setstate_cython, __pyx_k_Pyx_EnumMeta___setstate_cython, sizeof(__pyx_k_Pyx_EnumMeta___setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_Pyx_FlagBase, __pyx_k_Pyx_FlagBase, sizeof(__pyx_k_Pyx_FlagBase), 0, 0, 1, 1}, + {&__pyx_n_s_Pyx_FlagBase___new, __pyx_k_Pyx_FlagBase___new, sizeof(__pyx_k_Pyx_FlagBase___new), 0, 0, 1, 1}, + {&__pyx_n_s_Pyx_FlagBase___repr, __pyx_k_Pyx_FlagBase___repr, sizeof(__pyx_k_Pyx_FlagBase___repr), 0, 0, 1, 1}, + {&__pyx_n_s_Pyx_FlagBase___str, __pyx_k_Pyx_FlagBase___str, sizeof(__pyx_k_Pyx_FlagBase___str), 0, 0, 1, 1}, + {&__pyx_n_s_TypeError, __pyx_k_TypeError, sizeof(__pyx_k_TypeError), 0, 0, 1, 1}, + {&__pyx_n_s_UnknownKeyName, __pyx_k_UnknownKeyName, sizeof(__pyx_k_UnknownKeyName), 0, 0, 1, 1}, + {&__pyx_kp_s_Unknown_enum_value_s, __pyx_k_Unknown_enum_value_s, sizeof(__pyx_k_Unknown_enum_value_s), 0, 0, 1, 0}, + {&__pyx_n_s_ValueError, __pyx_k_ValueError, sizeof(__pyx_k_ValueError), 0, 0, 1, 1}, + {&__pyx_kp_u__3, __pyx_k__3, sizeof(__pyx_k__3), 0, 1, 0, 0}, + {&__pyx_n_s__52, __pyx_k__52, sizeof(__pyx_k__52), 0, 0, 1, 1}, + {&__pyx_n_s_all_keys, __pyx_k_all_keys, sizeof(__pyx_k_all_keys), 0, 0, 1, 1}, + {&__pyx_n_s_asyncio_coroutines, __pyx_k_asyncio_coroutines, sizeof(__pyx_k_asyncio_coroutines), 0, 0, 1, 1}, + {&__pyx_n_s_block, __pyx_k_block, sizeof(__pyx_k_block), 0, 0, 1, 1}, + {&__pyx_n_s_check_key, __pyx_k_check_key, sizeof(__pyx_k_check_key), 0, 0, 1, 1}, + {&__pyx_n_s_class, __pyx_k_class, sizeof(__pyx_k_class), 0, 0, 1, 1}, + {&__pyx_n_s_class_getitem, __pyx_k_class_getitem, sizeof(__pyx_k_class_getitem), 0, 0, 1, 1}, + {&__pyx_n_s_clear_all, __pyx_k_clear_all, sizeof(__pyx_k_clear_all), 0, 0, 1, 1}, + {&__pyx_n_s_cline_in_traceback, __pyx_k_cline_in_traceback, sizeof(__pyx_k_cline_in_traceback), 0, 0, 1, 1}, + {&__pyx_n_s_cls, __pyx_k_cls, sizeof(__pyx_k_cls), 0, 0, 1, 1}, + {&__pyx_n_s_collections, __pyx_k_collections, sizeof(__pyx_k_collections), 0, 0, 1, 1}, + {&__pyx_kp_s_common_params_pyx, __pyx_k_common_params_pyx, sizeof(__pyx_k_common_params_pyx), 0, 0, 1, 0}, + {&__pyx_kp_s_common_params_pyx_pyx, __pyx_k_common_params_pyx_pyx, sizeof(__pyx_k_common_params_pyx_pyx), 0, 0, 1, 0}, + {&__pyx_n_s_d, __pyx_k_d, sizeof(__pyx_k_d), 0, 0, 1, 1}, + {&__pyx_n_s_dat, __pyx_k_dat, sizeof(__pyx_k_dat), 0, 0, 1, 1}, + {&__pyx_n_s_dat_bytes, __pyx_k_dat_bytes, sizeof(__pyx_k_dat_bytes), 0, 0, 1, 1}, + {&__pyx_n_s_dct, __pyx_k_dct, sizeof(__pyx_k_dct), 0, 0, 1, 1}, + {&__pyx_n_s_decode, __pyx_k_decode, sizeof(__pyx_k_decode), 0, 0, 1, 1}, + {&__pyx_n_s_dict, __pyx_k_dict, sizeof(__pyx_k_dict), 0, 0, 1, 1}, + {&__pyx_n_s_dict_2, __pyx_k_dict_2, sizeof(__pyx_k_dict_2), 0, 0, 1, 1}, + {&__pyx_kp_u_disable, __pyx_k_disable, sizeof(__pyx_k_disable), 0, 1, 0, 0}, + {&__pyx_n_s_doc, __pyx_k_doc, sizeof(__pyx_k_doc), 0, 0, 1, 1}, + {&__pyx_kp_u_enable, __pyx_k_enable, sizeof(__pyx_k_enable), 0, 1, 0, 0}, + {&__pyx_n_s_encode, __pyx_k_encode, sizeof(__pyx_k_encode), 0, 0, 1, 1}, + {&__pyx_n_s_encoding, __pyx_k_encoding, sizeof(__pyx_k_encoding), 0, 0, 1, 1}, + {&__pyx_n_s_ensure_bytes, __pyx_k_ensure_bytes, sizeof(__pyx_k_ensure_bytes), 0, 0, 1, 1}, + {&__pyx_n_s_enum, __pyx_k_enum, sizeof(__pyx_k_enum), 0, 0, 1, 1}, + {&__pyx_kp_u_gc, __pyx_k_gc, sizeof(__pyx_k_gc), 0, 1, 0, 0}, + {&__pyx_n_s_get, __pyx_k_get, sizeof(__pyx_k_get), 0, 0, 1, 1}, + {&__pyx_n_s_get_bool, __pyx_k_get_bool, sizeof(__pyx_k_get_bool), 0, 0, 1, 1}, + {&__pyx_n_s_get_float, __pyx_k_get_float, sizeof(__pyx_k_get_float), 0, 0, 1, 1}, + {&__pyx_n_s_get_int, __pyx_k_get_int, sizeof(__pyx_k_get_int), 0, 0, 1, 1}, + {&__pyx_n_s_get_param_path, __pyx_k_get_param_path, sizeof(__pyx_k_get_param_path), 0, 0, 1, 1}, + {&__pyx_n_s_getstate, __pyx_k_getstate, sizeof(__pyx_k_getstate), 0, 0, 1, 1}, + {&__pyx_n_s_import, __pyx_k_import, sizeof(__pyx_k_import), 0, 0, 1, 1}, + {&__pyx_n_s_init, __pyx_k_init, sizeof(__pyx_k_init), 0, 0, 1, 1}, + {&__pyx_n_s_init_subclass, __pyx_k_init_subclass, sizeof(__pyx_k_init_subclass), 0, 0, 1, 1}, + {&__pyx_n_s_is_coroutine, __pyx_k_is_coroutine, sizeof(__pyx_k_is_coroutine), 0, 0, 1, 1}, + {&__pyx_kp_u_isenabled, __pyx_k_isenabled, sizeof(__pyx_k_isenabled), 0, 1, 0, 0}, + {&__pyx_n_s_k, __pyx_k_k, sizeof(__pyx_k_k), 0, 0, 1, 1}, + {&__pyx_n_s_key, __pyx_k_key, sizeof(__pyx_k_key), 0, 0, 1, 1}, + {&__pyx_n_s_key_bytes, __pyx_k_key_bytes, sizeof(__pyx_k_key_bytes), 0, 0, 1, 1}, + {&__pyx_n_s_main, __pyx_k_main, sizeof(__pyx_k_main), 0, 0, 1, 1}, + {&__pyx_n_s_member_names, __pyx_k_member_names, sizeof(__pyx_k_member_names), 0, 0, 1, 1}, + {&__pyx_n_s_members, __pyx_k_members, sizeof(__pyx_k_members), 0, 0, 1, 1}, + {&__pyx_n_s_metaclass, __pyx_k_metaclass, sizeof(__pyx_k_metaclass), 0, 0, 1, 1}, + {&__pyx_n_s_module, __pyx_k_module, sizeof(__pyx_k_module), 0, 0, 1, 1}, + {&__pyx_n_s_module_2, __pyx_k_module_2, sizeof(__pyx_k_module_2), 0, 0, 1, 1}, + {&__pyx_n_s_mro_entries, __pyx_k_mro_entries, sizeof(__pyx_k_mro_entries), 0, 0, 1, 1}, + {&__pyx_n_s_name, __pyx_k_name, sizeof(__pyx_k_name), 0, 0, 1, 1}, + {&__pyx_n_s_name_2, __pyx_k_name_2, sizeof(__pyx_k_name_2), 0, 0, 1, 1}, + {&__pyx_n_s_new, __pyx_k_new, sizeof(__pyx_k_new), 0, 0, 1, 1}, + {&__pyx_kp_s_no_default___reduce___due_to_non, __pyx_k_no_default___reduce___due_to_non, sizeof(__pyx_k_no_default___reduce___due_to_non), 0, 0, 1, 0}, + {&__pyx_n_s_parents, __pyx_k_parents, sizeof(__pyx_k_parents), 0, 0, 1, 1}, + {&__pyx_n_s_pickle, __pyx_k_pickle, sizeof(__pyx_k_pickle), 0, 0, 1, 1}, + {&__pyx_n_s_prepare, __pyx_k_prepare, sizeof(__pyx_k_prepare), 0, 0, 1, 1}, + {&__pyx_n_s_put, __pyx_k_put, sizeof(__pyx_k_put), 0, 0, 1, 1}, + {&__pyx_n_s_put_bool, __pyx_k_put_bool, sizeof(__pyx_k_put_bool), 0, 0, 1, 1}, + {&__pyx_n_s_put_bool_nonblocking, __pyx_k_put_bool_nonblocking, sizeof(__pyx_k_put_bool_nonblocking), 0, 0, 1, 1}, + {&__pyx_n_s_put_float, __pyx_k_put_float, sizeof(__pyx_k_put_float), 0, 0, 1, 1}, + {&__pyx_n_s_put_float_nonblocking, __pyx_k_put_float_nonblocking, sizeof(__pyx_k_put_float_nonblocking), 0, 0, 1, 1}, + {&__pyx_n_s_put_int, __pyx_k_put_int, sizeof(__pyx_k_put_int), 0, 0, 1, 1}, + {&__pyx_n_s_put_int_nonblocking, __pyx_k_put_int_nonblocking, sizeof(__pyx_k_put_int_nonblocking), 0, 0, 1, 1}, + {&__pyx_n_s_put_nonblocking, __pyx_k_put_nonblocking, sizeof(__pyx_k_put_nonblocking), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_PickleError, __pyx_k_pyx_PickleError, sizeof(__pyx_k_pyx_PickleError), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_checksum, __pyx_k_pyx_checksum, sizeof(__pyx_k_pyx_checksum), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_result, __pyx_k_pyx_result, sizeof(__pyx_k_pyx_result), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_state, __pyx_k_pyx_state, sizeof(__pyx_k_pyx_state), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_type, __pyx_k_pyx_type, sizeof(__pyx_k_pyx_type), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_unpickle___Pyx_EnumMeta, __pyx_k_pyx_unpickle___Pyx_EnumMeta, sizeof(__pyx_k_pyx_unpickle___Pyx_EnumMeta), 0, 0, 1, 1}, + {&__pyx_n_s_qualname, __pyx_k_qualname, sizeof(__pyx_k_qualname), 0, 0, 1, 1}, + {&__pyx_n_s_r, __pyx_k_r, sizeof(__pyx_k_r), 0, 0, 1, 1}, + {&__pyx_n_s_range, __pyx_k_range, sizeof(__pyx_k_range), 0, 0, 1, 1}, + {&__pyx_n_s_reduce, __pyx_k_reduce, sizeof(__pyx_k_reduce), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_cython, __pyx_k_reduce_cython, sizeof(__pyx_k_reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_ex, __pyx_k_reduce_ex, sizeof(__pyx_k_reduce_ex), 0, 0, 1, 1}, + {&__pyx_n_s_remove, __pyx_k_remove, sizeof(__pyx_k_remove), 0, 0, 1, 1}, + {&__pyx_n_s_repr, __pyx_k_repr, sizeof(__pyx_k_repr), 0, 0, 1, 1}, + {&__pyx_n_s_res, __pyx_k_res, sizeof(__pyx_k_res), 0, 0, 1, 1}, + {&__pyx_kp_s_s_s, __pyx_k_s_s, sizeof(__pyx_k_s_s), 0, 0, 1, 0}, + {&__pyx_kp_s_s_s_d, __pyx_k_s_s_d, sizeof(__pyx_k_s_s_d), 0, 0, 1, 0}, + {&__pyx_n_s_self, __pyx_k_self, sizeof(__pyx_k_self), 0, 0, 1, 1}, + {&__pyx_n_s_set_name, __pyx_k_set_name, sizeof(__pyx_k_set_name), 0, 0, 1, 1}, + {&__pyx_n_s_setstate, __pyx_k_setstate, sizeof(__pyx_k_setstate), 0, 0, 1, 1}, + {&__pyx_n_s_setstate_cython, __pyx_k_setstate_cython, sizeof(__pyx_k_setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_state, __pyx_k_state, sizeof(__pyx_k_state), 0, 0, 1, 1}, + {&__pyx_n_s_str, __pyx_k_str, sizeof(__pyx_k_str), 0, 0, 1, 1}, + {&__pyx_kp_s_stringsource, __pyx_k_stringsource, sizeof(__pyx_k_stringsource), 0, 0, 1, 0}, + {&__pyx_n_s_super, __pyx_k_super, sizeof(__pyx_k_super), 0, 0, 1, 1}, + {&__pyx_n_s_test, __pyx_k_test, sizeof(__pyx_k_test), 0, 0, 1, 1}, + {&__pyx_n_s_tx_type, __pyx_k_tx_type, sizeof(__pyx_k_tx_type), 0, 0, 1, 1}, + {&__pyx_n_s_update, __pyx_k_update, sizeof(__pyx_k_update), 0, 0, 1, 1}, + {&__pyx_n_s_use_setstate, __pyx_k_use_setstate, sizeof(__pyx_k_use_setstate), 0, 0, 1, 1}, + {&__pyx_n_s_v, __pyx_k_v, sizeof(__pyx_k_v), 0, 0, 1, 1}, + {&__pyx_n_s_val, __pyx_k_val, sizeof(__pyx_k_val), 0, 0, 1, 1}, + {&__pyx_n_s_value, __pyx_k_value, sizeof(__pyx_k_value), 0, 0, 1, 1}, + {&__pyx_n_s_values, __pyx_k_values, sizeof(__pyx_k_values), 0, 0, 1, 1}, + {0, 0, 0, 0, 0, 0, 0} + }; + return __Pyx_InitStrings(__pyx_string_tab); +} +/* #### Code section: cached_builtins ### */ +static CYTHON_SMALL_CODE int __Pyx_InitCachedBuiltins(void) { + __pyx_builtin_KeyboardInterrupt = __Pyx_GetBuiltinName(__pyx_n_s_KeyboardInterrupt); if (!__pyx_builtin_KeyboardInterrupt) __PYX_ERR(0, 73, __pyx_L1_error) + __pyx_builtin_TypeError = __Pyx_GetBuiltinName(__pyx_n_s_TypeError); if (!__pyx_builtin_TypeError) __PYX_ERR(1, 2, __pyx_L1_error) + __pyx_builtin_MemoryError = __Pyx_GetBuiltinName(__pyx_n_s_MemoryError); if (!__pyx_builtin_MemoryError) __PYX_ERR(1, 68, __pyx_L1_error) + __pyx_builtin_range = __Pyx_GetBuiltinName(__pyx_n_s_range); if (!__pyx_builtin_range) __PYX_ERR(1, 76, __pyx_L1_error) + __pyx_builtin_ValueError = __Pyx_GetBuiltinName(__pyx_n_s_ValueError); if (!__pyx_builtin_ValueError) __PYX_ERR(1, 33, __pyx_L1_error) + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: cached_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_InitCachedConstants", 0); + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0xe3b0c44, 0xda39a3e, 0xd41d8cd): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0xe3b0c44, 0xda39a3e, 0xd41d8cd) = ())" % __pyx_checksum + */ + __pyx_tuple__2 = PyTuple_Pack(3, __pyx_int_238750788, __pyx_int_228825662, __pyx_int_222419149); if (unlikely(!__pyx_tuple__2)) __PYX_ERR(1, 4, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__2); + __Pyx_GIVEREF(__pyx_tuple__2); + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * cdef tuple state + * cdef object _dict + */ + __pyx_tuple__5 = PyTuple_Pack(4, __pyx_n_s_self, __pyx_n_s_state, __pyx_n_s_dict_2, __pyx_n_s_use_setstate); if (unlikely(!__pyx_tuple__5)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__5); + __Pyx_GIVEREF(__pyx_tuple__5); + __pyx_codeobj__6 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 4, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__5, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__6)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "(tree fragment)":16 + * else: + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, state) + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * __pyx_unpickle___Pyx_EnumMeta__set_state(self, __pyx_state) + */ + __pyx_tuple__7 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_pyx_state); if (unlikely(!__pyx_tuple__7)) __PYX_ERR(1, 16, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__7); + __Pyx_GIVEREF(__pyx_tuple__7); + __pyx_codeobj__8 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__7, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 16, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__8)) __PYX_ERR(1, 16, __pyx_L1_error) + + /* "EnumBase":28 + * cdef object __Pyx_EnumBase + * class __Pyx_EnumBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): # <<<<<<<<<<<<<< + * for v in cls: + * if v == value: + */ + __pyx_tuple__9 = PyTuple_Pack(5, __pyx_n_s_cls, __pyx_n_s_value, __pyx_n_s_name, __pyx_n_s_v, __pyx_n_s_res); if (unlikely(!__pyx_tuple__9)) __PYX_ERR(1, 28, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__9); + __Pyx_GIVEREF(__pyx_tuple__9); + __pyx_codeobj__10 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__9, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_new, 28, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__10)) __PYX_ERR(1, 28, __pyx_L1_error) + __pyx_tuple__11 = PyTuple_Pack(1, Py_None); if (unlikely(!__pyx_tuple__11)) __PYX_ERR(1, 28, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__11); + __Pyx_GIVEREF(__pyx_tuple__11); + + /* "EnumBase":39 + * cls.__members__[name] = res + * return res + * def __repr__(self): # <<<<<<<<<<<<<< + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): + */ + __pyx_tuple__12 = PyTuple_Pack(1, __pyx_n_s_self); if (unlikely(!__pyx_tuple__12)) __PYX_ERR(1, 39, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__12); + __Pyx_GIVEREF(__pyx_tuple__12); + __pyx_codeobj__13 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__12, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_repr, 39, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__13)) __PYX_ERR(1, 39, __pyx_L1_error) + + /* "EnumBase":41 + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): # <<<<<<<<<<<<<< + * return "%s.%s" % (self.__class__.__name__, self.name) + * + */ + __pyx_codeobj__14 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__12, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_str, 41, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__14)) __PYX_ERR(1, 41, __pyx_L1_error) + + /* "EnumBase":49 + * cdef object __Pyx_FlagBase + * class __Pyx_FlagBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): # <<<<<<<<<<<<<< + * for v in cls: + * if v == value: + */ + __pyx_codeobj__15 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__9, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_new, 49, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__15)) __PYX_ERR(1, 49, __pyx_L1_error) + + /* "EnumBase":62 + * cls.__members__[name] = res + * return res + * def __repr__(self): # <<<<<<<<<<<<<< + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): + */ + __pyx_codeobj__16 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__12, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_repr, 62, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__16)) __PYX_ERR(1, 62, __pyx_L1_error) + + /* "EnumBase":64 + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): # <<<<<<<<<<<<<< + * return "%s.%s" % (self.__class__.__name__, self.name) + * + */ + __pyx_codeobj__17 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__12, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_str, 64, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__17)) __PYX_ERR(1, 64, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __pyx_unpickle___Pyx_EnumMeta(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + __pyx_tuple__18 = PyTuple_Pack(5, __pyx_n_s_pyx_type, __pyx_n_s_pyx_checksum, __pyx_n_s_pyx_state, __pyx_n_s_pyx_PickleError, __pyx_n_s_pyx_result); if (unlikely(!__pyx_tuple__18)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__18); + __Pyx_GIVEREF(__pyx_tuple__18); + __pyx_codeobj__19 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__18, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_pyx_unpickle___Pyx_EnumMeta, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__19)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "common/params_pyx.pyx":37 + * + * + * def ensure_bytes(v): # <<<<<<<<<<<<<< + * return v.encode() if isinstance(v, str) else v + * + */ + __pyx_tuple__20 = PyTuple_Pack(1, __pyx_n_s_v); if (unlikely(!__pyx_tuple__20)) __PYX_ERR(0, 37, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__20); + __Pyx_GIVEREF(__pyx_tuple__20); + __pyx_codeobj__21 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__20, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_params_pyx_pyx, __pyx_n_s_ensure_bytes, 37, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__21)) __PYX_ERR(0, 37, __pyx_L1_error) + + /* "common/params_pyx.pyx":54 + * del self.p + * + * def clear_all(self, tx_type=ParamKeyType.ALL): # <<<<<<<<<<<<<< + * self.p.clearAll(tx_type) + * + */ + __pyx_tuple__22 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_tx_type); if (unlikely(!__pyx_tuple__22)) __PYX_ERR(0, 54, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__22); + __Pyx_GIVEREF(__pyx_tuple__22); + __pyx_codeobj__23 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__22, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_params_pyx_pyx, __pyx_n_s_clear_all, 54, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__23)) __PYX_ERR(0, 54, __pyx_L1_error) + + /* "common/params_pyx.pyx":57 + * self.p.clearAll(tx_type) + * + * def check_key(self, key): # <<<<<<<<<<<<<< + * key = ensure_bytes(key) + * if not self.p.checkKey(key): + */ + __pyx_tuple__24 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_key); if (unlikely(!__pyx_tuple__24)) __PYX_ERR(0, 57, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__24); + __Pyx_GIVEREF(__pyx_tuple__24); + __pyx_codeobj__25 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__24, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_params_pyx_pyx, __pyx_n_s_check_key, 57, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__25)) __PYX_ERR(0, 57, __pyx_L1_error) + + /* "common/params_pyx.pyx":63 + * return key + * + * def get(self, key, bool block=False, encoding=None): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * cdef string val + */ + __pyx_tuple__26 = PyTuple_Pack(6, __pyx_n_s_self, __pyx_n_s_key, __pyx_n_s_block, __pyx_n_s_encoding, __pyx_n_s_k, __pyx_n_s_val); if (unlikely(!__pyx_tuple__26)) __PYX_ERR(0, 63, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__26); + __Pyx_GIVEREF(__pyx_tuple__26); + __pyx_codeobj__27 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 6, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__26, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_params_pyx_pyx, __pyx_n_s_get, 63, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__27)) __PYX_ERR(0, 63, __pyx_L1_error) + __pyx_tuple__28 = PyTuple_Pack(2, Py_False, Py_None); if (unlikely(!__pyx_tuple__28)) __PYX_ERR(0, 63, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__28); + __Pyx_GIVEREF(__pyx_tuple__28); + + /* "common/params_pyx.pyx":79 + * return val if encoding is None else val.decode(encoding) + * + * def get_bool(self, key, bool block=False): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * cdef bool r + */ + __pyx_tuple__29 = PyTuple_Pack(5, __pyx_n_s_self, __pyx_n_s_key, __pyx_n_s_block, __pyx_n_s_k, __pyx_n_s_r); if (unlikely(!__pyx_tuple__29)) __PYX_ERR(0, 79, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__29); + __Pyx_GIVEREF(__pyx_tuple__29); + __pyx_codeobj__30 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__29, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_params_pyx_pyx, __pyx_n_s_get_bool, 79, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__30)) __PYX_ERR(0, 79, __pyx_L1_error) + __pyx_tuple__31 = PyTuple_Pack(1, Py_False); if (unlikely(!__pyx_tuple__31)) __PYX_ERR(0, 79, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__31); + __Pyx_GIVEREF(__pyx_tuple__31); + + /* "common/params_pyx.pyx":86 + * return r + * + * def get_int(self, key, bool block=False): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * cdef int r + */ + __pyx_codeobj__32 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__29, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_params_pyx_pyx, __pyx_n_s_get_int, 86, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__32)) __PYX_ERR(0, 86, __pyx_L1_error) + + /* "common/params_pyx.pyx":93 + * return r + * + * def get_float(self, key, bool block=False): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * cdef float r + */ + __pyx_codeobj__33 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__29, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_params_pyx_pyx, __pyx_n_s_get_float, 93, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__33)) __PYX_ERR(0, 93, __pyx_L1_error) + + /* "common/params_pyx.pyx":100 + * return r + * + * def put(self, key, dat): # <<<<<<<<<<<<<< + * """ + * Warning: This function blocks until the param is written to disk! + */ + __pyx_tuple__34 = PyTuple_Pack(5, __pyx_n_s_self, __pyx_n_s_key, __pyx_n_s_dat, __pyx_n_s_k, __pyx_n_s_dat_bytes); if (unlikely(!__pyx_tuple__34)) __PYX_ERR(0, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__34); + __Pyx_GIVEREF(__pyx_tuple__34); + __pyx_codeobj__35 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__34, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_params_pyx_pyx, __pyx_n_s_put, 100, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__35)) __PYX_ERR(0, 100, __pyx_L1_error) + + /* "common/params_pyx.pyx":112 + * self.p.put(k, dat_bytes) + * + * def put_bool(self, key, bool val): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * with nogil: + */ + __pyx_tuple__36 = PyTuple_Pack(4, __pyx_n_s_self, __pyx_n_s_key, __pyx_n_s_val, __pyx_n_s_k); if (unlikely(!__pyx_tuple__36)) __PYX_ERR(0, 112, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__36); + __Pyx_GIVEREF(__pyx_tuple__36); + __pyx_codeobj__37 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 4, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__36, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_params_pyx_pyx, __pyx_n_s_put_bool, 112, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__37)) __PYX_ERR(0, 112, __pyx_L1_error) + + /* "common/params_pyx.pyx":117 + * self.p.putBool(k, val) + * + * def put_int(self, key, int val): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * with nogil: + */ + __pyx_codeobj__38 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 4, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__36, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_params_pyx_pyx, __pyx_n_s_put_int, 117, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__38)) __PYX_ERR(0, 117, __pyx_L1_error) + + /* "common/params_pyx.pyx":122 + * self.p.putInt(k, val) + * + * def put_float(self, key, float val): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * with nogil: + */ + __pyx_codeobj__39 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 4, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__36, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_params_pyx_pyx, __pyx_n_s_put_float, 122, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__39)) __PYX_ERR(0, 122, __pyx_L1_error) + + /* "common/params_pyx.pyx":127 + * self.p.putFloat(k, val) + * + * def put_nonblocking(self, key, dat): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * cdef string dat_bytes = ensure_bytes(dat) + */ + __pyx_codeobj__40 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__34, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_params_pyx_pyx, __pyx_n_s_put_nonblocking, 127, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__40)) __PYX_ERR(0, 127, __pyx_L1_error) + + /* "common/params_pyx.pyx":133 + * self.p.putNonBlocking(k, dat_bytes) + * + * def put_bool_nonblocking(self, key, bool val): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * with nogil: + */ + __pyx_codeobj__41 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 4, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__36, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_params_pyx_pyx, __pyx_n_s_put_bool_nonblocking, 133, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__41)) __PYX_ERR(0, 133, __pyx_L1_error) + + /* "common/params_pyx.pyx":138 + * self.p.putBoolNonBlocking(k, val) + * + * def put_int_nonblocking(self, key, int val): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * with nogil: + */ + __pyx_codeobj__42 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 4, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__36, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_params_pyx_pyx, __pyx_n_s_put_int_nonblocking, 138, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__42)) __PYX_ERR(0, 138, __pyx_L1_error) + + /* "common/params_pyx.pyx":143 + * self.p.putIntNonBlocking(k, val) + * + * def put_float_nonblocking(self, key, float val): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * with nogil: + */ + __pyx_codeobj__43 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 4, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__36, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_params_pyx_pyx, __pyx_n_s_put_float_nonblocking, 143, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__43)) __PYX_ERR(0, 143, __pyx_L1_error) + + /* "common/params_pyx.pyx":148 + * self.p.putFloatNonBlocking(k, val) + * + * def remove(self, key): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * with nogil: + */ + __pyx_tuple__44 = PyTuple_Pack(3, __pyx_n_s_self, __pyx_n_s_key, __pyx_n_s_k); if (unlikely(!__pyx_tuple__44)) __PYX_ERR(0, 148, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__44); + __Pyx_GIVEREF(__pyx_tuple__44); + __pyx_codeobj__45 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__44, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_params_pyx_pyx, __pyx_n_s_remove, 148, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__45)) __PYX_ERR(0, 148, __pyx_L1_error) + + /* "common/params_pyx.pyx":153 + * self.p.remove(k) + * + * def get_param_path(self, key=""): # <<<<<<<<<<<<<< + * cdef string key_bytes = ensure_bytes(key) + * return self.p.getParamPath(key_bytes).decode("utf-8") + */ + __pyx_tuple__46 = PyTuple_Pack(3, __pyx_n_s_self, __pyx_n_s_key, __pyx_n_s_key_bytes); if (unlikely(!__pyx_tuple__46)) __PYX_ERR(0, 153, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__46); + __Pyx_GIVEREF(__pyx_tuple__46); + __pyx_codeobj__47 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__46, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_params_pyx_pyx, __pyx_n_s_get_param_path, 153, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__47)) __PYX_ERR(0, 153, __pyx_L1_error) + __pyx_tuple__48 = PyTuple_Pack(1, __pyx_kp_u_); if (unlikely(!__pyx_tuple__48)) __PYX_ERR(0, 153, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__48); + __Pyx_GIVEREF(__pyx_tuple__48); + + /* "common/params_pyx.pyx":157 + * return self.p.getParamPath(key_bytes).decode("utf-8") + * + * def all_keys(self): # <<<<<<<<<<<<<< + * return self.p.allKeys() + */ + __pyx_codeobj__49 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__12, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_params_pyx_pyx, __pyx_n_s_all_keys, 157, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__49)) __PYX_ERR(0, 157, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_codeobj__50 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__12, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__50)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_codeobj__51 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__7, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__51)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_RefNannyFinishContext(); + return -1; +} +/* #### Code section: init_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitConstants(void) { + __pyx_umethod_PyDict_Type_get.type = (PyObject*)&PyDict_Type; + __pyx_umethod_PyDict_Type_get.method_name = &__pyx_n_s_get; + if (__Pyx_CreateStringTabAndInitStrings() < 0) __PYX_ERR(0, 1, __pyx_L1_error); + __pyx_int_222419149 = PyInt_FromLong(222419149L); if (unlikely(!__pyx_int_222419149)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_228825662 = PyInt_FromLong(228825662L); if (unlikely(!__pyx_int_228825662)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_238750788 = PyInt_FromLong(238750788L); if (unlikely(!__pyx_int_238750788)) __PYX_ERR(0, 1, __pyx_L1_error) + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: init_globals ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitGlobals(void) { + return 0; +} +/* #### Code section: init_module ### */ + +static CYTHON_SMALL_CODE int __Pyx_modinit_global_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_import_code(void); /*proto*/ + +static int __Pyx_modinit_global_init_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_global_init_code", 0); + /*--- Global init code ---*/ + __Pyx_OrderedDict = Py_None; Py_INCREF(Py_None); + __Pyx_EnumBase = Py_None; Py_INCREF(Py_None); + __Pyx_FlagBase = Py_None; Py_INCREF(Py_None); + __Pyx_globals = ((PyObject*)Py_None); Py_INCREF(Py_None); + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_variable_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_export_code", 0); + /*--- Variable export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_export_code", 0); + /*--- Function export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_type_init_code(void) { + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_modinit_type_init_code", 0); + /*--- Type init code ---*/ + #if CYTHON_USE_TYPE_SPECS + __pyx_ptype_6common_10params_pyx_Params = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_6common_10params_pyx_Params_spec, NULL); if (unlikely(!__pyx_ptype_6common_10params_pyx_Params)) __PYX_ERR(0, 43, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_6common_10params_pyx_Params_spec, __pyx_ptype_6common_10params_pyx_Params) < 0) __PYX_ERR(0, 43, __pyx_L1_error) + #else + __pyx_ptype_6common_10params_pyx_Params = &__pyx_type_6common_10params_pyx_Params; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_6common_10params_pyx_Params) < 0) __PYX_ERR(0, 43, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_6common_10params_pyx_Params->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_6common_10params_pyx_Params->tp_dictoffset && __pyx_ptype_6common_10params_pyx_Params->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_6common_10params_pyx_Params->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_Params, (PyObject *) __pyx_ptype_6common_10params_pyx_Params) < 0) __PYX_ERR(0, 43, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_6common_10params_pyx_Params) < 0) __PYX_ERR(0, 43, __pyx_L1_error) + #endif + #if CYTHON_USE_TYPE_SPECS + __pyx_t_1 = PyTuple_Pack(1, (PyObject *)(&PyType_Type)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 16, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_ptype___Pyx_EnumMeta = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__Pyx_EnumMeta_spec, __pyx_t_1); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_ptype___Pyx_EnumMeta)) __PYX_ERR(1, 16, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__Pyx_EnumMeta_spec, __pyx_ptype___Pyx_EnumMeta) < 0) __PYX_ERR(1, 16, __pyx_L1_error) + #else + __pyx_ptype___Pyx_EnumMeta = &__Pyx_EnumMeta; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + __pyx_ptype___Pyx_EnumMeta->tp_dealloc = (&PyType_Type)->tp_dealloc; + __pyx_ptype___Pyx_EnumMeta->tp_base = (&PyType_Type); + __pyx_ptype___Pyx_EnumMeta->tp_new = (&PyType_Type)->tp_new; + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype___Pyx_EnumMeta) < 0) __PYX_ERR(1, 16, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype___Pyx_EnumMeta->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype___Pyx_EnumMeta->tp_dictoffset && __pyx_ptype___Pyx_EnumMeta->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype___Pyx_EnumMeta->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype___Pyx_EnumMeta) < 0) __PYX_ERR(1, 16, __pyx_L1_error) + #endif + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_RefNannyFinishContext(); + return -1; +} + +static int __Pyx_modinit_type_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_type_import_code", 0); + /*--- Type import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_variable_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_import_code", 0); + /*--- Variable import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_import_code", 0); + /*--- Function import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + + +#if PY_MAJOR_VERSION >= 3 +#if CYTHON_PEP489_MULTI_PHASE_INIT +static PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def); /*proto*/ +static int __pyx_pymod_exec_params_pyx(PyObject* module); /*proto*/ +static PyModuleDef_Slot __pyx_moduledef_slots[] = { + {Py_mod_create, (void*)__pyx_pymod_create}, + {Py_mod_exec, (void*)__pyx_pymod_exec_params_pyx}, + {0, NULL} +}; +#endif + +#ifdef __cplusplus +namespace { + struct PyModuleDef __pyx_moduledef = + #else + static struct PyModuleDef __pyx_moduledef = + #endif + { + PyModuleDef_HEAD_INIT, + "params_pyx", + 0, /* m_doc */ + #if CYTHON_PEP489_MULTI_PHASE_INIT + 0, /* m_size */ + #elif CYTHON_USE_MODULE_STATE + sizeof(__pyx_mstate), /* m_size */ + #else + -1, /* m_size */ + #endif + __pyx_methods /* m_methods */, + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_moduledef_slots, /* m_slots */ + #else + NULL, /* m_reload */ + #endif + #if CYTHON_USE_MODULE_STATE + __pyx_m_traverse, /* m_traverse */ + __pyx_m_clear, /* m_clear */ + NULL /* m_free */ + #else + NULL, /* m_traverse */ + NULL, /* m_clear */ + NULL /* m_free */ + #endif + }; + #ifdef __cplusplus +} /* anonymous namespace */ +#endif +#endif + +#ifndef CYTHON_NO_PYINIT_EXPORT +#define __Pyx_PyMODINIT_FUNC PyMODINIT_FUNC +#elif PY_MAJOR_VERSION < 3 +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" void +#else +#define __Pyx_PyMODINIT_FUNC void +#endif +#else +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" PyObject * +#else +#define __Pyx_PyMODINIT_FUNC PyObject * +#endif +#endif + + +#if PY_MAJOR_VERSION < 3 +__Pyx_PyMODINIT_FUNC initparams_pyx(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC initparams_pyx(void) +#else +__Pyx_PyMODINIT_FUNC PyInit_params_pyx(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC PyInit_params_pyx(void) +#if CYTHON_PEP489_MULTI_PHASE_INIT +{ + return PyModuleDef_Init(&__pyx_moduledef); +} +static CYTHON_SMALL_CODE int __Pyx_check_single_interpreter(void) { + #if PY_VERSION_HEX >= 0x030700A1 + static PY_INT64_T main_interpreter_id = -1; + PY_INT64_T current_id = PyInterpreterState_GetID(PyThreadState_Get()->interp); + if (main_interpreter_id == -1) { + main_interpreter_id = current_id; + return (unlikely(current_id == -1)) ? -1 : 0; + } else if (unlikely(main_interpreter_id != current_id)) + #else + static PyInterpreterState *main_interpreter = NULL; + PyInterpreterState *current_interpreter = PyThreadState_Get()->interp; + if (!main_interpreter) { + main_interpreter = current_interpreter; + } else if (unlikely(main_interpreter != current_interpreter)) + #endif + { + PyErr_SetString( + PyExc_ImportError, + "Interpreter change detected - this module can only be loaded into one interpreter per process."); + return -1; + } + return 0; +} +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *module, const char* from_name, const char* to_name, int allow_none) +#else +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *moddict, const char* from_name, const char* to_name, int allow_none) +#endif +{ + PyObject *value = PyObject_GetAttrString(spec, from_name); + int result = 0; + if (likely(value)) { + if (allow_none || value != Py_None) { +#if CYTHON_COMPILING_IN_LIMITED_API + result = PyModule_AddObject(module, to_name, value); +#else + result = PyDict_SetItemString(moddict, to_name, value); +#endif + } + Py_DECREF(value); + } else if (PyErr_ExceptionMatches(PyExc_AttributeError)) { + PyErr_Clear(); + } else { + result = -1; + } + return result; +} +static CYTHON_SMALL_CODE PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def) { + PyObject *module = NULL, *moddict, *modname; + CYTHON_UNUSED_VAR(def); + if (__Pyx_check_single_interpreter()) + return NULL; + if (__pyx_m) + return __Pyx_NewRef(__pyx_m); + modname = PyObject_GetAttrString(spec, "name"); + if (unlikely(!modname)) goto bad; + module = PyModule_NewObject(modname); + Py_DECREF(modname); + if (unlikely(!module)) goto bad; +#if CYTHON_COMPILING_IN_LIMITED_API + moddict = module; +#else + moddict = PyModule_GetDict(module); + if (unlikely(!moddict)) goto bad; +#endif + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "loader", "__loader__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "origin", "__file__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "parent", "__package__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "submodule_search_locations", "__path__", 0) < 0)) goto bad; + return module; +bad: + Py_XDECREF(module); + return NULL; +} + + +static CYTHON_SMALL_CODE int __pyx_pymod_exec_params_pyx(PyObject *__pyx_pyinit_module) +#endif +#endif +{ + int stringtab_initialized = 0; + #if CYTHON_USE_MODULE_STATE + int pystate_addmodule_run = 0; + #endif + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + PyObject *__pyx_t_9 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannyDeclarations + #if CYTHON_PEP489_MULTI_PHASE_INIT + if (__pyx_m) { + if (__pyx_m == __pyx_pyinit_module) return 0; + PyErr_SetString(PyExc_RuntimeError, "Module 'params_pyx' has already been imported. Re-initialisation is not supported."); + return -1; + } + #elif PY_MAJOR_VERSION >= 3 + if (__pyx_m) return __Pyx_NewRef(__pyx_m); + #endif + /*--- Module creation code ---*/ + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_m = __pyx_pyinit_module; + Py_INCREF(__pyx_m); + #else + #if PY_MAJOR_VERSION < 3 + __pyx_m = Py_InitModule4("params_pyx", __pyx_methods, 0, 0, PYTHON_API_VERSION); Py_XINCREF(__pyx_m); + if (unlikely(!__pyx_m)) __PYX_ERR(0, 1, __pyx_L1_error) + #elif CYTHON_USE_MODULE_STATE + __pyx_t_1 = PyModule_Create(&__pyx_moduledef); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 1, __pyx_L1_error) + { + int add_module_result = PyState_AddModule(__pyx_t_1, &__pyx_moduledef); + __pyx_t_1 = 0; /* transfer ownership from __pyx_t_1 to "params_pyx" pseudovariable */ + if (unlikely((add_module_result < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + pystate_addmodule_run = 1; + } + #else + __pyx_m = PyModule_Create(&__pyx_moduledef); + if (unlikely(!__pyx_m)) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #endif + CYTHON_UNUSED_VAR(__pyx_t_1); + __pyx_d = PyModule_GetDict(__pyx_m); if (unlikely(!__pyx_d)) __PYX_ERR(0, 1, __pyx_L1_error) + Py_INCREF(__pyx_d); + __pyx_b = __Pyx_PyImport_AddModuleRef(__Pyx_BUILTIN_MODULE_NAME); if (unlikely(!__pyx_b)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_cython_runtime = __Pyx_PyImport_AddModuleRef((const char *) "cython_runtime"); if (unlikely(!__pyx_cython_runtime)) __PYX_ERR(0, 1, __pyx_L1_error) + if (PyObject_SetAttrString(__pyx_m, "__builtins__", __pyx_b) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #if CYTHON_REFNANNY +__Pyx_RefNanny = __Pyx_RefNannyImportAPI("refnanny"); +if (!__Pyx_RefNanny) { + PyErr_Clear(); + __Pyx_RefNanny = __Pyx_RefNannyImportAPI("Cython.Runtime.refnanny"); + if (!__Pyx_RefNanny) + Py_FatalError("failed to import 'refnanny' module"); +} +#endif + __Pyx_RefNannySetupContext("__Pyx_PyMODINIT_FUNC PyInit_params_pyx(void)", 0); + if (__Pyx_check_binary_version(__PYX_LIMITED_VERSION_HEX, __Pyx_get_runtime_version(), CYTHON_COMPILING_IN_LIMITED_API) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #ifdef __Pxy_PyFrame_Initialize_Offsets + __Pxy_PyFrame_Initialize_Offsets(); + #endif + __pyx_empty_tuple = PyTuple_New(0); if (unlikely(!__pyx_empty_tuple)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_empty_bytes = PyBytes_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_bytes)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_empty_unicode = PyUnicode_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_unicode)) __PYX_ERR(0, 1, __pyx_L1_error) + #ifdef __Pyx_CyFunction_USED + if (__pyx_CyFunction_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_FusedFunction_USED + if (__pyx_FusedFunction_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Coroutine_USED + if (__pyx_Coroutine_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Generator_USED + if (__pyx_Generator_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_AsyncGen_USED + if (__pyx_AsyncGen_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_StopAsyncIteration_USED + if (__pyx_StopAsyncIteration_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + /*--- Library function declarations ---*/ + /*--- Threads initialization code ---*/ + #if defined(WITH_THREAD) && PY_VERSION_HEX < 0x030700F0 && defined(__PYX_FORCE_INIT_THREADS) && __PYX_FORCE_INIT_THREADS + PyEval_InitThreads(); + #endif + /*--- Initialize various global constants etc. ---*/ + if (__Pyx_InitConstants() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + stringtab_initialized = 1; + if (__Pyx_InitGlobals() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #if PY_MAJOR_VERSION < 3 && (__PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT) + if (__Pyx_init_sys_getdefaultencoding_params() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + if (__pyx_module_is_main_common__params_pyx) { + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_name_2, __pyx_n_s_main) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + } + #if PY_MAJOR_VERSION >= 3 + { + PyObject *modules = PyImport_GetModuleDict(); if (unlikely(!modules)) __PYX_ERR(0, 1, __pyx_L1_error) + if (!PyDict_GetItemString(modules, "common.params_pyx")) { + if (unlikely((PyDict_SetItemString(modules, "common.params_pyx", __pyx_m) < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + } + } + #endif + /*--- Builtin init code ---*/ + if (__Pyx_InitCachedBuiltins() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + /*--- Constants init code ---*/ + if (__Pyx_InitCachedConstants() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + /*--- Global type/function init code ---*/ + (void)__Pyx_modinit_global_init_code(); + (void)__Pyx_modinit_variable_export_code(); + (void)__Pyx_modinit_function_export_code(); + if (unlikely((__Pyx_modinit_type_init_code() < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + (void)__Pyx_modinit_type_import_code(); + (void)__Pyx_modinit_variable_import_code(); + (void)__Pyx_modinit_function_import_code(); + /*--- Execution code ---*/ + #if defined(__Pyx_Generator_USED) || defined(__Pyx_Coroutine_USED) + if (__Pyx_patch_abc() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + + /* "EnumBase":10 + * cdef object __Pyx_OrderedDict + * + * if PY_VERSION_HEX >= 0x03060000: # <<<<<<<<<<<<<< + * __Pyx_OrderedDict = dict + * else: + */ + __pyx_t_2 = (PY_VERSION_HEX >= 0x03060000); + if (__pyx_t_2) { + + /* "EnumBase":11 + * + * if PY_VERSION_HEX >= 0x03060000: + * __Pyx_OrderedDict = dict # <<<<<<<<<<<<<< + * else: + * from collections import OrderedDict as __Pyx_OrderedDict + */ + __Pyx_INCREF((PyObject *)(&PyDict_Type)); + __Pyx_XGOTREF(__Pyx_OrderedDict); + __Pyx_DECREF_SET(__Pyx_OrderedDict, ((PyObject *)(&PyDict_Type))); + __Pyx_GIVEREF((PyObject *)(&PyDict_Type)); + + /* "EnumBase":10 + * cdef object __Pyx_OrderedDict + * + * if PY_VERSION_HEX >= 0x03060000: # <<<<<<<<<<<<<< + * __Pyx_OrderedDict = dict + * else: + */ + goto __pyx_L2; + } + + /* "EnumBase":13 + * __Pyx_OrderedDict = dict + * else: + * from collections import OrderedDict as __Pyx_OrderedDict # <<<<<<<<<<<<<< + * + * @cython.internal + */ + /*else*/ { + __pyx_t_3 = PyList_New(1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_n_s_OrderedDict); + __Pyx_GIVEREF(__pyx_n_s_OrderedDict); + if (__Pyx_PyList_SET_ITEM(__pyx_t_3, 0, __pyx_n_s_OrderedDict)) __PYX_ERR(1, 13, __pyx_L1_error); + __pyx_t_4 = __Pyx_Import(__pyx_n_s_collections, __pyx_t_3, 0); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_ImportFrom(__pyx_t_4, __pyx_n_s_OrderedDict); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_t_3); + __Pyx_XGOTREF(__Pyx_OrderedDict); + __Pyx_DECREF_SET(__Pyx_OrderedDict, __pyx_t_3); + __Pyx_GIVEREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + __pyx_L2:; + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * cdef tuple state + * cdef object _dict + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_8EnumBase_14__Pyx_EnumMeta_7__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Pyx_EnumMeta___reduce_cython, NULL, __pyx_n_s_EnumBase, __pyx_d, ((PyObject *)__pyx_codeobj__6)); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype___Pyx_EnumMeta, __pyx_n_s_reduce_cython, __pyx_t_4) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + PyType_Modified(__pyx_ptype___Pyx_EnumMeta); + + /* "(tree fragment)":16 + * else: + * return __pyx_unpickle___Pyx_EnumMeta, (type(self), 0xe3b0c44, state) + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * __pyx_unpickle___Pyx_EnumMeta__set_state(self, __pyx_state) + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_8EnumBase_14__Pyx_EnumMeta_9__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Pyx_EnumMeta___setstate_cython, NULL, __pyx_n_s_EnumBase, __pyx_d, ((PyObject *)__pyx_codeobj__8)); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 16, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype___Pyx_EnumMeta, __pyx_n_s_setstate_cython, __pyx_t_4) < 0) __PYX_ERR(1, 16, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + PyType_Modified(__pyx_ptype___Pyx_EnumMeta); + + /* "EnumBase":27 + * + * cdef object __Pyx_EnumBase + * class __Pyx_EnumBase(int, metaclass=__Pyx_EnumMeta): # <<<<<<<<<<<<<< + * def __new__(cls, value, name=None): + * for v in cls: + */ + __pyx_t_4 = PyTuple_New(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 27, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_INCREF((PyObject *)(&PyInt_Type)); + __Pyx_GIVEREF((PyObject *)(&PyInt_Type)); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, ((PyObject *)(&PyInt_Type)))) __PYX_ERR(1, 27, __pyx_L1_error); + __pyx_t_3 = __Pyx_PEP560_update_bases(__pyx_t_4); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 27, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 27, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = __Pyx_Py3MetaclassPrepare(((PyObject *)__pyx_ptype___Pyx_EnumMeta), __pyx_t_3, __pyx_n_s_Pyx_EnumBase, __pyx_n_s_Pyx_EnumBase, __pyx_t_5, __pyx_n_s_EnumBase, (PyObject *) NULL); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 27, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (__pyx_t_3 != __pyx_t_4) { + if (unlikely((PyDict_SetItemString(__pyx_t_6, "__orig_bases__", __pyx_t_4) < 0))) __PYX_ERR(1, 27, __pyx_L1_error) + } + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "EnumBase":28 + * cdef object __Pyx_EnumBase + * class __Pyx_EnumBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): # <<<<<<<<<<<<<< + * for v in cls: + * if v == value: + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_8EnumBase_14__Pyx_EnumBase_1__new__, __Pyx_CYFUNCTION_STATICMETHOD, __pyx_n_s_Pyx_EnumBase___new, NULL, __pyx_n_s_EnumBase, __pyx_d, ((PyObject *)__pyx_codeobj__10)); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 28, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_4, __pyx_tuple__11); + if (__Pyx_SetNewInClass(__pyx_t_6, __pyx_n_s_new, __pyx_t_4) < 0) __PYX_ERR(1, 28, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "EnumBase":39 + * cls.__members__[name] = res + * return res + * def __repr__(self): # <<<<<<<<<<<<<< + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_8EnumBase_14__Pyx_EnumBase_3__repr__, 0, __pyx_n_s_Pyx_EnumBase___repr, NULL, __pyx_n_s_EnumBase, __pyx_d, ((PyObject *)__pyx_codeobj__13)); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 39, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (__Pyx_SetNameInClass(__pyx_t_6, __pyx_n_s_repr, __pyx_t_4) < 0) __PYX_ERR(1, 39, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "EnumBase":41 + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): # <<<<<<<<<<<<<< + * return "%s.%s" % (self.__class__.__name__, self.name) + * + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_8EnumBase_14__Pyx_EnumBase_5__str__, 0, __pyx_n_s_Pyx_EnumBase___str, NULL, __pyx_n_s_EnumBase, __pyx_d, ((PyObject *)__pyx_codeobj__14)); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 41, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (__Pyx_SetNameInClass(__pyx_t_6, __pyx_n_s_str, __pyx_t_4) < 0) __PYX_ERR(1, 41, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "EnumBase":27 + * + * cdef object __Pyx_EnumBase + * class __Pyx_EnumBase(int, metaclass=__Pyx_EnumMeta): # <<<<<<<<<<<<<< + * def __new__(cls, value, name=None): + * for v in cls: + */ + __pyx_t_4 = __Pyx_Py3ClassCreate(((PyObject *)__pyx_ptype___Pyx_EnumMeta), __pyx_n_s_Pyx_EnumBase, __pyx_t_3, __pyx_t_6, __pyx_t_5, 1, 0); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 27, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_XGOTREF(__Pyx_EnumBase); + __Pyx_DECREF_SET(__Pyx_EnumBase, __pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "EnumBase":44 + * return "%s.%s" % (self.__class__.__name__, self.name) + * + * if PY_VERSION_HEX >= 0x03040000: # <<<<<<<<<<<<<< + * from enum import IntEnum as __Pyx_EnumBase + * + */ + __pyx_t_2 = (PY_VERSION_HEX >= 0x03040000); + if (__pyx_t_2) { + + /* "EnumBase":45 + * + * if PY_VERSION_HEX >= 0x03040000: + * from enum import IntEnum as __Pyx_EnumBase # <<<<<<<<<<<<<< + * + * cdef object __Pyx_FlagBase + */ + __pyx_t_3 = PyList_New(1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 45, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_n_s_IntEnum); + __Pyx_GIVEREF(__pyx_n_s_IntEnum); + if (__Pyx_PyList_SET_ITEM(__pyx_t_3, 0, __pyx_n_s_IntEnum)) __PYX_ERR(1, 45, __pyx_L1_error); + __pyx_t_5 = __Pyx_Import(__pyx_n_s_enum, __pyx_t_3, 0); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 45, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_ImportFrom(__pyx_t_5, __pyx_n_s_IntEnum); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 45, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_t_3); + __Pyx_XGOTREF(__Pyx_EnumBase); + __Pyx_DECREF_SET(__Pyx_EnumBase, __pyx_t_3); + __Pyx_GIVEREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "EnumBase":44 + * return "%s.%s" % (self.__class__.__name__, self.name) + * + * if PY_VERSION_HEX >= 0x03040000: # <<<<<<<<<<<<<< + * from enum import IntEnum as __Pyx_EnumBase + * + */ + } + + /* "EnumBase":48 + * + * cdef object __Pyx_FlagBase + * class __Pyx_FlagBase(int, metaclass=__Pyx_EnumMeta): # <<<<<<<<<<<<<< + * def __new__(cls, value, name=None): + * for v in cls: + */ + __pyx_t_5 = PyTuple_New(1); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 48, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_INCREF((PyObject *)(&PyInt_Type)); + __Pyx_GIVEREF((PyObject *)(&PyInt_Type)); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_5, 0, ((PyObject *)(&PyInt_Type)))) __PYX_ERR(1, 48, __pyx_L1_error); + __pyx_t_3 = __Pyx_PEP560_update_bases(__pyx_t_5); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 48, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_6 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 48, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_4 = __Pyx_Py3MetaclassPrepare(((PyObject *)__pyx_ptype___Pyx_EnumMeta), __pyx_t_3, __pyx_n_s_Pyx_FlagBase, __pyx_n_s_Pyx_FlagBase, __pyx_t_6, __pyx_n_s_EnumBase, (PyObject *) NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 48, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (__pyx_t_3 != __pyx_t_5) { + if (unlikely((PyDict_SetItemString(__pyx_t_4, "__orig_bases__", __pyx_t_5) < 0))) __PYX_ERR(1, 48, __pyx_L1_error) + } + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "EnumBase":49 + * cdef object __Pyx_FlagBase + * class __Pyx_FlagBase(int, metaclass=__Pyx_EnumMeta): + * def __new__(cls, value, name=None): # <<<<<<<<<<<<<< + * for v in cls: + * if v == value: + */ + __pyx_t_5 = __Pyx_CyFunction_New(&__pyx_mdef_8EnumBase_14__Pyx_FlagBase_1__new__, __Pyx_CYFUNCTION_STATICMETHOD, __pyx_n_s_Pyx_FlagBase___new, NULL, __pyx_n_s_EnumBase, __pyx_d, ((PyObject *)__pyx_codeobj__15)); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 49, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_5, __pyx_tuple__11); + if (__Pyx_SetNewInClass(__pyx_t_4, __pyx_n_s_new, __pyx_t_5) < 0) __PYX_ERR(1, 49, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "EnumBase":62 + * cls.__members__[name] = res + * return res + * def __repr__(self): # <<<<<<<<<<<<<< + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): + */ + __pyx_t_5 = __Pyx_CyFunction_New(&__pyx_mdef_8EnumBase_14__Pyx_FlagBase_3__repr__, 0, __pyx_n_s_Pyx_FlagBase___repr, NULL, __pyx_n_s_EnumBase, __pyx_d, ((PyObject *)__pyx_codeobj__16)); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 62, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + if (__Pyx_SetNameInClass(__pyx_t_4, __pyx_n_s_repr, __pyx_t_5) < 0) __PYX_ERR(1, 62, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "EnumBase":64 + * def __repr__(self): + * return "<%s.%s: %d>" % (self.__class__.__name__, self.name, self) + * def __str__(self): # <<<<<<<<<<<<<< + * return "%s.%s" % (self.__class__.__name__, self.name) + * + */ + __pyx_t_5 = __Pyx_CyFunction_New(&__pyx_mdef_8EnumBase_14__Pyx_FlagBase_5__str__, 0, __pyx_n_s_Pyx_FlagBase___str, NULL, __pyx_n_s_EnumBase, __pyx_d, ((PyObject *)__pyx_codeobj__17)); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 64, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + if (__Pyx_SetNameInClass(__pyx_t_4, __pyx_n_s_str, __pyx_t_5) < 0) __PYX_ERR(1, 64, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "EnumBase":48 + * + * cdef object __Pyx_FlagBase + * class __Pyx_FlagBase(int, metaclass=__Pyx_EnumMeta): # <<<<<<<<<<<<<< + * def __new__(cls, value, name=None): + * for v in cls: + */ + __pyx_t_5 = __Pyx_Py3ClassCreate(((PyObject *)__pyx_ptype___Pyx_EnumMeta), __pyx_n_s_Pyx_FlagBase, __pyx_t_3, __pyx_t_4, __pyx_t_6, 1, 0); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 48, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_XGOTREF(__Pyx_FlagBase); + __Pyx_DECREF_SET(__Pyx_FlagBase, __pyx_t_5); + __Pyx_GIVEREF(__pyx_t_5); + __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "EnumBase":67 + * return "%s.%s" % (self.__class__.__name__, self.name) + * + * if PY_VERSION_HEX >= 0x03060000: # <<<<<<<<<<<<<< + * from enum import IntFlag as __Pyx_FlagBase + * + */ + __pyx_t_2 = (PY_VERSION_HEX >= 0x03060000); + if (__pyx_t_2) { + + /* "EnumBase":68 + * + * if PY_VERSION_HEX >= 0x03060000: + * from enum import IntFlag as __Pyx_FlagBase # <<<<<<<<<<<<<< + * + */ + __pyx_t_3 = PyList_New(1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 68, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_n_s_IntFlag); + __Pyx_GIVEREF(__pyx_n_s_IntFlag); + if (__Pyx_PyList_SET_ITEM(__pyx_t_3, 0, __pyx_n_s_IntFlag)) __PYX_ERR(1, 68, __pyx_L1_error); + __pyx_t_6 = __Pyx_Import(__pyx_n_s_enum, __pyx_t_3, 0); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 68, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_ImportFrom(__pyx_t_6, __pyx_n_s_IntFlag); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 68, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_t_3); + __Pyx_XGOTREF(__Pyx_FlagBase); + __Pyx_DECREF_SET(__Pyx_FlagBase, __pyx_t_3); + __Pyx_GIVEREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + + /* "EnumBase":67 + * return "%s.%s" % (self.__class__.__name__, self.name) + * + * if PY_VERSION_HEX >= 0x03060000: # <<<<<<<<<<<<<< + * from enum import IntFlag as __Pyx_FlagBase + * + */ + } + + /* "(tree fragment)":1 + * def __pyx_unpickle___Pyx_EnumMeta(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + __pyx_t_6 = __Pyx_CyFunction_New(&__pyx_mdef_8EnumBase_1__pyx_unpickle___Pyx_EnumMeta, 0, __pyx_n_s_pyx_unpickle___Pyx_EnumMeta, NULL, __pyx_n_s_EnumBase, __pyx_d, ((PyObject *)__pyx_codeobj__19)); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_pyx_unpickle___Pyx_EnumMeta, __pyx_t_6) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + + /* "EnumType":76 + * object __Pyx_PyInt_From_enum__ParamKeyType(ParamKeyType value) + * + * cdef dict __Pyx_globals = globals() # <<<<<<<<<<<<<< + * if PY_VERSION_HEX >= 0x03060000: + * + */ + __pyx_t_6 = __Pyx_Globals(); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 76, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (!(likely(PyDict_CheckExact(__pyx_t_6))||((__pyx_t_6) == Py_None) || __Pyx_RaiseUnexpectedTypeError("dict", __pyx_t_6))) __PYX_ERR(1, 76, __pyx_L1_error) + __Pyx_XGOTREF(__Pyx_globals); + __Pyx_DECREF_SET(__Pyx_globals, ((PyObject*)__pyx_t_6)); + __Pyx_GIVEREF(__pyx_t_6); + __pyx_t_6 = 0; + + /* "EnumType":77 + * + * cdef dict __Pyx_globals = globals() + * if PY_VERSION_HEX >= 0x03060000: # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = (PY_VERSION_HEX >= 0x03060000); + if (__pyx_t_2) { + + /* "EnumType":81 + * + * ParamKeyType = __Pyx_FlagBase('ParamKeyType', [ + * ('PERSISTENT', __Pyx_PyInt_From_enum__ParamKeyType(PERSISTENT)), # <<<<<<<<<<<<<< + * ('CLEAR_ON_MANAGER_START', __Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_MANAGER_START)), + * ('CLEAR_ON_ONROAD_TRANSITION', __Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_ONROAD_TRANSITION)), + */ + __pyx_t_6 = __Pyx_PyInt_From_enum__ParamKeyType(PERSISTENT); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 81, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 81, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_n_s_PERSISTENT); + __Pyx_GIVEREF(__pyx_n_s_PERSISTENT); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_n_s_PERSISTENT)) __PYX_ERR(1, 81, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_6); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_6)) __PYX_ERR(1, 81, __pyx_L1_error); + __pyx_t_6 = 0; + + /* "EnumType":82 + * ParamKeyType = __Pyx_FlagBase('ParamKeyType', [ + * ('PERSISTENT', __Pyx_PyInt_From_enum__ParamKeyType(PERSISTENT)), + * ('CLEAR_ON_MANAGER_START', __Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_MANAGER_START)), # <<<<<<<<<<<<<< + * ('CLEAR_ON_ONROAD_TRANSITION', __Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_ONROAD_TRANSITION)), + * ('CLEAR_ON_OFFROAD_TRANSITION', __Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_OFFROAD_TRANSITION)), + */ + __pyx_t_6 = __Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_MANAGER_START); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 82, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_4 = PyTuple_New(2); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 82, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_INCREF(__pyx_n_s_CLEAR_ON_MANAGER_START); + __Pyx_GIVEREF(__pyx_n_s_CLEAR_ON_MANAGER_START); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_n_s_CLEAR_ON_MANAGER_START)) __PYX_ERR(1, 82, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_6); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_t_6)) __PYX_ERR(1, 82, __pyx_L1_error); + __pyx_t_6 = 0; + + /* "EnumType":83 + * ('PERSISTENT', __Pyx_PyInt_From_enum__ParamKeyType(PERSISTENT)), + * ('CLEAR_ON_MANAGER_START', __Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_MANAGER_START)), + * ('CLEAR_ON_ONROAD_TRANSITION', __Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_ONROAD_TRANSITION)), # <<<<<<<<<<<<<< + * ('CLEAR_ON_OFFROAD_TRANSITION', __Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_OFFROAD_TRANSITION)), + * ('DEVELOPMENT_ONLY', __Pyx_PyInt_From_enum__ParamKeyType(DEVELOPMENT_ONLY)), + */ + __pyx_t_6 = __Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_ONROAD_TRANSITION); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 83, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_5 = PyTuple_New(2); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 83, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_INCREF(__pyx_n_s_CLEAR_ON_ONROAD_TRANSITION); + __Pyx_GIVEREF(__pyx_n_s_CLEAR_ON_ONROAD_TRANSITION); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_n_s_CLEAR_ON_ONROAD_TRANSITION)) __PYX_ERR(1, 83, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_6); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_6)) __PYX_ERR(1, 83, __pyx_L1_error); + __pyx_t_6 = 0; + + /* "EnumType":84 + * ('CLEAR_ON_MANAGER_START', __Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_MANAGER_START)), + * ('CLEAR_ON_ONROAD_TRANSITION', __Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_ONROAD_TRANSITION)), + * ('CLEAR_ON_OFFROAD_TRANSITION', __Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_OFFROAD_TRANSITION)), # <<<<<<<<<<<<<< + * ('DEVELOPMENT_ONLY', __Pyx_PyInt_From_enum__ParamKeyType(DEVELOPMENT_ONLY)), + * ('ALL', __Pyx_PyInt_From_enum__ParamKeyType(ALL)), + */ + __pyx_t_6 = __Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_OFFROAD_TRANSITION); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 84, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_7 = PyTuple_New(2); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 84, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_INCREF(__pyx_n_s_CLEAR_ON_OFFROAD_TRANSITION); + __Pyx_GIVEREF(__pyx_n_s_CLEAR_ON_OFFROAD_TRANSITION); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_7, 0, __pyx_n_s_CLEAR_ON_OFFROAD_TRANSITION)) __PYX_ERR(1, 84, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_6); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_7, 1, __pyx_t_6)) __PYX_ERR(1, 84, __pyx_L1_error); + __pyx_t_6 = 0; + + /* "EnumType":85 + * ('CLEAR_ON_ONROAD_TRANSITION', __Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_ONROAD_TRANSITION)), + * ('CLEAR_ON_OFFROAD_TRANSITION', __Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_OFFROAD_TRANSITION)), + * ('DEVELOPMENT_ONLY', __Pyx_PyInt_From_enum__ParamKeyType(DEVELOPMENT_ONLY)), # <<<<<<<<<<<<<< + * ('ALL', __Pyx_PyInt_From_enum__ParamKeyType(ALL)), + * + */ + __pyx_t_6 = __Pyx_PyInt_From_enum__ParamKeyType(DEVELOPMENT_ONLY); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 85, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_8 = PyTuple_New(2); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 85, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_INCREF(__pyx_n_s_DEVELOPMENT_ONLY); + __Pyx_GIVEREF(__pyx_n_s_DEVELOPMENT_ONLY); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_8, 0, __pyx_n_s_DEVELOPMENT_ONLY)) __PYX_ERR(1, 85, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_6); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_8, 1, __pyx_t_6)) __PYX_ERR(1, 85, __pyx_L1_error); + __pyx_t_6 = 0; + + /* "EnumType":86 + * ('CLEAR_ON_OFFROAD_TRANSITION', __Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_OFFROAD_TRANSITION)), + * ('DEVELOPMENT_ONLY', __Pyx_PyInt_From_enum__ParamKeyType(DEVELOPMENT_ONLY)), + * ('ALL', __Pyx_PyInt_From_enum__ParamKeyType(ALL)), # <<<<<<<<<<<<<< + * + * ], module=__Pyx_globals.get("__module__", 'common.params_pyx')) + */ + __pyx_t_6 = __Pyx_PyInt_From_enum__ParamKeyType(ALL); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 86, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_9 = PyTuple_New(2); if (unlikely(!__pyx_t_9)) __PYX_ERR(1, 86, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_INCREF(__pyx_n_s_ALL); + __Pyx_GIVEREF(__pyx_n_s_ALL); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_9, 0, __pyx_n_s_ALL)) __PYX_ERR(1, 86, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_6); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_9, 1, __pyx_t_6)) __PYX_ERR(1, 86, __pyx_L1_error); + __pyx_t_6 = 0; + + /* "EnumType":80 + * + * + * ParamKeyType = __Pyx_FlagBase('ParamKeyType', [ # <<<<<<<<<<<<<< + * ('PERSISTENT', __Pyx_PyInt_From_enum__ParamKeyType(PERSISTENT)), + * ('CLEAR_ON_MANAGER_START', __Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_MANAGER_START)), + */ + __pyx_t_6 = PyList_New(6); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 80, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyList_SET_ITEM(__pyx_t_6, 0, __pyx_t_3)) __PYX_ERR(1, 80, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_4); + if (__Pyx_PyList_SET_ITEM(__pyx_t_6, 1, __pyx_t_4)) __PYX_ERR(1, 80, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_5); + if (__Pyx_PyList_SET_ITEM(__pyx_t_6, 2, __pyx_t_5)) __PYX_ERR(1, 80, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_7); + if (__Pyx_PyList_SET_ITEM(__pyx_t_6, 3, __pyx_t_7)) __PYX_ERR(1, 80, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_8); + if (__Pyx_PyList_SET_ITEM(__pyx_t_6, 4, __pyx_t_8)) __PYX_ERR(1, 80, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_9); + if (__Pyx_PyList_SET_ITEM(__pyx_t_6, 5, __pyx_t_9)) __PYX_ERR(1, 80, __pyx_L1_error); + __pyx_t_3 = 0; + __pyx_t_4 = 0; + __pyx_t_5 = 0; + __pyx_t_7 = 0; + __pyx_t_8 = 0; + __pyx_t_9 = 0; + __pyx_t_9 = PyTuple_New(2); if (unlikely(!__pyx_t_9)) __PYX_ERR(1, 80, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_INCREF(__pyx_n_s_ParamKeyType); + __Pyx_GIVEREF(__pyx_n_s_ParamKeyType); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_9, 0, __pyx_n_s_ParamKeyType)) __PYX_ERR(1, 80, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_6); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_9, 1, __pyx_t_6)) __PYX_ERR(1, 80, __pyx_L1_error); + __pyx_t_6 = 0; + + /* "EnumType":88 + * ('ALL', __Pyx_PyInt_From_enum__ParamKeyType(ALL)), + * + * ], module=__Pyx_globals.get("__module__", 'common.params_pyx')) # <<<<<<<<<<<<<< + * + * if PY_VERSION_HEX >= 0x030B0000: + */ + __pyx_t_6 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 88, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (unlikely(__Pyx_globals == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "get"); + __PYX_ERR(1, 88, __pyx_L1_error) + } + __pyx_t_8 = __Pyx_PyDict_GetItemDefault(__Pyx_globals, __pyx_n_s_module, __pyx_kp_s_common_params_pyx); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 88, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + if (PyDict_SetItem(__pyx_t_6, __pyx_n_s_module_2, __pyx_t_8) < 0) __PYX_ERR(1, 88, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + + /* "EnumType":80 + * + * + * ParamKeyType = __Pyx_FlagBase('ParamKeyType', [ # <<<<<<<<<<<<<< + * ('PERSISTENT', __Pyx_PyInt_From_enum__ParamKeyType(PERSISTENT)), + * ('CLEAR_ON_MANAGER_START', __Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_MANAGER_START)), + */ + __pyx_t_8 = __Pyx_PyObject_Call(__Pyx_FlagBase, __pyx_t_9, __pyx_t_6); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 80, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + if (PyDict_SetItem(__pyx_d, __pyx_n_s_ParamKeyType, __pyx_t_8) < 0) __PYX_ERR(1, 80, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + + /* "EnumType":90 + * ], module=__Pyx_globals.get("__module__", 'common.params_pyx')) + * + * if PY_VERSION_HEX >= 0x030B0000: # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = (PY_VERSION_HEX >= 0x030B0000); + if (__pyx_t_2) { + + /* "EnumType":95 + * + * + * ParamKeyType._member_names_ = list(ParamKeyType.__members__) # <<<<<<<<<<<<<< + * + * __Pyx_globals['PERSISTENT'] = ParamKeyType.PERSISTENT + */ + __Pyx_GetModuleGlobalName(__pyx_t_8, __pyx_n_s_ParamKeyType); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 95, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_8, __pyx_n_s_members); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 95, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_t_8 = __Pyx_PySequence_ListKeepNew(__pyx_t_6); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 95, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_GetModuleGlobalName(__pyx_t_6, __pyx_n_s_ParamKeyType); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 95, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (__Pyx_PyObject_SetAttrStr(__pyx_t_6, __pyx_n_s_member_names, __pyx_t_8) < 0) __PYX_ERR(1, 95, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + + /* "EnumType":90 + * ], module=__Pyx_globals.get("__module__", 'common.params_pyx')) + * + * if PY_VERSION_HEX >= 0x030B0000: # <<<<<<<<<<<<<< + * + * + */ + } + + /* "EnumType":97 + * ParamKeyType._member_names_ = list(ParamKeyType.__members__) + * + * __Pyx_globals['PERSISTENT'] = ParamKeyType.PERSISTENT # <<<<<<<<<<<<<< + * __Pyx_globals['CLEAR_ON_MANAGER_START'] = ParamKeyType.CLEAR_ON_MANAGER_START + * __Pyx_globals['CLEAR_ON_ONROAD_TRANSITION'] = ParamKeyType.CLEAR_ON_ONROAD_TRANSITION + */ + __Pyx_GetModuleGlobalName(__pyx_t_6, __pyx_n_s_ParamKeyType); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 97, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_t_6, __pyx_n_s_PERSISTENT); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 97, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(__Pyx_globals == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 97, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__Pyx_globals, __pyx_n_s_PERSISTENT, __pyx_t_8) < 0))) __PYX_ERR(1, 97, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + + /* "EnumType":98 + * + * __Pyx_globals['PERSISTENT'] = ParamKeyType.PERSISTENT + * __Pyx_globals['CLEAR_ON_MANAGER_START'] = ParamKeyType.CLEAR_ON_MANAGER_START # <<<<<<<<<<<<<< + * __Pyx_globals['CLEAR_ON_ONROAD_TRANSITION'] = ParamKeyType.CLEAR_ON_ONROAD_TRANSITION + * __Pyx_globals['CLEAR_ON_OFFROAD_TRANSITION'] = ParamKeyType.CLEAR_ON_OFFROAD_TRANSITION + */ + __Pyx_GetModuleGlobalName(__pyx_t_8, __pyx_n_s_ParamKeyType); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 98, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_8, __pyx_n_s_CLEAR_ON_MANAGER_START); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 98, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + if (unlikely(__Pyx_globals == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 98, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__Pyx_globals, __pyx_n_s_CLEAR_ON_MANAGER_START, __pyx_t_6) < 0))) __PYX_ERR(1, 98, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + + /* "EnumType":99 + * __Pyx_globals['PERSISTENT'] = ParamKeyType.PERSISTENT + * __Pyx_globals['CLEAR_ON_MANAGER_START'] = ParamKeyType.CLEAR_ON_MANAGER_START + * __Pyx_globals['CLEAR_ON_ONROAD_TRANSITION'] = ParamKeyType.CLEAR_ON_ONROAD_TRANSITION # <<<<<<<<<<<<<< + * __Pyx_globals['CLEAR_ON_OFFROAD_TRANSITION'] = ParamKeyType.CLEAR_ON_OFFROAD_TRANSITION + * __Pyx_globals['DEVELOPMENT_ONLY'] = ParamKeyType.DEVELOPMENT_ONLY + */ + __Pyx_GetModuleGlobalName(__pyx_t_6, __pyx_n_s_ParamKeyType); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 99, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_t_6, __pyx_n_s_CLEAR_ON_ONROAD_TRANSITION); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 99, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(__Pyx_globals == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 99, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__Pyx_globals, __pyx_n_s_CLEAR_ON_ONROAD_TRANSITION, __pyx_t_8) < 0))) __PYX_ERR(1, 99, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + + /* "EnumType":100 + * __Pyx_globals['CLEAR_ON_MANAGER_START'] = ParamKeyType.CLEAR_ON_MANAGER_START + * __Pyx_globals['CLEAR_ON_ONROAD_TRANSITION'] = ParamKeyType.CLEAR_ON_ONROAD_TRANSITION + * __Pyx_globals['CLEAR_ON_OFFROAD_TRANSITION'] = ParamKeyType.CLEAR_ON_OFFROAD_TRANSITION # <<<<<<<<<<<<<< + * __Pyx_globals['DEVELOPMENT_ONLY'] = ParamKeyType.DEVELOPMENT_ONLY + * __Pyx_globals['ALL'] = ParamKeyType.ALL + */ + __Pyx_GetModuleGlobalName(__pyx_t_8, __pyx_n_s_ParamKeyType); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_8, __pyx_n_s_CLEAR_ON_OFFROAD_TRANSITION); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + if (unlikely(__Pyx_globals == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 100, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__Pyx_globals, __pyx_n_s_CLEAR_ON_OFFROAD_TRANSITION, __pyx_t_6) < 0))) __PYX_ERR(1, 100, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + + /* "EnumType":101 + * __Pyx_globals['CLEAR_ON_ONROAD_TRANSITION'] = ParamKeyType.CLEAR_ON_ONROAD_TRANSITION + * __Pyx_globals['CLEAR_ON_OFFROAD_TRANSITION'] = ParamKeyType.CLEAR_ON_OFFROAD_TRANSITION + * __Pyx_globals['DEVELOPMENT_ONLY'] = ParamKeyType.DEVELOPMENT_ONLY # <<<<<<<<<<<<<< + * __Pyx_globals['ALL'] = ParamKeyType.ALL + * else: + */ + __Pyx_GetModuleGlobalName(__pyx_t_6, __pyx_n_s_ParamKeyType); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 101, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_t_6, __pyx_n_s_DEVELOPMENT_ONLY); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 101, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(__Pyx_globals == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 101, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__Pyx_globals, __pyx_n_s_DEVELOPMENT_ONLY, __pyx_t_8) < 0))) __PYX_ERR(1, 101, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + + /* "EnumType":102 + * __Pyx_globals['CLEAR_ON_OFFROAD_TRANSITION'] = ParamKeyType.CLEAR_ON_OFFROAD_TRANSITION + * __Pyx_globals['DEVELOPMENT_ONLY'] = ParamKeyType.DEVELOPMENT_ONLY + * __Pyx_globals['ALL'] = ParamKeyType.ALL # <<<<<<<<<<<<<< + * else: + * class ParamKeyType(__Pyx_FlagBase): + */ + __Pyx_GetModuleGlobalName(__pyx_t_8, __pyx_n_s_ParamKeyType); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 102, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_8, __pyx_n_s_ALL); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 102, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + if (unlikely(__Pyx_globals == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 102, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__Pyx_globals, __pyx_n_s_ALL, __pyx_t_6) < 0))) __PYX_ERR(1, 102, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + + /* "EnumType":77 + * + * cdef dict __Pyx_globals = globals() + * if PY_VERSION_HEX >= 0x03060000: # <<<<<<<<<<<<<< + * + * + */ + goto __pyx_L5; + } + + /* "EnumType":104 + * __Pyx_globals['ALL'] = ParamKeyType.ALL + * else: + * class ParamKeyType(__Pyx_FlagBase): # <<<<<<<<<<<<<< + * pass + * __Pyx_globals['PERSISTENT'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(PERSISTENT), 'PERSISTENT') + */ + /*else*/ { + __pyx_t_6 = PyTuple_New(1); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 104, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_INCREF(__Pyx_FlagBase); + __Pyx_GIVEREF(__Pyx_FlagBase); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_6, 0, __Pyx_FlagBase)) __PYX_ERR(1, 104, __pyx_L1_error); + __pyx_t_8 = __Pyx_PEP560_update_bases(__pyx_t_6); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 104, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_9 = __Pyx_CalculateMetaclass(NULL, __pyx_t_8); if (unlikely(!__pyx_t_9)) __PYX_ERR(1, 104, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __pyx_t_7 = __Pyx_Py3MetaclassPrepare(__pyx_t_9, __pyx_t_8, __pyx_n_s_ParamKeyType, __pyx_n_s_ParamKeyType, (PyObject *) NULL, __pyx_n_s_EnumType, (PyObject *) NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 104, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__pyx_t_8 != __pyx_t_6) { + if (unlikely((PyDict_SetItemString(__pyx_t_7, "__orig_bases__", __pyx_t_6) < 0))) __PYX_ERR(1, 104, __pyx_L1_error) + } + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __pyx_t_6 = __Pyx_Py3ClassCreate(__pyx_t_9, __pyx_n_s_ParamKeyType, __pyx_t_8, __pyx_t_7, NULL, 0, 0); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 104, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_ParamKeyType, __pyx_t_6) < 0) __PYX_ERR(1, 104, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + + /* "EnumType":106 + * class ParamKeyType(__Pyx_FlagBase): + * pass + * __Pyx_globals['PERSISTENT'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(PERSISTENT), 'PERSISTENT') # <<<<<<<<<<<<<< + * __Pyx_globals['CLEAR_ON_MANAGER_START'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_MANAGER_START), 'CLEAR_ON_MANAGER_START') + * __Pyx_globals['CLEAR_ON_ONROAD_TRANSITION'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_ONROAD_TRANSITION), 'CLEAR_ON_ONROAD_TRANSITION') + */ + __Pyx_GetModuleGlobalName(__pyx_t_8, __pyx_n_s_ParamKeyType); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 106, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_9 = __Pyx_PyInt_From_enum__ParamKeyType(PERSISTENT); if (unlikely(!__pyx_t_9)) __PYX_ERR(1, 106, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __pyx_t_7 = PyTuple_New(2); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 106, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_GIVEREF(__pyx_t_9); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_7, 0, __pyx_t_9)) __PYX_ERR(1, 106, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_s_PERSISTENT); + __Pyx_GIVEREF(__pyx_n_s_PERSISTENT); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_7, 1, __pyx_n_s_PERSISTENT)) __PYX_ERR(1, 106, __pyx_L1_error); + __pyx_t_9 = 0; + __pyx_t_9 = __Pyx_PyObject_Call(__pyx_t_8, __pyx_t_7, NULL); if (unlikely(!__pyx_t_9)) __PYX_ERR(1, 106, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(__Pyx_globals == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 106, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__Pyx_globals, __pyx_n_s_PERSISTENT, __pyx_t_9) < 0))) __PYX_ERR(1, 106, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + + /* "EnumType":107 + * pass + * __Pyx_globals['PERSISTENT'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(PERSISTENT), 'PERSISTENT') + * __Pyx_globals['CLEAR_ON_MANAGER_START'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_MANAGER_START), 'CLEAR_ON_MANAGER_START') # <<<<<<<<<<<<<< + * __Pyx_globals['CLEAR_ON_ONROAD_TRANSITION'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_ONROAD_TRANSITION), 'CLEAR_ON_ONROAD_TRANSITION') + * __Pyx_globals['CLEAR_ON_OFFROAD_TRANSITION'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_OFFROAD_TRANSITION), 'CLEAR_ON_OFFROAD_TRANSITION') + */ + __Pyx_GetModuleGlobalName(__pyx_t_9, __pyx_n_s_ParamKeyType); if (unlikely(!__pyx_t_9)) __PYX_ERR(1, 107, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __pyx_t_7 = __Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_MANAGER_START); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 107, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_8 = PyTuple_New(2); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 107, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_GIVEREF(__pyx_t_7); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_8, 0, __pyx_t_7)) __PYX_ERR(1, 107, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_s_CLEAR_ON_MANAGER_START); + __Pyx_GIVEREF(__pyx_n_s_CLEAR_ON_MANAGER_START); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_8, 1, __pyx_n_s_CLEAR_ON_MANAGER_START)) __PYX_ERR(1, 107, __pyx_L1_error); + __pyx_t_7 = 0; + __pyx_t_7 = __Pyx_PyObject_Call(__pyx_t_9, __pyx_t_8, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 107, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + if (unlikely(__Pyx_globals == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 107, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__Pyx_globals, __pyx_n_s_CLEAR_ON_MANAGER_START, __pyx_t_7) < 0))) __PYX_ERR(1, 107, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "EnumType":108 + * __Pyx_globals['PERSISTENT'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(PERSISTENT), 'PERSISTENT') + * __Pyx_globals['CLEAR_ON_MANAGER_START'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_MANAGER_START), 'CLEAR_ON_MANAGER_START') + * __Pyx_globals['CLEAR_ON_ONROAD_TRANSITION'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_ONROAD_TRANSITION), 'CLEAR_ON_ONROAD_TRANSITION') # <<<<<<<<<<<<<< + * __Pyx_globals['CLEAR_ON_OFFROAD_TRANSITION'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_OFFROAD_TRANSITION), 'CLEAR_ON_OFFROAD_TRANSITION') + * __Pyx_globals['DEVELOPMENT_ONLY'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(DEVELOPMENT_ONLY), 'DEVELOPMENT_ONLY') + */ + __Pyx_GetModuleGlobalName(__pyx_t_7, __pyx_n_s_ParamKeyType); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 108, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_8 = __Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_ONROAD_TRANSITION); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 108, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_9 = PyTuple_New(2); if (unlikely(!__pyx_t_9)) __PYX_ERR(1, 108, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_GIVEREF(__pyx_t_8); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_9, 0, __pyx_t_8)) __PYX_ERR(1, 108, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_s_CLEAR_ON_ONROAD_TRANSITION); + __Pyx_GIVEREF(__pyx_n_s_CLEAR_ON_ONROAD_TRANSITION); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_9, 1, __pyx_n_s_CLEAR_ON_ONROAD_TRANSITION)) __PYX_ERR(1, 108, __pyx_L1_error); + __pyx_t_8 = 0; + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_t_7, __pyx_t_9, NULL); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 108, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + if (unlikely(__Pyx_globals == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 108, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__Pyx_globals, __pyx_n_s_CLEAR_ON_ONROAD_TRANSITION, __pyx_t_8) < 0))) __PYX_ERR(1, 108, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + + /* "EnumType":109 + * __Pyx_globals['CLEAR_ON_MANAGER_START'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_MANAGER_START), 'CLEAR_ON_MANAGER_START') + * __Pyx_globals['CLEAR_ON_ONROAD_TRANSITION'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_ONROAD_TRANSITION), 'CLEAR_ON_ONROAD_TRANSITION') + * __Pyx_globals['CLEAR_ON_OFFROAD_TRANSITION'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_OFFROAD_TRANSITION), 'CLEAR_ON_OFFROAD_TRANSITION') # <<<<<<<<<<<<<< + * __Pyx_globals['DEVELOPMENT_ONLY'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(DEVELOPMENT_ONLY), 'DEVELOPMENT_ONLY') + * __Pyx_globals['ALL'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(ALL), 'ALL') + */ + __Pyx_GetModuleGlobalName(__pyx_t_8, __pyx_n_s_ParamKeyType); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 109, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_9 = __Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_OFFROAD_TRANSITION); if (unlikely(!__pyx_t_9)) __PYX_ERR(1, 109, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __pyx_t_7 = PyTuple_New(2); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 109, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_GIVEREF(__pyx_t_9); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_7, 0, __pyx_t_9)) __PYX_ERR(1, 109, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_s_CLEAR_ON_OFFROAD_TRANSITION); + __Pyx_GIVEREF(__pyx_n_s_CLEAR_ON_OFFROAD_TRANSITION); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_7, 1, __pyx_n_s_CLEAR_ON_OFFROAD_TRANSITION)) __PYX_ERR(1, 109, __pyx_L1_error); + __pyx_t_9 = 0; + __pyx_t_9 = __Pyx_PyObject_Call(__pyx_t_8, __pyx_t_7, NULL); if (unlikely(!__pyx_t_9)) __PYX_ERR(1, 109, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(__Pyx_globals == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 109, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__Pyx_globals, __pyx_n_s_CLEAR_ON_OFFROAD_TRANSITION, __pyx_t_9) < 0))) __PYX_ERR(1, 109, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + + /* "EnumType":110 + * __Pyx_globals['CLEAR_ON_ONROAD_TRANSITION'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_ONROAD_TRANSITION), 'CLEAR_ON_ONROAD_TRANSITION') + * __Pyx_globals['CLEAR_ON_OFFROAD_TRANSITION'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_OFFROAD_TRANSITION), 'CLEAR_ON_OFFROAD_TRANSITION') + * __Pyx_globals['DEVELOPMENT_ONLY'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(DEVELOPMENT_ONLY), 'DEVELOPMENT_ONLY') # <<<<<<<<<<<<<< + * __Pyx_globals['ALL'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(ALL), 'ALL') + * + */ + __Pyx_GetModuleGlobalName(__pyx_t_9, __pyx_n_s_ParamKeyType); if (unlikely(!__pyx_t_9)) __PYX_ERR(1, 110, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __pyx_t_7 = __Pyx_PyInt_From_enum__ParamKeyType(DEVELOPMENT_ONLY); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 110, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_8 = PyTuple_New(2); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 110, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_GIVEREF(__pyx_t_7); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_8, 0, __pyx_t_7)) __PYX_ERR(1, 110, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_s_DEVELOPMENT_ONLY); + __Pyx_GIVEREF(__pyx_n_s_DEVELOPMENT_ONLY); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_8, 1, __pyx_n_s_DEVELOPMENT_ONLY)) __PYX_ERR(1, 110, __pyx_L1_error); + __pyx_t_7 = 0; + __pyx_t_7 = __Pyx_PyObject_Call(__pyx_t_9, __pyx_t_8, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 110, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + if (unlikely(__Pyx_globals == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 110, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__Pyx_globals, __pyx_n_s_DEVELOPMENT_ONLY, __pyx_t_7) < 0))) __PYX_ERR(1, 110, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "EnumType":111 + * __Pyx_globals['CLEAR_ON_OFFROAD_TRANSITION'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(CLEAR_ON_OFFROAD_TRANSITION), 'CLEAR_ON_OFFROAD_TRANSITION') + * __Pyx_globals['DEVELOPMENT_ONLY'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(DEVELOPMENT_ONLY), 'DEVELOPMENT_ONLY') + * __Pyx_globals['ALL'] = ParamKeyType(__Pyx_PyInt_From_enum__ParamKeyType(ALL), 'ALL') # <<<<<<<<<<<<<< + * + */ + __Pyx_GetModuleGlobalName(__pyx_t_7, __pyx_n_s_ParamKeyType); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 111, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_8 = __Pyx_PyInt_From_enum__ParamKeyType(ALL); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 111, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_9 = PyTuple_New(2); if (unlikely(!__pyx_t_9)) __PYX_ERR(1, 111, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_GIVEREF(__pyx_t_8); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_9, 0, __pyx_t_8)) __PYX_ERR(1, 111, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_s_ALL); + __Pyx_GIVEREF(__pyx_n_s_ALL); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_9, 1, __pyx_n_s_ALL)) __PYX_ERR(1, 111, __pyx_L1_error); + __pyx_t_8 = 0; + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_t_7, __pyx_t_9, NULL); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 111, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + if (unlikely(__Pyx_globals == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 111, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__Pyx_globals, __pyx_n_s_ALL, __pyx_t_8) < 0))) __PYX_ERR(1, 111, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } + __pyx_L5:; + + /* "common/params_pyx.pyx":37 + * + * + * def ensure_bytes(v): # <<<<<<<<<<<<<< + * return v.encode() if isinstance(v, str) else v + * + */ + __pyx_t_8 = __Pyx_CyFunction_New(&__pyx_mdef_6common_10params_pyx_1ensure_bytes, 0, __pyx_n_s_ensure_bytes, NULL, __pyx_kp_s_common_params_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__21)); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 37, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_ensure_bytes, __pyx_t_8) < 0) __PYX_ERR(0, 37, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + + /* "common/params_pyx.pyx":40 + * return v.encode() if isinstance(v, str) else v + * + * class UnknownKeyName(Exception): # <<<<<<<<<<<<<< + * pass + * + */ + __pyx_t_8 = PyTuple_New(1); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_INCREF((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])); + __Pyx_GIVEREF((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_8, 0, ((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])))) __PYX_ERR(0, 40, __pyx_L1_error); + __pyx_t_9 = __Pyx_PEP560_update_bases(__pyx_t_8); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __pyx_t_7 = __Pyx_CalculateMetaclass(NULL, __pyx_t_9); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_6 = __Pyx_Py3MetaclassPrepare(__pyx_t_7, __pyx_t_9, __pyx_n_s_UnknownKeyName, __pyx_n_s_UnknownKeyName, (PyObject *) NULL, __pyx_kp_s_common_params_pyx, (PyObject *) NULL); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (__pyx_t_9 != __pyx_t_8) { + if (unlikely((PyDict_SetItemString(__pyx_t_6, "__orig_bases__", __pyx_t_8) < 0))) __PYX_ERR(0, 40, __pyx_L1_error) + } + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_t_8 = __Pyx_Py3ClassCreate(__pyx_t_7, __pyx_n_s_UnknownKeyName, __pyx_t_9, __pyx_t_6, NULL, 0, 0); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_UnknownKeyName, __pyx_t_8) < 0) __PYX_ERR(0, 40, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + + /* "common/params_pyx.pyx":54 + * del self.p + * + * def clear_all(self, tx_type=ParamKeyType.ALL): # <<<<<<<<<<<<<< + * self.p.clearAll(tx_type) + * + */ + __pyx_t_9 = __Pyx_Enum_enum__space_ParamKeyType_to_py(ALL); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 54, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __pyx_k__4 = __pyx_t_9; + __Pyx_GIVEREF(__pyx_t_9); + __pyx_t_9 = 0; + __pyx_t_9 = __Pyx_Enum_enum__space_ParamKeyType_to_py(ALL); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 54, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __pyx_t_7 = PyTuple_New(1); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 54, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_GIVEREF(__pyx_t_9); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_7, 0, __pyx_t_9)) __PYX_ERR(0, 54, __pyx_L1_error); + __pyx_t_9 = 0; + __pyx_t_9 = __Pyx_CyFunction_New(&__pyx_mdef_6common_10params_pyx_6Params_5clear_all, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Params_clear_all, NULL, __pyx_kp_s_common_params_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__23)); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 54, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_9, __pyx_t_7); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6common_10params_pyx_Params, __pyx_n_s_clear_all, __pyx_t_9) < 0) __PYX_ERR(0, 54, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + PyType_Modified(__pyx_ptype_6common_10params_pyx_Params); + + /* "common/params_pyx.pyx":57 + * self.p.clearAll(tx_type) + * + * def check_key(self, key): # <<<<<<<<<<<<<< + * key = ensure_bytes(key) + * if not self.p.checkKey(key): + */ + __pyx_t_9 = __Pyx_CyFunction_New(&__pyx_mdef_6common_10params_pyx_6Params_7check_key, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Params_check_key, NULL, __pyx_kp_s_common_params_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__25)); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 57, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6common_10params_pyx_Params, __pyx_n_s_check_key, __pyx_t_9) < 0) __PYX_ERR(0, 57, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + PyType_Modified(__pyx_ptype_6common_10params_pyx_Params); + + /* "common/params_pyx.pyx":63 + * return key + * + * def get(self, key, bool block=False, encoding=None): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * cdef string val + */ + __pyx_t_9 = __Pyx_CyFunction_New(&__pyx_mdef_6common_10params_pyx_6Params_9get, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Params_get, NULL, __pyx_kp_s_common_params_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__27)); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 63, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_9, __pyx_tuple__28); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6common_10params_pyx_Params, __pyx_n_s_get, __pyx_t_9) < 0) __PYX_ERR(0, 63, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + PyType_Modified(__pyx_ptype_6common_10params_pyx_Params); + + /* "common/params_pyx.pyx":79 + * return val if encoding is None else val.decode(encoding) + * + * def get_bool(self, key, bool block=False): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * cdef bool r + */ + __pyx_t_9 = __Pyx_CyFunction_New(&__pyx_mdef_6common_10params_pyx_6Params_11get_bool, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Params_get_bool, NULL, __pyx_kp_s_common_params_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__30)); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 79, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_9, __pyx_tuple__31); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6common_10params_pyx_Params, __pyx_n_s_get_bool, __pyx_t_9) < 0) __PYX_ERR(0, 79, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + PyType_Modified(__pyx_ptype_6common_10params_pyx_Params); + + /* "common/params_pyx.pyx":86 + * return r + * + * def get_int(self, key, bool block=False): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * cdef int r + */ + __pyx_t_9 = __Pyx_CyFunction_New(&__pyx_mdef_6common_10params_pyx_6Params_13get_int, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Params_get_int, NULL, __pyx_kp_s_common_params_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__32)); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 86, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_9, __pyx_tuple__31); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6common_10params_pyx_Params, __pyx_n_s_get_int, __pyx_t_9) < 0) __PYX_ERR(0, 86, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + PyType_Modified(__pyx_ptype_6common_10params_pyx_Params); + + /* "common/params_pyx.pyx":93 + * return r + * + * def get_float(self, key, bool block=False): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * cdef float r + */ + __pyx_t_9 = __Pyx_CyFunction_New(&__pyx_mdef_6common_10params_pyx_6Params_15get_float, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Params_get_float, NULL, __pyx_kp_s_common_params_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__33)); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 93, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_9, __pyx_tuple__31); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6common_10params_pyx_Params, __pyx_n_s_get_float, __pyx_t_9) < 0) __PYX_ERR(0, 93, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + PyType_Modified(__pyx_ptype_6common_10params_pyx_Params); + + /* "common/params_pyx.pyx":100 + * return r + * + * def put(self, key, dat): # <<<<<<<<<<<<<< + * """ + * Warning: This function blocks until the param is written to disk! + */ + __pyx_t_9 = __Pyx_CyFunction_New(&__pyx_mdef_6common_10params_pyx_6Params_17put, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Params_put, NULL, __pyx_kp_s_common_params_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__35)); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6common_10params_pyx_Params, __pyx_n_s_put, __pyx_t_9) < 0) __PYX_ERR(0, 100, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + PyType_Modified(__pyx_ptype_6common_10params_pyx_Params); + + /* "common/params_pyx.pyx":112 + * self.p.put(k, dat_bytes) + * + * def put_bool(self, key, bool val): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * with nogil: + */ + __pyx_t_9 = __Pyx_CyFunction_New(&__pyx_mdef_6common_10params_pyx_6Params_19put_bool, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Params_put_bool, NULL, __pyx_kp_s_common_params_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__37)); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 112, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6common_10params_pyx_Params, __pyx_n_s_put_bool, __pyx_t_9) < 0) __PYX_ERR(0, 112, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + PyType_Modified(__pyx_ptype_6common_10params_pyx_Params); + + /* "common/params_pyx.pyx":117 + * self.p.putBool(k, val) + * + * def put_int(self, key, int val): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * with nogil: + */ + __pyx_t_9 = __Pyx_CyFunction_New(&__pyx_mdef_6common_10params_pyx_6Params_21put_int, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Params_put_int, NULL, __pyx_kp_s_common_params_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__38)); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 117, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6common_10params_pyx_Params, __pyx_n_s_put_int, __pyx_t_9) < 0) __PYX_ERR(0, 117, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + PyType_Modified(__pyx_ptype_6common_10params_pyx_Params); + + /* "common/params_pyx.pyx":122 + * self.p.putInt(k, val) + * + * def put_float(self, key, float val): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * with nogil: + */ + __pyx_t_9 = __Pyx_CyFunction_New(&__pyx_mdef_6common_10params_pyx_6Params_23put_float, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Params_put_float, NULL, __pyx_kp_s_common_params_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__39)); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 122, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6common_10params_pyx_Params, __pyx_n_s_put_float, __pyx_t_9) < 0) __PYX_ERR(0, 122, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + PyType_Modified(__pyx_ptype_6common_10params_pyx_Params); + + /* "common/params_pyx.pyx":127 + * self.p.putFloat(k, val) + * + * def put_nonblocking(self, key, dat): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * cdef string dat_bytes = ensure_bytes(dat) + */ + __pyx_t_9 = __Pyx_CyFunction_New(&__pyx_mdef_6common_10params_pyx_6Params_25put_nonblocking, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Params_put_nonblocking, NULL, __pyx_kp_s_common_params_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__40)); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 127, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6common_10params_pyx_Params, __pyx_n_s_put_nonblocking, __pyx_t_9) < 0) __PYX_ERR(0, 127, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + PyType_Modified(__pyx_ptype_6common_10params_pyx_Params); + + /* "common/params_pyx.pyx":133 + * self.p.putNonBlocking(k, dat_bytes) + * + * def put_bool_nonblocking(self, key, bool val): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * with nogil: + */ + __pyx_t_9 = __Pyx_CyFunction_New(&__pyx_mdef_6common_10params_pyx_6Params_27put_bool_nonblocking, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Params_put_bool_nonblocking, NULL, __pyx_kp_s_common_params_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__41)); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 133, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6common_10params_pyx_Params, __pyx_n_s_put_bool_nonblocking, __pyx_t_9) < 0) __PYX_ERR(0, 133, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + PyType_Modified(__pyx_ptype_6common_10params_pyx_Params); + + /* "common/params_pyx.pyx":138 + * self.p.putBoolNonBlocking(k, val) + * + * def put_int_nonblocking(self, key, int val): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * with nogil: + */ + __pyx_t_9 = __Pyx_CyFunction_New(&__pyx_mdef_6common_10params_pyx_6Params_29put_int_nonblocking, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Params_put_int_nonblocking, NULL, __pyx_kp_s_common_params_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__42)); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 138, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6common_10params_pyx_Params, __pyx_n_s_put_int_nonblocking, __pyx_t_9) < 0) __PYX_ERR(0, 138, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + PyType_Modified(__pyx_ptype_6common_10params_pyx_Params); + + /* "common/params_pyx.pyx":143 + * self.p.putIntNonBlocking(k, val) + * + * def put_float_nonblocking(self, key, float val): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * with nogil: + */ + __pyx_t_9 = __Pyx_CyFunction_New(&__pyx_mdef_6common_10params_pyx_6Params_31put_float_nonblocking, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Params_put_float_nonblocking, NULL, __pyx_kp_s_common_params_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__43)); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6common_10params_pyx_Params, __pyx_n_s_put_float_nonblocking, __pyx_t_9) < 0) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + PyType_Modified(__pyx_ptype_6common_10params_pyx_Params); + + /* "common/params_pyx.pyx":148 + * self.p.putFloatNonBlocking(k, val) + * + * def remove(self, key): # <<<<<<<<<<<<<< + * cdef string k = self.check_key(key) + * with nogil: + */ + __pyx_t_9 = __Pyx_CyFunction_New(&__pyx_mdef_6common_10params_pyx_6Params_33remove, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Params_remove, NULL, __pyx_kp_s_common_params_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__45)); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 148, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6common_10params_pyx_Params, __pyx_n_s_remove, __pyx_t_9) < 0) __PYX_ERR(0, 148, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + PyType_Modified(__pyx_ptype_6common_10params_pyx_Params); + + /* "common/params_pyx.pyx":153 + * self.p.remove(k) + * + * def get_param_path(self, key=""): # <<<<<<<<<<<<<< + * cdef string key_bytes = ensure_bytes(key) + * return self.p.getParamPath(key_bytes).decode("utf-8") + */ + __pyx_t_9 = __Pyx_CyFunction_New(&__pyx_mdef_6common_10params_pyx_6Params_35get_param_path, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Params_get_param_path, NULL, __pyx_kp_s_common_params_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__47)); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 153, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_9, __pyx_tuple__48); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6common_10params_pyx_Params, __pyx_n_s_get_param_path, __pyx_t_9) < 0) __PYX_ERR(0, 153, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + PyType_Modified(__pyx_ptype_6common_10params_pyx_Params); + + /* "common/params_pyx.pyx":157 + * return self.p.getParamPath(key_bytes).decode("utf-8") + * + * def all_keys(self): # <<<<<<<<<<<<<< + * return self.p.allKeys() + */ + __pyx_t_9 = __Pyx_CyFunction_New(&__pyx_mdef_6common_10params_pyx_6Params_37all_keys, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Params_all_keys, NULL, __pyx_kp_s_common_params_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__49)); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 157, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6common_10params_pyx_Params, __pyx_n_s_all_keys, __pyx_t_9) < 0) __PYX_ERR(0, 157, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + PyType_Modified(__pyx_ptype_6common_10params_pyx_Params); + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_t_9 = __Pyx_CyFunction_New(&__pyx_mdef_6common_10params_pyx_6Params_39__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Params___reduce_cython, NULL, __pyx_kp_s_common_params_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__50)); if (unlikely(!__pyx_t_9)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_9) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_t_9 = __Pyx_CyFunction_New(&__pyx_mdef_6common_10params_pyx_6Params_41__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_Params___setstate_cython, NULL, __pyx_kp_s_common_params_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__51)); if (unlikely(!__pyx_t_9)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_9) < 0) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + + /* "common/params_pyx.pyx":1 + * # distutils: language = c++ # <<<<<<<<<<<<<< + * # cython: language_level = 3 + * from libcpp cimport bool + */ + __pyx_t_9 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_test, __pyx_t_9) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + + /*--- Wrapped vars code ---*/ + + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_XDECREF(__pyx_t_9); + if (__pyx_m) { + if (__pyx_d && stringtab_initialized) { + __Pyx_AddTraceback("init common.params_pyx", __pyx_clineno, __pyx_lineno, __pyx_filename); + } + #if !CYTHON_USE_MODULE_STATE + Py_CLEAR(__pyx_m); + #else + Py_DECREF(__pyx_m); + if (pystate_addmodule_run) { + PyObject *tp, *value, *tb; + PyErr_Fetch(&tp, &value, &tb); + PyState_RemoveModule(&__pyx_moduledef); + PyErr_Restore(tp, value, tb); + } + #endif + } else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_ImportError, "init common.params_pyx"); + } + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + #if CYTHON_PEP489_MULTI_PHASE_INIT + return (__pyx_m != NULL) ? 0 : -1; + #elif PY_MAJOR_VERSION >= 3 + return __pyx_m; + #else + return; + #endif +} +/* #### Code section: cleanup_globals ### */ +/* #### Code section: cleanup_module ### */ +/* #### Code section: main_method ### */ +/* #### Code section: utility_code_pragmas ### */ +#ifdef _MSC_VER +#pragma warning( push ) +/* Warning 4127: conditional expression is constant + * Cython uses constant conditional expressions to allow in inline functions to be optimized at + * compile-time, so this warning is not useful + */ +#pragma warning( disable : 4127 ) +#endif + + + +/* #### Code section: utility_code_def ### */ + +/* --- Runtime support code --- */ +/* Refnanny */ +#if CYTHON_REFNANNY +static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname) { + PyObject *m = NULL, *p = NULL; + void *r = NULL; + m = PyImport_ImportModule(modname); + if (!m) goto end; + p = PyObject_GetAttrString(m, "RefNannyAPI"); + if (!p) goto end; + r = PyLong_AsVoidPtr(p); +end: + Py_XDECREF(p); + Py_XDECREF(m); + return (__Pyx_RefNannyAPIStruct *)r; +} +#endif + +/* PyErrExceptionMatches */ +#if CYTHON_FAST_THREAD_STATE +static int __Pyx_PyErr_ExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; i= 0x030C00A6 + PyObject *current_exception = tstate->current_exception; + if (unlikely(!current_exception)) return 0; + exc_type = (PyObject*) Py_TYPE(current_exception); + if (exc_type == err) return 1; +#else + exc_type = tstate->curexc_type; + if (exc_type == err) return 1; + if (unlikely(!exc_type)) return 0; +#endif + #if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(exc_type); + #endif + if (unlikely(PyTuple_Check(err))) { + result = __Pyx_PyErr_ExceptionMatchesTuple(exc_type, err); + } else { + result = __Pyx_PyErr_GivenExceptionMatches(exc_type, err); + } + #if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(exc_type); + #endif + return result; +} +#endif + +/* PyErrFetchRestore */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject *tmp_value; + assert(type == NULL || (value != NULL && type == (PyObject*) Py_TYPE(value))); + if (value) { + #if CYTHON_COMPILING_IN_CPYTHON + if (unlikely(((PyBaseExceptionObject*) value)->traceback != tb)) + #endif + PyException_SetTraceback(value, tb); + } + tmp_value = tstate->current_exception; + tstate->current_exception = value; + Py_XDECREF(tmp_value); + Py_XDECREF(type); + Py_XDECREF(tb); +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + tmp_type = tstate->curexc_type; + tmp_value = tstate->curexc_value; + tmp_tb = tstate->curexc_traceback; + tstate->curexc_type = type; + tstate->curexc_value = value; + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); +#endif +} +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject* exc_value; + exc_value = tstate->current_exception; + tstate->current_exception = 0; + *value = exc_value; + *type = NULL; + *tb = NULL; + if (exc_value) { + *type = (PyObject*) Py_TYPE(exc_value); + Py_INCREF(*type); + #if CYTHON_COMPILING_IN_CPYTHON + *tb = ((PyBaseExceptionObject*) exc_value)->traceback; + Py_XINCREF(*tb); + #else + *tb = PyException_GetTraceback(exc_value); + #endif + } +#else + *type = tstate->curexc_type; + *value = tstate->curexc_value; + *tb = tstate->curexc_traceback; + tstate->curexc_type = 0; + tstate->curexc_value = 0; + tstate->curexc_traceback = 0; +#endif +} +#endif + +/* PyObjectGetAttrStr */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name) { + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro)) + return tp->tp_getattro(obj, attr_name); +#if PY_MAJOR_VERSION < 3 + if (likely(tp->tp_getattr)) + return tp->tp_getattr(obj, PyString_AS_STRING(attr_name)); +#endif + return PyObject_GetAttr(obj, attr_name); +} +#endif + +/* PyObjectGetAttrStrNoError */ +#if __PYX_LIMITED_VERSION_HEX < 0x030d00A1 +static void __Pyx_PyObject_GetAttrStr_ClearAttributeError(void) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + if (likely(__Pyx_PyErr_ExceptionMatches(PyExc_AttributeError))) + __Pyx_PyErr_Clear(); +} +#endif +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name) { + PyObject *result; +#if __PYX_LIMITED_VERSION_HEX >= 0x030d00A1 + (void) PyObject_GetOptionalAttr(obj, attr_name, &result); + return result; +#else +#if CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_TYPE_SLOTS && PY_VERSION_HEX >= 0x030700B1 + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro == PyObject_GenericGetAttr)) { + return _PyObject_GenericGetAttrWithDict(obj, attr_name, NULL, 1); + } +#endif + result = __Pyx_PyObject_GetAttrStr(obj, attr_name); + if (unlikely(!result)) { + __Pyx_PyObject_GetAttrStr_ClearAttributeError(); + } + return result; +#endif +} + +/* GetBuiltinName */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name) { + PyObject* result = __Pyx_PyObject_GetAttrStrNoError(__pyx_b, name); + if (unlikely(!result) && !PyErr_Occurred()) { + PyErr_Format(PyExc_NameError, +#if PY_MAJOR_VERSION >= 3 + "name '%U' is not defined", name); +#else + "name '%.200s' is not defined", PyString_AS_STRING(name)); +#endif + } + return result; +} + +/* PyDictVersioning */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + return likely(dict) ? __PYX_GET_DICT_VERSION(dict) : 0; +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj) { + PyObject **dictptr = NULL; + Py_ssize_t offset = Py_TYPE(obj)->tp_dictoffset; + if (offset) { +#if CYTHON_COMPILING_IN_CPYTHON + dictptr = (likely(offset > 0)) ? (PyObject **) ((char *)obj + offset) : _PyObject_GetDictPtr(obj); +#else + dictptr = _PyObject_GetDictPtr(obj); +#endif + } + return (dictptr && *dictptr) ? __PYX_GET_DICT_VERSION(*dictptr) : 0; +} +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + if (unlikely(!dict) || unlikely(tp_dict_version != __PYX_GET_DICT_VERSION(dict))) + return 0; + return obj_dict_version == __Pyx_get_object_dict_version(obj); +} +#endif + +/* GetModuleGlobalName */ +#if CYTHON_USE_DICT_VERSIONS +static PyObject *__Pyx__GetModuleGlobalName(PyObject *name, PY_UINT64_T *dict_version, PyObject **dict_cached_value) +#else +static CYTHON_INLINE PyObject *__Pyx__GetModuleGlobalName(PyObject *name) +#endif +{ + PyObject *result; +#if !CYTHON_AVOID_BORROWED_REFS +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030500A1 && PY_VERSION_HEX < 0x030d0000 + result = _PyDict_GetItem_KnownHash(__pyx_d, name, ((PyASCIIObject *) name)->hash); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } else if (unlikely(PyErr_Occurred())) { + return NULL; + } +#elif CYTHON_COMPILING_IN_LIMITED_API + if (unlikely(!__pyx_m)) { + return NULL; + } + result = PyObject_GetAttr(__pyx_m, name); + if (likely(result)) { + return result; + } +#else + result = PyDict_GetItem(__pyx_d, name); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } +#endif +#else + result = PyObject_GetItem(__pyx_d, name); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } + PyErr_Clear(); +#endif + return __Pyx_GetBuiltinName(name); +} + +/* PyFunctionFastCall */ +#if CYTHON_FAST_PYCALL && !CYTHON_VECTORCALL +static PyObject* __Pyx_PyFunction_FastCallNoKw(PyCodeObject *co, PyObject **args, Py_ssize_t na, + PyObject *globals) { + PyFrameObject *f; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject **fastlocals; + Py_ssize_t i; + PyObject *result; + assert(globals != NULL); + /* XXX Perhaps we should create a specialized + PyFrame_New() that doesn't take locals, but does + take builtins without sanity checking them. + */ + assert(tstate != NULL); + f = PyFrame_New(tstate, co, globals, NULL); + if (f == NULL) { + return NULL; + } + fastlocals = __Pyx_PyFrame_GetLocalsplus(f); + for (i = 0; i < na; i++) { + Py_INCREF(*args); + fastlocals[i] = *args++; + } + result = PyEval_EvalFrameEx(f,0); + ++tstate->recursion_depth; + Py_DECREF(f); + --tstate->recursion_depth; + return result; +} +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs) { + PyCodeObject *co = (PyCodeObject *)PyFunction_GET_CODE(func); + PyObject *globals = PyFunction_GET_GLOBALS(func); + PyObject *argdefs = PyFunction_GET_DEFAULTS(func); + PyObject *closure; +#if PY_MAJOR_VERSION >= 3 + PyObject *kwdefs; +#endif + PyObject *kwtuple, **k; + PyObject **d; + Py_ssize_t nd; + Py_ssize_t nk; + PyObject *result; + assert(kwargs == NULL || PyDict_Check(kwargs)); + nk = kwargs ? PyDict_Size(kwargs) : 0; + #if PY_MAJOR_VERSION < 3 + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) { + return NULL; + } + #else + if (unlikely(Py_EnterRecursiveCall(" while calling a Python object"))) { + return NULL; + } + #endif + if ( +#if PY_MAJOR_VERSION >= 3 + co->co_kwonlyargcount == 0 && +#endif + likely(kwargs == NULL || nk == 0) && + co->co_flags == (CO_OPTIMIZED | CO_NEWLOCALS | CO_NOFREE)) { + if (argdefs == NULL && co->co_argcount == nargs) { + result = __Pyx_PyFunction_FastCallNoKw(co, args, nargs, globals); + goto done; + } + else if (nargs == 0 && argdefs != NULL + && co->co_argcount == Py_SIZE(argdefs)) { + /* function called with no arguments, but all parameters have + a default value: use default values as arguments .*/ + args = &PyTuple_GET_ITEM(argdefs, 0); + result =__Pyx_PyFunction_FastCallNoKw(co, args, Py_SIZE(argdefs), globals); + goto done; + } + } + if (kwargs != NULL) { + Py_ssize_t pos, i; + kwtuple = PyTuple_New(2 * nk); + if (kwtuple == NULL) { + result = NULL; + goto done; + } + k = &PyTuple_GET_ITEM(kwtuple, 0); + pos = i = 0; + while (PyDict_Next(kwargs, &pos, &k[i], &k[i+1])) { + Py_INCREF(k[i]); + Py_INCREF(k[i+1]); + i += 2; + } + nk = i / 2; + } + else { + kwtuple = NULL; + k = NULL; + } + closure = PyFunction_GET_CLOSURE(func); +#if PY_MAJOR_VERSION >= 3 + kwdefs = PyFunction_GET_KW_DEFAULTS(func); +#endif + if (argdefs != NULL) { + d = &PyTuple_GET_ITEM(argdefs, 0); + nd = Py_SIZE(argdefs); + } + else { + d = NULL; + nd = 0; + } +#if PY_MAJOR_VERSION >= 3 + result = PyEval_EvalCodeEx((PyObject*)co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, kwdefs, closure); +#else + result = PyEval_EvalCodeEx(co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, closure); +#endif + Py_XDECREF(kwtuple); +done: + Py_LeaveRecursiveCall(); + return result; +} +#endif + +/* PyObjectCall */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw) { + PyObject *result; + ternaryfunc call = Py_TYPE(func)->tp_call; + if (unlikely(!call)) + return PyObject_Call(func, arg, kw); + #if PY_MAJOR_VERSION < 3 + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + #else + if (unlikely(Py_EnterRecursiveCall(" while calling a Python object"))) + return NULL; + #endif + result = (*call)(func, arg, kw); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* PyObjectCallMethO */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg) { + PyObject *self, *result; + PyCFunction cfunc; + cfunc = __Pyx_CyOrPyCFunction_GET_FUNCTION(func); + self = __Pyx_CyOrPyCFunction_GET_SELF(func); + #if PY_MAJOR_VERSION < 3 + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + #else + if (unlikely(Py_EnterRecursiveCall(" while calling a Python object"))) + return NULL; + #endif + result = cfunc(self, arg); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* PyObjectFastCall */ +#if PY_VERSION_HEX < 0x03090000 || CYTHON_COMPILING_IN_LIMITED_API +static PyObject* __Pyx_PyObject_FastCall_fallback(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs) { + PyObject *argstuple; + PyObject *result = 0; + size_t i; + argstuple = PyTuple_New((Py_ssize_t)nargs); + if (unlikely(!argstuple)) return NULL; + for (i = 0; i < nargs; i++) { + Py_INCREF(args[i]); + if (__Pyx_PyTuple_SET_ITEM(argstuple, (Py_ssize_t)i, args[i]) < 0) goto bad; + } + result = __Pyx_PyObject_Call(func, argstuple, kwargs); + bad: + Py_DECREF(argstuple); + return result; +} +#endif +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t _nargs, PyObject *kwargs) { + Py_ssize_t nargs = __Pyx_PyVectorcall_NARGS(_nargs); +#if CYTHON_COMPILING_IN_CPYTHON + if (nargs == 0 && kwargs == NULL) { + if (__Pyx_CyOrPyCFunction_Check(func) && likely( __Pyx_CyOrPyCFunction_GET_FLAGS(func) & METH_NOARGS)) + return __Pyx_PyObject_CallMethO(func, NULL); + } + else if (nargs == 1 && kwargs == NULL) { + if (__Pyx_CyOrPyCFunction_Check(func) && likely( __Pyx_CyOrPyCFunction_GET_FLAGS(func) & METH_O)) + return __Pyx_PyObject_CallMethO(func, args[0]); + } +#endif + #if PY_VERSION_HEX < 0x030800B1 + #if CYTHON_FAST_PYCCALL + if (PyCFunction_Check(func)) { + if (kwargs) { + return _PyCFunction_FastCallDict(func, args, nargs, kwargs); + } else { + return _PyCFunction_FastCallKeywords(func, args, nargs, NULL); + } + } + #if PY_VERSION_HEX >= 0x030700A1 + if (!kwargs && __Pyx_IS_TYPE(func, &PyMethodDescr_Type)) { + return _PyMethodDescr_FastCallKeywords(func, args, nargs, NULL); + } + #endif + #endif + #if CYTHON_FAST_PYCALL + if (PyFunction_Check(func)) { + return __Pyx_PyFunction_FastCallDict(func, args, nargs, kwargs); + } + #endif + #endif + if (kwargs == NULL) { + #if CYTHON_VECTORCALL + #if PY_VERSION_HEX < 0x03090000 + vectorcallfunc f = _PyVectorcall_Function(func); + #else + vectorcallfunc f = PyVectorcall_Function(func); + #endif + if (f) { + return f(func, args, (size_t)nargs, NULL); + } + #elif defined(__Pyx_CyFunction_USED) && CYTHON_BACKPORT_VECTORCALL + if (__Pyx_CyFunction_CheckExact(func)) { + __pyx_vectorcallfunc f = __Pyx_CyFunction_func_vectorcall(func); + if (f) return f(func, args, (size_t)nargs, NULL); + } + #endif + } + if (nargs == 0) { + return __Pyx_PyObject_Call(func, __pyx_empty_tuple, kwargs); + } + #if PY_VERSION_HEX >= 0x03090000 && !CYTHON_COMPILING_IN_LIMITED_API + return PyObject_VectorcallDict(func, args, (size_t)nargs, kwargs); + #else + return __Pyx_PyObject_FastCall_fallback(func, args, (size_t)nargs, kwargs); + #endif +} + +/* TupleAndListFromArray */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE void __Pyx_copy_object_array(PyObject *const *CYTHON_RESTRICT src, PyObject** CYTHON_RESTRICT dest, Py_ssize_t length) { + PyObject *v; + Py_ssize_t i; + for (i = 0; i < length; i++) { + v = dest[i] = src[i]; + Py_INCREF(v); + } +} +static CYTHON_INLINE PyObject * +__Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + Py_INCREF(__pyx_empty_tuple); + return __pyx_empty_tuple; + } + res = PyTuple_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyTupleObject*)res)->ob_item, n); + return res; +} +static CYTHON_INLINE PyObject * +__Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + return PyList_New(0); + } + res = PyList_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyListObject*)res)->ob_item, n); + return res; +} +#endif + +/* BytesEquals */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else + if (s1 == s2) { + return (equals == Py_EQ); + } else if (PyBytes_CheckExact(s1) & PyBytes_CheckExact(s2)) { + const char *ps1, *ps2; + Py_ssize_t length = PyBytes_GET_SIZE(s1); + if (length != PyBytes_GET_SIZE(s2)) + return (equals == Py_NE); + ps1 = PyBytes_AS_STRING(s1); + ps2 = PyBytes_AS_STRING(s2); + if (ps1[0] != ps2[0]) { + return (equals == Py_NE); + } else if (length == 1) { + return (equals == Py_EQ); + } else { + int result; +#if CYTHON_USE_UNICODE_INTERNALS && (PY_VERSION_HEX < 0x030B0000) + Py_hash_t hash1, hash2; + hash1 = ((PyBytesObject*)s1)->ob_shash; + hash2 = ((PyBytesObject*)s2)->ob_shash; + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + return (equals == Py_NE); + } +#endif + result = memcmp(ps1, ps2, (size_t)length); + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & PyBytes_CheckExact(s2)) { + return (equals == Py_NE); + } else if ((s2 == Py_None) & PyBytes_CheckExact(s1)) { + return (equals == Py_NE); + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +#endif +} + +/* UnicodeEquals */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else +#if PY_MAJOR_VERSION < 3 + PyObject* owned_ref = NULL; +#endif + int s1_is_unicode, s2_is_unicode; + if (s1 == s2) { + goto return_eq; + } + s1_is_unicode = PyUnicode_CheckExact(s1); + s2_is_unicode = PyUnicode_CheckExact(s2); +#if PY_MAJOR_VERSION < 3 + if ((s1_is_unicode & (!s2_is_unicode)) && PyString_CheckExact(s2)) { + owned_ref = PyUnicode_FromObject(s2); + if (unlikely(!owned_ref)) + return -1; + s2 = owned_ref; + s2_is_unicode = 1; + } else if ((s2_is_unicode & (!s1_is_unicode)) && PyString_CheckExact(s1)) { + owned_ref = PyUnicode_FromObject(s1); + if (unlikely(!owned_ref)) + return -1; + s1 = owned_ref; + s1_is_unicode = 1; + } else if (((!s2_is_unicode) & (!s1_is_unicode))) { + return __Pyx_PyBytes_Equals(s1, s2, equals); + } +#endif + if (s1_is_unicode & s2_is_unicode) { + Py_ssize_t length; + int kind; + void *data1, *data2; + if (unlikely(__Pyx_PyUnicode_READY(s1) < 0) || unlikely(__Pyx_PyUnicode_READY(s2) < 0)) + return -1; + length = __Pyx_PyUnicode_GET_LENGTH(s1); + if (length != __Pyx_PyUnicode_GET_LENGTH(s2)) { + goto return_ne; + } +#if CYTHON_USE_UNICODE_INTERNALS + { + Py_hash_t hash1, hash2; + #if CYTHON_PEP393_ENABLED + hash1 = ((PyASCIIObject*)s1)->hash; + hash2 = ((PyASCIIObject*)s2)->hash; + #else + hash1 = ((PyUnicodeObject*)s1)->hash; + hash2 = ((PyUnicodeObject*)s2)->hash; + #endif + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + goto return_ne; + } + } +#endif + kind = __Pyx_PyUnicode_KIND(s1); + if (kind != __Pyx_PyUnicode_KIND(s2)) { + goto return_ne; + } + data1 = __Pyx_PyUnicode_DATA(s1); + data2 = __Pyx_PyUnicode_DATA(s2); + if (__Pyx_PyUnicode_READ(kind, data1, 0) != __Pyx_PyUnicode_READ(kind, data2, 0)) { + goto return_ne; + } else if (length == 1) { + goto return_eq; + } else { + int result = memcmp(data1, data2, (size_t)(length * kind)); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & s2_is_unicode) { + goto return_ne; + } else if ((s2 == Py_None) & s1_is_unicode) { + goto return_ne; + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +return_eq: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ); +return_ne: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_NE); +#endif +} + +/* fastcall */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s) +{ + Py_ssize_t i, n = PyTuple_GET_SIZE(kwnames); + for (i = 0; i < n; i++) + { + if (s == PyTuple_GET_ITEM(kwnames, i)) return kwvalues[i]; + } + for (i = 0; i < n; i++) + { + int eq = __Pyx_PyUnicode_Equals(s, PyTuple_GET_ITEM(kwnames, i), Py_EQ); + if (unlikely(eq != 0)) { + if (unlikely(eq < 0)) return NULL; + return kwvalues[i]; + } + } + return NULL; +} +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 +CYTHON_UNUSED static PyObject *__Pyx_KwargsAsDict_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues) { + Py_ssize_t i, nkwargs = PyTuple_GET_SIZE(kwnames); + PyObject *dict; + dict = PyDict_New(); + if (unlikely(!dict)) + return NULL; + for (i=0; i= 3 + "%s() got multiple values for keyword argument '%U'", func_name, kw_name); + #else + "%s() got multiple values for keyword argument '%s'", func_name, + PyString_AsString(kw_name)); + #endif +} + +/* ParseKeywords */ +static int __Pyx_ParseOptionalKeywords( + PyObject *kwds, + PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, + PyObject *values[], + Py_ssize_t num_pos_args, + const char* function_name) +{ + PyObject *key = 0, *value = 0; + Py_ssize_t pos = 0; + PyObject*** name; + PyObject*** first_kw_arg = argnames + num_pos_args; + int kwds_is_tuple = CYTHON_METH_FASTCALL && likely(PyTuple_Check(kwds)); + while (1) { + Py_XDECREF(key); key = NULL; + Py_XDECREF(value); value = NULL; + if (kwds_is_tuple) { + Py_ssize_t size; +#if CYTHON_ASSUME_SAFE_MACROS + size = PyTuple_GET_SIZE(kwds); +#else + size = PyTuple_Size(kwds); + if (size < 0) goto bad; +#endif + if (pos >= size) break; +#if CYTHON_AVOID_BORROWED_REFS + key = __Pyx_PySequence_ITEM(kwds, pos); + if (!key) goto bad; +#elif CYTHON_ASSUME_SAFE_MACROS + key = PyTuple_GET_ITEM(kwds, pos); +#else + key = PyTuple_GetItem(kwds, pos); + if (!key) goto bad; +#endif + value = kwvalues[pos]; + pos++; + } + else + { + if (!PyDict_Next(kwds, &pos, &key, &value)) break; +#if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(key); +#endif + } + name = first_kw_arg; + while (*name && (**name != key)) name++; + if (*name) { + values[name-argnames] = value; +#if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(value); + Py_DECREF(key); +#endif + key = NULL; + value = NULL; + continue; + } +#if !CYTHON_AVOID_BORROWED_REFS + Py_INCREF(key); +#endif + Py_INCREF(value); + name = first_kw_arg; + #if PY_MAJOR_VERSION < 3 + if (likely(PyString_Check(key))) { + while (*name) { + if ((CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**name) == PyString_GET_SIZE(key)) + && _PyString_Eq(**name, key)) { + values[name-argnames] = value; +#if CYTHON_AVOID_BORROWED_REFS + value = NULL; +#endif + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + if ((**argname == key) || ( + (CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**argname) == PyString_GET_SIZE(key)) + && _PyString_Eq(**argname, key))) { + goto arg_passed_twice; + } + argname++; + } + } + } else + #endif + if (likely(PyUnicode_Check(key))) { + while (*name) { + int cmp = ( + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**name) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**name, key) + ); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) { + values[name-argnames] = value; +#if CYTHON_AVOID_BORROWED_REFS + value = NULL; +#endif + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + int cmp = (**argname == key) ? 0 : + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**argname) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**argname, key); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) goto arg_passed_twice; + argname++; + } + } + } else + goto invalid_keyword_type; + if (kwds2) { + if (unlikely(PyDict_SetItem(kwds2, key, value))) goto bad; + } else { + goto invalid_keyword; + } + } + Py_XDECREF(key); + Py_XDECREF(value); + return 0; +arg_passed_twice: + __Pyx_RaiseDoubleKeywordsError(function_name, key); + goto bad; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + goto bad; +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif +bad: + Py_XDECREF(key); + Py_XDECREF(value); + return -1; +} + +/* PyObjectSetAttrStr */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE int __Pyx_PyObject_SetAttrStr(PyObject* obj, PyObject* attr_name, PyObject* value) { + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_setattro)) + return tp->tp_setattro(obj, attr_name, value); +#if PY_MAJOR_VERSION < 3 + if (likely(tp->tp_setattr)) + return tp->tp_setattr(obj, PyString_AS_STRING(attr_name), value); +#endif + return PyObject_SetAttr(obj, attr_name, value); +} +#endif + +/* GetItemInt */ +static PyObject *__Pyx_GetItemInt_Generic(PyObject *o, PyObject* j) { + PyObject *r; + if (unlikely(!j)) return NULL; + r = PyObject_GetItem(o, j); + Py_DECREF(j); + return r; +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_List_Fast(PyObject *o, Py_ssize_t i, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + Py_ssize_t wrapped_i = i; + if (wraparound & unlikely(i < 0)) { + wrapped_i += PyList_GET_SIZE(o); + } + if ((!boundscheck) || likely(__Pyx_is_valid_index(wrapped_i, PyList_GET_SIZE(o)))) { + PyObject *r = PyList_GET_ITEM(o, wrapped_i); + Py_INCREF(r); + return r; + } + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +#else + return PySequence_GetItem(o, i); +#endif +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Tuple_Fast(PyObject *o, Py_ssize_t i, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + Py_ssize_t wrapped_i = i; + if (wraparound & unlikely(i < 0)) { + wrapped_i += PyTuple_GET_SIZE(o); + } + if ((!boundscheck) || likely(__Pyx_is_valid_index(wrapped_i, PyTuple_GET_SIZE(o)))) { + PyObject *r = PyTuple_GET_ITEM(o, wrapped_i); + Py_INCREF(r); + return r; + } + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +#else + return PySequence_GetItem(o, i); +#endif +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Fast(PyObject *o, Py_ssize_t i, int is_list, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS && CYTHON_USE_TYPE_SLOTS + if (is_list || PyList_CheckExact(o)) { + Py_ssize_t n = ((!wraparound) | likely(i >= 0)) ? i : i + PyList_GET_SIZE(o); + if ((!boundscheck) || (likely(__Pyx_is_valid_index(n, PyList_GET_SIZE(o))))) { + PyObject *r = PyList_GET_ITEM(o, n); + Py_INCREF(r); + return r; + } + } + else if (PyTuple_CheckExact(o)) { + Py_ssize_t n = ((!wraparound) | likely(i >= 0)) ? i : i + PyTuple_GET_SIZE(o); + if ((!boundscheck) || likely(__Pyx_is_valid_index(n, PyTuple_GET_SIZE(o)))) { + PyObject *r = PyTuple_GET_ITEM(o, n); + Py_INCREF(r); + return r; + } + } else { + PyMappingMethods *mm = Py_TYPE(o)->tp_as_mapping; + PySequenceMethods *sm = Py_TYPE(o)->tp_as_sequence; + if (mm && mm->mp_subscript) { + PyObject *r, *key = PyInt_FromSsize_t(i); + if (unlikely(!key)) return NULL; + r = mm->mp_subscript(o, key); + Py_DECREF(key); + return r; + } + if (likely(sm && sm->sq_item)) { + if (wraparound && unlikely(i < 0) && likely(sm->sq_length)) { + Py_ssize_t l = sm->sq_length(o); + if (likely(l >= 0)) { + i += l; + } else { + if (!PyErr_ExceptionMatches(PyExc_OverflowError)) + return NULL; + PyErr_Clear(); + } + } + return sm->sq_item(o, i); + } + } +#else + if (is_list || !PyMapping_Check(o)) { + return PySequence_GetItem(o, i); + } +#endif + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +} + +/* PyObjectCallOneArg */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg) { + PyObject *args[2] = {NULL, arg}; + return __Pyx_PyObject_FastCall(func, args+1, 1 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* ObjectGetItem */ +#if CYTHON_USE_TYPE_SLOTS +static PyObject *__Pyx_PyObject_GetIndex(PyObject *obj, PyObject *index) { + PyObject *runerr = NULL; + Py_ssize_t key_value; + key_value = __Pyx_PyIndex_AsSsize_t(index); + if (likely(key_value != -1 || !(runerr = PyErr_Occurred()))) { + return __Pyx_GetItemInt_Fast(obj, key_value, 0, 1, 1); + } + if (PyErr_GivenExceptionMatches(runerr, PyExc_OverflowError)) { + __Pyx_TypeName index_type_name = __Pyx_PyType_GetName(Py_TYPE(index)); + PyErr_Clear(); + PyErr_Format(PyExc_IndexError, + "cannot fit '" __Pyx_FMT_TYPENAME "' into an index-sized integer", index_type_name); + __Pyx_DECREF_TypeName(index_type_name); + } + return NULL; +} +static PyObject *__Pyx_PyObject_GetItem_Slow(PyObject *obj, PyObject *key) { + __Pyx_TypeName obj_type_name; + if (likely(PyType_Check(obj))) { + PyObject *meth = __Pyx_PyObject_GetAttrStrNoError(obj, __pyx_n_s_class_getitem); + if (!meth) { + PyErr_Clear(); + } else { + PyObject *result = __Pyx_PyObject_CallOneArg(meth, key); + Py_DECREF(meth); + return result; + } + } + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "'" __Pyx_FMT_TYPENAME "' object is not subscriptable", obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return NULL; +} +static PyObject *__Pyx_PyObject_GetItem(PyObject *obj, PyObject *key) { + PyTypeObject *tp = Py_TYPE(obj); + PyMappingMethods *mm = tp->tp_as_mapping; + PySequenceMethods *sm = tp->tp_as_sequence; + if (likely(mm && mm->mp_subscript)) { + return mm->mp_subscript(obj, key); + } + if (likely(sm && sm->sq_item)) { + return __Pyx_PyObject_GetIndex(obj, key); + } + return __Pyx_PyObject_GetItem_Slow(obj, key); +} +#endif + +/* KeywordStringCheck */ +static int __Pyx_CheckKeywordStrings( + PyObject *kw, + const char* function_name, + int kw_allowed) +{ + PyObject* key = 0; + Py_ssize_t pos = 0; +#if CYTHON_COMPILING_IN_PYPY + if (!kw_allowed && PyDict_Next(kw, &pos, &key, 0)) + goto invalid_keyword; + return 1; +#else + if (CYTHON_METH_FASTCALL && likely(PyTuple_Check(kw))) { + Py_ssize_t kwsize; +#if CYTHON_ASSUME_SAFE_MACROS + kwsize = PyTuple_GET_SIZE(kw); +#else + kwsize = PyTuple_Size(kw); + if (kwsize < 0) return 0; +#endif + if (unlikely(kwsize == 0)) + return 1; + if (!kw_allowed) { +#if CYTHON_ASSUME_SAFE_MACROS + key = PyTuple_GET_ITEM(kw, 0); +#else + key = PyTuple_GetItem(kw, pos); + if (!key) return 0; +#endif + goto invalid_keyword; + } +#if PY_VERSION_HEX < 0x03090000 + for (pos = 0; pos < kwsize; pos++) { +#if CYTHON_ASSUME_SAFE_MACROS + key = PyTuple_GET_ITEM(kw, pos); +#else + key = PyTuple_GetItem(kw, pos); + if (!key) return 0; +#endif + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } +#endif + return 1; + } + while (PyDict_Next(kw, &pos, &key, 0)) { + #if PY_MAJOR_VERSION < 3 + if (unlikely(!PyString_Check(key))) + #endif + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } + if (!kw_allowed && unlikely(key)) + goto invalid_keyword; + return 1; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + return 0; +#endif +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif + return 0; +} + +/* GetAttr3 */ +#if __PYX_LIMITED_VERSION_HEX < 0x030d00A1 +static PyObject *__Pyx_GetAttr3Default(PyObject *d) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + if (unlikely(!__Pyx_PyErr_ExceptionMatches(PyExc_AttributeError))) + return NULL; + __Pyx_PyErr_Clear(); + Py_INCREF(d); + return d; +} +#endif +static CYTHON_INLINE PyObject *__Pyx_GetAttr3(PyObject *o, PyObject *n, PyObject *d) { + PyObject *r; +#if __PYX_LIMITED_VERSION_HEX >= 0x030d00A1 + int res = PyObject_GetOptionalAttr(o, n, &r); + return (res != 0) ? r : __Pyx_NewRef(d); +#else + #if CYTHON_USE_TYPE_SLOTS + if (likely(PyString_Check(n))) { + r = __Pyx_PyObject_GetAttrStrNoError(o, n); + if (unlikely(!r) && likely(!PyErr_Occurred())) { + r = __Pyx_NewRef(d); + } + return r; + } + #endif + r = PyObject_GetAttr(o, n); + return (likely(r)) ? r : __Pyx_GetAttr3Default(d); +#endif +} + +/* RaiseUnexpectedTypeError */ +static int +__Pyx_RaiseUnexpectedTypeError(const char *expected, PyObject *obj) +{ + __Pyx_TypeName obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, "Expected %s, got " __Pyx_FMT_TYPENAME, + expected, obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return 0; +} + +/* RaiseException */ +#if PY_MAJOR_VERSION < 3 +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + __Pyx_PyThreadState_declare + CYTHON_UNUSED_VAR(cause); + Py_XINCREF(type); + if (!value || value == Py_None) + value = NULL; + else + Py_INCREF(value); + if (!tb || tb == Py_None) + tb = NULL; + else { + Py_INCREF(tb); + if (!PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto raise_error; + } + } + if (PyType_Check(type)) { +#if CYTHON_COMPILING_IN_PYPY + if (!value) { + Py_INCREF(Py_None); + value = Py_None; + } +#endif + PyErr_NormalizeException(&type, &value, &tb); + } else { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto raise_error; + } + value = type; + type = (PyObject*) Py_TYPE(type); + Py_INCREF(type); + if (!PyType_IsSubtype((PyTypeObject *)type, (PyTypeObject *)PyExc_BaseException)) { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto raise_error; + } + } + __Pyx_PyThreadState_assign + __Pyx_ErrRestore(type, value, tb); + return; +raise_error: + Py_XDECREF(value); + Py_XDECREF(type); + Py_XDECREF(tb); + return; +} +#else +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + PyObject* owned_instance = NULL; + if (tb == Py_None) { + tb = 0; + } else if (tb && !PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto bad; + } + if (value == Py_None) + value = 0; + if (PyExceptionInstance_Check(type)) { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto bad; + } + value = type; + type = (PyObject*) Py_TYPE(value); + } else if (PyExceptionClass_Check(type)) { + PyObject *instance_class = NULL; + if (value && PyExceptionInstance_Check(value)) { + instance_class = (PyObject*) Py_TYPE(value); + if (instance_class != type) { + int is_subclass = PyObject_IsSubclass(instance_class, type); + if (!is_subclass) { + instance_class = NULL; + } else if (unlikely(is_subclass == -1)) { + goto bad; + } else { + type = instance_class; + } + } + } + if (!instance_class) { + PyObject *args; + if (!value) + args = PyTuple_New(0); + else if (PyTuple_Check(value)) { + Py_INCREF(value); + args = value; + } else + args = PyTuple_Pack(1, value); + if (!args) + goto bad; + owned_instance = PyObject_Call(type, args, NULL); + Py_DECREF(args); + if (!owned_instance) + goto bad; + value = owned_instance; + if (!PyExceptionInstance_Check(value)) { + PyErr_Format(PyExc_TypeError, + "calling %R should have returned an instance of " + "BaseException, not %R", + type, Py_TYPE(value)); + goto bad; + } + } + } else { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto bad; + } + if (cause) { + PyObject *fixed_cause; + if (cause == Py_None) { + fixed_cause = NULL; + } else if (PyExceptionClass_Check(cause)) { + fixed_cause = PyObject_CallObject(cause, NULL); + if (fixed_cause == NULL) + goto bad; + } else if (PyExceptionInstance_Check(cause)) { + fixed_cause = cause; + Py_INCREF(fixed_cause); + } else { + PyErr_SetString(PyExc_TypeError, + "exception causes must derive from " + "BaseException"); + goto bad; + } + PyException_SetCause(value, fixed_cause); + } + PyErr_SetObject(type, value); + if (tb) { + #if PY_VERSION_HEX >= 0x030C00A6 + PyException_SetTraceback(value, tb); + #elif CYTHON_FAST_THREAD_STATE + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject* tmp_tb = tstate->curexc_traceback; + if (tb != tmp_tb) { + Py_INCREF(tb); + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_tb); + } +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + PyErr_Fetch(&tmp_type, &tmp_value, &tmp_tb); + Py_INCREF(tb); + PyErr_Restore(tmp_type, tmp_value, tb); + Py_XDECREF(tmp_tb); +#endif + } +bad: + Py_XDECREF(owned_instance); + return; +} +#endif + +/* Import */ +static PyObject *__Pyx_Import(PyObject *name, PyObject *from_list, int level) { + PyObject *module = 0; + PyObject *empty_dict = 0; + PyObject *empty_list = 0; + #if PY_MAJOR_VERSION < 3 + PyObject *py_import; + py_import = __Pyx_PyObject_GetAttrStr(__pyx_b, __pyx_n_s_import); + if (unlikely(!py_import)) + goto bad; + if (!from_list) { + empty_list = PyList_New(0); + if (unlikely(!empty_list)) + goto bad; + from_list = empty_list; + } + #endif + empty_dict = PyDict_New(); + if (unlikely(!empty_dict)) + goto bad; + { + #if PY_MAJOR_VERSION >= 3 + if (level == -1) { + if (strchr(__Pyx_MODULE_NAME, '.') != NULL) { + module = PyImport_ImportModuleLevelObject( + name, __pyx_d, empty_dict, from_list, 1); + if (unlikely(!module)) { + if (unlikely(!PyErr_ExceptionMatches(PyExc_ImportError))) + goto bad; + PyErr_Clear(); + } + } + level = 0; + } + #endif + if (!module) { + #if PY_MAJOR_VERSION < 3 + PyObject *py_level = PyInt_FromLong(level); + if (unlikely(!py_level)) + goto bad; + module = PyObject_CallFunctionObjArgs(py_import, + name, __pyx_d, empty_dict, from_list, py_level, (PyObject *)NULL); + Py_DECREF(py_level); + #else + module = PyImport_ImportModuleLevelObject( + name, __pyx_d, empty_dict, from_list, level); + #endif + } + } +bad: + Py_XDECREF(empty_dict); + Py_XDECREF(empty_list); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_import); + #endif + return module; +} + +/* ImportFrom */ +static PyObject* __Pyx_ImportFrom(PyObject* module, PyObject* name) { + PyObject* value = __Pyx_PyObject_GetAttrStr(module, name); + if (unlikely(!value) && PyErr_ExceptionMatches(PyExc_AttributeError)) { + const char* module_name_str = 0; + PyObject* module_name = 0; + PyObject* module_dot = 0; + PyObject* full_name = 0; + PyErr_Clear(); + module_name_str = PyModule_GetName(module); + if (unlikely(!module_name_str)) { goto modbad; } + module_name = PyUnicode_FromString(module_name_str); + if (unlikely(!module_name)) { goto modbad; } + module_dot = PyUnicode_Concat(module_name, __pyx_kp_u__3); + if (unlikely(!module_dot)) { goto modbad; } + full_name = PyUnicode_Concat(module_dot, name); + if (unlikely(!full_name)) { goto modbad; } + #if PY_VERSION_HEX < 0x030700A1 || (CYTHON_COMPILING_IN_PYPY && PYPY_VERSION_NUM < 0x07030400) + { + PyObject *modules = PyImport_GetModuleDict(); + if (unlikely(!modules)) + goto modbad; + value = PyObject_GetItem(modules, full_name); + } + #else + value = PyImport_GetModule(full_name); + #endif + modbad: + Py_XDECREF(full_name); + Py_XDECREF(module_dot); + Py_XDECREF(module_name); + } + if (unlikely(!value)) { + PyErr_Format(PyExc_ImportError, + #if PY_MAJOR_VERSION < 3 + "cannot import name %.230s", PyString_AS_STRING(name)); + #else + "cannot import name %S", name); + #endif + } + return value; +} + +/* GetAttr */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr(PyObject *o, PyObject *n) { +#if CYTHON_USE_TYPE_SLOTS +#if PY_MAJOR_VERSION >= 3 + if (likely(PyUnicode_Check(n))) +#else + if (likely(PyString_Check(n))) +#endif + return __Pyx_PyObject_GetAttrStr(o, n); +#endif + return PyObject_GetAttr(o, n); +} + +/* HasAttr */ +#if __PYX_LIMITED_VERSION_HEX < 0x030d00A1 +static CYTHON_INLINE int __Pyx_HasAttr(PyObject *o, PyObject *n) { + PyObject *r; + if (unlikely(!__Pyx_PyBaseString_Check(n))) { + PyErr_SetString(PyExc_TypeError, + "hasattr(): attribute name must be string"); + return -1; + } + r = __Pyx_GetAttr(o, n); + if (!r) { + PyErr_Clear(); + return 0; + } else { + Py_DECREF(r); + return 1; + } +} +#endif + +/* decode_c_bytes */ +static CYTHON_INLINE PyObject* __Pyx_decode_c_bytes( + const char* cstring, Py_ssize_t length, Py_ssize_t start, Py_ssize_t stop, + const char* encoding, const char* errors, + PyObject* (*decode_func)(const char *s, Py_ssize_t size, const char *errors)) { + if (unlikely((start < 0) | (stop < 0))) { + if (start < 0) { + start += length; + if (start < 0) + start = 0; + } + if (stop < 0) + stop += length; + } + if (stop > length) + stop = length; + if (unlikely(stop <= start)) + return __Pyx_NewRef(__pyx_empty_unicode); + length = stop - start; + cstring += start; + if (decode_func) { + return decode_func(cstring, length, errors); + } else { + return PyUnicode_Decode(cstring, length, encoding, errors); + } +} + +/* FixUpExtensionType */ +#if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type) { +#if PY_VERSION_HEX > 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + CYTHON_UNUSED_VAR(spec); + CYTHON_UNUSED_VAR(type); +#else + const PyType_Slot *slot = spec->slots; + while (slot && slot->slot && slot->slot != Py_tp_members) + slot++; + if (slot && slot->slot == Py_tp_members) { + int changed = 0; +#if !(PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON) + const +#endif + PyMemberDef *memb = (PyMemberDef*) slot->pfunc; + while (memb && memb->name) { + if (memb->name[0] == '_' && memb->name[1] == '_') { +#if PY_VERSION_HEX < 0x030900b1 + if (strcmp(memb->name, "__weaklistoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_weaklistoffset = memb->offset; + changed = 1; + } + else if (strcmp(memb->name, "__dictoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_dictoffset = memb->offset; + changed = 1; + } +#if CYTHON_METH_FASTCALL + else if (strcmp(memb->name, "__vectorcalloffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); +#if PY_VERSION_HEX >= 0x030800b4 + type->tp_vectorcall_offset = memb->offset; +#else + type->tp_print = (printfunc) memb->offset; +#endif + changed = 1; + } +#endif +#else + if ((0)); +#endif +#if PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON + else if (strcmp(memb->name, "__module__") == 0) { + PyObject *descr; + assert(memb->type == T_OBJECT); + assert(memb->flags == 0 || memb->flags == READONLY); + descr = PyDescr_NewMember(type, memb); + if (unlikely(!descr)) + return -1; + if (unlikely(PyDict_SetItem(type->tp_dict, PyDescr_NAME(descr), descr) < 0)) { + Py_DECREF(descr); + return -1; + } + Py_DECREF(descr); + changed = 1; + } +#endif + } + memb++; + } + if (changed) + PyType_Modified(type); + } +#endif + return 0; +} +#endif + +/* PyObjectCallNoArg */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func) { + PyObject *arg[2] = {NULL, NULL}; + return __Pyx_PyObject_FastCall(func, arg + 1, 0 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* PyObjectGetMethod */ +static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method) { + PyObject *attr; +#if CYTHON_UNPACK_METHODS && CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_PYTYPE_LOOKUP + __Pyx_TypeName type_name; + PyTypeObject *tp = Py_TYPE(obj); + PyObject *descr; + descrgetfunc f = NULL; + PyObject **dictptr, *dict; + int meth_found = 0; + assert (*method == NULL); + if (unlikely(tp->tp_getattro != PyObject_GenericGetAttr)) { + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; + } + if (unlikely(tp->tp_dict == NULL) && unlikely(PyType_Ready(tp) < 0)) { + return 0; + } + descr = _PyType_Lookup(tp, name); + if (likely(descr != NULL)) { + Py_INCREF(descr); +#if defined(Py_TPFLAGS_METHOD_DESCRIPTOR) && Py_TPFLAGS_METHOD_DESCRIPTOR + if (__Pyx_PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_METHOD_DESCRIPTOR)) +#elif PY_MAJOR_VERSION >= 3 + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type))) + #endif +#else + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr))) + #endif +#endif + { + meth_found = 1; + } else { + f = Py_TYPE(descr)->tp_descr_get; + if (f != NULL && PyDescr_IsData(descr)) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + } + } + dictptr = _PyObject_GetDictPtr(obj); + if (dictptr != NULL && (dict = *dictptr) != NULL) { + Py_INCREF(dict); + attr = __Pyx_PyDict_GetItemStr(dict, name); + if (attr != NULL) { + Py_INCREF(attr); + Py_DECREF(dict); + Py_XDECREF(descr); + goto try_unpack; + } + Py_DECREF(dict); + } + if (meth_found) { + *method = descr; + return 1; + } + if (f != NULL) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + if (likely(descr != NULL)) { + *method = descr; + return 0; + } + type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return 0; +#else + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; +#endif +try_unpack: +#if CYTHON_UNPACK_METHODS + if (likely(attr) && PyMethod_Check(attr) && likely(PyMethod_GET_SELF(attr) == obj)) { + PyObject *function = PyMethod_GET_FUNCTION(attr); + Py_INCREF(function); + Py_DECREF(attr); + *method = function; + return 1; + } +#endif + *method = attr; + return 0; +} + +/* PyObjectCallMethod0 */ +static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name) { + PyObject *method = NULL, *result = NULL; + int is_method = __Pyx_PyObject_GetMethod(obj, method_name, &method); + if (likely(is_method)) { + result = __Pyx_PyObject_CallOneArg(method, obj); + Py_DECREF(method); + return result; + } + if (unlikely(!method)) goto bad; + result = __Pyx_PyObject_CallNoArg(method); + Py_DECREF(method); +bad: + return result; +} + +/* ValidateBasesTuple */ +#if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases) { + Py_ssize_t i, n; +#if CYTHON_ASSUME_SAFE_MACROS + n = PyTuple_GET_SIZE(bases); +#else + n = PyTuple_Size(bases); + if (n < 0) return -1; +#endif + for (i = 1; i < n; i++) + { +#if CYTHON_AVOID_BORROWED_REFS + PyObject *b0 = PySequence_GetItem(bases, i); + if (!b0) return -1; +#elif CYTHON_ASSUME_SAFE_MACROS + PyObject *b0 = PyTuple_GET_ITEM(bases, i); +#else + PyObject *b0 = PyTuple_GetItem(bases, i); + if (!b0) return -1; +#endif + PyTypeObject *b; +#if PY_MAJOR_VERSION < 3 + if (PyClass_Check(b0)) + { + PyErr_Format(PyExc_TypeError, "base class '%.200s' is an old-style class", + PyString_AS_STRING(((PyClassObject*)b0)->cl_name)); +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + return -1; + } +#endif + b = (PyTypeObject*) b0; + if (!__Pyx_PyType_HasFeature(b, Py_TPFLAGS_HEAPTYPE)) + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "base class '" __Pyx_FMT_TYPENAME "' is not a heap type", b_name); + __Pyx_DECREF_TypeName(b_name); +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + return -1; + } + if (dictoffset == 0) + { + Py_ssize_t b_dictoffset = 0; +#if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + b_dictoffset = b->tp_dictoffset; +#else + PyObject *py_b_dictoffset = PyObject_GetAttrString((PyObject*)b, "__dictoffset__"); + if (!py_b_dictoffset) goto dictoffset_return; + b_dictoffset = PyLong_AsSsize_t(py_b_dictoffset); + Py_DECREF(py_b_dictoffset); + if (b_dictoffset == -1 && PyErr_Occurred()) goto dictoffset_return; +#endif + if (b_dictoffset) { + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "extension type '%.200s' has no __dict__ slot, " + "but base type '" __Pyx_FMT_TYPENAME "' has: " + "either add 'cdef dict __dict__' to the extension type " + "or add '__slots__ = [...]' to the base type", + type_name, b_name); + __Pyx_DECREF_TypeName(b_name); + } +#if !(CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY) + dictoffset_return: +#endif +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + return -1; + } + } +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + } + return 0; +} +#endif + +/* PyType_Ready */ +static int __Pyx_PyType_Ready(PyTypeObject *t) { +#if CYTHON_USE_TYPE_SPECS || !(CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API) || defined(PYSTON_MAJOR_VERSION) + (void)__Pyx_PyObject_CallMethod0; +#if CYTHON_USE_TYPE_SPECS + (void)__Pyx_validate_bases_tuple; +#endif + return PyType_Ready(t); +#else + int r; + PyObject *bases = __Pyx_PyType_GetSlot(t, tp_bases, PyObject*); + if (bases && unlikely(__Pyx_validate_bases_tuple(t->tp_name, t->tp_dictoffset, bases) == -1)) + return -1; +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + { + int gc_was_enabled; + #if PY_VERSION_HEX >= 0x030A00b1 + gc_was_enabled = PyGC_Disable(); + (void)__Pyx_PyObject_CallMethod0; + #else + PyObject *ret, *py_status; + PyObject *gc = NULL; + #if PY_VERSION_HEX >= 0x030700a1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM+0 >= 0x07030400) + gc = PyImport_GetModule(__pyx_kp_u_gc); + #endif + if (unlikely(!gc)) gc = PyImport_Import(__pyx_kp_u_gc); + if (unlikely(!gc)) return -1; + py_status = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_isenabled); + if (unlikely(!py_status)) { + Py_DECREF(gc); + return -1; + } + gc_was_enabled = __Pyx_PyObject_IsTrue(py_status); + Py_DECREF(py_status); + if (gc_was_enabled > 0) { + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_disable); + if (unlikely(!ret)) { + Py_DECREF(gc); + return -1; + } + Py_DECREF(ret); + } else if (unlikely(gc_was_enabled == -1)) { + Py_DECREF(gc); + return -1; + } + #endif + t->tp_flags |= Py_TPFLAGS_HEAPTYPE; +#if PY_VERSION_HEX >= 0x030A0000 + t->tp_flags |= Py_TPFLAGS_IMMUTABLETYPE; +#endif +#else + (void)__Pyx_PyObject_CallMethod0; +#endif + r = PyType_Ready(t); +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + t->tp_flags &= ~Py_TPFLAGS_HEAPTYPE; + #if PY_VERSION_HEX >= 0x030A00b1 + if (gc_was_enabled) + PyGC_Enable(); + #else + if (gc_was_enabled) { + PyObject *tp, *v, *tb; + PyErr_Fetch(&tp, &v, &tb); + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_enable); + if (likely(ret || r == -1)) { + Py_XDECREF(ret); + PyErr_Restore(tp, v, tb); + } else { + Py_XDECREF(tp); + Py_XDECREF(v); + Py_XDECREF(tb); + r = -1; + } + } + Py_DECREF(gc); + #endif + } +#endif + return r; +#endif +} + +/* PyObject_GenericGetAttrNoDict */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject *__Pyx_RaiseGenericGetAttributeError(PyTypeObject *tp, PyObject *attr_name) { + __Pyx_TypeName type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, attr_name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(attr_name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name) { + PyObject *descr; + PyTypeObject *tp = Py_TYPE(obj); + if (unlikely(!PyString_Check(attr_name))) { + return PyObject_GenericGetAttr(obj, attr_name); + } + assert(!tp->tp_dictoffset); + descr = _PyType_Lookup(tp, attr_name); + if (unlikely(!descr)) { + return __Pyx_RaiseGenericGetAttributeError(tp, attr_name); + } + Py_INCREF(descr); + #if PY_MAJOR_VERSION < 3 + if (likely(PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_HAVE_CLASS))) + #endif + { + descrgetfunc f = Py_TYPE(descr)->tp_descr_get; + if (unlikely(f)) { + PyObject *res = f(descr, obj, (PyObject *)tp); + Py_DECREF(descr); + return res; + } + } + return descr; +} +#endif + +/* PyObject_GenericGetAttr */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name) { + if (unlikely(Py_TYPE(obj)->tp_dictoffset)) { + return PyObject_GenericGetAttr(obj, attr_name); + } + return __Pyx_PyObject_GenericGetAttrNoDict(obj, attr_name); +} +#endif + +/* SetupReduce */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce_is_named(PyObject* meth, PyObject* name) { + int ret; + PyObject *name_attr; + name_attr = __Pyx_PyObject_GetAttrStrNoError(meth, __pyx_n_s_name_2); + if (likely(name_attr)) { + ret = PyObject_RichCompareBool(name_attr, name, Py_EQ); + } else { + ret = -1; + } + if (unlikely(ret < 0)) { + PyErr_Clear(); + ret = 0; + } + Py_XDECREF(name_attr); + return ret; +} +static int __Pyx_setup_reduce(PyObject* type_obj) { + int ret = 0; + PyObject *object_reduce = NULL; + PyObject *object_getstate = NULL; + PyObject *object_reduce_ex = NULL; + PyObject *reduce = NULL; + PyObject *reduce_ex = NULL; + PyObject *reduce_cython = NULL; + PyObject *setstate = NULL; + PyObject *setstate_cython = NULL; + PyObject *getstate = NULL; +#if CYTHON_USE_PYTYPE_LOOKUP + getstate = _PyType_Lookup((PyTypeObject*)type_obj, __pyx_n_s_getstate); +#else + getstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_getstate); + if (!getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (getstate) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_getstate = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_getstate); +#else + object_getstate = __Pyx_PyObject_GetAttrStrNoError((PyObject*)&PyBaseObject_Type, __pyx_n_s_getstate); + if (!object_getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (object_getstate != getstate) { + goto __PYX_GOOD; + } + } +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce_ex = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#else + object_reduce_ex = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#endif + reduce_ex = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce_ex); if (unlikely(!reduce_ex)) goto __PYX_BAD; + if (reduce_ex == object_reduce_ex) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#else + object_reduce = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#endif + reduce = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce); if (unlikely(!reduce)) goto __PYX_BAD; + if (reduce == object_reduce || __Pyx_setup_reduce_is_named(reduce, __pyx_n_s_reduce_cython)) { + reduce_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_reduce_cython); + if (likely(reduce_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce, reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (reduce == object_reduce || PyErr_Occurred()) { + goto __PYX_BAD; + } + setstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate); + if (!setstate) PyErr_Clear(); + if (!setstate || __Pyx_setup_reduce_is_named(setstate, __pyx_n_s_setstate_cython)) { + setstate_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate_cython); + if (likely(setstate_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate, setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (!setstate || PyErr_Occurred()) { + goto __PYX_BAD; + } + } + PyType_Modified((PyTypeObject*)type_obj); + } + } + goto __PYX_GOOD; +__PYX_BAD: + if (!PyErr_Occurred()) { + __Pyx_TypeName type_obj_name = + __Pyx_PyType_GetName((PyTypeObject*)type_obj); + PyErr_Format(PyExc_RuntimeError, + "Unable to initialize pickling for " __Pyx_FMT_TYPENAME, type_obj_name); + __Pyx_DECREF_TypeName(type_obj_name); + } + ret = -1; +__PYX_GOOD: +#if !CYTHON_USE_PYTYPE_LOOKUP + Py_XDECREF(object_reduce); + Py_XDECREF(object_reduce_ex); + Py_XDECREF(object_getstate); + Py_XDECREF(getstate); +#endif + Py_XDECREF(reduce); + Py_XDECREF(reduce_ex); + Py_XDECREF(reduce_cython); + Py_XDECREF(setstate); + Py_XDECREF(setstate_cython); + return ret; +} +#endif + +/* FetchSharedCythonModule */ +static PyObject *__Pyx_FetchSharedCythonABIModule(void) { + return __Pyx_PyImport_AddModuleRef((char*) __PYX_ABI_MODULE_NAME); +} + +/* FetchCommonType */ +static int __Pyx_VerifyCachedType(PyObject *cached_type, + const char *name, + Py_ssize_t basicsize, + Py_ssize_t expected_basicsize) { + if (!PyType_Check(cached_type)) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s is not a type object", name); + return -1; + } + if (basicsize != expected_basicsize) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s has the wrong size, try recompiling", + name); + return -1; + } + return 0; +} +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type) { + PyObject* abi_module; + const char* object_name; + PyTypeObject *cached_type = NULL; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + object_name = strrchr(type->tp_name, '.'); + object_name = object_name ? object_name+1 : type->tp_name; + cached_type = (PyTypeObject*) PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + if (__Pyx_VerifyCachedType( + (PyObject *)cached_type, + object_name, + cached_type->tp_basicsize, + type->tp_basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + if (PyType_Ready(type) < 0) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, (PyObject *)type) < 0) + goto bad; + Py_INCREF(type); + cached_type = type; +done: + Py_DECREF(abi_module); + return cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#else +static PyTypeObject *__Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases) { + PyObject *abi_module, *cached_type = NULL; + const char* object_name = strrchr(spec->name, '.'); + object_name = object_name ? object_name+1 : spec->name; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + cached_type = PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + Py_ssize_t basicsize; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *py_basicsize; + py_basicsize = PyObject_GetAttrString(cached_type, "__basicsize__"); + if (unlikely(!py_basicsize)) goto bad; + basicsize = PyLong_AsSsize_t(py_basicsize); + Py_DECREF(py_basicsize); + py_basicsize = 0; + if (unlikely(basicsize == (Py_ssize_t)-1) && PyErr_Occurred()) goto bad; +#else + basicsize = likely(PyType_Check(cached_type)) ? ((PyTypeObject*) cached_type)->tp_basicsize : -1; +#endif + if (__Pyx_VerifyCachedType( + cached_type, + object_name, + basicsize, + spec->basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + CYTHON_UNUSED_VAR(module); + cached_type = __Pyx_PyType_FromModuleAndSpec(abi_module, spec, bases); + if (unlikely(!cached_type)) goto bad; + if (unlikely(__Pyx_fix_up_extension_type_from_spec(spec, (PyTypeObject *) cached_type) < 0)) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, cached_type) < 0) goto bad; +done: + Py_DECREF(abi_module); + assert(cached_type == NULL || PyType_Check(cached_type)); + return (PyTypeObject *) cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#endif + +/* PyVectorcallFastCallDict */ +#if CYTHON_METH_FASTCALL +static PyObject *__Pyx_PyVectorcall_FastCallDict_kw(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + PyObject *res = NULL; + PyObject *kwnames; + PyObject **newargs; + PyObject **kwvalues; + Py_ssize_t i, pos; + size_t j; + PyObject *key, *value; + unsigned long keys_are_strings; + Py_ssize_t nkw = PyDict_GET_SIZE(kw); + newargs = (PyObject **)PyMem_Malloc((nargs + (size_t)nkw) * sizeof(args[0])); + if (unlikely(newargs == NULL)) { + PyErr_NoMemory(); + return NULL; + } + for (j = 0; j < nargs; j++) newargs[j] = args[j]; + kwnames = PyTuple_New(nkw); + if (unlikely(kwnames == NULL)) { + PyMem_Free(newargs); + return NULL; + } + kwvalues = newargs + nargs; + pos = i = 0; + keys_are_strings = Py_TPFLAGS_UNICODE_SUBCLASS; + while (PyDict_Next(kw, &pos, &key, &value)) { + keys_are_strings &= Py_TYPE(key)->tp_flags; + Py_INCREF(key); + Py_INCREF(value); + PyTuple_SET_ITEM(kwnames, i, key); + kwvalues[i] = value; + i++; + } + if (unlikely(!keys_are_strings)) { + PyErr_SetString(PyExc_TypeError, "keywords must be strings"); + goto cleanup; + } + res = vc(func, newargs, nargs, kwnames); +cleanup: + Py_DECREF(kwnames); + for (i = 0; i < nkw; i++) + Py_DECREF(kwvalues[i]); + PyMem_Free(newargs); + return res; +} +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + if (likely(kw == NULL) || PyDict_GET_SIZE(kw) == 0) { + return vc(func, args, nargs, NULL); + } + return __Pyx_PyVectorcall_FastCallDict_kw(func, vc, args, nargs, kw); +} +#endif + +/* CythonFunctionShared */ +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc) { + if (__Pyx_CyFunction_Check(func)) { + return PyCFunction_GetFunction(((__pyx_CyFunctionObject*)func)->func) == (PyCFunction) cfunc; + } else if (PyCFunction_Check(func)) { + return PyCFunction_GetFunction(func) == (PyCFunction) cfunc; + } + return 0; +} +#else +static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc) { + return __Pyx_CyOrPyCFunction_Check(func) && __Pyx_CyOrPyCFunction_GET_FUNCTION(func) == (PyCFunction) cfunc; +} +#endif +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj) { +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + __Pyx_Py_XDECREF_SET( + __Pyx_CyFunction_GetClassObj(f), + ((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#else + __Pyx_Py_XDECREF_SET( + ((PyCMethodObject *) (f))->mm_class, + (PyTypeObject*)((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#endif +} +static PyObject * +__Pyx_CyFunction_get_doc(__pyx_CyFunctionObject *op, void *closure) +{ + CYTHON_UNUSED_VAR(closure); + if (unlikely(op->func_doc == NULL)) { +#if CYTHON_COMPILING_IN_LIMITED_API + op->func_doc = PyObject_GetAttrString(op->func, "__doc__"); + if (unlikely(!op->func_doc)) return NULL; +#else + if (((PyCFunctionObject*)op)->m_ml->ml_doc) { +#if PY_MAJOR_VERSION >= 3 + op->func_doc = PyUnicode_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#else + op->func_doc = PyString_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#endif + if (unlikely(op->func_doc == NULL)) + return NULL; + } else { + Py_INCREF(Py_None); + return Py_None; + } +#endif + } + Py_INCREF(op->func_doc); + return op->func_doc; +} +static int +__Pyx_CyFunction_set_doc(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (value == NULL) { + value = Py_None; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_doc, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_name(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_name == NULL)) { +#if CYTHON_COMPILING_IN_LIMITED_API + op->func_name = PyObject_GetAttrString(op->func, "__name__"); +#elif PY_MAJOR_VERSION >= 3 + op->func_name = PyUnicode_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#else + op->func_name = PyString_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#endif + if (unlikely(op->func_name == NULL)) + return NULL; + } + Py_INCREF(op->func_name); + return op->func_name; +} +static int +__Pyx_CyFunction_set_name(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__name__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_name, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_qualname(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_qualname); + return op->func_qualname; +} +static int +__Pyx_CyFunction_set_qualname(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__qualname__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_qualname, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_dict(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_dict == NULL)) { + op->func_dict = PyDict_New(); + if (unlikely(op->func_dict == NULL)) + return NULL; + } + Py_INCREF(op->func_dict); + return op->func_dict; +} +static int +__Pyx_CyFunction_set_dict(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(value == NULL)) { + PyErr_SetString(PyExc_TypeError, + "function's dictionary may not be deleted"); + return -1; + } + if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "setting function's dictionary to a non-dict"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_dict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_globals(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_globals); + return op->func_globals; +} +static PyObject * +__Pyx_CyFunction_get_closure(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(op); + CYTHON_UNUSED_VAR(context); + Py_INCREF(Py_None); + return Py_None; +} +static PyObject * +__Pyx_CyFunction_get_code(__pyx_CyFunctionObject *op, void *context) +{ + PyObject* result = (op->func_code) ? op->func_code : Py_None; + CYTHON_UNUSED_VAR(context); + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_init_defaults(__pyx_CyFunctionObject *op) { + int result = 0; + PyObject *res = op->defaults_getter((PyObject *) op); + if (unlikely(!res)) + return -1; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + op->defaults_tuple = PyTuple_GET_ITEM(res, 0); + Py_INCREF(op->defaults_tuple); + op->defaults_kwdict = PyTuple_GET_ITEM(res, 1); + Py_INCREF(op->defaults_kwdict); + #else + op->defaults_tuple = __Pyx_PySequence_ITEM(res, 0); + if (unlikely(!op->defaults_tuple)) result = -1; + else { + op->defaults_kwdict = __Pyx_PySequence_ITEM(res, 1); + if (unlikely(!op->defaults_kwdict)) result = -1; + } + #endif + Py_DECREF(res); + return result; +} +static int +__Pyx_CyFunction_set_defaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyTuple_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__defaults__ must be set to a tuple object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__defaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_tuple, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_defaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_tuple; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_tuple; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_kwdefaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__kwdefaults__ must be set to a dict object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__kwdefaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_kwdict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_kwdefaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_kwdict; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_kwdict; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_annotations(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value || value == Py_None) { + value = NULL; + } else if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__annotations__ must be set to a dict object"); + return -1; + } + Py_XINCREF(value); + __Pyx_Py_XDECREF_SET(op->func_annotations, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_annotations(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->func_annotations; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + result = PyDict_New(); + if (unlikely(!result)) return NULL; + op->func_annotations = result; + } + Py_INCREF(result); + return result; +} +static PyObject * +__Pyx_CyFunction_get_is_coroutine(__pyx_CyFunctionObject *op, void *context) { + int is_coroutine; + CYTHON_UNUSED_VAR(context); + if (op->func_is_coroutine) { + return __Pyx_NewRef(op->func_is_coroutine); + } + is_coroutine = op->flags & __Pyx_CYFUNCTION_COROUTINE; +#if PY_VERSION_HEX >= 0x03050000 + if (is_coroutine) { + PyObject *module, *fromlist, *marker = __pyx_n_s_is_coroutine; + fromlist = PyList_New(1); + if (unlikely(!fromlist)) return NULL; + Py_INCREF(marker); +#if CYTHON_ASSUME_SAFE_MACROS + PyList_SET_ITEM(fromlist, 0, marker); +#else + if (unlikely(PyList_SetItem(fromlist, 0, marker) < 0)) { + Py_DECREF(marker); + Py_DECREF(fromlist); + return NULL; + } +#endif + module = PyImport_ImportModuleLevelObject(__pyx_n_s_asyncio_coroutines, NULL, NULL, fromlist, 0); + Py_DECREF(fromlist); + if (unlikely(!module)) goto ignore; + op->func_is_coroutine = __Pyx_PyObject_GetAttrStr(module, marker); + Py_DECREF(module); + if (likely(op->func_is_coroutine)) { + return __Pyx_NewRef(op->func_is_coroutine); + } +ignore: + PyErr_Clear(); + } +#endif + op->func_is_coroutine = __Pyx_PyBool_FromLong(is_coroutine); + return __Pyx_NewRef(op->func_is_coroutine); +} +#if CYTHON_COMPILING_IN_LIMITED_API +static PyObject * +__Pyx_CyFunction_get_module(__pyx_CyFunctionObject *op, void *context) { + CYTHON_UNUSED_VAR(context); + return PyObject_GetAttrString(op->func, "__module__"); +} +static int +__Pyx_CyFunction_set_module(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + return PyObject_SetAttrString(op->func, "__module__", value); +} +#endif +static PyGetSetDef __pyx_CyFunction_getsets[] = { + {(char *) "func_doc", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "__doc__", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "func_name", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__name__", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__qualname__", (getter)__Pyx_CyFunction_get_qualname, (setter)__Pyx_CyFunction_set_qualname, 0, 0}, + {(char *) "func_dict", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "__dict__", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "func_globals", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "__globals__", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "func_closure", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "__closure__", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "func_code", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "__code__", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "func_defaults", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__defaults__", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__kwdefaults__", (getter)__Pyx_CyFunction_get_kwdefaults, (setter)__Pyx_CyFunction_set_kwdefaults, 0, 0}, + {(char *) "__annotations__", (getter)__Pyx_CyFunction_get_annotations, (setter)__Pyx_CyFunction_set_annotations, 0, 0}, + {(char *) "_is_coroutine", (getter)__Pyx_CyFunction_get_is_coroutine, 0, 0, 0}, +#if CYTHON_COMPILING_IN_LIMITED_API + {"__module__", (getter)__Pyx_CyFunction_get_module, (setter)__Pyx_CyFunction_set_module, 0, 0}, +#endif + {0, 0, 0, 0, 0} +}; +static PyMemberDef __pyx_CyFunction_members[] = { +#if !CYTHON_COMPILING_IN_LIMITED_API + {(char *) "__module__", T_OBJECT, offsetof(PyCFunctionObject, m_module), 0, 0}, +#endif +#if CYTHON_USE_TYPE_SPECS + {(char *) "__dictoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_dict), READONLY, 0}, +#if CYTHON_METH_FASTCALL +#if CYTHON_BACKPORT_VECTORCALL + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_vectorcall), READONLY, 0}, +#else +#if !CYTHON_COMPILING_IN_LIMITED_API + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(PyCFunctionObject, vectorcall), READONLY, 0}, +#endif +#endif +#endif +#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_weakreflist), READONLY, 0}, +#else + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(PyCFunctionObject, m_weakreflist), READONLY, 0}, +#endif +#endif + {0, 0, 0, 0, 0} +}; +static PyObject * +__Pyx_CyFunction_reduce(__pyx_CyFunctionObject *m, PyObject *args) +{ + CYTHON_UNUSED_VAR(args); +#if PY_MAJOR_VERSION >= 3 + Py_INCREF(m->func_qualname); + return m->func_qualname; +#else + return PyString_FromString(((PyCFunctionObject*)m)->m_ml->ml_name); +#endif +} +static PyMethodDef __pyx_CyFunction_methods[] = { + {"__reduce__", (PyCFunction)__Pyx_CyFunction_reduce, METH_VARARGS, 0}, + {0, 0, 0, 0} +}; +#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API +#define __Pyx_CyFunction_weakreflist(cyfunc) ((cyfunc)->func_weakreflist) +#else +#define __Pyx_CyFunction_weakreflist(cyfunc) (((PyCFunctionObject*)cyfunc)->m_weakreflist) +#endif +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject *op, PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { +#if !CYTHON_COMPILING_IN_LIMITED_API + PyCFunctionObject *cf = (PyCFunctionObject*) op; +#endif + if (unlikely(op == NULL)) + return NULL; +#if CYTHON_COMPILING_IN_LIMITED_API + op->func = PyCFunction_NewEx(ml, (PyObject*)op, module); + if (unlikely(!op->func)) return NULL; +#endif + op->flags = flags; + __Pyx_CyFunction_weakreflist(op) = NULL; +#if !CYTHON_COMPILING_IN_LIMITED_API + cf->m_ml = ml; + cf->m_self = (PyObject *) op; +#endif + Py_XINCREF(closure); + op->func_closure = closure; +#if !CYTHON_COMPILING_IN_LIMITED_API + Py_XINCREF(module); + cf->m_module = module; +#endif + op->func_dict = NULL; + op->func_name = NULL; + Py_INCREF(qualname); + op->func_qualname = qualname; + op->func_doc = NULL; +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + op->func_classobj = NULL; +#else + ((PyCMethodObject*)op)->mm_class = NULL; +#endif + op->func_globals = globals; + Py_INCREF(op->func_globals); + Py_XINCREF(code); + op->func_code = code; + op->defaults_pyobjects = 0; + op->defaults_size = 0; + op->defaults = NULL; + op->defaults_tuple = NULL; + op->defaults_kwdict = NULL; + op->defaults_getter = NULL; + op->func_annotations = NULL; + op->func_is_coroutine = NULL; +#if CYTHON_METH_FASTCALL + switch (ml->ml_flags & (METH_VARARGS | METH_FASTCALL | METH_NOARGS | METH_O | METH_KEYWORDS | METH_METHOD)) { + case METH_NOARGS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_NOARGS; + break; + case METH_O: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_O; + break; + case METH_METHOD | METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD; + break; + case METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS; + break; + case METH_VARARGS | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = NULL; + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + Py_DECREF(op); + return NULL; + } +#endif + return (PyObject *) op; +} +static int +__Pyx_CyFunction_clear(__pyx_CyFunctionObject *m) +{ + Py_CLEAR(m->func_closure); +#if CYTHON_COMPILING_IN_LIMITED_API + Py_CLEAR(m->func); +#else + Py_CLEAR(((PyCFunctionObject*)m)->m_module); +#endif + Py_CLEAR(m->func_dict); + Py_CLEAR(m->func_name); + Py_CLEAR(m->func_qualname); + Py_CLEAR(m->func_doc); + Py_CLEAR(m->func_globals); + Py_CLEAR(m->func_code); +#if !CYTHON_COMPILING_IN_LIMITED_API +#if PY_VERSION_HEX < 0x030900B1 + Py_CLEAR(__Pyx_CyFunction_GetClassObj(m)); +#else + { + PyObject *cls = (PyObject*) ((PyCMethodObject *) (m))->mm_class; + ((PyCMethodObject *) (m))->mm_class = NULL; + Py_XDECREF(cls); + } +#endif +#endif + Py_CLEAR(m->defaults_tuple); + Py_CLEAR(m->defaults_kwdict); + Py_CLEAR(m->func_annotations); + Py_CLEAR(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_XDECREF(pydefaults[i]); + PyObject_Free(m->defaults); + m->defaults = NULL; + } + return 0; +} +static void __Pyx__CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + if (__Pyx_CyFunction_weakreflist(m) != NULL) + PyObject_ClearWeakRefs((PyObject *) m); + __Pyx_CyFunction_clear(m); + __Pyx_PyHeapTypeObject_GC_Del(m); +} +static void __Pyx_CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + PyObject_GC_UnTrack(m); + __Pyx__CyFunction_dealloc(m); +} +static int __Pyx_CyFunction_traverse(__pyx_CyFunctionObject *m, visitproc visit, void *arg) +{ + Py_VISIT(m->func_closure); +#if CYTHON_COMPILING_IN_LIMITED_API + Py_VISIT(m->func); +#else + Py_VISIT(((PyCFunctionObject*)m)->m_module); +#endif + Py_VISIT(m->func_dict); + Py_VISIT(m->func_name); + Py_VISIT(m->func_qualname); + Py_VISIT(m->func_doc); + Py_VISIT(m->func_globals); + Py_VISIT(m->func_code); +#if !CYTHON_COMPILING_IN_LIMITED_API + Py_VISIT(__Pyx_CyFunction_GetClassObj(m)); +#endif + Py_VISIT(m->defaults_tuple); + Py_VISIT(m->defaults_kwdict); + Py_VISIT(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_VISIT(pydefaults[i]); + } + return 0; +} +static PyObject* +__Pyx_CyFunction_repr(__pyx_CyFunctionObject *op) +{ +#if PY_MAJOR_VERSION >= 3 + return PyUnicode_FromFormat("", + op->func_qualname, (void *)op); +#else + return PyString_FromFormat("", + PyString_AsString(op->func_qualname), (void *)op); +#endif +} +static PyObject * __Pyx_CyFunction_CallMethod(PyObject *func, PyObject *self, PyObject *arg, PyObject *kw) { +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *f = ((__pyx_CyFunctionObject*)func)->func; + PyObject *py_name = NULL; + PyCFunction meth; + int flags; + meth = PyCFunction_GetFunction(f); + if (unlikely(!meth)) return NULL; + flags = PyCFunction_GetFlags(f); + if (unlikely(flags < 0)) return NULL; +#else + PyCFunctionObject* f = (PyCFunctionObject*)func; + PyCFunction meth = f->m_ml->ml_meth; + int flags = f->m_ml->ml_flags; +#endif + Py_ssize_t size; + switch (flags & (METH_VARARGS | METH_KEYWORDS | METH_NOARGS | METH_O)) { + case METH_VARARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) + return (*meth)(self, arg); + break; + case METH_VARARGS | METH_KEYWORDS: + return (*(PyCFunctionWithKeywords)(void*)meth)(self, arg, kw); + case METH_NOARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { +#if CYTHON_ASSUME_SAFE_MACROS + size = PyTuple_GET_SIZE(arg); +#else + size = PyTuple_Size(arg); + if (unlikely(size < 0)) return NULL; +#endif + if (likely(size == 0)) + return (*meth)(self, NULL); +#if CYTHON_COMPILING_IN_LIMITED_API + py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); + if (!py_name) return NULL; + PyErr_Format(PyExc_TypeError, + "%.200S() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + py_name, size); + Py_DECREF(py_name); +#else + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); +#endif + return NULL; + } + break; + case METH_O: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { +#if CYTHON_ASSUME_SAFE_MACROS + size = PyTuple_GET_SIZE(arg); +#else + size = PyTuple_Size(arg); + if (unlikely(size < 0)) return NULL; +#endif + if (likely(size == 1)) { + PyObject *result, *arg0; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + arg0 = PyTuple_GET_ITEM(arg, 0); + #else + arg0 = __Pyx_PySequence_ITEM(arg, 0); if (unlikely(!arg0)) return NULL; + #endif + result = (*meth)(self, arg0); + #if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(arg0); + #endif + return result; + } +#if CYTHON_COMPILING_IN_LIMITED_API + py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); + if (!py_name) return NULL; + PyErr_Format(PyExc_TypeError, + "%.200S() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + py_name, size); + Py_DECREF(py_name); +#else + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); +#endif + return NULL; + } + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + return NULL; + } +#if CYTHON_COMPILING_IN_LIMITED_API + py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); + if (!py_name) return NULL; + PyErr_Format(PyExc_TypeError, "%.200S() takes no keyword arguments", + py_name); + Py_DECREF(py_name); +#else + PyErr_Format(PyExc_TypeError, "%.200s() takes no keyword arguments", + f->m_ml->ml_name); +#endif + return NULL; +} +static CYTHON_INLINE PyObject *__Pyx_CyFunction_Call(PyObject *func, PyObject *arg, PyObject *kw) { + PyObject *self, *result; +#if CYTHON_COMPILING_IN_LIMITED_API + self = PyCFunction_GetSelf(((__pyx_CyFunctionObject*)func)->func); + if (unlikely(!self) && PyErr_Occurred()) return NULL; +#else + self = ((PyCFunctionObject*)func)->m_self; +#endif + result = __Pyx_CyFunction_CallMethod(func, self, arg, kw); + return result; +} +static PyObject *__Pyx_CyFunction_CallAsMethod(PyObject *func, PyObject *args, PyObject *kw) { + PyObject *result; + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *) func; +#if CYTHON_METH_FASTCALL + __pyx_vectorcallfunc vc = __Pyx_CyFunction_func_vectorcall(cyfunc); + if (vc) { +#if CYTHON_ASSUME_SAFE_MACROS + return __Pyx_PyVectorcall_FastCallDict(func, vc, &PyTuple_GET_ITEM(args, 0), (size_t)PyTuple_GET_SIZE(args), kw); +#else + (void) &__Pyx_PyVectorcall_FastCallDict; + return PyVectorcall_Call(func, args, kw); +#endif + } +#endif + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + Py_ssize_t argc; + PyObject *new_args; + PyObject *self; +#if CYTHON_ASSUME_SAFE_MACROS + argc = PyTuple_GET_SIZE(args); +#else + argc = PyTuple_Size(args); + if (unlikely(!argc) < 0) return NULL; +#endif + new_args = PyTuple_GetSlice(args, 1, argc); + if (unlikely(!new_args)) + return NULL; + self = PyTuple_GetItem(args, 0); + if (unlikely(!self)) { + Py_DECREF(new_args); +#if PY_MAJOR_VERSION > 2 + PyErr_Format(PyExc_TypeError, + "unbound method %.200S() needs an argument", + cyfunc->func_qualname); +#else + PyErr_SetString(PyExc_TypeError, + "unbound method needs an argument"); +#endif + return NULL; + } + result = __Pyx_CyFunction_CallMethod(func, self, new_args, kw); + Py_DECREF(new_args); + } else { + result = __Pyx_CyFunction_Call(func, args, kw); + } + return result; +} +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE int __Pyx_CyFunction_Vectorcall_CheckArgs(__pyx_CyFunctionObject *cyfunc, Py_ssize_t nargs, PyObject *kwnames) +{ + int ret = 0; + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + if (unlikely(nargs < 1)) { + PyErr_Format(PyExc_TypeError, "%.200s() needs an argument", + ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + ret = 1; + } + if (unlikely(kwnames) && unlikely(PyTuple_GET_SIZE(kwnames))) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no keyword arguments", ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + return ret; +} +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 0)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, NULL); +} +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 1)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, args[0]); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((_PyCFunctionFastWithKeywords)(void(*)(void))def->ml_meth)(self, args, nargs, kwnames); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; + PyTypeObject *cls = (PyTypeObject *) __Pyx_CyFunction_GetClassObj(cyfunc); +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((__Pyx_PyCMethod)(void(*)(void))def->ml_meth)(self, cls, args, (size_t)nargs, kwnames); +} +#endif +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_CyFunctionType_slots[] = { + {Py_tp_dealloc, (void *)__Pyx_CyFunction_dealloc}, + {Py_tp_repr, (void *)__Pyx_CyFunction_repr}, + {Py_tp_call, (void *)__Pyx_CyFunction_CallAsMethod}, + {Py_tp_traverse, (void *)__Pyx_CyFunction_traverse}, + {Py_tp_clear, (void *)__Pyx_CyFunction_clear}, + {Py_tp_methods, (void *)__pyx_CyFunction_methods}, + {Py_tp_members, (void *)__pyx_CyFunction_members}, + {Py_tp_getset, (void *)__pyx_CyFunction_getsets}, + {Py_tp_descr_get, (void *)__Pyx_PyMethod_New}, + {0, 0}, +}; +static PyType_Spec __pyx_CyFunctionType_spec = { + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#if (defined(_Py_TPFLAGS_HAVE_VECTORCALL) && CYTHON_METH_FASTCALL) + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + __pyx_CyFunctionType_slots +}; +#else +static PyTypeObject __pyx_CyFunctionType_type = { + PyVarObject_HEAD_INIT(0, 0) + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, + (destructor) __Pyx_CyFunction_dealloc, +#if !CYTHON_METH_FASTCALL + 0, +#elif CYTHON_BACKPORT_VECTORCALL + (printfunc)offsetof(__pyx_CyFunctionObject, func_vectorcall), +#else + offsetof(PyCFunctionObject, vectorcall), +#endif + 0, + 0, +#if PY_MAJOR_VERSION < 3 + 0, +#else + 0, +#endif + (reprfunc) __Pyx_CyFunction_repr, + 0, + 0, + 0, + 0, + __Pyx_CyFunction_CallAsMethod, + 0, + 0, + 0, + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#if defined(_Py_TPFLAGS_HAVE_VECTORCALL) && CYTHON_METH_FASTCALL + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + 0, + (traverseproc) __Pyx_CyFunction_traverse, + (inquiry) __Pyx_CyFunction_clear, + 0, +#if PY_VERSION_HEX < 0x030500A0 + offsetof(__pyx_CyFunctionObject, func_weakreflist), +#else + offsetof(PyCFunctionObject, m_weakreflist), +#endif + 0, + 0, + __pyx_CyFunction_methods, + __pyx_CyFunction_members, + __pyx_CyFunction_getsets, + 0, + 0, + __Pyx_PyMethod_New, + 0, + offsetof(__pyx_CyFunctionObject, func_dict), + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, +#if PY_VERSION_HEX >= 0x030400a1 + 0, +#endif +#if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, +#endif +#if __PYX_NEED_TP_PRINT_SLOT + 0, +#endif +#if PY_VERSION_HEX >= 0x030C0000 + 0, +#endif +#if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, +#endif +}; +#endif +static int __pyx_CyFunction_init(PyObject *module) { +#if CYTHON_USE_TYPE_SPECS + __pyx_CyFunctionType = __Pyx_FetchCommonTypeFromSpec(module, &__pyx_CyFunctionType_spec, NULL); +#else + CYTHON_UNUSED_VAR(module); + __pyx_CyFunctionType = __Pyx_FetchCommonType(&__pyx_CyFunctionType_type); +#endif + if (unlikely(__pyx_CyFunctionType == NULL)) { + return -1; + } + return 0; +} +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *func, size_t size, int pyobjects) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults = PyObject_Malloc(size); + if (unlikely(!m->defaults)) + return PyErr_NoMemory(); + memset(m->defaults, 0, size); + m->defaults_pyobjects = pyobjects; + m->defaults_size = size; + return m->defaults; +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *func, PyObject *tuple) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_tuple = tuple; + Py_INCREF(tuple); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_kwdict = dict; + Py_INCREF(dict); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->func_annotations = dict; + Py_INCREF(dict); +} + +/* CythonFunction */ +static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { + PyObject *op = __Pyx_CyFunction_Init( + PyObject_GC_New(__pyx_CyFunctionObject, __pyx_CyFunctionType), + ml, flags, qualname, closure, module, globals, code + ); + if (likely(op)) { + PyObject_GC_Track(op); + } + return op; +} + +/* Py3UpdateBases */ +static PyObject* +__Pyx_PEP560_update_bases(PyObject *bases) +{ + Py_ssize_t i, j, size_bases; + PyObject *base, *meth, *new_base, *result, *new_bases = NULL; + size_bases = PyTuple_GET_SIZE(bases); + for (i = 0; i < size_bases; i++) { + base = PyTuple_GET_ITEM(bases, i); + if (PyType_Check(base)) { + if (new_bases) { + if (PyList_Append(new_bases, base) < 0) { + goto error; + } + } + continue; + } + meth = __Pyx_PyObject_GetAttrStrNoError(base, __pyx_n_s_mro_entries); + if (!meth && PyErr_Occurred()) { + goto error; + } + if (!meth) { + if (new_bases) { + if (PyList_Append(new_bases, base) < 0) { + goto error; + } + } + continue; + } + new_base = __Pyx_PyObject_CallOneArg(meth, bases); + Py_DECREF(meth); + if (!new_base) { + goto error; + } + if (!PyTuple_Check(new_base)) { + PyErr_SetString(PyExc_TypeError, + "__mro_entries__ must return a tuple"); + Py_DECREF(new_base); + goto error; + } + if (!new_bases) { + if (!(new_bases = PyList_New(i))) { + goto error; + } + for (j = 0; j < i; j++) { + base = PyTuple_GET_ITEM(bases, j); + PyList_SET_ITEM(new_bases, j, base); + Py_INCREF(base); + } + } + j = PyList_GET_SIZE(new_bases); + if (PyList_SetSlice(new_bases, j, j, new_base) < 0) { + goto error; + } + Py_DECREF(new_base); + } + if (!new_bases) { + Py_INCREF(bases); + return bases; + } + result = PyList_AsTuple(new_bases); + Py_DECREF(new_bases); + return result; +error: + Py_XDECREF(new_bases); + return NULL; +} + +/* SetNewInClass */ +static int __Pyx_SetNewInClass(PyObject *ns, PyObject *name, PyObject *value) { +#ifdef __Pyx_CyFunction_USED + int ret; + if (__Pyx_CyFunction_Check(value)) { + PyObject *staticnew = PyStaticMethod_New(value); + if (unlikely(!staticnew)) return -1; + ret = __Pyx_SetNameInClass(ns, name, staticnew); + Py_DECREF(staticnew); + return ret; + } +#endif + return __Pyx_SetNameInClass(ns, name, value); +} + +/* CalculateMetaclass */ +static PyObject *__Pyx_CalculateMetaclass(PyTypeObject *metaclass, PyObject *bases) { + Py_ssize_t i, nbases; +#if CYTHON_ASSUME_SAFE_MACROS + nbases = PyTuple_GET_SIZE(bases); +#else + nbases = PyTuple_Size(bases); + if (nbases < 0) return NULL; +#endif + for (i=0; i < nbases; i++) { + PyTypeObject *tmptype; +#if CYTHON_ASSUME_SAFE_MACROS + PyObject *tmp = PyTuple_GET_ITEM(bases, i); +#else + PyObject *tmp = PyTuple_GetItem(bases, i); + if (!tmp) return NULL; +#endif + tmptype = Py_TYPE(tmp); +#if PY_MAJOR_VERSION < 3 + if (tmptype == &PyClass_Type) + continue; +#endif + if (!metaclass) { + metaclass = tmptype; + continue; + } + if (PyType_IsSubtype(metaclass, tmptype)) + continue; + if (PyType_IsSubtype(tmptype, metaclass)) { + metaclass = tmptype; + continue; + } + PyErr_SetString(PyExc_TypeError, + "metaclass conflict: " + "the metaclass of a derived class " + "must be a (non-strict) subclass " + "of the metaclasses of all its bases"); + return NULL; + } + if (!metaclass) { +#if PY_MAJOR_VERSION < 3 + metaclass = &PyClass_Type; +#else + metaclass = &PyType_Type; +#endif + } + Py_INCREF((PyObject*) metaclass); + return (PyObject*) metaclass; +} + +/* PyObjectCall2Args */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call2Args(PyObject* function, PyObject* arg1, PyObject* arg2) { + PyObject *args[3] = {NULL, arg1, arg2}; + return __Pyx_PyObject_FastCall(function, args+1, 2 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* PyObjectLookupSpecial */ +#if CYTHON_USE_PYTYPE_LOOKUP && CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx__PyObject_LookupSpecial(PyObject* obj, PyObject* attr_name, int with_error) { + PyObject *res; + PyTypeObject *tp = Py_TYPE(obj); +#if PY_MAJOR_VERSION < 3 + if (unlikely(PyInstance_Check(obj))) + return with_error ? __Pyx_PyObject_GetAttrStr(obj, attr_name) : __Pyx_PyObject_GetAttrStrNoError(obj, attr_name); +#endif + res = _PyType_Lookup(tp, attr_name); + if (likely(res)) { + descrgetfunc f = Py_TYPE(res)->tp_descr_get; + if (!f) { + Py_INCREF(res); + } else { + res = f(res, obj, (PyObject *)tp); + } + } else if (with_error) { + PyErr_SetObject(PyExc_AttributeError, attr_name); + } + return res; +} +#endif + +/* Py3ClassCreate */ +static PyObject *__Pyx_Py3MetaclassPrepare(PyObject *metaclass, PyObject *bases, PyObject *name, + PyObject *qualname, PyObject *mkw, PyObject *modname, PyObject *doc) { + PyObject *ns; + if (metaclass) { + PyObject *prep = __Pyx_PyObject_GetAttrStrNoError(metaclass, __pyx_n_s_prepare); + if (prep) { + PyObject *pargs[3] = {NULL, name, bases}; + ns = __Pyx_PyObject_FastCallDict(prep, pargs+1, 2 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET, mkw); + Py_DECREF(prep); + } else { + if (unlikely(PyErr_Occurred())) + return NULL; + ns = PyDict_New(); + } + } else { + ns = PyDict_New(); + } + if (unlikely(!ns)) + return NULL; + if (unlikely(PyObject_SetItem(ns, __pyx_n_s_module, modname) < 0)) goto bad; +#if PY_VERSION_HEX >= 0x03030000 + if (unlikely(PyObject_SetItem(ns, __pyx_n_s_qualname, qualname) < 0)) goto bad; +#else + CYTHON_MAYBE_UNUSED_VAR(qualname); +#endif + if (unlikely(doc && PyObject_SetItem(ns, __pyx_n_s_doc, doc) < 0)) goto bad; + return ns; +bad: + Py_DECREF(ns); + return NULL; +} +#if PY_VERSION_HEX < 0x030600A4 && CYTHON_PEP487_INIT_SUBCLASS +static int __Pyx_SetNamesPEP487(PyObject *type_obj) { + PyTypeObject *type = (PyTypeObject*) type_obj; + PyObject *names_to_set, *key, *value, *set_name, *tmp; + Py_ssize_t i = 0; +#if CYTHON_USE_TYPE_SLOTS + names_to_set = PyDict_Copy(type->tp_dict); +#else + { + PyObject *d = PyObject_GetAttr(type_obj, __pyx_n_s_dict); + names_to_set = NULL; + if (likely(d)) { + PyObject *names_to_set = PyDict_New(); + int ret = likely(names_to_set) ? PyDict_Update(names_to_set, d) : -1; + Py_DECREF(d); + if (unlikely(ret < 0)) + Py_CLEAR(names_to_set); + } + } +#endif + if (unlikely(names_to_set == NULL)) + goto bad; + while (PyDict_Next(names_to_set, &i, &key, &value)) { + set_name = __Pyx_PyObject_LookupSpecialNoError(value, __pyx_n_s_set_name); + if (unlikely(set_name != NULL)) { + tmp = __Pyx_PyObject_Call2Args(set_name, type_obj, key); + Py_DECREF(set_name); + if (unlikely(tmp == NULL)) { + __Pyx_TypeName value_type_name = + __Pyx_PyType_GetName(Py_TYPE(value)); + __Pyx_TypeName type_name = __Pyx_PyType_GetName(type); + PyErr_Format(PyExc_RuntimeError, +#if PY_MAJOR_VERSION >= 3 + "Error calling __set_name__ on '" __Pyx_FMT_TYPENAME "' instance %R " "in '" __Pyx_FMT_TYPENAME "'", + value_type_name, key, type_name); +#else + "Error calling __set_name__ on '" __Pyx_FMT_TYPENAME "' instance %.100s in '" __Pyx_FMT_TYPENAME "'", + value_type_name, + PyString_Check(key) ? PyString_AS_STRING(key) : "?", + type_name); +#endif + goto bad; + } else { + Py_DECREF(tmp); + } + } + else if (unlikely(PyErr_Occurred())) { + goto bad; + } + } + Py_DECREF(names_to_set); + return 0; +bad: + Py_XDECREF(names_to_set); + return -1; +} +static PyObject *__Pyx_InitSubclassPEP487(PyObject *type_obj, PyObject *mkw) { +#if CYTHON_USE_TYPE_SLOTS && CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + PyTypeObject *type = (PyTypeObject*) type_obj; + PyObject *mro = type->tp_mro; + Py_ssize_t i, nbases; + if (unlikely(!mro)) goto done; + (void) &__Pyx_GetBuiltinName; + Py_INCREF(mro); + nbases = PyTuple_GET_SIZE(mro); + assert(PyTuple_GET_ITEM(mro, 0) == type_obj); + for (i = 1; i < nbases-1; i++) { + PyObject *base, *dict, *meth; + base = PyTuple_GET_ITEM(mro, i); + dict = ((PyTypeObject *)base)->tp_dict; + meth = __Pyx_PyDict_GetItemStrWithError(dict, __pyx_n_s_init_subclass); + if (unlikely(meth)) { + descrgetfunc f = Py_TYPE(meth)->tp_descr_get; + PyObject *res; + Py_INCREF(meth); + if (likely(f)) { + res = f(meth, NULL, type_obj); + Py_DECREF(meth); + if (unlikely(!res)) goto bad; + meth = res; + } + res = __Pyx_PyObject_FastCallDict(meth, NULL, 0, mkw); + Py_DECREF(meth); + if (unlikely(!res)) goto bad; + Py_DECREF(res); + goto done; + } else if (unlikely(PyErr_Occurred())) { + goto bad; + } + } +done: + Py_XDECREF(mro); + return type_obj; +bad: + Py_XDECREF(mro); + Py_DECREF(type_obj); + return NULL; +#else + PyObject *super_type, *super, *func, *res; +#if CYTHON_COMPILING_IN_PYPY && !defined(PySuper_Type) + super_type = __Pyx_GetBuiltinName(__pyx_n_s_super); +#else + super_type = (PyObject*) &PySuper_Type; + (void) &__Pyx_GetBuiltinName; +#endif + super = likely(super_type) ? __Pyx_PyObject_Call2Args(super_type, type_obj, type_obj) : NULL; +#if CYTHON_COMPILING_IN_PYPY && !defined(PySuper_Type) + Py_XDECREF(super_type); +#endif + if (unlikely(!super)) { + Py_CLEAR(type_obj); + goto done; + } + func = __Pyx_PyObject_GetAttrStrNoError(super, __pyx_n_s_init_subclass); + Py_DECREF(super); + if (likely(!func)) { + if (unlikely(PyErr_Occurred())) + Py_CLEAR(type_obj); + goto done; + } + res = __Pyx_PyObject_FastCallDict(func, NULL, 0, mkw); + Py_DECREF(func); + if (unlikely(!res)) + Py_CLEAR(type_obj); + Py_XDECREF(res); +done: + return type_obj; +#endif +} +#endif +static PyObject *__Pyx_Py3ClassCreate(PyObject *metaclass, PyObject *name, PyObject *bases, + PyObject *dict, PyObject *mkw, + int calculate_metaclass, int allow_py2_metaclass) { + PyObject *result; + PyObject *owned_metaclass = NULL; + PyObject *margs[4] = {NULL, name, bases, dict}; + if (allow_py2_metaclass) { + owned_metaclass = PyObject_GetItem(dict, __pyx_n_s_metaclass); + if (owned_metaclass) { + metaclass = owned_metaclass; + } else if (likely(PyErr_ExceptionMatches(PyExc_KeyError))) { + PyErr_Clear(); + } else { + return NULL; + } + } + if (calculate_metaclass && (!metaclass || PyType_Check(metaclass))) { + metaclass = __Pyx_CalculateMetaclass((PyTypeObject*) metaclass, bases); + Py_XDECREF(owned_metaclass); + if (unlikely(!metaclass)) + return NULL; + owned_metaclass = metaclass; + } + result = __Pyx_PyObject_FastCallDict(metaclass, margs+1, 3 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET, +#if PY_VERSION_HEX < 0x030600A4 + (metaclass == (PyObject*)&PyType_Type) ? NULL : mkw +#else + mkw +#endif + ); + Py_XDECREF(owned_metaclass); +#if PY_VERSION_HEX < 0x030600A4 && CYTHON_PEP487_INIT_SUBCLASS + if (likely(result) && likely(PyType_Check(result))) { + if (unlikely(__Pyx_SetNamesPEP487(result) < 0)) { + Py_CLEAR(result); + } else { + result = __Pyx_InitSubclassPEP487(result, mkw); + } + } +#else + (void) &__Pyx_GetBuiltinName; +#endif + return result; +} + +/* Globals */ +static PyObject* __Pyx_Globals(void) { + return __Pyx_NewRef(__pyx_d); +} + +/* UnpackUnboundCMethod */ +static PyObject *__Pyx_SelflessCall(PyObject *method, PyObject *args, PyObject *kwargs) { + PyObject *result; + PyObject *selfless_args = PyTuple_GetSlice(args, 1, PyTuple_Size(args)); + if (unlikely(!selfless_args)) return NULL; + result = PyObject_Call(method, selfless_args, kwargs); + Py_DECREF(selfless_args); + return result; +} +static PyMethodDef __Pyx_UnboundCMethod_Def = { + "CythonUnboundCMethod", + __PYX_REINTERPRET_FUNCION(PyCFunction, __Pyx_SelflessCall), + METH_VARARGS | METH_KEYWORDS, + NULL +}; +static int __Pyx_TryUnpackUnboundCMethod(__Pyx_CachedCFunction* target) { + PyObject *method; + method = __Pyx_PyObject_GetAttrStr(target->type, *target->method_name); + if (unlikely(!method)) + return -1; + target->method = method; +#if CYTHON_COMPILING_IN_CPYTHON + #if PY_MAJOR_VERSION >= 3 + if (likely(__Pyx_TypeCheck(method, &PyMethodDescr_Type))) + #else + if (likely(!__Pyx_CyOrPyCFunction_Check(method))) + #endif + { + PyMethodDescrObject *descr = (PyMethodDescrObject*) method; + target->func = descr->d_method->ml_meth; + target->flag = descr->d_method->ml_flags & ~(METH_CLASS | METH_STATIC | METH_COEXIST | METH_STACKLESS); + } else +#endif +#if CYTHON_COMPILING_IN_PYPY +#else + if (PyCFunction_Check(method)) +#endif + { + PyObject *self; + int self_found; +#if CYTHON_COMPILING_IN_LIMITED_API || CYTHON_COMPILING_IN_PYPY + self = PyObject_GetAttrString(method, "__self__"); + if (!self) { + PyErr_Clear(); + } +#else + self = PyCFunction_GET_SELF(method); +#endif + self_found = (self && self != Py_None); +#if CYTHON_COMPILING_IN_LIMITED_API || CYTHON_COMPILING_IN_PYPY + Py_XDECREF(self); +#endif + if (self_found) { + PyObject *unbound_method = PyCFunction_New(&__Pyx_UnboundCMethod_Def, method); + if (unlikely(!unbound_method)) return -1; + Py_DECREF(method); + target->method = unbound_method; + } + } + return 0; +} + +/* CallUnboundCMethod1 */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_CallUnboundCMethod1(__Pyx_CachedCFunction* cfunc, PyObject* self, PyObject* arg) { + if (likely(cfunc->func)) { + int flag = cfunc->flag; + if (flag == METH_O) { + return (*(cfunc->func))(self, arg); + } else if ((PY_VERSION_HEX >= 0x030600B1) && flag == METH_FASTCALL) { + #if PY_VERSION_HEX >= 0x030700A0 + return (*(__Pyx_PyCFunctionFast)(void*)(PyCFunction)cfunc->func)(self, &arg, 1); + #else + return (*(__Pyx_PyCFunctionFastWithKeywords)(void*)(PyCFunction)cfunc->func)(self, &arg, 1, NULL); + #endif + } else if ((PY_VERSION_HEX >= 0x030700A0) && flag == (METH_FASTCALL | METH_KEYWORDS)) { + return (*(__Pyx_PyCFunctionFastWithKeywords)(void*)(PyCFunction)cfunc->func)(self, &arg, 1, NULL); + } + } + return __Pyx__CallUnboundCMethod1(cfunc, self, arg); +} +#endif +static PyObject* __Pyx__CallUnboundCMethod1(__Pyx_CachedCFunction* cfunc, PyObject* self, PyObject* arg){ + PyObject *args, *result = NULL; + if (unlikely(!cfunc->func && !cfunc->method) && unlikely(__Pyx_TryUnpackUnboundCMethod(cfunc) < 0)) return NULL; +#if CYTHON_COMPILING_IN_CPYTHON + if (cfunc->func && (cfunc->flag & METH_VARARGS)) { + args = PyTuple_New(1); + if (unlikely(!args)) goto bad; + Py_INCREF(arg); + PyTuple_SET_ITEM(args, 0, arg); + if (cfunc->flag & METH_KEYWORDS) + result = (*(PyCFunctionWithKeywords)(void*)(PyCFunction)cfunc->func)(self, args, NULL); + else + result = (*cfunc->func)(self, args); + } else { + args = PyTuple_New(2); + if (unlikely(!args)) goto bad; + Py_INCREF(self); + PyTuple_SET_ITEM(args, 0, self); + Py_INCREF(arg); + PyTuple_SET_ITEM(args, 1, arg); + result = __Pyx_PyObject_Call(cfunc->method, args, NULL); + } +#else + args = PyTuple_Pack(2, self, arg); + if (unlikely(!args)) goto bad; + result = __Pyx_PyObject_Call(cfunc->method, args, NULL); +#endif +bad: + Py_XDECREF(args); + return result; +} + +/* CallUnboundCMethod2 */ +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030600B1 +static CYTHON_INLINE PyObject *__Pyx_CallUnboundCMethod2(__Pyx_CachedCFunction *cfunc, PyObject *self, PyObject *arg1, PyObject *arg2) { + if (likely(cfunc->func)) { + PyObject *args[2] = {arg1, arg2}; + if (cfunc->flag == METH_FASTCALL) { + #if PY_VERSION_HEX >= 0x030700A0 + return (*(__Pyx_PyCFunctionFast)(void*)(PyCFunction)cfunc->func)(self, args, 2); + #else + return (*(__Pyx_PyCFunctionFastWithKeywords)(void*)(PyCFunction)cfunc->func)(self, args, 2, NULL); + #endif + } + #if PY_VERSION_HEX >= 0x030700A0 + if (cfunc->flag == (METH_FASTCALL | METH_KEYWORDS)) + return (*(__Pyx_PyCFunctionFastWithKeywords)(void*)(PyCFunction)cfunc->func)(self, args, 2, NULL); + #endif + } + return __Pyx__CallUnboundCMethod2(cfunc, self, arg1, arg2); +} +#endif +static PyObject* __Pyx__CallUnboundCMethod2(__Pyx_CachedCFunction* cfunc, PyObject* self, PyObject* arg1, PyObject* arg2){ + PyObject *args, *result = NULL; + if (unlikely(!cfunc->func && !cfunc->method) && unlikely(__Pyx_TryUnpackUnboundCMethod(cfunc) < 0)) return NULL; +#if CYTHON_COMPILING_IN_CPYTHON + if (cfunc->func && (cfunc->flag & METH_VARARGS)) { + args = PyTuple_New(2); + if (unlikely(!args)) goto bad; + Py_INCREF(arg1); + PyTuple_SET_ITEM(args, 0, arg1); + Py_INCREF(arg2); + PyTuple_SET_ITEM(args, 1, arg2); + if (cfunc->flag & METH_KEYWORDS) + result = (*(PyCFunctionWithKeywords)(void*)(PyCFunction)cfunc->func)(self, args, NULL); + else + result = (*cfunc->func)(self, args); + } else { + args = PyTuple_New(3); + if (unlikely(!args)) goto bad; + Py_INCREF(self); + PyTuple_SET_ITEM(args, 0, self); + Py_INCREF(arg1); + PyTuple_SET_ITEM(args, 1, arg1); + Py_INCREF(arg2); + PyTuple_SET_ITEM(args, 2, arg2); + result = __Pyx_PyObject_Call(cfunc->method, args, NULL); + } +#else + args = PyTuple_Pack(3, self, arg1, arg2); + if (unlikely(!args)) goto bad; + result = __Pyx_PyObject_Call(cfunc->method, args, NULL); +#endif +bad: + Py_XDECREF(args); + return result; +} + +/* dict_getitem_default */ +static PyObject* __Pyx_PyDict_GetItemDefault(PyObject* d, PyObject* key, PyObject* default_value) { + PyObject* value; +#if PY_MAJOR_VERSION >= 3 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07020000) + value = PyDict_GetItemWithError(d, key); + if (unlikely(!value)) { + if (unlikely(PyErr_Occurred())) + return NULL; + value = default_value; + } + Py_INCREF(value); + if ((1)); +#else + if (PyString_CheckExact(key) || PyUnicode_CheckExact(key) || PyInt_CheckExact(key)) { + value = PyDict_GetItem(d, key); + if (unlikely(!value)) { + value = default_value; + } + Py_INCREF(value); + } +#endif + else { + if (default_value == Py_None) + value = __Pyx_CallUnboundCMethod1(&__pyx_umethod_PyDict_Type_get, d, key); + else + value = __Pyx_CallUnboundCMethod2(&__pyx_umethod_PyDict_Type_get, d, key, default_value); + } + return value; +} + +/* CLineInTraceback */ +#ifndef CYTHON_CLINE_IN_TRACEBACK +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line) { + PyObject *use_cline; + PyObject *ptype, *pvalue, *ptraceback; +#if CYTHON_COMPILING_IN_CPYTHON + PyObject **cython_runtime_dict; +#endif + CYTHON_MAYBE_UNUSED_VAR(tstate); + if (unlikely(!__pyx_cython_runtime)) { + return c_line; + } + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); +#if CYTHON_COMPILING_IN_CPYTHON + cython_runtime_dict = _PyObject_GetDictPtr(__pyx_cython_runtime); + if (likely(cython_runtime_dict)) { + __PYX_PY_DICT_LOOKUP_IF_MODIFIED( + use_cline, *cython_runtime_dict, + __Pyx_PyDict_GetItemStr(*cython_runtime_dict, __pyx_n_s_cline_in_traceback)) + } else +#endif + { + PyObject *use_cline_obj = __Pyx_PyObject_GetAttrStrNoError(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback); + if (use_cline_obj) { + use_cline = PyObject_Not(use_cline_obj) ? Py_False : Py_True; + Py_DECREF(use_cline_obj); + } else { + PyErr_Clear(); + use_cline = NULL; + } + } + if (!use_cline) { + c_line = 0; + (void) PyObject_SetAttr(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback, Py_False); + } + else if (use_cline == Py_False || (use_cline != Py_True && PyObject_Not(use_cline) != 0)) { + c_line = 0; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + return c_line; +} +#endif + +/* CodeObjectCache */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line) { + int start = 0, mid = 0, end = count - 1; + if (end >= 0 && code_line > entries[end].code_line) { + return count; + } + while (start < end) { + mid = start + (end - start) / 2; + if (code_line < entries[mid].code_line) { + end = mid; + } else if (code_line > entries[mid].code_line) { + start = mid + 1; + } else { + return mid; + } + } + if (code_line <= entries[mid].code_line) { + return mid; + } else { + return mid + 1; + } +} +static PyCodeObject *__pyx_find_code_object(int code_line) { + PyCodeObject* code_object; + int pos; + if (unlikely(!code_line) || unlikely(!__pyx_code_cache.entries)) { + return NULL; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if (unlikely(pos >= __pyx_code_cache.count) || unlikely(__pyx_code_cache.entries[pos].code_line != code_line)) { + return NULL; + } + code_object = __pyx_code_cache.entries[pos].code_object; + Py_INCREF(code_object); + return code_object; +} +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object) { + int pos, i; + __Pyx_CodeObjectCacheEntry* entries = __pyx_code_cache.entries; + if (unlikely(!code_line)) { + return; + } + if (unlikely(!entries)) { + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Malloc(64*sizeof(__Pyx_CodeObjectCacheEntry)); + if (likely(entries)) { + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = 64; + __pyx_code_cache.count = 1; + entries[0].code_line = code_line; + entries[0].code_object = code_object; + Py_INCREF(code_object); + } + return; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if ((pos < __pyx_code_cache.count) && unlikely(__pyx_code_cache.entries[pos].code_line == code_line)) { + PyCodeObject* tmp = entries[pos].code_object; + entries[pos].code_object = code_object; + Py_DECREF(tmp); + return; + } + if (__pyx_code_cache.count == __pyx_code_cache.max_count) { + int new_max = __pyx_code_cache.max_count + 64; + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Realloc( + __pyx_code_cache.entries, ((size_t)new_max) * sizeof(__Pyx_CodeObjectCacheEntry)); + if (unlikely(!entries)) { + return; + } + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = new_max; + } + for (i=__pyx_code_cache.count; i>pos; i--) { + entries[i] = entries[i-1]; + } + entries[pos].code_line = code_line; + entries[pos].code_object = code_object; + __pyx_code_cache.count++; + Py_INCREF(code_object); +} +#endif + +/* AddTraceback */ +#include "compile.h" +#include "frameobject.h" +#include "traceback.h" +#if PY_VERSION_HEX >= 0x030b00a6 && !CYTHON_COMPILING_IN_LIMITED_API + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static PyObject *__Pyx_PyCode_Replace_For_AddTraceback(PyObject *code, PyObject *scratch_dict, + PyObject *firstlineno, PyObject *name) { + PyObject *replace = NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "co_firstlineno", firstlineno))) return NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "co_name", name))) return NULL; + replace = PyObject_GetAttrString(code, "replace"); + if (likely(replace)) { + PyObject *result; + result = PyObject_Call(replace, __pyx_empty_tuple, scratch_dict); + Py_DECREF(replace); + return result; + } + PyErr_Clear(); + #if __PYX_LIMITED_VERSION_HEX < 0x030780000 + { + PyObject *compiled = NULL, *result = NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "code", code))) return NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "type", (PyObject*)(&PyType_Type)))) return NULL; + compiled = Py_CompileString( + "out = type(code)(\n" + " code.co_argcount, code.co_kwonlyargcount, code.co_nlocals, code.co_stacksize,\n" + " code.co_flags, code.co_code, code.co_consts, code.co_names,\n" + " code.co_varnames, code.co_filename, co_name, co_firstlineno,\n" + " code.co_lnotab)\n", "", Py_file_input); + if (!compiled) return NULL; + result = PyEval_EvalCode(compiled, scratch_dict, scratch_dict); + Py_DECREF(compiled); + if (!result) PyErr_Print(); + Py_DECREF(result); + result = PyDict_GetItemString(scratch_dict, "out"); + if (result) Py_INCREF(result); + return result; + } + #else + return NULL; + #endif +} +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + PyObject *code_object = NULL, *py_py_line = NULL, *py_funcname = NULL, *dict = NULL; + PyObject *replace = NULL, *getframe = NULL, *frame = NULL; + PyObject *exc_type, *exc_value, *exc_traceback; + int success = 0; + if (c_line) { + (void) __pyx_cfilenm; + (void) __Pyx_CLineForTraceback(__Pyx_PyThreadState_Current, c_line); + } + PyErr_Fetch(&exc_type, &exc_value, &exc_traceback); + code_object = Py_CompileString("_getframe()", filename, Py_eval_input); + if (unlikely(!code_object)) goto bad; + py_py_line = PyLong_FromLong(py_line); + if (unlikely(!py_py_line)) goto bad; + py_funcname = PyUnicode_FromString(funcname); + if (unlikely(!py_funcname)) goto bad; + dict = PyDict_New(); + if (unlikely(!dict)) goto bad; + { + PyObject *old_code_object = code_object; + code_object = __Pyx_PyCode_Replace_For_AddTraceback(code_object, dict, py_py_line, py_funcname); + Py_DECREF(old_code_object); + } + if (unlikely(!code_object)) goto bad; + getframe = PySys_GetObject("_getframe"); + if (unlikely(!getframe)) goto bad; + if (unlikely(PyDict_SetItemString(dict, "_getframe", getframe))) goto bad; + frame = PyEval_EvalCode(code_object, dict, dict); + if (unlikely(!frame) || frame == Py_None) goto bad; + success = 1; + bad: + PyErr_Restore(exc_type, exc_value, exc_traceback); + Py_XDECREF(code_object); + Py_XDECREF(py_py_line); + Py_XDECREF(py_funcname); + Py_XDECREF(dict); + Py_XDECREF(replace); + if (success) { + PyTraceBack_Here( + (struct _frame*)frame); + } + Py_XDECREF(frame); +} +#else +static PyCodeObject* __Pyx_CreateCodeObjectForTraceback( + const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = NULL; + PyObject *py_funcname = NULL; + #if PY_MAJOR_VERSION < 3 + PyObject *py_srcfile = NULL; + py_srcfile = PyString_FromString(filename); + if (!py_srcfile) goto bad; + #endif + if (c_line) { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + #else + py_funcname = PyUnicode_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + funcname = PyUnicode_AsUTF8(py_funcname); + if (!funcname) goto bad; + #endif + } + else { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromString(funcname); + if (!py_funcname) goto bad; + #endif + } + #if PY_MAJOR_VERSION < 3 + py_code = __Pyx_PyCode_New( + 0, + 0, + 0, + 0, + 0, + 0, + __pyx_empty_bytes, /*PyObject *code,*/ + __pyx_empty_tuple, /*PyObject *consts,*/ + __pyx_empty_tuple, /*PyObject *names,*/ + __pyx_empty_tuple, /*PyObject *varnames,*/ + __pyx_empty_tuple, /*PyObject *freevars,*/ + __pyx_empty_tuple, /*PyObject *cellvars,*/ + py_srcfile, /*PyObject *filename,*/ + py_funcname, /*PyObject *name,*/ + py_line, + __pyx_empty_bytes /*PyObject *lnotab*/ + ); + Py_DECREF(py_srcfile); + #else + py_code = PyCode_NewEmpty(filename, funcname, py_line); + #endif + Py_XDECREF(py_funcname); + return py_code; +bad: + Py_XDECREF(py_funcname); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_srcfile); + #endif + return NULL; +} +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = 0; + PyFrameObject *py_frame = 0; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject *ptype, *pvalue, *ptraceback; + if (c_line) { + c_line = __Pyx_CLineForTraceback(tstate, c_line); + } + py_code = __pyx_find_code_object(c_line ? -c_line : py_line); + if (!py_code) { + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); + py_code = __Pyx_CreateCodeObjectForTraceback( + funcname, c_line, py_line, filename); + if (!py_code) { + /* If the code object creation fails, then we should clear the + fetched exception references and propagate the new exception */ + Py_XDECREF(ptype); + Py_XDECREF(pvalue); + Py_XDECREF(ptraceback); + goto bad; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + __pyx_insert_code_object(c_line ? -c_line : py_line, py_code); + } + py_frame = PyFrame_New( + tstate, /*PyThreadState *tstate,*/ + py_code, /*PyCodeObject *code,*/ + __pyx_d, /*PyObject *globals,*/ + 0 /*PyObject *locals*/ + ); + if (!py_frame) goto bad; + __Pyx_PyFrame_SetLineNumber(py_frame, py_line); + PyTraceBack_Here(py_frame); +bad: + Py_XDECREF(py_code); + Py_XDECREF(py_frame); +} +#endif + +/* CIntFromPyVerify */ +#define __PYX_VERIFY_RETURN_INT(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 0) +#define __PYX_VERIFY_RETURN_INT_EXC(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 1) +#define __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, exc)\ + {\ + func_type value = func_value;\ + if (sizeof(target_type) < sizeof(func_type)) {\ + if (unlikely(value != (func_type) (target_type) value)) {\ + func_type zero = 0;\ + if (exc && unlikely(value == (func_type)-1 && PyErr_Occurred()))\ + return (target_type) -1;\ + if (is_unsigned && unlikely(value < zero))\ + goto raise_neg_overflow;\ + else\ + goto raise_overflow;\ + }\ + }\ + return (target_type) value;\ + } + +/* CIntFromPy */ +static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(int) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(int, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (int) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 2 * PyLong_SHIFT)) { + return (int) (((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 3 * PyLong_SHIFT)) { + return (int) (((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 4 * PyLong_SHIFT)) { + return (int) (((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(int) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(int) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) ((((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) ((((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) ((((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(int) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + int val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (int) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (int) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (int) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (int) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(int) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(int) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((int) 1) << (sizeof(int) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (int) -1; + } + } else { + int val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (int) -1; + val = __Pyx_PyInt_As_int(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to int"); + return (int) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to int"); + return (int) -1; +} + +/* CIntFromPy */ +static CYTHON_INLINE enum ParamKeyType __Pyx_PyInt_As_enum__ParamKeyType(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const enum ParamKeyType neg_one = (enum ParamKeyType) -1, const_zero = (enum ParamKeyType) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(enum ParamKeyType) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(enum ParamKeyType, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (enum ParamKeyType) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(enum ParamKeyType, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(enum ParamKeyType) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(enum ParamKeyType, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(enum ParamKeyType) >= 2 * PyLong_SHIFT)) { + return (enum ParamKeyType) (((((enum ParamKeyType)digits[1]) << PyLong_SHIFT) | (enum ParamKeyType)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(enum ParamKeyType) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(enum ParamKeyType, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(enum ParamKeyType) >= 3 * PyLong_SHIFT)) { + return (enum ParamKeyType) (((((((enum ParamKeyType)digits[2]) << PyLong_SHIFT) | (enum ParamKeyType)digits[1]) << PyLong_SHIFT) | (enum ParamKeyType)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(enum ParamKeyType) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(enum ParamKeyType, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(enum ParamKeyType) >= 4 * PyLong_SHIFT)) { + return (enum ParamKeyType) (((((((((enum ParamKeyType)digits[3]) << PyLong_SHIFT) | (enum ParamKeyType)digits[2]) << PyLong_SHIFT) | (enum ParamKeyType)digits[1]) << PyLong_SHIFT) | (enum ParamKeyType)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (enum ParamKeyType) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(enum ParamKeyType) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(enum ParamKeyType, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(enum ParamKeyType) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(enum ParamKeyType, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(enum ParamKeyType, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(enum ParamKeyType) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(enum ParamKeyType, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(enum ParamKeyType) - 1 > 2 * PyLong_SHIFT)) { + return (enum ParamKeyType) (((enum ParamKeyType)-1)*(((((enum ParamKeyType)digits[1]) << PyLong_SHIFT) | (enum ParamKeyType)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(enum ParamKeyType) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(enum ParamKeyType, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(enum ParamKeyType) - 1 > 2 * PyLong_SHIFT)) { + return (enum ParamKeyType) ((((((enum ParamKeyType)digits[1]) << PyLong_SHIFT) | (enum ParamKeyType)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(enum ParamKeyType) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(enum ParamKeyType, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(enum ParamKeyType) - 1 > 3 * PyLong_SHIFT)) { + return (enum ParamKeyType) (((enum ParamKeyType)-1)*(((((((enum ParamKeyType)digits[2]) << PyLong_SHIFT) | (enum ParamKeyType)digits[1]) << PyLong_SHIFT) | (enum ParamKeyType)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(enum ParamKeyType) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(enum ParamKeyType, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(enum ParamKeyType) - 1 > 3 * PyLong_SHIFT)) { + return (enum ParamKeyType) ((((((((enum ParamKeyType)digits[2]) << PyLong_SHIFT) | (enum ParamKeyType)digits[1]) << PyLong_SHIFT) | (enum ParamKeyType)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(enum ParamKeyType) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(enum ParamKeyType, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(enum ParamKeyType) - 1 > 4 * PyLong_SHIFT)) { + return (enum ParamKeyType) (((enum ParamKeyType)-1)*(((((((((enum ParamKeyType)digits[3]) << PyLong_SHIFT) | (enum ParamKeyType)digits[2]) << PyLong_SHIFT) | (enum ParamKeyType)digits[1]) << PyLong_SHIFT) | (enum ParamKeyType)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(enum ParamKeyType) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(enum ParamKeyType, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(enum ParamKeyType) - 1 > 4 * PyLong_SHIFT)) { + return (enum ParamKeyType) ((((((((((enum ParamKeyType)digits[3]) << PyLong_SHIFT) | (enum ParamKeyType)digits[2]) << PyLong_SHIFT) | (enum ParamKeyType)digits[1]) << PyLong_SHIFT) | (enum ParamKeyType)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(enum ParamKeyType) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(enum ParamKeyType, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(enum ParamKeyType) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(enum ParamKeyType, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + PyErr_SetString(PyExc_RuntimeError, + "_PyLong_AsByteArray() not available, cannot convert large enums"); + return (enum ParamKeyType) -1; + } else { + enum ParamKeyType val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (enum ParamKeyType) -1; + val = __Pyx_PyInt_As_enum__ParamKeyType(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to enum ParamKeyType"); + return (enum ParamKeyType) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to enum ParamKeyType"); + return (enum ParamKeyType) -1; +} + +/* CIntToPy */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_int(int value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(int) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(int) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(int) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(int) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(int) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; +#if !CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030d0000 + return _PyLong_FromByteArray(bytes, sizeof(int), + little, !is_unsigned); +#else + PyObject *from_bytes, *result = NULL; + PyObject *py_bytes = NULL, *arg_tuple = NULL, *kwds = NULL, *order_str = NULL; + from_bytes = PyObject_GetAttrString((PyObject*)&PyLong_Type, "from_bytes"); + if (!from_bytes) return NULL; + py_bytes = PyBytes_FromStringAndSize((char*)bytes, sizeof(int)); + if (!py_bytes) goto limited_bad; + order_str = PyUnicode_FromString(little ? "little" : "big"); + if (!order_str) goto limited_bad; + arg_tuple = PyTuple_Pack(2, py_bytes, order_str); + if (!arg_tuple) goto limited_bad; + if (!is_unsigned) { + kwds = PyDict_New(); + if (!kwds) goto limited_bad; + if (PyDict_SetItemString(kwds, "signed", __Pyx_NewRef(Py_True))) goto limited_bad; + } + result = PyObject_Call(from_bytes, arg_tuple, kwds); + limited_bad: + Py_XDECREF(kwds); + Py_XDECREF(arg_tuple); + Py_XDECREF(order_str); + Py_XDECREF(py_bytes); + Py_XDECREF(from_bytes); + return result; +#endif + } +} + +/* CIntToPy */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_enum__ParamKeyType(enum ParamKeyType value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const enum ParamKeyType neg_one = (enum ParamKeyType) -1, const_zero = (enum ParamKeyType) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(enum ParamKeyType) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(enum ParamKeyType) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(enum ParamKeyType) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(enum ParamKeyType) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(enum ParamKeyType) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; +#if !CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030d0000 + return _PyLong_FromByteArray(bytes, sizeof(enum ParamKeyType), + little, !is_unsigned); +#else + PyObject *from_bytes, *result = NULL; + PyObject *py_bytes = NULL, *arg_tuple = NULL, *kwds = NULL, *order_str = NULL; + from_bytes = PyObject_GetAttrString((PyObject*)&PyLong_Type, "from_bytes"); + if (!from_bytes) return NULL; + py_bytes = PyBytes_FromStringAndSize((char*)bytes, sizeof(enum ParamKeyType)); + if (!py_bytes) goto limited_bad; + order_str = PyUnicode_FromString(little ? "little" : "big"); + if (!order_str) goto limited_bad; + arg_tuple = PyTuple_Pack(2, py_bytes, order_str); + if (!arg_tuple) goto limited_bad; + if (!is_unsigned) { + kwds = PyDict_New(); + if (!kwds) goto limited_bad; + if (PyDict_SetItemString(kwds, "signed", __Pyx_NewRef(Py_True))) goto limited_bad; + } + result = PyObject_Call(from_bytes, arg_tuple, kwds); + limited_bad: + Py_XDECREF(kwds); + Py_XDECREF(arg_tuple); + Py_XDECREF(order_str); + Py_XDECREF(py_bytes); + Py_XDECREF(from_bytes); + return result; +#endif + } +} + +/* CIntFromPy */ +static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(long) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(long, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (long) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 2 * PyLong_SHIFT)) { + return (long) (((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 3 * PyLong_SHIFT)) { + return (long) (((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 4 * PyLong_SHIFT)) { + return (long) (((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(long) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(long) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) ((((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) ((((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) ((((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(long) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + long val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (long) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (long) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (long) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (long) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(long) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(long) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((long) 1) << (sizeof(long) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (long) -1; + } + } else { + long val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (long) -1; + val = __Pyx_PyInt_As_long(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to long"); + return (long) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to long"); + return (long) -1; +} + +/* CIntToPy */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(long) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(long) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(long) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; +#if !CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030d0000 + return _PyLong_FromByteArray(bytes, sizeof(long), + little, !is_unsigned); +#else + PyObject *from_bytes, *result = NULL; + PyObject *py_bytes = NULL, *arg_tuple = NULL, *kwds = NULL, *order_str = NULL; + from_bytes = PyObject_GetAttrString((PyObject*)&PyLong_Type, "from_bytes"); + if (!from_bytes) return NULL; + py_bytes = PyBytes_FromStringAndSize((char*)bytes, sizeof(long)); + if (!py_bytes) goto limited_bad; + order_str = PyUnicode_FromString(little ? "little" : "big"); + if (!order_str) goto limited_bad; + arg_tuple = PyTuple_Pack(2, py_bytes, order_str); + if (!arg_tuple) goto limited_bad; + if (!is_unsigned) { + kwds = PyDict_New(); + if (!kwds) goto limited_bad; + if (PyDict_SetItemString(kwds, "signed", __Pyx_NewRef(Py_True))) goto limited_bad; + } + result = PyObject_Call(from_bytes, arg_tuple, kwds); + limited_bad: + Py_XDECREF(kwds); + Py_XDECREF(arg_tuple); + Py_XDECREF(order_str); + Py_XDECREF(py_bytes); + Py_XDECREF(from_bytes); + return result; +#endif + } +} + +/* FormatTypeName */ +#if CYTHON_COMPILING_IN_LIMITED_API +static __Pyx_TypeName +__Pyx_PyType_GetName(PyTypeObject* tp) +{ + PyObject *name = __Pyx_PyObject_GetAttrStr((PyObject *)tp, + __pyx_n_s_name_2); + if (unlikely(name == NULL) || unlikely(!PyUnicode_Check(name))) { + PyErr_Clear(); + Py_XDECREF(name); + name = __Pyx_NewRef(__pyx_n_s__52); + } + return name; +} +#endif + +/* FastTypeChecks */ +#if CYTHON_COMPILING_IN_CPYTHON +static int __Pyx_InBases(PyTypeObject *a, PyTypeObject *b) { + while (a) { + a = __Pyx_PyType_GetSlot(a, tp_base, PyTypeObject*); + if (a == b) + return 1; + } + return b == &PyBaseObject_Type; +} +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (a == b) return 1; + mro = a->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + if (PyTuple_GET_ITEM(mro, i) == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(a, b); +} +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (cls == a || cls == b) return 1; + mro = cls->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + PyObject *base = PyTuple_GET_ITEM(mro, i); + if (base == (PyObject *)a || base == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(cls, a) || __Pyx_InBases(cls, b); +} +#if PY_MAJOR_VERSION == 2 +static int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject* exc_type2) { + PyObject *exception, *value, *tb; + int res; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&exception, &value, &tb); + res = exc_type1 ? PyObject_IsSubclass(err, exc_type1) : 0; + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + if (!res) { + res = PyObject_IsSubclass(err, exc_type2); + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + } + __Pyx_ErrRestore(exception, value, tb); + return res; +} +#else +static CYTHON_INLINE int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject *exc_type2) { + if (exc_type1) { + return __Pyx_IsAnySubtype2((PyTypeObject*)err, (PyTypeObject*)exc_type1, (PyTypeObject*)exc_type2); + } else { + return __Pyx_IsSubtype((PyTypeObject*)err, (PyTypeObject*)exc_type2); + } +} +#endif +static int __Pyx_PyErr_GivenExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + assert(PyExceptionClass_Check(exc_type)); + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; i= 0x030B00A4 + return Py_Version & ~0xFFUL; +#else + const char* rt_version = Py_GetVersion(); + unsigned long version = 0; + unsigned long factor = 0x01000000UL; + unsigned int digit = 0; + int i = 0; + while (factor) { + while ('0' <= rt_version[i] && rt_version[i] <= '9') { + digit = digit * 10 + (unsigned int) (rt_version[i] - '0'); + ++i; + } + version += factor * digit; + if (rt_version[i] != '.') + break; + digit = 0; + factor >>= 8; + ++i; + } + return version; +#endif +} +static int __Pyx_check_binary_version(unsigned long ct_version, unsigned long rt_version, int allow_newer) { + const unsigned long MAJOR_MINOR = 0xFFFF0000UL; + if ((rt_version & MAJOR_MINOR) == (ct_version & MAJOR_MINOR)) + return 0; + if (likely(allow_newer && (rt_version & MAJOR_MINOR) > (ct_version & MAJOR_MINOR))) + return 1; + { + char message[200]; + PyOS_snprintf(message, sizeof(message), + "compile time Python version %d.%d " + "of module '%.100s' " + "%s " + "runtime version %d.%d", + (int) (ct_version >> 24), (int) ((ct_version >> 16) & 0xFF), + __Pyx_MODULE_NAME, + (allow_newer) ? "was newer than" : "does not match", + (int) (rt_version >> 24), (int) ((rt_version >> 16) & 0xFF) + ); + return PyErr_WarnEx(NULL, message, 1); + } +} + +/* InitStrings */ +#if PY_MAJOR_VERSION >= 3 +static int __Pyx_InitString(__Pyx_StringTabEntry t, PyObject **str) { + if (t.is_unicode | t.is_str) { + if (t.intern) { + *str = PyUnicode_InternFromString(t.s); + } else if (t.encoding) { + *str = PyUnicode_Decode(t.s, t.n - 1, t.encoding, NULL); + } else { + *str = PyUnicode_FromStringAndSize(t.s, t.n - 1); + } + } else { + *str = PyBytes_FromStringAndSize(t.s, t.n - 1); + } + if (!*str) + return -1; + if (PyObject_Hash(*str) == -1) + return -1; + return 0; +} +#endif +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t) { + while (t->p) { + #if PY_MAJOR_VERSION >= 3 + __Pyx_InitString(*t, t->p); + #else + if (t->is_unicode) { + *t->p = PyUnicode_DecodeUTF8(t->s, t->n - 1, NULL); + } else if (t->intern) { + *t->p = PyString_InternFromString(t->s); + } else { + *t->p = PyString_FromStringAndSize(t->s, t->n - 1); + } + if (!*t->p) + return -1; + if (PyObject_Hash(*t->p) == -1) + return -1; + #endif + ++t; + } + return 0; +} + +#include +static CYTHON_INLINE Py_ssize_t __Pyx_ssize_strlen(const char *s) { + size_t len = strlen(s); + if (unlikely(len > (size_t) PY_SSIZE_T_MAX)) { + PyErr_SetString(PyExc_OverflowError, "byte string is too long"); + return -1; + } + return (Py_ssize_t) len; +} +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char* c_str) { + Py_ssize_t len = __Pyx_ssize_strlen(c_str); + if (unlikely(len < 0)) return NULL; + return __Pyx_PyUnicode_FromStringAndSize(c_str, len); +} +static CYTHON_INLINE PyObject* __Pyx_PyByteArray_FromString(const char* c_str) { + Py_ssize_t len = __Pyx_ssize_strlen(c_str); + if (unlikely(len < 0)) return NULL; + return PyByteArray_FromStringAndSize(c_str, len); +} +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject* o) { + Py_ssize_t ignore; + return __Pyx_PyObject_AsStringAndSize(o, &ignore); +} +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +#if !CYTHON_PEP393_ENABLED +static const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + char* defenc_c; + PyObject* defenc = _PyUnicode_AsDefaultEncodedString(o, NULL); + if (!defenc) return NULL; + defenc_c = PyBytes_AS_STRING(defenc); +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + { + char* end = defenc_c + PyBytes_GET_SIZE(defenc); + char* c; + for (c = defenc_c; c < end; c++) { + if ((unsigned char) (*c) >= 128) { + PyUnicode_AsASCIIString(o); + return NULL; + } + } + } +#endif + *length = PyBytes_GET_SIZE(defenc); + return defenc_c; +} +#else +static CYTHON_INLINE const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + if (unlikely(__Pyx_PyUnicode_READY(o) == -1)) return NULL; +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + if (likely(PyUnicode_IS_ASCII(o))) { + *length = PyUnicode_GET_LENGTH(o); + return PyUnicode_AsUTF8(o); + } else { + PyUnicode_AsASCIIString(o); + return NULL; + } +#else + return PyUnicode_AsUTF8AndSize(o, length); +#endif +} +#endif +#endif +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject* o, Py_ssize_t *length) { +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT + if ( +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + __Pyx_sys_getdefaultencoding_not_ascii && +#endif + PyUnicode_Check(o)) { + return __Pyx_PyUnicode_AsStringAndSize(o, length); + } else +#endif +#if (!CYTHON_COMPILING_IN_PYPY && !CYTHON_COMPILING_IN_LIMITED_API) || (defined(PyByteArray_AS_STRING) && defined(PyByteArray_GET_SIZE)) + if (PyByteArray_Check(o)) { + *length = PyByteArray_GET_SIZE(o); + return PyByteArray_AS_STRING(o); + } else +#endif + { + char* result; + int r = PyBytes_AsStringAndSize(o, &result, length); + if (unlikely(r < 0)) { + return NULL; + } else { + return result; + } + } +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject* x) { + int is_true = x == Py_True; + if (is_true | (x == Py_False) | (x == Py_None)) return is_true; + else return PyObject_IsTrue(x); +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject* x) { + int retval; + if (unlikely(!x)) return -1; + retval = __Pyx_PyObject_IsTrue(x); + Py_DECREF(x); + return retval; +} +static PyObject* __Pyx_PyNumber_IntOrLongWrongResultType(PyObject* result, const char* type_name) { + __Pyx_TypeName result_type_name = __Pyx_PyType_GetName(Py_TYPE(result)); +#if PY_MAJOR_VERSION >= 3 + if (PyLong_Check(result)) { + if (PyErr_WarnFormat(PyExc_DeprecationWarning, 1, + "__int__ returned non-int (type " __Pyx_FMT_TYPENAME "). " + "The ability to return an instance of a strict subclass of int is deprecated, " + "and may be removed in a future version of Python.", + result_type_name)) { + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; + } + __Pyx_DECREF_TypeName(result_type_name); + return result; + } +#endif + PyErr_Format(PyExc_TypeError, + "__%.4s__ returned non-%.4s (type " __Pyx_FMT_TYPENAME ")", + type_name, type_name, result_type_name); + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x) { +#if CYTHON_USE_TYPE_SLOTS + PyNumberMethods *m; +#endif + const char *name = NULL; + PyObject *res = NULL; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x) || PyLong_Check(x))) +#else + if (likely(PyLong_Check(x))) +#endif + return __Pyx_NewRef(x); +#if CYTHON_USE_TYPE_SLOTS + m = Py_TYPE(x)->tp_as_number; + #if PY_MAJOR_VERSION < 3 + if (m && m->nb_int) { + name = "int"; + res = m->nb_int(x); + } + else if (m && m->nb_long) { + name = "long"; + res = m->nb_long(x); + } + #else + if (likely(m && m->nb_int)) { + name = "int"; + res = m->nb_int(x); + } + #endif +#else + if (!PyBytes_CheckExact(x) && !PyUnicode_CheckExact(x)) { + res = PyNumber_Int(x); + } +#endif + if (likely(res)) { +#if PY_MAJOR_VERSION < 3 + if (unlikely(!PyInt_Check(res) && !PyLong_Check(res))) { +#else + if (unlikely(!PyLong_CheckExact(res))) { +#endif + return __Pyx_PyNumber_IntOrLongWrongResultType(res, name); + } + } + else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_TypeError, + "an integer is required"); + } + return res; +} +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject* b) { + Py_ssize_t ival; + PyObject *x; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_CheckExact(b))) { + if (sizeof(Py_ssize_t) >= sizeof(long)) + return PyInt_AS_LONG(b); + else + return PyInt_AsSsize_t(b); + } +#endif + if (likely(PyLong_CheckExact(b))) { + #if CYTHON_USE_PYLONG_INTERNALS + if (likely(__Pyx_PyLong_IsCompact(b))) { + return __Pyx_PyLong_CompactValue(b); + } else { + const digit* digits = __Pyx_PyLong_Digits(b); + const Py_ssize_t size = __Pyx_PyLong_SignedDigitCount(b); + switch (size) { + case 2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return (Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + } + } + #endif + return PyLong_AsSsize_t(b); + } + x = PyNumber_Index(b); + if (!x) return -1; + ival = PyInt_AsSsize_t(x); + Py_DECREF(x); + return ival; +} +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject* o) { + if (sizeof(Py_hash_t) == sizeof(Py_ssize_t)) { + return (Py_hash_t) __Pyx_PyIndex_AsSsize_t(o); +#if PY_MAJOR_VERSION < 3 + } else if (likely(PyInt_CheckExact(o))) { + return PyInt_AS_LONG(o); +#endif + } else { + Py_ssize_t ival; + PyObject *x; + x = PyNumber_Index(o); + if (!x) return -1; + ival = PyInt_AsLong(x); + Py_DECREF(x); + return ival; + } +} +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b) { + return b ? __Pyx_NewRef(Py_True) : __Pyx_NewRef(Py_False); +} +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t ival) { + return PyInt_FromSize_t(ival); +} + + +/* #### Code section: utility_code_pragmas_end ### */ +#ifdef _MSC_VER +#pragma warning( pop ) +#endif + + + +/* #### Code section: end ### */ +#endif /* Py_PYTHON_H */ diff --git a/common/params_pyx.so b/common/params_pyx.so new file mode 100755 index 0000000..d1486af Binary files /dev/null and b/common/params_pyx.so differ diff --git a/common/prefix.h b/common/prefix.h deleted file mode 100644 index f5abe14..0000000 --- a/common/prefix.h +++ /dev/null @@ -1,34 +0,0 @@ -#pragma once - -#include -#include - -#include "common/params.h" -#include "common/util.h" - -class OpenpilotPrefix { -public: - OpenpilotPrefix(std::string prefix = {}) { - if (prefix.empty()) { - prefix = util::random_string(15); - } - msgq_path = "/dev/shm/" + prefix; - bool ret = util::create_directories(msgq_path, 0777); - assert(ret); - setenv("OPENPILOT_PREFIX", prefix.c_str(), 1); - } - - ~OpenpilotPrefix() { - auto param_path = Params().getParamPath(); - if (util::file_exists(param_path)) { - std::string real_path = util::readlink(param_path); - system(util::string_format("rm %s -rf", real_path.c_str()).c_str()); - unlink(param_path.c_str()); - } - system(util::string_format("rm %s -rf", msgq_path.c_str()).c_str()); - unsetenv("OPENPILOT_PREFIX"); - } - -private: - std::string msgq_path; -}; diff --git a/common/queue.h b/common/queue.h deleted file mode 100644 index b3558b1..0000000 --- a/common/queue.h +++ /dev/null @@ -1,52 +0,0 @@ -#pragma once - -#include -#include -#include - -template -class SafeQueue { -public: - SafeQueue() = default; - - void push(const T& v) { - { - std::unique_lock lk(m); - q.push(v); - } - cv.notify_one(); - } - - T pop() { - std::unique_lock lk(m); - cv.wait(lk, [this] { return !q.empty(); }); - T v = q.front(); - q.pop(); - return v; - } - - bool try_pop(T& v, int timeout_ms = 0) { - std::unique_lock lk(m); - if (!cv.wait_for(lk, std::chrono::milliseconds(timeout_ms), [this] { return !q.empty(); })) { - return false; - } - v = q.front(); - q.pop(); - return true; - } - - bool empty() const { - std::scoped_lock lk(m); - return q.empty(); - } - - size_t size() const { - std::scoped_lock lk(m); - return q.size(); - } - -private: - mutable std::mutex m; - std::condition_variable cv; - std::queue q; -}; diff --git a/common/ratekeeper.cc b/common/ratekeeper.cc deleted file mode 100644 index 7e63815..0000000 --- a/common/ratekeeper.cc +++ /dev/null @@ -1,40 +0,0 @@ -#include "common/ratekeeper.h" - -#include - -#include "common/swaglog.h" -#include "common/timing.h" -#include "common/util.h" - -RateKeeper::RateKeeper(const std::string &name, float rate, float print_delay_threshold) - : name(name), - print_delay_threshold(std::max(0.f, print_delay_threshold)) { - interval = 1 / rate; - last_monitor_time = seconds_since_boot(); - next_frame_time = last_monitor_time + interval; -} - -bool RateKeeper::keepTime() { - bool lagged = monitorTime(); - if (remaining_ > 0) { - util::sleep_for(remaining_ * 1000); - } - return lagged; -} - -bool RateKeeper::monitorTime() { - ++frame_; - last_monitor_time = seconds_since_boot(); - remaining_ = next_frame_time - last_monitor_time; - - bool lagged = remaining_ < 0; - if (lagged) { - if (print_delay_threshold > 0 && remaining_ < -print_delay_threshold) { - LOGW("%s lagging by %.2f ms", name.c_str(), -remaining_ * 1000); - } - next_frame_time = last_monitor_time + interval; - } else { - next_frame_time += interval; - } - return lagged; -} diff --git a/common/ratekeeper.h b/common/ratekeeper.h deleted file mode 100644 index b6e8ac6..0000000 --- a/common/ratekeeper.h +++ /dev/null @@ -1,23 +0,0 @@ -#pragma once - -#include -#include - -class RateKeeper { -public: - RateKeeper(const std::string &name, float rate, float print_delay_threshold = 0); - ~RateKeeper() {} - bool keepTime(); - bool monitorTime(); - inline double frame() const { return frame_; } - inline double remaining() const { return remaining_; } - -private: - double interval; - double next_frame_time; - double last_monitor_time; - double remaining_ = 0; - float print_delay_threshold = 0; - uint64_t frame_ = 0; - std::string name; -}; diff --git a/common/swaglog.cc b/common/swaglog.cc deleted file mode 100644 index 7864a63..0000000 --- a/common/swaglog.cc +++ /dev/null @@ -1,152 +0,0 @@ -#ifndef _GNU_SOURCE -#define _GNU_SOURCE -#endif - -#include "common/swaglog.h" - -#include -#include -#include -#include - -#include -#include -#include "third_party/json11/json11.hpp" -#include "common/version.h" -#include "system/hardware/hw.h" - -class SwaglogState { -public: - SwaglogState() { - zctx = zmq_ctx_new(); - sock = zmq_socket(zctx, ZMQ_PUSH); - - // Timeout on shutdown for messages to be received by the logging process - int timeout = 100; - zmq_setsockopt(sock, ZMQ_LINGER, &timeout, sizeof(timeout)); - zmq_connect(sock, Path::swaglog_ipc().c_str()); - - print_level = CLOUDLOG_WARNING; - if (const char* print_lvl = getenv("LOGPRINT")) { - if (strcmp(print_lvl, "debug") == 0) { - print_level = CLOUDLOG_DEBUG; - } else if (strcmp(print_lvl, "info") == 0) { - print_level = CLOUDLOG_INFO; - } else if (strcmp(print_lvl, "warning") == 0) { - print_level = CLOUDLOG_WARNING; - } - } - - ctx_j = json11::Json::object{}; - if (char* dongle_id = getenv("DONGLE_ID")) { - ctx_j["dongle_id"] = dongle_id; - } - if (char* git_origin = getenv("GIT_ORIGIN")) { - ctx_j["origin"] = git_origin; - } - if (char* git_branch = getenv("GIT_BRANCH")) { - ctx_j["branch"] = git_branch; - } - if (char* git_commit = getenv("GIT_COMMIT")) { - ctx_j["commit"] = git_commit; - } - if (char* daemon_name = getenv("MANAGER_DAEMON")) { - ctx_j["daemon"] = daemon_name; - } - ctx_j["version"] = COMMA_VERSION; - ctx_j["dirty"] = !getenv("CLEAN"); - ctx_j["device"] = Hardware::get_name(); - } - - ~SwaglogState() { - zmq_close(sock); - zmq_ctx_destroy(zctx); - } - - void log(int levelnum, const char* filename, int lineno, const char* func, const char* msg, const std::string& log_s) { - std::lock_guard lk(lock); - if (levelnum >= print_level) { - printf("%s: %s\n", filename, msg); - } - zmq_send(sock, log_s.data(), log_s.length(), ZMQ_NOBLOCK); - } - - std::mutex lock; - void* zctx = nullptr; - void* sock = nullptr; - int print_level; - json11::Json::object ctx_j; -}; - -bool LOG_TIMESTAMPS = getenv("LOG_TIMESTAMPS"); -uint32_t NO_FRAME_ID = std::numeric_limits::max(); - -static void cloudlog_common(int levelnum, const char* filename, int lineno, const char* func, - char* msg_buf, const json11::Json::object &msg_j={}) { - static SwaglogState s; - - json11::Json::object log_j = json11::Json::object { - {"ctx", s.ctx_j}, - {"levelnum", levelnum}, - {"filename", filename}, - {"lineno", lineno}, - {"funcname", func}, - {"created", seconds_since_epoch()} - }; - if (msg_j.empty()) { - log_j["msg"] = msg_buf; - } else { - log_j["msg"] = msg_j; - } - - std::string log_s; - log_s += (char)levelnum; - ((json11::Json)log_j).dump(log_s); - s.log(levelnum, filename, lineno, func, msg_buf, log_s); - - free(msg_buf); -} - -void cloudlog_e(int levelnum, const char* filename, int lineno, const char* func, - const char* fmt, ...) { - va_list args; - va_start(args, fmt); - char* msg_buf = nullptr; - int ret = vasprintf(&msg_buf, fmt, args); - va_end(args); - if (ret <= 0 || !msg_buf) return; - cloudlog_common(levelnum, filename, lineno, func, msg_buf); -} - -void cloudlog_t_common(int levelnum, const char* filename, int lineno, const char* func, - uint32_t frame_id, const char* fmt, va_list args) { - if (!LOG_TIMESTAMPS) return; - char* msg_buf = nullptr; - int ret = vasprintf(&msg_buf, fmt, args); - if (ret <= 0 || !msg_buf) return; - json11::Json::object tspt_j = json11::Json::object{ - {"event", msg_buf}, - {"time", std::to_string(nanos_since_boot())} - }; - if (frame_id < NO_FRAME_ID) { - tspt_j["frame_id"] = std::to_string(frame_id); - } - tspt_j = json11::Json::object{{"timestamp", tspt_j}}; - cloudlog_common(levelnum, filename, lineno, func, msg_buf, tspt_j); -} - - -void cloudlog_te(int levelnum, const char* filename, int lineno, const char* func, - const char* fmt, ...) { - va_list args; - va_start(args, fmt); - cloudlog_t_common(levelnum, filename, lineno, func, NO_FRAME_ID, fmt, args); - va_end(args); -} -void cloudlog_te(int levelnum, const char* filename, int lineno, const char* func, - uint32_t frame_id, const char* fmt, ...) { - va_list args; - va_start(args, fmt); - cloudlog_t_common(levelnum, filename, lineno, func, frame_id, fmt, args); - va_end(args); -} diff --git a/common/swaglog.h b/common/swaglog.h deleted file mode 100644 index 06d45b1..0000000 --- a/common/swaglog.h +++ /dev/null @@ -1,76 +0,0 @@ -#pragma once - -#include "common/timing.h" - -#define CLOUDLOG_DEBUG 10 -#define CLOUDLOG_INFO 20 -#define CLOUDLOG_WARNING 30 -#define CLOUDLOG_ERROR 40 -#define CLOUDLOG_CRITICAL 50 - - -#ifdef __GNUC__ -#define SWAG_LOG_CHECK_FMT(a, b) __attribute__ ((format (printf, a, b))) -#else -#define SWAG_LOG_CHECK_FMT(a, b) -#endif - -void cloudlog_e(int levelnum, const char* filename, int lineno, const char* func, - const char* fmt, ...) SWAG_LOG_CHECK_FMT(5, 6); - -void cloudlog_te(int levelnum, const char* filename, int lineno, const char* func, - const char* fmt, ...) SWAG_LOG_CHECK_FMT(5, 6); - -void cloudlog_te(int levelnum, const char* filename, int lineno, const char* func, - uint32_t frame_id, const char* fmt, ...) SWAG_LOG_CHECK_FMT(6, 7); - - -#define cloudlog(lvl, fmt, ...) cloudlog_e(lvl, __FILE__, __LINE__, \ - __func__, \ - fmt, ## __VA_ARGS__) - -#define cloudlog_t(lvl, ...) cloudlog_te(lvl, __FILE__, __LINE__, \ - __func__, \ - __VA_ARGS__) - - -#define cloudlog_rl(burst, millis, lvl, fmt, ...) \ -{ \ - static uint64_t __begin = 0; \ - static int __printed = 0; \ - static int __missed = 0; \ - \ - int __burst = (burst); \ - int __millis = (millis); \ - uint64_t __ts = nanos_since_boot(); \ - \ - if (!__begin) { __begin = __ts; } \ - \ - if (__begin + __millis*1000000ULL < __ts) { \ - if (__missed) { \ - cloudlog(CLOUDLOG_WARNING, "cloudlog: %d messages suppressed", __missed); \ - } \ - __begin = 0; \ - __printed = 0; \ - __missed = 0; \ - } \ - \ - if (__printed < __burst) { \ - cloudlog(lvl, fmt, ## __VA_ARGS__); \ - __printed++; \ - } else { \ - __missed++; \ - } \ -} - - -#define LOGT(...) cloudlog_t(CLOUDLOG_DEBUG, __VA_ARGS__) -#define LOGD(fmt, ...) cloudlog(CLOUDLOG_DEBUG, fmt, ## __VA_ARGS__) -#define LOG(fmt, ...) cloudlog(CLOUDLOG_INFO, fmt, ## __VA_ARGS__) -#define LOGW(fmt, ...) cloudlog(CLOUDLOG_WARNING, fmt, ## __VA_ARGS__) -#define LOGE(fmt, ...) cloudlog(CLOUDLOG_ERROR, fmt, ## __VA_ARGS__) - -#define LOGD_100(fmt, ...) cloudlog_rl(2, 100, CLOUDLOG_DEBUG, fmt, ## __VA_ARGS__) -#define LOG_100(fmt, ...) cloudlog_rl(2, 100, CLOUDLOG_INFO, fmt, ## __VA_ARGS__) -#define LOGW_100(fmt, ...) cloudlog_rl(2, 100, CLOUDLOG_WARNING, fmt, ## __VA_ARGS__) -#define LOGE_100(fmt, ...) cloudlog_rl(2, 100, CLOUDLOG_ERROR, fmt, ## __VA_ARGS__) diff --git a/common/timing.h b/common/timing.h deleted file mode 100644 index 83f55e0..0000000 --- a/common/timing.h +++ /dev/null @@ -1,51 +0,0 @@ -#pragma once - -#include -#include - -#ifdef __APPLE__ -#define CLOCK_BOOTTIME CLOCK_MONOTONIC -#endif - -static inline uint64_t nanos_since_boot() { - struct timespec t; - clock_gettime(CLOCK_BOOTTIME, &t); - return t.tv_sec * 1000000000ULL + t.tv_nsec; -} - -static inline double millis_since_boot() { - struct timespec t; - clock_gettime(CLOCK_BOOTTIME, &t); - return t.tv_sec * 1000.0 + t.tv_nsec * 1e-6; -} - -static inline double seconds_since_boot() { - struct timespec t; - clock_gettime(CLOCK_BOOTTIME, &t); - return (double)t.tv_sec + t.tv_nsec * 1e-9; -} - -static inline uint64_t nanos_since_epoch() { - struct timespec t; - clock_gettime(CLOCK_REALTIME, &t); - return t.tv_sec * 1000000000ULL + t.tv_nsec; -} - -static inline double seconds_since_epoch() { - struct timespec t; - clock_gettime(CLOCK_REALTIME, &t); - return (double)t.tv_sec + t.tv_nsec * 1e-9; -} - -// you probably should use nanos_since_boot instead -static inline uint64_t nanos_monotonic() { - struct timespec t; - clock_gettime(CLOCK_MONOTONIC, &t); - return t.tv_sec * 1000000000ULL + t.tv_nsec; -} - -static inline uint64_t nanos_monotonic_raw() { - struct timespec t; - clock_gettime(CLOCK_MONOTONIC_RAW, &t); - return t.tv_sec * 1000000000ULL + t.tv_nsec; -} diff --git a/common/transformations/SConscript b/common/transformations/SConscript deleted file mode 100644 index 4ac73a1..0000000 --- a/common/transformations/SConscript +++ /dev/null @@ -1,5 +0,0 @@ -Import('env', 'envCython') - -transformations = env.Library('transformations', ['orientation.cc', 'coordinates.cc']) -transformations_python = envCython.Program('transformations.so', 'transformations.pyx') -Export('transformations', 'transformations_python') diff --git a/common/transformations/coordinates.cc b/common/transformations/coordinates.cc deleted file mode 100644 index 5b00b53..0000000 --- a/common/transformations/coordinates.cc +++ /dev/null @@ -1,100 +0,0 @@ -#define _USE_MATH_DEFINES - -#include "common/transformations/coordinates.hpp" - -#include -#include -#include - -double a = 6378137; // lgtm [cpp/short-global-name] -double b = 6356752.3142; // lgtm [cpp/short-global-name] -double esq = 6.69437999014 * 0.001; // lgtm [cpp/short-global-name] -double e1sq = 6.73949674228 * 0.001; - - -static Geodetic to_degrees(Geodetic geodetic){ - geodetic.lat = RAD2DEG(geodetic.lat); - geodetic.lon = RAD2DEG(geodetic.lon); - return geodetic; -} - -static Geodetic to_radians(Geodetic geodetic){ - geodetic.lat = DEG2RAD(geodetic.lat); - geodetic.lon = DEG2RAD(geodetic.lon); - return geodetic; -} - - -ECEF geodetic2ecef(Geodetic g){ - g = to_radians(g); - double xi = sqrt(1.0 - esq * pow(sin(g.lat), 2)); - double x = (a / xi + g.alt) * cos(g.lat) * cos(g.lon); - double y = (a / xi + g.alt) * cos(g.lat) * sin(g.lon); - double z = (a / xi * (1.0 - esq) + g.alt) * sin(g.lat); - return {x, y, z}; -} - -Geodetic ecef2geodetic(ECEF e){ - // Convert from ECEF to geodetic using Ferrari's methods - // https://en.wikipedia.org/wiki/Geographic_coordinate_conversion#Ferrari.27s_solution - double x = e.x; - double y = e.y; - double z = e.z; - - double r = sqrt(x * x + y * y); - double Esq = a * a - b * b; - double F = 54 * b * b * z * z; - double G = r * r + (1 - esq) * z * z - esq * Esq; - double C = (esq * esq * F * r * r) / (pow(G, 3)); - double S = cbrt(1 + C + sqrt(C * C + 2 * C)); - double P = F / (3 * pow((S + 1 / S + 1), 2) * G * G); - double Q = sqrt(1 + 2 * esq * esq * P); - double r_0 = -(P * esq * r) / (1 + Q) + sqrt(0.5 * a * a*(1 + 1.0 / Q) - P * (1 - esq) * z * z / (Q * (1 + Q)) - 0.5 * P * r * r); - double U = sqrt(pow((r - esq * r_0), 2) + z * z); - double V = sqrt(pow((r - esq * r_0), 2) + (1 - esq) * z * z); - double Z_0 = b * b * z / (a * V); - double h = U * (1 - b * b / (a * V)); - - double lat = atan((z + e1sq * Z_0) / r); - double lon = atan2(y, x); - - return to_degrees({lat, lon, h}); -} - -LocalCoord::LocalCoord(Geodetic g, ECEF e){ - init_ecef << e.x, e.y, e.z; - - g = to_radians(g); - - ned2ecef_matrix << - -sin(g.lat)*cos(g.lon), -sin(g.lon), -cos(g.lat)*cos(g.lon), - -sin(g.lat)*sin(g.lon), cos(g.lon), -cos(g.lat)*sin(g.lon), - cos(g.lat), 0, -sin(g.lat); - ecef2ned_matrix = ned2ecef_matrix.transpose(); -} - -NED LocalCoord::ecef2ned(ECEF e) { - Eigen::Vector3d ecef; - ecef << e.x, e.y, e.z; - - Eigen::Vector3d ned = (ecef2ned_matrix * (ecef - init_ecef)); - return {ned[0], ned[1], ned[2]}; -} - -ECEF LocalCoord::ned2ecef(NED n) { - Eigen::Vector3d ned; - ned << n.n, n.e, n.d; - - Eigen::Vector3d ecef = (ned2ecef_matrix * ned) + init_ecef; - return {ecef[0], ecef[1], ecef[2]}; -} - -NED LocalCoord::geodetic2ned(Geodetic g) { - ECEF e = ::geodetic2ecef(g); - return ecef2ned(e); -} - -Geodetic LocalCoord::ned2geodetic(NED n){ - ECEF e = ned2ecef(n); - return ::ecef2geodetic(e); -} diff --git a/common/transformations/orientation.cc b/common/transformations/orientation.cc deleted file mode 100644 index 00888c3..0000000 --- a/common/transformations/orientation.cc +++ /dev/null @@ -1,144 +0,0 @@ -#define _USE_MATH_DEFINES - -#include -#include -#include - -#include "common/transformations/orientation.hpp" -#include "common/transformations/coordinates.hpp" - -Eigen::Quaterniond ensure_unique(Eigen::Quaterniond quat){ - if (quat.w() > 0){ - return quat; - } else { - return Eigen::Quaterniond(-quat.w(), -quat.x(), -quat.y(), -quat.z()); - } -} - -Eigen::Quaterniond euler2quat(Eigen::Vector3d euler){ - Eigen::Quaterniond q; - - q = Eigen::AngleAxisd(euler(2), Eigen::Vector3d::UnitZ()) - * Eigen::AngleAxisd(euler(1), Eigen::Vector3d::UnitY()) - * Eigen::AngleAxisd(euler(0), Eigen::Vector3d::UnitX()); - return ensure_unique(q); -} - - -Eigen::Vector3d quat2euler(Eigen::Quaterniond quat){ - // TODO: switch to eigen implementation if the range of the Euler angles doesn't matter anymore - // Eigen::Vector3d euler = quat.toRotationMatrix().eulerAngles(2, 1, 0); - // return {euler(2), euler(1), euler(0)}; - double gamma = atan2(2 * (quat.w() * quat.x() + quat.y() * quat.z()), 1 - 2 * (quat.x()*quat.x() + quat.y()*quat.y())); - double asin_arg_clipped = std::clamp(2 * (quat.w() * quat.y() - quat.z() * quat.x()), -1.0, 1.0); - double theta = asin(asin_arg_clipped); - double psi = atan2(2 * (quat.w() * quat.z() + quat.x() * quat.y()), 1 - 2 * (quat.y()*quat.y() + quat.z()*quat.z())); - return {gamma, theta, psi}; -} - -Eigen::Matrix3d quat2rot(Eigen::Quaterniond quat){ - return quat.toRotationMatrix(); -} - -Eigen::Quaterniond rot2quat(const Eigen::Matrix3d &rot){ - return ensure_unique(Eigen::Quaterniond(rot)); -} - -Eigen::Matrix3d euler2rot(Eigen::Vector3d euler){ - return quat2rot(euler2quat(euler)); -} - -Eigen::Vector3d rot2euler(const Eigen::Matrix3d &rot){ - return quat2euler(rot2quat(rot)); -} - -Eigen::Matrix3d rot_matrix(double roll, double pitch, double yaw){ - return euler2rot({roll, pitch, yaw}); -} - -Eigen::Matrix3d rot(Eigen::Vector3d axis, double angle){ - Eigen::Quaterniond q; - q = Eigen::AngleAxisd(angle, axis); - return q.toRotationMatrix(); -} - - -Eigen::Vector3d ecef_euler_from_ned(ECEF ecef_init, Eigen::Vector3d ned_pose) { - /* - Using Rotations to Build Aerospace Coordinate Systems - Don Koks - https://apps.dtic.mil/dtic/tr/fulltext/u2/a484864.pdf - */ - LocalCoord converter = LocalCoord(ecef_init); - Eigen::Vector3d zero = ecef_init.to_vector(); - - Eigen::Vector3d x0 = converter.ned2ecef({1, 0, 0}).to_vector() - zero; - Eigen::Vector3d y0 = converter.ned2ecef({0, 1, 0}).to_vector() - zero; - Eigen::Vector3d z0 = converter.ned2ecef({0, 0, 1}).to_vector() - zero; - - Eigen::Vector3d x1 = rot(z0, ned_pose(2)) * x0; - Eigen::Vector3d y1 = rot(z0, ned_pose(2)) * y0; - Eigen::Vector3d z1 = rot(z0, ned_pose(2)) * z0; - - Eigen::Vector3d x2 = rot(y1, ned_pose(1)) * x1; - Eigen::Vector3d y2 = rot(y1, ned_pose(1)) * y1; - Eigen::Vector3d z2 = rot(y1, ned_pose(1)) * z1; - - Eigen::Vector3d x3 = rot(x2, ned_pose(0)) * x2; - Eigen::Vector3d y3 = rot(x2, ned_pose(0)) * y2; - - - x0 = Eigen::Vector3d(1, 0, 0); - y0 = Eigen::Vector3d(0, 1, 0); - z0 = Eigen::Vector3d(0, 0, 1); - - double psi = atan2(x3.dot(y0), x3.dot(x0)); - double theta = atan2(-x3.dot(z0), sqrt(pow(x3.dot(x0), 2) + pow(x3.dot(y0), 2))); - - y2 = rot(z0, psi) * y0; - z2 = rot(y2, theta) * z0; - - double phi = atan2(y3.dot(z2), y3.dot(y2)); - - return {phi, theta, psi}; -} - -Eigen::Vector3d ned_euler_from_ecef(ECEF ecef_init, Eigen::Vector3d ecef_pose){ - /* - Using Rotations to Build Aerospace Coordinate Systems - Don Koks - https://apps.dtic.mil/dtic/tr/fulltext/u2/a484864.pdf - */ - LocalCoord converter = LocalCoord(ecef_init); - - Eigen::Vector3d x0 = Eigen::Vector3d(1, 0, 0); - Eigen::Vector3d y0 = Eigen::Vector3d(0, 1, 0); - Eigen::Vector3d z0 = Eigen::Vector3d(0, 0, 1); - - Eigen::Vector3d x1 = rot(z0, ecef_pose(2)) * x0; - Eigen::Vector3d y1 = rot(z0, ecef_pose(2)) * y0; - Eigen::Vector3d z1 = rot(z0, ecef_pose(2)) * z0; - - Eigen::Vector3d x2 = rot(y1, ecef_pose(1)) * x1; - Eigen::Vector3d y2 = rot(y1, ecef_pose(1)) * y1; - Eigen::Vector3d z2 = rot(y1, ecef_pose(1)) * z1; - - Eigen::Vector3d x3 = rot(x2, ecef_pose(0)) * x2; - Eigen::Vector3d y3 = rot(x2, ecef_pose(0)) * y2; - - Eigen::Vector3d zero = ecef_init.to_vector(); - x0 = converter.ned2ecef({1, 0, 0}).to_vector() - zero; - y0 = converter.ned2ecef({0, 1, 0}).to_vector() - zero; - z0 = converter.ned2ecef({0, 0, 1}).to_vector() - zero; - - double psi = atan2(x3.dot(y0), x3.dot(x0)); - double theta = atan2(-x3.dot(z0), sqrt(pow(x3.dot(x0), 2) + pow(x3.dot(y0), 2))); - - y2 = rot(z0, psi) * y0; - z2 = rot(y2, theta) * z0; - - double phi = atan2(y3.dot(z2), y3.dot(y2)); - - return {phi, theta, psi}; -} - diff --git a/common/transformations/transformations.cpp b/common/transformations/transformations.cpp new file mode 100644 index 0000000..0eea8b0 --- /dev/null +++ b/common/transformations/transformations.cpp @@ -0,0 +1,16660 @@ +/* Generated by Cython 3.0.8 */ + +/* BEGIN: Cython Metadata +{ + "distutils": { + "depends": [ + "common/transformations/coordinates.cc", + "common/transformations/coordinates.hpp", + "common/transformations/orientation.cc", + "common/transformations/orientation.hpp", + "openpilot/common/transformations/coordinates.cc", + "openpilot/common/transformations/coordinates.hpp", + "openpilot/common/transformations/orientation.cc", + "openpilot/common/transformations/orientation.hpp" + ], + "include_dirs": [ + "common/transformations", + "openpilot/common/transformations" + ], + "language": "c++", + "name": "common.transformations.transformations", + "sources": [ + "/data/openpilot/common/transformations/transformations.pyx" + ] + }, + "module_name": "common.transformations.transformations" +} +END: Cython Metadata */ + +#ifndef PY_SSIZE_T_CLEAN +#define PY_SSIZE_T_CLEAN +#endif /* PY_SSIZE_T_CLEAN */ +#if defined(CYTHON_LIMITED_API) && 0 + #ifndef Py_LIMITED_API + #if CYTHON_LIMITED_API+0 > 0x03030000 + #define Py_LIMITED_API CYTHON_LIMITED_API + #else + #define Py_LIMITED_API 0x03030000 + #endif + #endif +#endif + +#include "Python.h" +#ifndef Py_PYTHON_H + #error Python headers needed to compile C extensions, please install development version of Python. +#elif PY_VERSION_HEX < 0x02070000 || (0x03000000 <= PY_VERSION_HEX && PY_VERSION_HEX < 0x03030000) + #error Cython requires Python 2.7+ or Python 3.3+. +#else +#if defined(CYTHON_LIMITED_API) && CYTHON_LIMITED_API +#define __PYX_EXTRA_ABI_MODULE_NAME "limited" +#else +#define __PYX_EXTRA_ABI_MODULE_NAME "" +#endif +#define CYTHON_ABI "3_0_8" __PYX_EXTRA_ABI_MODULE_NAME +#define __PYX_ABI_MODULE_NAME "_cython_" CYTHON_ABI +#define __PYX_TYPE_MODULE_PREFIX __PYX_ABI_MODULE_NAME "." +#define CYTHON_HEX_VERSION 0x030008F0 +#define CYTHON_FUTURE_DIVISION 1 +#include +#ifndef offsetof + #define offsetof(type, member) ( (size_t) & ((type*)0) -> member ) +#endif +#if !defined(_WIN32) && !defined(WIN32) && !defined(MS_WINDOWS) + #ifndef __stdcall + #define __stdcall + #endif + #ifndef __cdecl + #define __cdecl + #endif + #ifndef __fastcall + #define __fastcall + #endif +#endif +#ifndef DL_IMPORT + #define DL_IMPORT(t) t +#endif +#ifndef DL_EXPORT + #define DL_EXPORT(t) t +#endif +#define __PYX_COMMA , +#ifndef HAVE_LONG_LONG + #define HAVE_LONG_LONG +#endif +#ifndef PY_LONG_LONG + #define PY_LONG_LONG LONG_LONG +#endif +#ifndef Py_HUGE_VAL + #define Py_HUGE_VAL HUGE_VAL +#endif +#define __PYX_LIMITED_VERSION_HEX PY_VERSION_HEX +#if defined(GRAALVM_PYTHON) + /* For very preliminary testing purposes. Most variables are set the same as PyPy. + The existence of this section does not imply that anything works or is even tested */ + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 1 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(PYPY_VERSION) + #define CYTHON_COMPILING_IN_PYPY 1 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #ifndef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #endif + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #if PY_VERSION_HEX < 0x03090000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE (PY_VERSION_HEX >= 0x030400a1 && PYPY_VERSION_NUM >= 0x07030C00) + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(CYTHON_LIMITED_API) + #ifdef Py_LIMITED_API + #undef __PYX_LIMITED_VERSION_HEX + #define __PYX_LIMITED_VERSION_HEX Py_LIMITED_API + #endif + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 1 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_CLINE_IN_TRACEBACK + #define CYTHON_CLINE_IN_TRACEBACK 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 1 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #endif + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 1 + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(Py_GIL_DISABLED) || defined(Py_NOGIL) + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 1 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #ifndef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 +#else + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 1 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #ifndef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #endif + #ifndef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 1 + #endif + #if PY_MAJOR_VERSION < 3 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #ifndef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 1 + #endif + #ifndef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 1 + #endif + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #if PY_VERSION_HEX < 0x030300F0 || PY_VERSION_HEX >= 0x030B00A2 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #elif !defined(CYTHON_USE_UNICODE_WRITER) + #define CYTHON_USE_UNICODE_WRITER 1 + #endif + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #ifndef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 1 + #endif + #ifndef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL (PY_MAJOR_VERSION < 3 || PY_VERSION_HEX >= 0x03060000 && PY_VERSION_HEX < 0x030C00A6) + #endif + #ifndef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL (PY_VERSION_HEX >= 0x030700A1) + #endif + #ifndef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 1 + #endif + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #endif + #if PY_VERSION_HEX < 0x030400a1 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #elif !defined(CYTHON_USE_TP_FINALIZE) + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #if PY_VERSION_HEX < 0x030600B1 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #elif !defined(CYTHON_USE_DICT_VERSIONS) + #define CYTHON_USE_DICT_VERSIONS (PY_VERSION_HEX < 0x030C00A5) + #endif + #if PY_VERSION_HEX < 0x030700A3 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #elif !defined(CYTHON_USE_EXC_INFO_STACK) + #define CYTHON_USE_EXC_INFO_STACK 1 + #endif + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 1 + #endif +#endif +#if !defined(CYTHON_FAST_PYCCALL) +#define CYTHON_FAST_PYCCALL (CYTHON_FAST_PYCALL && PY_VERSION_HEX >= 0x030600B1) +#endif +#if !defined(CYTHON_VECTORCALL) +#define CYTHON_VECTORCALL (CYTHON_FAST_PYCCALL && PY_VERSION_HEX >= 0x030800B1) +#endif +#define CYTHON_BACKPORT_VECTORCALL (CYTHON_METH_FASTCALL && PY_VERSION_HEX < 0x030800B1) +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_MAJOR_VERSION < 3 + #include "longintrepr.h" + #endif + #undef SHIFT + #undef BASE + #undef MASK + #ifdef SIZEOF_VOID_P + enum { __pyx_check_sizeof_voidp = 1 / (int)(SIZEOF_VOID_P == sizeof(void*)) }; + #endif +#endif +#ifndef __has_attribute + #define __has_attribute(x) 0 +#endif +#ifndef __has_cpp_attribute + #define __has_cpp_attribute(x) 0 +#endif +#ifndef CYTHON_RESTRICT + #if defined(__GNUC__) + #define CYTHON_RESTRICT __restrict__ + #elif defined(_MSC_VER) && _MSC_VER >= 1400 + #define CYTHON_RESTRICT __restrict + #elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define CYTHON_RESTRICT restrict + #else + #define CYTHON_RESTRICT + #endif +#endif +#ifndef CYTHON_UNUSED + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(maybe_unused) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(maybe_unused) + #define CYTHON_UNUSED [[maybe_unused]] + #endif + #endif + #endif +#endif +#ifndef CYTHON_UNUSED +# if defined(__GNUC__) +# if !(defined(__cplusplus)) || (__GNUC__ > 3 || (__GNUC__ == 3 && __GNUC_MINOR__ >= 4)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +# elif defined(__ICC) || (defined(__INTEL_COMPILER) && !defined(_MSC_VER)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +#endif +#ifndef CYTHON_UNUSED_VAR +# if defined(__cplusplus) + template void CYTHON_UNUSED_VAR( const T& ) { } +# else +# define CYTHON_UNUSED_VAR(x) (void)(x) +# endif +#endif +#ifndef CYTHON_MAYBE_UNUSED_VAR + #define CYTHON_MAYBE_UNUSED_VAR(x) CYTHON_UNUSED_VAR(x) +#endif +#ifndef CYTHON_NCP_UNUSED +# if CYTHON_COMPILING_IN_CPYTHON +# define CYTHON_NCP_UNUSED +# else +# define CYTHON_NCP_UNUSED CYTHON_UNUSED +# endif +#endif +#ifndef CYTHON_USE_CPP_STD_MOVE + #if defined(__cplusplus) && (\ + __cplusplus >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1600)) + #define CYTHON_USE_CPP_STD_MOVE 1 + #else + #define CYTHON_USE_CPP_STD_MOVE 0 + #endif +#endif +#define __Pyx_void_to_None(void_result) ((void)(void_result), Py_INCREF(Py_None), Py_None) +#ifdef _MSC_VER + #ifndef _MSC_STDINT_H_ + #if _MSC_VER < 1300 + typedef unsigned char uint8_t; + typedef unsigned short uint16_t; + typedef unsigned int uint32_t; + #else + typedef unsigned __int8 uint8_t; + typedef unsigned __int16 uint16_t; + typedef unsigned __int32 uint32_t; + #endif + #endif + #if _MSC_VER < 1300 + #ifdef _WIN64 + typedef unsigned long long __pyx_uintptr_t; + #else + typedef unsigned int __pyx_uintptr_t; + #endif + #else + #ifdef _WIN64 + typedef unsigned __int64 __pyx_uintptr_t; + #else + typedef unsigned __int32 __pyx_uintptr_t; + #endif + #endif +#else + #include + typedef uintptr_t __pyx_uintptr_t; +#endif +#ifndef CYTHON_FALLTHROUGH + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(fallthrough) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(fallthrough) + #define CYTHON_FALLTHROUGH [[fallthrough]] + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_cpp_attribute(clang::fallthrough) + #define CYTHON_FALLTHROUGH [[clang::fallthrough]] + #elif __has_cpp_attribute(gnu::fallthrough) + #define CYTHON_FALLTHROUGH [[gnu::fallthrough]] + #endif + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_attribute(fallthrough) + #define CYTHON_FALLTHROUGH __attribute__((fallthrough)) + #else + #define CYTHON_FALLTHROUGH + #endif + #endif + #if defined(__clang__) && defined(__apple_build_version__) + #if __apple_build_version__ < 7000000 + #undef CYTHON_FALLTHROUGH + #define CYTHON_FALLTHROUGH + #endif + #endif +#endif +#ifdef __cplusplus + template + struct __PYX_IS_UNSIGNED_IMPL {static const bool value = T(0) < T(-1);}; + #define __PYX_IS_UNSIGNED(type) (__PYX_IS_UNSIGNED_IMPL::value) +#else + #define __PYX_IS_UNSIGNED(type) (((type)-1) > 0) +#endif +#if CYTHON_COMPILING_IN_PYPY == 1 + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x030A0000) +#else + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x03090000) +#endif +#define __PYX_REINTERPRET_FUNCION(func_pointer, other_pointer) ((func_pointer)(void(*)(void))(other_pointer)) + +#ifndef __cplusplus + #error "Cython files generated with the C++ option must be compiled with a C++ compiler." +#endif +#ifndef CYTHON_INLINE + #if defined(__clang__) + #define CYTHON_INLINE __inline__ __attribute__ ((__unused__)) + #else + #define CYTHON_INLINE inline + #endif +#endif +template +void __Pyx_call_destructor(T& x) { + x.~T(); +} +template +class __Pyx_FakeReference { + public: + __Pyx_FakeReference() : ptr(NULL) { } + __Pyx_FakeReference(const T& ref) : ptr(const_cast(&ref)) { } + T *operator->() { return ptr; } + T *operator&() { return ptr; } + operator T&() { return *ptr; } + template bool operator ==(const U& other) const { return *ptr == other; } + template bool operator !=(const U& other) const { return *ptr != other; } + template bool operator==(const __Pyx_FakeReference& other) const { return *ptr == *other.ptr; } + template bool operator!=(const __Pyx_FakeReference& other) const { return *ptr != *other.ptr; } + private: + T *ptr; +}; + +#define __PYX_BUILD_PY_SSIZE_T "n" +#define CYTHON_FORMAT_SSIZE_T "z" +#if PY_MAJOR_VERSION < 3 + #define __Pyx_BUILTIN_MODULE_NAME "__builtin__" + #define __Pyx_DefaultClassType PyClass_Type + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a+k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_BUILTIN_MODULE_NAME "builtins" + #define __Pyx_DefaultClassType PyType_Type +#if CYTHON_COMPILING_IN_LIMITED_API + static CYTHON_INLINE PyObject* __Pyx_PyCode_New(int a, int p, int k, int l, int s, int f, + PyObject *code, PyObject *c, PyObject* n, PyObject *v, + PyObject *fv, PyObject *cell, PyObject* fn, + PyObject *name, int fline, PyObject *lnos) { + PyObject *exception_table = NULL; + PyObject *types_module=NULL, *code_type=NULL, *result=NULL; + #if __PYX_LIMITED_VERSION_HEX < 0x030B0000 + PyObject *version_info; + PyObject *py_minor_version = NULL; + #endif + long minor_version = 0; + PyObject *type, *value, *traceback; + PyErr_Fetch(&type, &value, &traceback); + #if __PYX_LIMITED_VERSION_HEX >= 0x030B0000 + minor_version = 11; + #else + if (!(version_info = PySys_GetObject("version_info"))) goto end; + if (!(py_minor_version = PySequence_GetItem(version_info, 1))) goto end; + minor_version = PyLong_AsLong(py_minor_version); + Py_DECREF(py_minor_version); + if (minor_version == -1 && PyErr_Occurred()) goto end; + #endif + if (!(types_module = PyImport_ImportModule("types"))) goto end; + if (!(code_type = PyObject_GetAttrString(types_module, "CodeType"))) goto end; + if (minor_version <= 7) { + (void)p; + result = PyObject_CallFunction(code_type, "iiiiiOOOOOOiOO", a, k, l, s, f, code, + c, n, v, fn, name, fline, lnos, fv, cell); + } else if (minor_version <= 10) { + result = PyObject_CallFunction(code_type, "iiiiiiOOOOOOiOO", a,p, k, l, s, f, code, + c, n, v, fn, name, fline, lnos, fv, cell); + } else { + if (!(exception_table = PyBytes_FromStringAndSize(NULL, 0))) goto end; + result = PyObject_CallFunction(code_type, "iiiiiiOOOOOOOiOO", a,p, k, l, s, f, code, + c, n, v, fn, name, name, fline, lnos, exception_table, fv, cell); + } + end: + Py_XDECREF(code_type); + Py_XDECREF(exception_table); + Py_XDECREF(types_module); + if (type) { + PyErr_Restore(type, value, traceback); + } + return result; + } + #ifndef CO_OPTIMIZED + #define CO_OPTIMIZED 0x0001 + #endif + #ifndef CO_NEWLOCALS + #define CO_NEWLOCALS 0x0002 + #endif + #ifndef CO_VARARGS + #define CO_VARARGS 0x0004 + #endif + #ifndef CO_VARKEYWORDS + #define CO_VARKEYWORDS 0x0008 + #endif + #ifndef CO_ASYNC_GENERATOR + #define CO_ASYNC_GENERATOR 0x0200 + #endif + #ifndef CO_GENERATOR + #define CO_GENERATOR 0x0020 + #endif + #ifndef CO_COROUTINE + #define CO_COROUTINE 0x0080 + #endif +#elif PY_VERSION_HEX >= 0x030B0000 + static CYTHON_INLINE PyCodeObject* __Pyx_PyCode_New(int a, int p, int k, int l, int s, int f, + PyObject *code, PyObject *c, PyObject* n, PyObject *v, + PyObject *fv, PyObject *cell, PyObject* fn, + PyObject *name, int fline, PyObject *lnos) { + PyCodeObject *result; + PyObject *empty_bytes = PyBytes_FromStringAndSize("", 0); + if (!empty_bytes) return NULL; + result = + #if PY_VERSION_HEX >= 0x030C0000 + PyUnstable_Code_NewWithPosOnlyArgs + #else + PyCode_NewWithPosOnlyArgs + #endif + (a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, name, fline, lnos, empty_bytes); + Py_DECREF(empty_bytes); + return result; + } +#elif PY_VERSION_HEX >= 0x030800B2 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_NewWithPosOnlyArgs(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#endif +#endif +#if PY_VERSION_HEX >= 0x030900A4 || defined(Py_IS_TYPE) + #define __Pyx_IS_TYPE(ob, type) Py_IS_TYPE(ob, type) +#else + #define __Pyx_IS_TYPE(ob, type) (((const PyObject*)ob)->ob_type == (type)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_Is) + #define __Pyx_Py_Is(x, y) Py_Is(x, y) +#else + #define __Pyx_Py_Is(x, y) ((x) == (y)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsNone) + #define __Pyx_Py_IsNone(ob) Py_IsNone(ob) +#else + #define __Pyx_Py_IsNone(ob) __Pyx_Py_Is((ob), Py_None) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsTrue) + #define __Pyx_Py_IsTrue(ob) Py_IsTrue(ob) +#else + #define __Pyx_Py_IsTrue(ob) __Pyx_Py_Is((ob), Py_True) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsFalse) + #define __Pyx_Py_IsFalse(ob) Py_IsFalse(ob) +#else + #define __Pyx_Py_IsFalse(ob) __Pyx_Py_Is((ob), Py_False) +#endif +#define __Pyx_NoneAsNull(obj) (__Pyx_Py_IsNone(obj) ? NULL : (obj)) +#if PY_VERSION_HEX >= 0x030900F0 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_GC_IsFinalized(o) PyObject_GC_IsFinalized(o) +#else + #define __Pyx_PyObject_GC_IsFinalized(o) _PyGC_FINALIZED(o) +#endif +#ifndef CO_COROUTINE + #define CO_COROUTINE 0x80 +#endif +#ifndef CO_ASYNC_GENERATOR + #define CO_ASYNC_GENERATOR 0x200 +#endif +#ifndef Py_TPFLAGS_CHECKTYPES + #define Py_TPFLAGS_CHECKTYPES 0 +#endif +#ifndef Py_TPFLAGS_HAVE_INDEX + #define Py_TPFLAGS_HAVE_INDEX 0 +#endif +#ifndef Py_TPFLAGS_HAVE_NEWBUFFER + #define Py_TPFLAGS_HAVE_NEWBUFFER 0 +#endif +#ifndef Py_TPFLAGS_HAVE_FINALIZE + #define Py_TPFLAGS_HAVE_FINALIZE 0 +#endif +#ifndef Py_TPFLAGS_SEQUENCE + #define Py_TPFLAGS_SEQUENCE 0 +#endif +#ifndef Py_TPFLAGS_MAPPING + #define Py_TPFLAGS_MAPPING 0 +#endif +#ifndef METH_STACKLESS + #define METH_STACKLESS 0 +#endif +#if PY_VERSION_HEX <= 0x030700A3 || !defined(METH_FASTCALL) + #ifndef METH_FASTCALL + #define METH_FASTCALL 0x80 + #endif + typedef PyObject *(*__Pyx_PyCFunctionFast) (PyObject *self, PyObject *const *args, Py_ssize_t nargs); + typedef PyObject *(*__Pyx_PyCFunctionFastWithKeywords) (PyObject *self, PyObject *const *args, + Py_ssize_t nargs, PyObject *kwnames); +#else + #define __Pyx_PyCFunctionFast _PyCFunctionFast + #define __Pyx_PyCFunctionFastWithKeywords _PyCFunctionFastWithKeywords +#endif +#if CYTHON_METH_FASTCALL + #define __Pyx_METH_FASTCALL METH_FASTCALL + #define __Pyx_PyCFunction_FastCall __Pyx_PyCFunctionFast + #define __Pyx_PyCFunction_FastCallWithKeywords __Pyx_PyCFunctionFastWithKeywords +#else + #define __Pyx_METH_FASTCALL METH_VARARGS + #define __Pyx_PyCFunction_FastCall PyCFunction + #define __Pyx_PyCFunction_FastCallWithKeywords PyCFunctionWithKeywords +#endif +#if CYTHON_VECTORCALL + #define __pyx_vectorcallfunc vectorcallfunc + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET PY_VECTORCALL_ARGUMENTS_OFFSET + #define __Pyx_PyVectorcall_NARGS(n) PyVectorcall_NARGS((size_t)(n)) +#elif CYTHON_BACKPORT_VECTORCALL + typedef PyObject *(*__pyx_vectorcallfunc)(PyObject *callable, PyObject *const *args, + size_t nargsf, PyObject *kwnames); + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET ((size_t)1 << (8 * sizeof(size_t) - 1)) + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(((size_t)(n)) & ~__Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET)) +#else + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET 0 + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(n)) +#endif +#if PY_MAJOR_VERSION >= 0x030900B1 +#define __Pyx_PyCFunction_CheckExact(func) PyCFunction_CheckExact(func) +#else +#define __Pyx_PyCFunction_CheckExact(func) PyCFunction_Check(func) +#endif +#define __Pyx_CyOrPyCFunction_Check(func) PyCFunction_Check(func) +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_CyOrPyCFunction_GET_FUNCTION(func) (((PyCFunctionObject*)(func))->m_ml->ml_meth) +#elif !CYTHON_COMPILING_IN_LIMITED_API +#define __Pyx_CyOrPyCFunction_GET_FUNCTION(func) PyCFunction_GET_FUNCTION(func) +#endif +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_CyOrPyCFunction_GET_FLAGS(func) (((PyCFunctionObject*)(func))->m_ml->ml_flags) +static CYTHON_INLINE PyObject* __Pyx_CyOrPyCFunction_GET_SELF(PyObject *func) { + return (__Pyx_CyOrPyCFunction_GET_FLAGS(func) & METH_STATIC) ? NULL : ((PyCFunctionObject*)func)->m_self; +} +#endif +static CYTHON_INLINE int __Pyx__IsSameCFunction(PyObject *func, void *cfunc) { +#if CYTHON_COMPILING_IN_LIMITED_API + return PyCFunction_Check(func) && PyCFunction_GetFunction(func) == (PyCFunction) cfunc; +#else + return PyCFunction_Check(func) && PyCFunction_GET_FUNCTION(func) == (PyCFunction) cfunc; +#endif +} +#define __Pyx_IsSameCFunction(func, cfunc) __Pyx__IsSameCFunction(func, cfunc) +#if __PYX_LIMITED_VERSION_HEX < 0x030900B1 + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) ((void)m, PyType_FromSpecWithBases(s, b)) + typedef PyObject *(*__Pyx_PyCMethod)(PyObject *, PyTypeObject *, PyObject *const *, size_t, PyObject *); +#else + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) PyType_FromModuleAndSpec(m, s, b) + #define __Pyx_PyCMethod PyCMethod +#endif +#ifndef METH_METHOD + #define METH_METHOD 0x200 +#endif +#if CYTHON_COMPILING_IN_PYPY && !defined(PyObject_Malloc) + #define PyObject_Malloc(s) PyMem_Malloc(s) + #define PyObject_Free(p) PyMem_Free(p) + #define PyObject_Realloc(p) PyMem_Realloc(p) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) +#else + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) (frame)->f_lineno = (lineno) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyThreadState_Current PyThreadState_Get() +#elif !CYTHON_FAST_THREAD_STATE + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#elif PY_VERSION_HEX >= 0x030d00A1 + #define __Pyx_PyThreadState_Current PyThreadState_GetUnchecked() +#elif PY_VERSION_HEX >= 0x03060000 + #define __Pyx_PyThreadState_Current _PyThreadState_UncheckedGet() +#elif PY_VERSION_HEX >= 0x03000000 + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#else + #define __Pyx_PyThreadState_Current _PyThreadState_Current +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE void *__Pyx_PyModule_GetState(PyObject *op) +{ + void *result; + result = PyModule_GetState(op); + if (!result) + Py_FatalError("Couldn't find the module state"); + return result; +} +#endif +#define __Pyx_PyObject_GetSlot(obj, name, func_ctype) __Pyx_PyType_GetSlot(Py_TYPE(obj), name, func_ctype) +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((func_ctype) PyType_GetSlot((type), Py_##name)) +#else + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((type)->name) +#endif +#if PY_VERSION_HEX < 0x030700A2 && !defined(PyThread_tss_create) && !defined(Py_tss_NEEDS_INIT) +#include "pythread.h" +#define Py_tss_NEEDS_INIT 0 +typedef int Py_tss_t; +static CYTHON_INLINE int PyThread_tss_create(Py_tss_t *key) { + *key = PyThread_create_key(); + return 0; +} +static CYTHON_INLINE Py_tss_t * PyThread_tss_alloc(void) { + Py_tss_t *key = (Py_tss_t *)PyObject_Malloc(sizeof(Py_tss_t)); + *key = Py_tss_NEEDS_INIT; + return key; +} +static CYTHON_INLINE void PyThread_tss_free(Py_tss_t *key) { + PyObject_Free(key); +} +static CYTHON_INLINE int PyThread_tss_is_created(Py_tss_t *key) { + return *key != Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE void PyThread_tss_delete(Py_tss_t *key) { + PyThread_delete_key(*key); + *key = Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE int PyThread_tss_set(Py_tss_t *key, void *value) { + return PyThread_set_key_value(*key, value); +} +static CYTHON_INLINE void * PyThread_tss_get(Py_tss_t *key) { + return PyThread_get_key_value(*key); +} +#endif +#if PY_MAJOR_VERSION < 3 + #if CYTHON_COMPILING_IN_PYPY + #if PYPY_VERSION_NUM < 0x07030600 + #if defined(__cplusplus) && __cplusplus >= 201402L + [[deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")]] + #elif defined(__GNUC__) || defined(__clang__) + __attribute__ ((__deprecated__("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6"))) + #elif defined(_MSC_VER) + __declspec(deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")) + #endif + static CYTHON_INLINE int PyGILState_Check(void) { + return 0; + } + #else // PYPY_VERSION_NUM < 0x07030600 + #endif // PYPY_VERSION_NUM < 0x07030600 + #else + static CYTHON_INLINE int PyGILState_Check(void) { + PyThreadState * tstate = _PyThreadState_Current; + return tstate && (tstate == PyGILState_GetThisThreadState()); + } + #endif +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030d0000 || defined(_PyDict_NewPresized) +#define __Pyx_PyDict_NewPresized(n) ((n <= 8) ? PyDict_New() : _PyDict_NewPresized(n)) +#else +#define __Pyx_PyDict_NewPresized(n) PyDict_New() +#endif +#if PY_MAJOR_VERSION >= 3 || CYTHON_FUTURE_DIVISION + #define __Pyx_PyNumber_Divide(x,y) PyNumber_TrueDivide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceTrueDivide(x,y) +#else + #define __Pyx_PyNumber_Divide(x,y) PyNumber_Divide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceDivide(x,y) +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX > 0x030600B4 && PY_VERSION_HEX < 0x030d0000 && CYTHON_USE_UNICODE_INTERNALS +#define __Pyx_PyDict_GetItemStrWithError(dict, name) _PyDict_GetItem_KnownHash(dict, name, ((PyASCIIObject *) name)->hash) +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStr(PyObject *dict, PyObject *name) { + PyObject *res = __Pyx_PyDict_GetItemStrWithError(dict, name); + if (res == NULL) PyErr_Clear(); + return res; +} +#elif PY_MAJOR_VERSION >= 3 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07020000) +#define __Pyx_PyDict_GetItemStrWithError PyDict_GetItemWithError +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#else +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStrWithError(PyObject *dict, PyObject *name) { +#if CYTHON_COMPILING_IN_PYPY + return PyDict_GetItem(dict, name); +#else + PyDictEntry *ep; + PyDictObject *mp = (PyDictObject*) dict; + long hash = ((PyStringObject *) name)->ob_shash; + assert(hash != -1); + ep = (mp->ma_lookup)(mp, name, hash); + if (ep == NULL) { + return NULL; + } + return ep->me_value; +#endif +} +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#endif +#if CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyType_GetFlags(tp) (((PyTypeObject *)tp)->tp_flags) + #define __Pyx_PyType_HasFeature(type, feature) ((__Pyx_PyType_GetFlags(type) & (feature)) != 0) + #define __Pyx_PyObject_GetIterNextFunc(obj) (Py_TYPE(obj)->tp_iternext) +#else + #define __Pyx_PyType_GetFlags(tp) (PyType_GetFlags((PyTypeObject *)tp)) + #define __Pyx_PyType_HasFeature(type, feature) PyType_HasFeature(type, feature) + #define __Pyx_PyObject_GetIterNextFunc(obj) PyIter_Next +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_SetItemOnTypeDict(tp, k, v) PyObject_GenericSetAttr((PyObject*)tp, k, v) +#else + #define __Pyx_SetItemOnTypeDict(tp, k, v) PyDict_SetItem(tp->tp_dict, k, v) +#endif +#if CYTHON_USE_TYPE_SPECS && PY_VERSION_HEX >= 0x03080000 +#define __Pyx_PyHeapTypeObject_GC_Del(obj) {\ + PyTypeObject *type = Py_TYPE((PyObject*)obj);\ + assert(__Pyx_PyType_HasFeature(type, Py_TPFLAGS_HEAPTYPE));\ + PyObject_GC_Del(obj);\ + Py_DECREF(type);\ +} +#else +#define __Pyx_PyHeapTypeObject_GC_Del(obj) PyObject_GC_Del(obj) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define CYTHON_PEP393_ENABLED 1 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GetLength(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_ReadChar(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((void)u, 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((void)u, (0)) + #define __Pyx_PyUnicode_DATA(u) ((void*)u) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)k, PyUnicode_ReadChar((PyObject*)(d), i)) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GetLength(u)) +#elif PY_VERSION_HEX > 0x03030000 && defined(PyUnicode_KIND) + #define CYTHON_PEP393_ENABLED 1 + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_READY(op) (0) + #else + #define __Pyx_PyUnicode_READY(op) (likely(PyUnicode_IS_READY(op)) ?\ + 0 : _PyUnicode_Ready((PyObject *)(op))) + #endif + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_LENGTH(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_READ_CHAR(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) PyUnicode_MAX_CHAR_VALUE(u) + #define __Pyx_PyUnicode_KIND(u) ((int)PyUnicode_KIND(u)) + #define __Pyx_PyUnicode_DATA(u) PyUnicode_DATA(u) + #define __Pyx_PyUnicode_READ(k, d, i) PyUnicode_READ(k, d, i) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) PyUnicode_WRITE(k, d, i, (Py_UCS4) ch) + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_LENGTH(u)) + #else + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x03090000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : ((PyCompactUnicodeObject *)(u))->wstr_length)) + #else + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : PyUnicode_GET_SIZE(u))) + #endif + #endif +#else + #define CYTHON_PEP393_ENABLED 0 + #define PyUnicode_1BYTE_KIND 1 + #define PyUnicode_2BYTE_KIND 2 + #define PyUnicode_4BYTE_KIND 4 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_SIZE(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) ((Py_UCS4)(PyUnicode_AS_UNICODE(u)[i])) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((sizeof(Py_UNICODE) == 2) ? 65535U : 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((int)sizeof(Py_UNICODE)) + #define __Pyx_PyUnicode_DATA(u) ((void*)PyUnicode_AS_UNICODE(u)) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)(k), (Py_UCS4)(((Py_UNICODE*)d)[i])) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) (((void)(k)), ((Py_UNICODE*)d)[i] = (Py_UNICODE) ch) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_SIZE(u)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyUnicode_Concat(a, b) PyNumber_Add(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) PyNumber_Add(a, b) +#else + #define __Pyx_PyUnicode_Concat(a, b) PyUnicode_Concat(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) ((unlikely((a) == Py_None) || unlikely((b) == Py_None)) ?\ + PyNumber_Add(a, b) : __Pyx_PyUnicode_Concat(a, b)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #if !defined(PyUnicode_DecodeUnicodeEscape) + #define PyUnicode_DecodeUnicodeEscape(s, size, errors) PyUnicode_Decode(s, size, "unicode_escape", errors) + #endif + #if !defined(PyUnicode_Contains) || (PY_MAJOR_VERSION == 2 && PYPY_VERSION_NUM < 0x07030500) + #undef PyUnicode_Contains + #define PyUnicode_Contains(u, s) PySequence_Contains(u, s) + #endif + #if !defined(PyByteArray_Check) + #define PyByteArray_Check(obj) PyObject_TypeCheck(obj, &PyByteArray_Type) + #endif + #if !defined(PyObject_Format) + #define PyObject_Format(obj, fmt) PyObject_CallMethod(obj, "__format__", "O", fmt) + #endif +#endif +#define __Pyx_PyString_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyString_Check(b) && !PyString_CheckExact(b)))) ? PyNumber_Remainder(a, b) : __Pyx_PyString_Format(a, b)) +#define __Pyx_PyUnicode_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyUnicode_Check(b) && !PyUnicode_CheckExact(b)))) ? PyNumber_Remainder(a, b) : PyUnicode_Format(a, b)) +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyString_Format(a, b) PyUnicode_Format(a, b) +#else + #define __Pyx_PyString_Format(a, b) PyString_Format(a, b) +#endif +#if PY_MAJOR_VERSION < 3 && !defined(PyObject_ASCII) + #define PyObject_ASCII(o) PyObject_Repr(o) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBaseString_Type PyUnicode_Type + #define PyStringObject PyUnicodeObject + #define PyString_Type PyUnicode_Type + #define PyString_Check PyUnicode_Check + #define PyString_CheckExact PyUnicode_CheckExact +#ifndef PyObject_Unicode + #define PyObject_Unicode PyObject_Str +#endif +#endif +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyBaseString_Check(obj) PyUnicode_Check(obj) + #define __Pyx_PyBaseString_CheckExact(obj) PyUnicode_CheckExact(obj) +#else + #define __Pyx_PyBaseString_Check(obj) (PyString_Check(obj) || PyUnicode_Check(obj)) + #define __Pyx_PyBaseString_CheckExact(obj) (PyString_CheckExact(obj) || PyUnicode_CheckExact(obj)) +#endif +#if CYTHON_COMPILING_IN_CPYTHON + #define __Pyx_PySequence_ListKeepNew(obj)\ + (likely(PyList_CheckExact(obj) && Py_REFCNT(obj) == 1) ? __Pyx_NewRef(obj) : PySequence_List(obj)) +#else + #define __Pyx_PySequence_ListKeepNew(obj) PySequence_List(obj) +#endif +#ifndef PySet_CheckExact + #define PySet_CheckExact(obj) __Pyx_IS_TYPE(obj, &PySet_Type) +#endif +#if PY_VERSION_HEX >= 0x030900A4 + #define __Pyx_SET_REFCNT(obj, refcnt) Py_SET_REFCNT(obj, refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SET_SIZE(obj, size) +#else + #define __Pyx_SET_REFCNT(obj, refcnt) Py_REFCNT(obj) = (refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SIZE(obj) = (size) +#endif +#if CYTHON_ASSUME_SAFE_MACROS + #define __Pyx_PySequence_ITEM(o, i) PySequence_ITEM(o, i) + #define __Pyx_PySequence_SIZE(seq) Py_SIZE(seq) + #define __Pyx_PyTuple_SET_ITEM(o, i, v) (PyTuple_SET_ITEM(o, i, v), (0)) + #define __Pyx_PyList_SET_ITEM(o, i, v) (PyList_SET_ITEM(o, i, v), (0)) + #define __Pyx_PyTuple_GET_SIZE(o) PyTuple_GET_SIZE(o) + #define __Pyx_PyList_GET_SIZE(o) PyList_GET_SIZE(o) + #define __Pyx_PySet_GET_SIZE(o) PySet_GET_SIZE(o) + #define __Pyx_PyBytes_GET_SIZE(o) PyBytes_GET_SIZE(o) + #define __Pyx_PyByteArray_GET_SIZE(o) PyByteArray_GET_SIZE(o) +#else + #define __Pyx_PySequence_ITEM(o, i) PySequence_GetItem(o, i) + #define __Pyx_PySequence_SIZE(seq) PySequence_Size(seq) + #define __Pyx_PyTuple_SET_ITEM(o, i, v) PyTuple_SetItem(o, i, v) + #define __Pyx_PyList_SET_ITEM(o, i, v) PyList_SetItem(o, i, v) + #define __Pyx_PyTuple_GET_SIZE(o) PyTuple_Size(o) + #define __Pyx_PyList_GET_SIZE(o) PyList_Size(o) + #define __Pyx_PySet_GET_SIZE(o) PySet_Size(o) + #define __Pyx_PyBytes_GET_SIZE(o) PyBytes_Size(o) + #define __Pyx_PyByteArray_GET_SIZE(o) PyByteArray_Size(o) +#endif +#if PY_VERSION_HEX >= 0x030d00A1 + #define __Pyx_PyImport_AddModuleRef(name) PyImport_AddModuleRef(name) +#else + static CYTHON_INLINE PyObject *__Pyx_PyImport_AddModuleRef(const char *name) { + PyObject *module = PyImport_AddModule(name); + Py_XINCREF(module); + return module; + } +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyIntObject PyLongObject + #define PyInt_Type PyLong_Type + #define PyInt_Check(op) PyLong_Check(op) + #define PyInt_CheckExact(op) PyLong_CheckExact(op) + #define __Pyx_Py3Int_Check(op) PyLong_Check(op) + #define __Pyx_Py3Int_CheckExact(op) PyLong_CheckExact(op) + #define PyInt_FromString PyLong_FromString + #define PyInt_FromUnicode PyLong_FromUnicode + #define PyInt_FromLong PyLong_FromLong + #define PyInt_FromSize_t PyLong_FromSize_t + #define PyInt_FromSsize_t PyLong_FromSsize_t + #define PyInt_AsLong PyLong_AsLong + #define PyInt_AS_LONG PyLong_AS_LONG + #define PyInt_AsSsize_t PyLong_AsSsize_t + #define PyInt_AsUnsignedLongMask PyLong_AsUnsignedLongMask + #define PyInt_AsUnsignedLongLongMask PyLong_AsUnsignedLongLongMask + #define PyNumber_Int PyNumber_Long +#else + #define __Pyx_Py3Int_Check(op) (PyLong_Check(op) || PyInt_Check(op)) + #define __Pyx_Py3Int_CheckExact(op) (PyLong_CheckExact(op) || PyInt_CheckExact(op)) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBoolObject PyLongObject +#endif +#if PY_MAJOR_VERSION >= 3 && CYTHON_COMPILING_IN_PYPY + #ifndef PyUnicode_InternFromString + #define PyUnicode_InternFromString(s) PyUnicode_FromString(s) + #endif +#endif +#if PY_VERSION_HEX < 0x030200A4 + typedef long Py_hash_t; + #define __Pyx_PyInt_FromHash_t PyInt_FromLong + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsHash_t +#else + #define __Pyx_PyInt_FromHash_t PyInt_FromSsize_t + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsSsize_t +#endif +#if CYTHON_USE_ASYNC_SLOTS + #if PY_VERSION_HEX >= 0x030500B1 + #define __Pyx_PyAsyncMethodsStruct PyAsyncMethods + #define __Pyx_PyType_AsAsync(obj) (Py_TYPE(obj)->tp_as_async) + #else + #define __Pyx_PyType_AsAsync(obj) ((__Pyx_PyAsyncMethodsStruct*) (Py_TYPE(obj)->tp_reserved)) + #endif +#else + #define __Pyx_PyType_AsAsync(obj) NULL +#endif +#ifndef __Pyx_PyAsyncMethodsStruct + typedef struct { + unaryfunc am_await; + unaryfunc am_aiter; + unaryfunc am_anext; + } __Pyx_PyAsyncMethodsStruct; +#endif + +#if defined(_WIN32) || defined(WIN32) || defined(MS_WINDOWS) + #if !defined(_USE_MATH_DEFINES) + #define _USE_MATH_DEFINES + #endif +#endif +#include +#ifdef NAN +#define __PYX_NAN() ((float) NAN) +#else +static CYTHON_INLINE float __PYX_NAN() { + float value; + memset(&value, 0xFF, sizeof(value)); + return value; +} +#endif +#if defined(__CYGWIN__) && defined(_LDBL_EQ_DBL) +#define __Pyx_truncl trunc +#else +#define __Pyx_truncl truncl +#endif + +#define __PYX_MARK_ERR_POS(f_index, lineno) \ + { __pyx_filename = __pyx_f[f_index]; (void)__pyx_filename; __pyx_lineno = lineno; (void)__pyx_lineno; __pyx_clineno = __LINE__; (void)__pyx_clineno; } +#define __PYX_ERR(f_index, lineno, Ln_error) \ + { __PYX_MARK_ERR_POS(f_index, lineno) goto Ln_error; } + +#ifdef CYTHON_EXTERN_C + #undef __PYX_EXTERN_C + #define __PYX_EXTERN_C CYTHON_EXTERN_C +#elif defined(__PYX_EXTERN_C) + #ifdef _MSC_VER + #pragma message ("Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead.") + #else + #warning Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead. + #endif +#else + #define __PYX_EXTERN_C extern "C++" +#endif + +#define __PYX_HAVE__common__transformations__transformations +#define __PYX_HAVE_API__common__transformations__transformations +/* Early includes */ +#include "orientation.cc" +#include "orientation.hpp" +#include "coordinates.cc" +#include "coordinates.hpp" +#include +#include + + /* Using NumPy API declarations from "numpy/__init__.cython-30.pxd" */ + +#include "numpy/arrayobject.h" +#include "numpy/ndarrayobject.h" +#include "numpy/ndarraytypes.h" +#include "numpy/arrayscalars.h" +#include "numpy/ufuncobject.h" +#ifdef _OPENMP +#include +#endif /* _OPENMP */ + +#if defined(PYREX_WITHOUT_ASSERTIONS) && !defined(CYTHON_WITHOUT_ASSERTIONS) +#define CYTHON_WITHOUT_ASSERTIONS +#endif + +typedef struct {PyObject **p; const char *s; const Py_ssize_t n; const char* encoding; + const char is_unicode; const char is_str; const char intern; } __Pyx_StringTabEntry; + +#define __PYX_DEFAULT_STRING_ENCODING_IS_ASCII 0 +#define __PYX_DEFAULT_STRING_ENCODING_IS_UTF8 0 +#define __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT (PY_MAJOR_VERSION >= 3 && __PYX_DEFAULT_STRING_ENCODING_IS_UTF8) +#define __PYX_DEFAULT_STRING_ENCODING "" +#define __Pyx_PyObject_FromString __Pyx_PyBytes_FromString +#define __Pyx_PyObject_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#define __Pyx_uchar_cast(c) ((unsigned char)c) +#define __Pyx_long_cast(x) ((long)x) +#define __Pyx_fits_Py_ssize_t(v, type, is_signed) (\ + (sizeof(type) < sizeof(Py_ssize_t)) ||\ + (sizeof(type) > sizeof(Py_ssize_t) &&\ + likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX) &&\ + (!is_signed || likely(v > (type)PY_SSIZE_T_MIN ||\ + v == (type)PY_SSIZE_T_MIN))) ||\ + (sizeof(type) == sizeof(Py_ssize_t) &&\ + (is_signed || likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX))) ) +static CYTHON_INLINE int __Pyx_is_valid_index(Py_ssize_t i, Py_ssize_t limit) { + return (size_t) i < (size_t) limit; +} +#if defined (__cplusplus) && __cplusplus >= 201103L + #include + #define __Pyx_sst_abs(value) std::abs(value) +#elif SIZEOF_INT >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) abs(value) +#elif SIZEOF_LONG >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) labs(value) +#elif defined (_MSC_VER) + #define __Pyx_sst_abs(value) ((Py_ssize_t)_abs64(value)) +#elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define __Pyx_sst_abs(value) llabs(value) +#elif defined (__GNUC__) + #define __Pyx_sst_abs(value) __builtin_llabs(value) +#else + #define __Pyx_sst_abs(value) ((value<0) ? -value : value) +#endif +static CYTHON_INLINE Py_ssize_t __Pyx_ssize_strlen(const char *s); +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject*); +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject*, Py_ssize_t* length); +static CYTHON_INLINE PyObject* __Pyx_PyByteArray_FromString(const char*); +#define __Pyx_PyByteArray_FromStringAndSize(s, l) PyByteArray_FromStringAndSize((const char*)s, l) +#define __Pyx_PyBytes_FromString PyBytes_FromString +#define __Pyx_PyBytes_FromStringAndSize PyBytes_FromStringAndSize +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char*); +#if PY_MAJOR_VERSION < 3 + #define __Pyx_PyStr_FromString __Pyx_PyBytes_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#else + #define __Pyx_PyStr_FromString __Pyx_PyUnicode_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyUnicode_FromStringAndSize +#endif +#define __Pyx_PyBytes_AsWritableString(s) ((char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableSString(s) ((signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableUString(s) ((unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsString(s) ((const char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsSString(s) ((const signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsUString(s) ((const unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyObject_AsWritableString(s) ((char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableSString(s) ((signed char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableUString(s) ((unsigned char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsSString(s) ((const signed char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsUString(s) ((const unsigned char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_FromCString(s) __Pyx_PyObject_FromString((const char*)s) +#define __Pyx_PyBytes_FromCString(s) __Pyx_PyBytes_FromString((const char*)s) +#define __Pyx_PyByteArray_FromCString(s) __Pyx_PyByteArray_FromString((const char*)s) +#define __Pyx_PyStr_FromCString(s) __Pyx_PyStr_FromString((const char*)s) +#define __Pyx_PyUnicode_FromCString(s) __Pyx_PyUnicode_FromString((const char*)s) +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const wchar_t *u) +{ + const wchar_t *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#else +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const Py_UNICODE *u) +{ + const Py_UNICODE *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#endif +#define __Pyx_PyUnicode_FromOrdinal(o) PyUnicode_FromOrdinal((int)o) +#define __Pyx_PyUnicode_FromUnicode(u) PyUnicode_FromUnicode(u, __Pyx_Py_UNICODE_strlen(u)) +#define __Pyx_PyUnicode_FromUnicodeAndLength PyUnicode_FromUnicode +#define __Pyx_PyUnicode_AsUnicode PyUnicode_AsUnicode +#define __Pyx_NewRef(obj) (Py_INCREF(obj), obj) +#define __Pyx_Owned_Py_None(b) __Pyx_NewRef(Py_None) +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b); +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject*); +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject*); +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x); +#define __Pyx_PySequence_Tuple(obj)\ + (likely(PyTuple_CheckExact(obj)) ? __Pyx_NewRef(obj) : PySequence_Tuple(obj)) +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject*); +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t); +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject*); +#if CYTHON_ASSUME_SAFE_MACROS +#define __pyx_PyFloat_AsDouble(x) (PyFloat_CheckExact(x) ? PyFloat_AS_DOUBLE(x) : PyFloat_AsDouble(x)) +#else +#define __pyx_PyFloat_AsDouble(x) PyFloat_AsDouble(x) +#endif +#define __pyx_PyFloat_AsFloat(x) ((float) __pyx_PyFloat_AsDouble(x)) +#if PY_MAJOR_VERSION >= 3 +#define __Pyx_PyNumber_Int(x) (PyLong_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Long(x)) +#else +#define __Pyx_PyNumber_Int(x) (PyInt_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Int(x)) +#endif +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_VERSION_HEX >= 0x030C00A7 + #ifndef _PyLong_SIGN_MASK + #define _PyLong_SIGN_MASK 3 + #endif + #ifndef _PyLong_NON_SIZE_BITS + #define _PyLong_NON_SIZE_BITS 3 + #endif + #define __Pyx_PyLong_Sign(x) (((PyLongObject*)x)->long_value.lv_tag & _PyLong_SIGN_MASK) + #define __Pyx_PyLong_IsNeg(x) ((__Pyx_PyLong_Sign(x) & 2) != 0) + #define __Pyx_PyLong_IsNonNeg(x) (!__Pyx_PyLong_IsNeg(x)) + #define __Pyx_PyLong_IsZero(x) (__Pyx_PyLong_Sign(x) & 1) + #define __Pyx_PyLong_IsPos(x) (__Pyx_PyLong_Sign(x) == 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) (__Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) ((Py_ssize_t) (((PyLongObject*)x)->long_value.lv_tag >> _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_SignedDigitCount(x)\ + ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * __Pyx_PyLong_DigitCount(x)) + #if defined(PyUnstable_Long_IsCompact) && defined(PyUnstable_Long_CompactValue) + #define __Pyx_PyLong_IsCompact(x) PyUnstable_Long_IsCompact((PyLongObject*) x) + #define __Pyx_PyLong_CompactValue(x) PyUnstable_Long_CompactValue((PyLongObject*) x) + #else + #define __Pyx_PyLong_IsCompact(x) (((PyLongObject*)x)->long_value.lv_tag < (2 << _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_CompactValue(x) ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * (Py_ssize_t) __Pyx_PyLong_Digits(x)[0]) + #endif + typedef Py_ssize_t __Pyx_compact_pylong; + typedef size_t __Pyx_compact_upylong; + #else + #define __Pyx_PyLong_IsNeg(x) (Py_SIZE(x) < 0) + #define __Pyx_PyLong_IsNonNeg(x) (Py_SIZE(x) >= 0) + #define __Pyx_PyLong_IsZero(x) (Py_SIZE(x) == 0) + #define __Pyx_PyLong_IsPos(x) (Py_SIZE(x) > 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) ((Py_SIZE(x) == 0) ? 0 : __Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) __Pyx_sst_abs(Py_SIZE(x)) + #define __Pyx_PyLong_SignedDigitCount(x) Py_SIZE(x) + #define __Pyx_PyLong_IsCompact(x) (Py_SIZE(x) == 0 || Py_SIZE(x) == 1 || Py_SIZE(x) == -1) + #define __Pyx_PyLong_CompactValue(x)\ + ((Py_SIZE(x) == 0) ? (sdigit) 0 : ((Py_SIZE(x) < 0) ? -(sdigit)__Pyx_PyLong_Digits(x)[0] : (sdigit)__Pyx_PyLong_Digits(x)[0])) + typedef sdigit __Pyx_compact_pylong; + typedef digit __Pyx_compact_upylong; + #endif + #if PY_VERSION_HEX >= 0x030C00A5 + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->long_value.ob_digit) + #else + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->ob_digit) + #endif +#endif +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII +#include +static int __Pyx_sys_getdefaultencoding_not_ascii; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + PyObject* ascii_chars_u = NULL; + PyObject* ascii_chars_b = NULL; + const char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + if (strcmp(default_encoding_c, "ascii") == 0) { + __Pyx_sys_getdefaultencoding_not_ascii = 0; + } else { + char ascii_chars[128]; + int c; + for (c = 0; c < 128; c++) { + ascii_chars[c] = (char) c; + } + __Pyx_sys_getdefaultencoding_not_ascii = 1; + ascii_chars_u = PyUnicode_DecodeASCII(ascii_chars, 128, NULL); + if (!ascii_chars_u) goto bad; + ascii_chars_b = PyUnicode_AsEncodedString(ascii_chars_u, default_encoding_c, NULL); + if (!ascii_chars_b || !PyBytes_Check(ascii_chars_b) || memcmp(ascii_chars, PyBytes_AS_STRING(ascii_chars_b), 128) != 0) { + PyErr_Format( + PyExc_ValueError, + "This module compiled with c_string_encoding=ascii, but default encoding '%.200s' is not a superset of ascii.", + default_encoding_c); + goto bad; + } + Py_DECREF(ascii_chars_u); + Py_DECREF(ascii_chars_b); + } + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + Py_XDECREF(ascii_chars_u); + Py_XDECREF(ascii_chars_b); + return -1; +} +#endif +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT && PY_MAJOR_VERSION >= 3 +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_DecodeUTF8(c_str, size, NULL) +#else +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_Decode(c_str, size, __PYX_DEFAULT_STRING_ENCODING, NULL) +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +#include +static char* __PYX_DEFAULT_STRING_ENCODING; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) (const char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + __PYX_DEFAULT_STRING_ENCODING = (char*) malloc(strlen(default_encoding_c) + 1); + if (!__PYX_DEFAULT_STRING_ENCODING) goto bad; + strcpy(__PYX_DEFAULT_STRING_ENCODING, default_encoding_c); + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + return -1; +} +#endif +#endif + + +/* Test for GCC > 2.95 */ +#if defined(__GNUC__) && (__GNUC__ > 2 || (__GNUC__ == 2 && (__GNUC_MINOR__ > 95))) + #define likely(x) __builtin_expect(!!(x), 1) + #define unlikely(x) __builtin_expect(!!(x), 0) +#else /* !__GNUC__ or GCC < 2.95 */ + #define likely(x) (x) + #define unlikely(x) (x) +#endif /* __GNUC__ */ +static CYTHON_INLINE void __Pyx_pretend_to_initialize(void* ptr) { (void)ptr; } + +#if !CYTHON_USE_MODULE_STATE +static PyObject *__pyx_m = NULL; +#endif +static int __pyx_lineno; +static int __pyx_clineno = 0; +static const char * __pyx_cfilenm = __FILE__; +static const char *__pyx_filename; + +/* Header.proto */ +#if !defined(CYTHON_CCOMPLEX) + #if defined(__cplusplus) + #define CYTHON_CCOMPLEX 1 + #elif (defined(_Complex_I) && !defined(_MSC_VER)) || ((defined (__STDC_VERSION__) && __STDC_VERSION__ >= 201112L) && !defined(__STDC_NO_COMPLEX__) && !defined(_MSC_VER)) + #define CYTHON_CCOMPLEX 1 + #else + #define CYTHON_CCOMPLEX 0 + #endif +#endif +#if CYTHON_CCOMPLEX + #ifdef __cplusplus + #include + #else + #include + #endif +#endif +#if CYTHON_CCOMPLEX && !defined(__cplusplus) && defined(__sun__) && defined(__GNUC__) + #undef _Complex_I + #define _Complex_I 1.0fj +#endif + +/* #### Code section: filename_table ### */ + +static const char *__pyx_f[] = { + "common/transformations/transformations.pyx", + "", + "__init__.cython-30.pxd", + "type.pxd", +}; +/* #### Code section: utility_code_proto_before_types ### */ +/* ForceInitThreads.proto */ +#ifndef __PYX_FORCE_INIT_THREADS + #define __PYX_FORCE_INIT_THREADS 0 +#endif + +/* BufferFormatStructs.proto */ +struct __Pyx_StructField_; +#define __PYX_BUF_FLAGS_PACKED_STRUCT (1 << 0) +typedef struct { + const char* name; + struct __Pyx_StructField_* fields; + size_t size; + size_t arraysize[8]; + int ndim; + char typegroup; + char is_unsigned; + int flags; +} __Pyx_TypeInfo; +typedef struct __Pyx_StructField_ { + __Pyx_TypeInfo* type; + const char* name; + size_t offset; +} __Pyx_StructField; +typedef struct { + __Pyx_StructField* field; + size_t parent_offset; +} __Pyx_BufFmt_StackElem; +typedef struct { + __Pyx_StructField root; + __Pyx_BufFmt_StackElem* head; + size_t fmt_offset; + size_t new_count, enc_count; + size_t struct_alignment; + int is_complex; + char enc_type; + char new_packmode; + char enc_packmode; + char is_valid_array; +} __Pyx_BufFmt_Context; + +/* #### Code section: numeric_typedefs ### */ + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":730 + * # in Cython to enable them only on the right systems. + * + * ctypedef npy_int8 int8_t # <<<<<<<<<<<<<< + * ctypedef npy_int16 int16_t + * ctypedef npy_int32 int32_t + */ +typedef npy_int8 __pyx_t_5numpy_int8_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":731 + * + * ctypedef npy_int8 int8_t + * ctypedef npy_int16 int16_t # <<<<<<<<<<<<<< + * ctypedef npy_int32 int32_t + * ctypedef npy_int64 int64_t + */ +typedef npy_int16 __pyx_t_5numpy_int16_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":732 + * ctypedef npy_int8 int8_t + * ctypedef npy_int16 int16_t + * ctypedef npy_int32 int32_t # <<<<<<<<<<<<<< + * ctypedef npy_int64 int64_t + * #ctypedef npy_int96 int96_t + */ +typedef npy_int32 __pyx_t_5numpy_int32_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":733 + * ctypedef npy_int16 int16_t + * ctypedef npy_int32 int32_t + * ctypedef npy_int64 int64_t # <<<<<<<<<<<<<< + * #ctypedef npy_int96 int96_t + * #ctypedef npy_int128 int128_t + */ +typedef npy_int64 __pyx_t_5numpy_int64_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":737 + * #ctypedef npy_int128 int128_t + * + * ctypedef npy_uint8 uint8_t # <<<<<<<<<<<<<< + * ctypedef npy_uint16 uint16_t + * ctypedef npy_uint32 uint32_t + */ +typedef npy_uint8 __pyx_t_5numpy_uint8_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":738 + * + * ctypedef npy_uint8 uint8_t + * ctypedef npy_uint16 uint16_t # <<<<<<<<<<<<<< + * ctypedef npy_uint32 uint32_t + * ctypedef npy_uint64 uint64_t + */ +typedef npy_uint16 __pyx_t_5numpy_uint16_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":739 + * ctypedef npy_uint8 uint8_t + * ctypedef npy_uint16 uint16_t + * ctypedef npy_uint32 uint32_t # <<<<<<<<<<<<<< + * ctypedef npy_uint64 uint64_t + * #ctypedef npy_uint96 uint96_t + */ +typedef npy_uint32 __pyx_t_5numpy_uint32_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":740 + * ctypedef npy_uint16 uint16_t + * ctypedef npy_uint32 uint32_t + * ctypedef npy_uint64 uint64_t # <<<<<<<<<<<<<< + * #ctypedef npy_uint96 uint96_t + * #ctypedef npy_uint128 uint128_t + */ +typedef npy_uint64 __pyx_t_5numpy_uint64_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":744 + * #ctypedef npy_uint128 uint128_t + * + * ctypedef npy_float32 float32_t # <<<<<<<<<<<<<< + * ctypedef npy_float64 float64_t + * #ctypedef npy_float80 float80_t + */ +typedef npy_float32 __pyx_t_5numpy_float32_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":745 + * + * ctypedef npy_float32 float32_t + * ctypedef npy_float64 float64_t # <<<<<<<<<<<<<< + * #ctypedef npy_float80 float80_t + * #ctypedef npy_float128 float128_t + */ +typedef npy_float64 __pyx_t_5numpy_float64_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":754 + * # The int types are mapped a bit surprising -- + * # numpy.int corresponds to 'l' and numpy.long to 'q' + * ctypedef npy_long int_t # <<<<<<<<<<<<<< + * ctypedef npy_longlong longlong_t + * + */ +typedef npy_long __pyx_t_5numpy_int_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":755 + * # numpy.int corresponds to 'l' and numpy.long to 'q' + * ctypedef npy_long int_t + * ctypedef npy_longlong longlong_t # <<<<<<<<<<<<<< + * + * ctypedef npy_ulong uint_t + */ +typedef npy_longlong __pyx_t_5numpy_longlong_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":757 + * ctypedef npy_longlong longlong_t + * + * ctypedef npy_ulong uint_t # <<<<<<<<<<<<<< + * ctypedef npy_ulonglong ulonglong_t + * + */ +typedef npy_ulong __pyx_t_5numpy_uint_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":758 + * + * ctypedef npy_ulong uint_t + * ctypedef npy_ulonglong ulonglong_t # <<<<<<<<<<<<<< + * + * ctypedef npy_intp intp_t + */ +typedef npy_ulonglong __pyx_t_5numpy_ulonglong_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":760 + * ctypedef npy_ulonglong ulonglong_t + * + * ctypedef npy_intp intp_t # <<<<<<<<<<<<<< + * ctypedef npy_uintp uintp_t + * + */ +typedef npy_intp __pyx_t_5numpy_intp_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":761 + * + * ctypedef npy_intp intp_t + * ctypedef npy_uintp uintp_t # <<<<<<<<<<<<<< + * + * ctypedef npy_double float_t + */ +typedef npy_uintp __pyx_t_5numpy_uintp_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":763 + * ctypedef npy_uintp uintp_t + * + * ctypedef npy_double float_t # <<<<<<<<<<<<<< + * ctypedef npy_double double_t + * ctypedef npy_longdouble longdouble_t + */ +typedef npy_double __pyx_t_5numpy_float_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":764 + * + * ctypedef npy_double float_t + * ctypedef npy_double double_t # <<<<<<<<<<<<<< + * ctypedef npy_longdouble longdouble_t + * + */ +typedef npy_double __pyx_t_5numpy_double_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":765 + * ctypedef npy_double float_t + * ctypedef npy_double double_t + * ctypedef npy_longdouble longdouble_t # <<<<<<<<<<<<<< + * + * ctypedef npy_cfloat cfloat_t + */ +typedef npy_longdouble __pyx_t_5numpy_longdouble_t; +/* #### Code section: complex_type_declarations ### */ +/* Declarations.proto */ +#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #ifdef __cplusplus + typedef ::std::complex< float > __pyx_t_float_complex; + #else + typedef float _Complex __pyx_t_float_complex; + #endif +#else + typedef struct { float real, imag; } __pyx_t_float_complex; +#endif +static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float, float); + +/* Declarations.proto */ +#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #ifdef __cplusplus + typedef ::std::complex< double > __pyx_t_double_complex; + #else + typedef double _Complex __pyx_t_double_complex; + #endif +#else + typedef struct { double real, imag; } __pyx_t_double_complex; +#endif +static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double, double); + +/* #### Code section: type_declarations ### */ + +/*--- Type declarations ---*/ +struct __pyx_obj_6common_15transformations_15transformations_LocalCoord; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":767 + * ctypedef npy_longdouble longdouble_t + * + * ctypedef npy_cfloat cfloat_t # <<<<<<<<<<<<<< + * ctypedef npy_cdouble cdouble_t + * ctypedef npy_clongdouble clongdouble_t + */ +typedef npy_cfloat __pyx_t_5numpy_cfloat_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":768 + * + * ctypedef npy_cfloat cfloat_t + * ctypedef npy_cdouble cdouble_t # <<<<<<<<<<<<<< + * ctypedef npy_clongdouble clongdouble_t + * + */ +typedef npy_cdouble __pyx_t_5numpy_cdouble_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":769 + * ctypedef npy_cfloat cfloat_t + * ctypedef npy_cdouble cdouble_t + * ctypedef npy_clongdouble clongdouble_t # <<<<<<<<<<<<<< + * + * ctypedef npy_cdouble complex_t + */ +typedef npy_clongdouble __pyx_t_5numpy_clongdouble_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":771 + * ctypedef npy_clongdouble clongdouble_t + * + * ctypedef npy_cdouble complex_t # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew1(a): + */ +typedef npy_cdouble __pyx_t_5numpy_complex_t; + +/* "common/transformations/transformations.pyx":114 + * + * + * cdef class LocalCoord: # <<<<<<<<<<<<<< + * cdef LocalCoord_c * lc + * + */ +struct __pyx_obj_6common_15transformations_15transformations_LocalCoord { + PyObject_HEAD + LocalCoord *lc; +}; + +/* #### Code section: utility_code_proto ### */ + +/* --- Runtime support code (head) --- */ +/* Refnanny.proto */ +#ifndef CYTHON_REFNANNY + #define CYTHON_REFNANNY 0 +#endif +#if CYTHON_REFNANNY + typedef struct { + void (*INCREF)(void*, PyObject*, Py_ssize_t); + void (*DECREF)(void*, PyObject*, Py_ssize_t); + void (*GOTREF)(void*, PyObject*, Py_ssize_t); + void (*GIVEREF)(void*, PyObject*, Py_ssize_t); + void* (*SetupContext)(const char*, Py_ssize_t, const char*); + void (*FinishContext)(void**); + } __Pyx_RefNannyAPIStruct; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNanny = NULL; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname); + #define __Pyx_RefNannyDeclarations void *__pyx_refnanny = NULL; +#ifdef WITH_THREAD + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + if (acquire_gil) {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + PyGILState_Release(__pyx_gilstate_save);\ + } else {\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + } + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } +#else + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__)) + #define __Pyx_RefNannyFinishContextNogil() __Pyx_RefNannyFinishContext() +#endif + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } + #define __Pyx_RefNannyFinishContext()\ + __Pyx_RefNanny->FinishContext(&__pyx_refnanny) + #define __Pyx_INCREF(r) __Pyx_RefNanny->INCREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_DECREF(r) __Pyx_RefNanny->DECREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GOTREF(r) __Pyx_RefNanny->GOTREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GIVEREF(r) __Pyx_RefNanny->GIVEREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_XINCREF(r) do { if((r) == NULL); else {__Pyx_INCREF(r); }} while(0) + #define __Pyx_XDECREF(r) do { if((r) == NULL); else {__Pyx_DECREF(r); }} while(0) + #define __Pyx_XGOTREF(r) do { if((r) == NULL); else {__Pyx_GOTREF(r); }} while(0) + #define __Pyx_XGIVEREF(r) do { if((r) == NULL); else {__Pyx_GIVEREF(r);}} while(0) +#else + #define __Pyx_RefNannyDeclarations + #define __Pyx_RefNannySetupContext(name, acquire_gil) + #define __Pyx_RefNannyFinishContextNogil() + #define __Pyx_RefNannyFinishContext() + #define __Pyx_INCREF(r) Py_INCREF(r) + #define __Pyx_DECREF(r) Py_DECREF(r) + #define __Pyx_GOTREF(r) + #define __Pyx_GIVEREF(r) + #define __Pyx_XINCREF(r) Py_XINCREF(r) + #define __Pyx_XDECREF(r) Py_XDECREF(r) + #define __Pyx_XGOTREF(r) + #define __Pyx_XGIVEREF(r) +#endif +#define __Pyx_Py_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; Py_XDECREF(tmp);\ + } while (0) +#define __Pyx_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_XDECREF(tmp);\ + } while (0) +#define __Pyx_DECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_DECREF(tmp);\ + } while (0) +#define __Pyx_CLEAR(r) do { PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);} while(0) +#define __Pyx_XCLEAR(r) do { if((r) != NULL) {PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);}} while(0) + +/* PyErrExceptionMatches.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_ExceptionMatches(err) __Pyx_PyErr_ExceptionMatchesInState(__pyx_tstate, err) +static CYTHON_INLINE int __Pyx_PyErr_ExceptionMatchesInState(PyThreadState* tstate, PyObject* err); +#else +#define __Pyx_PyErr_ExceptionMatches(err) PyErr_ExceptionMatches(err) +#endif + +/* PyThreadStateGet.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyThreadState_declare PyThreadState *__pyx_tstate; +#define __Pyx_PyThreadState_assign __pyx_tstate = __Pyx_PyThreadState_Current; +#if PY_VERSION_HEX >= 0x030C00A6 +#define __Pyx_PyErr_Occurred() (__pyx_tstate->current_exception != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->current_exception ? (PyObject*) Py_TYPE(__pyx_tstate->current_exception) : (PyObject*) NULL) +#else +#define __Pyx_PyErr_Occurred() (__pyx_tstate->curexc_type != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->curexc_type) +#endif +#else +#define __Pyx_PyThreadState_declare +#define __Pyx_PyThreadState_assign +#define __Pyx_PyErr_Occurred() (PyErr_Occurred() != NULL) +#define __Pyx_PyErr_CurrentExceptionType() PyErr_Occurred() +#endif + +/* PyErrFetchRestore.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_Clear() __Pyx_ErrRestore(NULL, NULL, NULL) +#define __Pyx_ErrRestoreWithState(type, value, tb) __Pyx_ErrRestoreInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) __Pyx_ErrFetchInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) __Pyx_ErrRestoreInState(__pyx_tstate, type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) __Pyx_ErrFetchInState(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb); +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A6 +#define __Pyx_PyErr_SetNone(exc) (Py_INCREF(exc), __Pyx_ErrRestore((exc), NULL, NULL)) +#else +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#endif +#else +#define __Pyx_PyErr_Clear() PyErr_Clear() +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#define __Pyx_ErrRestoreWithState(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestoreInState(tstate, type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchInState(tstate, type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) PyErr_Fetch(type, value, tb) +#endif + +/* PyObjectGetAttrStr.proto */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GetAttrStr(o,n) PyObject_GetAttr(o,n) +#endif + +/* PyObjectGetAttrStrNoError.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name); + +/* GetBuiltinName.proto */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name); + +/* GetTopmostException.proto */ +#if CYTHON_USE_EXC_INFO_STACK && CYTHON_FAST_THREAD_STATE +static _PyErr_StackItem * __Pyx_PyErr_GetTopmostException(PyThreadState *tstate); +#endif + +/* SaveResetException.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_ExceptionSave(type, value, tb) __Pyx__ExceptionSave(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx__ExceptionSave(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#define __Pyx_ExceptionReset(type, value, tb) __Pyx__ExceptionReset(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx__ExceptionReset(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb); +#else +#define __Pyx_ExceptionSave(type, value, tb) PyErr_GetExcInfo(type, value, tb) +#define __Pyx_ExceptionReset(type, value, tb) PyErr_SetExcInfo(type, value, tb) +#endif + +/* GetException.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_GetException(type, value, tb) __Pyx__GetException(__pyx_tstate, type, value, tb) +static int __Pyx__GetException(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#else +static int __Pyx_GetException(PyObject **type, PyObject **value, PyObject **tb); +#endif + +/* PyObjectCall.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw); +#else +#define __Pyx_PyObject_Call(func, arg, kw) PyObject_Call(func, arg, kw) +#endif + +/* RaiseException.proto */ +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause); + +/* PyDictVersioning.proto */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +#define __PYX_DICT_VERSION_INIT ((PY_UINT64_T) -1) +#define __PYX_GET_DICT_VERSION(dict) (((PyDictObject*)(dict))->ma_version_tag) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var)\ + (version_var) = __PYX_GET_DICT_VERSION(dict);\ + (cache_var) = (value); +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + if (likely(__PYX_GET_DICT_VERSION(DICT) == __pyx_dict_version)) {\ + (VAR) = __pyx_dict_cached_value;\ + } else {\ + (VAR) = __pyx_dict_cached_value = (LOOKUP);\ + __pyx_dict_version = __PYX_GET_DICT_VERSION(DICT);\ + }\ +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj); +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj); +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version); +#else +#define __PYX_GET_DICT_VERSION(dict) (0) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var) +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) (VAR) = (LOOKUP); +#endif + +/* GetModuleGlobalName.proto */ +#if CYTHON_USE_DICT_VERSIONS +#define __Pyx_GetModuleGlobalName(var, name) do {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + (var) = (likely(__pyx_dict_version == __PYX_GET_DICT_VERSION(__pyx_d))) ?\ + (likely(__pyx_dict_cached_value) ? __Pyx_NewRef(__pyx_dict_cached_value) : __Pyx_GetBuiltinName(name)) :\ + __Pyx__GetModuleGlobalName(name, &__pyx_dict_version, &__pyx_dict_cached_value);\ +} while(0) +#define __Pyx_GetModuleGlobalNameUncached(var, name) do {\ + PY_UINT64_T __pyx_dict_version;\ + PyObject *__pyx_dict_cached_value;\ + (var) = __Pyx__GetModuleGlobalName(name, &__pyx_dict_version, &__pyx_dict_cached_value);\ +} while(0) +static PyObject *__Pyx__GetModuleGlobalName(PyObject *name, PY_UINT64_T *dict_version, PyObject **dict_cached_value); +#else +#define __Pyx_GetModuleGlobalName(var, name) (var) = __Pyx__GetModuleGlobalName(name) +#define __Pyx_GetModuleGlobalNameUncached(var, name) (var) = __Pyx__GetModuleGlobalName(name) +static CYTHON_INLINE PyObject *__Pyx__GetModuleGlobalName(PyObject *name); +#endif + +/* PyFunctionFastCall.proto */ +#if CYTHON_FAST_PYCALL +#if !CYTHON_VECTORCALL +#define __Pyx_PyFunction_FastCall(func, args, nargs)\ + __Pyx_PyFunction_FastCallDict((func), (args), (nargs), NULL) +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs); +#endif +#define __Pyx_BUILD_ASSERT_EXPR(cond)\ + (sizeof(char [1 - 2*!(cond)]) - 1) +#ifndef Py_MEMBER_SIZE +#define Py_MEMBER_SIZE(type, member) sizeof(((type *)0)->member) +#endif +#if !CYTHON_VECTORCALL +#if PY_VERSION_HEX >= 0x03080000 + #include "frameobject.h" +#if PY_VERSION_HEX >= 0x030b00a6 && !CYTHON_COMPILING_IN_LIMITED_API + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif + #define __Pxy_PyFrame_Initialize_Offsets() + #define __Pyx_PyFrame_GetLocalsplus(frame) ((frame)->f_localsplus) +#else + static size_t __pyx_pyframe_localsplus_offset = 0; + #include "frameobject.h" + #define __Pxy_PyFrame_Initialize_Offsets()\ + ((void)__Pyx_BUILD_ASSERT_EXPR(sizeof(PyFrameObject) == offsetof(PyFrameObject, f_localsplus) + Py_MEMBER_SIZE(PyFrameObject, f_localsplus)),\ + (void)(__pyx_pyframe_localsplus_offset = ((size_t)PyFrame_Type.tp_basicsize) - Py_MEMBER_SIZE(PyFrameObject, f_localsplus))) + #define __Pyx_PyFrame_GetLocalsplus(frame)\ + (assert(__pyx_pyframe_localsplus_offset), (PyObject **)(((char *)(frame)) + __pyx_pyframe_localsplus_offset)) +#endif +#endif +#endif + +/* PyObjectCallMethO.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg); +#endif + +/* PyObjectFastCall.proto */ +#define __Pyx_PyObject_FastCall(func, args, nargs) __Pyx_PyObject_FastCallDict(func, args, (size_t)(nargs), NULL) +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs); + +/* ExtTypeTest.proto */ +static CYTHON_INLINE int __Pyx_TypeTest(PyObject *obj, PyTypeObject *type); + +/* IsLittleEndian.proto */ +static CYTHON_INLINE int __Pyx_Is_Little_Endian(void); + +/* BufferFormatCheck.proto */ +static const char* __Pyx_BufFmt_CheckString(__Pyx_BufFmt_Context* ctx, const char* ts); +static void __Pyx_BufFmt_Init(__Pyx_BufFmt_Context* ctx, + __Pyx_BufFmt_StackElem* stack, + __Pyx_TypeInfo* type); + +/* BufferGetAndValidate.proto */ +#define __Pyx_GetBufferAndValidate(buf, obj, dtype, flags, nd, cast, stack)\ + ((obj == Py_None || obj == NULL) ?\ + (__Pyx_ZeroBuffer(buf), 0) :\ + __Pyx__GetBufferAndValidate(buf, obj, dtype, flags, nd, cast, stack)) +static int __Pyx__GetBufferAndValidate(Py_buffer* buf, PyObject* obj, + __Pyx_TypeInfo* dtype, int flags, int nd, int cast, __Pyx_BufFmt_StackElem* stack); +static void __Pyx_ZeroBuffer(Py_buffer* buf); +static CYTHON_INLINE void __Pyx_SafeReleaseBuffer(Py_buffer* info); +static Py_ssize_t __Pyx_minusones[] = { -1, -1, -1, -1, -1, -1, -1, -1 }; +static Py_ssize_t __Pyx_zeros[] = { 0, 0, 0, 0, 0, 0, 0, 0 }; + +/* AssertionsEnabled.proto */ +#if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX < 0x02070600 && !defined(Py_OptimizeFlag) + #define __Pyx_init_assertions_enabled() (0) + #define __pyx_assertions_enabled() (1) +#elif CYTHON_COMPILING_IN_LIMITED_API || (CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030C0000) + static int __pyx_assertions_enabled_flag; + #define __pyx_assertions_enabled() (__pyx_assertions_enabled_flag) + static int __Pyx_init_assertions_enabled(void) { + PyObject *builtins, *debug, *debug_str; + int flag; + builtins = PyEval_GetBuiltins(); + if (!builtins) goto bad; + debug_str = PyUnicode_FromStringAndSize("__debug__", 9); + if (!debug_str) goto bad; + debug = PyObject_GetItem(builtins, debug_str); + Py_DECREF(debug_str); + if (!debug) goto bad; + flag = PyObject_IsTrue(debug); + Py_DECREF(debug); + if (flag == -1) goto bad; + __pyx_assertions_enabled_flag = flag; + return 0; + bad: + __pyx_assertions_enabled_flag = 1; + return -1; + } +#else + #define __Pyx_init_assertions_enabled() (0) + #define __pyx_assertions_enabled() (!Py_OptimizeFlag) +#endif + +/* GetItemInt.proto */ +#define __Pyx_GetItemInt(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_Fast(o, (Py_ssize_t)i, is_list, wraparound, boundscheck) :\ + (is_list ? (PyErr_SetString(PyExc_IndexError, "list index out of range"), (PyObject*)NULL) :\ + __Pyx_GetItemInt_Generic(o, to_py_func(i)))) +#define __Pyx_GetItemInt_List(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_List_Fast(o, (Py_ssize_t)i, wraparound, boundscheck) :\ + (PyErr_SetString(PyExc_IndexError, "list index out of range"), (PyObject*)NULL)) +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_List_Fast(PyObject *o, Py_ssize_t i, + int wraparound, int boundscheck); +#define __Pyx_GetItemInt_Tuple(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_Tuple_Fast(o, (Py_ssize_t)i, wraparound, boundscheck) :\ + (PyErr_SetString(PyExc_IndexError, "tuple index out of range"), (PyObject*)NULL)) +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Tuple_Fast(PyObject *o, Py_ssize_t i, + int wraparound, int boundscheck); +static PyObject *__Pyx_GetItemInt_Generic(PyObject *o, PyObject* j); +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Fast(PyObject *o, Py_ssize_t i, + int is_list, int wraparound, int boundscheck); + +/* TupleAndListFromArray.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n); +static CYTHON_INLINE PyObject* __Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n); +#endif + +/* IncludeStringH.proto */ +#include + +/* BytesEquals.proto */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals); + +/* UnicodeEquals.proto */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals); + +/* fastcall.proto */ +#if CYTHON_AVOID_BORROWED_REFS + #define __Pyx_Arg_VARARGS(args, i) PySequence_GetItem(args, i) +#elif CYTHON_ASSUME_SAFE_MACROS + #define __Pyx_Arg_VARARGS(args, i) PyTuple_GET_ITEM(args, i) +#else + #define __Pyx_Arg_VARARGS(args, i) PyTuple_GetItem(args, i) +#endif +#if CYTHON_AVOID_BORROWED_REFS + #define __Pyx_Arg_NewRef_VARARGS(arg) __Pyx_NewRef(arg) + #define __Pyx_Arg_XDECREF_VARARGS(arg) Py_XDECREF(arg) +#else + #define __Pyx_Arg_NewRef_VARARGS(arg) arg + #define __Pyx_Arg_XDECREF_VARARGS(arg) +#endif +#define __Pyx_NumKwargs_VARARGS(kwds) PyDict_Size(kwds) +#define __Pyx_KwValues_VARARGS(args, nargs) NULL +#define __Pyx_GetKwValue_VARARGS(kw, kwvalues, s) __Pyx_PyDict_GetItemStrWithError(kw, s) +#define __Pyx_KwargsAsDict_VARARGS(kw, kwvalues) PyDict_Copy(kw) +#if CYTHON_METH_FASTCALL + #define __Pyx_Arg_FASTCALL(args, i) args[i] + #define __Pyx_NumKwargs_FASTCALL(kwds) PyTuple_GET_SIZE(kwds) + #define __Pyx_KwValues_FASTCALL(args, nargs) ((args) + (nargs)) + static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 + CYTHON_UNUSED static PyObject *__Pyx_KwargsAsDict_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues); + #else + #define __Pyx_KwargsAsDict_FASTCALL(kw, kwvalues) _PyStack_AsDict(kwvalues, kw) + #endif + #define __Pyx_Arg_NewRef_FASTCALL(arg) arg /* no-op, __Pyx_Arg_FASTCALL is direct and this needs + to have the same reference counting */ + #define __Pyx_Arg_XDECREF_FASTCALL(arg) +#else + #define __Pyx_Arg_FASTCALL __Pyx_Arg_VARARGS + #define __Pyx_NumKwargs_FASTCALL __Pyx_NumKwargs_VARARGS + #define __Pyx_KwValues_FASTCALL __Pyx_KwValues_VARARGS + #define __Pyx_GetKwValue_FASTCALL __Pyx_GetKwValue_VARARGS + #define __Pyx_KwargsAsDict_FASTCALL __Pyx_KwargsAsDict_VARARGS + #define __Pyx_Arg_NewRef_FASTCALL(arg) __Pyx_Arg_NewRef_VARARGS(arg) + #define __Pyx_Arg_XDECREF_FASTCALL(arg) __Pyx_Arg_XDECREF_VARARGS(arg) +#endif +#if CYTHON_COMPILING_IN_CPYTHON && CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_VARARGS(args, start), stop - start) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_FASTCALL(args, start), stop - start) +#else +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) PyTuple_GetSlice(args, start, stop) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) PyTuple_GetSlice(args, start, stop) +#endif + +/* RaiseDoubleKeywords.proto */ +static void __Pyx_RaiseDoubleKeywordsError(const char* func_name, PyObject* kw_name); + +/* ParseKeywords.proto */ +static int __Pyx_ParseOptionalKeywords(PyObject *kwds, PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, PyObject *values[], Py_ssize_t num_pos_args, + const char* function_name); + +/* RaiseArgTupleInvalid.proto */ +static void __Pyx_RaiseArgtupleInvalid(const char* func_name, int exact, + Py_ssize_t num_min, Py_ssize_t num_max, Py_ssize_t num_found); + +/* MoveIfSupported.proto */ +#if CYTHON_USE_CPP_STD_MOVE + #include + #define __PYX_STD_MOVE_IF_SUPPORTED(x) std::move(x) +#else + #define __PYX_STD_MOVE_IF_SUPPORTED(x) x +#endif + +/* KeywordStringCheck.proto */ +static int __Pyx_CheckKeywordStrings(PyObject *kw, const char* function_name, int kw_allowed); + +/* IncludeStructmemberH.proto */ +#include + +/* FixUpExtensionType.proto */ +#if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type); +#endif + +/* PyObjectCallNoArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func); + +/* PyObjectCallOneArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg); + +/* PyObjectGetMethod.proto */ +static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method); + +/* PyObjectCallMethod0.proto */ +static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name); + +/* ValidateBasesTuple.proto */ +#if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases); +#endif + +/* PyType_Ready.proto */ +CYTHON_UNUSED static int __Pyx_PyType_Ready(PyTypeObject *t); + +/* PyObject_GenericGetAttrNoDict.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttrNoDict PyObject_GenericGetAttr +#endif + +/* PyObject_GenericGetAttr.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttr PyObject_GenericGetAttr +#endif + +/* SetupReduce.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce(PyObject* type_obj); +#endif + +/* TypeImport.proto */ +#ifndef __PYX_HAVE_RT_ImportType_proto_3_0_8 +#define __PYX_HAVE_RT_ImportType_proto_3_0_8 +#if defined (__STDC_VERSION__) && __STDC_VERSION__ >= 201112L +#include +#endif +#if (defined (__STDC_VERSION__) && __STDC_VERSION__ >= 201112L) || __cplusplus >= 201103L +#define __PYX_GET_STRUCT_ALIGNMENT_3_0_8(s) alignof(s) +#else +#define __PYX_GET_STRUCT_ALIGNMENT_3_0_8(s) sizeof(void*) +#endif +enum __Pyx_ImportType_CheckSize_3_0_8 { + __Pyx_ImportType_CheckSize_Error_3_0_8 = 0, + __Pyx_ImportType_CheckSize_Warn_3_0_8 = 1, + __Pyx_ImportType_CheckSize_Ignore_3_0_8 = 2 +}; +static PyTypeObject *__Pyx_ImportType_3_0_8(PyObject* module, const char *module_name, const char *class_name, size_t size, size_t alignment, enum __Pyx_ImportType_CheckSize_3_0_8 check_size); +#endif + +/* Import.proto */ +static PyObject *__Pyx_Import(PyObject *name, PyObject *from_list, int level); + +/* ImportDottedModule.proto */ +static PyObject *__Pyx_ImportDottedModule(PyObject *name, PyObject *parts_tuple); +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_ImportDottedModule_WalkParts(PyObject *module, PyObject *name, PyObject *parts_tuple); +#endif + +/* FetchSharedCythonModule.proto */ +static PyObject *__Pyx_FetchSharedCythonABIModule(void); + +/* FetchCommonType.proto */ +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type); +#else +static PyTypeObject* __Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases); +#endif + +/* PyMethodNew.proto */ +#if CYTHON_COMPILING_IN_LIMITED_API +static PyObject *__Pyx_PyMethod_New(PyObject *func, PyObject *self, PyObject *typ) { + PyObject *typesModule=NULL, *methodType=NULL, *result=NULL; + CYTHON_UNUSED_VAR(typ); + if (!self) + return __Pyx_NewRef(func); + typesModule = PyImport_ImportModule("types"); + if (!typesModule) return NULL; + methodType = PyObject_GetAttrString(typesModule, "MethodType"); + Py_DECREF(typesModule); + if (!methodType) return NULL; + result = PyObject_CallFunctionObjArgs(methodType, func, self, NULL); + Py_DECREF(methodType); + return result; +} +#elif PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_PyMethod_New(PyObject *func, PyObject *self, PyObject *typ) { + CYTHON_UNUSED_VAR(typ); + if (!self) + return __Pyx_NewRef(func); + return PyMethod_New(func, self); +} +#else + #define __Pyx_PyMethod_New PyMethod_New +#endif + +/* PyVectorcallFastCallDict.proto */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw); +#endif + +/* CythonFunctionShared.proto */ +#define __Pyx_CyFunction_USED +#define __Pyx_CYFUNCTION_STATICMETHOD 0x01 +#define __Pyx_CYFUNCTION_CLASSMETHOD 0x02 +#define __Pyx_CYFUNCTION_CCLASS 0x04 +#define __Pyx_CYFUNCTION_COROUTINE 0x08 +#define __Pyx_CyFunction_GetClosure(f)\ + (((__pyx_CyFunctionObject *) (f))->func_closure) +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_CyFunction_GetClassObj(f)\ + (((__pyx_CyFunctionObject *) (f))->func_classobj) +#else + #define __Pyx_CyFunction_GetClassObj(f)\ + ((PyObject*) ((PyCMethodObject *) (f))->mm_class) +#endif +#define __Pyx_CyFunction_SetClassObj(f, classobj)\ + __Pyx__CyFunction_SetClassObj((__pyx_CyFunctionObject *) (f), (classobj)) +#define __Pyx_CyFunction_Defaults(type, f)\ + ((type *)(((__pyx_CyFunctionObject *) (f))->defaults)) +#define __Pyx_CyFunction_SetDefaultsGetter(f, g)\ + ((__pyx_CyFunctionObject *) (f))->defaults_getter = (g) +typedef struct { +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject_HEAD + PyObject *func; +#elif PY_VERSION_HEX < 0x030900B1 + PyCFunctionObject func; +#else + PyCMethodObject func; +#endif +#if CYTHON_BACKPORT_VECTORCALL + __pyx_vectorcallfunc func_vectorcall; +#endif +#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API + PyObject *func_weakreflist; +#endif + PyObject *func_dict; + PyObject *func_name; + PyObject *func_qualname; + PyObject *func_doc; + PyObject *func_globals; + PyObject *func_code; + PyObject *func_closure; +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + PyObject *func_classobj; +#endif + void *defaults; + int defaults_pyobjects; + size_t defaults_size; + int flags; + PyObject *defaults_tuple; + PyObject *defaults_kwdict; + PyObject *(*defaults_getter)(PyObject *); + PyObject *func_annotations; + PyObject *func_is_coroutine; +} __pyx_CyFunctionObject; +#undef __Pyx_CyOrPyCFunction_Check +#define __Pyx_CyFunction_Check(obj) __Pyx_TypeCheck(obj, __pyx_CyFunctionType) +#define __Pyx_CyOrPyCFunction_Check(obj) __Pyx_TypeCheck2(obj, __pyx_CyFunctionType, &PyCFunction_Type) +#define __Pyx_CyFunction_CheckExact(obj) __Pyx_IS_TYPE(obj, __pyx_CyFunctionType) +static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc); +#undef __Pyx_IsSameCFunction +#define __Pyx_IsSameCFunction(func, cfunc) __Pyx__IsSameCyOrCFunction(func, cfunc) +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject* op, PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj); +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *m, + size_t size, + int pyobjects); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *m, + PyObject *tuple); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *m, + PyObject *dict); +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *m, + PyObject *dict); +static int __pyx_CyFunction_init(PyObject *module); +#if CYTHON_METH_FASTCALL +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +#if CYTHON_BACKPORT_VECTORCALL +#define __Pyx_CyFunction_func_vectorcall(f) (((__pyx_CyFunctionObject*)f)->func_vectorcall) +#else +#define __Pyx_CyFunction_func_vectorcall(f) (((PyCFunctionObject*)f)->vectorcall) +#endif +#endif + +/* CythonFunction.proto */ +static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); + +/* ClassMethod.proto */ +#include "descrobject.h" +CYTHON_UNUSED static PyObject* __Pyx_Method_ClassMethod(PyObject *method); + +/* GetNameInClass.proto */ +#define __Pyx_GetNameInClass(var, nmspace, name) (var) = __Pyx__GetNameInClass(nmspace, name) +static PyObject *__Pyx__GetNameInClass(PyObject *nmspace, PyObject *name); + +/* CLineInTraceback.proto */ +#ifdef CYTHON_CLINE_IN_TRACEBACK +#define __Pyx_CLineForTraceback(tstate, c_line) (((CYTHON_CLINE_IN_TRACEBACK)) ? c_line : 0) +#else +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line); +#endif + +/* CodeObjectCache.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +typedef struct { + PyCodeObject* code_object; + int code_line; +} __Pyx_CodeObjectCacheEntry; +struct __Pyx_CodeObjectCache { + int count; + int max_count; + __Pyx_CodeObjectCacheEntry* entries; +}; +static struct __Pyx_CodeObjectCache __pyx_code_cache = {0,0,NULL}; +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line); +static PyCodeObject *__pyx_find_code_object(int code_line); +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object); +#endif + +/* AddTraceback.proto */ +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename); + +/* BufferStructDeclare.proto */ +typedef struct { + Py_ssize_t shape, strides, suboffsets; +} __Pyx_Buf_DimInfo; +typedef struct { + size_t refcount; + Py_buffer pybuffer; +} __Pyx_Buffer; +typedef struct { + __Pyx_Buffer *rcbuffer; + char *data; + __Pyx_Buf_DimInfo diminfo[8]; +} __Pyx_LocalBuf_ND; + +#if PY_MAJOR_VERSION < 3 + static int __Pyx_GetBuffer(PyObject *obj, Py_buffer *view, int flags); + static void __Pyx_ReleaseBuffer(Py_buffer *view); +#else + #define __Pyx_GetBuffer PyObject_GetBuffer + #define __Pyx_ReleaseBuffer PyBuffer_Release +#endif + + +/* GCCDiagnostics.proto */ +#if !defined(__INTEL_COMPILER) && defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 6)) +#define __Pyx_HAS_GCC_DIAGNOSTIC +#endif + +/* RealImag.proto */ +#if CYTHON_CCOMPLEX + #ifdef __cplusplus + #define __Pyx_CREAL(z) ((z).real()) + #define __Pyx_CIMAG(z) ((z).imag()) + #else + #define __Pyx_CREAL(z) (__real__(z)) + #define __Pyx_CIMAG(z) (__imag__(z)) + #endif +#else + #define __Pyx_CREAL(z) ((z).real) + #define __Pyx_CIMAG(z) ((z).imag) +#endif +#if defined(__cplusplus) && CYTHON_CCOMPLEX\ + && (defined(_WIN32) || defined(__clang__) || (defined(__GNUC__) && (__GNUC__ >= 5 || __GNUC__ == 4 && __GNUC_MINOR__ >= 4 )) || __cplusplus >= 201103) + #define __Pyx_SET_CREAL(z,x) ((z).real(x)) + #define __Pyx_SET_CIMAG(z,y) ((z).imag(y)) +#else + #define __Pyx_SET_CREAL(z,x) __Pyx_CREAL(z) = (x) + #define __Pyx_SET_CIMAG(z,y) __Pyx_CIMAG(z) = (y) +#endif + +/* Arithmetic.proto */ +#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #define __Pyx_c_eq_float(a, b) ((a)==(b)) + #define __Pyx_c_sum_float(a, b) ((a)+(b)) + #define __Pyx_c_diff_float(a, b) ((a)-(b)) + #define __Pyx_c_prod_float(a, b) ((a)*(b)) + #define __Pyx_c_quot_float(a, b) ((a)/(b)) + #define __Pyx_c_neg_float(a) (-(a)) + #ifdef __cplusplus + #define __Pyx_c_is_zero_float(z) ((z)==(float)0) + #define __Pyx_c_conj_float(z) (::std::conj(z)) + #if 1 + #define __Pyx_c_abs_float(z) (::std::abs(z)) + #define __Pyx_c_pow_float(a, b) (::std::pow(a, b)) + #endif + #else + #define __Pyx_c_is_zero_float(z) ((z)==0) + #define __Pyx_c_conj_float(z) (conjf(z)) + #if 1 + #define __Pyx_c_abs_float(z) (cabsf(z)) + #define __Pyx_c_pow_float(a, b) (cpowf(a, b)) + #endif + #endif +#else + static CYTHON_INLINE int __Pyx_c_eq_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_sum_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_diff_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_prod_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_quot_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_neg_float(__pyx_t_float_complex); + static CYTHON_INLINE int __Pyx_c_is_zero_float(__pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_conj_float(__pyx_t_float_complex); + #if 1 + static CYTHON_INLINE float __Pyx_c_abs_float(__pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_pow_float(__pyx_t_float_complex, __pyx_t_float_complex); + #endif +#endif + +/* Arithmetic.proto */ +#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #define __Pyx_c_eq_double(a, b) ((a)==(b)) + #define __Pyx_c_sum_double(a, b) ((a)+(b)) + #define __Pyx_c_diff_double(a, b) ((a)-(b)) + #define __Pyx_c_prod_double(a, b) ((a)*(b)) + #define __Pyx_c_quot_double(a, b) ((a)/(b)) + #define __Pyx_c_neg_double(a) (-(a)) + #ifdef __cplusplus + #define __Pyx_c_is_zero_double(z) ((z)==(double)0) + #define __Pyx_c_conj_double(z) (::std::conj(z)) + #if 1 + #define __Pyx_c_abs_double(z) (::std::abs(z)) + #define __Pyx_c_pow_double(a, b) (::std::pow(a, b)) + #endif + #else + #define __Pyx_c_is_zero_double(z) ((z)==0) + #define __Pyx_c_conj_double(z) (conj(z)) + #if 1 + #define __Pyx_c_abs_double(z) (cabs(z)) + #define __Pyx_c_pow_double(a, b) (cpow(a, b)) + #endif + #endif +#else + static CYTHON_INLINE int __Pyx_c_eq_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_sum_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_diff_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_prod_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_quot_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_neg_double(__pyx_t_double_complex); + static CYTHON_INLINE int __Pyx_c_is_zero_double(__pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_conj_double(__pyx_t_double_complex); + #if 1 + static CYTHON_INLINE double __Pyx_c_abs_double(__pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_pow_double(__pyx_t_double_complex, __pyx_t_double_complex); + #endif +#endif + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value); + +/* FormatTypeName.proto */ +#if CYTHON_COMPILING_IN_LIMITED_API +typedef PyObject *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%U" +static __Pyx_TypeName __Pyx_PyType_GetName(PyTypeObject* tp); +#define __Pyx_DECREF_TypeName(obj) Py_XDECREF(obj) +#else +typedef const char *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%.200s" +#define __Pyx_PyType_GetName(tp) ((tp)->tp_name) +#define __Pyx_DECREF_TypeName(obj) +#endif + +/* CIntFromPy.proto */ +static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *); + +/* CIntFromPy.proto */ +static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *); + +/* FastTypeChecks.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_TypeCheck(obj, type) __Pyx_IsSubtype(Py_TYPE(obj), (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) __Pyx_IsAnySubtype2(Py_TYPE(obj), (PyTypeObject *)type1, (PyTypeObject *)type2) +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches(PyObject *err, PyObject *type); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches2(PyObject *err, PyObject *type1, PyObject *type2); +#else +#define __Pyx_TypeCheck(obj, type) PyObject_TypeCheck(obj, (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) (PyObject_TypeCheck(obj, (PyTypeObject *)type1) || PyObject_TypeCheck(obj, (PyTypeObject *)type2)) +#define __Pyx_PyErr_GivenExceptionMatches(err, type) PyErr_GivenExceptionMatches(err, type) +#define __Pyx_PyErr_GivenExceptionMatches2(err, type1, type2) (PyErr_GivenExceptionMatches(err, type1) || PyErr_GivenExceptionMatches(err, type2)) +#endif +#define __Pyx_PyErr_ExceptionMatches2(err1, err2) __Pyx_PyErr_GivenExceptionMatches2(__Pyx_PyErr_CurrentExceptionType(), err1, err2) +#define __Pyx_PyException_Check(obj) __Pyx_TypeCheck(obj, PyExc_Exception) + +/* CheckBinaryVersion.proto */ +static unsigned long __Pyx_get_runtime_version(void); +static int __Pyx_check_binary_version(unsigned long ct_version, unsigned long rt_version, int allow_newer); + +/* InitStrings.proto */ +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t); + +/* #### Code section: module_declarations ### */ +static CYTHON_INLINE PyObject *__pyx_f_5numpy_7ndarray_4base_base(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE PyArray_Descr *__pyx_f_5numpy_7ndarray_5descr_descr(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE int __pyx_f_5numpy_7ndarray_4ndim_ndim(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_5shape_shape(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_7strides_strides(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE npy_intp __pyx_f_5numpy_7ndarray_4size_size(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE char *__pyx_f_5numpy_7ndarray_4data_data(PyArrayObject *__pyx_v_self); /* proto*/ + +/* Module declarations from "libcpp" */ + +/* Module declarations from "openpilot.common.transformations.transformations" */ + +/* Module declarations from "libc.string" */ + +/* Module declarations from "libc.stdio" */ + +/* Module declarations from "__builtin__" */ + +/* Module declarations from "cpython.type" */ + +/* Module declarations from "cpython" */ + +/* Module declarations from "cpython.object" */ + +/* Module declarations from "cpython.ref" */ + +/* Module declarations from "numpy" */ + +/* Module declarations from "numpy" */ + +/* Module declarations from "common.transformations.transformations" */ +static PyArrayObject *__pyx_f_6common_15transformations_15transformations_matrix2numpy(Eigen::Matrix3d); /*proto*/ +static Eigen::Matrix3d __pyx_f_6common_15transformations_15transformations_numpy2matrix(PyArrayObject *); /*proto*/ +static struct ECEF __pyx_f_6common_15transformations_15transformations_list2ecef(PyObject *); /*proto*/ +static struct NED __pyx_f_6common_15transformations_15transformations_list2ned(PyObject *); /*proto*/ +static struct Geodetic __pyx_f_6common_15transformations_15transformations_list2geodetic(PyObject *); /*proto*/ +/* #### Code section: typeinfo ### */ +static __Pyx_TypeInfo __Pyx_TypeInfo_double = { "double", NULL, sizeof(double), { 0 }, 0, 'R', 0, 0 }; +/* #### Code section: before_global_var ### */ +#define __Pyx_MODULE_NAME "common.transformations.transformations" +extern int __pyx_module_is_main_common__transformations__transformations; +int __pyx_module_is_main_common__transformations__transformations = 0; + +/* Implementation of "common.transformations.transformations" */ +/* #### Code section: global_var ### */ +static PyObject *__pyx_builtin_AssertionError; +static PyObject *__pyx_builtin_TypeError; +static PyObject *__pyx_builtin_ImportError; +/* #### Code section: string_decls ### */ +static const char __pyx_k_e[] = "e"; +static const char __pyx_k_g[] = "g"; +static const char __pyx_k_n[] = "n"; +static const char __pyx_k_q[] = "q"; +static const char __pyx_k_r[] = "r"; +static const char __pyx_k__3[] = "*"; +static const char __pyx_k_gc[] = "gc"; +static const char __pyx_k_np[] = "np"; +static const char __pyx_k__42[] = "?"; +static const char __pyx_k_cls[] = "cls"; +static const char __pyx_k_ned[] = "ned"; +static const char __pyx_k_rot[] = "rot"; +static const char __pyx_k_yaw[] = "yaw"; +static const char __pyx_k_dict[] = "__dict__"; +static const char __pyx_k_ecef[] = "ecef"; +static const char __pyx_k_init[] = "init"; +static const char __pyx_k_main[] = "__main__"; +static const char __pyx_k_name[] = "__name__"; +static const char __pyx_k_pose[] = "pose"; +static const char __pyx_k_quat[] = "quat"; +static const char __pyx_k_roll[] = "roll"; +static const char __pyx_k_self[] = "self"; +static const char __pyx_k_spec[] = "__spec__"; +static const char __pyx_k_test[] = "__test__"; +static const char __pyx_k_array[] = "array"; +static const char __pyx_k_dtype[] = "dtype"; +static const char __pyx_k_euler[] = "euler"; +static const char __pyx_k_numpy[] = "numpy"; +static const char __pyx_k_pitch[] = "pitch"; +static const char __pyx_k_double[] = "double"; +static const char __pyx_k_enable[] = "enable"; +static const char __pyx_k_import[] = "__import__"; +static const char __pyx_k_reduce[] = "__reduce__"; +static const char __pyx_k_disable[] = "disable"; +static const char __pyx_k_geodetic[] = "geodetic"; +static const char __pyx_k_getstate[] = "__getstate__"; +static const char __pyx_k_ned_pose[] = "ned_pose"; +static const char __pyx_k_setstate[] = "__setstate__"; +static const char __pyx_k_TypeError[] = "TypeError"; +static const char __pyx_k_ecef_init[] = "ecef_init"; +static const char __pyx_k_ecef_pose[] = "ecef_pose"; +static const char __pyx_k_from_ecef[] = "from_ecef"; +static const char __pyx_k_isenabled[] = "isenabled"; +static const char __pyx_k_pyx_state[] = "__pyx_state"; +static const char __pyx_k_reduce_ex[] = "__reduce_ex__"; +static const char __pyx_k_LocalCoord[] = "LocalCoord"; +static const char __pyx_k_rot_matrix[] = "rot_matrix"; +static const char __pyx_k_ImportError[] = "ImportError"; +static const char __pyx_k_initializing[] = "_initializing"; +static const char __pyx_k_is_coroutine[] = "_is_coroutine"; +static const char __pyx_k_stringsource[] = ""; +static const char __pyx_k_from_geodetic[] = "from_geodetic"; +static const char __pyx_k_reduce_cython[] = "__reduce_cython__"; +static const char __pyx_k_AssertionError[] = "AssertionError"; +static const char __pyx_k_asfortranarray[] = "asfortranarray"; +static const char __pyx_k_ecef2ned_matrix[] = "ecef2ned_matrix"; +static const char __pyx_k_ecef2ned_single[] = "ecef2ned_single"; +static const char __pyx_k_ned2ecef_matrix[] = "ned2ecef_matrix"; +static const char __pyx_k_ned2ecef_single[] = "ned2ecef_single"; +static const char __pyx_k_quat2rot_single[] = "quat2rot_single"; +static const char __pyx_k_rot2quat_single[] = "rot2quat_single"; +static const char __pyx_k_setstate_cython[] = "__setstate_cython__"; +static const char __pyx_k_euler2rot_single[] = "euler2rot_single"; +static const char __pyx_k_rot2euler_single[] = "rot2euler_single"; +static const char __pyx_k_euler2quat_single[] = "euler2quat_single"; +static const char __pyx_k_quat2euler_single[] = "quat2euler_single"; +static const char __pyx_k_asyncio_coroutines[] = "asyncio.coroutines"; +static const char __pyx_k_cline_in_traceback[] = "cline_in_traceback"; +static const char __pyx_k_geodetic2ned_single[] = "geodetic2ned_single"; +static const char __pyx_k_ned2geodetic_single[] = "ned2geodetic_single"; +static const char __pyx_k_LocalCoord_from_ecef[] = "LocalCoord.from_ecef"; +static const char __pyx_k_ecef2geodetic_single[] = "ecef2geodetic_single"; +static const char __pyx_k_geodetic2ecef_single[] = "geodetic2ecef_single"; +static const char __pyx_k_LocalCoord_from_geodetic[] = "LocalCoord.from_geodetic"; +static const char __pyx_k_LocalCoord___reduce_cython[] = "LocalCoord.__reduce_cython__"; +static const char __pyx_k_LocalCoord_ecef2ned_single[] = "LocalCoord.ecef2ned_single"; +static const char __pyx_k_LocalCoord_ned2ecef_single[] = "LocalCoord.ned2ecef_single"; +static const char __pyx_k_ecef_euler_from_ned_single[] = "ecef_euler_from_ned_single"; +static const char __pyx_k_ned_euler_from_ecef_single[] = "ned_euler_from_ecef_single"; +static const char __pyx_k_LocalCoord___setstate_cython[] = "LocalCoord.__setstate_cython__"; +static const char __pyx_k_LocalCoord_geodetic2ned_single[] = "LocalCoord.geodetic2ned_single"; +static const char __pyx_k_LocalCoord_ned2geodetic_single[] = "LocalCoord.ned2geodetic_single"; +static const char __pyx_k_numpy_core_multiarray_failed_to[] = "numpy.core.multiarray failed to import"; +static const char __pyx_k_common_transformations_transform[] = "common/transformations/transformations.pyx"; +static const char __pyx_k_numpy_core_umath_failed_to_impor[] = "numpy.core.umath failed to import"; +static const char __pyx_k_self_lc_cannot_be_converted_to_a[] = "self.lc cannot be converted to a Python object for pickling"; +static const char __pyx_k_common_transformations_transform_2[] = "common.transformations.transformations"; +/* #### Code section: decls ### */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_euler2quat_single(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_euler); /* proto */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_2quat2euler_single(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_quat); /* proto */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_4quat2rot_single(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_quat); /* proto */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_6rot2quat_single(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_rot); /* proto */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_8euler2rot_single(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_euler); /* proto */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_10rot2euler_single(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_rot); /* proto */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_12rot_matrix(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_roll, PyObject *__pyx_v_pitch, PyObject *__pyx_v_yaw); /* proto */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_14ecef_euler_from_ned_single(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_ecef_init, PyObject *__pyx_v_ned_pose); /* proto */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_16ned_euler_from_ecef_single(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_ecef_init, PyObject *__pyx_v_ecef_pose); /* proto */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_18geodetic2ecef_single(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_geodetic); /* proto */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_20ecef2geodetic_single(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_ecef); /* proto */ +static int __pyx_pf_6common_15transformations_15transformations_10LocalCoord___init__(struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self, PyObject *__pyx_v_geodetic, PyObject *__pyx_v_ecef); /* proto */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_15ned2ecef_matrix___get__(struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_15ecef2ned_matrix___get__(struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_20ned_from_ecef_matrix___get__(struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_20ecef_from_ned_matrix___get__(struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_2from_geodetic(PyTypeObject *__pyx_v_cls, PyObject *__pyx_v_geodetic); /* proto */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_4from_ecef(PyTypeObject *__pyx_v_cls, PyObject *__pyx_v_ecef); /* proto */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_6ecef2ned_single(struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self, PyObject *__pyx_v_ecef); /* proto */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_8ned2ecef_single(struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self, PyObject *__pyx_v_ned); /* proto */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_10geodetic2ned_single(struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self, PyObject *__pyx_v_geodetic); /* proto */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_12ned2geodetic_single(struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self, PyObject *__pyx_v_ned); /* proto */ +static void __pyx_pf_6common_15transformations_15transformations_10LocalCoord_14__dealloc__(struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_16__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_18__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_tp_new_6common_15transformations_15transformations_LocalCoord(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +/* #### Code section: late_includes ### */ +/* #### Code section: module_state ### */ +typedef struct { + PyObject *__pyx_d; + PyObject *__pyx_b; + PyObject *__pyx_cython_runtime; + PyObject *__pyx_empty_tuple; + PyObject *__pyx_empty_bytes; + PyObject *__pyx_empty_unicode; + #ifdef __Pyx_CyFunction_USED + PyTypeObject *__pyx_CyFunctionType; + #endif + #ifdef __Pyx_FusedFunction_USED + PyTypeObject *__pyx_FusedFunctionType; + #endif + #ifdef __Pyx_Generator_USED + PyTypeObject *__pyx_GeneratorType; + #endif + #ifdef __Pyx_IterableCoroutine_USED + PyTypeObject *__pyx_IterableCoroutineType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineAwaitType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineType; + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + PyTypeObject *__pyx_ptype_7cpython_4type_type; + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + PyTypeObject *__pyx_ptype_5numpy_dtype; + PyTypeObject *__pyx_ptype_5numpy_flatiter; + PyTypeObject *__pyx_ptype_5numpy_broadcast; + PyTypeObject *__pyx_ptype_5numpy_ndarray; + PyTypeObject *__pyx_ptype_5numpy_generic; + PyTypeObject *__pyx_ptype_5numpy_number; + PyTypeObject *__pyx_ptype_5numpy_integer; + PyTypeObject *__pyx_ptype_5numpy_signedinteger; + PyTypeObject *__pyx_ptype_5numpy_unsignedinteger; + PyTypeObject *__pyx_ptype_5numpy_inexact; + PyTypeObject *__pyx_ptype_5numpy_floating; + PyTypeObject *__pyx_ptype_5numpy_complexfloating; + PyTypeObject *__pyx_ptype_5numpy_flexible; + PyTypeObject *__pyx_ptype_5numpy_character; + PyTypeObject *__pyx_ptype_5numpy_ufunc; + #if CYTHON_USE_MODULE_STATE + PyObject *__pyx_type_6common_15transformations_15transformations_LocalCoord; + #endif + PyTypeObject *__pyx_ptype_6common_15transformations_15transformations_LocalCoord; + PyObject *__pyx_n_s_AssertionError; + PyObject *__pyx_n_s_ImportError; + PyObject *__pyx_n_s_LocalCoord; + PyObject *__pyx_n_s_LocalCoord___reduce_cython; + PyObject *__pyx_n_s_LocalCoord___setstate_cython; + PyObject *__pyx_n_s_LocalCoord_ecef2ned_single; + PyObject *__pyx_n_s_LocalCoord_from_ecef; + PyObject *__pyx_n_s_LocalCoord_from_geodetic; + PyObject *__pyx_n_s_LocalCoord_geodetic2ned_single; + PyObject *__pyx_n_s_LocalCoord_ned2ecef_single; + PyObject *__pyx_n_s_LocalCoord_ned2geodetic_single; + PyObject *__pyx_n_s_TypeError; + PyObject *__pyx_n_s__3; + PyObject *__pyx_n_s__42; + PyObject *__pyx_n_s_array; + PyObject *__pyx_n_s_asfortranarray; + PyObject *__pyx_n_s_asyncio_coroutines; + PyObject *__pyx_n_s_cline_in_traceback; + PyObject *__pyx_n_s_cls; + PyObject *__pyx_kp_s_common_transformations_transform; + PyObject *__pyx_n_s_common_transformations_transform_2; + PyObject *__pyx_n_s_dict; + PyObject *__pyx_kp_u_disable; + PyObject *__pyx_n_s_double; + PyObject *__pyx_n_s_dtype; + PyObject *__pyx_n_s_e; + PyObject *__pyx_n_s_ecef; + PyObject *__pyx_n_s_ecef2geodetic_single; + PyObject *__pyx_n_s_ecef2ned_matrix; + PyObject *__pyx_n_s_ecef2ned_single; + PyObject *__pyx_n_s_ecef_euler_from_ned_single; + PyObject *__pyx_n_s_ecef_init; + PyObject *__pyx_n_s_ecef_pose; + PyObject *__pyx_kp_u_enable; + PyObject *__pyx_n_s_euler; + PyObject *__pyx_n_s_euler2quat_single; + PyObject *__pyx_n_s_euler2rot_single; + PyObject *__pyx_n_s_from_ecef; + PyObject *__pyx_n_s_from_geodetic; + PyObject *__pyx_n_s_g; + PyObject *__pyx_kp_u_gc; + PyObject *__pyx_n_s_geodetic; + PyObject *__pyx_n_s_geodetic2ecef_single; + PyObject *__pyx_n_s_geodetic2ned_single; + PyObject *__pyx_n_s_getstate; + PyObject *__pyx_n_s_import; + PyObject *__pyx_n_s_init; + PyObject *__pyx_n_s_initializing; + PyObject *__pyx_n_s_is_coroutine; + PyObject *__pyx_kp_u_isenabled; + PyObject *__pyx_n_s_main; + PyObject *__pyx_n_s_n; + PyObject *__pyx_n_s_name; + PyObject *__pyx_n_s_ned; + PyObject *__pyx_n_s_ned2ecef_matrix; + PyObject *__pyx_n_s_ned2ecef_single; + PyObject *__pyx_n_s_ned2geodetic_single; + PyObject *__pyx_n_s_ned_euler_from_ecef_single; + PyObject *__pyx_n_s_ned_pose; + PyObject *__pyx_n_s_np; + PyObject *__pyx_n_s_numpy; + PyObject *__pyx_kp_u_numpy_core_multiarray_failed_to; + PyObject *__pyx_kp_u_numpy_core_umath_failed_to_impor; + PyObject *__pyx_n_s_pitch; + PyObject *__pyx_n_s_pose; + PyObject *__pyx_n_s_pyx_state; + PyObject *__pyx_n_s_q; + PyObject *__pyx_n_s_quat; + PyObject *__pyx_n_s_quat2euler_single; + PyObject *__pyx_n_s_quat2rot_single; + PyObject *__pyx_n_s_r; + PyObject *__pyx_n_s_reduce; + PyObject *__pyx_n_s_reduce_cython; + PyObject *__pyx_n_s_reduce_ex; + PyObject *__pyx_n_s_roll; + PyObject *__pyx_n_s_rot; + PyObject *__pyx_n_s_rot2euler_single; + PyObject *__pyx_n_s_rot2quat_single; + PyObject *__pyx_n_s_rot_matrix; + PyObject *__pyx_n_s_self; + PyObject *__pyx_kp_s_self_lc_cannot_be_converted_to_a; + PyObject *__pyx_n_s_setstate; + PyObject *__pyx_n_s_setstate_cython; + PyObject *__pyx_n_s_spec; + PyObject *__pyx_kp_s_stringsource; + PyObject *__pyx_n_s_test; + PyObject *__pyx_n_s_yaw; + PyObject *__pyx_tuple_; + PyObject *__pyx_tuple__2; + PyObject *__pyx_tuple__4; + PyObject *__pyx_tuple__6; + PyObject *__pyx_tuple__8; + PyObject *__pyx_tuple__10; + PyObject *__pyx_tuple__12; + PyObject *__pyx_tuple__14; + PyObject *__pyx_tuple__16; + PyObject *__pyx_tuple__18; + PyObject *__pyx_tuple__20; + PyObject *__pyx_tuple__22; + PyObject *__pyx_tuple__24; + PyObject *__pyx_tuple__26; + PyObject *__pyx_tuple__28; + PyObject *__pyx_tuple__30; + PyObject *__pyx_tuple__32; + PyObject *__pyx_tuple__34; + PyObject *__pyx_tuple__36; + PyObject *__pyx_tuple__38; + PyObject *__pyx_tuple__40; + PyObject *__pyx_codeobj__5; + PyObject *__pyx_codeobj__7; + PyObject *__pyx_codeobj__9; + PyObject *__pyx_codeobj__11; + PyObject *__pyx_codeobj__13; + PyObject *__pyx_codeobj__15; + PyObject *__pyx_codeobj__17; + PyObject *__pyx_codeobj__19; + PyObject *__pyx_codeobj__21; + PyObject *__pyx_codeobj__23; + PyObject *__pyx_codeobj__25; + PyObject *__pyx_codeobj__27; + PyObject *__pyx_codeobj__29; + PyObject *__pyx_codeobj__31; + PyObject *__pyx_codeobj__33; + PyObject *__pyx_codeobj__35; + PyObject *__pyx_codeobj__37; + PyObject *__pyx_codeobj__39; + PyObject *__pyx_codeobj__41; +} __pyx_mstate; + +#if CYTHON_USE_MODULE_STATE +#ifdef __cplusplus +namespace { + extern struct PyModuleDef __pyx_moduledef; +} /* anonymous namespace */ +#else +static struct PyModuleDef __pyx_moduledef; +#endif + +#define __pyx_mstate(o) ((__pyx_mstate *)__Pyx_PyModule_GetState(o)) + +#define __pyx_mstate_global (__pyx_mstate(PyState_FindModule(&__pyx_moduledef))) + +#define __pyx_m (PyState_FindModule(&__pyx_moduledef)) +#else +static __pyx_mstate __pyx_mstate_global_static = +#ifdef __cplusplus + {}; +#else + {0}; +#endif +static __pyx_mstate *__pyx_mstate_global = &__pyx_mstate_global_static; +#endif +/* #### Code section: module_state_clear ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_clear(PyObject *m) { + __pyx_mstate *clear_module_state = __pyx_mstate(m); + if (!clear_module_state) return 0; + Py_CLEAR(clear_module_state->__pyx_d); + Py_CLEAR(clear_module_state->__pyx_b); + Py_CLEAR(clear_module_state->__pyx_cython_runtime); + Py_CLEAR(clear_module_state->__pyx_empty_tuple); + Py_CLEAR(clear_module_state->__pyx_empty_bytes); + Py_CLEAR(clear_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_CLEAR(clear_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_CLEAR(clear_module_state->__pyx_FusedFunctionType); + #endif + Py_CLEAR(clear_module_state->__pyx_ptype_7cpython_4type_type); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_dtype); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_flatiter); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_broadcast); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_ndarray); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_generic); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_number); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_integer); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_signedinteger); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_unsignedinteger); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_inexact); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_floating); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_complexfloating); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_flexible); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_character); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_ufunc); + Py_CLEAR(clear_module_state->__pyx_ptype_6common_15transformations_15transformations_LocalCoord); + Py_CLEAR(clear_module_state->__pyx_type_6common_15transformations_15transformations_LocalCoord); + Py_CLEAR(clear_module_state->__pyx_n_s_AssertionError); + Py_CLEAR(clear_module_state->__pyx_n_s_ImportError); + Py_CLEAR(clear_module_state->__pyx_n_s_LocalCoord); + Py_CLEAR(clear_module_state->__pyx_n_s_LocalCoord___reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_LocalCoord___setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_LocalCoord_ecef2ned_single); + Py_CLEAR(clear_module_state->__pyx_n_s_LocalCoord_from_ecef); + Py_CLEAR(clear_module_state->__pyx_n_s_LocalCoord_from_geodetic); + Py_CLEAR(clear_module_state->__pyx_n_s_LocalCoord_geodetic2ned_single); + Py_CLEAR(clear_module_state->__pyx_n_s_LocalCoord_ned2ecef_single); + Py_CLEAR(clear_module_state->__pyx_n_s_LocalCoord_ned2geodetic_single); + Py_CLEAR(clear_module_state->__pyx_n_s_TypeError); + Py_CLEAR(clear_module_state->__pyx_n_s__3); + Py_CLEAR(clear_module_state->__pyx_n_s__42); + Py_CLEAR(clear_module_state->__pyx_n_s_array); + Py_CLEAR(clear_module_state->__pyx_n_s_asfortranarray); + Py_CLEAR(clear_module_state->__pyx_n_s_asyncio_coroutines); + Py_CLEAR(clear_module_state->__pyx_n_s_cline_in_traceback); + Py_CLEAR(clear_module_state->__pyx_n_s_cls); + Py_CLEAR(clear_module_state->__pyx_kp_s_common_transformations_transform); + Py_CLEAR(clear_module_state->__pyx_n_s_common_transformations_transform_2); + Py_CLEAR(clear_module_state->__pyx_n_s_dict); + Py_CLEAR(clear_module_state->__pyx_kp_u_disable); + Py_CLEAR(clear_module_state->__pyx_n_s_double); + Py_CLEAR(clear_module_state->__pyx_n_s_dtype); + Py_CLEAR(clear_module_state->__pyx_n_s_e); + Py_CLEAR(clear_module_state->__pyx_n_s_ecef); + Py_CLEAR(clear_module_state->__pyx_n_s_ecef2geodetic_single); + Py_CLEAR(clear_module_state->__pyx_n_s_ecef2ned_matrix); + Py_CLEAR(clear_module_state->__pyx_n_s_ecef2ned_single); + Py_CLEAR(clear_module_state->__pyx_n_s_ecef_euler_from_ned_single); + Py_CLEAR(clear_module_state->__pyx_n_s_ecef_init); + Py_CLEAR(clear_module_state->__pyx_n_s_ecef_pose); + Py_CLEAR(clear_module_state->__pyx_kp_u_enable); + Py_CLEAR(clear_module_state->__pyx_n_s_euler); + Py_CLEAR(clear_module_state->__pyx_n_s_euler2quat_single); + Py_CLEAR(clear_module_state->__pyx_n_s_euler2rot_single); + Py_CLEAR(clear_module_state->__pyx_n_s_from_ecef); + Py_CLEAR(clear_module_state->__pyx_n_s_from_geodetic); + Py_CLEAR(clear_module_state->__pyx_n_s_g); + Py_CLEAR(clear_module_state->__pyx_kp_u_gc); + Py_CLEAR(clear_module_state->__pyx_n_s_geodetic); + Py_CLEAR(clear_module_state->__pyx_n_s_geodetic2ecef_single); + Py_CLEAR(clear_module_state->__pyx_n_s_geodetic2ned_single); + Py_CLEAR(clear_module_state->__pyx_n_s_getstate); + Py_CLEAR(clear_module_state->__pyx_n_s_import); + Py_CLEAR(clear_module_state->__pyx_n_s_init); + Py_CLEAR(clear_module_state->__pyx_n_s_initializing); + Py_CLEAR(clear_module_state->__pyx_n_s_is_coroutine); + Py_CLEAR(clear_module_state->__pyx_kp_u_isenabled); + Py_CLEAR(clear_module_state->__pyx_n_s_main); + Py_CLEAR(clear_module_state->__pyx_n_s_n); + Py_CLEAR(clear_module_state->__pyx_n_s_name); + Py_CLEAR(clear_module_state->__pyx_n_s_ned); + Py_CLEAR(clear_module_state->__pyx_n_s_ned2ecef_matrix); + Py_CLEAR(clear_module_state->__pyx_n_s_ned2ecef_single); + Py_CLEAR(clear_module_state->__pyx_n_s_ned2geodetic_single); + Py_CLEAR(clear_module_state->__pyx_n_s_ned_euler_from_ecef_single); + Py_CLEAR(clear_module_state->__pyx_n_s_ned_pose); + Py_CLEAR(clear_module_state->__pyx_n_s_np); + Py_CLEAR(clear_module_state->__pyx_n_s_numpy); + Py_CLEAR(clear_module_state->__pyx_kp_u_numpy_core_multiarray_failed_to); + Py_CLEAR(clear_module_state->__pyx_kp_u_numpy_core_umath_failed_to_impor); + Py_CLEAR(clear_module_state->__pyx_n_s_pitch); + Py_CLEAR(clear_module_state->__pyx_n_s_pose); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_state); + Py_CLEAR(clear_module_state->__pyx_n_s_q); + Py_CLEAR(clear_module_state->__pyx_n_s_quat); + Py_CLEAR(clear_module_state->__pyx_n_s_quat2euler_single); + Py_CLEAR(clear_module_state->__pyx_n_s_quat2rot_single); + Py_CLEAR(clear_module_state->__pyx_n_s_r); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_ex); + Py_CLEAR(clear_module_state->__pyx_n_s_roll); + Py_CLEAR(clear_module_state->__pyx_n_s_rot); + Py_CLEAR(clear_module_state->__pyx_n_s_rot2euler_single); + Py_CLEAR(clear_module_state->__pyx_n_s_rot2quat_single); + Py_CLEAR(clear_module_state->__pyx_n_s_rot_matrix); + Py_CLEAR(clear_module_state->__pyx_n_s_self); + Py_CLEAR(clear_module_state->__pyx_kp_s_self_lc_cannot_be_converted_to_a); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_spec); + Py_CLEAR(clear_module_state->__pyx_kp_s_stringsource); + Py_CLEAR(clear_module_state->__pyx_n_s_test); + Py_CLEAR(clear_module_state->__pyx_n_s_yaw); + Py_CLEAR(clear_module_state->__pyx_tuple_); + Py_CLEAR(clear_module_state->__pyx_tuple__2); + Py_CLEAR(clear_module_state->__pyx_tuple__4); + Py_CLEAR(clear_module_state->__pyx_tuple__6); + Py_CLEAR(clear_module_state->__pyx_tuple__8); + Py_CLEAR(clear_module_state->__pyx_tuple__10); + Py_CLEAR(clear_module_state->__pyx_tuple__12); + Py_CLEAR(clear_module_state->__pyx_tuple__14); + Py_CLEAR(clear_module_state->__pyx_tuple__16); + Py_CLEAR(clear_module_state->__pyx_tuple__18); + Py_CLEAR(clear_module_state->__pyx_tuple__20); + Py_CLEAR(clear_module_state->__pyx_tuple__22); + Py_CLEAR(clear_module_state->__pyx_tuple__24); + Py_CLEAR(clear_module_state->__pyx_tuple__26); + Py_CLEAR(clear_module_state->__pyx_tuple__28); + Py_CLEAR(clear_module_state->__pyx_tuple__30); + Py_CLEAR(clear_module_state->__pyx_tuple__32); + Py_CLEAR(clear_module_state->__pyx_tuple__34); + Py_CLEAR(clear_module_state->__pyx_tuple__36); + Py_CLEAR(clear_module_state->__pyx_tuple__38); + Py_CLEAR(clear_module_state->__pyx_tuple__40); + Py_CLEAR(clear_module_state->__pyx_codeobj__5); + Py_CLEAR(clear_module_state->__pyx_codeobj__7); + Py_CLEAR(clear_module_state->__pyx_codeobj__9); + Py_CLEAR(clear_module_state->__pyx_codeobj__11); + Py_CLEAR(clear_module_state->__pyx_codeobj__13); + Py_CLEAR(clear_module_state->__pyx_codeobj__15); + Py_CLEAR(clear_module_state->__pyx_codeobj__17); + Py_CLEAR(clear_module_state->__pyx_codeobj__19); + Py_CLEAR(clear_module_state->__pyx_codeobj__21); + Py_CLEAR(clear_module_state->__pyx_codeobj__23); + Py_CLEAR(clear_module_state->__pyx_codeobj__25); + Py_CLEAR(clear_module_state->__pyx_codeobj__27); + Py_CLEAR(clear_module_state->__pyx_codeobj__29); + Py_CLEAR(clear_module_state->__pyx_codeobj__31); + Py_CLEAR(clear_module_state->__pyx_codeobj__33); + Py_CLEAR(clear_module_state->__pyx_codeobj__35); + Py_CLEAR(clear_module_state->__pyx_codeobj__37); + Py_CLEAR(clear_module_state->__pyx_codeobj__39); + Py_CLEAR(clear_module_state->__pyx_codeobj__41); + return 0; +} +#endif +/* #### Code section: module_state_traverse ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { + __pyx_mstate *traverse_module_state = __pyx_mstate(m); + if (!traverse_module_state) return 0; + Py_VISIT(traverse_module_state->__pyx_d); + Py_VISIT(traverse_module_state->__pyx_b); + Py_VISIT(traverse_module_state->__pyx_cython_runtime); + Py_VISIT(traverse_module_state->__pyx_empty_tuple); + Py_VISIT(traverse_module_state->__pyx_empty_bytes); + Py_VISIT(traverse_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_VISIT(traverse_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_VISIT(traverse_module_state->__pyx_FusedFunctionType); + #endif + Py_VISIT(traverse_module_state->__pyx_ptype_7cpython_4type_type); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_dtype); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_flatiter); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_broadcast); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_ndarray); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_generic); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_number); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_integer); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_signedinteger); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_unsignedinteger); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_inexact); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_floating); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_complexfloating); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_flexible); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_character); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_ufunc); + Py_VISIT(traverse_module_state->__pyx_ptype_6common_15transformations_15transformations_LocalCoord); + Py_VISIT(traverse_module_state->__pyx_type_6common_15transformations_15transformations_LocalCoord); + Py_VISIT(traverse_module_state->__pyx_n_s_AssertionError); + Py_VISIT(traverse_module_state->__pyx_n_s_ImportError); + Py_VISIT(traverse_module_state->__pyx_n_s_LocalCoord); + Py_VISIT(traverse_module_state->__pyx_n_s_LocalCoord___reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_LocalCoord___setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_LocalCoord_ecef2ned_single); + Py_VISIT(traverse_module_state->__pyx_n_s_LocalCoord_from_ecef); + Py_VISIT(traverse_module_state->__pyx_n_s_LocalCoord_from_geodetic); + Py_VISIT(traverse_module_state->__pyx_n_s_LocalCoord_geodetic2ned_single); + Py_VISIT(traverse_module_state->__pyx_n_s_LocalCoord_ned2ecef_single); + Py_VISIT(traverse_module_state->__pyx_n_s_LocalCoord_ned2geodetic_single); + Py_VISIT(traverse_module_state->__pyx_n_s_TypeError); + Py_VISIT(traverse_module_state->__pyx_n_s__3); + Py_VISIT(traverse_module_state->__pyx_n_s__42); + Py_VISIT(traverse_module_state->__pyx_n_s_array); + Py_VISIT(traverse_module_state->__pyx_n_s_asfortranarray); + Py_VISIT(traverse_module_state->__pyx_n_s_asyncio_coroutines); + Py_VISIT(traverse_module_state->__pyx_n_s_cline_in_traceback); + Py_VISIT(traverse_module_state->__pyx_n_s_cls); + Py_VISIT(traverse_module_state->__pyx_kp_s_common_transformations_transform); + Py_VISIT(traverse_module_state->__pyx_n_s_common_transformations_transform_2); + Py_VISIT(traverse_module_state->__pyx_n_s_dict); + Py_VISIT(traverse_module_state->__pyx_kp_u_disable); + Py_VISIT(traverse_module_state->__pyx_n_s_double); + Py_VISIT(traverse_module_state->__pyx_n_s_dtype); + Py_VISIT(traverse_module_state->__pyx_n_s_e); + Py_VISIT(traverse_module_state->__pyx_n_s_ecef); + Py_VISIT(traverse_module_state->__pyx_n_s_ecef2geodetic_single); + Py_VISIT(traverse_module_state->__pyx_n_s_ecef2ned_matrix); + Py_VISIT(traverse_module_state->__pyx_n_s_ecef2ned_single); + Py_VISIT(traverse_module_state->__pyx_n_s_ecef_euler_from_ned_single); + Py_VISIT(traverse_module_state->__pyx_n_s_ecef_init); + Py_VISIT(traverse_module_state->__pyx_n_s_ecef_pose); + Py_VISIT(traverse_module_state->__pyx_kp_u_enable); + Py_VISIT(traverse_module_state->__pyx_n_s_euler); + Py_VISIT(traverse_module_state->__pyx_n_s_euler2quat_single); + Py_VISIT(traverse_module_state->__pyx_n_s_euler2rot_single); + Py_VISIT(traverse_module_state->__pyx_n_s_from_ecef); + Py_VISIT(traverse_module_state->__pyx_n_s_from_geodetic); + Py_VISIT(traverse_module_state->__pyx_n_s_g); + Py_VISIT(traverse_module_state->__pyx_kp_u_gc); + Py_VISIT(traverse_module_state->__pyx_n_s_geodetic); + Py_VISIT(traverse_module_state->__pyx_n_s_geodetic2ecef_single); + Py_VISIT(traverse_module_state->__pyx_n_s_geodetic2ned_single); + Py_VISIT(traverse_module_state->__pyx_n_s_getstate); + Py_VISIT(traverse_module_state->__pyx_n_s_import); + Py_VISIT(traverse_module_state->__pyx_n_s_init); + Py_VISIT(traverse_module_state->__pyx_n_s_initializing); + Py_VISIT(traverse_module_state->__pyx_n_s_is_coroutine); + Py_VISIT(traverse_module_state->__pyx_kp_u_isenabled); + Py_VISIT(traverse_module_state->__pyx_n_s_main); + Py_VISIT(traverse_module_state->__pyx_n_s_n); + Py_VISIT(traverse_module_state->__pyx_n_s_name); + Py_VISIT(traverse_module_state->__pyx_n_s_ned); + Py_VISIT(traverse_module_state->__pyx_n_s_ned2ecef_matrix); + Py_VISIT(traverse_module_state->__pyx_n_s_ned2ecef_single); + Py_VISIT(traverse_module_state->__pyx_n_s_ned2geodetic_single); + Py_VISIT(traverse_module_state->__pyx_n_s_ned_euler_from_ecef_single); + Py_VISIT(traverse_module_state->__pyx_n_s_ned_pose); + Py_VISIT(traverse_module_state->__pyx_n_s_np); + Py_VISIT(traverse_module_state->__pyx_n_s_numpy); + Py_VISIT(traverse_module_state->__pyx_kp_u_numpy_core_multiarray_failed_to); + Py_VISIT(traverse_module_state->__pyx_kp_u_numpy_core_umath_failed_to_impor); + Py_VISIT(traverse_module_state->__pyx_n_s_pitch); + Py_VISIT(traverse_module_state->__pyx_n_s_pose); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_state); + Py_VISIT(traverse_module_state->__pyx_n_s_q); + Py_VISIT(traverse_module_state->__pyx_n_s_quat); + Py_VISIT(traverse_module_state->__pyx_n_s_quat2euler_single); + Py_VISIT(traverse_module_state->__pyx_n_s_quat2rot_single); + Py_VISIT(traverse_module_state->__pyx_n_s_r); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_ex); + Py_VISIT(traverse_module_state->__pyx_n_s_roll); + Py_VISIT(traverse_module_state->__pyx_n_s_rot); + Py_VISIT(traverse_module_state->__pyx_n_s_rot2euler_single); + Py_VISIT(traverse_module_state->__pyx_n_s_rot2quat_single); + Py_VISIT(traverse_module_state->__pyx_n_s_rot_matrix); + Py_VISIT(traverse_module_state->__pyx_n_s_self); + Py_VISIT(traverse_module_state->__pyx_kp_s_self_lc_cannot_be_converted_to_a); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_spec); + Py_VISIT(traverse_module_state->__pyx_kp_s_stringsource); + Py_VISIT(traverse_module_state->__pyx_n_s_test); + Py_VISIT(traverse_module_state->__pyx_n_s_yaw); + Py_VISIT(traverse_module_state->__pyx_tuple_); + Py_VISIT(traverse_module_state->__pyx_tuple__2); + Py_VISIT(traverse_module_state->__pyx_tuple__4); + Py_VISIT(traverse_module_state->__pyx_tuple__6); + Py_VISIT(traverse_module_state->__pyx_tuple__8); + Py_VISIT(traverse_module_state->__pyx_tuple__10); + Py_VISIT(traverse_module_state->__pyx_tuple__12); + Py_VISIT(traverse_module_state->__pyx_tuple__14); + Py_VISIT(traverse_module_state->__pyx_tuple__16); + Py_VISIT(traverse_module_state->__pyx_tuple__18); + Py_VISIT(traverse_module_state->__pyx_tuple__20); + Py_VISIT(traverse_module_state->__pyx_tuple__22); + Py_VISIT(traverse_module_state->__pyx_tuple__24); + Py_VISIT(traverse_module_state->__pyx_tuple__26); + Py_VISIT(traverse_module_state->__pyx_tuple__28); + Py_VISIT(traverse_module_state->__pyx_tuple__30); + Py_VISIT(traverse_module_state->__pyx_tuple__32); + Py_VISIT(traverse_module_state->__pyx_tuple__34); + Py_VISIT(traverse_module_state->__pyx_tuple__36); + Py_VISIT(traverse_module_state->__pyx_tuple__38); + Py_VISIT(traverse_module_state->__pyx_tuple__40); + Py_VISIT(traverse_module_state->__pyx_codeobj__5); + Py_VISIT(traverse_module_state->__pyx_codeobj__7); + Py_VISIT(traverse_module_state->__pyx_codeobj__9); + Py_VISIT(traverse_module_state->__pyx_codeobj__11); + Py_VISIT(traverse_module_state->__pyx_codeobj__13); + Py_VISIT(traverse_module_state->__pyx_codeobj__15); + Py_VISIT(traverse_module_state->__pyx_codeobj__17); + Py_VISIT(traverse_module_state->__pyx_codeobj__19); + Py_VISIT(traverse_module_state->__pyx_codeobj__21); + Py_VISIT(traverse_module_state->__pyx_codeobj__23); + Py_VISIT(traverse_module_state->__pyx_codeobj__25); + Py_VISIT(traverse_module_state->__pyx_codeobj__27); + Py_VISIT(traverse_module_state->__pyx_codeobj__29); + Py_VISIT(traverse_module_state->__pyx_codeobj__31); + Py_VISIT(traverse_module_state->__pyx_codeobj__33); + Py_VISIT(traverse_module_state->__pyx_codeobj__35); + Py_VISIT(traverse_module_state->__pyx_codeobj__37); + Py_VISIT(traverse_module_state->__pyx_codeobj__39); + Py_VISIT(traverse_module_state->__pyx_codeobj__41); + return 0; +} +#endif +/* #### Code section: module_state_defines ### */ +#define __pyx_d __pyx_mstate_global->__pyx_d +#define __pyx_b __pyx_mstate_global->__pyx_b +#define __pyx_cython_runtime __pyx_mstate_global->__pyx_cython_runtime +#define __pyx_empty_tuple __pyx_mstate_global->__pyx_empty_tuple +#define __pyx_empty_bytes __pyx_mstate_global->__pyx_empty_bytes +#define __pyx_empty_unicode __pyx_mstate_global->__pyx_empty_unicode +#ifdef __Pyx_CyFunction_USED +#define __pyx_CyFunctionType __pyx_mstate_global->__pyx_CyFunctionType +#endif +#ifdef __Pyx_FusedFunction_USED +#define __pyx_FusedFunctionType __pyx_mstate_global->__pyx_FusedFunctionType +#endif +#ifdef __Pyx_Generator_USED +#define __pyx_GeneratorType __pyx_mstate_global->__pyx_GeneratorType +#endif +#ifdef __Pyx_IterableCoroutine_USED +#define __pyx_IterableCoroutineType __pyx_mstate_global->__pyx_IterableCoroutineType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineAwaitType __pyx_mstate_global->__pyx_CoroutineAwaitType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineType __pyx_mstate_global->__pyx_CoroutineType +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#define __pyx_ptype_7cpython_4type_type __pyx_mstate_global->__pyx_ptype_7cpython_4type_type +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#define __pyx_ptype_5numpy_dtype __pyx_mstate_global->__pyx_ptype_5numpy_dtype +#define __pyx_ptype_5numpy_flatiter __pyx_mstate_global->__pyx_ptype_5numpy_flatiter +#define __pyx_ptype_5numpy_broadcast __pyx_mstate_global->__pyx_ptype_5numpy_broadcast +#define __pyx_ptype_5numpy_ndarray __pyx_mstate_global->__pyx_ptype_5numpy_ndarray +#define __pyx_ptype_5numpy_generic __pyx_mstate_global->__pyx_ptype_5numpy_generic +#define __pyx_ptype_5numpy_number __pyx_mstate_global->__pyx_ptype_5numpy_number +#define __pyx_ptype_5numpy_integer __pyx_mstate_global->__pyx_ptype_5numpy_integer +#define __pyx_ptype_5numpy_signedinteger __pyx_mstate_global->__pyx_ptype_5numpy_signedinteger +#define __pyx_ptype_5numpy_unsignedinteger __pyx_mstate_global->__pyx_ptype_5numpy_unsignedinteger +#define __pyx_ptype_5numpy_inexact __pyx_mstate_global->__pyx_ptype_5numpy_inexact +#define __pyx_ptype_5numpy_floating __pyx_mstate_global->__pyx_ptype_5numpy_floating +#define __pyx_ptype_5numpy_complexfloating __pyx_mstate_global->__pyx_ptype_5numpy_complexfloating +#define __pyx_ptype_5numpy_flexible __pyx_mstate_global->__pyx_ptype_5numpy_flexible +#define __pyx_ptype_5numpy_character __pyx_mstate_global->__pyx_ptype_5numpy_character +#define __pyx_ptype_5numpy_ufunc __pyx_mstate_global->__pyx_ptype_5numpy_ufunc +#if CYTHON_USE_MODULE_STATE +#define __pyx_type_6common_15transformations_15transformations_LocalCoord __pyx_mstate_global->__pyx_type_6common_15transformations_15transformations_LocalCoord +#endif +#define __pyx_ptype_6common_15transformations_15transformations_LocalCoord __pyx_mstate_global->__pyx_ptype_6common_15transformations_15transformations_LocalCoord +#define __pyx_n_s_AssertionError __pyx_mstate_global->__pyx_n_s_AssertionError +#define __pyx_n_s_ImportError __pyx_mstate_global->__pyx_n_s_ImportError +#define __pyx_n_s_LocalCoord __pyx_mstate_global->__pyx_n_s_LocalCoord +#define __pyx_n_s_LocalCoord___reduce_cython __pyx_mstate_global->__pyx_n_s_LocalCoord___reduce_cython +#define __pyx_n_s_LocalCoord___setstate_cython __pyx_mstate_global->__pyx_n_s_LocalCoord___setstate_cython +#define __pyx_n_s_LocalCoord_ecef2ned_single __pyx_mstate_global->__pyx_n_s_LocalCoord_ecef2ned_single +#define __pyx_n_s_LocalCoord_from_ecef __pyx_mstate_global->__pyx_n_s_LocalCoord_from_ecef +#define __pyx_n_s_LocalCoord_from_geodetic __pyx_mstate_global->__pyx_n_s_LocalCoord_from_geodetic +#define __pyx_n_s_LocalCoord_geodetic2ned_single __pyx_mstate_global->__pyx_n_s_LocalCoord_geodetic2ned_single +#define __pyx_n_s_LocalCoord_ned2ecef_single __pyx_mstate_global->__pyx_n_s_LocalCoord_ned2ecef_single +#define __pyx_n_s_LocalCoord_ned2geodetic_single __pyx_mstate_global->__pyx_n_s_LocalCoord_ned2geodetic_single +#define __pyx_n_s_TypeError __pyx_mstate_global->__pyx_n_s_TypeError +#define __pyx_n_s__3 __pyx_mstate_global->__pyx_n_s__3 +#define __pyx_n_s__42 __pyx_mstate_global->__pyx_n_s__42 +#define __pyx_n_s_array __pyx_mstate_global->__pyx_n_s_array +#define __pyx_n_s_asfortranarray __pyx_mstate_global->__pyx_n_s_asfortranarray +#define __pyx_n_s_asyncio_coroutines __pyx_mstate_global->__pyx_n_s_asyncio_coroutines +#define __pyx_n_s_cline_in_traceback __pyx_mstate_global->__pyx_n_s_cline_in_traceback +#define __pyx_n_s_cls __pyx_mstate_global->__pyx_n_s_cls +#define __pyx_kp_s_common_transformations_transform __pyx_mstate_global->__pyx_kp_s_common_transformations_transform +#define __pyx_n_s_common_transformations_transform_2 __pyx_mstate_global->__pyx_n_s_common_transformations_transform_2 +#define __pyx_n_s_dict __pyx_mstate_global->__pyx_n_s_dict +#define __pyx_kp_u_disable __pyx_mstate_global->__pyx_kp_u_disable +#define __pyx_n_s_double __pyx_mstate_global->__pyx_n_s_double +#define __pyx_n_s_dtype __pyx_mstate_global->__pyx_n_s_dtype +#define __pyx_n_s_e __pyx_mstate_global->__pyx_n_s_e +#define __pyx_n_s_ecef __pyx_mstate_global->__pyx_n_s_ecef +#define __pyx_n_s_ecef2geodetic_single __pyx_mstate_global->__pyx_n_s_ecef2geodetic_single +#define __pyx_n_s_ecef2ned_matrix __pyx_mstate_global->__pyx_n_s_ecef2ned_matrix +#define __pyx_n_s_ecef2ned_single __pyx_mstate_global->__pyx_n_s_ecef2ned_single +#define __pyx_n_s_ecef_euler_from_ned_single __pyx_mstate_global->__pyx_n_s_ecef_euler_from_ned_single +#define __pyx_n_s_ecef_init __pyx_mstate_global->__pyx_n_s_ecef_init +#define __pyx_n_s_ecef_pose __pyx_mstate_global->__pyx_n_s_ecef_pose +#define __pyx_kp_u_enable __pyx_mstate_global->__pyx_kp_u_enable +#define __pyx_n_s_euler __pyx_mstate_global->__pyx_n_s_euler +#define __pyx_n_s_euler2quat_single __pyx_mstate_global->__pyx_n_s_euler2quat_single +#define __pyx_n_s_euler2rot_single __pyx_mstate_global->__pyx_n_s_euler2rot_single +#define __pyx_n_s_from_ecef __pyx_mstate_global->__pyx_n_s_from_ecef +#define __pyx_n_s_from_geodetic __pyx_mstate_global->__pyx_n_s_from_geodetic +#define __pyx_n_s_g __pyx_mstate_global->__pyx_n_s_g +#define __pyx_kp_u_gc __pyx_mstate_global->__pyx_kp_u_gc +#define __pyx_n_s_geodetic __pyx_mstate_global->__pyx_n_s_geodetic +#define __pyx_n_s_geodetic2ecef_single __pyx_mstate_global->__pyx_n_s_geodetic2ecef_single +#define __pyx_n_s_geodetic2ned_single __pyx_mstate_global->__pyx_n_s_geodetic2ned_single +#define __pyx_n_s_getstate __pyx_mstate_global->__pyx_n_s_getstate +#define __pyx_n_s_import __pyx_mstate_global->__pyx_n_s_import +#define __pyx_n_s_init __pyx_mstate_global->__pyx_n_s_init +#define __pyx_n_s_initializing __pyx_mstate_global->__pyx_n_s_initializing +#define __pyx_n_s_is_coroutine __pyx_mstate_global->__pyx_n_s_is_coroutine +#define __pyx_kp_u_isenabled __pyx_mstate_global->__pyx_kp_u_isenabled +#define __pyx_n_s_main __pyx_mstate_global->__pyx_n_s_main +#define __pyx_n_s_n __pyx_mstate_global->__pyx_n_s_n +#define __pyx_n_s_name __pyx_mstate_global->__pyx_n_s_name +#define __pyx_n_s_ned __pyx_mstate_global->__pyx_n_s_ned +#define __pyx_n_s_ned2ecef_matrix __pyx_mstate_global->__pyx_n_s_ned2ecef_matrix +#define __pyx_n_s_ned2ecef_single __pyx_mstate_global->__pyx_n_s_ned2ecef_single +#define __pyx_n_s_ned2geodetic_single __pyx_mstate_global->__pyx_n_s_ned2geodetic_single +#define __pyx_n_s_ned_euler_from_ecef_single __pyx_mstate_global->__pyx_n_s_ned_euler_from_ecef_single +#define __pyx_n_s_ned_pose __pyx_mstate_global->__pyx_n_s_ned_pose +#define __pyx_n_s_np __pyx_mstate_global->__pyx_n_s_np +#define __pyx_n_s_numpy __pyx_mstate_global->__pyx_n_s_numpy +#define __pyx_kp_u_numpy_core_multiarray_failed_to __pyx_mstate_global->__pyx_kp_u_numpy_core_multiarray_failed_to +#define __pyx_kp_u_numpy_core_umath_failed_to_impor __pyx_mstate_global->__pyx_kp_u_numpy_core_umath_failed_to_impor +#define __pyx_n_s_pitch __pyx_mstate_global->__pyx_n_s_pitch +#define __pyx_n_s_pose __pyx_mstate_global->__pyx_n_s_pose +#define __pyx_n_s_pyx_state __pyx_mstate_global->__pyx_n_s_pyx_state +#define __pyx_n_s_q __pyx_mstate_global->__pyx_n_s_q +#define __pyx_n_s_quat __pyx_mstate_global->__pyx_n_s_quat +#define __pyx_n_s_quat2euler_single __pyx_mstate_global->__pyx_n_s_quat2euler_single +#define __pyx_n_s_quat2rot_single __pyx_mstate_global->__pyx_n_s_quat2rot_single +#define __pyx_n_s_r __pyx_mstate_global->__pyx_n_s_r +#define __pyx_n_s_reduce __pyx_mstate_global->__pyx_n_s_reduce +#define __pyx_n_s_reduce_cython __pyx_mstate_global->__pyx_n_s_reduce_cython +#define __pyx_n_s_reduce_ex __pyx_mstate_global->__pyx_n_s_reduce_ex +#define __pyx_n_s_roll __pyx_mstate_global->__pyx_n_s_roll +#define __pyx_n_s_rot __pyx_mstate_global->__pyx_n_s_rot +#define __pyx_n_s_rot2euler_single __pyx_mstate_global->__pyx_n_s_rot2euler_single +#define __pyx_n_s_rot2quat_single __pyx_mstate_global->__pyx_n_s_rot2quat_single +#define __pyx_n_s_rot_matrix __pyx_mstate_global->__pyx_n_s_rot_matrix +#define __pyx_n_s_self __pyx_mstate_global->__pyx_n_s_self +#define __pyx_kp_s_self_lc_cannot_be_converted_to_a __pyx_mstate_global->__pyx_kp_s_self_lc_cannot_be_converted_to_a +#define __pyx_n_s_setstate __pyx_mstate_global->__pyx_n_s_setstate +#define __pyx_n_s_setstate_cython __pyx_mstate_global->__pyx_n_s_setstate_cython +#define __pyx_n_s_spec __pyx_mstate_global->__pyx_n_s_spec +#define __pyx_kp_s_stringsource __pyx_mstate_global->__pyx_kp_s_stringsource +#define __pyx_n_s_test __pyx_mstate_global->__pyx_n_s_test +#define __pyx_n_s_yaw __pyx_mstate_global->__pyx_n_s_yaw +#define __pyx_tuple_ __pyx_mstate_global->__pyx_tuple_ +#define __pyx_tuple__2 __pyx_mstate_global->__pyx_tuple__2 +#define __pyx_tuple__4 __pyx_mstate_global->__pyx_tuple__4 +#define __pyx_tuple__6 __pyx_mstate_global->__pyx_tuple__6 +#define __pyx_tuple__8 __pyx_mstate_global->__pyx_tuple__8 +#define __pyx_tuple__10 __pyx_mstate_global->__pyx_tuple__10 +#define __pyx_tuple__12 __pyx_mstate_global->__pyx_tuple__12 +#define __pyx_tuple__14 __pyx_mstate_global->__pyx_tuple__14 +#define __pyx_tuple__16 __pyx_mstate_global->__pyx_tuple__16 +#define __pyx_tuple__18 __pyx_mstate_global->__pyx_tuple__18 +#define __pyx_tuple__20 __pyx_mstate_global->__pyx_tuple__20 +#define __pyx_tuple__22 __pyx_mstate_global->__pyx_tuple__22 +#define __pyx_tuple__24 __pyx_mstate_global->__pyx_tuple__24 +#define __pyx_tuple__26 __pyx_mstate_global->__pyx_tuple__26 +#define __pyx_tuple__28 __pyx_mstate_global->__pyx_tuple__28 +#define __pyx_tuple__30 __pyx_mstate_global->__pyx_tuple__30 +#define __pyx_tuple__32 __pyx_mstate_global->__pyx_tuple__32 +#define __pyx_tuple__34 __pyx_mstate_global->__pyx_tuple__34 +#define __pyx_tuple__36 __pyx_mstate_global->__pyx_tuple__36 +#define __pyx_tuple__38 __pyx_mstate_global->__pyx_tuple__38 +#define __pyx_tuple__40 __pyx_mstate_global->__pyx_tuple__40 +#define __pyx_codeobj__5 __pyx_mstate_global->__pyx_codeobj__5 +#define __pyx_codeobj__7 __pyx_mstate_global->__pyx_codeobj__7 +#define __pyx_codeobj__9 __pyx_mstate_global->__pyx_codeobj__9 +#define __pyx_codeobj__11 __pyx_mstate_global->__pyx_codeobj__11 +#define __pyx_codeobj__13 __pyx_mstate_global->__pyx_codeobj__13 +#define __pyx_codeobj__15 __pyx_mstate_global->__pyx_codeobj__15 +#define __pyx_codeobj__17 __pyx_mstate_global->__pyx_codeobj__17 +#define __pyx_codeobj__19 __pyx_mstate_global->__pyx_codeobj__19 +#define __pyx_codeobj__21 __pyx_mstate_global->__pyx_codeobj__21 +#define __pyx_codeobj__23 __pyx_mstate_global->__pyx_codeobj__23 +#define __pyx_codeobj__25 __pyx_mstate_global->__pyx_codeobj__25 +#define __pyx_codeobj__27 __pyx_mstate_global->__pyx_codeobj__27 +#define __pyx_codeobj__29 __pyx_mstate_global->__pyx_codeobj__29 +#define __pyx_codeobj__31 __pyx_mstate_global->__pyx_codeobj__31 +#define __pyx_codeobj__33 __pyx_mstate_global->__pyx_codeobj__33 +#define __pyx_codeobj__35 __pyx_mstate_global->__pyx_codeobj__35 +#define __pyx_codeobj__37 __pyx_mstate_global->__pyx_codeobj__37 +#define __pyx_codeobj__39 __pyx_mstate_global->__pyx_codeobj__39 +#define __pyx_codeobj__41 __pyx_mstate_global->__pyx_codeobj__41 +/* #### Code section: module_code ### */ + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":245 + * + * @property + * cdef inline PyObject* base(self) nogil: # <<<<<<<<<<<<<< + * """Returns a borrowed reference to the object owning the data/memory. + * """ + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_7ndarray_4base_base(PyArrayObject *__pyx_v_self) { + PyObject *__pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":248 + * """Returns a borrowed reference to the object owning the data/memory. + * """ + * return PyArray_BASE(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_BASE(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":245 + * + * @property + * cdef inline PyObject* base(self) nogil: # <<<<<<<<<<<<<< + * """Returns a borrowed reference to the object owning the data/memory. + * """ + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":251 + * + * @property + * cdef inline dtype descr(self): # <<<<<<<<<<<<<< + * """Returns an owned reference to the dtype of the array. + * """ + */ + +static CYTHON_INLINE PyArray_Descr *__pyx_f_5numpy_7ndarray_5descr_descr(PyArrayObject *__pyx_v_self) { + PyArray_Descr *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyArray_Descr *__pyx_t_1; + __Pyx_RefNannySetupContext("descr", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":254 + * """Returns an owned reference to the dtype of the array. + * """ + * return PyArray_DESCR(self) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF((PyObject *)__pyx_r); + __pyx_t_1 = PyArray_DESCR(__pyx_v_self); + __Pyx_INCREF((PyObject *)((PyArray_Descr *)__pyx_t_1)); + __pyx_r = ((PyArray_Descr *)__pyx_t_1); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":251 + * + * @property + * cdef inline dtype descr(self): # <<<<<<<<<<<<<< + * """Returns an owned reference to the dtype of the array. + * """ + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF((PyObject *)__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":257 + * + * @property + * cdef inline int ndim(self) nogil: # <<<<<<<<<<<<<< + * """Returns the number of dimensions in the array. + * """ + */ + +static CYTHON_INLINE int __pyx_f_5numpy_7ndarray_4ndim_ndim(PyArrayObject *__pyx_v_self) { + int __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":260 + * """Returns the number of dimensions in the array. + * """ + * return PyArray_NDIM(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_NDIM(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":257 + * + * @property + * cdef inline int ndim(self) nogil: # <<<<<<<<<<<<<< + * """Returns the number of dimensions in the array. + * """ + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":263 + * + * @property + * cdef inline npy_intp *shape(self) nogil: # <<<<<<<<<<<<<< + * """Returns a pointer to the dimensions/shape of the array. + * The number of elements matches the number of dimensions of the array (ndim). + */ + +static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_5shape_shape(PyArrayObject *__pyx_v_self) { + npy_intp *__pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":268 + * Can return NULL for 0-dimensional arrays. + * """ + * return PyArray_DIMS(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_DIMS(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":263 + * + * @property + * cdef inline npy_intp *shape(self) nogil: # <<<<<<<<<<<<<< + * """Returns a pointer to the dimensions/shape of the array. + * The number of elements matches the number of dimensions of the array (ndim). + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":271 + * + * @property + * cdef inline npy_intp *strides(self) nogil: # <<<<<<<<<<<<<< + * """Returns a pointer to the strides of the array. + * The number of elements matches the number of dimensions of the array (ndim). + */ + +static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_7strides_strides(PyArrayObject *__pyx_v_self) { + npy_intp *__pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":275 + * The number of elements matches the number of dimensions of the array (ndim). + * """ + * return PyArray_STRIDES(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_STRIDES(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":271 + * + * @property + * cdef inline npy_intp *strides(self) nogil: # <<<<<<<<<<<<<< + * """Returns a pointer to the strides of the array. + * The number of elements matches the number of dimensions of the array (ndim). + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":278 + * + * @property + * cdef inline npy_intp size(self) nogil: # <<<<<<<<<<<<<< + * """Returns the total size (in number of elements) of the array. + * """ + */ + +static CYTHON_INLINE npy_intp __pyx_f_5numpy_7ndarray_4size_size(PyArrayObject *__pyx_v_self) { + npy_intp __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":281 + * """Returns the total size (in number of elements) of the array. + * """ + * return PyArray_SIZE(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_SIZE(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":278 + * + * @property + * cdef inline npy_intp size(self) nogil: # <<<<<<<<<<<<<< + * """Returns the total size (in number of elements) of the array. + * """ + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":284 + * + * @property + * cdef inline char* data(self) nogil: # <<<<<<<<<<<<<< + * """The pointer to the data buffer as a char*. + * This is provided for legacy reasons to avoid direct struct field access. + */ + +static CYTHON_INLINE char *__pyx_f_5numpy_7ndarray_4data_data(PyArrayObject *__pyx_v_self) { + char *__pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":290 + * of `PyArray_DATA()` instead, which returns a 'void*'. + * """ + * return PyArray_BYTES(self) # <<<<<<<<<<<<<< + * + * ctypedef unsigned char npy_bool + */ + __pyx_r = PyArray_BYTES(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":284 + * + * @property + * cdef inline char* data(self) nogil: # <<<<<<<<<<<<<< + * """The pointer to the data buffer as a char*. + * This is provided for legacy reasons to avoid direct struct field access. + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":773 + * ctypedef npy_cdouble complex_t + * + * cdef inline object PyArray_MultiIterNew1(a): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(1, a) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew1(PyObject *__pyx_v_a) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew1", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":774 + * + * cdef inline object PyArray_MultiIterNew1(a): + * return PyArray_MultiIterNew(1, a) # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew2(a, b): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(1, ((void *)__pyx_v_a)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 774, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":773 + * ctypedef npy_cdouble complex_t + * + * cdef inline object PyArray_MultiIterNew1(a): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(1, a) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew1", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":776 + * return PyArray_MultiIterNew(1, a) + * + * cdef inline object PyArray_MultiIterNew2(a, b): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(2, a, b) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew2(PyObject *__pyx_v_a, PyObject *__pyx_v_b) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew2", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":777 + * + * cdef inline object PyArray_MultiIterNew2(a, b): + * return PyArray_MultiIterNew(2, a, b) # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew3(a, b, c): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(2, ((void *)__pyx_v_a), ((void *)__pyx_v_b)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 777, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":776 + * return PyArray_MultiIterNew(1, a) + * + * cdef inline object PyArray_MultiIterNew2(a, b): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(2, a, b) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew2", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":779 + * return PyArray_MultiIterNew(2, a, b) + * + * cdef inline object PyArray_MultiIterNew3(a, b, c): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(3, a, b, c) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew3(PyObject *__pyx_v_a, PyObject *__pyx_v_b, PyObject *__pyx_v_c) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew3", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":780 + * + * cdef inline object PyArray_MultiIterNew3(a, b, c): + * return PyArray_MultiIterNew(3, a, b, c) # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew4(a, b, c, d): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(3, ((void *)__pyx_v_a), ((void *)__pyx_v_b), ((void *)__pyx_v_c)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 780, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":779 + * return PyArray_MultiIterNew(2, a, b) + * + * cdef inline object PyArray_MultiIterNew3(a, b, c): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(3, a, b, c) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew3", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":782 + * return PyArray_MultiIterNew(3, a, b, c) + * + * cdef inline object PyArray_MultiIterNew4(a, b, c, d): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(4, a, b, c, d) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew4(PyObject *__pyx_v_a, PyObject *__pyx_v_b, PyObject *__pyx_v_c, PyObject *__pyx_v_d) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew4", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":783 + * + * cdef inline object PyArray_MultiIterNew4(a, b, c, d): + * return PyArray_MultiIterNew(4, a, b, c, d) # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(4, ((void *)__pyx_v_a), ((void *)__pyx_v_b), ((void *)__pyx_v_c), ((void *)__pyx_v_d)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 783, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":782 + * return PyArray_MultiIterNew(3, a, b, c) + * + * cdef inline object PyArray_MultiIterNew4(a, b, c, d): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(4, a, b, c, d) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew4", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":785 + * return PyArray_MultiIterNew(4, a, b, c, d) + * + * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(5, a, b, c, d, e) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew5(PyObject *__pyx_v_a, PyObject *__pyx_v_b, PyObject *__pyx_v_c, PyObject *__pyx_v_d, PyObject *__pyx_v_e) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew5", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":786 + * + * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): + * return PyArray_MultiIterNew(5, a, b, c, d, e) # <<<<<<<<<<<<<< + * + * cdef inline tuple PyDataType_SHAPE(dtype d): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(5, ((void *)__pyx_v_a), ((void *)__pyx_v_b), ((void *)__pyx_v_c), ((void *)__pyx_v_d), ((void *)__pyx_v_e)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 786, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":785 + * return PyArray_MultiIterNew(4, a, b, c, d) + * + * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(5, a, b, c, d, e) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew5", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":788 + * return PyArray_MultiIterNew(5, a, b, c, d, e) + * + * cdef inline tuple PyDataType_SHAPE(dtype d): # <<<<<<<<<<<<<< + * if PyDataType_HASSUBARRAY(d): + * return d.subarray.shape + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyDataType_SHAPE(PyArray_Descr *__pyx_v_d) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + __Pyx_RefNannySetupContext("PyDataType_SHAPE", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":789 + * + * cdef inline tuple PyDataType_SHAPE(dtype d): + * if PyDataType_HASSUBARRAY(d): # <<<<<<<<<<<<<< + * return d.subarray.shape + * else: + */ + __pyx_t_1 = PyDataType_HASSUBARRAY(__pyx_v_d); + if (__pyx_t_1) { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":790 + * cdef inline tuple PyDataType_SHAPE(dtype d): + * if PyDataType_HASSUBARRAY(d): + * return d.subarray.shape # <<<<<<<<<<<<<< + * else: + * return () + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(((PyObject*)__pyx_v_d->subarray->shape)); + __pyx_r = ((PyObject*)__pyx_v_d->subarray->shape); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":789 + * + * cdef inline tuple PyDataType_SHAPE(dtype d): + * if PyDataType_HASSUBARRAY(d): # <<<<<<<<<<<<<< + * return d.subarray.shape + * else: + */ + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":792 + * return d.subarray.shape + * else: + * return () # <<<<<<<<<<<<<< + * + * + */ + /*else*/ { + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_empty_tuple); + __pyx_r = __pyx_empty_tuple; + goto __pyx_L0; + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":788 + * return PyArray_MultiIterNew(5, a, b, c, d, e) + * + * cdef inline tuple PyDataType_SHAPE(dtype d): # <<<<<<<<<<<<<< + * if PyDataType_HASSUBARRAY(d): + * return d.subarray.shape + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":968 + * int _import_umath() except -1 + * + * cdef inline void set_array_base(ndarray arr, object base): # <<<<<<<<<<<<<< + * Py_INCREF(base) # important to do this before stealing the reference below! + * PyArray_SetBaseObject(arr, base) + */ + +static CYTHON_INLINE void __pyx_f_5numpy_set_array_base(PyArrayObject *__pyx_v_arr, PyObject *__pyx_v_base) { + int __pyx_t_1; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":969 + * + * cdef inline void set_array_base(ndarray arr, object base): + * Py_INCREF(base) # important to do this before stealing the reference below! # <<<<<<<<<<<<<< + * PyArray_SetBaseObject(arr, base) + * + */ + Py_INCREF(__pyx_v_base); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":970 + * cdef inline void set_array_base(ndarray arr, object base): + * Py_INCREF(base) # important to do this before stealing the reference below! + * PyArray_SetBaseObject(arr, base) # <<<<<<<<<<<<<< + * + * cdef inline object get_array_base(ndarray arr): + */ + __pyx_t_1 = PyArray_SetBaseObject(__pyx_v_arr, __pyx_v_base); if (unlikely(__pyx_t_1 == ((int)-1))) __PYX_ERR(2, 970, __pyx_L1_error) + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":968 + * int _import_umath() except -1 + * + * cdef inline void set_array_base(ndarray arr, object base): # <<<<<<<<<<<<<< + * Py_INCREF(base) # important to do this before stealing the reference below! + * PyArray_SetBaseObject(arr, base) + */ + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("numpy.set_array_base", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_L0:; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":972 + * PyArray_SetBaseObject(arr, base) + * + * cdef inline object get_array_base(ndarray arr): # <<<<<<<<<<<<<< + * base = PyArray_BASE(arr) + * if base is NULL: + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_get_array_base(PyArrayObject *__pyx_v_arr) { + PyObject *__pyx_v_base; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + __Pyx_RefNannySetupContext("get_array_base", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":973 + * + * cdef inline object get_array_base(ndarray arr): + * base = PyArray_BASE(arr) # <<<<<<<<<<<<<< + * if base is NULL: + * return None + */ + __pyx_v_base = PyArray_BASE(__pyx_v_arr); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":974 + * cdef inline object get_array_base(ndarray arr): + * base = PyArray_BASE(arr) + * if base is NULL: # <<<<<<<<<<<<<< + * return None + * return base + */ + __pyx_t_1 = (__pyx_v_base == NULL); + if (__pyx_t_1) { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":975 + * base = PyArray_BASE(arr) + * if base is NULL: + * return None # <<<<<<<<<<<<<< + * return base + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":974 + * cdef inline object get_array_base(ndarray arr): + * base = PyArray_BASE(arr) + * if base is NULL: # <<<<<<<<<<<<<< + * return None + * return base + */ + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":976 + * if base is NULL: + * return None + * return base # <<<<<<<<<<<<<< + * + * # Versions of the import_* functions which are more suitable for + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(((PyObject *)__pyx_v_base)); + __pyx_r = ((PyObject *)__pyx_v_base); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":972 + * PyArray_SetBaseObject(arr, base) + * + * cdef inline object get_array_base(ndarray arr): # <<<<<<<<<<<<<< + * base = PyArray_BASE(arr) + * if base is NULL: + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":980 + * # Versions of the import_* functions which are more suitable for + * # Cython code. + * cdef inline int import_array() except -1: # <<<<<<<<<<<<<< + * try: + * __pyx_import_array() + */ + +static CYTHON_INLINE int __pyx_f_5numpy_import_array(void) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("import_array", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":981 + * # Cython code. + * cdef inline int import_array() except -1: + * try: # <<<<<<<<<<<<<< + * __pyx_import_array() + * except Exception: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":982 + * cdef inline int import_array() except -1: + * try: + * __pyx_import_array() # <<<<<<<<<<<<<< + * except Exception: + * raise ImportError("numpy.core.multiarray failed to import") + */ + __pyx_t_4 = _import_array(); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(2, 982, __pyx_L3_error) + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":981 + * # Cython code. + * cdef inline int import_array() except -1: + * try: # <<<<<<<<<<<<<< + * __pyx_import_array() + * except Exception: + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L8_try_end; + __pyx_L3_error:; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":983 + * try: + * __pyx_import_array() + * except Exception: # <<<<<<<<<<<<<< + * raise ImportError("numpy.core.multiarray failed to import") + * + */ + __pyx_t_4 = __Pyx_PyErr_ExceptionMatches(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0]))); + if (__pyx_t_4) { + __Pyx_AddTraceback("numpy.import_array", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_6, &__pyx_t_7) < 0) __PYX_ERR(2, 983, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_7); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":984 + * __pyx_import_array() + * except Exception: + * raise ImportError("numpy.core.multiarray failed to import") # <<<<<<<<<<<<<< + * + * cdef inline int import_umath() except -1: + */ + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_builtin_ImportError, __pyx_tuple_, NULL); if (unlikely(!__pyx_t_8)) __PYX_ERR(2, 984, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_Raise(__pyx_t_8, 0, 0, 0); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __PYX_ERR(2, 984, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":981 + * # Cython code. + * cdef inline int import_array() except -1: + * try: # <<<<<<<<<<<<<< + * __pyx_import_array() + * except Exception: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + goto __pyx_L1_error; + __pyx_L8_try_end:; + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":980 + * # Versions of the import_* functions which are more suitable for + * # Cython code. + * cdef inline int import_array() except -1: # <<<<<<<<<<<<<< + * try: + * __pyx_import_array() + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("numpy.import_array", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":986 + * raise ImportError("numpy.core.multiarray failed to import") + * + * cdef inline int import_umath() except -1: # <<<<<<<<<<<<<< + * try: + * _import_umath() + */ + +static CYTHON_INLINE int __pyx_f_5numpy_import_umath(void) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("import_umath", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":987 + * + * cdef inline int import_umath() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":988 + * cdef inline int import_umath() except -1: + * try: + * _import_umath() # <<<<<<<<<<<<<< + * except Exception: + * raise ImportError("numpy.core.umath failed to import") + */ + __pyx_t_4 = _import_umath(); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(2, 988, __pyx_L3_error) + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":987 + * + * cdef inline int import_umath() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L8_try_end; + __pyx_L3_error:; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":989 + * try: + * _import_umath() + * except Exception: # <<<<<<<<<<<<<< + * raise ImportError("numpy.core.umath failed to import") + * + */ + __pyx_t_4 = __Pyx_PyErr_ExceptionMatches(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0]))); + if (__pyx_t_4) { + __Pyx_AddTraceback("numpy.import_umath", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_6, &__pyx_t_7) < 0) __PYX_ERR(2, 989, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_7); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":990 + * _import_umath() + * except Exception: + * raise ImportError("numpy.core.umath failed to import") # <<<<<<<<<<<<<< + * + * cdef inline int import_ufunc() except -1: + */ + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_builtin_ImportError, __pyx_tuple__2, NULL); if (unlikely(!__pyx_t_8)) __PYX_ERR(2, 990, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_Raise(__pyx_t_8, 0, 0, 0); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __PYX_ERR(2, 990, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":987 + * + * cdef inline int import_umath() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + goto __pyx_L1_error; + __pyx_L8_try_end:; + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":986 + * raise ImportError("numpy.core.multiarray failed to import") + * + * cdef inline int import_umath() except -1: # <<<<<<<<<<<<<< + * try: + * _import_umath() + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("numpy.import_umath", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":992 + * raise ImportError("numpy.core.umath failed to import") + * + * cdef inline int import_ufunc() except -1: # <<<<<<<<<<<<<< + * try: + * _import_umath() + */ + +static CYTHON_INLINE int __pyx_f_5numpy_import_ufunc(void) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("import_ufunc", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":993 + * + * cdef inline int import_ufunc() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":994 + * cdef inline int import_ufunc() except -1: + * try: + * _import_umath() # <<<<<<<<<<<<<< + * except Exception: + * raise ImportError("numpy.core.umath failed to import") + */ + __pyx_t_4 = _import_umath(); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(2, 994, __pyx_L3_error) + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":993 + * + * cdef inline int import_ufunc() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L8_try_end; + __pyx_L3_error:; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":995 + * try: + * _import_umath() + * except Exception: # <<<<<<<<<<<<<< + * raise ImportError("numpy.core.umath failed to import") + * + */ + __pyx_t_4 = __Pyx_PyErr_ExceptionMatches(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0]))); + if (__pyx_t_4) { + __Pyx_AddTraceback("numpy.import_ufunc", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_6, &__pyx_t_7) < 0) __PYX_ERR(2, 995, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_7); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":996 + * _import_umath() + * except Exception: + * raise ImportError("numpy.core.umath failed to import") # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_builtin_ImportError, __pyx_tuple__2, NULL); if (unlikely(!__pyx_t_8)) __PYX_ERR(2, 996, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_Raise(__pyx_t_8, 0, 0, 0); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __PYX_ERR(2, 996, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":993 + * + * cdef inline int import_ufunc() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + goto __pyx_L1_error; + __pyx_L8_try_end:; + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":992 + * raise ImportError("numpy.core.umath failed to import") + * + * cdef inline int import_ufunc() except -1: # <<<<<<<<<<<<<< + * try: + * _import_umath() + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("numpy.import_ufunc", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":999 + * + * + * cdef inline bint is_timedelta64_object(object obj): # <<<<<<<<<<<<<< + * """ + * Cython equivalent of `isinstance(obj, np.timedelta64)` + */ + +static CYTHON_INLINE int __pyx_f_5numpy_is_timedelta64_object(PyObject *__pyx_v_obj) { + int __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1011 + * bool + * """ + * return PyObject_TypeCheck(obj, &PyTimedeltaArrType_Type) # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = PyObject_TypeCheck(__pyx_v_obj, (&PyTimedeltaArrType_Type)); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":999 + * + * + * cdef inline bint is_timedelta64_object(object obj): # <<<<<<<<<<<<<< + * """ + * Cython equivalent of `isinstance(obj, np.timedelta64)` + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1014 + * + * + * cdef inline bint is_datetime64_object(object obj): # <<<<<<<<<<<<<< + * """ + * Cython equivalent of `isinstance(obj, np.datetime64)` + */ + +static CYTHON_INLINE int __pyx_f_5numpy_is_datetime64_object(PyObject *__pyx_v_obj) { + int __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1026 + * bool + * """ + * return PyObject_TypeCheck(obj, &PyDatetimeArrType_Type) # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = PyObject_TypeCheck(__pyx_v_obj, (&PyDatetimeArrType_Type)); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1014 + * + * + * cdef inline bint is_datetime64_object(object obj): # <<<<<<<<<<<<<< + * """ + * Cython equivalent of `isinstance(obj, np.datetime64)` + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1029 + * + * + * cdef inline npy_datetime get_datetime64_value(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the int64 value underlying scalar numpy datetime64 object + */ + +static CYTHON_INLINE npy_datetime __pyx_f_5numpy_get_datetime64_value(PyObject *__pyx_v_obj) { + npy_datetime __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1036 + * also needed. That can be found using `get_datetime64_unit`. + * """ + * return (obj).obval # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = ((PyDatetimeScalarObject *)__pyx_v_obj)->obval; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1029 + * + * + * cdef inline npy_datetime get_datetime64_value(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the int64 value underlying scalar numpy datetime64 object + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1039 + * + * + * cdef inline npy_timedelta get_timedelta64_value(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the int64 value underlying scalar numpy timedelta64 object + */ + +static CYTHON_INLINE npy_timedelta __pyx_f_5numpy_get_timedelta64_value(PyObject *__pyx_v_obj) { + npy_timedelta __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1043 + * returns the int64 value underlying scalar numpy timedelta64 object + * """ + * return (obj).obval # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = ((PyTimedeltaScalarObject *)__pyx_v_obj)->obval; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1039 + * + * + * cdef inline npy_timedelta get_timedelta64_value(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the int64 value underlying scalar numpy timedelta64 object + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1046 + * + * + * cdef inline NPY_DATETIMEUNIT get_datetime64_unit(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the unit part of the dtype for a numpy datetime64 object. + */ + +static CYTHON_INLINE NPY_DATETIMEUNIT __pyx_f_5numpy_get_datetime64_unit(PyObject *__pyx_v_obj) { + NPY_DATETIMEUNIT __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1050 + * returns the unit part of the dtype for a numpy datetime64 object. + * """ + * return (obj).obmeta.base # <<<<<<<<<<<<<< + */ + __pyx_r = ((NPY_DATETIMEUNIT)((PyDatetimeScalarObject *)__pyx_v_obj)->obmeta.base); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1046 + * + * + * cdef inline NPY_DATETIMEUNIT get_datetime64_unit(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the unit part of the dtype for a numpy datetime64 object. + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":23 + * cimport numpy as np + * + * cdef np.ndarray[double, ndim=2] matrix2numpy(Matrix3 m): # <<<<<<<<<<<<<< + * return np.array([ + * [m(0, 0), m(0, 1), m(0, 2)], + */ + +static PyArrayObject *__pyx_f_6common_15transformations_15transformations_matrix2numpy(Eigen::Matrix3d __pyx_v_m) { + PyArrayObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("matrix2numpy", 1); + + /* "common/transformations/transformations.pyx":24 + * + * cdef np.ndarray[double, ndim=2] matrix2numpy(Matrix3 m): + * return np.array([ # <<<<<<<<<<<<<< + * [m(0, 0), m(0, 1), m(0, 2)], + * [m(1, 0), m(1, 1), m(1, 2)], + */ + __Pyx_XDECREF((PyObject *)__pyx_r); + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_np); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 24, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_array); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 24, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "common/transformations/transformations.pyx":25 + * cdef np.ndarray[double, ndim=2] matrix2numpy(Matrix3 m): + * return np.array([ + * [m(0, 0), m(0, 1), m(0, 2)], # <<<<<<<<<<<<<< + * [m(1, 0), m(1, 1), m(1, 2)], + * [m(2, 0), m(2, 1), m(2, 2)], + */ + __pyx_t_2 = PyFloat_FromDouble(__pyx_v_m(0, 0)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 25, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = PyFloat_FromDouble(__pyx_v_m(0, 1)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 25, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = PyFloat_FromDouble(__pyx_v_m(0, 2)); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 25, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = PyList_New(3); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 25, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyList_SET_ITEM(__pyx_t_6, 0, __pyx_t_2)) __PYX_ERR(0, 25, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_4); + if (__Pyx_PyList_SET_ITEM(__pyx_t_6, 1, __pyx_t_4)) __PYX_ERR(0, 25, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_5); + if (__Pyx_PyList_SET_ITEM(__pyx_t_6, 2, __pyx_t_5)) __PYX_ERR(0, 25, __pyx_L1_error); + __pyx_t_2 = 0; + __pyx_t_4 = 0; + __pyx_t_5 = 0; + + /* "common/transformations/transformations.pyx":26 + * return np.array([ + * [m(0, 0), m(0, 1), m(0, 2)], + * [m(1, 0), m(1, 1), m(1, 2)], # <<<<<<<<<<<<<< + * [m(2, 0), m(2, 1), m(2, 2)], + * ]) + */ + __pyx_t_5 = PyFloat_FromDouble(__pyx_v_m(1, 0)); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 26, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_4 = PyFloat_FromDouble(__pyx_v_m(1, 1)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 26, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_2 = PyFloat_FromDouble(__pyx_v_m(1, 2)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 26, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_7 = PyList_New(3); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 26, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_GIVEREF(__pyx_t_5); + if (__Pyx_PyList_SET_ITEM(__pyx_t_7, 0, __pyx_t_5)) __PYX_ERR(0, 26, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_4); + if (__Pyx_PyList_SET_ITEM(__pyx_t_7, 1, __pyx_t_4)) __PYX_ERR(0, 26, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyList_SET_ITEM(__pyx_t_7, 2, __pyx_t_2)) __PYX_ERR(0, 26, __pyx_L1_error); + __pyx_t_5 = 0; + __pyx_t_4 = 0; + __pyx_t_2 = 0; + + /* "common/transformations/transformations.pyx":27 + * [m(0, 0), m(0, 1), m(0, 2)], + * [m(1, 0), m(1, 1), m(1, 2)], + * [m(2, 0), m(2, 1), m(2, 2)], # <<<<<<<<<<<<<< + * ]) + * + */ + __pyx_t_2 = PyFloat_FromDouble(__pyx_v_m(2, 0)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 27, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = PyFloat_FromDouble(__pyx_v_m(2, 1)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 27, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = PyFloat_FromDouble(__pyx_v_m(2, 2)); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 27, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_8 = PyList_New(3); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 27, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyList_SET_ITEM(__pyx_t_8, 0, __pyx_t_2)) __PYX_ERR(0, 27, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_4); + if (__Pyx_PyList_SET_ITEM(__pyx_t_8, 1, __pyx_t_4)) __PYX_ERR(0, 27, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_5); + if (__Pyx_PyList_SET_ITEM(__pyx_t_8, 2, __pyx_t_5)) __PYX_ERR(0, 27, __pyx_L1_error); + __pyx_t_2 = 0; + __pyx_t_4 = 0; + __pyx_t_5 = 0; + + /* "common/transformations/transformations.pyx":24 + * + * cdef np.ndarray[double, ndim=2] matrix2numpy(Matrix3 m): + * return np.array([ # <<<<<<<<<<<<<< + * [m(0, 0), m(0, 1), m(0, 2)], + * [m(1, 0), m(1, 1), m(1, 2)], + */ + __pyx_t_5 = PyList_New(3); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 24, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_GIVEREF(__pyx_t_6); + if (__Pyx_PyList_SET_ITEM(__pyx_t_5, 0, __pyx_t_6)) __PYX_ERR(0, 24, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_7); + if (__Pyx_PyList_SET_ITEM(__pyx_t_5, 1, __pyx_t_7)) __PYX_ERR(0, 24, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_8); + if (__Pyx_PyList_SET_ITEM(__pyx_t_5, 2, __pyx_t_8)) __PYX_ERR(0, 24, __pyx_L1_error); + __pyx_t_6 = 0; + __pyx_t_7 = 0; + __pyx_t_8 = 0; + __pyx_t_8 = NULL; + __pyx_t_9 = 0; + #if CYTHON_UNPACK_METHODS + if (unlikely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_8 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_8)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_8); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_9 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_8, __pyx_t_5}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_9, 1+__pyx_t_9); + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 24, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + if (!(likely(((__pyx_t_1) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_1, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 24, __pyx_L1_error) + __pyx_r = ((PyArrayObject *)__pyx_t_1); + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":23 + * cimport numpy as np + * + * cdef np.ndarray[double, ndim=2] matrix2numpy(Matrix3 m): # <<<<<<<<<<<<<< + * return np.array([ + * [m(0, 0), m(0, 1), m(0, 2)], + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("common.transformations.transformations.matrix2numpy", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF((PyObject *)__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":30 + * ]) + * + * cdef Matrix3 numpy2matrix(np.ndarray[double, ndim=2, mode="fortran"] m): # <<<<<<<<<<<<<< + * assert m.shape[0] == 3 + * assert m.shape[1] == 3 + */ + +static Eigen::Matrix3d __pyx_f_6common_15transformations_15transformations_numpy2matrix(PyArrayObject *__pyx_v_m) { + __Pyx_LocalBuf_ND __pyx_pybuffernd_m; + __Pyx_Buffer __pyx_pybuffer_m; + Eigen::Matrix3d __pyx_r; + npy_intp *__pyx_t_1; + int __pyx_t_2; + char *__pyx_t_3; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __pyx_pybuffer_m.pybuffer.buf = NULL; + __pyx_pybuffer_m.refcount = 0; + __pyx_pybuffernd_m.data = NULL; + __pyx_pybuffernd_m.rcbuffer = &__pyx_pybuffer_m; + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_m.rcbuffer->pybuffer, (PyObject*)__pyx_v_m, &__Pyx_TypeInfo_double, PyBUF_FORMAT| PyBUF_F_CONTIGUOUS, 2, 0, __pyx_stack) == -1)) __PYX_ERR(0, 30, __pyx_L1_error) + } + __pyx_pybuffernd_m.diminfo[0].strides = __pyx_pybuffernd_m.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_m.diminfo[0].shape = __pyx_pybuffernd_m.rcbuffer->pybuffer.shape[0]; __pyx_pybuffernd_m.diminfo[1].strides = __pyx_pybuffernd_m.rcbuffer->pybuffer.strides[1]; __pyx_pybuffernd_m.diminfo[1].shape = __pyx_pybuffernd_m.rcbuffer->pybuffer.shape[1]; + + /* "common/transformations/transformations.pyx":31 + * + * cdef Matrix3 numpy2matrix(np.ndarray[double, ndim=2, mode="fortran"] m): + * assert m.shape[0] == 3 # <<<<<<<<<<<<<< + * assert m.shape[1] == 3 + * return Matrix3(m.data) + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_1 = __pyx_f_5numpy_7ndarray_5shape_shape(((PyArrayObject *)__pyx_v_m)); if (unlikely(__pyx_t_1 == ((npy_intp *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 31, __pyx_L1_error) + __pyx_t_2 = ((__pyx_t_1[0]) == 3); + if (unlikely(!__pyx_t_2)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(0, 31, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(0, 31, __pyx_L1_error) + #endif + + /* "common/transformations/transformations.pyx":32 + * cdef Matrix3 numpy2matrix(np.ndarray[double, ndim=2, mode="fortran"] m): + * assert m.shape[0] == 3 + * assert m.shape[1] == 3 # <<<<<<<<<<<<<< + * return Matrix3(m.data) + * + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_1 = __pyx_f_5numpy_7ndarray_5shape_shape(((PyArrayObject *)__pyx_v_m)); if (unlikely(__pyx_t_1 == ((npy_intp *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 32, __pyx_L1_error) + __pyx_t_2 = ((__pyx_t_1[1]) == 3); + if (unlikely(!__pyx_t_2)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(0, 32, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(0, 32, __pyx_L1_error) + #endif + + /* "common/transformations/transformations.pyx":33 + * assert m.shape[0] == 3 + * assert m.shape[1] == 3 + * return Matrix3(m.data) # <<<<<<<<<<<<<< + * + * cdef ECEF list2ecef(ecef): + */ + __pyx_t_3 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_m)); if (unlikely(__pyx_t_3 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 33, __pyx_L1_error) + __pyx_r = Eigen::Matrix3d(((double *)__pyx_t_3)); + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":30 + * ]) + * + * cdef Matrix3 numpy2matrix(np.ndarray[double, ndim=2, mode="fortran"] m): # <<<<<<<<<<<<<< + * assert m.shape[0] == 3 + * assert m.shape[1] == 3 + */ + + /* function exit code */ + __pyx_L1_error:; + { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_m.rcbuffer->pybuffer); + __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} + __Pyx_AddTraceback("common.transformations.transformations.numpy2matrix", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_pretend_to_initialize(&__pyx_r); + goto __pyx_L2; + __pyx_L0:; + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_m.rcbuffer->pybuffer); + __pyx_L2:; + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":35 + * return Matrix3(m.data) + * + * cdef ECEF list2ecef(ecef): # <<<<<<<<<<<<<< + * cdef ECEF e + * e.x = ecef[0] + */ + +static struct ECEF __pyx_f_6common_15transformations_15transformations_list2ecef(PyObject *__pyx_v_ecef) { + struct ECEF __pyx_v_e; + struct ECEF __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + double __pyx_t_2; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("list2ecef", 1); + + /* "common/transformations/transformations.pyx":37 + * cdef ECEF list2ecef(ecef): + * cdef ECEF e + * e.x = ecef[0] # <<<<<<<<<<<<<< + * e.y = ecef[1] + * e.z = ecef[2] + */ + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_ecef, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 37, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_2 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 37, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_e.x = __pyx_t_2; + + /* "common/transformations/transformations.pyx":38 + * cdef ECEF e + * e.x = ecef[0] + * e.y = ecef[1] # <<<<<<<<<<<<<< + * e.z = ecef[2] + * return e + */ + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_ecef, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 38, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_2 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 38, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_e.y = __pyx_t_2; + + /* "common/transformations/transformations.pyx":39 + * e.x = ecef[0] + * e.y = ecef[1] + * e.z = ecef[2] # <<<<<<<<<<<<<< + * return e + * + */ + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_ecef, 2, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 39, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_2 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 39, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_e.z = __pyx_t_2; + + /* "common/transformations/transformations.pyx":40 + * e.y = ecef[1] + * e.z = ecef[2] + * return e # <<<<<<<<<<<<<< + * + * cdef NED list2ned(ned): + */ + __pyx_r = __pyx_v_e; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":35 + * return Matrix3(m.data) + * + * cdef ECEF list2ecef(ecef): # <<<<<<<<<<<<<< + * cdef ECEF e + * e.x = ecef[0] + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("common.transformations.transformations.list2ecef", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_pretend_to_initialize(&__pyx_r); + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":42 + * return e + * + * cdef NED list2ned(ned): # <<<<<<<<<<<<<< + * cdef NED n + * n.n = ned[0] + */ + +static struct NED __pyx_f_6common_15transformations_15transformations_list2ned(PyObject *__pyx_v_ned) { + struct NED __pyx_v_n; + struct NED __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + double __pyx_t_2; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("list2ned", 1); + + /* "common/transformations/transformations.pyx":44 + * cdef NED list2ned(ned): + * cdef NED n + * n.n = ned[0] # <<<<<<<<<<<<<< + * n.e = ned[1] + * n.d = ned[2] + */ + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_ned, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 44, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_2 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 44, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_n.n = __pyx_t_2; + + /* "common/transformations/transformations.pyx":45 + * cdef NED n + * n.n = ned[0] + * n.e = ned[1] # <<<<<<<<<<<<<< + * n.d = ned[2] + * return n + */ + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_ned, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 45, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_2 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 45, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_n.e = __pyx_t_2; + + /* "common/transformations/transformations.pyx":46 + * n.n = ned[0] + * n.e = ned[1] + * n.d = ned[2] # <<<<<<<<<<<<<< + * return n + * + */ + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_ned, 2, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 46, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_2 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 46, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_n.d = __pyx_t_2; + + /* "common/transformations/transformations.pyx":47 + * n.e = ned[1] + * n.d = ned[2] + * return n # <<<<<<<<<<<<<< + * + * cdef Geodetic list2geodetic(geodetic): + */ + __pyx_r = __pyx_v_n; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":42 + * return e + * + * cdef NED list2ned(ned): # <<<<<<<<<<<<<< + * cdef NED n + * n.n = ned[0] + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("common.transformations.transformations.list2ned", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_pretend_to_initialize(&__pyx_r); + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":49 + * return n + * + * cdef Geodetic list2geodetic(geodetic): # <<<<<<<<<<<<<< + * cdef Geodetic g + * g.lat = geodetic[0] + */ + +static struct Geodetic __pyx_f_6common_15transformations_15transformations_list2geodetic(PyObject *__pyx_v_geodetic) { + struct Geodetic __pyx_v_g; + struct Geodetic __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + double __pyx_t_2; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("list2geodetic", 1); + + /* "common/transformations/transformations.pyx":51 + * cdef Geodetic list2geodetic(geodetic): + * cdef Geodetic g + * g.lat = geodetic[0] # <<<<<<<<<<<<<< + * g.lon = geodetic[1] + * g.alt = geodetic[2] + */ + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_geodetic, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 51, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_2 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 51, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_g.lat = __pyx_t_2; + + /* "common/transformations/transformations.pyx":52 + * cdef Geodetic g + * g.lat = geodetic[0] + * g.lon = geodetic[1] # <<<<<<<<<<<<<< + * g.alt = geodetic[2] + * return g + */ + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_geodetic, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 52, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_2 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 52, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_g.lon = __pyx_t_2; + + /* "common/transformations/transformations.pyx":53 + * g.lat = geodetic[0] + * g.lon = geodetic[1] + * g.alt = geodetic[2] # <<<<<<<<<<<<<< + * return g + * + */ + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_geodetic, 2, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 53, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_2 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 53, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_g.alt = __pyx_t_2; + + /* "common/transformations/transformations.pyx":54 + * g.lon = geodetic[1] + * g.alt = geodetic[2] + * return g # <<<<<<<<<<<<<< + * + * def euler2quat_single(euler): + */ + __pyx_r = __pyx_v_g; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":49 + * return n + * + * cdef Geodetic list2geodetic(geodetic): # <<<<<<<<<<<<<< + * cdef Geodetic g + * g.lat = geodetic[0] + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("common.transformations.transformations.list2geodetic", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_pretend_to_initialize(&__pyx_r); + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":56 + * return g + * + * def euler2quat_single(euler): # <<<<<<<<<<<<<< + * cdef Vector3 e = Vector3(euler[0], euler[1], euler[2]) + * cdef Quaternion q = euler2quat_c(e) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_1euler2quat_single(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_15transformations_15transformations_1euler2quat_single = {"euler2quat_single", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_1euler2quat_single, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_15transformations_15transformations_1euler2quat_single(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_euler = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("euler2quat_single (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_euler,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_euler)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 56, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "euler2quat_single") < 0)) __PYX_ERR(0, 56, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_euler = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("euler2quat_single", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 56, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("common.transformations.transformations.euler2quat_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_15transformations_15transformations_euler2quat_single(__pyx_self, __pyx_v_euler); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_euler2quat_single(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_euler) { + Eigen::Vector3d __pyx_v_e; + Eigen::Quaterniond __pyx_v_q; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + double __pyx_t_2; + double __pyx_t_3; + double __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("euler2quat_single", 1); + + /* "common/transformations/transformations.pyx":57 + * + * def euler2quat_single(euler): + * cdef Vector3 e = Vector3(euler[0], euler[1], euler[2]) # <<<<<<<<<<<<<< + * cdef Quaternion q = euler2quat_c(e) + * return [q.w(), q.x(), q.y(), q.z()] + */ + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_euler, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 57, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_2 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 57, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_euler, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 57, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_3 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 57, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_euler, 2, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 57, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_4 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_4 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 57, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_e = Eigen::Vector3d(__pyx_t_2, __pyx_t_3, __pyx_t_4); + + /* "common/transformations/transformations.pyx":58 + * def euler2quat_single(euler): + * cdef Vector3 e = Vector3(euler[0], euler[1], euler[2]) + * cdef Quaternion q = euler2quat_c(e) # <<<<<<<<<<<<<< + * return [q.w(), q.x(), q.y(), q.z()] + * + */ + __pyx_v_q = euler2quat(__pyx_v_e); + + /* "common/transformations/transformations.pyx":59 + * cdef Vector3 e = Vector3(euler[0], euler[1], euler[2]) + * cdef Quaternion q = euler2quat_c(e) + * return [q.w(), q.x(), q.y(), q.z()] # <<<<<<<<<<<<<< + * + * def quat2euler_single(quat): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyFloat_FromDouble(__pyx_v_q.w()); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 59, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = PyFloat_FromDouble(__pyx_v_q.x()); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 59, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = PyFloat_FromDouble(__pyx_v_q.y()); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 59, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_7 = PyFloat_FromDouble(__pyx_v_q.z()); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 59, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_8 = PyList_New(4); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 59, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyList_SET_ITEM(__pyx_t_8, 0, __pyx_t_1)) __PYX_ERR(0, 59, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_5); + if (__Pyx_PyList_SET_ITEM(__pyx_t_8, 1, __pyx_t_5)) __PYX_ERR(0, 59, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_6); + if (__Pyx_PyList_SET_ITEM(__pyx_t_8, 2, __pyx_t_6)) __PYX_ERR(0, 59, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_7); + if (__Pyx_PyList_SET_ITEM(__pyx_t_8, 3, __pyx_t_7)) __PYX_ERR(0, 59, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_5 = 0; + __pyx_t_6 = 0; + __pyx_t_7 = 0; + __pyx_r = __pyx_t_8; + __pyx_t_8 = 0; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":56 + * return g + * + * def euler2quat_single(euler): # <<<<<<<<<<<<<< + * cdef Vector3 e = Vector3(euler[0], euler[1], euler[2]) + * cdef Quaternion q = euler2quat_c(e) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("common.transformations.transformations.euler2quat_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":61 + * return [q.w(), q.x(), q.y(), q.z()] + * + * def quat2euler_single(quat): # <<<<<<<<<<<<<< + * cdef Quaternion q = Quaternion(quat[0], quat[1], quat[2], quat[3]) + * cdef Vector3 e = quat2euler_c(q) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_3quat2euler_single(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_15transformations_15transformations_3quat2euler_single = {"quat2euler_single", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_3quat2euler_single, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_15transformations_15transformations_3quat2euler_single(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_quat = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("quat2euler_single (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_quat,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_quat)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 61, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "quat2euler_single") < 0)) __PYX_ERR(0, 61, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_quat = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("quat2euler_single", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 61, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("common.transformations.transformations.quat2euler_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_15transformations_15transformations_2quat2euler_single(__pyx_self, __pyx_v_quat); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_2quat2euler_single(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_quat) { + Eigen::Quaterniond __pyx_v_q; + Eigen::Vector3d __pyx_v_e; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + double __pyx_t_2; + double __pyx_t_3; + double __pyx_t_4; + double __pyx_t_5; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("quat2euler_single", 1); + + /* "common/transformations/transformations.pyx":62 + * + * def quat2euler_single(quat): + * cdef Quaternion q = Quaternion(quat[0], quat[1], quat[2], quat[3]) # <<<<<<<<<<<<<< + * cdef Vector3 e = quat2euler_c(q) + * return [e(0), e(1), e(2)] + */ + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_quat, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 62, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_2 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 62, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_quat, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 62, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_3 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 62, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_quat, 2, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 62, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_4 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_4 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 62, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_quat, 3, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 62, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_5 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 62, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_q = Eigen::Quaterniond(__pyx_t_2, __pyx_t_3, __pyx_t_4, __pyx_t_5); + + /* "common/transformations/transformations.pyx":63 + * def quat2euler_single(quat): + * cdef Quaternion q = Quaternion(quat[0], quat[1], quat[2], quat[3]) + * cdef Vector3 e = quat2euler_c(q) # <<<<<<<<<<<<<< + * return [e(0), e(1), e(2)] + * + */ + __pyx_v_e = quat2euler(__pyx_v_q); + + /* "common/transformations/transformations.pyx":64 + * cdef Quaternion q = Quaternion(quat[0], quat[1], quat[2], quat[3]) + * cdef Vector3 e = quat2euler_c(q) + * return [e(0), e(1), e(2)] # <<<<<<<<<<<<<< + * + * def quat2rot_single(quat): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyFloat_FromDouble(__pyx_v_e(0)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 64, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_6 = PyFloat_FromDouble(__pyx_v_e(1)); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 64, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_7 = PyFloat_FromDouble(__pyx_v_e(2)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 64, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_8 = PyList_New(3); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 64, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyList_SET_ITEM(__pyx_t_8, 0, __pyx_t_1)) __PYX_ERR(0, 64, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_6); + if (__Pyx_PyList_SET_ITEM(__pyx_t_8, 1, __pyx_t_6)) __PYX_ERR(0, 64, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_7); + if (__Pyx_PyList_SET_ITEM(__pyx_t_8, 2, __pyx_t_7)) __PYX_ERR(0, 64, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_6 = 0; + __pyx_t_7 = 0; + __pyx_r = __pyx_t_8; + __pyx_t_8 = 0; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":61 + * return [q.w(), q.x(), q.y(), q.z()] + * + * def quat2euler_single(quat): # <<<<<<<<<<<<<< + * cdef Quaternion q = Quaternion(quat[0], quat[1], quat[2], quat[3]) + * cdef Vector3 e = quat2euler_c(q) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("common.transformations.transformations.quat2euler_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":66 + * return [e(0), e(1), e(2)] + * + * def quat2rot_single(quat): # <<<<<<<<<<<<<< + * cdef Quaternion q = Quaternion(quat[0], quat[1], quat[2], quat[3]) + * cdef Matrix3 r = quat2rot_c(q) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_5quat2rot_single(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_15transformations_15transformations_5quat2rot_single = {"quat2rot_single", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_5quat2rot_single, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_15transformations_15transformations_5quat2rot_single(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_quat = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("quat2rot_single (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_quat,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_quat)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 66, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "quat2rot_single") < 0)) __PYX_ERR(0, 66, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_quat = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("quat2rot_single", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 66, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("common.transformations.transformations.quat2rot_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_15transformations_15transformations_4quat2rot_single(__pyx_self, __pyx_v_quat); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_4quat2rot_single(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_quat) { + Eigen::Quaterniond __pyx_v_q; + Eigen::Matrix3d __pyx_v_r; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + double __pyx_t_2; + double __pyx_t_3; + double __pyx_t_4; + double __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("quat2rot_single", 1); + + /* "common/transformations/transformations.pyx":67 + * + * def quat2rot_single(quat): + * cdef Quaternion q = Quaternion(quat[0], quat[1], quat[2], quat[3]) # <<<<<<<<<<<<<< + * cdef Matrix3 r = quat2rot_c(q) + * return matrix2numpy(r) + */ + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_quat, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 67, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_2 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 67, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_quat, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 67, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_3 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 67, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_quat, 2, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 67, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_4 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_4 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 67, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_quat, 3, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 67, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_5 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 67, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_q = Eigen::Quaterniond(__pyx_t_2, __pyx_t_3, __pyx_t_4, __pyx_t_5); + + /* "common/transformations/transformations.pyx":68 + * def quat2rot_single(quat): + * cdef Quaternion q = Quaternion(quat[0], quat[1], quat[2], quat[3]) + * cdef Matrix3 r = quat2rot_c(q) # <<<<<<<<<<<<<< + * return matrix2numpy(r) + * + */ + __pyx_v_r = quat2rot(__pyx_v_q); + + /* "common/transformations/transformations.pyx":69 + * cdef Quaternion q = Quaternion(quat[0], quat[1], quat[2], quat[3]) + * cdef Matrix3 r = quat2rot_c(q) + * return matrix2numpy(r) # <<<<<<<<<<<<<< + * + * def rot2quat_single(rot): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = ((PyObject *)__pyx_f_6common_15transformations_15transformations_matrix2numpy(__pyx_v_r)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 69, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":66 + * return [e(0), e(1), e(2)] + * + * def quat2rot_single(quat): # <<<<<<<<<<<<<< + * cdef Quaternion q = Quaternion(quat[0], quat[1], quat[2], quat[3]) + * cdef Matrix3 r = quat2rot_c(q) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("common.transformations.transformations.quat2rot_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":71 + * return matrix2numpy(r) + * + * def rot2quat_single(rot): # <<<<<<<<<<<<<< + * cdef Matrix3 r = numpy2matrix(np.asfortranarray(rot, dtype=np.double)) + * cdef Quaternion q = rot2quat_c(r) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_7rot2quat_single(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_15transformations_15transformations_7rot2quat_single = {"rot2quat_single", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_7rot2quat_single, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_15transformations_15transformations_7rot2quat_single(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_rot = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("rot2quat_single (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_rot,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_rot)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 71, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "rot2quat_single") < 0)) __PYX_ERR(0, 71, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_rot = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("rot2quat_single", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 71, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("common.transformations.transformations.rot2quat_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_15transformations_15transformations_6rot2quat_single(__pyx_self, __pyx_v_rot); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_6rot2quat_single(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_rot) { + Eigen::Matrix3d __pyx_v_r; + Eigen::Quaterniond __pyx_v_q; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + Eigen::Matrix3d __pyx_t_6; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("rot2quat_single", 1); + + /* "common/transformations/transformations.pyx":72 + * + * def rot2quat_single(rot): + * cdef Matrix3 r = numpy2matrix(np.asfortranarray(rot, dtype=np.double)) # <<<<<<<<<<<<<< + * cdef Quaternion q = rot2quat_c(r) + * return [q.w(), q.x(), q.y(), q.z()] + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 72, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_asfortranarray); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 72, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = PyTuple_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 72, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v_rot); + __Pyx_GIVEREF(__pyx_v_rot); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v_rot)) __PYX_ERR(0, 72, __pyx_L1_error); + __pyx_t_3 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 72, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_np); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 72, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_double); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 72, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_dtype, __pyx_t_5) < 0) __PYX_ERR(0, 72, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_5 = __Pyx_PyObject_Call(__pyx_t_2, __pyx_t_1, __pyx_t_3); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 72, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + if (!(likely(((__pyx_t_5) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_5, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 72, __pyx_L1_error) + __pyx_t_6 = __pyx_f_6common_15transformations_15transformations_numpy2matrix(((PyArrayObject *)__pyx_t_5)); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 72, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_v_r = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_6); + + /* "common/transformations/transformations.pyx":73 + * def rot2quat_single(rot): + * cdef Matrix3 r = numpy2matrix(np.asfortranarray(rot, dtype=np.double)) + * cdef Quaternion q = rot2quat_c(r) # <<<<<<<<<<<<<< + * return [q.w(), q.x(), q.y(), q.z()] + * + */ + __pyx_v_q = rot2quat(__pyx_v_r); + + /* "common/transformations/transformations.pyx":74 + * cdef Matrix3 r = numpy2matrix(np.asfortranarray(rot, dtype=np.double)) + * cdef Quaternion q = rot2quat_c(r) + * return [q.w(), q.x(), q.y(), q.z()] # <<<<<<<<<<<<<< + * + * def euler2rot_single(euler): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_5 = PyFloat_FromDouble(__pyx_v_q.w()); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 74, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_3 = PyFloat_FromDouble(__pyx_v_q.x()); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 74, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = PyFloat_FromDouble(__pyx_v_q.y()); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 74, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = PyFloat_FromDouble(__pyx_v_q.z()); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 74, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = PyList_New(4); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 74, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_5); + if (__Pyx_PyList_SET_ITEM(__pyx_t_4, 0, __pyx_t_5)) __PYX_ERR(0, 74, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyList_SET_ITEM(__pyx_t_4, 1, __pyx_t_3)) __PYX_ERR(0, 74, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyList_SET_ITEM(__pyx_t_4, 2, __pyx_t_1)) __PYX_ERR(0, 74, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyList_SET_ITEM(__pyx_t_4, 3, __pyx_t_2)) __PYX_ERR(0, 74, __pyx_L1_error); + __pyx_t_5 = 0; + __pyx_t_3 = 0; + __pyx_t_1 = 0; + __pyx_t_2 = 0; + __pyx_r = __pyx_t_4; + __pyx_t_4 = 0; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":71 + * return matrix2numpy(r) + * + * def rot2quat_single(rot): # <<<<<<<<<<<<<< + * cdef Matrix3 r = numpy2matrix(np.asfortranarray(rot, dtype=np.double)) + * cdef Quaternion q = rot2quat_c(r) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("common.transformations.transformations.rot2quat_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":76 + * return [q.w(), q.x(), q.y(), q.z()] + * + * def euler2rot_single(euler): # <<<<<<<<<<<<<< + * cdef Vector3 e = Vector3(euler[0], euler[1], euler[2]) + * cdef Matrix3 r = euler2rot_c(e) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_9euler2rot_single(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_15transformations_15transformations_9euler2rot_single = {"euler2rot_single", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_9euler2rot_single, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_15transformations_15transformations_9euler2rot_single(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_euler = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("euler2rot_single (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_euler,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_euler)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 76, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "euler2rot_single") < 0)) __PYX_ERR(0, 76, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_euler = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("euler2rot_single", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 76, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("common.transformations.transformations.euler2rot_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_15transformations_15transformations_8euler2rot_single(__pyx_self, __pyx_v_euler); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_8euler2rot_single(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_euler) { + Eigen::Vector3d __pyx_v_e; + Eigen::Matrix3d __pyx_v_r; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + double __pyx_t_2; + double __pyx_t_3; + double __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("euler2rot_single", 1); + + /* "common/transformations/transformations.pyx":77 + * + * def euler2rot_single(euler): + * cdef Vector3 e = Vector3(euler[0], euler[1], euler[2]) # <<<<<<<<<<<<<< + * cdef Matrix3 r = euler2rot_c(e) + * return matrix2numpy(r) + */ + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_euler, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 77, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_2 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 77, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_euler, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 77, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_3 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 77, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_euler, 2, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 77, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_4 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_4 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 77, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_e = Eigen::Vector3d(__pyx_t_2, __pyx_t_3, __pyx_t_4); + + /* "common/transformations/transformations.pyx":78 + * def euler2rot_single(euler): + * cdef Vector3 e = Vector3(euler[0], euler[1], euler[2]) + * cdef Matrix3 r = euler2rot_c(e) # <<<<<<<<<<<<<< + * return matrix2numpy(r) + * + */ + __pyx_v_r = euler2rot(__pyx_v_e); + + /* "common/transformations/transformations.pyx":79 + * cdef Vector3 e = Vector3(euler[0], euler[1], euler[2]) + * cdef Matrix3 r = euler2rot_c(e) + * return matrix2numpy(r) # <<<<<<<<<<<<<< + * + * def rot2euler_single(rot): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = ((PyObject *)__pyx_f_6common_15transformations_15transformations_matrix2numpy(__pyx_v_r)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 79, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":76 + * return [q.w(), q.x(), q.y(), q.z()] + * + * def euler2rot_single(euler): # <<<<<<<<<<<<<< + * cdef Vector3 e = Vector3(euler[0], euler[1], euler[2]) + * cdef Matrix3 r = euler2rot_c(e) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("common.transformations.transformations.euler2rot_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":81 + * return matrix2numpy(r) + * + * def rot2euler_single(rot): # <<<<<<<<<<<<<< + * cdef Matrix3 r = numpy2matrix(np.asfortranarray(rot, dtype=np.double)) + * cdef Vector3 e = rot2euler_c(r) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_11rot2euler_single(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_15transformations_15transformations_11rot2euler_single = {"rot2euler_single", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_11rot2euler_single, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_15transformations_15transformations_11rot2euler_single(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_rot = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("rot2euler_single (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_rot,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_rot)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 81, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "rot2euler_single") < 0)) __PYX_ERR(0, 81, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_rot = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("rot2euler_single", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 81, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("common.transformations.transformations.rot2euler_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_15transformations_15transformations_10rot2euler_single(__pyx_self, __pyx_v_rot); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_10rot2euler_single(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_rot) { + Eigen::Matrix3d __pyx_v_r; + Eigen::Vector3d __pyx_v_e; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + Eigen::Matrix3d __pyx_t_6; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("rot2euler_single", 1); + + /* "common/transformations/transformations.pyx":82 + * + * def rot2euler_single(rot): + * cdef Matrix3 r = numpy2matrix(np.asfortranarray(rot, dtype=np.double)) # <<<<<<<<<<<<<< + * cdef Vector3 e = rot2euler_c(r) + * return [e(0), e(1), e(2)] + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 82, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_asfortranarray); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 82, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = PyTuple_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 82, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v_rot); + __Pyx_GIVEREF(__pyx_v_rot); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v_rot)) __PYX_ERR(0, 82, __pyx_L1_error); + __pyx_t_3 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 82, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_np); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 82, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_double); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 82, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_dtype, __pyx_t_5) < 0) __PYX_ERR(0, 82, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_5 = __Pyx_PyObject_Call(__pyx_t_2, __pyx_t_1, __pyx_t_3); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 82, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + if (!(likely(((__pyx_t_5) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_5, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 82, __pyx_L1_error) + __pyx_t_6 = __pyx_f_6common_15transformations_15transformations_numpy2matrix(((PyArrayObject *)__pyx_t_5)); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 82, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_v_r = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_6); + + /* "common/transformations/transformations.pyx":83 + * def rot2euler_single(rot): + * cdef Matrix3 r = numpy2matrix(np.asfortranarray(rot, dtype=np.double)) + * cdef Vector3 e = rot2euler_c(r) # <<<<<<<<<<<<<< + * return [e(0), e(1), e(2)] + * + */ + __pyx_v_e = rot2euler(__pyx_v_r); + + /* "common/transformations/transformations.pyx":84 + * cdef Matrix3 r = numpy2matrix(np.asfortranarray(rot, dtype=np.double)) + * cdef Vector3 e = rot2euler_c(r) + * return [e(0), e(1), e(2)] # <<<<<<<<<<<<<< + * + * def rot_matrix(roll, pitch, yaw): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_5 = PyFloat_FromDouble(__pyx_v_e(0)); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 84, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_3 = PyFloat_FromDouble(__pyx_v_e(1)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 84, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = PyFloat_FromDouble(__pyx_v_e(2)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 84, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = PyList_New(3); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 84, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_5); + if (__Pyx_PyList_SET_ITEM(__pyx_t_2, 0, __pyx_t_5)) __PYX_ERR(0, 84, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyList_SET_ITEM(__pyx_t_2, 1, __pyx_t_3)) __PYX_ERR(0, 84, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyList_SET_ITEM(__pyx_t_2, 2, __pyx_t_1)) __PYX_ERR(0, 84, __pyx_L1_error); + __pyx_t_5 = 0; + __pyx_t_3 = 0; + __pyx_t_1 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":81 + * return matrix2numpy(r) + * + * def rot2euler_single(rot): # <<<<<<<<<<<<<< + * cdef Matrix3 r = numpy2matrix(np.asfortranarray(rot, dtype=np.double)) + * cdef Vector3 e = rot2euler_c(r) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("common.transformations.transformations.rot2euler_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":86 + * return [e(0), e(1), e(2)] + * + * def rot_matrix(roll, pitch, yaw): # <<<<<<<<<<<<<< + * return matrix2numpy(rot_matrix_c(roll, pitch, yaw)) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_13rot_matrix(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_15transformations_15transformations_13rot_matrix = {"rot_matrix", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_13rot_matrix, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_15transformations_15transformations_13rot_matrix(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_roll = 0; + PyObject *__pyx_v_pitch = 0; + PyObject *__pyx_v_yaw = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("rot_matrix (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_roll,&__pyx_n_s_pitch,&__pyx_n_s_yaw,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_roll)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 86, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pitch)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 86, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("rot_matrix", 1, 3, 3, 1); __PYX_ERR(0, 86, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_yaw)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 86, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("rot_matrix", 1, 3, 3, 2); __PYX_ERR(0, 86, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "rot_matrix") < 0)) __PYX_ERR(0, 86, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + } + __pyx_v_roll = values[0]; + __pyx_v_pitch = values[1]; + __pyx_v_yaw = values[2]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("rot_matrix", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 86, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("common.transformations.transformations.rot_matrix", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_15transformations_15transformations_12rot_matrix(__pyx_self, __pyx_v_roll, __pyx_v_pitch, __pyx_v_yaw); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_12rot_matrix(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_roll, PyObject *__pyx_v_pitch, PyObject *__pyx_v_yaw) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + double __pyx_t_1; + double __pyx_t_2; + double __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("rot_matrix", 1); + + /* "common/transformations/transformations.pyx":87 + * + * def rot_matrix(roll, pitch, yaw): + * return matrix2numpy(rot_matrix_c(roll, pitch, yaw)) # <<<<<<<<<<<<<< + * + * def ecef_euler_from_ned_single(ecef_init, ned_pose): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __pyx_PyFloat_AsDouble(__pyx_v_roll); if (unlikely((__pyx_t_1 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 87, __pyx_L1_error) + __pyx_t_2 = __pyx_PyFloat_AsDouble(__pyx_v_pitch); if (unlikely((__pyx_t_2 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 87, __pyx_L1_error) + __pyx_t_3 = __pyx_PyFloat_AsDouble(__pyx_v_yaw); if (unlikely((__pyx_t_3 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 87, __pyx_L1_error) + __pyx_t_4 = ((PyObject *)__pyx_f_6common_15transformations_15transformations_matrix2numpy(rot_matrix(__pyx_t_1, __pyx_t_2, __pyx_t_3))); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 87, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_r = __pyx_t_4; + __pyx_t_4 = 0; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":86 + * return [e(0), e(1), e(2)] + * + * def rot_matrix(roll, pitch, yaw): # <<<<<<<<<<<<<< + * return matrix2numpy(rot_matrix_c(roll, pitch, yaw)) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("common.transformations.transformations.rot_matrix", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":89 + * return matrix2numpy(rot_matrix_c(roll, pitch, yaw)) + * + * def ecef_euler_from_ned_single(ecef_init, ned_pose): # <<<<<<<<<<<<<< + * cdef ECEF init = list2ecef(ecef_init) + * cdef Vector3 pose = Vector3(ned_pose[0], ned_pose[1], ned_pose[2]) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_15ecef_euler_from_ned_single(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_15transformations_15transformations_15ecef_euler_from_ned_single = {"ecef_euler_from_ned_single", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_15ecef_euler_from_ned_single, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_15transformations_15transformations_15ecef_euler_from_ned_single(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_ecef_init = 0; + PyObject *__pyx_v_ned_pose = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[2] = {0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("ecef_euler_from_ned_single (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_ecef_init,&__pyx_n_s_ned_pose,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_ecef_init)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 89, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_ned_pose)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 89, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("ecef_euler_from_ned_single", 1, 2, 2, 1); __PYX_ERR(0, 89, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "ecef_euler_from_ned_single") < 0)) __PYX_ERR(0, 89, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 2)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + } + __pyx_v_ecef_init = values[0]; + __pyx_v_ned_pose = values[1]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("ecef_euler_from_ned_single", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 89, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("common.transformations.transformations.ecef_euler_from_ned_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_15transformations_15transformations_14ecef_euler_from_ned_single(__pyx_self, __pyx_v_ecef_init, __pyx_v_ned_pose); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_14ecef_euler_from_ned_single(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_ecef_init, PyObject *__pyx_v_ned_pose) { + struct ECEF __pyx_v_init; + Eigen::Vector3d __pyx_v_pose; + Eigen::Vector3d __pyx_v_e; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + struct ECEF __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + double __pyx_t_3; + double __pyx_t_4; + double __pyx_t_5; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("ecef_euler_from_ned_single", 1); + + /* "common/transformations/transformations.pyx":90 + * + * def ecef_euler_from_ned_single(ecef_init, ned_pose): + * cdef ECEF init = list2ecef(ecef_init) # <<<<<<<<<<<<<< + * cdef Vector3 pose = Vector3(ned_pose[0], ned_pose[1], ned_pose[2]) + * + */ + __pyx_t_1 = __pyx_f_6common_15transformations_15transformations_list2ecef(__pyx_v_ecef_init); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 90, __pyx_L1_error) + __pyx_v_init = __pyx_t_1; + + /* "common/transformations/transformations.pyx":91 + * def ecef_euler_from_ned_single(ecef_init, ned_pose): + * cdef ECEF init = list2ecef(ecef_init) + * cdef Vector3 pose = Vector3(ned_pose[0], ned_pose[1], ned_pose[2]) # <<<<<<<<<<<<<< + * + * cdef Vector3 e = ecef_euler_from_ned_c(init, pose) + */ + __pyx_t_2 = __Pyx_GetItemInt(__pyx_v_ned_pose, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 91, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __pyx_PyFloat_AsDouble(__pyx_t_2); if (unlikely((__pyx_t_3 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 91, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_GetItemInt(__pyx_v_ned_pose, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 91, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __pyx_PyFloat_AsDouble(__pyx_t_2); if (unlikely((__pyx_t_4 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 91, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_GetItemInt(__pyx_v_ned_pose, 2, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 91, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_5 = __pyx_PyFloat_AsDouble(__pyx_t_2); if (unlikely((__pyx_t_5 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 91, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_v_pose = Eigen::Vector3d(__pyx_t_3, __pyx_t_4, __pyx_t_5); + + /* "common/transformations/transformations.pyx":93 + * cdef Vector3 pose = Vector3(ned_pose[0], ned_pose[1], ned_pose[2]) + * + * cdef Vector3 e = ecef_euler_from_ned_c(init, pose) # <<<<<<<<<<<<<< + * return [e(0), e(1), e(2)] + * + */ + __pyx_v_e = ecef_euler_from_ned(__pyx_v_init, __pyx_v_pose); + + /* "common/transformations/transformations.pyx":94 + * + * cdef Vector3 e = ecef_euler_from_ned_c(init, pose) + * return [e(0), e(1), e(2)] # <<<<<<<<<<<<<< + * + * def ned_euler_from_ecef_single(ecef_init, ecef_pose): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = PyFloat_FromDouble(__pyx_v_e(0)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 94, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_6 = PyFloat_FromDouble(__pyx_v_e(1)); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 94, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_7 = PyFloat_FromDouble(__pyx_v_e(2)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 94, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_8 = PyList_New(3); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 94, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyList_SET_ITEM(__pyx_t_8, 0, __pyx_t_2)) __PYX_ERR(0, 94, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_6); + if (__Pyx_PyList_SET_ITEM(__pyx_t_8, 1, __pyx_t_6)) __PYX_ERR(0, 94, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_7); + if (__Pyx_PyList_SET_ITEM(__pyx_t_8, 2, __pyx_t_7)) __PYX_ERR(0, 94, __pyx_L1_error); + __pyx_t_2 = 0; + __pyx_t_6 = 0; + __pyx_t_7 = 0; + __pyx_r = __pyx_t_8; + __pyx_t_8 = 0; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":89 + * return matrix2numpy(rot_matrix_c(roll, pitch, yaw)) + * + * def ecef_euler_from_ned_single(ecef_init, ned_pose): # <<<<<<<<<<<<<< + * cdef ECEF init = list2ecef(ecef_init) + * cdef Vector3 pose = Vector3(ned_pose[0], ned_pose[1], ned_pose[2]) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("common.transformations.transformations.ecef_euler_from_ned_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":96 + * return [e(0), e(1), e(2)] + * + * def ned_euler_from_ecef_single(ecef_init, ecef_pose): # <<<<<<<<<<<<<< + * cdef ECEF init = list2ecef(ecef_init) + * cdef Vector3 pose = Vector3(ecef_pose[0], ecef_pose[1], ecef_pose[2]) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_17ned_euler_from_ecef_single(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_15transformations_15transformations_17ned_euler_from_ecef_single = {"ned_euler_from_ecef_single", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_17ned_euler_from_ecef_single, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_15transformations_15transformations_17ned_euler_from_ecef_single(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_ecef_init = 0; + PyObject *__pyx_v_ecef_pose = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[2] = {0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("ned_euler_from_ecef_single (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_ecef_init,&__pyx_n_s_ecef_pose,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_ecef_init)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 96, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_ecef_pose)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 96, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("ned_euler_from_ecef_single", 1, 2, 2, 1); __PYX_ERR(0, 96, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "ned_euler_from_ecef_single") < 0)) __PYX_ERR(0, 96, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 2)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + } + __pyx_v_ecef_init = values[0]; + __pyx_v_ecef_pose = values[1]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("ned_euler_from_ecef_single", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 96, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("common.transformations.transformations.ned_euler_from_ecef_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_15transformations_15transformations_16ned_euler_from_ecef_single(__pyx_self, __pyx_v_ecef_init, __pyx_v_ecef_pose); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_16ned_euler_from_ecef_single(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_ecef_init, PyObject *__pyx_v_ecef_pose) { + struct ECEF __pyx_v_init; + Eigen::Vector3d __pyx_v_pose; + Eigen::Vector3d __pyx_v_e; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + struct ECEF __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + double __pyx_t_3; + double __pyx_t_4; + double __pyx_t_5; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("ned_euler_from_ecef_single", 1); + + /* "common/transformations/transformations.pyx":97 + * + * def ned_euler_from_ecef_single(ecef_init, ecef_pose): + * cdef ECEF init = list2ecef(ecef_init) # <<<<<<<<<<<<<< + * cdef Vector3 pose = Vector3(ecef_pose[0], ecef_pose[1], ecef_pose[2]) + * + */ + __pyx_t_1 = __pyx_f_6common_15transformations_15transformations_list2ecef(__pyx_v_ecef_init); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 97, __pyx_L1_error) + __pyx_v_init = __pyx_t_1; + + /* "common/transformations/transformations.pyx":98 + * def ned_euler_from_ecef_single(ecef_init, ecef_pose): + * cdef ECEF init = list2ecef(ecef_init) + * cdef Vector3 pose = Vector3(ecef_pose[0], ecef_pose[1], ecef_pose[2]) # <<<<<<<<<<<<<< + * + * cdef Vector3 e = ned_euler_from_ecef_c(init, pose) + */ + __pyx_t_2 = __Pyx_GetItemInt(__pyx_v_ecef_pose, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 98, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __pyx_PyFloat_AsDouble(__pyx_t_2); if (unlikely((__pyx_t_3 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 98, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_GetItemInt(__pyx_v_ecef_pose, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 98, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __pyx_PyFloat_AsDouble(__pyx_t_2); if (unlikely((__pyx_t_4 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 98, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_GetItemInt(__pyx_v_ecef_pose, 2, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 98, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_5 = __pyx_PyFloat_AsDouble(__pyx_t_2); if (unlikely((__pyx_t_5 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 98, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_v_pose = Eigen::Vector3d(__pyx_t_3, __pyx_t_4, __pyx_t_5); + + /* "common/transformations/transformations.pyx":100 + * cdef Vector3 pose = Vector3(ecef_pose[0], ecef_pose[1], ecef_pose[2]) + * + * cdef Vector3 e = ned_euler_from_ecef_c(init, pose) # <<<<<<<<<<<<<< + * return [e(0), e(1), e(2)] + * + */ + __pyx_v_e = ned_euler_from_ecef(__pyx_v_init, __pyx_v_pose); + + /* "common/transformations/transformations.pyx":101 + * + * cdef Vector3 e = ned_euler_from_ecef_c(init, pose) + * return [e(0), e(1), e(2)] # <<<<<<<<<<<<<< + * + * def geodetic2ecef_single(geodetic): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = PyFloat_FromDouble(__pyx_v_e(0)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 101, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_6 = PyFloat_FromDouble(__pyx_v_e(1)); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 101, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_7 = PyFloat_FromDouble(__pyx_v_e(2)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 101, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_8 = PyList_New(3); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 101, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyList_SET_ITEM(__pyx_t_8, 0, __pyx_t_2)) __PYX_ERR(0, 101, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_6); + if (__Pyx_PyList_SET_ITEM(__pyx_t_8, 1, __pyx_t_6)) __PYX_ERR(0, 101, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_7); + if (__Pyx_PyList_SET_ITEM(__pyx_t_8, 2, __pyx_t_7)) __PYX_ERR(0, 101, __pyx_L1_error); + __pyx_t_2 = 0; + __pyx_t_6 = 0; + __pyx_t_7 = 0; + __pyx_r = __pyx_t_8; + __pyx_t_8 = 0; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":96 + * return [e(0), e(1), e(2)] + * + * def ned_euler_from_ecef_single(ecef_init, ecef_pose): # <<<<<<<<<<<<<< + * cdef ECEF init = list2ecef(ecef_init) + * cdef Vector3 pose = Vector3(ecef_pose[0], ecef_pose[1], ecef_pose[2]) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("common.transformations.transformations.ned_euler_from_ecef_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":103 + * return [e(0), e(1), e(2)] + * + * def geodetic2ecef_single(geodetic): # <<<<<<<<<<<<<< + * cdef Geodetic g = list2geodetic(geodetic) + * cdef ECEF e = geodetic2ecef_c(g) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_19geodetic2ecef_single(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_15transformations_15transformations_19geodetic2ecef_single = {"geodetic2ecef_single", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_19geodetic2ecef_single, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_15transformations_15transformations_19geodetic2ecef_single(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_geodetic = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("geodetic2ecef_single (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_geodetic,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_geodetic)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 103, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "geodetic2ecef_single") < 0)) __PYX_ERR(0, 103, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_geodetic = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("geodetic2ecef_single", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 103, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("common.transformations.transformations.geodetic2ecef_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_15transformations_15transformations_18geodetic2ecef_single(__pyx_self, __pyx_v_geodetic); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_18geodetic2ecef_single(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_geodetic) { + struct Geodetic __pyx_v_g; + struct ECEF __pyx_v_e; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + struct Geodetic __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("geodetic2ecef_single", 1); + + /* "common/transformations/transformations.pyx":104 + * + * def geodetic2ecef_single(geodetic): + * cdef Geodetic g = list2geodetic(geodetic) # <<<<<<<<<<<<<< + * cdef ECEF e = geodetic2ecef_c(g) + * return [e.x, e.y, e.z] + */ + __pyx_t_1 = __pyx_f_6common_15transformations_15transformations_list2geodetic(__pyx_v_geodetic); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 104, __pyx_L1_error) + __pyx_v_g = __pyx_t_1; + + /* "common/transformations/transformations.pyx":105 + * def geodetic2ecef_single(geodetic): + * cdef Geodetic g = list2geodetic(geodetic) + * cdef ECEF e = geodetic2ecef_c(g) # <<<<<<<<<<<<<< + * return [e.x, e.y, e.z] + * + */ + __pyx_v_e = geodetic2ecef(__pyx_v_g); + + /* "common/transformations/transformations.pyx":106 + * cdef Geodetic g = list2geodetic(geodetic) + * cdef ECEF e = geodetic2ecef_c(g) + * return [e.x, e.y, e.z] # <<<<<<<<<<<<<< + * + * def ecef2geodetic_single(ecef): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = PyFloat_FromDouble(__pyx_v_e.x); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 106, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyFloat_FromDouble(__pyx_v_e.y); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 106, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PyFloat_FromDouble(__pyx_v_e.z); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 106, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = PyList_New(3); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 106, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyList_SET_ITEM(__pyx_t_5, 0, __pyx_t_2)) __PYX_ERR(0, 106, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyList_SET_ITEM(__pyx_t_5, 1, __pyx_t_3)) __PYX_ERR(0, 106, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_4); + if (__Pyx_PyList_SET_ITEM(__pyx_t_5, 2, __pyx_t_4)) __PYX_ERR(0, 106, __pyx_L1_error); + __pyx_t_2 = 0; + __pyx_t_3 = 0; + __pyx_t_4 = 0; + __pyx_r = __pyx_t_5; + __pyx_t_5 = 0; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":103 + * return [e(0), e(1), e(2)] + * + * def geodetic2ecef_single(geodetic): # <<<<<<<<<<<<<< + * cdef Geodetic g = list2geodetic(geodetic) + * cdef ECEF e = geodetic2ecef_c(g) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("common.transformations.transformations.geodetic2ecef_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":108 + * return [e.x, e.y, e.z] + * + * def ecef2geodetic_single(ecef): # <<<<<<<<<<<<<< + * cdef ECEF e = list2ecef(ecef) + * cdef Geodetic g = ecef2geodetic_c(e) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_21ecef2geodetic_single(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_15transformations_15transformations_21ecef2geodetic_single = {"ecef2geodetic_single", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_21ecef2geodetic_single, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_15transformations_15transformations_21ecef2geodetic_single(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_ecef = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("ecef2geodetic_single (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_ecef,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_ecef)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 108, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "ecef2geodetic_single") < 0)) __PYX_ERR(0, 108, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_ecef = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("ecef2geodetic_single", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 108, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("common.transformations.transformations.ecef2geodetic_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_15transformations_15transformations_20ecef2geodetic_single(__pyx_self, __pyx_v_ecef); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_20ecef2geodetic_single(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_ecef) { + struct ECEF __pyx_v_e; + struct Geodetic __pyx_v_g; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + struct ECEF __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("ecef2geodetic_single", 1); + + /* "common/transformations/transformations.pyx":109 + * + * def ecef2geodetic_single(ecef): + * cdef ECEF e = list2ecef(ecef) # <<<<<<<<<<<<<< + * cdef Geodetic g = ecef2geodetic_c(e) + * return [g.lat, g.lon, g.alt] + */ + __pyx_t_1 = __pyx_f_6common_15transformations_15transformations_list2ecef(__pyx_v_ecef); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 109, __pyx_L1_error) + __pyx_v_e = __pyx_t_1; + + /* "common/transformations/transformations.pyx":110 + * def ecef2geodetic_single(ecef): + * cdef ECEF e = list2ecef(ecef) + * cdef Geodetic g = ecef2geodetic_c(e) # <<<<<<<<<<<<<< + * return [g.lat, g.lon, g.alt] + * + */ + __pyx_v_g = ecef2geodetic(__pyx_v_e); + + /* "common/transformations/transformations.pyx":111 + * cdef ECEF e = list2ecef(ecef) + * cdef Geodetic g = ecef2geodetic_c(e) + * return [g.lat, g.lon, g.alt] # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = PyFloat_FromDouble(__pyx_v_g.lat); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 111, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyFloat_FromDouble(__pyx_v_g.lon); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 111, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PyFloat_FromDouble(__pyx_v_g.alt); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 111, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = PyList_New(3); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 111, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyList_SET_ITEM(__pyx_t_5, 0, __pyx_t_2)) __PYX_ERR(0, 111, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyList_SET_ITEM(__pyx_t_5, 1, __pyx_t_3)) __PYX_ERR(0, 111, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_4); + if (__Pyx_PyList_SET_ITEM(__pyx_t_5, 2, __pyx_t_4)) __PYX_ERR(0, 111, __pyx_L1_error); + __pyx_t_2 = 0; + __pyx_t_3 = 0; + __pyx_t_4 = 0; + __pyx_r = __pyx_t_5; + __pyx_t_5 = 0; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":108 + * return [e.x, e.y, e.z] + * + * def ecef2geodetic_single(ecef): # <<<<<<<<<<<<<< + * cdef ECEF e = list2ecef(ecef) + * cdef Geodetic g = ecef2geodetic_c(e) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("common.transformations.transformations.ecef2geodetic_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":117 + * cdef LocalCoord_c * lc + * + * def __init__(self, geodetic=None, ecef=None): # <<<<<<<<<<<<<< + * assert (geodetic is not None) or (ecef is not None) + * if geodetic is not None: + */ + +/* Python wrapper */ +static int __pyx_pw_6common_15transformations_15transformations_10LocalCoord_1__init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_pw_6common_15transformations_15transformations_10LocalCoord_1__init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_geodetic = 0; + PyObject *__pyx_v_ecef = 0; + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[2] = {0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__init__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_geodetic,&__pyx_n_s_ecef,0}; + values[0] = __Pyx_Arg_NewRef_VARARGS(((PyObject *)Py_None)); + values[1] = __Pyx_Arg_NewRef_VARARGS(((PyObject *)Py_None)); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_geodetic); + if (value) { values[0] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 117, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 1: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_ecef); + if (value) { values[1] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 117, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__init__") < 0)) __PYX_ERR(0, 117, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_geodetic = values[0]; + __pyx_v_ecef = values[1]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__init__", 0, 0, 2, __pyx_nargs); __PYX_ERR(0, 117, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("common.transformations.transformations.LocalCoord.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_15transformations_15transformations_10LocalCoord___init__(((struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *)__pyx_v_self), __pyx_v_geodetic, __pyx_v_ecef); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_6common_15transformations_15transformations_10LocalCoord___init__(struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self, PyObject *__pyx_v_geodetic, PyObject *__pyx_v_ecef) { + int __pyx_r; + int __pyx_t_1; + int __pyx_t_2; + struct Geodetic __pyx_t_3; + struct ECEF __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + + /* "common/transformations/transformations.pyx":118 + * + * def __init__(self, geodetic=None, ecef=None): + * assert (geodetic is not None) or (ecef is not None) # <<<<<<<<<<<<<< + * if geodetic is not None: + * self.lc = new LocalCoord_c(list2geodetic(geodetic)) + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_2 = (__pyx_v_geodetic != Py_None); + if (!__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L3_bool_binop_done; + } + __pyx_t_2 = (__pyx_v_ecef != Py_None); + __pyx_t_1 = __pyx_t_2; + __pyx_L3_bool_binop_done:; + if (unlikely(!__pyx_t_1)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(0, 118, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(0, 118, __pyx_L1_error) + #endif + + /* "common/transformations/transformations.pyx":119 + * def __init__(self, geodetic=None, ecef=None): + * assert (geodetic is not None) or (ecef is not None) + * if geodetic is not None: # <<<<<<<<<<<<<< + * self.lc = new LocalCoord_c(list2geodetic(geodetic)) + * elif ecef is not None: + */ + __pyx_t_1 = (__pyx_v_geodetic != Py_None); + if (__pyx_t_1) { + + /* "common/transformations/transformations.pyx":120 + * assert (geodetic is not None) or (ecef is not None) + * if geodetic is not None: + * self.lc = new LocalCoord_c(list2geodetic(geodetic)) # <<<<<<<<<<<<<< + * elif ecef is not None: + * self.lc = new LocalCoord_c(list2ecef(ecef)) + */ + __pyx_t_3 = __pyx_f_6common_15transformations_15transformations_list2geodetic(__pyx_v_geodetic); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 120, __pyx_L1_error) + __pyx_v_self->lc = new LocalCoord(__pyx_t_3); + + /* "common/transformations/transformations.pyx":119 + * def __init__(self, geodetic=None, ecef=None): + * assert (geodetic is not None) or (ecef is not None) + * if geodetic is not None: # <<<<<<<<<<<<<< + * self.lc = new LocalCoord_c(list2geodetic(geodetic)) + * elif ecef is not None: + */ + goto __pyx_L5; + } + + /* "common/transformations/transformations.pyx":121 + * if geodetic is not None: + * self.lc = new LocalCoord_c(list2geodetic(geodetic)) + * elif ecef is not None: # <<<<<<<<<<<<<< + * self.lc = new LocalCoord_c(list2ecef(ecef)) + * + */ + __pyx_t_1 = (__pyx_v_ecef != Py_None); + if (__pyx_t_1) { + + /* "common/transformations/transformations.pyx":122 + * self.lc = new LocalCoord_c(list2geodetic(geodetic)) + * elif ecef is not None: + * self.lc = new LocalCoord_c(list2ecef(ecef)) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_t_4 = __pyx_f_6common_15transformations_15transformations_list2ecef(__pyx_v_ecef); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 122, __pyx_L1_error) + __pyx_v_self->lc = new LocalCoord(__pyx_t_4); + + /* "common/transformations/transformations.pyx":121 + * if geodetic is not None: + * self.lc = new LocalCoord_c(list2geodetic(geodetic)) + * elif ecef is not None: # <<<<<<<<<<<<<< + * self.lc = new LocalCoord_c(list2ecef(ecef)) + * + */ + } + __pyx_L5:; + + /* "common/transformations/transformations.pyx":117 + * cdef LocalCoord_c * lc + * + * def __init__(self, geodetic=None, ecef=None): # <<<<<<<<<<<<<< + * assert (geodetic is not None) or (ecef is not None) + * if geodetic is not None: + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("common.transformations.transformations.LocalCoord.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":124 + * self.lc = new LocalCoord_c(list2ecef(ecef)) + * + * @property # <<<<<<<<<<<<<< + * def ned2ecef_matrix(self): + * return matrix2numpy(self.lc.ned2ecef_matrix) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_15ned2ecef_matrix_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_15ned2ecef_matrix_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_6common_15transformations_15transformations_10LocalCoord_15ned2ecef_matrix___get__(((struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_15ned2ecef_matrix___get__(struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "common/transformations/transformations.pyx":126 + * @property + * def ned2ecef_matrix(self): + * return matrix2numpy(self.lc.ned2ecef_matrix) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = ((PyObject *)__pyx_f_6common_15transformations_15transformations_matrix2numpy(__pyx_v_self->lc->ned2ecef_matrix)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 126, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":124 + * self.lc = new LocalCoord_c(list2ecef(ecef)) + * + * @property # <<<<<<<<<<<<<< + * def ned2ecef_matrix(self): + * return matrix2numpy(self.lc.ned2ecef_matrix) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("common.transformations.transformations.LocalCoord.ned2ecef_matrix.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":128 + * return matrix2numpy(self.lc.ned2ecef_matrix) + * + * @property # <<<<<<<<<<<<<< + * def ecef2ned_matrix(self): + * return matrix2numpy(self.lc.ecef2ned_matrix) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_15ecef2ned_matrix_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_15ecef2ned_matrix_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_6common_15transformations_15transformations_10LocalCoord_15ecef2ned_matrix___get__(((struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_15ecef2ned_matrix___get__(struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "common/transformations/transformations.pyx":130 + * @property + * def ecef2ned_matrix(self): + * return matrix2numpy(self.lc.ecef2ned_matrix) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = ((PyObject *)__pyx_f_6common_15transformations_15transformations_matrix2numpy(__pyx_v_self->lc->ecef2ned_matrix)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 130, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":128 + * return matrix2numpy(self.lc.ned2ecef_matrix) + * + * @property # <<<<<<<<<<<<<< + * def ecef2ned_matrix(self): + * return matrix2numpy(self.lc.ecef2ned_matrix) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("common.transformations.transformations.LocalCoord.ecef2ned_matrix.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":132 + * return matrix2numpy(self.lc.ecef2ned_matrix) + * + * @property # <<<<<<<<<<<<<< + * def ned_from_ecef_matrix(self): + * return self.ecef2ned_matrix + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_20ned_from_ecef_matrix_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_20ned_from_ecef_matrix_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_6common_15transformations_15transformations_10LocalCoord_20ned_from_ecef_matrix___get__(((struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_20ned_from_ecef_matrix___get__(struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "common/transformations/transformations.pyx":134 + * @property + * def ned_from_ecef_matrix(self): + * return self.ecef2ned_matrix # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_ecef2ned_matrix); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 134, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":132 + * return matrix2numpy(self.lc.ecef2ned_matrix) + * + * @property # <<<<<<<<<<<<<< + * def ned_from_ecef_matrix(self): + * return self.ecef2ned_matrix + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("common.transformations.transformations.LocalCoord.ned_from_ecef_matrix.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":136 + * return self.ecef2ned_matrix + * + * @property # <<<<<<<<<<<<<< + * def ecef_from_ned_matrix(self): + * return self.ned2ecef_matrix + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_20ecef_from_ned_matrix_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_20ecef_from_ned_matrix_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_6common_15transformations_15transformations_10LocalCoord_20ecef_from_ned_matrix___get__(((struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_20ecef_from_ned_matrix___get__(struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "common/transformations/transformations.pyx":138 + * @property + * def ecef_from_ned_matrix(self): + * return self.ned2ecef_matrix # <<<<<<<<<<<<<< + * + * @classmethod + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_ned2ecef_matrix); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 138, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":136 + * return self.ecef2ned_matrix + * + * @property # <<<<<<<<<<<<<< + * def ecef_from_ned_matrix(self): + * return self.ned2ecef_matrix + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("common.transformations.transformations.LocalCoord.ecef_from_ned_matrix.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":140 + * return self.ned2ecef_matrix + * + * @classmethod # <<<<<<<<<<<<<< + * def from_geodetic(cls, geodetic): + * return cls(geodetic=geodetic) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_3from_geodetic(PyObject *__pyx_v_cls, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_15transformations_15transformations_10LocalCoord_3from_geodetic = {"from_geodetic", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_10LocalCoord_3from_geodetic, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_3from_geodetic(PyObject *__pyx_v_cls, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_geodetic = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("from_geodetic (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_geodetic,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_geodetic)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 140, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "from_geodetic") < 0)) __PYX_ERR(0, 140, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_geodetic = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("from_geodetic", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 140, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("common.transformations.transformations.LocalCoord.from_geodetic", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_15transformations_15transformations_10LocalCoord_2from_geodetic(((PyTypeObject*)__pyx_v_cls), __pyx_v_geodetic); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_2from_geodetic(PyTypeObject *__pyx_v_cls, PyObject *__pyx_v_geodetic) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("from_geodetic", 1); + + /* "common/transformations/transformations.pyx":142 + * @classmethod + * def from_geodetic(cls, geodetic): + * return cls(geodetic=geodetic) # <<<<<<<<<<<<<< + * + * @classmethod + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 142, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (PyDict_SetItem(__pyx_t_1, __pyx_n_s_geodetic, __pyx_v_geodetic) < 0) __PYX_ERR(0, 142, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_Call(((PyObject *)__pyx_v_cls), __pyx_empty_tuple, __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 142, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":140 + * return self.ned2ecef_matrix + * + * @classmethod # <<<<<<<<<<<<<< + * def from_geodetic(cls, geodetic): + * return cls(geodetic=geodetic) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("common.transformations.transformations.LocalCoord.from_geodetic", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":144 + * return cls(geodetic=geodetic) + * + * @classmethod # <<<<<<<<<<<<<< + * def from_ecef(cls, ecef): + * return cls(ecef=ecef) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_5from_ecef(PyObject *__pyx_v_cls, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_15transformations_15transformations_10LocalCoord_5from_ecef = {"from_ecef", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_10LocalCoord_5from_ecef, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_5from_ecef(PyObject *__pyx_v_cls, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_ecef = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("from_ecef (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_ecef,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_ecef)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 144, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "from_ecef") < 0)) __PYX_ERR(0, 144, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_ecef = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("from_ecef", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 144, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("common.transformations.transformations.LocalCoord.from_ecef", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_15transformations_15transformations_10LocalCoord_4from_ecef(((PyTypeObject*)__pyx_v_cls), __pyx_v_ecef); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_4from_ecef(PyTypeObject *__pyx_v_cls, PyObject *__pyx_v_ecef) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("from_ecef", 1); + + /* "common/transformations/transformations.pyx":146 + * @classmethod + * def from_ecef(cls, ecef): + * return cls(ecef=ecef) # <<<<<<<<<<<<<< + * + * def ecef2ned_single(self, ecef): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 146, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (PyDict_SetItem(__pyx_t_1, __pyx_n_s_ecef, __pyx_v_ecef) < 0) __PYX_ERR(0, 146, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_Call(((PyObject *)__pyx_v_cls), __pyx_empty_tuple, __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 146, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":144 + * return cls(geodetic=geodetic) + * + * @classmethod # <<<<<<<<<<<<<< + * def from_ecef(cls, ecef): + * return cls(ecef=ecef) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("common.transformations.transformations.LocalCoord.from_ecef", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":148 + * return cls(ecef=ecef) + * + * def ecef2ned_single(self, ecef): # <<<<<<<<<<<<<< + * assert self.lc + * cdef ECEF e = list2ecef(ecef) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_7ecef2ned_single(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_15transformations_15transformations_10LocalCoord_7ecef2ned_single = {"ecef2ned_single", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_10LocalCoord_7ecef2ned_single, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_7ecef2ned_single(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_ecef = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("ecef2ned_single (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_ecef,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_ecef)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 148, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "ecef2ned_single") < 0)) __PYX_ERR(0, 148, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_ecef = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("ecef2ned_single", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 148, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("common.transformations.transformations.LocalCoord.ecef2ned_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_15transformations_15transformations_10LocalCoord_6ecef2ned_single(((struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *)__pyx_v_self), __pyx_v_ecef); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_6ecef2ned_single(struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self, PyObject *__pyx_v_ecef) { + struct ECEF __pyx_v_e; + struct NED __pyx_v_n; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + struct ECEF __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("ecef2ned_single", 1); + + /* "common/transformations/transformations.pyx":149 + * + * def ecef2ned_single(self, ecef): + * assert self.lc # <<<<<<<<<<<<<< + * cdef ECEF e = list2ecef(ecef) + * cdef NED n = self.lc.ecef2ned(e) + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_1 = (__pyx_v_self->lc != 0); + if (unlikely(!__pyx_t_1)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(0, 149, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(0, 149, __pyx_L1_error) + #endif + + /* "common/transformations/transformations.pyx":150 + * def ecef2ned_single(self, ecef): + * assert self.lc + * cdef ECEF e = list2ecef(ecef) # <<<<<<<<<<<<<< + * cdef NED n = self.lc.ecef2ned(e) + * return [n.n, n.e, n.d] + */ + __pyx_t_2 = __pyx_f_6common_15transformations_15transformations_list2ecef(__pyx_v_ecef); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 150, __pyx_L1_error) + __pyx_v_e = __pyx_t_2; + + /* "common/transformations/transformations.pyx":151 + * assert self.lc + * cdef ECEF e = list2ecef(ecef) + * cdef NED n = self.lc.ecef2ned(e) # <<<<<<<<<<<<<< + * return [n.n, n.e, n.d] + * + */ + __pyx_v_n = __pyx_v_self->lc->ecef2ned(__pyx_v_e); + + /* "common/transformations/transformations.pyx":152 + * cdef ECEF e = list2ecef(ecef) + * cdef NED n = self.lc.ecef2ned(e) + * return [n.n, n.e, n.d] # <<<<<<<<<<<<<< + * + * def ned2ecef_single(self, ned): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_3 = PyFloat_FromDouble(__pyx_v_n.n); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 152, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PyFloat_FromDouble(__pyx_v_n.e); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 152, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = PyFloat_FromDouble(__pyx_v_n.d); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 152, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = PyList_New(3); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 152, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyList_SET_ITEM(__pyx_t_6, 0, __pyx_t_3)) __PYX_ERR(0, 152, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_4); + if (__Pyx_PyList_SET_ITEM(__pyx_t_6, 1, __pyx_t_4)) __PYX_ERR(0, 152, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_5); + if (__Pyx_PyList_SET_ITEM(__pyx_t_6, 2, __pyx_t_5)) __PYX_ERR(0, 152, __pyx_L1_error); + __pyx_t_3 = 0; + __pyx_t_4 = 0; + __pyx_t_5 = 0; + __pyx_r = __pyx_t_6; + __pyx_t_6 = 0; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":148 + * return cls(ecef=ecef) + * + * def ecef2ned_single(self, ecef): # <<<<<<<<<<<<<< + * assert self.lc + * cdef ECEF e = list2ecef(ecef) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("common.transformations.transformations.LocalCoord.ecef2ned_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":154 + * return [n.n, n.e, n.d] + * + * def ned2ecef_single(self, ned): # <<<<<<<<<<<<<< + * assert self.lc + * cdef NED n = list2ned(ned) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_9ned2ecef_single(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_15transformations_15transformations_10LocalCoord_9ned2ecef_single = {"ned2ecef_single", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_10LocalCoord_9ned2ecef_single, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_9ned2ecef_single(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_ned = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("ned2ecef_single (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_ned,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_ned)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 154, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "ned2ecef_single") < 0)) __PYX_ERR(0, 154, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_ned = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("ned2ecef_single", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 154, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("common.transformations.transformations.LocalCoord.ned2ecef_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_15transformations_15transformations_10LocalCoord_8ned2ecef_single(((struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *)__pyx_v_self), __pyx_v_ned); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_8ned2ecef_single(struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self, PyObject *__pyx_v_ned) { + struct NED __pyx_v_n; + struct ECEF __pyx_v_e; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + struct NED __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("ned2ecef_single", 1); + + /* "common/transformations/transformations.pyx":155 + * + * def ned2ecef_single(self, ned): + * assert self.lc # <<<<<<<<<<<<<< + * cdef NED n = list2ned(ned) + * cdef ECEF e = self.lc.ned2ecef(n) + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_1 = (__pyx_v_self->lc != 0); + if (unlikely(!__pyx_t_1)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(0, 155, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(0, 155, __pyx_L1_error) + #endif + + /* "common/transformations/transformations.pyx":156 + * def ned2ecef_single(self, ned): + * assert self.lc + * cdef NED n = list2ned(ned) # <<<<<<<<<<<<<< + * cdef ECEF e = self.lc.ned2ecef(n) + * return [e.x, e.y, e.z] + */ + __pyx_t_2 = __pyx_f_6common_15transformations_15transformations_list2ned(__pyx_v_ned); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 156, __pyx_L1_error) + __pyx_v_n = __pyx_t_2; + + /* "common/transformations/transformations.pyx":157 + * assert self.lc + * cdef NED n = list2ned(ned) + * cdef ECEF e = self.lc.ned2ecef(n) # <<<<<<<<<<<<<< + * return [e.x, e.y, e.z] + * + */ + __pyx_v_e = __pyx_v_self->lc->ned2ecef(__pyx_v_n); + + /* "common/transformations/transformations.pyx":158 + * cdef NED n = list2ned(ned) + * cdef ECEF e = self.lc.ned2ecef(n) + * return [e.x, e.y, e.z] # <<<<<<<<<<<<<< + * + * def geodetic2ned_single(self, geodetic): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_3 = PyFloat_FromDouble(__pyx_v_e.x); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 158, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PyFloat_FromDouble(__pyx_v_e.y); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 158, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = PyFloat_FromDouble(__pyx_v_e.z); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 158, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = PyList_New(3); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 158, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyList_SET_ITEM(__pyx_t_6, 0, __pyx_t_3)) __PYX_ERR(0, 158, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_4); + if (__Pyx_PyList_SET_ITEM(__pyx_t_6, 1, __pyx_t_4)) __PYX_ERR(0, 158, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_5); + if (__Pyx_PyList_SET_ITEM(__pyx_t_6, 2, __pyx_t_5)) __PYX_ERR(0, 158, __pyx_L1_error); + __pyx_t_3 = 0; + __pyx_t_4 = 0; + __pyx_t_5 = 0; + __pyx_r = __pyx_t_6; + __pyx_t_6 = 0; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":154 + * return [n.n, n.e, n.d] + * + * def ned2ecef_single(self, ned): # <<<<<<<<<<<<<< + * assert self.lc + * cdef NED n = list2ned(ned) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("common.transformations.transformations.LocalCoord.ned2ecef_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":160 + * return [e.x, e.y, e.z] + * + * def geodetic2ned_single(self, geodetic): # <<<<<<<<<<<<<< + * assert self.lc + * cdef Geodetic g = list2geodetic(geodetic) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_11geodetic2ned_single(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_15transformations_15transformations_10LocalCoord_11geodetic2ned_single = {"geodetic2ned_single", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_10LocalCoord_11geodetic2ned_single, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_11geodetic2ned_single(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_geodetic = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("geodetic2ned_single (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_geodetic,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_geodetic)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 160, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "geodetic2ned_single") < 0)) __PYX_ERR(0, 160, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_geodetic = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("geodetic2ned_single", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 160, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("common.transformations.transformations.LocalCoord.geodetic2ned_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_15transformations_15transformations_10LocalCoord_10geodetic2ned_single(((struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *)__pyx_v_self), __pyx_v_geodetic); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_10geodetic2ned_single(struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self, PyObject *__pyx_v_geodetic) { + struct Geodetic __pyx_v_g; + struct NED __pyx_v_n; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + struct Geodetic __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("geodetic2ned_single", 1); + + /* "common/transformations/transformations.pyx":161 + * + * def geodetic2ned_single(self, geodetic): + * assert self.lc # <<<<<<<<<<<<<< + * cdef Geodetic g = list2geodetic(geodetic) + * cdef NED n = self.lc.geodetic2ned(g) + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_1 = (__pyx_v_self->lc != 0); + if (unlikely(!__pyx_t_1)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(0, 161, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(0, 161, __pyx_L1_error) + #endif + + /* "common/transformations/transformations.pyx":162 + * def geodetic2ned_single(self, geodetic): + * assert self.lc + * cdef Geodetic g = list2geodetic(geodetic) # <<<<<<<<<<<<<< + * cdef NED n = self.lc.geodetic2ned(g) + * return [n.n, n.e, n.d] + */ + __pyx_t_2 = __pyx_f_6common_15transformations_15transformations_list2geodetic(__pyx_v_geodetic); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 162, __pyx_L1_error) + __pyx_v_g = __pyx_t_2; + + /* "common/transformations/transformations.pyx":163 + * assert self.lc + * cdef Geodetic g = list2geodetic(geodetic) + * cdef NED n = self.lc.geodetic2ned(g) # <<<<<<<<<<<<<< + * return [n.n, n.e, n.d] + * + */ + __pyx_v_n = __pyx_v_self->lc->geodetic2ned(__pyx_v_g); + + /* "common/transformations/transformations.pyx":164 + * cdef Geodetic g = list2geodetic(geodetic) + * cdef NED n = self.lc.geodetic2ned(g) + * return [n.n, n.e, n.d] # <<<<<<<<<<<<<< + * + * def ned2geodetic_single(self, ned): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_3 = PyFloat_FromDouble(__pyx_v_n.n); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 164, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PyFloat_FromDouble(__pyx_v_n.e); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 164, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = PyFloat_FromDouble(__pyx_v_n.d); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 164, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = PyList_New(3); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 164, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyList_SET_ITEM(__pyx_t_6, 0, __pyx_t_3)) __PYX_ERR(0, 164, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_4); + if (__Pyx_PyList_SET_ITEM(__pyx_t_6, 1, __pyx_t_4)) __PYX_ERR(0, 164, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_5); + if (__Pyx_PyList_SET_ITEM(__pyx_t_6, 2, __pyx_t_5)) __PYX_ERR(0, 164, __pyx_L1_error); + __pyx_t_3 = 0; + __pyx_t_4 = 0; + __pyx_t_5 = 0; + __pyx_r = __pyx_t_6; + __pyx_t_6 = 0; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":160 + * return [e.x, e.y, e.z] + * + * def geodetic2ned_single(self, geodetic): # <<<<<<<<<<<<<< + * assert self.lc + * cdef Geodetic g = list2geodetic(geodetic) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("common.transformations.transformations.LocalCoord.geodetic2ned_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":166 + * return [n.n, n.e, n.d] + * + * def ned2geodetic_single(self, ned): # <<<<<<<<<<<<<< + * assert self.lc + * cdef NED n = list2ned(ned) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_13ned2geodetic_single(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_15transformations_15transformations_10LocalCoord_13ned2geodetic_single = {"ned2geodetic_single", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_10LocalCoord_13ned2geodetic_single, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_13ned2geodetic_single(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_ned = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("ned2geodetic_single (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_ned,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_ned)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 166, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "ned2geodetic_single") < 0)) __PYX_ERR(0, 166, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_ned = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("ned2geodetic_single", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 166, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("common.transformations.transformations.LocalCoord.ned2geodetic_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_15transformations_15transformations_10LocalCoord_12ned2geodetic_single(((struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *)__pyx_v_self), __pyx_v_ned); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_12ned2geodetic_single(struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self, PyObject *__pyx_v_ned) { + struct NED __pyx_v_n; + struct Geodetic __pyx_v_g; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + struct NED __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("ned2geodetic_single", 1); + + /* "common/transformations/transformations.pyx":167 + * + * def ned2geodetic_single(self, ned): + * assert self.lc # <<<<<<<<<<<<<< + * cdef NED n = list2ned(ned) + * cdef Geodetic g = self.lc.ned2geodetic(n) + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_1 = (__pyx_v_self->lc != 0); + if (unlikely(!__pyx_t_1)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(0, 167, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(0, 167, __pyx_L1_error) + #endif + + /* "common/transformations/transformations.pyx":168 + * def ned2geodetic_single(self, ned): + * assert self.lc + * cdef NED n = list2ned(ned) # <<<<<<<<<<<<<< + * cdef Geodetic g = self.lc.ned2geodetic(n) + * return [g.lat, g.lon, g.alt] + */ + __pyx_t_2 = __pyx_f_6common_15transformations_15transformations_list2ned(__pyx_v_ned); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 168, __pyx_L1_error) + __pyx_v_n = __pyx_t_2; + + /* "common/transformations/transformations.pyx":169 + * assert self.lc + * cdef NED n = list2ned(ned) + * cdef Geodetic g = self.lc.ned2geodetic(n) # <<<<<<<<<<<<<< + * return [g.lat, g.lon, g.alt] + * + */ + __pyx_v_g = __pyx_v_self->lc->ned2geodetic(__pyx_v_n); + + /* "common/transformations/transformations.pyx":170 + * cdef NED n = list2ned(ned) + * cdef Geodetic g = self.lc.ned2geodetic(n) + * return [g.lat, g.lon, g.alt] # <<<<<<<<<<<<<< + * + * def __dealloc__(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_3 = PyFloat_FromDouble(__pyx_v_g.lat); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 170, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PyFloat_FromDouble(__pyx_v_g.lon); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 170, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = PyFloat_FromDouble(__pyx_v_g.alt); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 170, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = PyList_New(3); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 170, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyList_SET_ITEM(__pyx_t_6, 0, __pyx_t_3)) __PYX_ERR(0, 170, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_4); + if (__Pyx_PyList_SET_ITEM(__pyx_t_6, 1, __pyx_t_4)) __PYX_ERR(0, 170, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_5); + if (__Pyx_PyList_SET_ITEM(__pyx_t_6, 2, __pyx_t_5)) __PYX_ERR(0, 170, __pyx_L1_error); + __pyx_t_3 = 0; + __pyx_t_4 = 0; + __pyx_t_5 = 0; + __pyx_r = __pyx_t_6; + __pyx_t_6 = 0; + goto __pyx_L0; + + /* "common/transformations/transformations.pyx":166 + * return [n.n, n.e, n.d] + * + * def ned2geodetic_single(self, ned): # <<<<<<<<<<<<<< + * assert self.lc + * cdef NED n = list2ned(ned) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("common.transformations.transformations.LocalCoord.ned2geodetic_single", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "common/transformations/transformations.pyx":172 + * return [g.lat, g.lon, g.alt] + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * del self.lc + */ + +/* Python wrapper */ +static void __pyx_pw_6common_15transformations_15transformations_10LocalCoord_15__dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_pw_6common_15transformations_15transformations_10LocalCoord_15__dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_pf_6common_15transformations_15transformations_10LocalCoord_14__dealloc__(((struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_pf_6common_15transformations_15transformations_10LocalCoord_14__dealloc__(struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self) { + + /* "common/transformations/transformations.pyx":173 + * + * def __dealloc__(self): + * del self.lc # <<<<<<<<<<<<<< + */ + delete __pyx_v_self->lc; + + /* "common/transformations/transformations.pyx":172 + * return [g.lat, g.lon, g.alt] + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * del self.lc + */ + + /* function exit code */ +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.lc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_17__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_15transformations_15transformations_10LocalCoord_17__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_10LocalCoord_17__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_17__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_6common_15transformations_15transformations_10LocalCoord_16__reduce_cython__(((struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_16__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "self.lc cannot be converted to a Python object for pickling" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "self.lc cannot be converted to a Python object for pickling" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_self_lc_cannot_be_converted_to_a, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.lc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("common.transformations.transformations.LocalCoord.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.lc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.lc cannot be converted to a Python object for pickling" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_19__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_6common_15transformations_15transformations_10LocalCoord_19__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_10LocalCoord_19__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_6common_15transformations_15transformations_10LocalCoord_19__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("common.transformations.transformations.LocalCoord.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_6common_15transformations_15transformations_10LocalCoord_18__setstate_cython__(((struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_6common_15transformations_15transformations_10LocalCoord_18__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_6common_15transformations_15transformations_LocalCoord *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "self.lc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "self.lc cannot be converted to a Python object for pickling" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_self_lc_cannot_be_converted_to_a, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.lc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.lc cannot be converted to a Python object for pickling" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("common.transformations.transformations.LocalCoord.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_tp_new_6common_15transformations_15transformations_LocalCoord(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + return o; +} + +static void __pyx_tp_dealloc_6common_15transformations_15transformations_LocalCoord(PyObject *o) { + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_6common_15transformations_15transformations_LocalCoord) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_pw_6common_15transformations_15transformations_10LocalCoord_15__dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} + +static PyObject *__pyx_getprop_6common_15transformations_15transformations_10LocalCoord_ned2ecef_matrix(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6common_15transformations_15transformations_10LocalCoord_15ned2ecef_matrix_1__get__(o); +} + +static PyObject *__pyx_getprop_6common_15transformations_15transformations_10LocalCoord_ecef2ned_matrix(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6common_15transformations_15transformations_10LocalCoord_15ecef2ned_matrix_1__get__(o); +} + +static PyObject *__pyx_getprop_6common_15transformations_15transformations_10LocalCoord_ned_from_ecef_matrix(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6common_15transformations_15transformations_10LocalCoord_20ned_from_ecef_matrix_1__get__(o); +} + +static PyObject *__pyx_getprop_6common_15transformations_15transformations_10LocalCoord_ecef_from_ned_matrix(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_6common_15transformations_15transformations_10LocalCoord_20ecef_from_ned_matrix_1__get__(o); +} + +static PyMethodDef __pyx_methods_6common_15transformations_15transformations_LocalCoord[] = { + {"from_geodetic", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_10LocalCoord_3from_geodetic, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"from_ecef", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_10LocalCoord_5from_ecef, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"ecef2ned_single", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_10LocalCoord_7ecef2ned_single, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"ned2ecef_single", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_10LocalCoord_9ned2ecef_single, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"geodetic2ned_single", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_10LocalCoord_11geodetic2ned_single, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"ned2geodetic_single", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_10LocalCoord_13ned2geodetic_single, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_10LocalCoord_17__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_10LocalCoord_19__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; + +static struct PyGetSetDef __pyx_getsets_6common_15transformations_15transformations_LocalCoord[] = { + {(char *)"ned2ecef_matrix", __pyx_getprop_6common_15transformations_15transformations_10LocalCoord_ned2ecef_matrix, 0, (char *)0, 0}, + {(char *)"ecef2ned_matrix", __pyx_getprop_6common_15transformations_15transformations_10LocalCoord_ecef2ned_matrix, 0, (char *)0, 0}, + {(char *)"ned_from_ecef_matrix", __pyx_getprop_6common_15transformations_15transformations_10LocalCoord_ned_from_ecef_matrix, 0, (char *)0, 0}, + {(char *)"ecef_from_ned_matrix", __pyx_getprop_6common_15transformations_15transformations_10LocalCoord_ecef_from_ned_matrix, 0, (char *)0, 0}, + {0, 0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_6common_15transformations_15transformations_LocalCoord_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_6common_15transformations_15transformations_LocalCoord}, + {Py_tp_methods, (void *)__pyx_methods_6common_15transformations_15transformations_LocalCoord}, + {Py_tp_getset, (void *)__pyx_getsets_6common_15transformations_15transformations_LocalCoord}, + {Py_tp_init, (void *)__pyx_pw_6common_15transformations_15transformations_10LocalCoord_1__init__}, + {Py_tp_new, (void *)__pyx_tp_new_6common_15transformations_15transformations_LocalCoord}, + {0, 0}, +}; +static PyType_Spec __pyx_type_6common_15transformations_15transformations_LocalCoord_spec = { + "common.transformations.transformations.LocalCoord", + sizeof(struct __pyx_obj_6common_15transformations_15transformations_LocalCoord), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, + __pyx_type_6common_15transformations_15transformations_LocalCoord_slots, +}; +#else + +static PyTypeObject __pyx_type_6common_15transformations_15transformations_LocalCoord = { + PyVarObject_HEAD_INIT(0, 0) + "common.transformations.transformations.""LocalCoord", /*tp_name*/ + sizeof(struct __pyx_obj_6common_15transformations_15transformations_LocalCoord), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_6common_15transformations_15transformations_LocalCoord, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, /*tp_flags*/ + 0, /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_6common_15transformations_15transformations_LocalCoord, /*tp_methods*/ + 0, /*tp_members*/ + __pyx_getsets_6common_15transformations_15transformations_LocalCoord, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + __pyx_pw_6common_15transformations_15transformations_10LocalCoord_1__init__, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_6common_15transformations_15transformations_LocalCoord, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyMethodDef __pyx_methods[] = { + {"rot_matrix", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_6common_15transformations_15transformations_13rot_matrix, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#ifndef CYTHON_SMALL_CODE +#if defined(__clang__) + #define CYTHON_SMALL_CODE +#elif defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 3)) + #define CYTHON_SMALL_CODE __attribute__((cold)) +#else + #define CYTHON_SMALL_CODE +#endif +#endif +/* #### Code section: pystring_table ### */ + +static int __Pyx_CreateStringTabAndInitStrings(void) { + __Pyx_StringTabEntry __pyx_string_tab[] = { + {&__pyx_n_s_AssertionError, __pyx_k_AssertionError, sizeof(__pyx_k_AssertionError), 0, 0, 1, 1}, + {&__pyx_n_s_ImportError, __pyx_k_ImportError, sizeof(__pyx_k_ImportError), 0, 0, 1, 1}, + {&__pyx_n_s_LocalCoord, __pyx_k_LocalCoord, sizeof(__pyx_k_LocalCoord), 0, 0, 1, 1}, + {&__pyx_n_s_LocalCoord___reduce_cython, __pyx_k_LocalCoord___reduce_cython, sizeof(__pyx_k_LocalCoord___reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_LocalCoord___setstate_cython, __pyx_k_LocalCoord___setstate_cython, sizeof(__pyx_k_LocalCoord___setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_LocalCoord_ecef2ned_single, __pyx_k_LocalCoord_ecef2ned_single, sizeof(__pyx_k_LocalCoord_ecef2ned_single), 0, 0, 1, 1}, + {&__pyx_n_s_LocalCoord_from_ecef, __pyx_k_LocalCoord_from_ecef, sizeof(__pyx_k_LocalCoord_from_ecef), 0, 0, 1, 1}, + {&__pyx_n_s_LocalCoord_from_geodetic, __pyx_k_LocalCoord_from_geodetic, sizeof(__pyx_k_LocalCoord_from_geodetic), 0, 0, 1, 1}, + {&__pyx_n_s_LocalCoord_geodetic2ned_single, __pyx_k_LocalCoord_geodetic2ned_single, sizeof(__pyx_k_LocalCoord_geodetic2ned_single), 0, 0, 1, 1}, + {&__pyx_n_s_LocalCoord_ned2ecef_single, __pyx_k_LocalCoord_ned2ecef_single, sizeof(__pyx_k_LocalCoord_ned2ecef_single), 0, 0, 1, 1}, + {&__pyx_n_s_LocalCoord_ned2geodetic_single, __pyx_k_LocalCoord_ned2geodetic_single, sizeof(__pyx_k_LocalCoord_ned2geodetic_single), 0, 0, 1, 1}, + {&__pyx_n_s_TypeError, __pyx_k_TypeError, sizeof(__pyx_k_TypeError), 0, 0, 1, 1}, + {&__pyx_n_s__3, __pyx_k__3, sizeof(__pyx_k__3), 0, 0, 1, 1}, + {&__pyx_n_s__42, __pyx_k__42, sizeof(__pyx_k__42), 0, 0, 1, 1}, + {&__pyx_n_s_array, __pyx_k_array, sizeof(__pyx_k_array), 0, 0, 1, 1}, + {&__pyx_n_s_asfortranarray, __pyx_k_asfortranarray, sizeof(__pyx_k_asfortranarray), 0, 0, 1, 1}, + {&__pyx_n_s_asyncio_coroutines, __pyx_k_asyncio_coroutines, sizeof(__pyx_k_asyncio_coroutines), 0, 0, 1, 1}, + {&__pyx_n_s_cline_in_traceback, __pyx_k_cline_in_traceback, sizeof(__pyx_k_cline_in_traceback), 0, 0, 1, 1}, + {&__pyx_n_s_cls, __pyx_k_cls, sizeof(__pyx_k_cls), 0, 0, 1, 1}, + {&__pyx_kp_s_common_transformations_transform, __pyx_k_common_transformations_transform, sizeof(__pyx_k_common_transformations_transform), 0, 0, 1, 0}, + {&__pyx_n_s_common_transformations_transform_2, __pyx_k_common_transformations_transform_2, sizeof(__pyx_k_common_transformations_transform_2), 0, 0, 1, 1}, + {&__pyx_n_s_dict, __pyx_k_dict, sizeof(__pyx_k_dict), 0, 0, 1, 1}, + {&__pyx_kp_u_disable, __pyx_k_disable, sizeof(__pyx_k_disable), 0, 1, 0, 0}, + {&__pyx_n_s_double, __pyx_k_double, sizeof(__pyx_k_double), 0, 0, 1, 1}, + {&__pyx_n_s_dtype, __pyx_k_dtype, sizeof(__pyx_k_dtype), 0, 0, 1, 1}, + {&__pyx_n_s_e, __pyx_k_e, sizeof(__pyx_k_e), 0, 0, 1, 1}, + {&__pyx_n_s_ecef, __pyx_k_ecef, sizeof(__pyx_k_ecef), 0, 0, 1, 1}, + {&__pyx_n_s_ecef2geodetic_single, __pyx_k_ecef2geodetic_single, sizeof(__pyx_k_ecef2geodetic_single), 0, 0, 1, 1}, + {&__pyx_n_s_ecef2ned_matrix, __pyx_k_ecef2ned_matrix, sizeof(__pyx_k_ecef2ned_matrix), 0, 0, 1, 1}, + {&__pyx_n_s_ecef2ned_single, __pyx_k_ecef2ned_single, sizeof(__pyx_k_ecef2ned_single), 0, 0, 1, 1}, + {&__pyx_n_s_ecef_euler_from_ned_single, __pyx_k_ecef_euler_from_ned_single, sizeof(__pyx_k_ecef_euler_from_ned_single), 0, 0, 1, 1}, + {&__pyx_n_s_ecef_init, __pyx_k_ecef_init, sizeof(__pyx_k_ecef_init), 0, 0, 1, 1}, + {&__pyx_n_s_ecef_pose, __pyx_k_ecef_pose, sizeof(__pyx_k_ecef_pose), 0, 0, 1, 1}, + {&__pyx_kp_u_enable, __pyx_k_enable, sizeof(__pyx_k_enable), 0, 1, 0, 0}, + {&__pyx_n_s_euler, __pyx_k_euler, sizeof(__pyx_k_euler), 0, 0, 1, 1}, + {&__pyx_n_s_euler2quat_single, __pyx_k_euler2quat_single, sizeof(__pyx_k_euler2quat_single), 0, 0, 1, 1}, + {&__pyx_n_s_euler2rot_single, __pyx_k_euler2rot_single, sizeof(__pyx_k_euler2rot_single), 0, 0, 1, 1}, + {&__pyx_n_s_from_ecef, __pyx_k_from_ecef, sizeof(__pyx_k_from_ecef), 0, 0, 1, 1}, + {&__pyx_n_s_from_geodetic, __pyx_k_from_geodetic, sizeof(__pyx_k_from_geodetic), 0, 0, 1, 1}, + {&__pyx_n_s_g, __pyx_k_g, sizeof(__pyx_k_g), 0, 0, 1, 1}, + {&__pyx_kp_u_gc, __pyx_k_gc, sizeof(__pyx_k_gc), 0, 1, 0, 0}, + {&__pyx_n_s_geodetic, __pyx_k_geodetic, sizeof(__pyx_k_geodetic), 0, 0, 1, 1}, + {&__pyx_n_s_geodetic2ecef_single, __pyx_k_geodetic2ecef_single, sizeof(__pyx_k_geodetic2ecef_single), 0, 0, 1, 1}, + {&__pyx_n_s_geodetic2ned_single, __pyx_k_geodetic2ned_single, sizeof(__pyx_k_geodetic2ned_single), 0, 0, 1, 1}, + {&__pyx_n_s_getstate, __pyx_k_getstate, sizeof(__pyx_k_getstate), 0, 0, 1, 1}, + {&__pyx_n_s_import, __pyx_k_import, sizeof(__pyx_k_import), 0, 0, 1, 1}, + {&__pyx_n_s_init, __pyx_k_init, sizeof(__pyx_k_init), 0, 0, 1, 1}, + {&__pyx_n_s_initializing, __pyx_k_initializing, sizeof(__pyx_k_initializing), 0, 0, 1, 1}, + {&__pyx_n_s_is_coroutine, __pyx_k_is_coroutine, sizeof(__pyx_k_is_coroutine), 0, 0, 1, 1}, + {&__pyx_kp_u_isenabled, __pyx_k_isenabled, sizeof(__pyx_k_isenabled), 0, 1, 0, 0}, + {&__pyx_n_s_main, __pyx_k_main, sizeof(__pyx_k_main), 0, 0, 1, 1}, + {&__pyx_n_s_n, __pyx_k_n, sizeof(__pyx_k_n), 0, 0, 1, 1}, + {&__pyx_n_s_name, __pyx_k_name, sizeof(__pyx_k_name), 0, 0, 1, 1}, + {&__pyx_n_s_ned, __pyx_k_ned, sizeof(__pyx_k_ned), 0, 0, 1, 1}, + {&__pyx_n_s_ned2ecef_matrix, __pyx_k_ned2ecef_matrix, sizeof(__pyx_k_ned2ecef_matrix), 0, 0, 1, 1}, + {&__pyx_n_s_ned2ecef_single, __pyx_k_ned2ecef_single, sizeof(__pyx_k_ned2ecef_single), 0, 0, 1, 1}, + {&__pyx_n_s_ned2geodetic_single, __pyx_k_ned2geodetic_single, sizeof(__pyx_k_ned2geodetic_single), 0, 0, 1, 1}, + {&__pyx_n_s_ned_euler_from_ecef_single, __pyx_k_ned_euler_from_ecef_single, sizeof(__pyx_k_ned_euler_from_ecef_single), 0, 0, 1, 1}, + {&__pyx_n_s_ned_pose, __pyx_k_ned_pose, sizeof(__pyx_k_ned_pose), 0, 0, 1, 1}, + {&__pyx_n_s_np, __pyx_k_np, sizeof(__pyx_k_np), 0, 0, 1, 1}, + {&__pyx_n_s_numpy, __pyx_k_numpy, sizeof(__pyx_k_numpy), 0, 0, 1, 1}, + {&__pyx_kp_u_numpy_core_multiarray_failed_to, __pyx_k_numpy_core_multiarray_failed_to, sizeof(__pyx_k_numpy_core_multiarray_failed_to), 0, 1, 0, 0}, + {&__pyx_kp_u_numpy_core_umath_failed_to_impor, __pyx_k_numpy_core_umath_failed_to_impor, sizeof(__pyx_k_numpy_core_umath_failed_to_impor), 0, 1, 0, 0}, + {&__pyx_n_s_pitch, __pyx_k_pitch, sizeof(__pyx_k_pitch), 0, 0, 1, 1}, + {&__pyx_n_s_pose, __pyx_k_pose, sizeof(__pyx_k_pose), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_state, __pyx_k_pyx_state, sizeof(__pyx_k_pyx_state), 0, 0, 1, 1}, + {&__pyx_n_s_q, __pyx_k_q, sizeof(__pyx_k_q), 0, 0, 1, 1}, + {&__pyx_n_s_quat, __pyx_k_quat, sizeof(__pyx_k_quat), 0, 0, 1, 1}, + {&__pyx_n_s_quat2euler_single, __pyx_k_quat2euler_single, sizeof(__pyx_k_quat2euler_single), 0, 0, 1, 1}, + {&__pyx_n_s_quat2rot_single, __pyx_k_quat2rot_single, sizeof(__pyx_k_quat2rot_single), 0, 0, 1, 1}, + {&__pyx_n_s_r, __pyx_k_r, sizeof(__pyx_k_r), 0, 0, 1, 1}, + {&__pyx_n_s_reduce, __pyx_k_reduce, sizeof(__pyx_k_reduce), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_cython, __pyx_k_reduce_cython, sizeof(__pyx_k_reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_ex, __pyx_k_reduce_ex, sizeof(__pyx_k_reduce_ex), 0, 0, 1, 1}, + {&__pyx_n_s_roll, __pyx_k_roll, sizeof(__pyx_k_roll), 0, 0, 1, 1}, + {&__pyx_n_s_rot, __pyx_k_rot, sizeof(__pyx_k_rot), 0, 0, 1, 1}, + {&__pyx_n_s_rot2euler_single, __pyx_k_rot2euler_single, sizeof(__pyx_k_rot2euler_single), 0, 0, 1, 1}, + {&__pyx_n_s_rot2quat_single, __pyx_k_rot2quat_single, sizeof(__pyx_k_rot2quat_single), 0, 0, 1, 1}, + {&__pyx_n_s_rot_matrix, __pyx_k_rot_matrix, sizeof(__pyx_k_rot_matrix), 0, 0, 1, 1}, + {&__pyx_n_s_self, __pyx_k_self, sizeof(__pyx_k_self), 0, 0, 1, 1}, + {&__pyx_kp_s_self_lc_cannot_be_converted_to_a, __pyx_k_self_lc_cannot_be_converted_to_a, sizeof(__pyx_k_self_lc_cannot_be_converted_to_a), 0, 0, 1, 0}, + {&__pyx_n_s_setstate, __pyx_k_setstate, sizeof(__pyx_k_setstate), 0, 0, 1, 1}, + {&__pyx_n_s_setstate_cython, __pyx_k_setstate_cython, sizeof(__pyx_k_setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_spec, __pyx_k_spec, sizeof(__pyx_k_spec), 0, 0, 1, 1}, + {&__pyx_kp_s_stringsource, __pyx_k_stringsource, sizeof(__pyx_k_stringsource), 0, 0, 1, 0}, + {&__pyx_n_s_test, __pyx_k_test, sizeof(__pyx_k_test), 0, 0, 1, 1}, + {&__pyx_n_s_yaw, __pyx_k_yaw, sizeof(__pyx_k_yaw), 0, 0, 1, 1}, + {0, 0, 0, 0, 0, 0, 0} + }; + return __Pyx_InitStrings(__pyx_string_tab); +} +/* #### Code section: cached_builtins ### */ +static CYTHON_SMALL_CODE int __Pyx_InitCachedBuiltins(void) { + __pyx_builtin_AssertionError = __Pyx_GetBuiltinName(__pyx_n_s_AssertionError); if (!__pyx_builtin_AssertionError) __PYX_ERR(0, 31, __pyx_L1_error) + __pyx_builtin_TypeError = __Pyx_GetBuiltinName(__pyx_n_s_TypeError); if (!__pyx_builtin_TypeError) __PYX_ERR(1, 2, __pyx_L1_error) + __pyx_builtin_ImportError = __Pyx_GetBuiltinName(__pyx_n_s_ImportError); if (!__pyx_builtin_ImportError) __PYX_ERR(2, 984, __pyx_L1_error) + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: cached_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_InitCachedConstants", 0); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":984 + * __pyx_import_array() + * except Exception: + * raise ImportError("numpy.core.multiarray failed to import") # <<<<<<<<<<<<<< + * + * cdef inline int import_umath() except -1: + */ + __pyx_tuple_ = PyTuple_Pack(1, __pyx_kp_u_numpy_core_multiarray_failed_to); if (unlikely(!__pyx_tuple_)) __PYX_ERR(2, 984, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple_); + __Pyx_GIVEREF(__pyx_tuple_); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":990 + * _import_umath() + * except Exception: + * raise ImportError("numpy.core.umath failed to import") # <<<<<<<<<<<<<< + * + * cdef inline int import_ufunc() except -1: + */ + __pyx_tuple__2 = PyTuple_Pack(1, __pyx_kp_u_numpy_core_umath_failed_to_impor); if (unlikely(!__pyx_tuple__2)) __PYX_ERR(2, 990, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__2); + __Pyx_GIVEREF(__pyx_tuple__2); + + /* "common/transformations/transformations.pyx":56 + * return g + * + * def euler2quat_single(euler): # <<<<<<<<<<<<<< + * cdef Vector3 e = Vector3(euler[0], euler[1], euler[2]) + * cdef Quaternion q = euler2quat_c(e) + */ + __pyx_tuple__4 = PyTuple_Pack(3, __pyx_n_s_euler, __pyx_n_s_e, __pyx_n_s_q); if (unlikely(!__pyx_tuple__4)) __PYX_ERR(0, 56, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__4); + __Pyx_GIVEREF(__pyx_tuple__4); + __pyx_codeobj__5 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__4, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_transformations_transform, __pyx_n_s_euler2quat_single, 56, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__5)) __PYX_ERR(0, 56, __pyx_L1_error) + + /* "common/transformations/transformations.pyx":61 + * return [q.w(), q.x(), q.y(), q.z()] + * + * def quat2euler_single(quat): # <<<<<<<<<<<<<< + * cdef Quaternion q = Quaternion(quat[0], quat[1], quat[2], quat[3]) + * cdef Vector3 e = quat2euler_c(q) + */ + __pyx_tuple__6 = PyTuple_Pack(3, __pyx_n_s_quat, __pyx_n_s_q, __pyx_n_s_e); if (unlikely(!__pyx_tuple__6)) __PYX_ERR(0, 61, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__6); + __Pyx_GIVEREF(__pyx_tuple__6); + __pyx_codeobj__7 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__6, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_transformations_transform, __pyx_n_s_quat2euler_single, 61, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__7)) __PYX_ERR(0, 61, __pyx_L1_error) + + /* "common/transformations/transformations.pyx":66 + * return [e(0), e(1), e(2)] + * + * def quat2rot_single(quat): # <<<<<<<<<<<<<< + * cdef Quaternion q = Quaternion(quat[0], quat[1], quat[2], quat[3]) + * cdef Matrix3 r = quat2rot_c(q) + */ + __pyx_tuple__8 = PyTuple_Pack(3, __pyx_n_s_quat, __pyx_n_s_q, __pyx_n_s_r); if (unlikely(!__pyx_tuple__8)) __PYX_ERR(0, 66, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__8); + __Pyx_GIVEREF(__pyx_tuple__8); + __pyx_codeobj__9 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__8, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_transformations_transform, __pyx_n_s_quat2rot_single, 66, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__9)) __PYX_ERR(0, 66, __pyx_L1_error) + + /* "common/transformations/transformations.pyx":71 + * return matrix2numpy(r) + * + * def rot2quat_single(rot): # <<<<<<<<<<<<<< + * cdef Matrix3 r = numpy2matrix(np.asfortranarray(rot, dtype=np.double)) + * cdef Quaternion q = rot2quat_c(r) + */ + __pyx_tuple__10 = PyTuple_Pack(3, __pyx_n_s_rot, __pyx_n_s_r, __pyx_n_s_q); if (unlikely(!__pyx_tuple__10)) __PYX_ERR(0, 71, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__10); + __Pyx_GIVEREF(__pyx_tuple__10); + __pyx_codeobj__11 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__10, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_transformations_transform, __pyx_n_s_rot2quat_single, 71, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__11)) __PYX_ERR(0, 71, __pyx_L1_error) + + /* "common/transformations/transformations.pyx":76 + * return [q.w(), q.x(), q.y(), q.z()] + * + * def euler2rot_single(euler): # <<<<<<<<<<<<<< + * cdef Vector3 e = Vector3(euler[0], euler[1], euler[2]) + * cdef Matrix3 r = euler2rot_c(e) + */ + __pyx_tuple__12 = PyTuple_Pack(3, __pyx_n_s_euler, __pyx_n_s_e, __pyx_n_s_r); if (unlikely(!__pyx_tuple__12)) __PYX_ERR(0, 76, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__12); + __Pyx_GIVEREF(__pyx_tuple__12); + __pyx_codeobj__13 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__12, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_transformations_transform, __pyx_n_s_euler2rot_single, 76, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__13)) __PYX_ERR(0, 76, __pyx_L1_error) + + /* "common/transformations/transformations.pyx":81 + * return matrix2numpy(r) + * + * def rot2euler_single(rot): # <<<<<<<<<<<<<< + * cdef Matrix3 r = numpy2matrix(np.asfortranarray(rot, dtype=np.double)) + * cdef Vector3 e = rot2euler_c(r) + */ + __pyx_tuple__14 = PyTuple_Pack(3, __pyx_n_s_rot, __pyx_n_s_r, __pyx_n_s_e); if (unlikely(!__pyx_tuple__14)) __PYX_ERR(0, 81, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__14); + __Pyx_GIVEREF(__pyx_tuple__14); + __pyx_codeobj__15 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__14, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_transformations_transform, __pyx_n_s_rot2euler_single, 81, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__15)) __PYX_ERR(0, 81, __pyx_L1_error) + + /* "common/transformations/transformations.pyx":86 + * return [e(0), e(1), e(2)] + * + * def rot_matrix(roll, pitch, yaw): # <<<<<<<<<<<<<< + * return matrix2numpy(rot_matrix_c(roll, pitch, yaw)) + * + */ + __pyx_tuple__16 = PyTuple_Pack(3, __pyx_n_s_roll, __pyx_n_s_pitch, __pyx_n_s_yaw); if (unlikely(!__pyx_tuple__16)) __PYX_ERR(0, 86, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__16); + __Pyx_GIVEREF(__pyx_tuple__16); + __pyx_codeobj__17 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__16, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_transformations_transform, __pyx_n_s_rot_matrix, 86, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__17)) __PYX_ERR(0, 86, __pyx_L1_error) + + /* "common/transformations/transformations.pyx":89 + * return matrix2numpy(rot_matrix_c(roll, pitch, yaw)) + * + * def ecef_euler_from_ned_single(ecef_init, ned_pose): # <<<<<<<<<<<<<< + * cdef ECEF init = list2ecef(ecef_init) + * cdef Vector3 pose = Vector3(ned_pose[0], ned_pose[1], ned_pose[2]) + */ + __pyx_tuple__18 = PyTuple_Pack(5, __pyx_n_s_ecef_init, __pyx_n_s_ned_pose, __pyx_n_s_init, __pyx_n_s_pose, __pyx_n_s_e); if (unlikely(!__pyx_tuple__18)) __PYX_ERR(0, 89, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__18); + __Pyx_GIVEREF(__pyx_tuple__18); + __pyx_codeobj__19 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__18, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_transformations_transform, __pyx_n_s_ecef_euler_from_ned_single, 89, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__19)) __PYX_ERR(0, 89, __pyx_L1_error) + + /* "common/transformations/transformations.pyx":96 + * return [e(0), e(1), e(2)] + * + * def ned_euler_from_ecef_single(ecef_init, ecef_pose): # <<<<<<<<<<<<<< + * cdef ECEF init = list2ecef(ecef_init) + * cdef Vector3 pose = Vector3(ecef_pose[0], ecef_pose[1], ecef_pose[2]) + */ + __pyx_tuple__20 = PyTuple_Pack(5, __pyx_n_s_ecef_init, __pyx_n_s_ecef_pose, __pyx_n_s_init, __pyx_n_s_pose, __pyx_n_s_e); if (unlikely(!__pyx_tuple__20)) __PYX_ERR(0, 96, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__20); + __Pyx_GIVEREF(__pyx_tuple__20); + __pyx_codeobj__21 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__20, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_transformations_transform, __pyx_n_s_ned_euler_from_ecef_single, 96, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__21)) __PYX_ERR(0, 96, __pyx_L1_error) + + /* "common/transformations/transformations.pyx":103 + * return [e(0), e(1), e(2)] + * + * def geodetic2ecef_single(geodetic): # <<<<<<<<<<<<<< + * cdef Geodetic g = list2geodetic(geodetic) + * cdef ECEF e = geodetic2ecef_c(g) + */ + __pyx_tuple__22 = PyTuple_Pack(3, __pyx_n_s_geodetic, __pyx_n_s_g, __pyx_n_s_e); if (unlikely(!__pyx_tuple__22)) __PYX_ERR(0, 103, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__22); + __Pyx_GIVEREF(__pyx_tuple__22); + __pyx_codeobj__23 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__22, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_transformations_transform, __pyx_n_s_geodetic2ecef_single, 103, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__23)) __PYX_ERR(0, 103, __pyx_L1_error) + + /* "common/transformations/transformations.pyx":108 + * return [e.x, e.y, e.z] + * + * def ecef2geodetic_single(ecef): # <<<<<<<<<<<<<< + * cdef ECEF e = list2ecef(ecef) + * cdef Geodetic g = ecef2geodetic_c(e) + */ + __pyx_tuple__24 = PyTuple_Pack(3, __pyx_n_s_ecef, __pyx_n_s_e, __pyx_n_s_g); if (unlikely(!__pyx_tuple__24)) __PYX_ERR(0, 108, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__24); + __Pyx_GIVEREF(__pyx_tuple__24); + __pyx_codeobj__25 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__24, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_transformations_transform, __pyx_n_s_ecef2geodetic_single, 108, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__25)) __PYX_ERR(0, 108, __pyx_L1_error) + + /* "common/transformations/transformations.pyx":140 + * return self.ned2ecef_matrix + * + * @classmethod # <<<<<<<<<<<<<< + * def from_geodetic(cls, geodetic): + * return cls(geodetic=geodetic) + */ + __pyx_tuple__26 = PyTuple_Pack(2, __pyx_n_s_cls, __pyx_n_s_geodetic); if (unlikely(!__pyx_tuple__26)) __PYX_ERR(0, 140, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__26); + __Pyx_GIVEREF(__pyx_tuple__26); + __pyx_codeobj__27 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__26, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_transformations_transform, __pyx_n_s_from_geodetic, 140, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__27)) __PYX_ERR(0, 140, __pyx_L1_error) + + /* "common/transformations/transformations.pyx":144 + * return cls(geodetic=geodetic) + * + * @classmethod # <<<<<<<<<<<<<< + * def from_ecef(cls, ecef): + * return cls(ecef=ecef) + */ + __pyx_tuple__28 = PyTuple_Pack(2, __pyx_n_s_cls, __pyx_n_s_ecef); if (unlikely(!__pyx_tuple__28)) __PYX_ERR(0, 144, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__28); + __Pyx_GIVEREF(__pyx_tuple__28); + __pyx_codeobj__29 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__28, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_transformations_transform, __pyx_n_s_from_ecef, 144, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__29)) __PYX_ERR(0, 144, __pyx_L1_error) + + /* "common/transformations/transformations.pyx":148 + * return cls(ecef=ecef) + * + * def ecef2ned_single(self, ecef): # <<<<<<<<<<<<<< + * assert self.lc + * cdef ECEF e = list2ecef(ecef) + */ + __pyx_tuple__30 = PyTuple_Pack(4, __pyx_n_s_self, __pyx_n_s_ecef, __pyx_n_s_e, __pyx_n_s_n); if (unlikely(!__pyx_tuple__30)) __PYX_ERR(0, 148, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__30); + __Pyx_GIVEREF(__pyx_tuple__30); + __pyx_codeobj__31 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 4, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__30, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_transformations_transform, __pyx_n_s_ecef2ned_single, 148, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__31)) __PYX_ERR(0, 148, __pyx_L1_error) + + /* "common/transformations/transformations.pyx":154 + * return [n.n, n.e, n.d] + * + * def ned2ecef_single(self, ned): # <<<<<<<<<<<<<< + * assert self.lc + * cdef NED n = list2ned(ned) + */ + __pyx_tuple__32 = PyTuple_Pack(4, __pyx_n_s_self, __pyx_n_s_ned, __pyx_n_s_n, __pyx_n_s_e); if (unlikely(!__pyx_tuple__32)) __PYX_ERR(0, 154, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__32); + __Pyx_GIVEREF(__pyx_tuple__32); + __pyx_codeobj__33 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 4, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__32, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_transformations_transform, __pyx_n_s_ned2ecef_single, 154, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__33)) __PYX_ERR(0, 154, __pyx_L1_error) + + /* "common/transformations/transformations.pyx":160 + * return [e.x, e.y, e.z] + * + * def geodetic2ned_single(self, geodetic): # <<<<<<<<<<<<<< + * assert self.lc + * cdef Geodetic g = list2geodetic(geodetic) + */ + __pyx_tuple__34 = PyTuple_Pack(4, __pyx_n_s_self, __pyx_n_s_geodetic, __pyx_n_s_g, __pyx_n_s_n); if (unlikely(!__pyx_tuple__34)) __PYX_ERR(0, 160, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__34); + __Pyx_GIVEREF(__pyx_tuple__34); + __pyx_codeobj__35 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 4, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__34, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_transformations_transform, __pyx_n_s_geodetic2ned_single, 160, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__35)) __PYX_ERR(0, 160, __pyx_L1_error) + + /* "common/transformations/transformations.pyx":166 + * return [n.n, n.e, n.d] + * + * def ned2geodetic_single(self, ned): # <<<<<<<<<<<<<< + * assert self.lc + * cdef NED n = list2ned(ned) + */ + __pyx_tuple__36 = PyTuple_Pack(4, __pyx_n_s_self, __pyx_n_s_ned, __pyx_n_s_n, __pyx_n_s_g); if (unlikely(!__pyx_tuple__36)) __PYX_ERR(0, 166, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__36); + __Pyx_GIVEREF(__pyx_tuple__36); + __pyx_codeobj__37 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 4, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__36, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_common_transformations_transform, __pyx_n_s_ned2geodetic_single, 166, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__37)) __PYX_ERR(0, 166, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.lc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_tuple__38 = PyTuple_Pack(1, __pyx_n_s_self); if (unlikely(!__pyx_tuple__38)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__38); + __Pyx_GIVEREF(__pyx_tuple__38); + __pyx_codeobj__39 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__38, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__39)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.lc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.lc cannot be converted to a Python object for pickling" + */ + __pyx_tuple__40 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_pyx_state); if (unlikely(!__pyx_tuple__40)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__40); + __Pyx_GIVEREF(__pyx_tuple__40); + __pyx_codeobj__41 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__40, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__41)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_RefNannyFinishContext(); + return -1; +} +/* #### Code section: init_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitConstants(void) { + if (__Pyx_CreateStringTabAndInitStrings() < 0) __PYX_ERR(0, 1, __pyx_L1_error); + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: init_globals ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitGlobals(void) { + /* AssertionsEnabled.init */ + if (likely(__Pyx_init_assertions_enabled() == 0)); else + +if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 1, __pyx_L1_error) + + /* NumpyImportArray.init */ + /* + * Cython has automatically inserted a call to _import_array since + * you didn't include one when you cimported numpy. To disable this + * add the line + * numpy._import_array + */ +#ifdef NPY_FEATURE_VERSION +#ifndef NO_IMPORT_ARRAY +if (unlikely(_import_array() == -1)) { + PyErr_SetString(PyExc_ImportError, "numpy.core.multiarray failed to import " + "(auto-generated because you didn't call 'numpy.import_array()' after cimporting numpy; " + "use 'numpy._import_array' to disable if you are certain you don't need it)."); +} +#endif +#endif + +if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 1, __pyx_L1_error) + + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: init_module ### */ + +static CYTHON_SMALL_CODE int __Pyx_modinit_global_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_import_code(void); /*proto*/ + +static int __Pyx_modinit_global_init_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_global_init_code", 0); + /*--- Global init code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_variable_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_export_code", 0); + /*--- Variable export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_export_code", 0); + /*--- Function export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_type_init_code(void) { + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_modinit_type_init_code", 0); + /*--- Type init code ---*/ + #if CYTHON_USE_TYPE_SPECS + __pyx_ptype_6common_15transformations_15transformations_LocalCoord = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_6common_15transformations_15transformations_LocalCoord_spec, NULL); if (unlikely(!__pyx_ptype_6common_15transformations_15transformations_LocalCoord)) __PYX_ERR(0, 114, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_6common_15transformations_15transformations_LocalCoord_spec, __pyx_ptype_6common_15transformations_15transformations_LocalCoord) < 0) __PYX_ERR(0, 114, __pyx_L1_error) + #else + __pyx_ptype_6common_15transformations_15transformations_LocalCoord = &__pyx_type_6common_15transformations_15transformations_LocalCoord; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_6common_15transformations_15transformations_LocalCoord) < 0) __PYX_ERR(0, 114, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_6common_15transformations_15transformations_LocalCoord->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_6common_15transformations_15transformations_LocalCoord->tp_dictoffset && __pyx_ptype_6common_15transformations_15transformations_LocalCoord->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_6common_15transformations_15transformations_LocalCoord->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_LocalCoord, (PyObject *) __pyx_ptype_6common_15transformations_15transformations_LocalCoord) < 0) __PYX_ERR(0, 114, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_6common_15transformations_15transformations_LocalCoord) < 0) __PYX_ERR(0, 114, __pyx_L1_error) + #endif + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_RefNannyFinishContext(); + return -1; +} + +static int __Pyx_modinit_type_import_code(void) { + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_modinit_type_import_code", 0); + /*--- Type import code ---*/ + __pyx_t_1 = PyImport_ImportModule(__Pyx_BUILTIN_MODULE_NAME); if (unlikely(!__pyx_t_1)) __PYX_ERR(3, 9, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_ptype_7cpython_4type_type = __Pyx_ImportType_3_0_8(__pyx_t_1, __Pyx_BUILTIN_MODULE_NAME, "type", + #if defined(PYPY_VERSION_NUM) && PYPY_VERSION_NUM < 0x050B0000 + sizeof(PyTypeObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyTypeObject), + #elif CYTHON_COMPILING_IN_LIMITED_API + sizeof(PyTypeObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyTypeObject), + #else + sizeof(PyHeapTypeObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyHeapTypeObject), + #endif + __Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_7cpython_4type_type) __PYX_ERR(3, 9, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = PyImport_ImportModule("numpy"); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 202, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_ptype_5numpy_dtype = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "dtype", sizeof(PyArray_Descr), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyArray_Descr),__Pyx_ImportType_CheckSize_Ignore_3_0_8); if (!__pyx_ptype_5numpy_dtype) __PYX_ERR(2, 202, __pyx_L1_error) + __pyx_ptype_5numpy_flatiter = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "flatiter", sizeof(PyArrayIterObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyArrayIterObject),__Pyx_ImportType_CheckSize_Ignore_3_0_8); if (!__pyx_ptype_5numpy_flatiter) __PYX_ERR(2, 225, __pyx_L1_error) + __pyx_ptype_5numpy_broadcast = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "broadcast", sizeof(PyArrayMultiIterObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyArrayMultiIterObject),__Pyx_ImportType_CheckSize_Ignore_3_0_8); if (!__pyx_ptype_5numpy_broadcast) __PYX_ERR(2, 229, __pyx_L1_error) + __pyx_ptype_5numpy_ndarray = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "ndarray", sizeof(PyArrayObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyArrayObject),__Pyx_ImportType_CheckSize_Ignore_3_0_8); if (!__pyx_ptype_5numpy_ndarray) __PYX_ERR(2, 238, __pyx_L1_error) + __pyx_ptype_5numpy_generic = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "generic", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_generic) __PYX_ERR(2, 809, __pyx_L1_error) + __pyx_ptype_5numpy_number = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "number", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_number) __PYX_ERR(2, 811, __pyx_L1_error) + __pyx_ptype_5numpy_integer = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "integer", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_integer) __PYX_ERR(2, 813, __pyx_L1_error) + __pyx_ptype_5numpy_signedinteger = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "signedinteger", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_signedinteger) __PYX_ERR(2, 815, __pyx_L1_error) + __pyx_ptype_5numpy_unsignedinteger = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "unsignedinteger", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_unsignedinteger) __PYX_ERR(2, 817, __pyx_L1_error) + __pyx_ptype_5numpy_inexact = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "inexact", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_inexact) __PYX_ERR(2, 819, __pyx_L1_error) + __pyx_ptype_5numpy_floating = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "floating", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_floating) __PYX_ERR(2, 821, __pyx_L1_error) + __pyx_ptype_5numpy_complexfloating = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "complexfloating", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_complexfloating) __PYX_ERR(2, 823, __pyx_L1_error) + __pyx_ptype_5numpy_flexible = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "flexible", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_flexible) __PYX_ERR(2, 825, __pyx_L1_error) + __pyx_ptype_5numpy_character = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "character", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_character) __PYX_ERR(2, 827, __pyx_L1_error) + __pyx_ptype_5numpy_ufunc = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "ufunc", sizeof(PyUFuncObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyUFuncObject),__Pyx_ImportType_CheckSize_Ignore_3_0_8); if (!__pyx_ptype_5numpy_ufunc) __PYX_ERR(2, 866, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_RefNannyFinishContext(); + return -1; +} + +static int __Pyx_modinit_variable_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_import_code", 0); + /*--- Variable import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_import_code", 0); + /*--- Function import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + + +#if PY_MAJOR_VERSION >= 3 +#if CYTHON_PEP489_MULTI_PHASE_INIT +static PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def); /*proto*/ +static int __pyx_pymod_exec_transformations(PyObject* module); /*proto*/ +static PyModuleDef_Slot __pyx_moduledef_slots[] = { + {Py_mod_create, (void*)__pyx_pymod_create}, + {Py_mod_exec, (void*)__pyx_pymod_exec_transformations}, + {0, NULL} +}; +#endif + +#ifdef __cplusplus +namespace { + struct PyModuleDef __pyx_moduledef = + #else + static struct PyModuleDef __pyx_moduledef = + #endif + { + PyModuleDef_HEAD_INIT, + "transformations", + 0, /* m_doc */ + #if CYTHON_PEP489_MULTI_PHASE_INIT + 0, /* m_size */ + #elif CYTHON_USE_MODULE_STATE + sizeof(__pyx_mstate), /* m_size */ + #else + -1, /* m_size */ + #endif + __pyx_methods /* m_methods */, + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_moduledef_slots, /* m_slots */ + #else + NULL, /* m_reload */ + #endif + #if CYTHON_USE_MODULE_STATE + __pyx_m_traverse, /* m_traverse */ + __pyx_m_clear, /* m_clear */ + NULL /* m_free */ + #else + NULL, /* m_traverse */ + NULL, /* m_clear */ + NULL /* m_free */ + #endif + }; + #ifdef __cplusplus +} /* anonymous namespace */ +#endif +#endif + +#ifndef CYTHON_NO_PYINIT_EXPORT +#define __Pyx_PyMODINIT_FUNC PyMODINIT_FUNC +#elif PY_MAJOR_VERSION < 3 +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" void +#else +#define __Pyx_PyMODINIT_FUNC void +#endif +#else +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" PyObject * +#else +#define __Pyx_PyMODINIT_FUNC PyObject * +#endif +#endif + + +#if PY_MAJOR_VERSION < 3 +__Pyx_PyMODINIT_FUNC inittransformations(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC inittransformations(void) +#else +__Pyx_PyMODINIT_FUNC PyInit_transformations(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC PyInit_transformations(void) +#if CYTHON_PEP489_MULTI_PHASE_INIT +{ + return PyModuleDef_Init(&__pyx_moduledef); +} +static CYTHON_SMALL_CODE int __Pyx_check_single_interpreter(void) { + #if PY_VERSION_HEX >= 0x030700A1 + static PY_INT64_T main_interpreter_id = -1; + PY_INT64_T current_id = PyInterpreterState_GetID(PyThreadState_Get()->interp); + if (main_interpreter_id == -1) { + main_interpreter_id = current_id; + return (unlikely(current_id == -1)) ? -1 : 0; + } else if (unlikely(main_interpreter_id != current_id)) + #else + static PyInterpreterState *main_interpreter = NULL; + PyInterpreterState *current_interpreter = PyThreadState_Get()->interp; + if (!main_interpreter) { + main_interpreter = current_interpreter; + } else if (unlikely(main_interpreter != current_interpreter)) + #endif + { + PyErr_SetString( + PyExc_ImportError, + "Interpreter change detected - this module can only be loaded into one interpreter per process."); + return -1; + } + return 0; +} +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *module, const char* from_name, const char* to_name, int allow_none) +#else +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *moddict, const char* from_name, const char* to_name, int allow_none) +#endif +{ + PyObject *value = PyObject_GetAttrString(spec, from_name); + int result = 0; + if (likely(value)) { + if (allow_none || value != Py_None) { +#if CYTHON_COMPILING_IN_LIMITED_API + result = PyModule_AddObject(module, to_name, value); +#else + result = PyDict_SetItemString(moddict, to_name, value); +#endif + } + Py_DECREF(value); + } else if (PyErr_ExceptionMatches(PyExc_AttributeError)) { + PyErr_Clear(); + } else { + result = -1; + } + return result; +} +static CYTHON_SMALL_CODE PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def) { + PyObject *module = NULL, *moddict, *modname; + CYTHON_UNUSED_VAR(def); + if (__Pyx_check_single_interpreter()) + return NULL; + if (__pyx_m) + return __Pyx_NewRef(__pyx_m); + modname = PyObject_GetAttrString(spec, "name"); + if (unlikely(!modname)) goto bad; + module = PyModule_NewObject(modname); + Py_DECREF(modname); + if (unlikely(!module)) goto bad; +#if CYTHON_COMPILING_IN_LIMITED_API + moddict = module; +#else + moddict = PyModule_GetDict(module); + if (unlikely(!moddict)) goto bad; +#endif + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "loader", "__loader__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "origin", "__file__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "parent", "__package__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "submodule_search_locations", "__path__", 0) < 0)) goto bad; + return module; +bad: + Py_XDECREF(module); + return NULL; +} + + +static CYTHON_SMALL_CODE int __pyx_pymod_exec_transformations(PyObject *__pyx_pyinit_module) +#endif +#endif +{ + int stringtab_initialized = 0; + #if CYTHON_USE_MODULE_STATE + int pystate_addmodule_run = 0; + #endif + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannyDeclarations + #if CYTHON_PEP489_MULTI_PHASE_INIT + if (__pyx_m) { + if (__pyx_m == __pyx_pyinit_module) return 0; + PyErr_SetString(PyExc_RuntimeError, "Module 'transformations' has already been imported. Re-initialisation is not supported."); + return -1; + } + #elif PY_MAJOR_VERSION >= 3 + if (__pyx_m) return __Pyx_NewRef(__pyx_m); + #endif + /*--- Module creation code ---*/ + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_m = __pyx_pyinit_module; + Py_INCREF(__pyx_m); + #else + #if PY_MAJOR_VERSION < 3 + __pyx_m = Py_InitModule4("transformations", __pyx_methods, 0, 0, PYTHON_API_VERSION); Py_XINCREF(__pyx_m); + if (unlikely(!__pyx_m)) __PYX_ERR(0, 1, __pyx_L1_error) + #elif CYTHON_USE_MODULE_STATE + __pyx_t_1 = PyModule_Create(&__pyx_moduledef); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 1, __pyx_L1_error) + { + int add_module_result = PyState_AddModule(__pyx_t_1, &__pyx_moduledef); + __pyx_t_1 = 0; /* transfer ownership from __pyx_t_1 to "transformations" pseudovariable */ + if (unlikely((add_module_result < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + pystate_addmodule_run = 1; + } + #else + __pyx_m = PyModule_Create(&__pyx_moduledef); + if (unlikely(!__pyx_m)) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #endif + CYTHON_UNUSED_VAR(__pyx_t_1); + __pyx_d = PyModule_GetDict(__pyx_m); if (unlikely(!__pyx_d)) __PYX_ERR(0, 1, __pyx_L1_error) + Py_INCREF(__pyx_d); + __pyx_b = __Pyx_PyImport_AddModuleRef(__Pyx_BUILTIN_MODULE_NAME); if (unlikely(!__pyx_b)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_cython_runtime = __Pyx_PyImport_AddModuleRef((const char *) "cython_runtime"); if (unlikely(!__pyx_cython_runtime)) __PYX_ERR(0, 1, __pyx_L1_error) + if (PyObject_SetAttrString(__pyx_m, "__builtins__", __pyx_b) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #if CYTHON_REFNANNY +__Pyx_RefNanny = __Pyx_RefNannyImportAPI("refnanny"); +if (!__Pyx_RefNanny) { + PyErr_Clear(); + __Pyx_RefNanny = __Pyx_RefNannyImportAPI("Cython.Runtime.refnanny"); + if (!__Pyx_RefNanny) + Py_FatalError("failed to import 'refnanny' module"); +} +#endif + __Pyx_RefNannySetupContext("__Pyx_PyMODINIT_FUNC PyInit_transformations(void)", 0); + if (__Pyx_check_binary_version(__PYX_LIMITED_VERSION_HEX, __Pyx_get_runtime_version(), CYTHON_COMPILING_IN_LIMITED_API) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #ifdef __Pxy_PyFrame_Initialize_Offsets + __Pxy_PyFrame_Initialize_Offsets(); + #endif + __pyx_empty_tuple = PyTuple_New(0); if (unlikely(!__pyx_empty_tuple)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_empty_bytes = PyBytes_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_bytes)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_empty_unicode = PyUnicode_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_unicode)) __PYX_ERR(0, 1, __pyx_L1_error) + #ifdef __Pyx_CyFunction_USED + if (__pyx_CyFunction_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_FusedFunction_USED + if (__pyx_FusedFunction_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Coroutine_USED + if (__pyx_Coroutine_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Generator_USED + if (__pyx_Generator_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_AsyncGen_USED + if (__pyx_AsyncGen_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_StopAsyncIteration_USED + if (__pyx_StopAsyncIteration_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + /*--- Library function declarations ---*/ + /*--- Threads initialization code ---*/ + #if defined(WITH_THREAD) && PY_VERSION_HEX < 0x030700F0 && defined(__PYX_FORCE_INIT_THREADS) && __PYX_FORCE_INIT_THREADS + PyEval_InitThreads(); + #endif + /*--- Initialize various global constants etc. ---*/ + if (__Pyx_InitConstants() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + stringtab_initialized = 1; + if (__Pyx_InitGlobals() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #if PY_MAJOR_VERSION < 3 && (__PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT) + if (__Pyx_init_sys_getdefaultencoding_params() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + if (__pyx_module_is_main_common__transformations__transformations) { + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_name, __pyx_n_s_main) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + } + #if PY_MAJOR_VERSION >= 3 + { + PyObject *modules = PyImport_GetModuleDict(); if (unlikely(!modules)) __PYX_ERR(0, 1, __pyx_L1_error) + if (!PyDict_GetItemString(modules, "common.transformations.transformations")) { + if (unlikely((PyDict_SetItemString(modules, "common.transformations.transformations", __pyx_m) < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + } + } + #endif + /*--- Builtin init code ---*/ + if (__Pyx_InitCachedBuiltins() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + /*--- Constants init code ---*/ + if (__Pyx_InitCachedConstants() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + /*--- Global type/function init code ---*/ + (void)__Pyx_modinit_global_init_code(); + (void)__Pyx_modinit_variable_export_code(); + (void)__Pyx_modinit_function_export_code(); + if (unlikely((__Pyx_modinit_type_init_code() < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + if (unlikely((__Pyx_modinit_type_import_code() < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + (void)__Pyx_modinit_variable_import_code(); + (void)__Pyx_modinit_function_import_code(); + /*--- Execution code ---*/ + #if defined(__Pyx_Generator_USED) || defined(__Pyx_Coroutine_USED) + if (__Pyx_patch_abc() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + + /* "common/transformations/transformations.pyx":20 + * + * + * import numpy as np # <<<<<<<<<<<<<< + * cimport numpy as np + * + */ + __pyx_t_2 = __Pyx_ImportDottedModule(__pyx_n_s_numpy, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 20, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_np, __pyx_t_2) < 0) __PYX_ERR(0, 20, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "common/transformations/transformations.pyx":56 + * return g + * + * def euler2quat_single(euler): # <<<<<<<<<<<<<< + * cdef Vector3 e = Vector3(euler[0], euler[1], euler[2]) + * cdef Quaternion q = euler2quat_c(e) + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_6common_15transformations_15transformations_1euler2quat_single, 0, __pyx_n_s_euler2quat_single, NULL, __pyx_n_s_common_transformations_transform_2, __pyx_d, ((PyObject *)__pyx_codeobj__5)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 56, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_euler2quat_single, __pyx_t_2) < 0) __PYX_ERR(0, 56, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "common/transformations/transformations.pyx":61 + * return [q.w(), q.x(), q.y(), q.z()] + * + * def quat2euler_single(quat): # <<<<<<<<<<<<<< + * cdef Quaternion q = Quaternion(quat[0], quat[1], quat[2], quat[3]) + * cdef Vector3 e = quat2euler_c(q) + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_6common_15transformations_15transformations_3quat2euler_single, 0, __pyx_n_s_quat2euler_single, NULL, __pyx_n_s_common_transformations_transform_2, __pyx_d, ((PyObject *)__pyx_codeobj__7)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 61, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_quat2euler_single, __pyx_t_2) < 0) __PYX_ERR(0, 61, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "common/transformations/transformations.pyx":66 + * return [e(0), e(1), e(2)] + * + * def quat2rot_single(quat): # <<<<<<<<<<<<<< + * cdef Quaternion q = Quaternion(quat[0], quat[1], quat[2], quat[3]) + * cdef Matrix3 r = quat2rot_c(q) + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_6common_15transformations_15transformations_5quat2rot_single, 0, __pyx_n_s_quat2rot_single, NULL, __pyx_n_s_common_transformations_transform_2, __pyx_d, ((PyObject *)__pyx_codeobj__9)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 66, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_quat2rot_single, __pyx_t_2) < 0) __PYX_ERR(0, 66, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "common/transformations/transformations.pyx":71 + * return matrix2numpy(r) + * + * def rot2quat_single(rot): # <<<<<<<<<<<<<< + * cdef Matrix3 r = numpy2matrix(np.asfortranarray(rot, dtype=np.double)) + * cdef Quaternion q = rot2quat_c(r) + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_6common_15transformations_15transformations_7rot2quat_single, 0, __pyx_n_s_rot2quat_single, NULL, __pyx_n_s_common_transformations_transform_2, __pyx_d, ((PyObject *)__pyx_codeobj__11)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 71, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_rot2quat_single, __pyx_t_2) < 0) __PYX_ERR(0, 71, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "common/transformations/transformations.pyx":76 + * return [q.w(), q.x(), q.y(), q.z()] + * + * def euler2rot_single(euler): # <<<<<<<<<<<<<< + * cdef Vector3 e = Vector3(euler[0], euler[1], euler[2]) + * cdef Matrix3 r = euler2rot_c(e) + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_6common_15transformations_15transformations_9euler2rot_single, 0, __pyx_n_s_euler2rot_single, NULL, __pyx_n_s_common_transformations_transform_2, __pyx_d, ((PyObject *)__pyx_codeobj__13)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 76, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_euler2rot_single, __pyx_t_2) < 0) __PYX_ERR(0, 76, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "common/transformations/transformations.pyx":81 + * return matrix2numpy(r) + * + * def rot2euler_single(rot): # <<<<<<<<<<<<<< + * cdef Matrix3 r = numpy2matrix(np.asfortranarray(rot, dtype=np.double)) + * cdef Vector3 e = rot2euler_c(r) + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_6common_15transformations_15transformations_11rot2euler_single, 0, __pyx_n_s_rot2euler_single, NULL, __pyx_n_s_common_transformations_transform_2, __pyx_d, ((PyObject *)__pyx_codeobj__15)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 81, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_rot2euler_single, __pyx_t_2) < 0) __PYX_ERR(0, 81, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "common/transformations/transformations.pyx":86 + * return [e(0), e(1), e(2)] + * + * def rot_matrix(roll, pitch, yaw): # <<<<<<<<<<<<<< + * return matrix2numpy(rot_matrix_c(roll, pitch, yaw)) + * + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_6common_15transformations_15transformations_13rot_matrix, 0, __pyx_n_s_rot_matrix, NULL, __pyx_n_s_common_transformations_transform_2, __pyx_d, ((PyObject *)__pyx_codeobj__17)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 86, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_rot_matrix, __pyx_t_2) < 0) __PYX_ERR(0, 86, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "common/transformations/transformations.pyx":89 + * return matrix2numpy(rot_matrix_c(roll, pitch, yaw)) + * + * def ecef_euler_from_ned_single(ecef_init, ned_pose): # <<<<<<<<<<<<<< + * cdef ECEF init = list2ecef(ecef_init) + * cdef Vector3 pose = Vector3(ned_pose[0], ned_pose[1], ned_pose[2]) + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_6common_15transformations_15transformations_15ecef_euler_from_ned_single, 0, __pyx_n_s_ecef_euler_from_ned_single, NULL, __pyx_n_s_common_transformations_transform_2, __pyx_d, ((PyObject *)__pyx_codeobj__19)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 89, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_ecef_euler_from_ned_single, __pyx_t_2) < 0) __PYX_ERR(0, 89, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "common/transformations/transformations.pyx":96 + * return [e(0), e(1), e(2)] + * + * def ned_euler_from_ecef_single(ecef_init, ecef_pose): # <<<<<<<<<<<<<< + * cdef ECEF init = list2ecef(ecef_init) + * cdef Vector3 pose = Vector3(ecef_pose[0], ecef_pose[1], ecef_pose[2]) + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_6common_15transformations_15transformations_17ned_euler_from_ecef_single, 0, __pyx_n_s_ned_euler_from_ecef_single, NULL, __pyx_n_s_common_transformations_transform_2, __pyx_d, ((PyObject *)__pyx_codeobj__21)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 96, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_ned_euler_from_ecef_single, __pyx_t_2) < 0) __PYX_ERR(0, 96, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "common/transformations/transformations.pyx":103 + * return [e(0), e(1), e(2)] + * + * def geodetic2ecef_single(geodetic): # <<<<<<<<<<<<<< + * cdef Geodetic g = list2geodetic(geodetic) + * cdef ECEF e = geodetic2ecef_c(g) + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_6common_15transformations_15transformations_19geodetic2ecef_single, 0, __pyx_n_s_geodetic2ecef_single, NULL, __pyx_n_s_common_transformations_transform_2, __pyx_d, ((PyObject *)__pyx_codeobj__23)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 103, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_geodetic2ecef_single, __pyx_t_2) < 0) __PYX_ERR(0, 103, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "common/transformations/transformations.pyx":108 + * return [e.x, e.y, e.z] + * + * def ecef2geodetic_single(ecef): # <<<<<<<<<<<<<< + * cdef ECEF e = list2ecef(ecef) + * cdef Geodetic g = ecef2geodetic_c(e) + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_6common_15transformations_15transformations_21ecef2geodetic_single, 0, __pyx_n_s_ecef2geodetic_single, NULL, __pyx_n_s_common_transformations_transform_2, __pyx_d, ((PyObject *)__pyx_codeobj__25)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 108, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_ecef2geodetic_single, __pyx_t_2) < 0) __PYX_ERR(0, 108, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "common/transformations/transformations.pyx":140 + * return self.ned2ecef_matrix + * + * @classmethod # <<<<<<<<<<<<<< + * def from_geodetic(cls, geodetic): + * return cls(geodetic=geodetic) + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_6common_15transformations_15transformations_10LocalCoord_3from_geodetic, __Pyx_CYFUNCTION_CLASSMETHOD | __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_LocalCoord_from_geodetic, NULL, __pyx_n_s_common_transformations_transform_2, __pyx_d, ((PyObject *)__pyx_codeobj__27)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 140, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6common_15transformations_15transformations_LocalCoord, __pyx_n_s_from_geodetic, __pyx_t_2) < 0) __PYX_ERR(0, 140, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + PyType_Modified(__pyx_ptype_6common_15transformations_15transformations_LocalCoord); + __Pyx_GetNameInClass(__pyx_t_2, (PyObject *)__pyx_ptype_6common_15transformations_15transformations_LocalCoord, __pyx_n_s_from_geodetic); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 140, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_Method_ClassMethod(__pyx_t_2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 140, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6common_15transformations_15transformations_LocalCoord, __pyx_n_s_from_geodetic, __pyx_t_3) < 0) __PYX_ERR(0, 140, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + PyType_Modified(__pyx_ptype_6common_15transformations_15transformations_LocalCoord); + + /* "common/transformations/transformations.pyx":144 + * return cls(geodetic=geodetic) + * + * @classmethod # <<<<<<<<<<<<<< + * def from_ecef(cls, ecef): + * return cls(ecef=ecef) + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_6common_15transformations_15transformations_10LocalCoord_5from_ecef, __Pyx_CYFUNCTION_CLASSMETHOD | __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_LocalCoord_from_ecef, NULL, __pyx_n_s_common_transformations_transform_2, __pyx_d, ((PyObject *)__pyx_codeobj__29)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 144, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6common_15transformations_15transformations_LocalCoord, __pyx_n_s_from_ecef, __pyx_t_3) < 0) __PYX_ERR(0, 144, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + PyType_Modified(__pyx_ptype_6common_15transformations_15transformations_LocalCoord); + __Pyx_GetNameInClass(__pyx_t_3, (PyObject *)__pyx_ptype_6common_15transformations_15transformations_LocalCoord, __pyx_n_s_from_ecef); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 144, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_2 = __Pyx_Method_ClassMethod(__pyx_t_3); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 144, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6common_15transformations_15transformations_LocalCoord, __pyx_n_s_from_ecef, __pyx_t_2) < 0) __PYX_ERR(0, 144, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + PyType_Modified(__pyx_ptype_6common_15transformations_15transformations_LocalCoord); + + /* "common/transformations/transformations.pyx":148 + * return cls(ecef=ecef) + * + * def ecef2ned_single(self, ecef): # <<<<<<<<<<<<<< + * assert self.lc + * cdef ECEF e = list2ecef(ecef) + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_6common_15transformations_15transformations_10LocalCoord_7ecef2ned_single, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_LocalCoord_ecef2ned_single, NULL, __pyx_n_s_common_transformations_transform_2, __pyx_d, ((PyObject *)__pyx_codeobj__31)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 148, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6common_15transformations_15transformations_LocalCoord, __pyx_n_s_ecef2ned_single, __pyx_t_2) < 0) __PYX_ERR(0, 148, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + PyType_Modified(__pyx_ptype_6common_15transformations_15transformations_LocalCoord); + + /* "common/transformations/transformations.pyx":154 + * return [n.n, n.e, n.d] + * + * def ned2ecef_single(self, ned): # <<<<<<<<<<<<<< + * assert self.lc + * cdef NED n = list2ned(ned) + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_6common_15transformations_15transformations_10LocalCoord_9ned2ecef_single, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_LocalCoord_ned2ecef_single, NULL, __pyx_n_s_common_transformations_transform_2, __pyx_d, ((PyObject *)__pyx_codeobj__33)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 154, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6common_15transformations_15transformations_LocalCoord, __pyx_n_s_ned2ecef_single, __pyx_t_2) < 0) __PYX_ERR(0, 154, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + PyType_Modified(__pyx_ptype_6common_15transformations_15transformations_LocalCoord); + + /* "common/transformations/transformations.pyx":160 + * return [e.x, e.y, e.z] + * + * def geodetic2ned_single(self, geodetic): # <<<<<<<<<<<<<< + * assert self.lc + * cdef Geodetic g = list2geodetic(geodetic) + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_6common_15transformations_15transformations_10LocalCoord_11geodetic2ned_single, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_LocalCoord_geodetic2ned_single, NULL, __pyx_n_s_common_transformations_transform_2, __pyx_d, ((PyObject *)__pyx_codeobj__35)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 160, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6common_15transformations_15transformations_LocalCoord, __pyx_n_s_geodetic2ned_single, __pyx_t_2) < 0) __PYX_ERR(0, 160, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + PyType_Modified(__pyx_ptype_6common_15transformations_15transformations_LocalCoord); + + /* "common/transformations/transformations.pyx":166 + * return [n.n, n.e, n.d] + * + * def ned2geodetic_single(self, ned): # <<<<<<<<<<<<<< + * assert self.lc + * cdef NED n = list2ned(ned) + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_6common_15transformations_15transformations_10LocalCoord_13ned2geodetic_single, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_LocalCoord_ned2geodetic_single, NULL, __pyx_n_s_common_transformations_transform_2, __pyx_d, ((PyObject *)__pyx_codeobj__37)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 166, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_6common_15transformations_15transformations_LocalCoord, __pyx_n_s_ned2geodetic_single, __pyx_t_2) < 0) __PYX_ERR(0, 166, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + PyType_Modified(__pyx_ptype_6common_15transformations_15transformations_LocalCoord); + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.lc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_6common_15transformations_15transformations_10LocalCoord_17__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_LocalCoord___reduce_cython, NULL, __pyx_n_s_common_transformations_transform_2, __pyx_d, ((PyObject *)__pyx_codeobj__39)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_2) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.lc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.lc cannot be converted to a Python object for pickling" + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_6common_15transformations_15transformations_10LocalCoord_19__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_LocalCoord___setstate_cython, NULL, __pyx_n_s_common_transformations_transform_2, __pyx_d, ((PyObject *)__pyx_codeobj__41)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_2) < 0) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "common/transformations/transformations.pyx":1 + * # distutils: language = c++ # <<<<<<<<<<<<<< + * # cython: language_level = 3 + * from openpilot.common.transformations.transformations cimport Matrix3, Vector3, Quaternion + */ + __pyx_t_2 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_test, __pyx_t_2) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /*--- Wrapped vars code ---*/ + + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + if (__pyx_m) { + if (__pyx_d && stringtab_initialized) { + __Pyx_AddTraceback("init common.transformations.transformations", __pyx_clineno, __pyx_lineno, __pyx_filename); + } + #if !CYTHON_USE_MODULE_STATE + Py_CLEAR(__pyx_m); + #else + Py_DECREF(__pyx_m); + if (pystate_addmodule_run) { + PyObject *tp, *value, *tb; + PyErr_Fetch(&tp, &value, &tb); + PyState_RemoveModule(&__pyx_moduledef); + PyErr_Restore(tp, value, tb); + } + #endif + } else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_ImportError, "init common.transformations.transformations"); + } + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + #if CYTHON_PEP489_MULTI_PHASE_INIT + return (__pyx_m != NULL) ? 0 : -1; + #elif PY_MAJOR_VERSION >= 3 + return __pyx_m; + #else + return; + #endif +} +/* #### Code section: cleanup_globals ### */ +/* #### Code section: cleanup_module ### */ +/* #### Code section: main_method ### */ +/* #### Code section: utility_code_pragmas ### */ +#ifdef _MSC_VER +#pragma warning( push ) +/* Warning 4127: conditional expression is constant + * Cython uses constant conditional expressions to allow in inline functions to be optimized at + * compile-time, so this warning is not useful + */ +#pragma warning( disable : 4127 ) +#endif + + + +/* #### Code section: utility_code_def ### */ + +/* --- Runtime support code --- */ +/* Refnanny */ +#if CYTHON_REFNANNY +static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname) { + PyObject *m = NULL, *p = NULL; + void *r = NULL; + m = PyImport_ImportModule(modname); + if (!m) goto end; + p = PyObject_GetAttrString(m, "RefNannyAPI"); + if (!p) goto end; + r = PyLong_AsVoidPtr(p); +end: + Py_XDECREF(p); + Py_XDECREF(m); + return (__Pyx_RefNannyAPIStruct *)r; +} +#endif + +/* PyErrExceptionMatches */ +#if CYTHON_FAST_THREAD_STATE +static int __Pyx_PyErr_ExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; i= 0x030C00A6 + PyObject *current_exception = tstate->current_exception; + if (unlikely(!current_exception)) return 0; + exc_type = (PyObject*) Py_TYPE(current_exception); + if (exc_type == err) return 1; +#else + exc_type = tstate->curexc_type; + if (exc_type == err) return 1; + if (unlikely(!exc_type)) return 0; +#endif + #if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(exc_type); + #endif + if (unlikely(PyTuple_Check(err))) { + result = __Pyx_PyErr_ExceptionMatchesTuple(exc_type, err); + } else { + result = __Pyx_PyErr_GivenExceptionMatches(exc_type, err); + } + #if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(exc_type); + #endif + return result; +} +#endif + +/* PyErrFetchRestore */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject *tmp_value; + assert(type == NULL || (value != NULL && type == (PyObject*) Py_TYPE(value))); + if (value) { + #if CYTHON_COMPILING_IN_CPYTHON + if (unlikely(((PyBaseExceptionObject*) value)->traceback != tb)) + #endif + PyException_SetTraceback(value, tb); + } + tmp_value = tstate->current_exception; + tstate->current_exception = value; + Py_XDECREF(tmp_value); + Py_XDECREF(type); + Py_XDECREF(tb); +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + tmp_type = tstate->curexc_type; + tmp_value = tstate->curexc_value; + tmp_tb = tstate->curexc_traceback; + tstate->curexc_type = type; + tstate->curexc_value = value; + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); +#endif +} +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject* exc_value; + exc_value = tstate->current_exception; + tstate->current_exception = 0; + *value = exc_value; + *type = NULL; + *tb = NULL; + if (exc_value) { + *type = (PyObject*) Py_TYPE(exc_value); + Py_INCREF(*type); + #if CYTHON_COMPILING_IN_CPYTHON + *tb = ((PyBaseExceptionObject*) exc_value)->traceback; + Py_XINCREF(*tb); + #else + *tb = PyException_GetTraceback(exc_value); + #endif + } +#else + *type = tstate->curexc_type; + *value = tstate->curexc_value; + *tb = tstate->curexc_traceback; + tstate->curexc_type = 0; + tstate->curexc_value = 0; + tstate->curexc_traceback = 0; +#endif +} +#endif + +/* PyObjectGetAttrStr */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name) { + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro)) + return tp->tp_getattro(obj, attr_name); +#if PY_MAJOR_VERSION < 3 + if (likely(tp->tp_getattr)) + return tp->tp_getattr(obj, PyString_AS_STRING(attr_name)); +#endif + return PyObject_GetAttr(obj, attr_name); +} +#endif + +/* PyObjectGetAttrStrNoError */ +#if __PYX_LIMITED_VERSION_HEX < 0x030d00A1 +static void __Pyx_PyObject_GetAttrStr_ClearAttributeError(void) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + if (likely(__Pyx_PyErr_ExceptionMatches(PyExc_AttributeError))) + __Pyx_PyErr_Clear(); +} +#endif +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name) { + PyObject *result; +#if __PYX_LIMITED_VERSION_HEX >= 0x030d00A1 + (void) PyObject_GetOptionalAttr(obj, attr_name, &result); + return result; +#else +#if CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_TYPE_SLOTS && PY_VERSION_HEX >= 0x030700B1 + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro == PyObject_GenericGetAttr)) { + return _PyObject_GenericGetAttrWithDict(obj, attr_name, NULL, 1); + } +#endif + result = __Pyx_PyObject_GetAttrStr(obj, attr_name); + if (unlikely(!result)) { + __Pyx_PyObject_GetAttrStr_ClearAttributeError(); + } + return result; +#endif +} + +/* GetBuiltinName */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name) { + PyObject* result = __Pyx_PyObject_GetAttrStrNoError(__pyx_b, name); + if (unlikely(!result) && !PyErr_Occurred()) { + PyErr_Format(PyExc_NameError, +#if PY_MAJOR_VERSION >= 3 + "name '%U' is not defined", name); +#else + "name '%.200s' is not defined", PyString_AS_STRING(name)); +#endif + } + return result; +} + +/* GetTopmostException */ +#if CYTHON_USE_EXC_INFO_STACK && CYTHON_FAST_THREAD_STATE +static _PyErr_StackItem * +__Pyx_PyErr_GetTopmostException(PyThreadState *tstate) +{ + _PyErr_StackItem *exc_info = tstate->exc_info; + while ((exc_info->exc_value == NULL || exc_info->exc_value == Py_None) && + exc_info->previous_item != NULL) + { + exc_info = exc_info->previous_item; + } + return exc_info; +} +#endif + +/* SaveResetException */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx__ExceptionSave(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { + #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 + _PyErr_StackItem *exc_info = __Pyx_PyErr_GetTopmostException(tstate); + PyObject *exc_value = exc_info->exc_value; + if (exc_value == NULL || exc_value == Py_None) { + *value = NULL; + *type = NULL; + *tb = NULL; + } else { + *value = exc_value; + Py_INCREF(*value); + *type = (PyObject*) Py_TYPE(exc_value); + Py_INCREF(*type); + *tb = PyException_GetTraceback(exc_value); + } + #elif CYTHON_USE_EXC_INFO_STACK + _PyErr_StackItem *exc_info = __Pyx_PyErr_GetTopmostException(tstate); + *type = exc_info->exc_type; + *value = exc_info->exc_value; + *tb = exc_info->exc_traceback; + Py_XINCREF(*type); + Py_XINCREF(*value); + Py_XINCREF(*tb); + #else + *type = tstate->exc_type; + *value = tstate->exc_value; + *tb = tstate->exc_traceback; + Py_XINCREF(*type); + Py_XINCREF(*value); + Py_XINCREF(*tb); + #endif +} +static CYTHON_INLINE void __Pyx__ExceptionReset(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb) { + #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 + _PyErr_StackItem *exc_info = tstate->exc_info; + PyObject *tmp_value = exc_info->exc_value; + exc_info->exc_value = value; + Py_XDECREF(tmp_value); + Py_XDECREF(type); + Py_XDECREF(tb); + #else + PyObject *tmp_type, *tmp_value, *tmp_tb; + #if CYTHON_USE_EXC_INFO_STACK + _PyErr_StackItem *exc_info = tstate->exc_info; + tmp_type = exc_info->exc_type; + tmp_value = exc_info->exc_value; + tmp_tb = exc_info->exc_traceback; + exc_info->exc_type = type; + exc_info->exc_value = value; + exc_info->exc_traceback = tb; + #else + tmp_type = tstate->exc_type; + tmp_value = tstate->exc_value; + tmp_tb = tstate->exc_traceback; + tstate->exc_type = type; + tstate->exc_value = value; + tstate->exc_traceback = tb; + #endif + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); + #endif +} +#endif + +/* GetException */ +#if CYTHON_FAST_THREAD_STATE +static int __Pyx__GetException(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) +#else +static int __Pyx_GetException(PyObject **type, PyObject **value, PyObject **tb) +#endif +{ + PyObject *local_type = NULL, *local_value, *local_tb = NULL; +#if CYTHON_FAST_THREAD_STATE + PyObject *tmp_type, *tmp_value, *tmp_tb; + #if PY_VERSION_HEX >= 0x030C00A6 + local_value = tstate->current_exception; + tstate->current_exception = 0; + if (likely(local_value)) { + local_type = (PyObject*) Py_TYPE(local_value); + Py_INCREF(local_type); + local_tb = PyException_GetTraceback(local_value); + } + #else + local_type = tstate->curexc_type; + local_value = tstate->curexc_value; + local_tb = tstate->curexc_traceback; + tstate->curexc_type = 0; + tstate->curexc_value = 0; + tstate->curexc_traceback = 0; + #endif +#else + PyErr_Fetch(&local_type, &local_value, &local_tb); +#endif + PyErr_NormalizeException(&local_type, &local_value, &local_tb); +#if CYTHON_FAST_THREAD_STATE && PY_VERSION_HEX >= 0x030C00A6 + if (unlikely(tstate->current_exception)) +#elif CYTHON_FAST_THREAD_STATE + if (unlikely(tstate->curexc_type)) +#else + if (unlikely(PyErr_Occurred())) +#endif + goto bad; + #if PY_MAJOR_VERSION >= 3 + if (local_tb) { + if (unlikely(PyException_SetTraceback(local_value, local_tb) < 0)) + goto bad; + } + #endif + Py_XINCREF(local_tb); + Py_XINCREF(local_type); + Py_XINCREF(local_value); + *type = local_type; + *value = local_value; + *tb = local_tb; +#if CYTHON_FAST_THREAD_STATE + #if CYTHON_USE_EXC_INFO_STACK + { + _PyErr_StackItem *exc_info = tstate->exc_info; + #if PY_VERSION_HEX >= 0x030B00a4 + tmp_value = exc_info->exc_value; + exc_info->exc_value = local_value; + tmp_type = NULL; + tmp_tb = NULL; + Py_XDECREF(local_type); + Py_XDECREF(local_tb); + #else + tmp_type = exc_info->exc_type; + tmp_value = exc_info->exc_value; + tmp_tb = exc_info->exc_traceback; + exc_info->exc_type = local_type; + exc_info->exc_value = local_value; + exc_info->exc_traceback = local_tb; + #endif + } + #else + tmp_type = tstate->exc_type; + tmp_value = tstate->exc_value; + tmp_tb = tstate->exc_traceback; + tstate->exc_type = local_type; + tstate->exc_value = local_value; + tstate->exc_traceback = local_tb; + #endif + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); +#else + PyErr_SetExcInfo(local_type, local_value, local_tb); +#endif + return 0; +bad: + *type = 0; + *value = 0; + *tb = 0; + Py_XDECREF(local_type); + Py_XDECREF(local_value); + Py_XDECREF(local_tb); + return -1; +} + +/* PyObjectCall */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw) { + PyObject *result; + ternaryfunc call = Py_TYPE(func)->tp_call; + if (unlikely(!call)) + return PyObject_Call(func, arg, kw); + #if PY_MAJOR_VERSION < 3 + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + #else + if (unlikely(Py_EnterRecursiveCall(" while calling a Python object"))) + return NULL; + #endif + result = (*call)(func, arg, kw); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* RaiseException */ +#if PY_MAJOR_VERSION < 3 +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + __Pyx_PyThreadState_declare + CYTHON_UNUSED_VAR(cause); + Py_XINCREF(type); + if (!value || value == Py_None) + value = NULL; + else + Py_INCREF(value); + if (!tb || tb == Py_None) + tb = NULL; + else { + Py_INCREF(tb); + if (!PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto raise_error; + } + } + if (PyType_Check(type)) { +#if CYTHON_COMPILING_IN_PYPY + if (!value) { + Py_INCREF(Py_None); + value = Py_None; + } +#endif + PyErr_NormalizeException(&type, &value, &tb); + } else { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto raise_error; + } + value = type; + type = (PyObject*) Py_TYPE(type); + Py_INCREF(type); + if (!PyType_IsSubtype((PyTypeObject *)type, (PyTypeObject *)PyExc_BaseException)) { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto raise_error; + } + } + __Pyx_PyThreadState_assign + __Pyx_ErrRestore(type, value, tb); + return; +raise_error: + Py_XDECREF(value); + Py_XDECREF(type); + Py_XDECREF(tb); + return; +} +#else +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + PyObject* owned_instance = NULL; + if (tb == Py_None) { + tb = 0; + } else if (tb && !PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto bad; + } + if (value == Py_None) + value = 0; + if (PyExceptionInstance_Check(type)) { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto bad; + } + value = type; + type = (PyObject*) Py_TYPE(value); + } else if (PyExceptionClass_Check(type)) { + PyObject *instance_class = NULL; + if (value && PyExceptionInstance_Check(value)) { + instance_class = (PyObject*) Py_TYPE(value); + if (instance_class != type) { + int is_subclass = PyObject_IsSubclass(instance_class, type); + if (!is_subclass) { + instance_class = NULL; + } else if (unlikely(is_subclass == -1)) { + goto bad; + } else { + type = instance_class; + } + } + } + if (!instance_class) { + PyObject *args; + if (!value) + args = PyTuple_New(0); + else if (PyTuple_Check(value)) { + Py_INCREF(value); + args = value; + } else + args = PyTuple_Pack(1, value); + if (!args) + goto bad; + owned_instance = PyObject_Call(type, args, NULL); + Py_DECREF(args); + if (!owned_instance) + goto bad; + value = owned_instance; + if (!PyExceptionInstance_Check(value)) { + PyErr_Format(PyExc_TypeError, + "calling %R should have returned an instance of " + "BaseException, not %R", + type, Py_TYPE(value)); + goto bad; + } + } + } else { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto bad; + } + if (cause) { + PyObject *fixed_cause; + if (cause == Py_None) { + fixed_cause = NULL; + } else if (PyExceptionClass_Check(cause)) { + fixed_cause = PyObject_CallObject(cause, NULL); + if (fixed_cause == NULL) + goto bad; + } else if (PyExceptionInstance_Check(cause)) { + fixed_cause = cause; + Py_INCREF(fixed_cause); + } else { + PyErr_SetString(PyExc_TypeError, + "exception causes must derive from " + "BaseException"); + goto bad; + } + PyException_SetCause(value, fixed_cause); + } + PyErr_SetObject(type, value); + if (tb) { + #if PY_VERSION_HEX >= 0x030C00A6 + PyException_SetTraceback(value, tb); + #elif CYTHON_FAST_THREAD_STATE + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject* tmp_tb = tstate->curexc_traceback; + if (tb != tmp_tb) { + Py_INCREF(tb); + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_tb); + } +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + PyErr_Fetch(&tmp_type, &tmp_value, &tmp_tb); + Py_INCREF(tb); + PyErr_Restore(tmp_type, tmp_value, tb); + Py_XDECREF(tmp_tb); +#endif + } +bad: + Py_XDECREF(owned_instance); + return; +} +#endif + +/* PyDictVersioning */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + return likely(dict) ? __PYX_GET_DICT_VERSION(dict) : 0; +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj) { + PyObject **dictptr = NULL; + Py_ssize_t offset = Py_TYPE(obj)->tp_dictoffset; + if (offset) { +#if CYTHON_COMPILING_IN_CPYTHON + dictptr = (likely(offset > 0)) ? (PyObject **) ((char *)obj + offset) : _PyObject_GetDictPtr(obj); +#else + dictptr = _PyObject_GetDictPtr(obj); +#endif + } + return (dictptr && *dictptr) ? __PYX_GET_DICT_VERSION(*dictptr) : 0; +} +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + if (unlikely(!dict) || unlikely(tp_dict_version != __PYX_GET_DICT_VERSION(dict))) + return 0; + return obj_dict_version == __Pyx_get_object_dict_version(obj); +} +#endif + +/* GetModuleGlobalName */ +#if CYTHON_USE_DICT_VERSIONS +static PyObject *__Pyx__GetModuleGlobalName(PyObject *name, PY_UINT64_T *dict_version, PyObject **dict_cached_value) +#else +static CYTHON_INLINE PyObject *__Pyx__GetModuleGlobalName(PyObject *name) +#endif +{ + PyObject *result; +#if !CYTHON_AVOID_BORROWED_REFS +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030500A1 && PY_VERSION_HEX < 0x030d0000 + result = _PyDict_GetItem_KnownHash(__pyx_d, name, ((PyASCIIObject *) name)->hash); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } else if (unlikely(PyErr_Occurred())) { + return NULL; + } +#elif CYTHON_COMPILING_IN_LIMITED_API + if (unlikely(!__pyx_m)) { + return NULL; + } + result = PyObject_GetAttr(__pyx_m, name); + if (likely(result)) { + return result; + } +#else + result = PyDict_GetItem(__pyx_d, name); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } +#endif +#else + result = PyObject_GetItem(__pyx_d, name); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } + PyErr_Clear(); +#endif + return __Pyx_GetBuiltinName(name); +} + +/* PyFunctionFastCall */ +#if CYTHON_FAST_PYCALL && !CYTHON_VECTORCALL +static PyObject* __Pyx_PyFunction_FastCallNoKw(PyCodeObject *co, PyObject **args, Py_ssize_t na, + PyObject *globals) { + PyFrameObject *f; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject **fastlocals; + Py_ssize_t i; + PyObject *result; + assert(globals != NULL); + /* XXX Perhaps we should create a specialized + PyFrame_New() that doesn't take locals, but does + take builtins without sanity checking them. + */ + assert(tstate != NULL); + f = PyFrame_New(tstate, co, globals, NULL); + if (f == NULL) { + return NULL; + } + fastlocals = __Pyx_PyFrame_GetLocalsplus(f); + for (i = 0; i < na; i++) { + Py_INCREF(*args); + fastlocals[i] = *args++; + } + result = PyEval_EvalFrameEx(f,0); + ++tstate->recursion_depth; + Py_DECREF(f); + --tstate->recursion_depth; + return result; +} +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs) { + PyCodeObject *co = (PyCodeObject *)PyFunction_GET_CODE(func); + PyObject *globals = PyFunction_GET_GLOBALS(func); + PyObject *argdefs = PyFunction_GET_DEFAULTS(func); + PyObject *closure; +#if PY_MAJOR_VERSION >= 3 + PyObject *kwdefs; +#endif + PyObject *kwtuple, **k; + PyObject **d; + Py_ssize_t nd; + Py_ssize_t nk; + PyObject *result; + assert(kwargs == NULL || PyDict_Check(kwargs)); + nk = kwargs ? PyDict_Size(kwargs) : 0; + #if PY_MAJOR_VERSION < 3 + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) { + return NULL; + } + #else + if (unlikely(Py_EnterRecursiveCall(" while calling a Python object"))) { + return NULL; + } + #endif + if ( +#if PY_MAJOR_VERSION >= 3 + co->co_kwonlyargcount == 0 && +#endif + likely(kwargs == NULL || nk == 0) && + co->co_flags == (CO_OPTIMIZED | CO_NEWLOCALS | CO_NOFREE)) { + if (argdefs == NULL && co->co_argcount == nargs) { + result = __Pyx_PyFunction_FastCallNoKw(co, args, nargs, globals); + goto done; + } + else if (nargs == 0 && argdefs != NULL + && co->co_argcount == Py_SIZE(argdefs)) { + /* function called with no arguments, but all parameters have + a default value: use default values as arguments .*/ + args = &PyTuple_GET_ITEM(argdefs, 0); + result =__Pyx_PyFunction_FastCallNoKw(co, args, Py_SIZE(argdefs), globals); + goto done; + } + } + if (kwargs != NULL) { + Py_ssize_t pos, i; + kwtuple = PyTuple_New(2 * nk); + if (kwtuple == NULL) { + result = NULL; + goto done; + } + k = &PyTuple_GET_ITEM(kwtuple, 0); + pos = i = 0; + while (PyDict_Next(kwargs, &pos, &k[i], &k[i+1])) { + Py_INCREF(k[i]); + Py_INCREF(k[i+1]); + i += 2; + } + nk = i / 2; + } + else { + kwtuple = NULL; + k = NULL; + } + closure = PyFunction_GET_CLOSURE(func); +#if PY_MAJOR_VERSION >= 3 + kwdefs = PyFunction_GET_KW_DEFAULTS(func); +#endif + if (argdefs != NULL) { + d = &PyTuple_GET_ITEM(argdefs, 0); + nd = Py_SIZE(argdefs); + } + else { + d = NULL; + nd = 0; + } +#if PY_MAJOR_VERSION >= 3 + result = PyEval_EvalCodeEx((PyObject*)co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, kwdefs, closure); +#else + result = PyEval_EvalCodeEx(co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, closure); +#endif + Py_XDECREF(kwtuple); +done: + Py_LeaveRecursiveCall(); + return result; +} +#endif + +/* PyObjectCallMethO */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg) { + PyObject *self, *result; + PyCFunction cfunc; + cfunc = __Pyx_CyOrPyCFunction_GET_FUNCTION(func); + self = __Pyx_CyOrPyCFunction_GET_SELF(func); + #if PY_MAJOR_VERSION < 3 + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + #else + if (unlikely(Py_EnterRecursiveCall(" while calling a Python object"))) + return NULL; + #endif + result = cfunc(self, arg); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* PyObjectFastCall */ +#if PY_VERSION_HEX < 0x03090000 || CYTHON_COMPILING_IN_LIMITED_API +static PyObject* __Pyx_PyObject_FastCall_fallback(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs) { + PyObject *argstuple; + PyObject *result = 0; + size_t i; + argstuple = PyTuple_New((Py_ssize_t)nargs); + if (unlikely(!argstuple)) return NULL; + for (i = 0; i < nargs; i++) { + Py_INCREF(args[i]); + if (__Pyx_PyTuple_SET_ITEM(argstuple, (Py_ssize_t)i, args[i]) < 0) goto bad; + } + result = __Pyx_PyObject_Call(func, argstuple, kwargs); + bad: + Py_DECREF(argstuple); + return result; +} +#endif +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t _nargs, PyObject *kwargs) { + Py_ssize_t nargs = __Pyx_PyVectorcall_NARGS(_nargs); +#if CYTHON_COMPILING_IN_CPYTHON + if (nargs == 0 && kwargs == NULL) { + if (__Pyx_CyOrPyCFunction_Check(func) && likely( __Pyx_CyOrPyCFunction_GET_FLAGS(func) & METH_NOARGS)) + return __Pyx_PyObject_CallMethO(func, NULL); + } + else if (nargs == 1 && kwargs == NULL) { + if (__Pyx_CyOrPyCFunction_Check(func) && likely( __Pyx_CyOrPyCFunction_GET_FLAGS(func) & METH_O)) + return __Pyx_PyObject_CallMethO(func, args[0]); + } +#endif + #if PY_VERSION_HEX < 0x030800B1 + #if CYTHON_FAST_PYCCALL + if (PyCFunction_Check(func)) { + if (kwargs) { + return _PyCFunction_FastCallDict(func, args, nargs, kwargs); + } else { + return _PyCFunction_FastCallKeywords(func, args, nargs, NULL); + } + } + #if PY_VERSION_HEX >= 0x030700A1 + if (!kwargs && __Pyx_IS_TYPE(func, &PyMethodDescr_Type)) { + return _PyMethodDescr_FastCallKeywords(func, args, nargs, NULL); + } + #endif + #endif + #if CYTHON_FAST_PYCALL + if (PyFunction_Check(func)) { + return __Pyx_PyFunction_FastCallDict(func, args, nargs, kwargs); + } + #endif + #endif + if (kwargs == NULL) { + #if CYTHON_VECTORCALL + #if PY_VERSION_HEX < 0x03090000 + vectorcallfunc f = _PyVectorcall_Function(func); + #else + vectorcallfunc f = PyVectorcall_Function(func); + #endif + if (f) { + return f(func, args, (size_t)nargs, NULL); + } + #elif defined(__Pyx_CyFunction_USED) && CYTHON_BACKPORT_VECTORCALL + if (__Pyx_CyFunction_CheckExact(func)) { + __pyx_vectorcallfunc f = __Pyx_CyFunction_func_vectorcall(func); + if (f) return f(func, args, (size_t)nargs, NULL); + } + #endif + } + if (nargs == 0) { + return __Pyx_PyObject_Call(func, __pyx_empty_tuple, kwargs); + } + #if PY_VERSION_HEX >= 0x03090000 && !CYTHON_COMPILING_IN_LIMITED_API + return PyObject_VectorcallDict(func, args, (size_t)nargs, kwargs); + #else + return __Pyx_PyObject_FastCall_fallback(func, args, (size_t)nargs, kwargs); + #endif +} + +/* ExtTypeTest */ +static CYTHON_INLINE int __Pyx_TypeTest(PyObject *obj, PyTypeObject *type) { + __Pyx_TypeName obj_type_name; + __Pyx_TypeName type_name; + if (unlikely(!type)) { + PyErr_SetString(PyExc_SystemError, "Missing type object"); + return 0; + } + if (likely(__Pyx_TypeCheck(obj, type))) + return 1; + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + type_name = __Pyx_PyType_GetName(type); + PyErr_Format(PyExc_TypeError, + "Cannot convert " __Pyx_FMT_TYPENAME " to " __Pyx_FMT_TYPENAME, + obj_type_name, type_name); + __Pyx_DECREF_TypeName(obj_type_name); + __Pyx_DECREF_TypeName(type_name); + return 0; +} + +/* IsLittleEndian */ +static CYTHON_INLINE int __Pyx_Is_Little_Endian(void) +{ + union { + uint32_t u32; + uint8_t u8[4]; + } S; + S.u32 = 0x01020304; + return S.u8[0] == 4; +} + +/* BufferFormatCheck */ +static void __Pyx_BufFmt_Init(__Pyx_BufFmt_Context* ctx, + __Pyx_BufFmt_StackElem* stack, + __Pyx_TypeInfo* type) { + stack[0].field = &ctx->root; + stack[0].parent_offset = 0; + ctx->root.type = type; + ctx->root.name = "buffer dtype"; + ctx->root.offset = 0; + ctx->head = stack; + ctx->head->field = &ctx->root; + ctx->fmt_offset = 0; + ctx->head->parent_offset = 0; + ctx->new_packmode = '@'; + ctx->enc_packmode = '@'; + ctx->new_count = 1; + ctx->enc_count = 0; + ctx->enc_type = 0; + ctx->is_complex = 0; + ctx->is_valid_array = 0; + ctx->struct_alignment = 0; + while (type->typegroup == 'S') { + ++ctx->head; + ctx->head->field = type->fields; + ctx->head->parent_offset = 0; + type = type->fields->type; + } +} +static int __Pyx_BufFmt_ParseNumber(const char** ts) { + int count; + const char* t = *ts; + if (*t < '0' || *t > '9') { + return -1; + } else { + count = *t++ - '0'; + while (*t >= '0' && *t <= '9') { + count *= 10; + count += *t++ - '0'; + } + } + *ts = t; + return count; +} +static int __Pyx_BufFmt_ExpectNumber(const char **ts) { + int number = __Pyx_BufFmt_ParseNumber(ts); + if (number == -1) + PyErr_Format(PyExc_ValueError,\ + "Does not understand character buffer dtype format string ('%c')", **ts); + return number; +} +static void __Pyx_BufFmt_RaiseUnexpectedChar(char ch) { + PyErr_Format(PyExc_ValueError, + "Unexpected format string character: '%c'", ch); +} +static const char* __Pyx_BufFmt_DescribeTypeChar(char ch, int is_complex) { + switch (ch) { + case '?': return "'bool'"; + case 'c': return "'char'"; + case 'b': return "'signed char'"; + case 'B': return "'unsigned char'"; + case 'h': return "'short'"; + case 'H': return "'unsigned short'"; + case 'i': return "'int'"; + case 'I': return "'unsigned int'"; + case 'l': return "'long'"; + case 'L': return "'unsigned long'"; + case 'q': return "'long long'"; + case 'Q': return "'unsigned long long'"; + case 'f': return (is_complex ? "'complex float'" : "'float'"); + case 'd': return (is_complex ? "'complex double'" : "'double'"); + case 'g': return (is_complex ? "'complex long double'" : "'long double'"); + case 'T': return "a struct"; + case 'O': return "Python object"; + case 'P': return "a pointer"; + case 's': case 'p': return "a string"; + case 0: return "end"; + default: return "unparsable format string"; + } +} +static size_t __Pyx_BufFmt_TypeCharToStandardSize(char ch, int is_complex) { + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return 2; + case 'i': case 'I': case 'l': case 'L': return 4; + case 'q': case 'Q': return 8; + case 'f': return (is_complex ? 8 : 4); + case 'd': return (is_complex ? 16 : 8); + case 'g': { + PyErr_SetString(PyExc_ValueError, "Python does not define a standard format string size for long double ('g').."); + return 0; + } + case 'O': case 'P': return sizeof(void*); + default: + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } +} +static size_t __Pyx_BufFmt_TypeCharToNativeSize(char ch, int is_complex) { + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return sizeof(short); + case 'i': case 'I': return sizeof(int); + case 'l': case 'L': return sizeof(long); + #ifdef HAVE_LONG_LONG + case 'q': case 'Q': return sizeof(PY_LONG_LONG); + #endif + case 'f': return sizeof(float) * (is_complex ? 2 : 1); + case 'd': return sizeof(double) * (is_complex ? 2 : 1); + case 'g': return sizeof(long double) * (is_complex ? 2 : 1); + case 'O': case 'P': return sizeof(void*); + default: { + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } + } +} +typedef struct { char c; short x; } __Pyx_st_short; +typedef struct { char c; int x; } __Pyx_st_int; +typedef struct { char c; long x; } __Pyx_st_long; +typedef struct { char c; float x; } __Pyx_st_float; +typedef struct { char c; double x; } __Pyx_st_double; +typedef struct { char c; long double x; } __Pyx_st_longdouble; +typedef struct { char c; void *x; } __Pyx_st_void_p; +#ifdef HAVE_LONG_LONG +typedef struct { char c; PY_LONG_LONG x; } __Pyx_st_longlong; +#endif +static size_t __Pyx_BufFmt_TypeCharToAlignment(char ch, int is_complex) { + CYTHON_UNUSED_VAR(is_complex); + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return sizeof(__Pyx_st_short) - sizeof(short); + case 'i': case 'I': return sizeof(__Pyx_st_int) - sizeof(int); + case 'l': case 'L': return sizeof(__Pyx_st_long) - sizeof(long); +#ifdef HAVE_LONG_LONG + case 'q': case 'Q': return sizeof(__Pyx_st_longlong) - sizeof(PY_LONG_LONG); +#endif + case 'f': return sizeof(__Pyx_st_float) - sizeof(float); + case 'd': return sizeof(__Pyx_st_double) - sizeof(double); + case 'g': return sizeof(__Pyx_st_longdouble) - sizeof(long double); + case 'P': case 'O': return sizeof(__Pyx_st_void_p) - sizeof(void*); + default: + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } +} +/* These are for computing the padding at the end of the struct to align + on the first member of the struct. This will probably the same as above, + but we don't have any guarantees. + */ +typedef struct { short x; char c; } __Pyx_pad_short; +typedef struct { int x; char c; } __Pyx_pad_int; +typedef struct { long x; char c; } __Pyx_pad_long; +typedef struct { float x; char c; } __Pyx_pad_float; +typedef struct { double x; char c; } __Pyx_pad_double; +typedef struct { long double x; char c; } __Pyx_pad_longdouble; +typedef struct { void *x; char c; } __Pyx_pad_void_p; +#ifdef HAVE_LONG_LONG +typedef struct { PY_LONG_LONG x; char c; } __Pyx_pad_longlong; +#endif +static size_t __Pyx_BufFmt_TypeCharToPadding(char ch, int is_complex) { + CYTHON_UNUSED_VAR(is_complex); + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return sizeof(__Pyx_pad_short) - sizeof(short); + case 'i': case 'I': return sizeof(__Pyx_pad_int) - sizeof(int); + case 'l': case 'L': return sizeof(__Pyx_pad_long) - sizeof(long); +#ifdef HAVE_LONG_LONG + case 'q': case 'Q': return sizeof(__Pyx_pad_longlong) - sizeof(PY_LONG_LONG); +#endif + case 'f': return sizeof(__Pyx_pad_float) - sizeof(float); + case 'd': return sizeof(__Pyx_pad_double) - sizeof(double); + case 'g': return sizeof(__Pyx_pad_longdouble) - sizeof(long double); + case 'P': case 'O': return sizeof(__Pyx_pad_void_p) - sizeof(void*); + default: + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } +} +static char __Pyx_BufFmt_TypeCharToGroup(char ch, int is_complex) { + switch (ch) { + case 'c': + return 'H'; + case 'b': case 'h': case 'i': + case 'l': case 'q': case 's': case 'p': + return 'I'; + case '?': case 'B': case 'H': case 'I': case 'L': case 'Q': + return 'U'; + case 'f': case 'd': case 'g': + return (is_complex ? 'C' : 'R'); + case 'O': + return 'O'; + case 'P': + return 'P'; + default: { + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } + } +} +static void __Pyx_BufFmt_RaiseExpected(__Pyx_BufFmt_Context* ctx) { + if (ctx->head == NULL || ctx->head->field == &ctx->root) { + const char* expected; + const char* quote; + if (ctx->head == NULL) { + expected = "end"; + quote = ""; + } else { + expected = ctx->head->field->type->name; + quote = "'"; + } + PyErr_Format(PyExc_ValueError, + "Buffer dtype mismatch, expected %s%s%s but got %s", + quote, expected, quote, + __Pyx_BufFmt_DescribeTypeChar(ctx->enc_type, ctx->is_complex)); + } else { + __Pyx_StructField* field = ctx->head->field; + __Pyx_StructField* parent = (ctx->head - 1)->field; + PyErr_Format(PyExc_ValueError, + "Buffer dtype mismatch, expected '%s' but got %s in '%s.%s'", + field->type->name, __Pyx_BufFmt_DescribeTypeChar(ctx->enc_type, ctx->is_complex), + parent->type->name, field->name); + } +} +static int __Pyx_BufFmt_ProcessTypeChunk(__Pyx_BufFmt_Context* ctx) { + char group; + size_t size, offset, arraysize = 1; + if (ctx->enc_type == 0) return 0; + if (ctx->head->field->type->arraysize[0]) { + int i, ndim = 0; + if (ctx->enc_type == 's' || ctx->enc_type == 'p') { + ctx->is_valid_array = ctx->head->field->type->ndim == 1; + ndim = 1; + if (ctx->enc_count != ctx->head->field->type->arraysize[0]) { + PyErr_Format(PyExc_ValueError, + "Expected a dimension of size %zu, got %zu", + ctx->head->field->type->arraysize[0], ctx->enc_count); + return -1; + } + } + if (!ctx->is_valid_array) { + PyErr_Format(PyExc_ValueError, "Expected %d dimensions, got %d", + ctx->head->field->type->ndim, ndim); + return -1; + } + for (i = 0; i < ctx->head->field->type->ndim; i++) { + arraysize *= ctx->head->field->type->arraysize[i]; + } + ctx->is_valid_array = 0; + ctx->enc_count = 1; + } + group = __Pyx_BufFmt_TypeCharToGroup(ctx->enc_type, ctx->is_complex); + do { + __Pyx_StructField* field = ctx->head->field; + __Pyx_TypeInfo* type = field->type; + if (ctx->enc_packmode == '@' || ctx->enc_packmode == '^') { + size = __Pyx_BufFmt_TypeCharToNativeSize(ctx->enc_type, ctx->is_complex); + } else { + size = __Pyx_BufFmt_TypeCharToStandardSize(ctx->enc_type, ctx->is_complex); + } + if (ctx->enc_packmode == '@') { + size_t align_at = __Pyx_BufFmt_TypeCharToAlignment(ctx->enc_type, ctx->is_complex); + size_t align_mod_offset; + if (align_at == 0) return -1; + align_mod_offset = ctx->fmt_offset % align_at; + if (align_mod_offset > 0) ctx->fmt_offset += align_at - align_mod_offset; + if (ctx->struct_alignment == 0) + ctx->struct_alignment = __Pyx_BufFmt_TypeCharToPadding(ctx->enc_type, + ctx->is_complex); + } + if (type->size != size || type->typegroup != group) { + if (type->typegroup == 'C' && type->fields != NULL) { + size_t parent_offset = ctx->head->parent_offset + field->offset; + ++ctx->head; + ctx->head->field = type->fields; + ctx->head->parent_offset = parent_offset; + continue; + } + if ((type->typegroup == 'H' || group == 'H') && type->size == size) { + } else { + __Pyx_BufFmt_RaiseExpected(ctx); + return -1; + } + } + offset = ctx->head->parent_offset + field->offset; + if (ctx->fmt_offset != offset) { + PyErr_Format(PyExc_ValueError, + "Buffer dtype mismatch; next field is at offset %" CYTHON_FORMAT_SSIZE_T "d but %" CYTHON_FORMAT_SSIZE_T "d expected", + (Py_ssize_t)ctx->fmt_offset, (Py_ssize_t)offset); + return -1; + } + ctx->fmt_offset += size; + if (arraysize) + ctx->fmt_offset += (arraysize - 1) * size; + --ctx->enc_count; + while (1) { + if (field == &ctx->root) { + ctx->head = NULL; + if (ctx->enc_count != 0) { + __Pyx_BufFmt_RaiseExpected(ctx); + return -1; + } + break; + } + ctx->head->field = ++field; + if (field->type == NULL) { + --ctx->head; + field = ctx->head->field; + continue; + } else if (field->type->typegroup == 'S') { + size_t parent_offset = ctx->head->parent_offset + field->offset; + if (field->type->fields->type == NULL) continue; + field = field->type->fields; + ++ctx->head; + ctx->head->field = field; + ctx->head->parent_offset = parent_offset; + break; + } else { + break; + } + } + } while (ctx->enc_count); + ctx->enc_type = 0; + ctx->is_complex = 0; + return 0; +} +static int +__pyx_buffmt_parse_array(__Pyx_BufFmt_Context* ctx, const char** tsp) +{ + const char *ts = *tsp; + int i = 0, number, ndim; + ++ts; + if (ctx->new_count != 1) { + PyErr_SetString(PyExc_ValueError, + "Cannot handle repeated arrays in format string"); + return -1; + } + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return -1; + ndim = ctx->head->field->type->ndim; + while (*ts && *ts != ')') { + switch (*ts) { + case ' ': case '\f': case '\r': case '\n': case '\t': case '\v': continue; + default: break; + } + number = __Pyx_BufFmt_ExpectNumber(&ts); + if (number == -1) return -1; + if (i < ndim && (size_t) number != ctx->head->field->type->arraysize[i]) { + PyErr_Format(PyExc_ValueError, + "Expected a dimension of size %zu, got %d", + ctx->head->field->type->arraysize[i], number); + return -1; + } + if (*ts != ',' && *ts != ')') { + PyErr_Format(PyExc_ValueError, + "Expected a comma in format string, got '%c'", *ts); + return -1; + } + if (*ts == ',') ts++; + i++; + } + if (i != ndim) { + PyErr_Format(PyExc_ValueError, "Expected %d dimension(s), got %d", + ctx->head->field->type->ndim, i); + return -1; + } + if (!*ts) { + PyErr_SetString(PyExc_ValueError, + "Unexpected end of format string, expected ')'"); + return -1; + } + ctx->is_valid_array = 1; + ctx->new_count = 1; + *tsp = ++ts; + return 0; +} +static const char* __Pyx_BufFmt_CheckString(__Pyx_BufFmt_Context* ctx, const char* ts) { + int got_Z = 0; + while (1) { + switch(*ts) { + case 0: + if (ctx->enc_type != 0 && ctx->head == NULL) { + __Pyx_BufFmt_RaiseExpected(ctx); + return NULL; + } + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + if (ctx->head != NULL) { + __Pyx_BufFmt_RaiseExpected(ctx); + return NULL; + } + return ts; + case ' ': + case '\r': + case '\n': + ++ts; + break; + case '<': + if (!__Pyx_Is_Little_Endian()) { + PyErr_SetString(PyExc_ValueError, "Little-endian buffer not supported on big-endian compiler"); + return NULL; + } + ctx->new_packmode = '='; + ++ts; + break; + case '>': + case '!': + if (__Pyx_Is_Little_Endian()) { + PyErr_SetString(PyExc_ValueError, "Big-endian buffer not supported on little-endian compiler"); + return NULL; + } + ctx->new_packmode = '='; + ++ts; + break; + case '=': + case '@': + case '^': + ctx->new_packmode = *ts++; + break; + case 'T': + { + const char* ts_after_sub; + size_t i, struct_count = ctx->new_count; + size_t struct_alignment = ctx->struct_alignment; + ctx->new_count = 1; + ++ts; + if (*ts != '{') { + PyErr_SetString(PyExc_ValueError, "Buffer acquisition: Expected '{' after 'T'"); + return NULL; + } + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->enc_type = 0; + ctx->enc_count = 0; + ctx->struct_alignment = 0; + ++ts; + ts_after_sub = ts; + for (i = 0; i != struct_count; ++i) { + ts_after_sub = __Pyx_BufFmt_CheckString(ctx, ts); + if (!ts_after_sub) return NULL; + } + ts = ts_after_sub; + if (struct_alignment) ctx->struct_alignment = struct_alignment; + } + break; + case '}': + { + size_t alignment = ctx->struct_alignment; + ++ts; + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->enc_type = 0; + if (alignment && ctx->fmt_offset % alignment) { + ctx->fmt_offset += alignment - (ctx->fmt_offset % alignment); + } + } + return ts; + case 'x': + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->fmt_offset += ctx->new_count; + ctx->new_count = 1; + ctx->enc_count = 0; + ctx->enc_type = 0; + ctx->enc_packmode = ctx->new_packmode; + ++ts; + break; + case 'Z': + got_Z = 1; + ++ts; + if (*ts != 'f' && *ts != 'd' && *ts != 'g') { + __Pyx_BufFmt_RaiseUnexpectedChar('Z'); + return NULL; + } + CYTHON_FALLTHROUGH; + case '?': case 'c': case 'b': case 'B': case 'h': case 'H': case 'i': case 'I': + case 'l': case 'L': case 'q': case 'Q': + case 'f': case 'd': case 'g': + case 'O': case 'p': + if ((ctx->enc_type == *ts) && (got_Z == ctx->is_complex) && + (ctx->enc_packmode == ctx->new_packmode) && (!ctx->is_valid_array)) { + ctx->enc_count += ctx->new_count; + ctx->new_count = 1; + got_Z = 0; + ++ts; + break; + } + CYTHON_FALLTHROUGH; + case 's': + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->enc_count = ctx->new_count; + ctx->enc_packmode = ctx->new_packmode; + ctx->enc_type = *ts; + ctx->is_complex = got_Z; + ++ts; + ctx->new_count = 1; + got_Z = 0; + break; + case ':': + ++ts; + while(*ts != ':') ++ts; + ++ts; + break; + case '(': + if (__pyx_buffmt_parse_array(ctx, &ts) < 0) return NULL; + break; + default: + { + int number = __Pyx_BufFmt_ExpectNumber(&ts); + if (number == -1) return NULL; + ctx->new_count = (size_t)number; + } + } + } +} + +/* BufferGetAndValidate */ + static CYTHON_INLINE void __Pyx_SafeReleaseBuffer(Py_buffer* info) { + if (unlikely(info->buf == NULL)) return; + if (info->suboffsets == __Pyx_minusones) info->suboffsets = NULL; + __Pyx_ReleaseBuffer(info); +} +static void __Pyx_ZeroBuffer(Py_buffer* buf) { + buf->buf = NULL; + buf->obj = NULL; + buf->strides = __Pyx_zeros; + buf->shape = __Pyx_zeros; + buf->suboffsets = __Pyx_minusones; +} +static int __Pyx__GetBufferAndValidate( + Py_buffer* buf, PyObject* obj, __Pyx_TypeInfo* dtype, int flags, + int nd, int cast, __Pyx_BufFmt_StackElem* stack) +{ + buf->buf = NULL; + if (unlikely(__Pyx_GetBuffer(obj, buf, flags) == -1)) { + __Pyx_ZeroBuffer(buf); + return -1; + } + if (unlikely(buf->ndim != nd)) { + PyErr_Format(PyExc_ValueError, + "Buffer has wrong number of dimensions (expected %d, got %d)", + nd, buf->ndim); + goto fail; + } + if (!cast) { + __Pyx_BufFmt_Context ctx; + __Pyx_BufFmt_Init(&ctx, stack, dtype); + if (!__Pyx_BufFmt_CheckString(&ctx, buf->format)) goto fail; + } + if (unlikely((size_t)buf->itemsize != dtype->size)) { + PyErr_Format(PyExc_ValueError, + "Item size of buffer (%" CYTHON_FORMAT_SSIZE_T "d byte%s) does not match size of '%s' (%" CYTHON_FORMAT_SSIZE_T "d byte%s)", + buf->itemsize, (buf->itemsize > 1) ? "s" : "", + dtype->name, (Py_ssize_t)dtype->size, (dtype->size > 1) ? "s" : ""); + goto fail; + } + if (buf->suboffsets == NULL) buf->suboffsets = __Pyx_minusones; + return 0; +fail:; + __Pyx_SafeReleaseBuffer(buf); + return -1; +} + +/* GetItemInt */ + static PyObject *__Pyx_GetItemInt_Generic(PyObject *o, PyObject* j) { + PyObject *r; + if (unlikely(!j)) return NULL; + r = PyObject_GetItem(o, j); + Py_DECREF(j); + return r; +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_List_Fast(PyObject *o, Py_ssize_t i, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + Py_ssize_t wrapped_i = i; + if (wraparound & unlikely(i < 0)) { + wrapped_i += PyList_GET_SIZE(o); + } + if ((!boundscheck) || likely(__Pyx_is_valid_index(wrapped_i, PyList_GET_SIZE(o)))) { + PyObject *r = PyList_GET_ITEM(o, wrapped_i); + Py_INCREF(r); + return r; + } + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +#else + return PySequence_GetItem(o, i); +#endif +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Tuple_Fast(PyObject *o, Py_ssize_t i, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + Py_ssize_t wrapped_i = i; + if (wraparound & unlikely(i < 0)) { + wrapped_i += PyTuple_GET_SIZE(o); + } + if ((!boundscheck) || likely(__Pyx_is_valid_index(wrapped_i, PyTuple_GET_SIZE(o)))) { + PyObject *r = PyTuple_GET_ITEM(o, wrapped_i); + Py_INCREF(r); + return r; + } + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +#else + return PySequence_GetItem(o, i); +#endif +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Fast(PyObject *o, Py_ssize_t i, int is_list, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS && CYTHON_USE_TYPE_SLOTS + if (is_list || PyList_CheckExact(o)) { + Py_ssize_t n = ((!wraparound) | likely(i >= 0)) ? i : i + PyList_GET_SIZE(o); + if ((!boundscheck) || (likely(__Pyx_is_valid_index(n, PyList_GET_SIZE(o))))) { + PyObject *r = PyList_GET_ITEM(o, n); + Py_INCREF(r); + return r; + } + } + else if (PyTuple_CheckExact(o)) { + Py_ssize_t n = ((!wraparound) | likely(i >= 0)) ? i : i + PyTuple_GET_SIZE(o); + if ((!boundscheck) || likely(__Pyx_is_valid_index(n, PyTuple_GET_SIZE(o)))) { + PyObject *r = PyTuple_GET_ITEM(o, n); + Py_INCREF(r); + return r; + } + } else { + PyMappingMethods *mm = Py_TYPE(o)->tp_as_mapping; + PySequenceMethods *sm = Py_TYPE(o)->tp_as_sequence; + if (mm && mm->mp_subscript) { + PyObject *r, *key = PyInt_FromSsize_t(i); + if (unlikely(!key)) return NULL; + r = mm->mp_subscript(o, key); + Py_DECREF(key); + return r; + } + if (likely(sm && sm->sq_item)) { + if (wraparound && unlikely(i < 0) && likely(sm->sq_length)) { + Py_ssize_t l = sm->sq_length(o); + if (likely(l >= 0)) { + i += l; + } else { + if (!PyErr_ExceptionMatches(PyExc_OverflowError)) + return NULL; + PyErr_Clear(); + } + } + return sm->sq_item(o, i); + } + } +#else + if (is_list || !PyMapping_Check(o)) { + return PySequence_GetItem(o, i); + } +#endif + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +} + +/* TupleAndListFromArray */ + #if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE void __Pyx_copy_object_array(PyObject *const *CYTHON_RESTRICT src, PyObject** CYTHON_RESTRICT dest, Py_ssize_t length) { + PyObject *v; + Py_ssize_t i; + for (i = 0; i < length; i++) { + v = dest[i] = src[i]; + Py_INCREF(v); + } +} +static CYTHON_INLINE PyObject * +__Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + Py_INCREF(__pyx_empty_tuple); + return __pyx_empty_tuple; + } + res = PyTuple_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyTupleObject*)res)->ob_item, n); + return res; +} +static CYTHON_INLINE PyObject * +__Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + return PyList_New(0); + } + res = PyList_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyListObject*)res)->ob_item, n); + return res; +} +#endif + +/* BytesEquals */ + static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else + if (s1 == s2) { + return (equals == Py_EQ); + } else if (PyBytes_CheckExact(s1) & PyBytes_CheckExact(s2)) { + const char *ps1, *ps2; + Py_ssize_t length = PyBytes_GET_SIZE(s1); + if (length != PyBytes_GET_SIZE(s2)) + return (equals == Py_NE); + ps1 = PyBytes_AS_STRING(s1); + ps2 = PyBytes_AS_STRING(s2); + if (ps1[0] != ps2[0]) { + return (equals == Py_NE); + } else if (length == 1) { + return (equals == Py_EQ); + } else { + int result; +#if CYTHON_USE_UNICODE_INTERNALS && (PY_VERSION_HEX < 0x030B0000) + Py_hash_t hash1, hash2; + hash1 = ((PyBytesObject*)s1)->ob_shash; + hash2 = ((PyBytesObject*)s2)->ob_shash; + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + return (equals == Py_NE); + } +#endif + result = memcmp(ps1, ps2, (size_t)length); + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & PyBytes_CheckExact(s2)) { + return (equals == Py_NE); + } else if ((s2 == Py_None) & PyBytes_CheckExact(s1)) { + return (equals == Py_NE); + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +#endif +} + +/* UnicodeEquals */ + static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else +#if PY_MAJOR_VERSION < 3 + PyObject* owned_ref = NULL; +#endif + int s1_is_unicode, s2_is_unicode; + if (s1 == s2) { + goto return_eq; + } + s1_is_unicode = PyUnicode_CheckExact(s1); + s2_is_unicode = PyUnicode_CheckExact(s2); +#if PY_MAJOR_VERSION < 3 + if ((s1_is_unicode & (!s2_is_unicode)) && PyString_CheckExact(s2)) { + owned_ref = PyUnicode_FromObject(s2); + if (unlikely(!owned_ref)) + return -1; + s2 = owned_ref; + s2_is_unicode = 1; + } else if ((s2_is_unicode & (!s1_is_unicode)) && PyString_CheckExact(s1)) { + owned_ref = PyUnicode_FromObject(s1); + if (unlikely(!owned_ref)) + return -1; + s1 = owned_ref; + s1_is_unicode = 1; + } else if (((!s2_is_unicode) & (!s1_is_unicode))) { + return __Pyx_PyBytes_Equals(s1, s2, equals); + } +#endif + if (s1_is_unicode & s2_is_unicode) { + Py_ssize_t length; + int kind; + void *data1, *data2; + if (unlikely(__Pyx_PyUnicode_READY(s1) < 0) || unlikely(__Pyx_PyUnicode_READY(s2) < 0)) + return -1; + length = __Pyx_PyUnicode_GET_LENGTH(s1); + if (length != __Pyx_PyUnicode_GET_LENGTH(s2)) { + goto return_ne; + } +#if CYTHON_USE_UNICODE_INTERNALS + { + Py_hash_t hash1, hash2; + #if CYTHON_PEP393_ENABLED + hash1 = ((PyASCIIObject*)s1)->hash; + hash2 = ((PyASCIIObject*)s2)->hash; + #else + hash1 = ((PyUnicodeObject*)s1)->hash; + hash2 = ((PyUnicodeObject*)s2)->hash; + #endif + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + goto return_ne; + } + } +#endif + kind = __Pyx_PyUnicode_KIND(s1); + if (kind != __Pyx_PyUnicode_KIND(s2)) { + goto return_ne; + } + data1 = __Pyx_PyUnicode_DATA(s1); + data2 = __Pyx_PyUnicode_DATA(s2); + if (__Pyx_PyUnicode_READ(kind, data1, 0) != __Pyx_PyUnicode_READ(kind, data2, 0)) { + goto return_ne; + } else if (length == 1) { + goto return_eq; + } else { + int result = memcmp(data1, data2, (size_t)(length * kind)); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & s2_is_unicode) { + goto return_ne; + } else if ((s2 == Py_None) & s1_is_unicode) { + goto return_ne; + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +return_eq: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ); +return_ne: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_NE); +#endif +} + +/* fastcall */ + #if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s) +{ + Py_ssize_t i, n = PyTuple_GET_SIZE(kwnames); + for (i = 0; i < n; i++) + { + if (s == PyTuple_GET_ITEM(kwnames, i)) return kwvalues[i]; + } + for (i = 0; i < n; i++) + { + int eq = __Pyx_PyUnicode_Equals(s, PyTuple_GET_ITEM(kwnames, i), Py_EQ); + if (unlikely(eq != 0)) { + if (unlikely(eq < 0)) return NULL; + return kwvalues[i]; + } + } + return NULL; +} +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 +CYTHON_UNUSED static PyObject *__Pyx_KwargsAsDict_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues) { + Py_ssize_t i, nkwargs = PyTuple_GET_SIZE(kwnames); + PyObject *dict; + dict = PyDict_New(); + if (unlikely(!dict)) + return NULL; + for (i=0; i= 3 + "%s() got multiple values for keyword argument '%U'", func_name, kw_name); + #else + "%s() got multiple values for keyword argument '%s'", func_name, + PyString_AsString(kw_name)); + #endif +} + +/* ParseKeywords */ + static int __Pyx_ParseOptionalKeywords( + PyObject *kwds, + PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, + PyObject *values[], + Py_ssize_t num_pos_args, + const char* function_name) +{ + PyObject *key = 0, *value = 0; + Py_ssize_t pos = 0; + PyObject*** name; + PyObject*** first_kw_arg = argnames + num_pos_args; + int kwds_is_tuple = CYTHON_METH_FASTCALL && likely(PyTuple_Check(kwds)); + while (1) { + Py_XDECREF(key); key = NULL; + Py_XDECREF(value); value = NULL; + if (kwds_is_tuple) { + Py_ssize_t size; +#if CYTHON_ASSUME_SAFE_MACROS + size = PyTuple_GET_SIZE(kwds); +#else + size = PyTuple_Size(kwds); + if (size < 0) goto bad; +#endif + if (pos >= size) break; +#if CYTHON_AVOID_BORROWED_REFS + key = __Pyx_PySequence_ITEM(kwds, pos); + if (!key) goto bad; +#elif CYTHON_ASSUME_SAFE_MACROS + key = PyTuple_GET_ITEM(kwds, pos); +#else + key = PyTuple_GetItem(kwds, pos); + if (!key) goto bad; +#endif + value = kwvalues[pos]; + pos++; + } + else + { + if (!PyDict_Next(kwds, &pos, &key, &value)) break; +#if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(key); +#endif + } + name = first_kw_arg; + while (*name && (**name != key)) name++; + if (*name) { + values[name-argnames] = value; +#if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(value); + Py_DECREF(key); +#endif + key = NULL; + value = NULL; + continue; + } +#if !CYTHON_AVOID_BORROWED_REFS + Py_INCREF(key); +#endif + Py_INCREF(value); + name = first_kw_arg; + #if PY_MAJOR_VERSION < 3 + if (likely(PyString_Check(key))) { + while (*name) { + if ((CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**name) == PyString_GET_SIZE(key)) + && _PyString_Eq(**name, key)) { + values[name-argnames] = value; +#if CYTHON_AVOID_BORROWED_REFS + value = NULL; +#endif + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + if ((**argname == key) || ( + (CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**argname) == PyString_GET_SIZE(key)) + && _PyString_Eq(**argname, key))) { + goto arg_passed_twice; + } + argname++; + } + } + } else + #endif + if (likely(PyUnicode_Check(key))) { + while (*name) { + int cmp = ( + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**name) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**name, key) + ); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) { + values[name-argnames] = value; +#if CYTHON_AVOID_BORROWED_REFS + value = NULL; +#endif + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + int cmp = (**argname == key) ? 0 : + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**argname) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**argname, key); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) goto arg_passed_twice; + argname++; + } + } + } else + goto invalid_keyword_type; + if (kwds2) { + if (unlikely(PyDict_SetItem(kwds2, key, value))) goto bad; + } else { + goto invalid_keyword; + } + } + Py_XDECREF(key); + Py_XDECREF(value); + return 0; +arg_passed_twice: + __Pyx_RaiseDoubleKeywordsError(function_name, key); + goto bad; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + goto bad; +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif +bad: + Py_XDECREF(key); + Py_XDECREF(value); + return -1; +} + +/* RaiseArgTupleInvalid */ + static void __Pyx_RaiseArgtupleInvalid( + const char* func_name, + int exact, + Py_ssize_t num_min, + Py_ssize_t num_max, + Py_ssize_t num_found) +{ + Py_ssize_t num_expected; + const char *more_or_less; + if (num_found < num_min) { + num_expected = num_min; + more_or_less = "at least"; + } else { + num_expected = num_max; + more_or_less = "at most"; + } + if (exact) { + more_or_less = "exactly"; + } + PyErr_Format(PyExc_TypeError, + "%.200s() takes %.8s %" CYTHON_FORMAT_SSIZE_T "d positional argument%.1s (%" CYTHON_FORMAT_SSIZE_T "d given)", + func_name, more_or_less, num_expected, + (num_expected == 1) ? "" : "s", num_found); +} + +/* KeywordStringCheck */ + static int __Pyx_CheckKeywordStrings( + PyObject *kw, + const char* function_name, + int kw_allowed) +{ + PyObject* key = 0; + Py_ssize_t pos = 0; +#if CYTHON_COMPILING_IN_PYPY + if (!kw_allowed && PyDict_Next(kw, &pos, &key, 0)) + goto invalid_keyword; + return 1; +#else + if (CYTHON_METH_FASTCALL && likely(PyTuple_Check(kw))) { + Py_ssize_t kwsize; +#if CYTHON_ASSUME_SAFE_MACROS + kwsize = PyTuple_GET_SIZE(kw); +#else + kwsize = PyTuple_Size(kw); + if (kwsize < 0) return 0; +#endif + if (unlikely(kwsize == 0)) + return 1; + if (!kw_allowed) { +#if CYTHON_ASSUME_SAFE_MACROS + key = PyTuple_GET_ITEM(kw, 0); +#else + key = PyTuple_GetItem(kw, pos); + if (!key) return 0; +#endif + goto invalid_keyword; + } +#if PY_VERSION_HEX < 0x03090000 + for (pos = 0; pos < kwsize; pos++) { +#if CYTHON_ASSUME_SAFE_MACROS + key = PyTuple_GET_ITEM(kw, pos); +#else + key = PyTuple_GetItem(kw, pos); + if (!key) return 0; +#endif + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } +#endif + return 1; + } + while (PyDict_Next(kw, &pos, &key, 0)) { + #if PY_MAJOR_VERSION < 3 + if (unlikely(!PyString_Check(key))) + #endif + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } + if (!kw_allowed && unlikely(key)) + goto invalid_keyword; + return 1; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + return 0; +#endif +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif + return 0; +} + +/* FixUpExtensionType */ + #if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type) { +#if PY_VERSION_HEX > 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + CYTHON_UNUSED_VAR(spec); + CYTHON_UNUSED_VAR(type); +#else + const PyType_Slot *slot = spec->slots; + while (slot && slot->slot && slot->slot != Py_tp_members) + slot++; + if (slot && slot->slot == Py_tp_members) { + int changed = 0; +#if !(PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON) + const +#endif + PyMemberDef *memb = (PyMemberDef*) slot->pfunc; + while (memb && memb->name) { + if (memb->name[0] == '_' && memb->name[1] == '_') { +#if PY_VERSION_HEX < 0x030900b1 + if (strcmp(memb->name, "__weaklistoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_weaklistoffset = memb->offset; + changed = 1; + } + else if (strcmp(memb->name, "__dictoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_dictoffset = memb->offset; + changed = 1; + } +#if CYTHON_METH_FASTCALL + else if (strcmp(memb->name, "__vectorcalloffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); +#if PY_VERSION_HEX >= 0x030800b4 + type->tp_vectorcall_offset = memb->offset; +#else + type->tp_print = (printfunc) memb->offset; +#endif + changed = 1; + } +#endif +#else + if ((0)); +#endif +#if PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON + else if (strcmp(memb->name, "__module__") == 0) { + PyObject *descr; + assert(memb->type == T_OBJECT); + assert(memb->flags == 0 || memb->flags == READONLY); + descr = PyDescr_NewMember(type, memb); + if (unlikely(!descr)) + return -1; + if (unlikely(PyDict_SetItem(type->tp_dict, PyDescr_NAME(descr), descr) < 0)) { + Py_DECREF(descr); + return -1; + } + Py_DECREF(descr); + changed = 1; + } +#endif + } + memb++; + } + if (changed) + PyType_Modified(type); + } +#endif + return 0; +} +#endif + +/* PyObjectCallNoArg */ + static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func) { + PyObject *arg[2] = {NULL, NULL}; + return __Pyx_PyObject_FastCall(func, arg + 1, 0 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* PyObjectCallOneArg */ + static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg) { + PyObject *args[2] = {NULL, arg}; + return __Pyx_PyObject_FastCall(func, args+1, 1 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* PyObjectGetMethod */ + static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method) { + PyObject *attr; +#if CYTHON_UNPACK_METHODS && CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_PYTYPE_LOOKUP + __Pyx_TypeName type_name; + PyTypeObject *tp = Py_TYPE(obj); + PyObject *descr; + descrgetfunc f = NULL; + PyObject **dictptr, *dict; + int meth_found = 0; + assert (*method == NULL); + if (unlikely(tp->tp_getattro != PyObject_GenericGetAttr)) { + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; + } + if (unlikely(tp->tp_dict == NULL) && unlikely(PyType_Ready(tp) < 0)) { + return 0; + } + descr = _PyType_Lookup(tp, name); + if (likely(descr != NULL)) { + Py_INCREF(descr); +#if defined(Py_TPFLAGS_METHOD_DESCRIPTOR) && Py_TPFLAGS_METHOD_DESCRIPTOR + if (__Pyx_PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_METHOD_DESCRIPTOR)) +#elif PY_MAJOR_VERSION >= 3 + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type))) + #endif +#else + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr))) + #endif +#endif + { + meth_found = 1; + } else { + f = Py_TYPE(descr)->tp_descr_get; + if (f != NULL && PyDescr_IsData(descr)) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + } + } + dictptr = _PyObject_GetDictPtr(obj); + if (dictptr != NULL && (dict = *dictptr) != NULL) { + Py_INCREF(dict); + attr = __Pyx_PyDict_GetItemStr(dict, name); + if (attr != NULL) { + Py_INCREF(attr); + Py_DECREF(dict); + Py_XDECREF(descr); + goto try_unpack; + } + Py_DECREF(dict); + } + if (meth_found) { + *method = descr; + return 1; + } + if (f != NULL) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + if (likely(descr != NULL)) { + *method = descr; + return 0; + } + type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return 0; +#else + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; +#endif +try_unpack: +#if CYTHON_UNPACK_METHODS + if (likely(attr) && PyMethod_Check(attr) && likely(PyMethod_GET_SELF(attr) == obj)) { + PyObject *function = PyMethod_GET_FUNCTION(attr); + Py_INCREF(function); + Py_DECREF(attr); + *method = function; + return 1; + } +#endif + *method = attr; + return 0; +} + +/* PyObjectCallMethod0 */ + static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name) { + PyObject *method = NULL, *result = NULL; + int is_method = __Pyx_PyObject_GetMethod(obj, method_name, &method); + if (likely(is_method)) { + result = __Pyx_PyObject_CallOneArg(method, obj); + Py_DECREF(method); + return result; + } + if (unlikely(!method)) goto bad; + result = __Pyx_PyObject_CallNoArg(method); + Py_DECREF(method); +bad: + return result; +} + +/* ValidateBasesTuple */ + #if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases) { + Py_ssize_t i, n; +#if CYTHON_ASSUME_SAFE_MACROS + n = PyTuple_GET_SIZE(bases); +#else + n = PyTuple_Size(bases); + if (n < 0) return -1; +#endif + for (i = 1; i < n; i++) + { +#if CYTHON_AVOID_BORROWED_REFS + PyObject *b0 = PySequence_GetItem(bases, i); + if (!b0) return -1; +#elif CYTHON_ASSUME_SAFE_MACROS + PyObject *b0 = PyTuple_GET_ITEM(bases, i); +#else + PyObject *b0 = PyTuple_GetItem(bases, i); + if (!b0) return -1; +#endif + PyTypeObject *b; +#if PY_MAJOR_VERSION < 3 + if (PyClass_Check(b0)) + { + PyErr_Format(PyExc_TypeError, "base class '%.200s' is an old-style class", + PyString_AS_STRING(((PyClassObject*)b0)->cl_name)); +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + return -1; + } +#endif + b = (PyTypeObject*) b0; + if (!__Pyx_PyType_HasFeature(b, Py_TPFLAGS_HEAPTYPE)) + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "base class '" __Pyx_FMT_TYPENAME "' is not a heap type", b_name); + __Pyx_DECREF_TypeName(b_name); +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + return -1; + } + if (dictoffset == 0) + { + Py_ssize_t b_dictoffset = 0; +#if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + b_dictoffset = b->tp_dictoffset; +#else + PyObject *py_b_dictoffset = PyObject_GetAttrString((PyObject*)b, "__dictoffset__"); + if (!py_b_dictoffset) goto dictoffset_return; + b_dictoffset = PyLong_AsSsize_t(py_b_dictoffset); + Py_DECREF(py_b_dictoffset); + if (b_dictoffset == -1 && PyErr_Occurred()) goto dictoffset_return; +#endif + if (b_dictoffset) { + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "extension type '%.200s' has no __dict__ slot, " + "but base type '" __Pyx_FMT_TYPENAME "' has: " + "either add 'cdef dict __dict__' to the extension type " + "or add '__slots__ = [...]' to the base type", + type_name, b_name); + __Pyx_DECREF_TypeName(b_name); + } +#if !(CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY) + dictoffset_return: +#endif +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + return -1; + } + } +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + } + return 0; +} +#endif + +/* PyType_Ready */ + static int __Pyx_PyType_Ready(PyTypeObject *t) { +#if CYTHON_USE_TYPE_SPECS || !(CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API) || defined(PYSTON_MAJOR_VERSION) + (void)__Pyx_PyObject_CallMethod0; +#if CYTHON_USE_TYPE_SPECS + (void)__Pyx_validate_bases_tuple; +#endif + return PyType_Ready(t); +#else + int r; + PyObject *bases = __Pyx_PyType_GetSlot(t, tp_bases, PyObject*); + if (bases && unlikely(__Pyx_validate_bases_tuple(t->tp_name, t->tp_dictoffset, bases) == -1)) + return -1; +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + { + int gc_was_enabled; + #if PY_VERSION_HEX >= 0x030A00b1 + gc_was_enabled = PyGC_Disable(); + (void)__Pyx_PyObject_CallMethod0; + #else + PyObject *ret, *py_status; + PyObject *gc = NULL; + #if PY_VERSION_HEX >= 0x030700a1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM+0 >= 0x07030400) + gc = PyImport_GetModule(__pyx_kp_u_gc); + #endif + if (unlikely(!gc)) gc = PyImport_Import(__pyx_kp_u_gc); + if (unlikely(!gc)) return -1; + py_status = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_isenabled); + if (unlikely(!py_status)) { + Py_DECREF(gc); + return -1; + } + gc_was_enabled = __Pyx_PyObject_IsTrue(py_status); + Py_DECREF(py_status); + if (gc_was_enabled > 0) { + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_disable); + if (unlikely(!ret)) { + Py_DECREF(gc); + return -1; + } + Py_DECREF(ret); + } else if (unlikely(gc_was_enabled == -1)) { + Py_DECREF(gc); + return -1; + } + #endif + t->tp_flags |= Py_TPFLAGS_HEAPTYPE; +#if PY_VERSION_HEX >= 0x030A0000 + t->tp_flags |= Py_TPFLAGS_IMMUTABLETYPE; +#endif +#else + (void)__Pyx_PyObject_CallMethod0; +#endif + r = PyType_Ready(t); +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + t->tp_flags &= ~Py_TPFLAGS_HEAPTYPE; + #if PY_VERSION_HEX >= 0x030A00b1 + if (gc_was_enabled) + PyGC_Enable(); + #else + if (gc_was_enabled) { + PyObject *tp, *v, *tb; + PyErr_Fetch(&tp, &v, &tb); + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_enable); + if (likely(ret || r == -1)) { + Py_XDECREF(ret); + PyErr_Restore(tp, v, tb); + } else { + Py_XDECREF(tp); + Py_XDECREF(v); + Py_XDECREF(tb); + r = -1; + } + } + Py_DECREF(gc); + #endif + } +#endif + return r; +#endif +} + +/* PyObject_GenericGetAttrNoDict */ + #if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject *__Pyx_RaiseGenericGetAttributeError(PyTypeObject *tp, PyObject *attr_name) { + __Pyx_TypeName type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, attr_name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(attr_name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name) { + PyObject *descr; + PyTypeObject *tp = Py_TYPE(obj); + if (unlikely(!PyString_Check(attr_name))) { + return PyObject_GenericGetAttr(obj, attr_name); + } + assert(!tp->tp_dictoffset); + descr = _PyType_Lookup(tp, attr_name); + if (unlikely(!descr)) { + return __Pyx_RaiseGenericGetAttributeError(tp, attr_name); + } + Py_INCREF(descr); + #if PY_MAJOR_VERSION < 3 + if (likely(PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_HAVE_CLASS))) + #endif + { + descrgetfunc f = Py_TYPE(descr)->tp_descr_get; + if (unlikely(f)) { + PyObject *res = f(descr, obj, (PyObject *)tp); + Py_DECREF(descr); + return res; + } + } + return descr; +} +#endif + +/* PyObject_GenericGetAttr */ + #if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name) { + if (unlikely(Py_TYPE(obj)->tp_dictoffset)) { + return PyObject_GenericGetAttr(obj, attr_name); + } + return __Pyx_PyObject_GenericGetAttrNoDict(obj, attr_name); +} +#endif + +/* SetupReduce */ + #if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce_is_named(PyObject* meth, PyObject* name) { + int ret; + PyObject *name_attr; + name_attr = __Pyx_PyObject_GetAttrStrNoError(meth, __pyx_n_s_name); + if (likely(name_attr)) { + ret = PyObject_RichCompareBool(name_attr, name, Py_EQ); + } else { + ret = -1; + } + if (unlikely(ret < 0)) { + PyErr_Clear(); + ret = 0; + } + Py_XDECREF(name_attr); + return ret; +} +static int __Pyx_setup_reduce(PyObject* type_obj) { + int ret = 0; + PyObject *object_reduce = NULL; + PyObject *object_getstate = NULL; + PyObject *object_reduce_ex = NULL; + PyObject *reduce = NULL; + PyObject *reduce_ex = NULL; + PyObject *reduce_cython = NULL; + PyObject *setstate = NULL; + PyObject *setstate_cython = NULL; + PyObject *getstate = NULL; +#if CYTHON_USE_PYTYPE_LOOKUP + getstate = _PyType_Lookup((PyTypeObject*)type_obj, __pyx_n_s_getstate); +#else + getstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_getstate); + if (!getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (getstate) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_getstate = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_getstate); +#else + object_getstate = __Pyx_PyObject_GetAttrStrNoError((PyObject*)&PyBaseObject_Type, __pyx_n_s_getstate); + if (!object_getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (object_getstate != getstate) { + goto __PYX_GOOD; + } + } +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce_ex = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#else + object_reduce_ex = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#endif + reduce_ex = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce_ex); if (unlikely(!reduce_ex)) goto __PYX_BAD; + if (reduce_ex == object_reduce_ex) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#else + object_reduce = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#endif + reduce = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce); if (unlikely(!reduce)) goto __PYX_BAD; + if (reduce == object_reduce || __Pyx_setup_reduce_is_named(reduce, __pyx_n_s_reduce_cython)) { + reduce_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_reduce_cython); + if (likely(reduce_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce, reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (reduce == object_reduce || PyErr_Occurred()) { + goto __PYX_BAD; + } + setstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate); + if (!setstate) PyErr_Clear(); + if (!setstate || __Pyx_setup_reduce_is_named(setstate, __pyx_n_s_setstate_cython)) { + setstate_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate_cython); + if (likely(setstate_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate, setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (!setstate || PyErr_Occurred()) { + goto __PYX_BAD; + } + } + PyType_Modified((PyTypeObject*)type_obj); + } + } + goto __PYX_GOOD; +__PYX_BAD: + if (!PyErr_Occurred()) { + __Pyx_TypeName type_obj_name = + __Pyx_PyType_GetName((PyTypeObject*)type_obj); + PyErr_Format(PyExc_RuntimeError, + "Unable to initialize pickling for " __Pyx_FMT_TYPENAME, type_obj_name); + __Pyx_DECREF_TypeName(type_obj_name); + } + ret = -1; +__PYX_GOOD: +#if !CYTHON_USE_PYTYPE_LOOKUP + Py_XDECREF(object_reduce); + Py_XDECREF(object_reduce_ex); + Py_XDECREF(object_getstate); + Py_XDECREF(getstate); +#endif + Py_XDECREF(reduce); + Py_XDECREF(reduce_ex); + Py_XDECREF(reduce_cython); + Py_XDECREF(setstate); + Py_XDECREF(setstate_cython); + return ret; +} +#endif + +/* TypeImport */ + #ifndef __PYX_HAVE_RT_ImportType_3_0_8 +#define __PYX_HAVE_RT_ImportType_3_0_8 +static PyTypeObject *__Pyx_ImportType_3_0_8(PyObject *module, const char *module_name, const char *class_name, + size_t size, size_t alignment, enum __Pyx_ImportType_CheckSize_3_0_8 check_size) +{ + PyObject *result = 0; + char warning[200]; + Py_ssize_t basicsize; + Py_ssize_t itemsize; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *py_basicsize; + PyObject *py_itemsize; +#endif + result = PyObject_GetAttrString(module, class_name); + if (!result) + goto bad; + if (!PyType_Check(result)) { + PyErr_Format(PyExc_TypeError, + "%.200s.%.200s is not a type object", + module_name, class_name); + goto bad; + } +#if !CYTHON_COMPILING_IN_LIMITED_API + basicsize = ((PyTypeObject *)result)->tp_basicsize; + itemsize = ((PyTypeObject *)result)->tp_itemsize; +#else + py_basicsize = PyObject_GetAttrString(result, "__basicsize__"); + if (!py_basicsize) + goto bad; + basicsize = PyLong_AsSsize_t(py_basicsize); + Py_DECREF(py_basicsize); + py_basicsize = 0; + if (basicsize == (Py_ssize_t)-1 && PyErr_Occurred()) + goto bad; + py_itemsize = PyObject_GetAttrString(result, "__itemsize__"); + if (!py_itemsize) + goto bad; + itemsize = PyLong_AsSsize_t(py_itemsize); + Py_DECREF(py_itemsize); + py_itemsize = 0; + if (itemsize == (Py_ssize_t)-1 && PyErr_Occurred()) + goto bad; +#endif + if (itemsize) { + if (size % alignment) { + alignment = size % alignment; + } + if (itemsize < (Py_ssize_t)alignment) + itemsize = (Py_ssize_t)alignment; + } + if ((size_t)(basicsize + itemsize) < size) { + PyErr_Format(PyExc_ValueError, + "%.200s.%.200s size changed, may indicate binary incompatibility. " + "Expected %zd from C header, got %zd from PyObject", + module_name, class_name, size, basicsize+itemsize); + goto bad; + } + if (check_size == __Pyx_ImportType_CheckSize_Error_3_0_8 && + ((size_t)basicsize > size || (size_t)(basicsize + itemsize) < size)) { + PyErr_Format(PyExc_ValueError, + "%.200s.%.200s size changed, may indicate binary incompatibility. " + "Expected %zd from C header, got %zd-%zd from PyObject", + module_name, class_name, size, basicsize, basicsize+itemsize); + goto bad; + } + else if (check_size == __Pyx_ImportType_CheckSize_Warn_3_0_8 && (size_t)basicsize > size) { + PyOS_snprintf(warning, sizeof(warning), + "%s.%s size changed, may indicate binary incompatibility. " + "Expected %zd from C header, got %zd from PyObject", + module_name, class_name, size, basicsize); + if (PyErr_WarnEx(NULL, warning, 0) < 0) goto bad; + } + return (PyTypeObject *)result; +bad: + Py_XDECREF(result); + return NULL; +} +#endif + +/* Import */ + static PyObject *__Pyx_Import(PyObject *name, PyObject *from_list, int level) { + PyObject *module = 0; + PyObject *empty_dict = 0; + PyObject *empty_list = 0; + #if PY_MAJOR_VERSION < 3 + PyObject *py_import; + py_import = __Pyx_PyObject_GetAttrStr(__pyx_b, __pyx_n_s_import); + if (unlikely(!py_import)) + goto bad; + if (!from_list) { + empty_list = PyList_New(0); + if (unlikely(!empty_list)) + goto bad; + from_list = empty_list; + } + #endif + empty_dict = PyDict_New(); + if (unlikely(!empty_dict)) + goto bad; + { + #if PY_MAJOR_VERSION >= 3 + if (level == -1) { + if (strchr(__Pyx_MODULE_NAME, '.') != NULL) { + module = PyImport_ImportModuleLevelObject( + name, __pyx_d, empty_dict, from_list, 1); + if (unlikely(!module)) { + if (unlikely(!PyErr_ExceptionMatches(PyExc_ImportError))) + goto bad; + PyErr_Clear(); + } + } + level = 0; + } + #endif + if (!module) { + #if PY_MAJOR_VERSION < 3 + PyObject *py_level = PyInt_FromLong(level); + if (unlikely(!py_level)) + goto bad; + module = PyObject_CallFunctionObjArgs(py_import, + name, __pyx_d, empty_dict, from_list, py_level, (PyObject *)NULL); + Py_DECREF(py_level); + #else + module = PyImport_ImportModuleLevelObject( + name, __pyx_d, empty_dict, from_list, level); + #endif + } + } +bad: + Py_XDECREF(empty_dict); + Py_XDECREF(empty_list); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_import); + #endif + return module; +} + +/* ImportDottedModule */ + #if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx__ImportDottedModule_Error(PyObject *name, PyObject *parts_tuple, Py_ssize_t count) { + PyObject *partial_name = NULL, *slice = NULL, *sep = NULL; + if (unlikely(PyErr_Occurred())) { + PyErr_Clear(); + } + if (likely(PyTuple_GET_SIZE(parts_tuple) == count)) { + partial_name = name; + } else { + slice = PySequence_GetSlice(parts_tuple, 0, count); + if (unlikely(!slice)) + goto bad; + sep = PyUnicode_FromStringAndSize(".", 1); + if (unlikely(!sep)) + goto bad; + partial_name = PyUnicode_Join(sep, slice); + } + PyErr_Format( +#if PY_MAJOR_VERSION < 3 + PyExc_ImportError, + "No module named '%s'", PyString_AS_STRING(partial_name)); +#else +#if PY_VERSION_HEX >= 0x030600B1 + PyExc_ModuleNotFoundError, +#else + PyExc_ImportError, +#endif + "No module named '%U'", partial_name); +#endif +bad: + Py_XDECREF(sep); + Py_XDECREF(slice); + Py_XDECREF(partial_name); + return NULL; +} +#endif +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx__ImportDottedModule_Lookup(PyObject *name) { + PyObject *imported_module; +#if PY_VERSION_HEX < 0x030700A1 || (CYTHON_COMPILING_IN_PYPY && PYPY_VERSION_NUM < 0x07030400) + PyObject *modules = PyImport_GetModuleDict(); + if (unlikely(!modules)) + return NULL; + imported_module = __Pyx_PyDict_GetItemStr(modules, name); + Py_XINCREF(imported_module); +#else + imported_module = PyImport_GetModule(name); +#endif + return imported_module; +} +#endif +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_ImportDottedModule_WalkParts(PyObject *module, PyObject *name, PyObject *parts_tuple) { + Py_ssize_t i, nparts; + nparts = PyTuple_GET_SIZE(parts_tuple); + for (i=1; i < nparts && module; i++) { + PyObject *part, *submodule; +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + part = PyTuple_GET_ITEM(parts_tuple, i); +#else + part = PySequence_ITEM(parts_tuple, i); +#endif + submodule = __Pyx_PyObject_GetAttrStrNoError(module, part); +#if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(part); +#endif + Py_DECREF(module); + module = submodule; + } + if (unlikely(!module)) { + return __Pyx__ImportDottedModule_Error(name, parts_tuple, i); + } + return module; +} +#endif +static PyObject *__Pyx__ImportDottedModule(PyObject *name, PyObject *parts_tuple) { +#if PY_MAJOR_VERSION < 3 + PyObject *module, *from_list, *star = __pyx_n_s__3; + CYTHON_UNUSED_VAR(parts_tuple); + from_list = PyList_New(1); + if (unlikely(!from_list)) + return NULL; + Py_INCREF(star); + PyList_SET_ITEM(from_list, 0, star); + module = __Pyx_Import(name, from_list, 0); + Py_DECREF(from_list); + return module; +#else + PyObject *imported_module; + PyObject *module = __Pyx_Import(name, NULL, 0); + if (!parts_tuple || unlikely(!module)) + return module; + imported_module = __Pyx__ImportDottedModule_Lookup(name); + if (likely(imported_module)) { + Py_DECREF(module); + return imported_module; + } + PyErr_Clear(); + return __Pyx_ImportDottedModule_WalkParts(module, name, parts_tuple); +#endif +} +static PyObject *__Pyx_ImportDottedModule(PyObject *name, PyObject *parts_tuple) { +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030400B1 + PyObject *module = __Pyx__ImportDottedModule_Lookup(name); + if (likely(module)) { + PyObject *spec = __Pyx_PyObject_GetAttrStrNoError(module, __pyx_n_s_spec); + if (likely(spec)) { + PyObject *unsafe = __Pyx_PyObject_GetAttrStrNoError(spec, __pyx_n_s_initializing); + if (likely(!unsafe || !__Pyx_PyObject_IsTrue(unsafe))) { + Py_DECREF(spec); + spec = NULL; + } + Py_XDECREF(unsafe); + } + if (likely(!spec)) { + PyErr_Clear(); + return module; + } + Py_DECREF(spec); + Py_DECREF(module); + } else if (PyErr_Occurred()) { + PyErr_Clear(); + } +#endif + return __Pyx__ImportDottedModule(name, parts_tuple); +} + +/* FetchSharedCythonModule */ + static PyObject *__Pyx_FetchSharedCythonABIModule(void) { + return __Pyx_PyImport_AddModuleRef((char*) __PYX_ABI_MODULE_NAME); +} + +/* FetchCommonType */ + static int __Pyx_VerifyCachedType(PyObject *cached_type, + const char *name, + Py_ssize_t basicsize, + Py_ssize_t expected_basicsize) { + if (!PyType_Check(cached_type)) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s is not a type object", name); + return -1; + } + if (basicsize != expected_basicsize) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s has the wrong size, try recompiling", + name); + return -1; + } + return 0; +} +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type) { + PyObject* abi_module; + const char* object_name; + PyTypeObject *cached_type = NULL; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + object_name = strrchr(type->tp_name, '.'); + object_name = object_name ? object_name+1 : type->tp_name; + cached_type = (PyTypeObject*) PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + if (__Pyx_VerifyCachedType( + (PyObject *)cached_type, + object_name, + cached_type->tp_basicsize, + type->tp_basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + if (PyType_Ready(type) < 0) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, (PyObject *)type) < 0) + goto bad; + Py_INCREF(type); + cached_type = type; +done: + Py_DECREF(abi_module); + return cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#else +static PyTypeObject *__Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases) { + PyObject *abi_module, *cached_type = NULL; + const char* object_name = strrchr(spec->name, '.'); + object_name = object_name ? object_name+1 : spec->name; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + cached_type = PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + Py_ssize_t basicsize; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *py_basicsize; + py_basicsize = PyObject_GetAttrString(cached_type, "__basicsize__"); + if (unlikely(!py_basicsize)) goto bad; + basicsize = PyLong_AsSsize_t(py_basicsize); + Py_DECREF(py_basicsize); + py_basicsize = 0; + if (unlikely(basicsize == (Py_ssize_t)-1) && PyErr_Occurred()) goto bad; +#else + basicsize = likely(PyType_Check(cached_type)) ? ((PyTypeObject*) cached_type)->tp_basicsize : -1; +#endif + if (__Pyx_VerifyCachedType( + cached_type, + object_name, + basicsize, + spec->basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + CYTHON_UNUSED_VAR(module); + cached_type = __Pyx_PyType_FromModuleAndSpec(abi_module, spec, bases); + if (unlikely(!cached_type)) goto bad; + if (unlikely(__Pyx_fix_up_extension_type_from_spec(spec, (PyTypeObject *) cached_type) < 0)) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, cached_type) < 0) goto bad; +done: + Py_DECREF(abi_module); + assert(cached_type == NULL || PyType_Check(cached_type)); + return (PyTypeObject *) cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#endif + +/* PyVectorcallFastCallDict */ + #if CYTHON_METH_FASTCALL +static PyObject *__Pyx_PyVectorcall_FastCallDict_kw(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + PyObject *res = NULL; + PyObject *kwnames; + PyObject **newargs; + PyObject **kwvalues; + Py_ssize_t i, pos; + size_t j; + PyObject *key, *value; + unsigned long keys_are_strings; + Py_ssize_t nkw = PyDict_GET_SIZE(kw); + newargs = (PyObject **)PyMem_Malloc((nargs + (size_t)nkw) * sizeof(args[0])); + if (unlikely(newargs == NULL)) { + PyErr_NoMemory(); + return NULL; + } + for (j = 0; j < nargs; j++) newargs[j] = args[j]; + kwnames = PyTuple_New(nkw); + if (unlikely(kwnames == NULL)) { + PyMem_Free(newargs); + return NULL; + } + kwvalues = newargs + nargs; + pos = i = 0; + keys_are_strings = Py_TPFLAGS_UNICODE_SUBCLASS; + while (PyDict_Next(kw, &pos, &key, &value)) { + keys_are_strings &= Py_TYPE(key)->tp_flags; + Py_INCREF(key); + Py_INCREF(value); + PyTuple_SET_ITEM(kwnames, i, key); + kwvalues[i] = value; + i++; + } + if (unlikely(!keys_are_strings)) { + PyErr_SetString(PyExc_TypeError, "keywords must be strings"); + goto cleanup; + } + res = vc(func, newargs, nargs, kwnames); +cleanup: + Py_DECREF(kwnames); + for (i = 0; i < nkw; i++) + Py_DECREF(kwvalues[i]); + PyMem_Free(newargs); + return res; +} +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + if (likely(kw == NULL) || PyDict_GET_SIZE(kw) == 0) { + return vc(func, args, nargs, NULL); + } + return __Pyx_PyVectorcall_FastCallDict_kw(func, vc, args, nargs, kw); +} +#endif + +/* CythonFunctionShared */ + #if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc) { + if (__Pyx_CyFunction_Check(func)) { + return PyCFunction_GetFunction(((__pyx_CyFunctionObject*)func)->func) == (PyCFunction) cfunc; + } else if (PyCFunction_Check(func)) { + return PyCFunction_GetFunction(func) == (PyCFunction) cfunc; + } + return 0; +} +#else +static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc) { + return __Pyx_CyOrPyCFunction_Check(func) && __Pyx_CyOrPyCFunction_GET_FUNCTION(func) == (PyCFunction) cfunc; +} +#endif +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj) { +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + __Pyx_Py_XDECREF_SET( + __Pyx_CyFunction_GetClassObj(f), + ((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#else + __Pyx_Py_XDECREF_SET( + ((PyCMethodObject *) (f))->mm_class, + (PyTypeObject*)((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#endif +} +static PyObject * +__Pyx_CyFunction_get_doc(__pyx_CyFunctionObject *op, void *closure) +{ + CYTHON_UNUSED_VAR(closure); + if (unlikely(op->func_doc == NULL)) { +#if CYTHON_COMPILING_IN_LIMITED_API + op->func_doc = PyObject_GetAttrString(op->func, "__doc__"); + if (unlikely(!op->func_doc)) return NULL; +#else + if (((PyCFunctionObject*)op)->m_ml->ml_doc) { +#if PY_MAJOR_VERSION >= 3 + op->func_doc = PyUnicode_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#else + op->func_doc = PyString_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#endif + if (unlikely(op->func_doc == NULL)) + return NULL; + } else { + Py_INCREF(Py_None); + return Py_None; + } +#endif + } + Py_INCREF(op->func_doc); + return op->func_doc; +} +static int +__Pyx_CyFunction_set_doc(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (value == NULL) { + value = Py_None; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_doc, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_name(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_name == NULL)) { +#if CYTHON_COMPILING_IN_LIMITED_API + op->func_name = PyObject_GetAttrString(op->func, "__name__"); +#elif PY_MAJOR_VERSION >= 3 + op->func_name = PyUnicode_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#else + op->func_name = PyString_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#endif + if (unlikely(op->func_name == NULL)) + return NULL; + } + Py_INCREF(op->func_name); + return op->func_name; +} +static int +__Pyx_CyFunction_set_name(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__name__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_name, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_qualname(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_qualname); + return op->func_qualname; +} +static int +__Pyx_CyFunction_set_qualname(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__qualname__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_qualname, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_dict(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_dict == NULL)) { + op->func_dict = PyDict_New(); + if (unlikely(op->func_dict == NULL)) + return NULL; + } + Py_INCREF(op->func_dict); + return op->func_dict; +} +static int +__Pyx_CyFunction_set_dict(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(value == NULL)) { + PyErr_SetString(PyExc_TypeError, + "function's dictionary may not be deleted"); + return -1; + } + if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "setting function's dictionary to a non-dict"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_dict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_globals(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_globals); + return op->func_globals; +} +static PyObject * +__Pyx_CyFunction_get_closure(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(op); + CYTHON_UNUSED_VAR(context); + Py_INCREF(Py_None); + return Py_None; +} +static PyObject * +__Pyx_CyFunction_get_code(__pyx_CyFunctionObject *op, void *context) +{ + PyObject* result = (op->func_code) ? op->func_code : Py_None; + CYTHON_UNUSED_VAR(context); + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_init_defaults(__pyx_CyFunctionObject *op) { + int result = 0; + PyObject *res = op->defaults_getter((PyObject *) op); + if (unlikely(!res)) + return -1; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + op->defaults_tuple = PyTuple_GET_ITEM(res, 0); + Py_INCREF(op->defaults_tuple); + op->defaults_kwdict = PyTuple_GET_ITEM(res, 1); + Py_INCREF(op->defaults_kwdict); + #else + op->defaults_tuple = __Pyx_PySequence_ITEM(res, 0); + if (unlikely(!op->defaults_tuple)) result = -1; + else { + op->defaults_kwdict = __Pyx_PySequence_ITEM(res, 1); + if (unlikely(!op->defaults_kwdict)) result = -1; + } + #endif + Py_DECREF(res); + return result; +} +static int +__Pyx_CyFunction_set_defaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyTuple_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__defaults__ must be set to a tuple object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__defaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_tuple, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_defaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_tuple; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_tuple; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_kwdefaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__kwdefaults__ must be set to a dict object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__kwdefaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_kwdict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_kwdefaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_kwdict; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_kwdict; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_annotations(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value || value == Py_None) { + value = NULL; + } else if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__annotations__ must be set to a dict object"); + return -1; + } + Py_XINCREF(value); + __Pyx_Py_XDECREF_SET(op->func_annotations, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_annotations(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->func_annotations; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + result = PyDict_New(); + if (unlikely(!result)) return NULL; + op->func_annotations = result; + } + Py_INCREF(result); + return result; +} +static PyObject * +__Pyx_CyFunction_get_is_coroutine(__pyx_CyFunctionObject *op, void *context) { + int is_coroutine; + CYTHON_UNUSED_VAR(context); + if (op->func_is_coroutine) { + return __Pyx_NewRef(op->func_is_coroutine); + } + is_coroutine = op->flags & __Pyx_CYFUNCTION_COROUTINE; +#if PY_VERSION_HEX >= 0x03050000 + if (is_coroutine) { + PyObject *module, *fromlist, *marker = __pyx_n_s_is_coroutine; + fromlist = PyList_New(1); + if (unlikely(!fromlist)) return NULL; + Py_INCREF(marker); +#if CYTHON_ASSUME_SAFE_MACROS + PyList_SET_ITEM(fromlist, 0, marker); +#else + if (unlikely(PyList_SetItem(fromlist, 0, marker) < 0)) { + Py_DECREF(marker); + Py_DECREF(fromlist); + return NULL; + } +#endif + module = PyImport_ImportModuleLevelObject(__pyx_n_s_asyncio_coroutines, NULL, NULL, fromlist, 0); + Py_DECREF(fromlist); + if (unlikely(!module)) goto ignore; + op->func_is_coroutine = __Pyx_PyObject_GetAttrStr(module, marker); + Py_DECREF(module); + if (likely(op->func_is_coroutine)) { + return __Pyx_NewRef(op->func_is_coroutine); + } +ignore: + PyErr_Clear(); + } +#endif + op->func_is_coroutine = __Pyx_PyBool_FromLong(is_coroutine); + return __Pyx_NewRef(op->func_is_coroutine); +} +#if CYTHON_COMPILING_IN_LIMITED_API +static PyObject * +__Pyx_CyFunction_get_module(__pyx_CyFunctionObject *op, void *context) { + CYTHON_UNUSED_VAR(context); + return PyObject_GetAttrString(op->func, "__module__"); +} +static int +__Pyx_CyFunction_set_module(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + return PyObject_SetAttrString(op->func, "__module__", value); +} +#endif +static PyGetSetDef __pyx_CyFunction_getsets[] = { + {(char *) "func_doc", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "__doc__", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "func_name", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__name__", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__qualname__", (getter)__Pyx_CyFunction_get_qualname, (setter)__Pyx_CyFunction_set_qualname, 0, 0}, + {(char *) "func_dict", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "__dict__", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "func_globals", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "__globals__", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "func_closure", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "__closure__", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "func_code", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "__code__", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "func_defaults", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__defaults__", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__kwdefaults__", (getter)__Pyx_CyFunction_get_kwdefaults, (setter)__Pyx_CyFunction_set_kwdefaults, 0, 0}, + {(char *) "__annotations__", (getter)__Pyx_CyFunction_get_annotations, (setter)__Pyx_CyFunction_set_annotations, 0, 0}, + {(char *) "_is_coroutine", (getter)__Pyx_CyFunction_get_is_coroutine, 0, 0, 0}, +#if CYTHON_COMPILING_IN_LIMITED_API + {"__module__", (getter)__Pyx_CyFunction_get_module, (setter)__Pyx_CyFunction_set_module, 0, 0}, +#endif + {0, 0, 0, 0, 0} +}; +static PyMemberDef __pyx_CyFunction_members[] = { +#if !CYTHON_COMPILING_IN_LIMITED_API + {(char *) "__module__", T_OBJECT, offsetof(PyCFunctionObject, m_module), 0, 0}, +#endif +#if CYTHON_USE_TYPE_SPECS + {(char *) "__dictoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_dict), READONLY, 0}, +#if CYTHON_METH_FASTCALL +#if CYTHON_BACKPORT_VECTORCALL + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_vectorcall), READONLY, 0}, +#else +#if !CYTHON_COMPILING_IN_LIMITED_API + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(PyCFunctionObject, vectorcall), READONLY, 0}, +#endif +#endif +#endif +#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_weakreflist), READONLY, 0}, +#else + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(PyCFunctionObject, m_weakreflist), READONLY, 0}, +#endif +#endif + {0, 0, 0, 0, 0} +}; +static PyObject * +__Pyx_CyFunction_reduce(__pyx_CyFunctionObject *m, PyObject *args) +{ + CYTHON_UNUSED_VAR(args); +#if PY_MAJOR_VERSION >= 3 + Py_INCREF(m->func_qualname); + return m->func_qualname; +#else + return PyString_FromString(((PyCFunctionObject*)m)->m_ml->ml_name); +#endif +} +static PyMethodDef __pyx_CyFunction_methods[] = { + {"__reduce__", (PyCFunction)__Pyx_CyFunction_reduce, METH_VARARGS, 0}, + {0, 0, 0, 0} +}; +#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API +#define __Pyx_CyFunction_weakreflist(cyfunc) ((cyfunc)->func_weakreflist) +#else +#define __Pyx_CyFunction_weakreflist(cyfunc) (((PyCFunctionObject*)cyfunc)->m_weakreflist) +#endif +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject *op, PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { +#if !CYTHON_COMPILING_IN_LIMITED_API + PyCFunctionObject *cf = (PyCFunctionObject*) op; +#endif + if (unlikely(op == NULL)) + return NULL; +#if CYTHON_COMPILING_IN_LIMITED_API + op->func = PyCFunction_NewEx(ml, (PyObject*)op, module); + if (unlikely(!op->func)) return NULL; +#endif + op->flags = flags; + __Pyx_CyFunction_weakreflist(op) = NULL; +#if !CYTHON_COMPILING_IN_LIMITED_API + cf->m_ml = ml; + cf->m_self = (PyObject *) op; +#endif + Py_XINCREF(closure); + op->func_closure = closure; +#if !CYTHON_COMPILING_IN_LIMITED_API + Py_XINCREF(module); + cf->m_module = module; +#endif + op->func_dict = NULL; + op->func_name = NULL; + Py_INCREF(qualname); + op->func_qualname = qualname; + op->func_doc = NULL; +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + op->func_classobj = NULL; +#else + ((PyCMethodObject*)op)->mm_class = NULL; +#endif + op->func_globals = globals; + Py_INCREF(op->func_globals); + Py_XINCREF(code); + op->func_code = code; + op->defaults_pyobjects = 0; + op->defaults_size = 0; + op->defaults = NULL; + op->defaults_tuple = NULL; + op->defaults_kwdict = NULL; + op->defaults_getter = NULL; + op->func_annotations = NULL; + op->func_is_coroutine = NULL; +#if CYTHON_METH_FASTCALL + switch (ml->ml_flags & (METH_VARARGS | METH_FASTCALL | METH_NOARGS | METH_O | METH_KEYWORDS | METH_METHOD)) { + case METH_NOARGS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_NOARGS; + break; + case METH_O: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_O; + break; + case METH_METHOD | METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD; + break; + case METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS; + break; + case METH_VARARGS | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = NULL; + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + Py_DECREF(op); + return NULL; + } +#endif + return (PyObject *) op; +} +static int +__Pyx_CyFunction_clear(__pyx_CyFunctionObject *m) +{ + Py_CLEAR(m->func_closure); +#if CYTHON_COMPILING_IN_LIMITED_API + Py_CLEAR(m->func); +#else + Py_CLEAR(((PyCFunctionObject*)m)->m_module); +#endif + Py_CLEAR(m->func_dict); + Py_CLEAR(m->func_name); + Py_CLEAR(m->func_qualname); + Py_CLEAR(m->func_doc); + Py_CLEAR(m->func_globals); + Py_CLEAR(m->func_code); +#if !CYTHON_COMPILING_IN_LIMITED_API +#if PY_VERSION_HEX < 0x030900B1 + Py_CLEAR(__Pyx_CyFunction_GetClassObj(m)); +#else + { + PyObject *cls = (PyObject*) ((PyCMethodObject *) (m))->mm_class; + ((PyCMethodObject *) (m))->mm_class = NULL; + Py_XDECREF(cls); + } +#endif +#endif + Py_CLEAR(m->defaults_tuple); + Py_CLEAR(m->defaults_kwdict); + Py_CLEAR(m->func_annotations); + Py_CLEAR(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_XDECREF(pydefaults[i]); + PyObject_Free(m->defaults); + m->defaults = NULL; + } + return 0; +} +static void __Pyx__CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + if (__Pyx_CyFunction_weakreflist(m) != NULL) + PyObject_ClearWeakRefs((PyObject *) m); + __Pyx_CyFunction_clear(m); + __Pyx_PyHeapTypeObject_GC_Del(m); +} +static void __Pyx_CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + PyObject_GC_UnTrack(m); + __Pyx__CyFunction_dealloc(m); +} +static int __Pyx_CyFunction_traverse(__pyx_CyFunctionObject *m, visitproc visit, void *arg) +{ + Py_VISIT(m->func_closure); +#if CYTHON_COMPILING_IN_LIMITED_API + Py_VISIT(m->func); +#else + Py_VISIT(((PyCFunctionObject*)m)->m_module); +#endif + Py_VISIT(m->func_dict); + Py_VISIT(m->func_name); + Py_VISIT(m->func_qualname); + Py_VISIT(m->func_doc); + Py_VISIT(m->func_globals); + Py_VISIT(m->func_code); +#if !CYTHON_COMPILING_IN_LIMITED_API + Py_VISIT(__Pyx_CyFunction_GetClassObj(m)); +#endif + Py_VISIT(m->defaults_tuple); + Py_VISIT(m->defaults_kwdict); + Py_VISIT(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_VISIT(pydefaults[i]); + } + return 0; +} +static PyObject* +__Pyx_CyFunction_repr(__pyx_CyFunctionObject *op) +{ +#if PY_MAJOR_VERSION >= 3 + return PyUnicode_FromFormat("", + op->func_qualname, (void *)op); +#else + return PyString_FromFormat("", + PyString_AsString(op->func_qualname), (void *)op); +#endif +} +static PyObject * __Pyx_CyFunction_CallMethod(PyObject *func, PyObject *self, PyObject *arg, PyObject *kw) { +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *f = ((__pyx_CyFunctionObject*)func)->func; + PyObject *py_name = NULL; + PyCFunction meth; + int flags; + meth = PyCFunction_GetFunction(f); + if (unlikely(!meth)) return NULL; + flags = PyCFunction_GetFlags(f); + if (unlikely(flags < 0)) return NULL; +#else + PyCFunctionObject* f = (PyCFunctionObject*)func; + PyCFunction meth = f->m_ml->ml_meth; + int flags = f->m_ml->ml_flags; +#endif + Py_ssize_t size; + switch (flags & (METH_VARARGS | METH_KEYWORDS | METH_NOARGS | METH_O)) { + case METH_VARARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) + return (*meth)(self, arg); + break; + case METH_VARARGS | METH_KEYWORDS: + return (*(PyCFunctionWithKeywords)(void*)meth)(self, arg, kw); + case METH_NOARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { +#if CYTHON_ASSUME_SAFE_MACROS + size = PyTuple_GET_SIZE(arg); +#else + size = PyTuple_Size(arg); + if (unlikely(size < 0)) return NULL; +#endif + if (likely(size == 0)) + return (*meth)(self, NULL); +#if CYTHON_COMPILING_IN_LIMITED_API + py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); + if (!py_name) return NULL; + PyErr_Format(PyExc_TypeError, + "%.200S() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + py_name, size); + Py_DECREF(py_name); +#else + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); +#endif + return NULL; + } + break; + case METH_O: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { +#if CYTHON_ASSUME_SAFE_MACROS + size = PyTuple_GET_SIZE(arg); +#else + size = PyTuple_Size(arg); + if (unlikely(size < 0)) return NULL; +#endif + if (likely(size == 1)) { + PyObject *result, *arg0; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + arg0 = PyTuple_GET_ITEM(arg, 0); + #else + arg0 = __Pyx_PySequence_ITEM(arg, 0); if (unlikely(!arg0)) return NULL; + #endif + result = (*meth)(self, arg0); + #if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(arg0); + #endif + return result; + } +#if CYTHON_COMPILING_IN_LIMITED_API + py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); + if (!py_name) return NULL; + PyErr_Format(PyExc_TypeError, + "%.200S() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + py_name, size); + Py_DECREF(py_name); +#else + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); +#endif + return NULL; + } + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + return NULL; + } +#if CYTHON_COMPILING_IN_LIMITED_API + py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); + if (!py_name) return NULL; + PyErr_Format(PyExc_TypeError, "%.200S() takes no keyword arguments", + py_name); + Py_DECREF(py_name); +#else + PyErr_Format(PyExc_TypeError, "%.200s() takes no keyword arguments", + f->m_ml->ml_name); +#endif + return NULL; +} +static CYTHON_INLINE PyObject *__Pyx_CyFunction_Call(PyObject *func, PyObject *arg, PyObject *kw) { + PyObject *self, *result; +#if CYTHON_COMPILING_IN_LIMITED_API + self = PyCFunction_GetSelf(((__pyx_CyFunctionObject*)func)->func); + if (unlikely(!self) && PyErr_Occurred()) return NULL; +#else + self = ((PyCFunctionObject*)func)->m_self; +#endif + result = __Pyx_CyFunction_CallMethod(func, self, arg, kw); + return result; +} +static PyObject *__Pyx_CyFunction_CallAsMethod(PyObject *func, PyObject *args, PyObject *kw) { + PyObject *result; + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *) func; +#if CYTHON_METH_FASTCALL + __pyx_vectorcallfunc vc = __Pyx_CyFunction_func_vectorcall(cyfunc); + if (vc) { +#if CYTHON_ASSUME_SAFE_MACROS + return __Pyx_PyVectorcall_FastCallDict(func, vc, &PyTuple_GET_ITEM(args, 0), (size_t)PyTuple_GET_SIZE(args), kw); +#else + (void) &__Pyx_PyVectorcall_FastCallDict; + return PyVectorcall_Call(func, args, kw); +#endif + } +#endif + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + Py_ssize_t argc; + PyObject *new_args; + PyObject *self; +#if CYTHON_ASSUME_SAFE_MACROS + argc = PyTuple_GET_SIZE(args); +#else + argc = PyTuple_Size(args); + if (unlikely(!argc) < 0) return NULL; +#endif + new_args = PyTuple_GetSlice(args, 1, argc); + if (unlikely(!new_args)) + return NULL; + self = PyTuple_GetItem(args, 0); + if (unlikely(!self)) { + Py_DECREF(new_args); +#if PY_MAJOR_VERSION > 2 + PyErr_Format(PyExc_TypeError, + "unbound method %.200S() needs an argument", + cyfunc->func_qualname); +#else + PyErr_SetString(PyExc_TypeError, + "unbound method needs an argument"); +#endif + return NULL; + } + result = __Pyx_CyFunction_CallMethod(func, self, new_args, kw); + Py_DECREF(new_args); + } else { + result = __Pyx_CyFunction_Call(func, args, kw); + } + return result; +} +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE int __Pyx_CyFunction_Vectorcall_CheckArgs(__pyx_CyFunctionObject *cyfunc, Py_ssize_t nargs, PyObject *kwnames) +{ + int ret = 0; + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + if (unlikely(nargs < 1)) { + PyErr_Format(PyExc_TypeError, "%.200s() needs an argument", + ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + ret = 1; + } + if (unlikely(kwnames) && unlikely(PyTuple_GET_SIZE(kwnames))) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no keyword arguments", ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + return ret; +} +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 0)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, NULL); +} +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 1)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, args[0]); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((_PyCFunctionFastWithKeywords)(void(*)(void))def->ml_meth)(self, args, nargs, kwnames); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; + PyTypeObject *cls = (PyTypeObject *) __Pyx_CyFunction_GetClassObj(cyfunc); +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((__Pyx_PyCMethod)(void(*)(void))def->ml_meth)(self, cls, args, (size_t)nargs, kwnames); +} +#endif +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_CyFunctionType_slots[] = { + {Py_tp_dealloc, (void *)__Pyx_CyFunction_dealloc}, + {Py_tp_repr, (void *)__Pyx_CyFunction_repr}, + {Py_tp_call, (void *)__Pyx_CyFunction_CallAsMethod}, + {Py_tp_traverse, (void *)__Pyx_CyFunction_traverse}, + {Py_tp_clear, (void *)__Pyx_CyFunction_clear}, + {Py_tp_methods, (void *)__pyx_CyFunction_methods}, + {Py_tp_members, (void *)__pyx_CyFunction_members}, + {Py_tp_getset, (void *)__pyx_CyFunction_getsets}, + {Py_tp_descr_get, (void *)__Pyx_PyMethod_New}, + {0, 0}, +}; +static PyType_Spec __pyx_CyFunctionType_spec = { + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#if (defined(_Py_TPFLAGS_HAVE_VECTORCALL) && CYTHON_METH_FASTCALL) + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + __pyx_CyFunctionType_slots +}; +#else +static PyTypeObject __pyx_CyFunctionType_type = { + PyVarObject_HEAD_INIT(0, 0) + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, + (destructor) __Pyx_CyFunction_dealloc, +#if !CYTHON_METH_FASTCALL + 0, +#elif CYTHON_BACKPORT_VECTORCALL + (printfunc)offsetof(__pyx_CyFunctionObject, func_vectorcall), +#else + offsetof(PyCFunctionObject, vectorcall), +#endif + 0, + 0, +#if PY_MAJOR_VERSION < 3 + 0, +#else + 0, +#endif + (reprfunc) __Pyx_CyFunction_repr, + 0, + 0, + 0, + 0, + __Pyx_CyFunction_CallAsMethod, + 0, + 0, + 0, + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#if defined(_Py_TPFLAGS_HAVE_VECTORCALL) && CYTHON_METH_FASTCALL + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + 0, + (traverseproc) __Pyx_CyFunction_traverse, + (inquiry) __Pyx_CyFunction_clear, + 0, +#if PY_VERSION_HEX < 0x030500A0 + offsetof(__pyx_CyFunctionObject, func_weakreflist), +#else + offsetof(PyCFunctionObject, m_weakreflist), +#endif + 0, + 0, + __pyx_CyFunction_methods, + __pyx_CyFunction_members, + __pyx_CyFunction_getsets, + 0, + 0, + __Pyx_PyMethod_New, + 0, + offsetof(__pyx_CyFunctionObject, func_dict), + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, +#if PY_VERSION_HEX >= 0x030400a1 + 0, +#endif +#if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, +#endif +#if __PYX_NEED_TP_PRINT_SLOT + 0, +#endif +#if PY_VERSION_HEX >= 0x030C0000 + 0, +#endif +#if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, +#endif +}; +#endif +static int __pyx_CyFunction_init(PyObject *module) { +#if CYTHON_USE_TYPE_SPECS + __pyx_CyFunctionType = __Pyx_FetchCommonTypeFromSpec(module, &__pyx_CyFunctionType_spec, NULL); +#else + CYTHON_UNUSED_VAR(module); + __pyx_CyFunctionType = __Pyx_FetchCommonType(&__pyx_CyFunctionType_type); +#endif + if (unlikely(__pyx_CyFunctionType == NULL)) { + return -1; + } + return 0; +} +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *func, size_t size, int pyobjects) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults = PyObject_Malloc(size); + if (unlikely(!m->defaults)) + return PyErr_NoMemory(); + memset(m->defaults, 0, size); + m->defaults_pyobjects = pyobjects; + m->defaults_size = size; + return m->defaults; +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *func, PyObject *tuple) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_tuple = tuple; + Py_INCREF(tuple); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_kwdict = dict; + Py_INCREF(dict); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->func_annotations = dict; + Py_INCREF(dict); +} + +/* CythonFunction */ + static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { + PyObject *op = __Pyx_CyFunction_Init( + PyObject_GC_New(__pyx_CyFunctionObject, __pyx_CyFunctionType), + ml, flags, qualname, closure, module, globals, code + ); + if (likely(op)) { + PyObject_GC_Track(op); + } + return op; +} + +/* ClassMethod */ + static PyObject* __Pyx_Method_ClassMethod(PyObject *method) { +#if CYTHON_COMPILING_IN_PYPY && PYPY_VERSION_NUM <= 0x05080000 + if (PyObject_TypeCheck(method, &PyWrapperDescr_Type)) { + return PyClassMethod_New(method); + } +#else +#if CYTHON_COMPILING_IN_PYPY + if (PyMethodDescr_Check(method)) +#else + #if PY_MAJOR_VERSION == 2 + static PyTypeObject *methoddescr_type = NULL; + if (unlikely(methoddescr_type == NULL)) { + PyObject *meth = PyObject_GetAttrString((PyObject*)&PyList_Type, "append"); + if (unlikely(!meth)) return NULL; + methoddescr_type = Py_TYPE(meth); + Py_DECREF(meth); + } + #else + PyTypeObject *methoddescr_type = &PyMethodDescr_Type; + #endif + if (__Pyx_TypeCheck(method, methoddescr_type)) +#endif + { + PyMethodDescrObject *descr = (PyMethodDescrObject *)method; + #if PY_VERSION_HEX < 0x03020000 + PyTypeObject *d_type = descr->d_type; + #else + PyTypeObject *d_type = descr->d_common.d_type; + #endif + return PyDescr_NewClassMethod(d_type, descr->d_method); + } +#endif + else if (PyMethod_Check(method)) { + return PyClassMethod_New(PyMethod_GET_FUNCTION(method)); + } + else { + return PyClassMethod_New(method); + } +} + +/* GetNameInClass */ + static PyObject *__Pyx__GetNameInClass(PyObject *nmspace, PyObject *name) { + PyObject *result; + PyObject *dict; + assert(PyType_Check(nmspace)); +#if CYTHON_USE_TYPE_SLOTS + dict = ((PyTypeObject*)nmspace)->tp_dict; + Py_XINCREF(dict); +#else + dict = PyObject_GetAttr(nmspace, __pyx_n_s_dict); +#endif + if (likely(dict)) { + result = PyObject_GetItem(dict, name); + Py_DECREF(dict); + if (result) { + return result; + } + } + PyErr_Clear(); + __Pyx_GetModuleGlobalNameUncached(result, name); + return result; +} + +/* CLineInTraceback */ + #ifndef CYTHON_CLINE_IN_TRACEBACK +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line) { + PyObject *use_cline; + PyObject *ptype, *pvalue, *ptraceback; +#if CYTHON_COMPILING_IN_CPYTHON + PyObject **cython_runtime_dict; +#endif + CYTHON_MAYBE_UNUSED_VAR(tstate); + if (unlikely(!__pyx_cython_runtime)) { + return c_line; + } + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); +#if CYTHON_COMPILING_IN_CPYTHON + cython_runtime_dict = _PyObject_GetDictPtr(__pyx_cython_runtime); + if (likely(cython_runtime_dict)) { + __PYX_PY_DICT_LOOKUP_IF_MODIFIED( + use_cline, *cython_runtime_dict, + __Pyx_PyDict_GetItemStr(*cython_runtime_dict, __pyx_n_s_cline_in_traceback)) + } else +#endif + { + PyObject *use_cline_obj = __Pyx_PyObject_GetAttrStrNoError(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback); + if (use_cline_obj) { + use_cline = PyObject_Not(use_cline_obj) ? Py_False : Py_True; + Py_DECREF(use_cline_obj); + } else { + PyErr_Clear(); + use_cline = NULL; + } + } + if (!use_cline) { + c_line = 0; + (void) PyObject_SetAttr(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback, Py_False); + } + else if (use_cline == Py_False || (use_cline != Py_True && PyObject_Not(use_cline) != 0)) { + c_line = 0; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + return c_line; +} +#endif + +/* CodeObjectCache */ + #if !CYTHON_COMPILING_IN_LIMITED_API +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line) { + int start = 0, mid = 0, end = count - 1; + if (end >= 0 && code_line > entries[end].code_line) { + return count; + } + while (start < end) { + mid = start + (end - start) / 2; + if (code_line < entries[mid].code_line) { + end = mid; + } else if (code_line > entries[mid].code_line) { + start = mid + 1; + } else { + return mid; + } + } + if (code_line <= entries[mid].code_line) { + return mid; + } else { + return mid + 1; + } +} +static PyCodeObject *__pyx_find_code_object(int code_line) { + PyCodeObject* code_object; + int pos; + if (unlikely(!code_line) || unlikely(!__pyx_code_cache.entries)) { + return NULL; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if (unlikely(pos >= __pyx_code_cache.count) || unlikely(__pyx_code_cache.entries[pos].code_line != code_line)) { + return NULL; + } + code_object = __pyx_code_cache.entries[pos].code_object; + Py_INCREF(code_object); + return code_object; +} +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object) { + int pos, i; + __Pyx_CodeObjectCacheEntry* entries = __pyx_code_cache.entries; + if (unlikely(!code_line)) { + return; + } + if (unlikely(!entries)) { + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Malloc(64*sizeof(__Pyx_CodeObjectCacheEntry)); + if (likely(entries)) { + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = 64; + __pyx_code_cache.count = 1; + entries[0].code_line = code_line; + entries[0].code_object = code_object; + Py_INCREF(code_object); + } + return; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if ((pos < __pyx_code_cache.count) && unlikely(__pyx_code_cache.entries[pos].code_line == code_line)) { + PyCodeObject* tmp = entries[pos].code_object; + entries[pos].code_object = code_object; + Py_DECREF(tmp); + return; + } + if (__pyx_code_cache.count == __pyx_code_cache.max_count) { + int new_max = __pyx_code_cache.max_count + 64; + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Realloc( + __pyx_code_cache.entries, ((size_t)new_max) * sizeof(__Pyx_CodeObjectCacheEntry)); + if (unlikely(!entries)) { + return; + } + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = new_max; + } + for (i=__pyx_code_cache.count; i>pos; i--) { + entries[i] = entries[i-1]; + } + entries[pos].code_line = code_line; + entries[pos].code_object = code_object; + __pyx_code_cache.count++; + Py_INCREF(code_object); +} +#endif + +/* AddTraceback */ + #include "compile.h" +#include "frameobject.h" +#include "traceback.h" +#if PY_VERSION_HEX >= 0x030b00a6 && !CYTHON_COMPILING_IN_LIMITED_API + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static PyObject *__Pyx_PyCode_Replace_For_AddTraceback(PyObject *code, PyObject *scratch_dict, + PyObject *firstlineno, PyObject *name) { + PyObject *replace = NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "co_firstlineno", firstlineno))) return NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "co_name", name))) return NULL; + replace = PyObject_GetAttrString(code, "replace"); + if (likely(replace)) { + PyObject *result; + result = PyObject_Call(replace, __pyx_empty_tuple, scratch_dict); + Py_DECREF(replace); + return result; + } + PyErr_Clear(); + #if __PYX_LIMITED_VERSION_HEX < 0x030780000 + { + PyObject *compiled = NULL, *result = NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "code", code))) return NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "type", (PyObject*)(&PyType_Type)))) return NULL; + compiled = Py_CompileString( + "out = type(code)(\n" + " code.co_argcount, code.co_kwonlyargcount, code.co_nlocals, code.co_stacksize,\n" + " code.co_flags, code.co_code, code.co_consts, code.co_names,\n" + " code.co_varnames, code.co_filename, co_name, co_firstlineno,\n" + " code.co_lnotab)\n", "", Py_file_input); + if (!compiled) return NULL; + result = PyEval_EvalCode(compiled, scratch_dict, scratch_dict); + Py_DECREF(compiled); + if (!result) PyErr_Print(); + Py_DECREF(result); + result = PyDict_GetItemString(scratch_dict, "out"); + if (result) Py_INCREF(result); + return result; + } + #else + return NULL; + #endif +} +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + PyObject *code_object = NULL, *py_py_line = NULL, *py_funcname = NULL, *dict = NULL; + PyObject *replace = NULL, *getframe = NULL, *frame = NULL; + PyObject *exc_type, *exc_value, *exc_traceback; + int success = 0; + if (c_line) { + (void) __pyx_cfilenm; + (void) __Pyx_CLineForTraceback(__Pyx_PyThreadState_Current, c_line); + } + PyErr_Fetch(&exc_type, &exc_value, &exc_traceback); + code_object = Py_CompileString("_getframe()", filename, Py_eval_input); + if (unlikely(!code_object)) goto bad; + py_py_line = PyLong_FromLong(py_line); + if (unlikely(!py_py_line)) goto bad; + py_funcname = PyUnicode_FromString(funcname); + if (unlikely(!py_funcname)) goto bad; + dict = PyDict_New(); + if (unlikely(!dict)) goto bad; + { + PyObject *old_code_object = code_object; + code_object = __Pyx_PyCode_Replace_For_AddTraceback(code_object, dict, py_py_line, py_funcname); + Py_DECREF(old_code_object); + } + if (unlikely(!code_object)) goto bad; + getframe = PySys_GetObject("_getframe"); + if (unlikely(!getframe)) goto bad; + if (unlikely(PyDict_SetItemString(dict, "_getframe", getframe))) goto bad; + frame = PyEval_EvalCode(code_object, dict, dict); + if (unlikely(!frame) || frame == Py_None) goto bad; + success = 1; + bad: + PyErr_Restore(exc_type, exc_value, exc_traceback); + Py_XDECREF(code_object); + Py_XDECREF(py_py_line); + Py_XDECREF(py_funcname); + Py_XDECREF(dict); + Py_XDECREF(replace); + if (success) { + PyTraceBack_Here( + (struct _frame*)frame); + } + Py_XDECREF(frame); +} +#else +static PyCodeObject* __Pyx_CreateCodeObjectForTraceback( + const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = NULL; + PyObject *py_funcname = NULL; + #if PY_MAJOR_VERSION < 3 + PyObject *py_srcfile = NULL; + py_srcfile = PyString_FromString(filename); + if (!py_srcfile) goto bad; + #endif + if (c_line) { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + #else + py_funcname = PyUnicode_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + funcname = PyUnicode_AsUTF8(py_funcname); + if (!funcname) goto bad; + #endif + } + else { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromString(funcname); + if (!py_funcname) goto bad; + #endif + } + #if PY_MAJOR_VERSION < 3 + py_code = __Pyx_PyCode_New( + 0, + 0, + 0, + 0, + 0, + 0, + __pyx_empty_bytes, /*PyObject *code,*/ + __pyx_empty_tuple, /*PyObject *consts,*/ + __pyx_empty_tuple, /*PyObject *names,*/ + __pyx_empty_tuple, /*PyObject *varnames,*/ + __pyx_empty_tuple, /*PyObject *freevars,*/ + __pyx_empty_tuple, /*PyObject *cellvars,*/ + py_srcfile, /*PyObject *filename,*/ + py_funcname, /*PyObject *name,*/ + py_line, + __pyx_empty_bytes /*PyObject *lnotab*/ + ); + Py_DECREF(py_srcfile); + #else + py_code = PyCode_NewEmpty(filename, funcname, py_line); + #endif + Py_XDECREF(py_funcname); + return py_code; +bad: + Py_XDECREF(py_funcname); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_srcfile); + #endif + return NULL; +} +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = 0; + PyFrameObject *py_frame = 0; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject *ptype, *pvalue, *ptraceback; + if (c_line) { + c_line = __Pyx_CLineForTraceback(tstate, c_line); + } + py_code = __pyx_find_code_object(c_line ? -c_line : py_line); + if (!py_code) { + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); + py_code = __Pyx_CreateCodeObjectForTraceback( + funcname, c_line, py_line, filename); + if (!py_code) { + /* If the code object creation fails, then we should clear the + fetched exception references and propagate the new exception */ + Py_XDECREF(ptype); + Py_XDECREF(pvalue); + Py_XDECREF(ptraceback); + goto bad; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + __pyx_insert_code_object(c_line ? -c_line : py_line, py_code); + } + py_frame = PyFrame_New( + tstate, /*PyThreadState *tstate,*/ + py_code, /*PyCodeObject *code,*/ + __pyx_d, /*PyObject *globals,*/ + 0 /*PyObject *locals*/ + ); + if (!py_frame) goto bad; + __Pyx_PyFrame_SetLineNumber(py_frame, py_line); + PyTraceBack_Here(py_frame); +bad: + Py_XDECREF(py_code); + Py_XDECREF(py_frame); +} +#endif + +#if PY_MAJOR_VERSION < 3 +static int __Pyx_GetBuffer(PyObject *obj, Py_buffer *view, int flags) { + __Pyx_TypeName obj_type_name; + if (PyObject_CheckBuffer(obj)) return PyObject_GetBuffer(obj, view, flags); + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "'" __Pyx_FMT_TYPENAME "' does not have the buffer interface", + obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return -1; +} +static void __Pyx_ReleaseBuffer(Py_buffer *view) { + PyObject *obj = view->obj; + if (!obj) return; + if (PyObject_CheckBuffer(obj)) { + PyBuffer_Release(view); + return; + } + if ((0)) {} + view->obj = NULL; + Py_DECREF(obj); +} +#endif + + + /* Declarations */ + #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #ifdef __cplusplus + static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float x, float y) { + return ::std::complex< float >(x, y); + } + #else + static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float x, float y) { + return x + y*(__pyx_t_float_complex)_Complex_I; + } + #endif +#else + static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float x, float y) { + __pyx_t_float_complex z; + z.real = x; + z.imag = y; + return z; + } +#endif + +/* Arithmetic */ + #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) +#else + static CYTHON_INLINE int __Pyx_c_eq_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + return (a.real == b.real) && (a.imag == b.imag); + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_sum_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + __pyx_t_float_complex z; + z.real = a.real + b.real; + z.imag = a.imag + b.imag; + return z; + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_diff_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + __pyx_t_float_complex z; + z.real = a.real - b.real; + z.imag = a.imag - b.imag; + return z; + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_prod_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + __pyx_t_float_complex z; + z.real = a.real * b.real - a.imag * b.imag; + z.imag = a.real * b.imag + a.imag * b.real; + return z; + } + #if 1 + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_quot_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + if (b.imag == 0) { + return __pyx_t_float_complex_from_parts(a.real / b.real, a.imag / b.real); + } else if (fabsf(b.real) >= fabsf(b.imag)) { + if (b.real == 0 && b.imag == 0) { + return __pyx_t_float_complex_from_parts(a.real / b.real, a.imag / b.imag); + } else { + float r = b.imag / b.real; + float s = (float)(1.0) / (b.real + b.imag * r); + return __pyx_t_float_complex_from_parts( + (a.real + a.imag * r) * s, (a.imag - a.real * r) * s); + } + } else { + float r = b.real / b.imag; + float s = (float)(1.0) / (b.imag + b.real * r); + return __pyx_t_float_complex_from_parts( + (a.real * r + a.imag) * s, (a.imag * r - a.real) * s); + } + } + #else + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_quot_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + if (b.imag == 0) { + return __pyx_t_float_complex_from_parts(a.real / b.real, a.imag / b.real); + } else { + float denom = b.real * b.real + b.imag * b.imag; + return __pyx_t_float_complex_from_parts( + (a.real * b.real + a.imag * b.imag) / denom, + (a.imag * b.real - a.real * b.imag) / denom); + } + } + #endif + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_neg_float(__pyx_t_float_complex a) { + __pyx_t_float_complex z; + z.real = -a.real; + z.imag = -a.imag; + return z; + } + static CYTHON_INLINE int __Pyx_c_is_zero_float(__pyx_t_float_complex a) { + return (a.real == 0) && (a.imag == 0); + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_conj_float(__pyx_t_float_complex a) { + __pyx_t_float_complex z; + z.real = a.real; + z.imag = -a.imag; + return z; + } + #if 1 + static CYTHON_INLINE float __Pyx_c_abs_float(__pyx_t_float_complex z) { + #if !defined(HAVE_HYPOT) || defined(_MSC_VER) + return sqrtf(z.real*z.real + z.imag*z.imag); + #else + return hypotf(z.real, z.imag); + #endif + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_pow_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + __pyx_t_float_complex z; + float r, lnr, theta, z_r, z_theta; + if (b.imag == 0 && b.real == (int)b.real) { + if (b.real < 0) { + float denom = a.real * a.real + a.imag * a.imag; + a.real = a.real / denom; + a.imag = -a.imag / denom; + b.real = -b.real; + } + switch ((int)b.real) { + case 0: + z.real = 1; + z.imag = 0; + return z; + case 1: + return a; + case 2: + return __Pyx_c_prod_float(a, a); + case 3: + z = __Pyx_c_prod_float(a, a); + return __Pyx_c_prod_float(z, a); + case 4: + z = __Pyx_c_prod_float(a, a); + return __Pyx_c_prod_float(z, z); + } + } + if (a.imag == 0) { + if (a.real == 0) { + return a; + } else if ((b.imag == 0) && (a.real >= 0)) { + z.real = powf(a.real, b.real); + z.imag = 0; + return z; + } else if (a.real > 0) { + r = a.real; + theta = 0; + } else { + r = -a.real; + theta = atan2f(0.0, -1.0); + } + } else { + r = __Pyx_c_abs_float(a); + theta = atan2f(a.imag, a.real); + } + lnr = logf(r); + z_r = expf(lnr * b.real - theta * b.imag); + z_theta = theta * b.real + lnr * b.imag; + z.real = z_r * cosf(z_theta); + z.imag = z_r * sinf(z_theta); + return z; + } + #endif +#endif + +/* Declarations */ + #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #ifdef __cplusplus + static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double x, double y) { + return ::std::complex< double >(x, y); + } + #else + static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double x, double y) { + return x + y*(__pyx_t_double_complex)_Complex_I; + } + #endif +#else + static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double x, double y) { + __pyx_t_double_complex z; + z.real = x; + z.imag = y; + return z; + } +#endif + +/* Arithmetic */ + #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) +#else + static CYTHON_INLINE int __Pyx_c_eq_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + return (a.real == b.real) && (a.imag == b.imag); + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_sum_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + __pyx_t_double_complex z; + z.real = a.real + b.real; + z.imag = a.imag + b.imag; + return z; + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_diff_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + __pyx_t_double_complex z; + z.real = a.real - b.real; + z.imag = a.imag - b.imag; + return z; + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_prod_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + __pyx_t_double_complex z; + z.real = a.real * b.real - a.imag * b.imag; + z.imag = a.real * b.imag + a.imag * b.real; + return z; + } + #if 1 + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_quot_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + if (b.imag == 0) { + return __pyx_t_double_complex_from_parts(a.real / b.real, a.imag / b.real); + } else if (fabs(b.real) >= fabs(b.imag)) { + if (b.real == 0 && b.imag == 0) { + return __pyx_t_double_complex_from_parts(a.real / b.real, a.imag / b.imag); + } else { + double r = b.imag / b.real; + double s = (double)(1.0) / (b.real + b.imag * r); + return __pyx_t_double_complex_from_parts( + (a.real + a.imag * r) * s, (a.imag - a.real * r) * s); + } + } else { + double r = b.real / b.imag; + double s = (double)(1.0) / (b.imag + b.real * r); + return __pyx_t_double_complex_from_parts( + (a.real * r + a.imag) * s, (a.imag * r - a.real) * s); + } + } + #else + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_quot_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + if (b.imag == 0) { + return __pyx_t_double_complex_from_parts(a.real / b.real, a.imag / b.real); + } else { + double denom = b.real * b.real + b.imag * b.imag; + return __pyx_t_double_complex_from_parts( + (a.real * b.real + a.imag * b.imag) / denom, + (a.imag * b.real - a.real * b.imag) / denom); + } + } + #endif + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_neg_double(__pyx_t_double_complex a) { + __pyx_t_double_complex z; + z.real = -a.real; + z.imag = -a.imag; + return z; + } + static CYTHON_INLINE int __Pyx_c_is_zero_double(__pyx_t_double_complex a) { + return (a.real == 0) && (a.imag == 0); + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_conj_double(__pyx_t_double_complex a) { + __pyx_t_double_complex z; + z.real = a.real; + z.imag = -a.imag; + return z; + } + #if 1 + static CYTHON_INLINE double __Pyx_c_abs_double(__pyx_t_double_complex z) { + #if !defined(HAVE_HYPOT) || defined(_MSC_VER) + return sqrt(z.real*z.real + z.imag*z.imag); + #else + return hypot(z.real, z.imag); + #endif + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_pow_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + __pyx_t_double_complex z; + double r, lnr, theta, z_r, z_theta; + if (b.imag == 0 && b.real == (int)b.real) { + if (b.real < 0) { + double denom = a.real * a.real + a.imag * a.imag; + a.real = a.real / denom; + a.imag = -a.imag / denom; + b.real = -b.real; + } + switch ((int)b.real) { + case 0: + z.real = 1; + z.imag = 0; + return z; + case 1: + return a; + case 2: + return __Pyx_c_prod_double(a, a); + case 3: + z = __Pyx_c_prod_double(a, a); + return __Pyx_c_prod_double(z, a); + case 4: + z = __Pyx_c_prod_double(a, a); + return __Pyx_c_prod_double(z, z); + } + } + if (a.imag == 0) { + if (a.real == 0) { + return a; + } else if ((b.imag == 0) && (a.real >= 0)) { + z.real = pow(a.real, b.real); + z.imag = 0; + return z; + } else if (a.real > 0) { + r = a.real; + theta = 0; + } else { + r = -a.real; + theta = atan2(0.0, -1.0); + } + } else { + r = __Pyx_c_abs_double(a); + theta = atan2(a.imag, a.real); + } + lnr = log(r); + z_r = exp(lnr * b.real - theta * b.imag); + z_theta = theta * b.real + lnr * b.imag; + z.real = z_r * cos(z_theta); + z.imag = z_r * sin(z_theta); + return z; + } + #endif +#endif + +/* CIntToPy */ + static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(long) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(long) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(long) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; +#if !CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030d0000 + return _PyLong_FromByteArray(bytes, sizeof(long), + little, !is_unsigned); +#else + PyObject *from_bytes, *result = NULL; + PyObject *py_bytes = NULL, *arg_tuple = NULL, *kwds = NULL, *order_str = NULL; + from_bytes = PyObject_GetAttrString((PyObject*)&PyLong_Type, "from_bytes"); + if (!from_bytes) return NULL; + py_bytes = PyBytes_FromStringAndSize((char*)bytes, sizeof(long)); + if (!py_bytes) goto limited_bad; + order_str = PyUnicode_FromString(little ? "little" : "big"); + if (!order_str) goto limited_bad; + arg_tuple = PyTuple_Pack(2, py_bytes, order_str); + if (!arg_tuple) goto limited_bad; + if (!is_unsigned) { + kwds = PyDict_New(); + if (!kwds) goto limited_bad; + if (PyDict_SetItemString(kwds, "signed", __Pyx_NewRef(Py_True))) goto limited_bad; + } + result = PyObject_Call(from_bytes, arg_tuple, kwds); + limited_bad: + Py_XDECREF(kwds); + Py_XDECREF(arg_tuple); + Py_XDECREF(order_str); + Py_XDECREF(py_bytes); + Py_XDECREF(from_bytes); + return result; +#endif + } +} + +/* FormatTypeName */ + #if CYTHON_COMPILING_IN_LIMITED_API +static __Pyx_TypeName +__Pyx_PyType_GetName(PyTypeObject* tp) +{ + PyObject *name = __Pyx_PyObject_GetAttrStr((PyObject *)tp, + __pyx_n_s_name); + if (unlikely(name == NULL) || unlikely(!PyUnicode_Check(name))) { + PyErr_Clear(); + Py_XDECREF(name); + name = __Pyx_NewRef(__pyx_n_s__42); + } + return name; +} +#endif + +/* CIntFromPyVerify */ + #define __PYX_VERIFY_RETURN_INT(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 0) +#define __PYX_VERIFY_RETURN_INT_EXC(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 1) +#define __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, exc)\ + {\ + func_type value = func_value;\ + if (sizeof(target_type) < sizeof(func_type)) {\ + if (unlikely(value != (func_type) (target_type) value)) {\ + func_type zero = 0;\ + if (exc && unlikely(value == (func_type)-1 && PyErr_Occurred()))\ + return (target_type) -1;\ + if (is_unsigned && unlikely(value < zero))\ + goto raise_neg_overflow;\ + else\ + goto raise_overflow;\ + }\ + }\ + return (target_type) value;\ + } + +/* CIntFromPy */ + static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(long) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(long, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (long) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 2 * PyLong_SHIFT)) { + return (long) (((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 3 * PyLong_SHIFT)) { + return (long) (((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 4 * PyLong_SHIFT)) { + return (long) (((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(long) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(long) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) ((((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) ((((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) ((((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(long) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + long val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (long) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (long) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (long) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (long) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(long) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(long) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((long) 1) << (sizeof(long) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (long) -1; + } + } else { + long val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (long) -1; + val = __Pyx_PyInt_As_long(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to long"); + return (long) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to long"); + return (long) -1; +} + +/* CIntFromPy */ + static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(int) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(int, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (int) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 2 * PyLong_SHIFT)) { + return (int) (((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 3 * PyLong_SHIFT)) { + return (int) (((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 4 * PyLong_SHIFT)) { + return (int) (((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(int) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(int) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) ((((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) ((((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) ((((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(int) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + int val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (int) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (int) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (int) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (int) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(int) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(int) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((int) 1) << (sizeof(int) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (int) -1; + } + } else { + int val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (int) -1; + val = __Pyx_PyInt_As_int(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to int"); + return (int) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to int"); + return (int) -1; +} + +/* FastTypeChecks */ + #if CYTHON_COMPILING_IN_CPYTHON +static int __Pyx_InBases(PyTypeObject *a, PyTypeObject *b) { + while (a) { + a = __Pyx_PyType_GetSlot(a, tp_base, PyTypeObject*); + if (a == b) + return 1; + } + return b == &PyBaseObject_Type; +} +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (a == b) return 1; + mro = a->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + if (PyTuple_GET_ITEM(mro, i) == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(a, b); +} +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (cls == a || cls == b) return 1; + mro = cls->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + PyObject *base = PyTuple_GET_ITEM(mro, i); + if (base == (PyObject *)a || base == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(cls, a) || __Pyx_InBases(cls, b); +} +#if PY_MAJOR_VERSION == 2 +static int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject* exc_type2) { + PyObject *exception, *value, *tb; + int res; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&exception, &value, &tb); + res = exc_type1 ? PyObject_IsSubclass(err, exc_type1) : 0; + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + if (!res) { + res = PyObject_IsSubclass(err, exc_type2); + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + } + __Pyx_ErrRestore(exception, value, tb); + return res; +} +#else +static CYTHON_INLINE int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject *exc_type2) { + if (exc_type1) { + return __Pyx_IsAnySubtype2((PyTypeObject*)err, (PyTypeObject*)exc_type1, (PyTypeObject*)exc_type2); + } else { + return __Pyx_IsSubtype((PyTypeObject*)err, (PyTypeObject*)exc_type2); + } +} +#endif +static int __Pyx_PyErr_GivenExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + assert(PyExceptionClass_Check(exc_type)); + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; i= 0x030B00A4 + return Py_Version & ~0xFFUL; +#else + const char* rt_version = Py_GetVersion(); + unsigned long version = 0; + unsigned long factor = 0x01000000UL; + unsigned int digit = 0; + int i = 0; + while (factor) { + while ('0' <= rt_version[i] && rt_version[i] <= '9') { + digit = digit * 10 + (unsigned int) (rt_version[i] - '0'); + ++i; + } + version += factor * digit; + if (rt_version[i] != '.') + break; + digit = 0; + factor >>= 8; + ++i; + } + return version; +#endif +} +static int __Pyx_check_binary_version(unsigned long ct_version, unsigned long rt_version, int allow_newer) { + const unsigned long MAJOR_MINOR = 0xFFFF0000UL; + if ((rt_version & MAJOR_MINOR) == (ct_version & MAJOR_MINOR)) + return 0; + if (likely(allow_newer && (rt_version & MAJOR_MINOR) > (ct_version & MAJOR_MINOR))) + return 1; + { + char message[200]; + PyOS_snprintf(message, sizeof(message), + "compile time Python version %d.%d " + "of module '%.100s' " + "%s " + "runtime version %d.%d", + (int) (ct_version >> 24), (int) ((ct_version >> 16) & 0xFF), + __Pyx_MODULE_NAME, + (allow_newer) ? "was newer than" : "does not match", + (int) (rt_version >> 24), (int) ((rt_version >> 16) & 0xFF) + ); + return PyErr_WarnEx(NULL, message, 1); + } +} + +/* InitStrings */ + #if PY_MAJOR_VERSION >= 3 +static int __Pyx_InitString(__Pyx_StringTabEntry t, PyObject **str) { + if (t.is_unicode | t.is_str) { + if (t.intern) { + *str = PyUnicode_InternFromString(t.s); + } else if (t.encoding) { + *str = PyUnicode_Decode(t.s, t.n - 1, t.encoding, NULL); + } else { + *str = PyUnicode_FromStringAndSize(t.s, t.n - 1); + } + } else { + *str = PyBytes_FromStringAndSize(t.s, t.n - 1); + } + if (!*str) + return -1; + if (PyObject_Hash(*str) == -1) + return -1; + return 0; +} +#endif +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t) { + while (t->p) { + #if PY_MAJOR_VERSION >= 3 + __Pyx_InitString(*t, t->p); + #else + if (t->is_unicode) { + *t->p = PyUnicode_DecodeUTF8(t->s, t->n - 1, NULL); + } else if (t->intern) { + *t->p = PyString_InternFromString(t->s); + } else { + *t->p = PyString_FromStringAndSize(t->s, t->n - 1); + } + if (!*t->p) + return -1; + if (PyObject_Hash(*t->p) == -1) + return -1; + #endif + ++t; + } + return 0; +} + +#include +static CYTHON_INLINE Py_ssize_t __Pyx_ssize_strlen(const char *s) { + size_t len = strlen(s); + if (unlikely(len > (size_t) PY_SSIZE_T_MAX)) { + PyErr_SetString(PyExc_OverflowError, "byte string is too long"); + return -1; + } + return (Py_ssize_t) len; +} +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char* c_str) { + Py_ssize_t len = __Pyx_ssize_strlen(c_str); + if (unlikely(len < 0)) return NULL; + return __Pyx_PyUnicode_FromStringAndSize(c_str, len); +} +static CYTHON_INLINE PyObject* __Pyx_PyByteArray_FromString(const char* c_str) { + Py_ssize_t len = __Pyx_ssize_strlen(c_str); + if (unlikely(len < 0)) return NULL; + return PyByteArray_FromStringAndSize(c_str, len); +} +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject* o) { + Py_ssize_t ignore; + return __Pyx_PyObject_AsStringAndSize(o, &ignore); +} +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +#if !CYTHON_PEP393_ENABLED +static const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + char* defenc_c; + PyObject* defenc = _PyUnicode_AsDefaultEncodedString(o, NULL); + if (!defenc) return NULL; + defenc_c = PyBytes_AS_STRING(defenc); +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + { + char* end = defenc_c + PyBytes_GET_SIZE(defenc); + char* c; + for (c = defenc_c; c < end; c++) { + if ((unsigned char) (*c) >= 128) { + PyUnicode_AsASCIIString(o); + return NULL; + } + } + } +#endif + *length = PyBytes_GET_SIZE(defenc); + return defenc_c; +} +#else +static CYTHON_INLINE const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + if (unlikely(__Pyx_PyUnicode_READY(o) == -1)) return NULL; +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + if (likely(PyUnicode_IS_ASCII(o))) { + *length = PyUnicode_GET_LENGTH(o); + return PyUnicode_AsUTF8(o); + } else { + PyUnicode_AsASCIIString(o); + return NULL; + } +#else + return PyUnicode_AsUTF8AndSize(o, length); +#endif +} +#endif +#endif +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject* o, Py_ssize_t *length) { +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT + if ( +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + __Pyx_sys_getdefaultencoding_not_ascii && +#endif + PyUnicode_Check(o)) { + return __Pyx_PyUnicode_AsStringAndSize(o, length); + } else +#endif +#if (!CYTHON_COMPILING_IN_PYPY && !CYTHON_COMPILING_IN_LIMITED_API) || (defined(PyByteArray_AS_STRING) && defined(PyByteArray_GET_SIZE)) + if (PyByteArray_Check(o)) { + *length = PyByteArray_GET_SIZE(o); + return PyByteArray_AS_STRING(o); + } else +#endif + { + char* result; + int r = PyBytes_AsStringAndSize(o, &result, length); + if (unlikely(r < 0)) { + return NULL; + } else { + return result; + } + } +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject* x) { + int is_true = x == Py_True; + if (is_true | (x == Py_False) | (x == Py_None)) return is_true; + else return PyObject_IsTrue(x); +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject* x) { + int retval; + if (unlikely(!x)) return -1; + retval = __Pyx_PyObject_IsTrue(x); + Py_DECREF(x); + return retval; +} +static PyObject* __Pyx_PyNumber_IntOrLongWrongResultType(PyObject* result, const char* type_name) { + __Pyx_TypeName result_type_name = __Pyx_PyType_GetName(Py_TYPE(result)); +#if PY_MAJOR_VERSION >= 3 + if (PyLong_Check(result)) { + if (PyErr_WarnFormat(PyExc_DeprecationWarning, 1, + "__int__ returned non-int (type " __Pyx_FMT_TYPENAME "). " + "The ability to return an instance of a strict subclass of int is deprecated, " + "and may be removed in a future version of Python.", + result_type_name)) { + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; + } + __Pyx_DECREF_TypeName(result_type_name); + return result; + } +#endif + PyErr_Format(PyExc_TypeError, + "__%.4s__ returned non-%.4s (type " __Pyx_FMT_TYPENAME ")", + type_name, type_name, result_type_name); + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x) { +#if CYTHON_USE_TYPE_SLOTS + PyNumberMethods *m; +#endif + const char *name = NULL; + PyObject *res = NULL; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x) || PyLong_Check(x))) +#else + if (likely(PyLong_Check(x))) +#endif + return __Pyx_NewRef(x); +#if CYTHON_USE_TYPE_SLOTS + m = Py_TYPE(x)->tp_as_number; + #if PY_MAJOR_VERSION < 3 + if (m && m->nb_int) { + name = "int"; + res = m->nb_int(x); + } + else if (m && m->nb_long) { + name = "long"; + res = m->nb_long(x); + } + #else + if (likely(m && m->nb_int)) { + name = "int"; + res = m->nb_int(x); + } + #endif +#else + if (!PyBytes_CheckExact(x) && !PyUnicode_CheckExact(x)) { + res = PyNumber_Int(x); + } +#endif + if (likely(res)) { +#if PY_MAJOR_VERSION < 3 + if (unlikely(!PyInt_Check(res) && !PyLong_Check(res))) { +#else + if (unlikely(!PyLong_CheckExact(res))) { +#endif + return __Pyx_PyNumber_IntOrLongWrongResultType(res, name); + } + } + else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_TypeError, + "an integer is required"); + } + return res; +} +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject* b) { + Py_ssize_t ival; + PyObject *x; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_CheckExact(b))) { + if (sizeof(Py_ssize_t) >= sizeof(long)) + return PyInt_AS_LONG(b); + else + return PyInt_AsSsize_t(b); + } +#endif + if (likely(PyLong_CheckExact(b))) { + #if CYTHON_USE_PYLONG_INTERNALS + if (likely(__Pyx_PyLong_IsCompact(b))) { + return __Pyx_PyLong_CompactValue(b); + } else { + const digit* digits = __Pyx_PyLong_Digits(b); + const Py_ssize_t size = __Pyx_PyLong_SignedDigitCount(b); + switch (size) { + case 2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return (Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + } + } + #endif + return PyLong_AsSsize_t(b); + } + x = PyNumber_Index(b); + if (!x) return -1; + ival = PyInt_AsSsize_t(x); + Py_DECREF(x); + return ival; +} +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject* o) { + if (sizeof(Py_hash_t) == sizeof(Py_ssize_t)) { + return (Py_hash_t) __Pyx_PyIndex_AsSsize_t(o); +#if PY_MAJOR_VERSION < 3 + } else if (likely(PyInt_CheckExact(o))) { + return PyInt_AS_LONG(o); +#endif + } else { + Py_ssize_t ival; + PyObject *x; + x = PyNumber_Index(o); + if (!x) return -1; + ival = PyInt_AsLong(x); + Py_DECREF(x); + return ival; + } +} +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b) { + return b ? __Pyx_NewRef(Py_True) : __Pyx_NewRef(Py_False); +} +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t ival) { + return PyInt_FromSize_t(ival); +} + + +/* #### Code section: utility_code_pragmas_end ### */ +#ifdef _MSC_VER +#pragma warning( pop ) +#endif + + + +/* #### Code section: end ### */ +#endif /* Py_PYTHON_H */ diff --git a/common/transformations/transformations.so b/common/transformations/transformations.so new file mode 100755 index 0000000..a7d5e60 Binary files /dev/null and b/common/transformations/transformations.so differ diff --git a/common/util.cc b/common/util.cc deleted file mode 100644 index 8af9f58..0000000 --- a/common/util.cc +++ /dev/null @@ -1,295 +0,0 @@ -#include "common/util.h" - -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include - -#ifdef __linux__ -#include -#include -#ifndef __USE_GNU -#define __USE_GNU -#endif -#include -#endif // __linux__ - -namespace util { - -void set_thread_name(const char* name) { -#ifdef __linux__ - // pthread_setname_np is dumb (fails instead of truncates) - prctl(PR_SET_NAME, (unsigned long)name, 0, 0, 0); -#endif -} - -int set_realtime_priority(int level) { -#ifdef __linux__ - long tid = syscall(SYS_gettid); - - // should match python using chrt - struct sched_param sa; - memset(&sa, 0, sizeof(sa)); - sa.sched_priority = level; - return sched_setscheduler(tid, SCHED_FIFO, &sa); -#else - return -1; -#endif -} - -int set_core_affinity(std::vector cores) { -#ifdef __linux__ - long tid = syscall(SYS_gettid); - cpu_set_t cpu; - - CPU_ZERO(&cpu); - for (const int n : cores) { - CPU_SET(n, &cpu); - } - return sched_setaffinity(tid, sizeof(cpu), &cpu); -#else - return -1; -#endif -} - -int set_file_descriptor_limit(uint64_t limit_val) { - struct rlimit limit; - int status; - - if ((status = getrlimit(RLIMIT_NOFILE, &limit)) < 0) - return status; - - limit.rlim_cur = limit_val; - if ((status = setrlimit(RLIMIT_NOFILE, &limit)) < 0) - return status; - - return 0; -} - -std::string read_file(const std::string& fn) { - std::ifstream f(fn, std::ios::binary | std::ios::in); - if (f.is_open()) { - f.seekg(0, std::ios::end); - int size = f.tellg(); - if (f.good() && size > 0) { - std::string result(size, '\0'); - f.seekg(0, std::ios::beg); - f.read(result.data(), size); - // return either good() or has reached end-of-file (e.g. /sys/power/wakeup_count) - if (f.good() || f.eof()) { - result.resize(f.gcount()); - return result; - } - } - // fallback for files created on read, e.g. procfs - std::stringstream buffer; - buffer << f.rdbuf(); - return buffer.str(); - } - return std::string(); -} - -std::map read_files_in_dir(const std::string &path) { - std::map ret; - DIR *d = opendir(path.c_str()); - if (!d) return ret; - - struct dirent *de = NULL; - while ((de = readdir(d))) { - if (de->d_type != DT_DIR) { - ret[de->d_name] = util::read_file(path + "/" + de->d_name); - } - } - - closedir(d); - return ret; -} - -int write_file(const char* path, const void* data, size_t size, int flags, mode_t mode) { - int fd = HANDLE_EINTR(open(path, flags, mode)); - if (fd == -1) { - return -1; - } - ssize_t n = HANDLE_EINTR(write(fd, data, size)); - close(fd); - return (n >= 0 && (size_t)n == size) ? 0 : -1; -} - -FILE* safe_fopen(const char* filename, const char* mode) { - FILE* fp = NULL; - do { - fp = fopen(filename, mode); - } while ((nullptr == fp) && (errno == EINTR)); - return fp; -} - -size_t safe_fwrite(const void* ptr, size_t size, size_t count, FILE* stream) { - size_t written = 0; - do { - size_t ret = ::fwrite((void*)((char *)ptr + written * size), size, count - written, stream); - if (ret == 0 && errno != EINTR) break; - written += ret; - } while (written != count); - return written; -} - -int safe_fflush(FILE *stream) { - int ret = EOF; - do { - ret = fflush(stream); - } while ((EOF == ret) && (errno == EINTR)); - return ret; -} - -int safe_ioctl(int fd, unsigned long request, void *argp) { - int ret; - do { - ret = ioctl(fd, request, argp); - } while ((ret == -1) && (errno == EINTR)); - return ret; -} - -std::string readlink(const std::string &path) { - char buff[4096]; - ssize_t len = ::readlink(path.c_str(), buff, sizeof(buff)-1); - if (len != -1) { - buff[len] = '\0'; - return std::string(buff); - } - return ""; -} - -bool file_exists(const std::string& fn) { - struct stat st = {}; - return stat(fn.c_str(), &st) != -1; -} - -static bool createDirectory(std::string dir, mode_t mode) { - auto verify_dir = [](const std::string& dir) -> bool { - struct stat st = {}; - return (stat(dir.c_str(), &st) == 0 && (st.st_mode & S_IFMT) == S_IFDIR); - }; - // remove trailing /'s - while (dir.size() > 1 && dir.back() == '/') { - dir.pop_back(); - } - // try to mkdir this directory - if (mkdir(dir.c_str(), mode) == 0) return true; - if (errno == EEXIST) return verify_dir(dir); - if (errno != ENOENT) return false; - - // mkdir failed because the parent dir doesn't exist, so try to create it - size_t slash = dir.rfind('/'); - if ((slash == std::string::npos || slash < 1) || - !createDirectory(dir.substr(0, slash), mode)) { - return false; - } - - // try again - if (mkdir(dir.c_str(), mode) == 0) return true; - return errno == EEXIST && verify_dir(dir); -} - -bool create_directories(const std::string& dir, mode_t mode) { - if (dir.empty()) return false; - return createDirectory(dir, mode); -} - -std::string getenv(const char* key, std::string default_val) { - const char* val = ::getenv(key); - return val ? val : default_val; -} - -int getenv(const char* key, int default_val) { - const char* val = ::getenv(key); - return val ? atoi(val) : default_val; -} - -float getenv(const char* key, float default_val) { - const char* val = ::getenv(key); - return val ? atof(val) : default_val; -} - -std::string hexdump(const uint8_t* in, const size_t size) { - std::stringstream ss; - ss << std::hex << std::setfill('0'); - for (size_t i = 0; i < size; i++) { - ss << std::setw(2) << static_cast(in[i]); - } - return ss.str(); -} - -int random_int(int min, int max) { - std::random_device dev; - std::mt19937 rng(dev()); - std::uniform_int_distribution dist(min, max); - return dist(rng); -} - -std::string random_string(std::string::size_type length) { - const std::string chrs = "0123456789abcdefghijklmnopqrstuvwxyzABCDEFGHIJKLMNOPQRSTUVWXYZ"; - std::mt19937 rg{std::random_device{}()}; - std::uniform_int_distribution pick(0, chrs.length() - 1); - std::string s; - s.reserve(length); - while (length--) { - s += chrs[pick(rg)]; - } - return s; -} - -std::string dir_name(std::string const &path) { - size_t pos = path.find_last_of("/"); - if (pos == std::string::npos) return ""; - return path.substr(0, pos); -} - -bool starts_with(const std::string &s1, const std::string &s2) { - return strncmp(s1.c_str(), s2.c_str(), s2.size()) == 0; -} - -bool ends_with(const std::string &s1, const std::string &s2) { - return strcmp(s1.c_str() + (s1.size() - s2.size()), s2.c_str()) == 0; -} - -std::string check_output(const std::string& command) { - char buffer[128]; - std::string result; - std::unique_ptr pipe(popen(command.c_str(), "r"), pclose); - - if (!pipe) { - return ""; - } - - while (fgets(buffer, std::size(buffer), pipe.get()) != nullptr) { - result += std::string(buffer); - } - - return result; -} - -struct tm get_time() { - time_t rawtime; - time(&rawtime); - - struct tm sys_time; - gmtime_r(&rawtime, &sys_time); - - return sys_time; -} - -bool time_valid(struct tm sys_time) { - int year = 1900 + sys_time.tm_year; - int month = 1 + sys_time.tm_mon; - return (year > 2023) || (year == 2023 && month >= 6); -} - -} // namespace util diff --git a/common/util.h b/common/util.h deleted file mode 100644 index 6f29a36..0000000 --- a/common/util.h +++ /dev/null @@ -1,184 +0,0 @@ -#pragma once - -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -// keep trying if x gets interrupted by a signal -#define HANDLE_EINTR(x) \ - ({ \ - decltype(x) ret_; \ - int try_cnt = 0; \ - do { \ - ret_ = (x); \ - } while (ret_ == -1 && errno == EINTR && try_cnt++ < 100); \ - ret_; \ - }) - -#ifndef sighandler_t -typedef void (*sighandler_t)(int sig); -#endif - -const double MILE_TO_KM = 1.609344; -const double KM_TO_MILE = 1. / MILE_TO_KM; -const double MS_TO_KPH = 3.6; -const double MS_TO_MPH = MS_TO_KPH * KM_TO_MILE; -const double METER_TO_MILE = KM_TO_MILE / 1000.0; -const double METER_TO_FOOT = 3.28084; -const double FOOT_TO_METER = 1 / METER_TO_FOOT; -const double CM_TO_INCH = METER_TO_FOOT / 100.0 * 12.0; -const double INCH_TO_CM = 1.0 / CM_TO_INCH; - -namespace util { - -void set_thread_name(const char* name); -int set_realtime_priority(int level); -int set_core_affinity(std::vector cores); -int set_file_descriptor_limit(uint64_t limit); - -// ***** Time helpers ***** -struct tm get_time(); -bool time_valid(struct tm sys_time); - -// ***** math helpers ***** - -// map x from [a1, a2] to [b1, b2] -template -T map_val(T x, T a1, T a2, T b1, T b2) { - x = std::clamp(x, a1, a2); - T ra = a2 - a1; - T rb = b2 - b1; - return (x - a1) * rb / ra + b1; -} - -// ***** string helpers ***** - -template -std::string string_format(const std::string& format, Args... args) { - size_t size = snprintf(nullptr, 0, format.c_str(), args...) + 1; - std::unique_ptr buf(new char[size]); - snprintf(buf.get(), size, format.c_str(), args...); - return std::string(buf.get(), buf.get() + size - 1); -} - -std::string getenv(const char* key, std::string default_val = ""); -int getenv(const char* key, int default_val); -float getenv(const char* key, float default_val); - -std::string hexdump(const uint8_t* in, const size_t size); -std::string dir_name(std::string const& path); -bool starts_with(const std::string &s1, const std::string &s2); -bool ends_with(const std::string &s1, const std::string &s2); - -// ***** random helpers ***** -int random_int(int min, int max); -std::string random_string(std::string::size_type length); - -// **** file helpers ***** -std::string read_file(const std::string& fn); -std::map read_files_in_dir(const std::string& path); -int write_file(const char* path, const void* data, size_t size, int flags = O_WRONLY, mode_t mode = 0664); - -FILE* safe_fopen(const char* filename, const char* mode); -size_t safe_fwrite(const void * ptr, size_t size, size_t count, FILE * stream); -int safe_fflush(FILE *stream); -int safe_ioctl(int fd, unsigned long request, void *argp); - -std::string readlink(const std::string& path); -bool file_exists(const std::string& fn); -bool create_directories(const std::string &dir, mode_t mode); - -std::string check_output(const std::string& command); - -inline void sleep_for(const int milliseconds) { - if (milliseconds > 0) { - std::this_thread::sleep_for(std::chrono::milliseconds(milliseconds)); - } -} - -} // namespace util - -class ExitHandler { -public: - ExitHandler() { - std::signal(SIGINT, (sighandler_t)set_do_exit); - std::signal(SIGTERM, (sighandler_t)set_do_exit); - -#ifndef __APPLE__ - std::signal(SIGPWR, (sighandler_t)set_do_exit); -#endif - } - inline static std::atomic power_failure = false; - inline static std::atomic signal = 0; - inline operator bool() { return do_exit; } - inline ExitHandler& operator=(bool v) { - signal = 0; - do_exit = v; - return *this; - } -private: - static void set_do_exit(int sig) { -#ifndef __APPLE__ - power_failure = (sig == SIGPWR); -#endif - signal = sig; - do_exit = true; - } - inline static std::atomic do_exit = false; -}; - -struct unique_fd { - unique_fd(int fd = -1) : fd_(fd) {} - unique_fd& operator=(unique_fd&& uf) { - fd_ = uf.fd_; - uf.fd_ = -1; - return *this; - } - ~unique_fd() { - if (fd_ != -1) close(fd_); - } - operator int() const { return fd_; } - int fd_; -}; - -class FirstOrderFilter { -public: - FirstOrderFilter(float x0, float ts, float dt, bool initialized = true) { - k_ = (dt / ts) / (1.0 + dt / ts); - x_ = x0; - initialized_ = initialized; - } - inline float update(float x) { - if (initialized_) { - x_ = (1. - k_) * x_ + k_ * x; - } else { - initialized_ = true; - x_ = x; - } - return x_; - } - inline void reset(float x) { x_ = x; } - inline float x(){ return x_; } - -private: - float x_, k_; - bool initialized_; -}; - -template -void update_max_atomic(std::atomic& max, T const& value) { - T prev = max; - while (prev < value && !max.compare_exchange_weak(prev, value)) {} -} diff --git a/common/watchdog.cc b/common/watchdog.cc deleted file mode 100644 index 3483ad2..0000000 --- a/common/watchdog.cc +++ /dev/null @@ -1,11 +0,0 @@ -#include - -#include "common/watchdog.h" -#include "common/util.h" - -const std::string watchdog_fn_prefix = "/dev/shm/wd_"; // + - -bool watchdog_kick(uint64_t ts) { - static std::string fn = watchdog_fn_prefix + std::to_string(getpid()); - return util::write_file(fn.c_str(), &ts, sizeof(ts), O_WRONLY | O_CREAT) > 0; -} diff --git a/common/watchdog.h b/common/watchdog.h deleted file mode 100644 index 12dd2ca..0000000 --- a/common/watchdog.h +++ /dev/null @@ -1,5 +0,0 @@ -#pragma once - -#include - -bool watchdog_kick(uint64_t ts); diff --git a/opendbc/can/SConscript b/opendbc/can/SConscript deleted file mode 100644 index f07234c..0000000 --- a/opendbc/can/SConscript +++ /dev/null @@ -1,24 +0,0 @@ -Import('env', 'envCython', 'cereal', 'common') - -import os - -envDBC = env.Clone() -dbc_file_path = '-DDBC_FILE_PATH=\'"%s"\'' % (envDBC.Dir("..").abspath) -envDBC['CXXFLAGS'] += [dbc_file_path] -src = ["dbc.cc", "parser.cc", "packer.cc", "common.cc"] -libs = [common, "capnp", "kj", "zmq"] - -# shared library for openpilot -libdbc = envDBC.SharedLibrary('libdbc', src, LIBS=libs) - -# static library for tools like cabana -envDBC.Library('libdbc_static', src, LIBS=libs) - -# Build packer and parser -lenv = envCython.Clone() -lenv["LINKFLAGS"] += [libdbc[0].get_labspath()] -parser = lenv.Program('parser_pyx.so', 'parser_pyx.pyx') -packer = lenv.Program('packer_pyx.so', 'packer_pyx.pyx') - -lenv.Depends(parser, libdbc) -lenv.Depends(packer, libdbc) diff --git a/opendbc/can/common.cc b/opendbc/can/common.cc deleted file mode 100644 index 37b48fa..0000000 --- a/opendbc/can/common.cc +++ /dev/null @@ -1,246 +0,0 @@ -#include "opendbc/can/common.h" - - -unsigned int honda_checksum(uint32_t address, const Signal &sig, const std::vector &d) { - int s = 0; - bool extended = address > 0x7FF; - while (address) { s += (address & 0xF); address >>= 4; } - for (int i = 0; i < d.size(); i++) { - uint8_t x = d[i]; - if (i == d.size()-1) x >>= 4; // remove checksum - s += (x & 0xF) + (x >> 4); - } - s = 8-s; - if (extended) s += 3; // extended can - - return s & 0xF; -} - -unsigned int toyota_checksum(uint32_t address, const Signal &sig, const std::vector &d) { - unsigned int s = d.size(); - while (address) { s += address & 0xFF; address >>= 8; } - for (int i = 0; i < d.size() - 1; i++) { s += d[i]; } - - return s & 0xFF; -} - -unsigned int subaru_checksum(uint32_t address, const Signal &sig, const std::vector &d) { - unsigned int s = 0; - while (address) { s += address & 0xFF; address >>= 8; } - - // skip checksum in first byte - for (int i = 1; i < d.size(); i++) { s += d[i]; } - - return s & 0xFF; -} - -unsigned int chrysler_checksum(uint32_t address, const Signal &sig, const std::vector &d) { - // jeep chrysler canbus checksum from http://illmatics.com/Remote%20Car%20Hacking.pdf - uint8_t checksum = 0xFF; - for (int j = 0; j < (d.size() - 1); j++) { - uint8_t shift = 0x80; - uint8_t curr = d[j]; - for (int i = 0; i < 8; i++) { - uint8_t bit_sum = curr & shift; - uint8_t temp_chk = checksum & 0x80U; - if (bit_sum != 0U) { - bit_sum = 0x1C; - if (temp_chk != 0U) { - bit_sum = 1; - } - checksum = checksum << 1; - temp_chk = checksum | 1U; - bit_sum ^= temp_chk; - } else { - if (temp_chk != 0U) { - bit_sum = 0x1D; - } - checksum = checksum << 1; - bit_sum ^= checksum; - } - checksum = bit_sum; - shift = shift >> 1; - } - } - return ~checksum & 0xFF; -} - -// Static lookup table for fast computation of CRCs -uint8_t crc8_lut_8h2f[256]; // CRC8 poly 0x2F, aka 8H2F/AUTOSAR -uint16_t crc16_lut_xmodem[256]; // CRC16 poly 0x1021, aka XMODEM - -void gen_crc_lookup_table_8(uint8_t poly, uint8_t crc_lut[]) { - uint8_t crc; - int i, j; - - for (i = 0; i < 256; i++) { - crc = i; - for (j = 0; j < 8; j++) { - if ((crc & 0x80) != 0) - crc = (uint8_t)((crc << 1) ^ poly); - else - crc <<= 1; - } - crc_lut[i] = crc; - } -} - -void gen_crc_lookup_table_16(uint16_t poly, uint16_t crc_lut[]) { - uint16_t crc; - int i, j; - - for (i = 0; i < 256; i++) { - crc = i << 8; - for (j = 0; j < 8; j++) { - if ((crc & 0x8000) != 0) { - crc = (uint16_t)((crc << 1) ^ poly); - } else { - crc <<= 1; - } - } - crc_lut[i] = crc; - } -} - -void init_crc_lookup_tables() { - // At init time, set up static lookup tables for fast CRC computation. - gen_crc_lookup_table_8(0x2F, crc8_lut_8h2f); // CRC-8 8H2F/AUTOSAR for Volkswagen - gen_crc_lookup_table_16(0x1021, crc16_lut_xmodem); // CRC-16 XMODEM for HKG CAN FD -} - -unsigned int volkswagen_mqb_checksum(uint32_t address, const Signal &sig, const std::vector &d) { - // Volkswagen uses standard CRC8 8H2F/AUTOSAR, but they compute it with - // a magic variable padding byte tacked onto the end of the payload. - // https://www.autosar.org/fileadmin/user_upload/standards/classic/4-3/AUTOSAR_SWS_CRCLibrary.pdf - - uint8_t crc = 0xFF; // Standard init value for CRC8 8H2F/AUTOSAR - - // CRC the payload first, skipping over the first byte where the CRC lives. - for (int i = 1; i < d.size(); i++) { - crc ^= d[i]; - crc = crc8_lut_8h2f[crc]; - } - - // Look up and apply the magic final CRC padding byte, which permutes by CAN - // address, and additionally (for SOME addresses) by the message counter. - uint8_t counter = d[1] & 0x0F; - switch (address) { - case 0x86: // LWI_01 Steering Angle - crc ^= (uint8_t[]){0x86, 0x86, 0x86, 0x86, 0x86, 0x86, 0x86, 0x86, 0x86, 0x86, 0x86, 0x86, 0x86, 0x86, 0x86, 0x86}[counter]; - break; - case 0x9F: // LH_EPS_03 Electric Power Steering - crc ^= (uint8_t[]){0xF5, 0xF5, 0xF5, 0xF5, 0xF5, 0xF5, 0xF5, 0xF5, 0xF5, 0xF5, 0xF5, 0xF5, 0xF5, 0xF5, 0xF5, 0xF5}[counter]; - break; - case 0xAD: // Getriebe_11 Automatic Gearbox - crc ^= (uint8_t[]){0x3F, 0x69, 0x39, 0xDC, 0x94, 0xF9, 0x14, 0x64, 0xD8, 0x6A, 0x34, 0xCE, 0xA2, 0x55, 0xB5, 0x2C}[counter]; - break; - case 0xFD: // ESP_21 Electronic Stability Program - crc ^= (uint8_t[]){0xB4, 0xEF, 0xF8, 0x49, 0x1E, 0xE5, 0xC2, 0xC0, 0x97, 0x19, 0x3C, 0xC9, 0xF1, 0x98, 0xD6, 0x61}[counter]; - break; - case 0x106: // ESP_05 Electronic Stability Program - crc ^= (uint8_t[]){0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07}[counter]; - break; - case 0x117: // ACC_10 Automatic Cruise Control - crc ^= (uint8_t[]){0x16, 0x16, 0x16, 0x16, 0x16, 0x16, 0x16, 0x16, 0x16, 0x16, 0x16, 0x16, 0x16, 0x16, 0x16, 0x16}[counter]; - break; - case 0x120: // TSK_06 Drivetrain Coordinator - crc ^= (uint8_t[]){0xC4, 0xE2, 0x4F, 0xE4, 0xF8, 0x2F, 0x56, 0x81, 0x9F, 0xE5, 0x83, 0x44, 0x05, 0x3F, 0x97, 0xDF}[counter]; - break; - case 0x121: // Motor_20 Driver Throttle Inputs - crc ^= (uint8_t[]){0xE9, 0x65, 0xAE, 0x6B, 0x7B, 0x35, 0xE5, 0x5F, 0x4E, 0xC7, 0x86, 0xA2, 0xBB, 0xDD, 0xEB, 0xB4}[counter]; - break; - case 0x122: // ACC_06 Automatic Cruise Control - crc ^= (uint8_t[]){0x37, 0x7D, 0xF3, 0xA9, 0x18, 0x46, 0x6D, 0x4D, 0x3D, 0x71, 0x92, 0x9C, 0xE5, 0x32, 0x10, 0xB9}[counter]; - break; - case 0x126: // HCA_01 Heading Control Assist - crc ^= (uint8_t[]){0xDA, 0xDA, 0xDA, 0xDA, 0xDA, 0xDA, 0xDA, 0xDA, 0xDA, 0xDA, 0xDA, 0xDA, 0xDA, 0xDA, 0xDA, 0xDA}[counter]; - break; - case 0x12B: // GRA_ACC_01 Steering wheel controls for ACC - crc ^= (uint8_t[]){0x6A, 0x38, 0xB4, 0x27, 0x22, 0xEF, 0xE1, 0xBB, 0xF8, 0x80, 0x84, 0x49, 0xC7, 0x9E, 0x1E, 0x2B}[counter]; - break; - case 0x12E: // ACC_07 Automatic Cruise Control - crc ^= (uint8_t[]){0xF8, 0xE5, 0x97, 0xC9, 0xD6, 0x07, 0x47, 0x21, 0x66, 0xDD, 0xCF, 0x6F, 0xA1, 0x94, 0x74, 0x63}[counter]; - break; - case 0x187: // EV_Gearshift "Gear" selection data for EVs with no gearbox - crc ^= (uint8_t[]){0x7F, 0xED, 0x17, 0xC2, 0x7C, 0xEB, 0x44, 0x21, 0x01, 0xFA, 0xDB, 0x15, 0x4A, 0x6B, 0x23, 0x05}[counter]; - break; - case 0x30C: // ACC_02 Automatic Cruise Control - crc ^= (uint8_t[]){0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F}[counter]; - break; - case 0x30F: // SWA_01 Lane Change Assist (SpurWechselAssistent) - crc ^= (uint8_t[]){0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C}[counter]; - break; - case 0x324: // ACC_04 Automatic Cruise Control - crc ^= (uint8_t[]){0x27, 0x27, 0x27, 0x27, 0x27, 0x27, 0x27, 0x27, 0x27, 0x27, 0x27, 0x27, 0x27, 0x27, 0x27, 0x27}[counter]; - break; - case 0x3C0: // Klemmen_Status_01 ignition and starting status - crc ^= (uint8_t[]){0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3}[counter]; - break; - case 0x65D: // ESP_20 Electronic Stability Program - crc ^= (uint8_t[]){0xAC, 0xB3, 0xAB, 0xEB, 0x7A, 0xE1, 0x3B, 0xF7, 0x73, 0xBA, 0x7C, 0x9E, 0x06, 0x5F, 0x02, 0xD9}[counter]; - break; - default: // As-yet undefined CAN message, CRC check expected to fail - printf("Attempt to CRC check undefined Volkswagen message 0x%02X\n", address); - crc ^= (uint8_t[]){0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00}[counter]; - break; - } - crc = crc8_lut_8h2f[crc]; - - return crc ^ 0xFF; // Return after standard final XOR for CRC8 8H2F/AUTOSAR -} - -unsigned int xor_checksum(uint32_t address, const Signal &sig, const std::vector &d) { - uint8_t checksum = 0; - int checksum_byte = sig.start_bit / 8; - - // Simple XOR over the payload, except for the byte where the checksum lives. - for (int i = 0; i < d.size(); i++) { - if (i != checksum_byte) { - checksum ^= d[i]; - } - } - - return checksum; -} - -unsigned int pedal_checksum(uint32_t address, const Signal &sig, const std::vector &d) { - uint8_t crc = 0xFF; - uint8_t poly = 0xD5; // standard crc8 - - // skip checksum byte - for (int i = d.size()-2; i >= 0; i--) { - crc ^= d[i]; - for (int j = 0; j < 8; j++) { - if ((crc & 0x80) != 0) { - crc = (uint8_t)((crc << 1) ^ poly); - } else { - crc <<= 1; - } - } - } - return crc; -} - -unsigned int hkg_can_fd_checksum(uint32_t address, const Signal &sig, const std::vector &d) { - uint16_t crc = 0; - - for (int i = 2; i < d.size(); i++) { - crc = (crc << 8) ^ crc16_lut_xmodem[(crc >> 8) ^ d[i]]; - } - - // Add address to crc - crc = (crc << 8) ^ crc16_lut_xmodem[(crc >> 8) ^ ((address >> 0) & 0xFF)]; - crc = (crc << 8) ^ crc16_lut_xmodem[(crc >> 8) ^ ((address >> 8) & 0xFF)]; - - if (d.size() == 8) { - crc ^= 0x5f29; - } else if (d.size() == 16) { - crc ^= 0x041d; - } else if (d.size() == 24) { - crc ^= 0x819d; - } else if (d.size() == 32) { - crc ^= 0x9f5b; - } - - return crc; -} diff --git a/opendbc/can/common.h b/opendbc/can/common.h deleted file mode 100644 index cfc63eb..0000000 --- a/opendbc/can/common.h +++ /dev/null @@ -1,102 +0,0 @@ -#pragma once - -#include -#include -#include -#include -#include - -#include -#include - -#ifndef DYNAMIC_CAPNP -#include "cereal/gen/cpp/log.capnp.h" -#endif - -#include "opendbc/can/common_dbc.h" - -#define INFO printf -#define WARN printf -#define DEBUG(...) -//#define DEBUG printf - -#define MAX_BAD_COUNTER 5 -#define CAN_INVALID_CNT 5 - -void init_crc_lookup_tables(); - -// Car specific functions -unsigned int honda_checksum(uint32_t address, const Signal &sig, const std::vector &d); -unsigned int toyota_checksum(uint32_t address, const Signal &sig, const std::vector &d); -unsigned int subaru_checksum(uint32_t address, const Signal &sig, const std::vector &d); -unsigned int chrysler_checksum(uint32_t address, const Signal &sig, const std::vector &d); -unsigned int volkswagen_mqb_checksum(uint32_t address, const Signal &sig, const std::vector &d); -unsigned int xor_checksum(uint32_t address, const Signal &sig, const std::vector &d); -unsigned int hkg_can_fd_checksum(uint32_t address, const Signal &sig, const std::vector &d); -unsigned int pedal_checksum(uint32_t address, const Signal &sig, const std::vector &d); - -class MessageState { -public: - std::string name; - uint32_t address; - unsigned int size; - - std::vector parse_sigs; - std::vector vals; - std::vector> all_vals; - - uint64_t last_seen_nanos; - uint64_t check_threshold; - - uint8_t counter; - uint8_t counter_fail; - - bool ignore_checksum = false; - bool ignore_counter = false; - - bool parse(uint64_t nanos, const std::vector &dat); - bool update_counter_generic(int64_t v, int cnt_size); -}; - -class CANParser { -private: - const int bus; - kj::Array aligned_buf; - - const DBC *dbc = NULL; - std::unordered_map message_states; - -public: - bool can_valid = false; - bool bus_timeout = false; - uint64_t first_nanos = 0; - uint64_t last_nanos = 0; - uint64_t last_nonempty_nanos = 0; - uint64_t bus_timeout_threshold = 0; - uint64_t can_invalid_cnt = CAN_INVALID_CNT; - - CANParser(int abus, const std::string& dbc_name, - const std::vector> &messages); - CANParser(int abus, const std::string& dbc_name, bool ignore_checksum, bool ignore_counter); - #ifndef DYNAMIC_CAPNP - void update_string(const std::string &data, bool sendcan); - void update_strings(const std::vector &data, std::vector &vals, bool sendcan); - void UpdateCans(uint64_t nanos, const capnp::List::Reader& cans); - #endif - void UpdateCans(uint64_t nanos, const capnp::DynamicStruct::Reader& cans); - void UpdateValid(uint64_t nanos); - void query_latest(std::vector &vals, uint64_t last_ts = 0); -}; - -class CANPacker { -private: - const DBC *dbc = NULL; - std::map, Signal> signal_lookup; - std::map message_lookup; - std::map counters; - -public: - CANPacker(const std::string& dbc_name); - std::vector pack(uint32_t address, const std::vector &values); - Msg* lookup_message(uint32_t address); -}; diff --git a/opendbc/can/common_dbc.h b/opendbc/can/common_dbc.h deleted file mode 100644 index ef4c98c..0000000 --- a/opendbc/can/common_dbc.h +++ /dev/null @@ -1,77 +0,0 @@ -#pragma once - -#include -#include -#include -#include - -struct SignalPackValue { - std::string name; - double value; -}; - -struct SignalValue { - uint32_t address; - uint64_t ts_nanos; - std::string name; - double value; // latest value - std::vector all_values; // all values from this cycle -}; - -enum SignalType { - DEFAULT, - COUNTER, - HONDA_CHECKSUM, - TOYOTA_CHECKSUM, - PEDAL_CHECKSUM, - VOLKSWAGEN_MQB_CHECKSUM, - XOR_CHECKSUM, - SUBARU_CHECKSUM, - CHRYSLER_CHECKSUM, - HKG_CAN_FD_CHECKSUM, -}; - -struct Signal { - std::string name; - int start_bit, msb, lsb, size; - bool is_signed; - double factor, offset; - bool is_little_endian; - SignalType type; - unsigned int (*calc_checksum)(uint32_t address, const Signal &sig, const std::vector &d); -}; - -struct Msg { - std::string name; - uint32_t address; - unsigned int size; - std::vector sigs; -}; - -struct Val { - std::string name; - uint32_t address; - std::string def_val; - std::vector sigs; -}; - -struct DBC { - std::string name; - std::vector msgs; - std::vector vals; -}; - -typedef struct ChecksumState { - int checksum_size; - int counter_size; - int checksum_start_bit; - int counter_start_bit; - bool little_endian; - SignalType checksum_type; - unsigned int (*calc_checksum)(uint32_t address, const Signal &sig, const std::vector &d); -} ChecksumState; - -DBC* dbc_parse(const std::string& dbc_path); -DBC* dbc_parse_from_stream(const std::string &dbc_name, std::istream &stream, ChecksumState *checksum = nullptr, bool allow_duplicate_msg_name=false); -const DBC* dbc_lookup(const std::string& dbc_name); -std::vector get_dbc_names(); diff --git a/opendbc/can/dbc.cc b/opendbc/can/dbc.cc deleted file mode 100644 index 7abe6b6..0000000 --- a/opendbc/can/dbc.cc +++ /dev/null @@ -1,258 +0,0 @@ -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include "opendbc/can/common.h" -#include "opendbc/can/common_dbc.h" - -std::regex bo_regexp(R"(^BO_ (\w+) (\w+) *: (\w+) (\w+))"); -std::regex sg_regexp(R"(^SG_ (\w+) : (\d+)\|(\d+)@(\d+)([\+|\-]) \(([0-9.+\-eE]+),([0-9.+\-eE]+)\) \[([0-9.+\-eE]+)\|([0-9.+\-eE]+)\] \"(.*)\" (.*))"); -std::regex sgm_regexp(R"(^SG_ (\w+) (\w+) *: (\d+)\|(\d+)@(\d+)([\+|\-]) \(([0-9.+\-eE]+),([0-9.+\-eE]+)\) \[([0-9.+\-eE]+)\|([0-9.+\-eE]+)\] \"(.*)\" (.*))"); -std::regex val_regexp(R"(VAL_ (\w+) (\w+) (\s*[-+]?[0-9]+\s+\".+?\"[^;]*))"); -std::regex val_split_regexp{R"([\"]+)"}; // split on " - -#define DBC_ASSERT(condition, message) \ - do { \ - if (!(condition)) { \ - std::stringstream is; \ - is << "[" << dbc_name << ":" << line_num << "] " << message; \ - throw std::runtime_error(is.str()); \ - } \ - } while (false) - -inline bool startswith(const std::string& str, const char* prefix) { - return str.find(prefix, 0) == 0; -} - -inline bool startswith(const std::string& str, std::initializer_list prefix_list) { - for (auto prefix : prefix_list) { - if (startswith(str, prefix)) return true; - } - return false; -} - -inline bool endswith(const std::string& str, const char* suffix) { - return str.find(suffix, 0) == (str.length() - strlen(suffix)); -} - -inline std::string& trim(std::string& s, const char* t = " \t\n\r\f\v") { - s.erase(s.find_last_not_of(t) + 1); - return s.erase(0, s.find_first_not_of(t)); -} - -ChecksumState* get_checksum(const std::string& dbc_name) { - ChecksumState* s = nullptr; - if (startswith(dbc_name, {"honda_", "acura_"})) { - s = new ChecksumState({4, 2, 3, 5, false, HONDA_CHECKSUM, &honda_checksum}); - } else if (startswith(dbc_name, {"toyota_", "lexus_"})) { - s = new ChecksumState({8, -1, 7, -1, false, TOYOTA_CHECKSUM, &toyota_checksum}); - } else if (startswith(dbc_name, "hyundai_canfd")) { - s = new ChecksumState({16, -1, 0, -1, true, HKG_CAN_FD_CHECKSUM, &hkg_can_fd_checksum}); - } else if (startswith(dbc_name, "vw_mqb_2010")) { - s = new ChecksumState({8, 4, 0, 0, true, VOLKSWAGEN_MQB_CHECKSUM, &volkswagen_mqb_checksum}); - } else if (startswith(dbc_name, "vw_golf_mk4")) { - s = new ChecksumState({8, 4, 0, -1, true, XOR_CHECKSUM, &xor_checksum}); - } else if (startswith(dbc_name, "subaru_global_")) { - s = new ChecksumState({8, -1, 0, -1, true, SUBARU_CHECKSUM, &subaru_checksum}); - } else if (startswith(dbc_name, "chrysler_")) { - s = new ChecksumState({8, -1, 7, -1, false, CHRYSLER_CHECKSUM, &chrysler_checksum}); - } else if (startswith(dbc_name, "comma_body")) { - s = new ChecksumState({8, 4, 7, 3, false, PEDAL_CHECKSUM, &pedal_checksum}); - } - return s; -} - -void set_signal_type(Signal& s, ChecksumState* chk, const std::string& dbc_name, int line_num) { - s.calc_checksum = nullptr; - if (chk) { - if (s.name == "CHECKSUM") { - DBC_ASSERT(chk->checksum_size == -1 || s.size == chk->checksum_size, "CHECKSUM is not " << chk->checksum_size << " bits long"); - DBC_ASSERT(chk->checksum_start_bit == -1 || (s.start_bit % 8) == chk->checksum_start_bit, " CHECKSUM starts at wrong bit"); - DBC_ASSERT(s.is_little_endian == chk->little_endian, "CHECKSUM has wrong endianness"); - DBC_ASSERT(chk->calc_checksum != nullptr, "CHECKSUM calculate function not supplied"); - s.type = chk->checksum_type; - s.calc_checksum = chk->calc_checksum; - } else if (s.name == "COUNTER") { - DBC_ASSERT(chk->counter_size == -1 || s.size == chk->counter_size, "COUNTER is not " << chk->counter_size << " bits long"); - DBC_ASSERT(chk->counter_start_bit == -1 || (s.start_bit % 8) == chk->counter_start_bit, "COUNTER starts at wrong bit"); - DBC_ASSERT(chk->little_endian == s.is_little_endian, "COUNTER has wrong endianness"); - s.type = COUNTER; - } - } - - // TODO: CAN packer/parser shouldn't know anything about interceptors or pedals - if (s.name == "CHECKSUM_PEDAL") { - DBC_ASSERT(s.size == 8, "INTERCEPTOR CHECKSUM is not 8 bits long"); - s.type = PEDAL_CHECKSUM; - } else if (s.name == "COUNTER_PEDAL") { - DBC_ASSERT(s.size == 4, "INTERCEPTOR COUNTER is not 4 bits long"); - s.type = COUNTER; - } -} - -DBC* dbc_parse_from_stream(const std::string &dbc_name, std::istream &stream, ChecksumState *checksum, bool allow_duplicate_msg_name) { - uint32_t address = 0; - std::set address_set; - std::set msg_name_set; - std::map> signal_name_sets; - std::map> signals; - DBC* dbc = new DBC; - dbc->name = dbc_name; - std::setlocale(LC_NUMERIC, "C"); - - // used to find big endian LSB from MSB and size - std::vector be_bits; - for (int i = 0; i < 64; i++) { - for (int j = 7; j >= 0; j--) { - be_bits.push_back(j + i * 8); - } - } - - std::string line; - int line_num = 0; - std::smatch match; - // TODO: see if we can speed up the regex statements in this loop, SG_ is specifically the slowest - while (std::getline(stream, line)) { - line = trim(line); - line_num += 1; - if (startswith(line, "BO_ ")) { - // new group - bool ret = std::regex_match(line, match, bo_regexp); - DBC_ASSERT(ret, "bad BO: " << line); - - Msg& msg = dbc->msgs.emplace_back(); - address = msg.address = std::stoul(match[1].str()); // could be hex - msg.name = match[2].str(); - msg.size = std::stoul(match[3].str()); - - // check for duplicates - DBC_ASSERT(address_set.find(address) == address_set.end(), "Duplicate message address: " << address << " (" << msg.name << ")"); - address_set.insert(address); - - if (!allow_duplicate_msg_name) { - DBC_ASSERT(msg_name_set.find(msg.name) == msg_name_set.end(), "Duplicate message name: " << msg.name); - msg_name_set.insert(msg.name); - } - } else if (startswith(line, "SG_ ")) { - // new signal - int offset = 0; - if (!std::regex_search(line, match, sg_regexp)) { - bool ret = std::regex_search(line, match, sgm_regexp); - DBC_ASSERT(ret, "bad SG: " << line); - offset = 1; - } - Signal& sig = signals[address].emplace_back(); - sig.name = match[1].str(); - sig.start_bit = std::stoi(match[offset + 2].str()); - sig.size = std::stoi(match[offset + 3].str()); - sig.is_little_endian = std::stoi(match[offset + 4].str()) == 1; - sig.is_signed = match[offset + 5].str() == "-"; - sig.factor = std::stod(match[offset + 6].str()); - sig.offset = std::stod(match[offset + 7].str()); - set_signal_type(sig, checksum, dbc_name, line_num); - if (sig.is_little_endian) { - sig.lsb = sig.start_bit; - sig.msb = sig.start_bit + sig.size - 1; - } else { - auto it = find(be_bits.begin(), be_bits.end(), sig.start_bit); - sig.lsb = be_bits[(it - be_bits.begin()) + sig.size - 1]; - sig.msb = sig.start_bit; - } - DBC_ASSERT(sig.lsb < (64 * 8) && sig.msb < (64 * 8), "Signal out of bounds: " << line); - - // Check for duplicate signal names - DBC_ASSERT(signal_name_sets[address].find(sig.name) == signal_name_sets[address].end(), "Duplicate signal name: " << sig.name); - signal_name_sets[address].insert(sig.name); - } else if (startswith(line, "VAL_ ")) { - // new signal value/definition - bool ret = std::regex_search(line, match, val_regexp); - DBC_ASSERT(ret, "bad VAL: " << line); - - auto& val = dbc->vals.emplace_back(); - val.address = std::stoul(match[1].str()); // could be hex - val.name = match[2].str(); - - auto defvals = match[3].str(); - std::sregex_token_iterator it{defvals.begin(), defvals.end(), val_split_regexp, -1}; - // convert strings to UPPER_CASE_WITH_UNDERSCORES - std::vector words{it, {}}; - for (auto& w : words) { - w = trim(w); - std::transform(w.begin(), w.end(), w.begin(), ::toupper); - std::replace(w.begin(), w.end(), ' ', '_'); - } - // join string - std::stringstream s; - std::copy(words.begin(), words.end(), std::ostream_iterator(s, " ")); - val.def_val = s.str(); - val.def_val = trim(val.def_val); - } - } - - for (auto& m : dbc->msgs) { - m.sigs = signals[m.address]; - } - for (auto& v : dbc->vals) { - v.sigs = signals[v.address]; - } - return dbc; -} - -DBC* dbc_parse(const std::string& dbc_path) { - std::ifstream infile(dbc_path); - if (!infile) return nullptr; - - const std::string dbc_name = std::filesystem::path(dbc_path).filename(); - - std::unique_ptr checksum(get_checksum(dbc_name)); - return dbc_parse_from_stream(dbc_name, infile, checksum.get()); -} - -const std::string get_dbc_root_path() { - char *basedir = std::getenv("BASEDIR"); - if (basedir != NULL) { - return std::string(basedir) + "/opendbc"; - } else { - return DBC_FILE_PATH; - } -} - -const DBC* dbc_lookup(const std::string& dbc_name) { - static std::mutex lock; - static std::map dbcs; - - std::string dbc_file_path = dbc_name; - if (!std::filesystem::exists(dbc_file_path)) { - dbc_file_path = get_dbc_root_path() + "/" + dbc_name + ".dbc"; - } - - std::unique_lock lk(lock); - auto it = dbcs.find(dbc_name); - if (it == dbcs.end()) { - it = dbcs.insert(it, {dbc_name, dbc_parse(dbc_file_path)}); - } - return it->second; -} - -std::vector get_dbc_names() { - static const std::string& dbc_file_path = get_dbc_root_path(); - std::vector dbcs; - for (std::filesystem::directory_iterator i(dbc_file_path), end; i != end; i++) { - if (!is_directory(i->path())) { - std::string filename = i->path().filename(); - if (!startswith(filename, "_") && endswith(filename, ".dbc")) { - dbcs.push_back(filename.substr(0, filename.length() - 4)); - } - } - } - return dbcs; -} diff --git a/opendbc/can/libdbc.so b/opendbc/can/libdbc.so new file mode 100755 index 0000000..e7e8517 Binary files /dev/null and b/opendbc/can/libdbc.so differ diff --git a/opendbc/can/packer.cc b/opendbc/can/packer.cc deleted file mode 100644 index 87fa0a8..0000000 --- a/opendbc/can/packer.cc +++ /dev/null @@ -1,98 +0,0 @@ -#include -#include -#include -#include -#include -#include - -#include "opendbc/can/common.h" - - -void set_value(std::vector &msg, const Signal &sig, int64_t ival) { - int i = sig.lsb / 8; - int bits = sig.size; - if (sig.size < 64) { - ival &= ((1ULL << sig.size) - 1); - } - - while (i >= 0 && i < msg.size() && bits > 0) { - int shift = (int)(sig.lsb / 8) == i ? sig.lsb % 8 : 0; - int size = std::min(bits, 8 - shift); - - msg[i] &= ~(((1ULL << size) - 1) << shift); - msg[i] |= (ival & ((1ULL << size) - 1)) << shift; - - bits -= size; - ival >>= size; - i = sig.is_little_endian ? i+1 : i-1; - } -} - -CANPacker::CANPacker(const std::string& dbc_name) { - dbc = dbc_lookup(dbc_name); - assert(dbc); - - for (const auto& msg : dbc->msgs) { - message_lookup[msg.address] = msg; - for (const auto& sig : msg.sigs) { - signal_lookup[std::make_pair(msg.address, sig.name)] = sig; - } - } - init_crc_lookup_tables(); -} - -std::vector CANPacker::pack(uint32_t address, const std::vector &signals) { - std::vector ret(message_lookup[address].size, 0); - - // set all values for all given signal/value pairs - bool counter_set = false; - for (const auto& sigval : signals) { - auto sig_it = signal_lookup.find(std::make_pair(address, sigval.name)); - if (sig_it == signal_lookup.end()) { - // TODO: do something more here. invalid flag like CANParser? - WARN("undefined signal %s - %d\n", sigval.name.c_str(), address); - continue; - } - const auto &sig = sig_it->second; - - int64_t ival = (int64_t)(round((sigval.value - sig.offset) / sig.factor)); - if (ival < 0) { - ival = (1ULL << sig.size) + ival; - } - set_value(ret, sig, ival); - - counter_set = counter_set || (sigval.name == "COUNTER"); - if (counter_set) { - counters[address] = sigval.value; - } - } - - // set message counter - auto sig_it_counter = signal_lookup.find(std::make_pair(address, "COUNTER")); - if (!counter_set && sig_it_counter != signal_lookup.end()) { - const auto& sig = sig_it_counter->second; - - if (counters.find(address) == counters.end()) { - counters[address] = 0; - } - set_value(ret, sig, counters[address]); - counters[address] = (counters[address] + 1) % (1 << sig.size); - } - - // set message checksum - auto sig_it_checksum = signal_lookup.find(std::make_pair(address, "CHECKSUM")); - if (sig_it_checksum != signal_lookup.end()) { - const auto &sig = sig_it_checksum->second; - if (sig.calc_checksum != nullptr) { - unsigned int checksum = sig.calc_checksum(address, sig, ret); - set_value(ret, sig, checksum); - } - } - - return ret; -} - -// This function has a definition in common.h and is used in PlotJuggler -Msg* CANPacker::lookup_message(uint32_t address) { - return &message_lookup[address]; -} diff --git a/opendbc/can/packer_pyx.cpp b/opendbc/can/packer_pyx.cpp new file mode 100644 index 0000000..cb86232 --- /dev/null +++ b/opendbc/can/packer_pyx.cpp @@ -0,0 +1,9741 @@ +/* Generated by Cython 3.0.8 */ + +/* BEGIN: Cython Metadata +{ + "distutils": { + "depends": [ + "opendbc/can/common.h", + "opendbc/can/common_dbc.h" + ], + "include_dirs": [ + "opendbc/can" + ], + "language": "c++", + "name": "opendbc.can.packer_pyx", + "sources": [ + "/data/openpilot/opendbc/can/packer_pyx.pyx" + ] + }, + "module_name": "opendbc.can.packer_pyx" +} +END: Cython Metadata */ + +#ifndef PY_SSIZE_T_CLEAN +#define PY_SSIZE_T_CLEAN +#endif /* PY_SSIZE_T_CLEAN */ +#if defined(CYTHON_LIMITED_API) && 0 + #ifndef Py_LIMITED_API + #if CYTHON_LIMITED_API+0 > 0x03030000 + #define Py_LIMITED_API CYTHON_LIMITED_API + #else + #define Py_LIMITED_API 0x03030000 + #endif + #endif +#endif + +#include "Python.h" +#ifndef Py_PYTHON_H + #error Python headers needed to compile C extensions, please install development version of Python. +#elif PY_VERSION_HEX < 0x02070000 || (0x03000000 <= PY_VERSION_HEX && PY_VERSION_HEX < 0x03030000) + #error Cython requires Python 2.7+ or Python 3.3+. +#else +#if defined(CYTHON_LIMITED_API) && CYTHON_LIMITED_API +#define __PYX_EXTRA_ABI_MODULE_NAME "limited" +#else +#define __PYX_EXTRA_ABI_MODULE_NAME "" +#endif +#define CYTHON_ABI "3_0_8" __PYX_EXTRA_ABI_MODULE_NAME +#define __PYX_ABI_MODULE_NAME "_cython_" CYTHON_ABI +#define __PYX_TYPE_MODULE_PREFIX __PYX_ABI_MODULE_NAME "." +#define CYTHON_HEX_VERSION 0x030008F0 +#define CYTHON_FUTURE_DIVISION 1 +#include +#ifndef offsetof + #define offsetof(type, member) ( (size_t) & ((type*)0) -> member ) +#endif +#if !defined(_WIN32) && !defined(WIN32) && !defined(MS_WINDOWS) + #ifndef __stdcall + #define __stdcall + #endif + #ifndef __cdecl + #define __cdecl + #endif + #ifndef __fastcall + #define __fastcall + #endif +#endif +#ifndef DL_IMPORT + #define DL_IMPORT(t) t +#endif +#ifndef DL_EXPORT + #define DL_EXPORT(t) t +#endif +#define __PYX_COMMA , +#ifndef HAVE_LONG_LONG + #define HAVE_LONG_LONG +#endif +#ifndef PY_LONG_LONG + #define PY_LONG_LONG LONG_LONG +#endif +#ifndef Py_HUGE_VAL + #define Py_HUGE_VAL HUGE_VAL +#endif +#define __PYX_LIMITED_VERSION_HEX PY_VERSION_HEX +#if defined(GRAALVM_PYTHON) + /* For very preliminary testing purposes. Most variables are set the same as PyPy. + The existence of this section does not imply that anything works or is even tested */ + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 1 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(PYPY_VERSION) + #define CYTHON_COMPILING_IN_PYPY 1 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #ifndef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #endif + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #if PY_VERSION_HEX < 0x03090000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE (PY_VERSION_HEX >= 0x030400a1 && PYPY_VERSION_NUM >= 0x07030C00) + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(CYTHON_LIMITED_API) + #ifdef Py_LIMITED_API + #undef __PYX_LIMITED_VERSION_HEX + #define __PYX_LIMITED_VERSION_HEX Py_LIMITED_API + #endif + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 1 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_CLINE_IN_TRACEBACK + #define CYTHON_CLINE_IN_TRACEBACK 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 1 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #endif + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 1 + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(Py_GIL_DISABLED) || defined(Py_NOGIL) + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 1 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #ifndef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 +#else + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 1 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #ifndef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #endif + #ifndef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 1 + #endif + #if PY_MAJOR_VERSION < 3 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #ifndef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 1 + #endif + #ifndef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 1 + #endif + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #if PY_VERSION_HEX < 0x030300F0 || PY_VERSION_HEX >= 0x030B00A2 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #elif !defined(CYTHON_USE_UNICODE_WRITER) + #define CYTHON_USE_UNICODE_WRITER 1 + #endif + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #ifndef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 1 + #endif + #ifndef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL (PY_MAJOR_VERSION < 3 || PY_VERSION_HEX >= 0x03060000 && PY_VERSION_HEX < 0x030C00A6) + #endif + #ifndef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL (PY_VERSION_HEX >= 0x030700A1) + #endif + #ifndef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 1 + #endif + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #endif + #if PY_VERSION_HEX < 0x030400a1 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #elif !defined(CYTHON_USE_TP_FINALIZE) + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #if PY_VERSION_HEX < 0x030600B1 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #elif !defined(CYTHON_USE_DICT_VERSIONS) + #define CYTHON_USE_DICT_VERSIONS (PY_VERSION_HEX < 0x030C00A5) + #endif + #if PY_VERSION_HEX < 0x030700A3 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #elif !defined(CYTHON_USE_EXC_INFO_STACK) + #define CYTHON_USE_EXC_INFO_STACK 1 + #endif + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 1 + #endif +#endif +#if !defined(CYTHON_FAST_PYCCALL) +#define CYTHON_FAST_PYCCALL (CYTHON_FAST_PYCALL && PY_VERSION_HEX >= 0x030600B1) +#endif +#if !defined(CYTHON_VECTORCALL) +#define CYTHON_VECTORCALL (CYTHON_FAST_PYCCALL && PY_VERSION_HEX >= 0x030800B1) +#endif +#define CYTHON_BACKPORT_VECTORCALL (CYTHON_METH_FASTCALL && PY_VERSION_HEX < 0x030800B1) +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_MAJOR_VERSION < 3 + #include "longintrepr.h" + #endif + #undef SHIFT + #undef BASE + #undef MASK + #ifdef SIZEOF_VOID_P + enum { __pyx_check_sizeof_voidp = 1 / (int)(SIZEOF_VOID_P == sizeof(void*)) }; + #endif +#endif +#ifndef __has_attribute + #define __has_attribute(x) 0 +#endif +#ifndef __has_cpp_attribute + #define __has_cpp_attribute(x) 0 +#endif +#ifndef CYTHON_RESTRICT + #if defined(__GNUC__) + #define CYTHON_RESTRICT __restrict__ + #elif defined(_MSC_VER) && _MSC_VER >= 1400 + #define CYTHON_RESTRICT __restrict + #elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define CYTHON_RESTRICT restrict + #else + #define CYTHON_RESTRICT + #endif +#endif +#ifndef CYTHON_UNUSED + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(maybe_unused) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(maybe_unused) + #define CYTHON_UNUSED [[maybe_unused]] + #endif + #endif + #endif +#endif +#ifndef CYTHON_UNUSED +# if defined(__GNUC__) +# if !(defined(__cplusplus)) || (__GNUC__ > 3 || (__GNUC__ == 3 && __GNUC_MINOR__ >= 4)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +# elif defined(__ICC) || (defined(__INTEL_COMPILER) && !defined(_MSC_VER)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +#endif +#ifndef CYTHON_UNUSED_VAR +# if defined(__cplusplus) + template void CYTHON_UNUSED_VAR( const T& ) { } +# else +# define CYTHON_UNUSED_VAR(x) (void)(x) +# endif +#endif +#ifndef CYTHON_MAYBE_UNUSED_VAR + #define CYTHON_MAYBE_UNUSED_VAR(x) CYTHON_UNUSED_VAR(x) +#endif +#ifndef CYTHON_NCP_UNUSED +# if CYTHON_COMPILING_IN_CPYTHON +# define CYTHON_NCP_UNUSED +# else +# define CYTHON_NCP_UNUSED CYTHON_UNUSED +# endif +#endif +#ifndef CYTHON_USE_CPP_STD_MOVE + #if defined(__cplusplus) && (\ + __cplusplus >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1600)) + #define CYTHON_USE_CPP_STD_MOVE 1 + #else + #define CYTHON_USE_CPP_STD_MOVE 0 + #endif +#endif +#define __Pyx_void_to_None(void_result) ((void)(void_result), Py_INCREF(Py_None), Py_None) +#ifdef _MSC_VER + #ifndef _MSC_STDINT_H_ + #if _MSC_VER < 1300 + typedef unsigned char uint8_t; + typedef unsigned short uint16_t; + typedef unsigned int uint32_t; + #else + typedef unsigned __int8 uint8_t; + typedef unsigned __int16 uint16_t; + typedef unsigned __int32 uint32_t; + #endif + #endif + #if _MSC_VER < 1300 + #ifdef _WIN64 + typedef unsigned long long __pyx_uintptr_t; + #else + typedef unsigned int __pyx_uintptr_t; + #endif + #else + #ifdef _WIN64 + typedef unsigned __int64 __pyx_uintptr_t; + #else + typedef unsigned __int32 __pyx_uintptr_t; + #endif + #endif +#else + #include + typedef uintptr_t __pyx_uintptr_t; +#endif +#ifndef CYTHON_FALLTHROUGH + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(fallthrough) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(fallthrough) + #define CYTHON_FALLTHROUGH [[fallthrough]] + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_cpp_attribute(clang::fallthrough) + #define CYTHON_FALLTHROUGH [[clang::fallthrough]] + #elif __has_cpp_attribute(gnu::fallthrough) + #define CYTHON_FALLTHROUGH [[gnu::fallthrough]] + #endif + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_attribute(fallthrough) + #define CYTHON_FALLTHROUGH __attribute__((fallthrough)) + #else + #define CYTHON_FALLTHROUGH + #endif + #endif + #if defined(__clang__) && defined(__apple_build_version__) + #if __apple_build_version__ < 7000000 + #undef CYTHON_FALLTHROUGH + #define CYTHON_FALLTHROUGH + #endif + #endif +#endif +#ifdef __cplusplus + template + struct __PYX_IS_UNSIGNED_IMPL {static const bool value = T(0) < T(-1);}; + #define __PYX_IS_UNSIGNED(type) (__PYX_IS_UNSIGNED_IMPL::value) +#else + #define __PYX_IS_UNSIGNED(type) (((type)-1) > 0) +#endif +#if CYTHON_COMPILING_IN_PYPY == 1 + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x030A0000) +#else + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x03090000) +#endif +#define __PYX_REINTERPRET_FUNCION(func_pointer, other_pointer) ((func_pointer)(void(*)(void))(other_pointer)) + +#ifndef __cplusplus + #error "Cython files generated with the C++ option must be compiled with a C++ compiler." +#endif +#ifndef CYTHON_INLINE + #if defined(__clang__) + #define CYTHON_INLINE __inline__ __attribute__ ((__unused__)) + #else + #define CYTHON_INLINE inline + #endif +#endif +template +void __Pyx_call_destructor(T& x) { + x.~T(); +} +template +class __Pyx_FakeReference { + public: + __Pyx_FakeReference() : ptr(NULL) { } + __Pyx_FakeReference(const T& ref) : ptr(const_cast(&ref)) { } + T *operator->() { return ptr; } + T *operator&() { return ptr; } + operator T&() { return *ptr; } + template bool operator ==(const U& other) const { return *ptr == other; } + template bool operator !=(const U& other) const { return *ptr != other; } + template bool operator==(const __Pyx_FakeReference& other) const { return *ptr == *other.ptr; } + template bool operator!=(const __Pyx_FakeReference& other) const { return *ptr != *other.ptr; } + private: + T *ptr; +}; + +#define __PYX_BUILD_PY_SSIZE_T "n" +#define CYTHON_FORMAT_SSIZE_T "z" +#if PY_MAJOR_VERSION < 3 + #define __Pyx_BUILTIN_MODULE_NAME "__builtin__" + #define __Pyx_DefaultClassType PyClass_Type + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a+k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_BUILTIN_MODULE_NAME "builtins" + #define __Pyx_DefaultClassType PyType_Type +#if CYTHON_COMPILING_IN_LIMITED_API + static CYTHON_INLINE PyObject* __Pyx_PyCode_New(int a, int p, int k, int l, int s, int f, + PyObject *code, PyObject *c, PyObject* n, PyObject *v, + PyObject *fv, PyObject *cell, PyObject* fn, + PyObject *name, int fline, PyObject *lnos) { + PyObject *exception_table = NULL; + PyObject *types_module=NULL, *code_type=NULL, *result=NULL; + #if __PYX_LIMITED_VERSION_HEX < 0x030B0000 + PyObject *version_info; + PyObject *py_minor_version = NULL; + #endif + long minor_version = 0; + PyObject *type, *value, *traceback; + PyErr_Fetch(&type, &value, &traceback); + #if __PYX_LIMITED_VERSION_HEX >= 0x030B0000 + minor_version = 11; + #else + if (!(version_info = PySys_GetObject("version_info"))) goto end; + if (!(py_minor_version = PySequence_GetItem(version_info, 1))) goto end; + minor_version = PyLong_AsLong(py_minor_version); + Py_DECREF(py_minor_version); + if (minor_version == -1 && PyErr_Occurred()) goto end; + #endif + if (!(types_module = PyImport_ImportModule("types"))) goto end; + if (!(code_type = PyObject_GetAttrString(types_module, "CodeType"))) goto end; + if (minor_version <= 7) { + (void)p; + result = PyObject_CallFunction(code_type, "iiiiiOOOOOOiOO", a, k, l, s, f, code, + c, n, v, fn, name, fline, lnos, fv, cell); + } else if (minor_version <= 10) { + result = PyObject_CallFunction(code_type, "iiiiiiOOOOOOiOO", a,p, k, l, s, f, code, + c, n, v, fn, name, fline, lnos, fv, cell); + } else { + if (!(exception_table = PyBytes_FromStringAndSize(NULL, 0))) goto end; + result = PyObject_CallFunction(code_type, "iiiiiiOOOOOOOiOO", a,p, k, l, s, f, code, + c, n, v, fn, name, name, fline, lnos, exception_table, fv, cell); + } + end: + Py_XDECREF(code_type); + Py_XDECREF(exception_table); + Py_XDECREF(types_module); + if (type) { + PyErr_Restore(type, value, traceback); + } + return result; + } + #ifndef CO_OPTIMIZED + #define CO_OPTIMIZED 0x0001 + #endif + #ifndef CO_NEWLOCALS + #define CO_NEWLOCALS 0x0002 + #endif + #ifndef CO_VARARGS + #define CO_VARARGS 0x0004 + #endif + #ifndef CO_VARKEYWORDS + #define CO_VARKEYWORDS 0x0008 + #endif + #ifndef CO_ASYNC_GENERATOR + #define CO_ASYNC_GENERATOR 0x0200 + #endif + #ifndef CO_GENERATOR + #define CO_GENERATOR 0x0020 + #endif + #ifndef CO_COROUTINE + #define CO_COROUTINE 0x0080 + #endif +#elif PY_VERSION_HEX >= 0x030B0000 + static CYTHON_INLINE PyCodeObject* __Pyx_PyCode_New(int a, int p, int k, int l, int s, int f, + PyObject *code, PyObject *c, PyObject* n, PyObject *v, + PyObject *fv, PyObject *cell, PyObject* fn, + PyObject *name, int fline, PyObject *lnos) { + PyCodeObject *result; + PyObject *empty_bytes = PyBytes_FromStringAndSize("", 0); + if (!empty_bytes) return NULL; + result = + #if PY_VERSION_HEX >= 0x030C0000 + PyUnstable_Code_NewWithPosOnlyArgs + #else + PyCode_NewWithPosOnlyArgs + #endif + (a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, name, fline, lnos, empty_bytes); + Py_DECREF(empty_bytes); + return result; + } +#elif PY_VERSION_HEX >= 0x030800B2 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_NewWithPosOnlyArgs(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#endif +#endif +#if PY_VERSION_HEX >= 0x030900A4 || defined(Py_IS_TYPE) + #define __Pyx_IS_TYPE(ob, type) Py_IS_TYPE(ob, type) +#else + #define __Pyx_IS_TYPE(ob, type) (((const PyObject*)ob)->ob_type == (type)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_Is) + #define __Pyx_Py_Is(x, y) Py_Is(x, y) +#else + #define __Pyx_Py_Is(x, y) ((x) == (y)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsNone) + #define __Pyx_Py_IsNone(ob) Py_IsNone(ob) +#else + #define __Pyx_Py_IsNone(ob) __Pyx_Py_Is((ob), Py_None) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsTrue) + #define __Pyx_Py_IsTrue(ob) Py_IsTrue(ob) +#else + #define __Pyx_Py_IsTrue(ob) __Pyx_Py_Is((ob), Py_True) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsFalse) + #define __Pyx_Py_IsFalse(ob) Py_IsFalse(ob) +#else + #define __Pyx_Py_IsFalse(ob) __Pyx_Py_Is((ob), Py_False) +#endif +#define __Pyx_NoneAsNull(obj) (__Pyx_Py_IsNone(obj) ? NULL : (obj)) +#if PY_VERSION_HEX >= 0x030900F0 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_GC_IsFinalized(o) PyObject_GC_IsFinalized(o) +#else + #define __Pyx_PyObject_GC_IsFinalized(o) _PyGC_FINALIZED(o) +#endif +#ifndef CO_COROUTINE + #define CO_COROUTINE 0x80 +#endif +#ifndef CO_ASYNC_GENERATOR + #define CO_ASYNC_GENERATOR 0x200 +#endif +#ifndef Py_TPFLAGS_CHECKTYPES + #define Py_TPFLAGS_CHECKTYPES 0 +#endif +#ifndef Py_TPFLAGS_HAVE_INDEX + #define Py_TPFLAGS_HAVE_INDEX 0 +#endif +#ifndef Py_TPFLAGS_HAVE_NEWBUFFER + #define Py_TPFLAGS_HAVE_NEWBUFFER 0 +#endif +#ifndef Py_TPFLAGS_HAVE_FINALIZE + #define Py_TPFLAGS_HAVE_FINALIZE 0 +#endif +#ifndef Py_TPFLAGS_SEQUENCE + #define Py_TPFLAGS_SEQUENCE 0 +#endif +#ifndef Py_TPFLAGS_MAPPING + #define Py_TPFLAGS_MAPPING 0 +#endif +#ifndef METH_STACKLESS + #define METH_STACKLESS 0 +#endif +#if PY_VERSION_HEX <= 0x030700A3 || !defined(METH_FASTCALL) + #ifndef METH_FASTCALL + #define METH_FASTCALL 0x80 + #endif + typedef PyObject *(*__Pyx_PyCFunctionFast) (PyObject *self, PyObject *const *args, Py_ssize_t nargs); + typedef PyObject *(*__Pyx_PyCFunctionFastWithKeywords) (PyObject *self, PyObject *const *args, + Py_ssize_t nargs, PyObject *kwnames); +#else + #define __Pyx_PyCFunctionFast _PyCFunctionFast + #define __Pyx_PyCFunctionFastWithKeywords _PyCFunctionFastWithKeywords +#endif +#if CYTHON_METH_FASTCALL + #define __Pyx_METH_FASTCALL METH_FASTCALL + #define __Pyx_PyCFunction_FastCall __Pyx_PyCFunctionFast + #define __Pyx_PyCFunction_FastCallWithKeywords __Pyx_PyCFunctionFastWithKeywords +#else + #define __Pyx_METH_FASTCALL METH_VARARGS + #define __Pyx_PyCFunction_FastCall PyCFunction + #define __Pyx_PyCFunction_FastCallWithKeywords PyCFunctionWithKeywords +#endif +#if CYTHON_VECTORCALL + #define __pyx_vectorcallfunc vectorcallfunc + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET PY_VECTORCALL_ARGUMENTS_OFFSET + #define __Pyx_PyVectorcall_NARGS(n) PyVectorcall_NARGS((size_t)(n)) +#elif CYTHON_BACKPORT_VECTORCALL + typedef PyObject *(*__pyx_vectorcallfunc)(PyObject *callable, PyObject *const *args, + size_t nargsf, PyObject *kwnames); + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET ((size_t)1 << (8 * sizeof(size_t) - 1)) + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(((size_t)(n)) & ~__Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET)) +#else + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET 0 + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(n)) +#endif +#if PY_MAJOR_VERSION >= 0x030900B1 +#define __Pyx_PyCFunction_CheckExact(func) PyCFunction_CheckExact(func) +#else +#define __Pyx_PyCFunction_CheckExact(func) PyCFunction_Check(func) +#endif +#define __Pyx_CyOrPyCFunction_Check(func) PyCFunction_Check(func) +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_CyOrPyCFunction_GET_FUNCTION(func) (((PyCFunctionObject*)(func))->m_ml->ml_meth) +#elif !CYTHON_COMPILING_IN_LIMITED_API +#define __Pyx_CyOrPyCFunction_GET_FUNCTION(func) PyCFunction_GET_FUNCTION(func) +#endif +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_CyOrPyCFunction_GET_FLAGS(func) (((PyCFunctionObject*)(func))->m_ml->ml_flags) +static CYTHON_INLINE PyObject* __Pyx_CyOrPyCFunction_GET_SELF(PyObject *func) { + return (__Pyx_CyOrPyCFunction_GET_FLAGS(func) & METH_STATIC) ? NULL : ((PyCFunctionObject*)func)->m_self; +} +#endif +static CYTHON_INLINE int __Pyx__IsSameCFunction(PyObject *func, void *cfunc) { +#if CYTHON_COMPILING_IN_LIMITED_API + return PyCFunction_Check(func) && PyCFunction_GetFunction(func) == (PyCFunction) cfunc; +#else + return PyCFunction_Check(func) && PyCFunction_GET_FUNCTION(func) == (PyCFunction) cfunc; +#endif +} +#define __Pyx_IsSameCFunction(func, cfunc) __Pyx__IsSameCFunction(func, cfunc) +#if __PYX_LIMITED_VERSION_HEX < 0x030900B1 + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) ((void)m, PyType_FromSpecWithBases(s, b)) + typedef PyObject *(*__Pyx_PyCMethod)(PyObject *, PyTypeObject *, PyObject *const *, size_t, PyObject *); +#else + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) PyType_FromModuleAndSpec(m, s, b) + #define __Pyx_PyCMethod PyCMethod +#endif +#ifndef METH_METHOD + #define METH_METHOD 0x200 +#endif +#if CYTHON_COMPILING_IN_PYPY && !defined(PyObject_Malloc) + #define PyObject_Malloc(s) PyMem_Malloc(s) + #define PyObject_Free(p) PyMem_Free(p) + #define PyObject_Realloc(p) PyMem_Realloc(p) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) +#else + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) (frame)->f_lineno = (lineno) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyThreadState_Current PyThreadState_Get() +#elif !CYTHON_FAST_THREAD_STATE + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#elif PY_VERSION_HEX >= 0x030d00A1 + #define __Pyx_PyThreadState_Current PyThreadState_GetUnchecked() +#elif PY_VERSION_HEX >= 0x03060000 + #define __Pyx_PyThreadState_Current _PyThreadState_UncheckedGet() +#elif PY_VERSION_HEX >= 0x03000000 + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#else + #define __Pyx_PyThreadState_Current _PyThreadState_Current +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE void *__Pyx_PyModule_GetState(PyObject *op) +{ + void *result; + result = PyModule_GetState(op); + if (!result) + Py_FatalError("Couldn't find the module state"); + return result; +} +#endif +#define __Pyx_PyObject_GetSlot(obj, name, func_ctype) __Pyx_PyType_GetSlot(Py_TYPE(obj), name, func_ctype) +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((func_ctype) PyType_GetSlot((type), Py_##name)) +#else + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((type)->name) +#endif +#if PY_VERSION_HEX < 0x030700A2 && !defined(PyThread_tss_create) && !defined(Py_tss_NEEDS_INIT) +#include "pythread.h" +#define Py_tss_NEEDS_INIT 0 +typedef int Py_tss_t; +static CYTHON_INLINE int PyThread_tss_create(Py_tss_t *key) { + *key = PyThread_create_key(); + return 0; +} +static CYTHON_INLINE Py_tss_t * PyThread_tss_alloc(void) { + Py_tss_t *key = (Py_tss_t *)PyObject_Malloc(sizeof(Py_tss_t)); + *key = Py_tss_NEEDS_INIT; + return key; +} +static CYTHON_INLINE void PyThread_tss_free(Py_tss_t *key) { + PyObject_Free(key); +} +static CYTHON_INLINE int PyThread_tss_is_created(Py_tss_t *key) { + return *key != Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE void PyThread_tss_delete(Py_tss_t *key) { + PyThread_delete_key(*key); + *key = Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE int PyThread_tss_set(Py_tss_t *key, void *value) { + return PyThread_set_key_value(*key, value); +} +static CYTHON_INLINE void * PyThread_tss_get(Py_tss_t *key) { + return PyThread_get_key_value(*key); +} +#endif +#if PY_MAJOR_VERSION < 3 + #if CYTHON_COMPILING_IN_PYPY + #if PYPY_VERSION_NUM < 0x07030600 + #if defined(__cplusplus) && __cplusplus >= 201402L + [[deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")]] + #elif defined(__GNUC__) || defined(__clang__) + __attribute__ ((__deprecated__("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6"))) + #elif defined(_MSC_VER) + __declspec(deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")) + #endif + static CYTHON_INLINE int PyGILState_Check(void) { + return 0; + } + #else // PYPY_VERSION_NUM < 0x07030600 + #endif // PYPY_VERSION_NUM < 0x07030600 + #else + static CYTHON_INLINE int PyGILState_Check(void) { + PyThreadState * tstate = _PyThreadState_Current; + return tstate && (tstate == PyGILState_GetThisThreadState()); + } + #endif +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030d0000 || defined(_PyDict_NewPresized) +#define __Pyx_PyDict_NewPresized(n) ((n <= 8) ? PyDict_New() : _PyDict_NewPresized(n)) +#else +#define __Pyx_PyDict_NewPresized(n) PyDict_New() +#endif +#if PY_MAJOR_VERSION >= 3 || CYTHON_FUTURE_DIVISION + #define __Pyx_PyNumber_Divide(x,y) PyNumber_TrueDivide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceTrueDivide(x,y) +#else + #define __Pyx_PyNumber_Divide(x,y) PyNumber_Divide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceDivide(x,y) +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX > 0x030600B4 && PY_VERSION_HEX < 0x030d0000 && CYTHON_USE_UNICODE_INTERNALS +#define __Pyx_PyDict_GetItemStrWithError(dict, name) _PyDict_GetItem_KnownHash(dict, name, ((PyASCIIObject *) name)->hash) +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStr(PyObject *dict, PyObject *name) { + PyObject *res = __Pyx_PyDict_GetItemStrWithError(dict, name); + if (res == NULL) PyErr_Clear(); + return res; +} +#elif PY_MAJOR_VERSION >= 3 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07020000) +#define __Pyx_PyDict_GetItemStrWithError PyDict_GetItemWithError +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#else +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStrWithError(PyObject *dict, PyObject *name) { +#if CYTHON_COMPILING_IN_PYPY + return PyDict_GetItem(dict, name); +#else + PyDictEntry *ep; + PyDictObject *mp = (PyDictObject*) dict; + long hash = ((PyStringObject *) name)->ob_shash; + assert(hash != -1); + ep = (mp->ma_lookup)(mp, name, hash); + if (ep == NULL) { + return NULL; + } + return ep->me_value; +#endif +} +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#endif +#if CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyType_GetFlags(tp) (((PyTypeObject *)tp)->tp_flags) + #define __Pyx_PyType_HasFeature(type, feature) ((__Pyx_PyType_GetFlags(type) & (feature)) != 0) + #define __Pyx_PyObject_GetIterNextFunc(obj) (Py_TYPE(obj)->tp_iternext) +#else + #define __Pyx_PyType_GetFlags(tp) (PyType_GetFlags((PyTypeObject *)tp)) + #define __Pyx_PyType_HasFeature(type, feature) PyType_HasFeature(type, feature) + #define __Pyx_PyObject_GetIterNextFunc(obj) PyIter_Next +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_SetItemOnTypeDict(tp, k, v) PyObject_GenericSetAttr((PyObject*)tp, k, v) +#else + #define __Pyx_SetItemOnTypeDict(tp, k, v) PyDict_SetItem(tp->tp_dict, k, v) +#endif +#if CYTHON_USE_TYPE_SPECS && PY_VERSION_HEX >= 0x03080000 +#define __Pyx_PyHeapTypeObject_GC_Del(obj) {\ + PyTypeObject *type = Py_TYPE((PyObject*)obj);\ + assert(__Pyx_PyType_HasFeature(type, Py_TPFLAGS_HEAPTYPE));\ + PyObject_GC_Del(obj);\ + Py_DECREF(type);\ +} +#else +#define __Pyx_PyHeapTypeObject_GC_Del(obj) PyObject_GC_Del(obj) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define CYTHON_PEP393_ENABLED 1 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GetLength(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_ReadChar(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((void)u, 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((void)u, (0)) + #define __Pyx_PyUnicode_DATA(u) ((void*)u) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)k, PyUnicode_ReadChar((PyObject*)(d), i)) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GetLength(u)) +#elif PY_VERSION_HEX > 0x03030000 && defined(PyUnicode_KIND) + #define CYTHON_PEP393_ENABLED 1 + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_READY(op) (0) + #else + #define __Pyx_PyUnicode_READY(op) (likely(PyUnicode_IS_READY(op)) ?\ + 0 : _PyUnicode_Ready((PyObject *)(op))) + #endif + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_LENGTH(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_READ_CHAR(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) PyUnicode_MAX_CHAR_VALUE(u) + #define __Pyx_PyUnicode_KIND(u) ((int)PyUnicode_KIND(u)) + #define __Pyx_PyUnicode_DATA(u) PyUnicode_DATA(u) + #define __Pyx_PyUnicode_READ(k, d, i) PyUnicode_READ(k, d, i) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) PyUnicode_WRITE(k, d, i, (Py_UCS4) ch) + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_LENGTH(u)) + #else + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x03090000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : ((PyCompactUnicodeObject *)(u))->wstr_length)) + #else + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : PyUnicode_GET_SIZE(u))) + #endif + #endif +#else + #define CYTHON_PEP393_ENABLED 0 + #define PyUnicode_1BYTE_KIND 1 + #define PyUnicode_2BYTE_KIND 2 + #define PyUnicode_4BYTE_KIND 4 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_SIZE(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) ((Py_UCS4)(PyUnicode_AS_UNICODE(u)[i])) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((sizeof(Py_UNICODE) == 2) ? 65535U : 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((int)sizeof(Py_UNICODE)) + #define __Pyx_PyUnicode_DATA(u) ((void*)PyUnicode_AS_UNICODE(u)) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)(k), (Py_UCS4)(((Py_UNICODE*)d)[i])) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) (((void)(k)), ((Py_UNICODE*)d)[i] = (Py_UNICODE) ch) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_SIZE(u)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyUnicode_Concat(a, b) PyNumber_Add(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) PyNumber_Add(a, b) +#else + #define __Pyx_PyUnicode_Concat(a, b) PyUnicode_Concat(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) ((unlikely((a) == Py_None) || unlikely((b) == Py_None)) ?\ + PyNumber_Add(a, b) : __Pyx_PyUnicode_Concat(a, b)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #if !defined(PyUnicode_DecodeUnicodeEscape) + #define PyUnicode_DecodeUnicodeEscape(s, size, errors) PyUnicode_Decode(s, size, "unicode_escape", errors) + #endif + #if !defined(PyUnicode_Contains) || (PY_MAJOR_VERSION == 2 && PYPY_VERSION_NUM < 0x07030500) + #undef PyUnicode_Contains + #define PyUnicode_Contains(u, s) PySequence_Contains(u, s) + #endif + #if !defined(PyByteArray_Check) + #define PyByteArray_Check(obj) PyObject_TypeCheck(obj, &PyByteArray_Type) + #endif + #if !defined(PyObject_Format) + #define PyObject_Format(obj, fmt) PyObject_CallMethod(obj, "__format__", "O", fmt) + #endif +#endif +#define __Pyx_PyString_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyString_Check(b) && !PyString_CheckExact(b)))) ? PyNumber_Remainder(a, b) : __Pyx_PyString_Format(a, b)) +#define __Pyx_PyUnicode_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyUnicode_Check(b) && !PyUnicode_CheckExact(b)))) ? PyNumber_Remainder(a, b) : PyUnicode_Format(a, b)) +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyString_Format(a, b) PyUnicode_Format(a, b) +#else + #define __Pyx_PyString_Format(a, b) PyString_Format(a, b) +#endif +#if PY_MAJOR_VERSION < 3 && !defined(PyObject_ASCII) + #define PyObject_ASCII(o) PyObject_Repr(o) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBaseString_Type PyUnicode_Type + #define PyStringObject PyUnicodeObject + #define PyString_Type PyUnicode_Type + #define PyString_Check PyUnicode_Check + #define PyString_CheckExact PyUnicode_CheckExact +#ifndef PyObject_Unicode + #define PyObject_Unicode PyObject_Str +#endif +#endif +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyBaseString_Check(obj) PyUnicode_Check(obj) + #define __Pyx_PyBaseString_CheckExact(obj) PyUnicode_CheckExact(obj) +#else + #define __Pyx_PyBaseString_Check(obj) (PyString_Check(obj) || PyUnicode_Check(obj)) + #define __Pyx_PyBaseString_CheckExact(obj) (PyString_CheckExact(obj) || PyUnicode_CheckExact(obj)) +#endif +#if CYTHON_COMPILING_IN_CPYTHON + #define __Pyx_PySequence_ListKeepNew(obj)\ + (likely(PyList_CheckExact(obj) && Py_REFCNT(obj) == 1) ? __Pyx_NewRef(obj) : PySequence_List(obj)) +#else + #define __Pyx_PySequence_ListKeepNew(obj) PySequence_List(obj) +#endif +#ifndef PySet_CheckExact + #define PySet_CheckExact(obj) __Pyx_IS_TYPE(obj, &PySet_Type) +#endif +#if PY_VERSION_HEX >= 0x030900A4 + #define __Pyx_SET_REFCNT(obj, refcnt) Py_SET_REFCNT(obj, refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SET_SIZE(obj, size) +#else + #define __Pyx_SET_REFCNT(obj, refcnt) Py_REFCNT(obj) = (refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SIZE(obj) = (size) +#endif +#if CYTHON_ASSUME_SAFE_MACROS + #define __Pyx_PySequence_ITEM(o, i) PySequence_ITEM(o, i) + #define __Pyx_PySequence_SIZE(seq) Py_SIZE(seq) + #define __Pyx_PyTuple_SET_ITEM(o, i, v) (PyTuple_SET_ITEM(o, i, v), (0)) + #define __Pyx_PyList_SET_ITEM(o, i, v) (PyList_SET_ITEM(o, i, v), (0)) + #define __Pyx_PyTuple_GET_SIZE(o) PyTuple_GET_SIZE(o) + #define __Pyx_PyList_GET_SIZE(o) PyList_GET_SIZE(o) + #define __Pyx_PySet_GET_SIZE(o) PySet_GET_SIZE(o) + #define __Pyx_PyBytes_GET_SIZE(o) PyBytes_GET_SIZE(o) + #define __Pyx_PyByteArray_GET_SIZE(o) PyByteArray_GET_SIZE(o) +#else + #define __Pyx_PySequence_ITEM(o, i) PySequence_GetItem(o, i) + #define __Pyx_PySequence_SIZE(seq) PySequence_Size(seq) + #define __Pyx_PyTuple_SET_ITEM(o, i, v) PyTuple_SetItem(o, i, v) + #define __Pyx_PyList_SET_ITEM(o, i, v) PyList_SetItem(o, i, v) + #define __Pyx_PyTuple_GET_SIZE(o) PyTuple_Size(o) + #define __Pyx_PyList_GET_SIZE(o) PyList_Size(o) + #define __Pyx_PySet_GET_SIZE(o) PySet_Size(o) + #define __Pyx_PyBytes_GET_SIZE(o) PyBytes_Size(o) + #define __Pyx_PyByteArray_GET_SIZE(o) PyByteArray_Size(o) +#endif +#if PY_VERSION_HEX >= 0x030d00A1 + #define __Pyx_PyImport_AddModuleRef(name) PyImport_AddModuleRef(name) +#else + static CYTHON_INLINE PyObject *__Pyx_PyImport_AddModuleRef(const char *name) { + PyObject *module = PyImport_AddModule(name); + Py_XINCREF(module); + return module; + } +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyIntObject PyLongObject + #define PyInt_Type PyLong_Type + #define PyInt_Check(op) PyLong_Check(op) + #define PyInt_CheckExact(op) PyLong_CheckExact(op) + #define __Pyx_Py3Int_Check(op) PyLong_Check(op) + #define __Pyx_Py3Int_CheckExact(op) PyLong_CheckExact(op) + #define PyInt_FromString PyLong_FromString + #define PyInt_FromUnicode PyLong_FromUnicode + #define PyInt_FromLong PyLong_FromLong + #define PyInt_FromSize_t PyLong_FromSize_t + #define PyInt_FromSsize_t PyLong_FromSsize_t + #define PyInt_AsLong PyLong_AsLong + #define PyInt_AS_LONG PyLong_AS_LONG + #define PyInt_AsSsize_t PyLong_AsSsize_t + #define PyInt_AsUnsignedLongMask PyLong_AsUnsignedLongMask + #define PyInt_AsUnsignedLongLongMask PyLong_AsUnsignedLongLongMask + #define PyNumber_Int PyNumber_Long +#else + #define __Pyx_Py3Int_Check(op) (PyLong_Check(op) || PyInt_Check(op)) + #define __Pyx_Py3Int_CheckExact(op) (PyLong_CheckExact(op) || PyInt_CheckExact(op)) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBoolObject PyLongObject +#endif +#if PY_MAJOR_VERSION >= 3 && CYTHON_COMPILING_IN_PYPY + #ifndef PyUnicode_InternFromString + #define PyUnicode_InternFromString(s) PyUnicode_FromString(s) + #endif +#endif +#if PY_VERSION_HEX < 0x030200A4 + typedef long Py_hash_t; + #define __Pyx_PyInt_FromHash_t PyInt_FromLong + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsHash_t +#else + #define __Pyx_PyInt_FromHash_t PyInt_FromSsize_t + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsSsize_t +#endif +#if CYTHON_USE_ASYNC_SLOTS + #if PY_VERSION_HEX >= 0x030500B1 + #define __Pyx_PyAsyncMethodsStruct PyAsyncMethods + #define __Pyx_PyType_AsAsync(obj) (Py_TYPE(obj)->tp_as_async) + #else + #define __Pyx_PyType_AsAsync(obj) ((__Pyx_PyAsyncMethodsStruct*) (Py_TYPE(obj)->tp_reserved)) + #endif +#else + #define __Pyx_PyType_AsAsync(obj) NULL +#endif +#ifndef __Pyx_PyAsyncMethodsStruct + typedef struct { + unaryfunc am_await; + unaryfunc am_aiter; + unaryfunc am_anext; + } __Pyx_PyAsyncMethodsStruct; +#endif + +#if defined(_WIN32) || defined(WIN32) || defined(MS_WINDOWS) + #if !defined(_USE_MATH_DEFINES) + #define _USE_MATH_DEFINES + #endif +#endif +#include +#ifdef NAN +#define __PYX_NAN() ((float) NAN) +#else +static CYTHON_INLINE float __PYX_NAN() { + float value; + memset(&value, 0xFF, sizeof(value)); + return value; +} +#endif +#if defined(__CYGWIN__) && defined(_LDBL_EQ_DBL) +#define __Pyx_truncl trunc +#else +#define __Pyx_truncl truncl +#endif + +#define __PYX_MARK_ERR_POS(f_index, lineno) \ + { __pyx_filename = __pyx_f[f_index]; (void)__pyx_filename; __pyx_lineno = lineno; (void)__pyx_lineno; __pyx_clineno = __LINE__; (void)__pyx_clineno; } +#define __PYX_ERR(f_index, lineno, Ln_error) \ + { __PYX_MARK_ERR_POS(f_index, lineno) goto Ln_error; } + +#ifdef CYTHON_EXTERN_C + #undef __PYX_EXTERN_C + #define __PYX_EXTERN_C CYTHON_EXTERN_C +#elif defined(__PYX_EXTERN_C) + #ifdef _MSC_VER + #pragma message ("Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead.") + #else + #warning Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead. + #endif +#else + #define __PYX_EXTERN_C extern "C++" +#endif + +#define __PYX_HAVE__opendbc__can__packer_pyx +#define __PYX_HAVE_API__opendbc__can__packer_pyx +/* Early includes */ +#include +#include "ios" +#include "new" +#include "stdexcept" +#include "typeinfo" +#include +#include + + #if __cplusplus >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1600) + // move should be defined for these versions of MSVC, but __cplusplus isn't set usefully + #include + + namespace cython_std { + template typename std::remove_reference::type&& move(T& t) noexcept { return std::move(t); } + template typename std::remove_reference::type&& move(T&& t) noexcept { return std::move(t); } + } + + #endif + +#include +#include +#include +#include "common_dbc.h" +#include "common.h" +#ifdef _OPENMP +#include +#endif /* _OPENMP */ + +#if defined(PYREX_WITHOUT_ASSERTIONS) && !defined(CYTHON_WITHOUT_ASSERTIONS) +#define CYTHON_WITHOUT_ASSERTIONS +#endif + +typedef struct {PyObject **p; const char *s; const Py_ssize_t n; const char* encoding; + const char is_unicode; const char is_str; const char intern; } __Pyx_StringTabEntry; + +#define __PYX_DEFAULT_STRING_ENCODING_IS_ASCII 1 +#define __PYX_DEFAULT_STRING_ENCODING_IS_UTF8 0 +#define __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT (PY_MAJOR_VERSION >= 3 && __PYX_DEFAULT_STRING_ENCODING_IS_UTF8) +#define __PYX_DEFAULT_STRING_ENCODING "ascii" +#define __Pyx_PyObject_FromString __Pyx_PyBytes_FromString +#define __Pyx_PyObject_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#define __Pyx_uchar_cast(c) ((unsigned char)c) +#define __Pyx_long_cast(x) ((long)x) +#define __Pyx_fits_Py_ssize_t(v, type, is_signed) (\ + (sizeof(type) < sizeof(Py_ssize_t)) ||\ + (sizeof(type) > sizeof(Py_ssize_t) &&\ + likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX) &&\ + (!is_signed || likely(v > (type)PY_SSIZE_T_MIN ||\ + v == (type)PY_SSIZE_T_MIN))) ||\ + (sizeof(type) == sizeof(Py_ssize_t) &&\ + (is_signed || likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX))) ) +static CYTHON_INLINE int __Pyx_is_valid_index(Py_ssize_t i, Py_ssize_t limit) { + return (size_t) i < (size_t) limit; +} +#if defined (__cplusplus) && __cplusplus >= 201103L + #include + #define __Pyx_sst_abs(value) std::abs(value) +#elif SIZEOF_INT >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) abs(value) +#elif SIZEOF_LONG >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) labs(value) +#elif defined (_MSC_VER) + #define __Pyx_sst_abs(value) ((Py_ssize_t)_abs64(value)) +#elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define __Pyx_sst_abs(value) llabs(value) +#elif defined (__GNUC__) + #define __Pyx_sst_abs(value) __builtin_llabs(value) +#else + #define __Pyx_sst_abs(value) ((value<0) ? -value : value) +#endif +static CYTHON_INLINE Py_ssize_t __Pyx_ssize_strlen(const char *s); +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject*); +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject*, Py_ssize_t* length); +static CYTHON_INLINE PyObject* __Pyx_PyByteArray_FromString(const char*); +#define __Pyx_PyByteArray_FromStringAndSize(s, l) PyByteArray_FromStringAndSize((const char*)s, l) +#define __Pyx_PyBytes_FromString PyBytes_FromString +#define __Pyx_PyBytes_FromStringAndSize PyBytes_FromStringAndSize +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char*); +#if PY_MAJOR_VERSION < 3 + #define __Pyx_PyStr_FromString __Pyx_PyBytes_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#else + #define __Pyx_PyStr_FromString __Pyx_PyUnicode_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyUnicode_FromStringAndSize +#endif +#define __Pyx_PyBytes_AsWritableString(s) ((char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableSString(s) ((signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableUString(s) ((unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsString(s) ((const char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsSString(s) ((const signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsUString(s) ((const unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyObject_AsWritableString(s) ((char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableSString(s) ((signed char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableUString(s) ((unsigned char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsSString(s) ((const signed char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsUString(s) ((const unsigned char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_FromCString(s) __Pyx_PyObject_FromString((const char*)s) +#define __Pyx_PyBytes_FromCString(s) __Pyx_PyBytes_FromString((const char*)s) +#define __Pyx_PyByteArray_FromCString(s) __Pyx_PyByteArray_FromString((const char*)s) +#define __Pyx_PyStr_FromCString(s) __Pyx_PyStr_FromString((const char*)s) +#define __Pyx_PyUnicode_FromCString(s) __Pyx_PyUnicode_FromString((const char*)s) +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const wchar_t *u) +{ + const wchar_t *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#else +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const Py_UNICODE *u) +{ + const Py_UNICODE *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#endif +#define __Pyx_PyUnicode_FromOrdinal(o) PyUnicode_FromOrdinal((int)o) +#define __Pyx_PyUnicode_FromUnicode(u) PyUnicode_FromUnicode(u, __Pyx_Py_UNICODE_strlen(u)) +#define __Pyx_PyUnicode_FromUnicodeAndLength PyUnicode_FromUnicode +#define __Pyx_PyUnicode_AsUnicode PyUnicode_AsUnicode +#define __Pyx_NewRef(obj) (Py_INCREF(obj), obj) +#define __Pyx_Owned_Py_None(b) __Pyx_NewRef(Py_None) +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b); +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject*); +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject*); +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x); +#define __Pyx_PySequence_Tuple(obj)\ + (likely(PyTuple_CheckExact(obj)) ? __Pyx_NewRef(obj) : PySequence_Tuple(obj)) +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject*); +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t); +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject*); +#if CYTHON_ASSUME_SAFE_MACROS +#define __pyx_PyFloat_AsDouble(x) (PyFloat_CheckExact(x) ? PyFloat_AS_DOUBLE(x) : PyFloat_AsDouble(x)) +#else +#define __pyx_PyFloat_AsDouble(x) PyFloat_AsDouble(x) +#endif +#define __pyx_PyFloat_AsFloat(x) ((float) __pyx_PyFloat_AsDouble(x)) +#if PY_MAJOR_VERSION >= 3 +#define __Pyx_PyNumber_Int(x) (PyLong_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Long(x)) +#else +#define __Pyx_PyNumber_Int(x) (PyInt_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Int(x)) +#endif +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_VERSION_HEX >= 0x030C00A7 + #ifndef _PyLong_SIGN_MASK + #define _PyLong_SIGN_MASK 3 + #endif + #ifndef _PyLong_NON_SIZE_BITS + #define _PyLong_NON_SIZE_BITS 3 + #endif + #define __Pyx_PyLong_Sign(x) (((PyLongObject*)x)->long_value.lv_tag & _PyLong_SIGN_MASK) + #define __Pyx_PyLong_IsNeg(x) ((__Pyx_PyLong_Sign(x) & 2) != 0) + #define __Pyx_PyLong_IsNonNeg(x) (!__Pyx_PyLong_IsNeg(x)) + #define __Pyx_PyLong_IsZero(x) (__Pyx_PyLong_Sign(x) & 1) + #define __Pyx_PyLong_IsPos(x) (__Pyx_PyLong_Sign(x) == 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) (__Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) ((Py_ssize_t) (((PyLongObject*)x)->long_value.lv_tag >> _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_SignedDigitCount(x)\ + ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * __Pyx_PyLong_DigitCount(x)) + #if defined(PyUnstable_Long_IsCompact) && defined(PyUnstable_Long_CompactValue) + #define __Pyx_PyLong_IsCompact(x) PyUnstable_Long_IsCompact((PyLongObject*) x) + #define __Pyx_PyLong_CompactValue(x) PyUnstable_Long_CompactValue((PyLongObject*) x) + #else + #define __Pyx_PyLong_IsCompact(x) (((PyLongObject*)x)->long_value.lv_tag < (2 << _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_CompactValue(x) ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * (Py_ssize_t) __Pyx_PyLong_Digits(x)[0]) + #endif + typedef Py_ssize_t __Pyx_compact_pylong; + typedef size_t __Pyx_compact_upylong; + #else + #define __Pyx_PyLong_IsNeg(x) (Py_SIZE(x) < 0) + #define __Pyx_PyLong_IsNonNeg(x) (Py_SIZE(x) >= 0) + #define __Pyx_PyLong_IsZero(x) (Py_SIZE(x) == 0) + #define __Pyx_PyLong_IsPos(x) (Py_SIZE(x) > 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) ((Py_SIZE(x) == 0) ? 0 : __Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) __Pyx_sst_abs(Py_SIZE(x)) + #define __Pyx_PyLong_SignedDigitCount(x) Py_SIZE(x) + #define __Pyx_PyLong_IsCompact(x) (Py_SIZE(x) == 0 || Py_SIZE(x) == 1 || Py_SIZE(x) == -1) + #define __Pyx_PyLong_CompactValue(x)\ + ((Py_SIZE(x) == 0) ? (sdigit) 0 : ((Py_SIZE(x) < 0) ? -(sdigit)__Pyx_PyLong_Digits(x)[0] : (sdigit)__Pyx_PyLong_Digits(x)[0])) + typedef sdigit __Pyx_compact_pylong; + typedef digit __Pyx_compact_upylong; + #endif + #if PY_VERSION_HEX >= 0x030C00A5 + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->long_value.ob_digit) + #else + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->ob_digit) + #endif +#endif +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII +#include +static int __Pyx_sys_getdefaultencoding_not_ascii; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + PyObject* ascii_chars_u = NULL; + PyObject* ascii_chars_b = NULL; + const char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + if (strcmp(default_encoding_c, "ascii") == 0) { + __Pyx_sys_getdefaultencoding_not_ascii = 0; + } else { + char ascii_chars[128]; + int c; + for (c = 0; c < 128; c++) { + ascii_chars[c] = (char) c; + } + __Pyx_sys_getdefaultencoding_not_ascii = 1; + ascii_chars_u = PyUnicode_DecodeASCII(ascii_chars, 128, NULL); + if (!ascii_chars_u) goto bad; + ascii_chars_b = PyUnicode_AsEncodedString(ascii_chars_u, default_encoding_c, NULL); + if (!ascii_chars_b || !PyBytes_Check(ascii_chars_b) || memcmp(ascii_chars, PyBytes_AS_STRING(ascii_chars_b), 128) != 0) { + PyErr_Format( + PyExc_ValueError, + "This module compiled with c_string_encoding=ascii, but default encoding '%.200s' is not a superset of ascii.", + default_encoding_c); + goto bad; + } + Py_DECREF(ascii_chars_u); + Py_DECREF(ascii_chars_b); + } + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + Py_XDECREF(ascii_chars_u); + Py_XDECREF(ascii_chars_b); + return -1; +} +#endif +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT && PY_MAJOR_VERSION >= 3 +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_DecodeUTF8(c_str, size, NULL) +#else +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_Decode(c_str, size, __PYX_DEFAULT_STRING_ENCODING, NULL) +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +#include +static char* __PYX_DEFAULT_STRING_ENCODING; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) (const char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + __PYX_DEFAULT_STRING_ENCODING = (char*) malloc(strlen(default_encoding_c) + 1); + if (!__PYX_DEFAULT_STRING_ENCODING) goto bad; + strcpy(__PYX_DEFAULT_STRING_ENCODING, default_encoding_c); + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + return -1; +} +#endif +#endif + + +/* Test for GCC > 2.95 */ +#if defined(__GNUC__) && (__GNUC__ > 2 || (__GNUC__ == 2 && (__GNUC_MINOR__ > 95))) + #define likely(x) __builtin_expect(!!(x), 1) + #define unlikely(x) __builtin_expect(!!(x), 0) +#else /* !__GNUC__ or GCC < 2.95 */ + #define likely(x) (x) + #define unlikely(x) (x) +#endif /* __GNUC__ */ +static CYTHON_INLINE void __Pyx_pretend_to_initialize(void* ptr) { (void)ptr; } + +#if !CYTHON_USE_MODULE_STATE +static PyObject *__pyx_m = NULL; +#endif +static int __pyx_lineno; +static int __pyx_clineno = 0; +static const char * __pyx_cfilenm = __FILE__; +static const char *__pyx_filename; + +/* #### Code section: filename_table ### */ + +static const char *__pyx_f[] = { + "opendbc/can/packer_pyx.pyx", + "", +}; +/* #### Code section: utility_code_proto_before_types ### */ +/* ForceInitThreads.proto */ +#ifndef __PYX_FORCE_INIT_THREADS + #define __PYX_FORCE_INIT_THREADS 0 +#endif + +/* #### Code section: numeric_typedefs ### */ +/* #### Code section: complex_type_declarations ### */ +/* #### Code section: type_declarations ### */ + +/*--- Type declarations ---*/ +struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker; + +/* "common.pxd":11 + * + * + * ctypedef unsigned int (*calc_checksum_type)(uint32_t, const Signal&, const vector[uint8_t] &) # <<<<<<<<<<<<<< + * + * cdef extern from "common_dbc.h": + */ +typedef unsigned int (*__pyx_t_7opendbc_3can_6common_calc_checksum_type)(uint32_t, struct Signal const &, std::vector const &); + +/* "opendbc/can/packer_pyx.pyx":13 + * + * + * cdef class CANPacker: # <<<<<<<<<<<<<< + * cdef: + * cpp_CANPacker *packer + */ +struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker { + PyObject_HEAD + struct __pyx_vtabstruct_7opendbc_3can_10packer_pyx_CANPacker *__pyx_vtab; + CANPacker *packer; + struct DBC const *dbc; + std::map name_to_address; +}; + + + +struct __pyx_vtabstruct_7opendbc_3can_10packer_pyx_CANPacker { + std::vector (*pack)(struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *, PyObject *, PyObject *); + PyObject *(*make_can_msg)(struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *, PyObject *, PyObject *, PyObject *, int __pyx_skip_dispatch); +}; +static struct __pyx_vtabstruct_7opendbc_3can_10packer_pyx_CANPacker *__pyx_vtabptr_7opendbc_3can_10packer_pyx_CANPacker; +/* #### Code section: utility_code_proto ### */ + +/* --- Runtime support code (head) --- */ +/* Refnanny.proto */ +#ifndef CYTHON_REFNANNY + #define CYTHON_REFNANNY 0 +#endif +#if CYTHON_REFNANNY + typedef struct { + void (*INCREF)(void*, PyObject*, Py_ssize_t); + void (*DECREF)(void*, PyObject*, Py_ssize_t); + void (*GOTREF)(void*, PyObject*, Py_ssize_t); + void (*GIVEREF)(void*, PyObject*, Py_ssize_t); + void* (*SetupContext)(const char*, Py_ssize_t, const char*); + void (*FinishContext)(void**); + } __Pyx_RefNannyAPIStruct; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNanny = NULL; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname); + #define __Pyx_RefNannyDeclarations void *__pyx_refnanny = NULL; +#ifdef WITH_THREAD + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + if (acquire_gil) {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + PyGILState_Release(__pyx_gilstate_save);\ + } else {\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + } + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } +#else + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__)) + #define __Pyx_RefNannyFinishContextNogil() __Pyx_RefNannyFinishContext() +#endif + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } + #define __Pyx_RefNannyFinishContext()\ + __Pyx_RefNanny->FinishContext(&__pyx_refnanny) + #define __Pyx_INCREF(r) __Pyx_RefNanny->INCREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_DECREF(r) __Pyx_RefNanny->DECREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GOTREF(r) __Pyx_RefNanny->GOTREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GIVEREF(r) __Pyx_RefNanny->GIVEREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_XINCREF(r) do { if((r) == NULL); else {__Pyx_INCREF(r); }} while(0) + #define __Pyx_XDECREF(r) do { if((r) == NULL); else {__Pyx_DECREF(r); }} while(0) + #define __Pyx_XGOTREF(r) do { if((r) == NULL); else {__Pyx_GOTREF(r); }} while(0) + #define __Pyx_XGIVEREF(r) do { if((r) == NULL); else {__Pyx_GIVEREF(r);}} while(0) +#else + #define __Pyx_RefNannyDeclarations + #define __Pyx_RefNannySetupContext(name, acquire_gil) + #define __Pyx_RefNannyFinishContextNogil() + #define __Pyx_RefNannyFinishContext() + #define __Pyx_INCREF(r) Py_INCREF(r) + #define __Pyx_DECREF(r) Py_DECREF(r) + #define __Pyx_GOTREF(r) + #define __Pyx_GIVEREF(r) + #define __Pyx_XINCREF(r) Py_XINCREF(r) + #define __Pyx_XDECREF(r) Py_XDECREF(r) + #define __Pyx_XGOTREF(r) + #define __Pyx_XGIVEREF(r) +#endif +#define __Pyx_Py_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; Py_XDECREF(tmp);\ + } while (0) +#define __Pyx_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_XDECREF(tmp);\ + } while (0) +#define __Pyx_DECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_DECREF(tmp);\ + } while (0) +#define __Pyx_CLEAR(r) do { PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);} while(0) +#define __Pyx_XCLEAR(r) do { if((r) != NULL) {PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);}} while(0) + +/* PyErrExceptionMatches.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_ExceptionMatches(err) __Pyx_PyErr_ExceptionMatchesInState(__pyx_tstate, err) +static CYTHON_INLINE int __Pyx_PyErr_ExceptionMatchesInState(PyThreadState* tstate, PyObject* err); +#else +#define __Pyx_PyErr_ExceptionMatches(err) PyErr_ExceptionMatches(err) +#endif + +/* PyThreadStateGet.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyThreadState_declare PyThreadState *__pyx_tstate; +#define __Pyx_PyThreadState_assign __pyx_tstate = __Pyx_PyThreadState_Current; +#if PY_VERSION_HEX >= 0x030C00A6 +#define __Pyx_PyErr_Occurred() (__pyx_tstate->current_exception != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->current_exception ? (PyObject*) Py_TYPE(__pyx_tstate->current_exception) : (PyObject*) NULL) +#else +#define __Pyx_PyErr_Occurred() (__pyx_tstate->curexc_type != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->curexc_type) +#endif +#else +#define __Pyx_PyThreadState_declare +#define __Pyx_PyThreadState_assign +#define __Pyx_PyErr_Occurred() (PyErr_Occurred() != NULL) +#define __Pyx_PyErr_CurrentExceptionType() PyErr_Occurred() +#endif + +/* PyErrFetchRestore.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_Clear() __Pyx_ErrRestore(NULL, NULL, NULL) +#define __Pyx_ErrRestoreWithState(type, value, tb) __Pyx_ErrRestoreInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) __Pyx_ErrFetchInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) __Pyx_ErrRestoreInState(__pyx_tstate, type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) __Pyx_ErrFetchInState(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb); +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A6 +#define __Pyx_PyErr_SetNone(exc) (Py_INCREF(exc), __Pyx_ErrRestore((exc), NULL, NULL)) +#else +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#endif +#else +#define __Pyx_PyErr_Clear() PyErr_Clear() +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#define __Pyx_ErrRestoreWithState(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestoreInState(tstate, type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchInState(tstate, type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) PyErr_Fetch(type, value, tb) +#endif + +/* PyObjectGetAttrStr.proto */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GetAttrStr(o,n) PyObject_GetAttr(o,n) +#endif + +/* PyObjectGetAttrStrNoError.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name); + +/* GetBuiltinName.proto */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name); + +/* TupleAndListFromArray.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n); +static CYTHON_INLINE PyObject* __Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n); +#endif + +/* IncludeStringH.proto */ +#include + +/* BytesEquals.proto */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals); + +/* UnicodeEquals.proto */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals); + +/* fastcall.proto */ +#if CYTHON_AVOID_BORROWED_REFS + #define __Pyx_Arg_VARARGS(args, i) PySequence_GetItem(args, i) +#elif CYTHON_ASSUME_SAFE_MACROS + #define __Pyx_Arg_VARARGS(args, i) PyTuple_GET_ITEM(args, i) +#else + #define __Pyx_Arg_VARARGS(args, i) PyTuple_GetItem(args, i) +#endif +#if CYTHON_AVOID_BORROWED_REFS + #define __Pyx_Arg_NewRef_VARARGS(arg) __Pyx_NewRef(arg) + #define __Pyx_Arg_XDECREF_VARARGS(arg) Py_XDECREF(arg) +#else + #define __Pyx_Arg_NewRef_VARARGS(arg) arg + #define __Pyx_Arg_XDECREF_VARARGS(arg) +#endif +#define __Pyx_NumKwargs_VARARGS(kwds) PyDict_Size(kwds) +#define __Pyx_KwValues_VARARGS(args, nargs) NULL +#define __Pyx_GetKwValue_VARARGS(kw, kwvalues, s) __Pyx_PyDict_GetItemStrWithError(kw, s) +#define __Pyx_KwargsAsDict_VARARGS(kw, kwvalues) PyDict_Copy(kw) +#if CYTHON_METH_FASTCALL + #define __Pyx_Arg_FASTCALL(args, i) args[i] + #define __Pyx_NumKwargs_FASTCALL(kwds) PyTuple_GET_SIZE(kwds) + #define __Pyx_KwValues_FASTCALL(args, nargs) ((args) + (nargs)) + static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 + CYTHON_UNUSED static PyObject *__Pyx_KwargsAsDict_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues); + #else + #define __Pyx_KwargsAsDict_FASTCALL(kw, kwvalues) _PyStack_AsDict(kwvalues, kw) + #endif + #define __Pyx_Arg_NewRef_FASTCALL(arg) arg /* no-op, __Pyx_Arg_FASTCALL is direct and this needs + to have the same reference counting */ + #define __Pyx_Arg_XDECREF_FASTCALL(arg) +#else + #define __Pyx_Arg_FASTCALL __Pyx_Arg_VARARGS + #define __Pyx_NumKwargs_FASTCALL __Pyx_NumKwargs_VARARGS + #define __Pyx_KwValues_FASTCALL __Pyx_KwValues_VARARGS + #define __Pyx_GetKwValue_FASTCALL __Pyx_GetKwValue_VARARGS + #define __Pyx_KwargsAsDict_FASTCALL __Pyx_KwargsAsDict_VARARGS + #define __Pyx_Arg_NewRef_FASTCALL(arg) __Pyx_Arg_NewRef_VARARGS(arg) + #define __Pyx_Arg_XDECREF_FASTCALL(arg) __Pyx_Arg_XDECREF_VARARGS(arg) +#endif +#if CYTHON_COMPILING_IN_CPYTHON && CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_VARARGS(args, start), stop - start) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_FASTCALL(args, start), stop - start) +#else +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) PyTuple_GetSlice(args, start, stop) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) PyTuple_GetSlice(args, start, stop) +#endif + +/* RaiseDoubleKeywords.proto */ +static void __Pyx_RaiseDoubleKeywordsError(const char* func_name, PyObject* kw_name); + +/* ParseKeywords.proto */ +static int __Pyx_ParseOptionalKeywords(PyObject *kwds, PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, PyObject *values[], Py_ssize_t num_pos_args, + const char* function_name); + +/* RaiseArgTupleInvalid.proto */ +static void __Pyx_RaiseArgtupleInvalid(const char* func_name, int exact, + Py_ssize_t num_min, Py_ssize_t num_max, Py_ssize_t num_found); + +/* MoveIfSupported.proto */ +#if CYTHON_USE_CPP_STD_MOVE + #include + #define __PYX_STD_MOVE_IF_SUPPORTED(x) std::move(x) +#else + #define __PYX_STD_MOVE_IF_SUPPORTED(x) x +#endif + +/* PyObjectFormatSimple.proto */ +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + PyObject_Format(s, f)) +#elif PY_MAJOR_VERSION < 3 + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + likely(PyString_CheckExact(s)) ? PyUnicode_FromEncodedObject(s, NULL, "strict") :\ + PyObject_Format(s, f)) +#elif CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + likely(PyLong_CheckExact(s)) ? PyLong_Type.tp_repr(s) :\ + likely(PyFloat_CheckExact(s)) ? PyFloat_Type.tp_repr(s) :\ + PyObject_Format(s, f)) +#else + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + PyObject_Format(s, f)) +#endif + +/* PyFunctionFastCall.proto */ +#if CYTHON_FAST_PYCALL +#if !CYTHON_VECTORCALL +#define __Pyx_PyFunction_FastCall(func, args, nargs)\ + __Pyx_PyFunction_FastCallDict((func), (args), (nargs), NULL) +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs); +#endif +#define __Pyx_BUILD_ASSERT_EXPR(cond)\ + (sizeof(char [1 - 2*!(cond)]) - 1) +#ifndef Py_MEMBER_SIZE +#define Py_MEMBER_SIZE(type, member) sizeof(((type *)0)->member) +#endif +#if !CYTHON_VECTORCALL +#if PY_VERSION_HEX >= 0x03080000 + #include "frameobject.h" +#if PY_VERSION_HEX >= 0x030b00a6 && !CYTHON_COMPILING_IN_LIMITED_API + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif + #define __Pxy_PyFrame_Initialize_Offsets() + #define __Pyx_PyFrame_GetLocalsplus(frame) ((frame)->f_localsplus) +#else + static size_t __pyx_pyframe_localsplus_offset = 0; + #include "frameobject.h" + #define __Pxy_PyFrame_Initialize_Offsets()\ + ((void)__Pyx_BUILD_ASSERT_EXPR(sizeof(PyFrameObject) == offsetof(PyFrameObject, f_localsplus) + Py_MEMBER_SIZE(PyFrameObject, f_localsplus)),\ + (void)(__pyx_pyframe_localsplus_offset = ((size_t)PyFrame_Type.tp_basicsize) - Py_MEMBER_SIZE(PyFrameObject, f_localsplus))) + #define __Pyx_PyFrame_GetLocalsplus(frame)\ + (assert(__pyx_pyframe_localsplus_offset), (PyObject **)(((char *)(frame)) + __pyx_pyframe_localsplus_offset)) +#endif +#endif +#endif + +/* PyObjectCall.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw); +#else +#define __Pyx_PyObject_Call(func, arg, kw) PyObject_Call(func, arg, kw) +#endif + +/* PyObjectCallMethO.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg); +#endif + +/* PyObjectFastCall.proto */ +#define __Pyx_PyObject_FastCall(func, args, nargs) __Pyx_PyObject_FastCallDict(func, args, (size_t)(nargs), NULL) +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs); + +/* PyObjectCallOneArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg); + +/* RaiseException.proto */ +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause); + +/* IterFinish.proto */ +static CYTHON_INLINE int __Pyx_IterFinish(void); + +/* PyObjectCallNoArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func); + +/* PyObjectGetMethod.proto */ +static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method); + +/* PyObjectCallMethod0.proto */ +static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name); + +/* RaiseNeedMoreValuesToUnpack.proto */ +static CYTHON_INLINE void __Pyx_RaiseNeedMoreValuesError(Py_ssize_t index); + +/* RaiseTooManyValuesToUnpack.proto */ +static CYTHON_INLINE void __Pyx_RaiseTooManyValuesError(Py_ssize_t expected); + +/* UnpackItemEndCheck.proto */ +static int __Pyx_IternextUnpackEndCheck(PyObject *retval, Py_ssize_t expected); + +/* RaiseNoneIterError.proto */ +static CYTHON_INLINE void __Pyx_RaiseNoneNotIterableError(void); + +/* UnpackTupleError.proto */ +static void __Pyx_UnpackTupleError(PyObject *, Py_ssize_t index); + +/* UnpackTuple2.proto */ +#define __Pyx_unpack_tuple2(tuple, value1, value2, is_tuple, has_known_size, decref_tuple)\ + (likely(is_tuple || PyTuple_Check(tuple)) ?\ + (likely(has_known_size || PyTuple_GET_SIZE(tuple) == 2) ?\ + __Pyx_unpack_tuple2_exact(tuple, value1, value2, decref_tuple) :\ + (__Pyx_UnpackTupleError(tuple, 2), -1)) :\ + __Pyx_unpack_tuple2_generic(tuple, value1, value2, has_known_size, decref_tuple)) +static CYTHON_INLINE int __Pyx_unpack_tuple2_exact( + PyObject* tuple, PyObject** value1, PyObject** value2, int decref_tuple); +static int __Pyx_unpack_tuple2_generic( + PyObject* tuple, PyObject** value1, PyObject** value2, int has_known_size, int decref_tuple); + +/* dict_iter.proto */ +static CYTHON_INLINE PyObject* __Pyx_dict_iterator(PyObject* dict, int is_dict, PyObject* method_name, + Py_ssize_t* p_orig_length, int* p_is_dict); +static CYTHON_INLINE int __Pyx_dict_iter_next(PyObject* dict_or_iter, Py_ssize_t orig_length, Py_ssize_t* ppos, + PyObject** pkey, PyObject** pvalue, PyObject** pitem, int is_dict); + +/* PyDictVersioning.proto */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +#define __PYX_DICT_VERSION_INIT ((PY_UINT64_T) -1) +#define __PYX_GET_DICT_VERSION(dict) (((PyDictObject*)(dict))->ma_version_tag) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var)\ + (version_var) = __PYX_GET_DICT_VERSION(dict);\ + (cache_var) = (value); +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + if (likely(__PYX_GET_DICT_VERSION(DICT) == __pyx_dict_version)) {\ + (VAR) = __pyx_dict_cached_value;\ + } else {\ + (VAR) = __pyx_dict_cached_value = (LOOKUP);\ + __pyx_dict_version = __PYX_GET_DICT_VERSION(DICT);\ + }\ +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj); +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj); +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version); +#else +#define __PYX_GET_DICT_VERSION(dict) (0) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var) +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) (VAR) = (LOOKUP); +#endif + +/* KeywordStringCheck.proto */ +static int __Pyx_CheckKeywordStrings(PyObject *kw, const char* function_name, int kw_allowed); + +/* IncludeStructmemberH.proto */ +#include + +/* FixUpExtensionType.proto */ +#if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type); +#endif + +/* ValidateBasesTuple.proto */ +#if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases); +#endif + +/* PyType_Ready.proto */ +CYTHON_UNUSED static int __Pyx_PyType_Ready(PyTypeObject *t); + +/* PyObject_GenericGetAttrNoDict.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttrNoDict PyObject_GenericGetAttr +#endif + +/* PyObject_GenericGetAttr.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttr PyObject_GenericGetAttr +#endif + +/* SetVTable.proto */ +static int __Pyx_SetVtable(PyTypeObject* typeptr , void* vtable); + +/* GetVTable.proto */ +static void* __Pyx_GetVtable(PyTypeObject *type); + +/* MergeVTables.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_MergeVtables(PyTypeObject *type); +#endif + +/* SetupReduce.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce(PyObject* type_obj); +#endif + +/* FetchSharedCythonModule.proto */ +static PyObject *__Pyx_FetchSharedCythonABIModule(void); + +/* FetchCommonType.proto */ +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type); +#else +static PyTypeObject* __Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases); +#endif + +/* PyMethodNew.proto */ +#if CYTHON_COMPILING_IN_LIMITED_API +static PyObject *__Pyx_PyMethod_New(PyObject *func, PyObject *self, PyObject *typ) { + PyObject *typesModule=NULL, *methodType=NULL, *result=NULL; + CYTHON_UNUSED_VAR(typ); + if (!self) + return __Pyx_NewRef(func); + typesModule = PyImport_ImportModule("types"); + if (!typesModule) return NULL; + methodType = PyObject_GetAttrString(typesModule, "MethodType"); + Py_DECREF(typesModule); + if (!methodType) return NULL; + result = PyObject_CallFunctionObjArgs(methodType, func, self, NULL); + Py_DECREF(methodType); + return result; +} +#elif PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_PyMethod_New(PyObject *func, PyObject *self, PyObject *typ) { + CYTHON_UNUSED_VAR(typ); + if (!self) + return __Pyx_NewRef(func); + return PyMethod_New(func, self); +} +#else + #define __Pyx_PyMethod_New PyMethod_New +#endif + +/* PyVectorcallFastCallDict.proto */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw); +#endif + +/* CythonFunctionShared.proto */ +#define __Pyx_CyFunction_USED +#define __Pyx_CYFUNCTION_STATICMETHOD 0x01 +#define __Pyx_CYFUNCTION_CLASSMETHOD 0x02 +#define __Pyx_CYFUNCTION_CCLASS 0x04 +#define __Pyx_CYFUNCTION_COROUTINE 0x08 +#define __Pyx_CyFunction_GetClosure(f)\ + (((__pyx_CyFunctionObject *) (f))->func_closure) +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_CyFunction_GetClassObj(f)\ + (((__pyx_CyFunctionObject *) (f))->func_classobj) +#else + #define __Pyx_CyFunction_GetClassObj(f)\ + ((PyObject*) ((PyCMethodObject *) (f))->mm_class) +#endif +#define __Pyx_CyFunction_SetClassObj(f, classobj)\ + __Pyx__CyFunction_SetClassObj((__pyx_CyFunctionObject *) (f), (classobj)) +#define __Pyx_CyFunction_Defaults(type, f)\ + ((type *)(((__pyx_CyFunctionObject *) (f))->defaults)) +#define __Pyx_CyFunction_SetDefaultsGetter(f, g)\ + ((__pyx_CyFunctionObject *) (f))->defaults_getter = (g) +typedef struct { +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject_HEAD + PyObject *func; +#elif PY_VERSION_HEX < 0x030900B1 + PyCFunctionObject func; +#else + PyCMethodObject func; +#endif +#if CYTHON_BACKPORT_VECTORCALL + __pyx_vectorcallfunc func_vectorcall; +#endif +#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API + PyObject *func_weakreflist; +#endif + PyObject *func_dict; + PyObject *func_name; + PyObject *func_qualname; + PyObject *func_doc; + PyObject *func_globals; + PyObject *func_code; + PyObject *func_closure; +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + PyObject *func_classobj; +#endif + void *defaults; + int defaults_pyobjects; + size_t defaults_size; + int flags; + PyObject *defaults_tuple; + PyObject *defaults_kwdict; + PyObject *(*defaults_getter)(PyObject *); + PyObject *func_annotations; + PyObject *func_is_coroutine; +} __pyx_CyFunctionObject; +#undef __Pyx_CyOrPyCFunction_Check +#define __Pyx_CyFunction_Check(obj) __Pyx_TypeCheck(obj, __pyx_CyFunctionType) +#define __Pyx_CyOrPyCFunction_Check(obj) __Pyx_TypeCheck2(obj, __pyx_CyFunctionType, &PyCFunction_Type) +#define __Pyx_CyFunction_CheckExact(obj) __Pyx_IS_TYPE(obj, __pyx_CyFunctionType) +static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc); +#undef __Pyx_IsSameCFunction +#define __Pyx_IsSameCFunction(func, cfunc) __Pyx__IsSameCyOrCFunction(func, cfunc) +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject* op, PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj); +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *m, + size_t size, + int pyobjects); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *m, + PyObject *tuple); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *m, + PyObject *dict); +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *m, + PyObject *dict); +static int __pyx_CyFunction_init(PyObject *module); +#if CYTHON_METH_FASTCALL +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +#if CYTHON_BACKPORT_VECTORCALL +#define __Pyx_CyFunction_func_vectorcall(f) (((__pyx_CyFunctionObject*)f)->func_vectorcall) +#else +#define __Pyx_CyFunction_func_vectorcall(f) (((PyCFunctionObject*)f)->vectorcall) +#endif +#endif + +/* CythonFunction.proto */ +static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); + +/* CLineInTraceback.proto */ +#ifdef CYTHON_CLINE_IN_TRACEBACK +#define __Pyx_CLineForTraceback(tstate, c_line) (((CYTHON_CLINE_IN_TRACEBACK)) ? c_line : 0) +#else +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line); +#endif + +/* CodeObjectCache.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +typedef struct { + PyCodeObject* code_object; + int code_line; +} __Pyx_CodeObjectCacheEntry; +struct __Pyx_CodeObjectCache { + int count; + int max_count; + __Pyx_CodeObjectCacheEntry* entries; +}; +static struct __Pyx_CodeObjectCache __pyx_code_cache = {0,0,NULL}; +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line); +static PyCodeObject *__pyx_find_code_object(int code_line); +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object); +#endif + +/* AddTraceback.proto */ +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename); + +/* None.proto */ +#include + +/* CppExceptionConversion.proto */ +#ifndef __Pyx_CppExn2PyErr +#include +#include +#include +#include +static void __Pyx_CppExn2PyErr() { + try { + if (PyErr_Occurred()) + ; // let the latest Python exn pass through and ignore the current one + else + throw; + } catch (const std::bad_alloc& exn) { + PyErr_SetString(PyExc_MemoryError, exn.what()); + } catch (const std::bad_cast& exn) { + PyErr_SetString(PyExc_TypeError, exn.what()); + } catch (const std::bad_typeid& exn) { + PyErr_SetString(PyExc_TypeError, exn.what()); + } catch (const std::domain_error& exn) { + PyErr_SetString(PyExc_ValueError, exn.what()); + } catch (const std::invalid_argument& exn) { + PyErr_SetString(PyExc_ValueError, exn.what()); + } catch (const std::ios_base::failure& exn) { + PyErr_SetString(PyExc_IOError, exn.what()); + } catch (const std::out_of_range& exn) { + PyErr_SetString(PyExc_IndexError, exn.what()); + } catch (const std::overflow_error& exn) { + PyErr_SetString(PyExc_OverflowError, exn.what()); + } catch (const std::range_error& exn) { + PyErr_SetString(PyExc_ArithmeticError, exn.what()); + } catch (const std::underflow_error& exn) { + PyErr_SetString(PyExc_ArithmeticError, exn.what()); + } catch (const std::exception& exn) { + PyErr_SetString(PyExc_RuntimeError, exn.what()); + } + catch (...) + { + PyErr_SetString(PyExc_RuntimeError, "Unknown exception"); + } +} +#endif + +/* GCCDiagnostics.proto */ +#if !defined(__INTEL_COMPILER) && defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 6)) +#define __Pyx_HAS_GCC_DIAGNOSTIC +#endif + +/* CIntFromPy.proto */ +static CYTHON_INLINE size_t __Pyx_PyInt_As_size_t(PyObject *); + +/* CIntFromPy.proto */ +static CYTHON_INLINE uint32_t __Pyx_PyInt_As_uint32_t(PyObject *); + +/* CIntFromPy.proto */ +static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_int(int value); + +/* FormatTypeName.proto */ +#if CYTHON_COMPILING_IN_LIMITED_API +typedef PyObject *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%U" +static __Pyx_TypeName __Pyx_PyType_GetName(PyTypeObject* tp); +#define __Pyx_DECREF_TypeName(obj) Py_XDECREF(obj) +#else +typedef const char *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%.200s" +#define __Pyx_PyType_GetName(tp) ((tp)->tp_name) +#define __Pyx_DECREF_TypeName(obj) +#endif + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value); + +/* CIntFromPy.proto */ +static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *); + +/* FastTypeChecks.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_TypeCheck(obj, type) __Pyx_IsSubtype(Py_TYPE(obj), (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) __Pyx_IsAnySubtype2(Py_TYPE(obj), (PyTypeObject *)type1, (PyTypeObject *)type2) +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches(PyObject *err, PyObject *type); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches2(PyObject *err, PyObject *type1, PyObject *type2); +#else +#define __Pyx_TypeCheck(obj, type) PyObject_TypeCheck(obj, (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) (PyObject_TypeCheck(obj, (PyTypeObject *)type1) || PyObject_TypeCheck(obj, (PyTypeObject *)type2)) +#define __Pyx_PyErr_GivenExceptionMatches(err, type) PyErr_GivenExceptionMatches(err, type) +#define __Pyx_PyErr_GivenExceptionMatches2(err, type1, type2) (PyErr_GivenExceptionMatches(err, type1) || PyErr_GivenExceptionMatches(err, type2)) +#endif +#define __Pyx_PyErr_ExceptionMatches2(err1, err2) __Pyx_PyErr_GivenExceptionMatches2(__Pyx_PyErr_CurrentExceptionType(), err1, err2) +#define __Pyx_PyException_Check(obj) __Pyx_TypeCheck(obj, PyExc_Exception) + +/* CheckBinaryVersion.proto */ +static unsigned long __Pyx_get_runtime_version(void); +static int __Pyx_check_binary_version(unsigned long ct_version, unsigned long rt_version, int allow_newer); + +/* InitStrings.proto */ +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t); + +/* #### Code section: module_declarations ### */ +static std::vector __pyx_f_7opendbc_3can_10packer_pyx_9CANPacker_pack(struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *__pyx_v_self, PyObject *__pyx_v_addr, PyObject *__pyx_v_values); /* proto*/ +static PyObject *__pyx_f_7opendbc_3can_10packer_pyx_9CANPacker_make_can_msg(struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *__pyx_v_self, PyObject *__pyx_v_name_or_addr, PyObject *__pyx_v_bus, PyObject *__pyx_v_values, int __pyx_skip_dispatch); /* proto*/ + +/* Module declarations from "libc.stdint" */ + +/* Module declarations from "libcpp.vector" */ + +/* Module declarations from "libcpp.utility" */ + +/* Module declarations from "libcpp.map" */ + +/* Module declarations from "libc.string" */ + +/* Module declarations from "libcpp.string" */ + +/* Module declarations from "libcpp" */ + +/* Module declarations from "libcpp.pair" */ + +/* Module declarations from "opendbc.can.common" */ + +/* Module declarations from "opendbc.can.packer_pyx" */ +static std::string __pyx_convert_string_from_py_std__in_string(PyObject *); /*proto*/ +/* #### Code section: typeinfo ### */ +/* #### Code section: before_global_var ### */ +#define __Pyx_MODULE_NAME "opendbc.can.packer_pyx" +extern int __pyx_module_is_main_opendbc__can__packer_pyx; +int __pyx_module_is_main_opendbc__can__packer_pyx = 0; + +/* Implementation of "opendbc.can.packer_pyx" */ +/* #### Code section: global_var ### */ +static PyObject *__pyx_builtin_RuntimeError; +static PyObject *__pyx_builtin_range; +static PyObject *__pyx_builtin_TypeError; +/* #### Code section: string_decls ### */ +static const char __pyx_k__7[] = "?"; +static const char __pyx_k_gc[] = "gc"; +static const char __pyx_k_bus[] = "bus"; +static const char __pyx_k_main[] = "__main__"; +static const char __pyx_k_name[] = "__name__"; +static const char __pyx_k_self[] = "self"; +static const char __pyx_k_test[] = "__test__"; +static const char __pyx_k_utf8[] = "utf8"; +static const char __pyx_k_range[] = "range"; +static const char __pyx_k_enable[] = "enable"; +static const char __pyx_k_encode[] = "encode"; +static const char __pyx_k_reduce[] = "__reduce__"; +static const char __pyx_k_values[] = "values"; +static const char __pyx_k_disable[] = "disable"; +static const char __pyx_k_dbc_name[] = "dbc_name"; +static const char __pyx_k_getstate[] = "__getstate__"; +static const char __pyx_k_setstate[] = "__setstate__"; +static const char __pyx_k_CANPacker[] = "CANPacker"; +static const char __pyx_k_TypeError[] = "TypeError"; +static const char __pyx_k_isenabled[] = "isenabled"; +static const char __pyx_k_iteritems[] = "iteritems"; +static const char __pyx_k_pyx_state[] = "__pyx_state"; +static const char __pyx_k_reduce_ex[] = "__reduce_ex__"; +static const char __pyx_k_pyx_vtable[] = "__pyx_vtable__"; +static const char __pyx_k_Can_t_lookup[] = "Can't lookup "; +static const char __pyx_k_RuntimeError[] = "RuntimeError"; +static const char __pyx_k_is_coroutine[] = "_is_coroutine"; +static const char __pyx_k_make_can_msg[] = "make_can_msg"; +static const char __pyx_k_name_or_addr[] = "name_or_addr"; +static const char __pyx_k_stringsource[] = ""; +static const char __pyx_k_reduce_cython[] = "__reduce_cython__"; +static const char __pyx_k_setstate_cython[] = "__setstate_cython__"; +static const char __pyx_k_asyncio_coroutines[] = "asyncio.coroutines"; +static const char __pyx_k_cline_in_traceback[] = "cline_in_traceback"; +static const char __pyx_k_CANPacker_make_can_msg[] = "CANPacker.make_can_msg"; +static const char __pyx_k_opendbc_can_packer_pyx[] = "opendbc.can.packer_pyx"; +static const char __pyx_k_CANPacker___reduce_cython[] = "CANPacker.__reduce_cython__"; +static const char __pyx_k_opendbc_can_packer_pyx_pyx[] = "opendbc/can/packer_pyx.pyx"; +static const char __pyx_k_CANPacker___setstate_cython[] = "CANPacker.__setstate_cython__"; +static const char __pyx_k_self_dbc_self_packer_cannot_be_c[] = "self.dbc,self.packer cannot be converted to a Python object for pickling"; +/* #### Code section: decls ### */ +static int __pyx_pf_7opendbc_3can_10packer_pyx_9CANPacker___init__(struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *__pyx_v_self, PyObject *__pyx_v_dbc_name); /* proto */ +static void __pyx_pf_7opendbc_3can_10packer_pyx_9CANPacker_2__dealloc__(struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_7opendbc_3can_10packer_pyx_9CANPacker_4make_can_msg(struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *__pyx_v_self, PyObject *__pyx_v_name_or_addr, PyObject *__pyx_v_bus, PyObject *__pyx_v_values); /* proto */ +static PyObject *__pyx_pf_7opendbc_3can_10packer_pyx_9CANPacker_6__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_7opendbc_3can_10packer_pyx_9CANPacker_8__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_tp_new_7opendbc_3can_10packer_pyx_CANPacker(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +/* #### Code section: late_includes ### */ +/* #### Code section: module_state ### */ +typedef struct { + PyObject *__pyx_d; + PyObject *__pyx_b; + PyObject *__pyx_cython_runtime; + PyObject *__pyx_empty_tuple; + PyObject *__pyx_empty_bytes; + PyObject *__pyx_empty_unicode; + #ifdef __Pyx_CyFunction_USED + PyTypeObject *__pyx_CyFunctionType; + #endif + #ifdef __Pyx_FusedFunction_USED + PyTypeObject *__pyx_FusedFunctionType; + #endif + #ifdef __Pyx_Generator_USED + PyTypeObject *__pyx_GeneratorType; + #endif + #ifdef __Pyx_IterableCoroutine_USED + PyTypeObject *__pyx_IterableCoroutineType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineAwaitType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineType; + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + PyObject *__pyx_type_7opendbc_3can_10packer_pyx_CANPacker; + #endif + PyTypeObject *__pyx_ptype_7opendbc_3can_10packer_pyx_CANPacker; + PyObject *__pyx_n_s_CANPacker; + PyObject *__pyx_n_s_CANPacker___reduce_cython; + PyObject *__pyx_n_s_CANPacker___setstate_cython; + PyObject *__pyx_n_s_CANPacker_make_can_msg; + PyObject *__pyx_kp_u_Can_t_lookup; + PyObject *__pyx_n_s_RuntimeError; + PyObject *__pyx_n_s_TypeError; + PyObject *__pyx_n_s__7; + PyObject *__pyx_n_s_asyncio_coroutines; + PyObject *__pyx_n_s_bus; + PyObject *__pyx_n_s_cline_in_traceback; + PyObject *__pyx_n_s_dbc_name; + PyObject *__pyx_kp_u_disable; + PyObject *__pyx_kp_u_enable; + PyObject *__pyx_n_s_encode; + PyObject *__pyx_kp_u_gc; + PyObject *__pyx_n_s_getstate; + PyObject *__pyx_n_s_is_coroutine; + PyObject *__pyx_kp_u_isenabled; + PyObject *__pyx_n_s_iteritems; + PyObject *__pyx_n_s_main; + PyObject *__pyx_n_s_make_can_msg; + PyObject *__pyx_n_s_name; + PyObject *__pyx_n_s_name_or_addr; + PyObject *__pyx_n_s_opendbc_can_packer_pyx; + PyObject *__pyx_kp_s_opendbc_can_packer_pyx_pyx; + PyObject *__pyx_n_s_pyx_state; + PyObject *__pyx_n_s_pyx_vtable; + PyObject *__pyx_n_s_range; + PyObject *__pyx_n_s_reduce; + PyObject *__pyx_n_s_reduce_cython; + PyObject *__pyx_n_s_reduce_ex; + PyObject *__pyx_n_s_self; + PyObject *__pyx_kp_s_self_dbc_self_packer_cannot_be_c; + PyObject *__pyx_n_s_setstate; + PyObject *__pyx_n_s_setstate_cython; + PyObject *__pyx_kp_s_stringsource; + PyObject *__pyx_n_s_test; + PyObject *__pyx_n_u_utf8; + PyObject *__pyx_n_s_values; + PyObject *__pyx_int_0; + PyObject *__pyx_tuple_; + PyObject *__pyx_tuple__3; + PyObject *__pyx_tuple__5; + PyObject *__pyx_codeobj__2; + PyObject *__pyx_codeobj__4; + PyObject *__pyx_codeobj__6; +} __pyx_mstate; + +#if CYTHON_USE_MODULE_STATE +#ifdef __cplusplus +namespace { + extern struct PyModuleDef __pyx_moduledef; +} /* anonymous namespace */ +#else +static struct PyModuleDef __pyx_moduledef; +#endif + +#define __pyx_mstate(o) ((__pyx_mstate *)__Pyx_PyModule_GetState(o)) + +#define __pyx_mstate_global (__pyx_mstate(PyState_FindModule(&__pyx_moduledef))) + +#define __pyx_m (PyState_FindModule(&__pyx_moduledef)) +#else +static __pyx_mstate __pyx_mstate_global_static = +#ifdef __cplusplus + {}; +#else + {0}; +#endif +static __pyx_mstate *__pyx_mstate_global = &__pyx_mstate_global_static; +#endif +/* #### Code section: module_state_clear ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_clear(PyObject *m) { + __pyx_mstate *clear_module_state = __pyx_mstate(m); + if (!clear_module_state) return 0; + Py_CLEAR(clear_module_state->__pyx_d); + Py_CLEAR(clear_module_state->__pyx_b); + Py_CLEAR(clear_module_state->__pyx_cython_runtime); + Py_CLEAR(clear_module_state->__pyx_empty_tuple); + Py_CLEAR(clear_module_state->__pyx_empty_bytes); + Py_CLEAR(clear_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_CLEAR(clear_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_CLEAR(clear_module_state->__pyx_FusedFunctionType); + #endif + Py_CLEAR(clear_module_state->__pyx_ptype_7opendbc_3can_10packer_pyx_CANPacker); + Py_CLEAR(clear_module_state->__pyx_type_7opendbc_3can_10packer_pyx_CANPacker); + Py_CLEAR(clear_module_state->__pyx_n_s_CANPacker); + Py_CLEAR(clear_module_state->__pyx_n_s_CANPacker___reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_CANPacker___setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_CANPacker_make_can_msg); + Py_CLEAR(clear_module_state->__pyx_kp_u_Can_t_lookup); + Py_CLEAR(clear_module_state->__pyx_n_s_RuntimeError); + Py_CLEAR(clear_module_state->__pyx_n_s_TypeError); + Py_CLEAR(clear_module_state->__pyx_n_s__7); + Py_CLEAR(clear_module_state->__pyx_n_s_asyncio_coroutines); + Py_CLEAR(clear_module_state->__pyx_n_s_bus); + Py_CLEAR(clear_module_state->__pyx_n_s_cline_in_traceback); + Py_CLEAR(clear_module_state->__pyx_n_s_dbc_name); + Py_CLEAR(clear_module_state->__pyx_kp_u_disable); + Py_CLEAR(clear_module_state->__pyx_kp_u_enable); + Py_CLEAR(clear_module_state->__pyx_n_s_encode); + Py_CLEAR(clear_module_state->__pyx_kp_u_gc); + Py_CLEAR(clear_module_state->__pyx_n_s_getstate); + Py_CLEAR(clear_module_state->__pyx_n_s_is_coroutine); + Py_CLEAR(clear_module_state->__pyx_kp_u_isenabled); + Py_CLEAR(clear_module_state->__pyx_n_s_iteritems); + Py_CLEAR(clear_module_state->__pyx_n_s_main); + Py_CLEAR(clear_module_state->__pyx_n_s_make_can_msg); + Py_CLEAR(clear_module_state->__pyx_n_s_name); + Py_CLEAR(clear_module_state->__pyx_n_s_name_or_addr); + Py_CLEAR(clear_module_state->__pyx_n_s_opendbc_can_packer_pyx); + Py_CLEAR(clear_module_state->__pyx_kp_s_opendbc_can_packer_pyx_pyx); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_state); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_vtable); + Py_CLEAR(clear_module_state->__pyx_n_s_range); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_ex); + Py_CLEAR(clear_module_state->__pyx_n_s_self); + Py_CLEAR(clear_module_state->__pyx_kp_s_self_dbc_self_packer_cannot_be_c); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate_cython); + Py_CLEAR(clear_module_state->__pyx_kp_s_stringsource); + Py_CLEAR(clear_module_state->__pyx_n_s_test); + Py_CLEAR(clear_module_state->__pyx_n_u_utf8); + Py_CLEAR(clear_module_state->__pyx_n_s_values); + Py_CLEAR(clear_module_state->__pyx_int_0); + Py_CLEAR(clear_module_state->__pyx_tuple_); + Py_CLEAR(clear_module_state->__pyx_tuple__3); + Py_CLEAR(clear_module_state->__pyx_tuple__5); + Py_CLEAR(clear_module_state->__pyx_codeobj__2); + Py_CLEAR(clear_module_state->__pyx_codeobj__4); + Py_CLEAR(clear_module_state->__pyx_codeobj__6); + return 0; +} +#endif +/* #### Code section: module_state_traverse ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { + __pyx_mstate *traverse_module_state = __pyx_mstate(m); + if (!traverse_module_state) return 0; + Py_VISIT(traverse_module_state->__pyx_d); + Py_VISIT(traverse_module_state->__pyx_b); + Py_VISIT(traverse_module_state->__pyx_cython_runtime); + Py_VISIT(traverse_module_state->__pyx_empty_tuple); + Py_VISIT(traverse_module_state->__pyx_empty_bytes); + Py_VISIT(traverse_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_VISIT(traverse_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_VISIT(traverse_module_state->__pyx_FusedFunctionType); + #endif + Py_VISIT(traverse_module_state->__pyx_ptype_7opendbc_3can_10packer_pyx_CANPacker); + Py_VISIT(traverse_module_state->__pyx_type_7opendbc_3can_10packer_pyx_CANPacker); + Py_VISIT(traverse_module_state->__pyx_n_s_CANPacker); + Py_VISIT(traverse_module_state->__pyx_n_s_CANPacker___reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_CANPacker___setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_CANPacker_make_can_msg); + Py_VISIT(traverse_module_state->__pyx_kp_u_Can_t_lookup); + Py_VISIT(traverse_module_state->__pyx_n_s_RuntimeError); + Py_VISIT(traverse_module_state->__pyx_n_s_TypeError); + Py_VISIT(traverse_module_state->__pyx_n_s__7); + Py_VISIT(traverse_module_state->__pyx_n_s_asyncio_coroutines); + Py_VISIT(traverse_module_state->__pyx_n_s_bus); + Py_VISIT(traverse_module_state->__pyx_n_s_cline_in_traceback); + Py_VISIT(traverse_module_state->__pyx_n_s_dbc_name); + Py_VISIT(traverse_module_state->__pyx_kp_u_disable); + Py_VISIT(traverse_module_state->__pyx_kp_u_enable); + Py_VISIT(traverse_module_state->__pyx_n_s_encode); + Py_VISIT(traverse_module_state->__pyx_kp_u_gc); + Py_VISIT(traverse_module_state->__pyx_n_s_getstate); + Py_VISIT(traverse_module_state->__pyx_n_s_is_coroutine); + Py_VISIT(traverse_module_state->__pyx_kp_u_isenabled); + Py_VISIT(traverse_module_state->__pyx_n_s_iteritems); + Py_VISIT(traverse_module_state->__pyx_n_s_main); + Py_VISIT(traverse_module_state->__pyx_n_s_make_can_msg); + Py_VISIT(traverse_module_state->__pyx_n_s_name); + Py_VISIT(traverse_module_state->__pyx_n_s_name_or_addr); + Py_VISIT(traverse_module_state->__pyx_n_s_opendbc_can_packer_pyx); + Py_VISIT(traverse_module_state->__pyx_kp_s_opendbc_can_packer_pyx_pyx); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_state); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_vtable); + Py_VISIT(traverse_module_state->__pyx_n_s_range); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_ex); + Py_VISIT(traverse_module_state->__pyx_n_s_self); + Py_VISIT(traverse_module_state->__pyx_kp_s_self_dbc_self_packer_cannot_be_c); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate_cython); + Py_VISIT(traverse_module_state->__pyx_kp_s_stringsource); + Py_VISIT(traverse_module_state->__pyx_n_s_test); + Py_VISIT(traverse_module_state->__pyx_n_u_utf8); + Py_VISIT(traverse_module_state->__pyx_n_s_values); + Py_VISIT(traverse_module_state->__pyx_int_0); + Py_VISIT(traverse_module_state->__pyx_tuple_); + Py_VISIT(traverse_module_state->__pyx_tuple__3); + Py_VISIT(traverse_module_state->__pyx_tuple__5); + Py_VISIT(traverse_module_state->__pyx_codeobj__2); + Py_VISIT(traverse_module_state->__pyx_codeobj__4); + Py_VISIT(traverse_module_state->__pyx_codeobj__6); + return 0; +} +#endif +/* #### Code section: module_state_defines ### */ +#define __pyx_d __pyx_mstate_global->__pyx_d +#define __pyx_b __pyx_mstate_global->__pyx_b +#define __pyx_cython_runtime __pyx_mstate_global->__pyx_cython_runtime +#define __pyx_empty_tuple __pyx_mstate_global->__pyx_empty_tuple +#define __pyx_empty_bytes __pyx_mstate_global->__pyx_empty_bytes +#define __pyx_empty_unicode __pyx_mstate_global->__pyx_empty_unicode +#ifdef __Pyx_CyFunction_USED +#define __pyx_CyFunctionType __pyx_mstate_global->__pyx_CyFunctionType +#endif +#ifdef __Pyx_FusedFunction_USED +#define __pyx_FusedFunctionType __pyx_mstate_global->__pyx_FusedFunctionType +#endif +#ifdef __Pyx_Generator_USED +#define __pyx_GeneratorType __pyx_mstate_global->__pyx_GeneratorType +#endif +#ifdef __Pyx_IterableCoroutine_USED +#define __pyx_IterableCoroutineType __pyx_mstate_global->__pyx_IterableCoroutineType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineAwaitType __pyx_mstate_global->__pyx_CoroutineAwaitType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineType __pyx_mstate_global->__pyx_CoroutineType +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#define __pyx_type_7opendbc_3can_10packer_pyx_CANPacker __pyx_mstate_global->__pyx_type_7opendbc_3can_10packer_pyx_CANPacker +#endif +#define __pyx_ptype_7opendbc_3can_10packer_pyx_CANPacker __pyx_mstate_global->__pyx_ptype_7opendbc_3can_10packer_pyx_CANPacker +#define __pyx_n_s_CANPacker __pyx_mstate_global->__pyx_n_s_CANPacker +#define __pyx_n_s_CANPacker___reduce_cython __pyx_mstate_global->__pyx_n_s_CANPacker___reduce_cython +#define __pyx_n_s_CANPacker___setstate_cython __pyx_mstate_global->__pyx_n_s_CANPacker___setstate_cython +#define __pyx_n_s_CANPacker_make_can_msg __pyx_mstate_global->__pyx_n_s_CANPacker_make_can_msg +#define __pyx_kp_u_Can_t_lookup __pyx_mstate_global->__pyx_kp_u_Can_t_lookup +#define __pyx_n_s_RuntimeError __pyx_mstate_global->__pyx_n_s_RuntimeError +#define __pyx_n_s_TypeError __pyx_mstate_global->__pyx_n_s_TypeError +#define __pyx_n_s__7 __pyx_mstate_global->__pyx_n_s__7 +#define __pyx_n_s_asyncio_coroutines __pyx_mstate_global->__pyx_n_s_asyncio_coroutines +#define __pyx_n_s_bus __pyx_mstate_global->__pyx_n_s_bus +#define __pyx_n_s_cline_in_traceback __pyx_mstate_global->__pyx_n_s_cline_in_traceback +#define __pyx_n_s_dbc_name __pyx_mstate_global->__pyx_n_s_dbc_name +#define __pyx_kp_u_disable __pyx_mstate_global->__pyx_kp_u_disable +#define __pyx_kp_u_enable __pyx_mstate_global->__pyx_kp_u_enable +#define __pyx_n_s_encode __pyx_mstate_global->__pyx_n_s_encode +#define __pyx_kp_u_gc __pyx_mstate_global->__pyx_kp_u_gc +#define __pyx_n_s_getstate __pyx_mstate_global->__pyx_n_s_getstate +#define __pyx_n_s_is_coroutine __pyx_mstate_global->__pyx_n_s_is_coroutine +#define __pyx_kp_u_isenabled __pyx_mstate_global->__pyx_kp_u_isenabled +#define __pyx_n_s_iteritems __pyx_mstate_global->__pyx_n_s_iteritems +#define __pyx_n_s_main __pyx_mstate_global->__pyx_n_s_main +#define __pyx_n_s_make_can_msg __pyx_mstate_global->__pyx_n_s_make_can_msg +#define __pyx_n_s_name __pyx_mstate_global->__pyx_n_s_name +#define __pyx_n_s_name_or_addr __pyx_mstate_global->__pyx_n_s_name_or_addr +#define __pyx_n_s_opendbc_can_packer_pyx __pyx_mstate_global->__pyx_n_s_opendbc_can_packer_pyx +#define __pyx_kp_s_opendbc_can_packer_pyx_pyx __pyx_mstate_global->__pyx_kp_s_opendbc_can_packer_pyx_pyx +#define __pyx_n_s_pyx_state __pyx_mstate_global->__pyx_n_s_pyx_state +#define __pyx_n_s_pyx_vtable __pyx_mstate_global->__pyx_n_s_pyx_vtable +#define __pyx_n_s_range __pyx_mstate_global->__pyx_n_s_range +#define __pyx_n_s_reduce __pyx_mstate_global->__pyx_n_s_reduce +#define __pyx_n_s_reduce_cython __pyx_mstate_global->__pyx_n_s_reduce_cython +#define __pyx_n_s_reduce_ex __pyx_mstate_global->__pyx_n_s_reduce_ex +#define __pyx_n_s_self __pyx_mstate_global->__pyx_n_s_self +#define __pyx_kp_s_self_dbc_self_packer_cannot_be_c __pyx_mstate_global->__pyx_kp_s_self_dbc_self_packer_cannot_be_c +#define __pyx_n_s_setstate __pyx_mstate_global->__pyx_n_s_setstate +#define __pyx_n_s_setstate_cython __pyx_mstate_global->__pyx_n_s_setstate_cython +#define __pyx_kp_s_stringsource __pyx_mstate_global->__pyx_kp_s_stringsource +#define __pyx_n_s_test __pyx_mstate_global->__pyx_n_s_test +#define __pyx_n_u_utf8 __pyx_mstate_global->__pyx_n_u_utf8 +#define __pyx_n_s_values __pyx_mstate_global->__pyx_n_s_values +#define __pyx_int_0 __pyx_mstate_global->__pyx_int_0 +#define __pyx_tuple_ __pyx_mstate_global->__pyx_tuple_ +#define __pyx_tuple__3 __pyx_mstate_global->__pyx_tuple__3 +#define __pyx_tuple__5 __pyx_mstate_global->__pyx_tuple__5 +#define __pyx_codeobj__2 __pyx_mstate_global->__pyx_codeobj__2 +#define __pyx_codeobj__4 __pyx_mstate_global->__pyx_codeobj__4 +#define __pyx_codeobj__6 __pyx_mstate_global->__pyx_codeobj__6 +/* #### Code section: module_code ### */ + +/* "string.from_py":13 + * + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: # <<<<<<<<<<<<<< + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + */ + +static std::string __pyx_convert_string_from_py_std__in_string(PyObject *__pyx_v_o) { + Py_ssize_t __pyx_v_length; + char const *__pyx_v_data; + std::string __pyx_r; + char const *__pyx_t_1; + std::string __pyx_t_2; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + + /* "string.from_py":14 + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: + * cdef Py_ssize_t length = 0 # <<<<<<<<<<<<<< + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + * return string(data, length) + */ + __pyx_v_length = 0; + + /* "string.from_py":15 + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) # <<<<<<<<<<<<<< + * return string(data, length) + * + */ + __pyx_t_1 = __Pyx_PyObject_AsStringAndSize(__pyx_v_o, (&__pyx_v_length)); if (unlikely(__pyx_t_1 == ((char const *)NULL))) __PYX_ERR(1, 15, __pyx_L1_error) + __pyx_v_data = __pyx_t_1; + + /* "string.from_py":16 + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + * return string(data, length) # <<<<<<<<<<<<<< + * + * + */ + try { + __pyx_t_2 = std::string(__pyx_v_data, __pyx_v_length); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(1, 16, __pyx_L1_error) + } + __pyx_r = __pyx_t_2; + goto __pyx_L0; + + /* "string.from_py":13 + * + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: # <<<<<<<<<<<<<< + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("string.from_py.__pyx_convert_string_from_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_pretend_to_initialize(&__pyx_r); + __pyx_L0:; + return __pyx_r; +} + +/* "opendbc/can/packer_pyx.pyx":19 + * map[string, int] name_to_address + * + * def __init__(self, dbc_name): # <<<<<<<<<<<<<< + * self.dbc = dbc_lookup(dbc_name) + * if not self.dbc: + */ + +/* Python wrapper */ +static int __pyx_pw_7opendbc_3can_10packer_pyx_9CANPacker_1__init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_pw_7opendbc_3can_10packer_pyx_9CANPacker_1__init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_dbc_name = 0; + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__init__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_dbc_name,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_dbc_name)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 19, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__init__") < 0)) __PYX_ERR(0, 19, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + } + __pyx_v_dbc_name = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__init__", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 19, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("opendbc.can.packer_pyx.CANPacker.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_7opendbc_3can_10packer_pyx_9CANPacker___init__(((struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *)__pyx_v_self), __pyx_v_dbc_name); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_7opendbc_3can_10packer_pyx_9CANPacker___init__(struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *__pyx_v_self, PyObject *__pyx_v_dbc_name) { + std::vector ::size_type __pyx_v_i; + struct Msg __pyx_v_msg; + int __pyx_r; + __Pyx_RefNannyDeclarations + std::string __pyx_t_1; + struct DBC const *__pyx_t_2; + int __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + std::vector ::size_type __pyx_t_6; + std::vector ::size_type __pyx_t_7; + std::vector ::size_type __pyx_t_8; + uint32_t __pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__init__", 1); + + /* "opendbc/can/packer_pyx.pyx":20 + * + * def __init__(self, dbc_name): + * self.dbc = dbc_lookup(dbc_name) # <<<<<<<<<<<<<< + * if not self.dbc: + * raise RuntimeError(f"Can't lookup {dbc_name}") + */ + __pyx_t_1 = __pyx_convert_string_from_py_std__in_string(__pyx_v_dbc_name); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 20, __pyx_L1_error) + try { + __pyx_t_2 = dbc_lookup(__PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_1)); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(0, 20, __pyx_L1_error) + } + __pyx_v_self->dbc = __pyx_t_2; + + /* "opendbc/can/packer_pyx.pyx":21 + * def __init__(self, dbc_name): + * self.dbc = dbc_lookup(dbc_name) + * if not self.dbc: # <<<<<<<<<<<<<< + * raise RuntimeError(f"Can't lookup {dbc_name}") + * + */ + __pyx_t_3 = (!(__pyx_v_self->dbc != 0)); + if (unlikely(__pyx_t_3)) { + + /* "opendbc/can/packer_pyx.pyx":22 + * self.dbc = dbc_lookup(dbc_name) + * if not self.dbc: + * raise RuntimeError(f"Can't lookup {dbc_name}") # <<<<<<<<<<<<<< + * + * self.packer = new cpp_CANPacker(dbc_name) + */ + __pyx_t_4 = __Pyx_PyObject_FormatSimple(__pyx_v_dbc_name, __pyx_empty_unicode); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 22, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyUnicode_Concat(__pyx_kp_u_Can_t_lookup, __pyx_t_4); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 22, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyObject_CallOneArg(__pyx_builtin_RuntimeError, __pyx_t_5); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 22, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_Raise(__pyx_t_4, 0, 0, 0); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __PYX_ERR(0, 22, __pyx_L1_error) + + /* "opendbc/can/packer_pyx.pyx":21 + * def __init__(self, dbc_name): + * self.dbc = dbc_lookup(dbc_name) + * if not self.dbc: # <<<<<<<<<<<<<< + * raise RuntimeError(f"Can't lookup {dbc_name}") + * + */ + } + + /* "opendbc/can/packer_pyx.pyx":24 + * raise RuntimeError(f"Can't lookup {dbc_name}") + * + * self.packer = new cpp_CANPacker(dbc_name) # <<<<<<<<<<<<<< + * for i in range(self.dbc[0].msgs.size()): + * msg = self.dbc[0].msgs[i] + */ + __pyx_t_1 = __pyx_convert_string_from_py_std__in_string(__pyx_v_dbc_name); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 24, __pyx_L1_error) + __pyx_v_self->packer = new CANPacker(__pyx_t_1); + + /* "opendbc/can/packer_pyx.pyx":25 + * + * self.packer = new cpp_CANPacker(dbc_name) + * for i in range(self.dbc[0].msgs.size()): # <<<<<<<<<<<<<< + * msg = self.dbc[0].msgs[i] + * self.name_to_address[string(msg.name)] = msg.address + */ + __pyx_t_6 = (__pyx_v_self->dbc[0]).msgs.size(); + __pyx_t_7 = __pyx_t_6; + for (__pyx_t_8 = 0; __pyx_t_8 < __pyx_t_7; __pyx_t_8+=1) { + __pyx_v_i = __pyx_t_8; + + /* "opendbc/can/packer_pyx.pyx":26 + * self.packer = new cpp_CANPacker(dbc_name) + * for i in range(self.dbc[0].msgs.size()): + * msg = self.dbc[0].msgs[i] # <<<<<<<<<<<<<< + * self.name_to_address[string(msg.name)] = msg.address + * + */ + __pyx_v_msg = ((__pyx_v_self->dbc[0]).msgs[__pyx_v_i]); + + /* "opendbc/can/packer_pyx.pyx":27 + * for i in range(self.dbc[0].msgs.size()): + * msg = self.dbc[0].msgs[i] + * self.name_to_address[string(msg.name)] = msg.address # <<<<<<<<<<<<<< + * + * def __dealloc__(self): + */ + __pyx_t_9 = __pyx_v_msg.address; + try { + __pyx_t_1 = std::string(__pyx_v_msg.name); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(0, 27, __pyx_L1_error) + } + (__pyx_v_self->name_to_address[__pyx_t_1]) = __pyx_t_9; + } + + /* "opendbc/can/packer_pyx.pyx":19 + * map[string, int] name_to_address + * + * def __init__(self, dbc_name): # <<<<<<<<<<<<<< + * self.dbc = dbc_lookup(dbc_name) + * if not self.dbc: + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("opendbc.can.packer_pyx.CANPacker.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "opendbc/can/packer_pyx.pyx":29 + * self.name_to_address[string(msg.name)] = msg.address + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * if self.packer: + * del self.packer + */ + +/* Python wrapper */ +static void __pyx_pw_7opendbc_3can_10packer_pyx_9CANPacker_3__dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_pw_7opendbc_3can_10packer_pyx_9CANPacker_3__dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_pf_7opendbc_3can_10packer_pyx_9CANPacker_2__dealloc__(((struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_pf_7opendbc_3can_10packer_pyx_9CANPacker_2__dealloc__(struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *__pyx_v_self) { + int __pyx_t_1; + + /* "opendbc/can/packer_pyx.pyx":30 + * + * def __dealloc__(self): + * if self.packer: # <<<<<<<<<<<<<< + * del self.packer + * + */ + __pyx_t_1 = (__pyx_v_self->packer != 0); + if (__pyx_t_1) { + + /* "opendbc/can/packer_pyx.pyx":31 + * def __dealloc__(self): + * if self.packer: + * del self.packer # <<<<<<<<<<<<<< + * + * cdef vector[uint8_t] pack(self, addr, values): + */ + delete __pyx_v_self->packer; + + /* "opendbc/can/packer_pyx.pyx":30 + * + * def __dealloc__(self): + * if self.packer: # <<<<<<<<<<<<<< + * del self.packer + * + */ + } + + /* "opendbc/can/packer_pyx.pyx":29 + * self.name_to_address[string(msg.name)] = msg.address + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * if self.packer: + * del self.packer + */ + + /* function exit code */ +} + +/* "opendbc/can/packer_pyx.pyx":33 + * del self.packer + * + * cdef vector[uint8_t] pack(self, addr, values): # <<<<<<<<<<<<<< + * cdef vector[SignalPackValue] values_thing + * values_thing.reserve(len(values)) + */ + +static std::vector __pyx_f_7opendbc_3can_10packer_pyx_9CANPacker_pack(struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *__pyx_v_self, PyObject *__pyx_v_addr, PyObject *__pyx_v_values) { + std::vector __pyx_v_values_thing; + struct SignalPackValue __pyx_v_spv; + PyObject *__pyx_v_name = NULL; + PyObject *__pyx_v_value = NULL; + std::vector __pyx_r; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + int __pyx_t_7; + PyObject *__pyx_t_8 = NULL; + std::string __pyx_t_9; + double __pyx_t_10; + uint32_t __pyx_t_11; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("pack", 1); + + /* "opendbc/can/packer_pyx.pyx":35 + * cdef vector[uint8_t] pack(self, addr, values): + * cdef vector[SignalPackValue] values_thing + * values_thing.reserve(len(values)) # <<<<<<<<<<<<<< + * cdef SignalPackValue spv + * + */ + __pyx_t_1 = PyObject_Length(__pyx_v_values); if (unlikely(__pyx_t_1 == ((Py_ssize_t)-1))) __PYX_ERR(0, 35, __pyx_L1_error) + try { + __pyx_v_values_thing.reserve(__pyx_t_1); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(0, 35, __pyx_L1_error) + } + + /* "opendbc/can/packer_pyx.pyx":38 + * cdef SignalPackValue spv + * + * for name, value in values.iteritems(): # <<<<<<<<<<<<<< + * spv.name = name.encode("utf8") + * spv.value = value + */ + __pyx_t_1 = 0; + if (unlikely(__pyx_v_values == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "iteritems"); + __PYX_ERR(0, 38, __pyx_L1_error) + } + __pyx_t_5 = __Pyx_dict_iterator(__pyx_v_values, 0, __pyx_n_s_iteritems, (&__pyx_t_3), (&__pyx_t_4)); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 38, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_2); + __pyx_t_2 = __pyx_t_5; + __pyx_t_5 = 0; + while (1) { + __pyx_t_7 = __Pyx_dict_iter_next(__pyx_t_2, __pyx_t_3, &__pyx_t_1, &__pyx_t_5, &__pyx_t_6, NULL, __pyx_t_4); + if (unlikely(__pyx_t_7 == 0)) break; + if (unlikely(__pyx_t_7 == -1)) __PYX_ERR(0, 38, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_GOTREF(__pyx_t_6); + __Pyx_XDECREF_SET(__pyx_v_name, __pyx_t_5); + __pyx_t_5 = 0; + __Pyx_XDECREF_SET(__pyx_v_value, __pyx_t_6); + __pyx_t_6 = 0; + + /* "opendbc/can/packer_pyx.pyx":39 + * + * for name, value in values.iteritems(): + * spv.name = name.encode("utf8") # <<<<<<<<<<<<<< + * spv.value = value + * values_thing.push_back(spv) + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_name, __pyx_n_s_encode); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 39, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_8 = NULL; + __pyx_t_7 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_8 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_8)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_8); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_7 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_8, __pyx_n_u_utf8}; + __pyx_t_6 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_7, 1+__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 39, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + __pyx_t_9 = __pyx_convert_string_from_py_std__in_string(__pyx_t_6); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 39, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __pyx_v_spv.name = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_9); + + /* "opendbc/can/packer_pyx.pyx":40 + * for name, value in values.iteritems(): + * spv.name = name.encode("utf8") + * spv.value = value # <<<<<<<<<<<<<< + * values_thing.push_back(spv) + * + */ + __pyx_t_10 = __pyx_PyFloat_AsDouble(__pyx_v_value); if (unlikely((__pyx_t_10 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 40, __pyx_L1_error) + __pyx_v_spv.value = __pyx_t_10; + + /* "opendbc/can/packer_pyx.pyx":41 + * spv.name = name.encode("utf8") + * spv.value = value + * values_thing.push_back(spv) # <<<<<<<<<<<<<< + * + * return self.packer.pack(addr, values_thing) + */ + try { + __pyx_v_values_thing.push_back(__pyx_v_spv); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(0, 41, __pyx_L1_error) + } + } + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "opendbc/can/packer_pyx.pyx":43 + * values_thing.push_back(spv) + * + * return self.packer.pack(addr, values_thing) # <<<<<<<<<<<<<< + * + * cpdef make_can_msg(self, name_or_addr, bus, values): + */ + __pyx_t_11 = __Pyx_PyInt_As_uint32_t(__pyx_v_addr); if (unlikely((__pyx_t_11 == ((uint32_t)-1)) && PyErr_Occurred())) __PYX_ERR(0, 43, __pyx_L1_error) + __pyx_r = __pyx_v_self->packer->pack(__pyx_t_11, __pyx_v_values_thing); + goto __pyx_L0; + + /* "opendbc/can/packer_pyx.pyx":33 + * del self.packer + * + * cdef vector[uint8_t] pack(self, addr, values): # <<<<<<<<<<<<<< + * cdef vector[SignalPackValue] values_thing + * values_thing.reserve(len(values)) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("opendbc.can.packer_pyx.CANPacker.pack", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_pretend_to_initialize(&__pyx_r); + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_name); + __Pyx_XDECREF(__pyx_v_value); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "opendbc/can/packer_pyx.pyx":45 + * return self.packer.pack(addr, values_thing) + * + * cpdef make_can_msg(self, name_or_addr, bus, values): # <<<<<<<<<<<<<< + * cdef int addr + * if isinstance(name_or_addr, int): + */ + +static PyObject *__pyx_pw_7opendbc_3can_10packer_pyx_9CANPacker_5make_can_msg(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_f_7opendbc_3can_10packer_pyx_9CANPacker_make_can_msg(struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *__pyx_v_self, PyObject *__pyx_v_name_or_addr, PyObject *__pyx_v_bus, PyObject *__pyx_v_values, int __pyx_skip_dispatch) { + int __pyx_v_addr; + std::vector __pyx_v_val; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_t_5; + int __pyx_t_6; + std::string __pyx_t_7; + std::vector __pyx_t_8; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("make_can_msg", 1); + /* Check if called by wrapper */ + if (unlikely(__pyx_skip_dispatch)) ; + /* Check if overridden in Python */ + else if (unlikely((Py_TYPE(((PyObject *)__pyx_v_self))->tp_dictoffset != 0) || __Pyx_PyType_HasFeature(Py_TYPE(((PyObject *)__pyx_v_self)), (Py_TPFLAGS_IS_ABSTRACT | Py_TPFLAGS_HEAPTYPE)))) { + #if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_PYTYPE_LOOKUP && CYTHON_USE_TYPE_SLOTS + static PY_UINT64_T __pyx_tp_dict_version = __PYX_DICT_VERSION_INIT, __pyx_obj_dict_version = __PYX_DICT_VERSION_INIT; + if (unlikely(!__Pyx_object_dict_version_matches(((PyObject *)__pyx_v_self), __pyx_tp_dict_version, __pyx_obj_dict_version))) { + PY_UINT64_T __pyx_typedict_guard = __Pyx_get_tp_dict_version(((PyObject *)__pyx_v_self)); + #endif + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_make_can_msg); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 45, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (!__Pyx_IsSameCFunction(__pyx_t_1, (void*) __pyx_pw_7opendbc_3can_10packer_pyx_9CANPacker_5make_can_msg)) { + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_t_1); + __pyx_t_3 = __pyx_t_1; __pyx_t_4 = NULL; + __pyx_t_5 = 0; + #if CYTHON_UNPACK_METHODS + if (unlikely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_5 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[4] = {__pyx_t_4, __pyx_v_name_or_addr, __pyx_v_bus, __pyx_v_values}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_5, 3+__pyx_t_5); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 45, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + goto __pyx_L0; + } + #if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_PYTYPE_LOOKUP && CYTHON_USE_TYPE_SLOTS + __pyx_tp_dict_version = __Pyx_get_tp_dict_version(((PyObject *)__pyx_v_self)); + __pyx_obj_dict_version = __Pyx_get_object_dict_version(((PyObject *)__pyx_v_self)); + if (unlikely(__pyx_typedict_guard != __pyx_tp_dict_version)) { + __pyx_tp_dict_version = __pyx_obj_dict_version = __PYX_DICT_VERSION_INIT; + } + #endif + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + #if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_PYTYPE_LOOKUP && CYTHON_USE_TYPE_SLOTS + } + #endif + } + + /* "opendbc/can/packer_pyx.pyx":47 + * cpdef make_can_msg(self, name_or_addr, bus, values): + * cdef int addr + * if isinstance(name_or_addr, int): # <<<<<<<<<<<<<< + * addr = name_or_addr + * else: + */ + __pyx_t_6 = PyInt_Check(__pyx_v_name_or_addr); + if (__pyx_t_6) { + + /* "opendbc/can/packer_pyx.pyx":48 + * cdef int addr + * if isinstance(name_or_addr, int): + * addr = name_or_addr # <<<<<<<<<<<<<< + * else: + * addr = self.name_to_address[name_or_addr.encode("utf8")] + */ + __pyx_t_5 = __Pyx_PyInt_As_int(__pyx_v_name_or_addr); if (unlikely((__pyx_t_5 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 48, __pyx_L1_error) + __pyx_v_addr = __pyx_t_5; + + /* "opendbc/can/packer_pyx.pyx":47 + * cpdef make_can_msg(self, name_or_addr, bus, values): + * cdef int addr + * if isinstance(name_or_addr, int): # <<<<<<<<<<<<<< + * addr = name_or_addr + * else: + */ + goto __pyx_L3; + } + + /* "opendbc/can/packer_pyx.pyx":50 + * addr = name_or_addr + * else: + * addr = self.name_to_address[name_or_addr.encode("utf8")] # <<<<<<<<<<<<<< + * + * cdef vector[uint8_t] val = self.pack(addr, values) + */ + /*else*/ { + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_name_or_addr, __pyx_n_s_encode); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 50, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_5 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_5 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_n_u_utf8}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_5, 1+__pyx_t_5); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 50, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_t_7 = __pyx_convert_string_from_py_std__in_string(__pyx_t_1); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 50, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_addr = (__pyx_v_self->name_to_address[__pyx_t_7]); + } + __pyx_L3:; + + /* "opendbc/can/packer_pyx.pyx":52 + * addr = self.name_to_address[name_or_addr.encode("utf8")] + * + * cdef vector[uint8_t] val = self.pack(addr, values) # <<<<<<<<<<<<<< + * return [addr, 0, (&val[0])[:val.size()], bus] + */ + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_addr); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 52, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_8 = ((struct __pyx_vtabstruct_7opendbc_3can_10packer_pyx_CANPacker *)__pyx_v_self->__pyx_vtab)->pack(__pyx_v_self, __pyx_t_1, __pyx_v_values); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 52, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_val = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_8); + + /* "opendbc/can/packer_pyx.pyx":53 + * + * cdef vector[uint8_t] val = self.pack(addr, values) + * return [addr, 0, (&val[0])[:val.size()], bus] # <<<<<<<<<<<<<< + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_addr); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 53, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyBytes_FromStringAndSize(((char *)(&(__pyx_v_val[0]))) + 0, __pyx_v_val.size() - 0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 53, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyList_New(4); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 53, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyList_SET_ITEM(__pyx_t_3, 0, __pyx_t_1)) __PYX_ERR(0, 53, __pyx_L1_error); + __Pyx_INCREF(__pyx_int_0); + __Pyx_GIVEREF(__pyx_int_0); + if (__Pyx_PyList_SET_ITEM(__pyx_t_3, 1, __pyx_int_0)) __PYX_ERR(0, 53, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyList_SET_ITEM(__pyx_t_3, 2, __pyx_t_2)) __PYX_ERR(0, 53, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_bus); + __Pyx_GIVEREF(__pyx_v_bus); + if (__Pyx_PyList_SET_ITEM(__pyx_t_3, 3, __pyx_v_bus)) __PYX_ERR(0, 53, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_2 = 0; + __pyx_r = __pyx_t_3; + __pyx_t_3 = 0; + goto __pyx_L0; + + /* "opendbc/can/packer_pyx.pyx":45 + * return self.packer.pack(addr, values_thing) + * + * cpdef make_can_msg(self, name_or_addr, bus, values): # <<<<<<<<<<<<<< + * cdef int addr + * if isinstance(name_or_addr, int): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("opendbc.can.packer_pyx.CANPacker.make_can_msg", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* Python wrapper */ +static PyObject *__pyx_pw_7opendbc_3can_10packer_pyx_9CANPacker_5make_can_msg(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7opendbc_3can_10packer_pyx_9CANPacker_5make_can_msg = {"make_can_msg", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7opendbc_3can_10packer_pyx_9CANPacker_5make_can_msg, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7opendbc_3can_10packer_pyx_9CANPacker_5make_can_msg(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_name_or_addr = 0; + PyObject *__pyx_v_bus = 0; + PyObject *__pyx_v_values = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("make_can_msg (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_name_or_addr,&__pyx_n_s_bus,&__pyx_n_s_values,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_name_or_addr)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 45, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_bus)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 45, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("make_can_msg", 1, 3, 3, 1); __PYX_ERR(0, 45, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_values)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 45, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("make_can_msg", 1, 3, 3, 2); __PYX_ERR(0, 45, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "make_can_msg") < 0)) __PYX_ERR(0, 45, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + } + __pyx_v_name_or_addr = values[0]; + __pyx_v_bus = values[1]; + __pyx_v_values = values[2]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("make_can_msg", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 45, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("opendbc.can.packer_pyx.CANPacker.make_can_msg", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_7opendbc_3can_10packer_pyx_9CANPacker_4make_can_msg(((struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *)__pyx_v_self), __pyx_v_name_or_addr, __pyx_v_bus, __pyx_v_values); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7opendbc_3can_10packer_pyx_9CANPacker_4make_can_msg(struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *__pyx_v_self, PyObject *__pyx_v_name_or_addr, PyObject *__pyx_v_bus, PyObject *__pyx_v_values) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("make_can_msg", 1); + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __pyx_f_7opendbc_3can_10packer_pyx_9CANPacker_make_can_msg(__pyx_v_self, __pyx_v_name_or_addr, __pyx_v_bus, __pyx_v_values, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 45, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("opendbc.can.packer_pyx.CANPacker.make_can_msg", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.dbc,self.packer cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7opendbc_3can_10packer_pyx_9CANPacker_7__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7opendbc_3can_10packer_pyx_9CANPacker_7__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7opendbc_3can_10packer_pyx_9CANPacker_7__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7opendbc_3can_10packer_pyx_9CANPacker_7__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_7opendbc_3can_10packer_pyx_9CANPacker_6__reduce_cython__(((struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7opendbc_3can_10packer_pyx_9CANPacker_6__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "self.dbc,self.packer cannot be converted to a Python object for pickling" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "self.dbc,self.packer cannot be converted to a Python object for pickling" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_self_dbc_self_packer_cannot_be_c, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.dbc,self.packer cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("opendbc.can.packer_pyx.CANPacker.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.dbc,self.packer cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.dbc,self.packer cannot be converted to a Python object for pickling" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7opendbc_3can_10packer_pyx_9CANPacker_9__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7opendbc_3can_10packer_pyx_9CANPacker_9__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7opendbc_3can_10packer_pyx_9CANPacker_9__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7opendbc_3can_10packer_pyx_9CANPacker_9__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("opendbc.can.packer_pyx.CANPacker.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_7opendbc_3can_10packer_pyx_9CANPacker_8__setstate_cython__(((struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7opendbc_3can_10packer_pyx_9CANPacker_8__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "self.dbc,self.packer cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "self.dbc,self.packer cannot be converted to a Python object for pickling" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_self_dbc_self_packer_cannot_be_c, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.dbc,self.packer cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.dbc,self.packer cannot be converted to a Python object for pickling" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("opendbc.can.packer_pyx.CANPacker.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} +static struct __pyx_vtabstruct_7opendbc_3can_10packer_pyx_CANPacker __pyx_vtable_7opendbc_3can_10packer_pyx_CANPacker; + +static PyObject *__pyx_tp_new_7opendbc_3can_10packer_pyx_CANPacker(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { + struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *)o); + p->__pyx_vtab = __pyx_vtabptr_7opendbc_3can_10packer_pyx_CANPacker; + new((void*)&(p->name_to_address)) std::map (); + return o; +} + +static void __pyx_tp_dealloc_7opendbc_3can_10packer_pyx_CANPacker(PyObject *o) { + struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *p = (struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_7opendbc_3can_10packer_pyx_CANPacker) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_pw_7opendbc_3can_10packer_pyx_9CANPacker_3__dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + __Pyx_call_destructor(p->name_to_address); + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} + +static PyMethodDef __pyx_methods_7opendbc_3can_10packer_pyx_CANPacker[] = { + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7opendbc_3can_10packer_pyx_9CANPacker_7__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7opendbc_3can_10packer_pyx_9CANPacker_9__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_7opendbc_3can_10packer_pyx_CANPacker_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_7opendbc_3can_10packer_pyx_CANPacker}, + {Py_tp_methods, (void *)__pyx_methods_7opendbc_3can_10packer_pyx_CANPacker}, + {Py_tp_init, (void *)__pyx_pw_7opendbc_3can_10packer_pyx_9CANPacker_1__init__}, + {Py_tp_new, (void *)__pyx_tp_new_7opendbc_3can_10packer_pyx_CANPacker}, + {0, 0}, +}; +static PyType_Spec __pyx_type_7opendbc_3can_10packer_pyx_CANPacker_spec = { + "opendbc.can.packer_pyx.CANPacker", + sizeof(struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, + __pyx_type_7opendbc_3can_10packer_pyx_CANPacker_slots, +}; +#else + +static PyTypeObject __pyx_type_7opendbc_3can_10packer_pyx_CANPacker = { + PyVarObject_HEAD_INIT(0, 0) + "opendbc.can.packer_pyx.""CANPacker", /*tp_name*/ + sizeof(struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_7opendbc_3can_10packer_pyx_CANPacker, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, /*tp_flags*/ + 0, /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_7opendbc_3can_10packer_pyx_CANPacker, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + __pyx_pw_7opendbc_3can_10packer_pyx_9CANPacker_1__init__, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_7opendbc_3can_10packer_pyx_CANPacker, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyMethodDef __pyx_methods[] = { + {0, 0, 0, 0} +}; +#ifndef CYTHON_SMALL_CODE +#if defined(__clang__) + #define CYTHON_SMALL_CODE +#elif defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 3)) + #define CYTHON_SMALL_CODE __attribute__((cold)) +#else + #define CYTHON_SMALL_CODE +#endif +#endif +/* #### Code section: pystring_table ### */ + +static int __Pyx_CreateStringTabAndInitStrings(void) { + __Pyx_StringTabEntry __pyx_string_tab[] = { + {&__pyx_n_s_CANPacker, __pyx_k_CANPacker, sizeof(__pyx_k_CANPacker), 0, 0, 1, 1}, + {&__pyx_n_s_CANPacker___reduce_cython, __pyx_k_CANPacker___reduce_cython, sizeof(__pyx_k_CANPacker___reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_CANPacker___setstate_cython, __pyx_k_CANPacker___setstate_cython, sizeof(__pyx_k_CANPacker___setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_CANPacker_make_can_msg, __pyx_k_CANPacker_make_can_msg, sizeof(__pyx_k_CANPacker_make_can_msg), 0, 0, 1, 1}, + {&__pyx_kp_u_Can_t_lookup, __pyx_k_Can_t_lookup, sizeof(__pyx_k_Can_t_lookup), 0, 1, 0, 0}, + {&__pyx_n_s_RuntimeError, __pyx_k_RuntimeError, sizeof(__pyx_k_RuntimeError), 0, 0, 1, 1}, + {&__pyx_n_s_TypeError, __pyx_k_TypeError, sizeof(__pyx_k_TypeError), 0, 0, 1, 1}, + {&__pyx_n_s__7, __pyx_k__7, sizeof(__pyx_k__7), 0, 0, 1, 1}, + {&__pyx_n_s_asyncio_coroutines, __pyx_k_asyncio_coroutines, sizeof(__pyx_k_asyncio_coroutines), 0, 0, 1, 1}, + {&__pyx_n_s_bus, __pyx_k_bus, sizeof(__pyx_k_bus), 0, 0, 1, 1}, + {&__pyx_n_s_cline_in_traceback, __pyx_k_cline_in_traceback, sizeof(__pyx_k_cline_in_traceback), 0, 0, 1, 1}, + {&__pyx_n_s_dbc_name, __pyx_k_dbc_name, sizeof(__pyx_k_dbc_name), 0, 0, 1, 1}, + {&__pyx_kp_u_disable, __pyx_k_disable, sizeof(__pyx_k_disable), 0, 1, 0, 0}, + {&__pyx_kp_u_enable, __pyx_k_enable, sizeof(__pyx_k_enable), 0, 1, 0, 0}, + {&__pyx_n_s_encode, __pyx_k_encode, sizeof(__pyx_k_encode), 0, 0, 1, 1}, + {&__pyx_kp_u_gc, __pyx_k_gc, sizeof(__pyx_k_gc), 0, 1, 0, 0}, + {&__pyx_n_s_getstate, __pyx_k_getstate, sizeof(__pyx_k_getstate), 0, 0, 1, 1}, + {&__pyx_n_s_is_coroutine, __pyx_k_is_coroutine, sizeof(__pyx_k_is_coroutine), 0, 0, 1, 1}, + {&__pyx_kp_u_isenabled, __pyx_k_isenabled, sizeof(__pyx_k_isenabled), 0, 1, 0, 0}, + {&__pyx_n_s_iteritems, __pyx_k_iteritems, sizeof(__pyx_k_iteritems), 0, 0, 1, 1}, + {&__pyx_n_s_main, __pyx_k_main, sizeof(__pyx_k_main), 0, 0, 1, 1}, + {&__pyx_n_s_make_can_msg, __pyx_k_make_can_msg, sizeof(__pyx_k_make_can_msg), 0, 0, 1, 1}, + {&__pyx_n_s_name, __pyx_k_name, sizeof(__pyx_k_name), 0, 0, 1, 1}, + {&__pyx_n_s_name_or_addr, __pyx_k_name_or_addr, sizeof(__pyx_k_name_or_addr), 0, 0, 1, 1}, + {&__pyx_n_s_opendbc_can_packer_pyx, __pyx_k_opendbc_can_packer_pyx, sizeof(__pyx_k_opendbc_can_packer_pyx), 0, 0, 1, 1}, + {&__pyx_kp_s_opendbc_can_packer_pyx_pyx, __pyx_k_opendbc_can_packer_pyx_pyx, sizeof(__pyx_k_opendbc_can_packer_pyx_pyx), 0, 0, 1, 0}, + {&__pyx_n_s_pyx_state, __pyx_k_pyx_state, sizeof(__pyx_k_pyx_state), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_vtable, __pyx_k_pyx_vtable, sizeof(__pyx_k_pyx_vtable), 0, 0, 1, 1}, + {&__pyx_n_s_range, __pyx_k_range, sizeof(__pyx_k_range), 0, 0, 1, 1}, + {&__pyx_n_s_reduce, __pyx_k_reduce, sizeof(__pyx_k_reduce), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_cython, __pyx_k_reduce_cython, sizeof(__pyx_k_reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_ex, __pyx_k_reduce_ex, sizeof(__pyx_k_reduce_ex), 0, 0, 1, 1}, + {&__pyx_n_s_self, __pyx_k_self, sizeof(__pyx_k_self), 0, 0, 1, 1}, + {&__pyx_kp_s_self_dbc_self_packer_cannot_be_c, __pyx_k_self_dbc_self_packer_cannot_be_c, sizeof(__pyx_k_self_dbc_self_packer_cannot_be_c), 0, 0, 1, 0}, + {&__pyx_n_s_setstate, __pyx_k_setstate, sizeof(__pyx_k_setstate), 0, 0, 1, 1}, + {&__pyx_n_s_setstate_cython, __pyx_k_setstate_cython, sizeof(__pyx_k_setstate_cython), 0, 0, 1, 1}, + {&__pyx_kp_s_stringsource, __pyx_k_stringsource, sizeof(__pyx_k_stringsource), 0, 0, 1, 0}, + {&__pyx_n_s_test, __pyx_k_test, sizeof(__pyx_k_test), 0, 0, 1, 1}, + {&__pyx_n_u_utf8, __pyx_k_utf8, sizeof(__pyx_k_utf8), 0, 1, 0, 1}, + {&__pyx_n_s_values, __pyx_k_values, sizeof(__pyx_k_values), 0, 0, 1, 1}, + {0, 0, 0, 0, 0, 0, 0} + }; + return __Pyx_InitStrings(__pyx_string_tab); +} +/* #### Code section: cached_builtins ### */ +static CYTHON_SMALL_CODE int __Pyx_InitCachedBuiltins(void) { + __pyx_builtin_RuntimeError = __Pyx_GetBuiltinName(__pyx_n_s_RuntimeError); if (!__pyx_builtin_RuntimeError) __PYX_ERR(0, 22, __pyx_L1_error) + __pyx_builtin_range = __Pyx_GetBuiltinName(__pyx_n_s_range); if (!__pyx_builtin_range) __PYX_ERR(0, 25, __pyx_L1_error) + __pyx_builtin_TypeError = __Pyx_GetBuiltinName(__pyx_n_s_TypeError); if (!__pyx_builtin_TypeError) __PYX_ERR(1, 2, __pyx_L1_error) + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: cached_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_InitCachedConstants", 0); + + /* "opendbc/can/packer_pyx.pyx":45 + * return self.packer.pack(addr, values_thing) + * + * cpdef make_can_msg(self, name_or_addr, bus, values): # <<<<<<<<<<<<<< + * cdef int addr + * if isinstance(name_or_addr, int): + */ + __pyx_tuple_ = PyTuple_Pack(4, __pyx_n_s_self, __pyx_n_s_name_or_addr, __pyx_n_s_bus, __pyx_n_s_values); if (unlikely(!__pyx_tuple_)) __PYX_ERR(0, 45, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple_); + __Pyx_GIVEREF(__pyx_tuple_); + __pyx_codeobj__2 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 4, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple_, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_opendbc_can_packer_pyx_pyx, __pyx_n_s_make_can_msg, 45, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__2)) __PYX_ERR(0, 45, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.dbc,self.packer cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_tuple__3 = PyTuple_Pack(1, __pyx_n_s_self); if (unlikely(!__pyx_tuple__3)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__3); + __Pyx_GIVEREF(__pyx_tuple__3); + __pyx_codeobj__4 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__3, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__4)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.dbc,self.packer cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.dbc,self.packer cannot be converted to a Python object for pickling" + */ + __pyx_tuple__5 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_pyx_state); if (unlikely(!__pyx_tuple__5)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__5); + __Pyx_GIVEREF(__pyx_tuple__5); + __pyx_codeobj__6 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__5, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__6)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_RefNannyFinishContext(); + return -1; +} +/* #### Code section: init_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitConstants(void) { + if (__Pyx_CreateStringTabAndInitStrings() < 0) __PYX_ERR(0, 1, __pyx_L1_error); + __pyx_int_0 = PyInt_FromLong(0); if (unlikely(!__pyx_int_0)) __PYX_ERR(0, 1, __pyx_L1_error) + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: init_globals ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitGlobals(void) { + return 0; +} +/* #### Code section: init_module ### */ + +static CYTHON_SMALL_CODE int __Pyx_modinit_global_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_import_code(void); /*proto*/ + +static int __Pyx_modinit_global_init_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_global_init_code", 0); + /*--- Global init code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_variable_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_export_code", 0); + /*--- Variable export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_export_code", 0); + /*--- Function export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_type_init_code(void) { + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_modinit_type_init_code", 0); + /*--- Type init code ---*/ + __pyx_vtabptr_7opendbc_3can_10packer_pyx_CANPacker = &__pyx_vtable_7opendbc_3can_10packer_pyx_CANPacker; + __pyx_vtable_7opendbc_3can_10packer_pyx_CANPacker.pack = (std::vector (*)(struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *, PyObject *, PyObject *))__pyx_f_7opendbc_3can_10packer_pyx_9CANPacker_pack; + __pyx_vtable_7opendbc_3can_10packer_pyx_CANPacker.make_can_msg = (PyObject *(*)(struct __pyx_obj_7opendbc_3can_10packer_pyx_CANPacker *, PyObject *, PyObject *, PyObject *, int __pyx_skip_dispatch))__pyx_f_7opendbc_3can_10packer_pyx_9CANPacker_make_can_msg; + #if CYTHON_USE_TYPE_SPECS + __pyx_ptype_7opendbc_3can_10packer_pyx_CANPacker = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_7opendbc_3can_10packer_pyx_CANPacker_spec, NULL); if (unlikely(!__pyx_ptype_7opendbc_3can_10packer_pyx_CANPacker)) __PYX_ERR(0, 13, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_7opendbc_3can_10packer_pyx_CANPacker_spec, __pyx_ptype_7opendbc_3can_10packer_pyx_CANPacker) < 0) __PYX_ERR(0, 13, __pyx_L1_error) + #else + __pyx_ptype_7opendbc_3can_10packer_pyx_CANPacker = &__pyx_type_7opendbc_3can_10packer_pyx_CANPacker; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_7opendbc_3can_10packer_pyx_CANPacker) < 0) __PYX_ERR(0, 13, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_7opendbc_3can_10packer_pyx_CANPacker->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_7opendbc_3can_10packer_pyx_CANPacker->tp_dictoffset && __pyx_ptype_7opendbc_3can_10packer_pyx_CANPacker->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_7opendbc_3can_10packer_pyx_CANPacker->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (__Pyx_SetVtable(__pyx_ptype_7opendbc_3can_10packer_pyx_CANPacker, __pyx_vtabptr_7opendbc_3can_10packer_pyx_CANPacker) < 0) __PYX_ERR(0, 13, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_ptype_7opendbc_3can_10packer_pyx_CANPacker) < 0) __PYX_ERR(0, 13, __pyx_L1_error) + #endif + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_CANPacker, (PyObject *) __pyx_ptype_7opendbc_3can_10packer_pyx_CANPacker) < 0) __PYX_ERR(0, 13, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_7opendbc_3can_10packer_pyx_CANPacker) < 0) __PYX_ERR(0, 13, __pyx_L1_error) + #endif + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_RefNannyFinishContext(); + return -1; +} + +static int __Pyx_modinit_type_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_type_import_code", 0); + /*--- Type import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_variable_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_import_code", 0); + /*--- Variable import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_import_code", 0); + /*--- Function import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + + +#if PY_MAJOR_VERSION >= 3 +#if CYTHON_PEP489_MULTI_PHASE_INIT +static PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def); /*proto*/ +static int __pyx_pymod_exec_packer_pyx(PyObject* module); /*proto*/ +static PyModuleDef_Slot __pyx_moduledef_slots[] = { + {Py_mod_create, (void*)__pyx_pymod_create}, + {Py_mod_exec, (void*)__pyx_pymod_exec_packer_pyx}, + {0, NULL} +}; +#endif + +#ifdef __cplusplus +namespace { + struct PyModuleDef __pyx_moduledef = + #else + static struct PyModuleDef __pyx_moduledef = + #endif + { + PyModuleDef_HEAD_INIT, + "packer_pyx", + 0, /* m_doc */ + #if CYTHON_PEP489_MULTI_PHASE_INIT + 0, /* m_size */ + #elif CYTHON_USE_MODULE_STATE + sizeof(__pyx_mstate), /* m_size */ + #else + -1, /* m_size */ + #endif + __pyx_methods /* m_methods */, + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_moduledef_slots, /* m_slots */ + #else + NULL, /* m_reload */ + #endif + #if CYTHON_USE_MODULE_STATE + __pyx_m_traverse, /* m_traverse */ + __pyx_m_clear, /* m_clear */ + NULL /* m_free */ + #else + NULL, /* m_traverse */ + NULL, /* m_clear */ + NULL /* m_free */ + #endif + }; + #ifdef __cplusplus +} /* anonymous namespace */ +#endif +#endif + +#ifndef CYTHON_NO_PYINIT_EXPORT +#define __Pyx_PyMODINIT_FUNC PyMODINIT_FUNC +#elif PY_MAJOR_VERSION < 3 +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" void +#else +#define __Pyx_PyMODINIT_FUNC void +#endif +#else +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" PyObject * +#else +#define __Pyx_PyMODINIT_FUNC PyObject * +#endif +#endif + + +#if PY_MAJOR_VERSION < 3 +__Pyx_PyMODINIT_FUNC initpacker_pyx(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC initpacker_pyx(void) +#else +__Pyx_PyMODINIT_FUNC PyInit_packer_pyx(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC PyInit_packer_pyx(void) +#if CYTHON_PEP489_MULTI_PHASE_INIT +{ + return PyModuleDef_Init(&__pyx_moduledef); +} +static CYTHON_SMALL_CODE int __Pyx_check_single_interpreter(void) { + #if PY_VERSION_HEX >= 0x030700A1 + static PY_INT64_T main_interpreter_id = -1; + PY_INT64_T current_id = PyInterpreterState_GetID(PyThreadState_Get()->interp); + if (main_interpreter_id == -1) { + main_interpreter_id = current_id; + return (unlikely(current_id == -1)) ? -1 : 0; + } else if (unlikely(main_interpreter_id != current_id)) + #else + static PyInterpreterState *main_interpreter = NULL; + PyInterpreterState *current_interpreter = PyThreadState_Get()->interp; + if (!main_interpreter) { + main_interpreter = current_interpreter; + } else if (unlikely(main_interpreter != current_interpreter)) + #endif + { + PyErr_SetString( + PyExc_ImportError, + "Interpreter change detected - this module can only be loaded into one interpreter per process."); + return -1; + } + return 0; +} +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *module, const char* from_name, const char* to_name, int allow_none) +#else +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *moddict, const char* from_name, const char* to_name, int allow_none) +#endif +{ + PyObject *value = PyObject_GetAttrString(spec, from_name); + int result = 0; + if (likely(value)) { + if (allow_none || value != Py_None) { +#if CYTHON_COMPILING_IN_LIMITED_API + result = PyModule_AddObject(module, to_name, value); +#else + result = PyDict_SetItemString(moddict, to_name, value); +#endif + } + Py_DECREF(value); + } else if (PyErr_ExceptionMatches(PyExc_AttributeError)) { + PyErr_Clear(); + } else { + result = -1; + } + return result; +} +static CYTHON_SMALL_CODE PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def) { + PyObject *module = NULL, *moddict, *modname; + CYTHON_UNUSED_VAR(def); + if (__Pyx_check_single_interpreter()) + return NULL; + if (__pyx_m) + return __Pyx_NewRef(__pyx_m); + modname = PyObject_GetAttrString(spec, "name"); + if (unlikely(!modname)) goto bad; + module = PyModule_NewObject(modname); + Py_DECREF(modname); + if (unlikely(!module)) goto bad; +#if CYTHON_COMPILING_IN_LIMITED_API + moddict = module; +#else + moddict = PyModule_GetDict(module); + if (unlikely(!moddict)) goto bad; +#endif + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "loader", "__loader__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "origin", "__file__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "parent", "__package__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "submodule_search_locations", "__path__", 0) < 0)) goto bad; + return module; +bad: + Py_XDECREF(module); + return NULL; +} + + +static CYTHON_SMALL_CODE int __pyx_pymod_exec_packer_pyx(PyObject *__pyx_pyinit_module) +#endif +#endif +{ + int stringtab_initialized = 0; + #if CYTHON_USE_MODULE_STATE + int pystate_addmodule_run = 0; + #endif + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannyDeclarations + #if CYTHON_PEP489_MULTI_PHASE_INIT + if (__pyx_m) { + if (__pyx_m == __pyx_pyinit_module) return 0; + PyErr_SetString(PyExc_RuntimeError, "Module 'packer_pyx' has already been imported. Re-initialisation is not supported."); + return -1; + } + #elif PY_MAJOR_VERSION >= 3 + if (__pyx_m) return __Pyx_NewRef(__pyx_m); + #endif + /*--- Module creation code ---*/ + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_m = __pyx_pyinit_module; + Py_INCREF(__pyx_m); + #else + #if PY_MAJOR_VERSION < 3 + __pyx_m = Py_InitModule4("packer_pyx", __pyx_methods, 0, 0, PYTHON_API_VERSION); Py_XINCREF(__pyx_m); + if (unlikely(!__pyx_m)) __PYX_ERR(0, 1, __pyx_L1_error) + #elif CYTHON_USE_MODULE_STATE + __pyx_t_1 = PyModule_Create(&__pyx_moduledef); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 1, __pyx_L1_error) + { + int add_module_result = PyState_AddModule(__pyx_t_1, &__pyx_moduledef); + __pyx_t_1 = 0; /* transfer ownership from __pyx_t_1 to "packer_pyx" pseudovariable */ + if (unlikely((add_module_result < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + pystate_addmodule_run = 1; + } + #else + __pyx_m = PyModule_Create(&__pyx_moduledef); + if (unlikely(!__pyx_m)) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #endif + CYTHON_UNUSED_VAR(__pyx_t_1); + __pyx_d = PyModule_GetDict(__pyx_m); if (unlikely(!__pyx_d)) __PYX_ERR(0, 1, __pyx_L1_error) + Py_INCREF(__pyx_d); + __pyx_b = __Pyx_PyImport_AddModuleRef(__Pyx_BUILTIN_MODULE_NAME); if (unlikely(!__pyx_b)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_cython_runtime = __Pyx_PyImport_AddModuleRef((const char *) "cython_runtime"); if (unlikely(!__pyx_cython_runtime)) __PYX_ERR(0, 1, __pyx_L1_error) + if (PyObject_SetAttrString(__pyx_m, "__builtins__", __pyx_b) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #if CYTHON_REFNANNY +__Pyx_RefNanny = __Pyx_RefNannyImportAPI("refnanny"); +if (!__Pyx_RefNanny) { + PyErr_Clear(); + __Pyx_RefNanny = __Pyx_RefNannyImportAPI("Cython.Runtime.refnanny"); + if (!__Pyx_RefNanny) + Py_FatalError("failed to import 'refnanny' module"); +} +#endif + __Pyx_RefNannySetupContext("__Pyx_PyMODINIT_FUNC PyInit_packer_pyx(void)", 0); + if (__Pyx_check_binary_version(__PYX_LIMITED_VERSION_HEX, __Pyx_get_runtime_version(), CYTHON_COMPILING_IN_LIMITED_API) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #ifdef __Pxy_PyFrame_Initialize_Offsets + __Pxy_PyFrame_Initialize_Offsets(); + #endif + __pyx_empty_tuple = PyTuple_New(0); if (unlikely(!__pyx_empty_tuple)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_empty_bytes = PyBytes_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_bytes)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_empty_unicode = PyUnicode_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_unicode)) __PYX_ERR(0, 1, __pyx_L1_error) + #ifdef __Pyx_CyFunction_USED + if (__pyx_CyFunction_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_FusedFunction_USED + if (__pyx_FusedFunction_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Coroutine_USED + if (__pyx_Coroutine_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Generator_USED + if (__pyx_Generator_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_AsyncGen_USED + if (__pyx_AsyncGen_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_StopAsyncIteration_USED + if (__pyx_StopAsyncIteration_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + /*--- Library function declarations ---*/ + /*--- Threads initialization code ---*/ + #if defined(WITH_THREAD) && PY_VERSION_HEX < 0x030700F0 && defined(__PYX_FORCE_INIT_THREADS) && __PYX_FORCE_INIT_THREADS + PyEval_InitThreads(); + #endif + /*--- Initialize various global constants etc. ---*/ + if (__Pyx_InitConstants() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + stringtab_initialized = 1; + if (__Pyx_InitGlobals() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #if PY_MAJOR_VERSION < 3 && (__PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT) + if (__Pyx_init_sys_getdefaultencoding_params() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + if (__pyx_module_is_main_opendbc__can__packer_pyx) { + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_name, __pyx_n_s_main) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + } + #if PY_MAJOR_VERSION >= 3 + { + PyObject *modules = PyImport_GetModuleDict(); if (unlikely(!modules)) __PYX_ERR(0, 1, __pyx_L1_error) + if (!PyDict_GetItemString(modules, "opendbc.can.packer_pyx")) { + if (unlikely((PyDict_SetItemString(modules, "opendbc.can.packer_pyx", __pyx_m) < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + } + } + #endif + /*--- Builtin init code ---*/ + if (__Pyx_InitCachedBuiltins() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + /*--- Constants init code ---*/ + if (__Pyx_InitCachedConstants() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + /*--- Global type/function init code ---*/ + (void)__Pyx_modinit_global_init_code(); + (void)__Pyx_modinit_variable_export_code(); + (void)__Pyx_modinit_function_export_code(); + if (unlikely((__Pyx_modinit_type_init_code() < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + (void)__Pyx_modinit_type_import_code(); + (void)__Pyx_modinit_variable_import_code(); + (void)__Pyx_modinit_function_import_code(); + /*--- Execution code ---*/ + #if defined(__Pyx_Generator_USED) || defined(__Pyx_Coroutine_USED) + if (__Pyx_patch_abc() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + + /* "opendbc/can/packer_pyx.pyx":45 + * return self.packer.pack(addr, values_thing) + * + * cpdef make_can_msg(self, name_or_addr, bus, values): # <<<<<<<<<<<<<< + * cdef int addr + * if isinstance(name_or_addr, int): + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_7opendbc_3can_10packer_pyx_9CANPacker_5make_can_msg, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_CANPacker_make_can_msg, NULL, __pyx_n_s_opendbc_can_packer_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__2)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 45, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_7opendbc_3can_10packer_pyx_CANPacker, __pyx_n_s_make_can_msg, __pyx_t_2) < 0) __PYX_ERR(0, 45, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + PyType_Modified(__pyx_ptype_7opendbc_3can_10packer_pyx_CANPacker); + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.dbc,self.packer cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_7opendbc_3can_10packer_pyx_9CANPacker_7__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_CANPacker___reduce_cython, NULL, __pyx_n_s_opendbc_can_packer_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__4)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_2) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.dbc,self.packer cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.dbc,self.packer cannot be converted to a Python object for pickling" + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_7opendbc_3can_10packer_pyx_9CANPacker_9__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_CANPacker___setstate_cython, NULL, __pyx_n_s_opendbc_can_packer_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__6)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_2) < 0) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "opendbc/can/packer_pyx.pyx":1 + * # distutils: language = c++ # <<<<<<<<<<<<<< + * # cython: c_string_encoding=ascii, language_level=3 + * + */ + __pyx_t_2 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_test, __pyx_t_2) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /*--- Wrapped vars code ---*/ + + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + if (__pyx_m) { + if (__pyx_d && stringtab_initialized) { + __Pyx_AddTraceback("init opendbc.can.packer_pyx", __pyx_clineno, __pyx_lineno, __pyx_filename); + } + #if !CYTHON_USE_MODULE_STATE + Py_CLEAR(__pyx_m); + #else + Py_DECREF(__pyx_m); + if (pystate_addmodule_run) { + PyObject *tp, *value, *tb; + PyErr_Fetch(&tp, &value, &tb); + PyState_RemoveModule(&__pyx_moduledef); + PyErr_Restore(tp, value, tb); + } + #endif + } else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_ImportError, "init opendbc.can.packer_pyx"); + } + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + #if CYTHON_PEP489_MULTI_PHASE_INIT + return (__pyx_m != NULL) ? 0 : -1; + #elif PY_MAJOR_VERSION >= 3 + return __pyx_m; + #else + return; + #endif +} +/* #### Code section: cleanup_globals ### */ +/* #### Code section: cleanup_module ### */ +/* #### Code section: main_method ### */ +/* #### Code section: utility_code_pragmas ### */ +#ifdef _MSC_VER +#pragma warning( push ) +/* Warning 4127: conditional expression is constant + * Cython uses constant conditional expressions to allow in inline functions to be optimized at + * compile-time, so this warning is not useful + */ +#pragma warning( disable : 4127 ) +#endif + + + +/* #### Code section: utility_code_def ### */ + +/* --- Runtime support code --- */ +/* Refnanny */ +#if CYTHON_REFNANNY +static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname) { + PyObject *m = NULL, *p = NULL; + void *r = NULL; + m = PyImport_ImportModule(modname); + if (!m) goto end; + p = PyObject_GetAttrString(m, "RefNannyAPI"); + if (!p) goto end; + r = PyLong_AsVoidPtr(p); +end: + Py_XDECREF(p); + Py_XDECREF(m); + return (__Pyx_RefNannyAPIStruct *)r; +} +#endif + +/* PyErrExceptionMatches */ +#if CYTHON_FAST_THREAD_STATE +static int __Pyx_PyErr_ExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; i= 0x030C00A6 + PyObject *current_exception = tstate->current_exception; + if (unlikely(!current_exception)) return 0; + exc_type = (PyObject*) Py_TYPE(current_exception); + if (exc_type == err) return 1; +#else + exc_type = tstate->curexc_type; + if (exc_type == err) return 1; + if (unlikely(!exc_type)) return 0; +#endif + #if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(exc_type); + #endif + if (unlikely(PyTuple_Check(err))) { + result = __Pyx_PyErr_ExceptionMatchesTuple(exc_type, err); + } else { + result = __Pyx_PyErr_GivenExceptionMatches(exc_type, err); + } + #if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(exc_type); + #endif + return result; +} +#endif + +/* PyErrFetchRestore */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject *tmp_value; + assert(type == NULL || (value != NULL && type == (PyObject*) Py_TYPE(value))); + if (value) { + #if CYTHON_COMPILING_IN_CPYTHON + if (unlikely(((PyBaseExceptionObject*) value)->traceback != tb)) + #endif + PyException_SetTraceback(value, tb); + } + tmp_value = tstate->current_exception; + tstate->current_exception = value; + Py_XDECREF(tmp_value); + Py_XDECREF(type); + Py_XDECREF(tb); +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + tmp_type = tstate->curexc_type; + tmp_value = tstate->curexc_value; + tmp_tb = tstate->curexc_traceback; + tstate->curexc_type = type; + tstate->curexc_value = value; + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); +#endif +} +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject* exc_value; + exc_value = tstate->current_exception; + tstate->current_exception = 0; + *value = exc_value; + *type = NULL; + *tb = NULL; + if (exc_value) { + *type = (PyObject*) Py_TYPE(exc_value); + Py_INCREF(*type); + #if CYTHON_COMPILING_IN_CPYTHON + *tb = ((PyBaseExceptionObject*) exc_value)->traceback; + Py_XINCREF(*tb); + #else + *tb = PyException_GetTraceback(exc_value); + #endif + } +#else + *type = tstate->curexc_type; + *value = tstate->curexc_value; + *tb = tstate->curexc_traceback; + tstate->curexc_type = 0; + tstate->curexc_value = 0; + tstate->curexc_traceback = 0; +#endif +} +#endif + +/* PyObjectGetAttrStr */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name) { + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro)) + return tp->tp_getattro(obj, attr_name); +#if PY_MAJOR_VERSION < 3 + if (likely(tp->tp_getattr)) + return tp->tp_getattr(obj, PyString_AS_STRING(attr_name)); +#endif + return PyObject_GetAttr(obj, attr_name); +} +#endif + +/* PyObjectGetAttrStrNoError */ +#if __PYX_LIMITED_VERSION_HEX < 0x030d00A1 +static void __Pyx_PyObject_GetAttrStr_ClearAttributeError(void) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + if (likely(__Pyx_PyErr_ExceptionMatches(PyExc_AttributeError))) + __Pyx_PyErr_Clear(); +} +#endif +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name) { + PyObject *result; +#if __PYX_LIMITED_VERSION_HEX >= 0x030d00A1 + (void) PyObject_GetOptionalAttr(obj, attr_name, &result); + return result; +#else +#if CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_TYPE_SLOTS && PY_VERSION_HEX >= 0x030700B1 + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro == PyObject_GenericGetAttr)) { + return _PyObject_GenericGetAttrWithDict(obj, attr_name, NULL, 1); + } +#endif + result = __Pyx_PyObject_GetAttrStr(obj, attr_name); + if (unlikely(!result)) { + __Pyx_PyObject_GetAttrStr_ClearAttributeError(); + } + return result; +#endif +} + +/* GetBuiltinName */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name) { + PyObject* result = __Pyx_PyObject_GetAttrStrNoError(__pyx_b, name); + if (unlikely(!result) && !PyErr_Occurred()) { + PyErr_Format(PyExc_NameError, +#if PY_MAJOR_VERSION >= 3 + "name '%U' is not defined", name); +#else + "name '%.200s' is not defined", PyString_AS_STRING(name)); +#endif + } + return result; +} + +/* TupleAndListFromArray */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE void __Pyx_copy_object_array(PyObject *const *CYTHON_RESTRICT src, PyObject** CYTHON_RESTRICT dest, Py_ssize_t length) { + PyObject *v; + Py_ssize_t i; + for (i = 0; i < length; i++) { + v = dest[i] = src[i]; + Py_INCREF(v); + } +} +static CYTHON_INLINE PyObject * +__Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + Py_INCREF(__pyx_empty_tuple); + return __pyx_empty_tuple; + } + res = PyTuple_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyTupleObject*)res)->ob_item, n); + return res; +} +static CYTHON_INLINE PyObject * +__Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + return PyList_New(0); + } + res = PyList_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyListObject*)res)->ob_item, n); + return res; +} +#endif + +/* BytesEquals */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else + if (s1 == s2) { + return (equals == Py_EQ); + } else if (PyBytes_CheckExact(s1) & PyBytes_CheckExact(s2)) { + const char *ps1, *ps2; + Py_ssize_t length = PyBytes_GET_SIZE(s1); + if (length != PyBytes_GET_SIZE(s2)) + return (equals == Py_NE); + ps1 = PyBytes_AS_STRING(s1); + ps2 = PyBytes_AS_STRING(s2); + if (ps1[0] != ps2[0]) { + return (equals == Py_NE); + } else if (length == 1) { + return (equals == Py_EQ); + } else { + int result; +#if CYTHON_USE_UNICODE_INTERNALS && (PY_VERSION_HEX < 0x030B0000) + Py_hash_t hash1, hash2; + hash1 = ((PyBytesObject*)s1)->ob_shash; + hash2 = ((PyBytesObject*)s2)->ob_shash; + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + return (equals == Py_NE); + } +#endif + result = memcmp(ps1, ps2, (size_t)length); + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & PyBytes_CheckExact(s2)) { + return (equals == Py_NE); + } else if ((s2 == Py_None) & PyBytes_CheckExact(s1)) { + return (equals == Py_NE); + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +#endif +} + +/* UnicodeEquals */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else +#if PY_MAJOR_VERSION < 3 + PyObject* owned_ref = NULL; +#endif + int s1_is_unicode, s2_is_unicode; + if (s1 == s2) { + goto return_eq; + } + s1_is_unicode = PyUnicode_CheckExact(s1); + s2_is_unicode = PyUnicode_CheckExact(s2); +#if PY_MAJOR_VERSION < 3 + if ((s1_is_unicode & (!s2_is_unicode)) && PyString_CheckExact(s2)) { + owned_ref = PyUnicode_FromObject(s2); + if (unlikely(!owned_ref)) + return -1; + s2 = owned_ref; + s2_is_unicode = 1; + } else if ((s2_is_unicode & (!s1_is_unicode)) && PyString_CheckExact(s1)) { + owned_ref = PyUnicode_FromObject(s1); + if (unlikely(!owned_ref)) + return -1; + s1 = owned_ref; + s1_is_unicode = 1; + } else if (((!s2_is_unicode) & (!s1_is_unicode))) { + return __Pyx_PyBytes_Equals(s1, s2, equals); + } +#endif + if (s1_is_unicode & s2_is_unicode) { + Py_ssize_t length; + int kind; + void *data1, *data2; + if (unlikely(__Pyx_PyUnicode_READY(s1) < 0) || unlikely(__Pyx_PyUnicode_READY(s2) < 0)) + return -1; + length = __Pyx_PyUnicode_GET_LENGTH(s1); + if (length != __Pyx_PyUnicode_GET_LENGTH(s2)) { + goto return_ne; + } +#if CYTHON_USE_UNICODE_INTERNALS + { + Py_hash_t hash1, hash2; + #if CYTHON_PEP393_ENABLED + hash1 = ((PyASCIIObject*)s1)->hash; + hash2 = ((PyASCIIObject*)s2)->hash; + #else + hash1 = ((PyUnicodeObject*)s1)->hash; + hash2 = ((PyUnicodeObject*)s2)->hash; + #endif + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + goto return_ne; + } + } +#endif + kind = __Pyx_PyUnicode_KIND(s1); + if (kind != __Pyx_PyUnicode_KIND(s2)) { + goto return_ne; + } + data1 = __Pyx_PyUnicode_DATA(s1); + data2 = __Pyx_PyUnicode_DATA(s2); + if (__Pyx_PyUnicode_READ(kind, data1, 0) != __Pyx_PyUnicode_READ(kind, data2, 0)) { + goto return_ne; + } else if (length == 1) { + goto return_eq; + } else { + int result = memcmp(data1, data2, (size_t)(length * kind)); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & s2_is_unicode) { + goto return_ne; + } else if ((s2 == Py_None) & s1_is_unicode) { + goto return_ne; + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +return_eq: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ); +return_ne: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_NE); +#endif +} + +/* fastcall */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s) +{ + Py_ssize_t i, n = PyTuple_GET_SIZE(kwnames); + for (i = 0; i < n; i++) + { + if (s == PyTuple_GET_ITEM(kwnames, i)) return kwvalues[i]; + } + for (i = 0; i < n; i++) + { + int eq = __Pyx_PyUnicode_Equals(s, PyTuple_GET_ITEM(kwnames, i), Py_EQ); + if (unlikely(eq != 0)) { + if (unlikely(eq < 0)) return NULL; + return kwvalues[i]; + } + } + return NULL; +} +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 +CYTHON_UNUSED static PyObject *__Pyx_KwargsAsDict_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues) { + Py_ssize_t i, nkwargs = PyTuple_GET_SIZE(kwnames); + PyObject *dict; + dict = PyDict_New(); + if (unlikely(!dict)) + return NULL; + for (i=0; i= 3 + "%s() got multiple values for keyword argument '%U'", func_name, kw_name); + #else + "%s() got multiple values for keyword argument '%s'", func_name, + PyString_AsString(kw_name)); + #endif +} + +/* ParseKeywords */ +static int __Pyx_ParseOptionalKeywords( + PyObject *kwds, + PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, + PyObject *values[], + Py_ssize_t num_pos_args, + const char* function_name) +{ + PyObject *key = 0, *value = 0; + Py_ssize_t pos = 0; + PyObject*** name; + PyObject*** first_kw_arg = argnames + num_pos_args; + int kwds_is_tuple = CYTHON_METH_FASTCALL && likely(PyTuple_Check(kwds)); + while (1) { + Py_XDECREF(key); key = NULL; + Py_XDECREF(value); value = NULL; + if (kwds_is_tuple) { + Py_ssize_t size; +#if CYTHON_ASSUME_SAFE_MACROS + size = PyTuple_GET_SIZE(kwds); +#else + size = PyTuple_Size(kwds); + if (size < 0) goto bad; +#endif + if (pos >= size) break; +#if CYTHON_AVOID_BORROWED_REFS + key = __Pyx_PySequence_ITEM(kwds, pos); + if (!key) goto bad; +#elif CYTHON_ASSUME_SAFE_MACROS + key = PyTuple_GET_ITEM(kwds, pos); +#else + key = PyTuple_GetItem(kwds, pos); + if (!key) goto bad; +#endif + value = kwvalues[pos]; + pos++; + } + else + { + if (!PyDict_Next(kwds, &pos, &key, &value)) break; +#if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(key); +#endif + } + name = first_kw_arg; + while (*name && (**name != key)) name++; + if (*name) { + values[name-argnames] = value; +#if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(value); + Py_DECREF(key); +#endif + key = NULL; + value = NULL; + continue; + } +#if !CYTHON_AVOID_BORROWED_REFS + Py_INCREF(key); +#endif + Py_INCREF(value); + name = first_kw_arg; + #if PY_MAJOR_VERSION < 3 + if (likely(PyString_Check(key))) { + while (*name) { + if ((CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**name) == PyString_GET_SIZE(key)) + && _PyString_Eq(**name, key)) { + values[name-argnames] = value; +#if CYTHON_AVOID_BORROWED_REFS + value = NULL; +#endif + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + if ((**argname == key) || ( + (CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**argname) == PyString_GET_SIZE(key)) + && _PyString_Eq(**argname, key))) { + goto arg_passed_twice; + } + argname++; + } + } + } else + #endif + if (likely(PyUnicode_Check(key))) { + while (*name) { + int cmp = ( + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**name) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**name, key) + ); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) { + values[name-argnames] = value; +#if CYTHON_AVOID_BORROWED_REFS + value = NULL; +#endif + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + int cmp = (**argname == key) ? 0 : + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**argname) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**argname, key); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) goto arg_passed_twice; + argname++; + } + } + } else + goto invalid_keyword_type; + if (kwds2) { + if (unlikely(PyDict_SetItem(kwds2, key, value))) goto bad; + } else { + goto invalid_keyword; + } + } + Py_XDECREF(key); + Py_XDECREF(value); + return 0; +arg_passed_twice: + __Pyx_RaiseDoubleKeywordsError(function_name, key); + goto bad; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + goto bad; +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif +bad: + Py_XDECREF(key); + Py_XDECREF(value); + return -1; +} + +/* RaiseArgTupleInvalid */ +static void __Pyx_RaiseArgtupleInvalid( + const char* func_name, + int exact, + Py_ssize_t num_min, + Py_ssize_t num_max, + Py_ssize_t num_found) +{ + Py_ssize_t num_expected; + const char *more_or_less; + if (num_found < num_min) { + num_expected = num_min; + more_or_less = "at least"; + } else { + num_expected = num_max; + more_or_less = "at most"; + } + if (exact) { + more_or_less = "exactly"; + } + PyErr_Format(PyExc_TypeError, + "%.200s() takes %.8s %" CYTHON_FORMAT_SSIZE_T "d positional argument%.1s (%" CYTHON_FORMAT_SSIZE_T "d given)", + func_name, more_or_less, num_expected, + (num_expected == 1) ? "" : "s", num_found); +} + +/* PyFunctionFastCall */ +#if CYTHON_FAST_PYCALL && !CYTHON_VECTORCALL +static PyObject* __Pyx_PyFunction_FastCallNoKw(PyCodeObject *co, PyObject **args, Py_ssize_t na, + PyObject *globals) { + PyFrameObject *f; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject **fastlocals; + Py_ssize_t i; + PyObject *result; + assert(globals != NULL); + /* XXX Perhaps we should create a specialized + PyFrame_New() that doesn't take locals, but does + take builtins without sanity checking them. + */ + assert(tstate != NULL); + f = PyFrame_New(tstate, co, globals, NULL); + if (f == NULL) { + return NULL; + } + fastlocals = __Pyx_PyFrame_GetLocalsplus(f); + for (i = 0; i < na; i++) { + Py_INCREF(*args); + fastlocals[i] = *args++; + } + result = PyEval_EvalFrameEx(f,0); + ++tstate->recursion_depth; + Py_DECREF(f); + --tstate->recursion_depth; + return result; +} +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs) { + PyCodeObject *co = (PyCodeObject *)PyFunction_GET_CODE(func); + PyObject *globals = PyFunction_GET_GLOBALS(func); + PyObject *argdefs = PyFunction_GET_DEFAULTS(func); + PyObject *closure; +#if PY_MAJOR_VERSION >= 3 + PyObject *kwdefs; +#endif + PyObject *kwtuple, **k; + PyObject **d; + Py_ssize_t nd; + Py_ssize_t nk; + PyObject *result; + assert(kwargs == NULL || PyDict_Check(kwargs)); + nk = kwargs ? PyDict_Size(kwargs) : 0; + #if PY_MAJOR_VERSION < 3 + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) { + return NULL; + } + #else + if (unlikely(Py_EnterRecursiveCall(" while calling a Python object"))) { + return NULL; + } + #endif + if ( +#if PY_MAJOR_VERSION >= 3 + co->co_kwonlyargcount == 0 && +#endif + likely(kwargs == NULL || nk == 0) && + co->co_flags == (CO_OPTIMIZED | CO_NEWLOCALS | CO_NOFREE)) { + if (argdefs == NULL && co->co_argcount == nargs) { + result = __Pyx_PyFunction_FastCallNoKw(co, args, nargs, globals); + goto done; + } + else if (nargs == 0 && argdefs != NULL + && co->co_argcount == Py_SIZE(argdefs)) { + /* function called with no arguments, but all parameters have + a default value: use default values as arguments .*/ + args = &PyTuple_GET_ITEM(argdefs, 0); + result =__Pyx_PyFunction_FastCallNoKw(co, args, Py_SIZE(argdefs), globals); + goto done; + } + } + if (kwargs != NULL) { + Py_ssize_t pos, i; + kwtuple = PyTuple_New(2 * nk); + if (kwtuple == NULL) { + result = NULL; + goto done; + } + k = &PyTuple_GET_ITEM(kwtuple, 0); + pos = i = 0; + while (PyDict_Next(kwargs, &pos, &k[i], &k[i+1])) { + Py_INCREF(k[i]); + Py_INCREF(k[i+1]); + i += 2; + } + nk = i / 2; + } + else { + kwtuple = NULL; + k = NULL; + } + closure = PyFunction_GET_CLOSURE(func); +#if PY_MAJOR_VERSION >= 3 + kwdefs = PyFunction_GET_KW_DEFAULTS(func); +#endif + if (argdefs != NULL) { + d = &PyTuple_GET_ITEM(argdefs, 0); + nd = Py_SIZE(argdefs); + } + else { + d = NULL; + nd = 0; + } +#if PY_MAJOR_VERSION >= 3 + result = PyEval_EvalCodeEx((PyObject*)co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, kwdefs, closure); +#else + result = PyEval_EvalCodeEx(co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, closure); +#endif + Py_XDECREF(kwtuple); +done: + Py_LeaveRecursiveCall(); + return result; +} +#endif + +/* PyObjectCall */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw) { + PyObject *result; + ternaryfunc call = Py_TYPE(func)->tp_call; + if (unlikely(!call)) + return PyObject_Call(func, arg, kw); + #if PY_MAJOR_VERSION < 3 + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + #else + if (unlikely(Py_EnterRecursiveCall(" while calling a Python object"))) + return NULL; + #endif + result = (*call)(func, arg, kw); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* PyObjectCallMethO */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg) { + PyObject *self, *result; + PyCFunction cfunc; + cfunc = __Pyx_CyOrPyCFunction_GET_FUNCTION(func); + self = __Pyx_CyOrPyCFunction_GET_SELF(func); + #if PY_MAJOR_VERSION < 3 + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + #else + if (unlikely(Py_EnterRecursiveCall(" while calling a Python object"))) + return NULL; + #endif + result = cfunc(self, arg); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* PyObjectFastCall */ +#if PY_VERSION_HEX < 0x03090000 || CYTHON_COMPILING_IN_LIMITED_API +static PyObject* __Pyx_PyObject_FastCall_fallback(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs) { + PyObject *argstuple; + PyObject *result = 0; + size_t i; + argstuple = PyTuple_New((Py_ssize_t)nargs); + if (unlikely(!argstuple)) return NULL; + for (i = 0; i < nargs; i++) { + Py_INCREF(args[i]); + if (__Pyx_PyTuple_SET_ITEM(argstuple, (Py_ssize_t)i, args[i]) < 0) goto bad; + } + result = __Pyx_PyObject_Call(func, argstuple, kwargs); + bad: + Py_DECREF(argstuple); + return result; +} +#endif +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t _nargs, PyObject *kwargs) { + Py_ssize_t nargs = __Pyx_PyVectorcall_NARGS(_nargs); +#if CYTHON_COMPILING_IN_CPYTHON + if (nargs == 0 && kwargs == NULL) { + if (__Pyx_CyOrPyCFunction_Check(func) && likely( __Pyx_CyOrPyCFunction_GET_FLAGS(func) & METH_NOARGS)) + return __Pyx_PyObject_CallMethO(func, NULL); + } + else if (nargs == 1 && kwargs == NULL) { + if (__Pyx_CyOrPyCFunction_Check(func) && likely( __Pyx_CyOrPyCFunction_GET_FLAGS(func) & METH_O)) + return __Pyx_PyObject_CallMethO(func, args[0]); + } +#endif + #if PY_VERSION_HEX < 0x030800B1 + #if CYTHON_FAST_PYCCALL + if (PyCFunction_Check(func)) { + if (kwargs) { + return _PyCFunction_FastCallDict(func, args, nargs, kwargs); + } else { + return _PyCFunction_FastCallKeywords(func, args, nargs, NULL); + } + } + #if PY_VERSION_HEX >= 0x030700A1 + if (!kwargs && __Pyx_IS_TYPE(func, &PyMethodDescr_Type)) { + return _PyMethodDescr_FastCallKeywords(func, args, nargs, NULL); + } + #endif + #endif + #if CYTHON_FAST_PYCALL + if (PyFunction_Check(func)) { + return __Pyx_PyFunction_FastCallDict(func, args, nargs, kwargs); + } + #endif + #endif + if (kwargs == NULL) { + #if CYTHON_VECTORCALL + #if PY_VERSION_HEX < 0x03090000 + vectorcallfunc f = _PyVectorcall_Function(func); + #else + vectorcallfunc f = PyVectorcall_Function(func); + #endif + if (f) { + return f(func, args, (size_t)nargs, NULL); + } + #elif defined(__Pyx_CyFunction_USED) && CYTHON_BACKPORT_VECTORCALL + if (__Pyx_CyFunction_CheckExact(func)) { + __pyx_vectorcallfunc f = __Pyx_CyFunction_func_vectorcall(func); + if (f) return f(func, args, (size_t)nargs, NULL); + } + #endif + } + if (nargs == 0) { + return __Pyx_PyObject_Call(func, __pyx_empty_tuple, kwargs); + } + #if PY_VERSION_HEX >= 0x03090000 && !CYTHON_COMPILING_IN_LIMITED_API + return PyObject_VectorcallDict(func, args, (size_t)nargs, kwargs); + #else + return __Pyx_PyObject_FastCall_fallback(func, args, (size_t)nargs, kwargs); + #endif +} + +/* PyObjectCallOneArg */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg) { + PyObject *args[2] = {NULL, arg}; + return __Pyx_PyObject_FastCall(func, args+1, 1 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* RaiseException */ +#if PY_MAJOR_VERSION < 3 +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + __Pyx_PyThreadState_declare + CYTHON_UNUSED_VAR(cause); + Py_XINCREF(type); + if (!value || value == Py_None) + value = NULL; + else + Py_INCREF(value); + if (!tb || tb == Py_None) + tb = NULL; + else { + Py_INCREF(tb); + if (!PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto raise_error; + } + } + if (PyType_Check(type)) { +#if CYTHON_COMPILING_IN_PYPY + if (!value) { + Py_INCREF(Py_None); + value = Py_None; + } +#endif + PyErr_NormalizeException(&type, &value, &tb); + } else { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto raise_error; + } + value = type; + type = (PyObject*) Py_TYPE(type); + Py_INCREF(type); + if (!PyType_IsSubtype((PyTypeObject *)type, (PyTypeObject *)PyExc_BaseException)) { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto raise_error; + } + } + __Pyx_PyThreadState_assign + __Pyx_ErrRestore(type, value, tb); + return; +raise_error: + Py_XDECREF(value); + Py_XDECREF(type); + Py_XDECREF(tb); + return; +} +#else +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + PyObject* owned_instance = NULL; + if (tb == Py_None) { + tb = 0; + } else if (tb && !PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto bad; + } + if (value == Py_None) + value = 0; + if (PyExceptionInstance_Check(type)) { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto bad; + } + value = type; + type = (PyObject*) Py_TYPE(value); + } else if (PyExceptionClass_Check(type)) { + PyObject *instance_class = NULL; + if (value && PyExceptionInstance_Check(value)) { + instance_class = (PyObject*) Py_TYPE(value); + if (instance_class != type) { + int is_subclass = PyObject_IsSubclass(instance_class, type); + if (!is_subclass) { + instance_class = NULL; + } else if (unlikely(is_subclass == -1)) { + goto bad; + } else { + type = instance_class; + } + } + } + if (!instance_class) { + PyObject *args; + if (!value) + args = PyTuple_New(0); + else if (PyTuple_Check(value)) { + Py_INCREF(value); + args = value; + } else + args = PyTuple_Pack(1, value); + if (!args) + goto bad; + owned_instance = PyObject_Call(type, args, NULL); + Py_DECREF(args); + if (!owned_instance) + goto bad; + value = owned_instance; + if (!PyExceptionInstance_Check(value)) { + PyErr_Format(PyExc_TypeError, + "calling %R should have returned an instance of " + "BaseException, not %R", + type, Py_TYPE(value)); + goto bad; + } + } + } else { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto bad; + } + if (cause) { + PyObject *fixed_cause; + if (cause == Py_None) { + fixed_cause = NULL; + } else if (PyExceptionClass_Check(cause)) { + fixed_cause = PyObject_CallObject(cause, NULL); + if (fixed_cause == NULL) + goto bad; + } else if (PyExceptionInstance_Check(cause)) { + fixed_cause = cause; + Py_INCREF(fixed_cause); + } else { + PyErr_SetString(PyExc_TypeError, + "exception causes must derive from " + "BaseException"); + goto bad; + } + PyException_SetCause(value, fixed_cause); + } + PyErr_SetObject(type, value); + if (tb) { + #if PY_VERSION_HEX >= 0x030C00A6 + PyException_SetTraceback(value, tb); + #elif CYTHON_FAST_THREAD_STATE + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject* tmp_tb = tstate->curexc_traceback; + if (tb != tmp_tb) { + Py_INCREF(tb); + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_tb); + } +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + PyErr_Fetch(&tmp_type, &tmp_value, &tmp_tb); + Py_INCREF(tb); + PyErr_Restore(tmp_type, tmp_value, tb); + Py_XDECREF(tmp_tb); +#endif + } +bad: + Py_XDECREF(owned_instance); + return; +} +#endif + +/* IterFinish */ +static CYTHON_INLINE int __Pyx_IterFinish(void) { + PyObject* exc_type; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + exc_type = __Pyx_PyErr_CurrentExceptionType(); + if (unlikely(exc_type)) { + if (unlikely(!__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) + return -1; + __Pyx_PyErr_Clear(); + return 0; + } + return 0; +} + +/* PyObjectCallNoArg */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func) { + PyObject *arg[2] = {NULL, NULL}; + return __Pyx_PyObject_FastCall(func, arg + 1, 0 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* PyObjectGetMethod */ +static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method) { + PyObject *attr; +#if CYTHON_UNPACK_METHODS && CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_PYTYPE_LOOKUP + __Pyx_TypeName type_name; + PyTypeObject *tp = Py_TYPE(obj); + PyObject *descr; + descrgetfunc f = NULL; + PyObject **dictptr, *dict; + int meth_found = 0; + assert (*method == NULL); + if (unlikely(tp->tp_getattro != PyObject_GenericGetAttr)) { + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; + } + if (unlikely(tp->tp_dict == NULL) && unlikely(PyType_Ready(tp) < 0)) { + return 0; + } + descr = _PyType_Lookup(tp, name); + if (likely(descr != NULL)) { + Py_INCREF(descr); +#if defined(Py_TPFLAGS_METHOD_DESCRIPTOR) && Py_TPFLAGS_METHOD_DESCRIPTOR + if (__Pyx_PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_METHOD_DESCRIPTOR)) +#elif PY_MAJOR_VERSION >= 3 + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type))) + #endif +#else + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr))) + #endif +#endif + { + meth_found = 1; + } else { + f = Py_TYPE(descr)->tp_descr_get; + if (f != NULL && PyDescr_IsData(descr)) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + } + } + dictptr = _PyObject_GetDictPtr(obj); + if (dictptr != NULL && (dict = *dictptr) != NULL) { + Py_INCREF(dict); + attr = __Pyx_PyDict_GetItemStr(dict, name); + if (attr != NULL) { + Py_INCREF(attr); + Py_DECREF(dict); + Py_XDECREF(descr); + goto try_unpack; + } + Py_DECREF(dict); + } + if (meth_found) { + *method = descr; + return 1; + } + if (f != NULL) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + if (likely(descr != NULL)) { + *method = descr; + return 0; + } + type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return 0; +#else + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; +#endif +try_unpack: +#if CYTHON_UNPACK_METHODS + if (likely(attr) && PyMethod_Check(attr) && likely(PyMethod_GET_SELF(attr) == obj)) { + PyObject *function = PyMethod_GET_FUNCTION(attr); + Py_INCREF(function); + Py_DECREF(attr); + *method = function; + return 1; + } +#endif + *method = attr; + return 0; +} + +/* PyObjectCallMethod0 */ +static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name) { + PyObject *method = NULL, *result = NULL; + int is_method = __Pyx_PyObject_GetMethod(obj, method_name, &method); + if (likely(is_method)) { + result = __Pyx_PyObject_CallOneArg(method, obj); + Py_DECREF(method); + return result; + } + if (unlikely(!method)) goto bad; + result = __Pyx_PyObject_CallNoArg(method); + Py_DECREF(method); +bad: + return result; +} + +/* RaiseNeedMoreValuesToUnpack */ +static CYTHON_INLINE void __Pyx_RaiseNeedMoreValuesError(Py_ssize_t index) { + PyErr_Format(PyExc_ValueError, + "need more than %" CYTHON_FORMAT_SSIZE_T "d value%.1s to unpack", + index, (index == 1) ? "" : "s"); +} + +/* RaiseTooManyValuesToUnpack */ +static CYTHON_INLINE void __Pyx_RaiseTooManyValuesError(Py_ssize_t expected) { + PyErr_Format(PyExc_ValueError, + "too many values to unpack (expected %" CYTHON_FORMAT_SSIZE_T "d)", expected); +} + +/* UnpackItemEndCheck */ +static int __Pyx_IternextUnpackEndCheck(PyObject *retval, Py_ssize_t expected) { + if (unlikely(retval)) { + Py_DECREF(retval); + __Pyx_RaiseTooManyValuesError(expected); + return -1; + } + return __Pyx_IterFinish(); +} + +/* RaiseNoneIterError */ +static CYTHON_INLINE void __Pyx_RaiseNoneNotIterableError(void) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not iterable"); +} + +/* UnpackTupleError */ +static void __Pyx_UnpackTupleError(PyObject *t, Py_ssize_t index) { + if (t == Py_None) { + __Pyx_RaiseNoneNotIterableError(); + } else if (PyTuple_GET_SIZE(t) < index) { + __Pyx_RaiseNeedMoreValuesError(PyTuple_GET_SIZE(t)); + } else { + __Pyx_RaiseTooManyValuesError(index); + } +} + +/* UnpackTuple2 */ +static CYTHON_INLINE int __Pyx_unpack_tuple2_exact( + PyObject* tuple, PyObject** pvalue1, PyObject** pvalue2, int decref_tuple) { + PyObject *value1 = NULL, *value2 = NULL; +#if CYTHON_COMPILING_IN_PYPY + value1 = PySequence_ITEM(tuple, 0); if (unlikely(!value1)) goto bad; + value2 = PySequence_ITEM(tuple, 1); if (unlikely(!value2)) goto bad; +#else + value1 = PyTuple_GET_ITEM(tuple, 0); Py_INCREF(value1); + value2 = PyTuple_GET_ITEM(tuple, 1); Py_INCREF(value2); +#endif + if (decref_tuple) { + Py_DECREF(tuple); + } + *pvalue1 = value1; + *pvalue2 = value2; + return 0; +#if CYTHON_COMPILING_IN_PYPY +bad: + Py_XDECREF(value1); + Py_XDECREF(value2); + if (decref_tuple) { Py_XDECREF(tuple); } + return -1; +#endif +} +static int __Pyx_unpack_tuple2_generic(PyObject* tuple, PyObject** pvalue1, PyObject** pvalue2, + int has_known_size, int decref_tuple) { + Py_ssize_t index; + PyObject *value1 = NULL, *value2 = NULL, *iter = NULL; + iternextfunc iternext; + iter = PyObject_GetIter(tuple); + if (unlikely(!iter)) goto bad; + if (decref_tuple) { Py_DECREF(tuple); tuple = NULL; } + iternext = __Pyx_PyObject_GetIterNextFunc(iter); + value1 = iternext(iter); if (unlikely(!value1)) { index = 0; goto unpacking_failed; } + value2 = iternext(iter); if (unlikely(!value2)) { index = 1; goto unpacking_failed; } + if (!has_known_size && unlikely(__Pyx_IternextUnpackEndCheck(iternext(iter), 2))) goto bad; + Py_DECREF(iter); + *pvalue1 = value1; + *pvalue2 = value2; + return 0; +unpacking_failed: + if (!has_known_size && __Pyx_IterFinish() == 0) + __Pyx_RaiseNeedMoreValuesError(index); +bad: + Py_XDECREF(iter); + Py_XDECREF(value1); + Py_XDECREF(value2); + if (decref_tuple) { Py_XDECREF(tuple); } + return -1; +} + +/* dict_iter */ +#if CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 +#include +#endif +static CYTHON_INLINE PyObject* __Pyx_dict_iterator(PyObject* iterable, int is_dict, PyObject* method_name, + Py_ssize_t* p_orig_length, int* p_source_is_dict) { + is_dict = is_dict || likely(PyDict_CheckExact(iterable)); + *p_source_is_dict = is_dict; + if (is_dict) { +#if !CYTHON_COMPILING_IN_PYPY + *p_orig_length = PyDict_Size(iterable); + Py_INCREF(iterable); + return iterable; +#elif PY_MAJOR_VERSION >= 3 + static PyObject *py_items = NULL, *py_keys = NULL, *py_values = NULL; + PyObject **pp = NULL; + if (method_name) { + const char *name = PyUnicode_AsUTF8(method_name); + if (strcmp(name, "iteritems") == 0) pp = &py_items; + else if (strcmp(name, "iterkeys") == 0) pp = &py_keys; + else if (strcmp(name, "itervalues") == 0) pp = &py_values; + if (pp) { + if (!*pp) { + *pp = PyUnicode_FromString(name + 4); + if (!*pp) + return NULL; + } + method_name = *pp; + } + } +#endif + } + *p_orig_length = 0; + if (method_name) { + PyObject* iter; + iterable = __Pyx_PyObject_CallMethod0(iterable, method_name); + if (!iterable) + return NULL; +#if !CYTHON_COMPILING_IN_PYPY + if (PyTuple_CheckExact(iterable) || PyList_CheckExact(iterable)) + return iterable; +#endif + iter = PyObject_GetIter(iterable); + Py_DECREF(iterable); + return iter; + } + return PyObject_GetIter(iterable); +} +static CYTHON_INLINE int __Pyx_dict_iter_next( + PyObject* iter_obj, CYTHON_NCP_UNUSED Py_ssize_t orig_length, CYTHON_NCP_UNUSED Py_ssize_t* ppos, + PyObject** pkey, PyObject** pvalue, PyObject** pitem, int source_is_dict) { + PyObject* next_item; +#if !CYTHON_COMPILING_IN_PYPY + if (source_is_dict) { + PyObject *key, *value; + if (unlikely(orig_length != PyDict_Size(iter_obj))) { + PyErr_SetString(PyExc_RuntimeError, "dictionary changed size during iteration"); + return -1; + } + if (unlikely(!PyDict_Next(iter_obj, ppos, &key, &value))) { + return 0; + } + if (pitem) { + PyObject* tuple = PyTuple_New(2); + if (unlikely(!tuple)) { + return -1; + } + Py_INCREF(key); + Py_INCREF(value); + PyTuple_SET_ITEM(tuple, 0, key); + PyTuple_SET_ITEM(tuple, 1, value); + *pitem = tuple; + } else { + if (pkey) { + Py_INCREF(key); + *pkey = key; + } + if (pvalue) { + Py_INCREF(value); + *pvalue = value; + } + } + return 1; + } else if (PyTuple_CheckExact(iter_obj)) { + Py_ssize_t pos = *ppos; + if (unlikely(pos >= PyTuple_GET_SIZE(iter_obj))) return 0; + *ppos = pos + 1; + next_item = PyTuple_GET_ITEM(iter_obj, pos); + Py_INCREF(next_item); + } else if (PyList_CheckExact(iter_obj)) { + Py_ssize_t pos = *ppos; + if (unlikely(pos >= PyList_GET_SIZE(iter_obj))) return 0; + *ppos = pos + 1; + next_item = PyList_GET_ITEM(iter_obj, pos); + Py_INCREF(next_item); + } else +#endif + { + next_item = PyIter_Next(iter_obj); + if (unlikely(!next_item)) { + return __Pyx_IterFinish(); + } + } + if (pitem) { + *pitem = next_item; + } else if (pkey && pvalue) { + if (__Pyx_unpack_tuple2(next_item, pkey, pvalue, source_is_dict, source_is_dict, 1)) + return -1; + } else if (pkey) { + *pkey = next_item; + } else { + *pvalue = next_item; + } + return 1; +} + +/* PyDictVersioning */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + return likely(dict) ? __PYX_GET_DICT_VERSION(dict) : 0; +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj) { + PyObject **dictptr = NULL; + Py_ssize_t offset = Py_TYPE(obj)->tp_dictoffset; + if (offset) { +#if CYTHON_COMPILING_IN_CPYTHON + dictptr = (likely(offset > 0)) ? (PyObject **) ((char *)obj + offset) : _PyObject_GetDictPtr(obj); +#else + dictptr = _PyObject_GetDictPtr(obj); +#endif + } + return (dictptr && *dictptr) ? __PYX_GET_DICT_VERSION(*dictptr) : 0; +} +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + if (unlikely(!dict) || unlikely(tp_dict_version != __PYX_GET_DICT_VERSION(dict))) + return 0; + return obj_dict_version == __Pyx_get_object_dict_version(obj); +} +#endif + +/* KeywordStringCheck */ +static int __Pyx_CheckKeywordStrings( + PyObject *kw, + const char* function_name, + int kw_allowed) +{ + PyObject* key = 0; + Py_ssize_t pos = 0; +#if CYTHON_COMPILING_IN_PYPY + if (!kw_allowed && PyDict_Next(kw, &pos, &key, 0)) + goto invalid_keyword; + return 1; +#else + if (CYTHON_METH_FASTCALL && likely(PyTuple_Check(kw))) { + Py_ssize_t kwsize; +#if CYTHON_ASSUME_SAFE_MACROS + kwsize = PyTuple_GET_SIZE(kw); +#else + kwsize = PyTuple_Size(kw); + if (kwsize < 0) return 0; +#endif + if (unlikely(kwsize == 0)) + return 1; + if (!kw_allowed) { +#if CYTHON_ASSUME_SAFE_MACROS + key = PyTuple_GET_ITEM(kw, 0); +#else + key = PyTuple_GetItem(kw, pos); + if (!key) return 0; +#endif + goto invalid_keyword; + } +#if PY_VERSION_HEX < 0x03090000 + for (pos = 0; pos < kwsize; pos++) { +#if CYTHON_ASSUME_SAFE_MACROS + key = PyTuple_GET_ITEM(kw, pos); +#else + key = PyTuple_GetItem(kw, pos); + if (!key) return 0; +#endif + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } +#endif + return 1; + } + while (PyDict_Next(kw, &pos, &key, 0)) { + #if PY_MAJOR_VERSION < 3 + if (unlikely(!PyString_Check(key))) + #endif + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } + if (!kw_allowed && unlikely(key)) + goto invalid_keyword; + return 1; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + return 0; +#endif +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif + return 0; +} + +/* FixUpExtensionType */ +#if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type) { +#if PY_VERSION_HEX > 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + CYTHON_UNUSED_VAR(spec); + CYTHON_UNUSED_VAR(type); +#else + const PyType_Slot *slot = spec->slots; + while (slot && slot->slot && slot->slot != Py_tp_members) + slot++; + if (slot && slot->slot == Py_tp_members) { + int changed = 0; +#if !(PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON) + const +#endif + PyMemberDef *memb = (PyMemberDef*) slot->pfunc; + while (memb && memb->name) { + if (memb->name[0] == '_' && memb->name[1] == '_') { +#if PY_VERSION_HEX < 0x030900b1 + if (strcmp(memb->name, "__weaklistoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_weaklistoffset = memb->offset; + changed = 1; + } + else if (strcmp(memb->name, "__dictoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_dictoffset = memb->offset; + changed = 1; + } +#if CYTHON_METH_FASTCALL + else if (strcmp(memb->name, "__vectorcalloffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); +#if PY_VERSION_HEX >= 0x030800b4 + type->tp_vectorcall_offset = memb->offset; +#else + type->tp_print = (printfunc) memb->offset; +#endif + changed = 1; + } +#endif +#else + if ((0)); +#endif +#if PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON + else if (strcmp(memb->name, "__module__") == 0) { + PyObject *descr; + assert(memb->type == T_OBJECT); + assert(memb->flags == 0 || memb->flags == READONLY); + descr = PyDescr_NewMember(type, memb); + if (unlikely(!descr)) + return -1; + if (unlikely(PyDict_SetItem(type->tp_dict, PyDescr_NAME(descr), descr) < 0)) { + Py_DECREF(descr); + return -1; + } + Py_DECREF(descr); + changed = 1; + } +#endif + } + memb++; + } + if (changed) + PyType_Modified(type); + } +#endif + return 0; +} +#endif + +/* ValidateBasesTuple */ +#if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases) { + Py_ssize_t i, n; +#if CYTHON_ASSUME_SAFE_MACROS + n = PyTuple_GET_SIZE(bases); +#else + n = PyTuple_Size(bases); + if (n < 0) return -1; +#endif + for (i = 1; i < n; i++) + { +#if CYTHON_AVOID_BORROWED_REFS + PyObject *b0 = PySequence_GetItem(bases, i); + if (!b0) return -1; +#elif CYTHON_ASSUME_SAFE_MACROS + PyObject *b0 = PyTuple_GET_ITEM(bases, i); +#else + PyObject *b0 = PyTuple_GetItem(bases, i); + if (!b0) return -1; +#endif + PyTypeObject *b; +#if PY_MAJOR_VERSION < 3 + if (PyClass_Check(b0)) + { + PyErr_Format(PyExc_TypeError, "base class '%.200s' is an old-style class", + PyString_AS_STRING(((PyClassObject*)b0)->cl_name)); +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + return -1; + } +#endif + b = (PyTypeObject*) b0; + if (!__Pyx_PyType_HasFeature(b, Py_TPFLAGS_HEAPTYPE)) + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "base class '" __Pyx_FMT_TYPENAME "' is not a heap type", b_name); + __Pyx_DECREF_TypeName(b_name); +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + return -1; + } + if (dictoffset == 0) + { + Py_ssize_t b_dictoffset = 0; +#if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + b_dictoffset = b->tp_dictoffset; +#else + PyObject *py_b_dictoffset = PyObject_GetAttrString((PyObject*)b, "__dictoffset__"); + if (!py_b_dictoffset) goto dictoffset_return; + b_dictoffset = PyLong_AsSsize_t(py_b_dictoffset); + Py_DECREF(py_b_dictoffset); + if (b_dictoffset == -1 && PyErr_Occurred()) goto dictoffset_return; +#endif + if (b_dictoffset) { + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "extension type '%.200s' has no __dict__ slot, " + "but base type '" __Pyx_FMT_TYPENAME "' has: " + "either add 'cdef dict __dict__' to the extension type " + "or add '__slots__ = [...]' to the base type", + type_name, b_name); + __Pyx_DECREF_TypeName(b_name); + } +#if !(CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY) + dictoffset_return: +#endif +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + return -1; + } + } +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + } + return 0; +} +#endif + +/* PyType_Ready */ +static int __Pyx_PyType_Ready(PyTypeObject *t) { +#if CYTHON_USE_TYPE_SPECS || !(CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API) || defined(PYSTON_MAJOR_VERSION) + (void)__Pyx_PyObject_CallMethod0; +#if CYTHON_USE_TYPE_SPECS + (void)__Pyx_validate_bases_tuple; +#endif + return PyType_Ready(t); +#else + int r; + PyObject *bases = __Pyx_PyType_GetSlot(t, tp_bases, PyObject*); + if (bases && unlikely(__Pyx_validate_bases_tuple(t->tp_name, t->tp_dictoffset, bases) == -1)) + return -1; +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + { + int gc_was_enabled; + #if PY_VERSION_HEX >= 0x030A00b1 + gc_was_enabled = PyGC_Disable(); + (void)__Pyx_PyObject_CallMethod0; + #else + PyObject *ret, *py_status; + PyObject *gc = NULL; + #if PY_VERSION_HEX >= 0x030700a1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM+0 >= 0x07030400) + gc = PyImport_GetModule(__pyx_kp_u_gc); + #endif + if (unlikely(!gc)) gc = PyImport_Import(__pyx_kp_u_gc); + if (unlikely(!gc)) return -1; + py_status = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_isenabled); + if (unlikely(!py_status)) { + Py_DECREF(gc); + return -1; + } + gc_was_enabled = __Pyx_PyObject_IsTrue(py_status); + Py_DECREF(py_status); + if (gc_was_enabled > 0) { + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_disable); + if (unlikely(!ret)) { + Py_DECREF(gc); + return -1; + } + Py_DECREF(ret); + } else if (unlikely(gc_was_enabled == -1)) { + Py_DECREF(gc); + return -1; + } + #endif + t->tp_flags |= Py_TPFLAGS_HEAPTYPE; +#if PY_VERSION_HEX >= 0x030A0000 + t->tp_flags |= Py_TPFLAGS_IMMUTABLETYPE; +#endif +#else + (void)__Pyx_PyObject_CallMethod0; +#endif + r = PyType_Ready(t); +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + t->tp_flags &= ~Py_TPFLAGS_HEAPTYPE; + #if PY_VERSION_HEX >= 0x030A00b1 + if (gc_was_enabled) + PyGC_Enable(); + #else + if (gc_was_enabled) { + PyObject *tp, *v, *tb; + PyErr_Fetch(&tp, &v, &tb); + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_enable); + if (likely(ret || r == -1)) { + Py_XDECREF(ret); + PyErr_Restore(tp, v, tb); + } else { + Py_XDECREF(tp); + Py_XDECREF(v); + Py_XDECREF(tb); + r = -1; + } + } + Py_DECREF(gc); + #endif + } +#endif + return r; +#endif +} + +/* PyObject_GenericGetAttrNoDict */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject *__Pyx_RaiseGenericGetAttributeError(PyTypeObject *tp, PyObject *attr_name) { + __Pyx_TypeName type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, attr_name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(attr_name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name) { + PyObject *descr; + PyTypeObject *tp = Py_TYPE(obj); + if (unlikely(!PyString_Check(attr_name))) { + return PyObject_GenericGetAttr(obj, attr_name); + } + assert(!tp->tp_dictoffset); + descr = _PyType_Lookup(tp, attr_name); + if (unlikely(!descr)) { + return __Pyx_RaiseGenericGetAttributeError(tp, attr_name); + } + Py_INCREF(descr); + #if PY_MAJOR_VERSION < 3 + if (likely(PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_HAVE_CLASS))) + #endif + { + descrgetfunc f = Py_TYPE(descr)->tp_descr_get; + if (unlikely(f)) { + PyObject *res = f(descr, obj, (PyObject *)tp); + Py_DECREF(descr); + return res; + } + } + return descr; +} +#endif + +/* PyObject_GenericGetAttr */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name) { + if (unlikely(Py_TYPE(obj)->tp_dictoffset)) { + return PyObject_GenericGetAttr(obj, attr_name); + } + return __Pyx_PyObject_GenericGetAttrNoDict(obj, attr_name); +} +#endif + +/* SetVTable */ +static int __Pyx_SetVtable(PyTypeObject *type, void *vtable) { + PyObject *ob = PyCapsule_New(vtable, 0, 0); + if (unlikely(!ob)) + goto bad; +#if CYTHON_COMPILING_IN_LIMITED_API + if (unlikely(PyObject_SetAttr((PyObject *) type, __pyx_n_s_pyx_vtable, ob) < 0)) +#else + if (unlikely(PyDict_SetItem(type->tp_dict, __pyx_n_s_pyx_vtable, ob) < 0)) +#endif + goto bad; + Py_DECREF(ob); + return 0; +bad: + Py_XDECREF(ob); + return -1; +} + +/* GetVTable */ +static void* __Pyx_GetVtable(PyTypeObject *type) { + void* ptr; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *ob = PyObject_GetAttr((PyObject *)type, __pyx_n_s_pyx_vtable); +#else + PyObject *ob = PyObject_GetItem(type->tp_dict, __pyx_n_s_pyx_vtable); +#endif + if (!ob) + goto bad; + ptr = PyCapsule_GetPointer(ob, 0); + if (!ptr && !PyErr_Occurred()) + PyErr_SetString(PyExc_RuntimeError, "invalid vtable found for imported type"); + Py_DECREF(ob); + return ptr; +bad: + Py_XDECREF(ob); + return NULL; +} + +/* MergeVTables */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_MergeVtables(PyTypeObject *type) { + int i; + void** base_vtables; + __Pyx_TypeName tp_base_name; + __Pyx_TypeName base_name; + void* unknown = (void*)-1; + PyObject* bases = type->tp_bases; + int base_depth = 0; + { + PyTypeObject* base = type->tp_base; + while (base) { + base_depth += 1; + base = base->tp_base; + } + } + base_vtables = (void**) malloc(sizeof(void*) * (size_t)(base_depth + 1)); + base_vtables[0] = unknown; + for (i = 1; i < PyTuple_GET_SIZE(bases); i++) { + void* base_vtable = __Pyx_GetVtable(((PyTypeObject*)PyTuple_GET_ITEM(bases, i))); + if (base_vtable != NULL) { + int j; + PyTypeObject* base = type->tp_base; + for (j = 0; j < base_depth; j++) { + if (base_vtables[j] == unknown) { + base_vtables[j] = __Pyx_GetVtable(base); + base_vtables[j + 1] = unknown; + } + if (base_vtables[j] == base_vtable) { + break; + } else if (base_vtables[j] == NULL) { + goto bad; + } + base = base->tp_base; + } + } + } + PyErr_Clear(); + free(base_vtables); + return 0; +bad: + tp_base_name = __Pyx_PyType_GetName(type->tp_base); + base_name = __Pyx_PyType_GetName((PyTypeObject*)PyTuple_GET_ITEM(bases, i)); + PyErr_Format(PyExc_TypeError, + "multiple bases have vtable conflict: '" __Pyx_FMT_TYPENAME "' and '" __Pyx_FMT_TYPENAME "'", tp_base_name, base_name); + __Pyx_DECREF_TypeName(tp_base_name); + __Pyx_DECREF_TypeName(base_name); + free(base_vtables); + return -1; +} +#endif + +/* SetupReduce */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce_is_named(PyObject* meth, PyObject* name) { + int ret; + PyObject *name_attr; + name_attr = __Pyx_PyObject_GetAttrStrNoError(meth, __pyx_n_s_name); + if (likely(name_attr)) { + ret = PyObject_RichCompareBool(name_attr, name, Py_EQ); + } else { + ret = -1; + } + if (unlikely(ret < 0)) { + PyErr_Clear(); + ret = 0; + } + Py_XDECREF(name_attr); + return ret; +} +static int __Pyx_setup_reduce(PyObject* type_obj) { + int ret = 0; + PyObject *object_reduce = NULL; + PyObject *object_getstate = NULL; + PyObject *object_reduce_ex = NULL; + PyObject *reduce = NULL; + PyObject *reduce_ex = NULL; + PyObject *reduce_cython = NULL; + PyObject *setstate = NULL; + PyObject *setstate_cython = NULL; + PyObject *getstate = NULL; +#if CYTHON_USE_PYTYPE_LOOKUP + getstate = _PyType_Lookup((PyTypeObject*)type_obj, __pyx_n_s_getstate); +#else + getstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_getstate); + if (!getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (getstate) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_getstate = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_getstate); +#else + object_getstate = __Pyx_PyObject_GetAttrStrNoError((PyObject*)&PyBaseObject_Type, __pyx_n_s_getstate); + if (!object_getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (object_getstate != getstate) { + goto __PYX_GOOD; + } + } +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce_ex = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#else + object_reduce_ex = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#endif + reduce_ex = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce_ex); if (unlikely(!reduce_ex)) goto __PYX_BAD; + if (reduce_ex == object_reduce_ex) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#else + object_reduce = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#endif + reduce = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce); if (unlikely(!reduce)) goto __PYX_BAD; + if (reduce == object_reduce || __Pyx_setup_reduce_is_named(reduce, __pyx_n_s_reduce_cython)) { + reduce_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_reduce_cython); + if (likely(reduce_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce, reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (reduce == object_reduce || PyErr_Occurred()) { + goto __PYX_BAD; + } + setstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate); + if (!setstate) PyErr_Clear(); + if (!setstate || __Pyx_setup_reduce_is_named(setstate, __pyx_n_s_setstate_cython)) { + setstate_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate_cython); + if (likely(setstate_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate, setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (!setstate || PyErr_Occurred()) { + goto __PYX_BAD; + } + } + PyType_Modified((PyTypeObject*)type_obj); + } + } + goto __PYX_GOOD; +__PYX_BAD: + if (!PyErr_Occurred()) { + __Pyx_TypeName type_obj_name = + __Pyx_PyType_GetName((PyTypeObject*)type_obj); + PyErr_Format(PyExc_RuntimeError, + "Unable to initialize pickling for " __Pyx_FMT_TYPENAME, type_obj_name); + __Pyx_DECREF_TypeName(type_obj_name); + } + ret = -1; +__PYX_GOOD: +#if !CYTHON_USE_PYTYPE_LOOKUP + Py_XDECREF(object_reduce); + Py_XDECREF(object_reduce_ex); + Py_XDECREF(object_getstate); + Py_XDECREF(getstate); +#endif + Py_XDECREF(reduce); + Py_XDECREF(reduce_ex); + Py_XDECREF(reduce_cython); + Py_XDECREF(setstate); + Py_XDECREF(setstate_cython); + return ret; +} +#endif + +/* FetchSharedCythonModule */ +static PyObject *__Pyx_FetchSharedCythonABIModule(void) { + return __Pyx_PyImport_AddModuleRef((char*) __PYX_ABI_MODULE_NAME); +} + +/* FetchCommonType */ +static int __Pyx_VerifyCachedType(PyObject *cached_type, + const char *name, + Py_ssize_t basicsize, + Py_ssize_t expected_basicsize) { + if (!PyType_Check(cached_type)) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s is not a type object", name); + return -1; + } + if (basicsize != expected_basicsize) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s has the wrong size, try recompiling", + name); + return -1; + } + return 0; +} +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type) { + PyObject* abi_module; + const char* object_name; + PyTypeObject *cached_type = NULL; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + object_name = strrchr(type->tp_name, '.'); + object_name = object_name ? object_name+1 : type->tp_name; + cached_type = (PyTypeObject*) PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + if (__Pyx_VerifyCachedType( + (PyObject *)cached_type, + object_name, + cached_type->tp_basicsize, + type->tp_basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + if (PyType_Ready(type) < 0) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, (PyObject *)type) < 0) + goto bad; + Py_INCREF(type); + cached_type = type; +done: + Py_DECREF(abi_module); + return cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#else +static PyTypeObject *__Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases) { + PyObject *abi_module, *cached_type = NULL; + const char* object_name = strrchr(spec->name, '.'); + object_name = object_name ? object_name+1 : spec->name; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + cached_type = PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + Py_ssize_t basicsize; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *py_basicsize; + py_basicsize = PyObject_GetAttrString(cached_type, "__basicsize__"); + if (unlikely(!py_basicsize)) goto bad; + basicsize = PyLong_AsSsize_t(py_basicsize); + Py_DECREF(py_basicsize); + py_basicsize = 0; + if (unlikely(basicsize == (Py_ssize_t)-1) && PyErr_Occurred()) goto bad; +#else + basicsize = likely(PyType_Check(cached_type)) ? ((PyTypeObject*) cached_type)->tp_basicsize : -1; +#endif + if (__Pyx_VerifyCachedType( + cached_type, + object_name, + basicsize, + spec->basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + CYTHON_UNUSED_VAR(module); + cached_type = __Pyx_PyType_FromModuleAndSpec(abi_module, spec, bases); + if (unlikely(!cached_type)) goto bad; + if (unlikely(__Pyx_fix_up_extension_type_from_spec(spec, (PyTypeObject *) cached_type) < 0)) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, cached_type) < 0) goto bad; +done: + Py_DECREF(abi_module); + assert(cached_type == NULL || PyType_Check(cached_type)); + return (PyTypeObject *) cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#endif + +/* PyVectorcallFastCallDict */ +#if CYTHON_METH_FASTCALL +static PyObject *__Pyx_PyVectorcall_FastCallDict_kw(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + PyObject *res = NULL; + PyObject *kwnames; + PyObject **newargs; + PyObject **kwvalues; + Py_ssize_t i, pos; + size_t j; + PyObject *key, *value; + unsigned long keys_are_strings; + Py_ssize_t nkw = PyDict_GET_SIZE(kw); + newargs = (PyObject **)PyMem_Malloc((nargs + (size_t)nkw) * sizeof(args[0])); + if (unlikely(newargs == NULL)) { + PyErr_NoMemory(); + return NULL; + } + for (j = 0; j < nargs; j++) newargs[j] = args[j]; + kwnames = PyTuple_New(nkw); + if (unlikely(kwnames == NULL)) { + PyMem_Free(newargs); + return NULL; + } + kwvalues = newargs + nargs; + pos = i = 0; + keys_are_strings = Py_TPFLAGS_UNICODE_SUBCLASS; + while (PyDict_Next(kw, &pos, &key, &value)) { + keys_are_strings &= Py_TYPE(key)->tp_flags; + Py_INCREF(key); + Py_INCREF(value); + PyTuple_SET_ITEM(kwnames, i, key); + kwvalues[i] = value; + i++; + } + if (unlikely(!keys_are_strings)) { + PyErr_SetString(PyExc_TypeError, "keywords must be strings"); + goto cleanup; + } + res = vc(func, newargs, nargs, kwnames); +cleanup: + Py_DECREF(kwnames); + for (i = 0; i < nkw; i++) + Py_DECREF(kwvalues[i]); + PyMem_Free(newargs); + return res; +} +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + if (likely(kw == NULL) || PyDict_GET_SIZE(kw) == 0) { + return vc(func, args, nargs, NULL); + } + return __Pyx_PyVectorcall_FastCallDict_kw(func, vc, args, nargs, kw); +} +#endif + +/* CythonFunctionShared */ +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc) { + if (__Pyx_CyFunction_Check(func)) { + return PyCFunction_GetFunction(((__pyx_CyFunctionObject*)func)->func) == (PyCFunction) cfunc; + } else if (PyCFunction_Check(func)) { + return PyCFunction_GetFunction(func) == (PyCFunction) cfunc; + } + return 0; +} +#else +static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc) { + return __Pyx_CyOrPyCFunction_Check(func) && __Pyx_CyOrPyCFunction_GET_FUNCTION(func) == (PyCFunction) cfunc; +} +#endif +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj) { +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + __Pyx_Py_XDECREF_SET( + __Pyx_CyFunction_GetClassObj(f), + ((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#else + __Pyx_Py_XDECREF_SET( + ((PyCMethodObject *) (f))->mm_class, + (PyTypeObject*)((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#endif +} +static PyObject * +__Pyx_CyFunction_get_doc(__pyx_CyFunctionObject *op, void *closure) +{ + CYTHON_UNUSED_VAR(closure); + if (unlikely(op->func_doc == NULL)) { +#if CYTHON_COMPILING_IN_LIMITED_API + op->func_doc = PyObject_GetAttrString(op->func, "__doc__"); + if (unlikely(!op->func_doc)) return NULL; +#else + if (((PyCFunctionObject*)op)->m_ml->ml_doc) { +#if PY_MAJOR_VERSION >= 3 + op->func_doc = PyUnicode_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#else + op->func_doc = PyString_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#endif + if (unlikely(op->func_doc == NULL)) + return NULL; + } else { + Py_INCREF(Py_None); + return Py_None; + } +#endif + } + Py_INCREF(op->func_doc); + return op->func_doc; +} +static int +__Pyx_CyFunction_set_doc(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (value == NULL) { + value = Py_None; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_doc, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_name(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_name == NULL)) { +#if CYTHON_COMPILING_IN_LIMITED_API + op->func_name = PyObject_GetAttrString(op->func, "__name__"); +#elif PY_MAJOR_VERSION >= 3 + op->func_name = PyUnicode_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#else + op->func_name = PyString_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#endif + if (unlikely(op->func_name == NULL)) + return NULL; + } + Py_INCREF(op->func_name); + return op->func_name; +} +static int +__Pyx_CyFunction_set_name(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__name__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_name, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_qualname(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_qualname); + return op->func_qualname; +} +static int +__Pyx_CyFunction_set_qualname(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__qualname__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_qualname, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_dict(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_dict == NULL)) { + op->func_dict = PyDict_New(); + if (unlikely(op->func_dict == NULL)) + return NULL; + } + Py_INCREF(op->func_dict); + return op->func_dict; +} +static int +__Pyx_CyFunction_set_dict(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(value == NULL)) { + PyErr_SetString(PyExc_TypeError, + "function's dictionary may not be deleted"); + return -1; + } + if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "setting function's dictionary to a non-dict"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_dict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_globals(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_globals); + return op->func_globals; +} +static PyObject * +__Pyx_CyFunction_get_closure(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(op); + CYTHON_UNUSED_VAR(context); + Py_INCREF(Py_None); + return Py_None; +} +static PyObject * +__Pyx_CyFunction_get_code(__pyx_CyFunctionObject *op, void *context) +{ + PyObject* result = (op->func_code) ? op->func_code : Py_None; + CYTHON_UNUSED_VAR(context); + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_init_defaults(__pyx_CyFunctionObject *op) { + int result = 0; + PyObject *res = op->defaults_getter((PyObject *) op); + if (unlikely(!res)) + return -1; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + op->defaults_tuple = PyTuple_GET_ITEM(res, 0); + Py_INCREF(op->defaults_tuple); + op->defaults_kwdict = PyTuple_GET_ITEM(res, 1); + Py_INCREF(op->defaults_kwdict); + #else + op->defaults_tuple = __Pyx_PySequence_ITEM(res, 0); + if (unlikely(!op->defaults_tuple)) result = -1; + else { + op->defaults_kwdict = __Pyx_PySequence_ITEM(res, 1); + if (unlikely(!op->defaults_kwdict)) result = -1; + } + #endif + Py_DECREF(res); + return result; +} +static int +__Pyx_CyFunction_set_defaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyTuple_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__defaults__ must be set to a tuple object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__defaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_tuple, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_defaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_tuple; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_tuple; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_kwdefaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__kwdefaults__ must be set to a dict object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__kwdefaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_kwdict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_kwdefaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_kwdict; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_kwdict; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_annotations(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value || value == Py_None) { + value = NULL; + } else if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__annotations__ must be set to a dict object"); + return -1; + } + Py_XINCREF(value); + __Pyx_Py_XDECREF_SET(op->func_annotations, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_annotations(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->func_annotations; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + result = PyDict_New(); + if (unlikely(!result)) return NULL; + op->func_annotations = result; + } + Py_INCREF(result); + return result; +} +static PyObject * +__Pyx_CyFunction_get_is_coroutine(__pyx_CyFunctionObject *op, void *context) { + int is_coroutine; + CYTHON_UNUSED_VAR(context); + if (op->func_is_coroutine) { + return __Pyx_NewRef(op->func_is_coroutine); + } + is_coroutine = op->flags & __Pyx_CYFUNCTION_COROUTINE; +#if PY_VERSION_HEX >= 0x03050000 + if (is_coroutine) { + PyObject *module, *fromlist, *marker = __pyx_n_s_is_coroutine; + fromlist = PyList_New(1); + if (unlikely(!fromlist)) return NULL; + Py_INCREF(marker); +#if CYTHON_ASSUME_SAFE_MACROS + PyList_SET_ITEM(fromlist, 0, marker); +#else + if (unlikely(PyList_SetItem(fromlist, 0, marker) < 0)) { + Py_DECREF(marker); + Py_DECREF(fromlist); + return NULL; + } +#endif + module = PyImport_ImportModuleLevelObject(__pyx_n_s_asyncio_coroutines, NULL, NULL, fromlist, 0); + Py_DECREF(fromlist); + if (unlikely(!module)) goto ignore; + op->func_is_coroutine = __Pyx_PyObject_GetAttrStr(module, marker); + Py_DECREF(module); + if (likely(op->func_is_coroutine)) { + return __Pyx_NewRef(op->func_is_coroutine); + } +ignore: + PyErr_Clear(); + } +#endif + op->func_is_coroutine = __Pyx_PyBool_FromLong(is_coroutine); + return __Pyx_NewRef(op->func_is_coroutine); +} +#if CYTHON_COMPILING_IN_LIMITED_API +static PyObject * +__Pyx_CyFunction_get_module(__pyx_CyFunctionObject *op, void *context) { + CYTHON_UNUSED_VAR(context); + return PyObject_GetAttrString(op->func, "__module__"); +} +static int +__Pyx_CyFunction_set_module(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + return PyObject_SetAttrString(op->func, "__module__", value); +} +#endif +static PyGetSetDef __pyx_CyFunction_getsets[] = { + {(char *) "func_doc", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "__doc__", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "func_name", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__name__", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__qualname__", (getter)__Pyx_CyFunction_get_qualname, (setter)__Pyx_CyFunction_set_qualname, 0, 0}, + {(char *) "func_dict", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "__dict__", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "func_globals", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "__globals__", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "func_closure", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "__closure__", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "func_code", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "__code__", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "func_defaults", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__defaults__", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__kwdefaults__", (getter)__Pyx_CyFunction_get_kwdefaults, (setter)__Pyx_CyFunction_set_kwdefaults, 0, 0}, + {(char *) "__annotations__", (getter)__Pyx_CyFunction_get_annotations, (setter)__Pyx_CyFunction_set_annotations, 0, 0}, + {(char *) "_is_coroutine", (getter)__Pyx_CyFunction_get_is_coroutine, 0, 0, 0}, +#if CYTHON_COMPILING_IN_LIMITED_API + {"__module__", (getter)__Pyx_CyFunction_get_module, (setter)__Pyx_CyFunction_set_module, 0, 0}, +#endif + {0, 0, 0, 0, 0} +}; +static PyMemberDef __pyx_CyFunction_members[] = { +#if !CYTHON_COMPILING_IN_LIMITED_API + {(char *) "__module__", T_OBJECT, offsetof(PyCFunctionObject, m_module), 0, 0}, +#endif +#if CYTHON_USE_TYPE_SPECS + {(char *) "__dictoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_dict), READONLY, 0}, +#if CYTHON_METH_FASTCALL +#if CYTHON_BACKPORT_VECTORCALL + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_vectorcall), READONLY, 0}, +#else +#if !CYTHON_COMPILING_IN_LIMITED_API + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(PyCFunctionObject, vectorcall), READONLY, 0}, +#endif +#endif +#endif +#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_weakreflist), READONLY, 0}, +#else + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(PyCFunctionObject, m_weakreflist), READONLY, 0}, +#endif +#endif + {0, 0, 0, 0, 0} +}; +static PyObject * +__Pyx_CyFunction_reduce(__pyx_CyFunctionObject *m, PyObject *args) +{ + CYTHON_UNUSED_VAR(args); +#if PY_MAJOR_VERSION >= 3 + Py_INCREF(m->func_qualname); + return m->func_qualname; +#else + return PyString_FromString(((PyCFunctionObject*)m)->m_ml->ml_name); +#endif +} +static PyMethodDef __pyx_CyFunction_methods[] = { + {"__reduce__", (PyCFunction)__Pyx_CyFunction_reduce, METH_VARARGS, 0}, + {0, 0, 0, 0} +}; +#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API +#define __Pyx_CyFunction_weakreflist(cyfunc) ((cyfunc)->func_weakreflist) +#else +#define __Pyx_CyFunction_weakreflist(cyfunc) (((PyCFunctionObject*)cyfunc)->m_weakreflist) +#endif +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject *op, PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { +#if !CYTHON_COMPILING_IN_LIMITED_API + PyCFunctionObject *cf = (PyCFunctionObject*) op; +#endif + if (unlikely(op == NULL)) + return NULL; +#if CYTHON_COMPILING_IN_LIMITED_API + op->func = PyCFunction_NewEx(ml, (PyObject*)op, module); + if (unlikely(!op->func)) return NULL; +#endif + op->flags = flags; + __Pyx_CyFunction_weakreflist(op) = NULL; +#if !CYTHON_COMPILING_IN_LIMITED_API + cf->m_ml = ml; + cf->m_self = (PyObject *) op; +#endif + Py_XINCREF(closure); + op->func_closure = closure; +#if !CYTHON_COMPILING_IN_LIMITED_API + Py_XINCREF(module); + cf->m_module = module; +#endif + op->func_dict = NULL; + op->func_name = NULL; + Py_INCREF(qualname); + op->func_qualname = qualname; + op->func_doc = NULL; +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + op->func_classobj = NULL; +#else + ((PyCMethodObject*)op)->mm_class = NULL; +#endif + op->func_globals = globals; + Py_INCREF(op->func_globals); + Py_XINCREF(code); + op->func_code = code; + op->defaults_pyobjects = 0; + op->defaults_size = 0; + op->defaults = NULL; + op->defaults_tuple = NULL; + op->defaults_kwdict = NULL; + op->defaults_getter = NULL; + op->func_annotations = NULL; + op->func_is_coroutine = NULL; +#if CYTHON_METH_FASTCALL + switch (ml->ml_flags & (METH_VARARGS | METH_FASTCALL | METH_NOARGS | METH_O | METH_KEYWORDS | METH_METHOD)) { + case METH_NOARGS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_NOARGS; + break; + case METH_O: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_O; + break; + case METH_METHOD | METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD; + break; + case METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS; + break; + case METH_VARARGS | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = NULL; + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + Py_DECREF(op); + return NULL; + } +#endif + return (PyObject *) op; +} +static int +__Pyx_CyFunction_clear(__pyx_CyFunctionObject *m) +{ + Py_CLEAR(m->func_closure); +#if CYTHON_COMPILING_IN_LIMITED_API + Py_CLEAR(m->func); +#else + Py_CLEAR(((PyCFunctionObject*)m)->m_module); +#endif + Py_CLEAR(m->func_dict); + Py_CLEAR(m->func_name); + Py_CLEAR(m->func_qualname); + Py_CLEAR(m->func_doc); + Py_CLEAR(m->func_globals); + Py_CLEAR(m->func_code); +#if !CYTHON_COMPILING_IN_LIMITED_API +#if PY_VERSION_HEX < 0x030900B1 + Py_CLEAR(__Pyx_CyFunction_GetClassObj(m)); +#else + { + PyObject *cls = (PyObject*) ((PyCMethodObject *) (m))->mm_class; + ((PyCMethodObject *) (m))->mm_class = NULL; + Py_XDECREF(cls); + } +#endif +#endif + Py_CLEAR(m->defaults_tuple); + Py_CLEAR(m->defaults_kwdict); + Py_CLEAR(m->func_annotations); + Py_CLEAR(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_XDECREF(pydefaults[i]); + PyObject_Free(m->defaults); + m->defaults = NULL; + } + return 0; +} +static void __Pyx__CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + if (__Pyx_CyFunction_weakreflist(m) != NULL) + PyObject_ClearWeakRefs((PyObject *) m); + __Pyx_CyFunction_clear(m); + __Pyx_PyHeapTypeObject_GC_Del(m); +} +static void __Pyx_CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + PyObject_GC_UnTrack(m); + __Pyx__CyFunction_dealloc(m); +} +static int __Pyx_CyFunction_traverse(__pyx_CyFunctionObject *m, visitproc visit, void *arg) +{ + Py_VISIT(m->func_closure); +#if CYTHON_COMPILING_IN_LIMITED_API + Py_VISIT(m->func); +#else + Py_VISIT(((PyCFunctionObject*)m)->m_module); +#endif + Py_VISIT(m->func_dict); + Py_VISIT(m->func_name); + Py_VISIT(m->func_qualname); + Py_VISIT(m->func_doc); + Py_VISIT(m->func_globals); + Py_VISIT(m->func_code); +#if !CYTHON_COMPILING_IN_LIMITED_API + Py_VISIT(__Pyx_CyFunction_GetClassObj(m)); +#endif + Py_VISIT(m->defaults_tuple); + Py_VISIT(m->defaults_kwdict); + Py_VISIT(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_VISIT(pydefaults[i]); + } + return 0; +} +static PyObject* +__Pyx_CyFunction_repr(__pyx_CyFunctionObject *op) +{ +#if PY_MAJOR_VERSION >= 3 + return PyUnicode_FromFormat("", + op->func_qualname, (void *)op); +#else + return PyString_FromFormat("", + PyString_AsString(op->func_qualname), (void *)op); +#endif +} +static PyObject * __Pyx_CyFunction_CallMethod(PyObject *func, PyObject *self, PyObject *arg, PyObject *kw) { +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *f = ((__pyx_CyFunctionObject*)func)->func; + PyObject *py_name = NULL; + PyCFunction meth; + int flags; + meth = PyCFunction_GetFunction(f); + if (unlikely(!meth)) return NULL; + flags = PyCFunction_GetFlags(f); + if (unlikely(flags < 0)) return NULL; +#else + PyCFunctionObject* f = (PyCFunctionObject*)func; + PyCFunction meth = f->m_ml->ml_meth; + int flags = f->m_ml->ml_flags; +#endif + Py_ssize_t size; + switch (flags & (METH_VARARGS | METH_KEYWORDS | METH_NOARGS | METH_O)) { + case METH_VARARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) + return (*meth)(self, arg); + break; + case METH_VARARGS | METH_KEYWORDS: + return (*(PyCFunctionWithKeywords)(void*)meth)(self, arg, kw); + case METH_NOARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { +#if CYTHON_ASSUME_SAFE_MACROS + size = PyTuple_GET_SIZE(arg); +#else + size = PyTuple_Size(arg); + if (unlikely(size < 0)) return NULL; +#endif + if (likely(size == 0)) + return (*meth)(self, NULL); +#if CYTHON_COMPILING_IN_LIMITED_API + py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); + if (!py_name) return NULL; + PyErr_Format(PyExc_TypeError, + "%.200S() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + py_name, size); + Py_DECREF(py_name); +#else + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); +#endif + return NULL; + } + break; + case METH_O: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { +#if CYTHON_ASSUME_SAFE_MACROS + size = PyTuple_GET_SIZE(arg); +#else + size = PyTuple_Size(arg); + if (unlikely(size < 0)) return NULL; +#endif + if (likely(size == 1)) { + PyObject *result, *arg0; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + arg0 = PyTuple_GET_ITEM(arg, 0); + #else + arg0 = __Pyx_PySequence_ITEM(arg, 0); if (unlikely(!arg0)) return NULL; + #endif + result = (*meth)(self, arg0); + #if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(arg0); + #endif + return result; + } +#if CYTHON_COMPILING_IN_LIMITED_API + py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); + if (!py_name) return NULL; + PyErr_Format(PyExc_TypeError, + "%.200S() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + py_name, size); + Py_DECREF(py_name); +#else + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); +#endif + return NULL; + } + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + return NULL; + } +#if CYTHON_COMPILING_IN_LIMITED_API + py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); + if (!py_name) return NULL; + PyErr_Format(PyExc_TypeError, "%.200S() takes no keyword arguments", + py_name); + Py_DECREF(py_name); +#else + PyErr_Format(PyExc_TypeError, "%.200s() takes no keyword arguments", + f->m_ml->ml_name); +#endif + return NULL; +} +static CYTHON_INLINE PyObject *__Pyx_CyFunction_Call(PyObject *func, PyObject *arg, PyObject *kw) { + PyObject *self, *result; +#if CYTHON_COMPILING_IN_LIMITED_API + self = PyCFunction_GetSelf(((__pyx_CyFunctionObject*)func)->func); + if (unlikely(!self) && PyErr_Occurred()) return NULL; +#else + self = ((PyCFunctionObject*)func)->m_self; +#endif + result = __Pyx_CyFunction_CallMethod(func, self, arg, kw); + return result; +} +static PyObject *__Pyx_CyFunction_CallAsMethod(PyObject *func, PyObject *args, PyObject *kw) { + PyObject *result; + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *) func; +#if CYTHON_METH_FASTCALL + __pyx_vectorcallfunc vc = __Pyx_CyFunction_func_vectorcall(cyfunc); + if (vc) { +#if CYTHON_ASSUME_SAFE_MACROS + return __Pyx_PyVectorcall_FastCallDict(func, vc, &PyTuple_GET_ITEM(args, 0), (size_t)PyTuple_GET_SIZE(args), kw); +#else + (void) &__Pyx_PyVectorcall_FastCallDict; + return PyVectorcall_Call(func, args, kw); +#endif + } +#endif + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + Py_ssize_t argc; + PyObject *new_args; + PyObject *self; +#if CYTHON_ASSUME_SAFE_MACROS + argc = PyTuple_GET_SIZE(args); +#else + argc = PyTuple_Size(args); + if (unlikely(!argc) < 0) return NULL; +#endif + new_args = PyTuple_GetSlice(args, 1, argc); + if (unlikely(!new_args)) + return NULL; + self = PyTuple_GetItem(args, 0); + if (unlikely(!self)) { + Py_DECREF(new_args); +#if PY_MAJOR_VERSION > 2 + PyErr_Format(PyExc_TypeError, + "unbound method %.200S() needs an argument", + cyfunc->func_qualname); +#else + PyErr_SetString(PyExc_TypeError, + "unbound method needs an argument"); +#endif + return NULL; + } + result = __Pyx_CyFunction_CallMethod(func, self, new_args, kw); + Py_DECREF(new_args); + } else { + result = __Pyx_CyFunction_Call(func, args, kw); + } + return result; +} +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE int __Pyx_CyFunction_Vectorcall_CheckArgs(__pyx_CyFunctionObject *cyfunc, Py_ssize_t nargs, PyObject *kwnames) +{ + int ret = 0; + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + if (unlikely(nargs < 1)) { + PyErr_Format(PyExc_TypeError, "%.200s() needs an argument", + ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + ret = 1; + } + if (unlikely(kwnames) && unlikely(PyTuple_GET_SIZE(kwnames))) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no keyword arguments", ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + return ret; +} +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 0)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, NULL); +} +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 1)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, args[0]); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((_PyCFunctionFastWithKeywords)(void(*)(void))def->ml_meth)(self, args, nargs, kwnames); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; + PyTypeObject *cls = (PyTypeObject *) __Pyx_CyFunction_GetClassObj(cyfunc); +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((__Pyx_PyCMethod)(void(*)(void))def->ml_meth)(self, cls, args, (size_t)nargs, kwnames); +} +#endif +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_CyFunctionType_slots[] = { + {Py_tp_dealloc, (void *)__Pyx_CyFunction_dealloc}, + {Py_tp_repr, (void *)__Pyx_CyFunction_repr}, + {Py_tp_call, (void *)__Pyx_CyFunction_CallAsMethod}, + {Py_tp_traverse, (void *)__Pyx_CyFunction_traverse}, + {Py_tp_clear, (void *)__Pyx_CyFunction_clear}, + {Py_tp_methods, (void *)__pyx_CyFunction_methods}, + {Py_tp_members, (void *)__pyx_CyFunction_members}, + {Py_tp_getset, (void *)__pyx_CyFunction_getsets}, + {Py_tp_descr_get, (void *)__Pyx_PyMethod_New}, + {0, 0}, +}; +static PyType_Spec __pyx_CyFunctionType_spec = { + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#if (defined(_Py_TPFLAGS_HAVE_VECTORCALL) && CYTHON_METH_FASTCALL) + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + __pyx_CyFunctionType_slots +}; +#else +static PyTypeObject __pyx_CyFunctionType_type = { + PyVarObject_HEAD_INIT(0, 0) + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, + (destructor) __Pyx_CyFunction_dealloc, +#if !CYTHON_METH_FASTCALL + 0, +#elif CYTHON_BACKPORT_VECTORCALL + (printfunc)offsetof(__pyx_CyFunctionObject, func_vectorcall), +#else + offsetof(PyCFunctionObject, vectorcall), +#endif + 0, + 0, +#if PY_MAJOR_VERSION < 3 + 0, +#else + 0, +#endif + (reprfunc) __Pyx_CyFunction_repr, + 0, + 0, + 0, + 0, + __Pyx_CyFunction_CallAsMethod, + 0, + 0, + 0, + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#if defined(_Py_TPFLAGS_HAVE_VECTORCALL) && CYTHON_METH_FASTCALL + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + 0, + (traverseproc) __Pyx_CyFunction_traverse, + (inquiry) __Pyx_CyFunction_clear, + 0, +#if PY_VERSION_HEX < 0x030500A0 + offsetof(__pyx_CyFunctionObject, func_weakreflist), +#else + offsetof(PyCFunctionObject, m_weakreflist), +#endif + 0, + 0, + __pyx_CyFunction_methods, + __pyx_CyFunction_members, + __pyx_CyFunction_getsets, + 0, + 0, + __Pyx_PyMethod_New, + 0, + offsetof(__pyx_CyFunctionObject, func_dict), + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, +#if PY_VERSION_HEX >= 0x030400a1 + 0, +#endif +#if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, +#endif +#if __PYX_NEED_TP_PRINT_SLOT + 0, +#endif +#if PY_VERSION_HEX >= 0x030C0000 + 0, +#endif +#if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, +#endif +}; +#endif +static int __pyx_CyFunction_init(PyObject *module) { +#if CYTHON_USE_TYPE_SPECS + __pyx_CyFunctionType = __Pyx_FetchCommonTypeFromSpec(module, &__pyx_CyFunctionType_spec, NULL); +#else + CYTHON_UNUSED_VAR(module); + __pyx_CyFunctionType = __Pyx_FetchCommonType(&__pyx_CyFunctionType_type); +#endif + if (unlikely(__pyx_CyFunctionType == NULL)) { + return -1; + } + return 0; +} +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *func, size_t size, int pyobjects) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults = PyObject_Malloc(size); + if (unlikely(!m->defaults)) + return PyErr_NoMemory(); + memset(m->defaults, 0, size); + m->defaults_pyobjects = pyobjects; + m->defaults_size = size; + return m->defaults; +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *func, PyObject *tuple) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_tuple = tuple; + Py_INCREF(tuple); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_kwdict = dict; + Py_INCREF(dict); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->func_annotations = dict; + Py_INCREF(dict); +} + +/* CythonFunction */ +static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { + PyObject *op = __Pyx_CyFunction_Init( + PyObject_GC_New(__pyx_CyFunctionObject, __pyx_CyFunctionType), + ml, flags, qualname, closure, module, globals, code + ); + if (likely(op)) { + PyObject_GC_Track(op); + } + return op; +} + +/* CLineInTraceback */ +#ifndef CYTHON_CLINE_IN_TRACEBACK +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line) { + PyObject *use_cline; + PyObject *ptype, *pvalue, *ptraceback; +#if CYTHON_COMPILING_IN_CPYTHON + PyObject **cython_runtime_dict; +#endif + CYTHON_MAYBE_UNUSED_VAR(tstate); + if (unlikely(!__pyx_cython_runtime)) { + return c_line; + } + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); +#if CYTHON_COMPILING_IN_CPYTHON + cython_runtime_dict = _PyObject_GetDictPtr(__pyx_cython_runtime); + if (likely(cython_runtime_dict)) { + __PYX_PY_DICT_LOOKUP_IF_MODIFIED( + use_cline, *cython_runtime_dict, + __Pyx_PyDict_GetItemStr(*cython_runtime_dict, __pyx_n_s_cline_in_traceback)) + } else +#endif + { + PyObject *use_cline_obj = __Pyx_PyObject_GetAttrStrNoError(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback); + if (use_cline_obj) { + use_cline = PyObject_Not(use_cline_obj) ? Py_False : Py_True; + Py_DECREF(use_cline_obj); + } else { + PyErr_Clear(); + use_cline = NULL; + } + } + if (!use_cline) { + c_line = 0; + (void) PyObject_SetAttr(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback, Py_False); + } + else if (use_cline == Py_False || (use_cline != Py_True && PyObject_Not(use_cline) != 0)) { + c_line = 0; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + return c_line; +} +#endif + +/* CodeObjectCache */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line) { + int start = 0, mid = 0, end = count - 1; + if (end >= 0 && code_line > entries[end].code_line) { + return count; + } + while (start < end) { + mid = start + (end - start) / 2; + if (code_line < entries[mid].code_line) { + end = mid; + } else if (code_line > entries[mid].code_line) { + start = mid + 1; + } else { + return mid; + } + } + if (code_line <= entries[mid].code_line) { + return mid; + } else { + return mid + 1; + } +} +static PyCodeObject *__pyx_find_code_object(int code_line) { + PyCodeObject* code_object; + int pos; + if (unlikely(!code_line) || unlikely(!__pyx_code_cache.entries)) { + return NULL; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if (unlikely(pos >= __pyx_code_cache.count) || unlikely(__pyx_code_cache.entries[pos].code_line != code_line)) { + return NULL; + } + code_object = __pyx_code_cache.entries[pos].code_object; + Py_INCREF(code_object); + return code_object; +} +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object) { + int pos, i; + __Pyx_CodeObjectCacheEntry* entries = __pyx_code_cache.entries; + if (unlikely(!code_line)) { + return; + } + if (unlikely(!entries)) { + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Malloc(64*sizeof(__Pyx_CodeObjectCacheEntry)); + if (likely(entries)) { + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = 64; + __pyx_code_cache.count = 1; + entries[0].code_line = code_line; + entries[0].code_object = code_object; + Py_INCREF(code_object); + } + return; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if ((pos < __pyx_code_cache.count) && unlikely(__pyx_code_cache.entries[pos].code_line == code_line)) { + PyCodeObject* tmp = entries[pos].code_object; + entries[pos].code_object = code_object; + Py_DECREF(tmp); + return; + } + if (__pyx_code_cache.count == __pyx_code_cache.max_count) { + int new_max = __pyx_code_cache.max_count + 64; + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Realloc( + __pyx_code_cache.entries, ((size_t)new_max) * sizeof(__Pyx_CodeObjectCacheEntry)); + if (unlikely(!entries)) { + return; + } + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = new_max; + } + for (i=__pyx_code_cache.count; i>pos; i--) { + entries[i] = entries[i-1]; + } + entries[pos].code_line = code_line; + entries[pos].code_object = code_object; + __pyx_code_cache.count++; + Py_INCREF(code_object); +} +#endif + +/* AddTraceback */ +#include "compile.h" +#include "frameobject.h" +#include "traceback.h" +#if PY_VERSION_HEX >= 0x030b00a6 && !CYTHON_COMPILING_IN_LIMITED_API + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static PyObject *__Pyx_PyCode_Replace_For_AddTraceback(PyObject *code, PyObject *scratch_dict, + PyObject *firstlineno, PyObject *name) { + PyObject *replace = NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "co_firstlineno", firstlineno))) return NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "co_name", name))) return NULL; + replace = PyObject_GetAttrString(code, "replace"); + if (likely(replace)) { + PyObject *result; + result = PyObject_Call(replace, __pyx_empty_tuple, scratch_dict); + Py_DECREF(replace); + return result; + } + PyErr_Clear(); + #if __PYX_LIMITED_VERSION_HEX < 0x030780000 + { + PyObject *compiled = NULL, *result = NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "code", code))) return NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "type", (PyObject*)(&PyType_Type)))) return NULL; + compiled = Py_CompileString( + "out = type(code)(\n" + " code.co_argcount, code.co_kwonlyargcount, code.co_nlocals, code.co_stacksize,\n" + " code.co_flags, code.co_code, code.co_consts, code.co_names,\n" + " code.co_varnames, code.co_filename, co_name, co_firstlineno,\n" + " code.co_lnotab)\n", "", Py_file_input); + if (!compiled) return NULL; + result = PyEval_EvalCode(compiled, scratch_dict, scratch_dict); + Py_DECREF(compiled); + if (!result) PyErr_Print(); + Py_DECREF(result); + result = PyDict_GetItemString(scratch_dict, "out"); + if (result) Py_INCREF(result); + return result; + } + #else + return NULL; + #endif +} +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + PyObject *code_object = NULL, *py_py_line = NULL, *py_funcname = NULL, *dict = NULL; + PyObject *replace = NULL, *getframe = NULL, *frame = NULL; + PyObject *exc_type, *exc_value, *exc_traceback; + int success = 0; + if (c_line) { + (void) __pyx_cfilenm; + (void) __Pyx_CLineForTraceback(__Pyx_PyThreadState_Current, c_line); + } + PyErr_Fetch(&exc_type, &exc_value, &exc_traceback); + code_object = Py_CompileString("_getframe()", filename, Py_eval_input); + if (unlikely(!code_object)) goto bad; + py_py_line = PyLong_FromLong(py_line); + if (unlikely(!py_py_line)) goto bad; + py_funcname = PyUnicode_FromString(funcname); + if (unlikely(!py_funcname)) goto bad; + dict = PyDict_New(); + if (unlikely(!dict)) goto bad; + { + PyObject *old_code_object = code_object; + code_object = __Pyx_PyCode_Replace_For_AddTraceback(code_object, dict, py_py_line, py_funcname); + Py_DECREF(old_code_object); + } + if (unlikely(!code_object)) goto bad; + getframe = PySys_GetObject("_getframe"); + if (unlikely(!getframe)) goto bad; + if (unlikely(PyDict_SetItemString(dict, "_getframe", getframe))) goto bad; + frame = PyEval_EvalCode(code_object, dict, dict); + if (unlikely(!frame) || frame == Py_None) goto bad; + success = 1; + bad: + PyErr_Restore(exc_type, exc_value, exc_traceback); + Py_XDECREF(code_object); + Py_XDECREF(py_py_line); + Py_XDECREF(py_funcname); + Py_XDECREF(dict); + Py_XDECREF(replace); + if (success) { + PyTraceBack_Here( + (struct _frame*)frame); + } + Py_XDECREF(frame); +} +#else +static PyCodeObject* __Pyx_CreateCodeObjectForTraceback( + const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = NULL; + PyObject *py_funcname = NULL; + #if PY_MAJOR_VERSION < 3 + PyObject *py_srcfile = NULL; + py_srcfile = PyString_FromString(filename); + if (!py_srcfile) goto bad; + #endif + if (c_line) { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + #else + py_funcname = PyUnicode_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + funcname = PyUnicode_AsUTF8(py_funcname); + if (!funcname) goto bad; + #endif + } + else { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromString(funcname); + if (!py_funcname) goto bad; + #endif + } + #if PY_MAJOR_VERSION < 3 + py_code = __Pyx_PyCode_New( + 0, + 0, + 0, + 0, + 0, + 0, + __pyx_empty_bytes, /*PyObject *code,*/ + __pyx_empty_tuple, /*PyObject *consts,*/ + __pyx_empty_tuple, /*PyObject *names,*/ + __pyx_empty_tuple, /*PyObject *varnames,*/ + __pyx_empty_tuple, /*PyObject *freevars,*/ + __pyx_empty_tuple, /*PyObject *cellvars,*/ + py_srcfile, /*PyObject *filename,*/ + py_funcname, /*PyObject *name,*/ + py_line, + __pyx_empty_bytes /*PyObject *lnotab*/ + ); + Py_DECREF(py_srcfile); + #else + py_code = PyCode_NewEmpty(filename, funcname, py_line); + #endif + Py_XDECREF(py_funcname); + return py_code; +bad: + Py_XDECREF(py_funcname); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_srcfile); + #endif + return NULL; +} +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = 0; + PyFrameObject *py_frame = 0; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject *ptype, *pvalue, *ptraceback; + if (c_line) { + c_line = __Pyx_CLineForTraceback(tstate, c_line); + } + py_code = __pyx_find_code_object(c_line ? -c_line : py_line); + if (!py_code) { + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); + py_code = __Pyx_CreateCodeObjectForTraceback( + funcname, c_line, py_line, filename); + if (!py_code) { + /* If the code object creation fails, then we should clear the + fetched exception references and propagate the new exception */ + Py_XDECREF(ptype); + Py_XDECREF(pvalue); + Py_XDECREF(ptraceback); + goto bad; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + __pyx_insert_code_object(c_line ? -c_line : py_line, py_code); + } + py_frame = PyFrame_New( + tstate, /*PyThreadState *tstate,*/ + py_code, /*PyCodeObject *code,*/ + __pyx_d, /*PyObject *globals,*/ + 0 /*PyObject *locals*/ + ); + if (!py_frame) goto bad; + __Pyx_PyFrame_SetLineNumber(py_frame, py_line); + PyTraceBack_Here(py_frame); +bad: + Py_XDECREF(py_code); + Py_XDECREF(py_frame); +} +#endif + +/* CIntFromPyVerify */ +#define __PYX_VERIFY_RETURN_INT(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 0) +#define __PYX_VERIFY_RETURN_INT_EXC(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 1) +#define __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, exc)\ + {\ + func_type value = func_value;\ + if (sizeof(target_type) < sizeof(func_type)) {\ + if (unlikely(value != (func_type) (target_type) value)) {\ + func_type zero = 0;\ + if (exc && unlikely(value == (func_type)-1 && PyErr_Occurred()))\ + return (target_type) -1;\ + if (is_unsigned && unlikely(value < zero))\ + goto raise_neg_overflow;\ + else\ + goto raise_overflow;\ + }\ + }\ + return (target_type) value;\ + } + +/* CIntFromPy */ +static CYTHON_INLINE size_t __Pyx_PyInt_As_size_t(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const size_t neg_one = (size_t) -1, const_zero = (size_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(size_t) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(size_t, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (size_t) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(size_t, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(size_t) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) >= 2 * PyLong_SHIFT)) { + return (size_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(size_t) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) >= 3 * PyLong_SHIFT)) { + return (size_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(size_t) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) >= 4 * PyLong_SHIFT)) { + return (size_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (size_t) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(size_t) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(size_t) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(size_t, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(size_t) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 2 * PyLong_SHIFT)) { + return (size_t) (((size_t)-1)*(((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(size_t) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 2 * PyLong_SHIFT)) { + return (size_t) ((((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(size_t) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 3 * PyLong_SHIFT)) { + return (size_t) (((size_t)-1)*(((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(size_t) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 3 * PyLong_SHIFT)) { + return (size_t) ((((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(size_t) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 4 * PyLong_SHIFT)) { + return (size_t) (((size_t)-1)*(((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(size_t) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 4 * PyLong_SHIFT)) { + return (size_t) ((((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(size_t) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(size_t) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + size_t val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (size_t) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (size_t) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (size_t) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (size_t) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (size_t) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(size_t) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((size_t) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(size_t) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((size_t) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((size_t) 1) << (sizeof(size_t) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (size_t) -1; + } + } else { + size_t val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (size_t) -1; + val = __Pyx_PyInt_As_size_t(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to size_t"); + return (size_t) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to size_t"); + return (size_t) -1; +} + +/* CIntFromPy */ +static CYTHON_INLINE uint32_t __Pyx_PyInt_As_uint32_t(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const uint32_t neg_one = (uint32_t) -1, const_zero = (uint32_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(uint32_t) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(uint32_t, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (uint32_t) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(uint32_t, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(uint32_t) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) >= 2 * PyLong_SHIFT)) { + return (uint32_t) (((((uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(uint32_t) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) >= 3 * PyLong_SHIFT)) { + return (uint32_t) (((((((uint32_t)digits[2]) << PyLong_SHIFT) | (uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(uint32_t) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) >= 4 * PyLong_SHIFT)) { + return (uint32_t) (((((((((uint32_t)digits[3]) << PyLong_SHIFT) | (uint32_t)digits[2]) << PyLong_SHIFT) | (uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (uint32_t) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(uint32_t) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(uint32_t, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(uint32_t) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(uint32_t, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(uint32_t, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(uint32_t) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) - 1 > 2 * PyLong_SHIFT)) { + return (uint32_t) (((uint32_t)-1)*(((((uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(uint32_t) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) - 1 > 2 * PyLong_SHIFT)) { + return (uint32_t) ((((((uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(uint32_t) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) - 1 > 3 * PyLong_SHIFT)) { + return (uint32_t) (((uint32_t)-1)*(((((((uint32_t)digits[2]) << PyLong_SHIFT) | (uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(uint32_t) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) - 1 > 3 * PyLong_SHIFT)) { + return (uint32_t) ((((((((uint32_t)digits[2]) << PyLong_SHIFT) | (uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(uint32_t) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) - 1 > 4 * PyLong_SHIFT)) { + return (uint32_t) (((uint32_t)-1)*(((((((((uint32_t)digits[3]) << PyLong_SHIFT) | (uint32_t)digits[2]) << PyLong_SHIFT) | (uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(uint32_t) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) - 1 > 4 * PyLong_SHIFT)) { + return (uint32_t) ((((((((((uint32_t)digits[3]) << PyLong_SHIFT) | (uint32_t)digits[2]) << PyLong_SHIFT) | (uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(uint32_t) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(uint32_t, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(uint32_t) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(uint32_t, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + uint32_t val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (uint32_t) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (uint32_t) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (uint32_t) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (uint32_t) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (uint32_t) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(uint32_t) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((uint32_t) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(uint32_t) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((uint32_t) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((uint32_t) 1) << (sizeof(uint32_t) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (uint32_t) -1; + } + } else { + uint32_t val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (uint32_t) -1; + val = __Pyx_PyInt_As_uint32_t(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to uint32_t"); + return (uint32_t) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to uint32_t"); + return (uint32_t) -1; +} + +/* CIntFromPy */ +static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(int) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(int, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (int) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 2 * PyLong_SHIFT)) { + return (int) (((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 3 * PyLong_SHIFT)) { + return (int) (((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 4 * PyLong_SHIFT)) { + return (int) (((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(int) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(int) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) ((((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) ((((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) ((((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(int) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + int val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (int) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (int) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (int) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (int) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(int) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(int) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((int) 1) << (sizeof(int) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (int) -1; + } + } else { + int val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (int) -1; + val = __Pyx_PyInt_As_int(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to int"); + return (int) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to int"); + return (int) -1; +} + +/* CIntToPy */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_int(int value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(int) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(int) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(int) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(int) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(int) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; +#if !CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030d0000 + return _PyLong_FromByteArray(bytes, sizeof(int), + little, !is_unsigned); +#else + PyObject *from_bytes, *result = NULL; + PyObject *py_bytes = NULL, *arg_tuple = NULL, *kwds = NULL, *order_str = NULL; + from_bytes = PyObject_GetAttrString((PyObject*)&PyLong_Type, "from_bytes"); + if (!from_bytes) return NULL; + py_bytes = PyBytes_FromStringAndSize((char*)bytes, sizeof(int)); + if (!py_bytes) goto limited_bad; + order_str = PyUnicode_FromString(little ? "little" : "big"); + if (!order_str) goto limited_bad; + arg_tuple = PyTuple_Pack(2, py_bytes, order_str); + if (!arg_tuple) goto limited_bad; + if (!is_unsigned) { + kwds = PyDict_New(); + if (!kwds) goto limited_bad; + if (PyDict_SetItemString(kwds, "signed", __Pyx_NewRef(Py_True))) goto limited_bad; + } + result = PyObject_Call(from_bytes, arg_tuple, kwds); + limited_bad: + Py_XDECREF(kwds); + Py_XDECREF(arg_tuple); + Py_XDECREF(order_str); + Py_XDECREF(py_bytes); + Py_XDECREF(from_bytes); + return result; +#endif + } +} + +/* FormatTypeName */ +#if CYTHON_COMPILING_IN_LIMITED_API +static __Pyx_TypeName +__Pyx_PyType_GetName(PyTypeObject* tp) +{ + PyObject *name = __Pyx_PyObject_GetAttrStr((PyObject *)tp, + __pyx_n_s_name); + if (unlikely(name == NULL) || unlikely(!PyUnicode_Check(name))) { + PyErr_Clear(); + Py_XDECREF(name); + name = __Pyx_NewRef(__pyx_n_s__7); + } + return name; +} +#endif + +/* CIntToPy */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(long) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(long) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(long) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; +#if !CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030d0000 + return _PyLong_FromByteArray(bytes, sizeof(long), + little, !is_unsigned); +#else + PyObject *from_bytes, *result = NULL; + PyObject *py_bytes = NULL, *arg_tuple = NULL, *kwds = NULL, *order_str = NULL; + from_bytes = PyObject_GetAttrString((PyObject*)&PyLong_Type, "from_bytes"); + if (!from_bytes) return NULL; + py_bytes = PyBytes_FromStringAndSize((char*)bytes, sizeof(long)); + if (!py_bytes) goto limited_bad; + order_str = PyUnicode_FromString(little ? "little" : "big"); + if (!order_str) goto limited_bad; + arg_tuple = PyTuple_Pack(2, py_bytes, order_str); + if (!arg_tuple) goto limited_bad; + if (!is_unsigned) { + kwds = PyDict_New(); + if (!kwds) goto limited_bad; + if (PyDict_SetItemString(kwds, "signed", __Pyx_NewRef(Py_True))) goto limited_bad; + } + result = PyObject_Call(from_bytes, arg_tuple, kwds); + limited_bad: + Py_XDECREF(kwds); + Py_XDECREF(arg_tuple); + Py_XDECREF(order_str); + Py_XDECREF(py_bytes); + Py_XDECREF(from_bytes); + return result; +#endif + } +} + +/* CIntFromPy */ +static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(long) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(long, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (long) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 2 * PyLong_SHIFT)) { + return (long) (((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 3 * PyLong_SHIFT)) { + return (long) (((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 4 * PyLong_SHIFT)) { + return (long) (((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(long) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(long) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) ((((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) ((((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) ((((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(long) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + long val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (long) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (long) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (long) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (long) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(long) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(long) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((long) 1) << (sizeof(long) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (long) -1; + } + } else { + long val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (long) -1; + val = __Pyx_PyInt_As_long(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to long"); + return (long) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to long"); + return (long) -1; +} + +/* FastTypeChecks */ +#if CYTHON_COMPILING_IN_CPYTHON +static int __Pyx_InBases(PyTypeObject *a, PyTypeObject *b) { + while (a) { + a = __Pyx_PyType_GetSlot(a, tp_base, PyTypeObject*); + if (a == b) + return 1; + } + return b == &PyBaseObject_Type; +} +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (a == b) return 1; + mro = a->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + if (PyTuple_GET_ITEM(mro, i) == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(a, b); +} +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (cls == a || cls == b) return 1; + mro = cls->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + PyObject *base = PyTuple_GET_ITEM(mro, i); + if (base == (PyObject *)a || base == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(cls, a) || __Pyx_InBases(cls, b); +} +#if PY_MAJOR_VERSION == 2 +static int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject* exc_type2) { + PyObject *exception, *value, *tb; + int res; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&exception, &value, &tb); + res = exc_type1 ? PyObject_IsSubclass(err, exc_type1) : 0; + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + if (!res) { + res = PyObject_IsSubclass(err, exc_type2); + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + } + __Pyx_ErrRestore(exception, value, tb); + return res; +} +#else +static CYTHON_INLINE int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject *exc_type2) { + if (exc_type1) { + return __Pyx_IsAnySubtype2((PyTypeObject*)err, (PyTypeObject*)exc_type1, (PyTypeObject*)exc_type2); + } else { + return __Pyx_IsSubtype((PyTypeObject*)err, (PyTypeObject*)exc_type2); + } +} +#endif +static int __Pyx_PyErr_GivenExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + assert(PyExceptionClass_Check(exc_type)); + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; i= 0x030B00A4 + return Py_Version & ~0xFFUL; +#else + const char* rt_version = Py_GetVersion(); + unsigned long version = 0; + unsigned long factor = 0x01000000UL; + unsigned int digit = 0; + int i = 0; + while (factor) { + while ('0' <= rt_version[i] && rt_version[i] <= '9') { + digit = digit * 10 + (unsigned int) (rt_version[i] - '0'); + ++i; + } + version += factor * digit; + if (rt_version[i] != '.') + break; + digit = 0; + factor >>= 8; + ++i; + } + return version; +#endif +} +static int __Pyx_check_binary_version(unsigned long ct_version, unsigned long rt_version, int allow_newer) { + const unsigned long MAJOR_MINOR = 0xFFFF0000UL; + if ((rt_version & MAJOR_MINOR) == (ct_version & MAJOR_MINOR)) + return 0; + if (likely(allow_newer && (rt_version & MAJOR_MINOR) > (ct_version & MAJOR_MINOR))) + return 1; + { + char message[200]; + PyOS_snprintf(message, sizeof(message), + "compile time Python version %d.%d " + "of module '%.100s' " + "%s " + "runtime version %d.%d", + (int) (ct_version >> 24), (int) ((ct_version >> 16) & 0xFF), + __Pyx_MODULE_NAME, + (allow_newer) ? "was newer than" : "does not match", + (int) (rt_version >> 24), (int) ((rt_version >> 16) & 0xFF) + ); + return PyErr_WarnEx(NULL, message, 1); + } +} + +/* InitStrings */ +#if PY_MAJOR_VERSION >= 3 +static int __Pyx_InitString(__Pyx_StringTabEntry t, PyObject **str) { + if (t.is_unicode | t.is_str) { + if (t.intern) { + *str = PyUnicode_InternFromString(t.s); + } else if (t.encoding) { + *str = PyUnicode_Decode(t.s, t.n - 1, t.encoding, NULL); + } else { + *str = PyUnicode_FromStringAndSize(t.s, t.n - 1); + } + } else { + *str = PyBytes_FromStringAndSize(t.s, t.n - 1); + } + if (!*str) + return -1; + if (PyObject_Hash(*str) == -1) + return -1; + return 0; +} +#endif +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t) { + while (t->p) { + #if PY_MAJOR_VERSION >= 3 + __Pyx_InitString(*t, t->p); + #else + if (t->is_unicode) { + *t->p = PyUnicode_DecodeUTF8(t->s, t->n - 1, NULL); + } else if (t->intern) { + *t->p = PyString_InternFromString(t->s); + } else { + *t->p = PyString_FromStringAndSize(t->s, t->n - 1); + } + if (!*t->p) + return -1; + if (PyObject_Hash(*t->p) == -1) + return -1; + #endif + ++t; + } + return 0; +} + +#include +static CYTHON_INLINE Py_ssize_t __Pyx_ssize_strlen(const char *s) { + size_t len = strlen(s); + if (unlikely(len > (size_t) PY_SSIZE_T_MAX)) { + PyErr_SetString(PyExc_OverflowError, "byte string is too long"); + return -1; + } + return (Py_ssize_t) len; +} +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char* c_str) { + Py_ssize_t len = __Pyx_ssize_strlen(c_str); + if (unlikely(len < 0)) return NULL; + return __Pyx_PyUnicode_FromStringAndSize(c_str, len); +} +static CYTHON_INLINE PyObject* __Pyx_PyByteArray_FromString(const char* c_str) { + Py_ssize_t len = __Pyx_ssize_strlen(c_str); + if (unlikely(len < 0)) return NULL; + return PyByteArray_FromStringAndSize(c_str, len); +} +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject* o) { + Py_ssize_t ignore; + return __Pyx_PyObject_AsStringAndSize(o, &ignore); +} +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +#if !CYTHON_PEP393_ENABLED +static const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + char* defenc_c; + PyObject* defenc = _PyUnicode_AsDefaultEncodedString(o, NULL); + if (!defenc) return NULL; + defenc_c = PyBytes_AS_STRING(defenc); +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + { + char* end = defenc_c + PyBytes_GET_SIZE(defenc); + char* c; + for (c = defenc_c; c < end; c++) { + if ((unsigned char) (*c) >= 128) { + PyUnicode_AsASCIIString(o); + return NULL; + } + } + } +#endif + *length = PyBytes_GET_SIZE(defenc); + return defenc_c; +} +#else +static CYTHON_INLINE const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + if (unlikely(__Pyx_PyUnicode_READY(o) == -1)) return NULL; +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + if (likely(PyUnicode_IS_ASCII(o))) { + *length = PyUnicode_GET_LENGTH(o); + return PyUnicode_AsUTF8(o); + } else { + PyUnicode_AsASCIIString(o); + return NULL; + } +#else + return PyUnicode_AsUTF8AndSize(o, length); +#endif +} +#endif +#endif +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject* o, Py_ssize_t *length) { +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT + if ( +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + __Pyx_sys_getdefaultencoding_not_ascii && +#endif + PyUnicode_Check(o)) { + return __Pyx_PyUnicode_AsStringAndSize(o, length); + } else +#endif +#if (!CYTHON_COMPILING_IN_PYPY && !CYTHON_COMPILING_IN_LIMITED_API) || (defined(PyByteArray_AS_STRING) && defined(PyByteArray_GET_SIZE)) + if (PyByteArray_Check(o)) { + *length = PyByteArray_GET_SIZE(o); + return PyByteArray_AS_STRING(o); + } else +#endif + { + char* result; + int r = PyBytes_AsStringAndSize(o, &result, length); + if (unlikely(r < 0)) { + return NULL; + } else { + return result; + } + } +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject* x) { + int is_true = x == Py_True; + if (is_true | (x == Py_False) | (x == Py_None)) return is_true; + else return PyObject_IsTrue(x); +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject* x) { + int retval; + if (unlikely(!x)) return -1; + retval = __Pyx_PyObject_IsTrue(x); + Py_DECREF(x); + return retval; +} +static PyObject* __Pyx_PyNumber_IntOrLongWrongResultType(PyObject* result, const char* type_name) { + __Pyx_TypeName result_type_name = __Pyx_PyType_GetName(Py_TYPE(result)); +#if PY_MAJOR_VERSION >= 3 + if (PyLong_Check(result)) { + if (PyErr_WarnFormat(PyExc_DeprecationWarning, 1, + "__int__ returned non-int (type " __Pyx_FMT_TYPENAME "). " + "The ability to return an instance of a strict subclass of int is deprecated, " + "and may be removed in a future version of Python.", + result_type_name)) { + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; + } + __Pyx_DECREF_TypeName(result_type_name); + return result; + } +#endif + PyErr_Format(PyExc_TypeError, + "__%.4s__ returned non-%.4s (type " __Pyx_FMT_TYPENAME ")", + type_name, type_name, result_type_name); + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x) { +#if CYTHON_USE_TYPE_SLOTS + PyNumberMethods *m; +#endif + const char *name = NULL; + PyObject *res = NULL; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x) || PyLong_Check(x))) +#else + if (likely(PyLong_Check(x))) +#endif + return __Pyx_NewRef(x); +#if CYTHON_USE_TYPE_SLOTS + m = Py_TYPE(x)->tp_as_number; + #if PY_MAJOR_VERSION < 3 + if (m && m->nb_int) { + name = "int"; + res = m->nb_int(x); + } + else if (m && m->nb_long) { + name = "long"; + res = m->nb_long(x); + } + #else + if (likely(m && m->nb_int)) { + name = "int"; + res = m->nb_int(x); + } + #endif +#else + if (!PyBytes_CheckExact(x) && !PyUnicode_CheckExact(x)) { + res = PyNumber_Int(x); + } +#endif + if (likely(res)) { +#if PY_MAJOR_VERSION < 3 + if (unlikely(!PyInt_Check(res) && !PyLong_Check(res))) { +#else + if (unlikely(!PyLong_CheckExact(res))) { +#endif + return __Pyx_PyNumber_IntOrLongWrongResultType(res, name); + } + } + else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_TypeError, + "an integer is required"); + } + return res; +} +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject* b) { + Py_ssize_t ival; + PyObject *x; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_CheckExact(b))) { + if (sizeof(Py_ssize_t) >= sizeof(long)) + return PyInt_AS_LONG(b); + else + return PyInt_AsSsize_t(b); + } +#endif + if (likely(PyLong_CheckExact(b))) { + #if CYTHON_USE_PYLONG_INTERNALS + if (likely(__Pyx_PyLong_IsCompact(b))) { + return __Pyx_PyLong_CompactValue(b); + } else { + const digit* digits = __Pyx_PyLong_Digits(b); + const Py_ssize_t size = __Pyx_PyLong_SignedDigitCount(b); + switch (size) { + case 2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return (Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + } + } + #endif + return PyLong_AsSsize_t(b); + } + x = PyNumber_Index(b); + if (!x) return -1; + ival = PyInt_AsSsize_t(x); + Py_DECREF(x); + return ival; +} +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject* o) { + if (sizeof(Py_hash_t) == sizeof(Py_ssize_t)) { + return (Py_hash_t) __Pyx_PyIndex_AsSsize_t(o); +#if PY_MAJOR_VERSION < 3 + } else if (likely(PyInt_CheckExact(o))) { + return PyInt_AS_LONG(o); +#endif + } else { + Py_ssize_t ival; + PyObject *x; + x = PyNumber_Index(o); + if (!x) return -1; + ival = PyInt_AsLong(x); + Py_DECREF(x); + return ival; + } +} +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b) { + return b ? __Pyx_NewRef(Py_True) : __Pyx_NewRef(Py_False); +} +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t ival) { + return PyInt_FromSize_t(ival); +} + + +/* #### Code section: utility_code_pragmas_end ### */ +#ifdef _MSC_VER +#pragma warning( pop ) +#endif + + + +/* #### Code section: end ### */ +#endif /* Py_PYTHON_H */ diff --git a/opendbc/can/packer_pyx.so b/opendbc/can/packer_pyx.so new file mode 100755 index 0000000..e791807 Binary files /dev/null and b/opendbc/can/packer_pyx.so differ diff --git a/opendbc/can/parser.cc b/opendbc/can/parser.cc deleted file mode 100644 index 3ed9f02..0000000 --- a/opendbc/can/parser.cc +++ /dev/null @@ -1,326 +0,0 @@ -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include - -#include "cereal/logger/logger.h" -#include "opendbc/can/common.h" - -int64_t get_raw_value(const std::vector &msg, const Signal &sig) { - int64_t ret = 0; - - int i = sig.msb / 8; - int bits = sig.size; - while (i >= 0 && i < msg.size() && bits > 0) { - int lsb = (int)(sig.lsb / 8) == i ? sig.lsb : i*8; - int msb = (int)(sig.msb / 8) == i ? sig.msb : (i+1)*8 - 1; - int size = msb - lsb + 1; - - uint64_t d = (msg[i] >> (lsb - (i*8))) & ((1ULL << size) - 1); - ret |= d << (bits - size); - - bits -= size; - i = sig.is_little_endian ? i-1 : i+1; - } - return ret; -} - - -bool MessageState::parse(uint64_t nanos, const std::vector &dat) { - std::vector tmp_vals(parse_sigs.size()); - bool checksum_failed = false; - bool counter_failed = false; - - for (int i = 0; i < parse_sigs.size(); i++) { - const auto &sig = parse_sigs[i]; - - int64_t tmp = get_raw_value(dat, sig); - if (sig.is_signed) { - tmp -= ((tmp >> (sig.size-1)) & 0x1) ? (1ULL << sig.size) : 0; - } - - //DEBUG("parse 0x%X %s -> %ld\n", address, sig.name, tmp); - - if (!ignore_checksum) { - if (sig.calc_checksum != nullptr && sig.calc_checksum(address, sig, dat) != tmp) { - checksum_failed = true; - } - } - - if (!ignore_counter) { - if (sig.type == SignalType::COUNTER && !update_counter_generic(tmp, sig.size)) { - counter_failed = true; - } - } - - tmp_vals[i] = tmp * sig.factor + sig.offset; - } - - // only update values if both checksum and counter are valid - if (checksum_failed || counter_failed) { - LOGE("0x%X message checks failed, checksum failed %d, counter failed %d", address, checksum_failed, counter_failed); - return false; - } - - for (int i = 0; i < parse_sigs.size(); i++) { - vals[i] = tmp_vals[i]; - all_vals[i].push_back(vals[i]); - } - last_seen_nanos = nanos; - - return true; -} - - -bool MessageState::update_counter_generic(int64_t v, int cnt_size) { - if (((counter + 1) & ((1 << cnt_size) -1)) != v) { - counter_fail = std::min(counter_fail + 1, MAX_BAD_COUNTER); - if (counter_fail > 1) { - INFO("0x%X COUNTER FAIL #%d -- %d -> %d\n", address, counter_fail, counter, (int)v); - } - } else if (counter_fail > 0) { - counter_fail--; - } - counter = v; - return counter_fail < MAX_BAD_COUNTER; -} - - -CANParser::CANParser(int abus, const std::string& dbc_name, const std::vector> &messages) - : bus(abus), aligned_buf(kj::heapArray(1024)) { - dbc = dbc_lookup(dbc_name); - assert(dbc); - init_crc_lookup_tables(); - - bus_timeout_threshold = std::numeric_limits::max(); - - for (const auto& [address, frequency] : messages) { - // disallow duplicate message checks - if (message_states.find(address) != message_states.end()) { - std::stringstream is; - is << "Duplicate Message Check: " << address; - throw std::runtime_error(is.str()); - } - - MessageState &state = message_states[address]; - state.address = address; - // state.check_frequency = op.check_frequency, - - // msg is not valid if a message isn't received for 10 consecutive steps - if (frequency > 0) { - state.check_threshold = (1000000000ULL / frequency) * 10; - - // bus timeout threshold should be 10x the fastest msg - bus_timeout_threshold = std::min(bus_timeout_threshold, state.check_threshold); - } - - const Msg* msg = NULL; - for (const auto& m : dbc->msgs) { - if (m.address == address) { - msg = &m; - break; - } - } - if (!msg) { - fprintf(stderr, "CANParser: could not find message 0x%X in DBC %s\n", address, dbc_name.c_str()); - assert(false); - } - - state.name = msg->name; - state.size = msg->size; - assert(state.size <= 64); // max signal size is 64 bytes - - // track all signals for this message - state.parse_sigs = msg->sigs; - state.vals.resize(msg->sigs.size()); - state.all_vals.resize(msg->sigs.size()); - } -} - -CANParser::CANParser(int abus, const std::string& dbc_name, bool ignore_checksum, bool ignore_counter) - : bus(abus) { - // Add all messages and signals - - dbc = dbc_lookup(dbc_name); - assert(dbc); - init_crc_lookup_tables(); - - for (const auto& msg : dbc->msgs) { - MessageState state = { - .name = msg.name, - .address = msg.address, - .size = msg.size, - .ignore_checksum = ignore_checksum, - .ignore_counter = ignore_counter, - }; - - for (const auto& sig : msg.sigs) { - state.parse_sigs.push_back(sig); - state.vals.push_back(0); - state.all_vals.push_back({}); - } - - message_states[state.address] = state; - } -} - -#ifndef DYNAMIC_CAPNP -void CANParser::update_string(const std::string &data, bool sendcan) { - // format for board, make copy due to alignment issues. - const size_t buf_size = (data.length() / sizeof(capnp::word)) + 1; - if (aligned_buf.size() < buf_size) { - aligned_buf = kj::heapArray(buf_size); - } - memcpy(aligned_buf.begin(), data.data(), data.length()); - - // extract the messages - capnp::FlatArrayMessageReader cmsg(aligned_buf.slice(0, buf_size)); - cereal::Event::Reader event = cmsg.getRoot(); - - if (first_nanos == 0) { - first_nanos = event.getLogMonoTime(); - } - last_nanos = event.getLogMonoTime(); - - auto cans = sendcan ? event.getSendcan() : event.getCan(); - UpdateCans(last_nanos, cans); - - UpdateValid(last_nanos); -} - -void CANParser::update_strings(const std::vector &data, std::vector &vals, bool sendcan) { - uint64_t current_nanos = 0; - for (const auto &d : data) { - update_string(d, sendcan); - if (current_nanos == 0) { - current_nanos = last_nanos; - } - } - query_latest(vals, current_nanos); -} - -void CANParser::UpdateCans(uint64_t nanos, const capnp::List::Reader& cans) { - //DEBUG("got %d messages\n", cans.size()); - - bool bus_empty = true; - - // parse the messages - for (const auto cmsg : cans) { - if (cmsg.getSrc() != bus) { - // DEBUG("skip %d: wrong bus\n", cmsg.getAddress()); - continue; - } - bus_empty = false; - - auto state_it = message_states.find(cmsg.getAddress()); - if (state_it == message_states.end()) { - // DEBUG("skip %d: not specified\n", cmsg.getAddress()); - continue; - } - - auto dat = cmsg.getDat(); - - if (dat.size() > 64) { - DEBUG("got message longer than 64 bytes: 0x%X %zu\n", cmsg.getAddress(), dat.size()); - continue; - } - - // TODO: this actually triggers for some cars. fix and enable this - //if (dat.size() != state_it->second.size) { - // DEBUG("got message with unexpected length: expected %d, got %zu for %d", state_it->second.size, dat.size(), cmsg.getAddress()); - // continue; - //} - - std::vector data(dat.size(), 0); - memcpy(data.data(), dat.begin(), dat.size()); - state_it->second.parse(nanos, data); - } - - // update bus timeout - if (!bus_empty) { - last_nonempty_nanos = nanos; - } - bus_timeout = (nanos - last_nonempty_nanos) > bus_timeout_threshold; -} -#endif - -void CANParser::UpdateCans(uint64_t nanos, const capnp::DynamicStruct::Reader& cmsg) { - // assume message struct is `cereal::CanData` and parse - assert(cmsg.has("address") && cmsg.has("src") && cmsg.has("dat") && cmsg.has("busTime")); - - if (cmsg.get("src").as() != bus) { - DEBUG("skip %d: wrong bus\n", cmsg.get("address").as()); - return; - } - - auto state_it = message_states.find(cmsg.get("address").as()); - if (state_it == message_states.end()) { - DEBUG("skip %d: not specified\n", cmsg.get("address").as()); - return; - } - - auto dat = cmsg.get("dat").as(); - if (dat.size() > 64) return; // shouldn't ever happen - std::vector data(dat.size(), 0); - memcpy(data.data(), dat.begin(), dat.size()); - state_it->second.parse(nanos, data); -} - -void CANParser::UpdateValid(uint64_t nanos) { - const bool show_missing = (last_nanos - first_nanos) > 8e9; - - bool _valid = true; - bool _counters_valid = true; - for (const auto& kv : message_states) { - const auto& state = kv.second; - - if (state.counter_fail >= MAX_BAD_COUNTER) { - _counters_valid = false; - } - - const bool missing = state.last_seen_nanos == 0; - const bool timed_out = (nanos - state.last_seen_nanos) > state.check_threshold; - if (state.check_threshold > 0 && (missing || timed_out)) { - if (show_missing && !bus_timeout) { - if (missing) { - LOGE("0x%X '%s' NOT SEEN", state.address, state.name.c_str()); - } else if (timed_out) { - LOGE("0x%X '%s' TIMED OUT", state.address, state.name.c_str()); - } - } - _valid = false; - } - } - can_invalid_cnt = _valid ? 0 : (can_invalid_cnt + 1); - can_valid = (can_invalid_cnt < CAN_INVALID_CNT) && _counters_valid; -} - -void CANParser::query_latest(std::vector &vals, uint64_t last_ts) { - if (last_ts == 0) { - last_ts = last_nanos; - } - for (auto& kv : message_states) { - auto& state = kv.second; - if (last_ts != 0 && state.last_seen_nanos < last_ts) { - continue; - } - - for (int i = 0; i < state.parse_sigs.size(); i++) { - const Signal &sig = state.parse_sigs[i]; - SignalValue &v = vals.emplace_back(); - v.address = state.address; - v.ts_nanos = state.last_seen_nanos; - v.name = sig.name; - v.value = state.vals[i]; - v.all_values = state.all_vals[i]; - state.all_vals[i].clear(); - } - } -} diff --git a/opendbc/can/parser_pyx.cpp b/opendbc/can/parser_pyx.cpp new file mode 100644 index 0000000..c29ee7f --- /dev/null +++ b/opendbc/can/parser_pyx.cpp @@ -0,0 +1,13645 @@ +/* Generated by Cython 3.0.8 */ + +/* BEGIN: Cython Metadata +{ + "distutils": { + "depends": [ + "opendbc/can/common.h", + "opendbc/can/common_dbc.h" + ], + "include_dirs": [ + "opendbc/can" + ], + "language": "c++", + "name": "opendbc.can.parser_pyx", + "sources": [ + "/data/openpilot/opendbc/can/parser_pyx.pyx" + ] + }, + "module_name": "opendbc.can.parser_pyx" +} +END: Cython Metadata */ + +#ifndef PY_SSIZE_T_CLEAN +#define PY_SSIZE_T_CLEAN +#endif /* PY_SSIZE_T_CLEAN */ +#if defined(CYTHON_LIMITED_API) && 0 + #ifndef Py_LIMITED_API + #if CYTHON_LIMITED_API+0 > 0x03030000 + #define Py_LIMITED_API CYTHON_LIMITED_API + #else + #define Py_LIMITED_API 0x03030000 + #endif + #endif +#endif + +#include "Python.h" +#ifndef Py_PYTHON_H + #error Python headers needed to compile C extensions, please install development version of Python. +#elif PY_VERSION_HEX < 0x02070000 || (0x03000000 <= PY_VERSION_HEX && PY_VERSION_HEX < 0x03030000) + #error Cython requires Python 2.7+ or Python 3.3+. +#else +#if defined(CYTHON_LIMITED_API) && CYTHON_LIMITED_API +#define __PYX_EXTRA_ABI_MODULE_NAME "limited" +#else +#define __PYX_EXTRA_ABI_MODULE_NAME "" +#endif +#define CYTHON_ABI "3_0_8" __PYX_EXTRA_ABI_MODULE_NAME +#define __PYX_ABI_MODULE_NAME "_cython_" CYTHON_ABI +#define __PYX_TYPE_MODULE_PREFIX __PYX_ABI_MODULE_NAME "." +#define CYTHON_HEX_VERSION 0x030008F0 +#define CYTHON_FUTURE_DIVISION 1 +#include +#ifndef offsetof + #define offsetof(type, member) ( (size_t) & ((type*)0) -> member ) +#endif +#if !defined(_WIN32) && !defined(WIN32) && !defined(MS_WINDOWS) + #ifndef __stdcall + #define __stdcall + #endif + #ifndef __cdecl + #define __cdecl + #endif + #ifndef __fastcall + #define __fastcall + #endif +#endif +#ifndef DL_IMPORT + #define DL_IMPORT(t) t +#endif +#ifndef DL_EXPORT + #define DL_EXPORT(t) t +#endif +#define __PYX_COMMA , +#ifndef HAVE_LONG_LONG + #define HAVE_LONG_LONG +#endif +#ifndef PY_LONG_LONG + #define PY_LONG_LONG LONG_LONG +#endif +#ifndef Py_HUGE_VAL + #define Py_HUGE_VAL HUGE_VAL +#endif +#define __PYX_LIMITED_VERSION_HEX PY_VERSION_HEX +#if defined(GRAALVM_PYTHON) + /* For very preliminary testing purposes. Most variables are set the same as PyPy. + The existence of this section does not imply that anything works or is even tested */ + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 1 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(PYPY_VERSION) + #define CYTHON_COMPILING_IN_PYPY 1 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #ifndef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #endif + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #if PY_VERSION_HEX < 0x03090000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE (PY_VERSION_HEX >= 0x030400a1 && PYPY_VERSION_NUM >= 0x07030C00) + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(CYTHON_LIMITED_API) + #ifdef Py_LIMITED_API + #undef __PYX_LIMITED_VERSION_HEX + #define __PYX_LIMITED_VERSION_HEX Py_LIMITED_API + #endif + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 1 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_CLINE_IN_TRACEBACK + #define CYTHON_CLINE_IN_TRACEBACK 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 1 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #endif + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 1 + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(Py_GIL_DISABLED) || defined(Py_NOGIL) + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 1 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #ifndef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 +#else + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 1 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #ifndef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #endif + #ifndef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 1 + #endif + #if PY_MAJOR_VERSION < 3 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #ifndef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 1 + #endif + #ifndef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 1 + #endif + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #if PY_VERSION_HEX < 0x030300F0 || PY_VERSION_HEX >= 0x030B00A2 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #elif !defined(CYTHON_USE_UNICODE_WRITER) + #define CYTHON_USE_UNICODE_WRITER 1 + #endif + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #ifndef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 1 + #endif + #ifndef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL (PY_MAJOR_VERSION < 3 || PY_VERSION_HEX >= 0x03060000 && PY_VERSION_HEX < 0x030C00A6) + #endif + #ifndef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL (PY_VERSION_HEX >= 0x030700A1) + #endif + #ifndef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 1 + #endif + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #endif + #if PY_VERSION_HEX < 0x030400a1 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #elif !defined(CYTHON_USE_TP_FINALIZE) + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #if PY_VERSION_HEX < 0x030600B1 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #elif !defined(CYTHON_USE_DICT_VERSIONS) + #define CYTHON_USE_DICT_VERSIONS (PY_VERSION_HEX < 0x030C00A5) + #endif + #if PY_VERSION_HEX < 0x030700A3 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #elif !defined(CYTHON_USE_EXC_INFO_STACK) + #define CYTHON_USE_EXC_INFO_STACK 1 + #endif + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 1 + #endif +#endif +#if !defined(CYTHON_FAST_PYCCALL) +#define CYTHON_FAST_PYCCALL (CYTHON_FAST_PYCALL && PY_VERSION_HEX >= 0x030600B1) +#endif +#if !defined(CYTHON_VECTORCALL) +#define CYTHON_VECTORCALL (CYTHON_FAST_PYCCALL && PY_VERSION_HEX >= 0x030800B1) +#endif +#define CYTHON_BACKPORT_VECTORCALL (CYTHON_METH_FASTCALL && PY_VERSION_HEX < 0x030800B1) +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_MAJOR_VERSION < 3 + #include "longintrepr.h" + #endif + #undef SHIFT + #undef BASE + #undef MASK + #ifdef SIZEOF_VOID_P + enum { __pyx_check_sizeof_voidp = 1 / (int)(SIZEOF_VOID_P == sizeof(void*)) }; + #endif +#endif +#ifndef __has_attribute + #define __has_attribute(x) 0 +#endif +#ifndef __has_cpp_attribute + #define __has_cpp_attribute(x) 0 +#endif +#ifndef CYTHON_RESTRICT + #if defined(__GNUC__) + #define CYTHON_RESTRICT __restrict__ + #elif defined(_MSC_VER) && _MSC_VER >= 1400 + #define CYTHON_RESTRICT __restrict + #elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define CYTHON_RESTRICT restrict + #else + #define CYTHON_RESTRICT + #endif +#endif +#ifndef CYTHON_UNUSED + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(maybe_unused) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(maybe_unused) + #define CYTHON_UNUSED [[maybe_unused]] + #endif + #endif + #endif +#endif +#ifndef CYTHON_UNUSED +# if defined(__GNUC__) +# if !(defined(__cplusplus)) || (__GNUC__ > 3 || (__GNUC__ == 3 && __GNUC_MINOR__ >= 4)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +# elif defined(__ICC) || (defined(__INTEL_COMPILER) && !defined(_MSC_VER)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +#endif +#ifndef CYTHON_UNUSED_VAR +# if defined(__cplusplus) + template void CYTHON_UNUSED_VAR( const T& ) { } +# else +# define CYTHON_UNUSED_VAR(x) (void)(x) +# endif +#endif +#ifndef CYTHON_MAYBE_UNUSED_VAR + #define CYTHON_MAYBE_UNUSED_VAR(x) CYTHON_UNUSED_VAR(x) +#endif +#ifndef CYTHON_NCP_UNUSED +# if CYTHON_COMPILING_IN_CPYTHON +# define CYTHON_NCP_UNUSED +# else +# define CYTHON_NCP_UNUSED CYTHON_UNUSED +# endif +#endif +#ifndef CYTHON_USE_CPP_STD_MOVE + #if defined(__cplusplus) && (\ + __cplusplus >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1600)) + #define CYTHON_USE_CPP_STD_MOVE 1 + #else + #define CYTHON_USE_CPP_STD_MOVE 0 + #endif +#endif +#define __Pyx_void_to_None(void_result) ((void)(void_result), Py_INCREF(Py_None), Py_None) +#ifdef _MSC_VER + #ifndef _MSC_STDINT_H_ + #if _MSC_VER < 1300 + typedef unsigned char uint8_t; + typedef unsigned short uint16_t; + typedef unsigned int uint32_t; + #else + typedef unsigned __int8 uint8_t; + typedef unsigned __int16 uint16_t; + typedef unsigned __int32 uint32_t; + #endif + #endif + #if _MSC_VER < 1300 + #ifdef _WIN64 + typedef unsigned long long __pyx_uintptr_t; + #else + typedef unsigned int __pyx_uintptr_t; + #endif + #else + #ifdef _WIN64 + typedef unsigned __int64 __pyx_uintptr_t; + #else + typedef unsigned __int32 __pyx_uintptr_t; + #endif + #endif +#else + #include + typedef uintptr_t __pyx_uintptr_t; +#endif +#ifndef CYTHON_FALLTHROUGH + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(fallthrough) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(fallthrough) + #define CYTHON_FALLTHROUGH [[fallthrough]] + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_cpp_attribute(clang::fallthrough) + #define CYTHON_FALLTHROUGH [[clang::fallthrough]] + #elif __has_cpp_attribute(gnu::fallthrough) + #define CYTHON_FALLTHROUGH [[gnu::fallthrough]] + #endif + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_attribute(fallthrough) + #define CYTHON_FALLTHROUGH __attribute__((fallthrough)) + #else + #define CYTHON_FALLTHROUGH + #endif + #endif + #if defined(__clang__) && defined(__apple_build_version__) + #if __apple_build_version__ < 7000000 + #undef CYTHON_FALLTHROUGH + #define CYTHON_FALLTHROUGH + #endif + #endif +#endif +#ifdef __cplusplus + template + struct __PYX_IS_UNSIGNED_IMPL {static const bool value = T(0) < T(-1);}; + #define __PYX_IS_UNSIGNED(type) (__PYX_IS_UNSIGNED_IMPL::value) +#else + #define __PYX_IS_UNSIGNED(type) (((type)-1) > 0) +#endif +#if CYTHON_COMPILING_IN_PYPY == 1 + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x030A0000) +#else + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x03090000) +#endif +#define __PYX_REINTERPRET_FUNCION(func_pointer, other_pointer) ((func_pointer)(void(*)(void))(other_pointer)) + +#ifndef __cplusplus + #error "Cython files generated with the C++ option must be compiled with a C++ compiler." +#endif +#ifndef CYTHON_INLINE + #if defined(__clang__) + #define CYTHON_INLINE __inline__ __attribute__ ((__unused__)) + #else + #define CYTHON_INLINE inline + #endif +#endif +template +void __Pyx_call_destructor(T& x) { + x.~T(); +} +template +class __Pyx_FakeReference { + public: + __Pyx_FakeReference() : ptr(NULL) { } + __Pyx_FakeReference(const T& ref) : ptr(const_cast(&ref)) { } + T *operator->() { return ptr; } + T *operator&() { return ptr; } + operator T&() { return *ptr; } + template bool operator ==(const U& other) const { return *ptr == other; } + template bool operator !=(const U& other) const { return *ptr != other; } + template bool operator==(const __Pyx_FakeReference& other) const { return *ptr == *other.ptr; } + template bool operator!=(const __Pyx_FakeReference& other) const { return *ptr != *other.ptr; } + private: + T *ptr; +}; + +#define __PYX_BUILD_PY_SSIZE_T "n" +#define CYTHON_FORMAT_SSIZE_T "z" +#if PY_MAJOR_VERSION < 3 + #define __Pyx_BUILTIN_MODULE_NAME "__builtin__" + #define __Pyx_DefaultClassType PyClass_Type + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a+k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_BUILTIN_MODULE_NAME "builtins" + #define __Pyx_DefaultClassType PyType_Type +#if CYTHON_COMPILING_IN_LIMITED_API + static CYTHON_INLINE PyObject* __Pyx_PyCode_New(int a, int p, int k, int l, int s, int f, + PyObject *code, PyObject *c, PyObject* n, PyObject *v, + PyObject *fv, PyObject *cell, PyObject* fn, + PyObject *name, int fline, PyObject *lnos) { + PyObject *exception_table = NULL; + PyObject *types_module=NULL, *code_type=NULL, *result=NULL; + #if __PYX_LIMITED_VERSION_HEX < 0x030B0000 + PyObject *version_info; + PyObject *py_minor_version = NULL; + #endif + long minor_version = 0; + PyObject *type, *value, *traceback; + PyErr_Fetch(&type, &value, &traceback); + #if __PYX_LIMITED_VERSION_HEX >= 0x030B0000 + minor_version = 11; + #else + if (!(version_info = PySys_GetObject("version_info"))) goto end; + if (!(py_minor_version = PySequence_GetItem(version_info, 1))) goto end; + minor_version = PyLong_AsLong(py_minor_version); + Py_DECREF(py_minor_version); + if (minor_version == -1 && PyErr_Occurred()) goto end; + #endif + if (!(types_module = PyImport_ImportModule("types"))) goto end; + if (!(code_type = PyObject_GetAttrString(types_module, "CodeType"))) goto end; + if (minor_version <= 7) { + (void)p; + result = PyObject_CallFunction(code_type, "iiiiiOOOOOOiOO", a, k, l, s, f, code, + c, n, v, fn, name, fline, lnos, fv, cell); + } else if (minor_version <= 10) { + result = PyObject_CallFunction(code_type, "iiiiiiOOOOOOiOO", a,p, k, l, s, f, code, + c, n, v, fn, name, fline, lnos, fv, cell); + } else { + if (!(exception_table = PyBytes_FromStringAndSize(NULL, 0))) goto end; + result = PyObject_CallFunction(code_type, "iiiiiiOOOOOOOiOO", a,p, k, l, s, f, code, + c, n, v, fn, name, name, fline, lnos, exception_table, fv, cell); + } + end: + Py_XDECREF(code_type); + Py_XDECREF(exception_table); + Py_XDECREF(types_module); + if (type) { + PyErr_Restore(type, value, traceback); + } + return result; + } + #ifndef CO_OPTIMIZED + #define CO_OPTIMIZED 0x0001 + #endif + #ifndef CO_NEWLOCALS + #define CO_NEWLOCALS 0x0002 + #endif + #ifndef CO_VARARGS + #define CO_VARARGS 0x0004 + #endif + #ifndef CO_VARKEYWORDS + #define CO_VARKEYWORDS 0x0008 + #endif + #ifndef CO_ASYNC_GENERATOR + #define CO_ASYNC_GENERATOR 0x0200 + #endif + #ifndef CO_GENERATOR + #define CO_GENERATOR 0x0020 + #endif + #ifndef CO_COROUTINE + #define CO_COROUTINE 0x0080 + #endif +#elif PY_VERSION_HEX >= 0x030B0000 + static CYTHON_INLINE PyCodeObject* __Pyx_PyCode_New(int a, int p, int k, int l, int s, int f, + PyObject *code, PyObject *c, PyObject* n, PyObject *v, + PyObject *fv, PyObject *cell, PyObject* fn, + PyObject *name, int fline, PyObject *lnos) { + PyCodeObject *result; + PyObject *empty_bytes = PyBytes_FromStringAndSize("", 0); + if (!empty_bytes) return NULL; + result = + #if PY_VERSION_HEX >= 0x030C0000 + PyUnstable_Code_NewWithPosOnlyArgs + #else + PyCode_NewWithPosOnlyArgs + #endif + (a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, name, fline, lnos, empty_bytes); + Py_DECREF(empty_bytes); + return result; + } +#elif PY_VERSION_HEX >= 0x030800B2 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_NewWithPosOnlyArgs(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#endif +#endif +#if PY_VERSION_HEX >= 0x030900A4 || defined(Py_IS_TYPE) + #define __Pyx_IS_TYPE(ob, type) Py_IS_TYPE(ob, type) +#else + #define __Pyx_IS_TYPE(ob, type) (((const PyObject*)ob)->ob_type == (type)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_Is) + #define __Pyx_Py_Is(x, y) Py_Is(x, y) +#else + #define __Pyx_Py_Is(x, y) ((x) == (y)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsNone) + #define __Pyx_Py_IsNone(ob) Py_IsNone(ob) +#else + #define __Pyx_Py_IsNone(ob) __Pyx_Py_Is((ob), Py_None) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsTrue) + #define __Pyx_Py_IsTrue(ob) Py_IsTrue(ob) +#else + #define __Pyx_Py_IsTrue(ob) __Pyx_Py_Is((ob), Py_True) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsFalse) + #define __Pyx_Py_IsFalse(ob) Py_IsFalse(ob) +#else + #define __Pyx_Py_IsFalse(ob) __Pyx_Py_Is((ob), Py_False) +#endif +#define __Pyx_NoneAsNull(obj) (__Pyx_Py_IsNone(obj) ? NULL : (obj)) +#if PY_VERSION_HEX >= 0x030900F0 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_GC_IsFinalized(o) PyObject_GC_IsFinalized(o) +#else + #define __Pyx_PyObject_GC_IsFinalized(o) _PyGC_FINALIZED(o) +#endif +#ifndef CO_COROUTINE + #define CO_COROUTINE 0x80 +#endif +#ifndef CO_ASYNC_GENERATOR + #define CO_ASYNC_GENERATOR 0x200 +#endif +#ifndef Py_TPFLAGS_CHECKTYPES + #define Py_TPFLAGS_CHECKTYPES 0 +#endif +#ifndef Py_TPFLAGS_HAVE_INDEX + #define Py_TPFLAGS_HAVE_INDEX 0 +#endif +#ifndef Py_TPFLAGS_HAVE_NEWBUFFER + #define Py_TPFLAGS_HAVE_NEWBUFFER 0 +#endif +#ifndef Py_TPFLAGS_HAVE_FINALIZE + #define Py_TPFLAGS_HAVE_FINALIZE 0 +#endif +#ifndef Py_TPFLAGS_SEQUENCE + #define Py_TPFLAGS_SEQUENCE 0 +#endif +#ifndef Py_TPFLAGS_MAPPING + #define Py_TPFLAGS_MAPPING 0 +#endif +#ifndef METH_STACKLESS + #define METH_STACKLESS 0 +#endif +#if PY_VERSION_HEX <= 0x030700A3 || !defined(METH_FASTCALL) + #ifndef METH_FASTCALL + #define METH_FASTCALL 0x80 + #endif + typedef PyObject *(*__Pyx_PyCFunctionFast) (PyObject *self, PyObject *const *args, Py_ssize_t nargs); + typedef PyObject *(*__Pyx_PyCFunctionFastWithKeywords) (PyObject *self, PyObject *const *args, + Py_ssize_t nargs, PyObject *kwnames); +#else + #define __Pyx_PyCFunctionFast _PyCFunctionFast + #define __Pyx_PyCFunctionFastWithKeywords _PyCFunctionFastWithKeywords +#endif +#if CYTHON_METH_FASTCALL + #define __Pyx_METH_FASTCALL METH_FASTCALL + #define __Pyx_PyCFunction_FastCall __Pyx_PyCFunctionFast + #define __Pyx_PyCFunction_FastCallWithKeywords __Pyx_PyCFunctionFastWithKeywords +#else + #define __Pyx_METH_FASTCALL METH_VARARGS + #define __Pyx_PyCFunction_FastCall PyCFunction + #define __Pyx_PyCFunction_FastCallWithKeywords PyCFunctionWithKeywords +#endif +#if CYTHON_VECTORCALL + #define __pyx_vectorcallfunc vectorcallfunc + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET PY_VECTORCALL_ARGUMENTS_OFFSET + #define __Pyx_PyVectorcall_NARGS(n) PyVectorcall_NARGS((size_t)(n)) +#elif CYTHON_BACKPORT_VECTORCALL + typedef PyObject *(*__pyx_vectorcallfunc)(PyObject *callable, PyObject *const *args, + size_t nargsf, PyObject *kwnames); + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET ((size_t)1 << (8 * sizeof(size_t) - 1)) + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(((size_t)(n)) & ~__Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET)) +#else + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET 0 + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(n)) +#endif +#if PY_MAJOR_VERSION >= 0x030900B1 +#define __Pyx_PyCFunction_CheckExact(func) PyCFunction_CheckExact(func) +#else +#define __Pyx_PyCFunction_CheckExact(func) PyCFunction_Check(func) +#endif +#define __Pyx_CyOrPyCFunction_Check(func) PyCFunction_Check(func) +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_CyOrPyCFunction_GET_FUNCTION(func) (((PyCFunctionObject*)(func))->m_ml->ml_meth) +#elif !CYTHON_COMPILING_IN_LIMITED_API +#define __Pyx_CyOrPyCFunction_GET_FUNCTION(func) PyCFunction_GET_FUNCTION(func) +#endif +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_CyOrPyCFunction_GET_FLAGS(func) (((PyCFunctionObject*)(func))->m_ml->ml_flags) +static CYTHON_INLINE PyObject* __Pyx_CyOrPyCFunction_GET_SELF(PyObject *func) { + return (__Pyx_CyOrPyCFunction_GET_FLAGS(func) & METH_STATIC) ? NULL : ((PyCFunctionObject*)func)->m_self; +} +#endif +static CYTHON_INLINE int __Pyx__IsSameCFunction(PyObject *func, void *cfunc) { +#if CYTHON_COMPILING_IN_LIMITED_API + return PyCFunction_Check(func) && PyCFunction_GetFunction(func) == (PyCFunction) cfunc; +#else + return PyCFunction_Check(func) && PyCFunction_GET_FUNCTION(func) == (PyCFunction) cfunc; +#endif +} +#define __Pyx_IsSameCFunction(func, cfunc) __Pyx__IsSameCFunction(func, cfunc) +#if __PYX_LIMITED_VERSION_HEX < 0x030900B1 + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) ((void)m, PyType_FromSpecWithBases(s, b)) + typedef PyObject *(*__Pyx_PyCMethod)(PyObject *, PyTypeObject *, PyObject *const *, size_t, PyObject *); +#else + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) PyType_FromModuleAndSpec(m, s, b) + #define __Pyx_PyCMethod PyCMethod +#endif +#ifndef METH_METHOD + #define METH_METHOD 0x200 +#endif +#if CYTHON_COMPILING_IN_PYPY && !defined(PyObject_Malloc) + #define PyObject_Malloc(s) PyMem_Malloc(s) + #define PyObject_Free(p) PyMem_Free(p) + #define PyObject_Realloc(p) PyMem_Realloc(p) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) +#else + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) (frame)->f_lineno = (lineno) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyThreadState_Current PyThreadState_Get() +#elif !CYTHON_FAST_THREAD_STATE + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#elif PY_VERSION_HEX >= 0x030d00A1 + #define __Pyx_PyThreadState_Current PyThreadState_GetUnchecked() +#elif PY_VERSION_HEX >= 0x03060000 + #define __Pyx_PyThreadState_Current _PyThreadState_UncheckedGet() +#elif PY_VERSION_HEX >= 0x03000000 + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#else + #define __Pyx_PyThreadState_Current _PyThreadState_Current +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE void *__Pyx_PyModule_GetState(PyObject *op) +{ + void *result; + result = PyModule_GetState(op); + if (!result) + Py_FatalError("Couldn't find the module state"); + return result; +} +#endif +#define __Pyx_PyObject_GetSlot(obj, name, func_ctype) __Pyx_PyType_GetSlot(Py_TYPE(obj), name, func_ctype) +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((func_ctype) PyType_GetSlot((type), Py_##name)) +#else + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((type)->name) +#endif +#if PY_VERSION_HEX < 0x030700A2 && !defined(PyThread_tss_create) && !defined(Py_tss_NEEDS_INIT) +#include "pythread.h" +#define Py_tss_NEEDS_INIT 0 +typedef int Py_tss_t; +static CYTHON_INLINE int PyThread_tss_create(Py_tss_t *key) { + *key = PyThread_create_key(); + return 0; +} +static CYTHON_INLINE Py_tss_t * PyThread_tss_alloc(void) { + Py_tss_t *key = (Py_tss_t *)PyObject_Malloc(sizeof(Py_tss_t)); + *key = Py_tss_NEEDS_INIT; + return key; +} +static CYTHON_INLINE void PyThread_tss_free(Py_tss_t *key) { + PyObject_Free(key); +} +static CYTHON_INLINE int PyThread_tss_is_created(Py_tss_t *key) { + return *key != Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE void PyThread_tss_delete(Py_tss_t *key) { + PyThread_delete_key(*key); + *key = Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE int PyThread_tss_set(Py_tss_t *key, void *value) { + return PyThread_set_key_value(*key, value); +} +static CYTHON_INLINE void * PyThread_tss_get(Py_tss_t *key) { + return PyThread_get_key_value(*key); +} +#endif +#if PY_MAJOR_VERSION < 3 + #if CYTHON_COMPILING_IN_PYPY + #if PYPY_VERSION_NUM < 0x07030600 + #if defined(__cplusplus) && __cplusplus >= 201402L + [[deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")]] + #elif defined(__GNUC__) || defined(__clang__) + __attribute__ ((__deprecated__("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6"))) + #elif defined(_MSC_VER) + __declspec(deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")) + #endif + static CYTHON_INLINE int PyGILState_Check(void) { + return 0; + } + #else // PYPY_VERSION_NUM < 0x07030600 + #endif // PYPY_VERSION_NUM < 0x07030600 + #else + static CYTHON_INLINE int PyGILState_Check(void) { + PyThreadState * tstate = _PyThreadState_Current; + return tstate && (tstate == PyGILState_GetThisThreadState()); + } + #endif +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030d0000 || defined(_PyDict_NewPresized) +#define __Pyx_PyDict_NewPresized(n) ((n <= 8) ? PyDict_New() : _PyDict_NewPresized(n)) +#else +#define __Pyx_PyDict_NewPresized(n) PyDict_New() +#endif +#if PY_MAJOR_VERSION >= 3 || CYTHON_FUTURE_DIVISION + #define __Pyx_PyNumber_Divide(x,y) PyNumber_TrueDivide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceTrueDivide(x,y) +#else + #define __Pyx_PyNumber_Divide(x,y) PyNumber_Divide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceDivide(x,y) +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX > 0x030600B4 && PY_VERSION_HEX < 0x030d0000 && CYTHON_USE_UNICODE_INTERNALS +#define __Pyx_PyDict_GetItemStrWithError(dict, name) _PyDict_GetItem_KnownHash(dict, name, ((PyASCIIObject *) name)->hash) +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStr(PyObject *dict, PyObject *name) { + PyObject *res = __Pyx_PyDict_GetItemStrWithError(dict, name); + if (res == NULL) PyErr_Clear(); + return res; +} +#elif PY_MAJOR_VERSION >= 3 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07020000) +#define __Pyx_PyDict_GetItemStrWithError PyDict_GetItemWithError +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#else +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStrWithError(PyObject *dict, PyObject *name) { +#if CYTHON_COMPILING_IN_PYPY + return PyDict_GetItem(dict, name); +#else + PyDictEntry *ep; + PyDictObject *mp = (PyDictObject*) dict; + long hash = ((PyStringObject *) name)->ob_shash; + assert(hash != -1); + ep = (mp->ma_lookup)(mp, name, hash); + if (ep == NULL) { + return NULL; + } + return ep->me_value; +#endif +} +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#endif +#if CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyType_GetFlags(tp) (((PyTypeObject *)tp)->tp_flags) + #define __Pyx_PyType_HasFeature(type, feature) ((__Pyx_PyType_GetFlags(type) & (feature)) != 0) + #define __Pyx_PyObject_GetIterNextFunc(obj) (Py_TYPE(obj)->tp_iternext) +#else + #define __Pyx_PyType_GetFlags(tp) (PyType_GetFlags((PyTypeObject *)tp)) + #define __Pyx_PyType_HasFeature(type, feature) PyType_HasFeature(type, feature) + #define __Pyx_PyObject_GetIterNextFunc(obj) PyIter_Next +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_SetItemOnTypeDict(tp, k, v) PyObject_GenericSetAttr((PyObject*)tp, k, v) +#else + #define __Pyx_SetItemOnTypeDict(tp, k, v) PyDict_SetItem(tp->tp_dict, k, v) +#endif +#if CYTHON_USE_TYPE_SPECS && PY_VERSION_HEX >= 0x03080000 +#define __Pyx_PyHeapTypeObject_GC_Del(obj) {\ + PyTypeObject *type = Py_TYPE((PyObject*)obj);\ + assert(__Pyx_PyType_HasFeature(type, Py_TPFLAGS_HEAPTYPE));\ + PyObject_GC_Del(obj);\ + Py_DECREF(type);\ +} +#else +#define __Pyx_PyHeapTypeObject_GC_Del(obj) PyObject_GC_Del(obj) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define CYTHON_PEP393_ENABLED 1 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GetLength(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_ReadChar(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((void)u, 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((void)u, (0)) + #define __Pyx_PyUnicode_DATA(u) ((void*)u) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)k, PyUnicode_ReadChar((PyObject*)(d), i)) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GetLength(u)) +#elif PY_VERSION_HEX > 0x03030000 && defined(PyUnicode_KIND) + #define CYTHON_PEP393_ENABLED 1 + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_READY(op) (0) + #else + #define __Pyx_PyUnicode_READY(op) (likely(PyUnicode_IS_READY(op)) ?\ + 0 : _PyUnicode_Ready((PyObject *)(op))) + #endif + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_LENGTH(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_READ_CHAR(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) PyUnicode_MAX_CHAR_VALUE(u) + #define __Pyx_PyUnicode_KIND(u) ((int)PyUnicode_KIND(u)) + #define __Pyx_PyUnicode_DATA(u) PyUnicode_DATA(u) + #define __Pyx_PyUnicode_READ(k, d, i) PyUnicode_READ(k, d, i) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) PyUnicode_WRITE(k, d, i, (Py_UCS4) ch) + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_LENGTH(u)) + #else + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x03090000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : ((PyCompactUnicodeObject *)(u))->wstr_length)) + #else + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : PyUnicode_GET_SIZE(u))) + #endif + #endif +#else + #define CYTHON_PEP393_ENABLED 0 + #define PyUnicode_1BYTE_KIND 1 + #define PyUnicode_2BYTE_KIND 2 + #define PyUnicode_4BYTE_KIND 4 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_SIZE(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) ((Py_UCS4)(PyUnicode_AS_UNICODE(u)[i])) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((sizeof(Py_UNICODE) == 2) ? 65535U : 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((int)sizeof(Py_UNICODE)) + #define __Pyx_PyUnicode_DATA(u) ((void*)PyUnicode_AS_UNICODE(u)) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)(k), (Py_UCS4)(((Py_UNICODE*)d)[i])) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) (((void)(k)), ((Py_UNICODE*)d)[i] = (Py_UNICODE) ch) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_SIZE(u)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyUnicode_Concat(a, b) PyNumber_Add(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) PyNumber_Add(a, b) +#else + #define __Pyx_PyUnicode_Concat(a, b) PyUnicode_Concat(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) ((unlikely((a) == Py_None) || unlikely((b) == Py_None)) ?\ + PyNumber_Add(a, b) : __Pyx_PyUnicode_Concat(a, b)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #if !defined(PyUnicode_DecodeUnicodeEscape) + #define PyUnicode_DecodeUnicodeEscape(s, size, errors) PyUnicode_Decode(s, size, "unicode_escape", errors) + #endif + #if !defined(PyUnicode_Contains) || (PY_MAJOR_VERSION == 2 && PYPY_VERSION_NUM < 0x07030500) + #undef PyUnicode_Contains + #define PyUnicode_Contains(u, s) PySequence_Contains(u, s) + #endif + #if !defined(PyByteArray_Check) + #define PyByteArray_Check(obj) PyObject_TypeCheck(obj, &PyByteArray_Type) + #endif + #if !defined(PyObject_Format) + #define PyObject_Format(obj, fmt) PyObject_CallMethod(obj, "__format__", "O", fmt) + #endif +#endif +#define __Pyx_PyString_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyString_Check(b) && !PyString_CheckExact(b)))) ? PyNumber_Remainder(a, b) : __Pyx_PyString_Format(a, b)) +#define __Pyx_PyUnicode_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyUnicode_Check(b) && !PyUnicode_CheckExact(b)))) ? PyNumber_Remainder(a, b) : PyUnicode_Format(a, b)) +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyString_Format(a, b) PyUnicode_Format(a, b) +#else + #define __Pyx_PyString_Format(a, b) PyString_Format(a, b) +#endif +#if PY_MAJOR_VERSION < 3 && !defined(PyObject_ASCII) + #define PyObject_ASCII(o) PyObject_Repr(o) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBaseString_Type PyUnicode_Type + #define PyStringObject PyUnicodeObject + #define PyString_Type PyUnicode_Type + #define PyString_Check PyUnicode_Check + #define PyString_CheckExact PyUnicode_CheckExact +#ifndef PyObject_Unicode + #define PyObject_Unicode PyObject_Str +#endif +#endif +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyBaseString_Check(obj) PyUnicode_Check(obj) + #define __Pyx_PyBaseString_CheckExact(obj) PyUnicode_CheckExact(obj) +#else + #define __Pyx_PyBaseString_Check(obj) (PyString_Check(obj) || PyUnicode_Check(obj)) + #define __Pyx_PyBaseString_CheckExact(obj) (PyString_CheckExact(obj) || PyUnicode_CheckExact(obj)) +#endif +#if CYTHON_COMPILING_IN_CPYTHON + #define __Pyx_PySequence_ListKeepNew(obj)\ + (likely(PyList_CheckExact(obj) && Py_REFCNT(obj) == 1) ? __Pyx_NewRef(obj) : PySequence_List(obj)) +#else + #define __Pyx_PySequence_ListKeepNew(obj) PySequence_List(obj) +#endif +#ifndef PySet_CheckExact + #define PySet_CheckExact(obj) __Pyx_IS_TYPE(obj, &PySet_Type) +#endif +#if PY_VERSION_HEX >= 0x030900A4 + #define __Pyx_SET_REFCNT(obj, refcnt) Py_SET_REFCNT(obj, refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SET_SIZE(obj, size) +#else + #define __Pyx_SET_REFCNT(obj, refcnt) Py_REFCNT(obj) = (refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SIZE(obj) = (size) +#endif +#if CYTHON_ASSUME_SAFE_MACROS + #define __Pyx_PySequence_ITEM(o, i) PySequence_ITEM(o, i) + #define __Pyx_PySequence_SIZE(seq) Py_SIZE(seq) + #define __Pyx_PyTuple_SET_ITEM(o, i, v) (PyTuple_SET_ITEM(o, i, v), (0)) + #define __Pyx_PyList_SET_ITEM(o, i, v) (PyList_SET_ITEM(o, i, v), (0)) + #define __Pyx_PyTuple_GET_SIZE(o) PyTuple_GET_SIZE(o) + #define __Pyx_PyList_GET_SIZE(o) PyList_GET_SIZE(o) + #define __Pyx_PySet_GET_SIZE(o) PySet_GET_SIZE(o) + #define __Pyx_PyBytes_GET_SIZE(o) PyBytes_GET_SIZE(o) + #define __Pyx_PyByteArray_GET_SIZE(o) PyByteArray_GET_SIZE(o) +#else + #define __Pyx_PySequence_ITEM(o, i) PySequence_GetItem(o, i) + #define __Pyx_PySequence_SIZE(seq) PySequence_Size(seq) + #define __Pyx_PyTuple_SET_ITEM(o, i, v) PyTuple_SetItem(o, i, v) + #define __Pyx_PyList_SET_ITEM(o, i, v) PyList_SetItem(o, i, v) + #define __Pyx_PyTuple_GET_SIZE(o) PyTuple_Size(o) + #define __Pyx_PyList_GET_SIZE(o) PyList_Size(o) + #define __Pyx_PySet_GET_SIZE(o) PySet_Size(o) + #define __Pyx_PyBytes_GET_SIZE(o) PyBytes_Size(o) + #define __Pyx_PyByteArray_GET_SIZE(o) PyByteArray_Size(o) +#endif +#if PY_VERSION_HEX >= 0x030d00A1 + #define __Pyx_PyImport_AddModuleRef(name) PyImport_AddModuleRef(name) +#else + static CYTHON_INLINE PyObject *__Pyx_PyImport_AddModuleRef(const char *name) { + PyObject *module = PyImport_AddModule(name); + Py_XINCREF(module); + return module; + } +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyIntObject PyLongObject + #define PyInt_Type PyLong_Type + #define PyInt_Check(op) PyLong_Check(op) + #define PyInt_CheckExact(op) PyLong_CheckExact(op) + #define __Pyx_Py3Int_Check(op) PyLong_Check(op) + #define __Pyx_Py3Int_CheckExact(op) PyLong_CheckExact(op) + #define PyInt_FromString PyLong_FromString + #define PyInt_FromUnicode PyLong_FromUnicode + #define PyInt_FromLong PyLong_FromLong + #define PyInt_FromSize_t PyLong_FromSize_t + #define PyInt_FromSsize_t PyLong_FromSsize_t + #define PyInt_AsLong PyLong_AsLong + #define PyInt_AS_LONG PyLong_AS_LONG + #define PyInt_AsSsize_t PyLong_AsSsize_t + #define PyInt_AsUnsignedLongMask PyLong_AsUnsignedLongMask + #define PyInt_AsUnsignedLongLongMask PyLong_AsUnsignedLongLongMask + #define PyNumber_Int PyNumber_Long +#else + #define __Pyx_Py3Int_Check(op) (PyLong_Check(op) || PyInt_Check(op)) + #define __Pyx_Py3Int_CheckExact(op) (PyLong_CheckExact(op) || PyInt_CheckExact(op)) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBoolObject PyLongObject +#endif +#if PY_MAJOR_VERSION >= 3 && CYTHON_COMPILING_IN_PYPY + #ifndef PyUnicode_InternFromString + #define PyUnicode_InternFromString(s) PyUnicode_FromString(s) + #endif +#endif +#if PY_VERSION_HEX < 0x030200A4 + typedef long Py_hash_t; + #define __Pyx_PyInt_FromHash_t PyInt_FromLong + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsHash_t +#else + #define __Pyx_PyInt_FromHash_t PyInt_FromSsize_t + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsSsize_t +#endif +#if CYTHON_USE_ASYNC_SLOTS + #if PY_VERSION_HEX >= 0x030500B1 + #define __Pyx_PyAsyncMethodsStruct PyAsyncMethods + #define __Pyx_PyType_AsAsync(obj) (Py_TYPE(obj)->tp_as_async) + #else + #define __Pyx_PyType_AsAsync(obj) ((__Pyx_PyAsyncMethodsStruct*) (Py_TYPE(obj)->tp_reserved)) + #endif +#else + #define __Pyx_PyType_AsAsync(obj) NULL +#endif +#ifndef __Pyx_PyAsyncMethodsStruct + typedef struct { + unaryfunc am_await; + unaryfunc am_aiter; + unaryfunc am_anext; + } __Pyx_PyAsyncMethodsStruct; +#endif + +#if defined(_WIN32) || defined(WIN32) || defined(MS_WINDOWS) + #if !defined(_USE_MATH_DEFINES) + #define _USE_MATH_DEFINES + #endif +#endif +#include +#ifdef NAN +#define __PYX_NAN() ((float) NAN) +#else +static CYTHON_INLINE float __PYX_NAN() { + float value; + memset(&value, 0xFF, sizeof(value)); + return value; +} +#endif +#if defined(__CYGWIN__) && defined(_LDBL_EQ_DBL) +#define __Pyx_truncl trunc +#else +#define __Pyx_truncl truncl +#endif + +#define __PYX_MARK_ERR_POS(f_index, lineno) \ + { __pyx_filename = __pyx_f[f_index]; (void)__pyx_filename; __pyx_lineno = lineno; (void)__pyx_lineno; __pyx_clineno = __LINE__; (void)__pyx_clineno; } +#define __PYX_ERR(f_index, lineno, Ln_error) \ + { __PYX_MARK_ERR_POS(f_index, lineno) goto Ln_error; } + +#ifdef CYTHON_EXTERN_C + #undef __PYX_EXTERN_C + #define __PYX_EXTERN_C CYTHON_EXTERN_C +#elif defined(__PYX_EXTERN_C) + #ifdef _MSC_VER + #pragma message ("Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead.") + #else + #warning Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead. + #endif +#else + #define __PYX_EXTERN_C extern "C++" +#endif + +#define __PYX_HAVE__opendbc__can__parser_pyx +#define __PYX_HAVE_API__opendbc__can__parser_pyx +/* Early includes */ +#include "ios" +#include "new" +#include "stdexcept" +#include "typeinfo" +#include + + #if __cplusplus >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1600) + // move should be defined for these versions of MSVC, but __cplusplus isn't set usefully + #include + + namespace cython_std { + template typename std::remove_reference::type&& move(T& t) noexcept { return std::move(t); } + template typename std::remove_reference::type&& move(T&& t) noexcept { return std::move(t); } + } + + #endif + +#include +#include +#include +#include +#include +#include "common_dbc.h" +#include "common.h" +#ifdef _OPENMP +#include +#endif /* _OPENMP */ + +#if defined(PYREX_WITHOUT_ASSERTIONS) && !defined(CYTHON_WITHOUT_ASSERTIONS) +#define CYTHON_WITHOUT_ASSERTIONS +#endif + +typedef struct {PyObject **p; const char *s; const Py_ssize_t n; const char* encoding; + const char is_unicode; const char is_str; const char intern; } __Pyx_StringTabEntry; + +#define __PYX_DEFAULT_STRING_ENCODING_IS_ASCII 1 +#define __PYX_DEFAULT_STRING_ENCODING_IS_UTF8 0 +#define __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT (PY_MAJOR_VERSION >= 3 && __PYX_DEFAULT_STRING_ENCODING_IS_UTF8) +#define __PYX_DEFAULT_STRING_ENCODING "ascii" +#define __Pyx_PyObject_FromString __Pyx_PyBytes_FromString +#define __Pyx_PyObject_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#define __Pyx_uchar_cast(c) ((unsigned char)c) +#define __Pyx_long_cast(x) ((long)x) +#define __Pyx_fits_Py_ssize_t(v, type, is_signed) (\ + (sizeof(type) < sizeof(Py_ssize_t)) ||\ + (sizeof(type) > sizeof(Py_ssize_t) &&\ + likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX) &&\ + (!is_signed || likely(v > (type)PY_SSIZE_T_MIN ||\ + v == (type)PY_SSIZE_T_MIN))) ||\ + (sizeof(type) == sizeof(Py_ssize_t) &&\ + (is_signed || likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX))) ) +static CYTHON_INLINE int __Pyx_is_valid_index(Py_ssize_t i, Py_ssize_t limit) { + return (size_t) i < (size_t) limit; +} +#if defined (__cplusplus) && __cplusplus >= 201103L + #include + #define __Pyx_sst_abs(value) std::abs(value) +#elif SIZEOF_INT >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) abs(value) +#elif SIZEOF_LONG >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) labs(value) +#elif defined (_MSC_VER) + #define __Pyx_sst_abs(value) ((Py_ssize_t)_abs64(value)) +#elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define __Pyx_sst_abs(value) llabs(value) +#elif defined (__GNUC__) + #define __Pyx_sst_abs(value) __builtin_llabs(value) +#else + #define __Pyx_sst_abs(value) ((value<0) ? -value : value) +#endif +static CYTHON_INLINE Py_ssize_t __Pyx_ssize_strlen(const char *s); +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject*); +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject*, Py_ssize_t* length); +static CYTHON_INLINE PyObject* __Pyx_PyByteArray_FromString(const char*); +#define __Pyx_PyByteArray_FromStringAndSize(s, l) PyByteArray_FromStringAndSize((const char*)s, l) +#define __Pyx_PyBytes_FromString PyBytes_FromString +#define __Pyx_PyBytes_FromStringAndSize PyBytes_FromStringAndSize +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char*); +#if PY_MAJOR_VERSION < 3 + #define __Pyx_PyStr_FromString __Pyx_PyBytes_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#else + #define __Pyx_PyStr_FromString __Pyx_PyUnicode_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyUnicode_FromStringAndSize +#endif +#define __Pyx_PyBytes_AsWritableString(s) ((char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableSString(s) ((signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableUString(s) ((unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsString(s) ((const char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsSString(s) ((const signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsUString(s) ((const unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyObject_AsWritableString(s) ((char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableSString(s) ((signed char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableUString(s) ((unsigned char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsSString(s) ((const signed char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsUString(s) ((const unsigned char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_FromCString(s) __Pyx_PyObject_FromString((const char*)s) +#define __Pyx_PyBytes_FromCString(s) __Pyx_PyBytes_FromString((const char*)s) +#define __Pyx_PyByteArray_FromCString(s) __Pyx_PyByteArray_FromString((const char*)s) +#define __Pyx_PyStr_FromCString(s) __Pyx_PyStr_FromString((const char*)s) +#define __Pyx_PyUnicode_FromCString(s) __Pyx_PyUnicode_FromString((const char*)s) +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const wchar_t *u) +{ + const wchar_t *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#else +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const Py_UNICODE *u) +{ + const Py_UNICODE *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#endif +#define __Pyx_PyUnicode_FromOrdinal(o) PyUnicode_FromOrdinal((int)o) +#define __Pyx_PyUnicode_FromUnicode(u) PyUnicode_FromUnicode(u, __Pyx_Py_UNICODE_strlen(u)) +#define __Pyx_PyUnicode_FromUnicodeAndLength PyUnicode_FromUnicode +#define __Pyx_PyUnicode_AsUnicode PyUnicode_AsUnicode +#define __Pyx_NewRef(obj) (Py_INCREF(obj), obj) +#define __Pyx_Owned_Py_None(b) __Pyx_NewRef(Py_None) +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b); +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject*); +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject*); +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x); +#define __Pyx_PySequence_Tuple(obj)\ + (likely(PyTuple_CheckExact(obj)) ? __Pyx_NewRef(obj) : PySequence_Tuple(obj)) +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject*); +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t); +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject*); +#if CYTHON_ASSUME_SAFE_MACROS +#define __pyx_PyFloat_AsDouble(x) (PyFloat_CheckExact(x) ? PyFloat_AS_DOUBLE(x) : PyFloat_AsDouble(x)) +#else +#define __pyx_PyFloat_AsDouble(x) PyFloat_AsDouble(x) +#endif +#define __pyx_PyFloat_AsFloat(x) ((float) __pyx_PyFloat_AsDouble(x)) +#if PY_MAJOR_VERSION >= 3 +#define __Pyx_PyNumber_Int(x) (PyLong_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Long(x)) +#else +#define __Pyx_PyNumber_Int(x) (PyInt_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Int(x)) +#endif +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_VERSION_HEX >= 0x030C00A7 + #ifndef _PyLong_SIGN_MASK + #define _PyLong_SIGN_MASK 3 + #endif + #ifndef _PyLong_NON_SIZE_BITS + #define _PyLong_NON_SIZE_BITS 3 + #endif + #define __Pyx_PyLong_Sign(x) (((PyLongObject*)x)->long_value.lv_tag & _PyLong_SIGN_MASK) + #define __Pyx_PyLong_IsNeg(x) ((__Pyx_PyLong_Sign(x) & 2) != 0) + #define __Pyx_PyLong_IsNonNeg(x) (!__Pyx_PyLong_IsNeg(x)) + #define __Pyx_PyLong_IsZero(x) (__Pyx_PyLong_Sign(x) & 1) + #define __Pyx_PyLong_IsPos(x) (__Pyx_PyLong_Sign(x) == 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) (__Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) ((Py_ssize_t) (((PyLongObject*)x)->long_value.lv_tag >> _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_SignedDigitCount(x)\ + ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * __Pyx_PyLong_DigitCount(x)) + #if defined(PyUnstable_Long_IsCompact) && defined(PyUnstable_Long_CompactValue) + #define __Pyx_PyLong_IsCompact(x) PyUnstable_Long_IsCompact((PyLongObject*) x) + #define __Pyx_PyLong_CompactValue(x) PyUnstable_Long_CompactValue((PyLongObject*) x) + #else + #define __Pyx_PyLong_IsCompact(x) (((PyLongObject*)x)->long_value.lv_tag < (2 << _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_CompactValue(x) ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * (Py_ssize_t) __Pyx_PyLong_Digits(x)[0]) + #endif + typedef Py_ssize_t __Pyx_compact_pylong; + typedef size_t __Pyx_compact_upylong; + #else + #define __Pyx_PyLong_IsNeg(x) (Py_SIZE(x) < 0) + #define __Pyx_PyLong_IsNonNeg(x) (Py_SIZE(x) >= 0) + #define __Pyx_PyLong_IsZero(x) (Py_SIZE(x) == 0) + #define __Pyx_PyLong_IsPos(x) (Py_SIZE(x) > 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) ((Py_SIZE(x) == 0) ? 0 : __Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) __Pyx_sst_abs(Py_SIZE(x)) + #define __Pyx_PyLong_SignedDigitCount(x) Py_SIZE(x) + #define __Pyx_PyLong_IsCompact(x) (Py_SIZE(x) == 0 || Py_SIZE(x) == 1 || Py_SIZE(x) == -1) + #define __Pyx_PyLong_CompactValue(x)\ + ((Py_SIZE(x) == 0) ? (sdigit) 0 : ((Py_SIZE(x) < 0) ? -(sdigit)__Pyx_PyLong_Digits(x)[0] : (sdigit)__Pyx_PyLong_Digits(x)[0])) + typedef sdigit __Pyx_compact_pylong; + typedef digit __Pyx_compact_upylong; + #endif + #if PY_VERSION_HEX >= 0x030C00A5 + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->long_value.ob_digit) + #else + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->ob_digit) + #endif +#endif +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII +#include +static int __Pyx_sys_getdefaultencoding_not_ascii; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + PyObject* ascii_chars_u = NULL; + PyObject* ascii_chars_b = NULL; + const char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + if (strcmp(default_encoding_c, "ascii") == 0) { + __Pyx_sys_getdefaultencoding_not_ascii = 0; + } else { + char ascii_chars[128]; + int c; + for (c = 0; c < 128; c++) { + ascii_chars[c] = (char) c; + } + __Pyx_sys_getdefaultencoding_not_ascii = 1; + ascii_chars_u = PyUnicode_DecodeASCII(ascii_chars, 128, NULL); + if (!ascii_chars_u) goto bad; + ascii_chars_b = PyUnicode_AsEncodedString(ascii_chars_u, default_encoding_c, NULL); + if (!ascii_chars_b || !PyBytes_Check(ascii_chars_b) || memcmp(ascii_chars, PyBytes_AS_STRING(ascii_chars_b), 128) != 0) { + PyErr_Format( + PyExc_ValueError, + "This module compiled with c_string_encoding=ascii, but default encoding '%.200s' is not a superset of ascii.", + default_encoding_c); + goto bad; + } + Py_DECREF(ascii_chars_u); + Py_DECREF(ascii_chars_b); + } + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + Py_XDECREF(ascii_chars_u); + Py_XDECREF(ascii_chars_b); + return -1; +} +#endif +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT && PY_MAJOR_VERSION >= 3 +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_DecodeUTF8(c_str, size, NULL) +#else +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_Decode(c_str, size, __PYX_DEFAULT_STRING_ENCODING, NULL) +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +#include +static char* __PYX_DEFAULT_STRING_ENCODING; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) (const char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + __PYX_DEFAULT_STRING_ENCODING = (char*) malloc(strlen(default_encoding_c) + 1); + if (!__PYX_DEFAULT_STRING_ENCODING) goto bad; + strcpy(__PYX_DEFAULT_STRING_ENCODING, default_encoding_c); + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + return -1; +} +#endif +#endif + + +/* Test for GCC > 2.95 */ +#if defined(__GNUC__) && (__GNUC__ > 2 || (__GNUC__ == 2 && (__GNUC_MINOR__ > 95))) + #define likely(x) __builtin_expect(!!(x), 1) + #define unlikely(x) __builtin_expect(!!(x), 0) +#else /* !__GNUC__ or GCC < 2.95 */ + #define likely(x) (x) + #define unlikely(x) (x) +#endif /* __GNUC__ */ +static CYTHON_INLINE void __Pyx_pretend_to_initialize(void* ptr) { (void)ptr; } + +#if !CYTHON_USE_MODULE_STATE +static PyObject *__pyx_m = NULL; +#endif +static int __pyx_lineno; +static int __pyx_clineno = 0; +static const char * __pyx_cfilenm = __FILE__; +static const char *__pyx_filename; + +/* #### Code section: filename_table ### */ + +static const char *__pyx_f[] = { + "opendbc/can/parser_pyx.pyx", + "", +}; +/* #### Code section: utility_code_proto_before_types ### */ +/* ForceInitThreads.proto */ +#ifndef __PYX_FORCE_INIT_THREADS + #define __PYX_FORCE_INIT_THREADS 0 +#endif + +/* #### Code section: numeric_typedefs ### */ +/* #### Code section: complex_type_declarations ### */ +/* #### Code section: type_declarations ### */ + +/*--- Type declarations ---*/ +struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser; +struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine; + +/* "common.pxd":11 + * + * + * ctypedef unsigned int (*calc_checksum_type)(uint32_t, const Signal&, const vector[uint8_t] &) # <<<<<<<<<<<<<< + * + * cdef extern from "common_dbc.h": + */ +typedef unsigned int (*__pyx_t_7opendbc_3can_6common_calc_checksum_type)(uint32_t, struct Signal const &, std::vector const &); + +/* "opendbc/can/parser_pyx.pyx":18 + * + * + * cdef class CANParser: # <<<<<<<<<<<<<< + * cdef: + * cpp_CANParser *can + */ +struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser { + PyObject_HEAD + CANParser *can; + struct DBC const *dbc; + std::vector can_values; + PyObject *vl; + PyObject *vl_all; + PyObject *ts_nanos; + std::string dbc_name; +}; + + +/* "opendbc/can/parser_pyx.pyx":105 + * + * + * cdef class CANDefine(): # <<<<<<<<<<<<<< + * cdef: + * const DBC *dbc + */ +struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine { + PyObject_HEAD + struct DBC const *dbc; + PyObject *dv; + std::string dbc_name; +}; + +/* #### Code section: utility_code_proto ### */ + +/* --- Runtime support code (head) --- */ +/* Refnanny.proto */ +#ifndef CYTHON_REFNANNY + #define CYTHON_REFNANNY 0 +#endif +#if CYTHON_REFNANNY + typedef struct { + void (*INCREF)(void*, PyObject*, Py_ssize_t); + void (*DECREF)(void*, PyObject*, Py_ssize_t); + void (*GOTREF)(void*, PyObject*, Py_ssize_t); + void (*GIVEREF)(void*, PyObject*, Py_ssize_t); + void* (*SetupContext)(const char*, Py_ssize_t, const char*); + void (*FinishContext)(void**); + } __Pyx_RefNannyAPIStruct; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNanny = NULL; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname); + #define __Pyx_RefNannyDeclarations void *__pyx_refnanny = NULL; +#ifdef WITH_THREAD + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + if (acquire_gil) {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + PyGILState_Release(__pyx_gilstate_save);\ + } else {\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + } + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } +#else + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__)) + #define __Pyx_RefNannyFinishContextNogil() __Pyx_RefNannyFinishContext() +#endif + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } + #define __Pyx_RefNannyFinishContext()\ + __Pyx_RefNanny->FinishContext(&__pyx_refnanny) + #define __Pyx_INCREF(r) __Pyx_RefNanny->INCREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_DECREF(r) __Pyx_RefNanny->DECREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GOTREF(r) __Pyx_RefNanny->GOTREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GIVEREF(r) __Pyx_RefNanny->GIVEREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_XINCREF(r) do { if((r) == NULL); else {__Pyx_INCREF(r); }} while(0) + #define __Pyx_XDECREF(r) do { if((r) == NULL); else {__Pyx_DECREF(r); }} while(0) + #define __Pyx_XGOTREF(r) do { if((r) == NULL); else {__Pyx_GOTREF(r); }} while(0) + #define __Pyx_XGIVEREF(r) do { if((r) == NULL); else {__Pyx_GIVEREF(r);}} while(0) +#else + #define __Pyx_RefNannyDeclarations + #define __Pyx_RefNannySetupContext(name, acquire_gil) + #define __Pyx_RefNannyFinishContextNogil() + #define __Pyx_RefNannyFinishContext() + #define __Pyx_INCREF(r) Py_INCREF(r) + #define __Pyx_DECREF(r) Py_DECREF(r) + #define __Pyx_GOTREF(r) + #define __Pyx_GIVEREF(r) + #define __Pyx_XINCREF(r) Py_XINCREF(r) + #define __Pyx_XDECREF(r) Py_XDECREF(r) + #define __Pyx_XGOTREF(r) + #define __Pyx_XGIVEREF(r) +#endif +#define __Pyx_Py_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; Py_XDECREF(tmp);\ + } while (0) +#define __Pyx_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_XDECREF(tmp);\ + } while (0) +#define __Pyx_DECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_DECREF(tmp);\ + } while (0) +#define __Pyx_CLEAR(r) do { PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);} while(0) +#define __Pyx_XCLEAR(r) do { if((r) != NULL) {PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);}} while(0) + +/* PyErrExceptionMatches.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_ExceptionMatches(err) __Pyx_PyErr_ExceptionMatchesInState(__pyx_tstate, err) +static CYTHON_INLINE int __Pyx_PyErr_ExceptionMatchesInState(PyThreadState* tstate, PyObject* err); +#else +#define __Pyx_PyErr_ExceptionMatches(err) PyErr_ExceptionMatches(err) +#endif + +/* PyThreadStateGet.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyThreadState_declare PyThreadState *__pyx_tstate; +#define __Pyx_PyThreadState_assign __pyx_tstate = __Pyx_PyThreadState_Current; +#if PY_VERSION_HEX >= 0x030C00A6 +#define __Pyx_PyErr_Occurred() (__pyx_tstate->current_exception != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->current_exception ? (PyObject*) Py_TYPE(__pyx_tstate->current_exception) : (PyObject*) NULL) +#else +#define __Pyx_PyErr_Occurred() (__pyx_tstate->curexc_type != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->curexc_type) +#endif +#else +#define __Pyx_PyThreadState_declare +#define __Pyx_PyThreadState_assign +#define __Pyx_PyErr_Occurred() (PyErr_Occurred() != NULL) +#define __Pyx_PyErr_CurrentExceptionType() PyErr_Occurred() +#endif + +/* PyErrFetchRestore.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_Clear() __Pyx_ErrRestore(NULL, NULL, NULL) +#define __Pyx_ErrRestoreWithState(type, value, tb) __Pyx_ErrRestoreInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) __Pyx_ErrFetchInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) __Pyx_ErrRestoreInState(__pyx_tstate, type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) __Pyx_ErrFetchInState(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb); +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A6 +#define __Pyx_PyErr_SetNone(exc) (Py_INCREF(exc), __Pyx_ErrRestore((exc), NULL, NULL)) +#else +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#endif +#else +#define __Pyx_PyErr_Clear() PyErr_Clear() +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#define __Pyx_ErrRestoreWithState(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestoreInState(tstate, type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchInState(tstate, type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) PyErr_Fetch(type, value, tb) +#endif + +/* PyObjectGetAttrStr.proto */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GetAttrStr(o,n) PyObject_GetAttr(o,n) +#endif + +/* PyObjectGetAttrStrNoError.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name); + +/* GetBuiltinName.proto */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name); + +/* RaiseTooManyValuesToUnpack.proto */ +static CYTHON_INLINE void __Pyx_RaiseTooManyValuesError(Py_ssize_t expected); + +/* RaiseNeedMoreValuesToUnpack.proto */ +static CYTHON_INLINE void __Pyx_RaiseNeedMoreValuesError(Py_ssize_t index); + +/* IterFinish.proto */ +static CYTHON_INLINE int __Pyx_IterFinish(void); + +/* UnpackItemEndCheck.proto */ +static int __Pyx_IternextUnpackEndCheck(PyObject *retval, Py_ssize_t expected); + +/* TupleAndListFromArray.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n); +static CYTHON_INLINE PyObject* __Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n); +#endif + +/* IncludeStringH.proto */ +#include + +/* BytesEquals.proto */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals); + +/* UnicodeEquals.proto */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals); + +/* fastcall.proto */ +#if CYTHON_AVOID_BORROWED_REFS + #define __Pyx_Arg_VARARGS(args, i) PySequence_GetItem(args, i) +#elif CYTHON_ASSUME_SAFE_MACROS + #define __Pyx_Arg_VARARGS(args, i) PyTuple_GET_ITEM(args, i) +#else + #define __Pyx_Arg_VARARGS(args, i) PyTuple_GetItem(args, i) +#endif +#if CYTHON_AVOID_BORROWED_REFS + #define __Pyx_Arg_NewRef_VARARGS(arg) __Pyx_NewRef(arg) + #define __Pyx_Arg_XDECREF_VARARGS(arg) Py_XDECREF(arg) +#else + #define __Pyx_Arg_NewRef_VARARGS(arg) arg + #define __Pyx_Arg_XDECREF_VARARGS(arg) +#endif +#define __Pyx_NumKwargs_VARARGS(kwds) PyDict_Size(kwds) +#define __Pyx_KwValues_VARARGS(args, nargs) NULL +#define __Pyx_GetKwValue_VARARGS(kw, kwvalues, s) __Pyx_PyDict_GetItemStrWithError(kw, s) +#define __Pyx_KwargsAsDict_VARARGS(kw, kwvalues) PyDict_Copy(kw) +#if CYTHON_METH_FASTCALL + #define __Pyx_Arg_FASTCALL(args, i) args[i] + #define __Pyx_NumKwargs_FASTCALL(kwds) PyTuple_GET_SIZE(kwds) + #define __Pyx_KwValues_FASTCALL(args, nargs) ((args) + (nargs)) + static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 + CYTHON_UNUSED static PyObject *__Pyx_KwargsAsDict_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues); + #else + #define __Pyx_KwargsAsDict_FASTCALL(kw, kwvalues) _PyStack_AsDict(kwvalues, kw) + #endif + #define __Pyx_Arg_NewRef_FASTCALL(arg) arg /* no-op, __Pyx_Arg_FASTCALL is direct and this needs + to have the same reference counting */ + #define __Pyx_Arg_XDECREF_FASTCALL(arg) +#else + #define __Pyx_Arg_FASTCALL __Pyx_Arg_VARARGS + #define __Pyx_NumKwargs_FASTCALL __Pyx_NumKwargs_VARARGS + #define __Pyx_KwValues_FASTCALL __Pyx_KwValues_VARARGS + #define __Pyx_GetKwValue_FASTCALL __Pyx_GetKwValue_VARARGS + #define __Pyx_KwargsAsDict_FASTCALL __Pyx_KwargsAsDict_VARARGS + #define __Pyx_Arg_NewRef_FASTCALL(arg) __Pyx_Arg_NewRef_VARARGS(arg) + #define __Pyx_Arg_XDECREF_FASTCALL(arg) __Pyx_Arg_XDECREF_VARARGS(arg) +#endif +#if CYTHON_COMPILING_IN_CPYTHON && CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_VARARGS(args, start), stop - start) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_FASTCALL(args, start), stop - start) +#else +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) PyTuple_GetSlice(args, start, stop) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) PyTuple_GetSlice(args, start, stop) +#endif + +/* RaiseArgTupleInvalid.proto */ +static void __Pyx_RaiseArgtupleInvalid(const char* func_name, int exact, + Py_ssize_t num_min, Py_ssize_t num_max, Py_ssize_t num_found); + +/* RaiseDoubleKeywords.proto */ +static void __Pyx_RaiseDoubleKeywordsError(const char* func_name, PyObject* kw_name); + +/* ParseKeywords.proto */ +static int __Pyx_ParseOptionalKeywords(PyObject *kwds, PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, PyObject *values[], Py_ssize_t num_pos_args, + const char* function_name); + +/* MoveIfSupported.proto */ +#if CYTHON_USE_CPP_STD_MOVE + #include + #define __PYX_STD_MOVE_IF_SUPPORTED(x) std::move(x) +#else + #define __PYX_STD_MOVE_IF_SUPPORTED(x) x +#endif + +/* PyObjectFormatSimple.proto */ +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + PyObject_Format(s, f)) +#elif PY_MAJOR_VERSION < 3 + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + likely(PyString_CheckExact(s)) ? PyUnicode_FromEncodedObject(s, NULL, "strict") :\ + PyObject_Format(s, f)) +#elif CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + likely(PyLong_CheckExact(s)) ? PyLong_Type.tp_repr(s) :\ + likely(PyFloat_CheckExact(s)) ? PyFloat_Type.tp_repr(s) :\ + PyObject_Format(s, f)) +#else + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + PyObject_Format(s, f)) +#endif + +/* PyFunctionFastCall.proto */ +#if CYTHON_FAST_PYCALL +#if !CYTHON_VECTORCALL +#define __Pyx_PyFunction_FastCall(func, args, nargs)\ + __Pyx_PyFunction_FastCallDict((func), (args), (nargs), NULL) +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs); +#endif +#define __Pyx_BUILD_ASSERT_EXPR(cond)\ + (sizeof(char [1 - 2*!(cond)]) - 1) +#ifndef Py_MEMBER_SIZE +#define Py_MEMBER_SIZE(type, member) sizeof(((type *)0)->member) +#endif +#if !CYTHON_VECTORCALL +#if PY_VERSION_HEX >= 0x03080000 + #include "frameobject.h" +#if PY_VERSION_HEX >= 0x030b00a6 && !CYTHON_COMPILING_IN_LIMITED_API + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif + #define __Pxy_PyFrame_Initialize_Offsets() + #define __Pyx_PyFrame_GetLocalsplus(frame) ((frame)->f_localsplus) +#else + static size_t __pyx_pyframe_localsplus_offset = 0; + #include "frameobject.h" + #define __Pxy_PyFrame_Initialize_Offsets()\ + ((void)__Pyx_BUILD_ASSERT_EXPR(sizeof(PyFrameObject) == offsetof(PyFrameObject, f_localsplus) + Py_MEMBER_SIZE(PyFrameObject, f_localsplus)),\ + (void)(__pyx_pyframe_localsplus_offset = ((size_t)PyFrame_Type.tp_basicsize) - Py_MEMBER_SIZE(PyFrameObject, f_localsplus))) + #define __Pyx_PyFrame_GetLocalsplus(frame)\ + (assert(__pyx_pyframe_localsplus_offset), (PyObject **)(((char *)(frame)) + __pyx_pyframe_localsplus_offset)) +#endif +#endif +#endif + +/* PyObjectCall.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw); +#else +#define __Pyx_PyObject_Call(func, arg, kw) PyObject_Call(func, arg, kw) +#endif + +/* PyObjectCallMethO.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg); +#endif + +/* PyObjectFastCall.proto */ +#define __Pyx_PyObject_FastCall(func, args, nargs) __Pyx_PyObject_FastCallDict(func, args, (size_t)(nargs), NULL) +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs); + +/* PyObjectCallOneArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg); + +/* RaiseException.proto */ +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause); + +/* IncludeCppStringH.proto */ +#include + +/* decode_c_string_utf16.proto */ +static CYTHON_INLINE PyObject *__Pyx_PyUnicode_DecodeUTF16(const char *s, Py_ssize_t size, const char *errors) { + int byteorder = 0; + return PyUnicode_DecodeUTF16(s, size, errors, &byteorder); +} +static CYTHON_INLINE PyObject *__Pyx_PyUnicode_DecodeUTF16LE(const char *s, Py_ssize_t size, const char *errors) { + int byteorder = -1; + return PyUnicode_DecodeUTF16(s, size, errors, &byteorder); +} +static CYTHON_INLINE PyObject *__Pyx_PyUnicode_DecodeUTF16BE(const char *s, Py_ssize_t size, const char *errors) { + int byteorder = 1; + return PyUnicode_DecodeUTF16(s, size, errors, &byteorder); +} + +/* decode_c_bytes.proto */ +static CYTHON_INLINE PyObject* __Pyx_decode_c_bytes( + const char* cstring, Py_ssize_t length, Py_ssize_t start, Py_ssize_t stop, + const char* encoding, const char* errors, + PyObject* (*decode_func)(const char *s, Py_ssize_t size, const char *errors)); + +/* decode_cpp_string.proto */ +static CYTHON_INLINE PyObject* __Pyx_decode_cpp_string( + std::string cppstring, Py_ssize_t start, Py_ssize_t stop, + const char* encoding, const char* errors, + PyObject* (*decode_func)(const char *s, Py_ssize_t size, const char *errors)) { + return __Pyx_decode_c_bytes( + cppstring.data(), cppstring.size(), start, stop, encoding, errors, decode_func); +} + +/* GetItemInt.proto */ +#define __Pyx_GetItemInt(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_Fast(o, (Py_ssize_t)i, is_list, wraparound, boundscheck) :\ + (is_list ? (PyErr_SetString(PyExc_IndexError, "list index out of range"), (PyObject*)NULL) :\ + __Pyx_GetItemInt_Generic(o, to_py_func(i)))) +#define __Pyx_GetItemInt_List(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_List_Fast(o, (Py_ssize_t)i, wraparound, boundscheck) :\ + (PyErr_SetString(PyExc_IndexError, "list index out of range"), (PyObject*)NULL)) +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_List_Fast(PyObject *o, Py_ssize_t i, + int wraparound, int boundscheck); +#define __Pyx_GetItemInt_Tuple(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_Tuple_Fast(o, (Py_ssize_t)i, wraparound, boundscheck) :\ + (PyErr_SetString(PyExc_IndexError, "tuple index out of range"), (PyObject*)NULL)) +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Tuple_Fast(PyObject *o, Py_ssize_t i, + int wraparound, int boundscheck); +static PyObject *__Pyx_GetItemInt_Generic(PyObject *o, PyObject* j); +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Fast(PyObject *o, Py_ssize_t i, + int is_list, int wraparound, int boundscheck); + +/* PyDictVersioning.proto */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +#define __PYX_DICT_VERSION_INIT ((PY_UINT64_T) -1) +#define __PYX_GET_DICT_VERSION(dict) (((PyDictObject*)(dict))->ma_version_tag) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var)\ + (version_var) = __PYX_GET_DICT_VERSION(dict);\ + (cache_var) = (value); +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + if (likely(__PYX_GET_DICT_VERSION(DICT) == __pyx_dict_version)) {\ + (VAR) = __pyx_dict_cached_value;\ + } else {\ + (VAR) = __pyx_dict_cached_value = (LOOKUP);\ + __pyx_dict_version = __PYX_GET_DICT_VERSION(DICT);\ + }\ +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj); +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj); +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version); +#else +#define __PYX_GET_DICT_VERSION(dict) (0) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var) +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) (VAR) = (LOOKUP); +#endif + +/* GetModuleGlobalName.proto */ +#if CYTHON_USE_DICT_VERSIONS +#define __Pyx_GetModuleGlobalName(var, name) do {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + (var) = (likely(__pyx_dict_version == __PYX_GET_DICT_VERSION(__pyx_d))) ?\ + (likely(__pyx_dict_cached_value) ? __Pyx_NewRef(__pyx_dict_cached_value) : __Pyx_GetBuiltinName(name)) :\ + __Pyx__GetModuleGlobalName(name, &__pyx_dict_version, &__pyx_dict_cached_value);\ +} while(0) +#define __Pyx_GetModuleGlobalNameUncached(var, name) do {\ + PY_UINT64_T __pyx_dict_version;\ + PyObject *__pyx_dict_cached_value;\ + (var) = __Pyx__GetModuleGlobalName(name, &__pyx_dict_version, &__pyx_dict_cached_value);\ +} while(0) +static PyObject *__Pyx__GetModuleGlobalName(PyObject *name, PY_UINT64_T *dict_version, PyObject **dict_cached_value); +#else +#define __Pyx_GetModuleGlobalName(var, name) (var) = __Pyx__GetModuleGlobalName(name) +#define __Pyx_GetModuleGlobalNameUncached(var, name) (var) = __Pyx__GetModuleGlobalName(name) +static CYTHON_INLINE PyObject *__Pyx__GetModuleGlobalName(PyObject *name); +#endif + +/* dict_getitem_default.proto */ +static PyObject* __Pyx_PyDict_GetItemDefault(PyObject* d, PyObject* key, PyObject* default_value); + +/* UnpackUnboundCMethod.proto */ +typedef struct { + PyObject *type; + PyObject **method_name; + PyCFunction func; + PyObject *method; + int flag; +} __Pyx_CachedCFunction; + +/* CallUnboundCMethod1.proto */ +static PyObject* __Pyx__CallUnboundCMethod1(__Pyx_CachedCFunction* cfunc, PyObject* self, PyObject* arg); +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_CallUnboundCMethod1(__Pyx_CachedCFunction* cfunc, PyObject* self, PyObject* arg); +#else +#define __Pyx_CallUnboundCMethod1(cfunc, self, arg) __Pyx__CallUnboundCMethod1(cfunc, self, arg) +#endif + +/* CallUnboundCMethod2.proto */ +static PyObject* __Pyx__CallUnboundCMethod2(__Pyx_CachedCFunction* cfunc, PyObject* self, PyObject* arg1, PyObject* arg2); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030600B1 +static CYTHON_INLINE PyObject *__Pyx_CallUnboundCMethod2(__Pyx_CachedCFunction *cfunc, PyObject *self, PyObject *arg1, PyObject *arg2); +#else +#define __Pyx_CallUnboundCMethod2(cfunc, self, arg1, arg2) __Pyx__CallUnboundCMethod2(cfunc, self, arg1, arg2) +#endif + +/* PyDictContains.proto */ +static CYTHON_INLINE int __Pyx_PyDict_ContainsTF(PyObject* item, PyObject* dict, int eq) { + int result = PyDict_Contains(dict, item); + return unlikely(result < 0) ? result : (result == (eq == Py_EQ)); +} + +/* JoinPyUnicode.proto */ +static PyObject* __Pyx_PyUnicode_Join(PyObject* value_tuple, Py_ssize_t value_count, Py_ssize_t result_ulength, + Py_UCS4 max_char); + +/* DictGetItem.proto */ +#if PY_MAJOR_VERSION >= 3 && !CYTHON_COMPILING_IN_PYPY +static PyObject *__Pyx_PyDict_GetItem(PyObject *d, PyObject* key); +#define __Pyx_PyObject_Dict_GetItem(obj, name)\ + (likely(PyDict_CheckExact(obj)) ?\ + __Pyx_PyDict_GetItem(obj, name) : PyObject_GetItem(obj, name)) +#else +#define __Pyx_PyDict_GetItem(d, key) PyObject_GetItem(d, key) +#define __Pyx_PyObject_Dict_GetItem(obj, name) PyObject_GetItem(obj, name) +#endif + +/* PyObjectCallNoArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func); + +/* PyObjectGetMethod.proto */ +static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method); + +/* PyObjectCallMethod0.proto */ +static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name); + +/* RaiseNoneIterError.proto */ +static CYTHON_INLINE void __Pyx_RaiseNoneNotIterableError(void); + +/* UnpackTupleError.proto */ +static void __Pyx_UnpackTupleError(PyObject *, Py_ssize_t index); + +/* UnpackTuple2.proto */ +#define __Pyx_unpack_tuple2(tuple, value1, value2, is_tuple, has_known_size, decref_tuple)\ + (likely(is_tuple || PyTuple_Check(tuple)) ?\ + (likely(has_known_size || PyTuple_GET_SIZE(tuple) == 2) ?\ + __Pyx_unpack_tuple2_exact(tuple, value1, value2, decref_tuple) :\ + (__Pyx_UnpackTupleError(tuple, 2), -1)) :\ + __Pyx_unpack_tuple2_generic(tuple, value1, value2, has_known_size, decref_tuple)) +static CYTHON_INLINE int __Pyx_unpack_tuple2_exact( + PyObject* tuple, PyObject** value1, PyObject** value2, int decref_tuple); +static int __Pyx_unpack_tuple2_generic( + PyObject* tuple, PyObject** value1, PyObject** value2, int has_known_size, int decref_tuple); + +/* dict_iter.proto */ +static CYTHON_INLINE PyObject* __Pyx_dict_iterator(PyObject* dict, int is_dict, PyObject* method_name, + Py_ssize_t* p_orig_length, int* p_is_dict); +static CYTHON_INLINE int __Pyx_dict_iter_next(PyObject* dict_or_iter, Py_ssize_t orig_length, Py_ssize_t* ppos, + PyObject** pkey, PyObject** pvalue, PyObject** pitem, int is_dict); + +/* KeywordStringCheck.proto */ +static int __Pyx_CheckKeywordStrings(PyObject *kw, const char* function_name, int kw_allowed); + +/* ObjectGetItem.proto */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject *__Pyx_PyObject_GetItem(PyObject *obj, PyObject *key); +#else +#define __Pyx_PyObject_GetItem(obj, key) PyObject_GetItem(obj, key) +#endif + +/* ListCompAppend.proto */ +#if CYTHON_USE_PYLIST_INTERNALS && CYTHON_ASSUME_SAFE_MACROS +static CYTHON_INLINE int __Pyx_ListComp_Append(PyObject* list, PyObject* x) { + PyListObject* L = (PyListObject*) list; + Py_ssize_t len = Py_SIZE(list); + if (likely(L->allocated > len)) { + Py_INCREF(x); + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 + L->ob_item[len] = x; + #else + PyList_SET_ITEM(list, len, x); + #endif + __Pyx_SET_SIZE(list, len + 1); + return 0; + } + return PyList_Append(list, x); +} +#else +#define __Pyx_ListComp_Append(L,x) PyList_Append(L,x) +#endif + +/* RaiseUnexpectedTypeError.proto */ +static int __Pyx_RaiseUnexpectedTypeError(const char *expected, PyObject *obj); + +/* IncludeStructmemberH.proto */ +#include + +/* FixUpExtensionType.proto */ +#if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type); +#endif + +/* ValidateBasesTuple.proto */ +#if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases); +#endif + +/* PyType_Ready.proto */ +CYTHON_UNUSED static int __Pyx_PyType_Ready(PyTypeObject *t); + +/* PyObject_GenericGetAttrNoDict.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttrNoDict PyObject_GenericGetAttr +#endif + +/* PyObject_GenericGetAttr.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttr PyObject_GenericGetAttr +#endif + +/* SetupReduce.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce(PyObject* type_obj); +#endif + +/* Import.proto */ +static PyObject *__Pyx_Import(PyObject *name, PyObject *from_list, int level); + +/* ImportDottedModule.proto */ +static PyObject *__Pyx_ImportDottedModule(PyObject *name, PyObject *parts_tuple); +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_ImportDottedModule_WalkParts(PyObject *module, PyObject *name, PyObject *parts_tuple); +#endif + +/* ImportFrom.proto */ +static PyObject* __Pyx_ImportFrom(PyObject* module, PyObject* name); + +/* FetchSharedCythonModule.proto */ +static PyObject *__Pyx_FetchSharedCythonABIModule(void); + +/* FetchCommonType.proto */ +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type); +#else +static PyTypeObject* __Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases); +#endif + +/* PyMethodNew.proto */ +#if CYTHON_COMPILING_IN_LIMITED_API +static PyObject *__Pyx_PyMethod_New(PyObject *func, PyObject *self, PyObject *typ) { + PyObject *typesModule=NULL, *methodType=NULL, *result=NULL; + CYTHON_UNUSED_VAR(typ); + if (!self) + return __Pyx_NewRef(func); + typesModule = PyImport_ImportModule("types"); + if (!typesModule) return NULL; + methodType = PyObject_GetAttrString(typesModule, "MethodType"); + Py_DECREF(typesModule); + if (!methodType) return NULL; + result = PyObject_CallFunctionObjArgs(methodType, func, self, NULL); + Py_DECREF(methodType); + return result; +} +#elif PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_PyMethod_New(PyObject *func, PyObject *self, PyObject *typ) { + CYTHON_UNUSED_VAR(typ); + if (!self) + return __Pyx_NewRef(func); + return PyMethod_New(func, self); +} +#else + #define __Pyx_PyMethod_New PyMethod_New +#endif + +/* PyVectorcallFastCallDict.proto */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw); +#endif + +/* CythonFunctionShared.proto */ +#define __Pyx_CyFunction_USED +#define __Pyx_CYFUNCTION_STATICMETHOD 0x01 +#define __Pyx_CYFUNCTION_CLASSMETHOD 0x02 +#define __Pyx_CYFUNCTION_CCLASS 0x04 +#define __Pyx_CYFUNCTION_COROUTINE 0x08 +#define __Pyx_CyFunction_GetClosure(f)\ + (((__pyx_CyFunctionObject *) (f))->func_closure) +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_CyFunction_GetClassObj(f)\ + (((__pyx_CyFunctionObject *) (f))->func_classobj) +#else + #define __Pyx_CyFunction_GetClassObj(f)\ + ((PyObject*) ((PyCMethodObject *) (f))->mm_class) +#endif +#define __Pyx_CyFunction_SetClassObj(f, classobj)\ + __Pyx__CyFunction_SetClassObj((__pyx_CyFunctionObject *) (f), (classobj)) +#define __Pyx_CyFunction_Defaults(type, f)\ + ((type *)(((__pyx_CyFunctionObject *) (f))->defaults)) +#define __Pyx_CyFunction_SetDefaultsGetter(f, g)\ + ((__pyx_CyFunctionObject *) (f))->defaults_getter = (g) +typedef struct { +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject_HEAD + PyObject *func; +#elif PY_VERSION_HEX < 0x030900B1 + PyCFunctionObject func; +#else + PyCMethodObject func; +#endif +#if CYTHON_BACKPORT_VECTORCALL + __pyx_vectorcallfunc func_vectorcall; +#endif +#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API + PyObject *func_weakreflist; +#endif + PyObject *func_dict; + PyObject *func_name; + PyObject *func_qualname; + PyObject *func_doc; + PyObject *func_globals; + PyObject *func_code; + PyObject *func_closure; +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + PyObject *func_classobj; +#endif + void *defaults; + int defaults_pyobjects; + size_t defaults_size; + int flags; + PyObject *defaults_tuple; + PyObject *defaults_kwdict; + PyObject *(*defaults_getter)(PyObject *); + PyObject *func_annotations; + PyObject *func_is_coroutine; +} __pyx_CyFunctionObject; +#undef __Pyx_CyOrPyCFunction_Check +#define __Pyx_CyFunction_Check(obj) __Pyx_TypeCheck(obj, __pyx_CyFunctionType) +#define __Pyx_CyOrPyCFunction_Check(obj) __Pyx_TypeCheck2(obj, __pyx_CyFunctionType, &PyCFunction_Type) +#define __Pyx_CyFunction_CheckExact(obj) __Pyx_IS_TYPE(obj, __pyx_CyFunctionType) +static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc); +#undef __Pyx_IsSameCFunction +#define __Pyx_IsSameCFunction(func, cfunc) __Pyx__IsSameCyOrCFunction(func, cfunc) +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject* op, PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj); +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *m, + size_t size, + int pyobjects); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *m, + PyObject *tuple); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *m, + PyObject *dict); +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *m, + PyObject *dict); +static int __pyx_CyFunction_init(PyObject *module); +#if CYTHON_METH_FASTCALL +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +#if CYTHON_BACKPORT_VECTORCALL +#define __Pyx_CyFunction_func_vectorcall(f) (((__pyx_CyFunctionObject*)f)->func_vectorcall) +#else +#define __Pyx_CyFunction_func_vectorcall(f) (((PyCFunctionObject*)f)->vectorcall) +#endif +#endif + +/* CythonFunction.proto */ +static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); + +/* CLineInTraceback.proto */ +#ifdef CYTHON_CLINE_IN_TRACEBACK +#define __Pyx_CLineForTraceback(tstate, c_line) (((CYTHON_CLINE_IN_TRACEBACK)) ? c_line : 0) +#else +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line); +#endif + +/* CodeObjectCache.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +typedef struct { + PyCodeObject* code_object; + int code_line; +} __Pyx_CodeObjectCacheEntry; +struct __Pyx_CodeObjectCache { + int count; + int max_count; + __Pyx_CodeObjectCacheEntry* entries; +}; +static struct __Pyx_CodeObjectCache __pyx_code_cache = {0,0,NULL}; +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line); +static PyCodeObject *__pyx_find_code_object(int code_line); +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object); +#endif + +/* AddTraceback.proto */ +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename); + +/* None.proto */ +#include + +/* CppExceptionConversion.proto */ +#ifndef __Pyx_CppExn2PyErr +#include +#include +#include +#include +static void __Pyx_CppExn2PyErr() { + try { + if (PyErr_Occurred()) + ; // let the latest Python exn pass through and ignore the current one + else + throw; + } catch (const std::bad_alloc& exn) { + PyErr_SetString(PyExc_MemoryError, exn.what()); + } catch (const std::bad_cast& exn) { + PyErr_SetString(PyExc_TypeError, exn.what()); + } catch (const std::bad_typeid& exn) { + PyErr_SetString(PyExc_TypeError, exn.what()); + } catch (const std::domain_error& exn) { + PyErr_SetString(PyExc_ValueError, exn.what()); + } catch (const std::invalid_argument& exn) { + PyErr_SetString(PyExc_ValueError, exn.what()); + } catch (const std::ios_base::failure& exn) { + PyErr_SetString(PyExc_IOError, exn.what()); + } catch (const std::out_of_range& exn) { + PyErr_SetString(PyExc_IndexError, exn.what()); + } catch (const std::overflow_error& exn) { + PyErr_SetString(PyExc_OverflowError, exn.what()); + } catch (const std::range_error& exn) { + PyErr_SetString(PyExc_ArithmeticError, exn.what()); + } catch (const std::underflow_error& exn) { + PyErr_SetString(PyExc_ArithmeticError, exn.what()); + } catch (const std::exception& exn) { + PyErr_SetString(PyExc_RuntimeError, exn.what()); + } + catch (...) + { + PyErr_SetString(PyExc_RuntimeError, "Unknown exception"); + } +} +#endif + +/* GCCDiagnostics.proto */ +#if !defined(__INTEL_COMPILER) && defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 6)) +#define __Pyx_HAS_GCC_DIAGNOSTIC +#endif + +/* CIntFromPy.proto */ +static CYTHON_INLINE size_t __Pyx_PyInt_As_size_t(PyObject *); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_uint32_t(uint32_t value); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value); + +/* CIntFromPy.proto */ +static CYTHON_INLINE uint32_t __Pyx_PyInt_As_uint32_t(PyObject *); + +/* CIntFromPy.proto */ +static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_uint64_t(uint64_t value); + +/* FormatTypeName.proto */ +#if CYTHON_COMPILING_IN_LIMITED_API +typedef PyObject *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%U" +static __Pyx_TypeName __Pyx_PyType_GetName(PyTypeObject* tp); +#define __Pyx_DECREF_TypeName(obj) Py_XDECREF(obj) +#else +typedef const char *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%.200s" +#define __Pyx_PyType_GetName(tp) ((tp)->tp_name) +#define __Pyx_DECREF_TypeName(obj) +#endif + +/* CIntFromPy.proto */ +static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *); + +/* FastTypeChecks.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_TypeCheck(obj, type) __Pyx_IsSubtype(Py_TYPE(obj), (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) __Pyx_IsAnySubtype2(Py_TYPE(obj), (PyTypeObject *)type1, (PyTypeObject *)type2) +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches(PyObject *err, PyObject *type); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches2(PyObject *err, PyObject *type1, PyObject *type2); +#else +#define __Pyx_TypeCheck(obj, type) PyObject_TypeCheck(obj, (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) (PyObject_TypeCheck(obj, (PyTypeObject *)type1) || PyObject_TypeCheck(obj, (PyTypeObject *)type2)) +#define __Pyx_PyErr_GivenExceptionMatches(err, type) PyErr_GivenExceptionMatches(err, type) +#define __Pyx_PyErr_GivenExceptionMatches2(err, type1, type2) (PyErr_GivenExceptionMatches(err, type1) || PyErr_GivenExceptionMatches(err, type2)) +#endif +#define __Pyx_PyErr_ExceptionMatches2(err1, err2) __Pyx_PyErr_GivenExceptionMatches2(__Pyx_PyErr_CurrentExceptionType(), err1, err2) +#define __Pyx_PyException_Check(obj) __Pyx_TypeCheck(obj, PyExc_Exception) + +/* CheckBinaryVersion.proto */ +static unsigned long __Pyx_get_runtime_version(void); +static int __Pyx_check_binary_version(unsigned long ct_version, unsigned long rt_version, int allow_newer); + +/* InitStrings.proto */ +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t); + +/* #### Code section: module_declarations ### */ + +/* Module declarations from "libcpp.utility" */ + +/* Module declarations from "libcpp.pair" */ + +/* Module declarations from "libc.string" */ + +/* Module declarations from "libcpp.string" */ + +/* Module declarations from "libcpp.vector" */ + +/* Module declarations from "libcpp.unordered_set" */ + +/* Module declarations from "libc.stdint" */ + +/* Module declarations from "libcpp" */ + +/* Module declarations from "opendbc.can.common" */ + +/* Module declarations from "opendbc.can.parser_pyx" */ +static std::string __pyx_convert_string_from_py_std__in_string(PyObject *); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyObject_string_to_py_std__in_string(std::string const &); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyUnicode_string_to_py_std__in_string(std::string const &); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyStr_string_to_py_std__in_string(std::string const &); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyBytes_string_to_py_std__in_string(std::string const &); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyByteArray_string_to_py_std__in_string(std::string const &); /*proto*/ +static std::pair __pyx_convert_pair_from_py_uint32_t__and_int(PyObject *); /*proto*/ +static std::vector __pyx_convert_vector_from_py_std_3a__3a_string(PyObject *); /*proto*/ +static PyObject *__pyx_convert_vector_to_py_double(std::vector const &); /*proto*/ +static PyObject *__pyx_convert_unordered_set_to_py_uint32_t(std::unordered_set const &); /*proto*/ +/* #### Code section: typeinfo ### */ +/* #### Code section: before_global_var ### */ +#define __Pyx_MODULE_NAME "opendbc.can.parser_pyx" +extern int __pyx_module_is_main_opendbc__can__parser_pyx; +int __pyx_module_is_main_opendbc__can__parser_pyx = 0; + +/* Implementation of "opendbc.can.parser_pyx" */ +/* #### Code section: global_var ### */ +static PyObject *__pyx_builtin_RuntimeError; +static PyObject *__pyx_builtin_range; +static PyObject *__pyx_builtin_TypeError; +static PyObject *__pyx_builtin_zip; +static PyObject *__pyx_builtin_MemoryError; +/* #### Code section: string_decls ### */ +static const char __pyx_k_[] = "'"; +static const char __pyx_k_l[] = "l"; +static const char __pyx_k_v[] = "v"; +static const char __pyx_k__4[] = "*"; +static const char __pyx_k__5[] = "."; +static const char __pyx_k_cv[] = "cv"; +static const char __pyx_k_gc[] = "gc"; +static const char __pyx_k_it[] = "it"; +static const char __pyx_k__15[] = "?"; +static const char __pyx_k_bus[] = "bus"; +static const char __pyx_k_get[] = "get"; +static const char __pyx_k_zip[] = "zip"; +static const char __pyx_k_main[] = "__main__"; +static const char __pyx_k_name[] = "__name__"; +static const char __pyx_k_self[] = "self"; +static const char __pyx_k_spec[] = "__spec__"; +static const char __pyx_k_test[] = "__test__"; +static const char __pyx_k_clear[] = "clear"; +static const char __pyx_k_range[] = "range"; +static const char __pyx_k_split[] = "split"; +static const char __pyx_k_Number[] = "Number"; +static const char __pyx_k_enable[] = "enable"; +static const char __pyx_k_import[] = "__import__"; +static const char __pyx_k_in_DBC[] = " in DBC "; +static const char __pyx_k_reduce[] = "__reduce__"; +static const char __pyx_k_values[] = "values"; +static const char __pyx_k_cv_name[] = "cv_name"; +static const char __pyx_k_disable[] = "disable"; +static const char __pyx_k_numbers[] = "numbers"; +static const char __pyx_k_sendcan[] = "sendcan"; +static const char __pyx_k_strings[] = "strings"; +static const char __pyx_k_dbc_name[] = "dbc_name"; +static const char __pyx_k_getstate[] = "__getstate__"; +static const char __pyx_k_messages[] = "messages"; +static const char __pyx_k_new_vals[] = "new_vals"; +static const char __pyx_k_setstate[] = "__setstate__"; +static const char __pyx_k_CANDefine[] = "CANDefine"; +static const char __pyx_k_CANParser[] = "CANParser"; +static const char __pyx_k_TypeError[] = "TypeError"; +static const char __pyx_k_isenabled[] = "isenabled"; +static const char __pyx_k_pyx_state[] = "__pyx_state"; +static const char __pyx_k_reduce_ex[] = "__reduce_ex__"; +static const char __pyx_k_MemoryError[] = "MemoryError"; +static const char __pyx_k_collections[] = "collections"; +static const char __pyx_k_defaultdict[] = "defaultdict"; +static const char __pyx_k_RuntimeError[] = "RuntimeError"; +static const char __pyx_k_initializing[] = "_initializing"; +static const char __pyx_k_is_coroutine[] = "_is_coroutine"; +static const char __pyx_k_stringsource[] = ""; +static const char __pyx_k_class_getitem[] = "__class_getitem__"; +static const char __pyx_k_reduce_cython[] = "__reduce_cython__"; +static const char __pyx_k_updated_addrs[] = "updated_addrs"; +static const char __pyx_k_Can_t_find_DBC[] = "Can't find DBC: "; +static const char __pyx_k_update_strings[] = "update_strings"; +static const char __pyx_k_setstate_cython[] = "__setstate_cython__"; +static const char __pyx_k_Can_t_find_DBC_2[] = "Can't find DBC: '"; +static const char __pyx_k_asyncio_coroutines[] = "asyncio.coroutines"; +static const char __pyx_k_cline_in_traceback[] = "cline_in_traceback"; +static const char __pyx_k_could_not_find_message[] = "could not find message "; +static const char __pyx_k_opendbc_can_parser_pyx[] = "opendbc.can.parser_pyx"; +static const char __pyx_k_CANParser_update_strings[] = "CANParser.update_strings"; +static const char __pyx_k_CANDefine___reduce_cython[] = "CANDefine.__reduce_cython__"; +static const char __pyx_k_CANParser___reduce_cython[] = "CANParser.__reduce_cython__"; +static const char __pyx_k_opendbc_can_parser_pyx_pyx[] = "opendbc/can/parser_pyx.pyx"; +static const char __pyx_k_CANDefine___setstate_cython[] = "CANDefine.__setstate_cython__"; +static const char __pyx_k_CANParser___setstate_cython[] = "CANParser.__setstate_cython__"; +static const char __pyx_k_self_dbc_cannot_be_converted_to[] = "self.dbc cannot be converted to a Python object for pickling"; +static const char __pyx_k_self_can_self_dbc_cannot_be_conv[] = "self.can,self.dbc cannot be converted to a Python object for pickling"; +/* #### Code section: decls ### */ +static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANParser___init__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self, PyObject *__pyx_v_dbc_name, PyObject *__pyx_v_messages, PyObject *__pyx_v_bus); /* proto */ +static void __pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_2__dealloc__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_4update_strings(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self, PyObject *__pyx_v_strings, PyObject *__pyx_v_sendcan); /* proto */ +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_9can_valid___get__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_11bus_timeout___get__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_2vl___get__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_6vl_all___get__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_8ts_nanos___get__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_8dbc_name___get__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_6__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_8__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine___init__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *__pyx_v_self, PyObject *__pyx_v_dbc_name); /* proto */ +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_2dv___get__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *__pyx_v_self); /* proto */ +static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_2dv_2__set__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *__pyx_v_self, PyObject *__pyx_v_value); /* proto */ +static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_2dv_4__del__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_8dbc_name___get__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *__pyx_v_self); /* proto */ +static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_8dbc_name_2__set__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *__pyx_v_self, PyObject *__pyx_v_value); /* proto */ +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_2__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_4__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_tp_new_7opendbc_3can_10parser_pyx_CANParser(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_7opendbc_3can_10parser_pyx_CANDefine(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static __Pyx_CachedCFunction __pyx_umethod_PyDict_Type_get = {0, 0, 0, 0, 0}; +/* #### Code section: late_includes ### */ +/* #### Code section: module_state ### */ +typedef struct { + PyObject *__pyx_d; + PyObject *__pyx_b; + PyObject *__pyx_cython_runtime; + PyObject *__pyx_empty_tuple; + PyObject *__pyx_empty_bytes; + PyObject *__pyx_empty_unicode; + #ifdef __Pyx_CyFunction_USED + PyTypeObject *__pyx_CyFunctionType; + #endif + #ifdef __Pyx_FusedFunction_USED + PyTypeObject *__pyx_FusedFunctionType; + #endif + #ifdef __Pyx_Generator_USED + PyTypeObject *__pyx_GeneratorType; + #endif + #ifdef __Pyx_IterableCoroutine_USED + PyTypeObject *__pyx_IterableCoroutineType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineAwaitType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineType; + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + PyObject *__pyx_type_7opendbc_3can_10parser_pyx_CANParser; + PyObject *__pyx_type_7opendbc_3can_10parser_pyx_CANDefine; + #endif + PyTypeObject *__pyx_ptype_7opendbc_3can_10parser_pyx_CANParser; + PyTypeObject *__pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine; + PyObject *__pyx_kp_u_; + PyObject *__pyx_n_s_CANDefine; + PyObject *__pyx_n_s_CANDefine___reduce_cython; + PyObject *__pyx_n_s_CANDefine___setstate_cython; + PyObject *__pyx_n_s_CANParser; + PyObject *__pyx_n_s_CANParser___reduce_cython; + PyObject *__pyx_n_s_CANParser___setstate_cython; + PyObject *__pyx_n_s_CANParser_update_strings; + PyObject *__pyx_kp_u_Can_t_find_DBC; + PyObject *__pyx_kp_u_Can_t_find_DBC_2; + PyObject *__pyx_n_s_MemoryError; + PyObject *__pyx_n_s_Number; + PyObject *__pyx_n_s_RuntimeError; + PyObject *__pyx_n_s_TypeError; + PyObject *__pyx_n_s__15; + PyObject *__pyx_n_s__4; + PyObject *__pyx_kp_u__5; + PyObject *__pyx_n_s_asyncio_coroutines; + PyObject *__pyx_n_s_bus; + PyObject *__pyx_n_s_class_getitem; + PyObject *__pyx_n_s_clear; + PyObject *__pyx_n_s_cline_in_traceback; + PyObject *__pyx_n_s_collections; + PyObject *__pyx_kp_u_could_not_find_message; + PyObject *__pyx_n_s_cv; + PyObject *__pyx_n_s_cv_name; + PyObject *__pyx_n_s_dbc_name; + PyObject *__pyx_n_s_defaultdict; + PyObject *__pyx_kp_u_disable; + PyObject *__pyx_kp_u_enable; + PyObject *__pyx_kp_u_gc; + PyObject *__pyx_n_s_get; + PyObject *__pyx_n_s_getstate; + PyObject *__pyx_n_s_import; + PyObject *__pyx_kp_u_in_DBC; + PyObject *__pyx_n_s_initializing; + PyObject *__pyx_n_s_is_coroutine; + PyObject *__pyx_kp_u_isenabled; + PyObject *__pyx_n_s_it; + PyObject *__pyx_n_s_l; + PyObject *__pyx_n_s_main; + PyObject *__pyx_n_s_messages; + PyObject *__pyx_n_s_name; + PyObject *__pyx_n_s_new_vals; + PyObject *__pyx_n_s_numbers; + PyObject *__pyx_n_s_opendbc_can_parser_pyx; + PyObject *__pyx_kp_s_opendbc_can_parser_pyx_pyx; + PyObject *__pyx_n_s_pyx_state; + PyObject *__pyx_n_s_range; + PyObject *__pyx_n_s_reduce; + PyObject *__pyx_n_s_reduce_cython; + PyObject *__pyx_n_s_reduce_ex; + PyObject *__pyx_n_s_self; + PyObject *__pyx_kp_s_self_can_self_dbc_cannot_be_conv; + PyObject *__pyx_kp_s_self_dbc_cannot_be_converted_to; + PyObject *__pyx_n_s_sendcan; + PyObject *__pyx_n_s_setstate; + PyObject *__pyx_n_s_setstate_cython; + PyObject *__pyx_n_s_spec; + PyObject *__pyx_n_s_split; + PyObject *__pyx_n_s_strings; + PyObject *__pyx_kp_s_stringsource; + PyObject *__pyx_n_s_test; + PyObject *__pyx_n_s_update_strings; + PyObject *__pyx_n_s_updated_addrs; + PyObject *__pyx_n_s_v; + PyObject *__pyx_n_s_values; + PyObject *__pyx_n_s_zip; + PyObject *__pyx_int_0; + PyObject *__pyx_int_1; + PyObject *__pyx_int_2; + PyObject *__pyx_slice__2; + PyObject *__pyx_slice__3; + PyObject *__pyx_tuple__6; + PyObject *__pyx_tuple__8; + PyObject *__pyx_tuple__9; + PyObject *__pyx_tuple__11; + PyObject *__pyx_codeobj__7; + PyObject *__pyx_codeobj__10; + PyObject *__pyx_codeobj__12; + PyObject *__pyx_codeobj__13; + PyObject *__pyx_codeobj__14; +} __pyx_mstate; + +#if CYTHON_USE_MODULE_STATE +#ifdef __cplusplus +namespace { + extern struct PyModuleDef __pyx_moduledef; +} /* anonymous namespace */ +#else +static struct PyModuleDef __pyx_moduledef; +#endif + +#define __pyx_mstate(o) ((__pyx_mstate *)__Pyx_PyModule_GetState(o)) + +#define __pyx_mstate_global (__pyx_mstate(PyState_FindModule(&__pyx_moduledef))) + +#define __pyx_m (PyState_FindModule(&__pyx_moduledef)) +#else +static __pyx_mstate __pyx_mstate_global_static = +#ifdef __cplusplus + {}; +#else + {0}; +#endif +static __pyx_mstate *__pyx_mstate_global = &__pyx_mstate_global_static; +#endif +/* #### Code section: module_state_clear ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_clear(PyObject *m) { + __pyx_mstate *clear_module_state = __pyx_mstate(m); + if (!clear_module_state) return 0; + Py_CLEAR(clear_module_state->__pyx_d); + Py_CLEAR(clear_module_state->__pyx_b); + Py_CLEAR(clear_module_state->__pyx_cython_runtime); + Py_CLEAR(clear_module_state->__pyx_empty_tuple); + Py_CLEAR(clear_module_state->__pyx_empty_bytes); + Py_CLEAR(clear_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_CLEAR(clear_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_CLEAR(clear_module_state->__pyx_FusedFunctionType); + #endif + Py_CLEAR(clear_module_state->__pyx_ptype_7opendbc_3can_10parser_pyx_CANParser); + Py_CLEAR(clear_module_state->__pyx_type_7opendbc_3can_10parser_pyx_CANParser); + Py_CLEAR(clear_module_state->__pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine); + Py_CLEAR(clear_module_state->__pyx_type_7opendbc_3can_10parser_pyx_CANDefine); + Py_CLEAR(clear_module_state->__pyx_kp_u_); + Py_CLEAR(clear_module_state->__pyx_n_s_CANDefine); + Py_CLEAR(clear_module_state->__pyx_n_s_CANDefine___reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_CANDefine___setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_CANParser); + Py_CLEAR(clear_module_state->__pyx_n_s_CANParser___reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_CANParser___setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_CANParser_update_strings); + Py_CLEAR(clear_module_state->__pyx_kp_u_Can_t_find_DBC); + Py_CLEAR(clear_module_state->__pyx_kp_u_Can_t_find_DBC_2); + Py_CLEAR(clear_module_state->__pyx_n_s_MemoryError); + Py_CLEAR(clear_module_state->__pyx_n_s_Number); + Py_CLEAR(clear_module_state->__pyx_n_s_RuntimeError); + Py_CLEAR(clear_module_state->__pyx_n_s_TypeError); + Py_CLEAR(clear_module_state->__pyx_n_s__15); + Py_CLEAR(clear_module_state->__pyx_n_s__4); + Py_CLEAR(clear_module_state->__pyx_kp_u__5); + Py_CLEAR(clear_module_state->__pyx_n_s_asyncio_coroutines); + Py_CLEAR(clear_module_state->__pyx_n_s_bus); + Py_CLEAR(clear_module_state->__pyx_n_s_class_getitem); + Py_CLEAR(clear_module_state->__pyx_n_s_clear); + Py_CLEAR(clear_module_state->__pyx_n_s_cline_in_traceback); + Py_CLEAR(clear_module_state->__pyx_n_s_collections); + Py_CLEAR(clear_module_state->__pyx_kp_u_could_not_find_message); + Py_CLEAR(clear_module_state->__pyx_n_s_cv); + Py_CLEAR(clear_module_state->__pyx_n_s_cv_name); + Py_CLEAR(clear_module_state->__pyx_n_s_dbc_name); + Py_CLEAR(clear_module_state->__pyx_n_s_defaultdict); + Py_CLEAR(clear_module_state->__pyx_kp_u_disable); + Py_CLEAR(clear_module_state->__pyx_kp_u_enable); + Py_CLEAR(clear_module_state->__pyx_kp_u_gc); + Py_CLEAR(clear_module_state->__pyx_n_s_get); + Py_CLEAR(clear_module_state->__pyx_n_s_getstate); + Py_CLEAR(clear_module_state->__pyx_n_s_import); + Py_CLEAR(clear_module_state->__pyx_kp_u_in_DBC); + Py_CLEAR(clear_module_state->__pyx_n_s_initializing); + Py_CLEAR(clear_module_state->__pyx_n_s_is_coroutine); + Py_CLEAR(clear_module_state->__pyx_kp_u_isenabled); + Py_CLEAR(clear_module_state->__pyx_n_s_it); + Py_CLEAR(clear_module_state->__pyx_n_s_l); + Py_CLEAR(clear_module_state->__pyx_n_s_main); + Py_CLEAR(clear_module_state->__pyx_n_s_messages); + Py_CLEAR(clear_module_state->__pyx_n_s_name); + Py_CLEAR(clear_module_state->__pyx_n_s_new_vals); + Py_CLEAR(clear_module_state->__pyx_n_s_numbers); + Py_CLEAR(clear_module_state->__pyx_n_s_opendbc_can_parser_pyx); + Py_CLEAR(clear_module_state->__pyx_kp_s_opendbc_can_parser_pyx_pyx); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_state); + Py_CLEAR(clear_module_state->__pyx_n_s_range); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_ex); + Py_CLEAR(clear_module_state->__pyx_n_s_self); + Py_CLEAR(clear_module_state->__pyx_kp_s_self_can_self_dbc_cannot_be_conv); + Py_CLEAR(clear_module_state->__pyx_kp_s_self_dbc_cannot_be_converted_to); + Py_CLEAR(clear_module_state->__pyx_n_s_sendcan); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_spec); + Py_CLEAR(clear_module_state->__pyx_n_s_split); + Py_CLEAR(clear_module_state->__pyx_n_s_strings); + Py_CLEAR(clear_module_state->__pyx_kp_s_stringsource); + Py_CLEAR(clear_module_state->__pyx_n_s_test); + Py_CLEAR(clear_module_state->__pyx_n_s_update_strings); + Py_CLEAR(clear_module_state->__pyx_n_s_updated_addrs); + Py_CLEAR(clear_module_state->__pyx_n_s_v); + Py_CLEAR(clear_module_state->__pyx_n_s_values); + Py_CLEAR(clear_module_state->__pyx_n_s_zip); + Py_CLEAR(clear_module_state->__pyx_int_0); + Py_CLEAR(clear_module_state->__pyx_int_1); + Py_CLEAR(clear_module_state->__pyx_int_2); + Py_CLEAR(clear_module_state->__pyx_slice__2); + Py_CLEAR(clear_module_state->__pyx_slice__3); + Py_CLEAR(clear_module_state->__pyx_tuple__6); + Py_CLEAR(clear_module_state->__pyx_tuple__8); + Py_CLEAR(clear_module_state->__pyx_tuple__9); + Py_CLEAR(clear_module_state->__pyx_tuple__11); + Py_CLEAR(clear_module_state->__pyx_codeobj__7); + Py_CLEAR(clear_module_state->__pyx_codeobj__10); + Py_CLEAR(clear_module_state->__pyx_codeobj__12); + Py_CLEAR(clear_module_state->__pyx_codeobj__13); + Py_CLEAR(clear_module_state->__pyx_codeobj__14); + return 0; +} +#endif +/* #### Code section: module_state_traverse ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { + __pyx_mstate *traverse_module_state = __pyx_mstate(m); + if (!traverse_module_state) return 0; + Py_VISIT(traverse_module_state->__pyx_d); + Py_VISIT(traverse_module_state->__pyx_b); + Py_VISIT(traverse_module_state->__pyx_cython_runtime); + Py_VISIT(traverse_module_state->__pyx_empty_tuple); + Py_VISIT(traverse_module_state->__pyx_empty_bytes); + Py_VISIT(traverse_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_VISIT(traverse_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_VISIT(traverse_module_state->__pyx_FusedFunctionType); + #endif + Py_VISIT(traverse_module_state->__pyx_ptype_7opendbc_3can_10parser_pyx_CANParser); + Py_VISIT(traverse_module_state->__pyx_type_7opendbc_3can_10parser_pyx_CANParser); + Py_VISIT(traverse_module_state->__pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine); + Py_VISIT(traverse_module_state->__pyx_type_7opendbc_3can_10parser_pyx_CANDefine); + Py_VISIT(traverse_module_state->__pyx_kp_u_); + Py_VISIT(traverse_module_state->__pyx_n_s_CANDefine); + Py_VISIT(traverse_module_state->__pyx_n_s_CANDefine___reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_CANDefine___setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_CANParser); + Py_VISIT(traverse_module_state->__pyx_n_s_CANParser___reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_CANParser___setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_CANParser_update_strings); + Py_VISIT(traverse_module_state->__pyx_kp_u_Can_t_find_DBC); + Py_VISIT(traverse_module_state->__pyx_kp_u_Can_t_find_DBC_2); + Py_VISIT(traverse_module_state->__pyx_n_s_MemoryError); + Py_VISIT(traverse_module_state->__pyx_n_s_Number); + Py_VISIT(traverse_module_state->__pyx_n_s_RuntimeError); + Py_VISIT(traverse_module_state->__pyx_n_s_TypeError); + Py_VISIT(traverse_module_state->__pyx_n_s__15); + Py_VISIT(traverse_module_state->__pyx_n_s__4); + Py_VISIT(traverse_module_state->__pyx_kp_u__5); + Py_VISIT(traverse_module_state->__pyx_n_s_asyncio_coroutines); + Py_VISIT(traverse_module_state->__pyx_n_s_bus); + Py_VISIT(traverse_module_state->__pyx_n_s_class_getitem); + Py_VISIT(traverse_module_state->__pyx_n_s_clear); + Py_VISIT(traverse_module_state->__pyx_n_s_cline_in_traceback); + Py_VISIT(traverse_module_state->__pyx_n_s_collections); + Py_VISIT(traverse_module_state->__pyx_kp_u_could_not_find_message); + Py_VISIT(traverse_module_state->__pyx_n_s_cv); + Py_VISIT(traverse_module_state->__pyx_n_s_cv_name); + Py_VISIT(traverse_module_state->__pyx_n_s_dbc_name); + Py_VISIT(traverse_module_state->__pyx_n_s_defaultdict); + Py_VISIT(traverse_module_state->__pyx_kp_u_disable); + Py_VISIT(traverse_module_state->__pyx_kp_u_enable); + Py_VISIT(traverse_module_state->__pyx_kp_u_gc); + Py_VISIT(traverse_module_state->__pyx_n_s_get); + Py_VISIT(traverse_module_state->__pyx_n_s_getstate); + Py_VISIT(traverse_module_state->__pyx_n_s_import); + Py_VISIT(traverse_module_state->__pyx_kp_u_in_DBC); + Py_VISIT(traverse_module_state->__pyx_n_s_initializing); + Py_VISIT(traverse_module_state->__pyx_n_s_is_coroutine); + Py_VISIT(traverse_module_state->__pyx_kp_u_isenabled); + Py_VISIT(traverse_module_state->__pyx_n_s_it); + Py_VISIT(traverse_module_state->__pyx_n_s_l); + Py_VISIT(traverse_module_state->__pyx_n_s_main); + Py_VISIT(traverse_module_state->__pyx_n_s_messages); + Py_VISIT(traverse_module_state->__pyx_n_s_name); + Py_VISIT(traverse_module_state->__pyx_n_s_new_vals); + Py_VISIT(traverse_module_state->__pyx_n_s_numbers); + Py_VISIT(traverse_module_state->__pyx_n_s_opendbc_can_parser_pyx); + Py_VISIT(traverse_module_state->__pyx_kp_s_opendbc_can_parser_pyx_pyx); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_state); + Py_VISIT(traverse_module_state->__pyx_n_s_range); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_ex); + Py_VISIT(traverse_module_state->__pyx_n_s_self); + Py_VISIT(traverse_module_state->__pyx_kp_s_self_can_self_dbc_cannot_be_conv); + Py_VISIT(traverse_module_state->__pyx_kp_s_self_dbc_cannot_be_converted_to); + Py_VISIT(traverse_module_state->__pyx_n_s_sendcan); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_spec); + Py_VISIT(traverse_module_state->__pyx_n_s_split); + Py_VISIT(traverse_module_state->__pyx_n_s_strings); + Py_VISIT(traverse_module_state->__pyx_kp_s_stringsource); + Py_VISIT(traverse_module_state->__pyx_n_s_test); + Py_VISIT(traverse_module_state->__pyx_n_s_update_strings); + Py_VISIT(traverse_module_state->__pyx_n_s_updated_addrs); + Py_VISIT(traverse_module_state->__pyx_n_s_v); + Py_VISIT(traverse_module_state->__pyx_n_s_values); + Py_VISIT(traverse_module_state->__pyx_n_s_zip); + Py_VISIT(traverse_module_state->__pyx_int_0); + Py_VISIT(traverse_module_state->__pyx_int_1); + Py_VISIT(traverse_module_state->__pyx_int_2); + Py_VISIT(traverse_module_state->__pyx_slice__2); + Py_VISIT(traverse_module_state->__pyx_slice__3); + Py_VISIT(traverse_module_state->__pyx_tuple__6); + Py_VISIT(traverse_module_state->__pyx_tuple__8); + Py_VISIT(traverse_module_state->__pyx_tuple__9); + Py_VISIT(traverse_module_state->__pyx_tuple__11); + Py_VISIT(traverse_module_state->__pyx_codeobj__7); + Py_VISIT(traverse_module_state->__pyx_codeobj__10); + Py_VISIT(traverse_module_state->__pyx_codeobj__12); + Py_VISIT(traverse_module_state->__pyx_codeobj__13); + Py_VISIT(traverse_module_state->__pyx_codeobj__14); + return 0; +} +#endif +/* #### Code section: module_state_defines ### */ +#define __pyx_d __pyx_mstate_global->__pyx_d +#define __pyx_b __pyx_mstate_global->__pyx_b +#define __pyx_cython_runtime __pyx_mstate_global->__pyx_cython_runtime +#define __pyx_empty_tuple __pyx_mstate_global->__pyx_empty_tuple +#define __pyx_empty_bytes __pyx_mstate_global->__pyx_empty_bytes +#define __pyx_empty_unicode __pyx_mstate_global->__pyx_empty_unicode +#ifdef __Pyx_CyFunction_USED +#define __pyx_CyFunctionType __pyx_mstate_global->__pyx_CyFunctionType +#endif +#ifdef __Pyx_FusedFunction_USED +#define __pyx_FusedFunctionType __pyx_mstate_global->__pyx_FusedFunctionType +#endif +#ifdef __Pyx_Generator_USED +#define __pyx_GeneratorType __pyx_mstate_global->__pyx_GeneratorType +#endif +#ifdef __Pyx_IterableCoroutine_USED +#define __pyx_IterableCoroutineType __pyx_mstate_global->__pyx_IterableCoroutineType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineAwaitType __pyx_mstate_global->__pyx_CoroutineAwaitType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineType __pyx_mstate_global->__pyx_CoroutineType +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#define __pyx_type_7opendbc_3can_10parser_pyx_CANParser __pyx_mstate_global->__pyx_type_7opendbc_3can_10parser_pyx_CANParser +#define __pyx_type_7opendbc_3can_10parser_pyx_CANDefine __pyx_mstate_global->__pyx_type_7opendbc_3can_10parser_pyx_CANDefine +#endif +#define __pyx_ptype_7opendbc_3can_10parser_pyx_CANParser __pyx_mstate_global->__pyx_ptype_7opendbc_3can_10parser_pyx_CANParser +#define __pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine __pyx_mstate_global->__pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine +#define __pyx_kp_u_ __pyx_mstate_global->__pyx_kp_u_ +#define __pyx_n_s_CANDefine __pyx_mstate_global->__pyx_n_s_CANDefine +#define __pyx_n_s_CANDefine___reduce_cython __pyx_mstate_global->__pyx_n_s_CANDefine___reduce_cython +#define __pyx_n_s_CANDefine___setstate_cython __pyx_mstate_global->__pyx_n_s_CANDefine___setstate_cython +#define __pyx_n_s_CANParser __pyx_mstate_global->__pyx_n_s_CANParser +#define __pyx_n_s_CANParser___reduce_cython __pyx_mstate_global->__pyx_n_s_CANParser___reduce_cython +#define __pyx_n_s_CANParser___setstate_cython __pyx_mstate_global->__pyx_n_s_CANParser___setstate_cython +#define __pyx_n_s_CANParser_update_strings __pyx_mstate_global->__pyx_n_s_CANParser_update_strings +#define __pyx_kp_u_Can_t_find_DBC __pyx_mstate_global->__pyx_kp_u_Can_t_find_DBC +#define __pyx_kp_u_Can_t_find_DBC_2 __pyx_mstate_global->__pyx_kp_u_Can_t_find_DBC_2 +#define __pyx_n_s_MemoryError __pyx_mstate_global->__pyx_n_s_MemoryError +#define __pyx_n_s_Number __pyx_mstate_global->__pyx_n_s_Number +#define __pyx_n_s_RuntimeError __pyx_mstate_global->__pyx_n_s_RuntimeError +#define __pyx_n_s_TypeError __pyx_mstate_global->__pyx_n_s_TypeError +#define __pyx_n_s__15 __pyx_mstate_global->__pyx_n_s__15 +#define __pyx_n_s__4 __pyx_mstate_global->__pyx_n_s__4 +#define __pyx_kp_u__5 __pyx_mstate_global->__pyx_kp_u__5 +#define __pyx_n_s_asyncio_coroutines __pyx_mstate_global->__pyx_n_s_asyncio_coroutines +#define __pyx_n_s_bus __pyx_mstate_global->__pyx_n_s_bus +#define __pyx_n_s_class_getitem __pyx_mstate_global->__pyx_n_s_class_getitem +#define __pyx_n_s_clear __pyx_mstate_global->__pyx_n_s_clear +#define __pyx_n_s_cline_in_traceback __pyx_mstate_global->__pyx_n_s_cline_in_traceback +#define __pyx_n_s_collections __pyx_mstate_global->__pyx_n_s_collections +#define __pyx_kp_u_could_not_find_message __pyx_mstate_global->__pyx_kp_u_could_not_find_message +#define __pyx_n_s_cv __pyx_mstate_global->__pyx_n_s_cv +#define __pyx_n_s_cv_name __pyx_mstate_global->__pyx_n_s_cv_name +#define __pyx_n_s_dbc_name __pyx_mstate_global->__pyx_n_s_dbc_name +#define __pyx_n_s_defaultdict __pyx_mstate_global->__pyx_n_s_defaultdict +#define __pyx_kp_u_disable __pyx_mstate_global->__pyx_kp_u_disable +#define __pyx_kp_u_enable __pyx_mstate_global->__pyx_kp_u_enable +#define __pyx_kp_u_gc __pyx_mstate_global->__pyx_kp_u_gc +#define __pyx_n_s_get __pyx_mstate_global->__pyx_n_s_get +#define __pyx_n_s_getstate __pyx_mstate_global->__pyx_n_s_getstate +#define __pyx_n_s_import __pyx_mstate_global->__pyx_n_s_import +#define __pyx_kp_u_in_DBC __pyx_mstate_global->__pyx_kp_u_in_DBC +#define __pyx_n_s_initializing __pyx_mstate_global->__pyx_n_s_initializing +#define __pyx_n_s_is_coroutine __pyx_mstate_global->__pyx_n_s_is_coroutine +#define __pyx_kp_u_isenabled __pyx_mstate_global->__pyx_kp_u_isenabled +#define __pyx_n_s_it __pyx_mstate_global->__pyx_n_s_it +#define __pyx_n_s_l __pyx_mstate_global->__pyx_n_s_l +#define __pyx_n_s_main __pyx_mstate_global->__pyx_n_s_main +#define __pyx_n_s_messages __pyx_mstate_global->__pyx_n_s_messages +#define __pyx_n_s_name __pyx_mstate_global->__pyx_n_s_name +#define __pyx_n_s_new_vals __pyx_mstate_global->__pyx_n_s_new_vals +#define __pyx_n_s_numbers __pyx_mstate_global->__pyx_n_s_numbers +#define __pyx_n_s_opendbc_can_parser_pyx __pyx_mstate_global->__pyx_n_s_opendbc_can_parser_pyx +#define __pyx_kp_s_opendbc_can_parser_pyx_pyx __pyx_mstate_global->__pyx_kp_s_opendbc_can_parser_pyx_pyx +#define __pyx_n_s_pyx_state __pyx_mstate_global->__pyx_n_s_pyx_state +#define __pyx_n_s_range __pyx_mstate_global->__pyx_n_s_range +#define __pyx_n_s_reduce __pyx_mstate_global->__pyx_n_s_reduce +#define __pyx_n_s_reduce_cython __pyx_mstate_global->__pyx_n_s_reduce_cython +#define __pyx_n_s_reduce_ex __pyx_mstate_global->__pyx_n_s_reduce_ex +#define __pyx_n_s_self __pyx_mstate_global->__pyx_n_s_self +#define __pyx_kp_s_self_can_self_dbc_cannot_be_conv __pyx_mstate_global->__pyx_kp_s_self_can_self_dbc_cannot_be_conv +#define __pyx_kp_s_self_dbc_cannot_be_converted_to __pyx_mstate_global->__pyx_kp_s_self_dbc_cannot_be_converted_to +#define __pyx_n_s_sendcan __pyx_mstate_global->__pyx_n_s_sendcan +#define __pyx_n_s_setstate __pyx_mstate_global->__pyx_n_s_setstate +#define __pyx_n_s_setstate_cython __pyx_mstate_global->__pyx_n_s_setstate_cython +#define __pyx_n_s_spec __pyx_mstate_global->__pyx_n_s_spec +#define __pyx_n_s_split __pyx_mstate_global->__pyx_n_s_split +#define __pyx_n_s_strings __pyx_mstate_global->__pyx_n_s_strings +#define __pyx_kp_s_stringsource __pyx_mstate_global->__pyx_kp_s_stringsource +#define __pyx_n_s_test __pyx_mstate_global->__pyx_n_s_test +#define __pyx_n_s_update_strings __pyx_mstate_global->__pyx_n_s_update_strings +#define __pyx_n_s_updated_addrs __pyx_mstate_global->__pyx_n_s_updated_addrs +#define __pyx_n_s_v __pyx_mstate_global->__pyx_n_s_v +#define __pyx_n_s_values __pyx_mstate_global->__pyx_n_s_values +#define __pyx_n_s_zip __pyx_mstate_global->__pyx_n_s_zip +#define __pyx_int_0 __pyx_mstate_global->__pyx_int_0 +#define __pyx_int_1 __pyx_mstate_global->__pyx_int_1 +#define __pyx_int_2 __pyx_mstate_global->__pyx_int_2 +#define __pyx_slice__2 __pyx_mstate_global->__pyx_slice__2 +#define __pyx_slice__3 __pyx_mstate_global->__pyx_slice__3 +#define __pyx_tuple__6 __pyx_mstate_global->__pyx_tuple__6 +#define __pyx_tuple__8 __pyx_mstate_global->__pyx_tuple__8 +#define __pyx_tuple__9 __pyx_mstate_global->__pyx_tuple__9 +#define __pyx_tuple__11 __pyx_mstate_global->__pyx_tuple__11 +#define __pyx_codeobj__7 __pyx_mstate_global->__pyx_codeobj__7 +#define __pyx_codeobj__10 __pyx_mstate_global->__pyx_codeobj__10 +#define __pyx_codeobj__12 __pyx_mstate_global->__pyx_codeobj__12 +#define __pyx_codeobj__13 __pyx_mstate_global->__pyx_codeobj__13 +#define __pyx_codeobj__14 __pyx_mstate_global->__pyx_codeobj__14 +/* #### Code section: module_code ### */ + +/* "string.from_py":13 + * + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: # <<<<<<<<<<<<<< + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + */ + +static std::string __pyx_convert_string_from_py_std__in_string(PyObject *__pyx_v_o) { + Py_ssize_t __pyx_v_length; + char const *__pyx_v_data; + std::string __pyx_r; + char const *__pyx_t_1; + std::string __pyx_t_2; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + + /* "string.from_py":14 + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: + * cdef Py_ssize_t length = 0 # <<<<<<<<<<<<<< + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + * return string(data, length) + */ + __pyx_v_length = 0; + + /* "string.from_py":15 + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) # <<<<<<<<<<<<<< + * return string(data, length) + * + */ + __pyx_t_1 = __Pyx_PyObject_AsStringAndSize(__pyx_v_o, (&__pyx_v_length)); if (unlikely(__pyx_t_1 == ((char const *)NULL))) __PYX_ERR(1, 15, __pyx_L1_error) + __pyx_v_data = __pyx_t_1; + + /* "string.from_py":16 + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + * return string(data, length) # <<<<<<<<<<<<<< + * + * + */ + try { + __pyx_t_2 = std::string(__pyx_v_data, __pyx_v_length); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(1, 16, __pyx_L1_error) + } + __pyx_r = __pyx_t_2; + goto __pyx_L0; + + /* "string.from_py":13 + * + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: # <<<<<<<<<<<<<< + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("string.from_py.__pyx_convert_string_from_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_pretend_to_initialize(&__pyx_r); + __pyx_L0:; + return __pyx_r; +} + +/* "string.to_py":31 + * + * @cname("__pyx_convert_PyObject_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyObject_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyObject_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyObject_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyObject_string_to_py_std__in_string", 1); + + /* "string.to_py":32 + * @cname("__pyx_convert_PyObject_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyObject_string_to_py_std__in_string(const string& s): + * return __Pyx_PyObject_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * cdef extern from *: + * cdef object __Pyx_PyUnicode_FromStringAndSize(const char*, size_t) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 32, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":31 + * + * @cname("__pyx_convert_PyObject_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyObject_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyObject_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyObject_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":37 + * + * @cname("__pyx_convert_PyUnicode_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyUnicode_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyUnicode_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyUnicode_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyUnicode_string_to_py_std__in_string", 1); + + /* "string.to_py":38 + * @cname("__pyx_convert_PyUnicode_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyUnicode_string_to_py_std__in_string(const string& s): + * return __Pyx_PyUnicode_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * cdef extern from *: + * cdef object __Pyx_PyStr_FromStringAndSize(const char*, size_t) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyUnicode_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 38, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":37 + * + * @cname("__pyx_convert_PyUnicode_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyUnicode_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyUnicode_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyUnicode_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":43 + * + * @cname("__pyx_convert_PyStr_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyStr_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyStr_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyStr_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyStr_string_to_py_std__in_string", 1); + + /* "string.to_py":44 + * @cname("__pyx_convert_PyStr_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyStr_string_to_py_std__in_string(const string& s): + * return __Pyx_PyStr_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * cdef extern from *: + * cdef object __Pyx_PyBytes_FromStringAndSize(const char*, size_t) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyStr_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 44, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":43 + * + * @cname("__pyx_convert_PyStr_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyStr_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyStr_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyStr_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":49 + * + * @cname("__pyx_convert_PyBytes_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyBytes_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyBytes_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyBytes_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyBytes_string_to_py_std__in_string", 1); + + /* "string.to_py":50 + * @cname("__pyx_convert_PyBytes_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyBytes_string_to_py_std__in_string(const string& s): + * return __Pyx_PyBytes_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * cdef extern from *: + * cdef object __Pyx_PyByteArray_FromStringAndSize(const char*, size_t) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyBytes_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 50, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":49 + * + * @cname("__pyx_convert_PyBytes_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyBytes_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyBytes_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyBytes_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":55 + * + * @cname("__pyx_convert_PyByteArray_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyByteArray_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyByteArray_FromStringAndSize(s.data(), s.size()) + * + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyByteArray_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyByteArray_string_to_py_std__in_string", 1); + + /* "string.to_py":56 + * @cname("__pyx_convert_PyByteArray_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyByteArray_string_to_py_std__in_string(const string& s): + * return __Pyx_PyByteArray_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyByteArray_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 56, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":55 + * + * @cname("__pyx_convert_PyByteArray_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyByteArray_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyByteArray_FromStringAndSize(s.data(), s.size()) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyByteArray_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "pair.from_py":177 + * + * @cname("__pyx_convert_pair_from_py_uint32_t__and_int") + * cdef pair[X,Y] __pyx_convert_pair_from_py_uint32_t__and_int(object o) except *: # <<<<<<<<<<<<<< + * x, y = o + * return pair[X,Y](x, y) + */ + +static std::pair __pyx_convert_pair_from_py_uint32_t__and_int(PyObject *__pyx_v_o) { + PyObject *__pyx_v_x = NULL; + PyObject *__pyx_v_y = NULL; + std::pair __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *(*__pyx_t_4)(PyObject *); + uint32_t __pyx_t_5; + int __pyx_t_6; + std::pair __pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_pair_from_py_uint32_t__and_int", 1); + + /* "pair.from_py":178 + * @cname("__pyx_convert_pair_from_py_uint32_t__and_int") + * cdef pair[X,Y] __pyx_convert_pair_from_py_uint32_t__and_int(object o) except *: + * x, y = o # <<<<<<<<<<<<<< + * return pair[X,Y](x, y) + * + */ + if ((likely(PyTuple_CheckExact(__pyx_v_o))) || (PyList_CheckExact(__pyx_v_o))) { + PyObject* sequence = __pyx_v_o; + Py_ssize_t size = __Pyx_PySequence_SIZE(sequence); + if (unlikely(size != 2)) { + if (size > 2) __Pyx_RaiseTooManyValuesError(2); + else if (size >= 0) __Pyx_RaiseNeedMoreValuesError(size); + __PYX_ERR(1, 178, __pyx_L1_error) + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + if (likely(PyTuple_CheckExact(sequence))) { + __pyx_t_1 = PyTuple_GET_ITEM(sequence, 0); + __pyx_t_2 = PyTuple_GET_ITEM(sequence, 1); + } else { + __pyx_t_1 = PyList_GET_ITEM(sequence, 0); + __pyx_t_2 = PyList_GET_ITEM(sequence, 1); + } + __Pyx_INCREF(__pyx_t_1); + __Pyx_INCREF(__pyx_t_2); + #else + __pyx_t_1 = PySequence_ITEM(sequence, 0); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 178, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = PySequence_ITEM(sequence, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 178, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + #endif + } else { + Py_ssize_t index = -1; + __pyx_t_3 = PyObject_GetIter(__pyx_v_o); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 178, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_3); + index = 0; __pyx_t_1 = __pyx_t_4(__pyx_t_3); if (unlikely(!__pyx_t_1)) goto __pyx_L3_unpacking_failed; + __Pyx_GOTREF(__pyx_t_1); + index = 1; __pyx_t_2 = __pyx_t_4(__pyx_t_3); if (unlikely(!__pyx_t_2)) goto __pyx_L3_unpacking_failed; + __Pyx_GOTREF(__pyx_t_2); + if (__Pyx_IternextUnpackEndCheck(__pyx_t_4(__pyx_t_3), 2) < 0) __PYX_ERR(1, 178, __pyx_L1_error) + __pyx_t_4 = NULL; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L4_unpacking_done; + __pyx_L3_unpacking_failed:; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_4 = NULL; + if (__Pyx_IterFinish() == 0) __Pyx_RaiseNeedMoreValuesError(index); + __PYX_ERR(1, 178, __pyx_L1_error) + __pyx_L4_unpacking_done:; + } + __pyx_v_x = __pyx_t_1; + __pyx_t_1 = 0; + __pyx_v_y = __pyx_t_2; + __pyx_t_2 = 0; + + /* "pair.from_py":179 + * cdef pair[X,Y] __pyx_convert_pair_from_py_uint32_t__and_int(object o) except *: + * x, y = o + * return pair[X,Y](x, y) # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_5 = __Pyx_PyInt_As_uint32_t(__pyx_v_x); if (unlikely((__pyx_t_5 == ((uint32_t)-1)) && PyErr_Occurred())) __PYX_ERR(1, 179, __pyx_L1_error) + __pyx_t_6 = __Pyx_PyInt_As_int(__pyx_v_y); if (unlikely((__pyx_t_6 == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 179, __pyx_L1_error) + try { + __pyx_t_7 = std::pair (((uint32_t)__pyx_t_5), ((int)__pyx_t_6)); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(1, 179, __pyx_L1_error) + } + __pyx_r = __pyx_t_7; + goto __pyx_L0; + + /* "pair.from_py":177 + * + * @cname("__pyx_convert_pair_from_py_uint32_t__and_int") + * cdef pair[X,Y] __pyx_convert_pair_from_py_uint32_t__and_int(object o) except *: # <<<<<<<<<<<<<< + * x, y = o + * return pair[X,Y](x, y) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("pair.from_py.__pyx_convert_pair_from_py_uint32_t__and_int", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_pretend_to_initialize(&__pyx_r); + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_x); + __Pyx_XDECREF(__pyx_v_y); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "vector.from_py":45 + * + * @cname("__pyx_convert_vector_from_py_std_3a__3a_string") + * cdef vector[X] __pyx_convert_vector_from_py_std_3a__3a_string(object o) except *: # <<<<<<<<<<<<<< + * cdef vector[X] v + * for item in o: + */ + +static std::vector __pyx_convert_vector_from_py_std_3a__3a_string(PyObject *__pyx_v_o) { + std::vector __pyx_v_v; + PyObject *__pyx_v_item = NULL; + std::vector __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + Py_ssize_t __pyx_t_2; + PyObject *(*__pyx_t_3)(PyObject *); + PyObject *__pyx_t_4 = NULL; + std::string __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_vector_from_py_std_3a__3a_string", 1); + + /* "vector.from_py":47 + * cdef vector[X] __pyx_convert_vector_from_py_std_3a__3a_string(object o) except *: + * cdef vector[X] v + * for item in o: # <<<<<<<<<<<<<< + * v.push_back(item) + * return v + */ + if (likely(PyList_CheckExact(__pyx_v_o)) || PyTuple_CheckExact(__pyx_v_o)) { + __pyx_t_1 = __pyx_v_o; __Pyx_INCREF(__pyx_t_1); + __pyx_t_2 = 0; + __pyx_t_3 = NULL; + } else { + __pyx_t_2 = -1; __pyx_t_1 = PyObject_GetIter(__pyx_v_o); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 47, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 47, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_3)) { + if (likely(PyList_CheckExact(__pyx_t_1))) { + { + Py_ssize_t __pyx_temp = __Pyx_PyList_GET_SIZE(__pyx_t_1); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 47, __pyx_L1_error) + #endif + if (__pyx_t_2 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyList_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(1, 47, __pyx_L1_error) + #else + __pyx_t_4 = __Pyx_PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 47, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } else { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_1); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 47, __pyx_L1_error) + #endif + if (__pyx_t_2 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyTuple_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(1, 47, __pyx_L1_error) + #else + __pyx_t_4 = __Pyx_PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 47, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } + } else { + __pyx_t_4 = __pyx_t_3(__pyx_t_1); + if (unlikely(!__pyx_t_4)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(1, 47, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_4); + } + __Pyx_XDECREF_SET(__pyx_v_item, __pyx_t_4); + __pyx_t_4 = 0; + + /* "vector.from_py":48 + * cdef vector[X] v + * for item in o: + * v.push_back(item) # <<<<<<<<<<<<<< + * return v + * + */ + __pyx_t_5 = __pyx_convert_string_from_py_std__in_string(__pyx_v_item); if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 48, __pyx_L1_error) + try { + __pyx_v_v.push_back(((std::string)__pyx_t_5)); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(1, 48, __pyx_L1_error) + } + + /* "vector.from_py":47 + * cdef vector[X] __pyx_convert_vector_from_py_std_3a__3a_string(object o) except *: + * cdef vector[X] v + * for item in o: # <<<<<<<<<<<<<< + * v.push_back(item) + * return v + */ + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "vector.from_py":49 + * for item in o: + * v.push_back(item) + * return v # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = __pyx_v_v; + goto __pyx_L0; + + /* "vector.from_py":45 + * + * @cname("__pyx_convert_vector_from_py_std_3a__3a_string") + * cdef vector[X] __pyx_convert_vector_from_py_std_3a__3a_string(object o) except *: # <<<<<<<<<<<<<< + * cdef vector[X] v + * for item in o: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("vector.from_py.__pyx_convert_vector_from_py_std_3a__3a_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_pretend_to_initialize(&__pyx_r); + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_item); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "vector.to_py":66 + * + * @cname("__pyx_convert_vector_to_py_double") + * cdef object __pyx_convert_vector_to_py_double(const vector[X]& v): # <<<<<<<<<<<<<< + * if v.size() > PY_SSIZE_T_MAX: + * raise MemoryError() + */ + +static PyObject *__pyx_convert_vector_to_py_double(std::vector const &__pyx_v_v) { + Py_ssize_t __pyx_v_v_size_signed; + PyObject *__pyx_v_o = NULL; + Py_ssize_t __pyx_v_i; + PyObject *__pyx_v_item = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + Py_ssize_t __pyx_t_3; + Py_ssize_t __pyx_t_4; + Py_ssize_t __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_vector_to_py_double", 1); + + /* "vector.to_py":67 + * @cname("__pyx_convert_vector_to_py_double") + * cdef object __pyx_convert_vector_to_py_double(const vector[X]& v): + * if v.size() > PY_SSIZE_T_MAX: # <<<<<<<<<<<<<< + * raise MemoryError() + * v_size_signed = v.size() + */ + __pyx_t_1 = (__pyx_v_v.size() > ((size_t)PY_SSIZE_T_MAX)); + if (unlikely(__pyx_t_1)) { + + /* "vector.to_py":68 + * cdef object __pyx_convert_vector_to_py_double(const vector[X]& v): + * if v.size() > PY_SSIZE_T_MAX: + * raise MemoryError() # <<<<<<<<<<<<<< + * v_size_signed = v.size() + * + */ + PyErr_NoMemory(); __PYX_ERR(1, 68, __pyx_L1_error) + + /* "vector.to_py":67 + * @cname("__pyx_convert_vector_to_py_double") + * cdef object __pyx_convert_vector_to_py_double(const vector[X]& v): + * if v.size() > PY_SSIZE_T_MAX: # <<<<<<<<<<<<<< + * raise MemoryError() + * v_size_signed = v.size() + */ + } + + /* "vector.to_py":69 + * if v.size() > PY_SSIZE_T_MAX: + * raise MemoryError() + * v_size_signed = v.size() # <<<<<<<<<<<<<< + * + * o = PyList_New(v_size_signed) + */ + __pyx_v_v_size_signed = ((Py_ssize_t)__pyx_v_v.size()); + + /* "vector.to_py":71 + * v_size_signed = v.size() + * + * o = PyList_New(v_size_signed) # <<<<<<<<<<<<<< + * + * cdef Py_ssize_t i + */ + __pyx_t_2 = PyList_New(__pyx_v_v_size_signed); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 71, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_v_o = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; + + /* "vector.to_py":76 + * cdef object item + * + * for i in range(v_size_signed): # <<<<<<<<<<<<<< + * item = v[i] + * Py_INCREF(item) + */ + __pyx_t_3 = __pyx_v_v_size_signed; + __pyx_t_4 = __pyx_t_3; + for (__pyx_t_5 = 0; __pyx_t_5 < __pyx_t_4; __pyx_t_5+=1) { + __pyx_v_i = __pyx_t_5; + + /* "vector.to_py":77 + * + * for i in range(v_size_signed): + * item = v[i] # <<<<<<<<<<<<<< + * Py_INCREF(item) + * PyList_SET_ITEM(o, i, item) + */ + __pyx_t_2 = PyFloat_FromDouble((__pyx_v_v[__pyx_v_i])); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 77, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_XDECREF_SET(__pyx_v_item, __pyx_t_2); + __pyx_t_2 = 0; + + /* "vector.to_py":78 + * for i in range(v_size_signed): + * item = v[i] + * Py_INCREF(item) # <<<<<<<<<<<<<< + * PyList_SET_ITEM(o, i, item) + * + */ + Py_INCREF(__pyx_v_item); + + /* "vector.to_py":79 + * item = v[i] + * Py_INCREF(item) + * PyList_SET_ITEM(o, i, item) # <<<<<<<<<<<<<< + * + * return o + */ + PyList_SET_ITEM(__pyx_v_o, __pyx_v_i, __pyx_v_item); + } + + /* "vector.to_py":81 + * PyList_SET_ITEM(o, i, item) + * + * return o # <<<<<<<<<<<<<< + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_o); + __pyx_r = __pyx_v_o; + goto __pyx_L0; + + /* "vector.to_py":66 + * + * @cname("__pyx_convert_vector_to_py_double") + * cdef object __pyx_convert_vector_to_py_double(const vector[X]& v): # <<<<<<<<<<<<<< + * if v.size() > PY_SSIZE_T_MAX: + * raise MemoryError() + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("vector.to_py.__pyx_convert_vector_to_py_double", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_o); + __Pyx_XDECREF(__pyx_v_item); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "set.to_py":166 + * + * @cname("__pyx_convert_unordered_set_to_py_uint32_t") + * cdef object __pyx_convert_unordered_set_to_py_uint32_t(const cpp_set[X]& s): # <<<<<<<<<<<<<< + * return {v for v in s} + * + */ + +static PyObject *__pyx_convert_unordered_set_to_py_uint32_t(std::unordered_set const &__pyx_v_s) { + uint32_t __pyx_7genexpr__pyx_v_v; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + std::unordered_set ::const_iterator __pyx_t_2; + uint32_t __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_unordered_set_to_py_uint32_t", 1); + + /* "set.to_py":167 + * @cname("__pyx_convert_unordered_set_to_py_uint32_t") + * cdef object __pyx_convert_unordered_set_to_py_uint32_t(const cpp_set[X]& s): + * return {v for v in s} # <<<<<<<<<<<<<< + * + */ + __Pyx_XDECREF(__pyx_r); + { /* enter inner scope */ + __pyx_t_1 = PySet_New(NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 167, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_v_s.begin(); + for (;;) { + if (!(__pyx_t_2 != __pyx_v_s.end())) break; + __pyx_t_3 = *__pyx_t_2; + ++__pyx_t_2; + __pyx_7genexpr__pyx_v_v = __pyx_t_3; + __pyx_t_4 = __Pyx_PyInt_From_uint32_t(__pyx_7genexpr__pyx_v_v); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 167, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (unlikely(PySet_Add(__pyx_t_1, (PyObject*)__pyx_t_4))) __PYX_ERR(1, 167, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + } /* exit inner scope */ + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "set.to_py":166 + * + * @cname("__pyx_convert_unordered_set_to_py_uint32_t") + * cdef object __pyx_convert_unordered_set_to_py_uint32_t(const cpp_set[X]& s): # <<<<<<<<<<<<<< + * return {v for v in s} + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("set.to_py.__pyx_convert_unordered_set_to_py_uint32_t", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "opendbc/can/parser_pyx.pyx":30 + * string dbc_name + * + * def __init__(self, dbc_name, messages, bus=0): # <<<<<<<<<<<<<< + * self.dbc_name = dbc_name + * self.dbc = dbc_lookup(dbc_name) + */ + +/* Python wrapper */ +static int __pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_1__init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_1__init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_dbc_name = 0; + PyObject *__pyx_v_messages = 0; + PyObject *__pyx_v_bus = 0; + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__init__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_dbc_name,&__pyx_n_s_messages,&__pyx_n_s_bus,0}; + values[2] = __Pyx_Arg_NewRef_VARARGS(((PyObject *)__pyx_int_0)); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_dbc_name)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 30, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_messages)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 30, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__init__", 0, 2, 3, 1); __PYX_ERR(0, 30, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_bus); + if (value) { values[2] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 30, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__init__") < 0)) __PYX_ERR(0, 30, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_dbc_name = values[0]; + __pyx_v_messages = values[1]; + __pyx_v_bus = values[2]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__init__", 0, 2, 3, __pyx_nargs); __PYX_ERR(0, 30, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("opendbc.can.parser_pyx.CANParser.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_7opendbc_3can_10parser_pyx_9CANParser___init__(((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *)__pyx_v_self), __pyx_v_dbc_name, __pyx_v_messages, __pyx_v_bus); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANParser___init__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self, PyObject *__pyx_v_dbc_name, PyObject *__pyx_v_messages, PyObject *__pyx_v_bus) { + PyObject *__pyx_v_msg_name_to_address = NULL; + PyObject *__pyx_v_address_to_msg_name = NULL; + std::vector ::size_type __pyx_v_i; + struct Msg __pyx_v_msg; + PyObject *__pyx_v_name = NULL; + std::vector > __pyx_v_message_v; + PyObject *__pyx_v_c = NULL; + PyObject *__pyx_v_address = NULL; + int __pyx_r; + __Pyx_RefNannyDeclarations + std::string __pyx_t_1; + struct DBC const *__pyx_t_2; + int __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + std::vector ::size_type __pyx_t_6; + std::vector ::size_type __pyx_t_7; + std::vector ::size_type __pyx_t_8; + Py_ssize_t __pyx_t_9; + Py_ssize_t __pyx_t_10; + PyObject *__pyx_t_11 = NULL; + PyObject *__pyx_t_12 = NULL; + Py_ssize_t __pyx_t_13; + Py_UCS4 __pyx_t_14; + std::pair __pyx_t_15; + int __pyx_t_16; + CANParser *__pyx_t_17; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__init__", 1); + + /* "opendbc/can/parser_pyx.pyx":31 + * + * def __init__(self, dbc_name, messages, bus=0): + * self.dbc_name = dbc_name # <<<<<<<<<<<<<< + * self.dbc = dbc_lookup(dbc_name) + * if not self.dbc: + */ + __pyx_t_1 = __pyx_convert_string_from_py_std__in_string(__pyx_v_dbc_name); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 31, __pyx_L1_error) + __pyx_v_self->dbc_name = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_1); + + /* "opendbc/can/parser_pyx.pyx":32 + * def __init__(self, dbc_name, messages, bus=0): + * self.dbc_name = dbc_name + * self.dbc = dbc_lookup(dbc_name) # <<<<<<<<<<<<<< + * if not self.dbc: + * raise RuntimeError(f"Can't find DBC: {dbc_name}") + */ + __pyx_t_1 = __pyx_convert_string_from_py_std__in_string(__pyx_v_dbc_name); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 32, __pyx_L1_error) + try { + __pyx_t_2 = dbc_lookup(__PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_1)); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(0, 32, __pyx_L1_error) + } + __pyx_v_self->dbc = __pyx_t_2; + + /* "opendbc/can/parser_pyx.pyx":33 + * self.dbc_name = dbc_name + * self.dbc = dbc_lookup(dbc_name) + * if not self.dbc: # <<<<<<<<<<<<<< + * raise RuntimeError(f"Can't find DBC: {dbc_name}") + * + */ + __pyx_t_3 = (!(__pyx_v_self->dbc != 0)); + if (unlikely(__pyx_t_3)) { + + /* "opendbc/can/parser_pyx.pyx":34 + * self.dbc = dbc_lookup(dbc_name) + * if not self.dbc: + * raise RuntimeError(f"Can't find DBC: {dbc_name}") # <<<<<<<<<<<<<< + * + * self.vl = {} + */ + __pyx_t_4 = __Pyx_PyObject_FormatSimple(__pyx_v_dbc_name, __pyx_empty_unicode); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 34, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyUnicode_Concat(__pyx_kp_u_Can_t_find_DBC, __pyx_t_4); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 34, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyObject_CallOneArg(__pyx_builtin_RuntimeError, __pyx_t_5); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 34, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_Raise(__pyx_t_4, 0, 0, 0); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __PYX_ERR(0, 34, __pyx_L1_error) + + /* "opendbc/can/parser_pyx.pyx":33 + * self.dbc_name = dbc_name + * self.dbc = dbc_lookup(dbc_name) + * if not self.dbc: # <<<<<<<<<<<<<< + * raise RuntimeError(f"Can't find DBC: {dbc_name}") + * + */ + } + + /* "opendbc/can/parser_pyx.pyx":36 + * raise RuntimeError(f"Can't find DBC: {dbc_name}") + * + * self.vl = {} # <<<<<<<<<<<<<< + * self.vl_all = {} + * self.ts_nanos = {} + */ + __pyx_t_4 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 36, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + __Pyx_GOTREF(__pyx_v_self->vl); + __Pyx_DECREF(__pyx_v_self->vl); + __pyx_v_self->vl = ((PyObject*)__pyx_t_4); + __pyx_t_4 = 0; + + /* "opendbc/can/parser_pyx.pyx":37 + * + * self.vl = {} + * self.vl_all = {} # <<<<<<<<<<<<<< + * self.ts_nanos = {} + * msg_name_to_address = {} + */ + __pyx_t_4 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 37, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + __Pyx_GOTREF(__pyx_v_self->vl_all); + __Pyx_DECREF(__pyx_v_self->vl_all); + __pyx_v_self->vl_all = ((PyObject*)__pyx_t_4); + __pyx_t_4 = 0; + + /* "opendbc/can/parser_pyx.pyx":38 + * self.vl = {} + * self.vl_all = {} + * self.ts_nanos = {} # <<<<<<<<<<<<<< + * msg_name_to_address = {} + * address_to_msg_name = {} + */ + __pyx_t_4 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 38, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + __Pyx_GOTREF(__pyx_v_self->ts_nanos); + __Pyx_DECREF(__pyx_v_self->ts_nanos); + __pyx_v_self->ts_nanos = ((PyObject*)__pyx_t_4); + __pyx_t_4 = 0; + + /* "opendbc/can/parser_pyx.pyx":39 + * self.vl_all = {} + * self.ts_nanos = {} + * msg_name_to_address = {} # <<<<<<<<<<<<<< + * address_to_msg_name = {} + * + */ + __pyx_t_4 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 39, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_v_msg_name_to_address = ((PyObject*)__pyx_t_4); + __pyx_t_4 = 0; + + /* "opendbc/can/parser_pyx.pyx":40 + * self.ts_nanos = {} + * msg_name_to_address = {} + * address_to_msg_name = {} # <<<<<<<<<<<<<< + * + * for i in range(self.dbc[0].msgs.size()): + */ + __pyx_t_4 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_v_address_to_msg_name = ((PyObject*)__pyx_t_4); + __pyx_t_4 = 0; + + /* "opendbc/can/parser_pyx.pyx":42 + * address_to_msg_name = {} + * + * for i in range(self.dbc[0].msgs.size()): # <<<<<<<<<<<<<< + * msg = self.dbc[0].msgs[i] + * name = msg.name.decode("utf8") + */ + __pyx_t_6 = (__pyx_v_self->dbc[0]).msgs.size(); + __pyx_t_7 = __pyx_t_6; + for (__pyx_t_8 = 0; __pyx_t_8 < __pyx_t_7; __pyx_t_8+=1) { + __pyx_v_i = __pyx_t_8; + + /* "opendbc/can/parser_pyx.pyx":43 + * + * for i in range(self.dbc[0].msgs.size()): + * msg = self.dbc[0].msgs[i] # <<<<<<<<<<<<<< + * name = msg.name.decode("utf8") + * + */ + __pyx_v_msg = ((__pyx_v_self->dbc[0]).msgs[__pyx_v_i]); + + /* "opendbc/can/parser_pyx.pyx":44 + * for i in range(self.dbc[0].msgs.size()): + * msg = self.dbc[0].msgs[i] + * name = msg.name.decode("utf8") # <<<<<<<<<<<<<< + * + * msg_name_to_address[name] = msg.address + */ + __pyx_t_4 = __Pyx_decode_cpp_string(__pyx_v_msg.name, 0, PY_SSIZE_T_MAX, NULL, NULL, PyUnicode_DecodeUTF8); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 44, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_XDECREF_SET(__pyx_v_name, __pyx_t_4); + __pyx_t_4 = 0; + + /* "opendbc/can/parser_pyx.pyx":46 + * name = msg.name.decode("utf8") + * + * msg_name_to_address[name] = msg.address # <<<<<<<<<<<<<< + * address_to_msg_name[msg.address] = name + * + */ + __pyx_t_4 = __Pyx_PyInt_From_uint32_t(__pyx_v_msg.address); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 46, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (unlikely((PyDict_SetItem(__pyx_v_msg_name_to_address, __pyx_v_name, __pyx_t_4) < 0))) __PYX_ERR(0, 46, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "opendbc/can/parser_pyx.pyx":47 + * + * msg_name_to_address[name] = msg.address + * address_to_msg_name[msg.address] = name # <<<<<<<<<<<<<< + * + * # Convert message names into addresses and check existence in DBC + */ + __pyx_t_4 = __Pyx_PyInt_From_uint32_t(__pyx_v_msg.address); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 47, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (unlikely((PyDict_SetItem(__pyx_v_address_to_msg_name, __pyx_t_4, __pyx_v_name) < 0))) __PYX_ERR(0, 47, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + + /* "opendbc/can/parser_pyx.pyx":51 + * # Convert message names into addresses and check existence in DBC + * cdef vector[pair[uint32_t, int]] message_v + * for i in range(len(messages)): # <<<<<<<<<<<<<< + * c = messages[i] + * address = c[0] if isinstance(c[0], numbers.Number) else msg_name_to_address.get(c[0]) + */ + __pyx_t_9 = PyObject_Length(__pyx_v_messages); if (unlikely(__pyx_t_9 == ((Py_ssize_t)-1))) __PYX_ERR(0, 51, __pyx_L1_error) + __pyx_t_10 = __pyx_t_9; + for (__pyx_t_6 = 0; __pyx_t_6 < __pyx_t_10; __pyx_t_6+=1) { + __pyx_v_i = __pyx_t_6; + + /* "opendbc/can/parser_pyx.pyx":52 + * cdef vector[pair[uint32_t, int]] message_v + * for i in range(len(messages)): + * c = messages[i] # <<<<<<<<<<<<<< + * address = c[0] if isinstance(c[0], numbers.Number) else msg_name_to_address.get(c[0]) + * if address not in address_to_msg_name: + */ + __pyx_t_4 = __Pyx_GetItemInt(__pyx_v_messages, __pyx_v_i, std::vector ::size_type, 0, __Pyx_PyInt_FromSize_t, 0, 0, 1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 52, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_XDECREF_SET(__pyx_v_c, __pyx_t_4); + __pyx_t_4 = 0; + + /* "opendbc/can/parser_pyx.pyx":53 + * for i in range(len(messages)): + * c = messages[i] + * address = c[0] if isinstance(c[0], numbers.Number) else msg_name_to_address.get(c[0]) # <<<<<<<<<<<<<< + * if address not in address_to_msg_name: + * raise RuntimeError(f"could not find message {repr(c[0])} in DBC {self.dbc_name}") + */ + __pyx_t_5 = __Pyx_GetItemInt(__pyx_v_c, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 53, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_GetModuleGlobalName(__pyx_t_11, __pyx_n_s_numbers); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 53, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_11); + __pyx_t_12 = __Pyx_PyObject_GetAttrStr(__pyx_t_11, __pyx_n_s_Number); if (unlikely(!__pyx_t_12)) __PYX_ERR(0, 53, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_12); + __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; + __pyx_t_3 = PyObject_IsInstance(__pyx_t_5, __pyx_t_12); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(0, 53, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_12); __pyx_t_12 = 0; + if (__pyx_t_3) { + __pyx_t_12 = __Pyx_GetItemInt(__pyx_v_c, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_12)) __PYX_ERR(0, 53, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_12); + __pyx_t_4 = __pyx_t_12; + __pyx_t_12 = 0; + } else { + __pyx_t_12 = __Pyx_GetItemInt(__pyx_v_c, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_12)) __PYX_ERR(0, 53, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_12); + __pyx_t_5 = __Pyx_PyDict_GetItemDefault(__pyx_v_msg_name_to_address, __pyx_t_12, Py_None); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 53, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_12); __pyx_t_12 = 0; + __pyx_t_4 = __pyx_t_5; + __pyx_t_5 = 0; + } + __Pyx_XDECREF_SET(__pyx_v_address, __pyx_t_4); + __pyx_t_4 = 0; + + /* "opendbc/can/parser_pyx.pyx":54 + * c = messages[i] + * address = c[0] if isinstance(c[0], numbers.Number) else msg_name_to_address.get(c[0]) + * if address not in address_to_msg_name: # <<<<<<<<<<<<<< + * raise RuntimeError(f"could not find message {repr(c[0])} in DBC {self.dbc_name}") + * message_v.push_back((address, c[1])) + */ + __pyx_t_3 = (__Pyx_PyDict_ContainsTF(__pyx_v_address, __pyx_v_address_to_msg_name, Py_NE)); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(0, 54, __pyx_L1_error) + if (unlikely(__pyx_t_3)) { + + /* "opendbc/can/parser_pyx.pyx":55 + * address = c[0] if isinstance(c[0], numbers.Number) else msg_name_to_address.get(c[0]) + * if address not in address_to_msg_name: + * raise RuntimeError(f"could not find message {repr(c[0])} in DBC {self.dbc_name}") # <<<<<<<<<<<<<< + * message_v.push_back((address, c[1])) + * + */ + __pyx_t_4 = PyTuple_New(4); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 55, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_13 = 0; + __pyx_t_14 = 127; + __Pyx_INCREF(__pyx_kp_u_could_not_find_message); + __pyx_t_13 += 23; + __Pyx_GIVEREF(__pyx_kp_u_could_not_find_message); + PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_kp_u_could_not_find_message); + __pyx_t_5 = __Pyx_GetItemInt(__pyx_v_c, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 55, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_12 = PyObject_Repr(__pyx_t_5); if (unlikely(!__pyx_t_12)) __PYX_ERR(0, 55, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_12); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_5 = __Pyx_PyObject_FormatSimple(__pyx_t_12, __pyx_empty_unicode); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 55, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_12); __pyx_t_12 = 0; + __pyx_t_14 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_5) > __pyx_t_14) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_5) : __pyx_t_14; + __pyx_t_13 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_5); + __Pyx_GIVEREF(__pyx_t_5); + PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_t_5); + __pyx_t_5 = 0; + __Pyx_INCREF(__pyx_kp_u_in_DBC); + __pyx_t_13 += 8; + __Pyx_GIVEREF(__pyx_kp_u_in_DBC); + PyTuple_SET_ITEM(__pyx_t_4, 2, __pyx_kp_u_in_DBC); + __pyx_t_5 = __pyx_convert_PyBytes_string_to_py_std__in_string(__pyx_v_self->dbc_name); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 55, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_12 = __Pyx_PyObject_FormatSimple(__pyx_t_5, __pyx_empty_unicode); if (unlikely(!__pyx_t_12)) __PYX_ERR(0, 55, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_12); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_14 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_12) > __pyx_t_14) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_12) : __pyx_t_14; + __pyx_t_13 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_12); + __Pyx_GIVEREF(__pyx_t_12); + PyTuple_SET_ITEM(__pyx_t_4, 3, __pyx_t_12); + __pyx_t_12 = 0; + __pyx_t_12 = __Pyx_PyUnicode_Join(__pyx_t_4, 4, __pyx_t_13, __pyx_t_14); if (unlikely(!__pyx_t_12)) __PYX_ERR(0, 55, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_12); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyObject_CallOneArg(__pyx_builtin_RuntimeError, __pyx_t_12); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 55, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_12); __pyx_t_12 = 0; + __Pyx_Raise(__pyx_t_4, 0, 0, 0); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __PYX_ERR(0, 55, __pyx_L1_error) + + /* "opendbc/can/parser_pyx.pyx":54 + * c = messages[i] + * address = c[0] if isinstance(c[0], numbers.Number) else msg_name_to_address.get(c[0]) + * if address not in address_to_msg_name: # <<<<<<<<<<<<<< + * raise RuntimeError(f"could not find message {repr(c[0])} in DBC {self.dbc_name}") + * message_v.push_back((address, c[1])) + */ + } + + /* "opendbc/can/parser_pyx.pyx":56 + * if address not in address_to_msg_name: + * raise RuntimeError(f"could not find message {repr(c[0])} in DBC {self.dbc_name}") + * message_v.push_back((address, c[1])) # <<<<<<<<<<<<<< + * + * name = address_to_msg_name[address] + */ + __pyx_t_4 = __Pyx_GetItemInt(__pyx_v_c, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 56, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_12 = PyTuple_New(2); if (unlikely(!__pyx_t_12)) __PYX_ERR(0, 56, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_12); + __Pyx_INCREF(__pyx_v_address); + __Pyx_GIVEREF(__pyx_v_address); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_12, 0, __pyx_v_address)) __PYX_ERR(0, 56, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_4); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_12, 1, __pyx_t_4)) __PYX_ERR(0, 56, __pyx_L1_error); + __pyx_t_4 = 0; + __pyx_t_15 = __pyx_convert_pair_from_py_uint32_t__and_int(__pyx_t_12); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 56, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_12); __pyx_t_12 = 0; + try { + __pyx_v_message_v.push_back(__pyx_t_15); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(0, 56, __pyx_L1_error) + } + + /* "opendbc/can/parser_pyx.pyx":58 + * message_v.push_back((address, c[1])) + * + * name = address_to_msg_name[address] # <<<<<<<<<<<<<< + * self.vl[address] = {} + * self.vl[name] = self.vl[address] + */ + __pyx_t_12 = __Pyx_PyDict_GetItem(__pyx_v_address_to_msg_name, __pyx_v_address); if (unlikely(!__pyx_t_12)) __PYX_ERR(0, 58, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_12); + __Pyx_XDECREF_SET(__pyx_v_name, __pyx_t_12); + __pyx_t_12 = 0; + + /* "opendbc/can/parser_pyx.pyx":59 + * + * name = address_to_msg_name[address] + * self.vl[address] = {} # <<<<<<<<<<<<<< + * self.vl[name] = self.vl[address] + * self.vl_all[address] = {} + */ + __pyx_t_12 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_12)) __PYX_ERR(0, 59, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_12); + if (unlikely(__pyx_v_self->vl == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(0, 59, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__pyx_v_self->vl, __pyx_v_address, __pyx_t_12) < 0))) __PYX_ERR(0, 59, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_12); __pyx_t_12 = 0; + + /* "opendbc/can/parser_pyx.pyx":60 + * name = address_to_msg_name[address] + * self.vl[address] = {} + * self.vl[name] = self.vl[address] # <<<<<<<<<<<<<< + * self.vl_all[address] = {} + * self.vl_all[name] = self.vl_all[address] + */ + if (unlikely(__pyx_v_self->vl == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(0, 60, __pyx_L1_error) + } + __pyx_t_12 = __Pyx_PyDict_GetItem(__pyx_v_self->vl, __pyx_v_address); if (unlikely(!__pyx_t_12)) __PYX_ERR(0, 60, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_12); + if (unlikely(__pyx_v_self->vl == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(0, 60, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__pyx_v_self->vl, __pyx_v_name, __pyx_t_12) < 0))) __PYX_ERR(0, 60, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_12); __pyx_t_12 = 0; + + /* "opendbc/can/parser_pyx.pyx":61 + * self.vl[address] = {} + * self.vl[name] = self.vl[address] + * self.vl_all[address] = {} # <<<<<<<<<<<<<< + * self.vl_all[name] = self.vl_all[address] + * self.ts_nanos[address] = {} + */ + __pyx_t_12 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_12)) __PYX_ERR(0, 61, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_12); + if (unlikely(__pyx_v_self->vl_all == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(0, 61, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__pyx_v_self->vl_all, __pyx_v_address, __pyx_t_12) < 0))) __PYX_ERR(0, 61, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_12); __pyx_t_12 = 0; + + /* "opendbc/can/parser_pyx.pyx":62 + * self.vl[name] = self.vl[address] + * self.vl_all[address] = {} + * self.vl_all[name] = self.vl_all[address] # <<<<<<<<<<<<<< + * self.ts_nanos[address] = {} + * self.ts_nanos[name] = self.ts_nanos[address] + */ + if (unlikely(__pyx_v_self->vl_all == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(0, 62, __pyx_L1_error) + } + __pyx_t_12 = __Pyx_PyDict_GetItem(__pyx_v_self->vl_all, __pyx_v_address); if (unlikely(!__pyx_t_12)) __PYX_ERR(0, 62, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_12); + if (unlikely(__pyx_v_self->vl_all == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(0, 62, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__pyx_v_self->vl_all, __pyx_v_name, __pyx_t_12) < 0))) __PYX_ERR(0, 62, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_12); __pyx_t_12 = 0; + + /* "opendbc/can/parser_pyx.pyx":63 + * self.vl_all[address] = {} + * self.vl_all[name] = self.vl_all[address] + * self.ts_nanos[address] = {} # <<<<<<<<<<<<<< + * self.ts_nanos[name] = self.ts_nanos[address] + * + */ + __pyx_t_12 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_12)) __PYX_ERR(0, 63, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_12); + if (unlikely(__pyx_v_self->ts_nanos == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(0, 63, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__pyx_v_self->ts_nanos, __pyx_v_address, __pyx_t_12) < 0))) __PYX_ERR(0, 63, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_12); __pyx_t_12 = 0; + + /* "opendbc/can/parser_pyx.pyx":64 + * self.vl_all[name] = self.vl_all[address] + * self.ts_nanos[address] = {} + * self.ts_nanos[name] = self.ts_nanos[address] # <<<<<<<<<<<<<< + * + * self.can = new cpp_CANParser(bus, dbc_name, message_v) + */ + if (unlikely(__pyx_v_self->ts_nanos == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(0, 64, __pyx_L1_error) + } + __pyx_t_12 = __Pyx_PyDict_GetItem(__pyx_v_self->ts_nanos, __pyx_v_address); if (unlikely(!__pyx_t_12)) __PYX_ERR(0, 64, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_12); + if (unlikely(__pyx_v_self->ts_nanos == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(0, 64, __pyx_L1_error) + } + if (unlikely((PyDict_SetItem(__pyx_v_self->ts_nanos, __pyx_v_name, __pyx_t_12) < 0))) __PYX_ERR(0, 64, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_12); __pyx_t_12 = 0; + } + + /* "opendbc/can/parser_pyx.pyx":66 + * self.ts_nanos[name] = self.ts_nanos[address] + * + * self.can = new cpp_CANParser(bus, dbc_name, message_v) # <<<<<<<<<<<<<< + * self.update_strings([]) + * + */ + __pyx_t_16 = __Pyx_PyInt_As_int(__pyx_v_bus); if (unlikely((__pyx_t_16 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 66, __pyx_L1_error) + __pyx_t_1 = __pyx_convert_string_from_py_std__in_string(__pyx_v_dbc_name); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 66, __pyx_L1_error) + try { + __pyx_t_17 = new CANParser(__pyx_t_16, __pyx_t_1, __pyx_v_message_v); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(0, 66, __pyx_L1_error) + } + __pyx_v_self->can = __pyx_t_17; + + /* "opendbc/can/parser_pyx.pyx":67 + * + * self.can = new cpp_CANParser(bus, dbc_name, message_v) + * self.update_strings([]) # <<<<<<<<<<<<<< + * + * def __dealloc__(self): + */ + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_update_strings); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 67, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = PyList_New(0); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 67, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_11 = NULL; + __pyx_t_16 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_4))) { + __pyx_t_11 = PyMethod_GET_SELF(__pyx_t_4); + if (likely(__pyx_t_11)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_4); + __Pyx_INCREF(__pyx_t_11); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_4, function); + __pyx_t_16 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_11, __pyx_t_5}; + __pyx_t_12 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_16, 1+__pyx_t_16); + __Pyx_XDECREF(__pyx_t_11); __pyx_t_11 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_12)) __PYX_ERR(0, 67, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_12); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + __Pyx_DECREF(__pyx_t_12); __pyx_t_12 = 0; + + /* "opendbc/can/parser_pyx.pyx":30 + * string dbc_name + * + * def __init__(self, dbc_name, messages, bus=0): # <<<<<<<<<<<<<< + * self.dbc_name = dbc_name + * self.dbc = dbc_lookup(dbc_name) + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_11); + __Pyx_XDECREF(__pyx_t_12); + __Pyx_AddTraceback("opendbc.can.parser_pyx.CANParser.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_msg_name_to_address); + __Pyx_XDECREF(__pyx_v_address_to_msg_name); + __Pyx_XDECREF(__pyx_v_name); + __Pyx_XDECREF(__pyx_v_c); + __Pyx_XDECREF(__pyx_v_address); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "opendbc/can/parser_pyx.pyx":69 + * self.update_strings([]) + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * if self.can: + * del self.can + */ + +/* Python wrapper */ +static void __pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_3__dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_3__dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_2__dealloc__(((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_2__dealloc__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self) { + int __pyx_t_1; + + /* "opendbc/can/parser_pyx.pyx":70 + * + * def __dealloc__(self): + * if self.can: # <<<<<<<<<<<<<< + * del self.can + * + */ + __pyx_t_1 = (__pyx_v_self->can != 0); + if (__pyx_t_1) { + + /* "opendbc/can/parser_pyx.pyx":71 + * def __dealloc__(self): + * if self.can: + * del self.can # <<<<<<<<<<<<<< + * + * def update_strings(self, strings, sendcan=False): + */ + delete __pyx_v_self->can; + + /* "opendbc/can/parser_pyx.pyx":70 + * + * def __dealloc__(self): + * if self.can: # <<<<<<<<<<<<<< + * del self.can + * + */ + } + + /* "opendbc/can/parser_pyx.pyx":69 + * self.update_strings([]) + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * if self.can: + * del self.can + */ + + /* function exit code */ +} + +/* "opendbc/can/parser_pyx.pyx":73 + * del self.can + * + * def update_strings(self, strings, sendcan=False): # <<<<<<<<<<<<<< + * for v in self.vl_all.values(): + * for l in v.values(): # no-cython-lint + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_5update_strings(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7opendbc_3can_10parser_pyx_9CANParser_5update_strings = {"update_strings", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_5update_strings, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_5update_strings(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_strings = 0; + PyObject *__pyx_v_sendcan = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[2] = {0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("update_strings (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_strings,&__pyx_n_s_sendcan,0}; + values[1] = __Pyx_Arg_NewRef_FASTCALL(((PyObject *)Py_False)); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_strings)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 73, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_sendcan); + if (value) { values[1] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 73, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "update_strings") < 0)) __PYX_ERR(0, 73, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_strings = values[0]; + __pyx_v_sendcan = values[1]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("update_strings", 0, 1, 2, __pyx_nargs); __PYX_ERR(0, 73, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("opendbc.can.parser_pyx.CANParser.update_strings", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_4update_strings(((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *)__pyx_v_self), __pyx_v_strings, __pyx_v_sendcan); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_4update_strings(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self, PyObject *__pyx_v_strings, PyObject *__pyx_v_sendcan) { + PyObject *__pyx_v_v = NULL; + PyObject *__pyx_v_l = NULL; + std::vector __pyx_v_new_vals; + std::unordered_set __pyx_v_updated_addrs; + std::vector ::iterator __pyx_v_it; + struct SignalValue *__pyx_v_cv; + PyObject *__pyx_v_cv_name = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + Py_ssize_t __pyx_t_2; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + Py_ssize_t __pyx_t_7; + Py_ssize_t __pyx_t_8; + PyObject *__pyx_t_9 = NULL; + int __pyx_t_10; + PyObject *__pyx_t_11 = NULL; + PyObject *__pyx_t_12 = NULL; + std::vector __pyx_t_13; + bool __pyx_t_14; + int __pyx_t_15; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("update_strings", 1); + + /* "opendbc/can/parser_pyx.pyx":74 + * + * def update_strings(self, strings, sendcan=False): + * for v in self.vl_all.values(): # <<<<<<<<<<<<<< + * for l in v.values(): # no-cython-lint + * l.clear() + */ + __pyx_t_2 = 0; + if (unlikely(__pyx_v_self->vl_all == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "values"); + __PYX_ERR(0, 74, __pyx_L1_error) + } + __pyx_t_5 = __Pyx_dict_iterator(__pyx_v_self->vl_all, 1, __pyx_n_s_values, (&__pyx_t_3), (&__pyx_t_4)); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 74, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_1); + __pyx_t_1 = __pyx_t_5; + __pyx_t_5 = 0; + while (1) { + __pyx_t_6 = __Pyx_dict_iter_next(__pyx_t_1, __pyx_t_3, &__pyx_t_2, NULL, &__pyx_t_5, NULL, __pyx_t_4); + if (unlikely(__pyx_t_6 == 0)) break; + if (unlikely(__pyx_t_6 == -1)) __PYX_ERR(0, 74, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_XDECREF_SET(__pyx_v_v, __pyx_t_5); + __pyx_t_5 = 0; + + /* "opendbc/can/parser_pyx.pyx":75 + * def update_strings(self, strings, sendcan=False): + * for v in self.vl_all.values(): + * for l in v.values(): # no-cython-lint # <<<<<<<<<<<<<< + * l.clear() + * + */ + __pyx_t_7 = 0; + if (unlikely(__pyx_v_v == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "values"); + __PYX_ERR(0, 75, __pyx_L1_error) + } + __pyx_t_9 = __Pyx_dict_iterator(__pyx_v_v, 0, __pyx_n_s_values, (&__pyx_t_8), (&__pyx_t_6)); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 75, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_XDECREF(__pyx_t_5); + __pyx_t_5 = __pyx_t_9; + __pyx_t_9 = 0; + while (1) { + __pyx_t_10 = __Pyx_dict_iter_next(__pyx_t_5, __pyx_t_8, &__pyx_t_7, NULL, &__pyx_t_9, NULL, __pyx_t_6); + if (unlikely(__pyx_t_10 == 0)) break; + if (unlikely(__pyx_t_10 == -1)) __PYX_ERR(0, 75, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_XDECREF_SET(__pyx_v_l, __pyx_t_9); + __pyx_t_9 = 0; + + /* "opendbc/can/parser_pyx.pyx":76 + * for v in self.vl_all.values(): + * for l in v.values(): # no-cython-lint + * l.clear() # <<<<<<<<<<<<<< + * + * cdef vector[SignalValue] new_vals + */ + __pyx_t_11 = __Pyx_PyObject_GetAttrStr(__pyx_v_l, __pyx_n_s_clear); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 76, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_11); + __pyx_t_12 = NULL; + __pyx_t_10 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_11))) { + __pyx_t_12 = PyMethod_GET_SELF(__pyx_t_11); + if (likely(__pyx_t_12)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_11); + __Pyx_INCREF(__pyx_t_12); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_11, function); + __pyx_t_10 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_12, NULL}; + __pyx_t_9 = __Pyx_PyObject_FastCall(__pyx_t_11, __pyx_callargs+1-__pyx_t_10, 0+__pyx_t_10); + __Pyx_XDECREF(__pyx_t_12); __pyx_t_12 = 0; + if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 76, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; + } + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + } + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "opendbc/can/parser_pyx.pyx":81 + * cdef unordered_set[uint32_t] updated_addrs + * + * self.can.update_strings(strings, new_vals, sendcan) # <<<<<<<<<<<<<< + * cdef vector[SignalValue].iterator it = new_vals.begin() + * cdef SignalValue* cv + */ + __pyx_t_13 = __pyx_convert_vector_from_py_std_3a__3a_string(__pyx_v_strings); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 81, __pyx_L1_error) + __pyx_t_14 = __Pyx_PyObject_IsTrue(__pyx_v_sendcan); if (unlikely((__pyx_t_14 == ((bool)-1)) && PyErr_Occurred())) __PYX_ERR(0, 81, __pyx_L1_error) + try { + __pyx_v_self->can->update_strings(__pyx_t_13, __pyx_v_new_vals, __pyx_t_14); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(0, 81, __pyx_L1_error) + } + + /* "opendbc/can/parser_pyx.pyx":82 + * + * self.can.update_strings(strings, new_vals, sendcan) + * cdef vector[SignalValue].iterator it = new_vals.begin() # <<<<<<<<<<<<<< + * cdef SignalValue* cv + * while it != new_vals.end(): + */ + __pyx_v_it = __pyx_v_new_vals.begin(); + + /* "opendbc/can/parser_pyx.pyx":84 + * cdef vector[SignalValue].iterator it = new_vals.begin() + * cdef SignalValue* cv + * while it != new_vals.end(): # <<<<<<<<<<<<<< + * cv = &deref(it) + * # Cast char * directly to unicode + */ + while (1) { + __pyx_t_15 = (__pyx_v_it != __pyx_v_new_vals.end()); + if (!__pyx_t_15) break; + + /* "opendbc/can/parser_pyx.pyx":85 + * cdef SignalValue* cv + * while it != new_vals.end(): + * cv = &deref(it) # <<<<<<<<<<<<<< + * # Cast char * directly to unicode + * cv_name = cv.name + */ + __pyx_v_cv = (&(*__pyx_v_it)); + + /* "opendbc/can/parser_pyx.pyx":87 + * cv = &deref(it) + * # Cast char * directly to unicode + * cv_name = cv.name # <<<<<<<<<<<<<< + * self.vl[cv.address][cv_name] = cv.value + * self.vl_all[cv.address][cv_name] = cv.all_values + */ + __pyx_t_1 = __pyx_convert_PyUnicode_string_to_py_std__in_string(__pyx_v_cv->name); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 87, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = __pyx_t_1; + __Pyx_INCREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF_SET(__pyx_v_cv_name, ((PyObject*)__pyx_t_5)); + __pyx_t_5 = 0; + + /* "opendbc/can/parser_pyx.pyx":88 + * # Cast char * directly to unicode + * cv_name = cv.name + * self.vl[cv.address][cv_name] = cv.value # <<<<<<<<<<<<<< + * self.vl_all[cv.address][cv_name] = cv.all_values + * self.ts_nanos[cv.address][cv_name] = cv.ts_nanos + */ + __pyx_t_5 = PyFloat_FromDouble(__pyx_v_cv->value); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 88, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + if (unlikely(__pyx_v_self->vl == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(0, 88, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_PyInt_From_uint32_t(__pyx_v_cv->address); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 88, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_9 = __Pyx_PyDict_GetItem(__pyx_v_self->vl, __pyx_t_1); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 88, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely((PyObject_SetItem(__pyx_t_9, __pyx_v_cv_name, __pyx_t_5) < 0))) __PYX_ERR(0, 88, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "opendbc/can/parser_pyx.pyx":89 + * cv_name = cv.name + * self.vl[cv.address][cv_name] = cv.value + * self.vl_all[cv.address][cv_name] = cv.all_values # <<<<<<<<<<<<<< + * self.ts_nanos[cv.address][cv_name] = cv.ts_nanos + * updated_addrs.insert(cv.address) + */ + __pyx_t_5 = __pyx_convert_vector_to_py_double(__pyx_v_cv->all_values); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 89, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + if (unlikely(__pyx_v_self->vl_all == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(0, 89, __pyx_L1_error) + } + __pyx_t_9 = __Pyx_PyInt_From_uint32_t(__pyx_v_cv->address); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 89, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __pyx_t_1 = __Pyx_PyDict_GetItem(__pyx_v_self->vl_all, __pyx_t_9); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 89, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + if (unlikely((PyObject_SetItem(__pyx_t_1, __pyx_v_cv_name, __pyx_t_5) < 0))) __PYX_ERR(0, 89, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "opendbc/can/parser_pyx.pyx":90 + * self.vl[cv.address][cv_name] = cv.value + * self.vl_all[cv.address][cv_name] = cv.all_values + * self.ts_nanos[cv.address][cv_name] = cv.ts_nanos # <<<<<<<<<<<<<< + * updated_addrs.insert(cv.address) + * preinc(it) + */ + __pyx_t_5 = __Pyx_PyInt_From_uint64_t(__pyx_v_cv->ts_nanos); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 90, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + if (unlikely(__pyx_v_self->ts_nanos == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(0, 90, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_PyInt_From_uint32_t(__pyx_v_cv->address); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 90, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_9 = __Pyx_PyDict_GetItem(__pyx_v_self->ts_nanos, __pyx_t_1); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 90, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely((PyObject_SetItem(__pyx_t_9, __pyx_v_cv_name, __pyx_t_5) < 0))) __PYX_ERR(0, 90, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "opendbc/can/parser_pyx.pyx":91 + * self.vl_all[cv.address][cv_name] = cv.all_values + * self.ts_nanos[cv.address][cv_name] = cv.ts_nanos + * updated_addrs.insert(cv.address) # <<<<<<<<<<<<<< + * preinc(it) + * + */ + try { + __pyx_v_updated_addrs.insert(__pyx_v_cv->address); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(0, 91, __pyx_L1_error) + } + + /* "opendbc/can/parser_pyx.pyx":92 + * self.ts_nanos[cv.address][cv_name] = cv.ts_nanos + * updated_addrs.insert(cv.address) + * preinc(it) # <<<<<<<<<<<<<< + * + * return updated_addrs + */ + (void)((++__pyx_v_it)); + } + + /* "opendbc/can/parser_pyx.pyx":94 + * preinc(it) + * + * return updated_addrs # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_5 = __pyx_convert_unordered_set_to_py_uint32_t(__pyx_v_updated_addrs); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 94, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_r = __pyx_t_5; + __pyx_t_5 = 0; + goto __pyx_L0; + + /* "opendbc/can/parser_pyx.pyx":73 + * del self.can + * + * def update_strings(self, strings, sendcan=False): # <<<<<<<<<<<<<< + * for v in self.vl_all.values(): + * for l in v.values(): # no-cython-lint + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_9); + __Pyx_XDECREF(__pyx_t_11); + __Pyx_XDECREF(__pyx_t_12); + __Pyx_AddTraceback("opendbc.can.parser_pyx.CANParser.update_strings", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_v); + __Pyx_XDECREF(__pyx_v_l); + __Pyx_XDECREF(__pyx_v_cv_name); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "opendbc/can/parser_pyx.pyx":96 + * return updated_addrs + * + * @property # <<<<<<<<<<<<<< + * def can_valid(self): + * return self.can.can_valid + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_9can_valid_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_9can_valid_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_9can_valid___get__(((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_9can_valid___get__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "opendbc/can/parser_pyx.pyx":98 + * @property + * def can_valid(self): + * return self.can.can_valid # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyBool_FromLong(__pyx_v_self->can->can_valid); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 98, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "opendbc/can/parser_pyx.pyx":96 + * return updated_addrs + * + * @property # <<<<<<<<<<<<<< + * def can_valid(self): + * return self.can.can_valid + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("opendbc.can.parser_pyx.CANParser.can_valid.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "opendbc/can/parser_pyx.pyx":100 + * return self.can.can_valid + * + * @property # <<<<<<<<<<<<<< + * def bus_timeout(self): + * return self.can.bus_timeout + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_11bus_timeout_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_11bus_timeout_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_11bus_timeout___get__(((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_11bus_timeout___get__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "opendbc/can/parser_pyx.pyx":102 + * @property + * def bus_timeout(self): + * return self.can.bus_timeout # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyBool_FromLong(__pyx_v_self->can->bus_timeout); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 102, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "opendbc/can/parser_pyx.pyx":100 + * return self.can.can_valid + * + * @property # <<<<<<<<<<<<<< + * def bus_timeout(self): + * return self.can.bus_timeout + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("opendbc.can.parser_pyx.CANParser.bus_timeout.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "opendbc/can/parser_pyx.pyx":25 + * + * cdef readonly: + * dict vl # <<<<<<<<<<<<<< + * dict vl_all + * dict ts_nanos + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_2vl_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_2vl_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_2vl___get__(((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_2vl___get__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__", 1); + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->vl); + __pyx_r = __pyx_v_self->vl; + goto __pyx_L0; + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "opendbc/can/parser_pyx.pyx":26 + * cdef readonly: + * dict vl + * dict vl_all # <<<<<<<<<<<<<< + * dict ts_nanos + * string dbc_name + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_6vl_all_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_6vl_all_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_6vl_all___get__(((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_6vl_all___get__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__", 1); + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->vl_all); + __pyx_r = __pyx_v_self->vl_all; + goto __pyx_L0; + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "opendbc/can/parser_pyx.pyx":27 + * dict vl + * dict vl_all + * dict ts_nanos # <<<<<<<<<<<<<< + * string dbc_name + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_8ts_nanos_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_8ts_nanos_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_8ts_nanos___get__(((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_8ts_nanos___get__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__", 1); + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->ts_nanos); + __pyx_r = __pyx_v_self->ts_nanos; + goto __pyx_L0; + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "opendbc/can/parser_pyx.pyx":28 + * dict vl_all + * dict ts_nanos + * string dbc_name # <<<<<<<<<<<<<< + * + * def __init__(self, dbc_name, messages, bus=0): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_8dbc_name_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_8dbc_name_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_8dbc_name___get__(((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_8dbc_name___get__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __pyx_convert_PyBytes_string_to_py_std__in_string(__pyx_v_self->dbc_name); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 28, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("opendbc.can.parser_pyx.CANParser.dbc_name.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.can,self.dbc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_7__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7opendbc_3can_10parser_pyx_9CANParser_7__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_7__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_7__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_6__reduce_cython__(((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_6__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "self.can,self.dbc cannot be converted to a Python object for pickling" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "self.can,self.dbc cannot be converted to a Python object for pickling" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_self_can_self_dbc_cannot_be_conv, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.can,self.dbc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("opendbc.can.parser_pyx.CANParser.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.can,self.dbc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.can,self.dbc cannot be converted to a Python object for pickling" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_9__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7opendbc_3can_10parser_pyx_9CANParser_9__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_9__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_9__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("opendbc.can.parser_pyx.CANParser.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_8__setstate_cython__(((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANParser_8__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "self.can,self.dbc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "self.can,self.dbc cannot be converted to a Python object for pickling" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_self_can_self_dbc_cannot_be_conv, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.can,self.dbc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.can,self.dbc cannot be converted to a Python object for pickling" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("opendbc.can.parser_pyx.CANParser.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "opendbc/can/parser_pyx.pyx":113 + * string dbc_name + * + * def __init__(self, dbc_name): # <<<<<<<<<<<<<< + * self.dbc_name = dbc_name + * self.dbc = dbc_lookup(dbc_name) + */ + +/* Python wrapper */ +static int __pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_1__init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_1__init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_dbc_name = 0; + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__init__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_dbc_name,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_dbc_name)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 113, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__init__") < 0)) __PYX_ERR(0, 113, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + } + __pyx_v_dbc_name = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__init__", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 113, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("opendbc.can.parser_pyx.CANDefine.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine___init__(((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *)__pyx_v_self), __pyx_v_dbc_name); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine___init__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *__pyx_v_self, PyObject *__pyx_v_dbc_name) { + PyObject *__pyx_v_address_to_msg_name = NULL; + std::vector ::size_type __pyx_v_i; + struct Msg __pyx_v_msg; + PyObject *__pyx_v_name = NULL; + uint32_t __pyx_v_address; + PyObject *__pyx_v_dv = NULL; + struct Val __pyx_v_val; + PyObject *__pyx_v_sgname = NULL; + PyObject *__pyx_v_def_val = NULL; + PyObject *__pyx_v_msgname = NULL; + PyObject *__pyx_v_values = NULL; + PyObject *__pyx_v_defs = NULL; + PyObject *__pyx_7genexpr__pyx_v_v = NULL; + int __pyx_r; + __Pyx_RefNannyDeclarations + std::string __pyx_t_1; + struct DBC const *__pyx_t_2; + int __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + Py_ssize_t __pyx_t_5; + Py_UCS4 __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + std::vector ::size_type __pyx_t_8; + std::vector ::size_type __pyx_t_9; + std::vector ::size_type __pyx_t_10; + uint32_t __pyx_t_11; + PyObject *__pyx_t_12 = NULL; + int __pyx_t_13; + std::vector ::size_type __pyx_t_14; + std::vector ::size_type __pyx_t_15; + PyObject *(*__pyx_t_16)(PyObject *); + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__init__", 1); + + /* "opendbc/can/parser_pyx.pyx":114 + * + * def __init__(self, dbc_name): + * self.dbc_name = dbc_name # <<<<<<<<<<<<<< + * self.dbc = dbc_lookup(dbc_name) + * if not self.dbc: + */ + __pyx_t_1 = __pyx_convert_string_from_py_std__in_string(__pyx_v_dbc_name); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 114, __pyx_L1_error) + __pyx_v_self->dbc_name = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_1); + + /* "opendbc/can/parser_pyx.pyx":115 + * def __init__(self, dbc_name): + * self.dbc_name = dbc_name + * self.dbc = dbc_lookup(dbc_name) # <<<<<<<<<<<<<< + * if not self.dbc: + * raise RuntimeError(f"Can't find DBC: '{dbc_name}'") + */ + __pyx_t_1 = __pyx_convert_string_from_py_std__in_string(__pyx_v_dbc_name); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 115, __pyx_L1_error) + try { + __pyx_t_2 = dbc_lookup(__PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_1)); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(0, 115, __pyx_L1_error) + } + __pyx_v_self->dbc = __pyx_t_2; + + /* "opendbc/can/parser_pyx.pyx":116 + * self.dbc_name = dbc_name + * self.dbc = dbc_lookup(dbc_name) + * if not self.dbc: # <<<<<<<<<<<<<< + * raise RuntimeError(f"Can't find DBC: '{dbc_name}'") + * + */ + __pyx_t_3 = (!(__pyx_v_self->dbc != 0)); + if (unlikely(__pyx_t_3)) { + + /* "opendbc/can/parser_pyx.pyx":117 + * self.dbc = dbc_lookup(dbc_name) + * if not self.dbc: + * raise RuntimeError(f"Can't find DBC: '{dbc_name}'") # <<<<<<<<<<<<<< + * + * address_to_msg_name = {} + */ + __pyx_t_4 = PyTuple_New(3); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 117, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = 0; + __pyx_t_6 = 127; + __Pyx_INCREF(__pyx_kp_u_Can_t_find_DBC_2); + __pyx_t_5 += 17; + __Pyx_GIVEREF(__pyx_kp_u_Can_t_find_DBC_2); + PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_kp_u_Can_t_find_DBC_2); + __pyx_t_7 = __Pyx_PyObject_FormatSimple(__pyx_v_dbc_name, __pyx_empty_unicode); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 117, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_7) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_7) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_t_7); + __pyx_t_7 = 0; + __Pyx_INCREF(__pyx_kp_u_); + __pyx_t_5 += 1; + __Pyx_GIVEREF(__pyx_kp_u_); + PyTuple_SET_ITEM(__pyx_t_4, 2, __pyx_kp_u_); + __pyx_t_7 = __Pyx_PyUnicode_Join(__pyx_t_4, 3, __pyx_t_5, __pyx_t_6); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 117, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyObject_CallOneArg(__pyx_builtin_RuntimeError, __pyx_t_7); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 117, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_Raise(__pyx_t_4, 0, 0, 0); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __PYX_ERR(0, 117, __pyx_L1_error) + + /* "opendbc/can/parser_pyx.pyx":116 + * self.dbc_name = dbc_name + * self.dbc = dbc_lookup(dbc_name) + * if not self.dbc: # <<<<<<<<<<<<<< + * raise RuntimeError(f"Can't find DBC: '{dbc_name}'") + * + */ + } + + /* "opendbc/can/parser_pyx.pyx":119 + * raise RuntimeError(f"Can't find DBC: '{dbc_name}'") + * + * address_to_msg_name = {} # <<<<<<<<<<<<<< + * + * for i in range(self.dbc[0].msgs.size()): + */ + __pyx_t_4 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 119, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_v_address_to_msg_name = ((PyObject*)__pyx_t_4); + __pyx_t_4 = 0; + + /* "opendbc/can/parser_pyx.pyx":121 + * address_to_msg_name = {} + * + * for i in range(self.dbc[0].msgs.size()): # <<<<<<<<<<<<<< + * msg = self.dbc[0].msgs[i] + * name = msg.name.decode("utf8") + */ + __pyx_t_8 = (__pyx_v_self->dbc[0]).msgs.size(); + __pyx_t_9 = __pyx_t_8; + for (__pyx_t_10 = 0; __pyx_t_10 < __pyx_t_9; __pyx_t_10+=1) { + __pyx_v_i = __pyx_t_10; + + /* "opendbc/can/parser_pyx.pyx":122 + * + * for i in range(self.dbc[0].msgs.size()): + * msg = self.dbc[0].msgs[i] # <<<<<<<<<<<<<< + * name = msg.name.decode("utf8") + * address = msg.address + */ + __pyx_v_msg = ((__pyx_v_self->dbc[0]).msgs[__pyx_v_i]); + + /* "opendbc/can/parser_pyx.pyx":123 + * for i in range(self.dbc[0].msgs.size()): + * msg = self.dbc[0].msgs[i] + * name = msg.name.decode("utf8") # <<<<<<<<<<<<<< + * address = msg.address + * address_to_msg_name[address] = name + */ + __pyx_t_4 = __Pyx_decode_cpp_string(__pyx_v_msg.name, 0, PY_SSIZE_T_MAX, NULL, NULL, PyUnicode_DecodeUTF8); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 123, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_XDECREF_SET(__pyx_v_name, __pyx_t_4); + __pyx_t_4 = 0; + + /* "opendbc/can/parser_pyx.pyx":124 + * msg = self.dbc[0].msgs[i] + * name = msg.name.decode("utf8") + * address = msg.address # <<<<<<<<<<<<<< + * address_to_msg_name[address] = name + * + */ + __pyx_t_11 = __pyx_v_msg.address; + __pyx_v_address = __pyx_t_11; + + /* "opendbc/can/parser_pyx.pyx":125 + * name = msg.name.decode("utf8") + * address = msg.address + * address_to_msg_name[address] = name # <<<<<<<<<<<<<< + * + * dv = defaultdict(dict) + */ + __pyx_t_4 = __Pyx_PyInt_From_uint32_t(__pyx_v_address); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 125, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (unlikely((PyDict_SetItem(__pyx_v_address_to_msg_name, __pyx_t_4, __pyx_v_name) < 0))) __PYX_ERR(0, 125, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + + /* "opendbc/can/parser_pyx.pyx":127 + * address_to_msg_name[address] = name + * + * dv = defaultdict(dict) # <<<<<<<<<<<<<< + * + * for i in range(self.dbc[0].vals.size()): + */ + __Pyx_GetModuleGlobalName(__pyx_t_7, __pyx_n_s_defaultdict); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 127, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_12 = NULL; + __pyx_t_13 = 0; + #if CYTHON_UNPACK_METHODS + if (unlikely(PyMethod_Check(__pyx_t_7))) { + __pyx_t_12 = PyMethod_GET_SELF(__pyx_t_7); + if (likely(__pyx_t_12)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_7); + __Pyx_INCREF(__pyx_t_12); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_7, function); + __pyx_t_13 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_12, ((PyObject *)(&PyDict_Type))}; + __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_7, __pyx_callargs+1-__pyx_t_13, 1+__pyx_t_13); + __Pyx_XDECREF(__pyx_t_12); __pyx_t_12 = 0; + if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 127, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + } + __pyx_v_dv = __pyx_t_4; + __pyx_t_4 = 0; + + /* "opendbc/can/parser_pyx.pyx":129 + * dv = defaultdict(dict) + * + * for i in range(self.dbc[0].vals.size()): # <<<<<<<<<<<<<< + * val = self.dbc[0].vals[i] + * + */ + __pyx_t_10 = (__pyx_v_self->dbc[0]).vals.size(); + __pyx_t_14 = __pyx_t_10; + for (__pyx_t_15 = 0; __pyx_t_15 < __pyx_t_14; __pyx_t_15+=1) { + __pyx_v_i = __pyx_t_15; + + /* "opendbc/can/parser_pyx.pyx":130 + * + * for i in range(self.dbc[0].vals.size()): + * val = self.dbc[0].vals[i] # <<<<<<<<<<<<<< + * + * sgname = val.name.decode("utf8") + */ + __pyx_v_val = ((__pyx_v_self->dbc[0]).vals[__pyx_v_i]); + + /* "opendbc/can/parser_pyx.pyx":132 + * val = self.dbc[0].vals[i] + * + * sgname = val.name.decode("utf8") # <<<<<<<<<<<<<< + * def_val = val.def_val.decode("utf8") + * address = val.address + */ + __pyx_t_4 = __Pyx_decode_cpp_string(__pyx_v_val.name, 0, PY_SSIZE_T_MAX, NULL, NULL, PyUnicode_DecodeUTF8); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 132, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_XDECREF_SET(__pyx_v_sgname, __pyx_t_4); + __pyx_t_4 = 0; + + /* "opendbc/can/parser_pyx.pyx":133 + * + * sgname = val.name.decode("utf8") + * def_val = val.def_val.decode("utf8") # <<<<<<<<<<<<<< + * address = val.address + * msgname = address_to_msg_name[address] + */ + __pyx_t_4 = __Pyx_decode_cpp_string(__pyx_v_val.def_val, 0, PY_SSIZE_T_MAX, NULL, NULL, PyUnicode_DecodeUTF8); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 133, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_XDECREF_SET(__pyx_v_def_val, __pyx_t_4); + __pyx_t_4 = 0; + + /* "opendbc/can/parser_pyx.pyx":134 + * sgname = val.name.decode("utf8") + * def_val = val.def_val.decode("utf8") + * address = val.address # <<<<<<<<<<<<<< + * msgname = address_to_msg_name[address] + * + */ + __pyx_t_11 = __pyx_v_val.address; + __pyx_v_address = __pyx_t_11; + + /* "opendbc/can/parser_pyx.pyx":135 + * def_val = val.def_val.decode("utf8") + * address = val.address + * msgname = address_to_msg_name[address] # <<<<<<<<<<<<<< + * + * # separate definition/value pairs + */ + __pyx_t_4 = __Pyx_PyInt_From_uint32_t(__pyx_v_address); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 135, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_7 = __Pyx_PyDict_GetItem(__pyx_v_address_to_msg_name, __pyx_t_4); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 135, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF_SET(__pyx_v_msgname, __pyx_t_7); + __pyx_t_7 = 0; + + /* "opendbc/can/parser_pyx.pyx":138 + * + * # separate definition/value pairs + * def_val = def_val.split() # <<<<<<<<<<<<<< + * values = [int(v) for v in def_val[::2]] + * defs = def_val[1::2] + */ + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_v_def_val, __pyx_n_s_split); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 138, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_12 = NULL; + __pyx_t_13 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_4))) { + __pyx_t_12 = PyMethod_GET_SELF(__pyx_t_4); + if (likely(__pyx_t_12)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_4); + __Pyx_INCREF(__pyx_t_12); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_4, function); + __pyx_t_13 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_12, NULL}; + __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_13, 0+__pyx_t_13); + __Pyx_XDECREF(__pyx_t_12); __pyx_t_12 = 0; + if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 138, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + __Pyx_DECREF_SET(__pyx_v_def_val, __pyx_t_7); + __pyx_t_7 = 0; + + /* "opendbc/can/parser_pyx.pyx":139 + * # separate definition/value pairs + * def_val = def_val.split() + * values = [int(v) for v in def_val[::2]] # <<<<<<<<<<<<<< + * defs = def_val[1::2] + * + */ + { /* enter inner scope */ + __pyx_t_7 = PyList_New(0); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 139, __pyx_L10_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_4 = __Pyx_PyObject_GetItem(__pyx_v_def_val, __pyx_slice__2); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 139, __pyx_L10_error) + __Pyx_GOTREF(__pyx_t_4); + if (likely(PyList_CheckExact(__pyx_t_4)) || PyTuple_CheckExact(__pyx_t_4)) { + __pyx_t_12 = __pyx_t_4; __Pyx_INCREF(__pyx_t_12); + __pyx_t_5 = 0; + __pyx_t_16 = NULL; + } else { + __pyx_t_5 = -1; __pyx_t_12 = PyObject_GetIter(__pyx_t_4); if (unlikely(!__pyx_t_12)) __PYX_ERR(0, 139, __pyx_L10_error) + __Pyx_GOTREF(__pyx_t_12); + __pyx_t_16 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_12); if (unlikely(!__pyx_t_16)) __PYX_ERR(0, 139, __pyx_L10_error) + } + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + for (;;) { + if (likely(!__pyx_t_16)) { + if (likely(PyList_CheckExact(__pyx_t_12))) { + { + Py_ssize_t __pyx_temp = __Pyx_PyList_GET_SIZE(__pyx_t_12); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 139, __pyx_L10_error) + #endif + if (__pyx_t_5 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyList_GET_ITEM(__pyx_t_12, __pyx_t_5); __Pyx_INCREF(__pyx_t_4); __pyx_t_5++; if (unlikely((0 < 0))) __PYX_ERR(0, 139, __pyx_L10_error) + #else + __pyx_t_4 = __Pyx_PySequence_ITEM(__pyx_t_12, __pyx_t_5); __pyx_t_5++; if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 139, __pyx_L10_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } else { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_12); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 139, __pyx_L10_error) + #endif + if (__pyx_t_5 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyTuple_GET_ITEM(__pyx_t_12, __pyx_t_5); __Pyx_INCREF(__pyx_t_4); __pyx_t_5++; if (unlikely((0 < 0))) __PYX_ERR(0, 139, __pyx_L10_error) + #else + __pyx_t_4 = __Pyx_PySequence_ITEM(__pyx_t_12, __pyx_t_5); __pyx_t_5++; if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 139, __pyx_L10_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } + } else { + __pyx_t_4 = __pyx_t_16(__pyx_t_12); + if (unlikely(!__pyx_t_4)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(0, 139, __pyx_L10_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_4); + } + __Pyx_XDECREF_SET(__pyx_7genexpr__pyx_v_v, __pyx_t_4); + __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyNumber_Int(__pyx_7genexpr__pyx_v_v); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 139, __pyx_L10_error) + __Pyx_GOTREF(__pyx_t_4); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_7, (PyObject*)__pyx_t_4))) __PYX_ERR(0, 139, __pyx_L10_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + __Pyx_DECREF(__pyx_t_12); __pyx_t_12 = 0; + __Pyx_XDECREF(__pyx_7genexpr__pyx_v_v); __pyx_7genexpr__pyx_v_v = 0; + goto __pyx_L14_exit_scope; + __pyx_L10_error:; + __Pyx_XDECREF(__pyx_7genexpr__pyx_v_v); __pyx_7genexpr__pyx_v_v = 0; + goto __pyx_L1_error; + __pyx_L14_exit_scope:; + } /* exit inner scope */ + __Pyx_XDECREF_SET(__pyx_v_values, ((PyObject*)__pyx_t_7)); + __pyx_t_7 = 0; + + /* "opendbc/can/parser_pyx.pyx":140 + * def_val = def_val.split() + * values = [int(v) for v in def_val[::2]] + * defs = def_val[1::2] # <<<<<<<<<<<<<< + * + * # two ways to lookup: address or msg name + */ + __pyx_t_7 = __Pyx_PyObject_GetItem(__pyx_v_def_val, __pyx_slice__3); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 140, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XDECREF_SET(__pyx_v_defs, __pyx_t_7); + __pyx_t_7 = 0; + + /* "opendbc/can/parser_pyx.pyx":143 + * + * # two ways to lookup: address or msg name + * dv[address][sgname] = dict(zip(values, defs)) # <<<<<<<<<<<<<< + * dv[msgname][sgname] = dv[address][sgname] + * + */ + __pyx_t_7 = PyTuple_New(2); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_INCREF(__pyx_v_values); + __Pyx_GIVEREF(__pyx_v_values); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_7, 0, __pyx_v_values)) __PYX_ERR(0, 143, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_defs); + __Pyx_GIVEREF(__pyx_v_defs); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_7, 1, __pyx_v_defs)) __PYX_ERR(0, 143, __pyx_L1_error); + __pyx_t_12 = __Pyx_PyObject_Call(__pyx_builtin_zip, __pyx_t_7, NULL); if (unlikely(!__pyx_t_12)) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_12); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __pyx_t_7 = __Pyx_PyObject_CallOneArg(((PyObject *)(&PyDict_Type)), __pyx_t_12); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_12); __pyx_t_12 = 0; + __pyx_t_12 = __Pyx_GetItemInt(__pyx_v_dv, __pyx_v_address, uint32_t, 0, __Pyx_PyInt_From_uint32_t, 0, 0, 1); if (unlikely(!__pyx_t_12)) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_12); + if (unlikely((PyObject_SetItem(__pyx_t_12, __pyx_v_sgname, __pyx_t_7) < 0))) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_12); __pyx_t_12 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "opendbc/can/parser_pyx.pyx":144 + * # two ways to lookup: address or msg name + * dv[address][sgname] = dict(zip(values, defs)) + * dv[msgname][sgname] = dv[address][sgname] # <<<<<<<<<<<<<< + * + * self.dv = dict(dv) + */ + __pyx_t_7 = __Pyx_GetItemInt(__pyx_v_dv, __pyx_v_address, uint32_t, 0, __Pyx_PyInt_From_uint32_t, 0, 0, 1); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 144, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_12 = __Pyx_PyObject_GetItem(__pyx_t_7, __pyx_v_sgname); if (unlikely(!__pyx_t_12)) __PYX_ERR(0, 144, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_12); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __pyx_t_7 = __Pyx_PyObject_GetItem(__pyx_v_dv, __pyx_v_msgname); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 144, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (unlikely((PyObject_SetItem(__pyx_t_7, __pyx_v_sgname, __pyx_t_12) < 0))) __PYX_ERR(0, 144, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_12); __pyx_t_12 = 0; + } + + /* "opendbc/can/parser_pyx.pyx":146 + * dv[msgname][sgname] = dv[address][sgname] + * + * self.dv = dict(dv) # <<<<<<<<<<<<<< + */ + __pyx_t_12 = __Pyx_PyObject_CallOneArg(((PyObject *)(&PyDict_Type)), __pyx_v_dv); if (unlikely(!__pyx_t_12)) __PYX_ERR(0, 146, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_12); + __Pyx_GIVEREF(__pyx_t_12); + __Pyx_GOTREF(__pyx_v_self->dv); + __Pyx_DECREF(__pyx_v_self->dv); + __pyx_v_self->dv = ((PyObject*)__pyx_t_12); + __pyx_t_12 = 0; + + /* "opendbc/can/parser_pyx.pyx":113 + * string dbc_name + * + * def __init__(self, dbc_name): # <<<<<<<<<<<<<< + * self.dbc_name = dbc_name + * self.dbc = dbc_lookup(dbc_name) + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_12); + __Pyx_AddTraceback("opendbc.can.parser_pyx.CANDefine.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_address_to_msg_name); + __Pyx_XDECREF(__pyx_v_name); + __Pyx_XDECREF(__pyx_v_dv); + __Pyx_XDECREF(__pyx_v_sgname); + __Pyx_XDECREF(__pyx_v_def_val); + __Pyx_XDECREF(__pyx_v_msgname); + __Pyx_XDECREF(__pyx_v_values); + __Pyx_XDECREF(__pyx_v_defs); + __Pyx_XDECREF(__pyx_7genexpr__pyx_v_v); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "opendbc/can/parser_pyx.pyx":110 + * + * cdef public: + * dict dv # <<<<<<<<<<<<<< + * string dbc_name + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_2dv_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_2dv_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_2dv___get__(((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_2dv___get__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__", 1); + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->dv); + __pyx_r = __pyx_v_self->dv; + goto __pyx_L0; + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* Python wrapper */ +static int __pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_2dv_3__set__(PyObject *__pyx_v_self, PyObject *__pyx_v_value); /*proto*/ +static int __pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_2dv_3__set__(PyObject *__pyx_v_self, PyObject *__pyx_v_value) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__set__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_2dv_2__set__(((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *)__pyx_v_self), ((PyObject *)__pyx_v_value)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_2dv_2__set__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *__pyx_v_self, PyObject *__pyx_v_value) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__set__", 1); + if (!(likely(PyDict_CheckExact(__pyx_v_value))||((__pyx_v_value) == Py_None) || __Pyx_RaiseUnexpectedTypeError("dict", __pyx_v_value))) __PYX_ERR(0, 110, __pyx_L1_error) + __pyx_t_1 = __pyx_v_value; + __Pyx_INCREF(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + __Pyx_GOTREF(__pyx_v_self->dv); + __Pyx_DECREF(__pyx_v_self->dv); + __pyx_v_self->dv = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("opendbc.can.parser_pyx.CANDefine.dv.__set__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* Python wrapper */ +static int __pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_2dv_5__del__(PyObject *__pyx_v_self); /*proto*/ +static int __pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_2dv_5__del__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__del__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_2dv_4__del__(((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_2dv_4__del__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *__pyx_v_self) { + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__del__", 1); + __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(Py_None); + __Pyx_GOTREF(__pyx_v_self->dv); + __Pyx_DECREF(__pyx_v_self->dv); + __pyx_v_self->dv = ((PyObject*)Py_None); + + /* function exit code */ + __pyx_r = 0; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "opendbc/can/parser_pyx.pyx":111 + * cdef public: + * dict dv + * string dbc_name # <<<<<<<<<<<<<< + * + * def __init__(self, dbc_name): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_8dbc_name_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_8dbc_name_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_8dbc_name___get__(((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_8dbc_name___get__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __pyx_convert_PyBytes_string_to_py_std__in_string(__pyx_v_self->dbc_name); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 111, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("opendbc.can.parser_pyx.CANDefine.dbc_name.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* Python wrapper */ +static int __pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_8dbc_name_3__set__(PyObject *__pyx_v_self, PyObject *__pyx_v_value); /*proto*/ +static int __pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_8dbc_name_3__set__(PyObject *__pyx_v_self, PyObject *__pyx_v_value) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__set__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_8dbc_name_2__set__(((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *)__pyx_v_self), ((PyObject *)__pyx_v_value)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_8dbc_name_2__set__(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *__pyx_v_self, PyObject *__pyx_v_value) { + int __pyx_r; + std::string __pyx_t_1; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __pyx_t_1 = __pyx_convert_string_from_py_std__in_string(__pyx_v_value); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 111, __pyx_L1_error) + __pyx_v_self->dbc_name = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_1); + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("opendbc.can.parser_pyx.CANDefine.dbc_name.__set__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.dbc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_3__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7opendbc_3can_10parser_pyx_9CANDefine_3__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_3__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_3__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_2__reduce_cython__(((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_2__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "self.dbc cannot be converted to a Python object for pickling" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "self.dbc cannot be converted to a Python object for pickling" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_self_dbc_cannot_be_converted_to, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.dbc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("opendbc.can.parser_pyx.CANDefine.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.dbc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.dbc cannot be converted to a Python object for pickling" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_5__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7opendbc_3can_10parser_pyx_9CANDefine_5__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_5__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_5__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("opendbc.can.parser_pyx.CANDefine.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_4__setstate_cython__(((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7opendbc_3can_10parser_pyx_9CANDefine_4__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "self.dbc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "self.dbc cannot be converted to a Python object for pickling" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_self_dbc_cannot_be_converted_to, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.dbc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.dbc cannot be converted to a Python object for pickling" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("opendbc.can.parser_pyx.CANDefine.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_tp_new_7opendbc_3can_10parser_pyx_CANParser(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { + struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *)o); + new((void*)&(p->can_values)) std::vector (); + new((void*)&(p->dbc_name)) std::string(); + p->vl = ((PyObject*)Py_None); Py_INCREF(Py_None); + p->vl_all = ((PyObject*)Py_None); Py_INCREF(Py_None); + p->ts_nanos = ((PyObject*)Py_None); Py_INCREF(Py_None); + return o; +} + +static void __pyx_tp_dealloc_7opendbc_3can_10parser_pyx_CANParser(PyObject *o) { + struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *p = (struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_7opendbc_3can_10parser_pyx_CANParser) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_3__dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + __Pyx_call_destructor(p->can_values); + __Pyx_call_destructor(p->dbc_name); + Py_CLEAR(p->vl); + Py_CLEAR(p->vl_all); + Py_CLEAR(p->ts_nanos); + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} + +static int __pyx_tp_traverse_7opendbc_3can_10parser_pyx_CANParser(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *p = (struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *)o; + if (p->vl) { + e = (*v)(p->vl, a); if (e) return e; + } + if (p->vl_all) { + e = (*v)(p->vl_all, a); if (e) return e; + } + if (p->ts_nanos) { + e = (*v)(p->ts_nanos, a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear_7opendbc_3can_10parser_pyx_CANParser(PyObject *o) { + PyObject* tmp; + struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *p = (struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser *)o; + tmp = ((PyObject*)p->vl); + p->vl = ((PyObject*)Py_None); Py_INCREF(Py_None); + Py_XDECREF(tmp); + tmp = ((PyObject*)p->vl_all); + p->vl_all = ((PyObject*)Py_None); Py_INCREF(Py_None); + Py_XDECREF(tmp); + tmp = ((PyObject*)p->ts_nanos); + p->ts_nanos = ((PyObject*)Py_None); Py_INCREF(Py_None); + Py_XDECREF(tmp); + return 0; +} + +static PyObject *__pyx_getprop_7opendbc_3can_10parser_pyx_9CANParser_can_valid(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_9can_valid_1__get__(o); +} + +static PyObject *__pyx_getprop_7opendbc_3can_10parser_pyx_9CANParser_bus_timeout(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_11bus_timeout_1__get__(o); +} + +static PyObject *__pyx_getprop_7opendbc_3can_10parser_pyx_9CANParser_vl(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_2vl_1__get__(o); +} + +static PyObject *__pyx_getprop_7opendbc_3can_10parser_pyx_9CANParser_vl_all(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_6vl_all_1__get__(o); +} + +static PyObject *__pyx_getprop_7opendbc_3can_10parser_pyx_9CANParser_ts_nanos(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_8ts_nanos_1__get__(o); +} + +static PyObject *__pyx_getprop_7opendbc_3can_10parser_pyx_9CANParser_dbc_name(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_8dbc_name_1__get__(o); +} + +static PyMethodDef __pyx_methods_7opendbc_3can_10parser_pyx_CANParser[] = { + {"update_strings", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_5update_strings, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_7__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_9__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; + +static struct PyGetSetDef __pyx_getsets_7opendbc_3can_10parser_pyx_CANParser[] = { + {(char *)"can_valid", __pyx_getprop_7opendbc_3can_10parser_pyx_9CANParser_can_valid, 0, (char *)0, 0}, + {(char *)"bus_timeout", __pyx_getprop_7opendbc_3can_10parser_pyx_9CANParser_bus_timeout, 0, (char *)0, 0}, + {(char *)"vl", __pyx_getprop_7opendbc_3can_10parser_pyx_9CANParser_vl, 0, (char *)0, 0}, + {(char *)"vl_all", __pyx_getprop_7opendbc_3can_10parser_pyx_9CANParser_vl_all, 0, (char *)0, 0}, + {(char *)"ts_nanos", __pyx_getprop_7opendbc_3can_10parser_pyx_9CANParser_ts_nanos, 0, (char *)0, 0}, + {(char *)"dbc_name", __pyx_getprop_7opendbc_3can_10parser_pyx_9CANParser_dbc_name, 0, (char *)0, 0}, + {0, 0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_7opendbc_3can_10parser_pyx_CANParser_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_7opendbc_3can_10parser_pyx_CANParser}, + {Py_tp_traverse, (void *)__pyx_tp_traverse_7opendbc_3can_10parser_pyx_CANParser}, + {Py_tp_clear, (void *)__pyx_tp_clear_7opendbc_3can_10parser_pyx_CANParser}, + {Py_tp_methods, (void *)__pyx_methods_7opendbc_3can_10parser_pyx_CANParser}, + {Py_tp_getset, (void *)__pyx_getsets_7opendbc_3can_10parser_pyx_CANParser}, + {Py_tp_init, (void *)__pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_1__init__}, + {Py_tp_new, (void *)__pyx_tp_new_7opendbc_3can_10parser_pyx_CANParser}, + {0, 0}, +}; +static PyType_Spec __pyx_type_7opendbc_3can_10parser_pyx_CANParser_spec = { + "opendbc.can.parser_pyx.CANParser", + sizeof(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, + __pyx_type_7opendbc_3can_10parser_pyx_CANParser_slots, +}; +#else + +static PyTypeObject __pyx_type_7opendbc_3can_10parser_pyx_CANParser = { + PyVarObject_HEAD_INIT(0, 0) + "opendbc.can.parser_pyx.""CANParser", /*tp_name*/ + sizeof(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANParser), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_7opendbc_3can_10parser_pyx_CANParser, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, /*tp_flags*/ + 0, /*tp_doc*/ + __pyx_tp_traverse_7opendbc_3can_10parser_pyx_CANParser, /*tp_traverse*/ + __pyx_tp_clear_7opendbc_3can_10parser_pyx_CANParser, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_7opendbc_3can_10parser_pyx_CANParser, /*tp_methods*/ + 0, /*tp_members*/ + __pyx_getsets_7opendbc_3can_10parser_pyx_CANParser, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + __pyx_pw_7opendbc_3can_10parser_pyx_9CANParser_1__init__, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_7opendbc_3can_10parser_pyx_CANParser, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyObject *__pyx_tp_new_7opendbc_3can_10parser_pyx_CANDefine(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { + struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *)o); + new((void*)&(p->dbc_name)) std::string(); + p->dv = ((PyObject*)Py_None); Py_INCREF(Py_None); + return o; +} + +static void __pyx_tp_dealloc_7opendbc_3can_10parser_pyx_CANDefine(PyObject *o) { + struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *p = (struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_7opendbc_3can_10parser_pyx_CANDefine) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + __Pyx_call_destructor(p->dbc_name); + Py_CLEAR(p->dv); + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} + +static int __pyx_tp_traverse_7opendbc_3can_10parser_pyx_CANDefine(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *p = (struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *)o; + if (p->dv) { + e = (*v)(p->dv, a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear_7opendbc_3can_10parser_pyx_CANDefine(PyObject *o) { + PyObject* tmp; + struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *p = (struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine *)o; + tmp = ((PyObject*)p->dv); + p->dv = ((PyObject*)Py_None); Py_INCREF(Py_None); + Py_XDECREF(tmp); + return 0; +} + +static PyObject *__pyx_getprop_7opendbc_3can_10parser_pyx_9CANDefine_dv(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_2dv_1__get__(o); +} + +static int __pyx_setprop_7opendbc_3can_10parser_pyx_9CANDefine_dv(PyObject *o, PyObject *v, CYTHON_UNUSED void *x) { + if (v) { + return __pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_2dv_3__set__(o, v); + } + else { + return __pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_2dv_5__del__(o); + } +} + +static PyObject *__pyx_getprop_7opendbc_3can_10parser_pyx_9CANDefine_dbc_name(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_8dbc_name_1__get__(o); +} + +static int __pyx_setprop_7opendbc_3can_10parser_pyx_9CANDefine_dbc_name(PyObject *o, PyObject *v, CYTHON_UNUSED void *x) { + if (v) { + return __pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_8dbc_name_3__set__(o, v); + } + else { + PyErr_SetString(PyExc_NotImplementedError, "__del__"); + return -1; + } +} + +static PyMethodDef __pyx_methods_7opendbc_3can_10parser_pyx_CANDefine[] = { + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_3__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_5__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; + +static struct PyGetSetDef __pyx_getsets_7opendbc_3can_10parser_pyx_CANDefine[] = { + {(char *)"dv", __pyx_getprop_7opendbc_3can_10parser_pyx_9CANDefine_dv, __pyx_setprop_7opendbc_3can_10parser_pyx_9CANDefine_dv, (char *)0, 0}, + {(char *)"dbc_name", __pyx_getprop_7opendbc_3can_10parser_pyx_9CANDefine_dbc_name, __pyx_setprop_7opendbc_3can_10parser_pyx_9CANDefine_dbc_name, (char *)0, 0}, + {0, 0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_7opendbc_3can_10parser_pyx_CANDefine_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_7opendbc_3can_10parser_pyx_CANDefine}, + {Py_tp_traverse, (void *)__pyx_tp_traverse_7opendbc_3can_10parser_pyx_CANDefine}, + {Py_tp_clear, (void *)__pyx_tp_clear_7opendbc_3can_10parser_pyx_CANDefine}, + {Py_tp_methods, (void *)__pyx_methods_7opendbc_3can_10parser_pyx_CANDefine}, + {Py_tp_getset, (void *)__pyx_getsets_7opendbc_3can_10parser_pyx_CANDefine}, + {Py_tp_init, (void *)__pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_1__init__}, + {Py_tp_new, (void *)__pyx_tp_new_7opendbc_3can_10parser_pyx_CANDefine}, + {0, 0}, +}; +static PyType_Spec __pyx_type_7opendbc_3can_10parser_pyx_CANDefine_spec = { + "opendbc.can.parser_pyx.CANDefine", + sizeof(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, + __pyx_type_7opendbc_3can_10parser_pyx_CANDefine_slots, +}; +#else + +static PyTypeObject __pyx_type_7opendbc_3can_10parser_pyx_CANDefine = { + PyVarObject_HEAD_INIT(0, 0) + "opendbc.can.parser_pyx.""CANDefine", /*tp_name*/ + sizeof(struct __pyx_obj_7opendbc_3can_10parser_pyx_CANDefine), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_7opendbc_3can_10parser_pyx_CANDefine, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, /*tp_flags*/ + 0, /*tp_doc*/ + __pyx_tp_traverse_7opendbc_3can_10parser_pyx_CANDefine, /*tp_traverse*/ + __pyx_tp_clear_7opendbc_3can_10parser_pyx_CANDefine, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_7opendbc_3can_10parser_pyx_CANDefine, /*tp_methods*/ + 0, /*tp_members*/ + __pyx_getsets_7opendbc_3can_10parser_pyx_CANDefine, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + __pyx_pw_7opendbc_3can_10parser_pyx_9CANDefine_1__init__, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_7opendbc_3can_10parser_pyx_CANDefine, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyMethodDef __pyx_methods[] = { + {0, 0, 0, 0} +}; +#ifndef CYTHON_SMALL_CODE +#if defined(__clang__) + #define CYTHON_SMALL_CODE +#elif defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 3)) + #define CYTHON_SMALL_CODE __attribute__((cold)) +#else + #define CYTHON_SMALL_CODE +#endif +#endif +/* #### Code section: pystring_table ### */ + +static int __Pyx_CreateStringTabAndInitStrings(void) { + __Pyx_StringTabEntry __pyx_string_tab[] = { + {&__pyx_kp_u_, __pyx_k_, sizeof(__pyx_k_), 0, 1, 0, 0}, + {&__pyx_n_s_CANDefine, __pyx_k_CANDefine, sizeof(__pyx_k_CANDefine), 0, 0, 1, 1}, + {&__pyx_n_s_CANDefine___reduce_cython, __pyx_k_CANDefine___reduce_cython, sizeof(__pyx_k_CANDefine___reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_CANDefine___setstate_cython, __pyx_k_CANDefine___setstate_cython, sizeof(__pyx_k_CANDefine___setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_CANParser, __pyx_k_CANParser, sizeof(__pyx_k_CANParser), 0, 0, 1, 1}, + {&__pyx_n_s_CANParser___reduce_cython, __pyx_k_CANParser___reduce_cython, sizeof(__pyx_k_CANParser___reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_CANParser___setstate_cython, __pyx_k_CANParser___setstate_cython, sizeof(__pyx_k_CANParser___setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_CANParser_update_strings, __pyx_k_CANParser_update_strings, sizeof(__pyx_k_CANParser_update_strings), 0, 0, 1, 1}, + {&__pyx_kp_u_Can_t_find_DBC, __pyx_k_Can_t_find_DBC, sizeof(__pyx_k_Can_t_find_DBC), 0, 1, 0, 0}, + {&__pyx_kp_u_Can_t_find_DBC_2, __pyx_k_Can_t_find_DBC_2, sizeof(__pyx_k_Can_t_find_DBC_2), 0, 1, 0, 0}, + {&__pyx_n_s_MemoryError, __pyx_k_MemoryError, sizeof(__pyx_k_MemoryError), 0, 0, 1, 1}, + {&__pyx_n_s_Number, __pyx_k_Number, sizeof(__pyx_k_Number), 0, 0, 1, 1}, + {&__pyx_n_s_RuntimeError, __pyx_k_RuntimeError, sizeof(__pyx_k_RuntimeError), 0, 0, 1, 1}, + {&__pyx_n_s_TypeError, __pyx_k_TypeError, sizeof(__pyx_k_TypeError), 0, 0, 1, 1}, + {&__pyx_n_s__15, __pyx_k__15, sizeof(__pyx_k__15), 0, 0, 1, 1}, + {&__pyx_n_s__4, __pyx_k__4, sizeof(__pyx_k__4), 0, 0, 1, 1}, + {&__pyx_kp_u__5, __pyx_k__5, sizeof(__pyx_k__5), 0, 1, 0, 0}, + {&__pyx_n_s_asyncio_coroutines, __pyx_k_asyncio_coroutines, sizeof(__pyx_k_asyncio_coroutines), 0, 0, 1, 1}, + {&__pyx_n_s_bus, __pyx_k_bus, sizeof(__pyx_k_bus), 0, 0, 1, 1}, + {&__pyx_n_s_class_getitem, __pyx_k_class_getitem, sizeof(__pyx_k_class_getitem), 0, 0, 1, 1}, + {&__pyx_n_s_clear, __pyx_k_clear, sizeof(__pyx_k_clear), 0, 0, 1, 1}, + {&__pyx_n_s_cline_in_traceback, __pyx_k_cline_in_traceback, sizeof(__pyx_k_cline_in_traceback), 0, 0, 1, 1}, + {&__pyx_n_s_collections, __pyx_k_collections, sizeof(__pyx_k_collections), 0, 0, 1, 1}, + {&__pyx_kp_u_could_not_find_message, __pyx_k_could_not_find_message, sizeof(__pyx_k_could_not_find_message), 0, 1, 0, 0}, + {&__pyx_n_s_cv, __pyx_k_cv, sizeof(__pyx_k_cv), 0, 0, 1, 1}, + {&__pyx_n_s_cv_name, __pyx_k_cv_name, sizeof(__pyx_k_cv_name), 0, 0, 1, 1}, + {&__pyx_n_s_dbc_name, __pyx_k_dbc_name, sizeof(__pyx_k_dbc_name), 0, 0, 1, 1}, + {&__pyx_n_s_defaultdict, __pyx_k_defaultdict, sizeof(__pyx_k_defaultdict), 0, 0, 1, 1}, + {&__pyx_kp_u_disable, __pyx_k_disable, sizeof(__pyx_k_disable), 0, 1, 0, 0}, + {&__pyx_kp_u_enable, __pyx_k_enable, sizeof(__pyx_k_enable), 0, 1, 0, 0}, + {&__pyx_kp_u_gc, __pyx_k_gc, sizeof(__pyx_k_gc), 0, 1, 0, 0}, + {&__pyx_n_s_get, __pyx_k_get, sizeof(__pyx_k_get), 0, 0, 1, 1}, + {&__pyx_n_s_getstate, __pyx_k_getstate, sizeof(__pyx_k_getstate), 0, 0, 1, 1}, + {&__pyx_n_s_import, __pyx_k_import, sizeof(__pyx_k_import), 0, 0, 1, 1}, + {&__pyx_kp_u_in_DBC, __pyx_k_in_DBC, sizeof(__pyx_k_in_DBC), 0, 1, 0, 0}, + {&__pyx_n_s_initializing, __pyx_k_initializing, sizeof(__pyx_k_initializing), 0, 0, 1, 1}, + {&__pyx_n_s_is_coroutine, __pyx_k_is_coroutine, sizeof(__pyx_k_is_coroutine), 0, 0, 1, 1}, + {&__pyx_kp_u_isenabled, __pyx_k_isenabled, sizeof(__pyx_k_isenabled), 0, 1, 0, 0}, + {&__pyx_n_s_it, __pyx_k_it, sizeof(__pyx_k_it), 0, 0, 1, 1}, + {&__pyx_n_s_l, __pyx_k_l, sizeof(__pyx_k_l), 0, 0, 1, 1}, + {&__pyx_n_s_main, __pyx_k_main, sizeof(__pyx_k_main), 0, 0, 1, 1}, + {&__pyx_n_s_messages, __pyx_k_messages, sizeof(__pyx_k_messages), 0, 0, 1, 1}, + {&__pyx_n_s_name, __pyx_k_name, sizeof(__pyx_k_name), 0, 0, 1, 1}, + {&__pyx_n_s_new_vals, __pyx_k_new_vals, sizeof(__pyx_k_new_vals), 0, 0, 1, 1}, + {&__pyx_n_s_numbers, __pyx_k_numbers, sizeof(__pyx_k_numbers), 0, 0, 1, 1}, + {&__pyx_n_s_opendbc_can_parser_pyx, __pyx_k_opendbc_can_parser_pyx, sizeof(__pyx_k_opendbc_can_parser_pyx), 0, 0, 1, 1}, + {&__pyx_kp_s_opendbc_can_parser_pyx_pyx, __pyx_k_opendbc_can_parser_pyx_pyx, sizeof(__pyx_k_opendbc_can_parser_pyx_pyx), 0, 0, 1, 0}, + {&__pyx_n_s_pyx_state, __pyx_k_pyx_state, sizeof(__pyx_k_pyx_state), 0, 0, 1, 1}, + {&__pyx_n_s_range, __pyx_k_range, sizeof(__pyx_k_range), 0, 0, 1, 1}, + {&__pyx_n_s_reduce, __pyx_k_reduce, sizeof(__pyx_k_reduce), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_cython, __pyx_k_reduce_cython, sizeof(__pyx_k_reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_ex, __pyx_k_reduce_ex, sizeof(__pyx_k_reduce_ex), 0, 0, 1, 1}, + {&__pyx_n_s_self, __pyx_k_self, sizeof(__pyx_k_self), 0, 0, 1, 1}, + {&__pyx_kp_s_self_can_self_dbc_cannot_be_conv, __pyx_k_self_can_self_dbc_cannot_be_conv, sizeof(__pyx_k_self_can_self_dbc_cannot_be_conv), 0, 0, 1, 0}, + {&__pyx_kp_s_self_dbc_cannot_be_converted_to, __pyx_k_self_dbc_cannot_be_converted_to, sizeof(__pyx_k_self_dbc_cannot_be_converted_to), 0, 0, 1, 0}, + {&__pyx_n_s_sendcan, __pyx_k_sendcan, sizeof(__pyx_k_sendcan), 0, 0, 1, 1}, + {&__pyx_n_s_setstate, __pyx_k_setstate, sizeof(__pyx_k_setstate), 0, 0, 1, 1}, + {&__pyx_n_s_setstate_cython, __pyx_k_setstate_cython, sizeof(__pyx_k_setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_spec, __pyx_k_spec, sizeof(__pyx_k_spec), 0, 0, 1, 1}, + {&__pyx_n_s_split, __pyx_k_split, sizeof(__pyx_k_split), 0, 0, 1, 1}, + {&__pyx_n_s_strings, __pyx_k_strings, sizeof(__pyx_k_strings), 0, 0, 1, 1}, + {&__pyx_kp_s_stringsource, __pyx_k_stringsource, sizeof(__pyx_k_stringsource), 0, 0, 1, 0}, + {&__pyx_n_s_test, __pyx_k_test, sizeof(__pyx_k_test), 0, 0, 1, 1}, + {&__pyx_n_s_update_strings, __pyx_k_update_strings, sizeof(__pyx_k_update_strings), 0, 0, 1, 1}, + {&__pyx_n_s_updated_addrs, __pyx_k_updated_addrs, sizeof(__pyx_k_updated_addrs), 0, 0, 1, 1}, + {&__pyx_n_s_v, __pyx_k_v, sizeof(__pyx_k_v), 0, 0, 1, 1}, + {&__pyx_n_s_values, __pyx_k_values, sizeof(__pyx_k_values), 0, 0, 1, 1}, + {&__pyx_n_s_zip, __pyx_k_zip, sizeof(__pyx_k_zip), 0, 0, 1, 1}, + {0, 0, 0, 0, 0, 0, 0} + }; + return __Pyx_InitStrings(__pyx_string_tab); +} +/* #### Code section: cached_builtins ### */ +static CYTHON_SMALL_CODE int __Pyx_InitCachedBuiltins(void) { + __pyx_builtin_RuntimeError = __Pyx_GetBuiltinName(__pyx_n_s_RuntimeError); if (!__pyx_builtin_RuntimeError) __PYX_ERR(0, 34, __pyx_L1_error) + __pyx_builtin_range = __Pyx_GetBuiltinName(__pyx_n_s_range); if (!__pyx_builtin_range) __PYX_ERR(0, 42, __pyx_L1_error) + __pyx_builtin_TypeError = __Pyx_GetBuiltinName(__pyx_n_s_TypeError); if (!__pyx_builtin_TypeError) __PYX_ERR(1, 2, __pyx_L1_error) + __pyx_builtin_zip = __Pyx_GetBuiltinName(__pyx_n_s_zip); if (!__pyx_builtin_zip) __PYX_ERR(0, 143, __pyx_L1_error) + __pyx_builtin_MemoryError = __Pyx_GetBuiltinName(__pyx_n_s_MemoryError); if (!__pyx_builtin_MemoryError) __PYX_ERR(1, 68, __pyx_L1_error) + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: cached_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_InitCachedConstants", 0); + + /* "opendbc/can/parser_pyx.pyx":139 + * # separate definition/value pairs + * def_val = def_val.split() + * values = [int(v) for v in def_val[::2]] # <<<<<<<<<<<<<< + * defs = def_val[1::2] + * + */ + __pyx_slice__2 = PySlice_New(Py_None, Py_None, __pyx_int_2); if (unlikely(!__pyx_slice__2)) __PYX_ERR(0, 139, __pyx_L1_error) + __Pyx_GOTREF(__pyx_slice__2); + __Pyx_GIVEREF(__pyx_slice__2); + + /* "opendbc/can/parser_pyx.pyx":140 + * def_val = def_val.split() + * values = [int(v) for v in def_val[::2]] + * defs = def_val[1::2] # <<<<<<<<<<<<<< + * + * # two ways to lookup: address or msg name + */ + __pyx_slice__3 = PySlice_New(__pyx_int_1, Py_None, __pyx_int_2); if (unlikely(!__pyx_slice__3)) __PYX_ERR(0, 140, __pyx_L1_error) + __Pyx_GOTREF(__pyx_slice__3); + __Pyx_GIVEREF(__pyx_slice__3); + + /* "opendbc/can/parser_pyx.pyx":73 + * del self.can + * + * def update_strings(self, strings, sendcan=False): # <<<<<<<<<<<<<< + * for v in self.vl_all.values(): + * for l in v.values(): # no-cython-lint + */ + __pyx_tuple__6 = PyTuple_Pack(10, __pyx_n_s_self, __pyx_n_s_strings, __pyx_n_s_sendcan, __pyx_n_s_v, __pyx_n_s_l, __pyx_n_s_new_vals, __pyx_n_s_updated_addrs, __pyx_n_s_it, __pyx_n_s_cv, __pyx_n_s_cv_name); if (unlikely(!__pyx_tuple__6)) __PYX_ERR(0, 73, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__6); + __Pyx_GIVEREF(__pyx_tuple__6); + __pyx_codeobj__7 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 10, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__6, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_opendbc_can_parser_pyx_pyx, __pyx_n_s_update_strings, 73, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__7)) __PYX_ERR(0, 73, __pyx_L1_error) + __pyx_tuple__8 = PyTuple_Pack(1, Py_False); if (unlikely(!__pyx_tuple__8)) __PYX_ERR(0, 73, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__8); + __Pyx_GIVEREF(__pyx_tuple__8); + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.can,self.dbc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_tuple__9 = PyTuple_Pack(1, __pyx_n_s_self); if (unlikely(!__pyx_tuple__9)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__9); + __Pyx_GIVEREF(__pyx_tuple__9); + __pyx_codeobj__10 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__9, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__10)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.can,self.dbc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.can,self.dbc cannot be converted to a Python object for pickling" + */ + __pyx_tuple__11 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_pyx_state); if (unlikely(!__pyx_tuple__11)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__11); + __Pyx_GIVEREF(__pyx_tuple__11); + __pyx_codeobj__12 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__11, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__12)) __PYX_ERR(1, 3, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.dbc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_codeobj__13 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__9, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__13)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.dbc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.dbc cannot be converted to a Python object for pickling" + */ + __pyx_codeobj__14 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__11, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__14)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_RefNannyFinishContext(); + return -1; +} +/* #### Code section: init_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitConstants(void) { + __pyx_umethod_PyDict_Type_get.type = (PyObject*)&PyDict_Type; + __pyx_umethod_PyDict_Type_get.method_name = &__pyx_n_s_get; + if (__Pyx_CreateStringTabAndInitStrings() < 0) __PYX_ERR(0, 1, __pyx_L1_error); + __pyx_int_0 = PyInt_FromLong(0); if (unlikely(!__pyx_int_0)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_1 = PyInt_FromLong(1); if (unlikely(!__pyx_int_1)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_2 = PyInt_FromLong(2); if (unlikely(!__pyx_int_2)) __PYX_ERR(0, 1, __pyx_L1_error) + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: init_globals ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitGlobals(void) { + return 0; +} +/* #### Code section: init_module ### */ + +static CYTHON_SMALL_CODE int __Pyx_modinit_global_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_import_code(void); /*proto*/ + +static int __Pyx_modinit_global_init_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_global_init_code", 0); + /*--- Global init code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_variable_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_export_code", 0); + /*--- Variable export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_export_code", 0); + /*--- Function export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_type_init_code(void) { + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_modinit_type_init_code", 0); + /*--- Type init code ---*/ + #if CYTHON_USE_TYPE_SPECS + __pyx_ptype_7opendbc_3can_10parser_pyx_CANParser = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_7opendbc_3can_10parser_pyx_CANParser_spec, NULL); if (unlikely(!__pyx_ptype_7opendbc_3can_10parser_pyx_CANParser)) __PYX_ERR(0, 18, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_7opendbc_3can_10parser_pyx_CANParser_spec, __pyx_ptype_7opendbc_3can_10parser_pyx_CANParser) < 0) __PYX_ERR(0, 18, __pyx_L1_error) + #else + __pyx_ptype_7opendbc_3can_10parser_pyx_CANParser = &__pyx_type_7opendbc_3can_10parser_pyx_CANParser; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_7opendbc_3can_10parser_pyx_CANParser) < 0) __PYX_ERR(0, 18, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_7opendbc_3can_10parser_pyx_CANParser->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_7opendbc_3can_10parser_pyx_CANParser->tp_dictoffset && __pyx_ptype_7opendbc_3can_10parser_pyx_CANParser->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_7opendbc_3can_10parser_pyx_CANParser->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_CANParser, (PyObject *) __pyx_ptype_7opendbc_3can_10parser_pyx_CANParser) < 0) __PYX_ERR(0, 18, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_7opendbc_3can_10parser_pyx_CANParser) < 0) __PYX_ERR(0, 18, __pyx_L1_error) + #endif + #if CYTHON_USE_TYPE_SPECS + __pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_7opendbc_3can_10parser_pyx_CANDefine_spec, NULL); if (unlikely(!__pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine)) __PYX_ERR(0, 105, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_7opendbc_3can_10parser_pyx_CANDefine_spec, __pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine) < 0) __PYX_ERR(0, 105, __pyx_L1_error) + #else + __pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine = &__pyx_type_7opendbc_3can_10parser_pyx_CANDefine; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine) < 0) __PYX_ERR(0, 105, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine->tp_dictoffset && __pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_CANDefine, (PyObject *) __pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine) < 0) __PYX_ERR(0, 105, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_7opendbc_3can_10parser_pyx_CANDefine) < 0) __PYX_ERR(0, 105, __pyx_L1_error) + #endif + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_RefNannyFinishContext(); + return -1; +} + +static int __Pyx_modinit_type_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_type_import_code", 0); + /*--- Type import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_variable_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_import_code", 0); + /*--- Variable import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_import_code", 0); + /*--- Function import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + + +#if PY_MAJOR_VERSION >= 3 +#if CYTHON_PEP489_MULTI_PHASE_INIT +static PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def); /*proto*/ +static int __pyx_pymod_exec_parser_pyx(PyObject* module); /*proto*/ +static PyModuleDef_Slot __pyx_moduledef_slots[] = { + {Py_mod_create, (void*)__pyx_pymod_create}, + {Py_mod_exec, (void*)__pyx_pymod_exec_parser_pyx}, + {0, NULL} +}; +#endif + +#ifdef __cplusplus +namespace { + struct PyModuleDef __pyx_moduledef = + #else + static struct PyModuleDef __pyx_moduledef = + #endif + { + PyModuleDef_HEAD_INIT, + "parser_pyx", + 0, /* m_doc */ + #if CYTHON_PEP489_MULTI_PHASE_INIT + 0, /* m_size */ + #elif CYTHON_USE_MODULE_STATE + sizeof(__pyx_mstate), /* m_size */ + #else + -1, /* m_size */ + #endif + __pyx_methods /* m_methods */, + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_moduledef_slots, /* m_slots */ + #else + NULL, /* m_reload */ + #endif + #if CYTHON_USE_MODULE_STATE + __pyx_m_traverse, /* m_traverse */ + __pyx_m_clear, /* m_clear */ + NULL /* m_free */ + #else + NULL, /* m_traverse */ + NULL, /* m_clear */ + NULL /* m_free */ + #endif + }; + #ifdef __cplusplus +} /* anonymous namespace */ +#endif +#endif + +#ifndef CYTHON_NO_PYINIT_EXPORT +#define __Pyx_PyMODINIT_FUNC PyMODINIT_FUNC +#elif PY_MAJOR_VERSION < 3 +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" void +#else +#define __Pyx_PyMODINIT_FUNC void +#endif +#else +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" PyObject * +#else +#define __Pyx_PyMODINIT_FUNC PyObject * +#endif +#endif + + +#if PY_MAJOR_VERSION < 3 +__Pyx_PyMODINIT_FUNC initparser_pyx(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC initparser_pyx(void) +#else +__Pyx_PyMODINIT_FUNC PyInit_parser_pyx(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC PyInit_parser_pyx(void) +#if CYTHON_PEP489_MULTI_PHASE_INIT +{ + return PyModuleDef_Init(&__pyx_moduledef); +} +static CYTHON_SMALL_CODE int __Pyx_check_single_interpreter(void) { + #if PY_VERSION_HEX >= 0x030700A1 + static PY_INT64_T main_interpreter_id = -1; + PY_INT64_T current_id = PyInterpreterState_GetID(PyThreadState_Get()->interp); + if (main_interpreter_id == -1) { + main_interpreter_id = current_id; + return (unlikely(current_id == -1)) ? -1 : 0; + } else if (unlikely(main_interpreter_id != current_id)) + #else + static PyInterpreterState *main_interpreter = NULL; + PyInterpreterState *current_interpreter = PyThreadState_Get()->interp; + if (!main_interpreter) { + main_interpreter = current_interpreter; + } else if (unlikely(main_interpreter != current_interpreter)) + #endif + { + PyErr_SetString( + PyExc_ImportError, + "Interpreter change detected - this module can only be loaded into one interpreter per process."); + return -1; + } + return 0; +} +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *module, const char* from_name, const char* to_name, int allow_none) +#else +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *moddict, const char* from_name, const char* to_name, int allow_none) +#endif +{ + PyObject *value = PyObject_GetAttrString(spec, from_name); + int result = 0; + if (likely(value)) { + if (allow_none || value != Py_None) { +#if CYTHON_COMPILING_IN_LIMITED_API + result = PyModule_AddObject(module, to_name, value); +#else + result = PyDict_SetItemString(moddict, to_name, value); +#endif + } + Py_DECREF(value); + } else if (PyErr_ExceptionMatches(PyExc_AttributeError)) { + PyErr_Clear(); + } else { + result = -1; + } + return result; +} +static CYTHON_SMALL_CODE PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def) { + PyObject *module = NULL, *moddict, *modname; + CYTHON_UNUSED_VAR(def); + if (__Pyx_check_single_interpreter()) + return NULL; + if (__pyx_m) + return __Pyx_NewRef(__pyx_m); + modname = PyObject_GetAttrString(spec, "name"); + if (unlikely(!modname)) goto bad; + module = PyModule_NewObject(modname); + Py_DECREF(modname); + if (unlikely(!module)) goto bad; +#if CYTHON_COMPILING_IN_LIMITED_API + moddict = module; +#else + moddict = PyModule_GetDict(module); + if (unlikely(!moddict)) goto bad; +#endif + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "loader", "__loader__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "origin", "__file__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "parent", "__package__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "submodule_search_locations", "__path__", 0) < 0)) goto bad; + return module; +bad: + Py_XDECREF(module); + return NULL; +} + + +static CYTHON_SMALL_CODE int __pyx_pymod_exec_parser_pyx(PyObject *__pyx_pyinit_module) +#endif +#endif +{ + int stringtab_initialized = 0; + #if CYTHON_USE_MODULE_STATE + int pystate_addmodule_run = 0; + #endif + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannyDeclarations + #if CYTHON_PEP489_MULTI_PHASE_INIT + if (__pyx_m) { + if (__pyx_m == __pyx_pyinit_module) return 0; + PyErr_SetString(PyExc_RuntimeError, "Module 'parser_pyx' has already been imported. Re-initialisation is not supported."); + return -1; + } + #elif PY_MAJOR_VERSION >= 3 + if (__pyx_m) return __Pyx_NewRef(__pyx_m); + #endif + /*--- Module creation code ---*/ + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_m = __pyx_pyinit_module; + Py_INCREF(__pyx_m); + #else + #if PY_MAJOR_VERSION < 3 + __pyx_m = Py_InitModule4("parser_pyx", __pyx_methods, 0, 0, PYTHON_API_VERSION); Py_XINCREF(__pyx_m); + if (unlikely(!__pyx_m)) __PYX_ERR(0, 1, __pyx_L1_error) + #elif CYTHON_USE_MODULE_STATE + __pyx_t_1 = PyModule_Create(&__pyx_moduledef); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 1, __pyx_L1_error) + { + int add_module_result = PyState_AddModule(__pyx_t_1, &__pyx_moduledef); + __pyx_t_1 = 0; /* transfer ownership from __pyx_t_1 to "parser_pyx" pseudovariable */ + if (unlikely((add_module_result < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + pystate_addmodule_run = 1; + } + #else + __pyx_m = PyModule_Create(&__pyx_moduledef); + if (unlikely(!__pyx_m)) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #endif + CYTHON_UNUSED_VAR(__pyx_t_1); + __pyx_d = PyModule_GetDict(__pyx_m); if (unlikely(!__pyx_d)) __PYX_ERR(0, 1, __pyx_L1_error) + Py_INCREF(__pyx_d); + __pyx_b = __Pyx_PyImport_AddModuleRef(__Pyx_BUILTIN_MODULE_NAME); if (unlikely(!__pyx_b)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_cython_runtime = __Pyx_PyImport_AddModuleRef((const char *) "cython_runtime"); if (unlikely(!__pyx_cython_runtime)) __PYX_ERR(0, 1, __pyx_L1_error) + if (PyObject_SetAttrString(__pyx_m, "__builtins__", __pyx_b) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #if CYTHON_REFNANNY +__Pyx_RefNanny = __Pyx_RefNannyImportAPI("refnanny"); +if (!__Pyx_RefNanny) { + PyErr_Clear(); + __Pyx_RefNanny = __Pyx_RefNannyImportAPI("Cython.Runtime.refnanny"); + if (!__Pyx_RefNanny) + Py_FatalError("failed to import 'refnanny' module"); +} +#endif + __Pyx_RefNannySetupContext("__Pyx_PyMODINIT_FUNC PyInit_parser_pyx(void)", 0); + if (__Pyx_check_binary_version(__PYX_LIMITED_VERSION_HEX, __Pyx_get_runtime_version(), CYTHON_COMPILING_IN_LIMITED_API) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #ifdef __Pxy_PyFrame_Initialize_Offsets + __Pxy_PyFrame_Initialize_Offsets(); + #endif + __pyx_empty_tuple = PyTuple_New(0); if (unlikely(!__pyx_empty_tuple)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_empty_bytes = PyBytes_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_bytes)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_empty_unicode = PyUnicode_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_unicode)) __PYX_ERR(0, 1, __pyx_L1_error) + #ifdef __Pyx_CyFunction_USED + if (__pyx_CyFunction_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_FusedFunction_USED + if (__pyx_FusedFunction_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Coroutine_USED + if (__pyx_Coroutine_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Generator_USED + if (__pyx_Generator_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_AsyncGen_USED + if (__pyx_AsyncGen_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_StopAsyncIteration_USED + if (__pyx_StopAsyncIteration_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + /*--- Library function declarations ---*/ + /*--- Threads initialization code ---*/ + #if defined(WITH_THREAD) && PY_VERSION_HEX < 0x030700F0 && defined(__PYX_FORCE_INIT_THREADS) && __PYX_FORCE_INIT_THREADS + PyEval_InitThreads(); + #endif + /*--- Initialize various global constants etc. ---*/ + if (__Pyx_InitConstants() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + stringtab_initialized = 1; + if (__Pyx_InitGlobals() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #if PY_MAJOR_VERSION < 3 && (__PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT) + if (__Pyx_init_sys_getdefaultencoding_params() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + if (__pyx_module_is_main_opendbc__can__parser_pyx) { + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_name, __pyx_n_s_main) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + } + #if PY_MAJOR_VERSION >= 3 + { + PyObject *modules = PyImport_GetModuleDict(); if (unlikely(!modules)) __PYX_ERR(0, 1, __pyx_L1_error) + if (!PyDict_GetItemString(modules, "opendbc.can.parser_pyx")) { + if (unlikely((PyDict_SetItemString(modules, "opendbc.can.parser_pyx", __pyx_m) < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + } + } + #endif + /*--- Builtin init code ---*/ + if (__Pyx_InitCachedBuiltins() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + /*--- Constants init code ---*/ + if (__Pyx_InitCachedConstants() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + /*--- Global type/function init code ---*/ + (void)__Pyx_modinit_global_init_code(); + (void)__Pyx_modinit_variable_export_code(); + (void)__Pyx_modinit_function_export_code(); + if (unlikely((__Pyx_modinit_type_init_code() < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + (void)__Pyx_modinit_type_import_code(); + (void)__Pyx_modinit_variable_import_code(); + (void)__Pyx_modinit_function_import_code(); + /*--- Execution code ---*/ + #if defined(__Pyx_Generator_USED) || defined(__Pyx_Coroutine_USED) + if (__Pyx_patch_abc() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + + /* "opendbc/can/parser_pyx.pyx":14 + * from .common cimport dbc_lookup, SignalValue, DBC + * + * import numbers # <<<<<<<<<<<<<< + * from collections import defaultdict + * + */ + __pyx_t_2 = __Pyx_ImportDottedModule(__pyx_n_s_numbers, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_numbers, __pyx_t_2) < 0) __PYX_ERR(0, 14, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "opendbc/can/parser_pyx.pyx":15 + * + * import numbers + * from collections import defaultdict # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = PyList_New(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_INCREF(__pyx_n_s_defaultdict); + __Pyx_GIVEREF(__pyx_n_s_defaultdict); + if (__Pyx_PyList_SET_ITEM(__pyx_t_2, 0, __pyx_n_s_defaultdict)) __PYX_ERR(0, 15, __pyx_L1_error); + __pyx_t_3 = __Pyx_Import(__pyx_n_s_collections, __pyx_t_2, 0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_ImportFrom(__pyx_t_3, __pyx_n_s_defaultdict); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_defaultdict, __pyx_t_2) < 0) __PYX_ERR(0, 15, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "opendbc/can/parser_pyx.pyx":73 + * del self.can + * + * def update_strings(self, strings, sendcan=False): # <<<<<<<<<<<<<< + * for v in self.vl_all.values(): + * for l in v.values(): # no-cython-lint + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_7opendbc_3can_10parser_pyx_9CANParser_5update_strings, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_CANParser_update_strings, NULL, __pyx_n_s_opendbc_can_parser_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__7)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 73, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_3, __pyx_tuple__8); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_7opendbc_3can_10parser_pyx_CANParser, __pyx_n_s_update_strings, __pyx_t_3) < 0) __PYX_ERR(0, 73, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + PyType_Modified(__pyx_ptype_7opendbc_3can_10parser_pyx_CANParser); + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.can,self.dbc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_7opendbc_3can_10parser_pyx_9CANParser_7__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_CANParser___reduce_cython, NULL, __pyx_n_s_opendbc_can_parser_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__10)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_3) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.can,self.dbc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.can,self.dbc cannot be converted to a Python object for pickling" + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_7opendbc_3can_10parser_pyx_9CANParser_9__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_CANParser___setstate_cython, NULL, __pyx_n_s_opendbc_can_parser_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__12)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_3) < 0) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.dbc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_7opendbc_3can_10parser_pyx_9CANDefine_3__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_CANDefine___reduce_cython, NULL, __pyx_n_s_opendbc_can_parser_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__13)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_3) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.dbc cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.dbc cannot be converted to a Python object for pickling" + */ + __pyx_t_3 = __Pyx_CyFunction_New(&__pyx_mdef_7opendbc_3can_10parser_pyx_9CANDefine_5__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_CANDefine___setstate_cython, NULL, __pyx_n_s_opendbc_can_parser_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__14)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_3) < 0) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "opendbc/can/parser_pyx.pyx":1 + * # distutils: language = c++ # <<<<<<<<<<<<<< + * # cython: c_string_encoding=ascii, language_level=3 + * + */ + __pyx_t_3 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_test, __pyx_t_3) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /*--- Wrapped vars code ---*/ + + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + if (__pyx_m) { + if (__pyx_d && stringtab_initialized) { + __Pyx_AddTraceback("init opendbc.can.parser_pyx", __pyx_clineno, __pyx_lineno, __pyx_filename); + } + #if !CYTHON_USE_MODULE_STATE + Py_CLEAR(__pyx_m); + #else + Py_DECREF(__pyx_m); + if (pystate_addmodule_run) { + PyObject *tp, *value, *tb; + PyErr_Fetch(&tp, &value, &tb); + PyState_RemoveModule(&__pyx_moduledef); + PyErr_Restore(tp, value, tb); + } + #endif + } else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_ImportError, "init opendbc.can.parser_pyx"); + } + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + #if CYTHON_PEP489_MULTI_PHASE_INIT + return (__pyx_m != NULL) ? 0 : -1; + #elif PY_MAJOR_VERSION >= 3 + return __pyx_m; + #else + return; + #endif +} +/* #### Code section: cleanup_globals ### */ +/* #### Code section: cleanup_module ### */ +/* #### Code section: main_method ### */ +/* #### Code section: utility_code_pragmas ### */ +#ifdef _MSC_VER +#pragma warning( push ) +/* Warning 4127: conditional expression is constant + * Cython uses constant conditional expressions to allow in inline functions to be optimized at + * compile-time, so this warning is not useful + */ +#pragma warning( disable : 4127 ) +#endif + + + +/* #### Code section: utility_code_def ### */ + +/* --- Runtime support code --- */ +/* Refnanny */ +#if CYTHON_REFNANNY +static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname) { + PyObject *m = NULL, *p = NULL; + void *r = NULL; + m = PyImport_ImportModule(modname); + if (!m) goto end; + p = PyObject_GetAttrString(m, "RefNannyAPI"); + if (!p) goto end; + r = PyLong_AsVoidPtr(p); +end: + Py_XDECREF(p); + Py_XDECREF(m); + return (__Pyx_RefNannyAPIStruct *)r; +} +#endif + +/* PyErrExceptionMatches */ +#if CYTHON_FAST_THREAD_STATE +static int __Pyx_PyErr_ExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; i= 0x030C00A6 + PyObject *current_exception = tstate->current_exception; + if (unlikely(!current_exception)) return 0; + exc_type = (PyObject*) Py_TYPE(current_exception); + if (exc_type == err) return 1; +#else + exc_type = tstate->curexc_type; + if (exc_type == err) return 1; + if (unlikely(!exc_type)) return 0; +#endif + #if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(exc_type); + #endif + if (unlikely(PyTuple_Check(err))) { + result = __Pyx_PyErr_ExceptionMatchesTuple(exc_type, err); + } else { + result = __Pyx_PyErr_GivenExceptionMatches(exc_type, err); + } + #if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(exc_type); + #endif + return result; +} +#endif + +/* PyErrFetchRestore */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject *tmp_value; + assert(type == NULL || (value != NULL && type == (PyObject*) Py_TYPE(value))); + if (value) { + #if CYTHON_COMPILING_IN_CPYTHON + if (unlikely(((PyBaseExceptionObject*) value)->traceback != tb)) + #endif + PyException_SetTraceback(value, tb); + } + tmp_value = tstate->current_exception; + tstate->current_exception = value; + Py_XDECREF(tmp_value); + Py_XDECREF(type); + Py_XDECREF(tb); +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + tmp_type = tstate->curexc_type; + tmp_value = tstate->curexc_value; + tmp_tb = tstate->curexc_traceback; + tstate->curexc_type = type; + tstate->curexc_value = value; + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); +#endif +} +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject* exc_value; + exc_value = tstate->current_exception; + tstate->current_exception = 0; + *value = exc_value; + *type = NULL; + *tb = NULL; + if (exc_value) { + *type = (PyObject*) Py_TYPE(exc_value); + Py_INCREF(*type); + #if CYTHON_COMPILING_IN_CPYTHON + *tb = ((PyBaseExceptionObject*) exc_value)->traceback; + Py_XINCREF(*tb); + #else + *tb = PyException_GetTraceback(exc_value); + #endif + } +#else + *type = tstate->curexc_type; + *value = tstate->curexc_value; + *tb = tstate->curexc_traceback; + tstate->curexc_type = 0; + tstate->curexc_value = 0; + tstate->curexc_traceback = 0; +#endif +} +#endif + +/* PyObjectGetAttrStr */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name) { + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro)) + return tp->tp_getattro(obj, attr_name); +#if PY_MAJOR_VERSION < 3 + if (likely(tp->tp_getattr)) + return tp->tp_getattr(obj, PyString_AS_STRING(attr_name)); +#endif + return PyObject_GetAttr(obj, attr_name); +} +#endif + +/* PyObjectGetAttrStrNoError */ +#if __PYX_LIMITED_VERSION_HEX < 0x030d00A1 +static void __Pyx_PyObject_GetAttrStr_ClearAttributeError(void) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + if (likely(__Pyx_PyErr_ExceptionMatches(PyExc_AttributeError))) + __Pyx_PyErr_Clear(); +} +#endif +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name) { + PyObject *result; +#if __PYX_LIMITED_VERSION_HEX >= 0x030d00A1 + (void) PyObject_GetOptionalAttr(obj, attr_name, &result); + return result; +#else +#if CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_TYPE_SLOTS && PY_VERSION_HEX >= 0x030700B1 + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro == PyObject_GenericGetAttr)) { + return _PyObject_GenericGetAttrWithDict(obj, attr_name, NULL, 1); + } +#endif + result = __Pyx_PyObject_GetAttrStr(obj, attr_name); + if (unlikely(!result)) { + __Pyx_PyObject_GetAttrStr_ClearAttributeError(); + } + return result; +#endif +} + +/* GetBuiltinName */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name) { + PyObject* result = __Pyx_PyObject_GetAttrStrNoError(__pyx_b, name); + if (unlikely(!result) && !PyErr_Occurred()) { + PyErr_Format(PyExc_NameError, +#if PY_MAJOR_VERSION >= 3 + "name '%U' is not defined", name); +#else + "name '%.200s' is not defined", PyString_AS_STRING(name)); +#endif + } + return result; +} + +/* RaiseTooManyValuesToUnpack */ +static CYTHON_INLINE void __Pyx_RaiseTooManyValuesError(Py_ssize_t expected) { + PyErr_Format(PyExc_ValueError, + "too many values to unpack (expected %" CYTHON_FORMAT_SSIZE_T "d)", expected); +} + +/* RaiseNeedMoreValuesToUnpack */ +static CYTHON_INLINE void __Pyx_RaiseNeedMoreValuesError(Py_ssize_t index) { + PyErr_Format(PyExc_ValueError, + "need more than %" CYTHON_FORMAT_SSIZE_T "d value%.1s to unpack", + index, (index == 1) ? "" : "s"); +} + +/* IterFinish */ +static CYTHON_INLINE int __Pyx_IterFinish(void) { + PyObject* exc_type; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + exc_type = __Pyx_PyErr_CurrentExceptionType(); + if (unlikely(exc_type)) { + if (unlikely(!__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) + return -1; + __Pyx_PyErr_Clear(); + return 0; + } + return 0; +} + +/* UnpackItemEndCheck */ +static int __Pyx_IternextUnpackEndCheck(PyObject *retval, Py_ssize_t expected) { + if (unlikely(retval)) { + Py_DECREF(retval); + __Pyx_RaiseTooManyValuesError(expected); + return -1; + } + return __Pyx_IterFinish(); +} + +/* TupleAndListFromArray */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE void __Pyx_copy_object_array(PyObject *const *CYTHON_RESTRICT src, PyObject** CYTHON_RESTRICT dest, Py_ssize_t length) { + PyObject *v; + Py_ssize_t i; + for (i = 0; i < length; i++) { + v = dest[i] = src[i]; + Py_INCREF(v); + } +} +static CYTHON_INLINE PyObject * +__Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + Py_INCREF(__pyx_empty_tuple); + return __pyx_empty_tuple; + } + res = PyTuple_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyTupleObject*)res)->ob_item, n); + return res; +} +static CYTHON_INLINE PyObject * +__Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + return PyList_New(0); + } + res = PyList_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyListObject*)res)->ob_item, n); + return res; +} +#endif + +/* BytesEquals */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else + if (s1 == s2) { + return (equals == Py_EQ); + } else if (PyBytes_CheckExact(s1) & PyBytes_CheckExact(s2)) { + const char *ps1, *ps2; + Py_ssize_t length = PyBytes_GET_SIZE(s1); + if (length != PyBytes_GET_SIZE(s2)) + return (equals == Py_NE); + ps1 = PyBytes_AS_STRING(s1); + ps2 = PyBytes_AS_STRING(s2); + if (ps1[0] != ps2[0]) { + return (equals == Py_NE); + } else if (length == 1) { + return (equals == Py_EQ); + } else { + int result; +#if CYTHON_USE_UNICODE_INTERNALS && (PY_VERSION_HEX < 0x030B0000) + Py_hash_t hash1, hash2; + hash1 = ((PyBytesObject*)s1)->ob_shash; + hash2 = ((PyBytesObject*)s2)->ob_shash; + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + return (equals == Py_NE); + } +#endif + result = memcmp(ps1, ps2, (size_t)length); + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & PyBytes_CheckExact(s2)) { + return (equals == Py_NE); + } else if ((s2 == Py_None) & PyBytes_CheckExact(s1)) { + return (equals == Py_NE); + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +#endif +} + +/* UnicodeEquals */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else +#if PY_MAJOR_VERSION < 3 + PyObject* owned_ref = NULL; +#endif + int s1_is_unicode, s2_is_unicode; + if (s1 == s2) { + goto return_eq; + } + s1_is_unicode = PyUnicode_CheckExact(s1); + s2_is_unicode = PyUnicode_CheckExact(s2); +#if PY_MAJOR_VERSION < 3 + if ((s1_is_unicode & (!s2_is_unicode)) && PyString_CheckExact(s2)) { + owned_ref = PyUnicode_FromObject(s2); + if (unlikely(!owned_ref)) + return -1; + s2 = owned_ref; + s2_is_unicode = 1; + } else if ((s2_is_unicode & (!s1_is_unicode)) && PyString_CheckExact(s1)) { + owned_ref = PyUnicode_FromObject(s1); + if (unlikely(!owned_ref)) + return -1; + s1 = owned_ref; + s1_is_unicode = 1; + } else if (((!s2_is_unicode) & (!s1_is_unicode))) { + return __Pyx_PyBytes_Equals(s1, s2, equals); + } +#endif + if (s1_is_unicode & s2_is_unicode) { + Py_ssize_t length; + int kind; + void *data1, *data2; + if (unlikely(__Pyx_PyUnicode_READY(s1) < 0) || unlikely(__Pyx_PyUnicode_READY(s2) < 0)) + return -1; + length = __Pyx_PyUnicode_GET_LENGTH(s1); + if (length != __Pyx_PyUnicode_GET_LENGTH(s2)) { + goto return_ne; + } +#if CYTHON_USE_UNICODE_INTERNALS + { + Py_hash_t hash1, hash2; + #if CYTHON_PEP393_ENABLED + hash1 = ((PyASCIIObject*)s1)->hash; + hash2 = ((PyASCIIObject*)s2)->hash; + #else + hash1 = ((PyUnicodeObject*)s1)->hash; + hash2 = ((PyUnicodeObject*)s2)->hash; + #endif + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + goto return_ne; + } + } +#endif + kind = __Pyx_PyUnicode_KIND(s1); + if (kind != __Pyx_PyUnicode_KIND(s2)) { + goto return_ne; + } + data1 = __Pyx_PyUnicode_DATA(s1); + data2 = __Pyx_PyUnicode_DATA(s2); + if (__Pyx_PyUnicode_READ(kind, data1, 0) != __Pyx_PyUnicode_READ(kind, data2, 0)) { + goto return_ne; + } else if (length == 1) { + goto return_eq; + } else { + int result = memcmp(data1, data2, (size_t)(length * kind)); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & s2_is_unicode) { + goto return_ne; + } else if ((s2 == Py_None) & s1_is_unicode) { + goto return_ne; + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +return_eq: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ); +return_ne: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_NE); +#endif +} + +/* fastcall */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s) +{ + Py_ssize_t i, n = PyTuple_GET_SIZE(kwnames); + for (i = 0; i < n; i++) + { + if (s == PyTuple_GET_ITEM(kwnames, i)) return kwvalues[i]; + } + for (i = 0; i < n; i++) + { + int eq = __Pyx_PyUnicode_Equals(s, PyTuple_GET_ITEM(kwnames, i), Py_EQ); + if (unlikely(eq != 0)) { + if (unlikely(eq < 0)) return NULL; + return kwvalues[i]; + } + } + return NULL; +} +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 +CYTHON_UNUSED static PyObject *__Pyx_KwargsAsDict_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues) { + Py_ssize_t i, nkwargs = PyTuple_GET_SIZE(kwnames); + PyObject *dict; + dict = PyDict_New(); + if (unlikely(!dict)) + return NULL; + for (i=0; i= 3 + "%s() got multiple values for keyword argument '%U'", func_name, kw_name); + #else + "%s() got multiple values for keyword argument '%s'", func_name, + PyString_AsString(kw_name)); + #endif +} + +/* ParseKeywords */ +static int __Pyx_ParseOptionalKeywords( + PyObject *kwds, + PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, + PyObject *values[], + Py_ssize_t num_pos_args, + const char* function_name) +{ + PyObject *key = 0, *value = 0; + Py_ssize_t pos = 0; + PyObject*** name; + PyObject*** first_kw_arg = argnames + num_pos_args; + int kwds_is_tuple = CYTHON_METH_FASTCALL && likely(PyTuple_Check(kwds)); + while (1) { + Py_XDECREF(key); key = NULL; + Py_XDECREF(value); value = NULL; + if (kwds_is_tuple) { + Py_ssize_t size; +#if CYTHON_ASSUME_SAFE_MACROS + size = PyTuple_GET_SIZE(kwds); +#else + size = PyTuple_Size(kwds); + if (size < 0) goto bad; +#endif + if (pos >= size) break; +#if CYTHON_AVOID_BORROWED_REFS + key = __Pyx_PySequence_ITEM(kwds, pos); + if (!key) goto bad; +#elif CYTHON_ASSUME_SAFE_MACROS + key = PyTuple_GET_ITEM(kwds, pos); +#else + key = PyTuple_GetItem(kwds, pos); + if (!key) goto bad; +#endif + value = kwvalues[pos]; + pos++; + } + else + { + if (!PyDict_Next(kwds, &pos, &key, &value)) break; +#if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(key); +#endif + } + name = first_kw_arg; + while (*name && (**name != key)) name++; + if (*name) { + values[name-argnames] = value; +#if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(value); + Py_DECREF(key); +#endif + key = NULL; + value = NULL; + continue; + } +#if !CYTHON_AVOID_BORROWED_REFS + Py_INCREF(key); +#endif + Py_INCREF(value); + name = first_kw_arg; + #if PY_MAJOR_VERSION < 3 + if (likely(PyString_Check(key))) { + while (*name) { + if ((CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**name) == PyString_GET_SIZE(key)) + && _PyString_Eq(**name, key)) { + values[name-argnames] = value; +#if CYTHON_AVOID_BORROWED_REFS + value = NULL; +#endif + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + if ((**argname == key) || ( + (CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**argname) == PyString_GET_SIZE(key)) + && _PyString_Eq(**argname, key))) { + goto arg_passed_twice; + } + argname++; + } + } + } else + #endif + if (likely(PyUnicode_Check(key))) { + while (*name) { + int cmp = ( + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**name) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**name, key) + ); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) { + values[name-argnames] = value; +#if CYTHON_AVOID_BORROWED_REFS + value = NULL; +#endif + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + int cmp = (**argname == key) ? 0 : + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**argname) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**argname, key); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) goto arg_passed_twice; + argname++; + } + } + } else + goto invalid_keyword_type; + if (kwds2) { + if (unlikely(PyDict_SetItem(kwds2, key, value))) goto bad; + } else { + goto invalid_keyword; + } + } + Py_XDECREF(key); + Py_XDECREF(value); + return 0; +arg_passed_twice: + __Pyx_RaiseDoubleKeywordsError(function_name, key); + goto bad; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + goto bad; +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif +bad: + Py_XDECREF(key); + Py_XDECREF(value); + return -1; +} + +/* PyFunctionFastCall */ +#if CYTHON_FAST_PYCALL && !CYTHON_VECTORCALL +static PyObject* __Pyx_PyFunction_FastCallNoKw(PyCodeObject *co, PyObject **args, Py_ssize_t na, + PyObject *globals) { + PyFrameObject *f; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject **fastlocals; + Py_ssize_t i; + PyObject *result; + assert(globals != NULL); + /* XXX Perhaps we should create a specialized + PyFrame_New() that doesn't take locals, but does + take builtins without sanity checking them. + */ + assert(tstate != NULL); + f = PyFrame_New(tstate, co, globals, NULL); + if (f == NULL) { + return NULL; + } + fastlocals = __Pyx_PyFrame_GetLocalsplus(f); + for (i = 0; i < na; i++) { + Py_INCREF(*args); + fastlocals[i] = *args++; + } + result = PyEval_EvalFrameEx(f,0); + ++tstate->recursion_depth; + Py_DECREF(f); + --tstate->recursion_depth; + return result; +} +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs) { + PyCodeObject *co = (PyCodeObject *)PyFunction_GET_CODE(func); + PyObject *globals = PyFunction_GET_GLOBALS(func); + PyObject *argdefs = PyFunction_GET_DEFAULTS(func); + PyObject *closure; +#if PY_MAJOR_VERSION >= 3 + PyObject *kwdefs; +#endif + PyObject *kwtuple, **k; + PyObject **d; + Py_ssize_t nd; + Py_ssize_t nk; + PyObject *result; + assert(kwargs == NULL || PyDict_Check(kwargs)); + nk = kwargs ? PyDict_Size(kwargs) : 0; + #if PY_MAJOR_VERSION < 3 + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) { + return NULL; + } + #else + if (unlikely(Py_EnterRecursiveCall(" while calling a Python object"))) { + return NULL; + } + #endif + if ( +#if PY_MAJOR_VERSION >= 3 + co->co_kwonlyargcount == 0 && +#endif + likely(kwargs == NULL || nk == 0) && + co->co_flags == (CO_OPTIMIZED | CO_NEWLOCALS | CO_NOFREE)) { + if (argdefs == NULL && co->co_argcount == nargs) { + result = __Pyx_PyFunction_FastCallNoKw(co, args, nargs, globals); + goto done; + } + else if (nargs == 0 && argdefs != NULL + && co->co_argcount == Py_SIZE(argdefs)) { + /* function called with no arguments, but all parameters have + a default value: use default values as arguments .*/ + args = &PyTuple_GET_ITEM(argdefs, 0); + result =__Pyx_PyFunction_FastCallNoKw(co, args, Py_SIZE(argdefs), globals); + goto done; + } + } + if (kwargs != NULL) { + Py_ssize_t pos, i; + kwtuple = PyTuple_New(2 * nk); + if (kwtuple == NULL) { + result = NULL; + goto done; + } + k = &PyTuple_GET_ITEM(kwtuple, 0); + pos = i = 0; + while (PyDict_Next(kwargs, &pos, &k[i], &k[i+1])) { + Py_INCREF(k[i]); + Py_INCREF(k[i+1]); + i += 2; + } + nk = i / 2; + } + else { + kwtuple = NULL; + k = NULL; + } + closure = PyFunction_GET_CLOSURE(func); +#if PY_MAJOR_VERSION >= 3 + kwdefs = PyFunction_GET_KW_DEFAULTS(func); +#endif + if (argdefs != NULL) { + d = &PyTuple_GET_ITEM(argdefs, 0); + nd = Py_SIZE(argdefs); + } + else { + d = NULL; + nd = 0; + } +#if PY_MAJOR_VERSION >= 3 + result = PyEval_EvalCodeEx((PyObject*)co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, kwdefs, closure); +#else + result = PyEval_EvalCodeEx(co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, closure); +#endif + Py_XDECREF(kwtuple); +done: + Py_LeaveRecursiveCall(); + return result; +} +#endif + +/* PyObjectCall */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw) { + PyObject *result; + ternaryfunc call = Py_TYPE(func)->tp_call; + if (unlikely(!call)) + return PyObject_Call(func, arg, kw); + #if PY_MAJOR_VERSION < 3 + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + #else + if (unlikely(Py_EnterRecursiveCall(" while calling a Python object"))) + return NULL; + #endif + result = (*call)(func, arg, kw); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* PyObjectCallMethO */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg) { + PyObject *self, *result; + PyCFunction cfunc; + cfunc = __Pyx_CyOrPyCFunction_GET_FUNCTION(func); + self = __Pyx_CyOrPyCFunction_GET_SELF(func); + #if PY_MAJOR_VERSION < 3 + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + #else + if (unlikely(Py_EnterRecursiveCall(" while calling a Python object"))) + return NULL; + #endif + result = cfunc(self, arg); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* PyObjectFastCall */ +#if PY_VERSION_HEX < 0x03090000 || CYTHON_COMPILING_IN_LIMITED_API +static PyObject* __Pyx_PyObject_FastCall_fallback(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs) { + PyObject *argstuple; + PyObject *result = 0; + size_t i; + argstuple = PyTuple_New((Py_ssize_t)nargs); + if (unlikely(!argstuple)) return NULL; + for (i = 0; i < nargs; i++) { + Py_INCREF(args[i]); + if (__Pyx_PyTuple_SET_ITEM(argstuple, (Py_ssize_t)i, args[i]) < 0) goto bad; + } + result = __Pyx_PyObject_Call(func, argstuple, kwargs); + bad: + Py_DECREF(argstuple); + return result; +} +#endif +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t _nargs, PyObject *kwargs) { + Py_ssize_t nargs = __Pyx_PyVectorcall_NARGS(_nargs); +#if CYTHON_COMPILING_IN_CPYTHON + if (nargs == 0 && kwargs == NULL) { + if (__Pyx_CyOrPyCFunction_Check(func) && likely( __Pyx_CyOrPyCFunction_GET_FLAGS(func) & METH_NOARGS)) + return __Pyx_PyObject_CallMethO(func, NULL); + } + else if (nargs == 1 && kwargs == NULL) { + if (__Pyx_CyOrPyCFunction_Check(func) && likely( __Pyx_CyOrPyCFunction_GET_FLAGS(func) & METH_O)) + return __Pyx_PyObject_CallMethO(func, args[0]); + } +#endif + #if PY_VERSION_HEX < 0x030800B1 + #if CYTHON_FAST_PYCCALL + if (PyCFunction_Check(func)) { + if (kwargs) { + return _PyCFunction_FastCallDict(func, args, nargs, kwargs); + } else { + return _PyCFunction_FastCallKeywords(func, args, nargs, NULL); + } + } + #if PY_VERSION_HEX >= 0x030700A1 + if (!kwargs && __Pyx_IS_TYPE(func, &PyMethodDescr_Type)) { + return _PyMethodDescr_FastCallKeywords(func, args, nargs, NULL); + } + #endif + #endif + #if CYTHON_FAST_PYCALL + if (PyFunction_Check(func)) { + return __Pyx_PyFunction_FastCallDict(func, args, nargs, kwargs); + } + #endif + #endif + if (kwargs == NULL) { + #if CYTHON_VECTORCALL + #if PY_VERSION_HEX < 0x03090000 + vectorcallfunc f = _PyVectorcall_Function(func); + #else + vectorcallfunc f = PyVectorcall_Function(func); + #endif + if (f) { + return f(func, args, (size_t)nargs, NULL); + } + #elif defined(__Pyx_CyFunction_USED) && CYTHON_BACKPORT_VECTORCALL + if (__Pyx_CyFunction_CheckExact(func)) { + __pyx_vectorcallfunc f = __Pyx_CyFunction_func_vectorcall(func); + if (f) return f(func, args, (size_t)nargs, NULL); + } + #endif + } + if (nargs == 0) { + return __Pyx_PyObject_Call(func, __pyx_empty_tuple, kwargs); + } + #if PY_VERSION_HEX >= 0x03090000 && !CYTHON_COMPILING_IN_LIMITED_API + return PyObject_VectorcallDict(func, args, (size_t)nargs, kwargs); + #else + return __Pyx_PyObject_FastCall_fallback(func, args, (size_t)nargs, kwargs); + #endif +} + +/* PyObjectCallOneArg */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg) { + PyObject *args[2] = {NULL, arg}; + return __Pyx_PyObject_FastCall(func, args+1, 1 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* RaiseException */ +#if PY_MAJOR_VERSION < 3 +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + __Pyx_PyThreadState_declare + CYTHON_UNUSED_VAR(cause); + Py_XINCREF(type); + if (!value || value == Py_None) + value = NULL; + else + Py_INCREF(value); + if (!tb || tb == Py_None) + tb = NULL; + else { + Py_INCREF(tb); + if (!PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto raise_error; + } + } + if (PyType_Check(type)) { +#if CYTHON_COMPILING_IN_PYPY + if (!value) { + Py_INCREF(Py_None); + value = Py_None; + } +#endif + PyErr_NormalizeException(&type, &value, &tb); + } else { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto raise_error; + } + value = type; + type = (PyObject*) Py_TYPE(type); + Py_INCREF(type); + if (!PyType_IsSubtype((PyTypeObject *)type, (PyTypeObject *)PyExc_BaseException)) { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto raise_error; + } + } + __Pyx_PyThreadState_assign + __Pyx_ErrRestore(type, value, tb); + return; +raise_error: + Py_XDECREF(value); + Py_XDECREF(type); + Py_XDECREF(tb); + return; +} +#else +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + PyObject* owned_instance = NULL; + if (tb == Py_None) { + tb = 0; + } else if (tb && !PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto bad; + } + if (value == Py_None) + value = 0; + if (PyExceptionInstance_Check(type)) { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto bad; + } + value = type; + type = (PyObject*) Py_TYPE(value); + } else if (PyExceptionClass_Check(type)) { + PyObject *instance_class = NULL; + if (value && PyExceptionInstance_Check(value)) { + instance_class = (PyObject*) Py_TYPE(value); + if (instance_class != type) { + int is_subclass = PyObject_IsSubclass(instance_class, type); + if (!is_subclass) { + instance_class = NULL; + } else if (unlikely(is_subclass == -1)) { + goto bad; + } else { + type = instance_class; + } + } + } + if (!instance_class) { + PyObject *args; + if (!value) + args = PyTuple_New(0); + else if (PyTuple_Check(value)) { + Py_INCREF(value); + args = value; + } else + args = PyTuple_Pack(1, value); + if (!args) + goto bad; + owned_instance = PyObject_Call(type, args, NULL); + Py_DECREF(args); + if (!owned_instance) + goto bad; + value = owned_instance; + if (!PyExceptionInstance_Check(value)) { + PyErr_Format(PyExc_TypeError, + "calling %R should have returned an instance of " + "BaseException, not %R", + type, Py_TYPE(value)); + goto bad; + } + } + } else { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto bad; + } + if (cause) { + PyObject *fixed_cause; + if (cause == Py_None) { + fixed_cause = NULL; + } else if (PyExceptionClass_Check(cause)) { + fixed_cause = PyObject_CallObject(cause, NULL); + if (fixed_cause == NULL) + goto bad; + } else if (PyExceptionInstance_Check(cause)) { + fixed_cause = cause; + Py_INCREF(fixed_cause); + } else { + PyErr_SetString(PyExc_TypeError, + "exception causes must derive from " + "BaseException"); + goto bad; + } + PyException_SetCause(value, fixed_cause); + } + PyErr_SetObject(type, value); + if (tb) { + #if PY_VERSION_HEX >= 0x030C00A6 + PyException_SetTraceback(value, tb); + #elif CYTHON_FAST_THREAD_STATE + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject* tmp_tb = tstate->curexc_traceback; + if (tb != tmp_tb) { + Py_INCREF(tb); + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_tb); + } +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + PyErr_Fetch(&tmp_type, &tmp_value, &tmp_tb); + Py_INCREF(tb); + PyErr_Restore(tmp_type, tmp_value, tb); + Py_XDECREF(tmp_tb); +#endif + } +bad: + Py_XDECREF(owned_instance); + return; +} +#endif + +/* decode_c_bytes */ +static CYTHON_INLINE PyObject* __Pyx_decode_c_bytes( + const char* cstring, Py_ssize_t length, Py_ssize_t start, Py_ssize_t stop, + const char* encoding, const char* errors, + PyObject* (*decode_func)(const char *s, Py_ssize_t size, const char *errors)) { + if (unlikely((start < 0) | (stop < 0))) { + if (start < 0) { + start += length; + if (start < 0) + start = 0; + } + if (stop < 0) + stop += length; + } + if (stop > length) + stop = length; + if (unlikely(stop <= start)) + return __Pyx_NewRef(__pyx_empty_unicode); + length = stop - start; + cstring += start; + if (decode_func) { + return decode_func(cstring, length, errors); + } else { + return PyUnicode_Decode(cstring, length, encoding, errors); + } +} + +/* GetItemInt */ +static PyObject *__Pyx_GetItemInt_Generic(PyObject *o, PyObject* j) { + PyObject *r; + if (unlikely(!j)) return NULL; + r = PyObject_GetItem(o, j); + Py_DECREF(j); + return r; +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_List_Fast(PyObject *o, Py_ssize_t i, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + Py_ssize_t wrapped_i = i; + if (wraparound & unlikely(i < 0)) { + wrapped_i += PyList_GET_SIZE(o); + } + if ((!boundscheck) || likely(__Pyx_is_valid_index(wrapped_i, PyList_GET_SIZE(o)))) { + PyObject *r = PyList_GET_ITEM(o, wrapped_i); + Py_INCREF(r); + return r; + } + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +#else + return PySequence_GetItem(o, i); +#endif +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Tuple_Fast(PyObject *o, Py_ssize_t i, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + Py_ssize_t wrapped_i = i; + if (wraparound & unlikely(i < 0)) { + wrapped_i += PyTuple_GET_SIZE(o); + } + if ((!boundscheck) || likely(__Pyx_is_valid_index(wrapped_i, PyTuple_GET_SIZE(o)))) { + PyObject *r = PyTuple_GET_ITEM(o, wrapped_i); + Py_INCREF(r); + return r; + } + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +#else + return PySequence_GetItem(o, i); +#endif +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Fast(PyObject *o, Py_ssize_t i, int is_list, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS && CYTHON_USE_TYPE_SLOTS + if (is_list || PyList_CheckExact(o)) { + Py_ssize_t n = ((!wraparound) | likely(i >= 0)) ? i : i + PyList_GET_SIZE(o); + if ((!boundscheck) || (likely(__Pyx_is_valid_index(n, PyList_GET_SIZE(o))))) { + PyObject *r = PyList_GET_ITEM(o, n); + Py_INCREF(r); + return r; + } + } + else if (PyTuple_CheckExact(o)) { + Py_ssize_t n = ((!wraparound) | likely(i >= 0)) ? i : i + PyTuple_GET_SIZE(o); + if ((!boundscheck) || likely(__Pyx_is_valid_index(n, PyTuple_GET_SIZE(o)))) { + PyObject *r = PyTuple_GET_ITEM(o, n); + Py_INCREF(r); + return r; + } + } else { + PyMappingMethods *mm = Py_TYPE(o)->tp_as_mapping; + PySequenceMethods *sm = Py_TYPE(o)->tp_as_sequence; + if (mm && mm->mp_subscript) { + PyObject *r, *key = PyInt_FromSsize_t(i); + if (unlikely(!key)) return NULL; + r = mm->mp_subscript(o, key); + Py_DECREF(key); + return r; + } + if (likely(sm && sm->sq_item)) { + if (wraparound && unlikely(i < 0) && likely(sm->sq_length)) { + Py_ssize_t l = sm->sq_length(o); + if (likely(l >= 0)) { + i += l; + } else { + if (!PyErr_ExceptionMatches(PyExc_OverflowError)) + return NULL; + PyErr_Clear(); + } + } + return sm->sq_item(o, i); + } + } +#else + if (is_list || !PyMapping_Check(o)) { + return PySequence_GetItem(o, i); + } +#endif + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +} + +/* PyDictVersioning */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + return likely(dict) ? __PYX_GET_DICT_VERSION(dict) : 0; +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj) { + PyObject **dictptr = NULL; + Py_ssize_t offset = Py_TYPE(obj)->tp_dictoffset; + if (offset) { +#if CYTHON_COMPILING_IN_CPYTHON + dictptr = (likely(offset > 0)) ? (PyObject **) ((char *)obj + offset) : _PyObject_GetDictPtr(obj); +#else + dictptr = _PyObject_GetDictPtr(obj); +#endif + } + return (dictptr && *dictptr) ? __PYX_GET_DICT_VERSION(*dictptr) : 0; +} +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + if (unlikely(!dict) || unlikely(tp_dict_version != __PYX_GET_DICT_VERSION(dict))) + return 0; + return obj_dict_version == __Pyx_get_object_dict_version(obj); +} +#endif + +/* GetModuleGlobalName */ +#if CYTHON_USE_DICT_VERSIONS +static PyObject *__Pyx__GetModuleGlobalName(PyObject *name, PY_UINT64_T *dict_version, PyObject **dict_cached_value) +#else +static CYTHON_INLINE PyObject *__Pyx__GetModuleGlobalName(PyObject *name) +#endif +{ + PyObject *result; +#if !CYTHON_AVOID_BORROWED_REFS +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030500A1 && PY_VERSION_HEX < 0x030d0000 + result = _PyDict_GetItem_KnownHash(__pyx_d, name, ((PyASCIIObject *) name)->hash); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } else if (unlikely(PyErr_Occurred())) { + return NULL; + } +#elif CYTHON_COMPILING_IN_LIMITED_API + if (unlikely(!__pyx_m)) { + return NULL; + } + result = PyObject_GetAttr(__pyx_m, name); + if (likely(result)) { + return result; + } +#else + result = PyDict_GetItem(__pyx_d, name); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } +#endif +#else + result = PyObject_GetItem(__pyx_d, name); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } + PyErr_Clear(); +#endif + return __Pyx_GetBuiltinName(name); +} + +/* UnpackUnboundCMethod */ +static PyObject *__Pyx_SelflessCall(PyObject *method, PyObject *args, PyObject *kwargs) { + PyObject *result; + PyObject *selfless_args = PyTuple_GetSlice(args, 1, PyTuple_Size(args)); + if (unlikely(!selfless_args)) return NULL; + result = PyObject_Call(method, selfless_args, kwargs); + Py_DECREF(selfless_args); + return result; +} +static PyMethodDef __Pyx_UnboundCMethod_Def = { + "CythonUnboundCMethod", + __PYX_REINTERPRET_FUNCION(PyCFunction, __Pyx_SelflessCall), + METH_VARARGS | METH_KEYWORDS, + NULL +}; +static int __Pyx_TryUnpackUnboundCMethod(__Pyx_CachedCFunction* target) { + PyObject *method; + method = __Pyx_PyObject_GetAttrStr(target->type, *target->method_name); + if (unlikely(!method)) + return -1; + target->method = method; +#if CYTHON_COMPILING_IN_CPYTHON + #if PY_MAJOR_VERSION >= 3 + if (likely(__Pyx_TypeCheck(method, &PyMethodDescr_Type))) + #else + if (likely(!__Pyx_CyOrPyCFunction_Check(method))) + #endif + { + PyMethodDescrObject *descr = (PyMethodDescrObject*) method; + target->func = descr->d_method->ml_meth; + target->flag = descr->d_method->ml_flags & ~(METH_CLASS | METH_STATIC | METH_COEXIST | METH_STACKLESS); + } else +#endif +#if CYTHON_COMPILING_IN_PYPY +#else + if (PyCFunction_Check(method)) +#endif + { + PyObject *self; + int self_found; +#if CYTHON_COMPILING_IN_LIMITED_API || CYTHON_COMPILING_IN_PYPY + self = PyObject_GetAttrString(method, "__self__"); + if (!self) { + PyErr_Clear(); + } +#else + self = PyCFunction_GET_SELF(method); +#endif + self_found = (self && self != Py_None); +#if CYTHON_COMPILING_IN_LIMITED_API || CYTHON_COMPILING_IN_PYPY + Py_XDECREF(self); +#endif + if (self_found) { + PyObject *unbound_method = PyCFunction_New(&__Pyx_UnboundCMethod_Def, method); + if (unlikely(!unbound_method)) return -1; + Py_DECREF(method); + target->method = unbound_method; + } + } + return 0; +} + +/* CallUnboundCMethod1 */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_CallUnboundCMethod1(__Pyx_CachedCFunction* cfunc, PyObject* self, PyObject* arg) { + if (likely(cfunc->func)) { + int flag = cfunc->flag; + if (flag == METH_O) { + return (*(cfunc->func))(self, arg); + } else if ((PY_VERSION_HEX >= 0x030600B1) && flag == METH_FASTCALL) { + #if PY_VERSION_HEX >= 0x030700A0 + return (*(__Pyx_PyCFunctionFast)(void*)(PyCFunction)cfunc->func)(self, &arg, 1); + #else + return (*(__Pyx_PyCFunctionFastWithKeywords)(void*)(PyCFunction)cfunc->func)(self, &arg, 1, NULL); + #endif + } else if ((PY_VERSION_HEX >= 0x030700A0) && flag == (METH_FASTCALL | METH_KEYWORDS)) { + return (*(__Pyx_PyCFunctionFastWithKeywords)(void*)(PyCFunction)cfunc->func)(self, &arg, 1, NULL); + } + } + return __Pyx__CallUnboundCMethod1(cfunc, self, arg); +} +#endif +static PyObject* __Pyx__CallUnboundCMethod1(__Pyx_CachedCFunction* cfunc, PyObject* self, PyObject* arg){ + PyObject *args, *result = NULL; + if (unlikely(!cfunc->func && !cfunc->method) && unlikely(__Pyx_TryUnpackUnboundCMethod(cfunc) < 0)) return NULL; +#if CYTHON_COMPILING_IN_CPYTHON + if (cfunc->func && (cfunc->flag & METH_VARARGS)) { + args = PyTuple_New(1); + if (unlikely(!args)) goto bad; + Py_INCREF(arg); + PyTuple_SET_ITEM(args, 0, arg); + if (cfunc->flag & METH_KEYWORDS) + result = (*(PyCFunctionWithKeywords)(void*)(PyCFunction)cfunc->func)(self, args, NULL); + else + result = (*cfunc->func)(self, args); + } else { + args = PyTuple_New(2); + if (unlikely(!args)) goto bad; + Py_INCREF(self); + PyTuple_SET_ITEM(args, 0, self); + Py_INCREF(arg); + PyTuple_SET_ITEM(args, 1, arg); + result = __Pyx_PyObject_Call(cfunc->method, args, NULL); + } +#else + args = PyTuple_Pack(2, self, arg); + if (unlikely(!args)) goto bad; + result = __Pyx_PyObject_Call(cfunc->method, args, NULL); +#endif +bad: + Py_XDECREF(args); + return result; +} + +/* CallUnboundCMethod2 */ +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030600B1 +static CYTHON_INLINE PyObject *__Pyx_CallUnboundCMethod2(__Pyx_CachedCFunction *cfunc, PyObject *self, PyObject *arg1, PyObject *arg2) { + if (likely(cfunc->func)) { + PyObject *args[2] = {arg1, arg2}; + if (cfunc->flag == METH_FASTCALL) { + #if PY_VERSION_HEX >= 0x030700A0 + return (*(__Pyx_PyCFunctionFast)(void*)(PyCFunction)cfunc->func)(self, args, 2); + #else + return (*(__Pyx_PyCFunctionFastWithKeywords)(void*)(PyCFunction)cfunc->func)(self, args, 2, NULL); + #endif + } + #if PY_VERSION_HEX >= 0x030700A0 + if (cfunc->flag == (METH_FASTCALL | METH_KEYWORDS)) + return (*(__Pyx_PyCFunctionFastWithKeywords)(void*)(PyCFunction)cfunc->func)(self, args, 2, NULL); + #endif + } + return __Pyx__CallUnboundCMethod2(cfunc, self, arg1, arg2); +} +#endif +static PyObject* __Pyx__CallUnboundCMethod2(__Pyx_CachedCFunction* cfunc, PyObject* self, PyObject* arg1, PyObject* arg2){ + PyObject *args, *result = NULL; + if (unlikely(!cfunc->func && !cfunc->method) && unlikely(__Pyx_TryUnpackUnboundCMethod(cfunc) < 0)) return NULL; +#if CYTHON_COMPILING_IN_CPYTHON + if (cfunc->func && (cfunc->flag & METH_VARARGS)) { + args = PyTuple_New(2); + if (unlikely(!args)) goto bad; + Py_INCREF(arg1); + PyTuple_SET_ITEM(args, 0, arg1); + Py_INCREF(arg2); + PyTuple_SET_ITEM(args, 1, arg2); + if (cfunc->flag & METH_KEYWORDS) + result = (*(PyCFunctionWithKeywords)(void*)(PyCFunction)cfunc->func)(self, args, NULL); + else + result = (*cfunc->func)(self, args); + } else { + args = PyTuple_New(3); + if (unlikely(!args)) goto bad; + Py_INCREF(self); + PyTuple_SET_ITEM(args, 0, self); + Py_INCREF(arg1); + PyTuple_SET_ITEM(args, 1, arg1); + Py_INCREF(arg2); + PyTuple_SET_ITEM(args, 2, arg2); + result = __Pyx_PyObject_Call(cfunc->method, args, NULL); + } +#else + args = PyTuple_Pack(3, self, arg1, arg2); + if (unlikely(!args)) goto bad; + result = __Pyx_PyObject_Call(cfunc->method, args, NULL); +#endif +bad: + Py_XDECREF(args); + return result; +} + +/* dict_getitem_default */ +static PyObject* __Pyx_PyDict_GetItemDefault(PyObject* d, PyObject* key, PyObject* default_value) { + PyObject* value; +#if PY_MAJOR_VERSION >= 3 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07020000) + value = PyDict_GetItemWithError(d, key); + if (unlikely(!value)) { + if (unlikely(PyErr_Occurred())) + return NULL; + value = default_value; + } + Py_INCREF(value); + if ((1)); +#else + if (PyString_CheckExact(key) || PyUnicode_CheckExact(key) || PyInt_CheckExact(key)) { + value = PyDict_GetItem(d, key); + if (unlikely(!value)) { + value = default_value; + } + Py_INCREF(value); + } +#endif + else { + if (default_value == Py_None) + value = __Pyx_CallUnboundCMethod1(&__pyx_umethod_PyDict_Type_get, d, key); + else + value = __Pyx_CallUnboundCMethod2(&__pyx_umethod_PyDict_Type_get, d, key, default_value); + } + return value; +} + +/* JoinPyUnicode */ +static PyObject* __Pyx_PyUnicode_Join(PyObject* value_tuple, Py_ssize_t value_count, Py_ssize_t result_ulength, + Py_UCS4 max_char) { +#if CYTHON_USE_UNICODE_INTERNALS && CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + PyObject *result_uval; + int result_ukind, kind_shift; + Py_ssize_t i, char_pos; + void *result_udata; + CYTHON_MAYBE_UNUSED_VAR(max_char); +#if CYTHON_PEP393_ENABLED + result_uval = PyUnicode_New(result_ulength, max_char); + if (unlikely(!result_uval)) return NULL; + result_ukind = (max_char <= 255) ? PyUnicode_1BYTE_KIND : (max_char <= 65535) ? PyUnicode_2BYTE_KIND : PyUnicode_4BYTE_KIND; + kind_shift = (result_ukind == PyUnicode_4BYTE_KIND) ? 2 : result_ukind - 1; + result_udata = PyUnicode_DATA(result_uval); +#else + result_uval = PyUnicode_FromUnicode(NULL, result_ulength); + if (unlikely(!result_uval)) return NULL; + result_ukind = sizeof(Py_UNICODE); + kind_shift = (result_ukind == 4) ? 2 : result_ukind - 1; + result_udata = PyUnicode_AS_UNICODE(result_uval); +#endif + assert(kind_shift == 2 || kind_shift == 1 || kind_shift == 0); + char_pos = 0; + for (i=0; i < value_count; i++) { + int ukind; + Py_ssize_t ulength; + void *udata; + PyObject *uval = PyTuple_GET_ITEM(value_tuple, i); + if (unlikely(__Pyx_PyUnicode_READY(uval))) + goto bad; + ulength = __Pyx_PyUnicode_GET_LENGTH(uval); + if (unlikely(!ulength)) + continue; + if (unlikely((PY_SSIZE_T_MAX >> kind_shift) - ulength < char_pos)) + goto overflow; + ukind = __Pyx_PyUnicode_KIND(uval); + udata = __Pyx_PyUnicode_DATA(uval); + if (!CYTHON_PEP393_ENABLED || ukind == result_ukind) { + memcpy((char *)result_udata + (char_pos << kind_shift), udata, (size_t) (ulength << kind_shift)); + } else { + #if PY_VERSION_HEX >= 0x030d0000 + if (unlikely(PyUnicode_CopyCharacters(result_uval, char_pos, uval, 0, ulength) < 0)) goto bad; + #elif CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030300F0 || defined(_PyUnicode_FastCopyCharacters) + _PyUnicode_FastCopyCharacters(result_uval, char_pos, uval, 0, ulength); + #else + Py_ssize_t j; + for (j=0; j < ulength; j++) { + Py_UCS4 uchar = __Pyx_PyUnicode_READ(ukind, udata, j); + __Pyx_PyUnicode_WRITE(result_ukind, result_udata, char_pos+j, uchar); + } + #endif + } + char_pos += ulength; + } + return result_uval; +overflow: + PyErr_SetString(PyExc_OverflowError, "join() result is too long for a Python string"); +bad: + Py_DECREF(result_uval); + return NULL; +#else + CYTHON_UNUSED_VAR(max_char); + CYTHON_UNUSED_VAR(result_ulength); + CYTHON_UNUSED_VAR(value_count); + return PyUnicode_Join(__pyx_empty_unicode, value_tuple); +#endif +} + +/* DictGetItem */ +#if PY_MAJOR_VERSION >= 3 && !CYTHON_COMPILING_IN_PYPY +static PyObject *__Pyx_PyDict_GetItem(PyObject *d, PyObject* key) { + PyObject *value; + value = PyDict_GetItemWithError(d, key); + if (unlikely(!value)) { + if (!PyErr_Occurred()) { + if (unlikely(PyTuple_Check(key))) { + PyObject* args = PyTuple_Pack(1, key); + if (likely(args)) { + PyErr_SetObject(PyExc_KeyError, args); + Py_DECREF(args); + } + } else { + PyErr_SetObject(PyExc_KeyError, key); + } + } + return NULL; + } + Py_INCREF(value); + return value; +} +#endif + +/* PyObjectCallNoArg */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func) { + PyObject *arg[2] = {NULL, NULL}; + return __Pyx_PyObject_FastCall(func, arg + 1, 0 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* PyObjectGetMethod */ +static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method) { + PyObject *attr; +#if CYTHON_UNPACK_METHODS && CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_PYTYPE_LOOKUP + __Pyx_TypeName type_name; + PyTypeObject *tp = Py_TYPE(obj); + PyObject *descr; + descrgetfunc f = NULL; + PyObject **dictptr, *dict; + int meth_found = 0; + assert (*method == NULL); + if (unlikely(tp->tp_getattro != PyObject_GenericGetAttr)) { + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; + } + if (unlikely(tp->tp_dict == NULL) && unlikely(PyType_Ready(tp) < 0)) { + return 0; + } + descr = _PyType_Lookup(tp, name); + if (likely(descr != NULL)) { + Py_INCREF(descr); +#if defined(Py_TPFLAGS_METHOD_DESCRIPTOR) && Py_TPFLAGS_METHOD_DESCRIPTOR + if (__Pyx_PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_METHOD_DESCRIPTOR)) +#elif PY_MAJOR_VERSION >= 3 + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type))) + #endif +#else + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr))) + #endif +#endif + { + meth_found = 1; + } else { + f = Py_TYPE(descr)->tp_descr_get; + if (f != NULL && PyDescr_IsData(descr)) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + } + } + dictptr = _PyObject_GetDictPtr(obj); + if (dictptr != NULL && (dict = *dictptr) != NULL) { + Py_INCREF(dict); + attr = __Pyx_PyDict_GetItemStr(dict, name); + if (attr != NULL) { + Py_INCREF(attr); + Py_DECREF(dict); + Py_XDECREF(descr); + goto try_unpack; + } + Py_DECREF(dict); + } + if (meth_found) { + *method = descr; + return 1; + } + if (f != NULL) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + if (likely(descr != NULL)) { + *method = descr; + return 0; + } + type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return 0; +#else + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; +#endif +try_unpack: +#if CYTHON_UNPACK_METHODS + if (likely(attr) && PyMethod_Check(attr) && likely(PyMethod_GET_SELF(attr) == obj)) { + PyObject *function = PyMethod_GET_FUNCTION(attr); + Py_INCREF(function); + Py_DECREF(attr); + *method = function; + return 1; + } +#endif + *method = attr; + return 0; +} + +/* PyObjectCallMethod0 */ +static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name) { + PyObject *method = NULL, *result = NULL; + int is_method = __Pyx_PyObject_GetMethod(obj, method_name, &method); + if (likely(is_method)) { + result = __Pyx_PyObject_CallOneArg(method, obj); + Py_DECREF(method); + return result; + } + if (unlikely(!method)) goto bad; + result = __Pyx_PyObject_CallNoArg(method); + Py_DECREF(method); +bad: + return result; +} + +/* RaiseNoneIterError */ +static CYTHON_INLINE void __Pyx_RaiseNoneNotIterableError(void) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not iterable"); +} + +/* UnpackTupleError */ +static void __Pyx_UnpackTupleError(PyObject *t, Py_ssize_t index) { + if (t == Py_None) { + __Pyx_RaiseNoneNotIterableError(); + } else if (PyTuple_GET_SIZE(t) < index) { + __Pyx_RaiseNeedMoreValuesError(PyTuple_GET_SIZE(t)); + } else { + __Pyx_RaiseTooManyValuesError(index); + } +} + +/* UnpackTuple2 */ +static CYTHON_INLINE int __Pyx_unpack_tuple2_exact( + PyObject* tuple, PyObject** pvalue1, PyObject** pvalue2, int decref_tuple) { + PyObject *value1 = NULL, *value2 = NULL; +#if CYTHON_COMPILING_IN_PYPY + value1 = PySequence_ITEM(tuple, 0); if (unlikely(!value1)) goto bad; + value2 = PySequence_ITEM(tuple, 1); if (unlikely(!value2)) goto bad; +#else + value1 = PyTuple_GET_ITEM(tuple, 0); Py_INCREF(value1); + value2 = PyTuple_GET_ITEM(tuple, 1); Py_INCREF(value2); +#endif + if (decref_tuple) { + Py_DECREF(tuple); + } + *pvalue1 = value1; + *pvalue2 = value2; + return 0; +#if CYTHON_COMPILING_IN_PYPY +bad: + Py_XDECREF(value1); + Py_XDECREF(value2); + if (decref_tuple) { Py_XDECREF(tuple); } + return -1; +#endif +} +static int __Pyx_unpack_tuple2_generic(PyObject* tuple, PyObject** pvalue1, PyObject** pvalue2, + int has_known_size, int decref_tuple) { + Py_ssize_t index; + PyObject *value1 = NULL, *value2 = NULL, *iter = NULL; + iternextfunc iternext; + iter = PyObject_GetIter(tuple); + if (unlikely(!iter)) goto bad; + if (decref_tuple) { Py_DECREF(tuple); tuple = NULL; } + iternext = __Pyx_PyObject_GetIterNextFunc(iter); + value1 = iternext(iter); if (unlikely(!value1)) { index = 0; goto unpacking_failed; } + value2 = iternext(iter); if (unlikely(!value2)) { index = 1; goto unpacking_failed; } + if (!has_known_size && unlikely(__Pyx_IternextUnpackEndCheck(iternext(iter), 2))) goto bad; + Py_DECREF(iter); + *pvalue1 = value1; + *pvalue2 = value2; + return 0; +unpacking_failed: + if (!has_known_size && __Pyx_IterFinish() == 0) + __Pyx_RaiseNeedMoreValuesError(index); +bad: + Py_XDECREF(iter); + Py_XDECREF(value1); + Py_XDECREF(value2); + if (decref_tuple) { Py_XDECREF(tuple); } + return -1; +} + +/* dict_iter */ +#if CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 +#include +#endif +static CYTHON_INLINE PyObject* __Pyx_dict_iterator(PyObject* iterable, int is_dict, PyObject* method_name, + Py_ssize_t* p_orig_length, int* p_source_is_dict) { + is_dict = is_dict || likely(PyDict_CheckExact(iterable)); + *p_source_is_dict = is_dict; + if (is_dict) { +#if !CYTHON_COMPILING_IN_PYPY + *p_orig_length = PyDict_Size(iterable); + Py_INCREF(iterable); + return iterable; +#elif PY_MAJOR_VERSION >= 3 + static PyObject *py_items = NULL, *py_keys = NULL, *py_values = NULL; + PyObject **pp = NULL; + if (method_name) { + const char *name = PyUnicode_AsUTF8(method_name); + if (strcmp(name, "iteritems") == 0) pp = &py_items; + else if (strcmp(name, "iterkeys") == 0) pp = &py_keys; + else if (strcmp(name, "itervalues") == 0) pp = &py_values; + if (pp) { + if (!*pp) { + *pp = PyUnicode_FromString(name + 4); + if (!*pp) + return NULL; + } + method_name = *pp; + } + } +#endif + } + *p_orig_length = 0; + if (method_name) { + PyObject* iter; + iterable = __Pyx_PyObject_CallMethod0(iterable, method_name); + if (!iterable) + return NULL; +#if !CYTHON_COMPILING_IN_PYPY + if (PyTuple_CheckExact(iterable) || PyList_CheckExact(iterable)) + return iterable; +#endif + iter = PyObject_GetIter(iterable); + Py_DECREF(iterable); + return iter; + } + return PyObject_GetIter(iterable); +} +static CYTHON_INLINE int __Pyx_dict_iter_next( + PyObject* iter_obj, CYTHON_NCP_UNUSED Py_ssize_t orig_length, CYTHON_NCP_UNUSED Py_ssize_t* ppos, + PyObject** pkey, PyObject** pvalue, PyObject** pitem, int source_is_dict) { + PyObject* next_item; +#if !CYTHON_COMPILING_IN_PYPY + if (source_is_dict) { + PyObject *key, *value; + if (unlikely(orig_length != PyDict_Size(iter_obj))) { + PyErr_SetString(PyExc_RuntimeError, "dictionary changed size during iteration"); + return -1; + } + if (unlikely(!PyDict_Next(iter_obj, ppos, &key, &value))) { + return 0; + } + if (pitem) { + PyObject* tuple = PyTuple_New(2); + if (unlikely(!tuple)) { + return -1; + } + Py_INCREF(key); + Py_INCREF(value); + PyTuple_SET_ITEM(tuple, 0, key); + PyTuple_SET_ITEM(tuple, 1, value); + *pitem = tuple; + } else { + if (pkey) { + Py_INCREF(key); + *pkey = key; + } + if (pvalue) { + Py_INCREF(value); + *pvalue = value; + } + } + return 1; + } else if (PyTuple_CheckExact(iter_obj)) { + Py_ssize_t pos = *ppos; + if (unlikely(pos >= PyTuple_GET_SIZE(iter_obj))) return 0; + *ppos = pos + 1; + next_item = PyTuple_GET_ITEM(iter_obj, pos); + Py_INCREF(next_item); + } else if (PyList_CheckExact(iter_obj)) { + Py_ssize_t pos = *ppos; + if (unlikely(pos >= PyList_GET_SIZE(iter_obj))) return 0; + *ppos = pos + 1; + next_item = PyList_GET_ITEM(iter_obj, pos); + Py_INCREF(next_item); + } else +#endif + { + next_item = PyIter_Next(iter_obj); + if (unlikely(!next_item)) { + return __Pyx_IterFinish(); + } + } + if (pitem) { + *pitem = next_item; + } else if (pkey && pvalue) { + if (__Pyx_unpack_tuple2(next_item, pkey, pvalue, source_is_dict, source_is_dict, 1)) + return -1; + } else if (pkey) { + *pkey = next_item; + } else { + *pvalue = next_item; + } + return 1; +} + +/* KeywordStringCheck */ +static int __Pyx_CheckKeywordStrings( + PyObject *kw, + const char* function_name, + int kw_allowed) +{ + PyObject* key = 0; + Py_ssize_t pos = 0; +#if CYTHON_COMPILING_IN_PYPY + if (!kw_allowed && PyDict_Next(kw, &pos, &key, 0)) + goto invalid_keyword; + return 1; +#else + if (CYTHON_METH_FASTCALL && likely(PyTuple_Check(kw))) { + Py_ssize_t kwsize; +#if CYTHON_ASSUME_SAFE_MACROS + kwsize = PyTuple_GET_SIZE(kw); +#else + kwsize = PyTuple_Size(kw); + if (kwsize < 0) return 0; +#endif + if (unlikely(kwsize == 0)) + return 1; + if (!kw_allowed) { +#if CYTHON_ASSUME_SAFE_MACROS + key = PyTuple_GET_ITEM(kw, 0); +#else + key = PyTuple_GetItem(kw, pos); + if (!key) return 0; +#endif + goto invalid_keyword; + } +#if PY_VERSION_HEX < 0x03090000 + for (pos = 0; pos < kwsize; pos++) { +#if CYTHON_ASSUME_SAFE_MACROS + key = PyTuple_GET_ITEM(kw, pos); +#else + key = PyTuple_GetItem(kw, pos); + if (!key) return 0; +#endif + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } +#endif + return 1; + } + while (PyDict_Next(kw, &pos, &key, 0)) { + #if PY_MAJOR_VERSION < 3 + if (unlikely(!PyString_Check(key))) + #endif + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } + if (!kw_allowed && unlikely(key)) + goto invalid_keyword; + return 1; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + return 0; +#endif +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif + return 0; +} + +/* ObjectGetItem */ +#if CYTHON_USE_TYPE_SLOTS +static PyObject *__Pyx_PyObject_GetIndex(PyObject *obj, PyObject *index) { + PyObject *runerr = NULL; + Py_ssize_t key_value; + key_value = __Pyx_PyIndex_AsSsize_t(index); + if (likely(key_value != -1 || !(runerr = PyErr_Occurred()))) { + return __Pyx_GetItemInt_Fast(obj, key_value, 0, 1, 1); + } + if (PyErr_GivenExceptionMatches(runerr, PyExc_OverflowError)) { + __Pyx_TypeName index_type_name = __Pyx_PyType_GetName(Py_TYPE(index)); + PyErr_Clear(); + PyErr_Format(PyExc_IndexError, + "cannot fit '" __Pyx_FMT_TYPENAME "' into an index-sized integer", index_type_name); + __Pyx_DECREF_TypeName(index_type_name); + } + return NULL; +} +static PyObject *__Pyx_PyObject_GetItem_Slow(PyObject *obj, PyObject *key) { + __Pyx_TypeName obj_type_name; + if (likely(PyType_Check(obj))) { + PyObject *meth = __Pyx_PyObject_GetAttrStrNoError(obj, __pyx_n_s_class_getitem); + if (!meth) { + PyErr_Clear(); + } else { + PyObject *result = __Pyx_PyObject_CallOneArg(meth, key); + Py_DECREF(meth); + return result; + } + } + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "'" __Pyx_FMT_TYPENAME "' object is not subscriptable", obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return NULL; +} +static PyObject *__Pyx_PyObject_GetItem(PyObject *obj, PyObject *key) { + PyTypeObject *tp = Py_TYPE(obj); + PyMappingMethods *mm = tp->tp_as_mapping; + PySequenceMethods *sm = tp->tp_as_sequence; + if (likely(mm && mm->mp_subscript)) { + return mm->mp_subscript(obj, key); + } + if (likely(sm && sm->sq_item)) { + return __Pyx_PyObject_GetIndex(obj, key); + } + return __Pyx_PyObject_GetItem_Slow(obj, key); +} +#endif + +/* RaiseUnexpectedTypeError */ +static int +__Pyx_RaiseUnexpectedTypeError(const char *expected, PyObject *obj) +{ + __Pyx_TypeName obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, "Expected %s, got " __Pyx_FMT_TYPENAME, + expected, obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return 0; +} + +/* FixUpExtensionType */ +#if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type) { +#if PY_VERSION_HEX > 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + CYTHON_UNUSED_VAR(spec); + CYTHON_UNUSED_VAR(type); +#else + const PyType_Slot *slot = spec->slots; + while (slot && slot->slot && slot->slot != Py_tp_members) + slot++; + if (slot && slot->slot == Py_tp_members) { + int changed = 0; +#if !(PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON) + const +#endif + PyMemberDef *memb = (PyMemberDef*) slot->pfunc; + while (memb && memb->name) { + if (memb->name[0] == '_' && memb->name[1] == '_') { +#if PY_VERSION_HEX < 0x030900b1 + if (strcmp(memb->name, "__weaklistoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_weaklistoffset = memb->offset; + changed = 1; + } + else if (strcmp(memb->name, "__dictoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_dictoffset = memb->offset; + changed = 1; + } +#if CYTHON_METH_FASTCALL + else if (strcmp(memb->name, "__vectorcalloffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); +#if PY_VERSION_HEX >= 0x030800b4 + type->tp_vectorcall_offset = memb->offset; +#else + type->tp_print = (printfunc) memb->offset; +#endif + changed = 1; + } +#endif +#else + if ((0)); +#endif +#if PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON + else if (strcmp(memb->name, "__module__") == 0) { + PyObject *descr; + assert(memb->type == T_OBJECT); + assert(memb->flags == 0 || memb->flags == READONLY); + descr = PyDescr_NewMember(type, memb); + if (unlikely(!descr)) + return -1; + if (unlikely(PyDict_SetItem(type->tp_dict, PyDescr_NAME(descr), descr) < 0)) { + Py_DECREF(descr); + return -1; + } + Py_DECREF(descr); + changed = 1; + } +#endif + } + memb++; + } + if (changed) + PyType_Modified(type); + } +#endif + return 0; +} +#endif + +/* ValidateBasesTuple */ +#if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases) { + Py_ssize_t i, n; +#if CYTHON_ASSUME_SAFE_MACROS + n = PyTuple_GET_SIZE(bases); +#else + n = PyTuple_Size(bases); + if (n < 0) return -1; +#endif + for (i = 1; i < n; i++) + { +#if CYTHON_AVOID_BORROWED_REFS + PyObject *b0 = PySequence_GetItem(bases, i); + if (!b0) return -1; +#elif CYTHON_ASSUME_SAFE_MACROS + PyObject *b0 = PyTuple_GET_ITEM(bases, i); +#else + PyObject *b0 = PyTuple_GetItem(bases, i); + if (!b0) return -1; +#endif + PyTypeObject *b; +#if PY_MAJOR_VERSION < 3 + if (PyClass_Check(b0)) + { + PyErr_Format(PyExc_TypeError, "base class '%.200s' is an old-style class", + PyString_AS_STRING(((PyClassObject*)b0)->cl_name)); +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + return -1; + } +#endif + b = (PyTypeObject*) b0; + if (!__Pyx_PyType_HasFeature(b, Py_TPFLAGS_HEAPTYPE)) + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "base class '" __Pyx_FMT_TYPENAME "' is not a heap type", b_name); + __Pyx_DECREF_TypeName(b_name); +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + return -1; + } + if (dictoffset == 0) + { + Py_ssize_t b_dictoffset = 0; +#if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + b_dictoffset = b->tp_dictoffset; +#else + PyObject *py_b_dictoffset = PyObject_GetAttrString((PyObject*)b, "__dictoffset__"); + if (!py_b_dictoffset) goto dictoffset_return; + b_dictoffset = PyLong_AsSsize_t(py_b_dictoffset); + Py_DECREF(py_b_dictoffset); + if (b_dictoffset == -1 && PyErr_Occurred()) goto dictoffset_return; +#endif + if (b_dictoffset) { + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "extension type '%.200s' has no __dict__ slot, " + "but base type '" __Pyx_FMT_TYPENAME "' has: " + "either add 'cdef dict __dict__' to the extension type " + "or add '__slots__ = [...]' to the base type", + type_name, b_name); + __Pyx_DECREF_TypeName(b_name); + } +#if !(CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY) + dictoffset_return: +#endif +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + return -1; + } + } +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + } + return 0; +} +#endif + +/* PyType_Ready */ +static int __Pyx_PyType_Ready(PyTypeObject *t) { +#if CYTHON_USE_TYPE_SPECS || !(CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API) || defined(PYSTON_MAJOR_VERSION) + (void)__Pyx_PyObject_CallMethod0; +#if CYTHON_USE_TYPE_SPECS + (void)__Pyx_validate_bases_tuple; +#endif + return PyType_Ready(t); +#else + int r; + PyObject *bases = __Pyx_PyType_GetSlot(t, tp_bases, PyObject*); + if (bases && unlikely(__Pyx_validate_bases_tuple(t->tp_name, t->tp_dictoffset, bases) == -1)) + return -1; +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + { + int gc_was_enabled; + #if PY_VERSION_HEX >= 0x030A00b1 + gc_was_enabled = PyGC_Disable(); + (void)__Pyx_PyObject_CallMethod0; + #else + PyObject *ret, *py_status; + PyObject *gc = NULL; + #if PY_VERSION_HEX >= 0x030700a1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM+0 >= 0x07030400) + gc = PyImport_GetModule(__pyx_kp_u_gc); + #endif + if (unlikely(!gc)) gc = PyImport_Import(__pyx_kp_u_gc); + if (unlikely(!gc)) return -1; + py_status = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_isenabled); + if (unlikely(!py_status)) { + Py_DECREF(gc); + return -1; + } + gc_was_enabled = __Pyx_PyObject_IsTrue(py_status); + Py_DECREF(py_status); + if (gc_was_enabled > 0) { + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_disable); + if (unlikely(!ret)) { + Py_DECREF(gc); + return -1; + } + Py_DECREF(ret); + } else if (unlikely(gc_was_enabled == -1)) { + Py_DECREF(gc); + return -1; + } + #endif + t->tp_flags |= Py_TPFLAGS_HEAPTYPE; +#if PY_VERSION_HEX >= 0x030A0000 + t->tp_flags |= Py_TPFLAGS_IMMUTABLETYPE; +#endif +#else + (void)__Pyx_PyObject_CallMethod0; +#endif + r = PyType_Ready(t); +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + t->tp_flags &= ~Py_TPFLAGS_HEAPTYPE; + #if PY_VERSION_HEX >= 0x030A00b1 + if (gc_was_enabled) + PyGC_Enable(); + #else + if (gc_was_enabled) { + PyObject *tp, *v, *tb; + PyErr_Fetch(&tp, &v, &tb); + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_enable); + if (likely(ret || r == -1)) { + Py_XDECREF(ret); + PyErr_Restore(tp, v, tb); + } else { + Py_XDECREF(tp); + Py_XDECREF(v); + Py_XDECREF(tb); + r = -1; + } + } + Py_DECREF(gc); + #endif + } +#endif + return r; +#endif +} + +/* PyObject_GenericGetAttrNoDict */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject *__Pyx_RaiseGenericGetAttributeError(PyTypeObject *tp, PyObject *attr_name) { + __Pyx_TypeName type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, attr_name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(attr_name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name) { + PyObject *descr; + PyTypeObject *tp = Py_TYPE(obj); + if (unlikely(!PyString_Check(attr_name))) { + return PyObject_GenericGetAttr(obj, attr_name); + } + assert(!tp->tp_dictoffset); + descr = _PyType_Lookup(tp, attr_name); + if (unlikely(!descr)) { + return __Pyx_RaiseGenericGetAttributeError(tp, attr_name); + } + Py_INCREF(descr); + #if PY_MAJOR_VERSION < 3 + if (likely(PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_HAVE_CLASS))) + #endif + { + descrgetfunc f = Py_TYPE(descr)->tp_descr_get; + if (unlikely(f)) { + PyObject *res = f(descr, obj, (PyObject *)tp); + Py_DECREF(descr); + return res; + } + } + return descr; +} +#endif + +/* PyObject_GenericGetAttr */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name) { + if (unlikely(Py_TYPE(obj)->tp_dictoffset)) { + return PyObject_GenericGetAttr(obj, attr_name); + } + return __Pyx_PyObject_GenericGetAttrNoDict(obj, attr_name); +} +#endif + +/* SetupReduce */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce_is_named(PyObject* meth, PyObject* name) { + int ret; + PyObject *name_attr; + name_attr = __Pyx_PyObject_GetAttrStrNoError(meth, __pyx_n_s_name); + if (likely(name_attr)) { + ret = PyObject_RichCompareBool(name_attr, name, Py_EQ); + } else { + ret = -1; + } + if (unlikely(ret < 0)) { + PyErr_Clear(); + ret = 0; + } + Py_XDECREF(name_attr); + return ret; +} +static int __Pyx_setup_reduce(PyObject* type_obj) { + int ret = 0; + PyObject *object_reduce = NULL; + PyObject *object_getstate = NULL; + PyObject *object_reduce_ex = NULL; + PyObject *reduce = NULL; + PyObject *reduce_ex = NULL; + PyObject *reduce_cython = NULL; + PyObject *setstate = NULL; + PyObject *setstate_cython = NULL; + PyObject *getstate = NULL; +#if CYTHON_USE_PYTYPE_LOOKUP + getstate = _PyType_Lookup((PyTypeObject*)type_obj, __pyx_n_s_getstate); +#else + getstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_getstate); + if (!getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (getstate) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_getstate = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_getstate); +#else + object_getstate = __Pyx_PyObject_GetAttrStrNoError((PyObject*)&PyBaseObject_Type, __pyx_n_s_getstate); + if (!object_getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (object_getstate != getstate) { + goto __PYX_GOOD; + } + } +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce_ex = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#else + object_reduce_ex = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#endif + reduce_ex = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce_ex); if (unlikely(!reduce_ex)) goto __PYX_BAD; + if (reduce_ex == object_reduce_ex) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#else + object_reduce = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#endif + reduce = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce); if (unlikely(!reduce)) goto __PYX_BAD; + if (reduce == object_reduce || __Pyx_setup_reduce_is_named(reduce, __pyx_n_s_reduce_cython)) { + reduce_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_reduce_cython); + if (likely(reduce_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce, reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (reduce == object_reduce || PyErr_Occurred()) { + goto __PYX_BAD; + } + setstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate); + if (!setstate) PyErr_Clear(); + if (!setstate || __Pyx_setup_reduce_is_named(setstate, __pyx_n_s_setstate_cython)) { + setstate_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate_cython); + if (likely(setstate_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate, setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (!setstate || PyErr_Occurred()) { + goto __PYX_BAD; + } + } + PyType_Modified((PyTypeObject*)type_obj); + } + } + goto __PYX_GOOD; +__PYX_BAD: + if (!PyErr_Occurred()) { + __Pyx_TypeName type_obj_name = + __Pyx_PyType_GetName((PyTypeObject*)type_obj); + PyErr_Format(PyExc_RuntimeError, + "Unable to initialize pickling for " __Pyx_FMT_TYPENAME, type_obj_name); + __Pyx_DECREF_TypeName(type_obj_name); + } + ret = -1; +__PYX_GOOD: +#if !CYTHON_USE_PYTYPE_LOOKUP + Py_XDECREF(object_reduce); + Py_XDECREF(object_reduce_ex); + Py_XDECREF(object_getstate); + Py_XDECREF(getstate); +#endif + Py_XDECREF(reduce); + Py_XDECREF(reduce_ex); + Py_XDECREF(reduce_cython); + Py_XDECREF(setstate); + Py_XDECREF(setstate_cython); + return ret; +} +#endif + +/* Import */ +static PyObject *__Pyx_Import(PyObject *name, PyObject *from_list, int level) { + PyObject *module = 0; + PyObject *empty_dict = 0; + PyObject *empty_list = 0; + #if PY_MAJOR_VERSION < 3 + PyObject *py_import; + py_import = __Pyx_PyObject_GetAttrStr(__pyx_b, __pyx_n_s_import); + if (unlikely(!py_import)) + goto bad; + if (!from_list) { + empty_list = PyList_New(0); + if (unlikely(!empty_list)) + goto bad; + from_list = empty_list; + } + #endif + empty_dict = PyDict_New(); + if (unlikely(!empty_dict)) + goto bad; + { + #if PY_MAJOR_VERSION >= 3 + if (level == -1) { + if (strchr(__Pyx_MODULE_NAME, '.') != NULL) { + module = PyImport_ImportModuleLevelObject( + name, __pyx_d, empty_dict, from_list, 1); + if (unlikely(!module)) { + if (unlikely(!PyErr_ExceptionMatches(PyExc_ImportError))) + goto bad; + PyErr_Clear(); + } + } + level = 0; + } + #endif + if (!module) { + #if PY_MAJOR_VERSION < 3 + PyObject *py_level = PyInt_FromLong(level); + if (unlikely(!py_level)) + goto bad; + module = PyObject_CallFunctionObjArgs(py_import, + name, __pyx_d, empty_dict, from_list, py_level, (PyObject *)NULL); + Py_DECREF(py_level); + #else + module = PyImport_ImportModuleLevelObject( + name, __pyx_d, empty_dict, from_list, level); + #endif + } + } +bad: + Py_XDECREF(empty_dict); + Py_XDECREF(empty_list); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_import); + #endif + return module; +} + +/* ImportDottedModule */ +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx__ImportDottedModule_Error(PyObject *name, PyObject *parts_tuple, Py_ssize_t count) { + PyObject *partial_name = NULL, *slice = NULL, *sep = NULL; + if (unlikely(PyErr_Occurred())) { + PyErr_Clear(); + } + if (likely(PyTuple_GET_SIZE(parts_tuple) == count)) { + partial_name = name; + } else { + slice = PySequence_GetSlice(parts_tuple, 0, count); + if (unlikely(!slice)) + goto bad; + sep = PyUnicode_FromStringAndSize(".", 1); + if (unlikely(!sep)) + goto bad; + partial_name = PyUnicode_Join(sep, slice); + } + PyErr_Format( +#if PY_MAJOR_VERSION < 3 + PyExc_ImportError, + "No module named '%s'", PyString_AS_STRING(partial_name)); +#else +#if PY_VERSION_HEX >= 0x030600B1 + PyExc_ModuleNotFoundError, +#else + PyExc_ImportError, +#endif + "No module named '%U'", partial_name); +#endif +bad: + Py_XDECREF(sep); + Py_XDECREF(slice); + Py_XDECREF(partial_name); + return NULL; +} +#endif +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx__ImportDottedModule_Lookup(PyObject *name) { + PyObject *imported_module; +#if PY_VERSION_HEX < 0x030700A1 || (CYTHON_COMPILING_IN_PYPY && PYPY_VERSION_NUM < 0x07030400) + PyObject *modules = PyImport_GetModuleDict(); + if (unlikely(!modules)) + return NULL; + imported_module = __Pyx_PyDict_GetItemStr(modules, name); + Py_XINCREF(imported_module); +#else + imported_module = PyImport_GetModule(name); +#endif + return imported_module; +} +#endif +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_ImportDottedModule_WalkParts(PyObject *module, PyObject *name, PyObject *parts_tuple) { + Py_ssize_t i, nparts; + nparts = PyTuple_GET_SIZE(parts_tuple); + for (i=1; i < nparts && module; i++) { + PyObject *part, *submodule; +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + part = PyTuple_GET_ITEM(parts_tuple, i); +#else + part = PySequence_ITEM(parts_tuple, i); +#endif + submodule = __Pyx_PyObject_GetAttrStrNoError(module, part); +#if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(part); +#endif + Py_DECREF(module); + module = submodule; + } + if (unlikely(!module)) { + return __Pyx__ImportDottedModule_Error(name, parts_tuple, i); + } + return module; +} +#endif +static PyObject *__Pyx__ImportDottedModule(PyObject *name, PyObject *parts_tuple) { +#if PY_MAJOR_VERSION < 3 + PyObject *module, *from_list, *star = __pyx_n_s__4; + CYTHON_UNUSED_VAR(parts_tuple); + from_list = PyList_New(1); + if (unlikely(!from_list)) + return NULL; + Py_INCREF(star); + PyList_SET_ITEM(from_list, 0, star); + module = __Pyx_Import(name, from_list, 0); + Py_DECREF(from_list); + return module; +#else + PyObject *imported_module; + PyObject *module = __Pyx_Import(name, NULL, 0); + if (!parts_tuple || unlikely(!module)) + return module; + imported_module = __Pyx__ImportDottedModule_Lookup(name); + if (likely(imported_module)) { + Py_DECREF(module); + return imported_module; + } + PyErr_Clear(); + return __Pyx_ImportDottedModule_WalkParts(module, name, parts_tuple); +#endif +} +static PyObject *__Pyx_ImportDottedModule(PyObject *name, PyObject *parts_tuple) { +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030400B1 + PyObject *module = __Pyx__ImportDottedModule_Lookup(name); + if (likely(module)) { + PyObject *spec = __Pyx_PyObject_GetAttrStrNoError(module, __pyx_n_s_spec); + if (likely(spec)) { + PyObject *unsafe = __Pyx_PyObject_GetAttrStrNoError(spec, __pyx_n_s_initializing); + if (likely(!unsafe || !__Pyx_PyObject_IsTrue(unsafe))) { + Py_DECREF(spec); + spec = NULL; + } + Py_XDECREF(unsafe); + } + if (likely(!spec)) { + PyErr_Clear(); + return module; + } + Py_DECREF(spec); + Py_DECREF(module); + } else if (PyErr_Occurred()) { + PyErr_Clear(); + } +#endif + return __Pyx__ImportDottedModule(name, parts_tuple); +} + +/* ImportFrom */ +static PyObject* __Pyx_ImportFrom(PyObject* module, PyObject* name) { + PyObject* value = __Pyx_PyObject_GetAttrStr(module, name); + if (unlikely(!value) && PyErr_ExceptionMatches(PyExc_AttributeError)) { + const char* module_name_str = 0; + PyObject* module_name = 0; + PyObject* module_dot = 0; + PyObject* full_name = 0; + PyErr_Clear(); + module_name_str = PyModule_GetName(module); + if (unlikely(!module_name_str)) { goto modbad; } + module_name = PyUnicode_FromString(module_name_str); + if (unlikely(!module_name)) { goto modbad; } + module_dot = PyUnicode_Concat(module_name, __pyx_kp_u__5); + if (unlikely(!module_dot)) { goto modbad; } + full_name = PyUnicode_Concat(module_dot, name); + if (unlikely(!full_name)) { goto modbad; } + #if PY_VERSION_HEX < 0x030700A1 || (CYTHON_COMPILING_IN_PYPY && PYPY_VERSION_NUM < 0x07030400) + { + PyObject *modules = PyImport_GetModuleDict(); + if (unlikely(!modules)) + goto modbad; + value = PyObject_GetItem(modules, full_name); + } + #else + value = PyImport_GetModule(full_name); + #endif + modbad: + Py_XDECREF(full_name); + Py_XDECREF(module_dot); + Py_XDECREF(module_name); + } + if (unlikely(!value)) { + PyErr_Format(PyExc_ImportError, + #if PY_MAJOR_VERSION < 3 + "cannot import name %.230s", PyString_AS_STRING(name)); + #else + "cannot import name %S", name); + #endif + } + return value; +} + +/* FetchSharedCythonModule */ +static PyObject *__Pyx_FetchSharedCythonABIModule(void) { + return __Pyx_PyImport_AddModuleRef((char*) __PYX_ABI_MODULE_NAME); +} + +/* FetchCommonType */ +static int __Pyx_VerifyCachedType(PyObject *cached_type, + const char *name, + Py_ssize_t basicsize, + Py_ssize_t expected_basicsize) { + if (!PyType_Check(cached_type)) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s is not a type object", name); + return -1; + } + if (basicsize != expected_basicsize) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s has the wrong size, try recompiling", + name); + return -1; + } + return 0; +} +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type) { + PyObject* abi_module; + const char* object_name; + PyTypeObject *cached_type = NULL; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + object_name = strrchr(type->tp_name, '.'); + object_name = object_name ? object_name+1 : type->tp_name; + cached_type = (PyTypeObject*) PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + if (__Pyx_VerifyCachedType( + (PyObject *)cached_type, + object_name, + cached_type->tp_basicsize, + type->tp_basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + if (PyType_Ready(type) < 0) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, (PyObject *)type) < 0) + goto bad; + Py_INCREF(type); + cached_type = type; +done: + Py_DECREF(abi_module); + return cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#else +static PyTypeObject *__Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases) { + PyObject *abi_module, *cached_type = NULL; + const char* object_name = strrchr(spec->name, '.'); + object_name = object_name ? object_name+1 : spec->name; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + cached_type = PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + Py_ssize_t basicsize; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *py_basicsize; + py_basicsize = PyObject_GetAttrString(cached_type, "__basicsize__"); + if (unlikely(!py_basicsize)) goto bad; + basicsize = PyLong_AsSsize_t(py_basicsize); + Py_DECREF(py_basicsize); + py_basicsize = 0; + if (unlikely(basicsize == (Py_ssize_t)-1) && PyErr_Occurred()) goto bad; +#else + basicsize = likely(PyType_Check(cached_type)) ? ((PyTypeObject*) cached_type)->tp_basicsize : -1; +#endif + if (__Pyx_VerifyCachedType( + cached_type, + object_name, + basicsize, + spec->basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + CYTHON_UNUSED_VAR(module); + cached_type = __Pyx_PyType_FromModuleAndSpec(abi_module, spec, bases); + if (unlikely(!cached_type)) goto bad; + if (unlikely(__Pyx_fix_up_extension_type_from_spec(spec, (PyTypeObject *) cached_type) < 0)) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, cached_type) < 0) goto bad; +done: + Py_DECREF(abi_module); + assert(cached_type == NULL || PyType_Check(cached_type)); + return (PyTypeObject *) cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#endif + +/* PyVectorcallFastCallDict */ +#if CYTHON_METH_FASTCALL +static PyObject *__Pyx_PyVectorcall_FastCallDict_kw(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + PyObject *res = NULL; + PyObject *kwnames; + PyObject **newargs; + PyObject **kwvalues; + Py_ssize_t i, pos; + size_t j; + PyObject *key, *value; + unsigned long keys_are_strings; + Py_ssize_t nkw = PyDict_GET_SIZE(kw); + newargs = (PyObject **)PyMem_Malloc((nargs + (size_t)nkw) * sizeof(args[0])); + if (unlikely(newargs == NULL)) { + PyErr_NoMemory(); + return NULL; + } + for (j = 0; j < nargs; j++) newargs[j] = args[j]; + kwnames = PyTuple_New(nkw); + if (unlikely(kwnames == NULL)) { + PyMem_Free(newargs); + return NULL; + } + kwvalues = newargs + nargs; + pos = i = 0; + keys_are_strings = Py_TPFLAGS_UNICODE_SUBCLASS; + while (PyDict_Next(kw, &pos, &key, &value)) { + keys_are_strings &= Py_TYPE(key)->tp_flags; + Py_INCREF(key); + Py_INCREF(value); + PyTuple_SET_ITEM(kwnames, i, key); + kwvalues[i] = value; + i++; + } + if (unlikely(!keys_are_strings)) { + PyErr_SetString(PyExc_TypeError, "keywords must be strings"); + goto cleanup; + } + res = vc(func, newargs, nargs, kwnames); +cleanup: + Py_DECREF(kwnames); + for (i = 0; i < nkw; i++) + Py_DECREF(kwvalues[i]); + PyMem_Free(newargs); + return res; +} +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + if (likely(kw == NULL) || PyDict_GET_SIZE(kw) == 0) { + return vc(func, args, nargs, NULL); + } + return __Pyx_PyVectorcall_FastCallDict_kw(func, vc, args, nargs, kw); +} +#endif + +/* CythonFunctionShared */ +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc) { + if (__Pyx_CyFunction_Check(func)) { + return PyCFunction_GetFunction(((__pyx_CyFunctionObject*)func)->func) == (PyCFunction) cfunc; + } else if (PyCFunction_Check(func)) { + return PyCFunction_GetFunction(func) == (PyCFunction) cfunc; + } + return 0; +} +#else +static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc) { + return __Pyx_CyOrPyCFunction_Check(func) && __Pyx_CyOrPyCFunction_GET_FUNCTION(func) == (PyCFunction) cfunc; +} +#endif +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj) { +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + __Pyx_Py_XDECREF_SET( + __Pyx_CyFunction_GetClassObj(f), + ((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#else + __Pyx_Py_XDECREF_SET( + ((PyCMethodObject *) (f))->mm_class, + (PyTypeObject*)((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#endif +} +static PyObject * +__Pyx_CyFunction_get_doc(__pyx_CyFunctionObject *op, void *closure) +{ + CYTHON_UNUSED_VAR(closure); + if (unlikely(op->func_doc == NULL)) { +#if CYTHON_COMPILING_IN_LIMITED_API + op->func_doc = PyObject_GetAttrString(op->func, "__doc__"); + if (unlikely(!op->func_doc)) return NULL; +#else + if (((PyCFunctionObject*)op)->m_ml->ml_doc) { +#if PY_MAJOR_VERSION >= 3 + op->func_doc = PyUnicode_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#else + op->func_doc = PyString_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#endif + if (unlikely(op->func_doc == NULL)) + return NULL; + } else { + Py_INCREF(Py_None); + return Py_None; + } +#endif + } + Py_INCREF(op->func_doc); + return op->func_doc; +} +static int +__Pyx_CyFunction_set_doc(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (value == NULL) { + value = Py_None; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_doc, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_name(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_name == NULL)) { +#if CYTHON_COMPILING_IN_LIMITED_API + op->func_name = PyObject_GetAttrString(op->func, "__name__"); +#elif PY_MAJOR_VERSION >= 3 + op->func_name = PyUnicode_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#else + op->func_name = PyString_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#endif + if (unlikely(op->func_name == NULL)) + return NULL; + } + Py_INCREF(op->func_name); + return op->func_name; +} +static int +__Pyx_CyFunction_set_name(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__name__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_name, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_qualname(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_qualname); + return op->func_qualname; +} +static int +__Pyx_CyFunction_set_qualname(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__qualname__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_qualname, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_dict(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_dict == NULL)) { + op->func_dict = PyDict_New(); + if (unlikely(op->func_dict == NULL)) + return NULL; + } + Py_INCREF(op->func_dict); + return op->func_dict; +} +static int +__Pyx_CyFunction_set_dict(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(value == NULL)) { + PyErr_SetString(PyExc_TypeError, + "function's dictionary may not be deleted"); + return -1; + } + if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "setting function's dictionary to a non-dict"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_dict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_globals(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_globals); + return op->func_globals; +} +static PyObject * +__Pyx_CyFunction_get_closure(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(op); + CYTHON_UNUSED_VAR(context); + Py_INCREF(Py_None); + return Py_None; +} +static PyObject * +__Pyx_CyFunction_get_code(__pyx_CyFunctionObject *op, void *context) +{ + PyObject* result = (op->func_code) ? op->func_code : Py_None; + CYTHON_UNUSED_VAR(context); + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_init_defaults(__pyx_CyFunctionObject *op) { + int result = 0; + PyObject *res = op->defaults_getter((PyObject *) op); + if (unlikely(!res)) + return -1; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + op->defaults_tuple = PyTuple_GET_ITEM(res, 0); + Py_INCREF(op->defaults_tuple); + op->defaults_kwdict = PyTuple_GET_ITEM(res, 1); + Py_INCREF(op->defaults_kwdict); + #else + op->defaults_tuple = __Pyx_PySequence_ITEM(res, 0); + if (unlikely(!op->defaults_tuple)) result = -1; + else { + op->defaults_kwdict = __Pyx_PySequence_ITEM(res, 1); + if (unlikely(!op->defaults_kwdict)) result = -1; + } + #endif + Py_DECREF(res); + return result; +} +static int +__Pyx_CyFunction_set_defaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyTuple_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__defaults__ must be set to a tuple object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__defaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_tuple, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_defaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_tuple; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_tuple; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_kwdefaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__kwdefaults__ must be set to a dict object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__kwdefaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_kwdict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_kwdefaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_kwdict; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_kwdict; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_annotations(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value || value == Py_None) { + value = NULL; + } else if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__annotations__ must be set to a dict object"); + return -1; + } + Py_XINCREF(value); + __Pyx_Py_XDECREF_SET(op->func_annotations, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_annotations(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->func_annotations; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + result = PyDict_New(); + if (unlikely(!result)) return NULL; + op->func_annotations = result; + } + Py_INCREF(result); + return result; +} +static PyObject * +__Pyx_CyFunction_get_is_coroutine(__pyx_CyFunctionObject *op, void *context) { + int is_coroutine; + CYTHON_UNUSED_VAR(context); + if (op->func_is_coroutine) { + return __Pyx_NewRef(op->func_is_coroutine); + } + is_coroutine = op->flags & __Pyx_CYFUNCTION_COROUTINE; +#if PY_VERSION_HEX >= 0x03050000 + if (is_coroutine) { + PyObject *module, *fromlist, *marker = __pyx_n_s_is_coroutine; + fromlist = PyList_New(1); + if (unlikely(!fromlist)) return NULL; + Py_INCREF(marker); +#if CYTHON_ASSUME_SAFE_MACROS + PyList_SET_ITEM(fromlist, 0, marker); +#else + if (unlikely(PyList_SetItem(fromlist, 0, marker) < 0)) { + Py_DECREF(marker); + Py_DECREF(fromlist); + return NULL; + } +#endif + module = PyImport_ImportModuleLevelObject(__pyx_n_s_asyncio_coroutines, NULL, NULL, fromlist, 0); + Py_DECREF(fromlist); + if (unlikely(!module)) goto ignore; + op->func_is_coroutine = __Pyx_PyObject_GetAttrStr(module, marker); + Py_DECREF(module); + if (likely(op->func_is_coroutine)) { + return __Pyx_NewRef(op->func_is_coroutine); + } +ignore: + PyErr_Clear(); + } +#endif + op->func_is_coroutine = __Pyx_PyBool_FromLong(is_coroutine); + return __Pyx_NewRef(op->func_is_coroutine); +} +#if CYTHON_COMPILING_IN_LIMITED_API +static PyObject * +__Pyx_CyFunction_get_module(__pyx_CyFunctionObject *op, void *context) { + CYTHON_UNUSED_VAR(context); + return PyObject_GetAttrString(op->func, "__module__"); +} +static int +__Pyx_CyFunction_set_module(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + return PyObject_SetAttrString(op->func, "__module__", value); +} +#endif +static PyGetSetDef __pyx_CyFunction_getsets[] = { + {(char *) "func_doc", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "__doc__", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "func_name", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__name__", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__qualname__", (getter)__Pyx_CyFunction_get_qualname, (setter)__Pyx_CyFunction_set_qualname, 0, 0}, + {(char *) "func_dict", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "__dict__", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "func_globals", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "__globals__", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "func_closure", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "__closure__", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "func_code", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "__code__", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "func_defaults", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__defaults__", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__kwdefaults__", (getter)__Pyx_CyFunction_get_kwdefaults, (setter)__Pyx_CyFunction_set_kwdefaults, 0, 0}, + {(char *) "__annotations__", (getter)__Pyx_CyFunction_get_annotations, (setter)__Pyx_CyFunction_set_annotations, 0, 0}, + {(char *) "_is_coroutine", (getter)__Pyx_CyFunction_get_is_coroutine, 0, 0, 0}, +#if CYTHON_COMPILING_IN_LIMITED_API + {"__module__", (getter)__Pyx_CyFunction_get_module, (setter)__Pyx_CyFunction_set_module, 0, 0}, +#endif + {0, 0, 0, 0, 0} +}; +static PyMemberDef __pyx_CyFunction_members[] = { +#if !CYTHON_COMPILING_IN_LIMITED_API + {(char *) "__module__", T_OBJECT, offsetof(PyCFunctionObject, m_module), 0, 0}, +#endif +#if CYTHON_USE_TYPE_SPECS + {(char *) "__dictoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_dict), READONLY, 0}, +#if CYTHON_METH_FASTCALL +#if CYTHON_BACKPORT_VECTORCALL + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_vectorcall), READONLY, 0}, +#else +#if !CYTHON_COMPILING_IN_LIMITED_API + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(PyCFunctionObject, vectorcall), READONLY, 0}, +#endif +#endif +#endif +#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_weakreflist), READONLY, 0}, +#else + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(PyCFunctionObject, m_weakreflist), READONLY, 0}, +#endif +#endif + {0, 0, 0, 0, 0} +}; +static PyObject * +__Pyx_CyFunction_reduce(__pyx_CyFunctionObject *m, PyObject *args) +{ + CYTHON_UNUSED_VAR(args); +#if PY_MAJOR_VERSION >= 3 + Py_INCREF(m->func_qualname); + return m->func_qualname; +#else + return PyString_FromString(((PyCFunctionObject*)m)->m_ml->ml_name); +#endif +} +static PyMethodDef __pyx_CyFunction_methods[] = { + {"__reduce__", (PyCFunction)__Pyx_CyFunction_reduce, METH_VARARGS, 0}, + {0, 0, 0, 0} +}; +#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API +#define __Pyx_CyFunction_weakreflist(cyfunc) ((cyfunc)->func_weakreflist) +#else +#define __Pyx_CyFunction_weakreflist(cyfunc) (((PyCFunctionObject*)cyfunc)->m_weakreflist) +#endif +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject *op, PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { +#if !CYTHON_COMPILING_IN_LIMITED_API + PyCFunctionObject *cf = (PyCFunctionObject*) op; +#endif + if (unlikely(op == NULL)) + return NULL; +#if CYTHON_COMPILING_IN_LIMITED_API + op->func = PyCFunction_NewEx(ml, (PyObject*)op, module); + if (unlikely(!op->func)) return NULL; +#endif + op->flags = flags; + __Pyx_CyFunction_weakreflist(op) = NULL; +#if !CYTHON_COMPILING_IN_LIMITED_API + cf->m_ml = ml; + cf->m_self = (PyObject *) op; +#endif + Py_XINCREF(closure); + op->func_closure = closure; +#if !CYTHON_COMPILING_IN_LIMITED_API + Py_XINCREF(module); + cf->m_module = module; +#endif + op->func_dict = NULL; + op->func_name = NULL; + Py_INCREF(qualname); + op->func_qualname = qualname; + op->func_doc = NULL; +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + op->func_classobj = NULL; +#else + ((PyCMethodObject*)op)->mm_class = NULL; +#endif + op->func_globals = globals; + Py_INCREF(op->func_globals); + Py_XINCREF(code); + op->func_code = code; + op->defaults_pyobjects = 0; + op->defaults_size = 0; + op->defaults = NULL; + op->defaults_tuple = NULL; + op->defaults_kwdict = NULL; + op->defaults_getter = NULL; + op->func_annotations = NULL; + op->func_is_coroutine = NULL; +#if CYTHON_METH_FASTCALL + switch (ml->ml_flags & (METH_VARARGS | METH_FASTCALL | METH_NOARGS | METH_O | METH_KEYWORDS | METH_METHOD)) { + case METH_NOARGS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_NOARGS; + break; + case METH_O: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_O; + break; + case METH_METHOD | METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD; + break; + case METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS; + break; + case METH_VARARGS | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = NULL; + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + Py_DECREF(op); + return NULL; + } +#endif + return (PyObject *) op; +} +static int +__Pyx_CyFunction_clear(__pyx_CyFunctionObject *m) +{ + Py_CLEAR(m->func_closure); +#if CYTHON_COMPILING_IN_LIMITED_API + Py_CLEAR(m->func); +#else + Py_CLEAR(((PyCFunctionObject*)m)->m_module); +#endif + Py_CLEAR(m->func_dict); + Py_CLEAR(m->func_name); + Py_CLEAR(m->func_qualname); + Py_CLEAR(m->func_doc); + Py_CLEAR(m->func_globals); + Py_CLEAR(m->func_code); +#if !CYTHON_COMPILING_IN_LIMITED_API +#if PY_VERSION_HEX < 0x030900B1 + Py_CLEAR(__Pyx_CyFunction_GetClassObj(m)); +#else + { + PyObject *cls = (PyObject*) ((PyCMethodObject *) (m))->mm_class; + ((PyCMethodObject *) (m))->mm_class = NULL; + Py_XDECREF(cls); + } +#endif +#endif + Py_CLEAR(m->defaults_tuple); + Py_CLEAR(m->defaults_kwdict); + Py_CLEAR(m->func_annotations); + Py_CLEAR(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_XDECREF(pydefaults[i]); + PyObject_Free(m->defaults); + m->defaults = NULL; + } + return 0; +} +static void __Pyx__CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + if (__Pyx_CyFunction_weakreflist(m) != NULL) + PyObject_ClearWeakRefs((PyObject *) m); + __Pyx_CyFunction_clear(m); + __Pyx_PyHeapTypeObject_GC_Del(m); +} +static void __Pyx_CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + PyObject_GC_UnTrack(m); + __Pyx__CyFunction_dealloc(m); +} +static int __Pyx_CyFunction_traverse(__pyx_CyFunctionObject *m, visitproc visit, void *arg) +{ + Py_VISIT(m->func_closure); +#if CYTHON_COMPILING_IN_LIMITED_API + Py_VISIT(m->func); +#else + Py_VISIT(((PyCFunctionObject*)m)->m_module); +#endif + Py_VISIT(m->func_dict); + Py_VISIT(m->func_name); + Py_VISIT(m->func_qualname); + Py_VISIT(m->func_doc); + Py_VISIT(m->func_globals); + Py_VISIT(m->func_code); +#if !CYTHON_COMPILING_IN_LIMITED_API + Py_VISIT(__Pyx_CyFunction_GetClassObj(m)); +#endif + Py_VISIT(m->defaults_tuple); + Py_VISIT(m->defaults_kwdict); + Py_VISIT(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_VISIT(pydefaults[i]); + } + return 0; +} +static PyObject* +__Pyx_CyFunction_repr(__pyx_CyFunctionObject *op) +{ +#if PY_MAJOR_VERSION >= 3 + return PyUnicode_FromFormat("", + op->func_qualname, (void *)op); +#else + return PyString_FromFormat("", + PyString_AsString(op->func_qualname), (void *)op); +#endif +} +static PyObject * __Pyx_CyFunction_CallMethod(PyObject *func, PyObject *self, PyObject *arg, PyObject *kw) { +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *f = ((__pyx_CyFunctionObject*)func)->func; + PyObject *py_name = NULL; + PyCFunction meth; + int flags; + meth = PyCFunction_GetFunction(f); + if (unlikely(!meth)) return NULL; + flags = PyCFunction_GetFlags(f); + if (unlikely(flags < 0)) return NULL; +#else + PyCFunctionObject* f = (PyCFunctionObject*)func; + PyCFunction meth = f->m_ml->ml_meth; + int flags = f->m_ml->ml_flags; +#endif + Py_ssize_t size; + switch (flags & (METH_VARARGS | METH_KEYWORDS | METH_NOARGS | METH_O)) { + case METH_VARARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) + return (*meth)(self, arg); + break; + case METH_VARARGS | METH_KEYWORDS: + return (*(PyCFunctionWithKeywords)(void*)meth)(self, arg, kw); + case METH_NOARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { +#if CYTHON_ASSUME_SAFE_MACROS + size = PyTuple_GET_SIZE(arg); +#else + size = PyTuple_Size(arg); + if (unlikely(size < 0)) return NULL; +#endif + if (likely(size == 0)) + return (*meth)(self, NULL); +#if CYTHON_COMPILING_IN_LIMITED_API + py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); + if (!py_name) return NULL; + PyErr_Format(PyExc_TypeError, + "%.200S() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + py_name, size); + Py_DECREF(py_name); +#else + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); +#endif + return NULL; + } + break; + case METH_O: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { +#if CYTHON_ASSUME_SAFE_MACROS + size = PyTuple_GET_SIZE(arg); +#else + size = PyTuple_Size(arg); + if (unlikely(size < 0)) return NULL; +#endif + if (likely(size == 1)) { + PyObject *result, *arg0; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + arg0 = PyTuple_GET_ITEM(arg, 0); + #else + arg0 = __Pyx_PySequence_ITEM(arg, 0); if (unlikely(!arg0)) return NULL; + #endif + result = (*meth)(self, arg0); + #if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(arg0); + #endif + return result; + } +#if CYTHON_COMPILING_IN_LIMITED_API + py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); + if (!py_name) return NULL; + PyErr_Format(PyExc_TypeError, + "%.200S() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + py_name, size); + Py_DECREF(py_name); +#else + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); +#endif + return NULL; + } + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + return NULL; + } +#if CYTHON_COMPILING_IN_LIMITED_API + py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); + if (!py_name) return NULL; + PyErr_Format(PyExc_TypeError, "%.200S() takes no keyword arguments", + py_name); + Py_DECREF(py_name); +#else + PyErr_Format(PyExc_TypeError, "%.200s() takes no keyword arguments", + f->m_ml->ml_name); +#endif + return NULL; +} +static CYTHON_INLINE PyObject *__Pyx_CyFunction_Call(PyObject *func, PyObject *arg, PyObject *kw) { + PyObject *self, *result; +#if CYTHON_COMPILING_IN_LIMITED_API + self = PyCFunction_GetSelf(((__pyx_CyFunctionObject*)func)->func); + if (unlikely(!self) && PyErr_Occurred()) return NULL; +#else + self = ((PyCFunctionObject*)func)->m_self; +#endif + result = __Pyx_CyFunction_CallMethod(func, self, arg, kw); + return result; +} +static PyObject *__Pyx_CyFunction_CallAsMethod(PyObject *func, PyObject *args, PyObject *kw) { + PyObject *result; + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *) func; +#if CYTHON_METH_FASTCALL + __pyx_vectorcallfunc vc = __Pyx_CyFunction_func_vectorcall(cyfunc); + if (vc) { +#if CYTHON_ASSUME_SAFE_MACROS + return __Pyx_PyVectorcall_FastCallDict(func, vc, &PyTuple_GET_ITEM(args, 0), (size_t)PyTuple_GET_SIZE(args), kw); +#else + (void) &__Pyx_PyVectorcall_FastCallDict; + return PyVectorcall_Call(func, args, kw); +#endif + } +#endif + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + Py_ssize_t argc; + PyObject *new_args; + PyObject *self; +#if CYTHON_ASSUME_SAFE_MACROS + argc = PyTuple_GET_SIZE(args); +#else + argc = PyTuple_Size(args); + if (unlikely(!argc) < 0) return NULL; +#endif + new_args = PyTuple_GetSlice(args, 1, argc); + if (unlikely(!new_args)) + return NULL; + self = PyTuple_GetItem(args, 0); + if (unlikely(!self)) { + Py_DECREF(new_args); +#if PY_MAJOR_VERSION > 2 + PyErr_Format(PyExc_TypeError, + "unbound method %.200S() needs an argument", + cyfunc->func_qualname); +#else + PyErr_SetString(PyExc_TypeError, + "unbound method needs an argument"); +#endif + return NULL; + } + result = __Pyx_CyFunction_CallMethod(func, self, new_args, kw); + Py_DECREF(new_args); + } else { + result = __Pyx_CyFunction_Call(func, args, kw); + } + return result; +} +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE int __Pyx_CyFunction_Vectorcall_CheckArgs(__pyx_CyFunctionObject *cyfunc, Py_ssize_t nargs, PyObject *kwnames) +{ + int ret = 0; + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + if (unlikely(nargs < 1)) { + PyErr_Format(PyExc_TypeError, "%.200s() needs an argument", + ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + ret = 1; + } + if (unlikely(kwnames) && unlikely(PyTuple_GET_SIZE(kwnames))) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no keyword arguments", ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + return ret; +} +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 0)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, NULL); +} +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 1)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, args[0]); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((_PyCFunctionFastWithKeywords)(void(*)(void))def->ml_meth)(self, args, nargs, kwnames); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; + PyTypeObject *cls = (PyTypeObject *) __Pyx_CyFunction_GetClassObj(cyfunc); +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((__Pyx_PyCMethod)(void(*)(void))def->ml_meth)(self, cls, args, (size_t)nargs, kwnames); +} +#endif +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_CyFunctionType_slots[] = { + {Py_tp_dealloc, (void *)__Pyx_CyFunction_dealloc}, + {Py_tp_repr, (void *)__Pyx_CyFunction_repr}, + {Py_tp_call, (void *)__Pyx_CyFunction_CallAsMethod}, + {Py_tp_traverse, (void *)__Pyx_CyFunction_traverse}, + {Py_tp_clear, (void *)__Pyx_CyFunction_clear}, + {Py_tp_methods, (void *)__pyx_CyFunction_methods}, + {Py_tp_members, (void *)__pyx_CyFunction_members}, + {Py_tp_getset, (void *)__pyx_CyFunction_getsets}, + {Py_tp_descr_get, (void *)__Pyx_PyMethod_New}, + {0, 0}, +}; +static PyType_Spec __pyx_CyFunctionType_spec = { + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#if (defined(_Py_TPFLAGS_HAVE_VECTORCALL) && CYTHON_METH_FASTCALL) + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + __pyx_CyFunctionType_slots +}; +#else +static PyTypeObject __pyx_CyFunctionType_type = { + PyVarObject_HEAD_INIT(0, 0) + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, + (destructor) __Pyx_CyFunction_dealloc, +#if !CYTHON_METH_FASTCALL + 0, +#elif CYTHON_BACKPORT_VECTORCALL + (printfunc)offsetof(__pyx_CyFunctionObject, func_vectorcall), +#else + offsetof(PyCFunctionObject, vectorcall), +#endif + 0, + 0, +#if PY_MAJOR_VERSION < 3 + 0, +#else + 0, +#endif + (reprfunc) __Pyx_CyFunction_repr, + 0, + 0, + 0, + 0, + __Pyx_CyFunction_CallAsMethod, + 0, + 0, + 0, + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#if defined(_Py_TPFLAGS_HAVE_VECTORCALL) && CYTHON_METH_FASTCALL + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + 0, + (traverseproc) __Pyx_CyFunction_traverse, + (inquiry) __Pyx_CyFunction_clear, + 0, +#if PY_VERSION_HEX < 0x030500A0 + offsetof(__pyx_CyFunctionObject, func_weakreflist), +#else + offsetof(PyCFunctionObject, m_weakreflist), +#endif + 0, + 0, + __pyx_CyFunction_methods, + __pyx_CyFunction_members, + __pyx_CyFunction_getsets, + 0, + 0, + __Pyx_PyMethod_New, + 0, + offsetof(__pyx_CyFunctionObject, func_dict), + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, +#if PY_VERSION_HEX >= 0x030400a1 + 0, +#endif +#if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, +#endif +#if __PYX_NEED_TP_PRINT_SLOT + 0, +#endif +#if PY_VERSION_HEX >= 0x030C0000 + 0, +#endif +#if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, +#endif +}; +#endif +static int __pyx_CyFunction_init(PyObject *module) { +#if CYTHON_USE_TYPE_SPECS + __pyx_CyFunctionType = __Pyx_FetchCommonTypeFromSpec(module, &__pyx_CyFunctionType_spec, NULL); +#else + CYTHON_UNUSED_VAR(module); + __pyx_CyFunctionType = __Pyx_FetchCommonType(&__pyx_CyFunctionType_type); +#endif + if (unlikely(__pyx_CyFunctionType == NULL)) { + return -1; + } + return 0; +} +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *func, size_t size, int pyobjects) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults = PyObject_Malloc(size); + if (unlikely(!m->defaults)) + return PyErr_NoMemory(); + memset(m->defaults, 0, size); + m->defaults_pyobjects = pyobjects; + m->defaults_size = size; + return m->defaults; +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *func, PyObject *tuple) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_tuple = tuple; + Py_INCREF(tuple); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_kwdict = dict; + Py_INCREF(dict); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->func_annotations = dict; + Py_INCREF(dict); +} + +/* CythonFunction */ +static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { + PyObject *op = __Pyx_CyFunction_Init( + PyObject_GC_New(__pyx_CyFunctionObject, __pyx_CyFunctionType), + ml, flags, qualname, closure, module, globals, code + ); + if (likely(op)) { + PyObject_GC_Track(op); + } + return op; +} + +/* CLineInTraceback */ +#ifndef CYTHON_CLINE_IN_TRACEBACK +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line) { + PyObject *use_cline; + PyObject *ptype, *pvalue, *ptraceback; +#if CYTHON_COMPILING_IN_CPYTHON + PyObject **cython_runtime_dict; +#endif + CYTHON_MAYBE_UNUSED_VAR(tstate); + if (unlikely(!__pyx_cython_runtime)) { + return c_line; + } + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); +#if CYTHON_COMPILING_IN_CPYTHON + cython_runtime_dict = _PyObject_GetDictPtr(__pyx_cython_runtime); + if (likely(cython_runtime_dict)) { + __PYX_PY_DICT_LOOKUP_IF_MODIFIED( + use_cline, *cython_runtime_dict, + __Pyx_PyDict_GetItemStr(*cython_runtime_dict, __pyx_n_s_cline_in_traceback)) + } else +#endif + { + PyObject *use_cline_obj = __Pyx_PyObject_GetAttrStrNoError(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback); + if (use_cline_obj) { + use_cline = PyObject_Not(use_cline_obj) ? Py_False : Py_True; + Py_DECREF(use_cline_obj); + } else { + PyErr_Clear(); + use_cline = NULL; + } + } + if (!use_cline) { + c_line = 0; + (void) PyObject_SetAttr(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback, Py_False); + } + else if (use_cline == Py_False || (use_cline != Py_True && PyObject_Not(use_cline) != 0)) { + c_line = 0; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + return c_line; +} +#endif + +/* CodeObjectCache */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line) { + int start = 0, mid = 0, end = count - 1; + if (end >= 0 && code_line > entries[end].code_line) { + return count; + } + while (start < end) { + mid = start + (end - start) / 2; + if (code_line < entries[mid].code_line) { + end = mid; + } else if (code_line > entries[mid].code_line) { + start = mid + 1; + } else { + return mid; + } + } + if (code_line <= entries[mid].code_line) { + return mid; + } else { + return mid + 1; + } +} +static PyCodeObject *__pyx_find_code_object(int code_line) { + PyCodeObject* code_object; + int pos; + if (unlikely(!code_line) || unlikely(!__pyx_code_cache.entries)) { + return NULL; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if (unlikely(pos >= __pyx_code_cache.count) || unlikely(__pyx_code_cache.entries[pos].code_line != code_line)) { + return NULL; + } + code_object = __pyx_code_cache.entries[pos].code_object; + Py_INCREF(code_object); + return code_object; +} +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object) { + int pos, i; + __Pyx_CodeObjectCacheEntry* entries = __pyx_code_cache.entries; + if (unlikely(!code_line)) { + return; + } + if (unlikely(!entries)) { + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Malloc(64*sizeof(__Pyx_CodeObjectCacheEntry)); + if (likely(entries)) { + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = 64; + __pyx_code_cache.count = 1; + entries[0].code_line = code_line; + entries[0].code_object = code_object; + Py_INCREF(code_object); + } + return; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if ((pos < __pyx_code_cache.count) && unlikely(__pyx_code_cache.entries[pos].code_line == code_line)) { + PyCodeObject* tmp = entries[pos].code_object; + entries[pos].code_object = code_object; + Py_DECREF(tmp); + return; + } + if (__pyx_code_cache.count == __pyx_code_cache.max_count) { + int new_max = __pyx_code_cache.max_count + 64; + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Realloc( + __pyx_code_cache.entries, ((size_t)new_max) * sizeof(__Pyx_CodeObjectCacheEntry)); + if (unlikely(!entries)) { + return; + } + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = new_max; + } + for (i=__pyx_code_cache.count; i>pos; i--) { + entries[i] = entries[i-1]; + } + entries[pos].code_line = code_line; + entries[pos].code_object = code_object; + __pyx_code_cache.count++; + Py_INCREF(code_object); +} +#endif + +/* AddTraceback */ +#include "compile.h" +#include "frameobject.h" +#include "traceback.h" +#if PY_VERSION_HEX >= 0x030b00a6 && !CYTHON_COMPILING_IN_LIMITED_API + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static PyObject *__Pyx_PyCode_Replace_For_AddTraceback(PyObject *code, PyObject *scratch_dict, + PyObject *firstlineno, PyObject *name) { + PyObject *replace = NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "co_firstlineno", firstlineno))) return NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "co_name", name))) return NULL; + replace = PyObject_GetAttrString(code, "replace"); + if (likely(replace)) { + PyObject *result; + result = PyObject_Call(replace, __pyx_empty_tuple, scratch_dict); + Py_DECREF(replace); + return result; + } + PyErr_Clear(); + #if __PYX_LIMITED_VERSION_HEX < 0x030780000 + { + PyObject *compiled = NULL, *result = NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "code", code))) return NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "type", (PyObject*)(&PyType_Type)))) return NULL; + compiled = Py_CompileString( + "out = type(code)(\n" + " code.co_argcount, code.co_kwonlyargcount, code.co_nlocals, code.co_stacksize,\n" + " code.co_flags, code.co_code, code.co_consts, code.co_names,\n" + " code.co_varnames, code.co_filename, co_name, co_firstlineno,\n" + " code.co_lnotab)\n", "", Py_file_input); + if (!compiled) return NULL; + result = PyEval_EvalCode(compiled, scratch_dict, scratch_dict); + Py_DECREF(compiled); + if (!result) PyErr_Print(); + Py_DECREF(result); + result = PyDict_GetItemString(scratch_dict, "out"); + if (result) Py_INCREF(result); + return result; + } + #else + return NULL; + #endif +} +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + PyObject *code_object = NULL, *py_py_line = NULL, *py_funcname = NULL, *dict = NULL; + PyObject *replace = NULL, *getframe = NULL, *frame = NULL; + PyObject *exc_type, *exc_value, *exc_traceback; + int success = 0; + if (c_line) { + (void) __pyx_cfilenm; + (void) __Pyx_CLineForTraceback(__Pyx_PyThreadState_Current, c_line); + } + PyErr_Fetch(&exc_type, &exc_value, &exc_traceback); + code_object = Py_CompileString("_getframe()", filename, Py_eval_input); + if (unlikely(!code_object)) goto bad; + py_py_line = PyLong_FromLong(py_line); + if (unlikely(!py_py_line)) goto bad; + py_funcname = PyUnicode_FromString(funcname); + if (unlikely(!py_funcname)) goto bad; + dict = PyDict_New(); + if (unlikely(!dict)) goto bad; + { + PyObject *old_code_object = code_object; + code_object = __Pyx_PyCode_Replace_For_AddTraceback(code_object, dict, py_py_line, py_funcname); + Py_DECREF(old_code_object); + } + if (unlikely(!code_object)) goto bad; + getframe = PySys_GetObject("_getframe"); + if (unlikely(!getframe)) goto bad; + if (unlikely(PyDict_SetItemString(dict, "_getframe", getframe))) goto bad; + frame = PyEval_EvalCode(code_object, dict, dict); + if (unlikely(!frame) || frame == Py_None) goto bad; + success = 1; + bad: + PyErr_Restore(exc_type, exc_value, exc_traceback); + Py_XDECREF(code_object); + Py_XDECREF(py_py_line); + Py_XDECREF(py_funcname); + Py_XDECREF(dict); + Py_XDECREF(replace); + if (success) { + PyTraceBack_Here( + (struct _frame*)frame); + } + Py_XDECREF(frame); +} +#else +static PyCodeObject* __Pyx_CreateCodeObjectForTraceback( + const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = NULL; + PyObject *py_funcname = NULL; + #if PY_MAJOR_VERSION < 3 + PyObject *py_srcfile = NULL; + py_srcfile = PyString_FromString(filename); + if (!py_srcfile) goto bad; + #endif + if (c_line) { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + #else + py_funcname = PyUnicode_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + funcname = PyUnicode_AsUTF8(py_funcname); + if (!funcname) goto bad; + #endif + } + else { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromString(funcname); + if (!py_funcname) goto bad; + #endif + } + #if PY_MAJOR_VERSION < 3 + py_code = __Pyx_PyCode_New( + 0, + 0, + 0, + 0, + 0, + 0, + __pyx_empty_bytes, /*PyObject *code,*/ + __pyx_empty_tuple, /*PyObject *consts,*/ + __pyx_empty_tuple, /*PyObject *names,*/ + __pyx_empty_tuple, /*PyObject *varnames,*/ + __pyx_empty_tuple, /*PyObject *freevars,*/ + __pyx_empty_tuple, /*PyObject *cellvars,*/ + py_srcfile, /*PyObject *filename,*/ + py_funcname, /*PyObject *name,*/ + py_line, + __pyx_empty_bytes /*PyObject *lnotab*/ + ); + Py_DECREF(py_srcfile); + #else + py_code = PyCode_NewEmpty(filename, funcname, py_line); + #endif + Py_XDECREF(py_funcname); + return py_code; +bad: + Py_XDECREF(py_funcname); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_srcfile); + #endif + return NULL; +} +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = 0; + PyFrameObject *py_frame = 0; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject *ptype, *pvalue, *ptraceback; + if (c_line) { + c_line = __Pyx_CLineForTraceback(tstate, c_line); + } + py_code = __pyx_find_code_object(c_line ? -c_line : py_line); + if (!py_code) { + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); + py_code = __Pyx_CreateCodeObjectForTraceback( + funcname, c_line, py_line, filename); + if (!py_code) { + /* If the code object creation fails, then we should clear the + fetched exception references and propagate the new exception */ + Py_XDECREF(ptype); + Py_XDECREF(pvalue); + Py_XDECREF(ptraceback); + goto bad; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + __pyx_insert_code_object(c_line ? -c_line : py_line, py_code); + } + py_frame = PyFrame_New( + tstate, /*PyThreadState *tstate,*/ + py_code, /*PyCodeObject *code,*/ + __pyx_d, /*PyObject *globals,*/ + 0 /*PyObject *locals*/ + ); + if (!py_frame) goto bad; + __Pyx_PyFrame_SetLineNumber(py_frame, py_line); + PyTraceBack_Here(py_frame); +bad: + Py_XDECREF(py_code); + Py_XDECREF(py_frame); +} +#endif + +/* CIntFromPyVerify */ +#define __PYX_VERIFY_RETURN_INT(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 0) +#define __PYX_VERIFY_RETURN_INT_EXC(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 1) +#define __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, exc)\ + {\ + func_type value = func_value;\ + if (sizeof(target_type) < sizeof(func_type)) {\ + if (unlikely(value != (func_type) (target_type) value)) {\ + func_type zero = 0;\ + if (exc && unlikely(value == (func_type)-1 && PyErr_Occurred()))\ + return (target_type) -1;\ + if (is_unsigned && unlikely(value < zero))\ + goto raise_neg_overflow;\ + else\ + goto raise_overflow;\ + }\ + }\ + return (target_type) value;\ + } + +/* CIntFromPy */ +static CYTHON_INLINE size_t __Pyx_PyInt_As_size_t(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const size_t neg_one = (size_t) -1, const_zero = (size_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(size_t) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(size_t, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (size_t) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(size_t, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(size_t) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) >= 2 * PyLong_SHIFT)) { + return (size_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(size_t) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) >= 3 * PyLong_SHIFT)) { + return (size_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(size_t) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) >= 4 * PyLong_SHIFT)) { + return (size_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (size_t) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(size_t) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(size_t) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(size_t, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(size_t) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 2 * PyLong_SHIFT)) { + return (size_t) (((size_t)-1)*(((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(size_t) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 2 * PyLong_SHIFT)) { + return (size_t) ((((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(size_t) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 3 * PyLong_SHIFT)) { + return (size_t) (((size_t)-1)*(((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(size_t) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 3 * PyLong_SHIFT)) { + return (size_t) ((((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(size_t) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 4 * PyLong_SHIFT)) { + return (size_t) (((size_t)-1)*(((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(size_t) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 4 * PyLong_SHIFT)) { + return (size_t) ((((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(size_t) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(size_t) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + size_t val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (size_t) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (size_t) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (size_t) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (size_t) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (size_t) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(size_t) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((size_t) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(size_t) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((size_t) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((size_t) 1) << (sizeof(size_t) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (size_t) -1; + } + } else { + size_t val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (size_t) -1; + val = __Pyx_PyInt_As_size_t(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to size_t"); + return (size_t) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to size_t"); + return (size_t) -1; +} + +/* CIntToPy */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_uint32_t(uint32_t value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const uint32_t neg_one = (uint32_t) -1, const_zero = (uint32_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(uint32_t) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(uint32_t) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(uint32_t) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(uint32_t) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(uint32_t) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; +#if !CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030d0000 + return _PyLong_FromByteArray(bytes, sizeof(uint32_t), + little, !is_unsigned); +#else + PyObject *from_bytes, *result = NULL; + PyObject *py_bytes = NULL, *arg_tuple = NULL, *kwds = NULL, *order_str = NULL; + from_bytes = PyObject_GetAttrString((PyObject*)&PyLong_Type, "from_bytes"); + if (!from_bytes) return NULL; + py_bytes = PyBytes_FromStringAndSize((char*)bytes, sizeof(uint32_t)); + if (!py_bytes) goto limited_bad; + order_str = PyUnicode_FromString(little ? "little" : "big"); + if (!order_str) goto limited_bad; + arg_tuple = PyTuple_Pack(2, py_bytes, order_str); + if (!arg_tuple) goto limited_bad; + if (!is_unsigned) { + kwds = PyDict_New(); + if (!kwds) goto limited_bad; + if (PyDict_SetItemString(kwds, "signed", __Pyx_NewRef(Py_True))) goto limited_bad; + } + result = PyObject_Call(from_bytes, arg_tuple, kwds); + limited_bad: + Py_XDECREF(kwds); + Py_XDECREF(arg_tuple); + Py_XDECREF(order_str); + Py_XDECREF(py_bytes); + Py_XDECREF(from_bytes); + return result; +#endif + } +} + +/* CIntToPy */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(long) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(long) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(long) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; +#if !CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030d0000 + return _PyLong_FromByteArray(bytes, sizeof(long), + little, !is_unsigned); +#else + PyObject *from_bytes, *result = NULL; + PyObject *py_bytes = NULL, *arg_tuple = NULL, *kwds = NULL, *order_str = NULL; + from_bytes = PyObject_GetAttrString((PyObject*)&PyLong_Type, "from_bytes"); + if (!from_bytes) return NULL; + py_bytes = PyBytes_FromStringAndSize((char*)bytes, sizeof(long)); + if (!py_bytes) goto limited_bad; + order_str = PyUnicode_FromString(little ? "little" : "big"); + if (!order_str) goto limited_bad; + arg_tuple = PyTuple_Pack(2, py_bytes, order_str); + if (!arg_tuple) goto limited_bad; + if (!is_unsigned) { + kwds = PyDict_New(); + if (!kwds) goto limited_bad; + if (PyDict_SetItemString(kwds, "signed", __Pyx_NewRef(Py_True))) goto limited_bad; + } + result = PyObject_Call(from_bytes, arg_tuple, kwds); + limited_bad: + Py_XDECREF(kwds); + Py_XDECREF(arg_tuple); + Py_XDECREF(order_str); + Py_XDECREF(py_bytes); + Py_XDECREF(from_bytes); + return result; +#endif + } +} + +/* CIntFromPy */ +static CYTHON_INLINE uint32_t __Pyx_PyInt_As_uint32_t(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const uint32_t neg_one = (uint32_t) -1, const_zero = (uint32_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(uint32_t) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(uint32_t, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (uint32_t) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(uint32_t, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(uint32_t) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) >= 2 * PyLong_SHIFT)) { + return (uint32_t) (((((uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(uint32_t) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) >= 3 * PyLong_SHIFT)) { + return (uint32_t) (((((((uint32_t)digits[2]) << PyLong_SHIFT) | (uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(uint32_t) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) >= 4 * PyLong_SHIFT)) { + return (uint32_t) (((((((((uint32_t)digits[3]) << PyLong_SHIFT) | (uint32_t)digits[2]) << PyLong_SHIFT) | (uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (uint32_t) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(uint32_t) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(uint32_t, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(uint32_t) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(uint32_t, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(uint32_t, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(uint32_t) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) - 1 > 2 * PyLong_SHIFT)) { + return (uint32_t) (((uint32_t)-1)*(((((uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(uint32_t) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) - 1 > 2 * PyLong_SHIFT)) { + return (uint32_t) ((((((uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(uint32_t) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) - 1 > 3 * PyLong_SHIFT)) { + return (uint32_t) (((uint32_t)-1)*(((((((uint32_t)digits[2]) << PyLong_SHIFT) | (uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(uint32_t) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) - 1 > 3 * PyLong_SHIFT)) { + return (uint32_t) ((((((((uint32_t)digits[2]) << PyLong_SHIFT) | (uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(uint32_t) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) - 1 > 4 * PyLong_SHIFT)) { + return (uint32_t) (((uint32_t)-1)*(((((((((uint32_t)digits[3]) << PyLong_SHIFT) | (uint32_t)digits[2]) << PyLong_SHIFT) | (uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(uint32_t) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(uint32_t, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(uint32_t) - 1 > 4 * PyLong_SHIFT)) { + return (uint32_t) ((((((((((uint32_t)digits[3]) << PyLong_SHIFT) | (uint32_t)digits[2]) << PyLong_SHIFT) | (uint32_t)digits[1]) << PyLong_SHIFT) | (uint32_t)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(uint32_t) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(uint32_t, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(uint32_t) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(uint32_t, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + uint32_t val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (uint32_t) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (uint32_t) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (uint32_t) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (uint32_t) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (uint32_t) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(uint32_t) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((uint32_t) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(uint32_t) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((uint32_t) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((uint32_t) 1) << (sizeof(uint32_t) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (uint32_t) -1; + } + } else { + uint32_t val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (uint32_t) -1; + val = __Pyx_PyInt_As_uint32_t(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to uint32_t"); + return (uint32_t) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to uint32_t"); + return (uint32_t) -1; +} + +/* CIntFromPy */ +static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(int) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(int, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (int) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 2 * PyLong_SHIFT)) { + return (int) (((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 3 * PyLong_SHIFT)) { + return (int) (((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 4 * PyLong_SHIFT)) { + return (int) (((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(int) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(int) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) ((((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) ((((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) ((((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(int) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + int val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (int) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (int) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (int) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (int) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(int) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(int) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((int) 1) << (sizeof(int) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (int) -1; + } + } else { + int val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (int) -1; + val = __Pyx_PyInt_As_int(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to int"); + return (int) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to int"); + return (int) -1; +} + +/* CIntToPy */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_uint64_t(uint64_t value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const uint64_t neg_one = (uint64_t) -1, const_zero = (uint64_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(uint64_t) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(uint64_t) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(uint64_t) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(uint64_t) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(uint64_t) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; +#if !CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030d0000 + return _PyLong_FromByteArray(bytes, sizeof(uint64_t), + little, !is_unsigned); +#else + PyObject *from_bytes, *result = NULL; + PyObject *py_bytes = NULL, *arg_tuple = NULL, *kwds = NULL, *order_str = NULL; + from_bytes = PyObject_GetAttrString((PyObject*)&PyLong_Type, "from_bytes"); + if (!from_bytes) return NULL; + py_bytes = PyBytes_FromStringAndSize((char*)bytes, sizeof(uint64_t)); + if (!py_bytes) goto limited_bad; + order_str = PyUnicode_FromString(little ? "little" : "big"); + if (!order_str) goto limited_bad; + arg_tuple = PyTuple_Pack(2, py_bytes, order_str); + if (!arg_tuple) goto limited_bad; + if (!is_unsigned) { + kwds = PyDict_New(); + if (!kwds) goto limited_bad; + if (PyDict_SetItemString(kwds, "signed", __Pyx_NewRef(Py_True))) goto limited_bad; + } + result = PyObject_Call(from_bytes, arg_tuple, kwds); + limited_bad: + Py_XDECREF(kwds); + Py_XDECREF(arg_tuple); + Py_XDECREF(order_str); + Py_XDECREF(py_bytes); + Py_XDECREF(from_bytes); + return result; +#endif + } +} + +/* FormatTypeName */ +#if CYTHON_COMPILING_IN_LIMITED_API +static __Pyx_TypeName +__Pyx_PyType_GetName(PyTypeObject* tp) +{ + PyObject *name = __Pyx_PyObject_GetAttrStr((PyObject *)tp, + __pyx_n_s_name); + if (unlikely(name == NULL) || unlikely(!PyUnicode_Check(name))) { + PyErr_Clear(); + Py_XDECREF(name); + name = __Pyx_NewRef(__pyx_n_s__15); + } + return name; +} +#endif + +/* CIntFromPy */ +static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(long) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(long, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (long) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 2 * PyLong_SHIFT)) { + return (long) (((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 3 * PyLong_SHIFT)) { + return (long) (((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 4 * PyLong_SHIFT)) { + return (long) (((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(long) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(long) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) ((((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) ((((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) ((((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(long) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + long val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (long) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (long) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (long) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (long) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(long) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(long) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((long) 1) << (sizeof(long) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (long) -1; + } + } else { + long val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (long) -1; + val = __Pyx_PyInt_As_long(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to long"); + return (long) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to long"); + return (long) -1; +} + +/* FastTypeChecks */ +#if CYTHON_COMPILING_IN_CPYTHON +static int __Pyx_InBases(PyTypeObject *a, PyTypeObject *b) { + while (a) { + a = __Pyx_PyType_GetSlot(a, tp_base, PyTypeObject*); + if (a == b) + return 1; + } + return b == &PyBaseObject_Type; +} +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (a == b) return 1; + mro = a->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + if (PyTuple_GET_ITEM(mro, i) == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(a, b); +} +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (cls == a || cls == b) return 1; + mro = cls->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + PyObject *base = PyTuple_GET_ITEM(mro, i); + if (base == (PyObject *)a || base == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(cls, a) || __Pyx_InBases(cls, b); +} +#if PY_MAJOR_VERSION == 2 +static int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject* exc_type2) { + PyObject *exception, *value, *tb; + int res; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&exception, &value, &tb); + res = exc_type1 ? PyObject_IsSubclass(err, exc_type1) : 0; + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + if (!res) { + res = PyObject_IsSubclass(err, exc_type2); + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + } + __Pyx_ErrRestore(exception, value, tb); + return res; +} +#else +static CYTHON_INLINE int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject *exc_type2) { + if (exc_type1) { + return __Pyx_IsAnySubtype2((PyTypeObject*)err, (PyTypeObject*)exc_type1, (PyTypeObject*)exc_type2); + } else { + return __Pyx_IsSubtype((PyTypeObject*)err, (PyTypeObject*)exc_type2); + } +} +#endif +static int __Pyx_PyErr_GivenExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + assert(PyExceptionClass_Check(exc_type)); + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; i= 0x030B00A4 + return Py_Version & ~0xFFUL; +#else + const char* rt_version = Py_GetVersion(); + unsigned long version = 0; + unsigned long factor = 0x01000000UL; + unsigned int digit = 0; + int i = 0; + while (factor) { + while ('0' <= rt_version[i] && rt_version[i] <= '9') { + digit = digit * 10 + (unsigned int) (rt_version[i] - '0'); + ++i; + } + version += factor * digit; + if (rt_version[i] != '.') + break; + digit = 0; + factor >>= 8; + ++i; + } + return version; +#endif +} +static int __Pyx_check_binary_version(unsigned long ct_version, unsigned long rt_version, int allow_newer) { + const unsigned long MAJOR_MINOR = 0xFFFF0000UL; + if ((rt_version & MAJOR_MINOR) == (ct_version & MAJOR_MINOR)) + return 0; + if (likely(allow_newer && (rt_version & MAJOR_MINOR) > (ct_version & MAJOR_MINOR))) + return 1; + { + char message[200]; + PyOS_snprintf(message, sizeof(message), + "compile time Python version %d.%d " + "of module '%.100s' " + "%s " + "runtime version %d.%d", + (int) (ct_version >> 24), (int) ((ct_version >> 16) & 0xFF), + __Pyx_MODULE_NAME, + (allow_newer) ? "was newer than" : "does not match", + (int) (rt_version >> 24), (int) ((rt_version >> 16) & 0xFF) + ); + return PyErr_WarnEx(NULL, message, 1); + } +} + +/* InitStrings */ +#if PY_MAJOR_VERSION >= 3 +static int __Pyx_InitString(__Pyx_StringTabEntry t, PyObject **str) { + if (t.is_unicode | t.is_str) { + if (t.intern) { + *str = PyUnicode_InternFromString(t.s); + } else if (t.encoding) { + *str = PyUnicode_Decode(t.s, t.n - 1, t.encoding, NULL); + } else { + *str = PyUnicode_FromStringAndSize(t.s, t.n - 1); + } + } else { + *str = PyBytes_FromStringAndSize(t.s, t.n - 1); + } + if (!*str) + return -1; + if (PyObject_Hash(*str) == -1) + return -1; + return 0; +} +#endif +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t) { + while (t->p) { + #if PY_MAJOR_VERSION >= 3 + __Pyx_InitString(*t, t->p); + #else + if (t->is_unicode) { + *t->p = PyUnicode_DecodeUTF8(t->s, t->n - 1, NULL); + } else if (t->intern) { + *t->p = PyString_InternFromString(t->s); + } else { + *t->p = PyString_FromStringAndSize(t->s, t->n - 1); + } + if (!*t->p) + return -1; + if (PyObject_Hash(*t->p) == -1) + return -1; + #endif + ++t; + } + return 0; +} + +#include +static CYTHON_INLINE Py_ssize_t __Pyx_ssize_strlen(const char *s) { + size_t len = strlen(s); + if (unlikely(len > (size_t) PY_SSIZE_T_MAX)) { + PyErr_SetString(PyExc_OverflowError, "byte string is too long"); + return -1; + } + return (Py_ssize_t) len; +} +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char* c_str) { + Py_ssize_t len = __Pyx_ssize_strlen(c_str); + if (unlikely(len < 0)) return NULL; + return __Pyx_PyUnicode_FromStringAndSize(c_str, len); +} +static CYTHON_INLINE PyObject* __Pyx_PyByteArray_FromString(const char* c_str) { + Py_ssize_t len = __Pyx_ssize_strlen(c_str); + if (unlikely(len < 0)) return NULL; + return PyByteArray_FromStringAndSize(c_str, len); +} +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject* o) { + Py_ssize_t ignore; + return __Pyx_PyObject_AsStringAndSize(o, &ignore); +} +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +#if !CYTHON_PEP393_ENABLED +static const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + char* defenc_c; + PyObject* defenc = _PyUnicode_AsDefaultEncodedString(o, NULL); + if (!defenc) return NULL; + defenc_c = PyBytes_AS_STRING(defenc); +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + { + char* end = defenc_c + PyBytes_GET_SIZE(defenc); + char* c; + for (c = defenc_c; c < end; c++) { + if ((unsigned char) (*c) >= 128) { + PyUnicode_AsASCIIString(o); + return NULL; + } + } + } +#endif + *length = PyBytes_GET_SIZE(defenc); + return defenc_c; +} +#else +static CYTHON_INLINE const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + if (unlikely(__Pyx_PyUnicode_READY(o) == -1)) return NULL; +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + if (likely(PyUnicode_IS_ASCII(o))) { + *length = PyUnicode_GET_LENGTH(o); + return PyUnicode_AsUTF8(o); + } else { + PyUnicode_AsASCIIString(o); + return NULL; + } +#else + return PyUnicode_AsUTF8AndSize(o, length); +#endif +} +#endif +#endif +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject* o, Py_ssize_t *length) { +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT + if ( +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + __Pyx_sys_getdefaultencoding_not_ascii && +#endif + PyUnicode_Check(o)) { + return __Pyx_PyUnicode_AsStringAndSize(o, length); + } else +#endif +#if (!CYTHON_COMPILING_IN_PYPY && !CYTHON_COMPILING_IN_LIMITED_API) || (defined(PyByteArray_AS_STRING) && defined(PyByteArray_GET_SIZE)) + if (PyByteArray_Check(o)) { + *length = PyByteArray_GET_SIZE(o); + return PyByteArray_AS_STRING(o); + } else +#endif + { + char* result; + int r = PyBytes_AsStringAndSize(o, &result, length); + if (unlikely(r < 0)) { + return NULL; + } else { + return result; + } + } +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject* x) { + int is_true = x == Py_True; + if (is_true | (x == Py_False) | (x == Py_None)) return is_true; + else return PyObject_IsTrue(x); +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject* x) { + int retval; + if (unlikely(!x)) return -1; + retval = __Pyx_PyObject_IsTrue(x); + Py_DECREF(x); + return retval; +} +static PyObject* __Pyx_PyNumber_IntOrLongWrongResultType(PyObject* result, const char* type_name) { + __Pyx_TypeName result_type_name = __Pyx_PyType_GetName(Py_TYPE(result)); +#if PY_MAJOR_VERSION >= 3 + if (PyLong_Check(result)) { + if (PyErr_WarnFormat(PyExc_DeprecationWarning, 1, + "__int__ returned non-int (type " __Pyx_FMT_TYPENAME "). " + "The ability to return an instance of a strict subclass of int is deprecated, " + "and may be removed in a future version of Python.", + result_type_name)) { + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; + } + __Pyx_DECREF_TypeName(result_type_name); + return result; + } +#endif + PyErr_Format(PyExc_TypeError, + "__%.4s__ returned non-%.4s (type " __Pyx_FMT_TYPENAME ")", + type_name, type_name, result_type_name); + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x) { +#if CYTHON_USE_TYPE_SLOTS + PyNumberMethods *m; +#endif + const char *name = NULL; + PyObject *res = NULL; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x) || PyLong_Check(x))) +#else + if (likely(PyLong_Check(x))) +#endif + return __Pyx_NewRef(x); +#if CYTHON_USE_TYPE_SLOTS + m = Py_TYPE(x)->tp_as_number; + #if PY_MAJOR_VERSION < 3 + if (m && m->nb_int) { + name = "int"; + res = m->nb_int(x); + } + else if (m && m->nb_long) { + name = "long"; + res = m->nb_long(x); + } + #else + if (likely(m && m->nb_int)) { + name = "int"; + res = m->nb_int(x); + } + #endif +#else + if (!PyBytes_CheckExact(x) && !PyUnicode_CheckExact(x)) { + res = PyNumber_Int(x); + } +#endif + if (likely(res)) { +#if PY_MAJOR_VERSION < 3 + if (unlikely(!PyInt_Check(res) && !PyLong_Check(res))) { +#else + if (unlikely(!PyLong_CheckExact(res))) { +#endif + return __Pyx_PyNumber_IntOrLongWrongResultType(res, name); + } + } + else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_TypeError, + "an integer is required"); + } + return res; +} +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject* b) { + Py_ssize_t ival; + PyObject *x; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_CheckExact(b))) { + if (sizeof(Py_ssize_t) >= sizeof(long)) + return PyInt_AS_LONG(b); + else + return PyInt_AsSsize_t(b); + } +#endif + if (likely(PyLong_CheckExact(b))) { + #if CYTHON_USE_PYLONG_INTERNALS + if (likely(__Pyx_PyLong_IsCompact(b))) { + return __Pyx_PyLong_CompactValue(b); + } else { + const digit* digits = __Pyx_PyLong_Digits(b); + const Py_ssize_t size = __Pyx_PyLong_SignedDigitCount(b); + switch (size) { + case 2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return (Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + } + } + #endif + return PyLong_AsSsize_t(b); + } + x = PyNumber_Index(b); + if (!x) return -1; + ival = PyInt_AsSsize_t(x); + Py_DECREF(x); + return ival; +} +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject* o) { + if (sizeof(Py_hash_t) == sizeof(Py_ssize_t)) { + return (Py_hash_t) __Pyx_PyIndex_AsSsize_t(o); +#if PY_MAJOR_VERSION < 3 + } else if (likely(PyInt_CheckExact(o))) { + return PyInt_AS_LONG(o); +#endif + } else { + Py_ssize_t ival; + PyObject *x; + x = PyNumber_Index(o); + if (!x) return -1; + ival = PyInt_AsLong(x); + Py_DECREF(x); + return ival; + } +} +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b) { + return b ? __Pyx_NewRef(Py_True) : __Pyx_NewRef(Py_False); +} +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t ival) { + return PyInt_FromSize_t(ival); +} + + +/* #### Code section: utility_code_pragmas_end ### */ +#ifdef _MSC_VER +#pragma warning( pop ) +#endif + + + +/* #### Code section: end ### */ +#endif /* Py_PYTHON_H */ diff --git a/opendbc/can/parser_pyx.so b/opendbc/can/parser_pyx.so new file mode 100755 index 0000000..c949622 Binary files /dev/null and b/opendbc/can/parser_pyx.so differ diff --git a/panda/SConscript b/panda/SConscript deleted file mode 100644 index 357daba..0000000 --- a/panda/SConscript +++ /dev/null @@ -1,188 +0,0 @@ -import os -import subprocess - - -PREFIX = "arm-none-eabi-" -BUILDER = "DEV" - -common_flags = [] - -panda_root = Dir('.') - -if os.getenv("RELEASE"): - BUILD_TYPE = "RELEASE" - cert_fn = os.getenv("CERT") - assert cert_fn is not None, 'No certificate file specified. Please set CERT env variable' - assert os.path.exists(cert_fn), 'Certificate file not found. Please specify absolute path' -else: - BUILD_TYPE = "DEBUG" - cert_fn = File("./certs/debug").srcnode().relpath - common_flags += ["-DALLOW_DEBUG"] - - if os.getenv("DEBUG"): - common_flags += ["-DDEBUG"] - -def objcopy(source, target, env, for_signature): - return '$OBJCOPY -O binary %s %s' % (source[0], target[0]) - -def get_version(builder, build_type): - try: - git = subprocess.check_output(["git", "rev-parse", "--short=8", "HEAD"], encoding='utf8').strip() - except subprocess.CalledProcessError: - git = "unknown" - return f"{builder}-{git}-{build_type}" - -def get_key_header(name): - from Crypto.PublicKey import RSA - - public_fn = File(f'./certs/{name}.pub').srcnode().get_path() - with open(public_fn) as f: - rsa = RSA.importKey(f.read()) - assert(rsa.size_in_bits() == 1024) - - rr = pow(2**1024, 2, rsa.n) - n0inv = 2**32 - pow(rsa.n, -1, 2**32) - - r = [ - f"RSAPublicKey {name}_rsa_key = {{", - f" .len = 0x20,", - f" .n0inv = {n0inv}U,", - f" .n = {to_c_uint32(rsa.n)},", - f" .rr = {to_c_uint32(rr)},", - f" .exponent = {rsa.e},", - f"}};", - ] - return r - -def to_c_uint32(x): - nums = [] - for _ in range(0x20): - nums.append(x % (2**32)) - x //= (2**32) - return "{" + 'U,'.join(map(str, nums)) + "U}" - - -def build_project(project_name, project, extra_flags): - linkerscript_fn = File(project["LINKER_SCRIPT"]).srcnode().relpath - - flags = project["PROJECT_FLAGS"] + extra_flags + common_flags + [ - "-Wall", - "-Wextra", - "-Wstrict-prototypes", - "-Werror", - "-mlittle-endian", - "-mthumb", - "-nostdlib", - "-fno-builtin", - "-std=gnu11", - "-fmax-errors=1", - f"-T{linkerscript_fn}", - ] - - includes = [ - '.', - '..', - panda_root, - f"{panda_root}/board/", - f"{panda_root}/board/stm32fx/inc", - f"{panda_root}/board/stm32h7/inc", - ] - - env = Environment( - ENV=os.environ, - CC=PREFIX + 'gcc', - AS=PREFIX + 'gcc', - OBJCOPY=PREFIX + 'objcopy', - OBJDUMP=PREFIX + 'objdump', - CFLAGS=flags, - ASFLAGS=flags, - LINKFLAGS=flags, - CPPPATH=includes, - ASCOM="$AS $ASFLAGS -o $TARGET -c $SOURCES", - BUILDERS={ - 'Objcopy': Builder(generator=objcopy, suffix='.bin', src_suffix='.elf') - }, - tools=["default", "compilation_db"], - ) - - startup = env.Object(f"obj/startup_{project_name}", project["STARTUP_FILE"]) - - # Bootstub - crypto_obj = [ - env.Object(f"rsa-{project_name}", f"{panda_root}/crypto/rsa.c"), - env.Object(f"sha-{project_name}", f"{panda_root}/crypto/sha.c") - ] - bootstub_obj = env.Object(f"bootstub-{project_name}", File(project.get("BOOTSTUB", f"{panda_root}/board/bootstub.c"))) - bootstub_elf = env.Program(f"obj/bootstub.{project_name}.elf", - [startup] + crypto_obj + [bootstub_obj]) - env.Objcopy(f"obj/bootstub.{project_name}.bin", bootstub_elf) - - # Build main - main_obj = env.Object(f"main-{project_name}", project["MAIN"]) - main_elf = env.Program(f"obj/{project_name}.elf", [startup, main_obj], - LINKFLAGS=[f"-Wl,--section-start,.isr_vector={project['APP_START_ADDRESS']}"] + flags) - main_bin = env.Objcopy(f"obj/{project_name}.bin", main_elf) - - # Sign main - sign_py = File(f"{panda_root}/crypto/sign.py").srcnode().relpath - env.Command(f"obj/{project_name}.bin.signed", main_bin, f"SETLEN=1 {sign_py} $SOURCE $TARGET {cert_fn}") - - -base_project_f4 = { - "MAIN": "main.c", - "STARTUP_FILE": File("./board/stm32fx/startup_stm32f413xx.s"), - "LINKER_SCRIPT": File("./board/stm32fx/stm32f4_flash.ld"), - "APP_START_ADDRESS": "0x8004000", - "PROJECT_FLAGS": [ - "-mcpu=cortex-m4", - "-mhard-float", - "-DSTM32F4", - "-DSTM32F413xx", - "-mfpu=fpv4-sp-d16", - "-fsingle-precision-constant", - "-Os", - "-g", - ], -} - -base_project_h7 = { - "MAIN": "main.c", - "STARTUP_FILE": File("./board/stm32h7/startup_stm32h7x5xx.s"), - "LINKER_SCRIPT": File("./board/stm32h7/stm32h7x5_flash.ld"), - "APP_START_ADDRESS": "0x8020000", - "PROJECT_FLAGS": [ - "-mcpu=cortex-m7", - "-mhard-float", - "-DSTM32H7", - "-DSTM32H725xx", - "-mfpu=fpv5-d16", - "-fsingle-precision-constant", - "-Os", - "-g", - ], -} - -Export('base_project_f4', 'base_project_h7', 'build_project') - - -# Common autogenerated includes -with open("board/obj/gitversion.h", "w") as f: - f.write(f'const uint8_t gitversion[] = "{get_version(BUILDER, BUILD_TYPE)}";\n') - -with open("board/obj/version", "w") as f: - f.write(f'{get_version(BUILDER, BUILD_TYPE)}') - -certs = [get_key_header(n) for n in ["debug", "release"]] -with open("board/obj/cert.h", "w") as f: - for cert in certs: - f.write("\n".join(cert) + "\n") - -# panda fw -SConscript('board/SConscript') - -# panda jungle fw -SConscript('board/jungle/SConscript') - -# test files -if GetOption('extras'): - SConscript('tests/libpanda/SConscript') diff --git a/panda/board/SConscript b/panda/board/SConscript deleted file mode 100644 index 93fd47b..0000000 --- a/panda/board/SConscript +++ /dev/null @@ -1,21 +0,0 @@ -import os -import copy - -Import('build_project', 'base_project_f4', 'base_project_h7') - -build_projects = { - "panda": base_project_f4, - "panda_h7": base_project_h7, -} - -for project_name, project in build_projects.items(): - flags = [ - "-DPANDA", - ] - if ("ENABLE_SPI" in os.environ or "h7" in project_name): - flags.append('-DENABLE_SPI') - - if "H723" in os.environ: - flags.append('-DSTM32H723') - - build_project(project_name, project, flags) diff --git a/panda/board/boards/black.h b/panda/board/boards/black.h deleted file mode 100644 index ea63633..0000000 --- a/panda/board/boards/black.h +++ /dev/null @@ -1,189 +0,0 @@ -// /////////////////////////////// // -// Black Panda (STM32F4) + Harness // -// /////////////////////////////// // - -void black_enable_can_transceiver(uint8_t transceiver, bool enabled) { - switch (transceiver){ - case 1U: - set_gpio_output(GPIOC, 1, !enabled); - break; - case 2U: - set_gpio_output(GPIOC, 13, !enabled); - break; - case 3U: - set_gpio_output(GPIOA, 0, !enabled); - break; - case 4U: - set_gpio_output(GPIOB, 10, !enabled); - break; - default: - print("Invalid CAN transceiver ("); puth(transceiver); print("): enabling failed\n"); - break; - } -} - -void black_enable_can_transceivers(bool enabled) { - for(uint8_t i=1U; i<=4U; i++){ - // Leave main CAN always on for CAN-based ignition detection - if((harness.status == HARNESS_STATUS_FLIPPED) ? (i == 3U) : (i == 1U)){ - black_enable_can_transceiver(i, true); - } else { - black_enable_can_transceiver(i, enabled); - } - } -} - -void black_set_led(uint8_t color, bool enabled) { - switch (color){ - case LED_RED: - set_gpio_output(GPIOC, 9, !enabled); - break; - case LED_GREEN: - set_gpio_output(GPIOC, 7, !enabled); - break; - case LED_BLUE: - set_gpio_output(GPIOC, 6, !enabled); - break; - default: - break; - } -} - -void black_set_usb_load_switch(bool enabled) { - set_gpio_output(GPIOB, 1, !enabled); -} - -void black_set_can_mode(uint8_t mode) { - black_enable_can_transceiver(2U, false); - black_enable_can_transceiver(4U, false); - switch (mode) { - case CAN_MODE_NORMAL: - case CAN_MODE_OBD_CAN2: - if ((bool)(mode == CAN_MODE_NORMAL) != (bool)(harness.status == HARNESS_STATUS_FLIPPED)) { - // B12,B13: disable OBD mode - set_gpio_mode(GPIOB, 12, MODE_INPUT); - set_gpio_mode(GPIOB, 13, MODE_INPUT); - - // B5,B6: normal CAN2 mode - set_gpio_alternate(GPIOB, 5, GPIO_AF9_CAN2); - set_gpio_alternate(GPIOB, 6, GPIO_AF9_CAN2); - black_enable_can_transceiver(2U, true); - - } else { - // B5,B6: disable normal CAN2 mode - set_gpio_mode(GPIOB, 5, MODE_INPUT); - set_gpio_mode(GPIOB, 6, MODE_INPUT); - - // B12,B13: OBD mode - set_gpio_alternate(GPIOB, 12, GPIO_AF9_CAN2); - set_gpio_alternate(GPIOB, 13, GPIO_AF9_CAN2); - black_enable_can_transceiver(4U, true); - } - break; - default: - print("Tried to set unsupported CAN mode: "); puth(mode); print("\n"); - break; - } -} - -bool black_check_ignition(void){ - // ignition is checked through harness - return harness_check_ignition(); -} - -void black_init(void) { - common_init_gpio(); - - // A8,A15: normal CAN3 mode - set_gpio_alternate(GPIOA, 8, GPIO_AF11_CAN3); - set_gpio_alternate(GPIOA, 15, GPIO_AF11_CAN3); - - // C0: OBD_SBU1 (orientation detection) - // C3: OBD_SBU2 (orientation detection) - set_gpio_mode(GPIOC, 0, MODE_ANALOG); - set_gpio_mode(GPIOC, 3, MODE_ANALOG); - - // GPS OFF - set_gpio_output(GPIOC, 5, 0); - set_gpio_output(GPIOC, 12, 0); - - // C10: OBD_SBU1_RELAY (harness relay driving output) - // C11: OBD_SBU2_RELAY (harness relay driving output) - set_gpio_mode(GPIOC, 10, MODE_OUTPUT); - set_gpio_mode(GPIOC, 11, MODE_OUTPUT); - set_gpio_output_type(GPIOC, 10, OUTPUT_TYPE_OPEN_DRAIN); - set_gpio_output_type(GPIOC, 11, OUTPUT_TYPE_OPEN_DRAIN); - set_gpio_output(GPIOC, 10, 1); - set_gpio_output(GPIOC, 11, 1); - - // Turn on USB load switch. - black_set_usb_load_switch(true); - - // Initialize harness - harness_init(); - - // Initialize RTC - rtc_init(); - - // Enable CAN transceivers - black_enable_can_transceivers(true); - - // Disable LEDs - black_set_led(LED_RED, false); - black_set_led(LED_GREEN, false); - black_set_led(LED_BLUE, false); - - // Set normal CAN mode - black_set_can_mode(CAN_MODE_NORMAL); - - // change CAN mapping when flipped - if (harness.status == HARNESS_STATUS_FLIPPED) { - can_flip_buses(0, 2); - } -} - -void black_init_bootloader(void) { - // GPS OFF - set_gpio_output(GPIOC, 5, 0); - set_gpio_output(GPIOC, 12, 0); -} - -const harness_configuration black_harness_config = { - .has_harness = true, - .GPIO_SBU1 = GPIOC, - .GPIO_SBU2 = GPIOC, - .GPIO_relay_SBU1 = GPIOC, - .GPIO_relay_SBU2 = GPIOC, - .pin_SBU1 = 0, - .pin_SBU2 = 3, - .pin_relay_SBU1 = 10, - .pin_relay_SBU2 = 11, - .adc_channel_SBU1 = 10, - .adc_channel_SBU2 = 13 -}; - -const board board_black = { - .set_bootkick = unused_set_bootkick, - .harness_config = &black_harness_config, - .has_obd = true, - .has_spi = false, - .has_canfd = false, - .has_rtc_battery = false, - .fan_max_rpm = 0U, - .avdd_mV = 3300U, - .fan_stall_recovery = false, - .fan_enable_cooldown_time = 0U, - .init = black_init, - .init_bootloader = black_init_bootloader, - .enable_can_transceiver = black_enable_can_transceiver, - .enable_can_transceivers = black_enable_can_transceivers, - .set_led = black_set_led, - .set_can_mode = black_set_can_mode, - .check_ignition = black_check_ignition, - .read_voltage_mV = white_read_voltage_mV, - .read_current_mA = unused_read_current, - .set_fan_enabled = unused_set_fan_enabled, - .set_ir_power = unused_set_ir_power, - .set_siren = unused_set_siren, - .read_som_gpio = unused_read_som_gpio -}; diff --git a/panda/board/boards/board_declarations.h b/panda/board/boards/board_declarations.h deleted file mode 100644 index 600dc28..0000000 --- a/panda/board/boards/board_declarations.h +++ /dev/null @@ -1,78 +0,0 @@ -// ******************** Prototypes ******************** -typedef enum { - BOOT_STANDBY, - BOOT_BOOTKICK, - BOOT_RESET, -} BootState; - -typedef void (*board_init)(void); -typedef void (*board_init_bootloader)(void); -typedef void (*board_enable_can_transceiver)(uint8_t transceiver, bool enabled); -typedef void (*board_enable_can_transceivers)(bool enabled); -typedef void (*board_set_led)(uint8_t color, bool enabled); -typedef void (*board_set_can_mode)(uint8_t mode); -typedef bool (*board_check_ignition)(void); -typedef uint32_t (*board_read_voltage_mV)(void); -typedef uint32_t (*board_read_current_mA)(void); -typedef void (*board_set_ir_power)(uint8_t percentage); -typedef void (*board_set_fan_enabled)(bool enabled); -typedef void (*board_set_siren)(bool enabled); -typedef void (*board_set_bootkick)(BootState state); -typedef bool (*board_read_som_gpio)(void); - -struct board { - const harness_configuration *harness_config; - const bool has_obd; - const bool has_spi; - const bool has_canfd; - const bool has_rtc_battery; - const uint16_t fan_max_rpm; - const uint16_t avdd_mV; - const bool fan_stall_recovery; - const uint8_t fan_enable_cooldown_time; - board_init init; - board_init_bootloader init_bootloader; - board_enable_can_transceiver enable_can_transceiver; - board_enable_can_transceivers enable_can_transceivers; - board_set_led set_led; - board_set_can_mode set_can_mode; - board_check_ignition check_ignition; - board_read_voltage_mV read_voltage_mV; - board_read_current_mA read_current_mA; - board_set_ir_power set_ir_power; - board_set_fan_enabled set_fan_enabled; - board_set_siren set_siren; - board_set_bootkick set_bootkick; - board_read_som_gpio read_som_gpio; -}; - -// ******************* Definitions ******************** -// These should match the enums in cereal/log.capnp and __init__.py -#define HW_TYPE_UNKNOWN 0U -#define HW_TYPE_WHITE_PANDA 1U -#define HW_TYPE_GREY_PANDA 2U -#define HW_TYPE_BLACK_PANDA 3U -#define HW_TYPE_PEDAL 4U -#define HW_TYPE_UNO 5U -#define HW_TYPE_DOS 6U -#define HW_TYPE_RED_PANDA 7U -#define HW_TYPE_RED_PANDA_V2 8U -#define HW_TYPE_TRES 9U -#define HW_TYPE_CUATRO 10U - -// LED colors -#define LED_RED 0U -#define LED_GREEN 1U -#define LED_BLUE 2U - -// USB power modes (from cereal.log.health) -#define USB_POWER_NONE 0U -#define USB_POWER_CLIENT 1U -#define USB_POWER_CDP 2U -#define USB_POWER_DCP 3U - -// CAN modes -#define CAN_MODE_NORMAL 0U -#define CAN_MODE_GMLAN_CAN2 1U -#define CAN_MODE_GMLAN_CAN3 2U -#define CAN_MODE_OBD_CAN2 3U diff --git a/panda/board/boards/cuatro.h b/panda/board/boards/cuatro.h deleted file mode 100644 index b8cd3d0..0000000 --- a/panda/board/boards/cuatro.h +++ /dev/null @@ -1,130 +0,0 @@ -// ////////////////////////// // -// Cuatro (STM32H7) + Harness // -// ////////////////////////// // - -void cuatro_set_led(uint8_t color, bool enabled) { - switch (color) { - case LED_RED: - set_gpio_output(GPIOD, 15, !enabled); - break; - case LED_GREEN: - set_gpio_output(GPIOD, 14, !enabled); - break; - case LED_BLUE: - set_gpio_output(GPIOE, 2, !enabled); - break; - default: - break; - } -} - -void cuatro_enable_can_transceiver(uint8_t transceiver, bool enabled) { - switch (transceiver) { - case 1U: - set_gpio_output(GPIOB, 7, !enabled); - break; - case 2U: - set_gpio_output(GPIOB, 10, !enabled); - break; - case 3U: - set_gpio_output(GPIOD, 8, !enabled); - break; - case 4U: - set_gpio_output(GPIOB, 11, !enabled); - break; - default: - break; - } -} - -void cuatro_enable_can_transceivers(bool enabled) { - uint8_t main_bus = (harness.status == HARNESS_STATUS_FLIPPED) ? 3U : 1U; - for (uint8_t i=1U; i<=4U; i++) { - // Leave main CAN always on for CAN-based ignition detection - if (i == main_bus) { - cuatro_enable_can_transceiver(i, true); - } else { - cuatro_enable_can_transceiver(i, enabled); - } - } -} - -uint32_t cuatro_read_voltage_mV(void) { - return adc_get_mV(8) * 11U; -} - -uint32_t cuatro_read_current_mA(void) { - return adc_get_mV(3) * 2U; -} - -void cuatro_init(void) { - red_chiplet_init(); - - // Power readout - set_gpio_mode(GPIOC, 5, MODE_ANALOG); - set_gpio_mode(GPIOA, 6, MODE_ANALOG); - - // CAN transceiver enables - set_gpio_pullup(GPIOB, 7, PULL_NONE); - set_gpio_mode(GPIOB, 7, MODE_OUTPUT); - set_gpio_pullup(GPIOD, 8, PULL_NONE); - set_gpio_mode(GPIOD, 8, MODE_OUTPUT); - - // FDCAN3, different pins on this package than the rest of the reds - set_gpio_pullup(GPIOD, 12, PULL_NONE); - set_gpio_alternate(GPIOD, 12, GPIO_AF5_FDCAN3); - set_gpio_pullup(GPIOD, 13, PULL_NONE); - set_gpio_alternate(GPIOD, 13, GPIO_AF5_FDCAN3); - - // C2: SOM GPIO used as input (fan control at boot) - set_gpio_mode(GPIOC, 2, MODE_INPUT); - set_gpio_pullup(GPIOC, 2, PULL_DOWN); - - // SOM bootkick + reset lines - set_gpio_mode(GPIOC, 12, MODE_OUTPUT); - tres_set_bootkick(BOOT_BOOTKICK); - - // SOM debugging UART - gpio_uart7_init(); - uart_init(&uart_ring_som_debug, 115200); - - // SPI init - gpio_spi_init(); - - // fan setup - set_gpio_alternate(GPIOC, 8, GPIO_AF2_TIM3); - - // Initialize IR PWM and set to 0% - set_gpio_alternate(GPIOC, 9, GPIO_AF2_TIM3); - pwm_init(TIM3, 4); - tres_set_ir_power(0U); - - // Clock source - clock_source_init(); -} - -const board board_cuatro = { - .harness_config = &red_chiplet_harness_config, - .has_obd = true, - .has_spi = true, - .has_canfd = true, - .has_rtc_battery = true, - .fan_max_rpm = 6600U, - .avdd_mV = 1800U, - .fan_stall_recovery = false, - .fan_enable_cooldown_time = 3U, - .init = cuatro_init, - .init_bootloader = unused_init_bootloader, - .enable_can_transceiver = cuatro_enable_can_transceiver, - .enable_can_transceivers = cuatro_enable_can_transceivers, - .set_led = cuatro_set_led, - .set_can_mode = red_chiplet_set_can_mode, - .check_ignition = red_check_ignition, - .read_voltage_mV = cuatro_read_voltage_mV, - .read_current_mA = cuatro_read_current_mA, - .set_fan_enabled = tres_set_fan_enabled, - .set_ir_power = tres_set_ir_power, - .set_siren = unused_set_siren, - .set_bootkick = tres_set_bootkick, - .read_som_gpio = tres_read_som_gpio -}; diff --git a/panda/board/boards/dos.h b/panda/board/boards/dos.h deleted file mode 100644 index 428bbf2..0000000 --- a/panda/board/boards/dos.h +++ /dev/null @@ -1,218 +0,0 @@ -// /////////////////////// // -// Dos (STM32F4) + Harness // -// /////////////////////// // - -void dos_enable_can_transceiver(uint8_t transceiver, bool enabled) { - switch (transceiver){ - case 1U: - set_gpio_output(GPIOC, 1, !enabled); - break; - case 2U: - set_gpio_output(GPIOC, 13, !enabled); - break; - case 3U: - set_gpio_output(GPIOA, 0, !enabled); - break; - case 4U: - set_gpio_output(GPIOB, 10, !enabled); - break; - default: - print("Invalid CAN transceiver ("); puth(transceiver); print("): enabling failed\n"); - break; - } -} - -void dos_enable_can_transceivers(bool enabled) { - for(uint8_t i=1U; i<=4U; i++){ - // Leave main CAN always on for CAN-based ignition detection - if((harness.status == HARNESS_STATUS_FLIPPED) ? (i == 3U) : (i == 1U)){ - dos_enable_can_transceiver(i, true); - } else { - dos_enable_can_transceiver(i, enabled); - } - } -} - -void dos_set_led(uint8_t color, bool enabled) { - switch (color){ - case LED_RED: - set_gpio_output(GPIOC, 9, !enabled); - break; - case LED_GREEN: - set_gpio_output(GPIOC, 7, !enabled); - break; - case LED_BLUE: - set_gpio_output(GPIOC, 6, !enabled); - break; - default: - break; - } -} - -void dos_set_bootkick(BootState state) { - set_gpio_output(GPIOC, 4, state != BOOT_BOOTKICK); -} - -void dos_set_can_mode(uint8_t mode) { - dos_enable_can_transceiver(2U, false); - dos_enable_can_transceiver(4U, false); - switch (mode) { - case CAN_MODE_NORMAL: - case CAN_MODE_OBD_CAN2: - if ((bool)(mode == CAN_MODE_NORMAL) != (bool)(harness.status == HARNESS_STATUS_FLIPPED)) { - // B12,B13: disable OBD mode - set_gpio_mode(GPIOB, 12, MODE_INPUT); - set_gpio_mode(GPIOB, 13, MODE_INPUT); - - // B5,B6: normal CAN2 mode - set_gpio_alternate(GPIOB, 5, GPIO_AF9_CAN2); - set_gpio_alternate(GPIOB, 6, GPIO_AF9_CAN2); - dos_enable_can_transceiver(2U, true); - } else { - // B5,B6: disable normal CAN2 mode - set_gpio_mode(GPIOB, 5, MODE_INPUT); - set_gpio_mode(GPIOB, 6, MODE_INPUT); - - // B12,B13: OBD mode - set_gpio_alternate(GPIOB, 12, GPIO_AF9_CAN2); - set_gpio_alternate(GPIOB, 13, GPIO_AF9_CAN2); - dos_enable_can_transceiver(4U, true); - } - break; - default: - print("Tried to set unsupported CAN mode: "); puth(mode); print("\n"); - break; - } -} - -bool dos_check_ignition(void){ - // ignition is checked through harness - return harness_check_ignition(); -} - -void dos_set_ir_power(uint8_t percentage){ - pwm_set(TIM4, 2, percentage); -} - -void dos_set_fan_enabled(bool enabled){ - set_gpio_output(GPIOA, 1, enabled); -} - -void dos_set_siren(bool enabled){ - set_gpio_output(GPIOC, 12, enabled); -} - -bool dos_read_som_gpio (void){ - return (get_gpio_input(GPIOC, 2) != 0); -} - -void dos_init(void) { - common_init_gpio(); - - // A8,A15: normal CAN3 mode - set_gpio_alternate(GPIOA, 8, GPIO_AF11_CAN3); - set_gpio_alternate(GPIOA, 15, GPIO_AF11_CAN3); - - // C0: OBD_SBU1 (orientation detection) - // C3: OBD_SBU2 (orientation detection) - set_gpio_mode(GPIOC, 0, MODE_ANALOG); - set_gpio_mode(GPIOC, 3, MODE_ANALOG); - - // C10: OBD_SBU1_RELAY (harness relay driving output) - // C11: OBD_SBU2_RELAY (harness relay driving output) - set_gpio_mode(GPIOC, 10, MODE_OUTPUT); - set_gpio_mode(GPIOC, 11, MODE_OUTPUT); - set_gpio_output_type(GPIOC, 10, OUTPUT_TYPE_OPEN_DRAIN); - set_gpio_output_type(GPIOC, 11, OUTPUT_TYPE_OPEN_DRAIN); - set_gpio_output(GPIOC, 10, 1); - set_gpio_output(GPIOC, 11, 1); - -#ifdef ENABLE_SPI - // SPI init - gpio_spi_init(); -#endif - - // C8: FAN PWM aka TIM3_CH3 - set_gpio_alternate(GPIOC, 8, GPIO_AF2_TIM3); - - // C2: SOM GPIO used as input (fan control at boot) - set_gpio_mode(GPIOC, 2, MODE_INPUT); - set_gpio_pullup(GPIOC, 2, PULL_DOWN); - - // Initialize IR PWM and set to 0% - set_gpio_alternate(GPIOB, 7, GPIO_AF2_TIM4); - pwm_init(TIM4, 2); - dos_set_ir_power(0U); - - // Initialize harness - harness_init(); - - // Initialize RTC - rtc_init(); - - // Enable CAN transceivers - dos_enable_can_transceivers(true); - - // Disable LEDs - dos_set_led(LED_RED, false); - dos_set_led(LED_GREEN, false); - dos_set_led(LED_BLUE, false); - - // Bootkick - dos_set_bootkick(true); - - // Set normal CAN mode - dos_set_can_mode(CAN_MODE_NORMAL); - - // change CAN mapping when flipped - if (harness.status == HARNESS_STATUS_FLIPPED) { - can_flip_buses(0, 2); - } - - // Init clock source (camera strobe) using PWM - clock_source_init(); -} - -const harness_configuration dos_harness_config = { - .has_harness = true, - .GPIO_SBU1 = GPIOC, - .GPIO_SBU2 = GPIOC, - .GPIO_relay_SBU1 = GPIOC, - .GPIO_relay_SBU2 = GPIOC, - .pin_SBU1 = 0, - .pin_SBU2 = 3, - .pin_relay_SBU1 = 10, - .pin_relay_SBU2 = 11, - .adc_channel_SBU1 = 10, - .adc_channel_SBU2 = 13 -}; - -const board board_dos = { - .harness_config = &dos_harness_config, - .has_obd = true, -#ifdef ENABLE_SPI - .has_spi = true, -#else - .has_spi = false, -#endif - .has_canfd = false, - .has_rtc_battery = true, - .fan_max_rpm = 6500U, - .avdd_mV = 3300U, - .fan_stall_recovery = true, - .fan_enable_cooldown_time = 3U, - .init = dos_init, - .init_bootloader = unused_init_bootloader, - .enable_can_transceiver = dos_enable_can_transceiver, - .enable_can_transceivers = dos_enable_can_transceivers, - .set_led = dos_set_led, - .set_can_mode = dos_set_can_mode, - .check_ignition = dos_check_ignition, - .read_voltage_mV = white_read_voltage_mV, - .read_current_mA = unused_read_current, - .set_fan_enabled = dos_set_fan_enabled, - .set_ir_power = dos_set_ir_power, - .set_siren = dos_set_siren, - .set_bootkick = dos_set_bootkick, - .read_som_gpio = dos_read_som_gpio -}; diff --git a/panda/board/boards/grey.h b/panda/board/boards/grey.h deleted file mode 100644 index 8b3bd8a..0000000 --- a/panda/board/boards/grey.h +++ /dev/null @@ -1,31 +0,0 @@ -// //////////////////// // -// Grey Panda (STM32F4) // -// //////////////////// // - -// Most hardware functionality is similar to white panda - -const board board_grey = { - .set_bootkick = unused_set_bootkick, - .harness_config = &white_harness_config, - .has_obd = false, - .has_spi = false, - .has_canfd = false, - .has_rtc_battery = false, - .fan_max_rpm = 0U, - .avdd_mV = 3300U, - .fan_stall_recovery = false, - .fan_enable_cooldown_time = 0U, - .init = white_grey_init, - .init_bootloader = white_grey_init_bootloader, - .enable_can_transceiver = white_enable_can_transceiver, - .enable_can_transceivers = white_enable_can_transceivers, - .set_led = white_set_led, - .set_can_mode = white_set_can_mode, - .check_ignition = white_check_ignition, - .read_voltage_mV = white_read_voltage_mV, - .read_current_mA = white_read_current_mA, - .set_fan_enabled = unused_set_fan_enabled, - .set_ir_power = unused_set_ir_power, - .set_siren = unused_set_siren, - .read_som_gpio = unused_read_som_gpio -}; diff --git a/panda/board/boards/red.h b/panda/board/boards/red.h deleted file mode 100644 index aa8c91b..0000000 --- a/panda/board/boards/red.h +++ /dev/null @@ -1,201 +0,0 @@ -// ///////////////////////////// // -// Red Panda (STM32H7) + Harness // -// ///////////////////////////// // - -void red_enable_can_transceiver(uint8_t transceiver, bool enabled) { - switch (transceiver) { - case 1U: - set_gpio_output(GPIOG, 11, !enabled); - break; - case 2U: - set_gpio_output(GPIOB, 3, !enabled); - break; - case 3U: - set_gpio_output(GPIOD, 7, !enabled); - break; - case 4U: - set_gpio_output(GPIOB, 4, !enabled); - break; - default: - break; - } -} - -void red_enable_can_transceivers(bool enabled) { - uint8_t main_bus = (harness.status == HARNESS_STATUS_FLIPPED) ? 3U : 1U; - for (uint8_t i=1U; i<=4U; i++) { - // Leave main CAN always on for CAN-based ignition detection - if (i == main_bus) { - red_enable_can_transceiver(i, true); - } else { - red_enable_can_transceiver(i, enabled); - } - } -} - -void red_set_led(uint8_t color, bool enabled) { - switch (color) { - case LED_RED: - set_gpio_output(GPIOE, 4, !enabled); - break; - case LED_GREEN: - set_gpio_output(GPIOE, 3, !enabled); - break; - case LED_BLUE: - set_gpio_output(GPIOE, 2, !enabled); - break; - default: - break; - } -} - -void red_set_can_mode(uint8_t mode) { - red_enable_can_transceiver(2U, false); - red_enable_can_transceiver(4U, false); - switch (mode) { - case CAN_MODE_NORMAL: - case CAN_MODE_OBD_CAN2: - if ((bool)(mode == CAN_MODE_NORMAL) != (bool)(harness.status == HARNESS_STATUS_FLIPPED)) { - // B12,B13: disable normal mode - set_gpio_pullup(GPIOB, 12, PULL_NONE); - set_gpio_mode(GPIOB, 12, MODE_ANALOG); - - set_gpio_pullup(GPIOB, 13, PULL_NONE); - set_gpio_mode(GPIOB, 13, MODE_ANALOG); - - // B5,B6: FDCAN2 mode - set_gpio_pullup(GPIOB, 5, PULL_NONE); - set_gpio_alternate(GPIOB, 5, GPIO_AF9_FDCAN2); - - set_gpio_pullup(GPIOB, 6, PULL_NONE); - set_gpio_alternate(GPIOB, 6, GPIO_AF9_FDCAN2); - red_enable_can_transceiver(2U, true); - } else { - // B5,B6: disable normal mode - set_gpio_pullup(GPIOB, 5, PULL_NONE); - set_gpio_mode(GPIOB, 5, MODE_ANALOG); - - set_gpio_pullup(GPIOB, 6, PULL_NONE); - set_gpio_mode(GPIOB, 6, MODE_ANALOG); - // B12,B13: FDCAN2 mode - set_gpio_pullup(GPIOB, 12, PULL_NONE); - set_gpio_alternate(GPIOB, 12, GPIO_AF9_FDCAN2); - - set_gpio_pullup(GPIOB, 13, PULL_NONE); - set_gpio_alternate(GPIOB, 13, GPIO_AF9_FDCAN2); - red_enable_can_transceiver(4U, true); - } - break; - default: - break; - } -} - -bool red_check_ignition(void) { - // ignition is checked through harness - return harness_check_ignition(); -} - -uint32_t red_read_voltage_mV(void){ - return adc_get_mV(2) * 11U; // TODO: is this correct? -} - -void red_init(void) { - common_init_gpio(); - - //C10,C11 : OBD_SBU1_RELAY, OBD_SBU2_RELAY - set_gpio_output_type(GPIOC, 10, OUTPUT_TYPE_OPEN_DRAIN); - set_gpio_pullup(GPIOC, 10, PULL_NONE); - set_gpio_mode(GPIOC, 10, MODE_OUTPUT); - set_gpio_output(GPIOC, 10, 1); - - set_gpio_output_type(GPIOC, 11, OUTPUT_TYPE_OPEN_DRAIN); - set_gpio_pullup(GPIOC, 11, PULL_NONE); - set_gpio_mode(GPIOC, 11, MODE_OUTPUT); - set_gpio_output(GPIOC, 11, 1); - - // G11,B3,D7,B4: transceiver enable - set_gpio_pullup(GPIOG, 11, PULL_NONE); - set_gpio_mode(GPIOG, 11, MODE_OUTPUT); - - set_gpio_pullup(GPIOB, 3, PULL_NONE); - set_gpio_mode(GPIOB, 3, MODE_OUTPUT); - - set_gpio_pullup(GPIOD, 7, PULL_NONE); - set_gpio_mode(GPIOD, 7, MODE_OUTPUT); - - set_gpio_pullup(GPIOB, 4, PULL_NONE); - set_gpio_mode(GPIOB, 4, MODE_OUTPUT); - - //B1: 5VOUT_S - set_gpio_pullup(GPIOB, 1, PULL_NONE); - set_gpio_mode(GPIOB, 1, MODE_ANALOG); - - // B14: usb load switch, enabled by pull resistor on board, obsolete for red panda - set_gpio_output_type(GPIOB, 14, OUTPUT_TYPE_OPEN_DRAIN); - set_gpio_pullup(GPIOB, 14, PULL_UP); - set_gpio_mode(GPIOB, 14, MODE_OUTPUT); - set_gpio_output(GPIOB, 14, 1); - - // Initialize harness - harness_init(); - - // Initialize RTC - rtc_init(); - - // Enable CAN transceivers - red_enable_can_transceivers(true); - - // Disable LEDs - red_set_led(LED_RED, false); - red_set_led(LED_GREEN, false); - red_set_led(LED_BLUE, false); - - // Set normal CAN mode - red_set_can_mode(CAN_MODE_NORMAL); - - // change CAN mapping when flipped - if (harness.status == HARNESS_STATUS_FLIPPED) { - can_flip_buses(0, 2); - } -} - -const harness_configuration red_harness_config = { - .has_harness = true, - .GPIO_SBU1 = GPIOC, - .GPIO_SBU2 = GPIOA, - .GPIO_relay_SBU1 = GPIOC, - .GPIO_relay_SBU2 = GPIOC, - .pin_SBU1 = 4, - .pin_SBU2 = 1, - .pin_relay_SBU1 = 10, - .pin_relay_SBU2 = 11, - .adc_channel_SBU1 = 4, //ADC12_INP4 - .adc_channel_SBU2 = 17 //ADC1_INP17 -}; - -const board board_red = { - .set_bootkick = unused_set_bootkick, - .harness_config = &red_harness_config, - .has_obd = true, - .has_spi = false, - .has_canfd = true, - .has_rtc_battery = false, - .fan_max_rpm = 0U, - .avdd_mV = 3300U, - .fan_stall_recovery = false, - .fan_enable_cooldown_time = 0U, - .init = red_init, - .init_bootloader = unused_init_bootloader, - .enable_can_transceiver = red_enable_can_transceiver, - .enable_can_transceivers = red_enable_can_transceivers, - .set_led = red_set_led, - .set_can_mode = red_set_can_mode, - .check_ignition = red_check_ignition, - .read_voltage_mV = red_read_voltage_mV, - .read_current_mA = unused_read_current, - .set_fan_enabled = unused_set_fan_enabled, - .set_ir_power = unused_set_ir_power, - .set_siren = unused_set_siren, - .read_som_gpio = unused_read_som_gpio -}; diff --git a/panda/board/boards/red_chiplet.h b/panda/board/boards/red_chiplet.h deleted file mode 100644 index eec3d95..0000000 --- a/panda/board/boards/red_chiplet.h +++ /dev/null @@ -1,154 +0,0 @@ -// ///////////////////////////////////// // -// Red Panda chiplet (STM32H7) + Harness // -// ///////////////////////////////////// // - -// Most hardware functionality is similar to red panda - -void red_chiplet_enable_can_transceiver(uint8_t transceiver, bool enabled) { - switch (transceiver) { - case 1U: - set_gpio_output(GPIOG, 11, !enabled); - break; - case 2U: - set_gpio_output(GPIOB, 10, !enabled); - break; - case 3U: - set_gpio_output(GPIOD, 7, !enabled); - break; - case 4U: - set_gpio_output(GPIOB, 11, !enabled); - break; - default: - break; - } -} - -void red_chiplet_enable_can_transceivers(bool enabled) { - uint8_t main_bus = (harness.status == HARNESS_STATUS_FLIPPED) ? 3U : 1U; - for (uint8_t i=1U; i<=4U; i++) { - // Leave main CAN always on for CAN-based ignition detection - if (i == main_bus) { - red_chiplet_enable_can_transceiver(i, true); - } else { - red_chiplet_enable_can_transceiver(i, enabled); - } - } -} - -void red_chiplet_set_can_mode(uint8_t mode) { - red_chiplet_enable_can_transceiver(2U, false); - red_chiplet_enable_can_transceiver(4U, false); - switch (mode) { - case CAN_MODE_NORMAL: - case CAN_MODE_OBD_CAN2: - if ((bool)(mode == CAN_MODE_NORMAL) != (bool)(harness.status == HARNESS_STATUS_FLIPPED)) { - // B12,B13: disable normal mode - set_gpio_pullup(GPIOB, 12, PULL_NONE); - set_gpio_mode(GPIOB, 12, MODE_ANALOG); - - set_gpio_pullup(GPIOB, 13, PULL_NONE); - set_gpio_mode(GPIOB, 13, MODE_ANALOG); - - // B5,B6: FDCAN2 mode - set_gpio_pullup(GPIOB, 5, PULL_NONE); - set_gpio_alternate(GPIOB, 5, GPIO_AF9_FDCAN2); - - set_gpio_pullup(GPIOB, 6, PULL_NONE); - set_gpio_alternate(GPIOB, 6, GPIO_AF9_FDCAN2); - red_chiplet_enable_can_transceiver(2U, true); - } else { - // B5,B6: disable normal mode - set_gpio_pullup(GPIOB, 5, PULL_NONE); - set_gpio_mode(GPIOB, 5, MODE_ANALOG); - - set_gpio_pullup(GPIOB, 6, PULL_NONE); - set_gpio_mode(GPIOB, 6, MODE_ANALOG); - // B12,B13: FDCAN2 mode - set_gpio_pullup(GPIOB, 12, PULL_NONE); - set_gpio_alternate(GPIOB, 12, GPIO_AF9_FDCAN2); - - set_gpio_pullup(GPIOB, 13, PULL_NONE); - set_gpio_alternate(GPIOB, 13, GPIO_AF9_FDCAN2); - red_chiplet_enable_can_transceiver(4U, true); - } - break; - default: - break; - } -} - -void red_chiplet_set_fan_or_usb_load_switch(bool enabled) { - set_gpio_output(GPIOD, 3, enabled); -} - -void red_chiplet_init(void) { - common_init_gpio(); - - // A8, A3: OBD_SBU1_RELAY, OBD_SBU2_RELAY - set_gpio_output_type(GPIOA, 8, OUTPUT_TYPE_OPEN_DRAIN); - set_gpio_pullup(GPIOA, 8, PULL_NONE); - set_gpio_output(GPIOA, 8, 1); - set_gpio_mode(GPIOA, 8, MODE_OUTPUT); - - set_gpio_output_type(GPIOA, 3, OUTPUT_TYPE_OPEN_DRAIN); - set_gpio_pullup(GPIOA, 3, PULL_NONE); - set_gpio_output(GPIOA, 3, 1); - set_gpio_mode(GPIOA, 3, MODE_OUTPUT); - - // G11,B10,D7,B11: transceiver enable - set_gpio_pullup(GPIOG, 11, PULL_NONE); - set_gpio_mode(GPIOG, 11, MODE_OUTPUT); - - set_gpio_pullup(GPIOB, 10, PULL_NONE); - set_gpio_mode(GPIOB, 10, MODE_OUTPUT); - - set_gpio_pullup(GPIOD, 7, PULL_NONE); - set_gpio_mode(GPIOD, 7, MODE_OUTPUT); - - set_gpio_pullup(GPIOB, 11, PULL_NONE); - set_gpio_mode(GPIOB, 11, MODE_OUTPUT); - - // D3: usb load switch - set_gpio_pullup(GPIOD, 3, PULL_NONE); - set_gpio_mode(GPIOD, 3, MODE_OUTPUT); - - // B0: 5VOUT_S - set_gpio_pullup(GPIOB, 0, PULL_NONE); - set_gpio_mode(GPIOB, 0, MODE_ANALOG); - - // Initialize harness - harness_init(); - - // Initialize RTC - rtc_init(); - - // Enable CAN transceivers - red_chiplet_enable_can_transceivers(true); - - // Disable LEDs - red_set_led(LED_RED, false); - red_set_led(LED_GREEN, false); - red_set_led(LED_BLUE, false); - - // Set normal CAN mode - red_chiplet_set_can_mode(CAN_MODE_NORMAL); - - // change CAN mapping when flipped - if (harness.status == HARNESS_STATUS_FLIPPED) { - can_flip_buses(0, 2); - } -} - -const harness_configuration red_chiplet_harness_config = { - .has_harness = true, - .GPIO_SBU1 = GPIOC, - .GPIO_SBU2 = GPIOA, - .GPIO_relay_SBU1 = GPIOA, - .GPIO_relay_SBU2 = GPIOA, - .pin_SBU1 = 4, - .pin_SBU2 = 1, - .pin_relay_SBU1 = 8, - .pin_relay_SBU2 = 3, - .adc_channel_SBU1 = 4, // ADC12_INP4 - .adc_channel_SBU2 = 17 // ADC1_INP17 -}; diff --git a/panda/board/boards/tres.h b/panda/board/boards/tres.h deleted file mode 100644 index 959c93b..0000000 --- a/panda/board/boards/tres.h +++ /dev/null @@ -1,97 +0,0 @@ -// /////////////////////////// -// Tres (STM32H7) + Harness // -// /////////////////////////// - -bool tres_ir_enabled; -bool tres_fan_enabled; -void tres_update_fan_ir_power(void) { - red_chiplet_set_fan_or_usb_load_switch(tres_ir_enabled || tres_fan_enabled); -} - -void tres_set_ir_power(uint8_t percentage){ - tres_ir_enabled = (percentage > 0U); - tres_update_fan_ir_power(); - pwm_set(TIM3, 4, percentage); -} - -void tres_set_bootkick(BootState state) { - set_gpio_output(GPIOA, 0, state != BOOT_BOOTKICK); - set_gpio_output(GPIOC, 12, state != BOOT_RESET); -} - -void tres_set_fan_enabled(bool enabled) { - // NOTE: fan controller reset doesn't work on a tres if IR is enabled - tres_fan_enabled = enabled; - tres_update_fan_ir_power(); -} - -bool tres_read_som_gpio (void) { - return (get_gpio_input(GPIOC, 2) != 0); -} - -void tres_init(void) { - // Enable USB 3.3V LDO for USB block - register_set_bits(&(PWR->CR3), PWR_CR3_USBREGEN); - register_set_bits(&(PWR->CR3), PWR_CR3_USB33DEN); - while ((PWR->CR3 & PWR_CR3_USB33RDY) == 0); - - red_chiplet_init(); - - // C2: SOM GPIO used as input (fan control at boot) - set_gpio_mode(GPIOC, 2, MODE_INPUT); - set_gpio_pullup(GPIOC, 2, PULL_DOWN); - - // SOM bootkick + reset lines - set_gpio_mode(GPIOC, 12, MODE_OUTPUT); - tres_set_bootkick(BOOT_BOOTKICK); - - // SOM debugging UART - gpio_uart7_init(); - uart_init(&uart_ring_som_debug, 115200); - - // SPI init - gpio_spi_init(); - - // fan setup - set_gpio_alternate(GPIOC, 8, GPIO_AF2_TIM3); - - // Initialize IR PWM and set to 0% - set_gpio_alternate(GPIOC, 9, GPIO_AF2_TIM3); - pwm_init(TIM3, 4); - tres_set_ir_power(0U); - - // Fake siren - set_gpio_alternate(GPIOC, 10, GPIO_AF4_I2C5); - set_gpio_alternate(GPIOC, 11, GPIO_AF4_I2C5); - register_set_bits(&(GPIOC->OTYPER), GPIO_OTYPER_OT10 | GPIO_OTYPER_OT11); // open drain - fake_siren_init(); - - // Clock source - clock_source_init(); -} - -const board board_tres = { - .harness_config = &red_chiplet_harness_config, - .has_obd = true, - .has_spi = true, - .has_canfd = true, - .has_rtc_battery = true, - .fan_max_rpm = 6600U, - .avdd_mV = 1800U, - .fan_stall_recovery = false, - .fan_enable_cooldown_time = 3U, - .init = tres_init, - .init_bootloader = unused_init_bootloader, - .enable_can_transceiver = red_chiplet_enable_can_transceiver, - .enable_can_transceivers = red_chiplet_enable_can_transceivers, - .set_led = red_set_led, - .set_can_mode = red_chiplet_set_can_mode, - .check_ignition = red_check_ignition, - .read_voltage_mV = red_read_voltage_mV, - .read_current_mA = unused_read_current, - .set_fan_enabled = tres_set_fan_enabled, - .set_ir_power = tres_set_ir_power, - .set_siren = fake_siren_set, - .set_bootkick = tres_set_bootkick, - .read_som_gpio = tres_read_som_gpio -}; diff --git a/panda/board/boards/uno.h b/panda/board/boards/uno.h deleted file mode 100644 index f4e2016..0000000 --- a/panda/board/boards/uno.h +++ /dev/null @@ -1,225 +0,0 @@ -// /////////////////////// // -// Uno (STM32F4) + Harness // -// /////////////////////// // - -void uno_enable_can_transceiver(uint8_t transceiver, bool enabled) { - switch (transceiver){ - case 1U: - set_gpio_output(GPIOC, 1, !enabled); - break; - case 2U: - set_gpio_output(GPIOC, 13, !enabled); - break; - case 3U: - set_gpio_output(GPIOA, 0, !enabled); - break; - case 4U: - set_gpio_output(GPIOB, 10, !enabled); - break; - default: - print("Invalid CAN transceiver ("); puth(transceiver); print("): enabling failed\n"); - break; - } -} - -void uno_enable_can_transceivers(bool enabled) { - for(uint8_t i=1U; i<=4U; i++){ - // Leave main CAN always on for CAN-based ignition detection - if((harness.status == HARNESS_STATUS_FLIPPED) ? (i == 3U) : (i == 1U)){ - uno_enable_can_transceiver(i, true); - } else { - uno_enable_can_transceiver(i, enabled); - } - } -} - -void uno_set_led(uint8_t color, bool enabled) { - switch (color){ - case LED_RED: - set_gpio_output(GPIOC, 9, !enabled); - break; - case LED_GREEN: - set_gpio_output(GPIOC, 7, !enabled); - break; - case LED_BLUE: - set_gpio_output(GPIOC, 6, !enabled); - break; - default: - break; - } -} - -void uno_set_bootkick(BootState state) { - if (state == BOOT_BOOTKICK) { - set_gpio_output(GPIOB, 14, false); - } else { - // We want the pin to be floating, not forced high! - set_gpio_mode(GPIOB, 14, MODE_INPUT); - } -} - -void uno_set_can_mode(uint8_t mode) { - uno_enable_can_transceiver(2U, false); - uno_enable_can_transceiver(4U, false); - switch (mode) { - case CAN_MODE_NORMAL: - case CAN_MODE_OBD_CAN2: - if ((bool)(mode == CAN_MODE_NORMAL) != (bool)(harness.status == HARNESS_STATUS_FLIPPED)) { - // B12,B13: disable OBD mode - set_gpio_mode(GPIOB, 12, MODE_INPUT); - set_gpio_mode(GPIOB, 13, MODE_INPUT); - - // B5,B6: normal CAN2 mode - set_gpio_alternate(GPIOB, 5, GPIO_AF9_CAN2); - set_gpio_alternate(GPIOB, 6, GPIO_AF9_CAN2); - uno_enable_can_transceiver(2U, true); - } else { - // B5,B6: disable normal CAN2 mode - set_gpio_mode(GPIOB, 5, MODE_INPUT); - set_gpio_mode(GPIOB, 6, MODE_INPUT); - - // B12,B13: OBD mode - set_gpio_alternate(GPIOB, 12, GPIO_AF9_CAN2); - set_gpio_alternate(GPIOB, 13, GPIO_AF9_CAN2); - uno_enable_can_transceiver(4U, true); - } - break; - default: - print("Tried to set unsupported CAN mode: "); puth(mode); print("\n"); - break; - } -} - -bool uno_check_ignition(void){ - // ignition is checked through harness - return harness_check_ignition(); -} - -void uno_set_usb_switch(bool phone){ - set_gpio_output(GPIOB, 3, phone); -} - -void uno_set_ir_power(uint8_t percentage){ - pwm_set(TIM4, 2, percentage); -} - -void uno_set_fan_enabled(bool enabled){ - set_gpio_output(GPIOA, 1, enabled); -} - -void uno_init(void) { - common_init_gpio(); - - // A8,A15: normal CAN3 mode - set_gpio_alternate(GPIOA, 8, GPIO_AF11_CAN3); - set_gpio_alternate(GPIOA, 15, GPIO_AF11_CAN3); - - // C0: OBD_SBU1 (orientation detection) - // C3: OBD_SBU2 (orientation detection) - set_gpio_mode(GPIOC, 0, MODE_ANALOG); - set_gpio_mode(GPIOC, 3, MODE_ANALOG); - - // GPS off - set_gpio_output(GPIOB, 1, 0); - set_gpio_output(GPIOC, 5, 0); - set_gpio_output(GPIOC, 12, 0); - - // C10: OBD_SBU1_RELAY (harness relay driving output) - // C11: OBD_SBU2_RELAY (harness relay driving output) - set_gpio_mode(GPIOC, 10, MODE_OUTPUT); - set_gpio_mode(GPIOC, 11, MODE_OUTPUT); - set_gpio_output_type(GPIOC, 10, OUTPUT_TYPE_OPEN_DRAIN); - set_gpio_output_type(GPIOC, 11, OUTPUT_TYPE_OPEN_DRAIN); - set_gpio_output(GPIOC, 10, 1); - set_gpio_output(GPIOC, 11, 1); - - // C8: FAN PWM aka TIM3_CH3 - set_gpio_alternate(GPIOC, 8, GPIO_AF2_TIM3); - - // Turn on phone regulator - set_gpio_output(GPIOB, 4, true); - - // Initialize IR PWM and set to 0% - set_gpio_alternate(GPIOB, 7, GPIO_AF2_TIM4); - pwm_init(TIM4, 2); - uno_set_ir_power(0U); - - // Initialize harness - harness_init(); - - // Initialize RTC - rtc_init(); - - // Enable CAN transceivers - uno_enable_can_transceivers(true); - - // Disable LEDs - uno_set_led(LED_RED, false); - uno_set_led(LED_GREEN, false); - uno_set_led(LED_BLUE, false); - - // Set normal CAN mode - uno_set_can_mode(CAN_MODE_NORMAL); - - // change CAN mapping when flipped - if (harness.status == HARNESS_STATUS_FLIPPED) { - can_flip_buses(0, 2); - } - - // Switch to phone usb mode if harness connection is powered by less than 7V - if(white_read_voltage_mV() < 7000U){ - uno_set_usb_switch(true); - } else { - uno_set_usb_switch(false); - } - - // Bootkick phone - uno_set_bootkick(BOOT_BOOTKICK); -} - -void uno_init_bootloader(void) { - // GPS off - set_gpio_output(GPIOB, 1, 0); - set_gpio_output(GPIOC, 5, 0); - set_gpio_output(GPIOC, 12, 0); -} - -const harness_configuration uno_harness_config = { - .has_harness = true, - .GPIO_SBU1 = GPIOC, - .GPIO_SBU2 = GPIOC, - .GPIO_relay_SBU1 = GPIOC, - .GPIO_relay_SBU2 = GPIOC, - .pin_SBU1 = 0, - .pin_SBU2 = 3, - .pin_relay_SBU1 = 10, - .pin_relay_SBU2 = 11, - .adc_channel_SBU1 = 10, - .adc_channel_SBU2 = 13 -}; - -const board board_uno = { - .harness_config = &uno_harness_config, - .has_obd = true, - .has_spi = false, - .has_canfd = false, - .has_rtc_battery = true, - .fan_max_rpm = 5100U, - .avdd_mV = 3300U, - .fan_stall_recovery = false, - .fan_enable_cooldown_time = 0U, - .init = uno_init, - .init_bootloader = uno_init_bootloader, - .enable_can_transceiver = uno_enable_can_transceiver, - .enable_can_transceivers = uno_enable_can_transceivers, - .set_led = uno_set_led, - .set_can_mode = uno_set_can_mode, - .check_ignition = uno_check_ignition, - .read_voltage_mV = white_read_voltage_mV, - .read_current_mA = unused_read_current, - .set_fan_enabled = uno_set_fan_enabled, - .set_ir_power = uno_set_ir_power, - .set_siren = unused_set_siren, - .set_bootkick = uno_set_bootkick, - .read_som_gpio = unused_read_som_gpio -}; diff --git a/panda/board/boards/unused_funcs.h b/panda/board/boards/unused_funcs.h deleted file mode 100644 index 7bfde01..0000000 --- a/panda/board/boards/unused_funcs.h +++ /dev/null @@ -1,26 +0,0 @@ -void unused_init_bootloader(void) { -} - -void unused_set_ir_power(uint8_t percentage) { - UNUSED(percentage); -} - -void unused_set_fan_enabled(bool enabled) { - UNUSED(enabled); -} - -void unused_set_siren(bool enabled) { - UNUSED(enabled); -} - -uint32_t unused_read_current(void) { - return 0U; -} - -void unused_set_bootkick(BootState state) { - UNUSED(state); -} - -bool unused_read_som_gpio(void) { - return false; -} \ No newline at end of file diff --git a/panda/board/boards/white.h b/panda/board/boards/white.h deleted file mode 100644 index 0de29a3..0000000 --- a/panda/board/boards/white.h +++ /dev/null @@ -1,252 +0,0 @@ -// ///////////////////// // -// White Panda (STM32F4) // -// ///////////////////// // - -void white_enable_can_transceiver(uint8_t transceiver, bool enabled) { - switch (transceiver){ - case 1U: - set_gpio_output(GPIOC, 1, !enabled); - break; - case 2U: - set_gpio_output(GPIOC, 13, !enabled); - break; - case 3U: - set_gpio_output(GPIOA, 0, !enabled); - break; - default: - print("Invalid CAN transceiver ("); puth(transceiver); print("): enabling failed\n"); - break; - } -} - -void white_enable_can_transceivers(bool enabled) { - uint8_t t1 = enabled ? 1U : 2U; // leave transceiver 1 enabled to detect CAN ignition - for(uint8_t i=t1; i<=3U; i++) { - white_enable_can_transceiver(i, enabled); - } -} - -void white_set_led(uint8_t color, bool enabled) { - switch (color){ - case LED_RED: - set_gpio_output(GPIOC, 9, !enabled); - break; - case LED_GREEN: - set_gpio_output(GPIOC, 7, !enabled); - break; - case LED_BLUE: - set_gpio_output(GPIOC, 6, !enabled); - break; - default: - break; - } -} - -void white_set_usb_power_mode(uint8_t mode){ - switch (mode) { - case USB_POWER_CLIENT: - // B2,A13: set client mode - set_gpio_output(GPIOB, 2, 0); - set_gpio_output(GPIOA, 13, 1); - break; - case USB_POWER_CDP: - // B2,A13: set CDP mode - set_gpio_output(GPIOB, 2, 1); - set_gpio_output(GPIOA, 13, 1); - break; - case USB_POWER_DCP: - // B2,A13: set DCP mode on the charger (breaks USB!) - set_gpio_output(GPIOB, 2, 0); - set_gpio_output(GPIOA, 13, 0); - break; - default: - print("Invalid usb power mode\n"); - break; - } -} - -void white_set_can_mode(uint8_t mode){ - switch (mode) { - case CAN_MODE_NORMAL: - // B12,B13: disable GMLAN mode - set_gpio_mode(GPIOB, 12, MODE_INPUT); - set_gpio_mode(GPIOB, 13, MODE_INPUT); - - // B3,B4: disable GMLAN mode - set_gpio_mode(GPIOB, 3, MODE_INPUT); - set_gpio_mode(GPIOB, 4, MODE_INPUT); - - // B5,B6: normal CAN2 mode - set_gpio_alternate(GPIOB, 5, GPIO_AF9_CAN2); - set_gpio_alternate(GPIOB, 6, GPIO_AF9_CAN2); - - // A8,A15: normal CAN3 mode - set_gpio_alternate(GPIOA, 8, GPIO_AF11_CAN3); - set_gpio_alternate(GPIOA, 15, GPIO_AF11_CAN3); - break; - case CAN_MODE_GMLAN_CAN2: - // B5,B6: disable CAN2 mode - set_gpio_mode(GPIOB, 5, MODE_INPUT); - set_gpio_mode(GPIOB, 6, MODE_INPUT); - - // B3,B4: disable GMLAN mode - set_gpio_mode(GPIOB, 3, MODE_INPUT); - set_gpio_mode(GPIOB, 4, MODE_INPUT); - - // B12,B13: GMLAN mode - set_gpio_alternate(GPIOB, 12, GPIO_AF9_CAN2); - set_gpio_alternate(GPIOB, 13, GPIO_AF9_CAN2); - - // A8,A15: normal CAN3 mode - set_gpio_alternate(GPIOA, 8, GPIO_AF11_CAN3); - set_gpio_alternate(GPIOA, 15, GPIO_AF11_CAN3); - break; - case CAN_MODE_GMLAN_CAN3: - // A8,A15: disable CAN3 mode - set_gpio_mode(GPIOA, 8, MODE_INPUT); - set_gpio_mode(GPIOA, 15, MODE_INPUT); - - // B12,B13: disable GMLAN mode - set_gpio_mode(GPIOB, 12, MODE_INPUT); - set_gpio_mode(GPIOB, 13, MODE_INPUT); - - // B3,B4: GMLAN mode - set_gpio_alternate(GPIOB, 3, GPIO_AF11_CAN3); - set_gpio_alternate(GPIOB, 4, GPIO_AF11_CAN3); - - // B5,B6: normal CAN2 mode - set_gpio_alternate(GPIOB, 5, GPIO_AF9_CAN2); - set_gpio_alternate(GPIOB, 6, GPIO_AF9_CAN2); - break; - default: - print("Tried to set unsupported CAN mode: "); puth(mode); print("\n"); - break; - } -} - -uint32_t white_read_voltage_mV(void){ - return adc_get_mV(12) * 11U; -} - -uint32_t white_read_current_mA(void){ - // This isn't in mA, but we're keeping it for backwards compatibility - return adc_get_raw(13); -} - -bool white_check_ignition(void){ - // ignition is on PA1 - return !get_gpio_input(GPIOA, 1); -} - -void white_grey_init(void) { - common_init_gpio(); - - // C3: current sense - set_gpio_mode(GPIOC, 3, MODE_ANALOG); - - // A1: started_alt - set_gpio_pullup(GPIOA, 1, PULL_UP); - - // A2, A3: USART 2 for debugging - set_gpio_alternate(GPIOA, 2, GPIO_AF7_USART2); - set_gpio_alternate(GPIOA, 3, GPIO_AF7_USART2); - - // A4, A5, A6, A7: SPI - set_gpio_alternate(GPIOA, 4, GPIO_AF5_SPI1); - set_gpio_alternate(GPIOA, 5, GPIO_AF5_SPI1); - set_gpio_alternate(GPIOA, 6, GPIO_AF5_SPI1); - set_gpio_alternate(GPIOA, 7, GPIO_AF5_SPI1); - - // B12: GMLAN, ignition sense, pull up - set_gpio_pullup(GPIOB, 12, PULL_UP); - - /* GMLAN mode pins: - M0(B15) M1(B14) mode - ======================= - 0 0 sleep - 1 0 100kbit - 0 1 high voltage wakeup - 1 1 33kbit (normal) - */ - set_gpio_output(GPIOB, 14, 1); - set_gpio_output(GPIOB, 15, 1); - - // B7: K-line enable - set_gpio_output(GPIOB, 7, 1); - - // C12, D2: Setup K-line (UART5) - set_gpio_alternate(GPIOC, 12, GPIO_AF8_UART5); - set_gpio_alternate(GPIOD, 2, GPIO_AF8_UART5); - set_gpio_pullup(GPIOD, 2, PULL_UP); - - // L-line enable - set_gpio_output(GPIOA, 14, 1); - - // C10, C11: L-Line setup (USART3) - set_gpio_alternate(GPIOC, 10, GPIO_AF7_USART3); - set_gpio_alternate(GPIOC, 11, GPIO_AF7_USART3); - set_gpio_pullup(GPIOC, 11, PULL_UP); - - // Initialize RTC - rtc_init(); - - // Enable CAN transceivers - white_enable_can_transceivers(true); - - // Disable LEDs - white_set_led(LED_RED, false); - white_set_led(LED_GREEN, false); - white_set_led(LED_BLUE, false); - - // Set normal CAN mode - white_set_can_mode(CAN_MODE_NORMAL); - - // Init usb power mode - // Init in CDP mode only if panda is powered by 12V. - // Otherwise a PC would not be able to flash a standalone panda - if (white_read_voltage_mV() > 8000U) { // 8V threshold - white_set_usb_power_mode(USB_POWER_CDP); - } else { - white_set_usb_power_mode(USB_POWER_CLIENT); - } - - // ESP/GPS off - set_gpio_output(GPIOC, 5, 0); - set_gpio_output(GPIOC, 14, 0); -} - -void white_grey_init_bootloader(void) { - // ESP/GPS off - set_gpio_output(GPIOC, 5, 0); - set_gpio_output(GPIOC, 14, 0); -} - -const harness_configuration white_harness_config = { - .has_harness = false -}; - -const board board_white = { - .set_bootkick = unused_set_bootkick, - .harness_config = &white_harness_config, - .has_obd = false, - .has_spi = false, - .has_canfd = false, - .has_rtc_battery = false, - .fan_max_rpm = 0U, - .avdd_mV = 3300U, - .fan_stall_recovery = false, - .fan_enable_cooldown_time = 0U, - .init = white_grey_init, - .init_bootloader = white_grey_init_bootloader, - .enable_can_transceiver = white_enable_can_transceiver, - .enable_can_transceivers = white_enable_can_transceivers, - .set_led = white_set_led, - .set_can_mode = white_set_can_mode, - .check_ignition = white_check_ignition, - .read_voltage_mV = white_read_voltage_mV, - .read_current_mA = white_read_current_mA, - .set_fan_enabled = unused_set_fan_enabled, - .set_ir_power = unused_set_ir_power, - .set_siren = unused_set_siren, - .read_som_gpio = unused_read_som_gpio -}; diff --git a/panda/board/bootstub_declarations.h b/panda/board/bootstub_declarations.h deleted file mode 100644 index ae115d2..0000000 --- a/panda/board/bootstub_declarations.h +++ /dev/null @@ -1,20 +0,0 @@ -// ******************** Prototypes ******************** -void print(const char *a){ UNUSED(a); } -void puth(uint8_t i){ UNUSED(i); } -void puth2(uint8_t i){ UNUSED(i); } -void puth4(uint8_t i){ UNUSED(i); } -void hexdump(const void *a, int l){ UNUSED(a); UNUSED(l); } -typedef struct board board; -typedef struct harness_configuration harness_configuration; -// No CAN support on bootloader -void can_flip_buses(uint8_t bus1, uint8_t bus2){UNUSED(bus1); UNUSED(bus2);} -void pwm_init(TIM_TypeDef *TIM, uint8_t channel); -void pwm_set(TIM_TypeDef *TIM, uint8_t channel, uint8_t percentage); -// No UART support in bootloader -typedef struct uart_ring {} uart_ring; -uart_ring uart_ring_som_debug; -void uart_init(uart_ring *q, int baud) { UNUSED(q); UNUSED(baud); } - -// ********************* Globals ********************** -uint8_t hw_type = 0; -const board *current_board; diff --git a/panda/board/can_comms.h b/panda/board/can_comms.h deleted file mode 100644 index 56ca912..0000000 --- a/panda/board/can_comms.h +++ /dev/null @@ -1,122 +0,0 @@ -/* - CAN transactions to and from the host come in the form of - a certain number of CANPacket_t. The transaction is split - into multiple transfers or chunks. - - * comms_can_read outputs this buffer in chunks of a specified length. - chunks are always the given length, except the last one. - * comms_can_write reads in this buffer in chunks. - * both functions maintain an overflow buffer for a partial CANPacket_t that - spans multiple transfers/chunks. - * the overflow buffers are reset by a dedicated control transfer handler, - which is sent by the host on each start of a connection. -*/ - -typedef struct { - uint32_t ptr; - uint32_t tail_size; - uint8_t data[72]; -} asm_buffer; - -asm_buffer can_read_buffer = {.ptr = 0U, .tail_size = 0U}; - -int comms_can_read(uint8_t *data, uint32_t max_len) { - uint32_t pos = 0U; - - // Send tail of previous message if it is in buffer - if (can_read_buffer.ptr > 0U) { - uint32_t overflow_len = MIN(max_len - pos, can_read_buffer.ptr); - (void)memcpy(&data[pos], can_read_buffer.data, overflow_len); - pos += overflow_len; - (void)memcpy(can_read_buffer.data, &can_read_buffer.data[overflow_len], can_read_buffer.ptr - overflow_len); - can_read_buffer.ptr -= overflow_len; - } - - if (can_read_buffer.ptr == 0U) { - // Fill rest of buffer with new data - CANPacket_t can_packet; - while ((pos < max_len) && can_pop(&can_rx_q, &can_packet)) { - uint32_t pckt_len = CANPACKET_HEAD_SIZE + dlc_to_len[can_packet.data_len_code]; - if ((pos + pckt_len) <= max_len) { - (void)memcpy(&data[pos], &can_packet, pckt_len); - pos += pckt_len; - } else { - (void)memcpy(&data[pos], &can_packet, max_len - pos); - can_read_buffer.ptr += pckt_len - (max_len - pos); - // cppcheck-suppress objectIndex - (void)memcpy(can_read_buffer.data, &((uint8_t*)&can_packet)[(max_len - pos)], can_read_buffer.ptr); - pos = max_len; - } - } - } - - return pos; -} - -asm_buffer can_write_buffer = {.ptr = 0U, .tail_size = 0U}; - -// send on CAN -void comms_can_write(const uint8_t *data, uint32_t len) { - uint32_t pos = 0U; - - // Assembling can message with data from buffer - if (can_write_buffer.ptr != 0U) { - if (can_write_buffer.tail_size <= (len - pos)) { - // we have enough data to complete the buffer - CANPacket_t to_push; - (void)memcpy(&can_write_buffer.data[can_write_buffer.ptr], &data[pos], can_write_buffer.tail_size); - can_write_buffer.ptr += can_write_buffer.tail_size; - pos += can_write_buffer.tail_size; - - // send out - (void)memcpy(&to_push, can_write_buffer.data, can_write_buffer.ptr); - can_send(&to_push, to_push.bus, false); - - // reset overflow buffer - can_write_buffer.ptr = 0U; - can_write_buffer.tail_size = 0U; - } else { - // maybe next time - uint32_t data_size = len - pos; - (void) memcpy(&can_write_buffer.data[can_write_buffer.ptr], &data[pos], data_size); - can_write_buffer.tail_size -= data_size; - can_write_buffer.ptr += data_size; - pos += data_size; - } - } - - // rest of the message - while (pos < len) { - uint32_t pckt_len = CANPACKET_HEAD_SIZE + dlc_to_len[(data[pos] >> 4U)]; - if ((pos + pckt_len) <= len) { - CANPacket_t to_push; - (void)memcpy(&to_push, &data[pos], pckt_len); - can_send(&to_push, to_push.bus, false); - pos += pckt_len; - } else { - (void)memcpy(can_write_buffer.data, &data[pos], len - pos); - can_write_buffer.ptr = len - pos; - can_write_buffer.tail_size = pckt_len - can_write_buffer.ptr; - pos += can_write_buffer.ptr; - } - } - - refresh_can_tx_slots_available(); -} - -void comms_can_reset(void) { - can_write_buffer.ptr = 0U; - can_write_buffer.tail_size = 0U; - can_read_buffer.ptr = 0U; - can_read_buffer.tail_size = 0U; -} - -// TODO: make this more general! -void refresh_can_tx_slots_available(void) { - if (can_tx_check_min_slots_free(MAX_CAN_MSGS_PER_USB_BULK_TRANSFER)) { - can_tx_comms_resume_usb(); - } - if (can_tx_check_min_slots_free(MAX_CAN_MSGS_PER_SPI_BULK_TRANSFER)) { - can_tx_comms_resume_spi(); - } -} diff --git a/panda/board/can_definitions.h b/panda/board/can_definitions.h deleted file mode 100644 index b3631d8..0000000 --- a/panda/board/can_definitions.h +++ /dev/null @@ -1,34 +0,0 @@ -#pragma once - -const uint8_t PANDA_CAN_CNT = 3U; -const uint8_t PANDA_BUS_CNT = 4U; - -// bump this when changing the CAN packet -#define CAN_PACKET_VERSION 4 - -#define CANPACKET_HEAD_SIZE 6U - -#if !defined(STM32F4) - #define CANFD - #define CANPACKET_DATA_SIZE_MAX 64U -#else - #define CANPACKET_DATA_SIZE_MAX 8U -#endif - -typedef struct { - unsigned char reserved : 1; - unsigned char bus : 3; - unsigned char data_len_code : 4; // lookup length with dlc_to_len - unsigned char rejected : 1; - unsigned char returned : 1; - unsigned char extended : 1; - unsigned int addr : 29; - unsigned char checksum; - unsigned char data[CANPACKET_DATA_SIZE_MAX]; -} __attribute__((packed, aligned(4))) CANPacket_t; - -const unsigned char dlc_to_len[] = {0U, 1U, 2U, 3U, 4U, 5U, 6U, 7U, 8U, 12U, 16U, 20U, 24U, 32U, 48U, 64U}; - -#define GET_BUS(msg) ((msg)->bus) -#define GET_LEN(msg) (dlc_to_len[(msg)->data_len_code]) -#define GET_ADDR(msg) ((msg)->addr) diff --git a/panda/board/comms_definitions.h b/panda/board/comms_definitions.h deleted file mode 100644 index 18a6d2f..0000000 --- a/panda/board/comms_definitions.h +++ /dev/null @@ -1,12 +0,0 @@ -typedef struct { - uint8_t request; - uint16_t param1; - uint16_t param2; - uint16_t length; -} __attribute__((packed)) ControlPacket_t; - -int comms_control_handler(ControlPacket_t *req, uint8_t *resp); -void comms_endpoint2_write(const uint8_t *data, uint32_t len); -void comms_can_write(const uint8_t *data, uint32_t len); -int comms_can_read(uint8_t *data, uint32_t max_len); -void comms_can_reset(void); diff --git a/panda/board/config.h b/panda/board/config.h deleted file mode 100644 index 0adcc3e..0000000 --- a/panda/board/config.h +++ /dev/null @@ -1,45 +0,0 @@ -#pragma once - -#include - -//#define DEBUG -//#define DEBUG_UART -//#define DEBUG_USB -//#define DEBUG_SPI -//#define DEBUG_FAULTS -//#define DEBUG_COMMS -//#define DEBUG_FAN - -#define CAN_INIT_TIMEOUT_MS 500U -#define DEEPSLEEP_WAKEUP_DELAY 3U -#define USBPACKET_MAX_SIZE 0x40U -#define MAX_CAN_MSGS_PER_USB_BULK_TRANSFER 51U -#define MAX_CAN_MSGS_PER_SPI_BULK_TRANSFER 170U - -// USB definitions -#define USB_VID 0xBBAAU - -#ifdef PANDA_JUNGLE - #ifdef BOOTSTUB - #define USB_PID 0xDDEFU - #else - #define USB_PID 0xDDCFU - #endif -#else - #ifdef BOOTSTUB - #define USB_PID 0xDDEEU - #else - #define USB_PID 0xDDCCU - #endif -#endif - -// platform includes -#ifdef STM32H7 - #include "stm32h7/stm32h7_config.h" -#elif defined(STM32F4) - #include "stm32fx/stm32fx_config.h" -#else - // TODO: uncomment this, cppcheck complains - // building for tests - //#include "fake_stm.h" -#endif diff --git a/panda/board/crc.h b/panda/board/crc.h deleted file mode 100644 index 3e20fb0..0000000 --- a/panda/board/crc.h +++ /dev/null @@ -1,19 +0,0 @@ -#pragma once - -uint8_t crc_checksum(const uint8_t *dat, int len, const uint8_t poly) { - uint8_t crc = 0xFFU; - int i; - int j; - for (i = len - 1; i >= 0; i--) { - crc ^= dat[i]; - for (j = 0; j < 8; j++) { - if ((crc & 0x80U) != 0U) { - crc = (uint8_t)((crc << 1) ^ poly); - } - else { - crc <<= 1; - } - } - } - return crc; -} diff --git a/panda/board/critical.h b/panda/board/critical.h deleted file mode 100644 index c8cf52c..0000000 --- a/panda/board/critical.h +++ /dev/null @@ -1,23 +0,0 @@ -// ********************* Critical section helpers ********************* -volatile bool interrupts_enabled = false; - -void enable_interrupts(void) { - interrupts_enabled = true; - __enable_irq(); -} - -void disable_interrupts(void) { - interrupts_enabled = false; - __disable_irq(); -} - -uint8_t global_critical_depth = 0U; -#define ENTER_CRITICAL() \ - __disable_irq(); \ - global_critical_depth += 1U; - -#define EXIT_CRITICAL() \ - global_critical_depth -= 1U; \ - if ((global_critical_depth == 0U) && interrupts_enabled) { \ - __enable_irq(); \ - } diff --git a/panda/board/drivers/bootkick.h b/panda/board/drivers/bootkick.h deleted file mode 100644 index acae361..0000000 --- a/panda/board/drivers/bootkick.h +++ /dev/null @@ -1,67 +0,0 @@ -bool bootkick_ign_prev = false; -BootState boot_state = BOOT_BOOTKICK; -uint8_t bootkick_harness_status_prev = HARNESS_STATUS_NC; - -uint8_t boot_reset_countdown = 0; -uint8_t waiting_to_boot_countdown = 0; -bool bootkick_reset_triggered = false; -uint16_t bootkick_last_serial_ptr = 0; - -void bootkick_tick(bool ignition, bool recent_heartbeat) { - BootState boot_state_prev = boot_state; - const bool harness_inserted = (harness.status != bootkick_harness_status_prev) && (harness.status != HARNESS_STATUS_NC); - - if ((ignition && !bootkick_ign_prev) || harness_inserted) { - // bootkick on rising edge of ignition or harness insertion - boot_state = BOOT_BOOTKICK; - } else if (recent_heartbeat) { - // disable bootkick once openpilot is up - boot_state = BOOT_STANDBY; - } else { - - } - - /* - Ensure SOM boots in case it goes into QDL mode. Reset behavior: - * shouldn't trigger on the first boot after power-on - * only try reset once per bootkick, i.e. don't keep trying until booted - * only try once per panda boot, since openpilot will reset panda on startup - * once BOOT_RESET is triggered, it stays until countdown is finished - */ - if (!bootkick_reset_triggered && (boot_state == BOOT_BOOTKICK) && (boot_state_prev == BOOT_STANDBY)) { - waiting_to_boot_countdown = 45U; - } - if (waiting_to_boot_countdown > 0U) { - bool serial_activity = uart_ring_som_debug.w_ptr_tx != bootkick_last_serial_ptr; - if (serial_activity || current_board->read_som_gpio() || (boot_state != BOOT_BOOTKICK)) { - waiting_to_boot_countdown = 0U; - } else { - // try a reset - if (waiting_to_boot_countdown == 1U) { - boot_reset_countdown = 5U; - } - } - } - - // handle reset state - if (boot_reset_countdown > 0U) { - boot_state = BOOT_RESET; - bootkick_reset_triggered = true; - } else { - if (boot_state == BOOT_RESET) { - boot_state = BOOT_BOOTKICK; - } - } - - // update state - bootkick_ign_prev = ignition; - bootkick_harness_status_prev = harness.status; - bootkick_last_serial_ptr = uart_ring_som_debug.w_ptr_tx; - if (waiting_to_boot_countdown > 0U) { - waiting_to_boot_countdown--; - } - if (boot_reset_countdown > 0U) { - boot_reset_countdown--; - } - current_board->set_bootkick(boot_state); -} diff --git a/panda/board/drivers/bxcan.h b/panda/board/drivers/bxcan.h deleted file mode 100644 index ea2705d..0000000 --- a/panda/board/drivers/bxcan.h +++ /dev/null @@ -1,213 +0,0 @@ -// IRQs: CAN1_TX, CAN1_RX0, CAN1_SCE -// CAN2_TX, CAN2_RX0, CAN2_SCE -// CAN3_TX, CAN3_RX0, CAN3_SCE - -CAN_TypeDef *cans[] = {CAN1, CAN2, CAN3}; -uint8_t can_irq_number[3][3] = { - { CAN1_TX_IRQn, CAN1_RX0_IRQn, CAN1_SCE_IRQn }, - { CAN2_TX_IRQn, CAN2_RX0_IRQn, CAN2_SCE_IRQn }, - { CAN3_TX_IRQn, CAN3_RX0_IRQn, CAN3_SCE_IRQn }, -}; - -bool can_set_speed(uint8_t can_number) { - bool ret = true; - CAN_TypeDef *CANx = CANIF_FROM_CAN_NUM(can_number); - uint8_t bus_number = BUS_NUM_FROM_CAN_NUM(can_number); - - ret &= llcan_set_speed( - CANx, - bus_config[bus_number].can_speed, - can_loopback, - (unsigned int)(can_silent) & (1U << can_number) - ); - return ret; -} - -void update_can_health_pkt(uint8_t can_number, uint32_t ir_reg) { - CAN_TypeDef *CANx = CANIF_FROM_CAN_NUM(can_number); - uint32_t esr_reg = CANx->ESR; - - can_health[can_number].bus_off = ((esr_reg & CAN_ESR_BOFF) >> CAN_ESR_BOFF_Pos); - can_health[can_number].bus_off_cnt += can_health[can_number].bus_off; - can_health[can_number].error_warning = ((esr_reg & CAN_ESR_EWGF) >> CAN_ESR_EWGF_Pos); - can_health[can_number].error_passive = ((esr_reg & CAN_ESR_EPVF) >> CAN_ESR_EPVF_Pos); - - can_health[can_number].last_error = ((esr_reg & CAN_ESR_LEC) >> CAN_ESR_LEC_Pos); - if ((can_health[can_number].last_error != 0U) && (can_health[can_number].last_error != 7U)) { - can_health[can_number].last_stored_error = can_health[can_number].last_error; - } - - can_health[can_number].receive_error_cnt = ((esr_reg & CAN_ESR_REC) >> CAN_ESR_REC_Pos); - can_health[can_number].transmit_error_cnt = ((esr_reg & CAN_ESR_TEC) >> CAN_ESR_TEC_Pos); - - can_health[can_number].irq0_call_rate = interrupts[can_irq_number[can_number][0]].call_rate; - can_health[can_number].irq1_call_rate = interrupts[can_irq_number[can_number][1]].call_rate; - can_health[can_number].irq2_call_rate = interrupts[can_irq_number[can_number][2]].call_rate; - - if (ir_reg != 0U) { - can_health[can_number].total_error_cnt += 1U; - - // RX message lost due to FIFO overrun - if ((CANx->RF0R & (CAN_RF0R_FOVR0)) != 0) { - can_health[can_number].total_rx_lost_cnt += 1U; - CANx->RF0R &= ~(CAN_RF0R_FOVR0); - } - can_health[can_number].can_core_reset_cnt += 1U; - llcan_clear_send(CANx); - } -} - -// ***************************** CAN ***************************** -// CANx_SCE IRQ Handler -void can_sce(uint8_t can_number) { - update_can_health_pkt(can_number, 1U); -} - -// CANx_TX IRQ Handler -void process_can(uint8_t can_number) { - if (can_number != 0xffU) { - - ENTER_CRITICAL(); - - CAN_TypeDef *CANx = CANIF_FROM_CAN_NUM(can_number); - uint8_t bus_number = BUS_NUM_FROM_CAN_NUM(can_number); - - // check for empty mailbox - CANPacket_t to_send; - if ((CANx->TSR & (CAN_TSR_TERR0 | CAN_TSR_ALST0)) != 0) { // last TX failed due to error arbitration lost - can_health[can_number].total_tx_lost_cnt += 1U; - CANx->TSR |= (CAN_TSR_TERR0 | CAN_TSR_ALST0); - } - if ((CANx->TSR & CAN_TSR_TME0) == CAN_TSR_TME0) { - // add successfully transmitted message to my fifo - if ((CANx->TSR & CAN_TSR_RQCP0) == CAN_TSR_RQCP0) { - if ((CANx->TSR & CAN_TSR_TXOK0) == CAN_TSR_TXOK0) { - CANPacket_t to_push; - to_push.returned = 1U; - to_push.rejected = 0U; - to_push.extended = (CANx->sTxMailBox[0].TIR >> 2) & 0x1U; - to_push.addr = (to_push.extended != 0U) ? (CANx->sTxMailBox[0].TIR >> 3) : (CANx->sTxMailBox[0].TIR >> 21); - to_push.data_len_code = CANx->sTxMailBox[0].TDTR & 0xFU; - to_push.bus = bus_number; - WORD_TO_BYTE_ARRAY(&to_push.data[0], CANx->sTxMailBox[0].TDLR); - WORD_TO_BYTE_ARRAY(&to_push.data[4], CANx->sTxMailBox[0].TDHR); - can_set_checksum(&to_push); - - rx_buffer_overflow += can_push(&can_rx_q, &to_push) ? 0U : 1U; - } - - // clear interrupt - // careful, this can also be cleared by requesting a transmission - CANx->TSR |= CAN_TSR_RQCP0; - } - - if (can_pop(can_queues[bus_number], &to_send)) { - if (can_check_checksum(&to_send)) { - can_health[can_number].total_tx_cnt += 1U; - // only send if we have received a packet - CANx->sTxMailBox[0].TIR = ((to_send.extended != 0U) ? (to_send.addr << 3) : (to_send.addr << 21)) | (to_send.extended << 2); - CANx->sTxMailBox[0].TDTR = to_send.data_len_code; - BYTE_ARRAY_TO_WORD(CANx->sTxMailBox[0].TDLR, &to_send.data[0]); - BYTE_ARRAY_TO_WORD(CANx->sTxMailBox[0].TDHR, &to_send.data[4]); - // Send request TXRQ - CANx->sTxMailBox[0].TIR |= 0x1U; - } else { - can_health[can_number].total_tx_checksum_error_cnt += 1U; - } - - refresh_can_tx_slots_available(); - } - } - - EXIT_CRITICAL(); - } -} - -// CANx_RX0 IRQ Handler -// blink blue when we are receiving CAN messages -void can_rx(uint8_t can_number) { - CAN_TypeDef *CANx = CANIF_FROM_CAN_NUM(can_number); - uint8_t bus_number = BUS_NUM_FROM_CAN_NUM(can_number); - - while ((CANx->RF0R & CAN_RF0R_FMP0) != 0) { - can_health[can_number].total_rx_cnt += 1U; - - // can is live - pending_can_live = 1; - - // add to my fifo - CANPacket_t to_push; - - to_push.returned = 0U; - to_push.rejected = 0U; - to_push.extended = (CANx->sFIFOMailBox[0].RIR >> 2) & 0x1U; - to_push.addr = (to_push.extended != 0U) ? (CANx->sFIFOMailBox[0].RIR >> 3) : (CANx->sFIFOMailBox[0].RIR >> 21); - to_push.data_len_code = CANx->sFIFOMailBox[0].RDTR & 0xFU; - to_push.bus = bus_number; - WORD_TO_BYTE_ARRAY(&to_push.data[0], CANx->sFIFOMailBox[0].RDLR); - WORD_TO_BYTE_ARRAY(&to_push.data[4], CANx->sFIFOMailBox[0].RDHR); - can_set_checksum(&to_push); - - // forwarding (panda only) - int bus_fwd_num = safety_fwd_hook(bus_number, to_push.addr); - if (bus_fwd_num != -1) { - CANPacket_t to_send; - - to_send.returned = 0U; - to_send.rejected = 0U; - to_send.extended = to_push.extended; // TXRQ - to_send.addr = to_push.addr; - to_send.bus = to_push.bus; - to_send.data_len_code = to_push.data_len_code; - (void)memcpy(to_send.data, to_push.data, dlc_to_len[to_push.data_len_code]); - can_set_checksum(&to_send); - - can_send(&to_send, bus_fwd_num, true); - can_health[can_number].total_fwd_cnt += 1U; - } - - safety_rx_invalid += safety_rx_hook(&to_push) ? 0U : 1U; - ignition_can_hook(&to_push); - - current_board->set_led(LED_BLUE, true); - rx_buffer_overflow += can_push(&can_rx_q, &to_push) ? 0U : 1U; - - // next - CANx->RF0R |= CAN_RF0R_RFOM0; - } -} - -void CAN1_TX_IRQ_Handler(void) { process_can(0); } -void CAN1_RX0_IRQ_Handler(void) { can_rx(0); } -void CAN1_SCE_IRQ_Handler(void) { can_sce(0); } - -void CAN2_TX_IRQ_Handler(void) { process_can(1); } -void CAN2_RX0_IRQ_Handler(void) { can_rx(1); } -void CAN2_SCE_IRQ_Handler(void) { can_sce(1); } - -void CAN3_TX_IRQ_Handler(void) { process_can(2); } -void CAN3_RX0_IRQ_Handler(void) { can_rx(2); } -void CAN3_SCE_IRQ_Handler(void) { can_sce(2); } - -bool can_init(uint8_t can_number) { - bool ret = false; - - REGISTER_INTERRUPT(CAN1_TX_IRQn, CAN1_TX_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_1) - REGISTER_INTERRUPT(CAN1_RX0_IRQn, CAN1_RX0_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_1) - REGISTER_INTERRUPT(CAN1_SCE_IRQn, CAN1_SCE_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_1) - REGISTER_INTERRUPT(CAN2_TX_IRQn, CAN2_TX_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_2) - REGISTER_INTERRUPT(CAN2_RX0_IRQn, CAN2_RX0_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_2) - REGISTER_INTERRUPT(CAN2_SCE_IRQn, CAN2_SCE_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_2) - REGISTER_INTERRUPT(CAN3_TX_IRQn, CAN3_TX_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_3) - REGISTER_INTERRUPT(CAN3_RX0_IRQn, CAN3_RX0_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_3) - REGISTER_INTERRUPT(CAN3_SCE_IRQn, CAN3_SCE_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_3) - - if (can_number != 0xffU) { - CAN_TypeDef *CANx = CANIF_FROM_CAN_NUM(can_number); - ret &= can_set_speed(can_number); - ret &= llcan_init(CANx); - // in case there are queued up messages - process_can(can_number); - } - return ret; -} diff --git a/panda/board/drivers/can_common.h b/panda/board/drivers/can_common.h deleted file mode 100644 index ed611b5..0000000 --- a/panda/board/drivers/can_common.h +++ /dev/null @@ -1,295 +0,0 @@ -typedef struct { - volatile uint32_t w_ptr; - volatile uint32_t r_ptr; - uint32_t fifo_size; - CANPacket_t *elems; -} can_ring; - -typedef struct { - uint8_t bus_lookup; - uint8_t can_num_lookup; - int8_t forwarding_bus; - uint32_t can_speed; - uint32_t can_data_speed; - bool canfd_enabled; - bool brs_enabled; - bool canfd_non_iso; -} bus_config_t; - -uint32_t safety_tx_blocked = 0; -uint32_t safety_rx_invalid = 0; -uint32_t tx_buffer_overflow = 0; -uint32_t rx_buffer_overflow = 0; -uint32_t gmlan_send_errs = 0; - -can_health_t can_health[] = {{0}, {0}, {0}}; - -extern int can_live; -extern int pending_can_live; - -// must reinit after changing these -extern int can_silent; -extern bool can_loopback; - -// Ignition detected from CAN meessages -bool ignition_can = false; -uint32_t ignition_can_cnt = 0U; - -#define ALL_CAN_SILENT 0xFF -#define ALL_CAN_LIVE 0 - -int can_live = 0; -int pending_can_live = 0; -int can_silent = ALL_CAN_SILENT; -bool can_loopback = false; - -// ******************* functions prototypes ********************* -bool can_init(uint8_t can_number); -void process_can(uint8_t can_number); - -// ********************* instantiate queues ********************* -#define can_buffer(x, size) \ - CANPacket_t elems_##x[size]; \ - can_ring can_##x = { .w_ptr = 0, .r_ptr = 0, .fifo_size = (size), .elems = (CANPacket_t *)&(elems_##x) }; - -#define CAN_RX_BUFFER_SIZE 4096U -#define CAN_TX_BUFFER_SIZE 416U -#define GMLAN_TX_BUFFER_SIZE 416U - -#ifdef STM32H7 -// ITCM RAM and DTCM RAM are the fastest for Cortex-M7 core access -__attribute__((section(".axisram"))) can_buffer(rx_q, CAN_RX_BUFFER_SIZE) -__attribute__((section(".itcmram"))) can_buffer(tx1_q, CAN_TX_BUFFER_SIZE) -__attribute__((section(".itcmram"))) can_buffer(tx2_q, CAN_TX_BUFFER_SIZE) -#else -can_buffer(rx_q, CAN_RX_BUFFER_SIZE) -can_buffer(tx1_q, CAN_TX_BUFFER_SIZE) -can_buffer(tx2_q, CAN_TX_BUFFER_SIZE) -#endif -can_buffer(tx3_q, CAN_TX_BUFFER_SIZE) -can_buffer(txgmlan_q, GMLAN_TX_BUFFER_SIZE) -// FIXME: -// cppcheck-suppress misra-c2012-9.3 -can_ring *can_queues[] = {&can_tx1_q, &can_tx2_q, &can_tx3_q, &can_txgmlan_q}; - -// helpers -#define WORD_TO_BYTE_ARRAY(dst8, src32) 0[dst8] = ((src32) & 0xFFU); 1[dst8] = (((src32) >> 8U) & 0xFFU); 2[dst8] = (((src32) >> 16U) & 0xFFU); 3[dst8] = (((src32) >> 24U) & 0xFFU) -#define BYTE_ARRAY_TO_WORD(dst32, src8) ((dst32) = 0[src8] | (1[src8] << 8U) | (2[src8] << 16U) | (3[src8] << 24U)) - -// ********************* interrupt safe queue ********************* -bool can_pop(can_ring *q, CANPacket_t *elem) { - bool ret = 0; - - ENTER_CRITICAL(); - if (q->w_ptr != q->r_ptr) { - *elem = q->elems[q->r_ptr]; - if ((q->r_ptr + 1U) == q->fifo_size) { - q->r_ptr = 0; - } else { - q->r_ptr += 1U; - } - ret = 1; - } - EXIT_CRITICAL(); - - return ret; -} - -bool can_push(can_ring *q, const CANPacket_t *elem) { - bool ret = false; - uint32_t next_w_ptr; - - ENTER_CRITICAL(); - if ((q->w_ptr + 1U) == q->fifo_size) { - next_w_ptr = 0; - } else { - next_w_ptr = q->w_ptr + 1U; - } - if (next_w_ptr != q->r_ptr) { - q->elems[q->w_ptr] = *elem; - q->w_ptr = next_w_ptr; - ret = true; - } - EXIT_CRITICAL(); - if (!ret) { - #ifdef DEBUG - print("can_push to "); - if (q == &can_rx_q) { - print("can_rx_q"); - } else if (q == &can_tx1_q) { - print("can_tx1_q"); - } else if (q == &can_tx2_q) { - print("can_tx2_q"); - } else if (q == &can_tx3_q) { - print("can_tx3_q"); - } else if (q == &can_txgmlan_q) { - print("can_txgmlan_q"); - } else { - print("unknown"); - } - print(" failed!\n"); - #endif - } - return ret; -} - -uint32_t can_slots_empty(const can_ring *q) { - uint32_t ret = 0; - - ENTER_CRITICAL(); - if (q->w_ptr >= q->r_ptr) { - ret = q->fifo_size - 1U - q->w_ptr + q->r_ptr; - } else { - ret = q->r_ptr - q->w_ptr - 1U; - } - EXIT_CRITICAL(); - - return ret; -} - -void can_clear(can_ring *q) { - ENTER_CRITICAL(); - q->w_ptr = 0; - q->r_ptr = 0; - EXIT_CRITICAL(); - // handle TX buffer full with zero ECUs awake on the bus - refresh_can_tx_slots_available(); -} - -// assign CAN numbering -// bus num: Can bus number on ODB connector. Sent to/from USB -// Min: 0; Max: 127; Bit 7 marks message as receipt (bus 129 is receipt for but 1) -// cans: Look up MCU can interface from bus number -// can number: numeric lookup for MCU CAN interfaces (0 = CAN1, 1 = CAN2, etc); -// bus_lookup: Translates from 'can number' to 'bus number'. -// can_num_lookup: Translates from 'bus number' to 'can number'. -// forwarding bus: If >= 0, forward all messages from this bus to the specified bus. - -// Helpers -// Panda: Bus 0=CAN1 Bus 1=CAN2 Bus 2=CAN3 -bus_config_t bus_config[] = { - { .bus_lookup = 0U, .can_num_lookup = 0U, .forwarding_bus = -1, .can_speed = 5000U, .can_data_speed = 20000U, .canfd_enabled = false, .brs_enabled = false, .canfd_non_iso = false }, - { .bus_lookup = 1U, .can_num_lookup = 1U, .forwarding_bus = -1, .can_speed = 5000U, .can_data_speed = 20000U, .canfd_enabled = false, .brs_enabled = false, .canfd_non_iso = false }, - { .bus_lookup = 2U, .can_num_lookup = 2U, .forwarding_bus = -1, .can_speed = 5000U, .can_data_speed = 20000U, .canfd_enabled = false, .brs_enabled = false, .canfd_non_iso = false }, - { .bus_lookup = 0xFFU, .can_num_lookup = 0xFFU, .forwarding_bus = -1, .can_speed = 333U, .can_data_speed = 333U, .canfd_enabled = false, .brs_enabled = false, .canfd_non_iso = false }, -}; - -#define CANIF_FROM_CAN_NUM(num) (cans[num]) -#define BUS_NUM_FROM_CAN_NUM(num) (bus_config[num].bus_lookup) -#define CAN_NUM_FROM_BUS_NUM(num) (bus_config[num].can_num_lookup) - -void can_init_all(void) { - bool ret = true; - for (uint8_t i=0U; i < PANDA_CAN_CNT; i++) { - if (!current_board->has_canfd) { - bus_config[i].can_data_speed = 0U; - } - can_clear(can_queues[i]); - ret &= can_init(i); - } - UNUSED(ret); -} - -void can_flip_buses(uint8_t bus1, uint8_t bus2){ - bus_config[bus1].bus_lookup = bus2; - bus_config[bus2].bus_lookup = bus1; - bus_config[bus1].can_num_lookup = bus2; - bus_config[bus2].can_num_lookup = bus1; -} - -void can_set_forwarding(uint8_t from, uint8_t to) { - bus_config[from].forwarding_bus = to; -} - -void ignition_can_hook(CANPacket_t *to_push) { - int bus = GET_BUS(to_push); - int addr = GET_ADDR(to_push); - int len = GET_LEN(to_push); - - if (bus == 0) { - // GM exception - if ((addr == 0x1F1) && (len == 8)) { - // SystemPowerMode (2=Run, 3=Crank Request) - ignition_can = (GET_BYTE(to_push, 0) & 0x2U) != 0U; - ignition_can_cnt = 0U; - } - - // Tesla exception - if ((addr == 0x348) && (len == 8)) { - // GTW_status - ignition_can = (GET_BYTE(to_push, 0) & 0x1U) != 0U; - ignition_can_cnt = 0U; - } - - // Mazda exception - if ((addr == 0x9E) && (len == 8)) { - ignition_can = (GET_BYTE(to_push, 0) >> 5) == 0x6U; - ignition_can_cnt = 0U; - } - - } else if (bus == 2) { - // GM exception, SDGM cars have this message on bus 2 - if ((addr == 0x1F1) && (len == 8)) { - // SystemPowerMode (2=Run, 3=Crank Request) - ignition_can = (GET_BYTE(to_push, 0) & 0x2U) != 0U; - ignition_can_cnt = 0U; - } - } -} - -bool can_tx_check_min_slots_free(uint32_t min) { - return - (can_slots_empty(&can_tx1_q) >= min) && - (can_slots_empty(&can_tx2_q) >= min) && - (can_slots_empty(&can_tx3_q) >= min) && - (can_slots_empty(&can_txgmlan_q) >= min); -} - -uint8_t calculate_checksum(const uint8_t *dat, uint32_t len) { - uint8_t checksum = 0U; - for (uint32_t i = 0U; i < len; i++) { - checksum ^= dat[i]; - } - return checksum; -} - -void can_set_checksum(CANPacket_t *packet) { - packet->checksum = 0U; - packet->checksum = calculate_checksum((uint8_t *) packet, CANPACKET_HEAD_SIZE + GET_LEN(packet)); -} - -bool can_check_checksum(CANPacket_t *packet) { - return (calculate_checksum((uint8_t *) packet, CANPACKET_HEAD_SIZE + GET_LEN(packet)) == 0U); -} - -void can_send(CANPacket_t *to_push, uint8_t bus_number, bool skip_tx_hook) { - if (skip_tx_hook || safety_tx_hook(to_push) != 0) { - if (bus_number < PANDA_BUS_CNT) { - // add CAN packet to send queue - if ((bus_number == 3U) && (bus_config[3].can_num_lookup == 0xFFU)) { - gmlan_send_errs += bitbang_gmlan(to_push) ? 0U : 1U; - } else { - tx_buffer_overflow += can_push(can_queues[bus_number], to_push) ? 0U : 1U; - process_can(CAN_NUM_FROM_BUS_NUM(bus_number)); - } - } - } else { - safety_tx_blocked += 1U; - to_push->returned = 0U; - to_push->rejected = 1U; - - // data changed - can_set_checksum(to_push); - rx_buffer_overflow += can_push(&can_rx_q, to_push) ? 0U : 1U; - } -} - -bool is_speed_valid(uint32_t speed, const uint32_t *all_speeds, uint8_t len) { - bool ret = false; - for (uint8_t i = 0U; i < len; i++) { - if (all_speeds[i] == speed) { - ret = true; - } - } - return ret; -} diff --git a/panda/board/drivers/clock_source.h b/panda/board/drivers/clock_source.h deleted file mode 100644 index 11b2fa3..0000000 --- a/panda/board/drivers/clock_source.h +++ /dev/null @@ -1,37 +0,0 @@ -#define CLOCK_SOURCE_PERIOD_MS 50U -#define CLOCK_SOURCE_PULSE_LEN_MS 2U - -void clock_source_set_period(uint8_t period) { - register_set(&(TIM1->ARR), ((period*10U) - 1U), 0xFFFFU); -} - -void clock_source_init(void) { - // Setup timer - register_set(&(TIM1->PSC), ((APB2_TIMER_FREQ*100U)-1U), 0xFFFFU); // Tick on 0.1 ms - register_set(&(TIM1->ARR), ((CLOCK_SOURCE_PERIOD_MS*10U) - 1U), 0xFFFFU); // Period - register_set(&(TIM1->CCMR1), 0U, 0xFFFFU); // No output on compare - register_set(&(TIM1->CCER), TIM_CCER_CC1E, 0xFFFFU); // Enable compare 1 - register_set(&(TIM1->CCR1), (CLOCK_SOURCE_PULSE_LEN_MS*10U), 0xFFFFU); // Compare 1 value - register_set(&(TIM1->CCR2), (CLOCK_SOURCE_PULSE_LEN_MS*10U), 0xFFFFU); // Compare 1 value - register_set(&(TIM1->CCR3), (CLOCK_SOURCE_PULSE_LEN_MS*10U), 0xFFFFU); // Compare 1 value - register_set_bits(&(TIM1->DIER), TIM_DIER_UIE | TIM_DIER_CC1IE); // Enable interrupts - register_set(&(TIM1->CR1), TIM_CR1_CEN, 0x3FU); // Enable timer - - // No interrupts - NVIC_DisableIRQ(TIM1_UP_TIM10_IRQn); - NVIC_DisableIRQ(TIM1_CC_IRQn); - - // Set GPIO as timer channels - set_gpio_alternate(GPIOB, 14, GPIO_AF1_TIM1); - set_gpio_alternate(GPIOB, 15, GPIO_AF1_TIM1); - - // Set PWM mode - register_set(&(TIM1->CCMR1), (0b110 << TIM_CCMR1_OC2M_Pos), 0xFFFFU); - register_set(&(TIM1->CCMR2), (0b110 << TIM_CCMR2_OC3M_Pos), 0xFFFFU); - - // Enable output - register_set(&(TIM1->BDTR), TIM_BDTR_MOE, 0xFFFFU); - - // Enable complementary compares - register_set_bits(&(TIM1->CCER), TIM_CCER_CC2NE | TIM_CCER_CC3NE); -} diff --git a/panda/board/drivers/fake_siren.h b/panda/board/drivers/fake_siren.h deleted file mode 100644 index 38c87de..0000000 --- a/panda/board/drivers/fake_siren.h +++ /dev/null @@ -1,76 +0,0 @@ -#include "stm32h7/lli2c.h" - -#define CODEC_I2C_ADDR 0x10 - -// 1Vpp sine wave with 1V offset -const uint8_t fake_siren_lut[360] = { 134U, 135U, 137U, 138U, 139U, 140U, 141U, 143U, 144U, 145U, 146U, 148U, 149U, 150U, 151U, 152U, 154U, 155U, 156U, 157U, 158U, 159U, 160U, 162U, 163U, 164U, 165U, 166U, 167U, 168U, 169U, 170U, 171U, 172U, 174U, 175U, 176U, 177U, 177U, 178U, 179U, 180U, 181U, 182U, 183U, 184U, 185U, 186U, 186U, 187U, 188U, 189U, 190U, 190U, 191U, 192U, 193U, 193U, 194U, 195U, 195U, 196U, 196U, 197U, 197U, 198U, 199U, 199U, 199U, 200U, 200U, 201U, 201U, 202U, 202U, 202U, 203U, 203U, 203U, 203U, 204U, 204U, 204U, 204U, 204U, 204U, 204U, 205U, 205U, 205U, 205U, 205U, 205U, 205U, 204U, 204U, 204U, 204U, 204U, 204U, 204U, 203U, 203U, 203U, 203U, 202U, 202U, 202U, 201U, 201U, 200U, 200U, 199U, 199U, 199U, 198U, 197U, 197U, 196U, 196U, 195U, 195U, 194U, 193U, 193U, 192U, 191U, 190U, 190U, 189U, 188U, 187U, 186U, 186U, 185U, 184U, 183U, 182U, 181U, 180U, 179U, 178U, 177U, 177U, 176U, 175U, 174U, 172U, 171U, 170U, 169U, 168U, 167U, 166U, 165U, 164U, 163U, 162U, 160U, 159U, 158U, 157U, 156U, 155U, 154U, 152U, 151U, 150U, 149U, 148U, 146U, 145U, 144U, 143U, 141U, 140U, 139U, 138U, 137U, 135U, 134U, 133U, 132U, 130U, 129U, 128U, 127U, 125U, 124U, 123U, 122U, 121U, 119U, 118U, 117U, 116U, 115U, 113U, 112U, 111U, 110U, 109U, 108U, 106U, 105U, 104U, 103U, 102U, 101U, 100U, 99U, 98U, 97U, 96U, 95U, 94U, 93U, 92U, 91U, 90U, 89U, 88U, 87U, 86U, 85U, 84U, 83U, 82U, 82U, 81U, 80U, 79U, 78U, 78U, 77U, 76U, 76U, 75U, 74U, 74U, 73U, 72U, 72U, 71U, 71U, 70U, 70U, 69U, 69U, 68U, 68U, 67U, 67U, 67U, 66U, 66U, 66U, 65U, 65U, 65U, 65U, 64U, 64U, 64U, 64U, 64U, 64U, 64U, 64U, 64U, 63U, 64U, 64U, 64U, 64U, 64U, 64U, 64U, 64U, 64U, 65U, 65U, 65U, 65U, 66U, 66U, 66U, 67U, 67U, 67U, 68U, 68U, 69U, 69U, 70U, 70U, 71U, 71U, 72U, 72U, 73U, 74U, 74U, 75U, 76U, 76U, 77U, 78U, 78U, 79U, 80U, 81U, 82U, 82U, 83U, 84U, 85U, 86U, 87U, 88U, 89U, 90U, 91U, 92U, 93U, 94U, 95U, 96U, 97U, 98U, 99U, 100U, 101U, 102U, 103U, 104U, 105U, 106U, 108U, 109U, 110U, 111U, 112U, 113U, 115U, 116U, 117U, 118U, 119U, 121U, 122U, 123U, 124U, 125U, 127U, 128U, 129U, 130U, 132U, 133U }; - -bool fake_siren_enabled = false; - -void fake_siren_codec_enable(bool enabled) { - if (enabled) { - bool success = true; - success &= i2c_set_reg_bits(I2C5, CODEC_I2C_ADDR, 0x2B, (1U << 1)); // Left speaker mix from INA1 - success &= i2c_set_reg_bits(I2C5, CODEC_I2C_ADDR, 0x2C, (1U << 1)); // Right speaker mix from INA1 - success &= i2c_set_reg_mask(I2C5, CODEC_I2C_ADDR, 0x3D, 0x17, 0b11111); // Left speaker volume - success &= i2c_set_reg_mask(I2C5, CODEC_I2C_ADDR, 0x3E, 0x17, 0b11111); // Right speaker volume - success &= i2c_set_reg_mask(I2C5, CODEC_I2C_ADDR, 0x37, 0b101, 0b111); // INA gain - success &= i2c_set_reg_bits(I2C5, CODEC_I2C_ADDR, 0x4C, (1U << 7)); // Enable INA - success &= i2c_set_reg_bits(I2C5, CODEC_I2C_ADDR, 0x51, (1U << 7)); // Disable global shutdown - if (!success) { - print("Siren codec enable failed\n"); - fault_occurred(FAULT_SIREN_MALFUNCTION); - } - } else { - // Disable INA input. Make sure to retry a few times if the I2C bus is busy. - for (uint8_t i=0U; i<10U; i++) { - if (i2c_clear_reg_bits(I2C5, CODEC_I2C_ADDR, 0x4C, (1U << 7))) { - break; - } - } - } -} - - -void fake_siren_set(bool enabled) { - if (enabled != fake_siren_enabled) { - fake_siren_codec_enable(enabled); - } - - if (enabled) { - register_set_bits(&DMA1_Stream1->CR, DMA_SxCR_EN); - } else { - register_clear_bits(&DMA1_Stream1->CR, DMA_SxCR_EN); - } - fake_siren_enabled = enabled; -} - -void fake_siren_init(void) { - // Init DAC - register_set(&DAC1->MCR, 0U, 0xFFFFFFFFU); - register_set(&DAC1->CR, DAC_CR_TEN1 | (6U << DAC_CR_TSEL1_Pos) | DAC_CR_DMAEN1, 0xFFFFFFFFU); - register_set_bits(&DAC1->CR, DAC_CR_EN1); - - // Setup DMAMUX (DAC_CH1_DMA as input) - register_set(&DMAMUX1_Channel1->CCR, 67U, DMAMUX_CxCR_DMAREQ_ID_Msk); - - // Setup DMA - register_set(&DMA1_Stream1->M0AR, (uint32_t) fake_siren_lut, 0xFFFFFFFFU); - register_set(&DMA1_Stream1->PAR, (uint32_t) &(DAC1->DHR8R1), 0xFFFFFFFFU); - DMA1_Stream1->NDTR = sizeof(fake_siren_lut); - register_set(&DMA1_Stream1->FCR, 0U, 0x00000083U); - DMA1_Stream1->CR = (0b11 << DMA_SxCR_PL_Pos); - DMA1_Stream1->CR |= DMA_SxCR_MINC | DMA_SxCR_CIRC | (1 << DMA_SxCR_DIR_Pos); - - // Init trigger timer (around 2.5kHz) - register_set(&TIM7->PSC, 0U, 0xFFFFU); - register_set(&TIM7->ARR, 133U, 0xFFFFU); - register_set(&TIM7->CR2, (0b10 << TIM_CR2_MMS_Pos), TIM_CR2_MMS_Msk); - register_set(&TIM7->CR1, TIM_CR1_ARPE | TIM_CR1_URS, 0x088EU); - TIM7->SR = 0U; - TIM7->CR1 |= TIM_CR1_CEN; - - // Enable the I2C to the codec - i2c_init(I2C5); - fake_siren_codec_enable(false); -} diff --git a/panda/board/drivers/fan.h b/panda/board/drivers/fan.h deleted file mode 100644 index 1529607..0000000 --- a/panda/board/drivers/fan.h +++ /dev/null @@ -1,95 +0,0 @@ -struct fan_state_t { - uint16_t tach_counter; - uint16_t rpm; - uint16_t target_rpm; - uint8_t power; - float error_integral; - uint8_t stall_counter; - uint8_t stall_threshold; - uint8_t total_stall_count; - uint8_t cooldown_counter; -} fan_state_t; -struct fan_state_t fan_state; - -const float FAN_I = 0.001f; - -const uint8_t FAN_TICK_FREQ = 8U; -const uint8_t FAN_STALL_THRESHOLD_MIN = 3U; -const uint8_t FAN_STALL_THRESHOLD_MAX = 8U; - - -void fan_set_power(uint8_t percentage) { - fan_state.target_rpm = ((current_board->fan_max_rpm * CLAMP(percentage, 0U, 100U)) / 100U); -} - -void llfan_init(void); -void fan_init(void) { - fan_state.stall_threshold = FAN_STALL_THRESHOLD_MIN; - fan_state.cooldown_counter = current_board->fan_enable_cooldown_time * FAN_TICK_FREQ; - llfan_init(); -} - -// Call this at FAN_TICK_FREQ -void fan_tick(void) { - if (current_board->fan_max_rpm > 0U) { - // Measure fan RPM - uint16_t fan_rpm_fast = fan_state.tach_counter * (60U * FAN_TICK_FREQ / 4U); // 4 interrupts per rotation - fan_state.tach_counter = 0U; - fan_state.rpm = (fan_rpm_fast + (3U * fan_state.rpm)) / 4U; - - // Stall detection - bool fan_stalled = false; - if (current_board->fan_stall_recovery) { - if (fan_state.target_rpm > 0U) { - if (fan_rpm_fast == 0U) { - fan_state.stall_counter = MIN(fan_state.stall_counter + 1U, 255U); - } else { - fan_state.stall_counter = 0U; - } - - if (fan_state.stall_counter > (fan_state.stall_threshold*FAN_TICK_FREQ)) { - fan_stalled = true; - fan_state.stall_counter = 0U; - fan_state.stall_threshold = CLAMP(fan_state.stall_threshold + 2U, FAN_STALL_THRESHOLD_MIN, FAN_STALL_THRESHOLD_MAX); - fan_state.total_stall_count += 1U; - - // datasheet gives this range as the minimum startup duty - fan_state.error_integral = CLAMP(fan_state.error_integral, 20.0f, 45.0f); - } - } else { - fan_state.stall_counter = 0U; - fan_state.stall_threshold = FAN_STALL_THRESHOLD_MIN; - } - } - - #ifdef DEBUG_FAN - puth(fan_state.target_rpm); - print(" "); puth(fan_rpm_fast); - print(" "); puth(fan_state.power); - print(" "); puth(fan_state.stall_counter); - print("\n"); - #endif - - // Cooldown counter - if (fan_state.target_rpm > 0U) { - fan_state.cooldown_counter = current_board->fan_enable_cooldown_time * FAN_TICK_FREQ; - } else { - if (fan_state.cooldown_counter > 0U) { - fan_state.cooldown_counter--; - } - } - - // Update controller - if (fan_state.target_rpm == 0U) { - fan_state.error_integral = 0.0f; - } else { - float error = fan_state.target_rpm - fan_rpm_fast; - fan_state.error_integral += FAN_I * error; - } - fan_state.power = CLAMP(fan_state.error_integral, 0U, 100U); - - // Set PWM and enable line - pwm_set(TIM3, 3, fan_state.power); - current_board->set_fan_enabled(!fan_stalled && ((fan_state.target_rpm > 0U) || (fan_state.cooldown_counter > 0U))); - } -} diff --git a/panda/board/drivers/fdcan.h b/panda/board/drivers/fdcan.h deleted file mode 100644 index bc4c2a5..0000000 --- a/panda/board/drivers/fdcan.h +++ /dev/null @@ -1,267 +0,0 @@ -// IRQs: FDCAN1_IT0, FDCAN1_IT1 -// FDCAN2_IT0, FDCAN2_IT1 -// FDCAN3_IT0, FDCAN3_IT1 - -#define CANFD - -typedef struct { - volatile uint32_t header[2]; - volatile uint32_t data_word[CANPACKET_DATA_SIZE_MAX/4U]; -} canfd_fifo; - -FDCAN_GlobalTypeDef *cans[] = {FDCAN1, FDCAN2, FDCAN3}; - -uint8_t can_irq_number[3][2] = { - { FDCAN1_IT0_IRQn, FDCAN1_IT1_IRQn }, - { FDCAN2_IT0_IRQn, FDCAN2_IT1_IRQn }, - { FDCAN3_IT0_IRQn, FDCAN3_IT1_IRQn }, -}; - -#define CAN_ACK_ERROR 3U - -bool can_set_speed(uint8_t can_number) { - bool ret = true; - FDCAN_GlobalTypeDef *FDCANx = CANIF_FROM_CAN_NUM(can_number); - uint8_t bus_number = BUS_NUM_FROM_CAN_NUM(can_number); - - ret &= llcan_set_speed( - FDCANx, - bus_config[bus_number].can_speed, - bus_config[bus_number].can_data_speed, - bus_config[bus_number].canfd_non_iso, - can_loopback, - (unsigned int)(can_silent) & (1U << can_number) - ); - return ret; -} - -void update_can_health_pkt(uint8_t can_number, uint32_t ir_reg) { - FDCAN_GlobalTypeDef *FDCANx = CANIF_FROM_CAN_NUM(can_number); - uint32_t psr_reg = FDCANx->PSR; - uint32_t ecr_reg = FDCANx->ECR; - - can_health[can_number].bus_off = ((psr_reg & FDCAN_PSR_BO) >> FDCAN_PSR_BO_Pos); - can_health[can_number].bus_off_cnt += can_health[can_number].bus_off; - can_health[can_number].error_warning = ((psr_reg & FDCAN_PSR_EW) >> FDCAN_PSR_EW_Pos); - can_health[can_number].error_passive = ((psr_reg & FDCAN_PSR_EP) >> FDCAN_PSR_EP_Pos); - - can_health[can_number].last_error = ((psr_reg & FDCAN_PSR_LEC) >> FDCAN_PSR_LEC_Pos); - if ((can_health[can_number].last_error != 0U) && (can_health[can_number].last_error != 7U)) { - can_health[can_number].last_stored_error = can_health[can_number].last_error; - } - - can_health[can_number].last_data_error = ((psr_reg & FDCAN_PSR_DLEC) >> FDCAN_PSR_DLEC_Pos); - if ((can_health[can_number].last_data_error != 0U) && (can_health[can_number].last_data_error != 7U)) { - can_health[can_number].last_data_stored_error = can_health[can_number].last_data_error; - } - - can_health[can_number].receive_error_cnt = ((ecr_reg & FDCAN_ECR_REC) >> FDCAN_ECR_REC_Pos); - can_health[can_number].transmit_error_cnt = ((ecr_reg & FDCAN_ECR_TEC) >> FDCAN_ECR_TEC_Pos); - - can_health[can_number].irq0_call_rate = interrupts[can_irq_number[can_number][0]].call_rate; - can_health[can_number].irq1_call_rate = interrupts[can_irq_number[can_number][1]].call_rate; - - - if (ir_reg != 0U) { - // Clear error interrupts - FDCANx->IR |= (FDCAN_IR_PED | FDCAN_IR_PEA | FDCAN_IR_EP | FDCAN_IR_BO | FDCAN_IR_RF0L); - can_health[can_number].total_error_cnt += 1U; - // Check for RX FIFO overflow - if ((ir_reg & (FDCAN_IR_RF0L)) != 0) { - can_health[can_number].total_rx_lost_cnt += 1U; - } - // Cases: - // 1. while multiplexing between buses 1 and 3 we are getting ACK errors that overwhelm CAN core, by resetting it recovers faster - // 2. H7 gets stuck in bus off recovery state indefinitely - if ((((can_health[can_number].last_error == CAN_ACK_ERROR) || (can_health[can_number].last_data_error == CAN_ACK_ERROR)) && (can_health[can_number].transmit_error_cnt > 127U)) || - ((ir_reg & FDCAN_IR_BO) != 0)) { - can_health[can_number].can_core_reset_cnt += 1U; - can_health[can_number].total_tx_lost_cnt += (FDCAN_TX_FIFO_EL_CNT - (FDCANx->TXFQS & FDCAN_TXFQS_TFFL)); // TX FIFO msgs will be lost after reset - llcan_clear_send(FDCANx); - } - } -} - -// ***************************** CAN ***************************** -// FDFDCANx_IT1 IRQ Handler (TX) -void process_can(uint8_t can_number) { - if (can_number != 0xffU) { - ENTER_CRITICAL(); - - FDCAN_GlobalTypeDef *FDCANx = CANIF_FROM_CAN_NUM(can_number); - uint8_t bus_number = BUS_NUM_FROM_CAN_NUM(can_number); - - FDCANx->IR |= FDCAN_IR_TFE; // Clear Tx FIFO Empty flag - - if ((FDCANx->TXFQS & FDCAN_TXFQS_TFQF) == 0) { - CANPacket_t to_send; - if (can_pop(can_queues[bus_number], &to_send)) { - if (can_check_checksum(&to_send)) { - can_health[can_number].total_tx_cnt += 1U; - - uint32_t TxFIFOSA = FDCAN_START_ADDRESS + (can_number * FDCAN_OFFSET) + (FDCAN_RX_FIFO_0_EL_CNT * FDCAN_RX_FIFO_0_EL_SIZE); - // get the index of the next TX FIFO element (0 to FDCAN_TX_FIFO_EL_CNT - 1) - uint32_t tx_index = (FDCANx->TXFQS >> FDCAN_TXFQS_TFQPI_Pos) & 0x1F; - // only send if we have received a packet - canfd_fifo *fifo; - fifo = (canfd_fifo *)(TxFIFOSA + (tx_index * FDCAN_TX_FIFO_EL_SIZE)); - - fifo->header[0] = (to_send.extended << 30) | ((to_send.extended != 0U) ? (to_send.addr) : (to_send.addr << 18)); - uint32_t canfd_enabled_header = bus_config[can_number].canfd_enabled ? (1UL << 21) : 0UL; - uint32_t brs_enabled_header = bus_config[can_number].brs_enabled ? (1UL << 20) : 0UL; - fifo->header[1] = (to_send.data_len_code << 16) | canfd_enabled_header | brs_enabled_header; - - uint8_t data_len_w = (dlc_to_len[to_send.data_len_code] / 4U); - data_len_w += ((dlc_to_len[to_send.data_len_code] % 4U) > 0U) ? 1U : 0U; - for (unsigned int i = 0; i < data_len_w; i++) { - BYTE_ARRAY_TO_WORD(fifo->data_word[i], &to_send.data[i*4U]); - } - - FDCANx->TXBAR = (1UL << tx_index); - - // Send back to USB - CANPacket_t to_push; - - to_push.returned = 1U; - to_push.rejected = 0U; - to_push.extended = to_send.extended; - to_push.addr = to_send.addr; - to_push.bus = to_send.bus; - to_push.data_len_code = to_send.data_len_code; - (void)memcpy(to_push.data, to_send.data, dlc_to_len[to_push.data_len_code]); - can_set_checksum(&to_push); - - rx_buffer_overflow += can_push(&can_rx_q, &to_push) ? 0U : 1U; - } else { - can_health[can_number].total_tx_checksum_error_cnt += 1U; - } - - refresh_can_tx_slots_available(); - } - } - EXIT_CRITICAL(); - } -} - -// FDFDCANx_IT0 IRQ Handler (RX and errors) -// blink blue when we are receiving CAN messages -void can_rx(uint8_t can_number) { - FDCAN_GlobalTypeDef *FDCANx = CANIF_FROM_CAN_NUM(can_number); - uint8_t bus_number = BUS_NUM_FROM_CAN_NUM(can_number); - - uint32_t ir_reg = FDCANx->IR; - - // Clear all new messages from Rx FIFO 0 - FDCANx->IR |= FDCAN_IR_RF0N; - while((FDCANx->RXF0S & FDCAN_RXF0S_F0FL) != 0) { - can_health[can_number].total_rx_cnt += 1U; - - // can is live - pending_can_live = 1; - - // get the index of the next RX FIFO element (0 to FDCAN_RX_FIFO_0_EL_CNT - 1) - uint32_t rx_fifo_idx = (uint8_t)((FDCANx->RXF0S >> FDCAN_RXF0S_F0GI_Pos) & 0x3F); - - // Recommended to offset get index by at least +1 if RX FIFO is in overwrite mode and full (datasheet) - if((FDCANx->RXF0S & FDCAN_RXF0S_F0F) == FDCAN_RXF0S_F0F) { - rx_fifo_idx = ((rx_fifo_idx + 1U) >= FDCAN_RX_FIFO_0_EL_CNT) ? 0U : (rx_fifo_idx + 1U); - can_health[can_number].total_rx_lost_cnt += 1U; // At least one message was lost - } - - uint32_t RxFIFO0SA = FDCAN_START_ADDRESS + (can_number * FDCAN_OFFSET); - CANPacket_t to_push; - canfd_fifo *fifo; - - // getting address - fifo = (canfd_fifo *)(RxFIFO0SA + (rx_fifo_idx * FDCAN_RX_FIFO_0_EL_SIZE)); - - to_push.returned = 0U; - to_push.rejected = 0U; - to_push.extended = (fifo->header[0] >> 30) & 0x1U; - to_push.addr = ((to_push.extended != 0U) ? (fifo->header[0] & 0x1FFFFFFFU) : ((fifo->header[0] >> 18) & 0x7FFU)); - to_push.bus = bus_number; - to_push.data_len_code = ((fifo->header[1] >> 16) & 0xFU); - - bool canfd_frame = ((fifo->header[1] >> 21) & 0x1U); - bool brs_frame = ((fifo->header[1] >> 20) & 0x1U); - - uint8_t data_len_w = (dlc_to_len[to_push.data_len_code] / 4U); - data_len_w += ((dlc_to_len[to_push.data_len_code] % 4U) > 0U) ? 1U : 0U; - for (unsigned int i = 0; i < data_len_w; i++) { - WORD_TO_BYTE_ARRAY(&to_push.data[i*4U], fifo->data_word[i]); - } - can_set_checksum(&to_push); - - // forwarding (panda only) - int bus_fwd_num = safety_fwd_hook(bus_number, to_push.addr); - if (bus_fwd_num < 0) { - bus_fwd_num = bus_config[can_number].forwarding_bus; - } - if (bus_fwd_num != -1) { - CANPacket_t to_send; - - to_send.returned = 0U; - to_send.rejected = 0U; - to_send.extended = to_push.extended; - to_send.addr = to_push.addr; - to_send.bus = to_push.bus; - to_send.data_len_code = to_push.data_len_code; - (void)memcpy(to_send.data, to_push.data, dlc_to_len[to_push.data_len_code]); - can_set_checksum(&to_send); - - can_send(&to_send, bus_fwd_num, true); - can_health[can_number].total_fwd_cnt += 1U; - } - - safety_rx_invalid += safety_rx_hook(&to_push) ? 0U : 1U; - ignition_can_hook(&to_push); - - current_board->set_led(LED_BLUE, true); - rx_buffer_overflow += can_push(&can_rx_q, &to_push) ? 0U : 1U; - - // Enable CAN FD and BRS if CAN FD message was received - if (!(bus_config[can_number].canfd_enabled) && (canfd_frame)) { - bus_config[can_number].canfd_enabled = true; - } - if (!(bus_config[can_number].brs_enabled) && (brs_frame)) { - bus_config[can_number].brs_enabled = true; - } - - // update read index - FDCANx->RXF0A = rx_fifo_idx; - } - - // Error handling - if ((ir_reg & (FDCAN_IR_PED | FDCAN_IR_PEA | FDCAN_IR_EP | FDCAN_IR_BO | FDCAN_IR_RF0L)) != 0) { - update_can_health_pkt(can_number, ir_reg); - } -} - -void FDCAN1_IT0_IRQ_Handler(void) { can_rx(0); } -void FDCAN1_IT1_IRQ_Handler(void) { process_can(0); } - -void FDCAN2_IT0_IRQ_Handler(void) { can_rx(1); } -void FDCAN2_IT1_IRQ_Handler(void) { process_can(1); } - -void FDCAN3_IT0_IRQ_Handler(void) { can_rx(2); } -void FDCAN3_IT1_IRQ_Handler(void) { process_can(2); } - -bool can_init(uint8_t can_number) { - bool ret = false; - - REGISTER_INTERRUPT(FDCAN1_IT0_IRQn, FDCAN1_IT0_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_1) - REGISTER_INTERRUPT(FDCAN1_IT1_IRQn, FDCAN1_IT1_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_1) - REGISTER_INTERRUPT(FDCAN2_IT0_IRQn, FDCAN2_IT0_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_2) - REGISTER_INTERRUPT(FDCAN2_IT1_IRQn, FDCAN2_IT1_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_2) - REGISTER_INTERRUPT(FDCAN3_IT0_IRQn, FDCAN3_IT0_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_3) - REGISTER_INTERRUPT(FDCAN3_IT1_IRQn, FDCAN3_IT1_IRQ_Handler, CAN_INTERRUPT_RATE, FAULT_INTERRUPT_RATE_CAN_3) - - if (can_number != 0xffU) { - FDCAN_GlobalTypeDef *FDCANx = CANIF_FROM_CAN_NUM(can_number); - ret &= can_set_speed(can_number); - ret &= llcan_init(FDCANx); - // in case there are queued up messages - process_can(can_number); - } - return ret; -} diff --git a/panda/board/drivers/gmlan_alt.h b/panda/board/drivers/gmlan_alt.h deleted file mode 100644 index 2dbc381..0000000 --- a/panda/board/drivers/gmlan_alt.h +++ /dev/null @@ -1,270 +0,0 @@ -#define GMLAN_TICKS_PER_SECOND 33300 //1sec @ 33.3kbps -#define GMLAN_TICKS_PER_TIMEOUT_TICKLE 500 //15ms @ 33.3kbps -#define GMLAN_HIGH 0 //0 is high on bus (dominant) -#define GMLAN_LOW 1 //1 is low on bus - -#define DISABLED -1 -#define BITBANG 0 -#define GPIO_SWITCH 1 - -#define MAX_BITS_CAN_PACKET (200) - -int gmlan_alt_mode = DISABLED; - -// returns out_len -int do_bitstuff(char *out, const char *in, int in_len) { - int last_bit = -1; - int bit_cnt = 0; - int j = 0; - for (int i = 0; i < in_len; i++) { - char bit = in[i]; - out[j] = bit; - j++; - - // do the stuffing - if (bit == (char)last_bit) { - bit_cnt++; - if (bit_cnt == 5) { - // 5 in a row the same, do stuff - last_bit = !bit ? 1 : 0; - out[j] = last_bit; - j++; - bit_cnt = 1; - } - } else { - // this is a new bit - last_bit = (int)bit; - bit_cnt = 1; - } - } - return j; -} - -int append_crc(char *in, int in_len) { - unsigned int crc = 0; - for (int i = 0; i < in_len; i++) { - crc <<= 1; - if (((unsigned int)(in[i]) ^ ((crc >> 15) & 1U)) != 0U) { - crc = crc ^ 0x4599U; - } - crc &= 0x7fffU; - } - int in_len_copy = in_len; - for (int i = 14; i >= 0; i--) { - in[in_len_copy] = (crc >> (unsigned int)(i)) & 1U; - in_len_copy++; - } - return in_len_copy; -} - -int append_bits(char *in, int in_len, const char *app, int app_len) { - int in_len_copy = in_len; - for (int i = 0; i < app_len; i++) { - in[in_len_copy] = app[i]; - in_len_copy++; - } - return in_len_copy; -} - -int append_int(char *in, int in_len, int val, int val_len) { - int in_len_copy = in_len; - for (int i = val_len - 1; i >= 0; i--) { - in[in_len_copy] = ((unsigned int)(val) & (1U << (unsigned int)(i))) != 0U; - in_len_copy++; - } - return in_len_copy; -} - -int get_bit_message(char *out, const CANPacket_t *to_bang) { - char pkt[MAX_BITS_CAN_PACKET]; - char footer[] = { - 1, // CRC delimiter - 1, // ACK - 1, // ACK delimiter - 1,1,1,1,1,1,1, // EOF - 1,1,1, // IFS - }; - - int len = 0; - - // test packet - int dlc_len = GET_LEN(to_bang); - len = append_int(pkt, len, 0, 1); // Start-of-frame - - if (to_bang->extended != 0U) { - // extended identifier - len = append_int(pkt, len, GET_ADDR(to_bang) >> 18, 11); // Identifier - len = append_int(pkt, len, 3, 2); // SRR+IDE - len = append_int(pkt, len, (GET_ADDR(to_bang)) & ((1UL << 18) - 1U), 18); // Identifier - len = append_int(pkt, len, 0, 3); // RTR+r1+r0 - } else { - // standard identifier - len = append_int(pkt, len, GET_ADDR(to_bang), 11); // Identifier - len = append_int(pkt, len, 0, 3); // RTR+IDE+reserved - } - - len = append_int(pkt, len, dlc_len, 4); // Data length code - - // append data - for (int i = 0; i < dlc_len; i++) { - len = append_int(pkt, len, to_bang->data[i], 8); - } - - // append crc - len = append_crc(pkt, len); - - // do bitstuffing - len = do_bitstuff(out, pkt, len); - - // append footer - len = append_bits(out, len, footer, sizeof(footer)); - return len; -} - -void TIM12_IRQ_Handler(void); - -void setup_timer(void) { - // register interrupt - REGISTER_INTERRUPT(TIM8_BRK_TIM12_IRQn, TIM12_IRQ_Handler, 40000U, FAULT_INTERRUPT_RATE_GMLAN) - - // setup - register_set(&(TIM12->PSC), (APB1_TIMER_FREQ-1U), 0xFFFFU); // Tick on 1 us - register_set(&(TIM12->CR1), TIM_CR1_CEN, 0x3FU); // Enable - register_set(&(TIM12->ARR), (30U-1U), 0xFFFFU); // 33.3 kbps - - // in case it's disabled - NVIC_EnableIRQ(TIM8_BRK_TIM12_IRQn); - - // run the interrupt - register_set(&(TIM12->DIER), TIM_DIER_UIE, 0x5F5FU); // Update interrupt - TIM12->SR = 0; -} - -int gmlan_timeout_counter = GMLAN_TICKS_PER_TIMEOUT_TICKLE; //GMLAN transceiver times out every 17ms held high; tickle every 15ms -int can_timeout_counter = GMLAN_TICKS_PER_SECOND; //1 second - -int inverted_bit_to_send = GMLAN_HIGH; -int gmlan_switch_below_timeout = -1; -int gmlan_switch_timeout_enable = 0; - -void set_bitbanged_gmlan(int val) { - if (val != 0) { - register_set_bits(&(GPIOB->ODR), (1UL << 13)); - } else { - register_clear_bits(&(GPIOB->ODR), (1UL << 13)); - } -} - -char pkt_stuffed[MAX_BITS_CAN_PACKET]; -int gmlan_sending = -1; -int gmlan_sendmax = -1; -bool gmlan_send_ok = true; - -int gmlan_silent_count = 0; -int gmlan_fail_count = 0; -#define REQUIRED_SILENT_TIME 10 -#define MAX_FAIL_COUNT 10 - -void TIM12_IRQ_Handler(void) { - if (gmlan_alt_mode == BITBANG) { - if ((TIM12->SR & TIM_SR_UIF) && (gmlan_sendmax != -1)) { - int read = get_gpio_input(GPIOB, 12); - if (gmlan_silent_count < REQUIRED_SILENT_TIME) { - if (read == 0) { - gmlan_silent_count = 0; - } else { - gmlan_silent_count++; - } - } else { - bool retry = 0; - // in send loop - if ((gmlan_sending > 0) && // not first bit - ((read == 0) && (pkt_stuffed[gmlan_sending-1] == (char)1)) && // bus wrongly dominant - (gmlan_sending != (gmlan_sendmax - 11))) { //not ack bit - print("GMLAN ERR: bus driven at "); - puth(gmlan_sending); - print("\n"); - retry = 1; - } else if ((read == 1) && (gmlan_sending == (gmlan_sendmax - 11))) { // recessive during ACK - print("GMLAN ERR: didn't recv ACK\n"); - retry = 1; - } else { - // do not retry - } - if (retry) { - // reset sender (retry after 7 silent) - set_bitbanged_gmlan(1); // recessive - gmlan_silent_count = 0; - gmlan_sending = 0; - gmlan_fail_count++; - if (gmlan_fail_count == MAX_FAIL_COUNT) { - print("GMLAN ERR: giving up send\n"); - gmlan_send_ok = false; - } - } else { - set_bitbanged_gmlan(pkt_stuffed[gmlan_sending]); - gmlan_sending++; - } - } - if ((gmlan_sending == gmlan_sendmax) || (gmlan_fail_count == MAX_FAIL_COUNT)) { - set_bitbanged_gmlan(1); // recessive - set_gpio_mode(GPIOB, 13, MODE_INPUT); - register_clear_bits(&(TIM12->DIER), TIM_DIER_UIE); // No update interrupt - register_set(&(TIM12->CR1), 0U, 0x3FU); // Disable timer - gmlan_sendmax = -1; // exit - } - } - } else if (gmlan_alt_mode == GPIO_SWITCH) { - if ((TIM12->SR & TIM_SR_UIF) && (gmlan_switch_below_timeout != -1)) { - if ((can_timeout_counter == 0) && gmlan_switch_timeout_enable) { - //it has been more than 1 second since timeout was reset; disable timer and restore the GMLAN output - set_gpio_output(GPIOB, 13, GMLAN_LOW); - gmlan_switch_below_timeout = -1; - gmlan_timeout_counter = GMLAN_TICKS_PER_TIMEOUT_TICKLE; - gmlan_alt_mode = DISABLED; - } - else { - can_timeout_counter--; - if (gmlan_timeout_counter == 0) { - //Send a 1 (bus low) every 15ms to reset the GMLAN transceivers timeout - gmlan_timeout_counter = GMLAN_TICKS_PER_TIMEOUT_TICKLE; - set_gpio_output(GPIOB, 13, GMLAN_LOW); - } - else { - set_gpio_output(GPIOB, 13, inverted_bit_to_send); - gmlan_timeout_counter--; - } - } - } - } else { - // Invalid GMLAN mode. Do not put a print statement here, way too fast to keep up with - } - TIM12->SR = 0; -} - -bool bitbang_gmlan(const CANPacket_t *to_bang) { - gmlan_send_ok = true; - gmlan_alt_mode = BITBANG; - -#ifdef HW_TYPE_DOS - if (hw_type == HW_TYPE_DOS) { - if (gmlan_sendmax == -1) { - int len = get_bit_message(pkt_stuffed, to_bang); - gmlan_fail_count = 0; - gmlan_silent_count = 0; - gmlan_sending = 0; - gmlan_sendmax = len; - // setup for bitbang loop - set_bitbanged_gmlan(1); // recessive - set_gpio_mode(GPIOB, 13, MODE_OUTPUT); - - // 33kbps - setup_timer(); - } - } -#else - UNUSED(to_bang); -#endif - - return gmlan_send_ok; -} diff --git a/panda/board/drivers/gpio.h b/panda/board/drivers/gpio.h deleted file mode 100644 index bf96a03..0000000 --- a/panda/board/drivers/gpio.h +++ /dev/null @@ -1,92 +0,0 @@ -#define MODE_INPUT 0 -#define MODE_OUTPUT 1 -#define MODE_ALTERNATE 2 -#define MODE_ANALOG 3 - -#define PULL_NONE 0 -#define PULL_UP 1 -#define PULL_DOWN 2 - -#define OUTPUT_TYPE_PUSH_PULL 0U -#define OUTPUT_TYPE_OPEN_DRAIN 1U - -typedef struct { - GPIO_TypeDef *bank; - uint8_t pin; -} gpio_t; - -void set_gpio_mode(GPIO_TypeDef *GPIO, unsigned int pin, unsigned int mode) { - ENTER_CRITICAL(); - uint32_t tmp = GPIO->MODER; - tmp &= ~(3U << (pin * 2U)); - tmp |= (mode << (pin * 2U)); - register_set(&(GPIO->MODER), tmp, 0xFFFFFFFFU); - EXIT_CRITICAL(); -} - -void set_gpio_output(GPIO_TypeDef *GPIO, unsigned int pin, bool enabled) { - ENTER_CRITICAL(); - if (enabled) { - register_set_bits(&(GPIO->ODR), (1UL << pin)); - } else { - register_clear_bits(&(GPIO->ODR), (1UL << pin)); - } - set_gpio_mode(GPIO, pin, MODE_OUTPUT); - EXIT_CRITICAL(); -} - -void set_gpio_output_type(GPIO_TypeDef *GPIO, unsigned int pin, unsigned int output_type){ - ENTER_CRITICAL(); - if(output_type == OUTPUT_TYPE_OPEN_DRAIN) { - register_set_bits(&(GPIO->OTYPER), (1UL << pin)); - } else { - register_clear_bits(&(GPIO->OTYPER), (1U << pin)); - } - EXIT_CRITICAL(); -} - -void set_gpio_alternate(GPIO_TypeDef *GPIO, unsigned int pin, unsigned int mode) { - ENTER_CRITICAL(); - uint32_t tmp = GPIO->AFR[pin >> 3U]; - tmp &= ~(0xFU << ((pin & 7U) * 4U)); - tmp |= mode << ((pin & 7U) * 4U); - register_set(&(GPIO->AFR[pin >> 3]), tmp, 0xFFFFFFFFU); - set_gpio_mode(GPIO, pin, MODE_ALTERNATE); - EXIT_CRITICAL(); -} - -void set_gpio_pullup(GPIO_TypeDef *GPIO, unsigned int pin, unsigned int mode) { - ENTER_CRITICAL(); - uint32_t tmp = GPIO->PUPDR; - tmp &= ~(3U << (pin * 2U)); - tmp |= (mode << (pin * 2U)); - register_set(&(GPIO->PUPDR), tmp, 0xFFFFFFFFU); - EXIT_CRITICAL(); -} - -int get_gpio_input(const GPIO_TypeDef *GPIO, unsigned int pin) { - return (GPIO->IDR & (1UL << pin)) == (1UL << pin); -} - -void gpio_set_all_output(const gpio_t *pins, uint8_t num_pins, bool enabled) { - for (uint8_t i = 0; i < num_pins; i++) { - set_gpio_output(pins[i].bank, pins[i].pin, enabled); - } -} - -void gpio_set_bitmask(const gpio_t *pins, uint8_t num_pins, uint32_t bitmask) { - for (uint8_t i = 0; i < num_pins; i++) { - set_gpio_output(pins[i].bank, pins[i].pin, (bitmask >> i) & 1U); - } -} - -// Detection with internal pullup -#define PULL_EFFECTIVE_DELAY 4096 -bool detect_with_pull(GPIO_TypeDef *GPIO, int pin, int mode) { - set_gpio_mode(GPIO, pin, MODE_INPUT); - set_gpio_pullup(GPIO, pin, mode); - for (volatile int i=0; iharness_config->has_harness) { - bool drive_relay = intercept; - if (harness.status == HARNESS_STATUS_NC) { - // no harness, no relay to drive - drive_relay = false; - } - - if (drive_relay || ignition_relay) { - harness.relay_driven = true; - } - - // wait until we're not reading the analog voltages anymore - while (harness.sbu_adc_lock) {} - - if (harness.status == HARNESS_STATUS_NORMAL) { - set_gpio_output(current_board->harness_config->GPIO_relay_SBU1, current_board->harness_config->pin_relay_SBU1, !ignition_relay); - set_gpio_output(current_board->harness_config->GPIO_relay_SBU2, current_board->harness_config->pin_relay_SBU2, !drive_relay); - } else { - set_gpio_output(current_board->harness_config->GPIO_relay_SBU1, current_board->harness_config->pin_relay_SBU1, !drive_relay); - set_gpio_output(current_board->harness_config->GPIO_relay_SBU2, current_board->harness_config->pin_relay_SBU2, !ignition_relay); - } - - if (!(drive_relay || ignition_relay)) { - harness.relay_driven = false; - } - } -} - -bool harness_check_ignition(void) { - bool ret = false; - - // wait until we're not reading the analog voltages anymore - while (harness.sbu_adc_lock) {} - - switch(harness.status){ - case HARNESS_STATUS_NORMAL: - ret = !get_gpio_input(current_board->harness_config->GPIO_SBU1, current_board->harness_config->pin_SBU1); - break; - case HARNESS_STATUS_FLIPPED: - ret = !get_gpio_input(current_board->harness_config->GPIO_SBU2, current_board->harness_config->pin_SBU2); - break; - default: - break; - } - return ret; -} - -uint8_t harness_detect_orientation(void) { - uint8_t ret = harness.status; - - #ifndef BOOTSTUB - // We can't detect orientation if the relay is being driven - if (!harness.relay_driven && current_board->harness_config->has_harness) { - harness.sbu_adc_lock = true; - set_gpio_mode(current_board->harness_config->GPIO_SBU1, current_board->harness_config->pin_SBU1, MODE_ANALOG); - set_gpio_mode(current_board->harness_config->GPIO_SBU2, current_board->harness_config->pin_SBU2, MODE_ANALOG); - - harness.sbu1_voltage_mV = adc_get_mV(current_board->harness_config->adc_channel_SBU1); - harness.sbu2_voltage_mV = adc_get_mV(current_board->harness_config->adc_channel_SBU2); - uint16_t detection_threshold = current_board->avdd_mV / 2U; - - // Detect connection and orientation - if((harness.sbu1_voltage_mV < detection_threshold) || (harness.sbu2_voltage_mV < detection_threshold)){ - if (harness.sbu1_voltage_mV < harness.sbu2_voltage_mV) { - // orientation flipped (PANDA_SBU1->HARNESS_SBU1(relay), PANDA_SBU2->HARNESS_SBU2(ign)) - ret = HARNESS_STATUS_FLIPPED; - } else { - // orientation normal (PANDA_SBU2->HARNESS_SBU1(relay), PANDA_SBU1->HARNESS_SBU2(ign)) - // (SBU1->SBU2 is the normal orientation connection per USB-C cable spec) - ret = HARNESS_STATUS_NORMAL; - } - } else { - ret = HARNESS_STATUS_NC; - } - - // Pins are not 5V tolerant in ADC mode - set_gpio_mode(current_board->harness_config->GPIO_SBU1, current_board->harness_config->pin_SBU1, MODE_INPUT); - set_gpio_mode(current_board->harness_config->GPIO_SBU2, current_board->harness_config->pin_SBU2, MODE_INPUT); - harness.sbu_adc_lock = false; - } - #endif - - return ret; -} - -void harness_tick(void) { - harness.status = harness_detect_orientation(); -} - -void harness_init(void) { - // delay such that the connection is fully made before trying orientation detection - current_board->set_led(LED_BLUE, true); - delay(10000000); - current_board->set_led(LED_BLUE, false); - - // try to detect orientation - harness.status = harness_detect_orientation(); - if (harness.status != HARNESS_STATUS_NC) { - print("detected car harness with orientation "); puth2(harness.status); print("\n"); - } else { - print("failed to detect car harness!\n"); - } - - // keep buses connected by default - set_intercept_relay(false, false); -} diff --git a/panda/board/drivers/interrupts.h b/panda/board/drivers/interrupts.h deleted file mode 100644 index d4c72be..0000000 --- a/panda/board/drivers/interrupts.h +++ /dev/null @@ -1,99 +0,0 @@ -typedef struct interrupt { - IRQn_Type irq_type; - void (*handler)(void); - uint32_t call_counter; - uint32_t call_rate; - uint32_t max_call_rate; // Call rate is defined as the amount of calls each second - uint32_t call_rate_fault; -} interrupt; - -void interrupt_timer_init(void); -uint32_t microsecond_timer_get(void); - -void unused_interrupt_handler(void) { - // Something is wrong if this handler is called! - print("Unused interrupt handler called!\n"); - fault_occurred(FAULT_UNUSED_INTERRUPT_HANDLED); -} - -interrupt interrupts[NUM_INTERRUPTS]; - -#define REGISTER_INTERRUPT(irq_num, func_ptr, call_rate_max, rate_fault) \ - interrupts[irq_num].irq_type = (irq_num); \ - interrupts[irq_num].handler = (func_ptr); \ - interrupts[irq_num].call_counter = 0U; \ - interrupts[irq_num].call_rate = 0U; \ - interrupts[irq_num].max_call_rate = (call_rate_max); \ - interrupts[irq_num].call_rate_fault = (rate_fault); - -bool check_interrupt_rate = false; - -uint8_t interrupt_depth = 0U; -uint32_t last_time = 0U; -uint32_t idle_time = 0U; -uint32_t busy_time = 0U; -float interrupt_load = 0.0f; - -void handle_interrupt(IRQn_Type irq_type){ - ENTER_CRITICAL(); - if (interrupt_depth == 0U) { - uint32_t time = microsecond_timer_get(); - idle_time += get_ts_elapsed(time, last_time); - last_time = time; - } - interrupt_depth += 1U; - EXIT_CRITICAL(); - - interrupts[irq_type].call_counter++; - interrupts[irq_type].handler(); - - // Check that the interrupts don't fire too often - if (check_interrupt_rate && (interrupts[irq_type].call_counter > interrupts[irq_type].max_call_rate)) { - fault_occurred(interrupts[irq_type].call_rate_fault); - } - - ENTER_CRITICAL(); - interrupt_depth -= 1U; - if (interrupt_depth == 0U) { - uint32_t time = microsecond_timer_get(); - busy_time += get_ts_elapsed(time, last_time); - last_time = time; - } - EXIT_CRITICAL(); -} - -// Every second -void interrupt_timer_handler(void) { - if (INTERRUPT_TIMER->SR != 0) { - for (uint16_t i = 0U; i < NUM_INTERRUPTS; i++) { - // Log IRQ call rate faults - if (check_interrupt_rate && (interrupts[i].call_counter > interrupts[i].max_call_rate)) { - print("Interrupt 0x"); puth(i); print(" fired too often (0x"); puth(interrupts[i].call_counter); print("/s)!\n"); - } - - // Reset interrupt counters - interrupts[i].call_rate = interrupts[i].call_counter; - interrupts[i].call_counter = 0U; - } - - // Calculate interrupt load - // The bootstub does not have the FPU enabled, so can't do float operations. -#if !defined(BOOTSTUB) - interrupt_load = ((busy_time + idle_time) > 0U) ? ((float) (((float) busy_time) / (busy_time + idle_time))) : 0.0f; -#endif - idle_time = 0U; - busy_time = 0U; - } - INTERRUPT_TIMER->SR = 0; -} - -void init_interrupts(bool check_rate_limit){ - check_interrupt_rate = check_rate_limit; - - for(uint16_t i=0U; iCR1), TIM_CR1_CEN | TIM_CR1_ARPE, 0x3FU); - - // Set channel as PWM mode 1 and enable output - switch(channel){ - case 1U: - register_set_bits(&(TIM->CCMR1), (TIM_CCMR1_OC1M_2 | TIM_CCMR1_OC1M_1 | TIM_CCMR1_OC1PE)); - register_set_bits(&(TIM->CCER), TIM_CCER_CC1E); - break; - case 2U: - register_set_bits(&(TIM->CCMR1), (TIM_CCMR1_OC2M_2 | TIM_CCMR1_OC2M_1 | TIM_CCMR1_OC2PE)); - register_set_bits(&(TIM->CCER), TIM_CCER_CC2E); - break; - case 3U: - register_set_bits(&(TIM->CCMR2), (TIM_CCMR2_OC3M_2 | TIM_CCMR2_OC3M_1 | TIM_CCMR2_OC3PE)); - register_set_bits(&(TIM->CCER), TIM_CCER_CC3E); - break; - case 4U: - register_set_bits(&(TIM->CCMR2), (TIM_CCMR2_OC4M_2 | TIM_CCMR2_OC4M_1 | TIM_CCMR2_OC4PE)); - register_set_bits(&(TIM->CCER), TIM_CCER_CC4E); - break; - default: - break; - } - - // Set max counter value - register_set(&(TIM->ARR), PWM_COUNTER_OVERFLOW, 0xFFFFU); - - // Update registers and clear counter - TIM->EGR |= TIM_EGR_UG; -} - -void pwm_set(TIM_TypeDef *TIM, uint8_t channel, uint8_t percentage){ - uint16_t comp_value = (((uint16_t) percentage * PWM_COUNTER_OVERFLOW) / 100U); - switch(channel){ - case 1U: - register_set(&(TIM->CCR1), comp_value, 0xFFFFU); - break; - case 2U: - register_set(&(TIM->CCR2), comp_value, 0xFFFFU); - break; - case 3U: - register_set(&(TIM->CCR3), comp_value, 0xFFFFU); - break; - case 4U: - register_set(&(TIM->CCR4), comp_value, 0xFFFFU); - break; - default: - break; - } -} diff --git a/panda/board/drivers/registers.h b/panda/board/drivers/registers.h deleted file mode 100644 index a5f8b02..0000000 --- a/panda/board/drivers/registers.h +++ /dev/null @@ -1,81 +0,0 @@ - -typedef struct reg { - volatile uint32_t *address; - uint32_t value; - uint32_t check_mask; -} reg; - -// 10 bit hash with 23 as a prime -#define REGISTER_MAP_SIZE 0x3FFU -#define HASHING_PRIME 23U -#define CHECK_COLLISION(hash, addr) (((uint32_t) register_map[hash].address != 0U) && (register_map[hash].address != (addr))) - -reg register_map[REGISTER_MAP_SIZE]; - -// Hash spread in first and second iterations seems to be reasonable. -// See: tests/development/register_hashmap_spread.py -// Also, check the collision warnings in the debug output, and minimize those. -uint16_t hash_addr(uint32_t input){ - return (((input >> 16U) ^ ((((input + 1U) & 0xFFFFU) * HASHING_PRIME) & 0xFFFFU)) & REGISTER_MAP_SIZE); -} - -// Do not put bits in the check mask that get changed by the hardware -void register_set(volatile uint32_t *addr, uint32_t val, uint32_t mask){ - ENTER_CRITICAL() - // Set bits in register that are also in the mask - (*addr) = ((*addr) & (~mask)) | (val & mask); - - // Add these values to the map - uint16_t hash = hash_addr((uint32_t) addr); - uint16_t tries = REGISTER_MAP_SIZE; - while(CHECK_COLLISION(hash, addr) && (tries > 0U)) { hash = hash_addr((uint32_t) hash); tries--;} - if (tries != 0U){ - register_map[hash].address = addr; - register_map[hash].value = (register_map[hash].value & (~mask)) | (val & mask); - register_map[hash].check_mask |= mask; - } else { - #ifdef DEBUG_FAULTS - print("Hash collision: address 0x"); puth((uint32_t) addr); print("!\n"); - #endif - } - EXIT_CRITICAL() -} - -// Set individual bits. Also add them to the check_mask. -// Do not use this to change bits that get reset by the hardware -void register_set_bits(volatile uint32_t *addr, uint32_t val) { - return register_set(addr, val, val); -} - -// Clear individual bits. Also add them to the check_mask. -// Do not use this to clear bits that get set by the hardware -void register_clear_bits(volatile uint32_t *addr, uint32_t val) { - return register_set(addr, (~val), val); -} - -// To be called periodically -void check_registers(void){ - for(uint16_t i=0U; i> 4U) * 10U) + (value & 0x0FU); -} - -void rtc_set_time(timestamp_t time){ - print("Setting RTC time\n"); - - // Disable write protection - disable_bdomain_protection(); - RTC->WPR = 0xCA; - RTC->WPR = 0x53; - - // Enable initialization mode - register_set_bits(&(RTC->ISR), RTC_ISR_INIT); - while((RTC->ISR & RTC_ISR_INITF) == 0){} - - // Set time - RTC->TR = (to_bcd(time.hour) << RTC_TR_HU_Pos) | (to_bcd(time.minute) << RTC_TR_MNU_Pos) | (to_bcd(time.second) << RTC_TR_SU_Pos); - RTC->DR = (to_bcd(time.year - YEAR_OFFSET) << RTC_DR_YU_Pos) | (time.weekday << RTC_DR_WDU_Pos) | (to_bcd(time.month) << RTC_DR_MU_Pos) | (to_bcd(time.day) << RTC_DR_DU_Pos); - - // Set options - register_set(&(RTC->CR), 0U, 0xFCFFFFU); - - // Disable initalization mode - register_clear_bits(&(RTC->ISR), RTC_ISR_INIT); - - // Wait for synchronization - while((RTC->ISR & RTC_ISR_RSF) == 0){} - - // Re-enable write protection - RTC->WPR = 0x00; - enable_bdomain_protection(); -} - -timestamp_t rtc_get_time(void){ - timestamp_t result; - // Init with zero values in case there is no RTC running - result.year = 0U; - result.month = 0U; - result.day = 0U; - result.weekday = 0U; - result.hour = 0U; - result.minute = 0U; - result.second = 0U; - - // Wait until the register sync flag is set - while((RTC->ISR & RTC_ISR_RSF) == 0){} - - // Read time and date registers. Since our HSE > 7*LSE, this should be fine. - uint32_t time = RTC->TR; - uint32_t date = RTC->DR; - - // Parse values - result.year = from_bcd((date & (RTC_DR_YT | RTC_DR_YU)) >> RTC_DR_YU_Pos) + YEAR_OFFSET; - result.month = from_bcd((date & (RTC_DR_MT | RTC_DR_MU)) >> RTC_DR_MU_Pos); - result.day = from_bcd((date & (RTC_DR_DT | RTC_DR_DU)) >> RTC_DR_DU_Pos); - result.weekday = ((date & RTC_DR_WDU) >> RTC_DR_WDU_Pos); - result.hour = from_bcd((time & (RTC_TR_HT | RTC_TR_HU)) >> RTC_TR_HU_Pos); - result.minute = from_bcd((time & (RTC_TR_MNT | RTC_TR_MNU)) >> RTC_TR_MNU_Pos); - result.second = from_bcd((time & (RTC_TR_ST | RTC_TR_SU)) >> RTC_TR_SU_Pos); - - return result; -} diff --git a/panda/board/drivers/simple_watchdog.h b/panda/board/drivers/simple_watchdog.h deleted file mode 100644 index fe0c856..0000000 --- a/panda/board/drivers/simple_watchdog.h +++ /dev/null @@ -1,26 +0,0 @@ -typedef struct simple_watchdog_state_t { - uint32_t fault; - uint32_t last_ts; - uint32_t threshold; -} simple_watchdog_state_t; - -simple_watchdog_state_t wd_state; - - -void simple_watchdog_kick(void) { - uint32_t ts = microsecond_timer_get(); - - uint32_t et = get_ts_elapsed(ts, wd_state.last_ts); - if (et > wd_state.threshold) { - print("WD timeout 0x"); puth(et); print("\n"); - fault_occurred(wd_state.fault); - } - - wd_state.last_ts = ts; -} - -void simple_watchdog_init(uint32_t fault, uint32_t threshold) { - wd_state.fault = fault; - wd_state.threshold = threshold; - wd_state.last_ts = microsecond_timer_get(); -} diff --git a/panda/board/drivers/spi.h b/panda/board/drivers/spi.h deleted file mode 100644 index 1a7b9be..0000000 --- a/panda/board/drivers/spi.h +++ /dev/null @@ -1,258 +0,0 @@ -#pragma once - -#include "crc.h" - -#define SPI_TIMEOUT_US 10000U - -// got max rate from hitting a non-existent endpoint -// in a tight loop, plus some buffer -#define SPI_IRQ_RATE 16000U - -#ifdef STM32H7 -#define SPI_BUF_SIZE 2048U -// H7 DMA2 located in D2 domain, so we need to use SRAM1/SRAM2 -__attribute__((section(".sram12"))) uint8_t spi_buf_rx[SPI_BUF_SIZE]; -__attribute__((section(".sram12"))) uint8_t spi_buf_tx[SPI_BUF_SIZE]; -#else -#define SPI_BUF_SIZE 1024U -uint8_t spi_buf_rx[SPI_BUF_SIZE]; -uint8_t spi_buf_tx[SPI_BUF_SIZE]; -#endif - -#define SPI_CHECKSUM_START 0xABU -#define SPI_SYNC_BYTE 0x5AU -#define SPI_HACK 0x79U -#define SPI_DACK 0x85U -#define SPI_NACK 0x1FU - -// SPI states -enum { - SPI_STATE_HEADER, - SPI_STATE_HEADER_ACK, - SPI_STATE_HEADER_NACK, - SPI_STATE_DATA_RX, - SPI_STATE_DATA_RX_ACK, - SPI_STATE_DATA_TX -}; - -bool spi_tx_dma_done = false; -uint8_t spi_state = SPI_STATE_HEADER; -uint8_t spi_endpoint; -uint16_t spi_data_len_mosi; -uint16_t spi_data_len_miso; -uint16_t spi_checksum_error_count = 0; -bool spi_can_tx_ready = false; - -const char version_text[] = "VERSION"; - -#define SPI_HEADER_SIZE 7U - -// low level SPI prototypes -void llspi_init(void); -void llspi_mosi_dma(uint8_t *addr, int len); -void llspi_miso_dma(uint8_t *addr, int len); - -void can_tx_comms_resume_spi(void) { - spi_can_tx_ready = true; -} - -uint16_t spi_version_packet(uint8_t *out) { - // this protocol version request is a stable portion of - // the panda's SPI protocol. its contents match that of the - // panda USB descriptors and are sufficent to list/enumerate - // a panda, determine panda type, and bootstub status. - - // the response is: - // VERSION + 2 byte data length + data + CRC8 - - // echo "VERSION" - (void)memcpy(out, version_text, 7); - - // write response - uint16_t data_len = 0; - uint16_t data_pos = 7U + 2U; - - // write serial - #ifdef UID_BASE - (void)memcpy(&out[data_pos], ((uint8_t *)UID_BASE), 12); - data_len += 12U; - #endif - - // HW type - out[data_pos + data_len] = hw_type; - data_len += 1U; - - // bootstub - out[data_pos + data_len] = USB_PID & 0xFFU; - data_len += 1U; - - // SPI protocol version - out[data_pos + data_len] = 0x2; - data_len += 1U; - - // data length - out[7] = data_len & 0xFFU; - out[8] = (data_len >> 8) & 0xFFU; - - // CRC8 - uint16_t resp_len = data_pos + data_len; - out[resp_len] = crc_checksum(out, resp_len, 0xD5U); - resp_len += 1U; - - return resp_len; -} - -void spi_init(void) { - // platform init - llspi_init(); - - // Start the first packet! - spi_state = SPI_STATE_HEADER; - llspi_mosi_dma(spi_buf_rx, SPI_HEADER_SIZE); -} - -bool validate_checksum(const uint8_t *data, uint16_t len) { - // TODO: can speed this up by casting the bulk to uint32_t and xor-ing the bytes afterwards - uint8_t checksum = SPI_CHECKSUM_START; - for(uint16_t i = 0U; i < len; i++){ - checksum ^= data[i]; - } - return checksum == 0U; -} - -void spi_rx_done(void) { - uint16_t response_len = 0U; - uint8_t next_rx_state = SPI_STATE_HEADER_NACK; - bool checksum_valid = false; - - // parse header - spi_endpoint = spi_buf_rx[1]; - spi_data_len_mosi = (spi_buf_rx[3] << 8) | spi_buf_rx[2]; - spi_data_len_miso = (spi_buf_rx[5] << 8) | spi_buf_rx[4]; - - if (memcmp(spi_buf_rx, version_text, 7) == 0) { - response_len = spi_version_packet(spi_buf_tx); - next_rx_state = SPI_STATE_HEADER_NACK;; - } else if (spi_state == SPI_STATE_HEADER) { - checksum_valid = validate_checksum(spi_buf_rx, SPI_HEADER_SIZE); - if ((spi_buf_rx[0] == SPI_SYNC_BYTE) && checksum_valid) { - // response: ACK and start receiving data portion - spi_buf_tx[0] = SPI_HACK; - next_rx_state = SPI_STATE_HEADER_ACK; - response_len = 1U; - } else { - // response: NACK and reset state machine - print("- incorrect header sync or checksum "); hexdump(spi_buf_rx, SPI_HEADER_SIZE); - spi_buf_tx[0] = SPI_NACK; - next_rx_state = SPI_STATE_HEADER_NACK; - response_len = 1U; - } - } else if (spi_state == SPI_STATE_DATA_RX) { - // We got everything! Based on the endpoint specified, call the appropriate handler - bool response_ack = false; - checksum_valid = validate_checksum(&(spi_buf_rx[SPI_HEADER_SIZE]), spi_data_len_mosi + 1U); - if (checksum_valid) { - if (spi_endpoint == 0U) { - if (spi_data_len_mosi >= sizeof(ControlPacket_t)) { - ControlPacket_t ctrl; - (void)memcpy(&ctrl, &spi_buf_rx[SPI_HEADER_SIZE], sizeof(ControlPacket_t)); - response_len = comms_control_handler(&ctrl, &spi_buf_tx[3]); - response_ack = true; - } else { - print("SPI: insufficient data for control handler\n"); - } - } else if ((spi_endpoint == 1U) || (spi_endpoint == 0x81U)) { - if (spi_data_len_mosi == 0U) { - response_len = comms_can_read(&(spi_buf_tx[3]), spi_data_len_miso); - response_ack = true; - } else { - print("SPI: did not expect data for can_read\n"); - } - } else if (spi_endpoint == 2U) { - comms_endpoint2_write(&spi_buf_rx[SPI_HEADER_SIZE], spi_data_len_mosi); - response_ack = true; - } else if (spi_endpoint == 3U) { - if (spi_data_len_mosi > 0U) { - if (spi_can_tx_ready) { - spi_can_tx_ready = false; - comms_can_write(&spi_buf_rx[SPI_HEADER_SIZE], spi_data_len_mosi); - response_ack = true; - } else { - response_ack = false; - print("SPI: CAN NACK\n"); - } - } else { - print("SPI: did expect data for can_write\n"); - } - } else { - print("SPI: unexpected endpoint"); puth(spi_endpoint); print("\n"); - } - } else { - // Checksum was incorrect - response_ack = false; - print("- incorrect data checksum "); - puth4(spi_data_len_mosi); - print("\n"); - hexdump(spi_buf_rx, SPI_HEADER_SIZE); - hexdump(&(spi_buf_rx[SPI_HEADER_SIZE]), MIN(spi_data_len_mosi, 64)); - print("\n"); - } - - if (!response_ack) { - spi_buf_tx[0] = SPI_NACK; - next_rx_state = SPI_STATE_HEADER_NACK; - response_len = 1U; - } else { - // Setup response header - spi_buf_tx[0] = SPI_DACK; - spi_buf_tx[1] = response_len & 0xFFU; - spi_buf_tx[2] = (response_len >> 8) & 0xFFU; - - // Add checksum - uint8_t checksum = SPI_CHECKSUM_START; - for(uint16_t i = 0U; i < (response_len + 3U); i++) { - checksum ^= spi_buf_tx[i]; - } - spi_buf_tx[response_len + 3U] = checksum; - response_len += 4U; - - next_rx_state = SPI_STATE_DATA_TX; - } - } else { - print("SPI: RX unexpected state: "); puth(spi_state); print("\n"); - } - - // send out response - if (response_len == 0U) { - print("SPI: no response\n"); - spi_buf_tx[0] = SPI_NACK; - spi_state = SPI_STATE_HEADER_NACK; - response_len = 1U; - } - llspi_miso_dma(spi_buf_tx, response_len); - - spi_state = next_rx_state; - if (!checksum_valid && (spi_checksum_error_count < __UINT16_MAX__)) { - spi_checksum_error_count += 1U; - } -} - -void spi_tx_done(bool reset) { - if ((spi_state == SPI_STATE_HEADER_NACK) || reset) { - // Reset state - spi_state = SPI_STATE_HEADER; - llspi_mosi_dma(spi_buf_rx, SPI_HEADER_SIZE); - } else if (spi_state == SPI_STATE_HEADER_ACK) { - // ACK was sent, queue up the RX buf for the data + checksum - spi_state = SPI_STATE_DATA_RX; - llspi_mosi_dma(&spi_buf_rx[SPI_HEADER_SIZE], spi_data_len_mosi + 1U); - } else if (spi_state == SPI_STATE_DATA_TX) { - // Reset state - spi_state = SPI_STATE_HEADER; - llspi_mosi_dma(spi_buf_rx, SPI_HEADER_SIZE); - } else { - spi_state = SPI_STATE_HEADER; - llspi_mosi_dma(spi_buf_rx, SPI_HEADER_SIZE); - print("SPI: TX unexpected state: "); puth(spi_state); print("\n"); - } -} diff --git a/panda/board/drivers/timers.h b/panda/board/drivers/timers.h deleted file mode 100644 index d7f3f01..0000000 --- a/panda/board/drivers/timers.h +++ /dev/null @@ -1,31 +0,0 @@ -void timer_init(TIM_TypeDef *TIM, int psc) { - register_set(&(TIM->PSC), (psc-1), 0xFFFFU); - register_set(&(TIM->DIER), TIM_DIER_UIE, 0x5F5FU); - register_set(&(TIM->CR1), TIM_CR1_CEN, 0x3FU); - TIM->SR = 0; -} - -void microsecond_timer_init(void) { - MICROSECOND_TIMER->PSC = (APB1_TIMER_FREQ - 1U); - MICROSECOND_TIMER->CR1 = TIM_CR1_CEN; - MICROSECOND_TIMER->EGR = TIM_EGR_UG; -} - -uint32_t microsecond_timer_get(void) { - return MICROSECOND_TIMER->CNT; -} - -void interrupt_timer_init(void) { - enable_interrupt_timer(); - REGISTER_INTERRUPT(INTERRUPT_TIMER_IRQ, interrupt_timer_handler, 1, FAULT_INTERRUPT_RATE_INTERRUPTS) - register_set(&(INTERRUPT_TIMER->PSC), ((uint16_t)(15.25*APB1_TIMER_FREQ)-1U), 0xFFFFU); - register_set(&(INTERRUPT_TIMER->DIER), TIM_DIER_UIE, 0x5F5FU); - register_set(&(INTERRUPT_TIMER->CR1), TIM_CR1_CEN, 0x3FU); - INTERRUPT_TIMER->SR = 0; - NVIC_EnableIRQ(INTERRUPT_TIMER_IRQ); -} - -void tick_timer_init(void) { - timer_init(TICK_TIMER, (uint16_t)((15.25*APB2_TIMER_FREQ)/8U)); - NVIC_EnableIRQ(TICK_TIMER_IRQ); -} diff --git a/panda/board/drivers/uart.h b/panda/board/drivers/uart.h deleted file mode 100644 index 01d8c2a..0000000 --- a/panda/board/drivers/uart.h +++ /dev/null @@ -1,196 +0,0 @@ -// IRQs: USART2, USART3, UART5 - -// ***************************** Definitions ***************************** -#define FIFO_SIZE_INT 0x400U - -typedef struct uart_ring { - volatile uint16_t w_ptr_tx; - volatile uint16_t r_ptr_tx; - uint8_t *elems_tx; - uint32_t tx_fifo_size; - volatile uint16_t w_ptr_rx; - volatile uint16_t r_ptr_rx; - uint8_t *elems_rx; - uint32_t rx_fifo_size; - USART_TypeDef *uart; - void (*callback)(struct uart_ring*); - bool overwrite; -} uart_ring; - -#define UART_BUFFER(x, size_rx, size_tx, uart_ptr, callback_ptr, overwrite_mode) \ - uint8_t elems_rx_##x[size_rx]; \ - uint8_t elems_tx_##x[size_tx]; \ - uart_ring uart_ring_##x = { \ - .w_ptr_tx = 0, \ - .r_ptr_tx = 0, \ - .elems_tx = ((uint8_t *)&(elems_tx_##x)), \ - .tx_fifo_size = (size_tx), \ - .w_ptr_rx = 0, \ - .r_ptr_rx = 0, \ - .elems_rx = ((uint8_t *)&(elems_rx_##x)), \ - .rx_fifo_size = (size_rx), \ - .uart = (uart_ptr), \ - .callback = (callback_ptr), \ - .overwrite = (overwrite_mode) \ - }; - -// ***************************** Function prototypes ***************************** -void debug_ring_callback(uart_ring *ring); -void uart_tx_ring(uart_ring *q); -void uart_send_break(uart_ring *u); - -// ******************************** UART buffers ******************************** - -// debug = USART2 -UART_BUFFER(debug, FIFO_SIZE_INT, FIFO_SIZE_INT, USART2, debug_ring_callback, true) - -// SOM debug = UART7 -#ifdef STM32H7 - UART_BUFFER(som_debug, FIFO_SIZE_INT, FIFO_SIZE_INT, UART7, NULL, true) -#else - // UART7 is not available on F4 - UART_BUFFER(som_debug, 1U, 1U, NULL, NULL, true) -#endif - -uart_ring *get_ring_by_number(int a) { - uart_ring *ring = NULL; - switch(a) { - case 0: - ring = &uart_ring_debug; - break; - case 4: - ring = &uart_ring_som_debug; - break; - default: - ring = NULL; - break; - } - return ring; -} - -// ************************* Low-level buffer functions ************************* -bool get_char(uart_ring *q, char *elem) { - bool ret = false; - - ENTER_CRITICAL(); - if (q->w_ptr_rx != q->r_ptr_rx) { - if (elem != NULL) *elem = q->elems_rx[q->r_ptr_rx]; - q->r_ptr_rx = (q->r_ptr_rx + 1U) % q->rx_fifo_size; - ret = true; - } - EXIT_CRITICAL(); - - return ret; -} - -bool injectc(uart_ring *q, char elem) { - int ret = false; - uint16_t next_w_ptr; - - ENTER_CRITICAL(); - next_w_ptr = (q->w_ptr_rx + 1U) % q->rx_fifo_size; - - if ((next_w_ptr == q->r_ptr_rx) && q->overwrite) { - // overwrite mode: drop oldest byte - q->r_ptr_rx = (q->r_ptr_rx + 1U) % q->rx_fifo_size; - } - - if (next_w_ptr != q->r_ptr_rx) { - q->elems_rx[q->w_ptr_rx] = elem; - q->w_ptr_rx = next_w_ptr; - ret = true; - } - EXIT_CRITICAL(); - - return ret; -} - -bool put_char(uart_ring *q, char elem) { - bool ret = false; - uint16_t next_w_ptr; - - ENTER_CRITICAL(); - next_w_ptr = (q->w_ptr_tx + 1U) % q->tx_fifo_size; - - if ((next_w_ptr == q->r_ptr_tx) && q->overwrite) { - // overwrite mode: drop oldest byte - q->r_ptr_tx = (q->r_ptr_tx + 1U) % q->tx_fifo_size; - } - - if (next_w_ptr != q->r_ptr_tx) { - q->elems_tx[q->w_ptr_tx] = elem; - q->w_ptr_tx = next_w_ptr; - ret = true; - } - EXIT_CRITICAL(); - - uart_tx_ring(q); - - return ret; -} - -void clear_uart_buff(uart_ring *q) { - ENTER_CRITICAL(); - q->w_ptr_tx = 0; - q->r_ptr_tx = 0; - q->w_ptr_rx = 0; - q->r_ptr_rx = 0; - EXIT_CRITICAL(); -} - -// ************************ High-level debug functions ********************** -void putch(const char a) { - // misra-c2012-17.7: serial debug function, ok to ignore output - (void)injectc(&uart_ring_debug, a); -} - -void print(const char *a) { - for (const char *in = a; *in; in++) { - if (*in == '\n') putch('\r'); - putch(*in); - } -} - -void putui(uint32_t i) { - uint32_t i_copy = i; - char str[11]; - uint8_t idx = 10; - str[idx] = '\0'; - idx--; - do { - str[idx] = (i_copy % 10U) + 0x30U; - idx--; - i_copy /= 10; - } while (i_copy != 0U); - print(&str[idx + 1U]); -} - -void puthx(uint32_t i, uint8_t len) { - const char c[] = "0123456789abcdef"; - for (int pos = ((int)len * 4) - 4; pos > -4; pos -= 4) { - putch(c[(i >> (unsigned int)(pos)) & 0xFU]); - } -} - -void puth(unsigned int i) { - puthx(i, 8U); -} - -void puth2(unsigned int i) { - puthx(i, 2U); -} - -void puth4(unsigned int i) { - puthx(i, 4U); -} - -void hexdump(const void *a, int l) { - if (a != NULL) { - for (int i=0; i < l; i++) { - if ((i != 0) && ((i & 0xf) == 0)) print("\n"); - puth2(((const unsigned char*)a)[i]); - print(" "); - } - } - print("\n"); -} diff --git a/panda/board/drivers/usb.h b/panda/board/drivers/usb.h deleted file mode 100644 index 1872dd5..0000000 --- a/panda/board/drivers/usb.h +++ /dev/null @@ -1,943 +0,0 @@ -// IRQs: OTG_FS - -typedef union { - uint16_t w; - struct BW { - uint8_t msb; - uint8_t lsb; - } - bw; -} -uint16_t_uint8_t; - -typedef union _USB_Setup { - uint32_t d8[2]; - struct _SetupPkt_Struc - { - uint8_t bmRequestType; - uint8_t bRequest; - uint16_t_uint8_t wValue; - uint16_t_uint8_t wIndex; - uint16_t_uint8_t wLength; - } b; -} -USB_Setup_TypeDef; - -bool usb_enumerated = false; -uint16_t usb_last_frame_num = 0U; - -void usb_init(void); -void refresh_can_tx_slots_available(void); - -// **** supporting defines **** - -#define USB_REQ_GET_STATUS 0x00 -#define USB_REQ_CLEAR_FEATURE 0x01 -#define USB_REQ_SET_FEATURE 0x03 -#define USB_REQ_SET_ADDRESS 0x05 -#define USB_REQ_GET_DESCRIPTOR 0x06 -#define USB_REQ_SET_DESCRIPTOR 0x07 -#define USB_REQ_GET_CONFIGURATION 0x08 -#define USB_REQ_SET_CONFIGURATION 0x09 -#define USB_REQ_GET_INTERFACE 0x0A -#define USB_REQ_SET_INTERFACE 0x0B -#define USB_REQ_SYNCH_FRAME 0x0C - -#define USB_DESC_TYPE_DEVICE 0x01 -#define USB_DESC_TYPE_CONFIGURATION 0x02 -#define USB_DESC_TYPE_STRING 0x03 -#define USB_DESC_TYPE_INTERFACE 0x04 -#define USB_DESC_TYPE_ENDPOINT 0x05 -#define USB_DESC_TYPE_DEVICE_QUALIFIER 0x06 -#define USB_DESC_TYPE_OTHER_SPEED_CONFIGURATION 0x07 -#define USB_DESC_TYPE_BINARY_OBJECT_STORE 0x0f - -// offsets for configuration strings -#define STRING_OFFSET_LANGID 0x00 -#define STRING_OFFSET_IMANUFACTURER 0x01 -#define STRING_OFFSET_IPRODUCT 0x02 -#define STRING_OFFSET_ISERIAL 0x03 -#define STRING_OFFSET_ICONFIGURATION 0x04 -#define STRING_OFFSET_IINTERFACE 0x05 - -// WebUSB requests -#define WEBUSB_REQ_GET_URL 0x02 - -// WebUSB types -#define WEBUSB_DESC_TYPE_URL 0x03 -#define WEBUSB_URL_SCHEME_HTTPS 0x01 -#define WEBUSB_URL_SCHEME_HTTP 0x00 - -// WinUSB requests -#define WINUSB_REQ_GET_COMPATID_DESCRIPTOR 0x04 -#define WINUSB_REQ_GET_EXT_PROPS_OS 0x05 -#define WINUSB_REQ_GET_DESCRIPTOR 0x07 - -#define STS_GOUT_NAK 1 -#define STS_DATA_UPDT 2 -#define STS_XFER_COMP 3 -#define STS_SETUP_COMP 4 -#define STS_SETUP_UPDT 6 - -uint8_t response[USBPACKET_MAX_SIZE]; - -// for the repeating interfaces -#define DSCR_INTERFACE_LEN 9 -#define DSCR_ENDPOINT_LEN 7 -#define DSCR_CONFIG_LEN 9 -#define DSCR_DEVICE_LEN 18 - -// endpoint types -#define ENDPOINT_TYPE_CONTROL 0 -#define ENDPOINT_TYPE_ISO 1 -#define ENDPOINT_TYPE_BULK 2 -#define ENDPOINT_TYPE_INT 3 - -// These are arbitrary values used in bRequest -#define MS_VENDOR_CODE 0x20 -#define WEBUSB_VENDOR_CODE 0x30 - -// BOS constants -#define BINARY_OBJECT_STORE_DESCRIPTOR_LENGTH 0x05 -#define BINARY_OBJECT_STORE_DESCRIPTOR 0x0F -#define WINUSB_PLATFORM_DESCRIPTOR_LENGTH 0x9E - -// Convert machine byte order to USB byte order -#define TOUSBORDER(num)\ - ((num) & 0xFFU), (((uint16_t)(num) >> 8) & 0xFFU) - -// take in string length and return the first 2 bytes of a string descriptor -#define STRING_DESCRIPTOR_HEADER(size)\ - (((((size) * 2) + 2) & 0xFF) | 0x0300) - -uint8_t device_desc[] = { - DSCR_DEVICE_LEN, USB_DESC_TYPE_DEVICE, //Length, Type - 0x10, 0x02, // bcdUSB max version of USB supported (2.1) - 0xFF, 0xFF, 0xFF, 0x40, // Class, Subclass, Protocol, Max Packet Size - TOUSBORDER(USB_VID), // idVendor - TOUSBORDER(USB_PID), // idProduct - 0x00, 0x00, // bcdDevice - 0x01, 0x02, // Manufacturer, Product - 0x03, 0x01 // Serial Number, Num Configurations -}; - -uint8_t device_qualifier[] = { - 0x0a, USB_DESC_TYPE_DEVICE_QUALIFIER, //Length, Type - 0x10, 0x02, // bcdUSB max version of USB supported (2.1) - 0xFF, 0xFF, 0xFF, 0x40, // bDeviceClass, bDeviceSubClass, bDeviceProtocol, bMaxPacketSize0 - 0x01, 0x00 // bNumConfigurations, bReserved -}; - -#define ENDPOINT_RCV 0x80 -#define ENDPOINT_SND 0x00 - -uint8_t configuration_desc[] = { - DSCR_CONFIG_LEN, USB_DESC_TYPE_CONFIGURATION, // Length, Type, - TOUSBORDER(0x0045U), // Total Len (uint16) - 0x01, 0x01, STRING_OFFSET_ICONFIGURATION, // Num Interface, Config Value, Configuration - 0xc0, 0x32, // Attributes, Max Power - // interface 0 ALT 0 - DSCR_INTERFACE_LEN, USB_DESC_TYPE_INTERFACE, // Length, Type - 0x00, 0x00, 0x03, // Index, Alt Index idx, Endpoint count - 0XFF, 0xFF, 0xFF, // Class, Subclass, Protocol - 0x00, // Interface - // endpoint 1, read CAN - DSCR_ENDPOINT_LEN, USB_DESC_TYPE_ENDPOINT, // Length, Type - ENDPOINT_RCV | 1, ENDPOINT_TYPE_BULK, // Endpoint Num/Direction, Type - TOUSBORDER(0x0040U), // Max Packet (0x0040) - 0x00, // Polling Interval (NA) - // endpoint 2, send serial - DSCR_ENDPOINT_LEN, USB_DESC_TYPE_ENDPOINT, // Length, Type - ENDPOINT_SND | 2, ENDPOINT_TYPE_BULK, // Endpoint Num/Direction, Type - TOUSBORDER(0x0040U), // Max Packet (0x0040) - 0x00, // Polling Interval - // endpoint 3, send CAN - DSCR_ENDPOINT_LEN, USB_DESC_TYPE_ENDPOINT, // Length, Type - ENDPOINT_SND | 3, ENDPOINT_TYPE_BULK, // Endpoint Num/Direction, Type - TOUSBORDER(0x0040U), // Max Packet (0x0040) - 0x00, // Polling Interval - // interface 0 ALT 1 - DSCR_INTERFACE_LEN, USB_DESC_TYPE_INTERFACE, // Length, Type - 0x00, 0x01, 0x03, // Index, Alt Index idx, Endpoint count - 0XFF, 0xFF, 0xFF, // Class, Subclass, Protocol - 0x00, // Interface - // endpoint 1, read CAN - DSCR_ENDPOINT_LEN, USB_DESC_TYPE_ENDPOINT, // Length, Type - ENDPOINT_RCV | 1, ENDPOINT_TYPE_INT, // Endpoint Num/Direction, Type - TOUSBORDER(0x0040U), // Max Packet (0x0040) - 0x05, // Polling Interval (5 frames) - // endpoint 2, send serial - DSCR_ENDPOINT_LEN, USB_DESC_TYPE_ENDPOINT, // Length, Type - ENDPOINT_SND | 2, ENDPOINT_TYPE_BULK, // Endpoint Num/Direction, Type - TOUSBORDER(0x0040U), // Max Packet (0x0040) - 0x00, // Polling Interval - // endpoint 3, send CAN - DSCR_ENDPOINT_LEN, USB_DESC_TYPE_ENDPOINT, // Length, Type - ENDPOINT_SND | 3, ENDPOINT_TYPE_BULK, // Endpoint Num/Direction, Type - TOUSBORDER(0x0040U), // Max Packet (0x0040) - 0x00, // Polling Interval -}; - -// STRING_DESCRIPTOR_HEADER is for uint16 string descriptors -// it takes in a string length, which is bytes/2 because unicode -uint16_t string_language_desc[] = { - STRING_DESCRIPTOR_HEADER(1), - 0x0409 // american english -}; - -// these strings are all uint16's so that we don't need to spam ,0 after every character -uint16_t string_manufacturer_desc[] = { - STRING_DESCRIPTOR_HEADER(8), - 'c', 'o', 'm', 'm', 'a', '.', 'a', 'i' -}; - -uint16_t string_product_desc[] = { - STRING_DESCRIPTOR_HEADER(5), - 'p', 'a', 'n', 'd', 'a' -}; - -// default serial number when we're not a panda -uint16_t string_serial_desc[] = { - STRING_DESCRIPTOR_HEADER(4), - 'n', 'o', 'n', 'e' -}; - -// a string containing the default configuration index -uint16_t string_configuration_desc[] = { - STRING_DESCRIPTOR_HEADER(2), - '0', '1' // "01" -}; - -// WCID (auto install WinUSB driver) -// https://github.com/pbatard/libwdi/wiki/WCID-Devices -// https://docs.microsoft.com/en-us/windows-hardware/drivers/usbcon/winusb-installation#automatic-installation-of--winusb-without-an-inf-file -// WinUSB 1.0 descriptors, this is mostly used by Windows XP -uint8_t string_238_desc[] = { - 0x12, USB_DESC_TYPE_STRING, // bLength, bDescriptorType - 'M',0, 'S',0, 'F',0, 'T',0, '1',0, '0',0, '0',0, // qwSignature (MSFT100) - MS_VENDOR_CODE, 0x00 // bMS_VendorCode, bPad -}; -uint8_t winusb_ext_compatid_os_desc[] = { - 0x28, 0x00, 0x00, 0x00, // dwLength - 0x00, 0x01, // bcdVersion - 0x04, 0x00, // wIndex - 0x01, // bCount - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Reserved - 0x00, // bFirstInterfaceNumber - 0x00, // Reserved - 'W', 'I', 'N', 'U', 'S', 'B', 0x00, 0x00, // compatible ID (WINUSB) - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // subcompatible ID (none) - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 // Reserved -}; -uint8_t winusb_ext_prop_os_desc[] = { - 0x8e, 0x00, 0x00, 0x00, // dwLength - 0x00, 0x01, // bcdVersion - 0x05, 0x00, // wIndex - 0x01, 0x00, // wCount - // first property - 0x84, 0x00, 0x00, 0x00, // dwSize - 0x01, 0x00, 0x00, 0x00, // dwPropertyDataType - 0x28, 0x00, // wPropertyNameLength - 'D',0, 'e',0, 'v',0, 'i',0, 'c',0, 'e',0, 'I',0, 'n',0, 't',0, 'e',0, 'r',0, 'f',0, 'a',0, 'c',0, 'e',0, 'G',0, 'U',0, 'I',0, 'D',0, 0, 0, // bPropertyName (DeviceInterfaceGUID) - 0x4e, 0x00, 0x00, 0x00, // dwPropertyDataLength - '{',0, 'c',0, 'c',0, 'e',0, '5',0, '2',0, '9',0, '1',0, 'c',0, '-',0, 'a',0, '6',0, '9',0, 'f',0, '-',0, '4',0 ,'9',0 ,'9',0 ,'5',0 ,'-',0, 'a',0, '4',0, 'c',0, '2',0, '-',0, '2',0, 'a',0, 'e',0, '5',0, '7',0, 'a',0, '5',0, '1',0, 'a',0, 'd',0, 'e',0, '9',0, '}',0, 0, 0, // bPropertyData ({CCE5291C-A69F-4995-A4C2-2AE57A51ADE9}) -}; - -/* -Binary Object Store descriptor used to expose WebUSB (and more WinUSB) metadata -comments are from the wicg spec -References used: - https://wicg.github.io/webusb/#webusb-platform-capability-descriptor - https://github.com/sowbug/weblight/blob/192ad7a0e903542e2aa28c607d98254a12a6399d/firmware/webusb.c - https://os.mbed.com/users/larsgk/code/USBDevice_WebUSB/file/1d8a6665d607/WebUSBDevice/ - -*/ -uint8_t binary_object_store_desc[] = { - // BOS header - BINARY_OBJECT_STORE_DESCRIPTOR_LENGTH, // bLength, this is only the length of the header - BINARY_OBJECT_STORE_DESCRIPTOR, // bDescriptorType - 0x39, 0x00, // wTotalLength (LSB, MSB) - 0x02, // bNumDeviceCaps (WebUSB + WinUSB) - - // ------------------------------------------------- - // WebUSB descriptor - // header - 0x18, // bLength, Size of this descriptor. Must be set to 24. - 0x10, // bDescriptorType, DEVICE CAPABILITY descriptor - 0x05, // bDevCapabilityType, PLATFORM capability - 0x00, // bReserved, This field is reserved and shall be set to zero. - - // PlatformCapabilityUUID, Must be set to {3408b638-09a9-47a0-8bfd-a0768815b665}. - 0x38, 0xB6, 0x08, 0x34, - 0xA9, 0x09, 0xA0, 0x47, - 0x8B, 0xFD, 0xA0, 0x76, - 0x88, 0x15, 0xB6, 0x65, - // - - 0x00, 0x01, // bcdVersion, Protocol version supported. Must be set to 0x0100. - WEBUSB_VENDOR_CODE, // bVendorCode, bRequest value used for issuing WebUSB requests. - // there used to be a concept of "allowed origins", but it was removed from the spec - // it was intended to be a security feature, but then the entire security model relies on domain ownership - // https://github.com/WICG/webusb/issues/49 - // other implementations use various other indexed to leverate this no-longer-valid feature. we wont. - // the spec says we *must* reply to index 0x03 with the url, so we'll hint that that's the right index - 0x03, // iLandingPage, URL descriptor index of the device’s landing page. - - // ------------------------------------------------- - // WinUSB descriptor - // header - 0x1C, // Descriptor size (28 bytes) - 0x10, // Descriptor type (Device Capability) - 0x05, // Capability type (Platform) - 0x00, // Reserved - - // MS OS 2.0 Platform Capability ID (D8DD60DF-4589-4CC7-9CD2-659D9E648A9F) - // Indicates the device supports the Microsoft OS 2.0 descriptor - 0xDF, 0x60, 0xDD, 0xD8, - 0x89, 0x45, 0xC7, 0x4C, - 0x9C, 0xD2, 0x65, 0x9D, - 0x9E, 0x64, 0x8A, 0x9F, - - 0x00, 0x00, 0x03, 0x06, // Windows version, currently set to 8.1 (0x06030000) - - WINUSB_PLATFORM_DESCRIPTOR_LENGTH, 0x00, // MS OS 2.0 descriptor size (word) - MS_VENDOR_CODE, 0x00 // vendor code, no alternate enumeration -}; - -uint8_t webusb_url_descriptor[] = { - 0x14, /* bLength */ - WEBUSB_DESC_TYPE_URL, // bDescriptorType - WEBUSB_URL_SCHEME_HTTPS, // bScheme - 'u', 's', 'b', 'p', 'a', 'n', 'd', 'a', '.', 'c', 'o', 'm', 'm', 'a', '.', 'a', 'i' -}; - -// WinUSB 2.0 descriptor. This is what modern systems use -// https://github.com/sowbug/weblight/blob/192ad7a0e903542e2aa28c607d98254a12a6399d/firmware/webusb.c -// http://janaxelson.com/files/ms_os_20_descriptors.c -// https://books.google.com/books?id=pkefBgAAQBAJ&pg=PA353&lpg=PA353 -uint8_t winusb_20_desc[WINUSB_PLATFORM_DESCRIPTOR_LENGTH] = { - // Microsoft OS 2.0 descriptor set header (table 10) - 0x0A, 0x00, // Descriptor size (10 bytes) - 0x00, 0x00, // MS OS 2.0 descriptor set header - - 0x00, 0x00, 0x03, 0x06, // Windows version (8.1) (0x06030000) - WINUSB_PLATFORM_DESCRIPTOR_LENGTH, 0x00, // Total size of MS OS 2.0 descriptor set - - // Microsoft OS 2.0 compatible ID descriptor - 0x14, 0x00, // Descriptor size (20 bytes) - 0x03, 0x00, // MS OS 2.0 compatible ID descriptor - 'W', 'I', 'N', 'U', 'S', 'B', 0x00, 0x00, // compatible ID (WINUSB) - 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, // Sub-compatible ID - - // Registry property descriptor - 0x80, 0x00, // Descriptor size (130 bytes) - 0x04, 0x00, // Registry Property descriptor - 0x01, 0x00, // Strings are null-terminated Unicode - 0x28, 0x00, // Size of Property Name (40 bytes) "DeviceInterfaceGUID" - - // bPropertyName (DeviceInterfaceGUID) - 'D', 0x00, 'e', 0x00, 'v', 0x00, 'i', 0x00, 'c', 0x00, 'e', 0x00, 'I', 0x00, 'n', 0x00, - 't', 0x00, 'e', 0x00, 'r', 0x00, 'f', 0x00, 'a', 0x00, 'c', 0x00, 'e', 0x00, 'G', 0x00, - 'U', 0x00, 'I', 0x00, 'D', 0x00, 0x00, 0x00, - - 0x4E, 0x00, // Size of Property Data (78 bytes) - - // Vendor-defined property data: {CCE5291C-A69F-4995-A4C2-2AE57A51ADE9} - '{', 0x00, 'c', 0x00, 'c', 0x00, 'e', 0x00, '5', 0x00, '2', 0x00, '9', 0x00, '1', 0x00, // 16 - 'c', 0x00, '-', 0x00, 'a', 0x00, '6', 0x00, '9', 0x00, 'f', 0x00, '-', 0x00, '4', 0x00, // 32 - '9', 0x00, '9', 0x00, '5', 0x00, '-', 0x00, 'a', 0x00, '4', 0x00, 'c', 0x00, '2', 0x00, // 48 - '-', 0x00, '2', 0x00, 'a', 0x00, 'e', 0x00, '5', 0x00, '7', 0x00, 'a', 0x00, '5', 0x00, // 64 - '1', 0x00, 'a', 0x00, 'd', 0x00, 'e', 0x00, '9', 0x00, '}', 0x00, 0x00, 0x00 // 78 bytes -}; - -// current packet -USB_Setup_TypeDef setup; -uint8_t usbdata[0x100] __attribute__((aligned(4))); -uint8_t* ep0_txdata = NULL; -uint16_t ep0_txlen = 0; -bool outep3_processing = false; - -// Store the current interface alt setting. -int current_int0_alt_setting = 0; - -// packet read and write - -void *USB_ReadPacket(void *dest, uint16_t len) { - uint32_t *dest_copy = (uint32_t *)dest; - uint32_t count32b = (len + 3U) / 4U; - - for (uint32_t i = 0; i < count32b; i++) { - *dest_copy = USBx_DFIFO(0); - dest_copy++; - } - return ((void *)dest_copy); -} - -void USB_WritePacket(const void *src, uint16_t len, uint32_t ep) { - #ifdef DEBUG_USB - print("writing "); - hexdump(src, len); - #endif - - uint32_t numpacket = (len + (USBPACKET_MAX_SIZE - 1U)) / USBPACKET_MAX_SIZE; - uint32_t count32b = 0; - count32b = (len + 3U) / 4U; - - // TODO: revisit this - USBx_INEP(ep)->DIEPTSIZ = ((numpacket << 19) & USB_OTG_DIEPTSIZ_PKTCNT) | - (len & USB_OTG_DIEPTSIZ_XFRSIZ); - USBx_INEP(ep)->DIEPCTL |= (USB_OTG_DIEPCTL_CNAK | USB_OTG_DIEPCTL_EPENA); - - // load the FIFO - if (src != NULL) { - const uint32_t *src_copy = (const uint32_t *)src; - for (uint32_t i = 0; i < count32b; i++) { - USBx_DFIFO(ep) = *src_copy; - src_copy++; - } - } -} - -// IN EP 0 TX FIFO has a max size of 127 bytes (much smaller than the rest) -// so use TX FIFO empty interrupt to send larger amounts of data -void USB_WritePacket_EP0(uint8_t *src, uint16_t len) { - #ifdef DEBUG_USB - print("writing "); - hexdump(src, len); - #endif - - uint16_t wplen = MIN(len, 0x40); - USB_WritePacket(src, wplen, 0); - - if (wplen < len) { - ep0_txdata = &src[wplen]; - ep0_txlen = len - wplen; - USBx_DEVICE->DIEPEMPMSK |= 1; - } else { - USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; - } -} - -void usb_reset(void) { - // unmask endpoint interrupts, so many sets - USBx_DEVICE->DAINT = 0xFFFFFFFFU; - USBx_DEVICE->DAINTMSK = 0xFFFFFFFFU; - //USBx_DEVICE->DOEPMSK = (USB_OTG_DOEPMSK_STUPM | USB_OTG_DOEPMSK_XFRCM | USB_OTG_DOEPMSK_EPDM); - //USBx_DEVICE->DIEPMSK = (USB_OTG_DIEPMSK_TOM | USB_OTG_DIEPMSK_XFRCM | USB_OTG_DIEPMSK_EPDM | USB_OTG_DIEPMSK_ITTXFEMSK); - //USBx_DEVICE->DIEPMSK = (USB_OTG_DIEPMSK_TOM | USB_OTG_DIEPMSK_XFRCM | USB_OTG_DIEPMSK_EPDM); - - // all interrupts for debugging - USBx_DEVICE->DIEPMSK = 0xFFFFFFFFU; - USBx_DEVICE->DOEPMSK = 0xFFFFFFFFU; - - // clear interrupts - USBx_INEP(0)->DIEPINT = 0xFF; - USBx_OUTEP(0)->DOEPINT = 0xFF; - - // unset the address - USBx_DEVICE->DCFG &= ~USB_OTG_DCFG_DAD; - - // set up USB FIFOs - // RX start address is fixed to 0 - USBx->GRXFSIZ = 0x40; - - // 0x100 to offset past GRXFSIZ - USBx->DIEPTXF0_HNPTXFSIZ = (0x40UL << 16) | 0x40U; - - // EP1, massive - USBx->DIEPTXF[0] = (0x40UL << 16) | 0x80U; - - // flush TX fifo - USBx->GRSTCTL = USB_OTG_GRSTCTL_TXFFLSH | USB_OTG_GRSTCTL_TXFNUM_4; - while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_TXFFLSH) == USB_OTG_GRSTCTL_TXFFLSH); - // flush RX FIFO - USBx->GRSTCTL = USB_OTG_GRSTCTL_RXFFLSH; - while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_RXFFLSH) == USB_OTG_GRSTCTL_RXFFLSH); - - // no global NAK - USBx_DEVICE->DCTL |= USB_OTG_DCTL_CGINAK; - - // ready to receive setup packets - USBx_OUTEP(0)->DOEPTSIZ = USB_OTG_DOEPTSIZ_STUPCNT | (USB_OTG_DOEPTSIZ_PKTCNT & (1UL << 19)) | (3U << 3); -} - -char to_hex_char(uint8_t a) { - char ret; - if (a < 10U) { - ret = '0' + a; - } else { - ret = 'a' + (a - 10U); - } - return ret; -} - -void usb_tick(void) { - uint16_t current_frame_num = (USBx_DEVICE->DSTS & USB_OTG_DSTS_FNSOF_Msk) >> USB_OTG_DSTS_FNSOF_Pos; - usb_enumerated = (current_frame_num != usb_last_frame_num); - usb_last_frame_num = current_frame_num; -} - -void usb_setup(void) { - int resp_len; - ControlPacket_t control_req; - - // setup packet is ready - switch (setup.b.bRequest) { - case USB_REQ_SET_CONFIGURATION: - // enable other endpoints, has to be here? - USBx_INEP(1)->DIEPCTL = (0x40U & USB_OTG_DIEPCTL_MPSIZ) | (2UL << 18) | (1UL << 22) | - USB_OTG_DIEPCTL_SD0PID_SEVNFRM | USB_OTG_DIEPCTL_USBAEP; - USBx_INEP(1)->DIEPINT = 0xFF; - - USBx_OUTEP(2)->DOEPTSIZ = (1UL << 19) | 0x40U; - USBx_OUTEP(2)->DOEPCTL = (0x40U & USB_OTG_DOEPCTL_MPSIZ) | (2UL << 18) | - USB_OTG_DOEPCTL_SD0PID_SEVNFRM | USB_OTG_DOEPCTL_USBAEP; - USBx_OUTEP(2)->DOEPINT = 0xFF; - - USBx_OUTEP(3)->DOEPTSIZ = (32UL << 19) | 0x800U; - USBx_OUTEP(3)->DOEPCTL = (0x40U & USB_OTG_DOEPCTL_MPSIZ) | (2UL << 18) | - USB_OTG_DOEPCTL_SD0PID_SEVNFRM | USB_OTG_DOEPCTL_USBAEP; - USBx_OUTEP(3)->DOEPINT = 0xFF; - - // mark ready to receive - USBx_OUTEP(2)->DOEPCTL |= USB_OTG_DOEPCTL_EPENA | USB_OTG_DOEPCTL_CNAK; - USBx_OUTEP(3)->DOEPCTL |= USB_OTG_DOEPCTL_EPENA | USB_OTG_DOEPCTL_CNAK; - - USB_WritePacket(0, 0, 0); - USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; - break; - case USB_REQ_SET_ADDRESS: - // set now? - USBx_DEVICE->DCFG |= ((setup.b.wValue.w & 0x7fU) << 4); - - #ifdef DEBUG_USB - print(" set address\n"); - #endif - - USB_WritePacket(0, 0, 0); - USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; - - break; - case USB_REQ_GET_DESCRIPTOR: - switch (setup.b.wValue.bw.lsb) { - case USB_DESC_TYPE_DEVICE: - //print(" writing device descriptor\n"); - - // set bcdDevice to hardware type - device_desc[13] = hw_type; - // setup transfer - USB_WritePacket(device_desc, MIN(sizeof(device_desc), setup.b.wLength.w), 0); - USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; - - //print("D"); - break; - case USB_DESC_TYPE_CONFIGURATION: - USB_WritePacket(configuration_desc, MIN(sizeof(configuration_desc), setup.b.wLength.w), 0); - USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; - break; - case USB_DESC_TYPE_DEVICE_QUALIFIER: - USB_WritePacket(device_qualifier, MIN(sizeof(device_qualifier), setup.b.wLength.w), 0); - USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; - break; - case USB_DESC_TYPE_STRING: - switch (setup.b.wValue.bw.msb) { - case STRING_OFFSET_LANGID: - USB_WritePacket((uint8_t*)string_language_desc, MIN(sizeof(string_language_desc), setup.b.wLength.w), 0); - break; - case STRING_OFFSET_IMANUFACTURER: - USB_WritePacket((uint8_t*)string_manufacturer_desc, MIN(sizeof(string_manufacturer_desc), setup.b.wLength.w), 0); - break; - case STRING_OFFSET_IPRODUCT: - USB_WritePacket((uint8_t*)string_product_desc, MIN(sizeof(string_product_desc), setup.b.wLength.w), 0); - break; - case STRING_OFFSET_ISERIAL: - #ifdef UID_BASE - response[0] = 0x02 + (12 * 4); - response[1] = 0x03; - - // 96 bits = 12 bytes - for (int i = 0; i < 12; i++){ - uint8_t cc = ((uint8_t *)UID_BASE)[i]; - response[2 + (i * 4)] = to_hex_char((cc >> 4) & 0xFU); - response[2 + (i * 4) + 1] = '\0'; - response[2 + (i * 4) + 2] = to_hex_char((cc >> 0) & 0xFU); - response[2 + (i * 4) + 3] = '\0'; - } - - USB_WritePacket(response, MIN(response[0], setup.b.wLength.w), 0); - #else - USB_WritePacket((const uint8_t *)string_serial_desc, MIN(sizeof(string_serial_desc), setup.b.wLength.w), 0); - #endif - break; - case STRING_OFFSET_ICONFIGURATION: - USB_WritePacket((uint8_t*)string_configuration_desc, MIN(sizeof(string_configuration_desc), setup.b.wLength.w), 0); - break; - case 238: - USB_WritePacket((uint8_t*)string_238_desc, MIN(sizeof(string_238_desc), setup.b.wLength.w), 0); - break; - default: - // nothing - USB_WritePacket(0, 0, 0); - break; - } - USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; - break; - case USB_DESC_TYPE_BINARY_OBJECT_STORE: - USB_WritePacket(binary_object_store_desc, MIN(sizeof(binary_object_store_desc), setup.b.wLength.w), 0); - USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; - break; - default: - // nothing here? - USB_WritePacket(0, 0, 0); - USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; - break; - } - break; - case USB_REQ_GET_STATUS: - // empty response? - response[0] = 0; - response[1] = 0; - USB_WritePacket((void*)&response, 2, 0); - USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; - break; - case USB_REQ_SET_INTERFACE: - // Store the alt setting number for IN EP behavior. - current_int0_alt_setting = setup.b.wValue.w; - USB_WritePacket(0, 0, 0); - USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; - break; - case WEBUSB_VENDOR_CODE: - switch (setup.b.wIndex.w) { - case WEBUSB_REQ_GET_URL: - USB_WritePacket(webusb_url_descriptor, MIN(sizeof(webusb_url_descriptor), setup.b.wLength.w), 0); - USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; - break; - default: - // probably asking for allowed origins, which was removed from the spec - USB_WritePacket(0, 0, 0); - USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; - break; - } - break; - case MS_VENDOR_CODE: - switch (setup.b.wIndex.w) { - // winusb 2.0 descriptor from BOS - case WINUSB_REQ_GET_DESCRIPTOR: - USB_WritePacket_EP0((uint8_t*)winusb_20_desc, MIN(sizeof(winusb_20_desc), setup.b.wLength.w)); - break; - // Extended Compat ID OS Descriptor - case WINUSB_REQ_GET_COMPATID_DESCRIPTOR: - USB_WritePacket_EP0((uint8_t*)winusb_ext_compatid_os_desc, MIN(sizeof(winusb_ext_compatid_os_desc), setup.b.wLength.w)); - break; - // Extended Properties OS Descriptor - case WINUSB_REQ_GET_EXT_PROPS_OS: - USB_WritePacket_EP0((uint8_t*)winusb_ext_prop_os_desc, MIN(sizeof(winusb_ext_prop_os_desc), setup.b.wLength.w)); - break; - default: - USB_WritePacket_EP0(0, 0); - } - break; - default: - control_req.request = setup.b.bRequest; - control_req.param1 = setup.b.wValue.w; - control_req.param2 = setup.b.wIndex.w; - control_req.length = setup.b.wLength.w; - - resp_len = comms_control_handler(&control_req, response); - // response pending if -1 was returned - if (resp_len != -1) { - USB_WritePacket(response, MIN(resp_len, setup.b.wLength.w), 0); - USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; - } - } -} - - - -// ***************************** USB port ***************************** - -void usb_irqhandler(void) { - //USBx->GINTMSK = 0; - - unsigned int gintsts = USBx->GINTSTS; - unsigned int gotgint = USBx->GOTGINT; - unsigned int daint = USBx_DEVICE->DAINT; - - // gintsts SUSPEND? 04008428 - #ifdef DEBUG_USB - puth(gintsts); - print(" "); - /*puth(USBx->GCCFG); - print(" ");*/ - puth(gotgint); - print(" ep "); - puth(daint); - print(" USB interrupt!\n"); - #endif - - if ((gintsts & USB_OTG_GINTSTS_CIDSCHG) != 0) { - print("connector ID status change\n"); - } - - if ((gintsts & USB_OTG_GINTSTS_USBRST) != 0) { - print("USB reset\n"); - usb_reset(); - } - - if ((gintsts & USB_OTG_GINTSTS_ENUMDNE) != 0) { - print("enumeration done"); - // Full speed, ENUMSPD - //puth(USBx_DEVICE->DSTS); - print("\n"); - } - - if ((gintsts & USB_OTG_GINTSTS_OTGINT) != 0) { - print("OTG int:"); - puth(USBx->GOTGINT); - print("\n"); - - // getting ADTOCHG - //USBx->GOTGINT = USBx->GOTGINT; - } - - // RX FIFO first - if ((gintsts & USB_OTG_GINTSTS_RXFLVL) != 0) { - // 1. Read the Receive status pop register - volatile unsigned int rxst = USBx->GRXSTSP; - int status = (rxst & USB_OTG_GRXSTSP_PKTSTS) >> 17; - - #ifdef DEBUG_USB - print(" RX FIFO:"); - puth(rxst); - print(" status: "); - puth(status); - print(" len: "); - puth((rxst & USB_OTG_GRXSTSP_BCNT) >> 4); - print("\n"); - #endif - - if (status == STS_DATA_UPDT) { - int endpoint = (rxst & USB_OTG_GRXSTSP_EPNUM); - int len = (rxst & USB_OTG_GRXSTSP_BCNT) >> 4; - (void)USB_ReadPacket(&usbdata, len); - #ifdef DEBUG_USB - print(" data "); - puth(len); - print("\n"); - hexdump(&usbdata, len); - #endif - - if (endpoint == 2) { - comms_endpoint2_write((uint8_t *) usbdata, len); - } - - if (endpoint == 3) { - outep3_processing = true; - comms_can_write(usbdata, len); - } - } else if (status == STS_SETUP_UPDT) { - (void)USB_ReadPacket(&setup, 8); - #ifdef DEBUG_USB - print(" setup "); - hexdump(&setup, 8); - print("\n"); - #endif - } else { - // status is neither STS_DATA_UPDT or STS_SETUP_UPDT, skip - } - } - - /*if (gintsts & USB_OTG_GINTSTS_HPRTINT) { - // host - print("HPRT:"); - puth(USBx_HOST_PORT->HPRT); - print("\n"); - if (USBx_HOST_PORT->HPRT & USB_OTG_HPRT_PCDET) { - USBx_HOST_PORT->HPRT |= USB_OTG_HPRT_PRST; - USBx_HOST_PORT->HPRT |= USB_OTG_HPRT_PCDET; - } - - }*/ - - if ((gintsts & USB_OTG_GINTSTS_BOUTNAKEFF) || (gintsts & USB_OTG_GINTSTS_GINAKEFF)) { - // no global NAK, why is this getting set? - #ifdef DEBUG_USB - print("GLOBAL NAK\n"); - #endif - USBx_DEVICE->DCTL |= USB_OTG_DCTL_CGONAK | USB_OTG_DCTL_CGINAK; - } - - if ((gintsts & USB_OTG_GINTSTS_SRQINT) != 0) { - // we want to do "A-device host negotiation protocol" since we are the A-device - /*print("start request\n"); - puth(USBx->GOTGCTL); - print("\n");*/ - //USBx->GUSBCFG |= USB_OTG_GUSBCFG_FDMOD; - //USBx_HOST_PORT->HPRT = USB_OTG_HPRT_PPWR | USB_OTG_HPRT_PENA; - //USBx->GOTGCTL |= USB_OTG_GOTGCTL_SRQ; - } - - // out endpoint hit - if ((gintsts & USB_OTG_GINTSTS_OEPINT) != 0) { - #ifdef DEBUG_USB - print(" 0:"); - puth(USBx_OUTEP(0)->DOEPINT); - print(" 2:"); - puth(USBx_OUTEP(2)->DOEPINT); - print(" 3:"); - puth(USBx_OUTEP(3)->DOEPINT); - print(" "); - puth(USBx_OUTEP(3)->DOEPCTL); - print(" 4:"); - puth(USBx_OUTEP(4)->DOEPINT); - print(" OUT ENDPOINT\n"); - #endif - - if ((USBx_OUTEP(2)->DOEPINT & USB_OTG_DOEPINT_XFRC) != 0) { - #ifdef DEBUG_USB - print(" OUT2 PACKET XFRC\n"); - #endif - USBx_OUTEP(2)->DOEPTSIZ = (1UL << 19) | 0x40U; - USBx_OUTEP(2)->DOEPCTL |= USB_OTG_DOEPCTL_EPENA | USB_OTG_DOEPCTL_CNAK; - } - - if ((USBx_OUTEP(3)->DOEPINT & USB_OTG_DOEPINT_XFRC) != 0) { - #ifdef DEBUG_USB - print(" OUT3 PACKET XFRC\n"); - #endif - // NAK cleared by process_can (if tx buffers have room) - outep3_processing = false; - refresh_can_tx_slots_available(); - } else if ((USBx_OUTEP(3)->DOEPINT & 0x2000) != 0) { - #ifdef DEBUG_USB - print(" OUT3 PACKET WTF\n"); - #endif - // if NAK was set trigger this, unknown interrupt - // TODO: why was this here? fires when TX buffers when we can't clear NAK - // USBx_OUTEP(3)->DOEPTSIZ = (1U << 19) | 0x40U; - // USBx_OUTEP(3)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; - } else if ((USBx_OUTEP(3)->DOEPINT) != 0) { - #ifdef DEBUG_USB - print("OUTEP3 error "); - puth(USBx_OUTEP(3)->DOEPINT); - print("\n"); - #endif - } else { - // USBx_OUTEP(3)->DOEPINT is 0, ok to skip - } - - if ((USBx_OUTEP(0)->DOEPINT & USB_OTG_DIEPINT_XFRC) != 0) { - // ready for next packet - USBx_OUTEP(0)->DOEPTSIZ = USB_OTG_DOEPTSIZ_STUPCNT | (USB_OTG_DOEPTSIZ_PKTCNT & (1UL << 19)) | (1U << 3); - } - - // respond to setup packets - if ((USBx_OUTEP(0)->DOEPINT & USB_OTG_DOEPINT_STUP) != 0) { - usb_setup(); - } - - USBx_OUTEP(0)->DOEPINT = USBx_OUTEP(0)->DOEPINT; - USBx_OUTEP(2)->DOEPINT = USBx_OUTEP(2)->DOEPINT; - USBx_OUTEP(3)->DOEPINT = USBx_OUTEP(3)->DOEPINT; - } - - // interrupt endpoint hit (Page 1221) - if ((gintsts & USB_OTG_GINTSTS_IEPINT) != 0) { - #ifdef DEBUG_USB - print(" "); - puth(USBx_INEP(0)->DIEPINT); - print(" "); - puth(USBx_INEP(1)->DIEPINT); - print(" IN ENDPOINT\n"); - #endif - - // Should likely check the EP of the IN request even if there is - // only one IN endpoint. - - // No need to set NAK in OTG_DIEPCTL0 when nothing to send, - // Appears USB core automatically sets NAK. WritePacket clears it. - - // Handle the two interface alternate settings. Setting 0 has EP1 - // as bulk. Setting 1 has EP1 as interrupt. The code to handle - // these two EP variations are very similar and can be - // restructured for smaller code footprint. Keeping split out for - // now for clarity. - - //TODO add default case. Should it NAK? - switch (current_int0_alt_setting) { - case 0: ////// Bulk config - // *** IN token received when TxFIFO is empty - if ((USBx_INEP(1)->DIEPINT & USB_OTG_DIEPMSK_ITTXFEMSK) != 0) { - #ifdef DEBUG_USB - print(" IN PACKET QUEUE\n"); - #endif - // TODO: always assuming max len, can we get the length? - USB_WritePacket((void *)response, comms_can_read(response, 0x40), 1); - } - break; - - case 1: ////// Interrupt config - // *** IN token received when TxFIFO is empty - if ((USBx_INEP(1)->DIEPINT & USB_OTG_DIEPMSK_ITTXFEMSK) != 0) { - #ifdef DEBUG_USB - print(" IN PACKET QUEUE\n"); - #endif - // TODO: always assuming max len, can we get the length? - int len = comms_can_read(response, 0x40); - if (len > 0) { - USB_WritePacket((void *)response, len, 1); - } - } - break; - default: - print("current_int0_alt_setting value invalid\n"); - break; - } - - if ((USBx_INEP(0)->DIEPINT & USB_OTG_DIEPMSK_ITTXFEMSK) != 0) { - #ifdef DEBUG_USB - print(" IN PACKET QUEUE\n"); - #endif - - if ((ep0_txlen != 0U) && ((USBx_INEP(0)->DTXFSTS & USB_OTG_DTXFSTS_INEPTFSAV) >= 0x40U)) { - uint16_t len = MIN(ep0_txlen, 0x40); - USB_WritePacket(ep0_txdata, len, 0); - ep0_txdata = &ep0_txdata[len]; - ep0_txlen -= len; - if (ep0_txlen == 0U) { - ep0_txdata = NULL; - USBx_DEVICE->DIEPEMPMSK &= ~1; - USBx_OUTEP(0)->DOEPCTL |= USB_OTG_DOEPCTL_CNAK; - } - } - } - - // clear interrupts - USBx_INEP(0)->DIEPINT = USBx_INEP(0)->DIEPINT; // Why ep0? - USBx_INEP(1)->DIEPINT = USBx_INEP(1)->DIEPINT; - } - - // clear all interrupts we handled - USBx_DEVICE->DAINT = daint; - USBx->GOTGINT = gotgint; - USBx->GINTSTS = gintsts; - - //USBx->GINTMSK = 0xFFFFFFFF & ~(USB_OTG_GINTMSK_NPTXFEM | USB_OTG_GINTMSK_PTXFEM | USB_OTG_GINTSTS_SOF | USB_OTG_GINTSTS_EOPF); -} - -void can_tx_comms_resume_usb(void) { - ENTER_CRITICAL(); - if (!outep3_processing && (USBx_OUTEP(3)->DOEPCTL & USB_OTG_DOEPCTL_NAKSTS) != 0) { - USBx_OUTEP(3)->DOEPTSIZ = (32UL << 19) | 0x800U; - USBx_OUTEP(3)->DOEPCTL |= USB_OTG_DOEPCTL_EPENA | USB_OTG_DOEPCTL_CNAK; - } - EXIT_CRITICAL(); -} - -void usb_soft_disconnect(bool enable) { - if (enable) { - USBx_DEVICE->DCTL |= USB_OTG_DCTL_SDIS; - } else { - USBx_DEVICE->DCTL &= ~USB_OTG_DCTL_SDIS; - } -} diff --git a/panda/board/drivers/watchdog.h b/panda/board/drivers/watchdog.h deleted file mode 100644 index 89cf01e..0000000 --- a/panda/board/drivers/watchdog.h +++ /dev/null @@ -1,24 +0,0 @@ -typedef enum { - WATCHDOG_50_MS = (400U - 1U), - WATCHDOG_500_MS = 4000U, -} WatchdogTimeout; - -void watchdog_feed(void) { - IND_WDG->KR = 0xAAAAU; -} - -void watchdog_init(WatchdogTimeout timeout) { - // enable watchdog - IND_WDG->KR = 0xCCCCU; - IND_WDG->KR = 0x5555U; - - // 32KHz / 4 prescaler = 8000Hz - register_set(&(IND_WDG->PR), 0x0U, IWDG_PR_PR_Msk); - register_set(&(IND_WDG->RLR), timeout, IWDG_RLR_RL_Msk); - - // wait for watchdog to be updated - while (IND_WDG->SR != 0U); - - // start the countdown - watchdog_feed(); -} diff --git a/panda/board/early_init.h b/panda/board/early_init.h deleted file mode 100644 index ae652ae..0000000 --- a/panda/board/early_init.h +++ /dev/null @@ -1,60 +0,0 @@ -// Early bringup -#define ENTER_BOOTLOADER_MAGIC 0xdeadbeefU -#define ENTER_SOFTLOADER_MAGIC 0xdeadc0deU -#define BOOT_NORMAL 0xdeadb111U - -extern void *g_pfnVectors; -extern uint32_t enter_bootloader_mode; - -void jump_to_bootloader(void) { - // do enter bootloader - enter_bootloader_mode = 0; - void (*bootloader)(void) = (void (*)(void)) (*((uint32_t *)BOOTLOADER_ADDRESS)); - - // jump to bootloader - enable_interrupts(); - bootloader(); - - // reset on exit - enter_bootloader_mode = BOOT_NORMAL; - NVIC_SystemReset(); -} - -void early_initialization(void) { - // Reset global critical depth - disable_interrupts(); - global_critical_depth = 0; - - // Init register and interrupt tables - init_registers(); - - // after it's been in the bootloader, things are initted differently, so we reset - if ((enter_bootloader_mode != BOOT_NORMAL) && - (enter_bootloader_mode != ENTER_BOOTLOADER_MAGIC) && - (enter_bootloader_mode != ENTER_SOFTLOADER_MAGIC)) { - enter_bootloader_mode = BOOT_NORMAL; - NVIC_SystemReset(); - } - - // if wrong chip, reboot - volatile unsigned int id = DBGMCU->IDCODE; - if ((id & 0xFFFU) != MCU_IDCODE) { - enter_bootloader_mode = ENTER_BOOTLOADER_MAGIC; - } - - // setup interrupt table - SCB->VTOR = (uint32_t)&g_pfnVectors; - - // early GPIOs float everything - early_gpio_float(); - - detect_board_type(); - - if (enter_bootloader_mode == ENTER_BOOTLOADER_MAGIC) { - #ifdef PANDA - current_board->init_bootloader(); - #endif - current_board->set_led(LED_GREEN, 1); - jump_to_bootloader(); - } -} diff --git a/panda/board/fake_stm.h b/panda/board/fake_stm.h deleted file mode 100644 index b73a4e8..0000000 --- a/panda/board/fake_stm.h +++ /dev/null @@ -1,33 +0,0 @@ -// minimal code to fake a panda for tests -#include -#include -#include - -#include "utils.h" - -#define CANFD -#define ALLOW_DEBUG -#define PANDA - -#define ENTER_CRITICAL() 0 -#define EXIT_CRITICAL() 0 - -void print(const char *a) { - printf("%s", a); -} - -void puth(unsigned int i) { - printf("%u", i); -} - -typedef struct { - uint32_t CNT; -} TIM_TypeDef; - -TIM_TypeDef timer; -TIM_TypeDef *MICROSECOND_TIMER = &timer; -uint32_t microsecond_timer_get(void); - -uint32_t microsecond_timer_get(void) { - return MICROSECOND_TIMER->CNT; -} diff --git a/panda/board/faults.h b/panda/board/faults.h deleted file mode 100644 index a7f437d..0000000 --- a/panda/board/faults.h +++ /dev/null @@ -1,59 +0,0 @@ -#define FAULT_STATUS_NONE 0U -#define FAULT_STATUS_TEMPORARY 1U -#define FAULT_STATUS_PERMANENT 2U - -// Fault types, matches cereal.log.PandaState.FaultType -#define FAULT_RELAY_MALFUNCTION (1UL << 0) -#define FAULT_UNUSED_INTERRUPT_HANDLED (1UL << 1) -#define FAULT_INTERRUPT_RATE_CAN_1 (1UL << 2) -#define FAULT_INTERRUPT_RATE_CAN_2 (1UL << 3) -#define FAULT_INTERRUPT_RATE_CAN_3 (1UL << 4) -#define FAULT_INTERRUPT_RATE_TACH (1UL << 5) -#define FAULT_INTERRUPT_RATE_GMLAN (1UL << 6) -#define FAULT_INTERRUPT_RATE_INTERRUPTS (1UL << 7) -#define FAULT_INTERRUPT_RATE_SPI_DMA (1UL << 8) -#define FAULT_INTERRUPT_RATE_SPI_CS (1UL << 9) -#define FAULT_INTERRUPT_RATE_UART_1 (1UL << 10) -#define FAULT_INTERRUPT_RATE_UART_2 (1UL << 11) -#define FAULT_INTERRUPT_RATE_UART_3 (1UL << 12) -#define FAULT_INTERRUPT_RATE_UART_5 (1UL << 13) -#define FAULT_INTERRUPT_RATE_UART_DMA (1UL << 14) -#define FAULT_INTERRUPT_RATE_USB (1UL << 15) -#define FAULT_INTERRUPT_RATE_TIM1 (1UL << 16) -#define FAULT_INTERRUPT_RATE_TIM3 (1UL << 17) -#define FAULT_REGISTER_DIVERGENT (1UL << 18) -#define FAULT_INTERRUPT_RATE_KLINE_INIT (1UL << 19) -#define FAULT_INTERRUPT_RATE_CLOCK_SOURCE (1UL << 20) -#define FAULT_INTERRUPT_RATE_TICK (1UL << 21) -#define FAULT_INTERRUPT_RATE_EXTI (1UL << 22) -#define FAULT_INTERRUPT_RATE_SPI (1UL << 23) -#define FAULT_INTERRUPT_RATE_UART_7 (1UL << 24) -#define FAULT_SIREN_MALFUNCTION (1UL << 25) -#define FAULT_HEARTBEAT_LOOP_WATCHDOG (1UL << 26) - -// Permanent faults -#define PERMANENT_FAULTS 0U - -uint8_t fault_status = FAULT_STATUS_NONE; -uint32_t faults = 0U; - -void fault_occurred(uint32_t fault) { - if ((faults & fault) == 0U) { - if ((PERMANENT_FAULTS & fault) != 0U) { - print("Permanent fault occurred: 0x"); puth(fault); print("\n"); - fault_status = FAULT_STATUS_PERMANENT; - } else { - print("Temporary fault occurred: 0x"); puth(fault); print("\n"); - fault_status = FAULT_STATUS_TEMPORARY; - } - } - faults |= fault; -} - -void fault_recovered(uint32_t fault) { - if ((PERMANENT_FAULTS & fault) == 0U) { - faults &= ~fault; - } else { - print("Cannot recover from a permanent fault!\n"); - } -} diff --git a/panda/board/flasher.h b/panda/board/flasher.h deleted file mode 100644 index d6c2c40..0000000 --- a/panda/board/flasher.h +++ /dev/null @@ -1,150 +0,0 @@ -// flasher state variables -uint32_t *prog_ptr = NULL; -bool unlocked = false; - -void spi_init(void); - -int comms_control_handler(ControlPacket_t *req, uint8_t *resp) { - int resp_len = 0; - - // flasher machine - memset(resp, 0, 4); - memcpy(resp+4, "\xde\xad\xd0\x0d", 4); - resp[0] = 0xff; - resp[2] = req->request; - resp[3] = ~req->request; - *((uint32_t **)&resp[8]) = prog_ptr; - resp_len = 0xc; - - int sec; - switch (req->request) { - // **** 0xb0: flasher echo - case 0xb0: - resp[1] = 0xff; - break; - // **** 0xb1: unlock flash - case 0xb1: - if (flash_is_locked()) { - flash_unlock(); - resp[1] = 0xff; - } - current_board->set_led(LED_GREEN, 1); - unlocked = true; - prog_ptr = (uint32_t *)APP_START_ADDRESS; - break; - // **** 0xb2: erase sector - case 0xb2: - sec = req->param1; - if (flash_erase_sector(sec, unlocked)) { - resp[1] = 0xff; - } - break; - // **** 0xc1: get hardware type - case 0xc1: - resp[0] = hw_type; - resp_len = 1; - break; - // **** 0xc3: fetch MCU UID - case 0xc3: - (void)memcpy(resp, ((uint8_t *)UID_BASE), 12); - resp_len = 12; - break; - // **** 0xd0: fetch serial number - case 0xd0: - // addresses are OTP - if (req->param1 == 1) { - memcpy(resp, (void *)DEVICE_SERIAL_NUMBER_ADDRESS, 0x10); - resp_len = 0x10; - } else { - get_provision_chunk(resp); - resp_len = PROVISION_CHUNK_LEN; - } - break; - // **** 0xd1: enter bootloader mode - case 0xd1: - // this allows reflashing of the bootstub - switch (req->param1) { - case 0: - print("-> entering bootloader\n"); - enter_bootloader_mode = ENTER_BOOTLOADER_MAGIC; - NVIC_SystemReset(); - break; - case 1: - print("-> entering softloader\n"); - enter_bootloader_mode = ENTER_SOFTLOADER_MAGIC; - NVIC_SystemReset(); - break; - } - break; - // **** 0xd6: get version - case 0xd6: - COMPILE_TIME_ASSERT(sizeof(gitversion) <= USBPACKET_MAX_SIZE); - memcpy(resp, gitversion, sizeof(gitversion)); - resp_len = sizeof(gitversion); - break; - // **** 0xd8: reset ST - case 0xd8: - flush_write_buffer(); - NVIC_SystemReset(); - break; - } - return resp_len; -} - -void comms_can_write(const uint8_t *data, uint32_t len) { - UNUSED(data); - UNUSED(len); -} - -int comms_can_read(uint8_t *data, uint32_t max_len) { - UNUSED(data); - UNUSED(max_len); - return 0; -} - -void refresh_can_tx_slots_available(void) {} - -void comms_endpoint2_write(const uint8_t *data, uint32_t len) { - current_board->set_led(LED_RED, 0); - for (uint32_t i = 0; i < len/4; i++) { - flash_write_word(prog_ptr, *(uint32_t*)(data+(i*4))); - - //*(uint64_t*)(&spi_tx_buf[0x30+(i*4)]) = *prog_ptr; - prog_ptr++; - } - current_board->set_led(LED_RED, 1); -} - - -void soft_flasher_start(void) { - print("\n\n\n************************ FLASHER START ************************\n"); - - enter_bootloader_mode = 0; - - flasher_peripherals_init(); - - gpio_usart2_init(); - gpio_usb_init(); - - // enable USB - usb_init(); - - // enable SPI - if (current_board->has_spi) { - gpio_spi_init(); - spi_init(); - } - - // green LED on for flashing - current_board->set_led(LED_GREEN, 1); - - enable_interrupts(); - - for (;;) { - // blink the green LED fast - current_board->set_led(LED_GREEN, 0); - delay(500000); - current_board->set_led(LED_GREEN, 1); - delay(500000); - } -} diff --git a/panda/board/health.h b/panda/board/health.h deleted file mode 100644 index fc7661c..0000000 --- a/panda/board/health.h +++ /dev/null @@ -1,62 +0,0 @@ -// When changing these structs, python/__init__.py needs to be kept up to date! - -#define HEALTH_PACKET_VERSION 15 -struct __attribute__((packed)) health_t { - uint32_t uptime_pkt; - uint32_t voltage_pkt; - uint32_t current_pkt; - uint32_t safety_tx_blocked_pkt; - uint32_t safety_rx_invalid_pkt; - uint32_t tx_buffer_overflow_pkt; - uint32_t rx_buffer_overflow_pkt; - uint32_t gmlan_send_errs_pkt; - uint32_t faults_pkt; - uint8_t ignition_line_pkt; - uint8_t ignition_can_pkt; - uint8_t controls_allowed_pkt; - uint8_t car_harness_status_pkt; - uint8_t safety_mode_pkt; - uint16_t safety_param_pkt; - uint8_t fault_status_pkt; - uint8_t power_save_enabled_pkt; - uint8_t heartbeat_lost_pkt; - uint16_t alternative_experience_pkt; - float interrupt_load_pkt; - uint8_t fan_power; - uint8_t safety_rx_checks_invalid_pkt; - uint16_t spi_checksum_error_count_pkt; - uint8_t fan_stall_count; - uint16_t sbu1_voltage_mV; - uint16_t sbu2_voltage_mV; - uint8_t som_reset_triggered; -}; - -#define CAN_HEALTH_PACKET_VERSION 5 -typedef struct __attribute__((packed)) { - uint8_t bus_off; - uint32_t bus_off_cnt; - uint8_t error_warning; - uint8_t error_passive; - uint8_t last_error; // real time LEC value - uint8_t last_stored_error; // last LEC positive error code stored - uint8_t last_data_error; // DLEC (for CANFD only) - uint8_t last_data_stored_error; // last DLEC positive error code stored (for CANFD only) - uint8_t receive_error_cnt; // Actual state of the receive error counter, values between 0 and 127. FDCAN_ECR.REC - uint8_t transmit_error_cnt; // Actual state of the transmit error counter, values between 0 and 255. FDCAN_ECR.TEC - uint32_t total_error_cnt; // How many times any error interrupt was invoked - uint32_t total_tx_lost_cnt; // Tx event FIFO element lost - uint32_t total_rx_lost_cnt; // Rx FIFO 0 message lost due to FIFO full condition - uint32_t total_tx_cnt; - uint32_t total_rx_cnt; - uint32_t total_fwd_cnt; // Messages forwarded from one bus to another - uint32_t total_tx_checksum_error_cnt; - uint16_t can_speed; - uint16_t can_data_speed; - uint8_t canfd_enabled; - uint8_t brs_enabled; - uint8_t canfd_non_iso; - uint32_t irq0_call_rate; - uint32_t irq1_call_rate; - uint32_t irq2_call_rate; - uint32_t can_core_reset_cnt; -} can_health_t; diff --git a/panda/board/jungle/SConscript b/panda/board/jungle/SConscript deleted file mode 100644 index 3e40611..0000000 --- a/panda/board/jungle/SConscript +++ /dev/null @@ -1,18 +0,0 @@ -import os -import copy - -Import('build_project', 'base_project_f4', 'base_project_h7') - -build_projects = { - "panda_jungle": base_project_f4, - "panda_jungle_h7": base_project_h7, -} - -for project_name, project in build_projects.items(): - flags = [ - "-DPANDA_JUNGLE", - ] - if os.getenv("FINAL_PROVISIONING"): - flags += ["-DFINAL_PROVISIONING"] - - build_project(project_name, project, flags) diff --git a/panda/board/jungle/boards/board_declarations.h b/panda/board/jungle/boards/board_declarations.h deleted file mode 100644 index 9259189..0000000 --- a/panda/board/jungle/boards/board_declarations.h +++ /dev/null @@ -1,82 +0,0 @@ -// ******************** Prototypes ******************** -typedef void (*board_init)(void); -typedef void (*board_set_led)(uint8_t color, bool enabled); -typedef void (*board_board_tick)(void); -typedef bool (*board_get_button)(void); -typedef void (*board_set_panda_power)(bool enabled); -typedef void (*board_set_panda_individual_power)(uint8_t port_num, bool enabled); -typedef void (*board_set_ignition)(bool enabled); -typedef void (*board_set_individual_ignition)(uint8_t bitmask); -typedef void (*board_set_harness_orientation)(uint8_t orientation); -typedef void (*board_set_can_mode)(uint8_t mode); -typedef void (*board_enable_can_transciever)(uint8_t transciever, bool enabled); -typedef void (*board_enable_header_pin)(uint8_t pin_num, bool enabled); -typedef float (*board_get_channel_power)(uint8_t channel); -typedef uint16_t (*board_get_sbu_mV)(uint8_t channel, uint8_t sbu); - -struct board { - const bool has_canfd; - const bool has_sbu_sense; - const uint16_t avdd_mV; - board_init init; - board_set_led set_led; - board_board_tick board_tick; - board_get_button get_button; - board_set_panda_power set_panda_power; - board_set_panda_individual_power set_panda_individual_power; - board_set_ignition set_ignition; - board_set_individual_ignition set_individual_ignition; - board_set_harness_orientation set_harness_orientation; - board_set_can_mode set_can_mode; - board_enable_can_transciever enable_can_transciever; - board_enable_header_pin enable_header_pin; - board_get_channel_power get_channel_power; - board_get_sbu_mV get_sbu_mV; - - // TODO: shouldn't need these - bool has_spi; -}; - -// ******************* Definitions ******************** -#define HW_TYPE_UNKNOWN 0U -#define HW_TYPE_V1 1U -#define HW_TYPE_V2 2U - -// LED colors -#define LED_RED 0U -#define LED_GREEN 1U -#define LED_BLUE 2U - -// CAN modes -#define CAN_MODE_NORMAL 0U -#define CAN_MODE_GMLAN_CAN2 1U -#define CAN_MODE_GMLAN_CAN3 2U -#define CAN_MODE_OBD_CAN2 3U - -// Harness states -#define HARNESS_ORIENTATION_NONE 0U -#define HARNESS_ORIENTATION_1 1U -#define HARNESS_ORIENTATION_2 2U - -#define SBU1 0U -#define SBU2 1U - -// ********************* Globals ********************** -uint8_t harness_orientation = HARNESS_ORIENTATION_NONE; -uint8_t can_mode = CAN_MODE_NORMAL; -uint8_t ignition = 0U; - - -void unused_set_individual_ignition(uint8_t bitmask) { - UNUSED(bitmask); -} - -void unused_board_enable_header_pin(uint8_t pin_num, bool enabled) { - UNUSED(pin_num); - UNUSED(enabled); -} - -void unused_set_panda_individual_power(uint8_t port_num, bool enabled) { - UNUSED(port_num); - UNUSED(enabled); -} diff --git a/panda/board/jungle/boards/board_v1.h b/panda/board/jungle/boards/board_v1.h deleted file mode 100644 index 9581686..0000000 --- a/panda/board/jungle/boards/board_v1.h +++ /dev/null @@ -1,178 +0,0 @@ -// ///////////////////////// // -// Jungle board v1 (STM32F4) // -// ///////////////////////// // - -void board_v1_set_led(uint8_t color, bool enabled) { - switch (color) { - case LED_RED: - set_gpio_output(GPIOC, 9, !enabled); - break; - case LED_GREEN: - set_gpio_output(GPIOC, 7, !enabled); - break; - case LED_BLUE: - set_gpio_output(GPIOC, 6, !enabled); - break; - default: - break; - } -} - -void board_v1_enable_can_transciever(uint8_t transciever, bool enabled) { - switch (transciever) { - case 1U: - set_gpio_output(GPIOC, 1, !enabled); - break; - case 2U: - set_gpio_output(GPIOC, 13, !enabled); - break; - case 3U: - set_gpio_output(GPIOA, 0, !enabled); - break; - case 4U: - set_gpio_output(GPIOB, 10, !enabled); - break; - default: - print("Invalid CAN transciever ("); puth(transciever); print("): enabling failed\n"); - break; - } -} - -void board_v1_set_can_mode(uint8_t mode) { - board_v1_enable_can_transciever(2U, false); - board_v1_enable_can_transciever(4U, false); - switch (mode) { - case CAN_MODE_NORMAL: - print("Setting normal CAN mode\n"); - // B12,B13: disable OBD mode - set_gpio_mode(GPIOB, 12, MODE_INPUT); - set_gpio_mode(GPIOB, 13, MODE_INPUT); - - // B5,B6: normal CAN2 mode - set_gpio_alternate(GPIOB, 5, GPIO_AF9_CAN2); - set_gpio_alternate(GPIOB, 6, GPIO_AF9_CAN2); - can_mode = CAN_MODE_NORMAL; - board_v1_enable_can_transciever(2U, true); - break; - case CAN_MODE_OBD_CAN2: - print("Setting OBD CAN mode\n"); - // B5,B6: disable normal CAN2 mode - set_gpio_mode(GPIOB, 5, MODE_INPUT); - set_gpio_mode(GPIOB, 6, MODE_INPUT); - - // B12,B13: OBD mode - set_gpio_alternate(GPIOB, 12, GPIO_AF9_CAN2); - set_gpio_alternate(GPIOB, 13, GPIO_AF9_CAN2); - can_mode = CAN_MODE_OBD_CAN2; - board_v1_enable_can_transciever(4U, true); - break; - default: - print("Tried to set unsupported CAN mode: "); puth(mode); print("\n"); - break; - } -} - -void board_v1_set_harness_orientation(uint8_t orientation) { - switch (orientation) { - case HARNESS_ORIENTATION_NONE: - set_gpio_output(GPIOA, 2, false); - set_gpio_output(GPIOA, 3, false); - set_gpio_output(GPIOA, 4, false); - set_gpio_output(GPIOA, 5, false); - harness_orientation = orientation; - break; - case HARNESS_ORIENTATION_1: - set_gpio_output(GPIOA, 2, false); - set_gpio_output(GPIOA, 3, (ignition != 0U)); - set_gpio_output(GPIOA, 4, true); - set_gpio_output(GPIOA, 5, false); - harness_orientation = orientation; - break; - case HARNESS_ORIENTATION_2: - set_gpio_output(GPIOA, 2, (ignition != 0U)); - set_gpio_output(GPIOA, 3, false); - set_gpio_output(GPIOA, 4, false); - set_gpio_output(GPIOA, 5, true); - harness_orientation = orientation; - break; - default: - print("Tried to set an unsupported harness orientation: "); puth(orientation); print("\n"); - break; - } -} - -bool panda_power = false; -void board_v1_set_panda_power(bool enable) { - panda_power = enable; - set_gpio_output(GPIOB, 14, enable); -} - -bool board_v1_get_button(void) { - return get_gpio_input(GPIOC, 8); -} - -void board_v1_set_ignition(bool enabled) { - ignition = enabled ? 0xFFU : 0U; - board_v1_set_harness_orientation(harness_orientation); -} - -float board_v1_get_channel_power(uint8_t channel) { - UNUSED(channel); - return 0.0f; -} - -uint16_t board_v1_get_sbu_mV(uint8_t channel, uint8_t sbu) { - UNUSED(channel); UNUSED(sbu); - return 0U; -} - -void board_v1_init(void) { - common_init_gpio(); - - // A8,A15: normal CAN3 mode - set_gpio_alternate(GPIOA, 8, GPIO_AF11_CAN3); - set_gpio_alternate(GPIOA, 15, GPIO_AF11_CAN3); - - board_v1_set_can_mode(CAN_MODE_NORMAL); - - // Enable CAN transcievers - for(uint8_t i = 1; i <= 4; i++) { - board_v1_enable_can_transciever(i, true); - } - - // Disable LEDs - board_v1_set_led(LED_RED, false); - board_v1_set_led(LED_GREEN, false); - board_v1_set_led(LED_BLUE, false); - - // Set normal CAN mode - board_v1_set_can_mode(CAN_MODE_NORMAL); - - // Set to no harness orientation - board_v1_set_harness_orientation(HARNESS_ORIENTATION_NONE); - - // Enable panda power by default - board_v1_set_panda_power(true); -} - -void board_v1_tick(void) {} - -const board board_v1 = { - .has_canfd = false, - .has_sbu_sense = false, - .avdd_mV = 3300U, - .init = &board_v1_init, - .set_led = &board_v1_set_led, - .board_tick = &board_v1_tick, - .get_button = &board_v1_get_button, - .set_panda_power = &board_v1_set_panda_power, - .set_panda_individual_power = &unused_set_panda_individual_power, - .set_ignition = &board_v1_set_ignition, - .set_individual_ignition = &unused_set_individual_ignition, - .set_harness_orientation = &board_v1_set_harness_orientation, - .set_can_mode = &board_v1_set_can_mode, - .enable_can_transciever = &board_v1_enable_can_transciever, - .enable_header_pin = &unused_board_enable_header_pin, - .get_channel_power = &board_v1_get_channel_power, - .get_sbu_mV = &board_v1_get_sbu_mV, -}; diff --git a/panda/board/jungle/boards/board_v2.h b/panda/board/jungle/boards/board_v2.h deleted file mode 100644 index 0951148..0000000 --- a/panda/board/jungle/boards/board_v2.h +++ /dev/null @@ -1,328 +0,0 @@ -// ///////////////////////// // -// Jungle board v2 (STM32H7) // -// ///////////////////////// // - -const gpio_t power_pins[] = { - {.bank = GPIOA, .pin = 0}, - {.bank = GPIOA, .pin = 1}, - {.bank = GPIOF, .pin = 12}, - {.bank = GPIOA, .pin = 5}, - {.bank = GPIOC, .pin = 5}, - {.bank = GPIOB, .pin = 2}, -}; - -const gpio_t sbu1_ignition_pins[] = { - {.bank = GPIOD, .pin = 0}, - {.bank = GPIOD, .pin = 5}, - {.bank = GPIOD, .pin = 12}, - {.bank = GPIOD, .pin = 14}, - {.bank = GPIOE, .pin = 5}, - {.bank = GPIOE, .pin = 9}, -}; - -const gpio_t sbu1_relay_pins[] = { - {.bank = GPIOD, .pin = 1}, - {.bank = GPIOD, .pin = 6}, - {.bank = GPIOD, .pin = 11}, - {.bank = GPIOD, .pin = 15}, - {.bank = GPIOE, .pin = 6}, - {.bank = GPIOE, .pin = 10}, -}; - -const gpio_t sbu2_ignition_pins[] = { - {.bank = GPIOD, .pin = 3}, - {.bank = GPIOD, .pin = 8}, - {.bank = GPIOD, .pin = 9}, - {.bank = GPIOE, .pin = 0}, - {.bank = GPIOE, .pin = 7}, - {.bank = GPIOE, .pin = 11}, -}; - -const gpio_t sbu2_relay_pins[] = { - {.bank = GPIOD, .pin = 4}, - {.bank = GPIOD, .pin = 10}, - {.bank = GPIOD, .pin = 13}, - {.bank = GPIOE, .pin = 1}, - {.bank = GPIOE, .pin = 8}, - {.bank = GPIOE, .pin = 12}, -}; - -const adc_channel_t sbu1_channels[] = { - {.adc = ADC3, .channel = 12}, - {.adc = ADC3, .channel = 2}, - {.adc = ADC3, .channel = 4}, - {.adc = ADC3, .channel = 6}, - {.adc = ADC3, .channel = 8}, - {.adc = ADC3, .channel = 10}, -}; - -const adc_channel_t sbu2_channels[] = { - {.adc = ADC1, .channel = 13}, - {.adc = ADC3, .channel = 3}, - {.adc = ADC3, .channel = 5}, - {.adc = ADC3, .channel = 7}, - {.adc = ADC3, .channel = 9}, - {.adc = ADC3, .channel = 11}, -}; - -void board_v2_set_led(uint8_t color, bool enabled) { - switch (color) { - case LED_RED: - set_gpio_output(GPIOE, 4, !enabled); - break; - case LED_GREEN: - set_gpio_output(GPIOE, 3, !enabled); - break; - case LED_BLUE: - set_gpio_output(GPIOE, 2, !enabled); - break; - default: - break; - } -} - -void board_v2_set_harness_orientation(uint8_t orientation) { - switch (orientation) { - case HARNESS_ORIENTATION_NONE: - gpio_set_all_output(sbu1_ignition_pins, sizeof(sbu1_ignition_pins) / sizeof(gpio_t), false); - gpio_set_all_output(sbu1_relay_pins, sizeof(sbu1_relay_pins) / sizeof(gpio_t), false); - gpio_set_all_output(sbu2_ignition_pins, sizeof(sbu2_ignition_pins) / sizeof(gpio_t), false); - gpio_set_all_output(sbu2_relay_pins, sizeof(sbu2_relay_pins) / sizeof(gpio_t), false); - harness_orientation = orientation; - break; - case HARNESS_ORIENTATION_1: - gpio_set_all_output(sbu1_ignition_pins, sizeof(sbu1_ignition_pins) / sizeof(gpio_t), false); - gpio_set_all_output(sbu1_relay_pins, sizeof(sbu1_relay_pins) / sizeof(gpio_t), true); - gpio_set_bitmask(sbu2_ignition_pins, sizeof(sbu2_ignition_pins) / sizeof(gpio_t), ignition); - gpio_set_all_output(sbu2_relay_pins, sizeof(sbu2_relay_pins) / sizeof(gpio_t), false); - harness_orientation = orientation; - break; - case HARNESS_ORIENTATION_2: - gpio_set_bitmask(sbu1_ignition_pins, sizeof(sbu1_ignition_pins) / sizeof(gpio_t), ignition); - gpio_set_all_output(sbu1_relay_pins, sizeof(sbu1_relay_pins) / sizeof(gpio_t), false); - gpio_set_all_output(sbu2_ignition_pins, sizeof(sbu2_ignition_pins) / sizeof(gpio_t), false); - gpio_set_all_output(sbu2_relay_pins, sizeof(sbu2_relay_pins) / sizeof(gpio_t), true); - harness_orientation = orientation; - break; - default: - print("Tried to set an unsupported harness orientation: "); puth(orientation); print("\n"); - break; - } -} - -void board_v2_enable_can_transciever(uint8_t transciever, bool enabled) { - switch (transciever) { - case 1U: - set_gpio_output(GPIOG, 11, !enabled); - break; - case 2U: - set_gpio_output(GPIOB, 3, !enabled); - break; - case 3U: - set_gpio_output(GPIOD, 7, !enabled); - break; - case 4U: - set_gpio_output(GPIOB, 4, !enabled); - break; - default: - print("Invalid CAN transciever ("); puth(transciever); print("): enabling failed\n"); - break; - } -} - -void board_v2_enable_header_pin(uint8_t pin_num, bool enabled) { - if (pin_num < 8U) { - set_gpio_output(GPIOG, pin_num, enabled); - } else { - print("Invalid pin number ("); puth(pin_num); print("): enabling failed\n"); - } -} - -void board_v2_set_can_mode(uint8_t mode) { - board_v2_enable_can_transciever(2U, false); - board_v2_enable_can_transciever(4U, false); - switch (mode) { - case CAN_MODE_NORMAL: - // B12,B13: disable normal mode - set_gpio_pullup(GPIOB, 12, PULL_NONE); - set_gpio_mode(GPIOB, 12, MODE_ANALOG); - - set_gpio_pullup(GPIOB, 13, PULL_NONE); - set_gpio_mode(GPIOB, 13, MODE_ANALOG); - - // B5,B6: FDCAN2 mode - set_gpio_pullup(GPIOB, 5, PULL_NONE); - set_gpio_alternate(GPIOB, 5, GPIO_AF9_FDCAN2); - - set_gpio_pullup(GPIOB, 6, PULL_NONE); - set_gpio_alternate(GPIOB, 6, GPIO_AF9_FDCAN2); - can_mode = CAN_MODE_NORMAL; - board_v2_enable_can_transciever(2U, true); - break; - case CAN_MODE_OBD_CAN2: - // B5,B6: disable normal mode - set_gpio_pullup(GPIOB, 5, PULL_NONE); - set_gpio_mode(GPIOB, 5, MODE_ANALOG); - - set_gpio_pullup(GPIOB, 6, PULL_NONE); - set_gpio_mode(GPIOB, 6, MODE_ANALOG); - // B12,B13: FDCAN2 mode - set_gpio_pullup(GPIOB, 12, PULL_NONE); - set_gpio_alternate(GPIOB, 12, GPIO_AF9_FDCAN2); - - set_gpio_pullup(GPIOB, 13, PULL_NONE); - set_gpio_alternate(GPIOB, 13, GPIO_AF9_FDCAN2); - can_mode = CAN_MODE_OBD_CAN2; - board_v2_enable_can_transciever(4U, true); - break; - default: - break; - } -} - -bool panda_power = false; -uint8_t panda_power_bitmask = 0U; -void board_v2_set_panda_power(bool enable) { - panda_power = enable; - gpio_set_all_output(power_pins, sizeof(power_pins) / sizeof(gpio_t), enable); - if (enable) { - panda_power_bitmask = 0xFFU; - } else { - panda_power_bitmask = 0U; - } -} - -void board_v2_set_panda_individual_power(uint8_t port_num, bool enable) { - port_num -= 1U; - if (port_num < 6U) { - panda_power_bitmask &= ~(1U << port_num); - panda_power_bitmask |= (enable ? 1U : 0U) << port_num; - } else { - print("Invalid port number ("); puth(port_num); print("): enabling failed\n"); - } - gpio_set_bitmask(power_pins, sizeof(power_pins) / sizeof(gpio_t), (uint32_t)panda_power_bitmask); -} - -bool board_v2_get_button(void) { - return get_gpio_input(GPIOG, 15); -} - -void board_v2_set_ignition(bool enabled) { - ignition = enabled ? 0xFFU : 0U; - board_v2_set_harness_orientation(harness_orientation); -} - -void board_v2_set_individual_ignition(uint8_t bitmask) { - ignition = bitmask; - board_v2_set_harness_orientation(harness_orientation); -} - -float board_v2_get_channel_power(uint8_t channel) { - float ret = 0.0f; - if ((channel >= 1U) && (channel <= 6U)) { - uint16_t readout = adc_get_mV(ADC1, channel - 1U); // these are mapped nicely in hardware - - ret = (((float) readout / 33e6) - 0.8e-6) / 52e-6 * 12.0f; - } else { - print("Invalid channel ("); puth(channel); print(")\n"); - } - return ret; -} - -uint16_t board_v2_get_sbu_mV(uint8_t channel, uint8_t sbu) { - uint16_t ret = 0U; - if ((channel >= 1U) && (channel <= 6U)) { - switch(sbu){ - case SBU1: - ret = adc_get_mV(sbu1_channels[channel - 1U].adc, sbu1_channels[channel - 1U].channel); - break; - case SBU2: - ret = adc_get_mV(sbu2_channels[channel - 1U].adc, sbu2_channels[channel - 1U].channel); - break; - default: - print("Invalid SBU ("); puth(sbu); print(")\n"); - break; - } - } else { - print("Invalid channel ("); puth(channel); print(")\n"); - } - return ret; -} - -void board_v2_init(void) { - common_init_gpio(); - - // Disable LEDs - board_v2_set_led(LED_RED, false); - board_v2_set_led(LED_GREEN, false); - board_v2_set_led(LED_BLUE, false); - - // Normal CAN mode - board_v2_set_can_mode(CAN_MODE_NORMAL); - - // Enable CAN transcievers - for(uint8_t i = 1; i <= 4; i++) { - board_v2_enable_can_transciever(i, true); - } - - // Set to no harness orientation - board_v2_set_harness_orientation(HARNESS_ORIENTATION_NONE); - - // Enable panda power by default - board_v2_set_panda_power(true); - - // Current monitor channels - adc_init(ADC1); - register_set_bits(&SYSCFG->PMCR, SYSCFG_PMCR_PA0SO | SYSCFG_PMCR_PA1SO); // open up analog switches for PA0_C and PA1_C - set_gpio_mode(GPIOF, 11, MODE_ANALOG); - set_gpio_mode(GPIOA, 6, MODE_ANALOG); - set_gpio_mode(GPIOC, 4, MODE_ANALOG); - set_gpio_mode(GPIOB, 1, MODE_ANALOG); - - // SBU channels - adc_init(ADC3); - set_gpio_mode(GPIOC, 2, MODE_ANALOG); - set_gpio_mode(GPIOC, 3, MODE_ANALOG); - set_gpio_mode(GPIOF, 9, MODE_ANALOG); - set_gpio_mode(GPIOF, 7, MODE_ANALOG); - set_gpio_mode(GPIOF, 5, MODE_ANALOG); - set_gpio_mode(GPIOF, 3, MODE_ANALOG); - set_gpio_mode(GPIOF, 10, MODE_ANALOG); - set_gpio_mode(GPIOF, 8, MODE_ANALOG); - set_gpio_mode(GPIOF, 6, MODE_ANALOG); - set_gpio_mode(GPIOF, 4, MODE_ANALOG); - set_gpio_mode(GPIOC, 0, MODE_ANALOG); - set_gpio_mode(GPIOC, 1, MODE_ANALOG); - - // Header pins - set_gpio_mode(GPIOG, 0, MODE_OUTPUT); - set_gpio_mode(GPIOG, 1, MODE_OUTPUT); - set_gpio_mode(GPIOG, 2, MODE_OUTPUT); - set_gpio_mode(GPIOG, 3, MODE_OUTPUT); - set_gpio_mode(GPIOG, 4, MODE_OUTPUT); - set_gpio_mode(GPIOG, 5, MODE_OUTPUT); - set_gpio_mode(GPIOG, 6, MODE_OUTPUT); - set_gpio_mode(GPIOG, 7, MODE_OUTPUT); -} - -void board_v2_tick(void) {} - -const board board_v2 = { - .has_canfd = true, - .has_sbu_sense = true, - .avdd_mV = 3300U, - .init = &board_v2_init, - .set_led = &board_v2_set_led, - .board_tick = &board_v2_tick, - .get_button = &board_v2_get_button, - .set_panda_power = &board_v2_set_panda_power, - .set_panda_individual_power = &board_v2_set_panda_individual_power, - .set_ignition = &board_v2_set_ignition, - .set_individual_ignition = &board_v2_set_individual_ignition, - .set_harness_orientation = &board_v2_set_harness_orientation, - .set_can_mode = &board_v2_set_can_mode, - .enable_can_transciever = &board_v2_enable_can_transciever, - .enable_header_pin = &board_v2_enable_header_pin, - .get_channel_power = &board_v2_get_channel_power, - .get_sbu_mV = &board_v2_get_sbu_mV, -}; diff --git a/panda/board/jungle/jungle_health.h b/panda/board/jungle/jungle_health.h deleted file mode 100644 index 931ed37..0000000 --- a/panda/board/jungle/jungle_health.h +++ /dev/null @@ -1,24 +0,0 @@ -// When changing these structs, python/__init__.py needs to be kept up to date! - -#define JUNGLE_HEALTH_PACKET_VERSION 1 -struct __attribute__((packed)) jungle_health_t { - uint32_t uptime_pkt; - float ch1_power; - float ch2_power; - float ch3_power; - float ch4_power; - float ch5_power; - float ch6_power; - uint16_t ch1_sbu1_mV; - uint16_t ch1_sbu2_mV; - uint16_t ch2_sbu1_mV; - uint16_t ch2_sbu2_mV; - uint16_t ch3_sbu1_mV; - uint16_t ch3_sbu2_mV; - uint16_t ch4_sbu1_mV; - uint16_t ch4_sbu2_mV; - uint16_t ch5_sbu1_mV; - uint16_t ch5_sbu2_mV; - uint16_t ch6_sbu1_mV; - uint16_t ch6_sbu2_mV; -}; diff --git a/panda/board/jungle/main_comms.h b/panda/board/jungle/main_comms.h deleted file mode 100644 index 928c554..0000000 --- a/panda/board/jungle/main_comms.h +++ /dev/null @@ -1,261 +0,0 @@ -extern int _app_start[0xc000]; // Only first 3 sectors of size 0x4000 are used - -int get_jungle_health_pkt(void *dat) { - COMPILE_TIME_ASSERT(sizeof(struct jungle_health_t) <= USBPACKET_MAX_SIZE); - struct jungle_health_t * health = (struct jungle_health_t*)dat; - - health->uptime_pkt = uptime_cnt; - health->ch1_power = current_board->get_channel_power(1U); - health->ch2_power = current_board->get_channel_power(2U); - health->ch3_power = current_board->get_channel_power(3U); - health->ch4_power = current_board->get_channel_power(4U); - health->ch5_power = current_board->get_channel_power(5U); - health->ch6_power = current_board->get_channel_power(6U); - - health->ch1_sbu1_mV = current_board->get_sbu_mV(1U, SBU1); - health->ch1_sbu2_mV = current_board->get_sbu_mV(1U, SBU2); - health->ch2_sbu1_mV = current_board->get_sbu_mV(2U, SBU1); - health->ch2_sbu2_mV = current_board->get_sbu_mV(2U, SBU2); - health->ch3_sbu1_mV = current_board->get_sbu_mV(3U, SBU1); - health->ch3_sbu2_mV = current_board->get_sbu_mV(3U, SBU2); - health->ch4_sbu1_mV = current_board->get_sbu_mV(4U, SBU1); - health->ch4_sbu2_mV = current_board->get_sbu_mV(4U, SBU2); - health->ch5_sbu1_mV = current_board->get_sbu_mV(5U, SBU1); - health->ch5_sbu2_mV = current_board->get_sbu_mV(5U, SBU2); - health->ch6_sbu1_mV = current_board->get_sbu_mV(6U, SBU1); - health->ch6_sbu2_mV = current_board->get_sbu_mV(6U, SBU2); - - return sizeof(*health); -} - -// send on serial, first byte to select the ring -void comms_endpoint2_write(const uint8_t *data, uint32_t len) { - UNUSED(data); - UNUSED(len); -} - -int comms_control_handler(ControlPacket_t *req, uint8_t *resp) { - unsigned int resp_len = 0; - uint32_t time; - -#ifdef DEBUG_COMMS - print("raw control request: "); hexdump(req, sizeof(ControlPacket_t)); print("\n"); - print("- request "); puth(req->request); print("\n"); - print("- param1 "); puth(req->param1); print("\n"); - print("- param2 "); puth(req->param2); print("\n"); -#endif - - switch (req->request) { - // **** 0xa0: Set panda power. - case 0xa0: - current_board->set_panda_power((req->param1 == 1U)); - break; - // **** 0xa1: Set harness orientation. - case 0xa1: - current_board->set_harness_orientation(req->param1); - break; - // **** 0xa2: Set ignition. - case 0xa2: - current_board->set_ignition((req->param1 == 1U)); - break; - // **** 0xa0: Set panda power per channel by bitmask. - case 0xa3: - current_board->set_panda_individual_power(req->param1, (req->param2 > 0U)); - break; - // **** 0xa8: get microsecond timer - case 0xa8: - time = microsecond_timer_get(); - resp[0] = (time & 0x000000FFU); - resp[1] = ((time & 0x0000FF00U) >> 8U); - resp[2] = ((time & 0x00FF0000U) >> 16U); - resp[3] = ((time & 0xFF000000U) >> 24U); - resp_len = 4U; - break; - // **** 0xc0: reset communications - case 0xc0: - comms_can_reset(); - break; - // **** 0xc1: get hardware type - case 0xc1: - resp[0] = hw_type; - resp_len = 1; - break; - // **** 0xc2: CAN health stats - case 0xc2: - COMPILE_TIME_ASSERT(sizeof(can_health_t) <= USBPACKET_MAX_SIZE); - if (req->param1 < 3U) { - update_can_health_pkt(req->param1, 0U); - can_health[req->param1].can_speed = (bus_config[req->param1].can_speed / 10U); - can_health[req->param1].can_data_speed = (bus_config[req->param1].can_data_speed / 10U); - can_health[req->param1].canfd_enabled = bus_config[req->param1].canfd_enabled; - can_health[req->param1].brs_enabled = bus_config[req->param1].brs_enabled; - can_health[req->param1].canfd_non_iso = bus_config[req->param1].canfd_non_iso; - resp_len = sizeof(can_health[req->param1]); - (void)memcpy(resp, &can_health[req->param1], resp_len); - } - break; - // **** 0xc3: fetch MCU UID - case 0xc3: - (void)memcpy(resp, ((uint8_t *)UID_BASE), 12); - resp_len = 12; - break; - // **** 0xd0: fetch serial (aka the provisioned dongle ID) - case 0xd0: - // addresses are OTP - if (req->param1 == 1U) { - (void)memcpy(resp, (uint8_t *)DEVICE_SERIAL_NUMBER_ADDRESS, 0x10); - resp_len = 0x10; - } else { - get_provision_chunk(resp); - resp_len = PROVISION_CHUNK_LEN; - } - break; - // **** 0xd1: enter bootloader mode - case 0xd1: - // this allows reflashing of the bootstub - switch (req->param1) { - case 0: - // only allow bootloader entry on debug builds - #ifdef ALLOW_DEBUG - print("-> entering bootloader\n"); - enter_bootloader_mode = ENTER_BOOTLOADER_MAGIC; - NVIC_SystemReset(); - #endif - break; - case 1: - print("-> entering softloader\n"); - enter_bootloader_mode = ENTER_SOFTLOADER_MAGIC; - NVIC_SystemReset(); - break; - default: - print("Bootloader mode invalid\n"); - break; - } - break; - // **** 0xd2: get health packet - case 0xd2: - resp_len = get_jungle_health_pkt(resp); - break; - // **** 0xd3: get first 64 bytes of signature - case 0xd3: - { - resp_len = 64; - char * code = (char*)_app_start; - int code_len = _app_start[0]; - (void)memcpy(resp, &code[code_len], resp_len); - } - break; - // **** 0xd4: get second 64 bytes of signature - case 0xd4: - { - resp_len = 64; - char * code = (char*)_app_start; - int code_len = _app_start[0]; - (void)memcpy(resp, &code[code_len + 64], resp_len); - } - break; - // **** 0xd6: get version - case 0xd6: - COMPILE_TIME_ASSERT(sizeof(gitversion) <= USBPACKET_MAX_SIZE); - (void)memcpy(resp, gitversion, sizeof(gitversion)); - resp_len = sizeof(gitversion) - 1U; - break; - // **** 0xd8: reset ST - case 0xd8: - NVIC_SystemReset(); - break; - // **** 0xdb: set OBD CAN multiplexing mode - case 0xdb: - if (req->param1 == 1U) { - // Enable OBD CAN - current_board->set_can_mode(CAN_MODE_OBD_CAN2); - } else { - // Disable OBD CAN - current_board->set_can_mode(CAN_MODE_NORMAL); - } - break; - // **** 0xdd: get healthpacket and CANPacket versions - case 0xdd: - resp[0] = JUNGLE_HEALTH_PACKET_VERSION; - resp[1] = CAN_PACKET_VERSION; - resp[2] = CAN_HEALTH_PACKET_VERSION; - resp_len = 3; - break; - // **** 0xde: set can bitrate - case 0xde: - if ((req->param1 < PANDA_BUS_CNT) && is_speed_valid(req->param2, speeds, sizeof(speeds)/sizeof(speeds[0]))) { - bus_config[req->param1].can_speed = req->param2; - bool ret = can_init(CAN_NUM_FROM_BUS_NUM(req->param1)); - UNUSED(ret); - } - break; - // **** 0xe0: debug read - case 0xe0: - // read - while ((resp_len < MIN(req->length, USBPACKET_MAX_SIZE)) && get_char(get_ring_by_number(0), (char*)&resp[resp_len])) { - ++resp_len; - } - break; - // **** 0xe5: set CAN loopback (for testing) - case 0xe5: - can_loopback = (req->param1 > 0U); - can_init_all(); - break; - // **** 0xf1: Clear CAN ring buffer. - case 0xf1: - if (req->param1 == 0xFFFFU) { - print("Clearing CAN Rx queue\n"); - can_clear(&can_rx_q); - } else if (req->param1 < PANDA_BUS_CNT) { - print("Clearing CAN Tx queue\n"); - can_clear(can_queues[req->param1]); - } else { - print("Clearing CAN CAN ring buffer failed: wrong bus number\n"); - } - break; - // **** 0xf2: Clear debug ring buffer. - case 0xf2: - print("Clearing debug queue.\n"); - clear_uart_buff(get_ring_by_number(0)); - break; - // **** 0xf4: Set CAN transceiver enable pin - case 0xf4: - current_board->enable_can_transciever(req->param1, req->param2 > 0U); - break; - // **** 0xf5: Set CAN silent mode - case 0xf5: - can_silent = (req->param1 > 0U) ? ALL_CAN_SILENT : ALL_CAN_LIVE; - can_init_all(); - break; - // **** 0xf7: enable/disable header pin by number - case 0xf7: - current_board->enable_header_pin(req->param1, req->param2 > 0U); - break; - // **** 0xf9: set CAN FD data bitrate - case 0xf9: - if ((req->param1 < PANDA_CAN_CNT) && - current_board->has_canfd && - is_speed_valid(req->param2, data_speeds, sizeof(data_speeds)/sizeof(data_speeds[0]))) { - bus_config[req->param1].can_data_speed = req->param2; - bus_config[req->param1].canfd_enabled = (req->param2 >= bus_config[req->param1].can_speed); - bus_config[req->param1].brs_enabled = (req->param2 > bus_config[req->param1].can_speed); - bool ret = can_init(CAN_NUM_FROM_BUS_NUM(req->param1)); - UNUSED(ret); - } - break; - // **** 0xfc: set CAN FD non-ISO mode - case 0xfc: - if ((req->param1 < PANDA_CAN_CNT) && current_board->has_canfd) { - bus_config[req->param1].canfd_non_iso = (req->param2 != 0U); - bool ret = can_init(CAN_NUM_FROM_BUS_NUM(req->param1)); - UNUSED(ret); - } - break; - default: - print("NO HANDLER "); - puth(req->request); - print("\n"); - break; - } - return resp_len; -} diff --git a/panda/board/jungle/obj/bootstub.panda_jungle.bin b/panda/board/jungle/obj/bootstub.panda_jungle.bin new file mode 100755 index 0000000..221d1cf Binary files /dev/null and b/panda/board/jungle/obj/bootstub.panda_jungle.bin differ diff --git a/panda/board/jungle/obj/bootstub.panda_jungle.elf b/panda/board/jungle/obj/bootstub.panda_jungle.elf new file mode 100755 index 0000000..028138a Binary files /dev/null and b/panda/board/jungle/obj/bootstub.panda_jungle.elf differ diff --git a/panda/board/jungle/obj/bootstub.panda_jungle_h7.bin b/panda/board/jungle/obj/bootstub.panda_jungle_h7.bin new file mode 100755 index 0000000..0a384d2 Binary files /dev/null and b/panda/board/jungle/obj/bootstub.panda_jungle_h7.bin differ diff --git a/panda/board/jungle/obj/bootstub.panda_jungle_h7.elf b/panda/board/jungle/obj/bootstub.panda_jungle_h7.elf new file mode 100755 index 0000000..6b1b6ea Binary files /dev/null and b/panda/board/jungle/obj/bootstub.panda_jungle_h7.elf differ diff --git a/panda/board/jungle/obj/panda_jungle.bin b/panda/board/jungle/obj/panda_jungle.bin new file mode 100755 index 0000000..e10d780 Binary files /dev/null and b/panda/board/jungle/obj/panda_jungle.bin differ diff --git a/panda/board/jungle/obj/panda_jungle.bin.signed b/panda/board/jungle/obj/panda_jungle.bin.signed new file mode 100644 index 0000000..d1d7722 Binary files /dev/null and b/panda/board/jungle/obj/panda_jungle.bin.signed differ diff --git a/panda/board/jungle/obj/panda_jungle.elf b/panda/board/jungle/obj/panda_jungle.elf new file mode 100755 index 0000000..4d7038a Binary files /dev/null and b/panda/board/jungle/obj/panda_jungle.elf differ diff --git a/panda/board/jungle/obj/panda_jungle_h7.bin b/panda/board/jungle/obj/panda_jungle_h7.bin new file mode 100755 index 0000000..294d67d Binary files /dev/null and b/panda/board/jungle/obj/panda_jungle_h7.bin differ diff --git a/panda/board/jungle/obj/panda_jungle_h7.bin.signed b/panda/board/jungle/obj/panda_jungle_h7.bin.signed new file mode 100644 index 0000000..c0b3843 Binary files /dev/null and b/panda/board/jungle/obj/panda_jungle_h7.bin.signed differ diff --git a/panda/board/jungle/obj/panda_jungle_h7.elf b/panda/board/jungle/obj/panda_jungle_h7.elf new file mode 100755 index 0000000..3b321b6 Binary files /dev/null and b/panda/board/jungle/obj/panda_jungle_h7.elf differ diff --git a/panda/board/jungle/stm32fx/board.h b/panda/board/jungle/stm32fx/board.h deleted file mode 100644 index 0adf792..0000000 --- a/panda/board/jungle/stm32fx/board.h +++ /dev/null @@ -1,7 +0,0 @@ -#include "boards/board_declarations.h" -#include "boards/board_v1.h" - -void detect_board_type(void) { - hw_type = HW_TYPE_V1; - current_board = &board_v1; -} diff --git a/panda/board/jungle/stm32h7/board.h b/panda/board/jungle/stm32h7/board.h deleted file mode 100644 index 4fe4fa4..0000000 --- a/panda/board/jungle/stm32h7/board.h +++ /dev/null @@ -1,9 +0,0 @@ -#include "boards/board_declarations.h" - -#include "stm32h7/lladc.h" -#include "boards/board_v2.h" - -void detect_board_type(void) { - hw_type = HW_TYPE_V2; - current_board = &board_v2; -} diff --git a/panda/board/jungle/stm32h7/lladc.h b/panda/board/jungle/stm32h7/lladc.h deleted file mode 100644 index 06b742d..0000000 --- a/panda/board/jungle/stm32h7/lladc.h +++ /dev/null @@ -1,54 +0,0 @@ - -typedef struct { - ADC_TypeDef *adc; - uint8_t channel; -} adc_channel_t; - -void adc_init(ADC_TypeDef *adc) { - adc->CR &= ~(ADC_CR_DEEPPWD); // Reset deep-power-down mode - adc->CR |= ADC_CR_ADVREGEN; // Enable ADC regulator - while(!(adc->ISR & ADC_ISR_LDORDY) && (adc != ADC3)); - - if (adc != ADC3) { - adc->CR &= ~(ADC_CR_ADCALDIF); // Choose single-ended calibration - adc->CR |= ADC_CR_ADCALLIN; // Lineriality calibration - } - adc->CR |= ADC_CR_ADCAL; // Start calibrtation - while((adc->CR & ADC_CR_ADCAL) != 0); - - adc->ISR |= ADC_ISR_ADRDY; - adc->CR |= ADC_CR_ADEN; - while(!(adc->ISR & ADC_ISR_ADRDY)); -} - -uint16_t adc_get_raw(ADC_TypeDef *adc, uint8_t channel) { - adc->SQR1 &= ~(ADC_SQR1_L); - adc->SQR1 = ((uint32_t) channel << 6U); - - if (channel < 10U) { - adc->SMPR1 = (0x7U << (channel * 3U)); - } else { - adc->SMPR2 = (0x7U << ((channel - 10U) * 3U)); - } - adc->PCSEL_RES0 = (0x1U << channel); - - adc->CR |= ADC_CR_ADSTART; - while (!(adc->ISR & ADC_ISR_EOC)); - - uint16_t res = adc->DR; - - while (!(adc->ISR & ADC_ISR_EOS)); - adc->ISR |= ADC_ISR_EOS; - - return res; -} - -uint16_t adc_get_mV(ADC_TypeDef *adc, uint8_t channel) { - uint16_t ret = 0; - if ((adc == ADC1) || (adc == ADC2)) { - ret = (adc_get_raw(adc, channel) * current_board->avdd_mV) / 65535U; - } else if (adc == ADC3) { - ret = (adc_get_raw(adc, channel) * current_board->avdd_mV) / 4095U; - } else {} - return ret; -} diff --git a/panda/board/libc.h b/panda/board/libc.h deleted file mode 100644 index 7f669b9..0000000 --- a/panda/board/libc.h +++ /dev/null @@ -1,67 +0,0 @@ -// **** libc **** - -void delay(uint32_t a) { - volatile uint32_t i; - for (i = 0; i < a; i++); -} - -// cppcheck-suppress misra-c2012-21.2 -void *memset(void *str, int c, unsigned int n) { - uint8_t *s = str; - for (unsigned int i = 0; i < n; i++) { - *s = c; - s++; - } - return str; -} - -#define UNALIGNED(X, Y) \ - (((uint32_t)(X) & (sizeof(uint32_t) - 1U)) | ((uint32_t)(Y) & (sizeof(uint32_t) - 1U))) - -// cppcheck-suppress misra-c2012-21.2 -void *memcpy(void *dest, const void *src, unsigned int len) { - unsigned int n = len; - uint8_t *d8 = dest; - const uint8_t *s8 = src; - - if ((n >= 4U) && !UNALIGNED(s8, d8)) { - uint32_t *d32 = (uint32_t *)d8; // cppcheck-suppress misra-c2012-11.3 ; already checked that it's properly aligned - const uint32_t *s32 = (const uint32_t *)s8; // cppcheck-suppress misra-c2012-11.3 ; already checked that it's properly aligned - - while(n >= 16U) { - *d32 = *s32; d32++; s32++; - *d32 = *s32; d32++; s32++; - *d32 = *s32; d32++; s32++; - *d32 = *s32; d32++; s32++; - n -= 16U; - } - - while(n >= 4U) { - *d32 = *s32; d32++; s32++; - n -= 4U; - } - - d8 = (uint8_t *)d32; - s8 = (const uint8_t *)s32; - } - while (n-- > 0U) { - *d8 = *s8; d8++; s8++; - } - return dest; -} - -// cppcheck-suppress misra-c2012-21.2 -int memcmp(const void * ptr1, const void * ptr2, unsigned int num) { - int ret = 0; - const uint8_t *p1 = ptr1; - const uint8_t *p2 = ptr2; - for (unsigned int i = 0; i < num; i++) { - if (*p1 != *p2) { - ret = -1; - break; - } - p1++; - p2++; - } - return ret; -} diff --git a/panda/board/main_comms.h b/panda/board/main_comms.h deleted file mode 100644 index c0d5c51..0000000 --- a/panda/board/main_comms.h +++ /dev/null @@ -1,450 +0,0 @@ -extern int _app_start[0xc000]; // Only first 3 sectors of size 0x4000 are used - -// Prototypes -void set_safety_mode(uint16_t mode, uint16_t param); -bool is_car_safety_mode(uint16_t mode); - -int get_health_pkt(void *dat) { - COMPILE_TIME_ASSERT(sizeof(struct health_t) <= USBPACKET_MAX_SIZE); - struct health_t * health = (struct health_t*)dat; - - health->uptime_pkt = uptime_cnt; - health->voltage_pkt = current_board->read_voltage_mV(); - health->current_pkt = current_board->read_current_mA(); - - // Use the GPIO pin to determine ignition or use a CAN based logic - health->ignition_line_pkt = (uint8_t)(current_board->check_ignition()); - health->ignition_can_pkt = ignition_can; - - health->controls_allowed_pkt = controls_allowed; - health->safety_tx_blocked_pkt = safety_tx_blocked; - health->safety_rx_invalid_pkt = safety_rx_invalid; - health->tx_buffer_overflow_pkt = tx_buffer_overflow; - health->rx_buffer_overflow_pkt = rx_buffer_overflow; - health->gmlan_send_errs_pkt = gmlan_send_errs; - health->car_harness_status_pkt = harness.status; - health->safety_mode_pkt = (uint8_t)(current_safety_mode); - health->safety_param_pkt = current_safety_param; - health->alternative_experience_pkt = alternative_experience; - health->power_save_enabled_pkt = power_save_status == POWER_SAVE_STATUS_ENABLED; - health->heartbeat_lost_pkt = heartbeat_lost; - health->safety_rx_checks_invalid_pkt = safety_rx_checks_invalid; - - health->spi_checksum_error_count_pkt = spi_checksum_error_count; - - health->fault_status_pkt = fault_status; - health->faults_pkt = faults; - - health->interrupt_load_pkt = interrupt_load; - - health->fan_power = fan_state.power; - health->fan_stall_count = fan_state.total_stall_count; - - health->sbu1_voltage_mV = harness.sbu1_voltage_mV; - health->sbu2_voltage_mV = harness.sbu2_voltage_mV; - - health->som_reset_triggered = bootkick_reset_triggered; - - return sizeof(*health); -} - -int get_rtc_pkt(void *dat) { - timestamp_t t = rtc_get_time(); - (void)memcpy(dat, &t, sizeof(t)); - return sizeof(t); -} - -// send on serial, first byte to select the ring -void comms_endpoint2_write(const uint8_t *data, uint32_t len) { - uart_ring *ur = get_ring_by_number(data[0]); - if ((len != 0U) && (ur != NULL)) { - if ((data[0] < 2U) || (data[0] >= 4U)) { - for (uint32_t i = 1; i < len; i++) { - while (!put_char(ur, data[i])) { - // wait - } - } - } - } -} - -int comms_control_handler(ControlPacket_t *req, uint8_t *resp) { - unsigned int resp_len = 0; - uart_ring *ur = NULL; - timestamp_t t; - uint32_t time; - -#ifdef DEBUG_COMMS - print("raw control request: "); hexdump(req, sizeof(ControlPacket_t)); print("\n"); - print("- request "); puth(req->request); print("\n"); - print("- param1 "); puth(req->param1); print("\n"); - print("- param2 "); puth(req->param2); print("\n"); -#endif - - switch (req->request) { - // **** 0xa0: get rtc time - case 0xa0: - resp_len = get_rtc_pkt(resp); - break; - // **** 0xa1: set rtc year - case 0xa1: - t = rtc_get_time(); - t.year = req->param1; - rtc_set_time(t); - break; - // **** 0xa2: set rtc month - case 0xa2: - t = rtc_get_time(); - t.month = req->param1; - rtc_set_time(t); - break; - // **** 0xa3: set rtc day - case 0xa3: - t = rtc_get_time(); - t.day = req->param1; - rtc_set_time(t); - break; - // **** 0xa4: set rtc weekday - case 0xa4: - t = rtc_get_time(); - t.weekday = req->param1; - rtc_set_time(t); - break; - // **** 0xa5: set rtc hour - case 0xa5: - t = rtc_get_time(); - t.hour = req->param1; - rtc_set_time(t); - break; - // **** 0xa6: set rtc minute - case 0xa6: - t = rtc_get_time(); - t.minute = req->param1; - rtc_set_time(t); - break; - // **** 0xa7: set rtc second - case 0xa7: - t = rtc_get_time(); - t.second = req->param1; - rtc_set_time(t); - break; - // **** 0xa8: get microsecond timer - case 0xa8: - time = microsecond_timer_get(); - resp[0] = (time & 0x000000FFU); - resp[1] = ((time & 0x0000FF00U) >> 8U); - resp[2] = ((time & 0x00FF0000U) >> 16U); - resp[3] = ((time & 0xFF000000U) >> 24U); - resp_len = 4U; - break; - // **** 0xb0: set IR power - case 0xb0: - current_board->set_ir_power(req->param1); - break; - // **** 0xb1: set fan power - case 0xb1: - fan_set_power(req->param1); - break; - // **** 0xb2: get fan rpm - case 0xb2: - resp[0] = (fan_state.rpm & 0x00FFU); - resp[1] = ((fan_state.rpm & 0xFF00U) >> 8U); - resp_len = 2; - break; - // **** 0xc0: reset communications - case 0xc0: - comms_can_reset(); - break; - // **** 0xc1: get hardware type - case 0xc1: - resp[0] = hw_type; - resp_len = 1; - break; - // **** 0xc2: CAN health stats - case 0xc2: - COMPILE_TIME_ASSERT(sizeof(can_health_t) <= USBPACKET_MAX_SIZE); - if (req->param1 < 3U) { - update_can_health_pkt(req->param1, 0U); - can_health[req->param1].can_speed = (bus_config[req->param1].can_speed / 10U); - can_health[req->param1].can_data_speed = (bus_config[req->param1].can_data_speed / 10U); - can_health[req->param1].canfd_enabled = bus_config[req->param1].canfd_enabled; - can_health[req->param1].brs_enabled = bus_config[req->param1].brs_enabled; - can_health[req->param1].canfd_non_iso = bus_config[req->param1].canfd_non_iso; - resp_len = sizeof(can_health[req->param1]); - (void)memcpy(resp, &can_health[req->param1], resp_len); - } - break; - // **** 0xc3: fetch MCU UID - case 0xc3: - (void)memcpy(resp, ((uint8_t *)UID_BASE), 12); - resp_len = 12; - break; - // **** 0xc4: get interrupt call rate - case 0xc4: - if (req->param1 < NUM_INTERRUPTS) { - uint32_t load = interrupts[req->param1].call_rate; - resp[0] = (load & 0x000000FFU); - resp[1] = ((load & 0x0000FF00U) >> 8U); - resp[2] = ((load & 0x00FF0000U) >> 16U); - resp[3] = ((load & 0xFF000000U) >> 24U); - resp_len = 4U; - } - break; - // **** 0xc5: DEBUG: drive relay - case 0xc5: - set_intercept_relay((req->param1 & 0x1U), (req->param1 & 0x2U)); - break; - // **** 0xc6: DEBUG: read SOM GPIO - case 0xc6: - resp[0] = current_board->read_som_gpio(); - resp_len = 1; - break; - // **** 0xd0: fetch serial (aka the provisioned dongle ID) - case 0xd0: - // addresses are OTP - if (req->param1 == 1U) { - (void)memcpy(resp, (uint8_t *)DEVICE_SERIAL_NUMBER_ADDRESS, 0x10); - resp_len = 0x10; - } else { - get_provision_chunk(resp); - resp_len = PROVISION_CHUNK_LEN; - } - break; - // **** 0xd1: enter bootloader mode - case 0xd1: - // this allows reflashing of the bootstub - switch (req->param1) { - case 0: - // only allow bootloader entry on debug builds - #ifdef ALLOW_DEBUG - print("-> entering bootloader\n"); - enter_bootloader_mode = ENTER_BOOTLOADER_MAGIC; - NVIC_SystemReset(); - #endif - break; - case 1: - print("-> entering softloader\n"); - enter_bootloader_mode = ENTER_SOFTLOADER_MAGIC; - NVIC_SystemReset(); - break; - default: - print("Bootloader mode invalid\n"); - break; - } - break; - // **** 0xd2: get health packet - case 0xd2: - resp_len = get_health_pkt(resp); - break; - // **** 0xd3: get first 64 bytes of signature - case 0xd3: - { - resp_len = 64; - char * code = (char*)_app_start; - int code_len = _app_start[0]; - (void)memcpy(resp, &code[code_len], resp_len); - } - break; - // **** 0xd4: get second 64 bytes of signature - case 0xd4: - { - resp_len = 64; - char * code = (char*)_app_start; - int code_len = _app_start[0]; - (void)memcpy(resp, &code[code_len + 64], resp_len); - } - break; - // **** 0xd6: get version - case 0xd6: - COMPILE_TIME_ASSERT(sizeof(gitversion) <= USBPACKET_MAX_SIZE); - (void)memcpy(resp, gitversion, sizeof(gitversion)); - resp_len = sizeof(gitversion) - 1U; - break; - // **** 0xd8: reset ST - case 0xd8: - NVIC_SystemReset(); - break; - // **** 0xdb: set GMLAN (white/grey) or OBD CAN (black) multiplexing mode - case 0xdb: - if(current_board->has_obd){ - if (req->param1 == 1U) { - // Enable OBD CAN - current_board->set_can_mode(CAN_MODE_OBD_CAN2); - } else { - // Disable OBD CAN - current_board->set_can_mode(CAN_MODE_NORMAL); - } - } - break; - - // **** 0xdc: set safety mode - case 0xdc: - set_safety_mode(req->param1, (uint16_t)req->param2); - break; - // **** 0xdd: get healthpacket and CANPacket versions - case 0xdd: - resp[0] = HEALTH_PACKET_VERSION; - resp[1] = CAN_PACKET_VERSION; - resp[2] = CAN_HEALTH_PACKET_VERSION; - resp_len = 3; - break; - // **** 0xde: set can bitrate - case 0xde: - if ((req->param1 < PANDA_BUS_CNT) && is_speed_valid(req->param2, speeds, sizeof(speeds)/sizeof(speeds[0]))) { - bus_config[req->param1].can_speed = req->param2; - bool ret = can_init(CAN_NUM_FROM_BUS_NUM(req->param1)); - UNUSED(ret); - } - break; - // **** 0xdf: set alternative experience - case 0xdf: - // you can only set this if you are in a non car safety mode - if (!is_car_safety_mode(current_safety_mode)) { - alternative_experience = req->param1; - } - break; - // **** 0xe0: uart read - case 0xe0: - ur = get_ring_by_number(req->param1); - if (!ur) { - break; - } - - // read - uint16_t req_length = MIN(req->length, USBPACKET_MAX_SIZE); - while ((resp_len < req_length) && - get_char(ur, (char*)&resp[resp_len])) { - ++resp_len; - } - break; - // **** 0xe1: uart set baud rate - case 0xe1: - ur = get_ring_by_number(req->param1); - if (!ur) { - break; - } - uart_set_baud(ur->uart, req->param2); - break; - // **** 0xe2: uart set parity - case 0xe2: - ur = get_ring_by_number(req->param1); - if (!ur) { - break; - } - switch (req->param2) { - case 0: - // disable parity, 8-bit - ur->uart->CR1 &= ~(USART_CR1_PCE | USART_CR1_M); - break; - case 1: - // even parity, 9-bit - ur->uart->CR1 &= ~USART_CR1_PS; - ur->uart->CR1 |= USART_CR1_PCE | USART_CR1_M; - break; - case 2: - // odd parity, 9-bit - ur->uart->CR1 |= USART_CR1_PS; - ur->uart->CR1 |= USART_CR1_PCE | USART_CR1_M; - break; - default: - break; - } - break; - // **** 0xe4: uart set baud rate extended - case 0xe4: - ur = get_ring_by_number(req->param1); - if (!ur) { - break; - } - uart_set_baud(ur->uart, (int)req->param2*300); - break; - // **** 0xe5: set CAN loopback (for testing) - case 0xe5: - can_loopback = req->param1 > 0U; - can_init_all(); - break; - // **** 0xe6: set custom clock source period - case 0xe6: - clock_source_set_period(req->param1); - break; - // **** 0xe7: set power save state - case 0xe7: - set_power_save_state(req->param1); - break; - // **** 0xf1: Clear CAN ring buffer. - case 0xf1: - if (req->param1 == 0xFFFFU) { - print("Clearing CAN Rx queue\n"); - can_clear(&can_rx_q); - } else if (req->param1 < PANDA_BUS_CNT) { - print("Clearing CAN Tx queue\n"); - can_clear(can_queues[req->param1]); - } else { - print("Clearing CAN CAN ring buffer failed: wrong bus number\n"); - } - break; - // **** 0xf2: Clear UART ring buffer. - case 0xf2: - { - uart_ring * rb = get_ring_by_number(req->param1); - if (rb != NULL) { - print("Clearing UART queue.\n"); - clear_uart_buff(rb); - } - break; - } - // **** 0xf3: Heartbeat. Resets heartbeat counter. - case 0xf3: - { - heartbeat_counter = 0U; - heartbeat_lost = false; - heartbeat_disabled = false; - heartbeat_engaged = (req->param1 == 1U); - break; - } - // **** 0xf6: set siren enabled - case 0xf6: - siren_enabled = (req->param1 != 0U); - break; - // **** 0xf7: set green led enabled - case 0xf7: - green_led_enabled = (req->param1 != 0U); - break; - // **** 0xf8: disable heartbeat checks - case 0xf8: - if (!is_car_safety_mode(current_safety_mode)) { - heartbeat_disabled = true; - } - break; - // **** 0xf9: set CAN FD data bitrate - case 0xf9: - if ((req->param1 < PANDA_CAN_CNT) && - current_board->has_canfd && - is_speed_valid(req->param2, data_speeds, sizeof(data_speeds)/sizeof(data_speeds[0]))) { - bus_config[req->param1].can_data_speed = req->param2; - bus_config[req->param1].canfd_enabled = (req->param2 >= bus_config[req->param1].can_speed); - bus_config[req->param1].brs_enabled = (req->param2 > bus_config[req->param1].can_speed); - bool ret = can_init(CAN_NUM_FROM_BUS_NUM(req->param1)); - UNUSED(ret); - } - break; - // **** 0xfb: allow highest power saving mode (stop) to be entered - case 0xfb: - deepsleep_allowed = true; - break; - // **** 0xfc: set CAN FD non-ISO mode - case 0xfc: - if ((req->param1 < PANDA_CAN_CNT) && current_board->has_canfd) { - bus_config[req->param1].canfd_non_iso = (req->param2 != 0U); - bool ret = can_init(CAN_NUM_FROM_BUS_NUM(req->param1)); - UNUSED(ret); - } - break; - default: - print("NO HANDLER "); - puth(req->request); - print("\n"); - break; - } - return resp_len; -} diff --git a/panda/board/main_declarations.h b/panda/board/main_declarations.h deleted file mode 100644 index 4570c6e..0000000 --- a/panda/board/main_declarations.h +++ /dev/null @@ -1,32 +0,0 @@ -// ******************** Prototypes ******************** -void print(const char *a); -void puth(unsigned int i); -void puth2(unsigned int i); -void puth4(unsigned int i); -void hexdump(const void *a, int l); -typedef struct board board; -typedef struct harness_configuration harness_configuration; -void can_flip_buses(uint8_t bus1, uint8_t bus2); -void pwm_init(TIM_TypeDef *TIM, uint8_t channel); -void pwm_set(TIM_TypeDef *TIM, uint8_t channel, uint8_t percentage); - -// ********************* Globals ********************** -uint8_t hw_type = 0; -const board *current_board; -uint32_t uptime_cnt = 0; -bool green_led_enabled = false; - -// heartbeat state -uint32_t heartbeat_counter = 0; -bool heartbeat_lost = false; -bool heartbeat_disabled = false; // set over USB - -// Enter deep sleep mode -bool deepsleep_allowed = false; -bool ignition_seen = false; - -// siren state -bool siren_enabled = false; -uint32_t siren_countdown = 0; // siren plays while countdown > 0 -uint32_t controls_allowed_countdown = 0; - diff --git a/panda/board/obj/bootstub.panda.bin b/panda/board/obj/bootstub.panda.bin new file mode 100755 index 0000000..da63792 Binary files /dev/null and b/panda/board/obj/bootstub.panda.bin differ diff --git a/panda/board/obj/bootstub.panda.elf b/panda/board/obj/bootstub.panda.elf new file mode 100755 index 0000000..1bb22b8 Binary files /dev/null and b/panda/board/obj/bootstub.panda.elf differ diff --git a/panda/board/obj/bootstub.panda_h7.bin b/panda/board/obj/bootstub.panda_h7.bin new file mode 100755 index 0000000..05ca5a6 Binary files /dev/null and b/panda/board/obj/bootstub.panda_h7.bin differ diff --git a/panda/board/obj/bootstub.panda_h7.elf b/panda/board/obj/bootstub.panda_h7.elf new file mode 100755 index 0000000..9f72756 Binary files /dev/null and b/panda/board/obj/bootstub.panda_h7.elf differ diff --git a/panda/board/obj/panda.bin b/panda/board/obj/panda.bin new file mode 100755 index 0000000..fba923c Binary files /dev/null and b/panda/board/obj/panda.bin differ diff --git a/panda/board/obj/panda.bin.signed b/panda/board/obj/panda.bin.signed new file mode 100644 index 0000000..1842ebb Binary files /dev/null and b/panda/board/obj/panda.bin.signed differ diff --git a/panda/board/obj/panda.elf b/panda/board/obj/panda.elf new file mode 100755 index 0000000..328b53d Binary files /dev/null and b/panda/board/obj/panda.elf differ diff --git a/panda/board/obj/panda_h7.bin b/panda/board/obj/panda_h7.bin new file mode 100755 index 0000000..dc62831 Binary files /dev/null and b/panda/board/obj/panda_h7.bin differ diff --git a/panda/board/obj/panda_h7.bin.signed b/panda/board/obj/panda_h7.bin.signed new file mode 100644 index 0000000..2f2f14f Binary files /dev/null and b/panda/board/obj/panda_h7.bin.signed differ diff --git a/panda/board/obj/panda_h7.elf b/panda/board/obj/panda_h7.elf new file mode 100755 index 0000000..0035d87 Binary files /dev/null and b/panda/board/obj/panda_h7.elf differ diff --git a/panda/board/obj/version b/panda/board/obj/version new file mode 100644 index 0000000..4c96b5a --- /dev/null +++ b/panda/board/obj/version @@ -0,0 +1 @@ +DEV-a165aa11-DEBUG \ No newline at end of file diff --git a/panda/board/power_saving.h b/panda/board/power_saving.h deleted file mode 100644 index 61541ca..0000000 --- a/panda/board/power_saving.h +++ /dev/null @@ -1,46 +0,0 @@ -// WARNING: To stay in compliance with the SIL2 rules laid out in STM UM1840, we should never implement any of the available hardware low power modes. -// See rule: CoU_3 - -#define POWER_SAVE_STATUS_DISABLED 0 -#define POWER_SAVE_STATUS_ENABLED 1 - -int power_save_status = POWER_SAVE_STATUS_DISABLED; - -void set_power_save_state(int state) { - - bool is_valid_state = (state == POWER_SAVE_STATUS_ENABLED) || (state == POWER_SAVE_STATUS_DISABLED); - if (is_valid_state && (state != power_save_status)) { - bool enable = false; - if (state == POWER_SAVE_STATUS_ENABLED) { - print("enable power savings\n"); - - // Disable CAN interrupts - if (harness.status == HARNESS_STATUS_FLIPPED) { - llcan_irq_disable(cans[0]); - } else { - llcan_irq_disable(cans[2]); - } - llcan_irq_disable(cans[1]); - } else { - print("disable power savings\n"); - - if (harness.status == HARNESS_STATUS_FLIPPED) { - llcan_irq_enable(cans[0]); - } else { - llcan_irq_enable(cans[2]); - } - llcan_irq_enable(cans[1]); - - enable = true; - } - - current_board->enable_can_transceivers(enable); - - // Switch off IR when in power saving - if(!enable){ - current_board->set_ir_power(0U); - } - - power_save_status = state; - } -} diff --git a/panda/board/provision.h b/panda/board/provision.h deleted file mode 100644 index 02768c9..0000000 --- a/panda/board/provision.h +++ /dev/null @@ -1,13 +0,0 @@ -// this is where we manage the dongle ID assigned during our -// manufacturing. aside from this, there's a UID for the MCU - -#define PROVISION_CHUNK_LEN 0x20 - -const char unprovisioned_text[] = "\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff\xff"; - -void get_provision_chunk(uint8_t *resp) { - (void)memcpy(resp, (uint8_t *)PROVISION_CHUNK_ADDRESS, PROVISION_CHUNK_LEN); - if (memcmp(resp, unprovisioned_text, 0x20) == 0) { - (void)memcpy(resp, "unprovisioned\x00\x00\x00testing123\x00\x00\xa3\xa6\x99\xec", 0x20); - } -} diff --git a/panda/board/safety.h b/panda/board/safety.h deleted file mode 100644 index 24ff779..0000000 --- a/panda/board/safety.h +++ /dev/null @@ -1,708 +0,0 @@ -#include "safety_declarations.h" -#include "can_definitions.h" - -// include the safety policies. -#include "safety/safety_defaults.h" -#include "safety/safety_honda.h" -#include "safety/safety_toyota.h" -#include "safety/safety_tesla.h" -#include "safety/safety_gm.h" -#include "safety/safety_ford.h" -#include "safety/safety_hyundai.h" -#include "safety/safety_chrysler.h" -#include "safety/safety_subaru.h" -#include "safety/safety_subaru_preglobal.h" -#include "safety/safety_mazda.h" -#include "safety/safety_nissan.h" -#include "safety/safety_volkswagen_mqb.h" -#include "safety/safety_volkswagen_pq.h" -#include "safety/safety_elm327.h" -#include "safety/safety_body.h" - -// CAN-FD only safety modes -#ifdef CANFD -#include "safety/safety_hyundai_canfd.h" -#endif - -// from cereal.car.CarParams.SafetyModel -#define SAFETY_SILENT 0U -#define SAFETY_HONDA_NIDEC 1U -#define SAFETY_TOYOTA 2U -#define SAFETY_ELM327 3U -#define SAFETY_GM 4U -#define SAFETY_HONDA_BOSCH_GIRAFFE 5U -#define SAFETY_FORD 6U -#define SAFETY_HYUNDAI 8U -#define SAFETY_CHRYSLER 9U -#define SAFETY_TESLA 10U -#define SAFETY_SUBARU 11U -#define SAFETY_MAZDA 13U -#define SAFETY_NISSAN 14U -#define SAFETY_VOLKSWAGEN_MQB 15U -#define SAFETY_ALLOUTPUT 17U -#define SAFETY_GM_ASCM 18U -#define SAFETY_NOOUTPUT 19U -#define SAFETY_HONDA_BOSCH 20U -#define SAFETY_VOLKSWAGEN_PQ 21U -#define SAFETY_SUBARU_PREGLOBAL 22U -#define SAFETY_HYUNDAI_LEGACY 23U -#define SAFETY_HYUNDAI_COMMUNITY 24U -#define SAFETY_STELLANTIS 25U -#define SAFETY_FAW 26U -#define SAFETY_BODY 27U -#define SAFETY_HYUNDAI_CANFD 28U - -uint16_t current_safety_mode = SAFETY_SILENT; -uint16_t current_safety_param = 0; -const safety_hooks *current_hooks = &nooutput_hooks; -safety_config current_safety_config; - -bool safety_rx_hook(const CANPacket_t *to_push) { - bool controls_allowed_prev = controls_allowed; - - bool valid = rx_msg_safety_check(to_push, ¤t_safety_config, current_hooks); - if (valid) { - current_hooks->rx(to_push); - } - - // reset mismatches on rising edge of controls_allowed to avoid rare race condition - if (controls_allowed && !controls_allowed_prev) { - heartbeat_engaged_mismatches = 0; - } - - return valid; -} - -bool safety_tx_hook(CANPacket_t *to_send) { - bool whitelisted = msg_allowed(to_send, current_safety_config.tx_msgs, current_safety_config.tx_msgs_len); - if ((current_safety_mode == SAFETY_ALLOUTPUT) || (current_safety_mode == SAFETY_ELM327)) { - whitelisted = true; - } - - const bool safety_allowed = current_hooks->tx(to_send); - return !relay_malfunction && whitelisted && safety_allowed; -} - -int safety_fwd_hook(int bus_num, int addr) { - return (relay_malfunction ? -1 : current_hooks->fwd(bus_num, addr)); -} - -bool get_longitudinal_allowed(void) { - return controls_allowed && !gas_pressed_prev; -} - -// Given a CRC-8 poly, generate a static lookup table to use with a fast CRC-8 -// algorithm. Called at init time for safety modes using CRC-8. -void gen_crc_lookup_table_8(uint8_t poly, uint8_t crc_lut[]) { - for (uint16_t i = 0U; i <= 0xFFU; i++) { - uint8_t crc = (uint8_t)i; - for (int j = 0; j < 8; j++) { - if ((crc & 0x80U) != 0U) { - crc = (uint8_t)((crc << 1) ^ poly); - } else { - crc <<= 1; - } - } - crc_lut[i] = crc; - } -} - -void gen_crc_lookup_table_16(uint16_t poly, uint16_t crc_lut[]) { - for (uint16_t i = 0; i < 256U; i++) { - uint16_t crc = i << 8U; - for (uint16_t j = 0; j < 8U; j++) { - if ((crc & 0x8000U) != 0U) { - crc = (uint16_t)((crc << 1) ^ poly); - } else { - crc <<= 1; - } - } - crc_lut[i] = crc; - } -} - -bool msg_allowed(const CANPacket_t *to_send, const CanMsg msg_list[], int len) { - int addr = GET_ADDR(to_send); - int bus = GET_BUS(to_send); - int length = GET_LEN(to_send); - - bool allowed = false; - for (int i = 0; i < len; i++) { - if ((addr == msg_list[i].addr) && (bus == msg_list[i].bus) && (length == msg_list[i].len)) { - allowed = true; - break; - } - } - return allowed; -} - -int get_addr_check_index(const CANPacket_t *to_push, RxCheck addr_list[], const int len) { - int bus = GET_BUS(to_push); - int addr = GET_ADDR(to_push); - int length = GET_LEN(to_push); - - int index = -1; - for (int i = 0; i < len; i++) { - // if multiple msgs are allowed, determine which one is present on the bus - if (!addr_list[i].status.msg_seen) { - for (uint8_t j = 0U; (j < MAX_ADDR_CHECK_MSGS) && (addr_list[i].msg[j].addr != 0); j++) { - if ((addr == addr_list[i].msg[j].addr) && (bus == addr_list[i].msg[j].bus) && - (length == addr_list[i].msg[j].len)) { - addr_list[i].status.index = j; - addr_list[i].status.msg_seen = true; - break; - } - } - } - - if (addr_list[i].status.msg_seen) { - int idx = addr_list[i].status.index; - if ((addr == addr_list[i].msg[idx].addr) && (bus == addr_list[i].msg[idx].bus) && - (length == addr_list[i].msg[idx].len)) { - index = i; - break; - } - } - } - return index; -} - -// 1Hz safety function called by main. Now just a check for lagging safety messages -void safety_tick(const safety_config *cfg) { - bool rx_checks_invalid = false; - uint32_t ts = microsecond_timer_get(); - if (cfg != NULL) { - for (int i=0; i < cfg->rx_checks_len; i++) { - uint32_t elapsed_time = get_ts_elapsed(ts, cfg->rx_checks[i].status.last_timestamp); - // lag threshold is max of: 1s and MAX_MISSED_MSGS * expected timestep. - // Quite conservative to not risk false triggers. - // 2s of lag is worse case, since the function is called at 1Hz - uint32_t timestep = 1e6 / cfg->rx_checks[i].msg[cfg->rx_checks[i].status.index].frequency; - bool lagging = elapsed_time > MAX(timestep * MAX_MISSED_MSGS, 1e6); - cfg->rx_checks[i].status.lagging = lagging; - if (lagging) { - controls_allowed = false; - } - - if (lagging || !is_msg_valid(cfg->rx_checks, i)) { - rx_checks_invalid = true; - } - } - } - - safety_rx_checks_invalid = rx_checks_invalid; -} - -void update_counter(RxCheck addr_list[], int index, uint8_t counter) { - if (index != -1) { - uint8_t expected_counter = (addr_list[index].status.last_counter + 1U) % (addr_list[index].msg[addr_list[index].status.index].max_counter + 1U); - addr_list[index].status.wrong_counters += (expected_counter == counter) ? -1 : 1; - addr_list[index].status.wrong_counters = CLAMP(addr_list[index].status.wrong_counters, 0, MAX_WRONG_COUNTERS); - addr_list[index].status.last_counter = counter; - } -} - -bool is_msg_valid(RxCheck addr_list[], int index) { - bool valid = true; - if (index != -1) { - if (!addr_list[index].status.valid_checksum || !addr_list[index].status.valid_quality_flag || (addr_list[index].status.wrong_counters >= MAX_WRONG_COUNTERS)) { - valid = false; - controls_allowed = false; - } - } - return valid; -} - -void update_addr_timestamp(RxCheck addr_list[], int index) { - if (index != -1) { - uint32_t ts = microsecond_timer_get(); - addr_list[index].status.last_timestamp = ts; - } -} - -bool rx_msg_safety_check(const CANPacket_t *to_push, - const safety_config *cfg, - const safety_hooks *safety_hooks) { - - int index = get_addr_check_index(to_push, cfg->rx_checks, cfg->rx_checks_len); - update_addr_timestamp(cfg->rx_checks, index); - - if (index != -1) { - // checksum check - if ((safety_hooks->get_checksum != NULL) && (safety_hooks->compute_checksum != NULL) && cfg->rx_checks[index].msg[cfg->rx_checks[index].status.index].check_checksum) { - uint32_t checksum = safety_hooks->get_checksum(to_push); - uint32_t checksum_comp = safety_hooks->compute_checksum(to_push); - cfg->rx_checks[index].status.valid_checksum = checksum_comp == checksum; - } else { - cfg->rx_checks[index].status.valid_checksum = true; - } - - // counter check (max_counter == 0 means skip check) - if ((safety_hooks->get_counter != NULL) && (cfg->rx_checks[index].msg[cfg->rx_checks[index].status.index].max_counter > 0U)) { - uint8_t counter = safety_hooks->get_counter(to_push); - update_counter(cfg->rx_checks, index, counter); - } else { - cfg->rx_checks[index].status.wrong_counters = 0U; - } - - // quality flag check - if ((safety_hooks->get_quality_flag_valid != NULL) && cfg->rx_checks[index].msg[cfg->rx_checks[index].status.index].quality_flag) { - cfg->rx_checks[index].status.valid_quality_flag = safety_hooks->get_quality_flag_valid(to_push); - } else { - cfg->rx_checks[index].status.valid_quality_flag = true; - } - } - return is_msg_valid(cfg->rx_checks, index); -} - -void generic_rx_checks(bool stock_ecu_detected) { - // exit controls on rising edge of gas press - if (gas_pressed && !gas_pressed_prev && !(alternative_experience & ALT_EXP_DISABLE_DISENGAGE_ON_GAS)) { - controls_allowed = false; - } - gas_pressed_prev = gas_pressed; - - // exit controls on rising edge of brake press - if (brake_pressed && (!brake_pressed_prev || vehicle_moving)) { - controls_allowed = false; - } - brake_pressed_prev = brake_pressed; - - // exit controls on rising edge of regen paddle - if (regen_braking && (!regen_braking_prev || vehicle_moving)) { - controls_allowed = false; - } - regen_braking_prev = regen_braking; - - // check if stock ECU is on bus broken by car harness - if ((safety_mode_cnt > RELAY_TRNS_TIMEOUT) && stock_ecu_detected && !gm_skip_relay_check) { - relay_malfunction_set(); - } -} - -void relay_malfunction_set(void) { - relay_malfunction = true; - fault_occurred(FAULT_RELAY_MALFUNCTION); -} - -void relay_malfunction_reset(void) { - relay_malfunction = false; - fault_recovered(FAULT_RELAY_MALFUNCTION); -} - -typedef struct { - uint16_t id; - const safety_hooks *hooks; -} safety_hook_config; - -const safety_hook_config safety_hook_registry[] = { - {SAFETY_SILENT, &nooutput_hooks}, - {SAFETY_HONDA_NIDEC, &honda_nidec_hooks}, - {SAFETY_TOYOTA, &toyota_hooks}, - {SAFETY_ELM327, &elm327_hooks}, - {SAFETY_GM, &gm_hooks}, - {SAFETY_HONDA_BOSCH, &honda_bosch_hooks}, - {SAFETY_HYUNDAI, &hyundai_hooks}, - {SAFETY_CHRYSLER, &chrysler_hooks}, - {SAFETY_SUBARU, &subaru_hooks}, - {SAFETY_VOLKSWAGEN_MQB, &volkswagen_mqb_hooks}, - {SAFETY_NISSAN, &nissan_hooks}, - {SAFETY_NOOUTPUT, &nooutput_hooks}, - {SAFETY_HYUNDAI_LEGACY, &hyundai_legacy_hooks}, - {SAFETY_MAZDA, &mazda_hooks}, - {SAFETY_BODY, &body_hooks}, - {SAFETY_FORD, &ford_hooks}, -#ifdef CANFD - {SAFETY_HYUNDAI_CANFD, &hyundai_canfd_hooks}, -#endif -#ifdef ALLOW_DEBUG - {SAFETY_TESLA, &tesla_hooks}, - {SAFETY_SUBARU_PREGLOBAL, &subaru_preglobal_hooks}, - {SAFETY_VOLKSWAGEN_PQ, &volkswagen_pq_hooks}, - {SAFETY_ALLOUTPUT, &alloutput_hooks}, -#endif -}; - -int set_safety_hooks(uint16_t mode, uint16_t param) { - // reset state set by safety mode - safety_mode_cnt = 0U; - relay_malfunction = false; - enable_gas_interceptor = false; - gas_interceptor_prev = 0; - gas_pressed = false; - gas_pressed_prev = false; - brake_pressed = false; - brake_pressed_prev = false; - regen_braking = false; - regen_braking_prev = false; - cruise_engaged_prev = false; - vehicle_moving = false; - acc_main_on = false; - cruise_button_prev = 0; - desired_torque_last = 0; - rt_torque_last = 0; - ts_angle_last = 0; - desired_angle_last = 0; - ts_torque_check_last = 0; - ts_steer_req_mismatch_last = 0; - valid_steer_req_count = 0; - invalid_steer_req_count = 0; - - // reset samples - reset_sample(&vehicle_speed); - reset_sample(&torque_meas); - reset_sample(&torque_driver); - reset_sample(&angle_meas); - - controls_allowed = false; - relay_malfunction_reset(); - safety_rx_checks_invalid = false; - - current_safety_config.rx_checks = NULL; - current_safety_config.rx_checks_len = 0; - current_safety_config.tx_msgs = NULL; - current_safety_config.tx_msgs_len = 0; - - int set_status = -1; // not set - int hook_config_count = sizeof(safety_hook_registry) / sizeof(safety_hook_config); - for (int i = 0; i < hook_config_count; i++) { - if (safety_hook_registry[i].id == mode) { - current_hooks = safety_hook_registry[i].hooks; - current_safety_mode = mode; - current_safety_param = param; - set_status = 0; // set - } - } - if ((set_status == 0) && (current_hooks->init != NULL)) { - safety_config cfg = current_hooks->init(param); - current_safety_config.rx_checks = cfg.rx_checks; - current_safety_config.rx_checks_len = cfg.rx_checks_len; - current_safety_config.tx_msgs = cfg.tx_msgs; - current_safety_config.tx_msgs_len = cfg.tx_msgs_len; - // reset all dynamic fields in addr struct - for (int j = 0; j < current_safety_config.rx_checks_len; j++) { - current_safety_config.rx_checks[j].status = (RxStatus){0}; - } - } - return set_status; -} - -// convert a trimmed integer to signed 32 bit int -int to_signed(int d, int bits) { - int d_signed = d; - int max_value = (1 << MAX((bits - 1), 0)); - if (d >= max_value) { - d_signed = d - (1 << MAX(bits, 0)); - } - return d_signed; -} - -// given a new sample, update the sample_t struct -void update_sample(struct sample_t *sample, int sample_new) { - for (int i = MAX_SAMPLE_VALS - 1; i > 0; i--) { - sample->values[i] = sample->values[i-1]; - } - sample->values[0] = sample_new; - - // get the minimum and maximum measured samples - sample->min = sample->values[0]; - sample->max = sample->values[0]; - for (int i = 1; i < MAX_SAMPLE_VALS; i++) { - if (sample->values[i] < sample->min) { - sample->min = sample->values[i]; - } - if (sample->values[i] > sample->max) { - sample->max = sample->values[i]; - } - } -} - -// resets values and min/max for sample_t struct -void reset_sample(struct sample_t *sample) { - for (int i = 0; i < MAX_SAMPLE_VALS; i++) { - sample->values[i] = 0; - } - update_sample(sample, 0); -} - -bool max_limit_check(int val, const int MAX_VAL, const int MIN_VAL) { - return (val > MAX_VAL) || (val < MIN_VAL); -} - -// check that commanded torque value isn't too far from measured -bool dist_to_meas_check(int val, int val_last, struct sample_t *val_meas, - const int MAX_RATE_UP, const int MAX_RATE_DOWN, const int MAX_ERROR) { - - // *** val rate limit check *** - int highest_allowed_rl = MAX(val_last, 0) + MAX_RATE_UP; - int lowest_allowed_rl = MIN(val_last, 0) - MAX_RATE_UP; - - // if we've exceeded the meas val, we must start moving toward 0 - int highest_allowed = MIN(highest_allowed_rl, MAX(val_last - MAX_RATE_DOWN, MAX(val_meas->max, 0) + MAX_ERROR)); - int lowest_allowed = MAX(lowest_allowed_rl, MIN(val_last + MAX_RATE_DOWN, MIN(val_meas->min, 0) - MAX_ERROR)); - - // check for violation - return max_limit_check(val, highest_allowed, lowest_allowed); -} - -// check that commanded value isn't fighting against driver -bool driver_limit_check(int val, int val_last, const struct sample_t *val_driver, - const int MAX_VAL, const int MAX_RATE_UP, const int MAX_RATE_DOWN, - const int MAX_ALLOWANCE, const int DRIVER_FACTOR) { - - // torque delta/rate limits - int highest_allowed_rl = MAX(val_last, 0) + MAX_RATE_UP; - int lowest_allowed_rl = MIN(val_last, 0) - MAX_RATE_UP; - - // driver - int driver_max_limit = MAX_VAL + (MAX_ALLOWANCE + val_driver->max) * DRIVER_FACTOR; - int driver_min_limit = -MAX_VAL + (-MAX_ALLOWANCE + val_driver->min) * DRIVER_FACTOR; - - // if we've exceeded the applied torque, we must start moving toward 0 - int highest_allowed = MIN(highest_allowed_rl, MAX(val_last - MAX_RATE_DOWN, - MAX(driver_max_limit, 0))); - int lowest_allowed = MAX(lowest_allowed_rl, MIN(val_last + MAX_RATE_DOWN, - MIN(driver_min_limit, 0))); - - // check for violation - return max_limit_check(val, highest_allowed, lowest_allowed); -} - - -// real time check, mainly used for steer torque rate limiter -bool rt_rate_limit_check(int val, int val_last, const int MAX_RT_DELTA) { - - // *** torque real time rate limit check *** - int highest_val = MAX(val_last, 0) + MAX_RT_DELTA; - int lowest_val = MIN(val_last, 0) - MAX_RT_DELTA; - - // check for violation - return max_limit_check(val, highest_val, lowest_val); -} - - -// interp function that holds extreme values -float interpolate(struct lookup_t xy, float x) { - - int size = sizeof(xy.x) / sizeof(xy.x[0]); - float ret = xy.y[size - 1]; // default output is last point - - // x is lower than the first point in the x array. Return the first point - if (x <= xy.x[0]) { - ret = xy.y[0]; - - } else { - // find the index such that (xy.x[i] <= x < xy.x[i+1]) and linearly interp - for (int i=0; i < (size - 1); i++) { - if (x < xy.x[i+1]) { - float x0 = xy.x[i]; - float y0 = xy.y[i]; - float dx = xy.x[i+1] - x0; - float dy = xy.y[i+1] - y0; - // dx should not be zero as xy.x is supposed to be monotonic - dx = MAX(dx, 0.0001); - ret = (dy * (x - x0) / dx) + y0; - break; - } - } - } - return ret; -} - -int ROUND(float val) { - return val + ((val > 0.0) ? 0.5 : -0.5); -} - -// Safety checks for longitudinal actuation -bool longitudinal_accel_checks(int desired_accel, const LongitudinalLimits limits) { - bool accel_valid = get_longitudinal_allowed() && !max_limit_check(desired_accel, limits.max_accel, limits.min_accel); - bool accel_inactive = desired_accel == limits.inactive_accel; - return !(accel_valid || accel_inactive); -} - -bool longitudinal_speed_checks(int desired_speed, const LongitudinalLimits limits) { - return !get_longitudinal_allowed() && (desired_speed != limits.inactive_speed); -} - -bool longitudinal_transmission_rpm_checks(int desired_transmission_rpm, const LongitudinalLimits limits) { - bool transmission_rpm_valid = get_longitudinal_allowed() && !max_limit_check(desired_transmission_rpm, limits.max_transmission_rpm, limits.min_transmission_rpm); - bool transmission_rpm_inactive = desired_transmission_rpm == limits.inactive_transmission_rpm; - return !(transmission_rpm_valid || transmission_rpm_inactive); -} - -bool longitudinal_gas_checks(int desired_gas, const LongitudinalLimits limits) { - bool gas_valid = get_longitudinal_allowed() && !max_limit_check(desired_gas, limits.max_gas, limits.min_gas); - bool gas_inactive = desired_gas == limits.inactive_gas; - return !(gas_valid || gas_inactive); -} - -bool longitudinal_brake_checks(int desired_brake, const LongitudinalLimits limits) { - bool violation = false; - violation |= !get_longitudinal_allowed() && (desired_brake != 0); - violation |= desired_brake > limits.max_brake; - return violation; -} - -bool longitudinal_interceptor_checks(const CANPacket_t *to_send) { - return (!get_longitudinal_allowed() || brake_pressed_prev) && (GET_BYTE(to_send, 0) || GET_BYTE(to_send, 1)); -} - -// Safety checks for torque-based steering commands -bool steer_torque_cmd_checks(int desired_torque, int steer_req, const SteeringLimits limits) { - bool violation = false; - uint32_t ts = microsecond_timer_get(); - - bool aol_allowed = acc_main_on && (alternative_experience & ALT_EXP_ALWAYS_ON_LATERAL); - if (controls_allowed) { - // acc main must be on if controls are allowed - acc_main_on = controls_allowed; - } - - if (controls_allowed || aol_allowed) { - // *** global torque limit check *** - violation |= max_limit_check(desired_torque, limits.max_steer, -limits.max_steer); - - // *** torque rate limit check *** - if (limits.type == TorqueDriverLimited) { - violation |= driver_limit_check(desired_torque, desired_torque_last, &torque_driver, - limits.max_steer, limits.max_rate_up, limits.max_rate_down, - limits.driver_torque_allowance, limits.driver_torque_factor); - } else { - violation |= dist_to_meas_check(desired_torque, desired_torque_last, &torque_meas, - limits.max_rate_up, limits.max_rate_down, limits.max_torque_error); - } - desired_torque_last = desired_torque; - - // *** torque real time rate limit check *** - violation |= rt_rate_limit_check(desired_torque, rt_torque_last, limits.max_rt_delta); - - // every RT_INTERVAL set the new limits - uint32_t ts_elapsed = get_ts_elapsed(ts, ts_torque_check_last); - if (ts_elapsed > limits.max_rt_interval) { - rt_torque_last = desired_torque; - ts_torque_check_last = ts; - } - } - - // no torque if controls is not allowed - if (!(controls_allowed || aol_allowed) && (desired_torque != 0)) { - violation = true; - } - - // certain safety modes set their steer request bit low for one or more frame at a - // predefined max frequency to avoid steering faults in certain situations - bool steer_req_mismatch = (steer_req == 0) && (desired_torque != 0); - if (!limits.has_steer_req_tolerance) { - if (steer_req_mismatch) { - violation = true; - } - - } else { - if (steer_req_mismatch) { - if (invalid_steer_req_count == 0) { - // disallow torque cut if not enough recent matching steer_req messages - if (valid_steer_req_count < limits.min_valid_request_frames) { - violation = true; - } - - // or we've cut torque too recently in time - uint32_t ts_elapsed = get_ts_elapsed(ts, ts_steer_req_mismatch_last); - if (ts_elapsed < limits.min_valid_request_rt_interval) { - violation = true; - } - } else { - // or we're cutting more frames consecutively than allowed - if (invalid_steer_req_count >= limits.max_invalid_request_frames) { - violation = true; - } - } - - valid_steer_req_count = 0; - ts_steer_req_mismatch_last = ts; - invalid_steer_req_count = MIN(invalid_steer_req_count + 1, limits.max_invalid_request_frames); - } else { - valid_steer_req_count = MIN(valid_steer_req_count + 1, limits.min_valid_request_frames); - invalid_steer_req_count = 0; - } - } - - // reset to 0 if either controls is not allowed or there's a violation - if (violation || !(controls_allowed || aol_allowed)) { - valid_steer_req_count = 0; - invalid_steer_req_count = 0; - desired_torque_last = 0; - rt_torque_last = 0; - ts_torque_check_last = ts; - ts_steer_req_mismatch_last = ts; - } - - return violation; -} - -// Safety checks for angle-based steering commands -bool steer_angle_cmd_checks(int desired_angle, bool steer_control_enabled, const SteeringLimits limits) { - bool violation = false; - bool aol_allowed = acc_main_on && (alternative_experience & ALT_EXP_ALWAYS_ON_LATERAL); - if (controls_allowed) { - // acc main must be on if controls are allowed - acc_main_on = controls_allowed; - } - - if ((controls_allowed || aol_allowed) && steer_control_enabled) { - // convert floating point angle rate limits to integers in the scale of the desired angle on CAN, - // add 1 to not false trigger the violation. also fudge the speed by 1 m/s so rate limits are - // always slightly above openpilot's in case we read an updated speed in between angle commands - // TODO: this speed fudge can be much lower, look at data to determine the lowest reasonable offset - int delta_angle_up = (interpolate(limits.angle_rate_up_lookup, (vehicle_speed.min / VEHICLE_SPEED_FACTOR) - 1.) * limits.angle_deg_to_can) + 1.; - int delta_angle_down = (interpolate(limits.angle_rate_down_lookup, (vehicle_speed.min / VEHICLE_SPEED_FACTOR) - 1.) * limits.angle_deg_to_can) + 1.; - - // allow down limits at zero since small floats will be rounded to 0 - int highest_desired_angle = desired_angle_last + ((desired_angle_last > 0) ? delta_angle_up : delta_angle_down); - int lowest_desired_angle = desired_angle_last - ((desired_angle_last >= 0) ? delta_angle_down : delta_angle_up); - - // check that commanded angle value isn't too far from measured, used to limit torque for some safety modes - // ensure we start moving in direction of meas while respecting rate limits if error is exceeded - if (limits.enforce_angle_error && ((vehicle_speed.values[0] / VEHICLE_SPEED_FACTOR) > limits.angle_error_min_speed)) { - // the rate limits above are liberally above openpilot's to avoid false positives. - // likewise, allow a lower rate for moving towards meas when error is exceeded - int delta_angle_up_lower = interpolate(limits.angle_rate_up_lookup, (vehicle_speed.max / VEHICLE_SPEED_FACTOR) + 1.) * limits.angle_deg_to_can; - int delta_angle_down_lower = interpolate(limits.angle_rate_down_lookup, (vehicle_speed.max / VEHICLE_SPEED_FACTOR) + 1.) * limits.angle_deg_to_can; - - int highest_desired_angle_lower = desired_angle_last + ((desired_angle_last > 0) ? delta_angle_up_lower : delta_angle_down_lower); - int lowest_desired_angle_lower = desired_angle_last - ((desired_angle_last >= 0) ? delta_angle_down_lower : delta_angle_up_lower); - - lowest_desired_angle = MIN(MAX(lowest_desired_angle, angle_meas.min - limits.max_angle_error - 1), highest_desired_angle_lower); - highest_desired_angle = MAX(MIN(highest_desired_angle, angle_meas.max + limits.max_angle_error + 1), lowest_desired_angle_lower); - - // don't enforce above the max steer - lowest_desired_angle = CLAMP(lowest_desired_angle, -limits.max_steer, limits.max_steer); - highest_desired_angle = CLAMP(highest_desired_angle, -limits.max_steer, limits.max_steer); - } - - // check for violation; - violation |= max_limit_check(desired_angle, highest_desired_angle, lowest_desired_angle); - } - desired_angle_last = desired_angle; - - // Angle should either be 0 or same as current angle while not steering - if (!steer_control_enabled) { - violation |= (limits.inactive_angle_is_zero ? (desired_angle != 0) : - max_limit_check(desired_angle, angle_meas.max + 1, angle_meas.min - 1)); - } - - // No angle control allowed when controls are not allowed - violation |= !(controls_allowed || aol_allowed) && steer_control_enabled; - - return violation; -} - -void pcm_cruise_check(bool cruise_engaged) { - // Enter controls on rising edge of stock ACC, exit controls if stock ACC disengages - if (!cruise_engaged) { - controls_allowed = false; - } - if (cruise_engaged && !cruise_engaged_prev) { - controls_allowed = true; - } - cruise_engaged_prev = cruise_engaged; -} diff --git a/panda/board/safety/safety_body.h b/panda/board/safety/safety_body.h deleted file mode 100644 index 2ebca28..0000000 --- a/panda/board/safety/safety_body.h +++ /dev/null @@ -1,46 +0,0 @@ -const CanMsg BODY_TX_MSGS[] = {{0x250, 0, 8}, {0x250, 0, 6}, {0x251, 0, 5}, // body - {0x350, 0, 8}, {0x350, 0, 6}, {0x351, 0, 5}, // knee - {0x1, 0, 8}}; // CAN flasher - -RxCheck body_rx_checks[] = { - {.msg = {{0x201, 0, 8, .check_checksum = false, .max_counter = 0U, .frequency = 100U}, { 0 }, { 0 }}}, -}; - -static void body_rx_hook(const CANPacket_t *to_push) { - // body is never at standstill - vehicle_moving = true; - - if (GET_ADDR(to_push) == 0x201U) { - controls_allowed = true; - } -} - -static bool body_tx_hook(const CANPacket_t *to_send) { - bool tx = true; - int addr = GET_ADDR(to_send); - int len = GET_LEN(to_send); - - if (!controls_allowed && (addr != 0x1)) { - tx = false; - } - - // Allow going into CAN flashing mode for base & knee even if controls are not allowed - bool flash_msg = ((addr == 0x250) || (addr == 0x350)) && (len == 8); - if (!controls_allowed && (GET_BYTES(to_send, 0, 4) == 0xdeadfaceU) && (GET_BYTES(to_send, 4, 4) == 0x0ab00b1eU) && flash_msg) { - tx = true; - } - - return tx; -} - -static safety_config body_init(uint16_t param) { - UNUSED(param); - return BUILD_SAFETY_CFG(body_rx_checks, BODY_TX_MSGS); -} - -const safety_hooks body_hooks = { - .init = body_init, - .rx = body_rx_hook, - .tx = body_tx_hook, - .fwd = default_fwd_hook, -}; diff --git a/panda/board/safety/safety_chrysler.h b/panda/board/safety/safety_chrysler.h deleted file mode 100644 index b80e3e8..0000000 --- a/panda/board/safety/safety_chrysler.h +++ /dev/null @@ -1,296 +0,0 @@ -const SteeringLimits CHRYSLER_STEERING_LIMITS = { - .max_steer = 261, - .max_rt_delta = 112, - .max_rt_interval = 250000, - .max_rate_up = 3, - .max_rate_down = 3, - .max_torque_error = 80, - .type = TorqueMotorLimited, -}; - -const SteeringLimits CHRYSLER_RAM_DT_STEERING_LIMITS = { - .max_steer = 350, - .max_rt_delta = 112, - .max_rt_interval = 250000, - .max_rate_up = 6, - .max_rate_down = 6, - .max_torque_error = 80, - .type = TorqueMotorLimited, -}; - -const SteeringLimits CHRYSLER_RAM_HD_STEERING_LIMITS = { - .max_steer = 361, - .max_rt_delta = 182, - .max_rt_interval = 250000, - .max_rate_up = 14, - .max_rate_down = 14, - .max_torque_error = 80, - .type = TorqueMotorLimited, -}; - -typedef struct { - const int EPS_2; - const int ESP_1; - const int ESP_8; - const int ECM_5; - const int DAS_3; - const int DAS_6; - const int LKAS_COMMAND; - const int CRUISE_BUTTONS; -} ChryslerAddrs; - -// CAN messages for Chrysler/Jeep platforms -const ChryslerAddrs CHRYSLER_ADDRS = { - .EPS_2 = 0x220, // EPS driver input torque - .ESP_1 = 0x140, // Brake pedal and vehicle speed - .ESP_8 = 0x11C, // Brake pedal and vehicle speed - .ECM_5 = 0x22F, // Throttle position sensor - .DAS_3 = 0x1F4, // ACC engagement states from DASM - .DAS_6 = 0x2A6, // LKAS HUD and auto headlight control from DASM - .LKAS_COMMAND = 0x292, // LKAS controls from DASM - .CRUISE_BUTTONS = 0x23B, // Cruise control buttons -}; - -// CAN messages for the 5th gen RAM DT platform -const ChryslerAddrs CHRYSLER_RAM_DT_ADDRS = { - .EPS_2 = 0x31, // EPS driver input torque - .ESP_1 = 0x83, // Brake pedal and vehicle speed - .ESP_8 = 0x79, // Brake pedal and vehicle speed - .ECM_5 = 0x9D, // Throttle position sensor - .DAS_3 = 0x99, // ACC engagement states from DASM - .DAS_6 = 0xFA, // LKAS HUD and auto headlight control from DASM - .LKAS_COMMAND = 0xA6, // LKAS controls from DASM - .CRUISE_BUTTONS = 0xB1, // Cruise control buttons -}; - -// CAN messages for the 5th gen RAM HD platform -const ChryslerAddrs CHRYSLER_RAM_HD_ADDRS = { - .EPS_2 = 0x220, // EPS driver input torque - .ESP_1 = 0x140, // Brake pedal and vehicle speed - .ESP_8 = 0x11C, // Brake pedal and vehicle speed - .ECM_5 = 0x22F, // Throttle position sensor - .DAS_3 = 0x1F4, // ACC engagement states from DASM - .DAS_6 = 0x275, // LKAS HUD and auto headlight control from DASM - .LKAS_COMMAND = 0x276, // LKAS controls from DASM - .CRUISE_BUTTONS = 0x23A, // Cruise control buttons -}; - -const CanMsg CHRYSLER_TX_MSGS[] = { - {CHRYSLER_ADDRS.CRUISE_BUTTONS, 0, 3}, - {CHRYSLER_ADDRS.LKAS_COMMAND, 0, 6}, - {CHRYSLER_ADDRS.DAS_6, 0, 8}, -}; - -const CanMsg CHRYSLER_RAM_DT_TX_MSGS[] = { - {CHRYSLER_RAM_DT_ADDRS.CRUISE_BUTTONS, 2, 3}, - {CHRYSLER_RAM_DT_ADDRS.LKAS_COMMAND, 0, 8}, - {CHRYSLER_RAM_DT_ADDRS.DAS_6, 0, 8}, -}; - -const CanMsg CHRYSLER_RAM_HD_TX_MSGS[] = { - {CHRYSLER_RAM_HD_ADDRS.CRUISE_BUTTONS, 2, 3}, - {CHRYSLER_RAM_HD_ADDRS.LKAS_COMMAND, 0, 8}, - {CHRYSLER_RAM_HD_ADDRS.DAS_6, 0, 8}, -}; - -RxCheck chrysler_rx_checks[] = { - {.msg = {{CHRYSLER_ADDRS.EPS_2, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 100U}, { 0 }, { 0 }}}, - {.msg = {{CHRYSLER_ADDRS.ESP_1, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, - //{.msg = {{ESP_8, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}}}, - {.msg = {{514, 0, 8, .check_checksum = false, .max_counter = 0U, .frequency = 100U}, { 0 }, { 0 }}}, - {.msg = {{CHRYSLER_ADDRS.ECM_5, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, - {.msg = {{CHRYSLER_ADDRS.DAS_3, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, -}; - -RxCheck chrysler_ram_dt_rx_checks[] = { - {.msg = {{CHRYSLER_RAM_DT_ADDRS.EPS_2, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 100U}, { 0 }, { 0 }}}, - {.msg = {{CHRYSLER_RAM_DT_ADDRS.ESP_1, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, - {.msg = {{CHRYSLER_RAM_DT_ADDRS.ESP_8, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, - {.msg = {{CHRYSLER_RAM_DT_ADDRS.ECM_5, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, - {.msg = {{CHRYSLER_RAM_DT_ADDRS.DAS_3, 2, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, -}; - -RxCheck chrysler_ram_hd_rx_checks[] = { - {.msg = {{CHRYSLER_RAM_HD_ADDRS.EPS_2, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 100U}, { 0 }, { 0 }}}, - {.msg = {{CHRYSLER_RAM_HD_ADDRS.ESP_1, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, - {.msg = {{CHRYSLER_RAM_HD_ADDRS.ESP_8, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, - {.msg = {{CHRYSLER_RAM_HD_ADDRS.ECM_5, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, - {.msg = {{CHRYSLER_RAM_HD_ADDRS.DAS_3, 2, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, -}; - - - -const uint32_t CHRYSLER_PARAM_RAM_DT = 1U; // set for Ram DT platform -const uint32_t CHRYSLER_PARAM_RAM_HD = 2U; // set for Ram HD platform - -enum { - CHRYSLER_RAM_DT, - CHRYSLER_RAM_HD, - CHRYSLER_PACIFICA, // plus Jeep -} chrysler_platform = CHRYSLER_PACIFICA; -const ChryslerAddrs *chrysler_addrs = &CHRYSLER_ADDRS; - -static uint32_t chrysler_get_checksum(const CANPacket_t *to_push) { - int checksum_byte = GET_LEN(to_push) - 1U; - return (uint8_t)(GET_BYTE(to_push, checksum_byte)); -} - -static uint32_t chrysler_compute_checksum(const CANPacket_t *to_push) { - // TODO: clean this up - // http://illmatics.com/Remote%20Car%20Hacking.pdf - uint8_t checksum = 0xFFU; - int len = GET_LEN(to_push); - for (int j = 0; j < (len - 1); j++) { - uint8_t shift = 0x80U; - uint8_t curr = (uint8_t)GET_BYTE(to_push, j); - for (int i=0; i<8; i++) { - uint8_t bit_sum = curr & shift; - uint8_t temp_chk = checksum & 0x80U; - if (bit_sum != 0U) { - bit_sum = 0x1C; - if (temp_chk != 0U) { - bit_sum = 1; - } - checksum = checksum << 1; - temp_chk = checksum | 1U; - bit_sum ^= temp_chk; - } else { - if (temp_chk != 0U) { - bit_sum = 0x1D; - } - checksum = checksum << 1; - bit_sum ^= checksum; - } - checksum = bit_sum; - shift = shift >> 1; - } - } - return (uint8_t)(~checksum); -} - -static uint8_t chrysler_get_counter(const CANPacket_t *to_push) { - return (uint8_t)(GET_BYTE(to_push, 6) >> 4); -} - -static void chrysler_rx_hook(const CANPacket_t *to_push) { - const int bus = GET_BUS(to_push); - const int addr = GET_ADDR(to_push); - - // Measured EPS torque - if ((bus == 0) && (addr == chrysler_addrs->EPS_2)) { - int torque_meas_new = ((GET_BYTE(to_push, 4) & 0x7U) << 8) + GET_BYTE(to_push, 5) - 1024U; - update_sample(&torque_meas, torque_meas_new); - } - - // enter controls on rising edge of ACC, exit controls on ACC off - const int das_3_bus = (chrysler_platform == CHRYSLER_PACIFICA) ? 0 : 2; - if ((bus == das_3_bus) && (addr == chrysler_addrs->DAS_3)) { - acc_main_on = GET_BIT(to_push, 20U); - bool cruise_engaged = GET_BIT(to_push, 21U); - pcm_cruise_check(cruise_engaged); - } - - // TODO: use the same message for both - // update vehicle moving - if ((chrysler_platform != CHRYSLER_PACIFICA) && (bus == 0) && (addr == chrysler_addrs->ESP_8)) { - vehicle_moving = ((GET_BYTE(to_push, 4) << 8) + GET_BYTE(to_push, 5)) != 0U; - } - if ((chrysler_platform == CHRYSLER_PACIFICA) && (bus == 0) && (addr == 514)) { - int speed_l = (GET_BYTE(to_push, 0) << 4) + (GET_BYTE(to_push, 1) >> 4); - int speed_r = (GET_BYTE(to_push, 2) << 4) + (GET_BYTE(to_push, 3) >> 4); - vehicle_moving = (speed_l != 0) || (speed_r != 0); - } - - // exit controls on rising edge of gas press - if ((bus == 0) && (addr == chrysler_addrs->ECM_5)) { - gas_pressed = GET_BYTE(to_push, 0U) != 0U; - } - - // exit controls on rising edge of brake press - if ((bus == 0) && (addr == chrysler_addrs->ESP_1)) { - brake_pressed = ((GET_BYTE(to_push, 0U) & 0xFU) >> 2U) == 1U; - } - - generic_rx_checks((bus == 0) && (addr == chrysler_addrs->LKAS_COMMAND)); -} - -static bool chrysler_tx_hook(const CANPacket_t *to_send) { - bool tx = true; - int addr = GET_ADDR(to_send); - - // STEERING - if (addr == chrysler_addrs->LKAS_COMMAND) { - int start_byte = (chrysler_platform == CHRYSLER_PACIFICA) ? 0 : 1; - int desired_torque = ((GET_BYTE(to_send, start_byte) & 0x7U) << 8) | GET_BYTE(to_send, start_byte + 1); - desired_torque -= 1024; - - const SteeringLimits limits = (chrysler_platform == CHRYSLER_PACIFICA) ? CHRYSLER_STEERING_LIMITS : - (chrysler_platform == CHRYSLER_RAM_DT) ? CHRYSLER_RAM_DT_STEERING_LIMITS : CHRYSLER_RAM_HD_STEERING_LIMITS; - - bool steer_req = (chrysler_platform == CHRYSLER_PACIFICA) ? GET_BIT(to_send, 4U) : (GET_BYTE(to_send, 3) & 0x7U) == 2U; - if (steer_torque_cmd_checks(desired_torque, steer_req, limits)) { - tx = false; - } - } - - // FORCE CANCEL: only the cancel button press is allowed - if (addr == chrysler_addrs->CRUISE_BUTTONS) { - const bool is_cancel = GET_BYTE(to_send, 0) == 1U; - const bool is_resume = GET_BYTE(to_send, 0) == 0x10U; - const bool allowed = is_cancel || (is_resume && controls_allowed); - if (!allowed) { - tx = false; - } - } - - return tx; -} - -static int chrysler_fwd_hook(int bus_num, int addr) { - int bus_fwd = -1; - - // forward to camera - if (bus_num == 0) { - bus_fwd = 2; - } - - // forward all messages from camera except LKAS messages - const bool is_lkas = ((addr == chrysler_addrs->LKAS_COMMAND) || (addr == chrysler_addrs->DAS_6)); - if ((bus_num == 2) && !is_lkas){ - bus_fwd = 0; - } - - return bus_fwd; -} - -static safety_config chrysler_init(uint16_t param) { - safety_config ret; - - bool enable_ram_dt = GET_FLAG(param, CHRYSLER_PARAM_RAM_DT); - if (enable_ram_dt) { - chrysler_platform = CHRYSLER_RAM_DT; - chrysler_addrs = &CHRYSLER_RAM_DT_ADDRS; - ret = BUILD_SAFETY_CFG(chrysler_ram_dt_rx_checks, CHRYSLER_RAM_DT_TX_MSGS); -#ifdef ALLOW_DEBUG - } else if (GET_FLAG(param, CHRYSLER_PARAM_RAM_HD)) { - chrysler_platform = CHRYSLER_RAM_HD; - chrysler_addrs = &CHRYSLER_RAM_HD_ADDRS; - ret = BUILD_SAFETY_CFG(chrysler_ram_hd_rx_checks, CHRYSLER_RAM_HD_TX_MSGS); -#endif - } else { - chrysler_platform = CHRYSLER_PACIFICA; - chrysler_addrs = &CHRYSLER_ADDRS; - ret = BUILD_SAFETY_CFG(chrysler_rx_checks, CHRYSLER_TX_MSGS); - } - return ret; -} - -const safety_hooks chrysler_hooks = { - .init = chrysler_init, - .rx = chrysler_rx_hook, - .tx = chrysler_tx_hook, - .fwd = chrysler_fwd_hook, - .get_counter = chrysler_get_counter, - .get_checksum = chrysler_get_checksum, - .compute_checksum = chrysler_compute_checksum, -}; diff --git a/panda/board/safety/safety_defaults.h b/panda/board/safety/safety_defaults.h deleted file mode 100644 index 6c47dba..0000000 --- a/panda/board/safety/safety_defaults.h +++ /dev/null @@ -1,68 +0,0 @@ -void default_rx_hook(const CANPacket_t *to_push) { - UNUSED(to_push); -} - -// *** no output safety mode *** - -static safety_config nooutput_init(uint16_t param) { - UNUSED(param); - return (safety_config){NULL, 0, NULL, 0}; -} - -static bool nooutput_tx_hook(const CANPacket_t *to_send) { - UNUSED(to_send); - return false; -} - -static int default_fwd_hook(int bus_num, int addr) { - UNUSED(bus_num); - UNUSED(addr); - return -1; -} - -const safety_hooks nooutput_hooks = { - .init = nooutput_init, - .rx = default_rx_hook, - .tx = nooutput_tx_hook, - .fwd = default_fwd_hook, -}; - -// *** all output safety mode *** - -// Enables passthrough mode where relay is open and bus 0 gets forwarded to bus 2 and vice versa -const uint16_t ALLOUTPUT_PARAM_PASSTHROUGH = 1; -bool alloutput_passthrough = false; - -static safety_config alloutput_init(uint16_t param) { - controls_allowed = true; - alloutput_passthrough = GET_FLAG(param, ALLOUTPUT_PARAM_PASSTHROUGH); - return (safety_config){NULL, 0, NULL, 0}; -} - -static bool alloutput_tx_hook(const CANPacket_t *to_send) { - UNUSED(to_send); - return true; -} - -static int alloutput_fwd_hook(int bus_num, int addr) { - int bus_fwd = -1; - UNUSED(addr); - - if (alloutput_passthrough) { - if (bus_num == 0) { - bus_fwd = 2; - } - if (bus_num == 2) { - bus_fwd = 0; - } - } - - return bus_fwd; -} - -const safety_hooks alloutput_hooks = { - .init = alloutput_init, - .rx = default_rx_hook, - .tx = alloutput_tx_hook, - .fwd = alloutput_fwd_hook, -}; diff --git a/panda/board/safety/safety_elm327.h b/panda/board/safety/safety_elm327.h deleted file mode 100644 index 954efca..0000000 --- a/panda/board/safety/safety_elm327.h +++ /dev/null @@ -1,37 +0,0 @@ -const int GM_CAMERA_DIAG_ADDR = 0x24B; - -static bool elm327_tx_hook(const CANPacket_t *to_send) { - bool tx = true; - int addr = GET_ADDR(to_send); - int len = GET_LEN(to_send); - - // All ISO 15765-4 messages must be 8 bytes long - if (len != 8) { - tx = false; - } - - // Check valid 29 bit send addresses for ISO 15765-4 - // Check valid 11 bit send addresses for ISO 15765-4 - if ((addr != 0x18DB33F1) && ((addr & 0x1FFF00FF) != 0x18DA00F1) && - ((addr & 0x1FFFFF00) != 0x600) && ((addr & 0x1FFFFF00) != 0x700) && - (addr != GM_CAMERA_DIAG_ADDR)) { - tx = false; - } - - // GM camera uses non-standard diagnostic address, this has no control message address collisions - if ((addr == GM_CAMERA_DIAG_ADDR) && (len == 8)) { - // Only allow known frame types for ISO 15765-2 - if ((GET_BYTE(to_send, 0) & 0xF0U) > 0x30U) { - tx = false; - } - } - return tx; -} - -// If current_board->has_obd and safety_param == 0, bus 1 is multiplexed to the OBD-II port -const safety_hooks elm327_hooks = { - .init = nooutput_init, - .rx = default_rx_hook, - .tx = elm327_tx_hook, - .fwd = default_fwd_hook, -}; diff --git a/panda/board/safety/safety_ford.h b/panda/board/safety/safety_ford.h deleted file mode 100644 index efbb91c..0000000 --- a/panda/board/safety/safety_ford.h +++ /dev/null @@ -1,430 +0,0 @@ -// Safety-relevant CAN messages for Ford vehicles. -#define FORD_EngBrakeData 0x165 // RX from PCM, for driver brake pedal and cruise state -#define FORD_EngVehicleSpThrottle 0x204 // RX from PCM, for driver throttle input -#define FORD_DesiredTorqBrk 0x213 // RX from ABS, for standstill state -#define FORD_BrakeSysFeatures 0x415 // RX from ABS, for vehicle speed -#define FORD_EngVehicleSpThrottle2 0x202 // RX from PCM, for second vehicle speed -#define FORD_Yaw_Data_FD1 0x91 // RX from RCM, for yaw rate -#define FORD_Steering_Data_FD1 0x083 // TX by OP, various driver switches and LKAS/CC buttons -#define FORD_ACCDATA 0x186 // TX by OP, ACC controls -#define FORD_ACCDATA_3 0x18A // TX by OP, ACC/TJA user interface -#define FORD_Lane_Assist_Data1 0x3CA // TX by OP, Lane Keep Assist -#define FORD_LateralMotionControl 0x3D3 // TX by OP, Lateral Control message -#define FORD_LateralMotionControl2 0x3D6 // TX by OP, alternate Lateral Control message -#define FORD_IPMA_Data 0x3D8 // TX by OP, IPMA and LKAS user interface - -// CAN bus numbers. -#define FORD_MAIN_BUS 0U -#define FORD_CAM_BUS 2U - -const CanMsg FORD_STOCK_TX_MSGS[] = { - {FORD_Steering_Data_FD1, 0, 8}, - {FORD_Steering_Data_FD1, 2, 8}, - {FORD_ACCDATA_3, 0, 8}, - {FORD_Lane_Assist_Data1, 0, 8}, - {FORD_LateralMotionControl, 0, 8}, - {FORD_IPMA_Data, 0, 8}, -}; - -const CanMsg FORD_LONG_TX_MSGS[] = { - {FORD_Steering_Data_FD1, 0, 8}, - {FORD_Steering_Data_FD1, 2, 8}, - {FORD_ACCDATA, 0, 8}, - {FORD_ACCDATA_3, 0, 8}, - {FORD_Lane_Assist_Data1, 0, 8}, - {FORD_LateralMotionControl, 0, 8}, - {FORD_IPMA_Data, 0, 8}, -}; - -const CanMsg FORD_CANFD_STOCK_TX_MSGS[] = { - {FORD_Steering_Data_FD1, 0, 8}, - {FORD_Steering_Data_FD1, 2, 8}, - {FORD_ACCDATA_3, 0, 8}, - {FORD_Lane_Assist_Data1, 0, 8}, - {FORD_LateralMotionControl2, 0, 8}, - {FORD_IPMA_Data, 0, 8}, -}; - -const CanMsg FORD_CANFD_LONG_TX_MSGS[] = { - {FORD_Steering_Data_FD1, 0, 8}, - {FORD_Steering_Data_FD1, 2, 8}, - {FORD_ACCDATA, 0, 8}, - {FORD_ACCDATA_3, 0, 8}, - {FORD_Lane_Assist_Data1, 0, 8}, - {FORD_LateralMotionControl2, 0, 8}, - {FORD_IPMA_Data, 0, 8}, -}; - -// warning: quality flags are not yet checked in openpilot's CAN parser, -// this may be the cause of blocked messages -RxCheck ford_rx_checks[] = { - {.msg = {{FORD_BrakeSysFeatures, 0, 8, .check_checksum = true, .max_counter = 15U, .quality_flag=true, .frequency = 50U}, { 0 }, { 0 }}}, - // TODO: FORD_EngVehicleSpThrottle2 has a counter that skips by 2, understand and enable counter check - {.msg = {{FORD_EngVehicleSpThrottle2, 0, 8, .check_checksum = true, .quality_flag=true, .frequency = 50U}, { 0 }, { 0 }}}, - {.msg = {{FORD_Yaw_Data_FD1, 0, 8, .check_checksum = true, .max_counter = 255U, .quality_flag=true, .frequency = 100U}, { 0 }, { 0 }}}, - // These messages have no counter or checksum - {.msg = {{FORD_EngBrakeData, 0, 8, .frequency = 10U}, { 0 }, { 0 }}}, - {.msg = {{FORD_EngVehicleSpThrottle, 0, 8, .frequency = 100U}, { 0 }, { 0 }}}, - {.msg = {{FORD_DesiredTorqBrk, 0, 8, .frequency = 50U}, { 0 }, { 0 }}}, -}; - -static uint8_t ford_get_counter(const CANPacket_t *to_push) { - int addr = GET_ADDR(to_push); - - uint8_t cnt = 0; - if (addr == FORD_BrakeSysFeatures) { - // Signal: VehVActlBrk_No_Cnt - cnt = (GET_BYTE(to_push, 2) >> 2) & 0xFU; - } else if (addr == FORD_Yaw_Data_FD1) { - // Signal: VehRollYaw_No_Cnt - cnt = GET_BYTE(to_push, 5); - } else { - } - return cnt; -} - -static uint32_t ford_get_checksum(const CANPacket_t *to_push) { - int addr = GET_ADDR(to_push); - - uint8_t chksum = 0; - if (addr == FORD_BrakeSysFeatures) { - // Signal: VehVActlBrk_No_Cs - chksum = GET_BYTE(to_push, 3); - } else if (addr == FORD_EngVehicleSpThrottle2) { - // Signal: VehVActlEng_No_Cs - chksum = GET_BYTE(to_push, 1); - } else if (addr == FORD_Yaw_Data_FD1) { - // Signal: VehRollYawW_No_Cs - chksum = GET_BYTE(to_push, 4); - } else { - } - return chksum; -} - -static uint32_t ford_compute_checksum(const CANPacket_t *to_push) { - int addr = GET_ADDR(to_push); - - uint8_t chksum = 0; - if (addr == FORD_BrakeSysFeatures) { - chksum += GET_BYTE(to_push, 0) + GET_BYTE(to_push, 1); // Veh_V_ActlBrk - chksum += GET_BYTE(to_push, 2) >> 6; // VehVActlBrk_D_Qf - chksum += (GET_BYTE(to_push, 2) >> 2) & 0xFU; // VehVActlBrk_No_Cnt - chksum = 0xFFU - chksum; - } else if (addr == FORD_EngVehicleSpThrottle2) { - chksum += (GET_BYTE(to_push, 2) >> 3) & 0xFU; // VehVActlEng_No_Cnt - chksum += (GET_BYTE(to_push, 4) >> 5) & 0x3U; // VehVActlEng_D_Qf - chksum += GET_BYTE(to_push, 6) + GET_BYTE(to_push, 7); // Veh_V_ActlEng - chksum = 0xFFU - chksum; - } else if (addr == FORD_Yaw_Data_FD1) { - chksum += GET_BYTE(to_push, 0) + GET_BYTE(to_push, 1); // VehRol_W_Actl - chksum += GET_BYTE(to_push, 2) + GET_BYTE(to_push, 3); // VehYaw_W_Actl - chksum += GET_BYTE(to_push, 5); // VehRollYaw_No_Cnt - chksum += GET_BYTE(to_push, 6) >> 6; // VehRolWActl_D_Qf - chksum += (GET_BYTE(to_push, 6) >> 4) & 0x3U; // VehYawWActl_D_Qf - chksum = 0xFFU - chksum; - } else { - } - - return chksum; -} - -static bool ford_get_quality_flag_valid(const CANPacket_t *to_push) { - int addr = GET_ADDR(to_push); - - bool valid = false; - if (addr == FORD_BrakeSysFeatures) { - valid = (GET_BYTE(to_push, 2) >> 6) == 0x3U; // VehVActlBrk_D_Qf - } else if (addr == FORD_EngVehicleSpThrottle2) { - valid = ((GET_BYTE(to_push, 4) >> 5) & 0x3U) == 0x3U; // VehVActlEng_D_Qf - } else if (addr == FORD_Yaw_Data_FD1) { - valid = ((GET_BYTE(to_push, 6) >> 4) & 0x3U) == 0x3U; // VehYawWActl_D_Qf - } else { - } - return valid; -} - -const uint16_t FORD_PARAM_LONGITUDINAL = 1; -const uint16_t FORD_PARAM_CANFD = 2; - -bool ford_longitudinal = false; -bool ford_canfd = false; - -const LongitudinalLimits FORD_LONG_LIMITS = { - // acceleration cmd limits (used for brakes) - // Signal: AccBrkTot_A_Rq - .max_accel = 5641, // 1.9999 m/s^s - .min_accel = 4231, // -3.4991 m/s^2 - .inactive_accel = 5128, // -0.0008 m/s^2 - - // gas cmd limits - // Signal: AccPrpl_A_Rq & AccPrpl_A_Pred - .max_gas = 700, // 2.0 m/s^2 - .min_gas = 450, // -0.5 m/s^2 - .inactive_gas = 0, // -5.0 m/s^2 -}; - -#define FORD_INACTIVE_CURVATURE 1000U -#define FORD_INACTIVE_CURVATURE_RATE 4096U -#define FORD_INACTIVE_PATH_OFFSET 512U -#define FORD_INACTIVE_PATH_ANGLE 1000U - -#define FORD_CANFD_INACTIVE_CURVATURE_RATE 1024U - -#define FORD_MAX_SPEED_DELTA 2.0 // m/s - -static bool ford_lkas_msg_check(int addr) { - return (addr == FORD_ACCDATA_3) - || (addr == FORD_Lane_Assist_Data1) - || (addr == FORD_LateralMotionControl) - || (addr == FORD_LateralMotionControl2) - || (addr == FORD_IPMA_Data); -} - -// Curvature rate limits -const SteeringLimits FORD_STEERING_LIMITS = { - .max_steer = 1000, - .angle_deg_to_can = 50000, // 1 / (2e-5) rad to can - .max_angle_error = 100, // 0.002 * FORD_STEERING_LIMITS.angle_deg_to_can - .angle_rate_up_lookup = { - {5., 25., 25.}, - {0.0002, 0.0001, 0.0001} - }, - .angle_rate_down_lookup = { - {5., 25., 25.}, - {0.000225, 0.00015, 0.00015} - }, - - // no blending at low speed due to lack of torque wind-up and inaccurate current curvature - .angle_error_min_speed = 10.0, // m/s - - .enforce_angle_error = true, - .inactive_angle_is_zero = true, -}; - -static void ford_rx_hook(const CANPacket_t *to_push) { - if (GET_BUS(to_push) == FORD_MAIN_BUS) { - int addr = GET_ADDR(to_push); - - // Update in motion state from standstill signal - if (addr == FORD_DesiredTorqBrk) { - // Signal: VehStop_D_Stat - vehicle_moving = ((GET_BYTE(to_push, 3) >> 3) & 0x3U) != 1U; - } - - // Update vehicle speed - if (addr == FORD_BrakeSysFeatures) { - // Signal: Veh_V_ActlBrk - UPDATE_VEHICLE_SPEED(((GET_BYTE(to_push, 0) << 8) | GET_BYTE(to_push, 1)) * 0.01 / 3.6); - } - - // Check vehicle speed against a second source - if (addr == FORD_EngVehicleSpThrottle2) { - // Disable controls if speeds from ABS and PCM ECUs are too far apart. - // Signal: Veh_V_ActlEng - float filtered_pcm_speed = ((GET_BYTE(to_push, 6) << 8) | GET_BYTE(to_push, 7)) * 0.01 / 3.6; - bool is_invalid_speed = ABS(filtered_pcm_speed - ((float)vehicle_speed.values[0] / VEHICLE_SPEED_FACTOR)) > FORD_MAX_SPEED_DELTA; - if (is_invalid_speed) { - controls_allowed = false; - } - } - - // Update vehicle yaw rate - if (addr == FORD_Yaw_Data_FD1) { - // Signal: VehYaw_W_Actl - float ford_yaw_rate = (((GET_BYTE(to_push, 2) << 8U) | GET_BYTE(to_push, 3)) * 0.0002) - 6.5; - float current_curvature = ford_yaw_rate / MAX(vehicle_speed.values[0] / VEHICLE_SPEED_FACTOR, 0.1); - // convert current curvature into units on CAN for comparison with desired curvature - update_sample(&angle_meas, ROUND(current_curvature * FORD_STEERING_LIMITS.angle_deg_to_can)); - } - - // Update gas pedal - if (addr == FORD_EngVehicleSpThrottle) { - // Pedal position: (0.1 * val) in percent - // Signal: ApedPos_Pc_ActlArb - gas_pressed = (((GET_BYTE(to_push, 0) & 0x03U) << 8) | GET_BYTE(to_push, 1)) > 0U; - } - - // Update brake pedal and cruise state - if (addr == FORD_EngBrakeData) { - // Signal: BpedDrvAppl_D_Actl - brake_pressed = ((GET_BYTE(to_push, 0) >> 4) & 0x3U) == 2U; - - // Signal: CcStat_D_Actl - unsigned int cruise_state = GET_BYTE(to_push, 1) & 0x07U; - acc_main_on = (cruise_state == 3U) ||(cruise_state == 4U) || (cruise_state == 5U); - bool cruise_engaged = (cruise_state == 4U) || (cruise_state == 5U); - pcm_cruise_check(cruise_engaged); - } - - // If steering controls messages are received on the destination bus, it's an indication - // that the relay might be malfunctioning. - bool stock_ecu_detected = ford_lkas_msg_check(addr); - if (ford_longitudinal) { - stock_ecu_detected = stock_ecu_detected || (addr == FORD_ACCDATA); - } - generic_rx_checks(stock_ecu_detected); - } - -} - -static bool ford_tx_hook(const CANPacket_t *to_send) { - bool tx = true; - - int addr = GET_ADDR(to_send); - - // Safety check for ACCDATA accel and brake requests - if (addr == FORD_ACCDATA) { - // Signal: AccPrpl_A_Rq - int gas = ((GET_BYTE(to_send, 6) & 0x3U) << 8) | GET_BYTE(to_send, 7); - // Signal: AccPrpl_A_Pred - int gas_pred = ((GET_BYTE(to_send, 2) & 0x3U) << 8) | GET_BYTE(to_send, 3); - // Signal: AccBrkTot_A_Rq - int accel = ((GET_BYTE(to_send, 0) & 0x1FU) << 8) | GET_BYTE(to_send, 1); - // Signal: CmbbDeny_B_Actl - bool cmbb_deny = GET_BIT(to_send, 37U); - - bool violation = false; - violation |= longitudinal_accel_checks(accel, FORD_LONG_LIMITS); - violation |= longitudinal_gas_checks(gas, FORD_LONG_LIMITS); - violation |= longitudinal_gas_checks(gas_pred, FORD_LONG_LIMITS); - - // Safety check for stock AEB - violation |= cmbb_deny; // do not prevent stock AEB actuation - - if (violation) { - tx = false; - } - } - - // Safety check for Steering_Data_FD1 button signals - // Note: Many other signals in this message are not relevant to safety (e.g. blinkers, wiper switches, high beam) - // which we passthru in OP. - if (addr == FORD_Steering_Data_FD1) { - // Violation if resume button is pressed while controls not allowed, or - // if cancel button is pressed when cruise isn't engaged. - bool violation = false; - violation |= GET_BIT(to_send, 8U) && !cruise_engaged_prev; // Signal: CcAslButtnCnclPress (cancel) - violation |= GET_BIT(to_send, 25U) && !controls_allowed; // Signal: CcAsllButtnResPress (resume) - - if (violation) { - tx = false; - } - } - - // Safety check for Lane_Assist_Data1 action - if (addr == FORD_Lane_Assist_Data1) { - // Do not allow steering using Lane_Assist_Data1 (Lane-Departure Aid). - // This message must be sent for Lane Centering to work, and can include - // values such as the steering angle or lane curvature for debugging, - // but the action (LkaActvStats_D2_Req) must be set to zero. - unsigned int action = GET_BYTE(to_send, 0) >> 5; - if (action != 0U) { - tx = false; - } - } - - // Safety check for LateralMotionControl action - if (addr == FORD_LateralMotionControl) { - // Signal: LatCtl_D_Rq - bool steer_control_enabled = ((GET_BYTE(to_send, 4) >> 2) & 0x7U) != 0U; - unsigned int raw_curvature = (GET_BYTE(to_send, 0) << 3) | (GET_BYTE(to_send, 1) >> 5); - unsigned int raw_curvature_rate = ((GET_BYTE(to_send, 1) & 0x1FU) << 8) | GET_BYTE(to_send, 2); - unsigned int raw_path_angle = (GET_BYTE(to_send, 3) << 3) | (GET_BYTE(to_send, 4) >> 5); - unsigned int raw_path_offset = (GET_BYTE(to_send, 5) << 2) | (GET_BYTE(to_send, 6) >> 6); - - // These signals are not yet tested with the current safety limits - bool violation = (raw_curvature_rate != FORD_INACTIVE_CURVATURE_RATE) || (raw_path_angle != FORD_INACTIVE_PATH_ANGLE) || (raw_path_offset != FORD_INACTIVE_PATH_OFFSET); - - // Check angle error and steer_control_enabled - int desired_curvature = raw_curvature - FORD_INACTIVE_CURVATURE; // /FORD_STEERING_LIMITS.angle_deg_to_can to get real curvature - violation |= steer_angle_cmd_checks(desired_curvature, steer_control_enabled, FORD_STEERING_LIMITS); - - if (violation) { - tx = false; - } - } - - // Safety check for LateralMotionControl2 action - if (addr == FORD_LateralMotionControl2) { - // Signal: LatCtl_D2_Rq - bool steer_control_enabled = ((GET_BYTE(to_send, 0) >> 4) & 0x7U) != 0U; - unsigned int raw_curvature = (GET_BYTE(to_send, 2) << 3) | (GET_BYTE(to_send, 3) >> 5); - unsigned int raw_curvature_rate = (GET_BYTE(to_send, 6) << 3) | (GET_BYTE(to_send, 7) >> 5); - unsigned int raw_path_angle = ((GET_BYTE(to_send, 3) & 0x1FU) << 6) | (GET_BYTE(to_send, 4) >> 2); - unsigned int raw_path_offset = ((GET_BYTE(to_send, 4) & 0x3U) << 8) | GET_BYTE(to_send, 5); - - // These signals are not yet tested with the current safety limits - bool violation = (raw_curvature_rate != FORD_CANFD_INACTIVE_CURVATURE_RATE) || (raw_path_angle != FORD_INACTIVE_PATH_ANGLE) || (raw_path_offset != FORD_INACTIVE_PATH_OFFSET); - - // Check angle error and steer_control_enabled - int desired_curvature = raw_curvature - FORD_INACTIVE_CURVATURE; // /FORD_STEERING_LIMITS.angle_deg_to_can to get real curvature - violation |= steer_angle_cmd_checks(desired_curvature, steer_control_enabled, FORD_STEERING_LIMITS); - - if (violation) { - tx = false; - } - } - - return tx; -} - -static int ford_fwd_hook(int bus_num, int addr) { - int bus_fwd = -1; - - switch (bus_num) { - case FORD_MAIN_BUS: { - // Forward all traffic from bus 0 onward - bus_fwd = FORD_CAM_BUS; - break; - } - case FORD_CAM_BUS: { - if (ford_lkas_msg_check(addr)) { - // Block stock LKAS and UI messages - bus_fwd = -1; - } else if (ford_longitudinal && (addr == FORD_ACCDATA)) { - // Block stock ACC message - bus_fwd = -1; - } else { - // Forward remaining traffic - bus_fwd = FORD_MAIN_BUS; - } - break; - } - default: { - // No other buses should be in use; fallback to do-not-forward - bus_fwd = -1; - break; - } - } - - return bus_fwd; -} - -static safety_config ford_init(uint16_t param) { - UNUSED(param); -#ifdef ALLOW_DEBUG - ford_longitudinal = GET_FLAG(param, FORD_PARAM_LONGITUDINAL); - ford_canfd = GET_FLAG(param, FORD_PARAM_CANFD); -#endif - - safety_config ret; - if (ford_canfd) { - ret = ford_longitudinal ? BUILD_SAFETY_CFG(ford_rx_checks, FORD_CANFD_LONG_TX_MSGS) : \ - BUILD_SAFETY_CFG(ford_rx_checks, FORD_CANFD_STOCK_TX_MSGS); - } else { - ret = ford_longitudinal ? BUILD_SAFETY_CFG(ford_rx_checks, FORD_LONG_TX_MSGS) : \ - BUILD_SAFETY_CFG(ford_rx_checks, FORD_STOCK_TX_MSGS); - } - return ret; -} - -const safety_hooks ford_hooks = { - .init = ford_init, - .rx = ford_rx_hook, - .tx = ford_tx_hook, - .fwd = ford_fwd_hook, - .get_counter = ford_get_counter, - .get_checksum = ford_get_checksum, - .compute_checksum = ford_compute_checksum, - .get_quality_flag_valid = ford_get_quality_flag_valid, -}; diff --git a/panda/board/safety/safety_gm.h b/panda/board/safety/safety_gm.h deleted file mode 100644 index fe1636b..0000000 --- a/panda/board/safety/safety_gm.h +++ /dev/null @@ -1,352 +0,0 @@ -const SteeringLimits GM_STEERING_LIMITS = { - .max_steer = 300, - .max_rate_up = 10, - .max_rate_down = 15, - .driver_torque_allowance = 65, - .driver_torque_factor = 4, - .max_rt_delta = 128, - .max_rt_interval = 250000, - .type = TorqueDriverLimited, -}; - -const LongitudinalLimits GM_ASCM_LONG_LIMITS = { - .max_gas = 3072, - .min_gas = 1404, - .inactive_gas = 1404, - .max_brake = 400, -}; - -const LongitudinalLimits GM_ASCM_LONG_LIMITS_SPORT = { - .max_gas = 8191, - .min_gas = 5500, - .inactive_gas = 5500, - .max_brake = 400, -}; - -const LongitudinalLimits GM_CAM_LONG_LIMITS = { - .max_gas = 3400, - .min_gas = 1514, - .inactive_gas = 1554, - .max_brake = 400, -}; - -const LongitudinalLimits GM_CAM_LONG_LIMITS_SPORT = { - .max_gas = 8848, - .min_gas = 5610, - .inactive_gas = 5650, - .max_brake = 400, -}; - -const LongitudinalLimits *gm_long_limits; - -const int GM_STANDSTILL_THRSLD = 10; // 0.311kph - -// panda interceptor threshold needs to be equivalent to openpilot threshold to avoid controls mismatches -// If thresholds are mismatched then it is possible for panda to see the gas fall and rise while openpilot is in the pre-enabled state -const int GM_GAS_INTERCEPTOR_THRESHOLD = 515; // (610 + 306.25) / 2 ratio between offset and gain from dbc file -#define GM_GET_INTERCEPTOR(msg) (((GET_BYTE((msg), 0) << 8) + GET_BYTE((msg), 1) + (GET_BYTE((msg), 2) << 8) + GET_BYTE((msg), 3)) / 2U) // avg between 2 tracks - -const CanMsg GM_ASCM_TX_MSGS[] = {{0x180, 0, 4}, {0x409, 0, 7}, {0x40A, 0, 7}, {0x2CB, 0, 8}, {0x370, 0, 6}, {0x200, 0, 6}, // pt bus - {0xA1, 1, 7}, {0x306, 1, 8}, {0x308, 1, 7}, {0x310, 1, 2}, // obs bus - {0x315, 2, 5}, // ch bus - {0x104c006c, 3, 3}, {0x10400060, 3, 5}}; // gmlan - -const CanMsg GM_CAM_TX_MSGS[] = {{0x180, 0, 4}, {0x200, 0, 6}, {0x1E1, 0, 7}, // pt bus - {0x1E1, 2, 7}, {0x184, 2, 8}}; // camera bus - -const CanMsg GM_CAM_LONG_TX_MSGS[] = {{0x180, 0, 4}, {0x315, 0, 5}, {0x2CB, 0, 8}, {0x370, 0, 6}, {0x200, 0, 6}, // pt bus - {0x1E1, 2, 7}, {0x184, 2, 8}}; // camera bus - -const CanMsg GM_SDGM_TX_MSGS[] = {{0x180, 0, 4}, {0x1E1, 0, 7}, // pt bus - {0x184, 2, 8}}; // camera bus - -const CanMsg GM_CC_LONG_TX_MSGS[] = {{0x180, 0, 4}, {0x1E1, 0, 7}, // pt bus - {0x184, 2, 8}, {0x1E1, 2, 7}}; // camera bus - -// TODO: do checksum and counter checks. Add correct timestep, 0.1s for now. -RxCheck gm_rx_checks[] = { - {.msg = {{0x184, 0, 8, .frequency = 10U}, { 0 }, { 0 }}}, - {.msg = {{0x34A, 0, 5, .frequency = 10U}, { 0 }, { 0 }}}, - {.msg = {{0x1E1, 0, 7, .frequency = 10U}, // Non-SDGM Car - {0x1E1, 2, 7, .frequency = 100000U}}}, // SDGM Car - {.msg = {{0xF1, 0, 6, .frequency = 10U}, // Non-SDGM Car - {0xF1, 2, 6, .frequency = 100000U}}}, // SDGM Car - {.msg = {{0x1C4, 0, 8, .frequency = 10U}, { 0 }, { 0 }}}, - {.msg = {{0xC9, 0, 8, .frequency = 10U}, { 0 }, { 0 }}}, -}; - -const uint16_t GM_PARAM_HW_CAM = 1; -const uint16_t GM_PARAM_HW_CAM_LONG = 2; -const uint16_t GM_PARAM_HW_SDGM = 4; -const uint16_t GM_PARAM_CC_LONG = 8; -const uint16_t GM_PARAM_HW_ASCM_LONG = 16; -const uint16_t GM_PARAM_NO_CAMERA = 32; -const uint16_t GM_PARAM_NO_ACC = 64; -const uint16_t GM_PARAM_PEDAL_LONG = 128; // TODO: this can be inferred -const uint16_t GM_PARAM_PEDAL_INTERCEPTOR = 256; - -enum { - GM_BTN_UNPRESS = 1, - GM_BTN_RESUME = 2, - GM_BTN_SET = 3, - GM_BTN_CANCEL = 6, -}; - -enum {GM_ASCM, GM_CAM, GM_SDGM} gm_hw = GM_ASCM; -bool gm_cam_long = false; -bool gm_pcm_cruise = false; -bool gm_has_acc = true; -bool gm_pedal_long = false; -bool gm_cc_long = false; -bool gm_skip_relay_check = false; -bool gm_force_ascm = false; - -static void handle_gm_wheel_buttons(const CANPacket_t *to_push) { - int button = (GET_BYTE(to_push, 5) & 0x70U) >> 4; - - // enter controls on falling edge of set or rising edge of resume (avoids fault) - bool set = (button != GM_BTN_SET) && (cruise_button_prev == GM_BTN_SET); - bool res = (button == GM_BTN_RESUME) && (cruise_button_prev != GM_BTN_RESUME); - if (set || res) { - controls_allowed = true; - } - - // exit controls on cancel press - if (button == GM_BTN_CANCEL) { - controls_allowed = false; - } - - cruise_button_prev = button; -} - -static void gm_rx_hook(const CANPacket_t *to_push) { - if ((GET_BUS(to_push) == 2U) && (GET_ADDR(to_push) == 0x1E1) && (gm_hw == GM_SDGM)) { - // SDGM buttons are on bus 2 - handle_gm_wheel_buttons(to_push); - } - - if (GET_BUS(to_push) == 0U) { - int addr = GET_ADDR(to_push); - - if (addr == 0x184) { - int torque_driver_new = ((GET_BYTE(to_push, 6) & 0x7U) << 8) | GET_BYTE(to_push, 7); - torque_driver_new = to_signed(torque_driver_new, 11); - // update array of samples - update_sample(&torque_driver, torque_driver_new); - } - - // sample rear wheel speeds - if (addr == 0x34A) { - int left_rear_speed = (GET_BYTE(to_push, 0) << 8) | GET_BYTE(to_push, 1); - int right_rear_speed = (GET_BYTE(to_push, 2) << 8) | GET_BYTE(to_push, 3); - vehicle_moving = (left_rear_speed > GM_STANDSTILL_THRSLD) || (right_rear_speed > GM_STANDSTILL_THRSLD); - } - - // ACC steering wheel buttons (GM_CAM and GM_SDGM are tied to the PCM) - if ((addr == 0x1E1) && (!gm_pcm_cruise || gm_cc_long) && (gm_hw != GM_SDGM)) { - handle_gm_wheel_buttons(to_push); - } - - // Reference for brake pressed signals: - // https://github.com/commaai/openpilot/blob/master/selfdrive/car/gm/carstate.py - if ((addr == 0xBE) && (gm_hw == GM_ASCM)) { - brake_pressed = GET_BYTE(to_push, 1) >= 8U; - } - - if ((addr == 0xC9) && ((gm_hw == GM_CAM) || (gm_hw == GM_SDGM))) { - acc_main_on = GET_BIT(to_push, 29U); - brake_pressed = GET_BIT(to_push, 40U); - } - - if (addr == 0x1C4) { - if (!enable_gas_interceptor) { - gas_pressed = GET_BYTE(to_push, 5) != 0U; - } - - // enter controls on rising edge of ACC, exit controls when ACC off - if (gm_pcm_cruise && gm_has_acc) { - bool cruise_engaged = (GET_BYTE(to_push, 1) >> 5) != 0U; - pcm_cruise_check(cruise_engaged); - } - } - - // Cruise check for CC only cars - if ((addr == 0x3D1) && !gm_has_acc) { - bool cruise_engaged = (GET_BYTE(to_push, 4) >> 7) != 0U; - if (gm_cc_long) { - pcm_cruise_check(cruise_engaged); - } else { - cruise_engaged_prev = cruise_engaged; - } - } - - if (addr == 0xBD) { - regen_braking = (GET_BYTE(to_push, 0) >> 4) != 0U; - } - - // Pedal Interceptor - if ((addr == 0x201) && enable_gas_interceptor) { - int gas_interceptor = GM_GET_INTERCEPTOR(to_push); - gas_pressed = gas_interceptor > GM_GAS_INTERCEPTOR_THRESHOLD; - gas_interceptor_prev = gas_interceptor; -// gm_pcm_cruise = false; - } - - bool stock_ecu_detected = (addr == 0x180); // ASCMLKASteeringCmd - - // Check ASCMGasRegenCmd only if we're blocking it - if (!gm_pcm_cruise && !gm_pedal_long && (addr == 0x2CB)) { - stock_ecu_detected = true; - } - generic_rx_checks(stock_ecu_detected); - } -} - -static bool gm_tx_hook(const CANPacket_t *to_send) { - bool tx = true; - int addr = GET_ADDR(to_send); - - // BRAKE: safety check - if (addr == 0x315) { - int brake = ((GET_BYTE(to_send, 0) & 0xFU) << 8) + GET_BYTE(to_send, 1); - brake = (0x1000 - brake) & 0xFFF; - if (longitudinal_brake_checks(brake, *gm_long_limits)) { - tx = false; - } - } - - // LKA STEER: safety check - if (addr == 0x180) { - int desired_torque = ((GET_BYTE(to_send, 0) & 0x7U) << 8) + GET_BYTE(to_send, 1); - desired_torque = to_signed(desired_torque, 11); - - bool steer_req = GET_BIT(to_send, 3U); - - if (steer_torque_cmd_checks(desired_torque, steer_req, GM_STEERING_LIMITS)) { - tx = false; - } - } - - // GAS: safety check (interceptor) - if (addr == 0x200) { - if (longitudinal_interceptor_checks(to_send)) { - tx = 0; - } - } - - // GAS/REGEN: safety check - if (addr == 0x2CB) { - bool apply = GET_BIT(to_send, 0U); - int gas_regen = ((GET_BYTE(to_send, 1) & 0x1U) << 13) + ((GET_BYTE(to_send, 2) & 0xFFU) << 5) + ((GET_BYTE(to_send, 3) & 0xF8U) >> 3); - - bool violation = false; - // Allow apply bit in pre-enabled and overriding states - violation |= !controls_allowed && apply; - violation |= longitudinal_gas_checks(gas_regen, *gm_long_limits); - - if (violation) { - tx = false; - } - } - - // BUTTONS: used for resume spamming and cruise cancellation with stock longitudinal - if ((addr == 0x1E1) && (gm_pcm_cruise || gm_pedal_long || gm_cc_long)) { - int button = (GET_BYTE(to_send, 5) >> 4) & 0x7U; - - bool allowed_btn = (button == GM_BTN_CANCEL) && cruise_engaged_prev; - // For standard CC, allow spamming of SET / RESUME - if (gm_cc_long) { - allowed_btn |= cruise_engaged_prev && (button == GM_BTN_SET || button == GM_BTN_RESUME || button == GM_BTN_UNPRESS); - } - - if (!allowed_btn) { - tx = false; - } - } - - return tx; -} - -static int gm_fwd_hook(int bus_num, int addr) { - int bus_fwd = -1; - - if ((gm_hw == GM_CAM) || (gm_hw == GM_SDGM)) { - if (bus_num == 0) { - // block PSCMStatus; forwarded through openpilot to hide an alert from the camera - bool is_pscm_msg = (addr == 0x184); - if (!is_pscm_msg) { - bus_fwd = 2; - } - } - - if (bus_num == 2) { - // block lkas message and acc messages if gm_cam_long, forward all others - bool is_lkas_msg = (addr == 0x180); - bool is_acc_msg = (addr == 0x315) || (addr == 0x2CB) || (addr == 0x370); - bool block_msg = is_lkas_msg || (is_acc_msg && gm_cam_long); - if (!block_msg) { - bus_fwd = 0; - } - } - } - - return bus_fwd; -} - -static safety_config gm_init(uint16_t param) { - sport_mode = alternative_experience & ALT_EXP_RAISE_LONGITUDINAL_LIMITS_TO_ISO_MAX; - - if GET_FLAG(param, GM_PARAM_HW_CAM) { - gm_hw = GM_CAM; - } else if GET_FLAG(param, GM_PARAM_HW_SDGM) { - gm_hw = GM_SDGM; - } else { - gm_hw = GM_ASCM; - } - - gm_force_ascm = GET_FLAG(param, GM_PARAM_HW_ASCM_LONG); - - if (gm_hw == GM_ASCM || gm_force_ascm) { - if (sport_mode) { - gm_long_limits = &GM_ASCM_LONG_LIMITS_SPORT; - } else { - gm_long_limits = &GM_ASCM_LONG_LIMITS; - } - } else if (gm_hw == GM_CAM) { - if (sport_mode) { - gm_long_limits = &GM_CAM_LONG_LIMITS_SPORT; - } else { - gm_long_limits = &GM_CAM_LONG_LIMITS; - } - } else { - } - - gm_pedal_long = GET_FLAG(param, GM_PARAM_PEDAL_LONG); - gm_cc_long = GET_FLAG(param, GM_PARAM_CC_LONG); - gm_cam_long = GET_FLAG(param, GM_PARAM_HW_CAM_LONG) && !gm_cc_long; - gm_pcm_cruise = ((gm_hw == GM_CAM) && (!gm_cam_long || gm_cc_long) && !gm_force_ascm && !gm_pedal_long) || (gm_hw == GM_SDGM); - gm_skip_relay_check = GET_FLAG(param, GM_PARAM_NO_CAMERA); - gm_has_acc = !GET_FLAG(param, GM_PARAM_NO_ACC); - enable_gas_interceptor = GET_FLAG(param, GM_PARAM_PEDAL_INTERCEPTOR); - - safety_config ret = BUILD_SAFETY_CFG(gm_rx_checks, GM_ASCM_TX_MSGS); - if (gm_hw == GM_CAM) { - if (gm_cc_long) { - ret = BUILD_SAFETY_CFG(gm_rx_checks, GM_CC_LONG_TX_MSGS); - } else if (gm_cam_long) { - ret = BUILD_SAFETY_CFG(gm_rx_checks, GM_CAM_LONG_TX_MSGS); - } else { - ret = BUILD_SAFETY_CFG(gm_rx_checks, GM_CAM_TX_MSGS); - } - } else if (gm_hw == GM_SDGM) { - ret = BUILD_SAFETY_CFG(gm_rx_checks, GM_SDGM_TX_MSGS); - } - return ret; -} - -const safety_hooks gm_hooks = { - .init = gm_init, - .rx = gm_rx_hook, - .tx = gm_tx_hook, - .fwd = gm_fwd_hook, -}; diff --git a/panda/board/safety/safety_honda.h b/panda/board/safety/safety_honda.h deleted file mode 100644 index 9af384b..0000000 --- a/panda/board/safety/safety_honda.h +++ /dev/null @@ -1,526 +0,0 @@ -const CanMsg HONDA_N_TX_MSGS[] = {{0xE4, 0, 5}, {0x194, 0, 4}, {0x1FA, 0, 8}, {0x30C, 0, 8}, {0x33D, 0, 5}}; -const CanMsg HONDA_N_INTERCEPTOR_TX_MSGS[] = {{0xE4, 0, 5}, {0x194, 0, 4}, {0x1FA, 0, 8}, {0x200, 0, 6}, {0x30C, 0, 8}, {0x33D, 0, 5}}; -const CanMsg HONDA_BOSCH_TX_MSGS[] = {{0xE4, 0, 5}, {0xE5, 0, 8}, {0x296, 1, 4}, {0x33D, 0, 5}, {0x33DA, 0, 5}, {0x33DB, 0, 8}}; // Bosch -const CanMsg HONDA_BOSCH_LONG_TX_MSGS[] = {{0xE4, 1, 5}, {0x1DF, 1, 8}, {0x1EF, 1, 8}, {0x1FA, 1, 8}, {0x30C, 1, 8}, {0x33D, 1, 5}, {0x33DA, 1, 5}, {0x33DB, 1, 8}, {0x39F, 1, 8}, {0x18DAB0F1, 1, 8}}; // Bosch w/ gas and brakes -const CanMsg HONDA_RADARLESS_TX_MSGS[] = {{0xE4, 0, 5}, {0x296, 2, 4}, {0x33D, 0, 8}}; // Bosch radarless -const CanMsg HONDA_RADARLESS_LONG_TX_MSGS[] = {{0xE4, 0, 5}, {0x33D, 0, 8}, {0x1C8, 0, 8}, {0x30C, 0, 8}}; // Bosch radarless w/ gas and brakes - -// panda interceptor threshold needs to be equivalent to openpilot threshold to avoid controls mismatches -// If thresholds are mismatched then it is possible for panda to see the gas fall and rise while openpilot is in the pre-enabled state -// Threshold calculated from DBC gains: round(((83.3 / 0.253984064) + (83.3 / 0.126992032)) / 2) = 492 -const int HONDA_GAS_INTERCEPTOR_THRESHOLD = 492; -#define HONDA_GET_INTERCEPTOR(msg) (((GET_BYTE((msg), 0) << 8) + GET_BYTE((msg), 1) + (GET_BYTE((msg), 2) << 8) + GET_BYTE((msg), 3)) / 2U) // avg between 2 tracks - -const LongitudinalLimits HONDA_BOSCH_LONG_LIMITS = { - .max_accel = 200, // accel is used for brakes - .min_accel = -350, - - .max_gas = 2000, - .inactive_gas = -30000, -}; - -const LongitudinalLimits HONDA_BOSCH_LONG_LIMITS_SPORT = { - .max_accel = 400, // accel is used for brakes - .min_accel = -350, - - .max_gas = 2000, - .inactive_gas = -30000, -}; - -const LongitudinalLimits HONDA_NIDEC_LONG_LIMITS = { - .max_gas = 198, // 0xc6 - .max_brake = 255, - - .inactive_speed = 0, -}; - -// All common address checks except SCM_BUTTONS which isn't on one Nidec safety configuration -#define HONDA_COMMON_NO_SCM_FEEDBACK_RX_CHECKS(pt_bus) \ - {.msg = {{0x1A6, (pt_bus), 8, .check_checksum = true, .max_counter = 3U, .frequency = 25U}, /* SCM_BUTTONS */ \ - {0x296, (pt_bus), 4, .check_checksum = true, .max_counter = 3U, .frequency = 25U}, { 0 }}}, \ - {.msg = {{0x158, (pt_bus), 8, .check_checksum = true, .max_counter = 3U, .frequency = 100U}, { 0 }, { 0 }}}, /* ENGINE_DATA */ \ - {.msg = {{0x17C, (pt_bus), 8, .check_checksum = true, .max_counter = 3U, .frequency = 100U}, { 0 }, { 0 }}}, /* POWERTRAIN_DATA */ \ - -#define HONDA_COMMON_RX_CHECKS(pt_bus) \ - HONDA_COMMON_NO_SCM_FEEDBACK_RX_CHECKS(pt_bus) \ - {.msg = {{0x326, (pt_bus), 8, .check_checksum = true, .max_counter = 3U, .frequency = 10U}, { 0 }, { 0 }}}, /* SCM_FEEDBACK */ \ - -// Alternate brake message is used on some Honda Bosch, and Honda Bosch radarless (where PT bus is 0) -#define HONDA_ALT_BRAKE_ADDR_CHECK(pt_bus) \ - {.msg = {{0x1BE, (pt_bus), 3, .check_checksum = true, .max_counter = 3U, .frequency = 50U}, { 0 }, { 0 }}}, /* BRAKE_MODULE */ \ - - -// Nidec and bosch radarless has the powertrain bus on bus 0 -RxCheck honda_common_rx_checks[] = { - HONDA_COMMON_RX_CHECKS(0) -}; - -RxCheck honda_common_interceptor_rx_checks[] = { - HONDA_COMMON_RX_CHECKS(0) - {.msg = {{0x201, 0, 6, .check_checksum = false, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, -}; - -RxCheck honda_common_alt_brake_rx_checks[] = { - HONDA_COMMON_RX_CHECKS(0) - HONDA_ALT_BRAKE_ADDR_CHECK(0) -}; - -// For Nidecs with main on signal on an alternate msg (missing 0x326) -RxCheck honda_nidec_alt_rx_checks[] = { - HONDA_COMMON_NO_SCM_FEEDBACK_RX_CHECKS(0) -}; - -RxCheck honda_nidec_alt_interceptor_rx_checks[] = { - HONDA_COMMON_NO_SCM_FEEDBACK_RX_CHECKS(0) - {.msg = {{0x201, 0, 6, .check_checksum = false, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, -}; - -// Bosch has pt on bus 1, verified 0x1A6 does not exist -RxCheck honda_bosch_rx_checks[] = { - HONDA_COMMON_RX_CHECKS(1) -}; - -RxCheck honda_bosch_alt_brake_rx_checks[] = { - HONDA_COMMON_RX_CHECKS(1) - HONDA_ALT_BRAKE_ADDR_CHECK(1) -}; - -const uint16_t HONDA_PARAM_ALT_BRAKE = 1; -const uint16_t HONDA_PARAM_BOSCH_LONG = 2; -const uint16_t HONDA_PARAM_NIDEC_ALT = 4; -const uint16_t HONDA_PARAM_RADARLESS = 8; -const uint16_t HONDA_PARAM_GAS_INTERCEPTOR = 16; -const uint16_t HONDA_PARAM_CLARITY = 32; - -enum { - HONDA_BTN_NONE = 0, - HONDA_BTN_MAIN = 1, - HONDA_BTN_CANCEL = 2, - HONDA_BTN_SET = 3, - HONDA_BTN_RESUME = 4, -}; - -int honda_brake = 0; -bool honda_brake_switch_prev = false; -bool honda_alt_brake_msg = false; -bool honda_fwd_brake = false; -bool honda_bosch_long = false; -bool honda_bosch_radarless = false; -bool honda_clarity_brake_msg = false; -enum {HONDA_NIDEC, HONDA_BOSCH} honda_hw = HONDA_NIDEC; - - -int honda_get_pt_bus(void) { - return ((honda_hw == HONDA_BOSCH) && !honda_bosch_radarless) ? 1 : 0; -} - -static uint32_t honda_get_checksum(const CANPacket_t *to_push) { - int checksum_byte = GET_LEN(to_push) - 1U; - return (uint8_t)(GET_BYTE(to_push, checksum_byte)) & 0xFU; -} - -static uint32_t honda_compute_checksum(const CANPacket_t *to_push) { - int len = GET_LEN(to_push); - uint8_t checksum = 0U; - unsigned int addr = GET_ADDR(to_push); - while (addr > 0U) { - checksum += (uint8_t)(addr & 0xFU); addr >>= 4; - } - for (int j = 0; j < len; j++) { - uint8_t byte = GET_BYTE(to_push, j); - checksum += (uint8_t)(byte & 0xFU) + (byte >> 4U); - if (j == (len - 1)) { - checksum -= (byte & 0xFU); // remove checksum in message - } - } - return (uint8_t)((8U - checksum) & 0xFU); -} - -static uint8_t honda_get_counter(const CANPacket_t *to_push) { - int addr = GET_ADDR(to_push); - - uint8_t cnt = 0U; - if (addr == 0x201) { - // Signal: COUNTER_PEDAL - cnt = GET_BYTE(to_push, 4) & 0x0FU; - } else { - int counter_byte = GET_LEN(to_push) - 1U; - cnt = (GET_BYTE(to_push, counter_byte) >> 4U) & 0x3U; - } - return cnt; -} - -static void honda_rx_hook(const CANPacket_t *to_push) { - const bool pcm_cruise = ((honda_hw == HONDA_BOSCH) && !honda_bosch_long) || \ - ((honda_hw == HONDA_NIDEC) && !enable_gas_interceptor); - int pt_bus = honda_get_pt_bus(); - - int addr = GET_ADDR(to_push); - int len = GET_LEN(to_push); - int bus = GET_BUS(to_push); - - // sample speed - if (addr == 0x158) { - // first 2 bytes - vehicle_moving = GET_BYTE(to_push, 0) | GET_BYTE(to_push, 1); - } - - // check ACC main state - // 0x326 for all Bosch and some Nidec, 0x1A6 for some Nidec - if ((addr == 0x326) || (addr == 0x1A6)) { - acc_main_on = GET_BIT(to_push, ((addr == 0x326) ? 28U : 47U)); - if (!acc_main_on) { - controls_allowed = false; - } - } - - // enter controls when PCM enters cruise state - if (pcm_cruise && (addr == 0x17C)) { - const bool cruise_engaged = GET_BIT(to_push, 38U); - // engage on rising edge - if (cruise_engaged && !cruise_engaged_prev) { - controls_allowed = true; - } - - // Since some Nidec cars can brake down to 0 after the PCM disengages, - // we don't disengage when the PCM does. - if (!cruise_engaged && (honda_hw != HONDA_NIDEC)) { - controls_allowed = false; - } - cruise_engaged_prev = cruise_engaged; - } - - // state machine to enter and exit controls for button enabling - // 0x1A6 for the ILX, 0x296 for the Civic Touring - if (((addr == 0x1A6) || (addr == 0x296)) && (bus == pt_bus)) { - int button = (GET_BYTE(to_push, 0) & 0xE0U) >> 5; - - // enter controls on the falling edge of set or resume - bool set = (button != HONDA_BTN_SET) && (cruise_button_prev == HONDA_BTN_SET); - bool res = (button != HONDA_BTN_RESUME) && (cruise_button_prev == HONDA_BTN_RESUME); - if (acc_main_on && !pcm_cruise && (set || res)) { - controls_allowed = true; - } - - // exit controls once main or cancel are pressed - if ((button == HONDA_BTN_MAIN) || (button == HONDA_BTN_CANCEL)) { - controls_allowed = false; - } - cruise_button_prev = button; - } - - // user brake signal on 0x17C reports applied brake from computer brake on accord - // and crv, which prevents the usual brake safety from working correctly. these - // cars have a signal on 0x1BE which only detects user's brake being applied so - // in these cases, this is used instead. - // most hondas: 0x17C - // accord, crv: 0x1BE - if (honda_alt_brake_msg) { - if (addr == 0x1BE) { - brake_pressed = GET_BIT(to_push, 4U); - } - } else { - if (addr == 0x17C) { - // also if brake switch is 1 for two CAN frames, as brake pressed is delayed - const bool brake_switch = GET_BIT(to_push, 32U); - brake_pressed = (GET_BIT(to_push, 53U)) || (brake_switch && honda_brake_switch_prev); - honda_brake_switch_prev = brake_switch; - } - } - - // length check because bosch hardware also uses this id (0x201 w/ len = 8) - if ((addr == 0x201) && (len == 6) && enable_gas_interceptor) { - int gas_interceptor = HONDA_GET_INTERCEPTOR(to_push); - gas_pressed = gas_interceptor > HONDA_GAS_INTERCEPTOR_THRESHOLD; - gas_interceptor_prev = gas_interceptor; - } - - if (!enable_gas_interceptor) { - if (addr == 0x17C) { - gas_pressed = GET_BYTE(to_push, 0) != 0U; - } - } - - // disable stock Honda AEB in alternative experience - if (!(alternative_experience & ALT_EXP_DISABLE_STOCK_AEB)) { - if ((bus == 2) && (addr == 0x1FA)) { - bool honda_stock_aeb = GET_BIT(to_push, 29U); - int honda_stock_brake = (GET_BYTE(to_push, 0) << 2) | (GET_BYTE(to_push, 1) >> 6); - - if (honda_clarity_brake_msg) { - honda_stock_brake = (GET_BYTE(to_push, 6) << 2) + ((GET_BYTE(to_push, 7) >> 6) & 0x3U); - } - // Forward AEB when stock braking is higher than openpilot braking - // only stop forwarding when AEB event is over - if (!honda_stock_aeb) { - honda_fwd_brake = false; - } else if (honda_stock_brake >= honda_brake) { - honda_fwd_brake = true; - } else { - // Leave Honda forward brake as is - } - } - } - - int bus_rdr_car = (honda_hw == HONDA_BOSCH) ? 0 : 2; // radar bus, car side - bool stock_ecu_detected = false; - - // If steering controls messages are received on the destination bus, it's an indication - // that the relay might be malfunctioning - if ((addr == 0xE4) || (addr == 0x194)) { - if (((honda_hw != HONDA_NIDEC) && (bus == bus_rdr_car)) || ((honda_hw == HONDA_NIDEC) && (bus == 0))) { - stock_ecu_detected = true; - } - } - // If Honda Bosch longitudinal mode is selected we need to ensure the radar is turned off - // Verify this by ensuring ACC_CONTROL (0x1DF) is not received on the PT bus - if (honda_bosch_long && !honda_bosch_radarless && (bus == pt_bus) && (addr == 0x1DF)) { - stock_ecu_detected = true; - } - - generic_rx_checks(stock_ecu_detected); - -} - -static bool honda_tx_hook(const CANPacket_t *to_send) { - sport_mode = alternative_experience & ALT_EXP_RAISE_LONGITUDINAL_LIMITS_TO_ISO_MAX; - - bool tx = true; - int addr = GET_ADDR(to_send); - int bus = GET_BUS(to_send); - - int bus_pt = honda_get_pt_bus(); - int bus_buttons = (honda_bosch_radarless) ? 2 : bus_pt; // the camera controls ACC on radarless Bosch cars - - // ACC_HUD: safety check (nidec w/o pedal) - if ((addr == 0x30C) && (bus == bus_pt)) { - int pcm_speed = (GET_BYTE(to_send, 0) << 8) | GET_BYTE(to_send, 1); - int pcm_gas = GET_BYTE(to_send, 2); - - bool violation = false; - violation |= longitudinal_speed_checks(pcm_speed, HONDA_NIDEC_LONG_LIMITS); - violation |= longitudinal_gas_checks(pcm_gas, HONDA_NIDEC_LONG_LIMITS); - if (violation) { - tx = false; - } - } - - // BRAKE: safety check (nidec) - if ((addr == 0x1FA) && (bus == bus_pt)) { - honda_brake = (GET_BYTE(to_send, 0) << 2) + ((GET_BYTE(to_send, 1) >> 6) & 0x3U); - if (honda_clarity_brake_msg) { - honda_brake = (GET_BYTE(to_send, 6) << 2) + ((GET_BYTE(to_send, 7) >> 6) & 0x3U); - } - if (longitudinal_brake_checks(honda_brake, HONDA_NIDEC_LONG_LIMITS)) { - tx = false; - } - if (honda_fwd_brake) { - tx = false; - } - } - - // BRAKE/GAS: safety check (bosch) - if ((addr == 0x1DF) && (bus == bus_pt)) { - int accel = (GET_BYTE(to_send, 3) << 3) | ((GET_BYTE(to_send, 4) >> 5) & 0x7U); - accel = to_signed(accel, 11); - - int gas = (GET_BYTE(to_send, 0) << 8) | GET_BYTE(to_send, 1); - gas = to_signed(gas, 16); - - bool violation = false; - if (sport_mode) { - violation |= longitudinal_accel_checks(accel, HONDA_BOSCH_LONG_LIMITS_SPORT); - violation |= longitudinal_gas_checks(gas, HONDA_BOSCH_LONG_LIMITS_SPORT); - } else { - violation |= longitudinal_accel_checks(accel, HONDA_BOSCH_LONG_LIMITS); - violation |= longitudinal_gas_checks(gas, HONDA_BOSCH_LONG_LIMITS); - } - if (violation) { - tx = false; - } - } - - // ACCEL: safety check (radarless) - if ((addr == 0x1C8) && (bus == bus_pt)) { - int accel = (GET_BYTE(to_send, 0) << 4) | (GET_BYTE(to_send, 1) >> 4); - accel = to_signed(accel, 12); - - bool violation = false; - if (sport_mode) { - violation |= longitudinal_accel_checks(accel, HONDA_BOSCH_LONG_LIMITS_SPORT); - } else { - violation |= longitudinal_accel_checks(accel, HONDA_BOSCH_LONG_LIMITS); - } - if (violation) { - tx = false; - } - } - - // STEER: safety check - if ((addr == 0xE4) || (addr == 0x194)) { - bool aol_allowed = acc_main_on && (alternative_experience & ALT_EXP_DISABLE_DISENGAGE_ON_GAS); - if (!(controls_allowed || aol_allowed)) { - bool steer_applied = GET_BYTE(to_send, 0) | GET_BYTE(to_send, 1); - if (steer_applied) { - tx = false; - } - } - } - - // Bosch supplemental control check - if (addr == 0xE5) { - if ((GET_BYTES(to_send, 0, 4) != 0x10800004U) || ((GET_BYTES(to_send, 4, 4) & 0x00FFFFFFU) != 0x0U)) { - tx = false; - } - } - - // GAS: safety check (interceptor) - if (addr == 0x200) { - if (longitudinal_interceptor_checks(to_send)) { - tx = false; - } - } - - // FORCE CANCEL: safety check only relevant when spamming the cancel button in Bosch HW - // ensuring that only the cancel button press is sent (VAL 2) when controls are off. - // This avoids unintended engagements while still allowing resume spam - if ((addr == 0x296) && !controls_allowed && (bus == bus_buttons)) { - if (((GET_BYTE(to_send, 0) >> 5) & 0x7U) != 2U) { - tx = false; - } - } - - // Only tester present ("\x02\x3E\x80\x00\x00\x00\x00\x00") allowed on diagnostics address - if (addr == 0x18DAB0F1) { - if ((GET_BYTES(to_send, 0, 4) != 0x00803E02U) || (GET_BYTES(to_send, 4, 4) != 0x0U)) { - tx = false; - } - } - - return tx; -} - -static safety_config honda_nidec_init(uint16_t param) { - honda_hw = HONDA_NIDEC; - honda_brake = 0; - honda_brake_switch_prev = false; - honda_fwd_brake = false; - honda_alt_brake_msg = false; - honda_bosch_long = false; - honda_bosch_radarless = false; - enable_gas_interceptor = GET_FLAG(param, HONDA_PARAM_GAS_INTERCEPTOR); - honda_clarity_brake_msg = GET_FLAG(param, HONDA_PARAM_CLARITY); - - safety_config ret; - - bool enable_nidec_alt = GET_FLAG(param, HONDA_PARAM_NIDEC_ALT); - if (enable_nidec_alt) { - enable_gas_interceptor ? SET_RX_CHECKS(honda_nidec_alt_interceptor_rx_checks, ret) : \ - SET_RX_CHECKS(honda_nidec_alt_rx_checks, ret); - } else { - enable_gas_interceptor ? SET_RX_CHECKS(honda_common_interceptor_rx_checks, ret) : \ - SET_RX_CHECKS(honda_common_rx_checks, ret); - } - - if (enable_gas_interceptor) { - SET_TX_MSGS(HONDA_N_INTERCEPTOR_TX_MSGS, ret); - } else { - SET_TX_MSGS(HONDA_N_TX_MSGS, ret); - } - return ret; -} - -static safety_config honda_bosch_init(uint16_t param) { - honda_hw = HONDA_BOSCH; - honda_brake_switch_prev = false; - honda_bosch_radarless = GET_FLAG(param, HONDA_PARAM_RADARLESS); - // Checking for alternate brake override from safety parameter - honda_alt_brake_msg = GET_FLAG(param, HONDA_PARAM_ALT_BRAKE); - - // radar disabled so allow gas/brakes -#ifdef ALLOW_DEBUG - honda_bosch_long = GET_FLAG(param, HONDA_PARAM_BOSCH_LONG); -#endif - - safety_config ret; - if (honda_bosch_radarless && honda_alt_brake_msg) { - SET_RX_CHECKS(honda_common_alt_brake_rx_checks, ret); - } else if (honda_bosch_radarless) { - SET_RX_CHECKS(honda_common_rx_checks, ret); - } else if (honda_alt_brake_msg) { - SET_RX_CHECKS(honda_bosch_alt_brake_rx_checks, ret); - } else { - SET_RX_CHECKS(honda_bosch_rx_checks, ret); - } - - if (honda_bosch_radarless) { - honda_bosch_long ? SET_TX_MSGS(HONDA_RADARLESS_LONG_TX_MSGS, ret) : \ - SET_TX_MSGS(HONDA_RADARLESS_TX_MSGS, ret); - } else { - honda_bosch_long ? SET_TX_MSGS(HONDA_BOSCH_LONG_TX_MSGS, ret) : \ - SET_TX_MSGS(HONDA_BOSCH_TX_MSGS, ret); - } - return ret; -} - -static int honda_nidec_fwd_hook(int bus_num, int addr) { - // fwd from car to camera. also fwd certain msgs from camera to car - // 0xE4 is steering on all cars except CRV and RDX, 0x194 for CRV and RDX, - // 0x1FA is brake control, 0x30C is acc hud, 0x33D is lkas hud - int bus_fwd = -1; - - if (bus_num == 0) { - bus_fwd = 2; - } - - if (bus_num == 2) { - // block stock lkas messages and stock acc messages (if OP is doing ACC) - bool is_lkas_msg = (addr == 0xE4) || (addr == 0x194) || (addr == 0x33D); - bool is_acc_hud_msg = addr == 0x30C; - bool is_brake_msg = addr == 0x1FA; - bool block_fwd = is_lkas_msg || is_acc_hud_msg || (is_brake_msg && !honda_fwd_brake); - if (!block_fwd) { - bus_fwd = 0; - } - } - - return bus_fwd; -} - -static int honda_bosch_fwd_hook(int bus_num, int addr) { - int bus_fwd = -1; - - if (bus_num == 0) { - bus_fwd = 2; - } - if (bus_num == 2) { - bool is_lkas_msg = (addr == 0xE4) || (addr == 0xE5) || (addr == 0x33D) || (addr == 0x33DA) || (addr == 0x33DB); - bool is_acc_msg = ((addr == 0x1C8) || (addr == 0x30C)) && honda_bosch_radarless && honda_bosch_long; - bool block_msg = is_lkas_msg || is_acc_msg; - if (!block_msg) { - bus_fwd = 0; - } - } - - return bus_fwd; -} - -const safety_hooks honda_nidec_hooks = { - .init = honda_nidec_init, - .rx = honda_rx_hook, - .tx = honda_tx_hook, - .fwd = honda_nidec_fwd_hook, - .get_counter = honda_get_counter, - .get_checksum = honda_get_checksum, - .compute_checksum = honda_compute_checksum, -}; - -const safety_hooks honda_bosch_hooks = { - .init = honda_bosch_init, - .rx = honda_rx_hook, - .tx = honda_tx_hook, - .fwd = honda_bosch_fwd_hook, - .get_counter = honda_get_counter, - .get_checksum = honda_get_checksum, - .compute_checksum = honda_compute_checksum, -}; diff --git a/panda/board/safety/safety_hyundai.h b/panda/board/safety/safety_hyundai.h deleted file mode 100644 index a849a87..0000000 --- a/panda/board/safety/safety_hyundai.h +++ /dev/null @@ -1,356 +0,0 @@ -#include "safety_hyundai_common.h" - -#define HYUNDAI_LIMITS(steer, rate_up, rate_down) { \ - .max_steer = (steer), \ - .max_rate_up = (rate_up), \ - .max_rate_down = (rate_down), \ - .max_rt_delta = 112, \ - .max_rt_interval = 250000, \ - .driver_torque_allowance = 50, \ - .driver_torque_factor = 2, \ - .type = TorqueDriverLimited, \ - /* the EPS faults when the steering angle is above a certain threshold for too long. to prevent this, */ \ - /* we allow setting CF_Lkas_ActToi bit to 0 while maintaining the requested torque value for two consecutive frames */ \ - .min_valid_request_frames = 89, \ - .max_invalid_request_frames = 2, \ - .min_valid_request_rt_interval = 810000, /* 810ms; a ~10% buffer on cutting every 90 frames */ \ - .has_steer_req_tolerance = true, \ -} - -const SteeringLimits HYUNDAI_STEERING_LIMITS = HYUNDAI_LIMITS(384, 3, 7); -const SteeringLimits HYUNDAI_STEERING_LIMITS_ALT = HYUNDAI_LIMITS(270, 2, 3); - -const LongitudinalLimits HYUNDAI_LONG_LIMITS = { - .max_accel = 200, // 1/100 m/s2 - .min_accel = -350, // 1/100 m/s2 -}; - -const LongitudinalLimits HYUNDAI_LONG_LIMITS_SPORT = { - .max_accel = 400, // 1/100 m/s2 - .min_accel = -350, // 1/100 m/s2 -}; - -const CanMsg HYUNDAI_TX_MSGS[] = { - {0x340, 0, 8}, // LKAS11 Bus 0 - {0x4F1, 0, 4}, // CLU11 Bus 0 - {0x485, 0, 4}, // LFAHDA_MFC Bus 0 -}; - -const CanMsg HYUNDAI_LONG_TX_MSGS[] = { - {0x340, 0, 8}, // LKAS11 Bus 0 - {0x4F1, 0, 4}, // CLU11 Bus 0 - {0x485, 0, 4}, // LFAHDA_MFC Bus 0 - {0x420, 0, 8}, // SCC11 Bus 0 - {0x421, 0, 8}, // SCC12 Bus 0 - {0x50A, 0, 8}, // SCC13 Bus 0 - {0x389, 0, 8}, // SCC14 Bus 0 - {0x4A2, 0, 2}, // FRT_RADAR11 Bus 0 - {0x38D, 0, 8}, // FCA11 Bus 0 - {0x483, 0, 8}, // FCA12 Bus 0 - {0x7D0, 0, 8}, // radar UDS TX addr Bus 0 (for radar disable) -}; - -const CanMsg HYUNDAI_CAMERA_SCC_TX_MSGS[] = { - {0x340, 0, 8}, // LKAS11 Bus 0 - {0x4F1, 2, 4}, // CLU11 Bus 2 - {0x485, 0, 4}, // LFAHDA_MFC Bus 0 -}; - -#define HYUNDAI_COMMON_RX_CHECKS(legacy) \ - {.msg = {{0x260, 0, 8, .check_checksum = true, .max_counter = 3U, .frequency = 100U}, \ - {0x371, 0, 8, .frequency = 100U}, { 0 }}}, \ - {.msg = {{0x386, 0, 8, .check_checksum = !(legacy), .max_counter = (legacy) ? 0U : 15U, .frequency = 100U}, { 0 }, { 0 }}}, \ - {.msg = {{0x394, 0, 8, .check_checksum = !(legacy), .max_counter = (legacy) ? 0U : 7U, .frequency = 100U}, { 0 }, { 0 }}}, \ - -#define HYUNDAI_SCC12_ADDR_CHECK(scc_bus) \ - {.msg = {{0x421, (scc_bus), 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, \ - -RxCheck hyundai_rx_checks[] = { - HYUNDAI_COMMON_RX_CHECKS(false) - HYUNDAI_SCC12_ADDR_CHECK(0) -}; - -RxCheck hyundai_cam_scc_rx_checks[] = { - HYUNDAI_COMMON_RX_CHECKS(false) - HYUNDAI_SCC12_ADDR_CHECK(2) -}; - -RxCheck hyundai_long_rx_checks[] = { - HYUNDAI_COMMON_RX_CHECKS(false) - // Use CLU11 (buttons) to manage controls allowed instead of SCC cruise state - {.msg = {{0x4F1, 0, 4, .check_checksum = false, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, -}; - -// older hyundai models have less checks due to missing counters and checksums -RxCheck hyundai_legacy_rx_checks[] = { - HYUNDAI_COMMON_RX_CHECKS(true) - HYUNDAI_SCC12_ADDR_CHECK(0) -}; - -bool hyundai_legacy = false; - - -static uint8_t hyundai_get_counter(const CANPacket_t *to_push) { - int addr = GET_ADDR(to_push); - - uint8_t cnt = 0; - if (addr == 0x260) { - cnt = (GET_BYTE(to_push, 7) >> 4) & 0x3U; - } else if (addr == 0x386) { - cnt = ((GET_BYTE(to_push, 3) >> 6) << 2) | (GET_BYTE(to_push, 1) >> 6); - } else if (addr == 0x394) { - cnt = (GET_BYTE(to_push, 1) >> 5) & 0x7U; - } else if (addr == 0x421) { - cnt = GET_BYTE(to_push, 7) & 0xFU; - } else if (addr == 0x4F1) { - cnt = (GET_BYTE(to_push, 3) >> 4) & 0xFU; - } else { - } - return cnt; -} - -static uint32_t hyundai_get_checksum(const CANPacket_t *to_push) { - int addr = GET_ADDR(to_push); - - uint8_t chksum = 0; - if (addr == 0x260) { - chksum = GET_BYTE(to_push, 7) & 0xFU; - } else if (addr == 0x386) { - chksum = ((GET_BYTE(to_push, 7) >> 6) << 2) | (GET_BYTE(to_push, 5) >> 6); - } else if (addr == 0x394) { - chksum = GET_BYTE(to_push, 6) & 0xFU; - } else if (addr == 0x421) { - chksum = GET_BYTE(to_push, 7) >> 4; - } else { - } - return chksum; -} - -static uint32_t hyundai_compute_checksum(const CANPacket_t *to_push) { - int addr = GET_ADDR(to_push); - - uint8_t chksum = 0; - if (addr == 0x386) { - // count the bits - for (int i = 0; i < 8; i++) { - uint8_t b = GET_BYTE(to_push, i); - for (int j = 0; j < 8; j++) { - uint8_t bit = 0; - // exclude checksum and counter - if (((i != 1) || (j < 6)) && ((i != 3) || (j < 6)) && ((i != 5) || (j < 6)) && ((i != 7) || (j < 6))) { - bit = (b >> (uint8_t)j) & 1U; - } - chksum += bit; - } - } - chksum = (chksum ^ 9U) & 15U; - } else { - // sum of nibbles - for (int i = 0; i < 8; i++) { - if ((addr == 0x394) && (i == 7)) { - continue; // exclude - } - uint8_t b = GET_BYTE(to_push, i); - if (((addr == 0x260) && (i == 7)) || ((addr == 0x394) && (i == 6)) || ((addr == 0x421) && (i == 7))) { - b &= (addr == 0x421) ? 0x0FU : 0xF0U; // remove checksum - } - chksum += (b % 16U) + (b / 16U); - } - chksum = (16U - (chksum % 16U)) % 16U; - } - - return chksum; -} - -static void hyundai_rx_hook(const CANPacket_t *to_push) { - int bus = GET_BUS(to_push); - int addr = GET_ADDR(to_push); - - // SCC12 is on bus 2 for camera-based SCC cars, bus 0 on all others - if ((addr == 0x421) && (((bus == 0) && !hyundai_camera_scc) || ((bus == 2) && hyundai_camera_scc))) { - // 2 bits: 13-14 - int cruise_engaged = (GET_BYTES(to_push, 0, 4) >> 13) & 0x3U; - hyundai_common_cruise_state_check(cruise_engaged); - } - - if (bus == 0) { - if (addr == 0x251) { - int torque_driver_new = (GET_BYTES(to_push, 0, 2) & 0x7ffU) - 1024U; - // update array of samples - update_sample(&torque_driver, torque_driver_new); - } - - // ACC steering wheel buttons - if (addr == 0x4F1) { - int cruise_button = GET_BYTE(to_push, 0) & 0x7U; - bool main_button = GET_BIT(to_push, 3U); - hyundai_common_cruise_buttons_check(cruise_button, main_button); - } - - // gas press, different for EV, hybrid, and ICE models - if ((addr == 0x371) && hyundai_ev_gas_signal) { - gas_pressed = (((GET_BYTE(to_push, 4) & 0x7FU) << 1) | GET_BYTE(to_push, 3) >> 7) != 0U; - } else if ((addr == 0x371) && hyundai_hybrid_gas_signal) { - gas_pressed = GET_BYTE(to_push, 7) != 0U; - } else if ((addr == 0x260) && !hyundai_ev_gas_signal && !hyundai_hybrid_gas_signal) { - gas_pressed = (GET_BYTE(to_push, 7) >> 6) != 0U; - } else { - } - - // sample wheel speed, averaging opposite corners - if (addr == 0x386) { - uint32_t front_left_speed = GET_BYTES(to_push, 0, 2) & 0x3FFFU; - uint32_t rear_right_speed = GET_BYTES(to_push, 6, 2) & 0x3FFFU; - vehicle_moving = (front_left_speed > HYUNDAI_STANDSTILL_THRSLD) || (rear_right_speed > HYUNDAI_STANDSTILL_THRSLD); - } - - if (addr == 0x394) { - brake_pressed = ((GET_BYTE(to_push, 5) >> 5U) & 0x3U) == 0x2U; - } - - bool stock_ecu_detected = (addr == 0x340); - - // If openpilot is controlling longitudinal we need to ensure the radar is turned off - // Enforce by checking we don't see SCC12 - if (hyundai_longitudinal && (addr == 0x421)) { - stock_ecu_detected = true; - } - generic_rx_checks(stock_ecu_detected); - } -} - -static bool hyundai_tx_hook(const CANPacket_t *to_send) { - sport_mode = alternative_experience & ALT_EXP_RAISE_LONGITUDINAL_LIMITS_TO_ISO_MAX; - - bool tx = true; - int addr = GET_ADDR(to_send); - - // FCA11: Block any potential actuation - if (addr == 0x38D) { - int CR_VSM_DecCmd = GET_BYTE(to_send, 1); - bool FCA_CmdAct = GET_BIT(to_send, 20U); - bool CF_VSM_DecCmdAct = GET_BIT(to_send, 31U); - - if ((CR_VSM_DecCmd != 0) || FCA_CmdAct || CF_VSM_DecCmdAct) { - tx = false; - } - } - - // ACCEL: safety check - if (addr == 0x421) { - int desired_accel_raw = (((GET_BYTE(to_send, 4) & 0x7U) << 8) | GET_BYTE(to_send, 3)) - 1023U; - int desired_accel_val = ((GET_BYTE(to_send, 5) << 3) | (GET_BYTE(to_send, 4) >> 5)) - 1023U; - - int aeb_decel_cmd = GET_BYTE(to_send, 2); - bool aeb_req = GET_BIT(to_send, 54U); - - bool violation = false; - - if (sport_mode) { - violation |= longitudinal_accel_checks(desired_accel_raw, HYUNDAI_LONG_LIMITS_SPORT); - violation |= longitudinal_accel_checks(desired_accel_val, HYUNDAI_LONG_LIMITS_SPORT); - } else { - violation |= longitudinal_accel_checks(desired_accel_raw, HYUNDAI_LONG_LIMITS); - violation |= longitudinal_accel_checks(desired_accel_val, HYUNDAI_LONG_LIMITS); - } - violation |= (aeb_decel_cmd != 0); - violation |= aeb_req; - - if (violation) { - tx = false; - } - } - - // LKA STEER: safety check - if (addr == 0x340) { - int desired_torque = ((GET_BYTES(to_send, 0, 4) >> 16) & 0x7ffU) - 1024U; - bool steer_req = GET_BIT(to_send, 27U); - - const SteeringLimits limits = hyundai_alt_limits ? HYUNDAI_STEERING_LIMITS_ALT : HYUNDAI_STEERING_LIMITS; - if (steer_torque_cmd_checks(desired_torque, steer_req, limits)) { - tx = false; - } - } - - // UDS: Only tester present ("\x02\x3E\x80\x00\x00\x00\x00\x00") allowed on diagnostics address - if (addr == 0x7D0) { - if ((GET_BYTES(to_send, 0, 4) != 0x00803E02U) || (GET_BYTES(to_send, 4, 4) != 0x0U)) { - tx = false; - } - } - - // BUTTONS: used for resume spamming and cruise cancellation - if ((addr == 0x4F1) && !hyundai_longitudinal) { - int button = GET_BYTE(to_send, 0) & 0x7U; - - bool allowed_resume = (button == 1) && controls_allowed; - bool allowed_cancel = (button == 4) && cruise_engaged_prev; - if (!(allowed_resume || allowed_cancel)) { - tx = false; - } - } - - return tx; -} - -static int hyundai_fwd_hook(int bus_num, int addr) { - - int bus_fwd = -1; - - // forward cam to ccan and viceversa, except lkas cmd - if (bus_num == 0) { - bus_fwd = 2; - } - if ((bus_num == 2) && (addr != 0x340) && (addr != 0x485)) { - bus_fwd = 0; - } - - return bus_fwd; -} - -static safety_config hyundai_init(uint16_t param) { - hyundai_common_init(param); - hyundai_legacy = false; - - if (hyundai_camera_scc) { - hyundai_longitudinal = false; - } - - safety_config ret; - if (hyundai_longitudinal) { - ret = BUILD_SAFETY_CFG(hyundai_long_rx_checks, HYUNDAI_LONG_TX_MSGS); - } else if (hyundai_camera_scc) { - ret = BUILD_SAFETY_CFG(hyundai_cam_scc_rx_checks, HYUNDAI_CAMERA_SCC_TX_MSGS); - } else { - ret = BUILD_SAFETY_CFG(hyundai_rx_checks, HYUNDAI_TX_MSGS); - } - return ret; -} - -static safety_config hyundai_legacy_init(uint16_t param) { - hyundai_common_init(param); - hyundai_legacy = true; - hyundai_longitudinal = false; - hyundai_camera_scc = false; - return BUILD_SAFETY_CFG(hyundai_legacy_rx_checks, HYUNDAI_TX_MSGS); -} - -const safety_hooks hyundai_hooks = { - .init = hyundai_init, - .rx = hyundai_rx_hook, - .tx = hyundai_tx_hook, - .fwd = hyundai_fwd_hook, - .get_counter = hyundai_get_counter, - .get_checksum = hyundai_get_checksum, - .compute_checksum = hyundai_compute_checksum, -}; - -const safety_hooks hyundai_legacy_hooks = { - .init = hyundai_legacy_init, - .rx = hyundai_rx_hook, - .tx = hyundai_tx_hook, - .fwd = hyundai_fwd_hook, - .get_counter = hyundai_get_counter, - .get_checksum = hyundai_get_checksum, - .compute_checksum = hyundai_compute_checksum, -}; diff --git a/panda/board/safety/safety_hyundai_canfd.h b/panda/board/safety/safety_hyundai_canfd.h deleted file mode 100644 index fb6ccf5..0000000 --- a/panda/board/safety/safety_hyundai_canfd.h +++ /dev/null @@ -1,360 +0,0 @@ -#include "safety_hyundai_common.h" - -const SteeringLimits HYUNDAI_CANFD_STEERING_LIMITS = { - .max_steer = 270, - .max_rt_delta = 112, - .max_rt_interval = 250000, - .max_rate_up = 2, - .max_rate_down = 3, - .driver_torque_allowance = 250, - .driver_torque_factor = 2, - .type = TorqueDriverLimited, - - // the EPS faults when the steering angle is above a certain threshold for too long. to prevent this, - // we allow setting torque actuation bit to 0 while maintaining the requested torque value for two consecutive frames - .min_valid_request_frames = 89, - .max_invalid_request_frames = 2, - .min_valid_request_rt_interval = 810000, // 810ms; a ~10% buffer on cutting every 90 frames - .has_steer_req_tolerance = true, -}; - -const CanMsg HYUNDAI_CANFD_HDA2_TX_MSGS[] = { - {0x50, 0, 16}, // LKAS - {0x1CF, 1, 8}, // CRUISE_BUTTON - {0x2A4, 0, 24}, // CAM_0x2A4 -}; - -const CanMsg HYUNDAI_CANFD_HDA2_ALT_STEERING_TX_MSGS[] = { - {0x110, 0, 32}, // LKAS_ALT - {0x1CF, 1, 8}, // CRUISE_BUTTON - {0x362, 0, 32}, // CAM_0x362 -}; - -const CanMsg HYUNDAI_CANFD_HDA2_LONG_TX_MSGS[] = { - {0x50, 0, 16}, // LKAS - {0x1CF, 1, 8}, // CRUISE_BUTTON - {0x2A4, 0, 24}, // CAM_0x2A4 - {0x51, 0, 32}, // ADRV_0x51 - {0x730, 1, 8}, // tester present for ADAS ECU disable - {0x12A, 1, 16}, // LFA - {0x160, 1, 16}, // ADRV_0x160 - {0x1E0, 1, 16}, // LFAHDA_CLUSTER - {0x1A0, 1, 32}, // CRUISE_INFO - {0x1EA, 1, 32}, // ADRV_0x1ea - {0x200, 1, 8}, // ADRV_0x200 - {0x345, 1, 8}, // ADRV_0x345 - {0x1DA, 1, 32}, // ADRV_0x1da -}; - -const CanMsg HYUNDAI_CANFD_HDA1_TX_MSGS[] = { - {0x12A, 0, 16}, // LFA - {0x1A0, 0, 32}, // CRUISE_INFO - {0x1CF, 2, 8}, // CRUISE_BUTTON - {0x1E0, 0, 16}, // LFAHDA_CLUSTER -}; - - -// *** Addresses checked in rx hook *** -// EV, ICE, HYBRID: ACCELERATOR (0x35), ACCELERATOR_BRAKE_ALT (0x100), ACCELERATOR_ALT (0x105) -#define HYUNDAI_CANFD_COMMON_RX_CHECKS(pt_bus) \ - {.msg = {{0x35, (pt_bus), 32, .check_checksum = true, .max_counter = 0xffU, .frequency = 100U}, \ - {0x100, (pt_bus), 32, .check_checksum = true, .max_counter = 0xffU, .frequency = 100U}, \ - {0x105, (pt_bus), 32, .check_checksum = true, .max_counter = 0xffU, .frequency = 100U}}}, \ - {.msg = {{0x175, (pt_bus), 24, .check_checksum = true, .max_counter = 0xffU, .frequency = 50U}, { 0 }, { 0 }}}, \ - {.msg = {{0xa0, (pt_bus), 24, .check_checksum = true, .max_counter = 0xffU, .frequency = 100U}, { 0 }, { 0 }}}, \ - {.msg = {{0xea, (pt_bus), 24, .check_checksum = true, .max_counter = 0xffU, .frequency = 100U}, { 0 }, { 0 }}}, \ - -#define HYUNDAI_CANFD_BUTTONS_ADDR_CHECK(pt_bus) \ - {.msg = {{0x1cf, (pt_bus), 8, .check_checksum = false, .max_counter = 0xfU, .frequency = 50U}, { 0 }, { 0 }}}, \ - -#define HYUNDAI_CANFD_ALT_BUTTONS_ADDR_CHECK(pt_bus) \ - {.msg = {{0x1aa, (pt_bus), 16, .check_checksum = false, .max_counter = 0xffU, .frequency = 50U}, { 0 }, { 0 }}}, \ - -// SCC_CONTROL (from ADAS unit or camera) -#define HYUNDAI_CANFD_SCC_ADDR_CHECK(scc_bus) \ - {.msg = {{0x1a0, (scc_bus), 32, .check_checksum = true, .max_counter = 0xffU, .frequency = 50U}, { 0 }, { 0 }}}, \ - - -// *** Non-HDA2 checks *** -// Camera sends SCC messages on HDA1. -// Both button messages exist on some platforms, so we ensure we track the correct one using flag -RxCheck hyundai_canfd_rx_checks[] = { - HYUNDAI_CANFD_COMMON_RX_CHECKS(0) - HYUNDAI_CANFD_BUTTONS_ADDR_CHECK(0) - HYUNDAI_CANFD_SCC_ADDR_CHECK(2) -}; -RxCheck hyundai_canfd_alt_buttons_rx_checks[] = { - HYUNDAI_CANFD_COMMON_RX_CHECKS(0) - HYUNDAI_CANFD_ALT_BUTTONS_ADDR_CHECK(0) - HYUNDAI_CANFD_SCC_ADDR_CHECK(2) -}; - -// Longitudinal checks for HDA1 -RxCheck hyundai_canfd_long_rx_checks[] = { - HYUNDAI_CANFD_COMMON_RX_CHECKS(0) - HYUNDAI_CANFD_BUTTONS_ADDR_CHECK(0) -}; -RxCheck hyundai_canfd_long_alt_buttons_rx_checks[] = { - HYUNDAI_CANFD_COMMON_RX_CHECKS(0) - HYUNDAI_CANFD_ALT_BUTTONS_ADDR_CHECK(0) -}; - -// Radar sends SCC messages on these cars instead of camera -RxCheck hyundai_canfd_radar_scc_rx_checks[] = { - HYUNDAI_CANFD_COMMON_RX_CHECKS(0) - HYUNDAI_CANFD_BUTTONS_ADDR_CHECK(0) - HYUNDAI_CANFD_SCC_ADDR_CHECK(0) -}; -RxCheck hyundai_canfd_radar_scc_alt_buttons_rx_checks[] = { - HYUNDAI_CANFD_COMMON_RX_CHECKS(0) - HYUNDAI_CANFD_ALT_BUTTONS_ADDR_CHECK(0) - HYUNDAI_CANFD_SCC_ADDR_CHECK(0) -}; - - -// *** HDA2 checks *** -// E-CAN is on bus 1, ADAS unit sends SCC messages on HDA2. -// Does not use the alt buttons message -RxCheck hyundai_canfd_hda2_rx_checks[] = { - HYUNDAI_CANFD_COMMON_RX_CHECKS(1) - HYUNDAI_CANFD_BUTTONS_ADDR_CHECK(1) - HYUNDAI_CANFD_SCC_ADDR_CHECK(1) -}; -RxCheck hyundai_canfd_hda2_long_rx_checks[] = { - HYUNDAI_CANFD_COMMON_RX_CHECKS(1) - HYUNDAI_CANFD_BUTTONS_ADDR_CHECK(1) -}; - - - -const int HYUNDAI_PARAM_CANFD_ALT_BUTTONS = 32; -const int HYUNDAI_PARAM_CANFD_HDA2_ALT_STEERING = 128; -bool hyundai_canfd_alt_buttons = false; -bool hyundai_canfd_hda2_alt_steering = false; - - -int hyundai_canfd_hda2_get_lkas_addr(void) { - return hyundai_canfd_hda2_alt_steering ? 0x110 : 0x50; -} - -static uint8_t hyundai_canfd_get_counter(const CANPacket_t *to_push) { - uint8_t ret = 0; - if (GET_LEN(to_push) == 8U) { - ret = GET_BYTE(to_push, 1) >> 4; - } else { - ret = GET_BYTE(to_push, 2); - } - return ret; -} - -static uint32_t hyundai_canfd_get_checksum(const CANPacket_t *to_push) { - uint32_t chksum = GET_BYTE(to_push, 0) | (GET_BYTE(to_push, 1) << 8); - return chksum; -} - -static void hyundai_canfd_rx_hook(const CANPacket_t *to_push) { - int bus = GET_BUS(to_push); - int addr = GET_ADDR(to_push); - - const int pt_bus = hyundai_canfd_hda2 ? 1 : 0; - const int scc_bus = hyundai_camera_scc ? 2 : pt_bus; - - if (bus == pt_bus) { - // driver torque - if (addr == 0xea) { - int torque_driver_new = ((GET_BYTE(to_push, 11) & 0x1fU) << 8U) | GET_BYTE(to_push, 10); - torque_driver_new -= 4095; - update_sample(&torque_driver, torque_driver_new); - } - - // cruise buttons - const int button_addr = hyundai_canfd_alt_buttons ? 0x1aa : 0x1cf; - if (addr == button_addr) { - bool main_button = false; - int cruise_button = 0; - if (addr == 0x1cf) { - cruise_button = GET_BYTE(to_push, 2) & 0x7U; - main_button = GET_BIT(to_push, 19U); - } else { - cruise_button = (GET_BYTE(to_push, 4) >> 4) & 0x7U; - main_button = GET_BIT(to_push, 34U); - } - hyundai_common_cruise_buttons_check(cruise_button, main_button); - } - - // gas press, different for EV, hybrid, and ICE models - if ((addr == 0x35) && hyundai_ev_gas_signal) { - gas_pressed = GET_BYTE(to_push, 5) != 0U; - } else if ((addr == 0x105) && hyundai_hybrid_gas_signal) { - gas_pressed = GET_BIT(to_push, 103U) || (GET_BYTE(to_push, 13) != 0U) || GET_BIT(to_push, 112U); - } else if ((addr == 0x100) && !hyundai_ev_gas_signal && !hyundai_hybrid_gas_signal) { - gas_pressed = GET_BIT(to_push, 176U); - } else { - } - - // brake press - if (addr == 0x175) { - brake_pressed = GET_BIT(to_push, 81U); - } - - // vehicle moving - if (addr == 0xa0) { - uint32_t front_left_speed = GET_BYTES(to_push, 8, 2); - uint32_t rear_right_speed = GET_BYTES(to_push, 14, 2); - vehicle_moving = (front_left_speed > HYUNDAI_STANDSTILL_THRSLD) || (rear_right_speed > HYUNDAI_STANDSTILL_THRSLD); - } - } - - if (bus == scc_bus) { - // cruise state - if ((addr == 0x1a0) && !hyundai_longitudinal) { - // 1=enabled, 2=driver override - int cruise_status = ((GET_BYTE(to_push, 8) >> 4) & 0x7U); - bool cruise_engaged = (cruise_status == 1) || (cruise_status == 2); - hyundai_common_cruise_state_check(cruise_engaged); - } - } - - const int steer_addr = hyundai_canfd_hda2 ? hyundai_canfd_hda2_get_lkas_addr() : 0x12a; - bool stock_ecu_detected = (addr == steer_addr) && (bus == 0); - if (hyundai_longitudinal) { - // on HDA2, ensure ADRV ECU is still knocked out - // on others, ensure accel msg is blocked from camera - const int stock_scc_bus = hyundai_canfd_hda2 ? 1 : 0; - stock_ecu_detected = stock_ecu_detected || ((addr == 0x1a0) && (bus == stock_scc_bus)); - } - generic_rx_checks(stock_ecu_detected); - -} - -static bool hyundai_canfd_tx_hook(const CANPacket_t *to_send) { - bool tx = true; - int addr = GET_ADDR(to_send); - - // steering - const int steer_addr = (hyundai_canfd_hda2 && !hyundai_longitudinal) ? hyundai_canfd_hda2_get_lkas_addr() : 0x12a; - if (addr == steer_addr) { - int desired_torque = (((GET_BYTE(to_send, 6) & 0xFU) << 7U) | (GET_BYTE(to_send, 5) >> 1U)) - 1024U; - bool steer_req = GET_BIT(to_send, 52U); - - if (steer_torque_cmd_checks(desired_torque, steer_req, HYUNDAI_CANFD_STEERING_LIMITS)) { - tx = false; - } - } - - // cruise buttons check - if (addr == 0x1cf) { - int button = GET_BYTE(to_send, 2) & 0x7U; - bool is_cancel = (button == HYUNDAI_BTN_CANCEL); - bool is_resume = (button == HYUNDAI_BTN_RESUME); - - bool allowed = (is_cancel && cruise_engaged_prev) || (is_resume && controls_allowed); - if (!allowed) { - tx = false; - } - } - - // UDS: only tester present ("\x02\x3E\x80\x00\x00\x00\x00\x00") allowed on diagnostics address - if ((addr == 0x730) && hyundai_canfd_hda2) { - if ((GET_BYTES(to_send, 0, 4) != 0x00803E02U) || (GET_BYTES(to_send, 4, 4) != 0x0U)) { - tx = false; - } - } - - // ACCEL: safety check - if (addr == 0x1a0) { - int desired_accel_raw = (((GET_BYTE(to_send, 17) & 0x7U) << 8) | GET_BYTE(to_send, 16)) - 1023U; - int desired_accel_val = ((GET_BYTE(to_send, 18) << 4) | (GET_BYTE(to_send, 17) >> 4)) - 1023U; - - bool violation = false; - - if (hyundai_longitudinal) { - violation |= longitudinal_accel_checks(desired_accel_raw, HYUNDAI_LONG_LIMITS); - violation |= longitudinal_accel_checks(desired_accel_val, HYUNDAI_LONG_LIMITS); - } else { - // only used to cancel on here - if ((desired_accel_raw != 0) || (desired_accel_val != 0)) { - violation = true; - } - } - - if (violation) { - tx = false; - } - } - - return tx; -} - -static int hyundai_canfd_fwd_hook(int bus_num, int addr) { - int bus_fwd = -1; - - if (bus_num == 0) { - bus_fwd = 2; - } - if (bus_num == 2) { - // LKAS for HDA2, LFA for HDA1 - int hda2_lfa_block_addr = hyundai_canfd_hda2_alt_steering ? 0x362 : 0x2a4; - bool is_lkas_msg = ((addr == hyundai_canfd_hda2_get_lkas_addr()) || (addr == hda2_lfa_block_addr)) && hyundai_canfd_hda2; - bool is_lfa_msg = ((addr == 0x12a) && !hyundai_canfd_hda2); - - // HUD icons - bool is_lfahda_msg = ((addr == 0x1e0) && !hyundai_canfd_hda2); - - // CRUISE_INFO for non-HDA2, we send our own longitudinal commands - bool is_scc_msg = ((addr == 0x1a0) && hyundai_longitudinal && !hyundai_canfd_hda2); - - bool block_msg = is_lkas_msg || is_lfa_msg || is_lfahda_msg || is_scc_msg; - if (!block_msg) { - bus_fwd = 0; - } - } - - return bus_fwd; -} - -static safety_config hyundai_canfd_init(uint16_t param) { - hyundai_common_init(param); - - gen_crc_lookup_table_16(0x1021, hyundai_canfd_crc_lut); - hyundai_canfd_alt_buttons = GET_FLAG(param, HYUNDAI_PARAM_CANFD_ALT_BUTTONS); - hyundai_canfd_hda2_alt_steering = GET_FLAG(param, HYUNDAI_PARAM_CANFD_HDA2_ALT_STEERING); - - // no long for radar-SCC HDA1 yet - if (!hyundai_canfd_hda2 && !hyundai_camera_scc) { - hyundai_longitudinal = false; - } - - safety_config ret; - if (hyundai_longitudinal) { - if (hyundai_canfd_hda2) { - ret = BUILD_SAFETY_CFG(hyundai_canfd_hda2_long_rx_checks, HYUNDAI_CANFD_HDA2_LONG_TX_MSGS); - } else { - ret = hyundai_canfd_alt_buttons ? BUILD_SAFETY_CFG(hyundai_canfd_long_alt_buttons_rx_checks, HYUNDAI_CANFD_HDA1_TX_MSGS) : \ - BUILD_SAFETY_CFG(hyundai_canfd_long_rx_checks, HYUNDAI_CANFD_HDA1_TX_MSGS); - } - } else { - if (hyundai_canfd_hda2) { - ret = hyundai_canfd_hda2_alt_steering ? BUILD_SAFETY_CFG(hyundai_canfd_hda2_rx_checks, HYUNDAI_CANFD_HDA2_ALT_STEERING_TX_MSGS) : \ - BUILD_SAFETY_CFG(hyundai_canfd_hda2_rx_checks, HYUNDAI_CANFD_HDA2_TX_MSGS); - } else if (!hyundai_camera_scc) { - ret = hyundai_canfd_alt_buttons ? BUILD_SAFETY_CFG(hyundai_canfd_radar_scc_alt_buttons_rx_checks, HYUNDAI_CANFD_HDA1_TX_MSGS) : \ - BUILD_SAFETY_CFG(hyundai_canfd_radar_scc_rx_checks, HYUNDAI_CANFD_HDA1_TX_MSGS); - } else { - ret = hyundai_canfd_alt_buttons ? BUILD_SAFETY_CFG(hyundai_canfd_alt_buttons_rx_checks, HYUNDAI_CANFD_HDA1_TX_MSGS) : \ - BUILD_SAFETY_CFG(hyundai_canfd_rx_checks, HYUNDAI_CANFD_HDA1_TX_MSGS); - } - } - - return ret; -} - -const safety_hooks hyundai_canfd_hooks = { - .init = hyundai_canfd_init, - .rx = hyundai_canfd_rx_hook, - .tx = hyundai_canfd_tx_hook, - .fwd = hyundai_canfd_fwd_hook, - .get_counter = hyundai_canfd_get_counter, - .get_checksum = hyundai_canfd_get_checksum, - .compute_checksum = hyundai_common_canfd_compute_checksum, -}; diff --git a/panda/board/safety/safety_hyundai_common.h b/panda/board/safety/safety_hyundai_common.h deleted file mode 100644 index bc30411..0000000 --- a/panda/board/safety/safety_hyundai_common.h +++ /dev/null @@ -1,118 +0,0 @@ -#ifndef SAFETY_HYUNDAI_COMMON_H -#define SAFETY_HYUNDAI_COMMON_H - -const int HYUNDAI_PARAM_EV_GAS = 1; -const int HYUNDAI_PARAM_HYBRID_GAS = 2; -const int HYUNDAI_PARAM_LONGITUDINAL = 4; -const int HYUNDAI_PARAM_CAMERA_SCC = 8; -const int HYUNDAI_PARAM_CANFD_HDA2 = 16; -const int HYUNDAI_PARAM_ALT_LIMITS = 64; // TODO: shift this down with the rest of the common flags - -const uint8_t HYUNDAI_PREV_BUTTON_SAMPLES = 8; // roughly 160 ms -const uint32_t HYUNDAI_STANDSTILL_THRSLD = 12; // 0.375 kph - -enum { - HYUNDAI_BTN_NONE = 0, - HYUNDAI_BTN_RESUME = 1, - HYUNDAI_BTN_SET = 2, - HYUNDAI_BTN_CANCEL = 4, -}; - -// common state -bool hyundai_ev_gas_signal = false; -bool hyundai_hybrid_gas_signal = false; -bool hyundai_longitudinal = false; -bool hyundai_camera_scc = false; -bool hyundai_canfd_hda2 = false; -bool hyundai_alt_limits = false; -uint8_t hyundai_last_button_interaction; // button messages since the user pressed an enable button - -uint16_t hyundai_canfd_crc_lut[256]; - -void hyundai_common_init(uint16_t param) { - hyundai_ev_gas_signal = GET_FLAG(param, HYUNDAI_PARAM_EV_GAS); - hyundai_hybrid_gas_signal = !hyundai_ev_gas_signal && GET_FLAG(param, HYUNDAI_PARAM_HYBRID_GAS); - hyundai_camera_scc = GET_FLAG(param, HYUNDAI_PARAM_CAMERA_SCC); - hyundai_canfd_hda2 = GET_FLAG(param, HYUNDAI_PARAM_CANFD_HDA2); - hyundai_alt_limits = GET_FLAG(param, HYUNDAI_PARAM_ALT_LIMITS); - - hyundai_last_button_interaction = HYUNDAI_PREV_BUTTON_SAMPLES; - -#ifdef ALLOW_DEBUG - hyundai_longitudinal = GET_FLAG(param, HYUNDAI_PARAM_LONGITUDINAL); -#else - hyundai_longitudinal = false; -#endif -} - -void hyundai_common_cruise_state_check(const bool cruise_engaged) { - // some newer HKG models can re-enable after spamming cancel button, - // so keep track of user button presses to deny engagement if no interaction - - // enter controls on rising edge of ACC and recent user button press, exit controls when ACC off - if (!hyundai_longitudinal) { - if (cruise_engaged && !cruise_engaged_prev && (hyundai_last_button_interaction < HYUNDAI_PREV_BUTTON_SAMPLES)) { - controls_allowed = true; - } - - if (!cruise_engaged) { - controls_allowed = false; - } - cruise_engaged_prev = cruise_engaged; - } -} - -void hyundai_common_cruise_buttons_check(const int cruise_button, const bool main_button) { - if (main_button != 0 && main_button != cruise_main_prev) { - acc_main_on = !acc_main_on; - } - cruise_main_prev = main_button; - if ((cruise_button == HYUNDAI_BTN_RESUME) || (cruise_button == HYUNDAI_BTN_SET) || (cruise_button == HYUNDAI_BTN_CANCEL) || main_button) { - hyundai_last_button_interaction = 0U; - } else { - hyundai_last_button_interaction = MIN(hyundai_last_button_interaction + 1U, HYUNDAI_PREV_BUTTON_SAMPLES); - } - - if (hyundai_longitudinal) { - // enter controls on falling edge of resume or set - bool set = (cruise_button != HYUNDAI_BTN_SET) && (cruise_button_prev == HYUNDAI_BTN_SET); - bool res = (cruise_button != HYUNDAI_BTN_RESUME) && (cruise_button_prev == HYUNDAI_BTN_RESUME); - if (set || res) { - controls_allowed = true; - } - - // exit controls on cancel press - if (cruise_button == HYUNDAI_BTN_CANCEL) { - controls_allowed = false; - } - - cruise_button_prev = cruise_button; - } -} - -uint32_t hyundai_common_canfd_compute_checksum(const CANPacket_t *to_push) { - int len = GET_LEN(to_push); - uint32_t address = GET_ADDR(to_push); - - uint16_t crc = 0; - - for (int i = 2; i < len; i++) { - crc = (crc << 8U) ^ hyundai_canfd_crc_lut[(crc >> 8U) ^ GET_BYTE(to_push, i)]; - } - - // Add address to crc - crc = (crc << 8U) ^ hyundai_canfd_crc_lut[(crc >> 8U) ^ ((address >> 0U) & 0xFFU)]; - crc = (crc << 8U) ^ hyundai_canfd_crc_lut[(crc >> 8U) ^ ((address >> 8U) & 0xFFU)]; - - if (len == 24) { - crc ^= 0x819dU; - } else if (len == 32) { - crc ^= 0x9f5bU; - } else { - - } - - return crc; -} - -#endif diff --git a/panda/board/safety/safety_mazda.h b/panda/board/safety/safety_mazda.h deleted file mode 100644 index b3a567f..0000000 --- a/panda/board/safety/safety_mazda.h +++ /dev/null @@ -1,130 +0,0 @@ -// CAN msgs we care about -#define MAZDA_LKAS 0x243 -#define MAZDA_LKAS_HUD 0x440 -#define MAZDA_CRZ_CTRL 0x21c -#define MAZDA_CRZ_BTNS 0x09d -#define MAZDA_STEER_TORQUE 0x240 -#define MAZDA_ENGINE_DATA 0x202 -#define MAZDA_PEDALS 0x165 - -// CAN bus numbers -#define MAZDA_MAIN 0 -#define MAZDA_AUX 1 -#define MAZDA_CAM 2 - -const SteeringLimits MAZDA_STEERING_LIMITS = { - .max_steer = 800, - .max_rate_up = 10, - .max_rate_down = 25, - .max_rt_delta = 300, - .max_rt_interval = 250000, - .driver_torque_factor = 1, - .driver_torque_allowance = 15, - .type = TorqueDriverLimited, -}; - -const CanMsg MAZDA_TX_MSGS[] = {{MAZDA_LKAS, 0, 8}, {MAZDA_CRZ_BTNS, 0, 8}, {MAZDA_LKAS_HUD, 0, 8}}; - -RxCheck mazda_rx_checks[] = { - {.msg = {{MAZDA_CRZ_CTRL, 0, 8, .frequency = 50U}, { 0 }, { 0 }}}, - {.msg = {{MAZDA_CRZ_BTNS, 0, 8, .frequency = 10U}, { 0 }, { 0 }}}, - {.msg = {{MAZDA_STEER_TORQUE, 0, 8, .frequency = 83U}, { 0 }, { 0 }}}, - {.msg = {{MAZDA_ENGINE_DATA, 0, 8, .frequency = 100U}, { 0 }, { 0 }}}, - {.msg = {{MAZDA_PEDALS, 0, 8, .frequency = 50U}, { 0 }, { 0 }}}, -}; - -// track msgs coming from OP so that we know what CAM msgs to drop and what to forward -static void mazda_rx_hook(const CANPacket_t *to_push) { - if ((int)GET_BUS(to_push) == MAZDA_MAIN) { - int addr = GET_ADDR(to_push); - - if (addr == MAZDA_ENGINE_DATA) { - // sample speed: scale by 0.01 to get kph - int speed = (GET_BYTE(to_push, 2) << 8) | GET_BYTE(to_push, 3); - vehicle_moving = speed > 10; // moving when speed > 0.1 kph - } - - if (addr == MAZDA_STEER_TORQUE) { - int torque_driver_new = GET_BYTE(to_push, 0) - 127U; - // update array of samples - update_sample(&torque_driver, torque_driver_new); - } - - // enter controls on rising edge of ACC, exit controls on ACC off - if (addr == MAZDA_CRZ_CTRL) { - acc_main_on = GET_BIT(to_push, 17U); - bool cruise_engaged = GET_BYTE(to_push, 0) & 0x8U; - pcm_cruise_check(cruise_engaged); - } - - if (addr == MAZDA_ENGINE_DATA) { - gas_pressed = (GET_BYTE(to_push, 4) || (GET_BYTE(to_push, 5) & 0xF0U)); - } - - if (addr == MAZDA_PEDALS) { - brake_pressed = (GET_BYTE(to_push, 0) & 0x10U); - } - - generic_rx_checks((addr == MAZDA_LKAS)); - } -} - -static bool mazda_tx_hook(const CANPacket_t *to_send) { - bool tx = true; - int addr = GET_ADDR(to_send); - int bus = GET_BUS(to_send); - - // Check if msg is sent on the main BUS - if (bus == MAZDA_MAIN) { - - // steer cmd checks - if (addr == MAZDA_LKAS) { - int desired_torque = (((GET_BYTE(to_send, 0) & 0x0FU) << 8) | GET_BYTE(to_send, 1)) - 2048U; - - if (steer_torque_cmd_checks(desired_torque, -1, MAZDA_STEERING_LIMITS)) { - tx = false; - } - } - - // cruise buttons check - if (addr == MAZDA_CRZ_BTNS) { - // allow resume spamming while controls allowed, but - // only allow cancel while contrls not allowed - bool cancel_cmd = (GET_BYTE(to_send, 0) == 0x1U); - if (!controls_allowed && !cancel_cmd) { - tx = false; - } - } - } - - return tx; -} - -static int mazda_fwd_hook(int bus, int addr) { - int bus_fwd = -1; - - if (bus == MAZDA_MAIN) { - bus_fwd = MAZDA_CAM; - } else if (bus == MAZDA_CAM) { - bool block = (addr == MAZDA_LKAS) || (addr == MAZDA_LKAS_HUD); - if (!block) { - bus_fwd = MAZDA_MAIN; - } - } else { - // don't fwd - } - - return bus_fwd; -} - -static safety_config mazda_init(uint16_t param) { - UNUSED(param); - return BUILD_SAFETY_CFG(mazda_rx_checks, MAZDA_TX_MSGS); -} - -const safety_hooks mazda_hooks = { - .init = mazda_init, - .rx = mazda_rx_hook, - .tx = mazda_tx_hook, - .fwd = mazda_fwd_hook, -}; diff --git a/panda/board/safety/safety_nissan.h b/panda/board/safety/safety_nissan.h deleted file mode 100644 index b8db422..0000000 --- a/panda/board/safety/safety_nissan.h +++ /dev/null @@ -1,166 +0,0 @@ -const SteeringLimits NISSAN_STEERING_LIMITS = { - .angle_deg_to_can = 100, - .angle_rate_up_lookup = { - {0., 5., 15.}, - {5., .8, .15} - }, - .angle_rate_down_lookup = { - {0., 5., 15.}, - {5., 3.5, .4} - }, -}; - -const CanMsg NISSAN_TX_MSGS[] = { - {0x169, 0, 8}, // LKAS - {0x2b1, 0, 8}, // PROPILOT_HUD - {0x4cc, 0, 8}, // PROPILOT_HUD_INFO_MSG - {0x20b, 2, 6}, // CRUISE_THROTTLE (X-Trail) - {0x20b, 1, 6}, // CRUISE_THROTTLE (Altima) - {0x280, 2, 8} // CANCEL_MSG (Leaf) -}; - -// Signals duplicated below due to the fact that these messages can come in on either CAN bus, depending on car model. -RxCheck nissan_rx_checks[] = { - {.msg = {{0x1b6, 0, 8, .frequency = 100U}, - {0x1b6, 1, 8, .frequency = 100U}, { 0 }}}, // PRO_PILOT (100HZ) - {.msg = {{0x2, 0, 5, .frequency = 100U}, - {0x2, 1, 5, .frequency = 100U}, { 0 }}}, // STEER_ANGLE_SENSOR - {.msg = {{0x285, 0, 8, .frequency = 50U}, - {0x285, 1, 8, .frequency = 50U}, { 0 }}}, // WHEEL_SPEEDS_REAR - {.msg = {{0x30f, 2, 3, .frequency = 10U}, - {0x30f, 1, 3, .frequency = 10U}, { 0 }}}, // CRUISE_STATE - {.msg = {{0x15c, 0, 8, .frequency = 50U}, - {0x15c, 1, 8, .frequency = 50U}, - {0x239, 0, 8, .frequency = 50U}}}, // GAS_PEDAL - {.msg = {{0x454, 0, 8, .frequency = 10U}, - {0x454, 1, 8, .frequency = 10U}, - {0x1cc, 0, 4, .frequency = 100U}}}, // DOORS_LIGHTS / BRAKE -}; - -// EPS Location. false = V-CAN, true = C-CAN -const int NISSAN_PARAM_ALT_EPS_BUS = 1; - -bool nissan_alt_eps = false; - -static void nissan_rx_hook(const CANPacket_t *to_push) { - int bus = GET_BUS(to_push); - int addr = GET_ADDR(to_push); - - if (bus == (nissan_alt_eps ? 1 : 0)) { - if (addr == 0x2) { - // Current steering angle - // Factor -0.1, little endian - int angle_meas_new = (GET_BYTES(to_push, 0, 4) & 0xFFFFU); - // Multiply by -10 to match scale of LKAS angle - angle_meas_new = to_signed(angle_meas_new, 16) * -10; - - // update array of samples - update_sample(&angle_meas, angle_meas_new); - } - - if (addr == 0x285) { - // Get current speed and standstill - uint16_t right_rear = (GET_BYTE(to_push, 0) << 8) | (GET_BYTE(to_push, 1)); - uint16_t left_rear = (GET_BYTE(to_push, 2) << 8) | (GET_BYTE(to_push, 3)); - vehicle_moving = (right_rear | left_rear) != 0U; - UPDATE_VEHICLE_SPEED((right_rear + left_rear) / 2.0 * 0.005 / 3.6); - } - - if (addr == 0x1b6) { - acc_main_on = GET_BIT(to_push, 36U); - } - - // X-Trail 0x15c, Leaf 0x239 - if ((addr == 0x15c) || (addr == 0x239)) { - if (addr == 0x15c){ - gas_pressed = ((GET_BYTE(to_push, 5) << 2) | ((GET_BYTE(to_push, 6) >> 6) & 0x3U)) > 3U; - } else { - acc_main_on = GET_BIT(to_push, 17U); - gas_pressed = GET_BYTE(to_push, 0) > 3U; - } - } - - // X-trail 0x454, Leaf 0x239 - if ((addr == 0x454) || (addr == 0x239)) { - if (addr == 0x454){ - brake_pressed = (GET_BYTE(to_push, 2) & 0x80U) != 0U; - } else { - brake_pressed = ((GET_BYTE(to_push, 4) >> 5) & 1U) != 0U; - } - } - } - - // Handle cruise enabled - if ((addr == 0x30f) && (bus == (nissan_alt_eps ? 1 : 2))) { - bool cruise_engaged = (GET_BYTE(to_push, 0) >> 3) & 1U; - pcm_cruise_check(cruise_engaged); - } - - generic_rx_checks((addr == 0x169) && (bus == 0)); -} - - -static bool nissan_tx_hook(const CANPacket_t *to_send) { - bool tx = true; - int addr = GET_ADDR(to_send); - bool violation = false; - - // steer cmd checks - if (addr == 0x169) { - int desired_angle = ((GET_BYTE(to_send, 0) << 10) | (GET_BYTE(to_send, 1) << 2) | ((GET_BYTE(to_send, 2) >> 6) & 0x3U)); - bool lka_active = (GET_BYTE(to_send, 6) >> 4) & 1U; - - // Factor is -0.01, offset is 1310. Flip to correct sign, but keep units in CAN scale - desired_angle = -desired_angle + (1310.0f * NISSAN_STEERING_LIMITS.angle_deg_to_can); - - if (steer_angle_cmd_checks(desired_angle, lka_active, NISSAN_STEERING_LIMITS)) { - violation = true; - } - } - - // acc button check, only allow cancel button to be sent - if (addr == 0x20b) { - // Violation of any button other than cancel is pressed - violation |= ((GET_BYTE(to_send, 1) & 0x3dU) > 0U); - } - - if (violation) { - tx = false; - } - - return tx; -} - - -static int nissan_fwd_hook(int bus_num, int addr) { - int bus_fwd = -1; - - if (bus_num == 0) { - bool block_msg = (addr == 0x280); // CANCEL_MSG - if (!block_msg) { - bus_fwd = 2; // ADAS - } - } - - if (bus_num == 2) { - // 0x169 is LKAS, 0x2b1 LKAS_HUD, 0x4cc LKAS_HUD_INFO_MSG - bool block_msg = ((addr == 0x169) || (addr == 0x2b1) || (addr == 0x4cc)); - if (!block_msg) { - bus_fwd = 0; // V-CAN - } - } - - return bus_fwd; -} - -static safety_config nissan_init(uint16_t param) { - nissan_alt_eps = GET_FLAG(param, NISSAN_PARAM_ALT_EPS_BUS); - return BUILD_SAFETY_CFG(nissan_rx_checks, NISSAN_TX_MSGS); -} - -const safety_hooks nissan_hooks = { - .init = nissan_init, - .rx = nissan_rx_hook, - .tx = nissan_tx_hook, - .fwd = nissan_fwd_hook, -}; diff --git a/panda/board/safety/safety_subaru.h b/panda/board/safety/safety_subaru.h deleted file mode 100644 index 7c887a0..0000000 --- a/panda/board/safety/safety_subaru.h +++ /dev/null @@ -1,295 +0,0 @@ -#define SUBARU_STEERING_LIMITS_GENERATOR(steer_max, rate_up, rate_down) \ - { \ - .max_steer = (steer_max), \ - .max_rt_delta = 940, \ - .max_rt_interval = 250000, \ - .max_rate_up = (rate_up), \ - .max_rate_down = (rate_down), \ - .driver_torque_factor = 50, \ - .driver_torque_allowance = 60, \ - .type = TorqueDriverLimited, \ - /* the EPS will temporary fault if the steering rate is too high, so we cut the \ - the steering torque every 7 frames for 1 frame if the steering rate is high */ \ - .min_valid_request_frames = 7, \ - .max_invalid_request_frames = 1, \ - .min_valid_request_rt_interval = 144000, /* 10% tolerance */ \ - .has_steer_req_tolerance = true, \ - } - - -const SteeringLimits SUBARU_STEERING_LIMITS = SUBARU_STEERING_LIMITS_GENERATOR(3071, 50, 70); -const SteeringLimits SUBARU_GEN2_STEERING_LIMITS = SUBARU_STEERING_LIMITS_GENERATOR(1000, 40, 40); - - -const LongitudinalLimits SUBARU_LONG_LIMITS = { - .min_gas = 808, // appears to be engine braking - .max_gas = 3400, // approx 2 m/s^2 when maxing cruise_rpm and cruise_throttle - .inactive_gas = 1818, // this is zero acceleration - .max_brake = 600, // approx -3.5 m/s^2 - - .min_transmission_rpm = 0, - .max_transmission_rpm = 2400, -}; - -#define MSG_SUBARU_Brake_Status 0x13c -#define MSG_SUBARU_CruiseControl 0x240 -#define MSG_SUBARU_Throttle 0x40 -#define MSG_SUBARU_Steering_Torque 0x119 -#define MSG_SUBARU_Wheel_Speeds 0x13a - -#define MSG_SUBARU_ES_LKAS 0x122 -#define MSG_SUBARU_ES_LKAS_ANGLE 0x124 -#define MSG_SUBARU_ES_Brake 0x220 -#define MSG_SUBARU_ES_Distance 0x221 -#define MSG_SUBARU_ES_Status 0x222 -#define MSG_SUBARU_ES_DashStatus 0x321 -#define MSG_SUBARU_ES_LKAS_State 0x322 -#define MSG_SUBARU_ES_Infotainment 0x323 - -#define MSG_SUBARU_ES_UDS_Request 0x787 - -#define MSG_SUBARU_ES_HighBeamAssist 0x121 -#define MSG_SUBARU_ES_STATIC_1 0x22a -#define MSG_SUBARU_ES_STATIC_2 0x325 - -#define SUBARU_MAIN_BUS 0 -#define SUBARU_ALT_BUS 1 -#define SUBARU_CAM_BUS 2 - -#define SUBARU_COMMON_TX_MSGS(alt_bus, lkas_msg) \ - {lkas_msg, SUBARU_MAIN_BUS, 8}, \ - {MSG_SUBARU_ES_Distance, alt_bus, 8}, \ - {MSG_SUBARU_ES_DashStatus, SUBARU_MAIN_BUS, 8}, \ - {MSG_SUBARU_ES_LKAS_State, SUBARU_MAIN_BUS, 8}, \ - {MSG_SUBARU_ES_Infotainment, SUBARU_MAIN_BUS, 8}, \ - -#define SUBARU_COMMON_LONG_TX_MSGS(alt_bus) \ - {MSG_SUBARU_ES_Brake, alt_bus, 8}, \ - {MSG_SUBARU_ES_Status, alt_bus, 8}, \ - -#define SUBARU_GEN2_LONG_ADDITIONAL_TX_MSGS() \ - {MSG_SUBARU_ES_UDS_Request, SUBARU_CAM_BUS, 8}, \ - {MSG_SUBARU_ES_HighBeamAssist, SUBARU_MAIN_BUS, 8}, \ - {MSG_SUBARU_ES_STATIC_1, SUBARU_MAIN_BUS, 8}, \ - {MSG_SUBARU_ES_STATIC_2, SUBARU_MAIN_BUS, 8}, \ - -#define SUBARU_COMMON_RX_CHECKS(alt_bus) \ - {.msg = {{MSG_SUBARU_Throttle, SUBARU_MAIN_BUS, 8, .check_checksum = true, .max_counter = 15U, .frequency = 100U}, { 0 }, { 0 }}}, \ - {.msg = {{MSG_SUBARU_Steering_Torque, SUBARU_MAIN_BUS, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, \ - {.msg = {{MSG_SUBARU_Wheel_Speeds, alt_bus, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, \ - {.msg = {{MSG_SUBARU_Brake_Status, alt_bus, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, \ - {.msg = {{MSG_SUBARU_CruiseControl, alt_bus, 8, .check_checksum = true, .max_counter = 15U, .frequency = 20U}, { 0 }, { 0 }}}, \ - -const CanMsg SUBARU_TX_MSGS[] = { - SUBARU_COMMON_TX_MSGS(SUBARU_MAIN_BUS, MSG_SUBARU_ES_LKAS) -}; - -const CanMsg SUBARU_LONG_TX_MSGS[] = { - SUBARU_COMMON_TX_MSGS(SUBARU_MAIN_BUS, MSG_SUBARU_ES_LKAS) - SUBARU_COMMON_LONG_TX_MSGS(SUBARU_MAIN_BUS) -}; - -const CanMsg SUBARU_GEN2_TX_MSGS[] = { - SUBARU_COMMON_TX_MSGS(SUBARU_ALT_BUS, MSG_SUBARU_ES_LKAS) -}; - -const CanMsg SUBARU_GEN2_LONG_TX_MSGS[] = { - SUBARU_COMMON_TX_MSGS(SUBARU_ALT_BUS, MSG_SUBARU_ES_LKAS) - SUBARU_COMMON_LONG_TX_MSGS(SUBARU_ALT_BUS) - SUBARU_GEN2_LONG_ADDITIONAL_TX_MSGS() -}; - -RxCheck subaru_rx_checks[] = { - SUBARU_COMMON_RX_CHECKS(SUBARU_MAIN_BUS) -}; - -RxCheck subaru_gen2_rx_checks[] = { - SUBARU_COMMON_RX_CHECKS(SUBARU_ALT_BUS) -}; - - -const uint16_t SUBARU_PARAM_GEN2 = 1; -const uint16_t SUBARU_PARAM_LONGITUDINAL = 2; - -bool subaru_gen2 = false; -bool subaru_longitudinal = false; - - -static uint32_t subaru_get_checksum(const CANPacket_t *to_push) { - return (uint8_t)GET_BYTE(to_push, 0); -} - -static uint8_t subaru_get_counter(const CANPacket_t *to_push) { - return (uint8_t)(GET_BYTE(to_push, 1) & 0xFU); -} - -static uint32_t subaru_compute_checksum(const CANPacket_t *to_push) { - int addr = GET_ADDR(to_push); - int len = GET_LEN(to_push); - uint8_t checksum = (uint8_t)(addr) + (uint8_t)((unsigned int)(addr) >> 8U); - for (int i = 1; i < len; i++) { - checksum += (uint8_t)GET_BYTE(to_push, i); - } - return checksum; -} - -static void subaru_rx_hook(const CANPacket_t *to_push) { - const int bus = GET_BUS(to_push); - const int alt_main_bus = subaru_gen2 ? SUBARU_ALT_BUS : SUBARU_MAIN_BUS; - - int addr = GET_ADDR(to_push); - if ((addr == MSG_SUBARU_Steering_Torque) && (bus == SUBARU_MAIN_BUS)) { - int torque_driver_new; - torque_driver_new = ((GET_BYTES(to_push, 0, 4) >> 16) & 0x7FFU); - torque_driver_new = -1 * to_signed(torque_driver_new, 11); - update_sample(&torque_driver, torque_driver_new); - - int angle_meas_new = (GET_BYTES(to_push, 4, 2) & 0xFFFFU); - // convert Steering_Torque -> Steering_Angle to centidegrees, to match the ES_LKAS_ANGLE angle request units - angle_meas_new = ROUND(to_signed(angle_meas_new, 16) * -2.17); - update_sample(&angle_meas, angle_meas_new); - } - - // enter controls on rising edge of ACC, exit controls on ACC off - if ((addr == MSG_SUBARU_CruiseControl) && (bus == alt_main_bus)) { - acc_main_on = GET_BIT(to_push, 40U); - bool cruise_engaged = GET_BIT(to_push, 41U); - pcm_cruise_check(cruise_engaged); - } - - // update vehicle moving with any non-zero wheel speed - if ((addr == MSG_SUBARU_Wheel_Speeds) && (bus == alt_main_bus)) { - uint32_t fr = (GET_BYTES(to_push, 1, 3) >> 4) & 0x1FFFU; - uint32_t rr = (GET_BYTES(to_push, 3, 3) >> 1) & 0x1FFFU; - uint32_t rl = (GET_BYTES(to_push, 4, 3) >> 6) & 0x1FFFU; - uint32_t fl = (GET_BYTES(to_push, 6, 2) >> 3) & 0x1FFFU; - - vehicle_moving = (fr > 0U) || (rr > 0U) || (rl > 0U) || (fl > 0U); - - UPDATE_VEHICLE_SPEED((fr + rr + rl + fl) / 4U * 0.057); - } - - if ((addr == MSG_SUBARU_Brake_Status) && (bus == alt_main_bus)) { - brake_pressed = GET_BIT(to_push, 62U); - } - - if ((addr == MSG_SUBARU_Throttle) && (bus == SUBARU_MAIN_BUS)) { - gas_pressed = GET_BYTE(to_push, 4) != 0U; - } - - generic_rx_checks((addr == MSG_SUBARU_ES_LKAS) && (bus == SUBARU_MAIN_BUS)); -} - -static bool subaru_tx_hook(const CANPacket_t *to_send) { - bool tx = true; - int addr = GET_ADDR(to_send); - bool violation = false; - - // steer cmd checks - if (addr == MSG_SUBARU_ES_LKAS) { - int desired_torque = ((GET_BYTES(to_send, 0, 4) >> 16) & 0x1FFFU); - desired_torque = -1 * to_signed(desired_torque, 13); - - bool steer_req = GET_BIT(to_send, 29U); - - const SteeringLimits limits = subaru_gen2 ? SUBARU_GEN2_STEERING_LIMITS : SUBARU_STEERING_LIMITS; - violation |= steer_torque_cmd_checks(desired_torque, steer_req, limits); - } - - // check es_brake brake_pressure limits - if (addr == MSG_SUBARU_ES_Brake) { - int es_brake_pressure = GET_BYTES(to_send, 2, 2); - violation |= longitudinal_brake_checks(es_brake_pressure, SUBARU_LONG_LIMITS); - } - - // check es_distance cruise_throttle limits - if (addr == MSG_SUBARU_ES_Distance) { - int cruise_throttle = (GET_BYTES(to_send, 2, 2) & 0x1FFFU); - bool cruise_cancel = GET_BIT(to_send, 56U); - - if (subaru_longitudinal) { - violation |= longitudinal_gas_checks(cruise_throttle, SUBARU_LONG_LIMITS); - } else { - // If openpilot is not controlling long, only allow ES_Distance for cruise cancel requests, - // (when Cruise_Cancel is true, and Cruise_Throttle is inactive) - violation |= (cruise_throttle != SUBARU_LONG_LIMITS.inactive_gas); - violation |= (!cruise_cancel); - } - } - - // check es_status transmission_rpm limits - if (addr == MSG_SUBARU_ES_Status) { - int transmission_rpm = (GET_BYTES(to_send, 2, 2) & 0x1FFFU); - violation |= longitudinal_transmission_rpm_checks(transmission_rpm, SUBARU_LONG_LIMITS); - } - - if (addr == MSG_SUBARU_ES_UDS_Request) { - // tester present ('\x02\x3E\x80\x00\x00\x00\x00\x00') is allowed for gen2 longitudinal to keep eyesight disabled - bool is_tester_present = (GET_BYTES(to_send, 0, 4) == 0x00803E02U) && (GET_BYTES(to_send, 4, 4) == 0x0U); - - // reading ES button data by identifier (b'\x03\x22\x11\x30\x00\x00\x00\x00') is also allowed (DID 0x1130) - bool is_button_rdbi = (GET_BYTES(to_send, 0, 4) == 0x30112203U) && (GET_BYTES(to_send, 4, 4) == 0x0U); - - violation |= !(is_tester_present || is_button_rdbi); - } - - if (violation){ - tx = false; - } - return tx; -} - -static int subaru_fwd_hook(int bus_num, int addr) { - int bus_fwd = -1; - - if (bus_num == SUBARU_MAIN_BUS) { - bus_fwd = SUBARU_CAM_BUS; // to the eyesight camera - } - - if (bus_num == SUBARU_CAM_BUS) { - // Global platform - bool block_lkas = ((addr == MSG_SUBARU_ES_LKAS) || - (addr == MSG_SUBARU_ES_DashStatus) || - (addr == MSG_SUBARU_ES_LKAS_State) || - (addr == MSG_SUBARU_ES_Infotainment)); - - bool block_long = ((addr == MSG_SUBARU_ES_Brake) || - (addr == MSG_SUBARU_ES_Distance) || - (addr == MSG_SUBARU_ES_Status)); - - bool block_msg = block_lkas || (subaru_longitudinal && block_long); - if (!block_msg) { - bus_fwd = SUBARU_MAIN_BUS; // Main CAN - } - } - - return bus_fwd; -} - -static safety_config subaru_init(uint16_t param) { - subaru_gen2 = GET_FLAG(param, SUBARU_PARAM_GEN2); - -#ifdef ALLOW_DEBUG - subaru_longitudinal = GET_FLAG(param, SUBARU_PARAM_LONGITUDINAL); -#endif - - safety_config ret; - if (subaru_gen2) { - ret = subaru_longitudinal ? BUILD_SAFETY_CFG(subaru_gen2_rx_checks, SUBARU_GEN2_LONG_TX_MSGS) : \ - BUILD_SAFETY_CFG(subaru_gen2_rx_checks, SUBARU_GEN2_TX_MSGS); - } else { - ret = subaru_longitudinal ? BUILD_SAFETY_CFG(subaru_rx_checks, SUBARU_LONG_TX_MSGS) : \ - BUILD_SAFETY_CFG(subaru_rx_checks, SUBARU_TX_MSGS); - } - return ret; -} - -const safety_hooks subaru_hooks = { - .init = subaru_init, - .rx = subaru_rx_hook, - .tx = subaru_tx_hook, - .fwd = subaru_fwd_hook, - .get_counter = subaru_get_counter, - .get_checksum = subaru_get_checksum, - .compute_checksum = subaru_compute_checksum, -}; diff --git a/panda/board/safety/safety_subaru_preglobal.h b/panda/board/safety/safety_subaru_preglobal.h deleted file mode 100644 index 7d44fb0..0000000 --- a/panda/board/safety/safety_subaru_preglobal.h +++ /dev/null @@ -1,127 +0,0 @@ -const SteeringLimits SUBARU_PG_STEERING_LIMITS = { - .max_steer = 2047, - .max_rt_delta = 940, - .max_rt_interval = 250000, - .max_rate_up = 50, - .max_rate_down = 70, - .driver_torque_factor = 10, - .driver_torque_allowance = 75, - .type = TorqueDriverLimited, -}; - -// Preglobal platform -// 0x161 is ES_CruiseThrottle -// 0x164 is ES_LKAS - -#define MSG_SUBARU_PG_CruiseControl 0x144 -#define MSG_SUBARU_PG_Throttle 0x140 -#define MSG_SUBARU_PG_Wheel_Speeds 0xD4 -#define MSG_SUBARU_PG_Brake_Pedal 0xD1 -#define MSG_SUBARU_PG_ES_LKAS 0x164 -#define MSG_SUBARU_PG_ES_Distance 0x161 -#define MSG_SUBARU_PG_Steering_Torque 0x371 - -#define SUBARU_PG_MAIN_BUS 0 -#define SUBARU_PG_CAM_BUS 2 - -const CanMsg SUBARU_PG_TX_MSGS[] = { - {MSG_SUBARU_PG_ES_Distance, SUBARU_PG_MAIN_BUS, 8}, - {MSG_SUBARU_PG_ES_LKAS, SUBARU_PG_MAIN_BUS, 8} -}; - -// TODO: do checksum and counter checks after adding the signals to the outback dbc file -RxCheck subaru_preglobal_rx_checks[] = { - {.msg = {{MSG_SUBARU_PG_Throttle, SUBARU_PG_MAIN_BUS, 8, .frequency = 100U}, { 0 }, { 0 }}}, - {.msg = {{MSG_SUBARU_PG_Steering_Torque, SUBARU_PG_MAIN_BUS, 8, .frequency = 50U}, { 0 }, { 0 }}}, - {.msg = {{MSG_SUBARU_PG_CruiseControl, SUBARU_PG_MAIN_BUS, 8, .frequency = 20U}, { 0 }, { 0 }}}, -}; - - -const int SUBARU_PG_PARAM_REVERSED_DRIVER_TORQUE = 1; -bool subaru_pg_reversed_driver_torque = false; - - -static void subaru_preglobal_rx_hook(const CANPacket_t *to_push) { - const int bus = GET_BUS(to_push); - - if (bus == SUBARU_PG_MAIN_BUS) { - int addr = GET_ADDR(to_push); - if (addr == MSG_SUBARU_PG_Steering_Torque) { - int torque_driver_new; - torque_driver_new = (GET_BYTE(to_push, 3) >> 5) + (GET_BYTE(to_push, 4) << 3); - torque_driver_new = to_signed(torque_driver_new, 11); - torque_driver_new = subaru_pg_reversed_driver_torque ? -torque_driver_new : torque_driver_new; - update_sample(&torque_driver, torque_driver_new); - } - - // enter controls on rising edge of ACC, exit controls on ACC off - if (addr == MSG_SUBARU_PG_CruiseControl) { - acc_main_on = GET_BIT(to_push, 48U); - bool cruise_engaged = GET_BIT(to_push, 49U); - pcm_cruise_check(cruise_engaged); - } - - // update vehicle moving with any non-zero wheel speed - if (addr == MSG_SUBARU_PG_Wheel_Speeds) { - vehicle_moving = ((GET_BYTES(to_push, 0, 4) >> 12) != 0U) || (GET_BYTES(to_push, 4, 4) != 0U); - } - - if (addr == MSG_SUBARU_PG_Brake_Pedal) { - brake_pressed = ((GET_BYTES(to_push, 0, 4) >> 16) & 0xFFU) > 0U; - } - - if (addr == MSG_SUBARU_PG_Throttle) { - gas_pressed = GET_BYTE(to_push, 0) != 0U; - } - - generic_rx_checks((addr == MSG_SUBARU_PG_ES_LKAS)); - } -} - -static bool subaru_preglobal_tx_hook(const CANPacket_t *to_send) { - bool tx = true; - int addr = GET_ADDR(to_send); - - // steer cmd checks - if (addr == MSG_SUBARU_PG_ES_LKAS) { - int desired_torque = ((GET_BYTES(to_send, 0, 4) >> 8) & 0x1FFFU); - desired_torque = -1 * to_signed(desired_torque, 13); - - bool steer_req = GET_BIT(to_send, 24U); - - if (steer_torque_cmd_checks(desired_torque, steer_req, SUBARU_PG_STEERING_LIMITS)) { - tx = false; - } - - } - return tx; -} - -static int subaru_preglobal_fwd_hook(int bus_num, int addr) { - int bus_fwd = -1; - - if (bus_num == SUBARU_PG_MAIN_BUS) { - bus_fwd = SUBARU_PG_CAM_BUS; // Camera CAN - } - - if (bus_num == SUBARU_PG_CAM_BUS) { - bool block_msg = ((addr == MSG_SUBARU_PG_ES_Distance) || (addr == MSG_SUBARU_PG_ES_LKAS)); - if (!block_msg) { - bus_fwd = SUBARU_PG_MAIN_BUS; // Main CAN - } - } - - return bus_fwd; -} - -static safety_config subaru_preglobal_init(uint16_t param) { - subaru_pg_reversed_driver_torque = GET_FLAG(param, SUBARU_PG_PARAM_REVERSED_DRIVER_TORQUE); - return BUILD_SAFETY_CFG(subaru_preglobal_rx_checks, SUBARU_PG_TX_MSGS); -} - -const safety_hooks subaru_preglobal_hooks = { - .init = subaru_preglobal_init, - .rx = subaru_preglobal_rx_hook, - .tx = subaru_preglobal_tx_hook, - .fwd = subaru_preglobal_fwd_hook, -}; diff --git a/panda/board/safety/safety_tesla.h b/panda/board/safety/safety_tesla.h deleted file mode 100644 index a2401c2..0000000 --- a/panda/board/safety/safety_tesla.h +++ /dev/null @@ -1,234 +0,0 @@ -const SteeringLimits TESLA_STEERING_LIMITS = { - .angle_deg_to_can = 10, - .angle_rate_up_lookup = { - {0., 5., 15.}, - {10., 1.6, .3} - }, - .angle_rate_down_lookup = { - {0., 5., 15.}, - {10., 7.0, .8} - }, -}; - -const LongitudinalLimits TESLA_LONG_LIMITS = { - .max_accel = 425, // 2. m/s^2 - .min_accel = 287, // -3.52 m/s^2 // TODO: limit to -3.48 - .inactive_accel = 375, // 0. m/s^2 -}; - - -const int TESLA_FLAG_POWERTRAIN = 1; -const int TESLA_FLAG_LONGITUDINAL_CONTROL = 2; - -const CanMsg TESLA_TX_MSGS[] = { - {0x488, 0, 4}, // DAS_steeringControl - {0x45, 0, 8}, // STW_ACTN_RQ - {0x45, 2, 8}, // STW_ACTN_RQ - {0x2b9, 0, 8}, // DAS_control -}; - -const CanMsg TESLA_PT_TX_MSGS[] = { - {0x2bf, 0, 8}, // DAS_control -}; - -RxCheck tesla_rx_checks[] = { - {.msg = {{0x2b9, 2, 8, .frequency = 25U}, { 0 }, { 0 }}}, // DAS_control - {.msg = {{0x370, 0, 8, .frequency = 25U}, { 0 }, { 0 }}}, // EPAS_sysStatus - {.msg = {{0x108, 0, 8, .frequency = 100U}, { 0 }, { 0 }}}, // DI_torque1 - {.msg = {{0x118, 0, 6, .frequency = 100U}, { 0 }, { 0 }}}, // DI_torque2 - {.msg = {{0x20a, 0, 8, .frequency = 50U}, { 0 }, { 0 }}}, // BrakeMessage - {.msg = {{0x368, 0, 8, .frequency = 10U}, { 0 }, { 0 }}}, // DI_state - {.msg = {{0x318, 0, 8, .frequency = 10U}, { 0 }, { 0 }}}, // GTW_carState -}; - -RxCheck tesla_pt_rx_checks[] = { - {.msg = {{0x106, 0, 8, .frequency = 100U}, { 0 }, { 0 }}}, // DI_torque1 - {.msg = {{0x116, 0, 6, .frequency = 100U}, { 0 }, { 0 }}}, // DI_torque2 - {.msg = {{0x1f8, 0, 8, .frequency = 50U}, { 0 }, { 0 }}}, // BrakeMessage - {.msg = {{0x2bf, 2, 8, .frequency = 25U}, { 0 }, { 0 }}}, // DAS_control - {.msg = {{0x256, 0, 8, .frequency = 10U}, { 0 }, { 0 }}}, // DI_state -}; - -bool tesla_longitudinal = false; -bool tesla_powertrain = false; // Are we the second panda intercepting the powertrain bus? - -bool tesla_stock_aeb = false; - -static void tesla_rx_hook(const CANPacket_t *to_push) { - int bus = GET_BUS(to_push); - int addr = GET_ADDR(to_push); - - if(bus == 0) { - if (!tesla_powertrain) { - if(addr == 0x370) { - // Steering angle: (0.1 * val) - 819.2 in deg. - // Store it 1/10 deg to match steering request - int angle_meas_new = (((GET_BYTE(to_push, 4) & 0x3FU) << 8) | GET_BYTE(to_push, 5)) - 8192U; - update_sample(&angle_meas, angle_meas_new); - } - } - - if(addr == (tesla_powertrain ? 0x116 : 0x118)) { - // Vehicle speed: ((0.05 * val) - 25) * MPH_TO_MPS - float speed = (((((GET_BYTE(to_push, 3) & 0x0FU) << 8) | (GET_BYTE(to_push, 2))) * 0.05) - 25) * 0.447; - vehicle_moving = ABS(speed) > 0.1; - UPDATE_VEHICLE_SPEED(speed); - } - - if(addr == (tesla_powertrain ? 0x106 : 0x108)) { - // Gas pressed - gas_pressed = (GET_BYTE(to_push, 6) != 0U); - } - - if(addr == (tesla_powertrain ? 0x1f8 : 0x20a)) { - // Brake pressed - brake_pressed = (((GET_BYTE(to_push, 0) & 0x0CU) >> 2) != 1U); - } - - if(addr == (tesla_powertrain ? 0x256 : 0x368)) { - // Cruise state - int cruise_state = (GET_BYTE(to_push, 1) >> 4); - - acc_main_on = (cruise_state == 1) || // STANDBY - (cruise_state == 2) || // ENABLED - (cruise_state == 3) || // STANDSTILL - (cruise_state == 4) || // OVERRIDE - (cruise_state == 6) || // PRE_FAULT - (cruise_state == 7); // PRE_CANCEL - - bool cruise_engaged = (cruise_state == 2) || // ENABLED - (cruise_state == 3) || // STANDSTILL - (cruise_state == 4) || // OVERRIDE - (cruise_state == 6) || // PRE_FAULT - (cruise_state == 7); // PRE_CANCEL - pcm_cruise_check(cruise_engaged); - } - } - - if (bus == 2) { - int das_control_addr = (tesla_powertrain ? 0x2bf : 0x2b9); - if (tesla_longitudinal && (addr == das_control_addr)) { - // "AEB_ACTIVE" - tesla_stock_aeb = ((GET_BYTE(to_push, 2) & 0x03U) == 1U); - } - } - - if (tesla_powertrain) { - // 0x2bf: DAS_control should not be received on bus 0 - generic_rx_checks((addr == 0x2bf) && (bus == 0)); - } else { - // 0x488: DAS_steeringControl should not be received on bus 0 - generic_rx_checks((addr == 0x488) && (bus == 0)); - } - -} - - -static bool tesla_tx_hook(const CANPacket_t *to_send) { - bool tx = true; - int addr = GET_ADDR(to_send); - bool violation = false; - - if(!tesla_powertrain && (addr == 0x488)) { - // Steering control: (0.1 * val) - 1638.35 in deg. - // We use 1/10 deg as a unit here - int raw_angle_can = (((GET_BYTE(to_send, 0) & 0x7FU) << 8) | GET_BYTE(to_send, 1)); - int desired_angle = raw_angle_can - 16384; - int steer_control_type = GET_BYTE(to_send, 2) >> 6; - bool steer_control_enabled = (steer_control_type != 0) && // NONE - (steer_control_type != 3); // DISABLED - - if (steer_angle_cmd_checks(desired_angle, steer_control_enabled, TESLA_STEERING_LIMITS)) { - violation = true; - } - } - - if (!tesla_powertrain && (addr == 0x45)) { - // No button other than cancel can be sent by us - int control_lever_status = (GET_BYTE(to_send, 0) & 0x3FU); - if (control_lever_status != 1) { - violation = true; - } - } - - if(addr == (tesla_powertrain ? 0x2bf : 0x2b9)) { - // DAS_control: longitudinal control message - if (tesla_longitudinal) { - // No AEB events may be sent by openpilot - int aeb_event = GET_BYTE(to_send, 2) & 0x03U; - if (aeb_event != 0) { - violation = true; - } - - // Don't send messages when the stock AEB system is active - if (tesla_stock_aeb) { - violation = true; - } - - // Don't allow any acceleration limits above the safety limits - int raw_accel_max = ((GET_BYTE(to_send, 6) & 0x1FU) << 4) | (GET_BYTE(to_send, 5) >> 4); - int raw_accel_min = ((GET_BYTE(to_send, 5) & 0x0FU) << 5) | (GET_BYTE(to_send, 4) >> 3); - violation |= longitudinal_accel_checks(raw_accel_max, TESLA_LONG_LIMITS); - violation |= longitudinal_accel_checks(raw_accel_min, TESLA_LONG_LIMITS); - } else { - violation = true; - } - } - - if (violation) { - tx = false; - } - - return tx; -} - -static int tesla_fwd_hook(int bus_num, int addr) { - int bus_fwd = -1; - - if(bus_num == 0) { - // Chassis/PT to autopilot - bus_fwd = 2; - } - - if(bus_num == 2) { - // Autopilot to chassis/PT - int das_control_addr = (tesla_powertrain ? 0x2bf : 0x2b9); - - bool block_msg = false; - if (!tesla_powertrain && (addr == 0x488)) { - block_msg = true; - } - - if (tesla_longitudinal && (addr == das_control_addr) && !tesla_stock_aeb) { - block_msg = true; - } - - if(!block_msg) { - bus_fwd = 0; - } - } - - return bus_fwd; -} - -static safety_config tesla_init(uint16_t param) { - tesla_powertrain = GET_FLAG(param, TESLA_FLAG_POWERTRAIN); - tesla_longitudinal = GET_FLAG(param, TESLA_FLAG_LONGITUDINAL_CONTROL); - - tesla_stock_aeb = false; - - safety_config ret; - if (tesla_powertrain) { - ret = BUILD_SAFETY_CFG(tesla_pt_rx_checks, TESLA_PT_TX_MSGS); - } else { - ret = BUILD_SAFETY_CFG(tesla_rx_checks, TESLA_TX_MSGS); - } - return ret; -} - -const safety_hooks tesla_hooks = { - .init = tesla_init, - .rx = tesla_rx_hook, - .tx = tesla_tx_hook, - .fwd = tesla_fwd_hook, -}; diff --git a/panda/board/safety/safety_toyota.h b/panda/board/safety/safety_toyota.h deleted file mode 100644 index 538fc79..0000000 --- a/panda/board/safety/safety_toyota.h +++ /dev/null @@ -1,434 +0,0 @@ -const SteeringLimits TOYOTA_STEERING_LIMITS = { - .max_steer = 1500, - .max_rate_up = 15, // ramp up slow - .max_rate_down = 25, // ramp down fast - .max_torque_error = 350, // max torque cmd in excess of motor torque - .max_rt_delta = 450, // the real time limit is 1800/sec, a 20% buffer - .max_rt_interval = 250000, - .type = TorqueMotorLimited, - - // the EPS faults when the steering angle rate is above a certain threshold for too long. to prevent this, - // we allow setting STEER_REQUEST bit to 0 while maintaining the requested torque value for a single frame - .min_valid_request_frames = 18, - .max_invalid_request_frames = 1, - .min_valid_request_rt_interval = 170000, // 170ms; a ~10% buffer on cutting every 19 frames - .has_steer_req_tolerance = true, - - // LTA angle limits - // factor for STEER_TORQUE_SENSOR->STEER_ANGLE and STEERING_LTA->STEER_ANGLE_CMD (1 / 0.0573) - .angle_deg_to_can = 17.452007, - .angle_rate_up_lookup = { - {5., 25., 25.}, - {0.3, 0.15, 0.15} - }, - .angle_rate_down_lookup = { - {5., 25., 25.}, - {0.36, 0.26, 0.26} - }, -}; - -const int TOYOTA_LTA_MAX_ANGLE = 1657; // EPS only accepts up to 94.9461 -const int TOYOTA_LTA_MAX_MEAS_TORQUE = 1500; -const int TOYOTA_LTA_MAX_DRIVER_TORQUE = 150; - -// longitudinal limits -const LongitudinalLimits TOYOTA_LONG_LIMITS = { - .max_accel = 2000, // 2.0 m/s2 - .min_accel = -3500, // -3.5 m/s2 -}; - -const LongitudinalLimits TOYOTA_LONG_LIMITS_SPORT = { - .max_accel = 4000, // 4.0 m/s2 - .min_accel = -3500, // -3.5 m/s2 -}; - -// panda interceptor threshold needs to be equivalent to openpilot threshold to avoid controls mismatches -// If thresholds are mismatched then it is possible for panda to see the gas fall and rise while openpilot is in the pre-enabled state -// Threshold calculated from DBC gains: round((((15 + 75.555) / 0.159375) + ((15 + 151.111) / 0.159375)) / 2) = 805 -const int TOYOTA_GAS_INTERCEPTOR_THRSLD = 805; -#define TOYOTA_GET_INTERCEPTOR(msg) (((GET_BYTE((msg), 0) << 8) + GET_BYTE((msg), 1) + (GET_BYTE((msg), 2) << 8) + GET_BYTE((msg), 3)) / 2U) // avg between 2 tracks - -// Stock longitudinal -#define TOYOTA_COMMON_TX_MSGS \ - {0x2E4, 0, 5}, {0x191, 0, 8}, {0x412, 0, 8}, {0x343, 0, 8}, {0x1D2, 0, 8}, /* LKAS + LTA + ACC & PCM cancel cmds */ \ - -#define TOYOTA_COMMON_LONG_TX_MSGS \ - TOYOTA_COMMON_TX_MSGS \ - {0x283, 0, 7}, {0x2E6, 0, 8}, {0x2E7, 0, 8}, {0x33E, 0, 7}, {0x344, 0, 8}, {0x365, 0, 7}, {0x366, 0, 7}, {0x4CB, 0, 8}, /* DSU bus 0 */ \ - {0x128, 1, 6}, {0x141, 1, 4}, {0x160, 1, 8}, {0x161, 1, 7}, {0x470, 1, 4}, /* DSU bus 1 */ \ - {0x411, 0, 8}, /* PCS_HUD */ \ - {0x750, 0, 8}, /* radar diagnostic address */ \ - {0x1D3, 0, 8}, \ - -const CanMsg TOYOTA_TX_MSGS[] = { - TOYOTA_COMMON_TX_MSGS -}; - -const CanMsg TOYOTA_LONG_TX_MSGS[] = { - TOYOTA_COMMON_LONG_TX_MSGS -}; - -const CanMsg TOYOTA_INTERCEPTOR_TX_MSGS[] = { - TOYOTA_COMMON_LONG_TX_MSGS - {0x200, 0, 6}, // gas interceptor -}; - -#define TOYOTA_COMMON_RX_CHECKS(lta) \ - {.msg = {{ 0xaa, 0, 8, .check_checksum = false, .frequency = 83U}, { 0 }, { 0 }}}, \ - {.msg = {{0x260, 0, 8, .check_checksum = true, .quality_flag = (lta), .frequency = 50U}, { 0 }, { 0 }}}, \ - {.msg = {{0x1D2, 0, 8, .check_checksum = true, .frequency = 33U}, { 0 }, { 0 }}}, \ - {.msg = {{0x1D3, 0, 8, .check_checksum = true, .frequency = 33U}, { 0 }, { 0 }}}, \ - {.msg = {{0x224, 0, 8, .check_checksum = false, .frequency = 40U}, \ - {0x226, 0, 8, .check_checksum = false, .frequency = 40U}, { 0 }}}, \ - -RxCheck toyota_lka_rx_checks[] = { - TOYOTA_COMMON_RX_CHECKS(false) -}; - -RxCheck toyota_lka_interceptor_rx_checks[] = { - TOYOTA_COMMON_RX_CHECKS(false) - {.msg = {{0x201, 0, 6, .check_checksum = false, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, -}; - -// Check the quality flag for angle measurement when using LTA, since it's not set on TSS-P cars -RxCheck toyota_lta_rx_checks[] = { - TOYOTA_COMMON_RX_CHECKS(true) -}; - -RxCheck toyota_lta_interceptor_rx_checks[] = { - TOYOTA_COMMON_RX_CHECKS(true) - {.msg = {{0x201, 0, 6, .check_checksum = false, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, -}; - -// safety param flags -// first byte is for EPS factor, second is for flags -const uint32_t TOYOTA_PARAM_OFFSET = 8U; -const uint32_t TOYOTA_EPS_FACTOR = (1UL << TOYOTA_PARAM_OFFSET) - 1U; -const uint32_t TOYOTA_PARAM_ALT_BRAKE = 1UL << TOYOTA_PARAM_OFFSET; -const uint32_t TOYOTA_PARAM_STOCK_LONGITUDINAL = 2UL << TOYOTA_PARAM_OFFSET; -const uint32_t TOYOTA_PARAM_LTA = 4UL << TOYOTA_PARAM_OFFSET; -const uint32_t TOYOTA_PARAM_GAS_INTERCEPTOR = 8UL << TOYOTA_PARAM_OFFSET; - -bool toyota_alt_brake = false; -bool toyota_stock_longitudinal = false; -bool toyota_lta = false; -int toyota_dbc_eps_torque_factor = 100; // conversion factor for STEER_TORQUE_EPS in %: see dbc file - -static uint32_t toyota_compute_checksum(const CANPacket_t *to_push) { - int addr = GET_ADDR(to_push); - int len = GET_LEN(to_push); - uint8_t checksum = (uint8_t)(addr) + (uint8_t)((unsigned int)(addr) >> 8U) + (uint8_t)(len); - for (int i = 0; i < (len - 1); i++) { - checksum += (uint8_t)GET_BYTE(to_push, i); - } - return checksum; -} - -static uint32_t toyota_get_checksum(const CANPacket_t *to_push) { - int checksum_byte = GET_LEN(to_push) - 1U; - return (uint8_t)(GET_BYTE(to_push, checksum_byte)); -} - -static uint8_t toyota_get_counter(const CANPacket_t *to_push) { - int addr = GET_ADDR(to_push); - - uint8_t cnt = 0U; - if (addr == 0x201) { - // Signal: COUNTER_PEDAL - cnt = GET_BYTE(to_push, 4) & 0x0FU; - } - return cnt; -} - -static bool toyota_get_quality_flag_valid(const CANPacket_t *to_push) { - int addr = GET_ADDR(to_push); - - bool valid = false; - if (addr == 0x260) { - valid = !GET_BIT(to_push, 3U); // STEER_ANGLE_INITIALIZING - } - return valid; -} - -static void toyota_rx_hook(const CANPacket_t *to_push) { - if (GET_BUS(to_push) == 0U) { - int addr = GET_ADDR(to_push); - - // get eps motor torque (0.66 factor in dbc) - if (addr == 0x260) { - int torque_meas_new = (GET_BYTE(to_push, 5) << 8) | GET_BYTE(to_push, 6); - torque_meas_new = to_signed(torque_meas_new, 16); - - // scale by dbc_factor - torque_meas_new = (torque_meas_new * toyota_dbc_eps_torque_factor) / 100; - - // update array of sample - update_sample(&torque_meas, torque_meas_new); - - // increase torque_meas by 1 to be conservative on rounding - torque_meas.min--; - torque_meas.max++; - - // driver torque for angle limiting - int torque_driver_new = (GET_BYTE(to_push, 1) << 8) | GET_BYTE(to_push, 2); - torque_driver_new = to_signed(torque_driver_new, 16); - update_sample(&torque_driver, torque_driver_new); - - // LTA request angle should match current angle while inactive, clipped to max accepted angle. - // note that angle can be relative to init angle on some TSS2 platforms, LTA has the same offset - bool steer_angle_initializing = GET_BIT(to_push, 3U); - if (!steer_angle_initializing) { - int angle_meas_new = (GET_BYTE(to_push, 3) << 8U) | GET_BYTE(to_push, 4); - angle_meas_new = CLAMP(to_signed(angle_meas_new, 16), -TOYOTA_LTA_MAX_ANGLE, TOYOTA_LTA_MAX_ANGLE); - update_sample(&angle_meas, angle_meas_new); - } - } - if (addr == 0x1D3) { - acc_main_on = GET_BIT(to_push, 15U); - } - - // enter controls on rising edge of ACC, exit controls on ACC off - // exit controls on rising edge of gas press - if (addr == 0x1D2) { - // 5th bit is CRUISE_ACTIVE - bool cruise_engaged = GET_BIT(to_push, 5U); - pcm_cruise_check(cruise_engaged); - - // sample gas pedal - if (!enable_gas_interceptor) { - gas_pressed = !GET_BIT(to_push, 4U); - } - } - - // sample speed - if (addr == 0xaa) { - int speed = 0; - // sum 4 wheel speeds. conversion: raw * 0.01 - 67.67 - for (uint8_t i = 0U; i < 8U; i += 2U) { - int wheel_speed = (GET_BYTE(to_push, i) << 8U) | GET_BYTE(to_push, (i + 1U)); - speed += wheel_speed - 6767; - } - // check that all wheel speeds are at zero value - vehicle_moving = speed != 0; - - UPDATE_VEHICLE_SPEED(speed / 4.0 * 0.01 / 3.6); - } - - // most cars have brake_pressed on 0x226, corolla and rav4 on 0x224 - if (((addr == 0x224) && toyota_alt_brake) || ((addr == 0x226) && !toyota_alt_brake)) { - uint8_t bit = (addr == 0x224) ? 5U : 37U; - brake_pressed = GET_BIT(to_push, bit); - } - - // sample gas interceptor - if ((addr == 0x201) && enable_gas_interceptor) { - int gas_interceptor = TOYOTA_GET_INTERCEPTOR(to_push); - gas_pressed = gas_interceptor > TOYOTA_GAS_INTERCEPTOR_THRSLD; - - // TODO: remove this, only left in for gas_interceptor_prev test - gas_interceptor_prev = gas_interceptor; - } - - bool stock_ecu_detected = addr == 0x2E4; // STEERING_LKA - if (!toyota_stock_longitudinal && (addr == 0x343)) { - stock_ecu_detected = true; // ACC_CONTROL - } - generic_rx_checks(stock_ecu_detected); - } -} - -static bool toyota_tx_hook(const CANPacket_t *to_send) { - sport_mode = alternative_experience & ALT_EXP_RAISE_LONGITUDINAL_LIMITS_TO_ISO_MAX; - - bool tx = true; - int addr = GET_ADDR(to_send); - int bus = GET_BUS(to_send); - - // Check if msg is sent on BUS 0 - if (bus == 0) { - - // GAS PEDAL: safety check - if (addr == 0x200) { - if (longitudinal_interceptor_checks(to_send)) { - tx = false; - } - } - - // ACCEL: safety check on byte 1-2 - if (addr == 0x343) { - int desired_accel = (GET_BYTE(to_send, 0) << 8) | GET_BYTE(to_send, 1); - desired_accel = to_signed(desired_accel, 16); - - bool violation = false; - if (sport_mode) { - violation |= longitudinal_accel_checks(desired_accel, TOYOTA_LONG_LIMITS_SPORT); - } else { - violation |= longitudinal_accel_checks(desired_accel, TOYOTA_LONG_LIMITS); - } - - // only ACC messages that cancel are allowed when openpilot is not controlling longitudinal - if (toyota_stock_longitudinal) { - bool cancel_req = GET_BIT(to_send, 24U); - if (!cancel_req) { - violation = true; - } - if (desired_accel != TOYOTA_LONG_LIMITS.inactive_accel) { - violation = true; - } - } - - if (violation) { - tx = false; - } - } - - // AEB: block all actuation. only used when DSU is unplugged - if (addr == 0x283) { - // only allow the checksum, which is the last byte - bool block = (GET_BYTES(to_send, 0, 4) != 0U) || (GET_BYTE(to_send, 4) != 0U) || (GET_BYTE(to_send, 5) != 0U); - if (block) { - tx = false; - } - } - - // LTA angle steering check - if (addr == 0x191) { - // check the STEER_REQUEST, STEER_REQUEST_2, TORQUE_WIND_DOWN, STEER_ANGLE_CMD signals - bool lta_request = GET_BIT(to_send, 0U); - bool lta_request2 = GET_BIT(to_send, 25U); - int torque_wind_down = GET_BYTE(to_send, 5); - int lta_angle = (GET_BYTE(to_send, 1) << 8) | GET_BYTE(to_send, 2); - lta_angle = to_signed(lta_angle, 16); - - bool steer_control_enabled = lta_request || lta_request2; - if (!toyota_lta) { - // using torque (LKA), block LTA msgs with actuation requests - if (steer_control_enabled || (lta_angle != 0) || (torque_wind_down != 0)) { - tx = false; - } - } else { - // check angle rate limits and inactive angle - if (steer_angle_cmd_checks(lta_angle, steer_control_enabled, TOYOTA_STEERING_LIMITS)) { - tx = false; - } - - if (lta_request != lta_request2) { - tx = false; - } - - // TORQUE_WIND_DOWN is gated on steer request - if (!steer_control_enabled && (torque_wind_down != 0)) { - tx = false; - } - - // TORQUE_WIND_DOWN can only be no or full torque - if ((torque_wind_down != 0) && (torque_wind_down != 100)) { - tx = false; - } - - // check if we should wind down torque - int driver_torque = MIN(ABS(torque_driver.min), ABS(torque_driver.max)); - if ((driver_torque > TOYOTA_LTA_MAX_DRIVER_TORQUE) && (torque_wind_down != 0)) { - tx = false; - } - - int eps_torque = MIN(ABS(torque_meas.min), ABS(torque_meas.max)); - if ((eps_torque > TOYOTA_LTA_MAX_MEAS_TORQUE) && (torque_wind_down != 0)) { - tx = false; - } - } - } - - // STEER: safety check on bytes 2-3 - if (addr == 0x2E4) { - int desired_torque = (GET_BYTE(to_send, 1) << 8) | GET_BYTE(to_send, 2); - desired_torque = to_signed(desired_torque, 16); - bool steer_req = GET_BIT(to_send, 0U); - // When using LTA (angle control), assert no actuation on LKA message - if (!toyota_lta) { - if (steer_torque_cmd_checks(desired_torque, steer_req, TOYOTA_STEERING_LIMITS)) { - tx = false; - } - } else { - if ((desired_torque != 0) || steer_req) { - tx = false; - } - } - } - } - - // UDS: Only tester present ("\x0F\x02\x3E\x00\x00\x00\x00\x00") allowed on diagnostics address - if (addr == 0x750) { - // this address is sub-addressed. only allow tester present to radar (0xF) - bool invalid_uds_msg = (GET_BYTES(to_send, 0, 4) != 0x003E020FU) || (GET_BYTES(to_send, 4, 4) != 0x0U); - if (invalid_uds_msg) { - tx = 0; - } - } - - return tx; -} - -static safety_config toyota_init(uint16_t param) { - toyota_alt_brake = GET_FLAG(param, TOYOTA_PARAM_ALT_BRAKE); - toyota_stock_longitudinal = GET_FLAG(param, TOYOTA_PARAM_STOCK_LONGITUDINAL); - toyota_lta = GET_FLAG(param, TOYOTA_PARAM_LTA); - enable_gas_interceptor = GET_FLAG(param, TOYOTA_PARAM_GAS_INTERCEPTOR); - toyota_dbc_eps_torque_factor = param & TOYOTA_EPS_FACTOR; - - // Gas interceptor should not be used if openpilot is not controlling longitudinal - if (toyota_stock_longitudinal) { - enable_gas_interceptor = false; - } - - safety_config ret; - if (toyota_stock_longitudinal) { - SET_TX_MSGS(TOYOTA_TX_MSGS, ret); - } else { - enable_gas_interceptor ? SET_TX_MSGS(TOYOTA_INTERCEPTOR_TX_MSGS, ret) : \ - SET_TX_MSGS(TOYOTA_LONG_TX_MSGS, ret); - } - - if (enable_gas_interceptor) { - toyota_lta ? SET_RX_CHECKS(toyota_lta_interceptor_rx_checks, ret) : \ - SET_RX_CHECKS(toyota_lka_interceptor_rx_checks, ret); - } else { - toyota_lta ? SET_RX_CHECKS(toyota_lta_rx_checks, ret) : \ - SET_RX_CHECKS(toyota_lka_rx_checks, ret); - } - return ret; -} - -static int toyota_fwd_hook(int bus_num, int addr) { - - int bus_fwd = -1; - - if (bus_num == 0) { - bus_fwd = 2; - } - - if (bus_num == 2) { - // block stock lkas messages and stock acc messages (if OP is doing ACC) - // in TSS2, 0x191 is LTA which we need to block to avoid controls collision - bool is_lkas_msg = ((addr == 0x2E4) || (addr == 0x412) || (addr == 0x191)); - // in TSS2 the camera does ACC as well, so filter 0x343 - bool is_acc_msg = (addr == 0x343); - bool block_msg = is_lkas_msg || (is_acc_msg && !toyota_stock_longitudinal); - if (!block_msg) { - bus_fwd = 0; - } - } - - return bus_fwd; -} - -const safety_hooks toyota_hooks = { - .init = toyota_init, - .rx = toyota_rx_hook, - .tx = toyota_tx_hook, - .fwd = toyota_fwd_hook, - .get_checksum = toyota_get_checksum, - .compute_checksum = toyota_compute_checksum, - .get_counter = toyota_get_counter, - .get_quality_flag_valid = toyota_get_quality_flag_valid, -}; diff --git a/panda/board/safety/safety_volkswagen_common.h b/panda/board/safety/safety_volkswagen_common.h deleted file mode 100644 index ce2bf58..0000000 --- a/panda/board/safety/safety_volkswagen_common.h +++ /dev/null @@ -1,10 +0,0 @@ -#ifndef SAFETY_VOLKSWAGEN_COMMON_H -#define SAFETY_VOLKSWAGEN_COMMON_H - -const uint16_t FLAG_VOLKSWAGEN_LONG_CONTROL = 1; - -bool volkswagen_longitudinal = false; -bool volkswagen_set_button_prev = false; -bool volkswagen_resume_button_prev = false; - -#endif diff --git a/panda/board/safety/safety_volkswagen_mqb.h b/panda/board/safety/safety_volkswagen_mqb.h deleted file mode 100644 index ce152f4..0000000 --- a/panda/board/safety/safety_volkswagen_mqb.h +++ /dev/null @@ -1,314 +0,0 @@ -#include "safety_volkswagen_common.h" - -// lateral limits -const SteeringLimits VOLKSWAGEN_MQB_STEERING_LIMITS = { - .max_steer = 300, // 3.0 Nm (EPS side max of 3.0Nm with fault if violated) - .max_rt_delta = 75, // 4 max rate up * 50Hz send rate * 250000 RT interval / 1000000 = 50 ; 50 * 1.5 for safety pad = 75 - .max_rt_interval = 250000, // 250ms between real time checks - .max_rate_up = 4, // 2.0 Nm/s RoC limit (EPS rack has own soft-limit of 5.0 Nm/s) - .max_rate_down = 10, // 5.0 Nm/s RoC limit (EPS rack has own soft-limit of 5.0 Nm/s) - .driver_torque_allowance = 80, - .driver_torque_factor = 3, - .type = TorqueDriverLimited, -}; - -// longitudinal limits -// acceleration in m/s2 * 1000 to avoid floating point math -const LongitudinalLimits VOLKSWAGEN_MQB_LONG_LIMITS = { - .max_accel = 2000, - .min_accel = -3500, - .inactive_accel = 3010, // VW sends one increment above the max range when inactive -}; - -const LongitudinalLimits VOLKSWAGEN_MQB_LONG_LIMITS_SPORT = { - .max_accel = 4000, - .min_accel = -3500, - .inactive_accel = 3010, // VW sends one increment above the max range when inactive -}; - -#define MSG_ESP_19 0x0B2 // RX from ABS, for wheel speeds -#define MSG_LH_EPS_03 0x09F // RX from EPS, for driver steering torque -#define MSG_ESP_05 0x106 // RX from ABS, for brake switch state -#define MSG_TSK_06 0x120 // RX from ECU, for ACC status from drivetrain coordinator -#define MSG_MOTOR_20 0x121 // RX from ECU, for driver throttle input -#define MSG_ACC_06 0x122 // TX by OP, ACC control instructions to the drivetrain coordinator -#define MSG_HCA_01 0x126 // TX by OP, Heading Control Assist steering torque -#define MSG_GRA_ACC_01 0x12B // TX by OP, ACC control buttons for cancel/resume -#define MSG_ACC_07 0x12E // TX by OP, ACC control instructions to the drivetrain coordinator -#define MSG_ACC_02 0x30C // TX by OP, ACC HUD data to the instrument cluster -#define MSG_MOTOR_14 0x3BE // RX from ECU, for brake switch status -#define MSG_LDW_02 0x397 // TX by OP, Lane line recognition and text alerts - -// Transmit of GRA_ACC_01 is allowed on bus 0 and 2 to keep compatibility with gateway and camera integration -const CanMsg VOLKSWAGEN_MQB_STOCK_TX_MSGS[] = {{MSG_HCA_01, 0, 8}, {MSG_GRA_ACC_01, 0, 8}, {MSG_GRA_ACC_01, 2, 8}, - {MSG_LDW_02, 0, 8}, {MSG_LH_EPS_03, 2, 8}}; -const CanMsg VOLKSWAGEN_MQB_LONG_TX_MSGS[] = {{MSG_HCA_01, 0, 8}, {MSG_LDW_02, 0, 8}, {MSG_LH_EPS_03, 2, 8}, - {MSG_ACC_02, 0, 8}, {MSG_ACC_06, 0, 8}, {MSG_ACC_07, 0, 8}}; - -RxCheck volkswagen_mqb_rx_checks[] = { - {.msg = {{MSG_ESP_19, 0, 8, .check_checksum = false, .max_counter = 0U, .frequency = 100U}, { 0 }, { 0 }}}, - {.msg = {{MSG_LH_EPS_03, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 100U}, { 0 }, { 0 }}}, - {.msg = {{MSG_ESP_05, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, - {.msg = {{MSG_TSK_06, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, - {.msg = {{MSG_MOTOR_20, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 50U}, { 0 }, { 0 }}}, - {.msg = {{MSG_MOTOR_14, 0, 8, .check_checksum = false, .max_counter = 0U, .frequency = 10U}, { 0 }, { 0 }}}, - {.msg = {{MSG_GRA_ACC_01, 0, 8, .check_checksum = true, .max_counter = 15U, .frequency = 33U}, { 0 }, { 0 }}}, -}; - -uint8_t volkswagen_crc8_lut_8h2f[256]; // Static lookup table for CRC8 poly 0x2F, aka 8H2F/AUTOSAR -bool volkswagen_mqb_brake_pedal_switch = false; -bool volkswagen_mqb_brake_pressure_detected = false; - -static uint32_t volkswagen_mqb_get_checksum(const CANPacket_t *to_push) { - return (uint8_t)GET_BYTE(to_push, 0); -} - -static uint8_t volkswagen_mqb_get_counter(const CANPacket_t *to_push) { - // MQB message counters are consistently found at LSB 8. - return (uint8_t)GET_BYTE(to_push, 1) & 0xFU; -} - -static uint32_t volkswagen_mqb_compute_crc(const CANPacket_t *to_push) { - int addr = GET_ADDR(to_push); - int len = GET_LEN(to_push); - - // This is CRC-8H2F/AUTOSAR with a twist. See the OpenDBC implementation - // of this algorithm for a version with explanatory comments. - - uint8_t crc = 0xFFU; - for (int i = 1; i < len; i++) { - crc ^= (uint8_t)GET_BYTE(to_push, i); - crc = volkswagen_crc8_lut_8h2f[crc]; - } - - uint8_t counter = volkswagen_mqb_get_counter(to_push); - if (addr == MSG_LH_EPS_03) { - crc ^= (uint8_t[]){0xF5,0xF5,0xF5,0xF5,0xF5,0xF5,0xF5,0xF5,0xF5,0xF5,0xF5,0xF5,0xF5,0xF5,0xF5,0xF5}[counter]; - } else if (addr == MSG_ESP_05) { - crc ^= (uint8_t[]){0x07,0x07,0x07,0x07,0x07,0x07,0x07,0x07,0x07,0x07,0x07,0x07,0x07,0x07,0x07,0x07}[counter]; - } else if (addr == MSG_TSK_06) { - crc ^= (uint8_t[]){0xC4,0xE2,0x4F,0xE4,0xF8,0x2F,0x56,0x81,0x9F,0xE5,0x83,0x44,0x05,0x3F,0x97,0xDF}[counter]; - } else if (addr == MSG_MOTOR_20) { - crc ^= (uint8_t[]){0xE9,0x65,0xAE,0x6B,0x7B,0x35,0xE5,0x5F,0x4E,0xC7,0x86,0xA2,0xBB,0xDD,0xEB,0xB4}[counter]; - } else if (addr == MSG_GRA_ACC_01) { - crc ^= (uint8_t[]){0x6A,0x38,0xB4,0x27,0x22,0xEF,0xE1,0xBB,0xF8,0x80,0x84,0x49,0xC7,0x9E,0x1E,0x2B}[counter]; - } else { - // Undefined CAN message, CRC check expected to fail - } - crc = volkswagen_crc8_lut_8h2f[crc]; - - return (uint8_t)(crc ^ 0xFFU); -} - -static safety_config volkswagen_mqb_init(uint16_t param) { - UNUSED(param); - - volkswagen_set_button_prev = false; - volkswagen_resume_button_prev = false; - volkswagen_mqb_brake_pedal_switch = false; - volkswagen_mqb_brake_pressure_detected = false; - -#ifdef ALLOW_DEBUG - volkswagen_longitudinal = GET_FLAG(param, FLAG_VOLKSWAGEN_LONG_CONTROL); -#endif - gen_crc_lookup_table_8(0x2F, volkswagen_crc8_lut_8h2f); - return volkswagen_longitudinal ? BUILD_SAFETY_CFG(volkswagen_mqb_rx_checks, VOLKSWAGEN_MQB_LONG_TX_MSGS) : \ - BUILD_SAFETY_CFG(volkswagen_mqb_rx_checks, VOLKSWAGEN_MQB_STOCK_TX_MSGS); -} - -static void volkswagen_mqb_rx_hook(const CANPacket_t *to_push) { - if (GET_BUS(to_push) == 0U) { - int addr = GET_ADDR(to_push); - - // Update in-motion state by sampling wheel speeds - if (addr == MSG_ESP_19) { - // sum 4 wheel speeds - int speed = 0; - for (uint8_t i = 0U; i < 8U; i += 2U) { - int wheel_speed = GET_BYTE(to_push, i) | (GET_BYTE(to_push, i + 1U) << 8); - speed += wheel_speed; - } - // Check all wheel speeds for any movement - vehicle_moving = speed > 0; - } - - // Update driver input torque samples - // Signal: LH_EPS_03.EPS_Lenkmoment (absolute torque) - // Signal: LH_EPS_03.EPS_VZ_Lenkmoment (direction) - if (addr == MSG_LH_EPS_03) { - int torque_driver_new = GET_BYTE(to_push, 5) | ((GET_BYTE(to_push, 6) & 0x1FU) << 8); - int sign = (GET_BYTE(to_push, 6) & 0x80U) >> 7; - if (sign == 1) { - torque_driver_new *= -1; - } - update_sample(&torque_driver, torque_driver_new); - } - - if (addr == MSG_TSK_06) { - // When using stock ACC, enter controls on rising edge of stock ACC engage, exit on disengage - // Always exit controls on main switch off - // Signal: TSK_06.TSK_Status - int acc_status = (GET_BYTE(to_push, 3) & 0x7U); - bool cruise_engaged = (acc_status == 3) || (acc_status == 4) || (acc_status == 5); - acc_main_on = cruise_engaged || (acc_status == 2); - - if (!volkswagen_longitudinal) { - pcm_cruise_check(cruise_engaged); - } - - if (!acc_main_on) { - controls_allowed = false; - } - } - - if (addr == MSG_GRA_ACC_01) { - // If using openpilot longitudinal, enter controls on falling edge of Set or Resume with main switch on - // Signal: GRA_ACC_01.GRA_Tip_Setzen - // Signal: GRA_ACC_01.GRA_Tip_Wiederaufnahme - if (volkswagen_longitudinal) { - bool set_button = GET_BIT(to_push, 16U); - bool resume_button = GET_BIT(to_push, 19U); - if ((volkswagen_set_button_prev && !set_button) || (volkswagen_resume_button_prev && !resume_button)) { - controls_allowed = acc_main_on; - } - volkswagen_set_button_prev = set_button; - volkswagen_resume_button_prev = resume_button; - } - // Always exit controls on rising edge of Cancel - // Signal: GRA_ACC_01.GRA_Abbrechen - if (GET_BIT(to_push, 13U)) { - controls_allowed = false; - } - } - - // Signal: Motor_20.MO_Fahrpedalrohwert_01 - if (addr == MSG_MOTOR_20) { - gas_pressed = ((GET_BYTES(to_push, 0, 4) >> 12) & 0xFFU) != 0U; - } - - // Signal: Motor_14.MO_Fahrer_bremst (ECU detected brake pedal switch F63) - if (addr == MSG_MOTOR_14) { - volkswagen_mqb_brake_pedal_switch = (GET_BYTE(to_push, 3) & 0x10U) >> 4; - } - - // Signal: ESP_05.ESP_Fahrer_bremst (ESP detected driver brake pressure above platform specified threshold) - if (addr == MSG_ESP_05) { - volkswagen_mqb_brake_pressure_detected = (GET_BYTE(to_push, 3) & 0x4U) >> 2; - } - - brake_pressed = volkswagen_mqb_brake_pedal_switch || volkswagen_mqb_brake_pressure_detected; - - generic_rx_checks((addr == MSG_HCA_01)); - } -} - -static bool volkswagen_mqb_tx_hook(const CANPacket_t *to_send) { - sport_mode = alternative_experience & ALT_EXP_RAISE_LONGITUDINAL_LIMITS_TO_ISO_MAX; - - int addr = GET_ADDR(to_send); - bool tx = true; - - // Safety check for HCA_01 Heading Control Assist torque - // Signal: HCA_01.HCA_01_LM_Offset (absolute torque) - // Signal: HCA_01.HCA_01_LM_OffSign (direction) - if (addr == MSG_HCA_01) { - int desired_torque = GET_BYTE(to_send, 2) | ((GET_BYTE(to_send, 3) & 0x1U) << 8); - bool sign = GET_BIT(to_send, 31U); - if (sign) { - desired_torque *= -1; - } - - bool steer_req = GET_BIT(to_send, 30U); - - if (steer_torque_cmd_checks(desired_torque, steer_req, VOLKSWAGEN_MQB_STEERING_LIMITS)) { - tx = false; - } - } - - // Safety check for both ACC_06 and ACC_07 acceleration requests - // To avoid floating point math, scale upward and compare to pre-scaled safety m/s2 boundaries - if ((addr == MSG_ACC_06) || (addr == MSG_ACC_07)) { - bool violation = false; - int desired_accel = 0; - - if (addr == MSG_ACC_06) { - // Signal: ACC_06.ACC_Sollbeschleunigung_02 (acceleration in m/s2, scale 0.005, offset -7.22) - desired_accel = ((((GET_BYTE(to_send, 4) & 0x7U) << 8) | GET_BYTE(to_send, 3)) * 5U) - 7220U; - } else { - // Signal: ACC_07.ACC_Folgebeschl (acceleration in m/s2, scale 0.03, offset -4.6) - int secondary_accel = (GET_BYTE(to_send, 4) * 30U) - 4600U; - violation |= (secondary_accel != 3020); // enforce always inactive (one increment above max range) at this time - // Signal: ACC_07.ACC_Sollbeschleunigung_02 (acceleration in m/s2, scale 0.005, offset -7.22) - desired_accel = (((GET_BYTE(to_send, 7) << 3) | ((GET_BYTE(to_send, 6) & 0xE0U) >> 5)) * 5U) - 7220U; - } - - if (sport_mode) { - if (desired_accel != 0) { - violation |= longitudinal_accel_checks(desired_accel, VOLKSWAGEN_MQB_LONG_LIMITS_SPORT); - } - } else { - if (desired_accel != 0) { - violation |= longitudinal_accel_checks(desired_accel, VOLKSWAGEN_MQB_LONG_LIMITS); - } - } - - if (violation) { - tx = false; - } - } - - // FORCE CANCEL: ensuring that only the cancel button press is sent when controls are off. - // This avoids unintended engagements while still allowing resume spam - if ((addr == MSG_GRA_ACC_01) && !controls_allowed) { - // disallow resume and set: bits 16 and 19 - if ((GET_BYTE(to_send, 2) & 0x9U) != 0U) { - tx = false; - } - } - - return tx; -} - -static int volkswagen_mqb_fwd_hook(int bus_num, int addr) { - int bus_fwd = -1; - - switch (bus_num) { - case 0: - if (addr == MSG_LH_EPS_03) { - // openpilot needs to replace apparent driver steering input torque to pacify VW Emergency Assist - bus_fwd = -1; - } else { - // Forward all remaining traffic from Extended CAN onward - bus_fwd = 2; - } - break; - case 2: - if ((addr == MSG_HCA_01) || (addr == MSG_LDW_02)) { - // openpilot takes over LKAS steering control and related HUD messages from the camera - bus_fwd = -1; - } else if (volkswagen_longitudinal && ((addr == MSG_ACC_02) || (addr == MSG_ACC_06) || (addr == MSG_ACC_07))) { - // openpilot takes over acceleration/braking control and related HUD messages from the stock ACC radar - bus_fwd = -1; - } else { - // Forward all remaining traffic from Extended CAN devices to J533 gateway - bus_fwd = 0; - } - break; - default: - // No other buses should be in use; fallback to do-not-forward - bus_fwd = -1; - break; - } - - return bus_fwd; -} - -const safety_hooks volkswagen_mqb_hooks = { - .init = volkswagen_mqb_init, - .rx = volkswagen_mqb_rx_hook, - .tx = volkswagen_mqb_tx_hook, - .fwd = volkswagen_mqb_fwd_hook, - .get_counter = volkswagen_mqb_get_counter, - .get_checksum = volkswagen_mqb_get_checksum, - .compute_checksum = volkswagen_mqb_compute_crc, -}; diff --git a/panda/board/safety/safety_volkswagen_pq.h b/panda/board/safety/safety_volkswagen_pq.h deleted file mode 100644 index 671f006..0000000 --- a/panda/board/safety/safety_volkswagen_pq.h +++ /dev/null @@ -1,269 +0,0 @@ -#include "safety_volkswagen_common.h" - -// lateral limits -const SteeringLimits VOLKSWAGEN_PQ_STEERING_LIMITS = { - .max_steer = 300, // 3.0 Nm (EPS side max of 3.0Nm with fault if violated) - .max_rt_delta = 113, // 6 max rate up * 50Hz send rate * 250000 RT interval / 1000000 = 75 ; 125 * 1.5 for safety pad = 113 - .max_rt_interval = 250000, // 250ms between real time checks - .max_rate_up = 6, // 3.0 Nm/s RoC limit (EPS rack has own soft-limit of 5.0 Nm/s) - .max_rate_down = 10, // 5.0 Nm/s RoC limit (EPS rack has own soft-limit of 5.0 Nm/s) - .driver_torque_factor = 3, - .driver_torque_allowance = 80, - .type = TorqueDriverLimited, -}; - -// longitudinal limits -// acceleration in m/s2 * 1000 to avoid floating point math -const LongitudinalLimits VOLKSWAGEN_PQ_LONG_LIMITS = { - .max_accel = 2000, - .min_accel = -3500, - .inactive_accel = 3010, // VW sends one increment above the max range when inactive -}; - -const LongitudinalLimits VOLKSWAGEN_PQ_LONG_LIMITS_SPORT = { - .max_accel = 4000, - .min_accel = -3500, - .inactive_accel = 3010, // VW sends one increment above the max range when inactive -}; - -#define MSG_LENKHILFE_3 0x0D0 // RX from EPS, for steering angle and driver steering torque -#define MSG_HCA_1 0x0D2 // TX by OP, Heading Control Assist steering torque -#define MSG_BREMSE_1 0x1A0 // RX from ABS, for ego speed -#define MSG_MOTOR_2 0x288 // RX from ECU, for CC state and brake switch state -#define MSG_ACC_SYSTEM 0x368 // TX by OP, longitudinal acceleration controls -#define MSG_MOTOR_3 0x380 // RX from ECU, for driver throttle input -#define MSG_GRA_NEU 0x38A // TX by OP, ACC control buttons for cancel/resume -#define MSG_MOTOR_5 0x480 // RX from ECU, for ACC main switch state -#define MSG_ACC_GRA_ANZEIGE 0x56A // TX by OP, ACC HUD -#define MSG_LDW_1 0x5BE // TX by OP, Lane line recognition and text alerts - -// Transmit of GRA_Neu is allowed on bus 0 and 2 to keep compatibility with gateway and camera integration -const CanMsg VOLKSWAGEN_PQ_STOCK_TX_MSGS[] = {{MSG_HCA_1, 0, 5}, {MSG_LDW_1, 0, 8}, - {MSG_GRA_NEU, 0, 4}, {MSG_GRA_NEU, 2, 4}}; -const CanMsg VOLKSWAGEN_PQ_LONG_TX_MSGS[] = {{MSG_HCA_1, 0, 5}, {MSG_LDW_1, 0, 8}, - {MSG_ACC_SYSTEM, 0, 8}, {MSG_ACC_GRA_ANZEIGE, 0, 8}}; - -RxCheck volkswagen_pq_rx_checks[] = { - {.msg = {{MSG_LENKHILFE_3, 0, 6, .check_checksum = true, .max_counter = 15U, .frequency = 100U}, { 0 }, { 0 }}}, - {.msg = {{MSG_BREMSE_1, 0, 8, .check_checksum = false, .max_counter = 0U, .frequency = 100U}, { 0 }, { 0 }}}, - {.msg = {{MSG_MOTOR_2, 0, 8, .check_checksum = false, .max_counter = 0U, .frequency = 50U}, { 0 }, { 0 }}}, - {.msg = {{MSG_MOTOR_3, 0, 8, .check_checksum = false, .max_counter = 0U, .frequency = 100U}, { 0 }, { 0 }}}, - {.msg = {{MSG_MOTOR_5, 0, 8, .check_checksum = true, .max_counter = 0U, .frequency = 50U}, { 0 }, { 0 }}}, - {.msg = {{MSG_GRA_NEU, 0, 4, .check_checksum = true, .max_counter = 15U, .frequency = 30U}, { 0 }, { 0 }}}, -}; - -static uint32_t volkswagen_pq_get_checksum(const CANPacket_t *to_push) { - int addr = GET_ADDR(to_push); - - return (uint32_t)GET_BYTE(to_push, (addr == MSG_MOTOR_5) ? 7 : 0); -} - -static uint8_t volkswagen_pq_get_counter(const CANPacket_t *to_push) { - int addr = GET_ADDR(to_push); - uint8_t counter = 0U; - - if (addr == MSG_LENKHILFE_3) { - counter = (uint8_t)(GET_BYTE(to_push, 1) & 0xF0U) >> 4; - } else if (addr == MSG_GRA_NEU) { - counter = (uint8_t)(GET_BYTE(to_push, 2) & 0xF0U) >> 4; - } else { - } - - return counter; -} - -static uint32_t volkswagen_pq_compute_checksum(const CANPacket_t *to_push) { - int addr = GET_ADDR(to_push); - int len = GET_LEN(to_push); - uint8_t checksum = 0U; - int checksum_byte = (addr == MSG_MOTOR_5) ? 7 : 0; - - // Simple XOR over the payload, except for the byte where the checksum lives. - for (int i = 0; i < len; i++) { - if (i != checksum_byte) { - checksum ^= (uint8_t)GET_BYTE(to_push, i); - } - } - - return checksum; -} - -static safety_config volkswagen_pq_init(uint16_t param) { - UNUSED(param); - - volkswagen_set_button_prev = false; - volkswagen_resume_button_prev = false; - -#ifdef ALLOW_DEBUG - volkswagen_longitudinal = GET_FLAG(param, FLAG_VOLKSWAGEN_LONG_CONTROL); -#endif - return volkswagen_longitudinal ? BUILD_SAFETY_CFG(volkswagen_pq_rx_checks, VOLKSWAGEN_PQ_LONG_TX_MSGS) : \ - BUILD_SAFETY_CFG(volkswagen_pq_rx_checks, VOLKSWAGEN_PQ_STOCK_TX_MSGS); -} - -static void volkswagen_pq_rx_hook(const CANPacket_t *to_push) { - if (GET_BUS(to_push) == 0U) { - int addr = GET_ADDR(to_push); - - // Update in-motion state from speed value. - // Signal: Bremse_1.Geschwindigkeit_neu__Bremse_1_ - if (addr == MSG_BREMSE_1) { - int speed = ((GET_BYTE(to_push, 2) & 0xFEU) >> 1) | (GET_BYTE(to_push, 3) << 7); - vehicle_moving = speed > 0; - } - - // Update driver input torque samples - // Signal: Lenkhilfe_3.LH3_LM (absolute torque) - // Signal: Lenkhilfe_3.LH3_LMSign (direction) - if (addr == MSG_LENKHILFE_3) { - int torque_driver_new = GET_BYTE(to_push, 2) | ((GET_BYTE(to_push, 3) & 0x3U) << 8); - int sign = (GET_BYTE(to_push, 3) & 0x4U) >> 2; - if (sign == 1) { - torque_driver_new *= -1; - } - update_sample(&torque_driver, torque_driver_new); - } - - if (volkswagen_longitudinal) { - if (addr == MSG_MOTOR_5) { - // ACC main switch on is a prerequisite to enter controls, exit controls immediately on main switch off - // Signal: Motor_5.GRA_Hauptschalter - acc_main_on = GET_BIT(to_push, 50U); - if (!acc_main_on) { - controls_allowed = false; - } - } - - if (addr == MSG_GRA_NEU) { - // If ACC main switch is on, enter controls on falling edge of Set or Resume - // Signal: GRA_Neu.GRA_Neu_Setzen - // Signal: GRA_Neu.GRA_Neu_Recall - bool set_button = GET_BIT(to_push, 16U); - bool resume_button = GET_BIT(to_push, 17U); - if ((volkswagen_set_button_prev && !set_button) || (volkswagen_resume_button_prev && !resume_button)) { - controls_allowed = acc_main_on; - } - volkswagen_set_button_prev = set_button; - volkswagen_resume_button_prev = resume_button; - // Exit controls on rising edge of Cancel, override Set/Resume if present simultaneously - // Signal: GRA_ACC_01.GRA_Abbrechen - if (GET_BIT(to_push, 9U)) { - controls_allowed = false; - } - } - } else { - if (addr == MSG_MOTOR_2) { - // Enter controls on rising edge of stock ACC, exit controls if stock ACC disengages - // Signal: Motor_2.GRA_Status - int acc_status = (GET_BYTE(to_push, 2) & 0xC0U) >> 6; - bool cruise_engaged = (acc_status == 1) || (acc_status == 2); - pcm_cruise_check(cruise_engaged); - } - } - - // Signal: Motor_3.Fahrpedal_Rohsignal - if (addr == MSG_MOTOR_3) { - gas_pressed = (GET_BYTE(to_push, 2)); - } - - // Signal: Motor_2.Bremslichtschalter - if (addr == MSG_MOTOR_2) { - brake_pressed = (GET_BYTE(to_push, 2) & 0x1U); - } - - generic_rx_checks((addr == MSG_HCA_1)); - } -} - -static bool volkswagen_pq_tx_hook(const CANPacket_t *to_send) { - sport_mode = alternative_experience & ALT_EXP_RAISE_LONGITUDINAL_LIMITS_TO_ISO_MAX; - - int addr = GET_ADDR(to_send); - bool tx = true; - - // Safety check for HCA_1 Heading Control Assist torque - // Signal: HCA_1.LM_Offset (absolute torque) - // Signal: HCA_1.LM_Offsign (direction) - if (addr == MSG_HCA_1) { - int desired_torque = GET_BYTE(to_send, 2) | ((GET_BYTE(to_send, 3) & 0x7FU) << 8); - desired_torque = desired_torque / 32; // DBC scale from PQ network to centi-Nm - int sign = (GET_BYTE(to_send, 3) & 0x80U) >> 7; - if (sign == 1) { - desired_torque *= -1; - } - - uint32_t hca_status = ((GET_BYTE(to_send, 1) >> 4) & 0xFU); - bool steer_req = (hca_status == 5U); - - if (steer_torque_cmd_checks(desired_torque, steer_req, VOLKSWAGEN_PQ_STEERING_LIMITS)) { - tx = false; - } - } - - // Safety check for acceleration commands - // To avoid floating point math, scale upward and compare to pre-scaled safety m/s2 boundaries - if (addr == MSG_ACC_SYSTEM) { - // Signal: ACC_System.ACS_Sollbeschl (acceleration in m/s2, scale 0.005, offset -7.22) - int desired_accel = ((((GET_BYTE(to_send, 4) & 0x7U) << 8) | GET_BYTE(to_send, 3)) * 5U) - 7220U; - - if (sport_mode) { - if (longitudinal_accel_checks(desired_accel, VOLKSWAGEN_PQ_LONG_LIMITS_SPORT)) { - tx = false; - } - } else { - if (longitudinal_accel_checks(desired_accel, VOLKSWAGEN_PQ_LONG_LIMITS)) { - tx = false; - } - } - } - - // FORCE CANCEL: ensuring that only the cancel button press is sent when controls are off. - // This avoids unintended engagements while still allowing resume spam - if ((addr == MSG_GRA_NEU) && !controls_allowed) { - // Signal: GRA_Neu.GRA_Neu_Setzen - // Signal: GRA_Neu.GRA_Neu_Recall - if (GET_BIT(to_send, 16U) || GET_BIT(to_send, 17U)) { - tx = false; - } - } - - return tx; -} - -static int volkswagen_pq_fwd_hook(int bus_num, int addr) { - int bus_fwd = -1; - - switch (bus_num) { - case 0: - // Forward all traffic from the Extended CAN onward - bus_fwd = 2; - break; - case 2: - if ((addr == MSG_HCA_1) || (addr == MSG_LDW_1)) { - // openpilot takes over LKAS steering control and related HUD messages from the camera - bus_fwd = -1; - } else if (volkswagen_longitudinal && ((addr == MSG_ACC_SYSTEM) || (addr == MSG_ACC_GRA_ANZEIGE))) { - // openpilot takes over acceleration/braking control and related HUD messages from the stock ACC radar - } else { - // Forward all remaining traffic from Extended CAN devices to J533 gateway - bus_fwd = 0; - } - break; - default: - // No other buses should be in use; fallback to do-not-forward - bus_fwd = -1; - break; - } - - return bus_fwd; -} - -const safety_hooks volkswagen_pq_hooks = { - .init = volkswagen_pq_init, - .rx = volkswagen_pq_rx_hook, - .tx = volkswagen_pq_tx_hook, - .fwd = volkswagen_pq_fwd_hook, - .get_counter = volkswagen_pq_get_counter, - .get_checksum = volkswagen_pq_get_checksum, - .compute_checksum = volkswagen_pq_compute_checksum, -}; diff --git a/panda/board/safety_declarations.h b/panda/board/safety_declarations.h deleted file mode 100644 index 7c5ddb9..0000000 --- a/panda/board/safety_declarations.h +++ /dev/null @@ -1,276 +0,0 @@ -#pragma once - -#define GET_BIT(msg, b) ((bool)!!(((msg)->data[((b) / 8U)] >> ((b) % 8U)) & 0x1U)) -#define GET_BYTE(msg, b) ((msg)->data[(b)]) -#define GET_FLAG(value, mask) (((__typeof__(mask))(value) & (mask)) == (mask)) - -#define BUILD_SAFETY_CFG(rx, tx) ((safety_config){(rx), (sizeof((rx)) / sizeof((rx)[0])), \ - (tx), (sizeof((tx)) / sizeof((tx)[0]))}) -#define SET_RX_CHECKS(rx, config) ((config).rx_checks = (rx), \ - (config).rx_checks_len = sizeof((rx)) / sizeof((rx)[0])) -#define SET_TX_MSGS(tx, config) ((config).tx_msgs = (tx), \ - (config).tx_msgs_len = sizeof((tx)) / sizeof((tx)[0])) -#define UPDATE_VEHICLE_SPEED(val_ms) (update_sample(&vehicle_speed, ROUND((val_ms) * VEHICLE_SPEED_FACTOR))) - -uint32_t GET_BYTES(const CANPacket_t *msg, int start, int len) { - uint32_t ret = 0U; - for (int i = 0; i < len; i++) { - const uint32_t shift = i * 8; - ret |= (((uint32_t)msg->data[start + i]) << shift); - } - return ret; -} - -const int MAX_WRONG_COUNTERS = 5; -const uint8_t MAX_MISSED_MSGS = 10U; -#define MAX_ADDR_CHECK_MSGS 3U -#define MAX_SAMPLE_VALS 6 -// used to represent floating point vehicle speed in a sample_t -#define VEHICLE_SPEED_FACTOR 100.0 - - -// sample struct that keeps 6 samples in memory -struct sample_t { - int values[MAX_SAMPLE_VALS]; - int min; - int max; -} sample_t_default = {.values = {0}, .min = 0, .max = 0}; - -// safety code requires floats -struct lookup_t { - float x[3]; - float y[3]; -}; - -typedef struct { - int addr; - int bus; - int len; -} CanMsg; - -typedef enum { - TorqueMotorLimited, // torque steering command, limited by EPS output torque - TorqueDriverLimited, // torque steering command, limited by driver's input torque -} SteeringControlType; - -typedef struct { - // torque cmd limits - const int max_steer; - const int max_rate_up; - const int max_rate_down; - const int max_rt_delta; - const uint32_t max_rt_interval; - - const SteeringControlType type; - - // driver torque limits - const int driver_torque_allowance; - const int driver_torque_factor; - - // motor torque limits - const int max_torque_error; - - // safety around steer req bit - const int min_valid_request_frames; - const int max_invalid_request_frames; - const uint32_t min_valid_request_rt_interval; - const bool has_steer_req_tolerance; - - // angle cmd limits - const float angle_deg_to_can; - const struct lookup_t angle_rate_up_lookup; - const struct lookup_t angle_rate_down_lookup; - const int max_angle_error; // used to limit error between meas and cmd while enabled - const float angle_error_min_speed; // minimum speed to start limiting angle error - - const bool enforce_angle_error; // enables max_angle_error check - const bool inactive_angle_is_zero; // if false, enforces angle near meas when disabled (default) -} SteeringLimits; - -typedef struct { - // acceleration cmd limits - const int max_accel; - const int min_accel; - const int inactive_accel; - - // gas & brake cmd limits - // inactive and min gas are 0 on most safety modes - const int max_gas; - const int min_gas; - const int inactive_gas; - const int max_brake; - - // transmission rpm limits - const int max_transmission_rpm; - const int min_transmission_rpm; - const int inactive_transmission_rpm; - - // speed cmd limits - const int inactive_speed; -} LongitudinalLimits; - -typedef struct { - const int addr; - const int bus; - const int len; - const bool check_checksum; // true is checksum check is performed - const uint8_t max_counter; // maximum value of the counter. 0 means that the counter check is skipped - const bool quality_flag; // true is quality flag check is performed - const uint32_t frequency; // expected frequency of the message [Hz] -} CanMsgCheck; - -typedef struct { - // dynamic flags, reset on safety mode init - bool msg_seen; - int index; // if multiple messages are allowed to be checked, this stores the index of the first one seen. only msg[msg_index] will be used - bool valid_checksum; // true if and only if checksum check is passed - int wrong_counters; // counter of wrong counters, saturated between 0 and MAX_WRONG_COUNTERS - bool valid_quality_flag; // true if the message's quality/health/status signals are valid - uint8_t last_counter; // last counter value - uint32_t last_timestamp; // micro-s - bool lagging; // true if and only if the time between updates is excessive -} RxStatus; - -// params and flags about checksum, counter and frequency checks for each monitored address -typedef struct { - const CanMsgCheck msg[MAX_ADDR_CHECK_MSGS]; // check either messages (e.g. honda steer) - RxStatus status; -} RxCheck; - -typedef struct { - RxCheck *rx_checks; - int rx_checks_len; - const CanMsg *tx_msgs; - int tx_msgs_len; -} safety_config; - -typedef uint32_t (*get_checksum_t)(const CANPacket_t *to_push); -typedef uint32_t (*compute_checksum_t)(const CANPacket_t *to_push); -typedef uint8_t (*get_counter_t)(const CANPacket_t *to_push); -typedef bool (*get_quality_flag_valid_t)(const CANPacket_t *to_push); - -typedef safety_config (*safety_hook_init)(uint16_t param); -typedef void (*rx_hook)(const CANPacket_t *to_push); -typedef bool (*tx_hook)(const CANPacket_t *to_send); -typedef int (*fwd_hook)(int bus_num, int addr); - -typedef struct { - safety_hook_init init; - rx_hook rx; - tx_hook tx; - fwd_hook fwd; - get_checksum_t get_checksum; - compute_checksum_t compute_checksum; - get_counter_t get_counter; - get_quality_flag_valid_t get_quality_flag_valid; -} safety_hooks; - -bool safety_rx_hook(const CANPacket_t *to_push); -bool safety_tx_hook(CANPacket_t *to_send); -uint32_t get_ts_elapsed(uint32_t ts, uint32_t ts_last); -int to_signed(int d, int bits); -void update_sample(struct sample_t *sample, int sample_new); -void reset_sample(struct sample_t *sample); -bool max_limit_check(int val, const int MAX, const int MIN); -bool angle_dist_to_meas_check(int val, struct sample_t *val_meas, - const int MAX_ERROR, const int MAX_VAL); -bool dist_to_meas_check(int val, int val_last, struct sample_t *val_meas, - const int MAX_RATE_UP, const int MAX_RATE_DOWN, const int MAX_ERROR); -bool driver_limit_check(int val, int val_last, const struct sample_t *val_driver, - const int MAX, const int MAX_RATE_UP, const int MAX_RATE_DOWN, - const int MAX_ALLOWANCE, const int DRIVER_FACTOR); -bool get_longitudinal_allowed(void); -bool rt_rate_limit_check(int val, int val_last, const int MAX_RT_DELTA); -float interpolate(struct lookup_t xy, float x); -int ROUND(float val); -void gen_crc_lookup_table_8(uint8_t poly, uint8_t crc_lut[]); -void gen_crc_lookup_table_16(uint16_t poly, uint16_t crc_lut[]); -bool msg_allowed(const CANPacket_t *to_send, const CanMsg msg_list[], int len); -int get_addr_check_index(const CANPacket_t *to_push, RxCheck addr_list[], const int len); -void update_counter(RxCheck addr_list[], int index, uint8_t counter); -void update_addr_timestamp(RxCheck addr_list[], int index); -bool is_msg_valid(RxCheck addr_list[], int index); -bool rx_msg_safety_check(const CANPacket_t *to_push, - const safety_config *cfg, - const safety_hooks *safety_hooks); -void generic_rx_checks(bool stock_ecu_detected); -void relay_malfunction_set(void); -void relay_malfunction_reset(void); -bool steer_torque_cmd_checks(int desired_torque, int steer_req, const SteeringLimits limits); -bool steer_angle_cmd_checks(int desired_angle, bool steer_control_enabled, const SteeringLimits limits); -bool longitudinal_accel_checks(int desired_accel, const LongitudinalLimits limits); -bool longitudinal_speed_checks(int desired_speed, const LongitudinalLimits limits); -bool longitudinal_gas_checks(int desired_gas, const LongitudinalLimits limits); -bool longitudinal_transmission_rpm_checks(int desired_transmission_rpm, const LongitudinalLimits limits); -bool longitudinal_brake_checks(int desired_brake, const LongitudinalLimits limits); -bool longitudinal_interceptor_checks(const CANPacket_t *to_send); -void pcm_cruise_check(bool cruise_engaged); - -void safety_tick(const safety_config *safety_config); - -// This can be set by the safety hooks -bool controls_allowed = false; -bool relay_malfunction = false; -bool enable_gas_interceptor = false; -int gas_interceptor_prev = 0; -bool gas_pressed = false; -bool gas_pressed_prev = false; -bool brake_pressed = false; -bool brake_pressed_prev = false; -bool regen_braking = false; -bool regen_braking_prev = false; -bool cruise_engaged_prev = false; -bool sport_mode = false; -struct sample_t vehicle_speed; -bool vehicle_moving = false; -bool acc_main_on = false; // referred to as "ACC off" in ISO 15622:2018 -int cruise_button_prev = 0; -int cruise_main_prev = 0; -bool safety_rx_checks_invalid = false; - -// for safety modes with torque steering control -int desired_torque_last = 0; // last desired steer torque -int rt_torque_last = 0; // last desired torque for real time check -int valid_steer_req_count = 0; // counter for steer request bit matching non-zero torque -int invalid_steer_req_count = 0; // counter to allow multiple frames of mismatching torque request bit -struct sample_t torque_meas; // last 6 motor torques produced by the eps -struct sample_t torque_driver; // last 6 driver torques measured -uint32_t ts_torque_check_last = 0; -uint32_t ts_steer_req_mismatch_last = 0; // last timestamp steer req was mismatched with torque - -// state for controls_allowed timeout logic -bool heartbeat_engaged = false; // openpilot enabled, passed in heartbeat USB command -uint32_t heartbeat_engaged_mismatches = 0; // count of mismatches between heartbeat_engaged and controls_allowed - -// for safety modes with angle steering control -uint32_t ts_angle_last = 0; -int desired_angle_last = 0; -struct sample_t angle_meas; // last 6 steer angles/curvatures - -// This can be set with a USB command -// It enables features that allow alternative experiences, like not disengaging on gas press -// It is only either 0 or 1 on mainline comma.ai openpilot - -#define ALT_EXP_DISABLE_DISENGAGE_ON_GAS 1 - -// If using this flag, make sure to communicate to your users that a stock safety feature is now disabled. -#define ALT_EXP_DISABLE_STOCK_AEB 2 - -// If using this flag, be aware that harder braking is more likely to lead to rear endings, -// and that alone this flag doesn't make braking compliant because there's also a time element. -// Setting this flag is used for allowing the full -5.0 to +4.0 m/s^2 at lower speeds -// See ISO 15622:2018 for more information. -#define ALT_EXP_RAISE_LONGITUDINAL_LIMITS_TO_ISO_MAX 8 - -// This flag allows AEB to be commanded from openpilot. -#define ALT_EXP_ALLOW_AEB 16 - -int alternative_experience = 0; - -// time since safety mode has been changed -uint32_t safety_mode_cnt = 0U; -// allow 1s of transition timeout after relay changes state before assessing malfunctioning -const uint32_t RELAY_TRNS_TIMEOUT = 1U; - -// Always on Lateral -#define ALT_EXP_ALWAYS_ON_LATERAL 32 diff --git a/panda/board/stm32fx/board.h b/panda/board/stm32fx/board.h deleted file mode 100644 index 808f773..0000000 --- a/panda/board/stm32fx/board.h +++ /dev/null @@ -1,41 +0,0 @@ -// ///////////////////////////////////////////////////////////// // -// Hardware abstraction layer for all different supported boards // -// ///////////////////////////////////////////////////////////// // -#include "boards/board_declarations.h" -#include "boards/unused_funcs.h" - -// ///// Board definition and detection ///// // -#include "stm32fx/lladc.h" -#include "drivers/harness.h" -#include "drivers/fan.h" -#include "stm32fx/llfan.h" -#include "stm32fx/llrtc.h" -#include "drivers/rtc.h" -#include "drivers/clock_source.h" -#include "boards/white.h" -#include "boards/grey.h" -#include "boards/black.h" -#include "boards/uno.h" -#include "boards/dos.h" - -void detect_board_type(void) { - // SPI lines floating: white (TODO: is this reliable? Not really, we have to enable ESP/GPS to be able to detect this on the UART) - set_gpio_output(GPIOC, 14, 1); - set_gpio_output(GPIOC, 5, 1); - if(!detect_with_pull(GPIOB, 1, PULL_UP) && !detect_with_pull(GPIOB, 7, PULL_UP)){ - hw_type = HW_TYPE_DOS; - current_board = &board_dos; - } else if((detect_with_pull(GPIOA, 4, PULL_DOWN)) || (detect_with_pull(GPIOA, 5, PULL_DOWN)) || (detect_with_pull(GPIOA, 6, PULL_DOWN)) || (detect_with_pull(GPIOA, 7, PULL_DOWN))){ - hw_type = HW_TYPE_WHITE_PANDA; - current_board = &board_white; - } else if(detect_with_pull(GPIOA, 13, PULL_DOWN)) { // Rev AB deprecated, so no pullup means black. In REV C, A13 is pulled up to 5V with a 10K - hw_type = HW_TYPE_GREY_PANDA; - current_board = &board_grey; - } else if(!detect_with_pull(GPIOB, 15, PULL_UP)) { - hw_type = HW_TYPE_UNO; - current_board = &board_uno; - } else { - hw_type = HW_TYPE_BLACK_PANDA; - current_board = &board_black; - } -} diff --git a/panda/board/stm32fx/clock.h b/panda/board/stm32fx/clock.h deleted file mode 100644 index 19be574..0000000 --- a/panda/board/stm32fx/clock.h +++ /dev/null @@ -1,34 +0,0 @@ -void clock_init(void) { - // enable external oscillator - register_set_bits(&(RCC->CR), RCC_CR_HSEON); - while ((RCC->CR & RCC_CR_HSERDY) == 0); - - // divide things - // AHB = 96MHz - // APB1 = 48MHz - // APB2 = 48MHz - register_set(&(RCC->CFGR), RCC_CFGR_HPRE_DIV1 | RCC_CFGR_PPRE2_DIV2 | RCC_CFGR_PPRE1_DIV2, 0xFF7FFCF3U); - - // 16MHz crystal - // PLLM: 8 - // PLLN: 96 - // PLLP: 2 - // PLLQ: 4 - // P output: 96MHz - // Q output: 48MHz - register_set(&(RCC->PLLCFGR), RCC_PLLCFGR_PLLQ_2 | RCC_PLLCFGR_PLLM_3 | RCC_PLLCFGR_PLLN_6 | RCC_PLLCFGR_PLLN_5 | RCC_PLLCFGR_PLLSRC_HSE, 0x7F437FFFU); - - // start PLL - register_set_bits(&(RCC->CR), RCC_CR_PLLON); - while ((RCC->CR & RCC_CR_PLLRDY) == 0); - - // Configure Flash prefetch, Instruction cache, Data cache and wait state - // *** without this, it breaks *** - register_set(&(FLASH->ACR), FLASH_ACR_ICEN | FLASH_ACR_DCEN | FLASH_ACR_LATENCY_5WS, 0x1F0FU); - - // switch to PLL - register_set_bits(&(RCC->CFGR), RCC_CFGR_SW_PLL); - while ((RCC->CFGR & RCC_CFGR_SWS) != RCC_CFGR_SWS_PLL); - - // *** running on PLL *** -} diff --git a/panda/board/stm32fx/inc/cmsis_compiler.h b/panda/board/stm32fx/inc/cmsis_compiler.h deleted file mode 100644 index d0f39ee..0000000 --- a/panda/board/stm32fx/inc/cmsis_compiler.h +++ /dev/null @@ -1,284 +0,0 @@ -/**************************************************************************//** - * @file cmsis_compiler.h - * @brief CMSIS compiler generic header file - * @version V5.1.0 - * @date 09. October 2018 - ******************************************************************************/ -/* - * Copyright (c) 2009-2018 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#ifndef __CMSIS_COMPILER_H -#define __CMSIS_COMPILER_H - -#include - -/* - * Arm Compiler 4/5 - */ -#if defined ( __CC_ARM ) - #include "cmsis_armcc.h" - - -/* - * Arm Compiler 6.6 LTM (armclang) - */ -#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) && (__ARMCC_VERSION < 6100100) - #include "cmsis_armclang_ltm.h" - - /* - * Arm Compiler above 6.10.1 (armclang) - */ -#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6100100) - #include "cmsis_armclang.h" - - -/* - * GNU Compiler - */ -#elif defined ( __GNUC__ ) - #include "cmsis_gcc.h" - - -/* - * IAR Compiler - */ -#elif defined ( __ICCARM__ ) - #include - - -/* - * TI Arm Compiler - */ -#elif defined ( __TI_ARM__ ) - #include - - #ifndef __ASM - #define __ASM __asm - #endif - #ifndef __INLINE - #define __INLINE inline - #endif - #ifndef __STATIC_INLINE - #define __STATIC_INLINE static inline - #endif - #ifndef __STATIC_FORCEINLINE - #define __STATIC_FORCEINLINE __STATIC_INLINE - #endif - #ifndef __NO_RETURN - #define __NO_RETURN __attribute__((noreturn)) - #endif - #ifndef __USED - #define __USED __attribute__((used)) - #endif - #ifndef __WEAK - #define __WEAK __attribute__((weak)) - #endif - #ifndef __PACKED - #define __PACKED __attribute__((packed)) - #endif - #ifndef __PACKED_STRUCT - #define __PACKED_STRUCT struct __attribute__((packed)) - #endif - #ifndef __PACKED_UNION - #define __PACKED_UNION union __attribute__((packed)) - #endif - #ifndef __UNALIGNED_UINT32 /* deprecated */ - struct __attribute__((packed)) T_UINT32 { uint32_t v; }; - #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) - #endif - #ifndef __UNALIGNED_UINT16_WRITE - __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; - #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void*)(addr))->v) = (val)) - #endif - #ifndef __UNALIGNED_UINT16_READ - __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; - #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) - #endif - #ifndef __UNALIGNED_UINT32_WRITE - __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; - #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) - #endif - #ifndef __UNALIGNED_UINT32_READ - __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; - #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) - #endif - #ifndef __ALIGNED - #define __ALIGNED(x) __attribute__((aligned(x))) - #endif - #ifndef __RESTRICT - #define __RESTRICT __restrict - #endif - #ifndef __COMPILER_BARRIER - #warning No compiler specific solution for __COMPILER_BARRIER. __COMPILER_BARRIER is ignored. - #define __COMPILER_BARRIER() (void)0 - #endif - - -/* - * TASKING Compiler - */ -#elif defined ( __TASKING__ ) - /* - * The CMSIS functions have been implemented as intrinsics in the compiler. - * Please use "carm -?i" to get an up to date list of all intrinsics, - * Including the CMSIS ones. - */ - - #ifndef __ASM - #define __ASM __asm - #endif - #ifndef __INLINE - #define __INLINE inline - #endif - #ifndef __STATIC_INLINE - #define __STATIC_INLINE static inline - #endif - #ifndef __STATIC_FORCEINLINE - #define __STATIC_FORCEINLINE __STATIC_INLINE - #endif - #ifndef __NO_RETURN - #define __NO_RETURN __attribute__((noreturn)) - #endif - #ifndef __USED - #define __USED __attribute__((used)) - #endif - #ifndef __WEAK - #define __WEAK __attribute__((weak)) - #endif - #ifndef __PACKED - #define __PACKED __packed__ - #endif - #ifndef __PACKED_STRUCT - #define __PACKED_STRUCT struct __packed__ - #endif - #ifndef __PACKED_UNION - #define __PACKED_UNION union __packed__ - #endif - #ifndef __UNALIGNED_UINT32 /* deprecated */ - struct __packed__ T_UINT32 { uint32_t v; }; - #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) - #endif - #ifndef __UNALIGNED_UINT16_WRITE - __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; - #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val)) - #endif - #ifndef __UNALIGNED_UINT16_READ - __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; - #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) - #endif - #ifndef __UNALIGNED_UINT32_WRITE - __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; - #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) - #endif - #ifndef __UNALIGNED_UINT32_READ - __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; - #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) - #endif - #ifndef __ALIGNED - #define __ALIGNED(x) __align(x) - #endif - #ifndef __RESTRICT - #warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored. - #define __RESTRICT - #endif - #ifndef __COMPILER_BARRIER - #warning No compiler specific solution for __COMPILER_BARRIER. __COMPILER_BARRIER is ignored. - #define __COMPILER_BARRIER() (void)0 - #endif - - -/* - * COSMIC Compiler - */ -#elif defined ( __CSMC__ ) - #include - - #ifndef __ASM - #define __ASM _asm - #endif - #ifndef __INLINE - #define __INLINE inline - #endif - #ifndef __STATIC_INLINE - #define __STATIC_INLINE static inline - #endif - #ifndef __STATIC_FORCEINLINE - #define __STATIC_FORCEINLINE __STATIC_INLINE - #endif - #ifndef __NO_RETURN - // NO RETURN is automatically detected hence no warning here - #define __NO_RETURN - #endif - #ifndef __USED - #warning No compiler specific solution for __USED. __USED is ignored. - #define __USED - #endif - #ifndef __WEAK - #define __WEAK __weak - #endif - #ifndef __PACKED - #define __PACKED @packed - #endif - #ifndef __PACKED_STRUCT - #define __PACKED_STRUCT @packed struct - #endif - #ifndef __PACKED_UNION - #define __PACKED_UNION @packed union - #endif - #ifndef __UNALIGNED_UINT32 /* deprecated */ - @packed struct T_UINT32 { uint32_t v; }; - #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) - #endif - #ifndef __UNALIGNED_UINT16_WRITE - __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; - #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val)) - #endif - #ifndef __UNALIGNED_UINT16_READ - __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; - #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) - #endif - #ifndef __UNALIGNED_UINT32_WRITE - __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; - #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) - #endif - #ifndef __UNALIGNED_UINT32_READ - __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; - #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) - #endif - #ifndef __ALIGNED - #warning No compiler specific solution for __ALIGNED. __ALIGNED is ignored. - #define __ALIGNED(x) - #endif - #ifndef __RESTRICT - #warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored. - #define __RESTRICT - #endif - #ifndef __COMPILER_BARRIER - #warning No compiler specific solution for __COMPILER_BARRIER. __COMPILER_BARRIER is ignored. - #define __COMPILER_BARRIER() (void)0 - #endif - - -#else - #error Unknown compiler. -#endif - - -#endif /* __CMSIS_COMPILER_H */ - - diff --git a/panda/board/stm32fx/inc/cmsis_gcc.h b/panda/board/stm32fx/inc/cmsis_gcc.h deleted file mode 100644 index 2f68473..0000000 --- a/panda/board/stm32fx/inc/cmsis_gcc.h +++ /dev/null @@ -1,2169 +0,0 @@ -/**************************************************************************//** - * @file cmsis_gcc.h - * @brief CMSIS compiler GCC header file - * @version V5.2.0 - * @date 08. May 2019 - ******************************************************************************/ -/* - * Copyright (c) 2009-2019 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#ifndef __CMSIS_GCC_H -#define __CMSIS_GCC_H - -/* ignore some GCC warnings */ -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wsign-conversion" -#pragma GCC diagnostic ignored "-Wconversion" -#pragma GCC diagnostic ignored "-Wunused-parameter" - -/* Fallback for __has_builtin */ -#ifndef __has_builtin - #define __has_builtin(x) (0) -#endif - -/* CMSIS compiler specific defines */ -#ifndef __ASM - #define __ASM __asm -#endif -#ifndef __INLINE - #define __INLINE inline -#endif -#ifndef __STATIC_INLINE - #define __STATIC_INLINE static inline -#endif -#ifndef __STATIC_FORCEINLINE - #define __STATIC_FORCEINLINE __attribute__((always_inline)) static inline -#endif -#ifndef __NO_RETURN - #define __NO_RETURN __attribute__((__noreturn__)) -#endif -#ifndef __USED - #define __USED __attribute__((used)) -#endif -#ifndef __WEAK - #define __WEAK __attribute__((weak)) -#endif -#ifndef __PACKED - #define __PACKED __attribute__((packed, aligned(1))) -#endif -#ifndef __PACKED_STRUCT - #define __PACKED_STRUCT struct __attribute__((packed, aligned(1))) -#endif -#ifndef __PACKED_UNION - #define __PACKED_UNION union __attribute__((packed, aligned(1))) -#endif -#ifndef __UNALIGNED_UINT32 /* deprecated */ - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wpacked" - #pragma GCC diagnostic ignored "-Wattributes" - struct __attribute__((packed)) T_UINT32 { uint32_t v; }; - #pragma GCC diagnostic pop - #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) -#endif -#ifndef __UNALIGNED_UINT16_WRITE - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wpacked" - #pragma GCC diagnostic ignored "-Wattributes" - __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; - #pragma GCC diagnostic pop - #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val)) -#endif -#ifndef __UNALIGNED_UINT16_READ - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wpacked" - #pragma GCC diagnostic ignored "-Wattributes" - __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; - #pragma GCC diagnostic pop - #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) -#endif -#ifndef __UNALIGNED_UINT32_WRITE - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wpacked" - #pragma GCC diagnostic ignored "-Wattributes" - __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; - #pragma GCC diagnostic pop - #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) -#endif -#ifndef __UNALIGNED_UINT32_READ - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wpacked" - #pragma GCC diagnostic ignored "-Wattributes" - __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; - #pragma GCC diagnostic pop - #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) -#endif -#ifndef __ALIGNED - #define __ALIGNED(x) __attribute__((aligned(x))) -#endif -#ifndef __RESTRICT - #define __RESTRICT __restrict -#endif -#ifndef __COMPILER_BARRIER - #define __COMPILER_BARRIER() __ASM volatile("":::"memory") -#endif - -/* ######################### Startup and Lowlevel Init ######################## */ - -#ifndef __PROGRAM_START - -/** - \brief Initializes data and bss sections - \details This default implementations initialized all data and additional bss - sections relying on .copy.table and .zero.table specified properly - in the used linker script. - - */ -__STATIC_FORCEINLINE __NO_RETURN void __cmsis_start(void) -{ - extern void _start(void) __NO_RETURN; - - typedef struct { - uint32_t const* src; - uint32_t* dest; - uint32_t wlen; - } __copy_table_t; - - typedef struct { - uint32_t* dest; - uint32_t wlen; - } __zero_table_t; - - extern const __copy_table_t __copy_table_start__; - extern const __copy_table_t __copy_table_end__; - extern const __zero_table_t __zero_table_start__; - extern const __zero_table_t __zero_table_end__; - - for (__copy_table_t const* pTable = &__copy_table_start__; pTable < &__copy_table_end__; ++pTable) { - for(uint32_t i=0u; iwlen; ++i) { - pTable->dest[i] = pTable->src[i]; - } - } - - for (__zero_table_t const* pTable = &__zero_table_start__; pTable < &__zero_table_end__; ++pTable) { - for(uint32_t i=0u; iwlen; ++i) { - pTable->dest[i] = 0u; - } - } - - _start(); -} - -#define __PROGRAM_START __cmsis_start -#endif - -#ifndef __INITIAL_SP -#define __INITIAL_SP __StackTop -#endif - -#ifndef __STACK_LIMIT -#define __STACK_LIMIT __StackLimit -#endif - -#ifndef __VECTOR_TABLE -#define __VECTOR_TABLE __Vectors -#endif - -#ifndef __VECTOR_TABLE_ATTRIBUTE -#define __VECTOR_TABLE_ATTRIBUTE __attribute((used, section(".vectors"))) -#endif - -/* ########################### Core Function Access ########################### */ -/** \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions - @{ - */ - -/** - \brief Enable IRQ Interrupts - \details Enables IRQ interrupts by clearing the I-bit in the CPSR. - Can only be executed in Privileged modes. - */ -__STATIC_FORCEINLINE void __enable_irq(void) -{ - __ASM volatile ("cpsie i" : : : "memory"); -} - - -/** - \brief Disable IRQ Interrupts - \details Disables IRQ interrupts by setting the I-bit in the CPSR. - Can only be executed in Privileged modes. - */ -__STATIC_FORCEINLINE void __disable_irq(void) -{ - __ASM volatile ("cpsid i" : : : "memory"); -} - - -/** - \brief Get Control Register - \details Returns the content of the Control Register. - \return Control Register value - */ -__STATIC_FORCEINLINE uint32_t __get_CONTROL(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, control" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Control Register (non-secure) - \details Returns the content of the non-secure Control Register when in secure mode. - \return non-secure Control Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_CONTROL_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, control_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Control Register - \details Writes the given value to the Control Register. - \param [in] control Control Register value to set - */ -__STATIC_FORCEINLINE void __set_CONTROL(uint32_t control) -{ - __ASM volatile ("MSR control, %0" : : "r" (control) : "memory"); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Control Register (non-secure) - \details Writes the given value to the non-secure Control Register when in secure state. - \param [in] control Control Register value to set - */ -__STATIC_FORCEINLINE void __TZ_set_CONTROL_NS(uint32_t control) -{ - __ASM volatile ("MSR control_ns, %0" : : "r" (control) : "memory"); -} -#endif - - -/** - \brief Get IPSR Register - \details Returns the content of the IPSR Register. - \return IPSR Register value - */ -__STATIC_FORCEINLINE uint32_t __get_IPSR(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, ipsr" : "=r" (result) ); - return(result); -} - - -/** - \brief Get APSR Register - \details Returns the content of the APSR Register. - \return APSR Register value - */ -__STATIC_FORCEINLINE uint32_t __get_APSR(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, apsr" : "=r" (result) ); - return(result); -} - - -/** - \brief Get xPSR Register - \details Returns the content of the xPSR Register. - \return xPSR Register value - */ -__STATIC_FORCEINLINE uint32_t __get_xPSR(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, xpsr" : "=r" (result) ); - return(result); -} - - -/** - \brief Get Process Stack Pointer - \details Returns the current value of the Process Stack Pointer (PSP). - \return PSP Register value - */ -__STATIC_FORCEINLINE uint32_t __get_PSP(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, psp" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Process Stack Pointer (non-secure) - \details Returns the current value of the non-secure Process Stack Pointer (PSP) when in secure state. - \return PSP Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_PSP_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, psp_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Process Stack Pointer - \details Assigns the given value to the Process Stack Pointer (PSP). - \param [in] topOfProcStack Process Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __set_PSP(uint32_t topOfProcStack) -{ - __ASM volatile ("MSR psp, %0" : : "r" (topOfProcStack) : ); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Process Stack Pointer (non-secure) - \details Assigns the given value to the non-secure Process Stack Pointer (PSP) when in secure state. - \param [in] topOfProcStack Process Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __TZ_set_PSP_NS(uint32_t topOfProcStack) -{ - __ASM volatile ("MSR psp_ns, %0" : : "r" (topOfProcStack) : ); -} -#endif - - -/** - \brief Get Main Stack Pointer - \details Returns the current value of the Main Stack Pointer (MSP). - \return MSP Register value - */ -__STATIC_FORCEINLINE uint32_t __get_MSP(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, msp" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Main Stack Pointer (non-secure) - \details Returns the current value of the non-secure Main Stack Pointer (MSP) when in secure state. - \return MSP Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_MSP_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, msp_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Main Stack Pointer - \details Assigns the given value to the Main Stack Pointer (MSP). - \param [in] topOfMainStack Main Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __set_MSP(uint32_t topOfMainStack) -{ - __ASM volatile ("MSR msp, %0" : : "r" (topOfMainStack) : ); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Main Stack Pointer (non-secure) - \details Assigns the given value to the non-secure Main Stack Pointer (MSP) when in secure state. - \param [in] topOfMainStack Main Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __TZ_set_MSP_NS(uint32_t topOfMainStack) -{ - __ASM volatile ("MSR msp_ns, %0" : : "r" (topOfMainStack) : ); -} -#endif - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Stack Pointer (non-secure) - \details Returns the current value of the non-secure Stack Pointer (SP) when in secure state. - \return SP Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_SP_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, sp_ns" : "=r" (result) ); - return(result); -} - - -/** - \brief Set Stack Pointer (non-secure) - \details Assigns the given value to the non-secure Stack Pointer (SP) when in secure state. - \param [in] topOfStack Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __TZ_set_SP_NS(uint32_t topOfStack) -{ - __ASM volatile ("MSR sp_ns, %0" : : "r" (topOfStack) : ); -} -#endif - - -/** - \brief Get Priority Mask - \details Returns the current state of the priority mask bit from the Priority Mask Register. - \return Priority Mask value - */ -__STATIC_FORCEINLINE uint32_t __get_PRIMASK(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, primask" : "=r" (result) :: "memory"); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Priority Mask (non-secure) - \details Returns the current state of the non-secure priority mask bit from the Priority Mask Register when in secure state. - \return Priority Mask value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_PRIMASK_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, primask_ns" : "=r" (result) :: "memory"); - return(result); -} -#endif - - -/** - \brief Set Priority Mask - \details Assigns the given value to the Priority Mask Register. - \param [in] priMask Priority Mask - */ -__STATIC_FORCEINLINE void __set_PRIMASK(uint32_t priMask) -{ - __ASM volatile ("MSR primask, %0" : : "r" (priMask) : "memory"); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Priority Mask (non-secure) - \details Assigns the given value to the non-secure Priority Mask Register when in secure state. - \param [in] priMask Priority Mask - */ -__STATIC_FORCEINLINE void __TZ_set_PRIMASK_NS(uint32_t priMask) -{ - __ASM volatile ("MSR primask_ns, %0" : : "r" (priMask) : "memory"); -} -#endif - - -#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) -/** - \brief Enable FIQ - \details Enables FIQ interrupts by clearing the F-bit in the CPSR. - Can only be executed in Privileged modes. - */ -__STATIC_FORCEINLINE void __enable_fault_irq(void) -{ - __ASM volatile ("cpsie f" : : : "memory"); -} - - -/** - \brief Disable FIQ - \details Disables FIQ interrupts by setting the F-bit in the CPSR. - Can only be executed in Privileged modes. - */ -__STATIC_FORCEINLINE void __disable_fault_irq(void) -{ - __ASM volatile ("cpsid f" : : : "memory"); -} - - -/** - \brief Get Base Priority - \details Returns the current value of the Base Priority register. - \return Base Priority register value - */ -__STATIC_FORCEINLINE uint32_t __get_BASEPRI(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, basepri" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Base Priority (non-secure) - \details Returns the current value of the non-secure Base Priority register when in secure state. - \return Base Priority register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_BASEPRI_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, basepri_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Base Priority - \details Assigns the given value to the Base Priority register. - \param [in] basePri Base Priority value to set - */ -__STATIC_FORCEINLINE void __set_BASEPRI(uint32_t basePri) -{ - __ASM volatile ("MSR basepri, %0" : : "r" (basePri) : "memory"); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Base Priority (non-secure) - \details Assigns the given value to the non-secure Base Priority register when in secure state. - \param [in] basePri Base Priority value to set - */ -__STATIC_FORCEINLINE void __TZ_set_BASEPRI_NS(uint32_t basePri) -{ - __ASM volatile ("MSR basepri_ns, %0" : : "r" (basePri) : "memory"); -} -#endif - - -/** - \brief Set Base Priority with condition - \details Assigns the given value to the Base Priority register only if BASEPRI masking is disabled, - or the new value increases the BASEPRI priority level. - \param [in] basePri Base Priority value to set - */ -__STATIC_FORCEINLINE void __set_BASEPRI_MAX(uint32_t basePri) -{ - __ASM volatile ("MSR basepri_max, %0" : : "r" (basePri) : "memory"); -} - - -/** - \brief Get Fault Mask - \details Returns the current value of the Fault Mask register. - \return Fault Mask register value - */ -__STATIC_FORCEINLINE uint32_t __get_FAULTMASK(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, faultmask" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Fault Mask (non-secure) - \details Returns the current value of the non-secure Fault Mask register when in secure state. - \return Fault Mask register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_FAULTMASK_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, faultmask_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Fault Mask - \details Assigns the given value to the Fault Mask register. - \param [in] faultMask Fault Mask value to set - */ -__STATIC_FORCEINLINE void __set_FAULTMASK(uint32_t faultMask) -{ - __ASM volatile ("MSR faultmask, %0" : : "r" (faultMask) : "memory"); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Fault Mask (non-secure) - \details Assigns the given value to the non-secure Fault Mask register when in secure state. - \param [in] faultMask Fault Mask value to set - */ -__STATIC_FORCEINLINE void __TZ_set_FAULTMASK_NS(uint32_t faultMask) -{ - __ASM volatile ("MSR faultmask_ns, %0" : : "r" (faultMask) : "memory"); -} -#endif - -#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ - - -#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) - -/** - \brief Get Process Stack Pointer Limit - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence zero is returned always in non-secure - mode. - - \details Returns the current value of the Process Stack Pointer Limit (PSPLIM). - \return PSPLIM Register value - */ -__STATIC_FORCEINLINE uint32_t __get_PSPLIM(void) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - return 0U; -#else - uint32_t result; - __ASM volatile ("MRS %0, psplim" : "=r" (result) ); - return result; -#endif -} - -#if (defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Process Stack Pointer Limit (non-secure) - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence zero is returned always. - - \details Returns the current value of the non-secure Process Stack Pointer Limit (PSPLIM) when in secure state. - \return PSPLIM Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_PSPLIM_NS(void) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - return 0U; -#else - uint32_t result; - __ASM volatile ("MRS %0, psplim_ns" : "=r" (result) ); - return result; -#endif -} -#endif - - -/** - \brief Set Process Stack Pointer Limit - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence the write is silently ignored in non-secure - mode. - - \details Assigns the given value to the Process Stack Pointer Limit (PSPLIM). - \param [in] ProcStackPtrLimit Process Stack Pointer Limit value to set - */ -__STATIC_FORCEINLINE void __set_PSPLIM(uint32_t ProcStackPtrLimit) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - (void)ProcStackPtrLimit; -#else - __ASM volatile ("MSR psplim, %0" : : "r" (ProcStackPtrLimit)); -#endif -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Process Stack Pointer (non-secure) - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence the write is silently ignored. - - \details Assigns the given value to the non-secure Process Stack Pointer Limit (PSPLIM) when in secure state. - \param [in] ProcStackPtrLimit Process Stack Pointer Limit value to set - */ -__STATIC_FORCEINLINE void __TZ_set_PSPLIM_NS(uint32_t ProcStackPtrLimit) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - (void)ProcStackPtrLimit; -#else - __ASM volatile ("MSR psplim_ns, %0\n" : : "r" (ProcStackPtrLimit)); -#endif -} -#endif - - -/** - \brief Get Main Stack Pointer Limit - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence zero is returned always in non-secure - mode. - - \details Returns the current value of the Main Stack Pointer Limit (MSPLIM). - \return MSPLIM Register value - */ -__STATIC_FORCEINLINE uint32_t __get_MSPLIM(void) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - return 0U; -#else - uint32_t result; - __ASM volatile ("MRS %0, msplim" : "=r" (result) ); - return result; -#endif -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Main Stack Pointer Limit (non-secure) - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence zero is returned always. - - \details Returns the current value of the non-secure Main Stack Pointer Limit(MSPLIM) when in secure state. - \return MSPLIM Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_MSPLIM_NS(void) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - return 0U; -#else - uint32_t result; - __ASM volatile ("MRS %0, msplim_ns" : "=r" (result) ); - return result; -#endif -} -#endif - - -/** - \brief Set Main Stack Pointer Limit - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence the write is silently ignored in non-secure - mode. - - \details Assigns the given value to the Main Stack Pointer Limit (MSPLIM). - \param [in] MainStackPtrLimit Main Stack Pointer Limit value to set - */ -__STATIC_FORCEINLINE void __set_MSPLIM(uint32_t MainStackPtrLimit) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - (void)MainStackPtrLimit; -#else - __ASM volatile ("MSR msplim, %0" : : "r" (MainStackPtrLimit)); -#endif -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Main Stack Pointer Limit (non-secure) - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence the write is silently ignored. - - \details Assigns the given value to the non-secure Main Stack Pointer Limit (MSPLIM) when in secure state. - \param [in] MainStackPtrLimit Main Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __TZ_set_MSPLIM_NS(uint32_t MainStackPtrLimit) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - (void)MainStackPtrLimit; -#else - __ASM volatile ("MSR msplim_ns, %0" : : "r" (MainStackPtrLimit)); -#endif -} -#endif - -#endif /* ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ - - -/** - \brief Get FPSCR - \details Returns the current value of the Floating Point Status/Control register. - \return Floating Point Status/Control register value - */ -__STATIC_FORCEINLINE uint32_t __get_FPSCR(void) -{ -#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ - (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) -#if __has_builtin(__builtin_arm_get_fpscr) -// Re-enable using built-in when GCC has been fixed -// || (__GNUC__ > 7) || (__GNUC__ == 7 && __GNUC_MINOR__ >= 2) - /* see https://gcc.gnu.org/ml/gcc-patches/2017-04/msg00443.html */ - return __builtin_arm_get_fpscr(); -#else - uint32_t result; - - __ASM volatile ("VMRS %0, fpscr" : "=r" (result) ); - return(result); -#endif -#else - return(0U); -#endif -} - - -/** - \brief Set FPSCR - \details Assigns the given value to the Floating Point Status/Control register. - \param [in] fpscr Floating Point Status/Control value to set - */ -__STATIC_FORCEINLINE void __set_FPSCR(uint32_t fpscr) -{ -#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ - (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) -#if __has_builtin(__builtin_arm_set_fpscr) -// Re-enable using built-in when GCC has been fixed -// || (__GNUC__ > 7) || (__GNUC__ == 7 && __GNUC_MINOR__ >= 2) - /* see https://gcc.gnu.org/ml/gcc-patches/2017-04/msg00443.html */ - __builtin_arm_set_fpscr(fpscr); -#else - __ASM volatile ("VMSR fpscr, %0" : : "r" (fpscr) : "vfpcc", "memory"); -#endif -#else - (void)fpscr; -#endif -} - - -/*@} end of CMSIS_Core_RegAccFunctions */ - - -/* ########################## Core Instruction Access ######################### */ -/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface - Access to dedicated instructions - @{ -*/ - -/* Define macros for porting to both thumb1 and thumb2. - * For thumb1, use low register (r0-r7), specified by constraint "l" - * Otherwise, use general registers, specified by constraint "r" */ -#if defined (__thumb__) && !defined (__thumb2__) -#define __CMSIS_GCC_OUT_REG(r) "=l" (r) -#define __CMSIS_GCC_RW_REG(r) "+l" (r) -#define __CMSIS_GCC_USE_REG(r) "l" (r) -#else -#define __CMSIS_GCC_OUT_REG(r) "=r" (r) -#define __CMSIS_GCC_RW_REG(r) "+r" (r) -#define __CMSIS_GCC_USE_REG(r) "r" (r) -#endif - -/** - \brief No Operation - \details No Operation does nothing. This instruction can be used for code alignment purposes. - */ -#define __NOP() __ASM volatile ("nop") - -/** - \brief Wait For Interrupt - \details Wait For Interrupt is a hint instruction that suspends execution until one of a number of events occurs. - */ -#define __WFI() __ASM volatile ("wfi") - - -/** - \brief Wait For Event - \details Wait For Event is a hint instruction that permits the processor to enter - a low-power state until one of a number of events occurs. - */ -#define __WFE() __ASM volatile ("wfe") - - -/** - \brief Send Event - \details Send Event is a hint instruction. It causes an event to be signaled to the CPU. - */ -#define __SEV() __ASM volatile ("sev") - - -/** - \brief Instruction Synchronization Barrier - \details Instruction Synchronization Barrier flushes the pipeline in the processor, - so that all instructions following the ISB are fetched from cache or memory, - after the instruction has been completed. - */ -__STATIC_FORCEINLINE void __ISB(void) -{ - __ASM volatile ("isb 0xF":::"memory"); -} - - -/** - \brief Data Synchronization Barrier - \details Acts as a special kind of Data Memory Barrier. - It completes when all explicit memory accesses before this instruction complete. - */ -__STATIC_FORCEINLINE void __DSB(void) -{ - __ASM volatile ("dsb 0xF":::"memory"); -} - - -/** - \brief Data Memory Barrier - \details Ensures the apparent order of the explicit memory operations before - and after the instruction, without ensuring their completion. - */ -__STATIC_FORCEINLINE void __DMB(void) -{ - __ASM volatile ("dmb 0xF":::"memory"); -} - - -/** - \brief Reverse byte order (32 bit) - \details Reverses the byte order in unsigned integer value. For example, 0x12345678 becomes 0x78563412. - \param [in] value Value to reverse - \return Reversed value - */ -__STATIC_FORCEINLINE uint32_t __REV(uint32_t value) -{ -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 5) - return __builtin_bswap32(value); -#else - uint32_t result; - - __ASM volatile ("rev %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return result; -#endif -} - - -/** - \brief Reverse byte order (16 bit) - \details Reverses the byte order within each halfword of a word. For example, 0x12345678 becomes 0x34127856. - \param [in] value Value to reverse - \return Reversed value - */ -__STATIC_FORCEINLINE uint32_t __REV16(uint32_t value) -{ - uint32_t result; - - __ASM volatile ("rev16 %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return result; -} - - -/** - \brief Reverse byte order (16 bit) - \details Reverses the byte order in a 16-bit value and returns the signed 16-bit result. For example, 0x0080 becomes 0x8000. - \param [in] value Value to reverse - \return Reversed value - */ -__STATIC_FORCEINLINE int16_t __REVSH(int16_t value) -{ -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - return (int16_t)__builtin_bswap16(value); -#else - int16_t result; - - __ASM volatile ("revsh %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return result; -#endif -} - - -/** - \brief Rotate Right in unsigned value (32 bit) - \details Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits. - \param [in] op1 Value to rotate - \param [in] op2 Number of Bits to rotate - \return Rotated value - */ -__STATIC_FORCEINLINE uint32_t __ROR(uint32_t op1, uint32_t op2) -{ - op2 %= 32U; - if (op2 == 0U) - { - return op1; - } - return (op1 >> op2) | (op1 << (32U - op2)); -} - - -/** - \brief Breakpoint - \details Causes the processor to enter Debug state. - Debug tools can use this to investigate system state when the instruction at a particular address is reached. - \param [in] value is ignored by the processor. - If required, a debugger can use it to store additional information about the breakpoint. - */ -#define __BKPT(value) __ASM volatile ("bkpt "#value) - - -/** - \brief Reverse bit order of value - \details Reverses the bit order of the given value. - \param [in] value Value to reverse - \return Reversed value - */ -__STATIC_FORCEINLINE uint32_t __RBIT(uint32_t value) -{ - uint32_t result; - -#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) - __ASM volatile ("rbit %0, %1" : "=r" (result) : "r" (value) ); -#else - uint32_t s = (4U /*sizeof(v)*/ * 8U) - 1U; /* extra shift needed at end */ - - result = value; /* r will be reversed bits of v; first get LSB of v */ - for (value >>= 1U; value != 0U; value >>= 1U) - { - result <<= 1U; - result |= value & 1U; - s--; - } - result <<= s; /* shift when v's highest bits are zero */ -#endif - return result; -} - - -/** - \brief Count leading zeros - \details Counts the number of leading zeros of a data value. - \param [in] value Value to count the leading zeros - \return number of leading zeros in value - */ -__STATIC_FORCEINLINE uint8_t __CLZ(uint32_t value) -{ - /* Even though __builtin_clz produces a CLZ instruction on ARM, formally - __builtin_clz(0) is undefined behaviour, so handle this case specially. - This guarantees ARM-compatible results if happening to compile on a non-ARM - target, and ensures the compiler doesn't decide to activate any - optimisations using the logic "value was passed to __builtin_clz, so it - is non-zero". - ARM GCC 7.3 and possibly earlier will optimise this test away, leaving a - single CLZ instruction. - */ - if (value == 0U) - { - return 32U; - } - return __builtin_clz(value); -} - - -#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) -/** - \brief LDR Exclusive (8 bit) - \details Executes a exclusive LDR instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -__STATIC_FORCEINLINE uint8_t __LDREXB(volatile uint8_t *addr) -{ - uint32_t result; - -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - __ASM volatile ("ldrexb %0, %1" : "=r" (result) : "Q" (*addr) ); -#else - /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not - accepted by assembler. So has to use following less efficient pattern. - */ - __ASM volatile ("ldrexb %0, [%1]" : "=r" (result) : "r" (addr) : "memory" ); -#endif - return ((uint8_t) result); /* Add explicit type cast here */ -} - - -/** - \brief LDR Exclusive (16 bit) - \details Executes a exclusive LDR instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -__STATIC_FORCEINLINE uint16_t __LDREXH(volatile uint16_t *addr) -{ - uint32_t result; - -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - __ASM volatile ("ldrexh %0, %1" : "=r" (result) : "Q" (*addr) ); -#else - /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not - accepted by assembler. So has to use following less efficient pattern. - */ - __ASM volatile ("ldrexh %0, [%1]" : "=r" (result) : "r" (addr) : "memory" ); -#endif - return ((uint16_t) result); /* Add explicit type cast here */ -} - - -/** - \brief LDR Exclusive (32 bit) - \details Executes a exclusive LDR instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -__STATIC_FORCEINLINE uint32_t __LDREXW(volatile uint32_t *addr) -{ - uint32_t result; - - __ASM volatile ("ldrex %0, %1" : "=r" (result) : "Q" (*addr) ); - return(result); -} - - -/** - \brief STR Exclusive (8 bit) - \details Executes a exclusive STR instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__STATIC_FORCEINLINE uint32_t __STREXB(uint8_t value, volatile uint8_t *addr) -{ - uint32_t result; - - __ASM volatile ("strexb %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" ((uint32_t)value) ); - return(result); -} - - -/** - \brief STR Exclusive (16 bit) - \details Executes a exclusive STR instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__STATIC_FORCEINLINE uint32_t __STREXH(uint16_t value, volatile uint16_t *addr) -{ - uint32_t result; - - __ASM volatile ("strexh %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" ((uint32_t)value) ); - return(result); -} - - -/** - \brief STR Exclusive (32 bit) - \details Executes a exclusive STR instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__STATIC_FORCEINLINE uint32_t __STREXW(uint32_t value, volatile uint32_t *addr) -{ - uint32_t result; - - __ASM volatile ("strex %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" (value) ); - return(result); -} - - -/** - \brief Remove the exclusive lock - \details Removes the exclusive lock which is created by LDREX. - */ -__STATIC_FORCEINLINE void __CLREX(void) -{ - __ASM volatile ("clrex" ::: "memory"); -} - -#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ - - -#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) -/** - \brief Signed Saturate - \details Saturates a signed value. - \param [in] ARG1 Value to be saturated - \param [in] ARG2 Bit position to saturate to (1..32) - \return Saturated value - */ -#define __SSAT(ARG1,ARG2) \ -__extension__ \ -({ \ - int32_t __RES, __ARG1 = (ARG1); \ - __ASM ("ssat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) - - -/** - \brief Unsigned Saturate - \details Saturates an unsigned value. - \param [in] ARG1 Value to be saturated - \param [in] ARG2 Bit position to saturate to (0..31) - \return Saturated value - */ -#define __USAT(ARG1,ARG2) \ - __extension__ \ -({ \ - uint32_t __RES, __ARG1 = (ARG1); \ - __ASM ("usat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) - - -/** - \brief Rotate Right with Extend (32 bit) - \details Moves each bit of a bitstring right by one bit. - The carry input is shifted in at the left end of the bitstring. - \param [in] value Value to rotate - \return Rotated value - */ -__STATIC_FORCEINLINE uint32_t __RRX(uint32_t value) -{ - uint32_t result; - - __ASM volatile ("rrx %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return(result); -} - - -/** - \brief LDRT Unprivileged (8 bit) - \details Executes a Unprivileged LDRT instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -__STATIC_FORCEINLINE uint8_t __LDRBT(volatile uint8_t *ptr) -{ - uint32_t result; - -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - __ASM volatile ("ldrbt %0, %1" : "=r" (result) : "Q" (*ptr) ); -#else - /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not - accepted by assembler. So has to use following less efficient pattern. - */ - __ASM volatile ("ldrbt %0, [%1]" : "=r" (result) : "r" (ptr) : "memory" ); -#endif - return ((uint8_t) result); /* Add explicit type cast here */ -} - - -/** - \brief LDRT Unprivileged (16 bit) - \details Executes a Unprivileged LDRT instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -__STATIC_FORCEINLINE uint16_t __LDRHT(volatile uint16_t *ptr) -{ - uint32_t result; - -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - __ASM volatile ("ldrht %0, %1" : "=r" (result) : "Q" (*ptr) ); -#else - /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not - accepted by assembler. So has to use following less efficient pattern. - */ - __ASM volatile ("ldrht %0, [%1]" : "=r" (result) : "r" (ptr) : "memory" ); -#endif - return ((uint16_t) result); /* Add explicit type cast here */ -} - - -/** - \brief LDRT Unprivileged (32 bit) - \details Executes a Unprivileged LDRT instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -__STATIC_FORCEINLINE uint32_t __LDRT(volatile uint32_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldrt %0, %1" : "=r" (result) : "Q" (*ptr) ); - return(result); -} - - -/** - \brief STRT Unprivileged (8 bit) - \details Executes a Unprivileged STRT instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STRBT(uint8_t value, volatile uint8_t *ptr) -{ - __ASM volatile ("strbt %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief STRT Unprivileged (16 bit) - \details Executes a Unprivileged STRT instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STRHT(uint16_t value, volatile uint16_t *ptr) -{ - __ASM volatile ("strht %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief STRT Unprivileged (32 bit) - \details Executes a Unprivileged STRT instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STRT(uint32_t value, volatile uint32_t *ptr) -{ - __ASM volatile ("strt %1, %0" : "=Q" (*ptr) : "r" (value) ); -} - -#else /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ - -/** - \brief Signed Saturate - \details Saturates a signed value. - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (1..32) - \return Saturated value - */ -__STATIC_FORCEINLINE int32_t __SSAT(int32_t val, uint32_t sat) -{ - if ((sat >= 1U) && (sat <= 32U)) - { - const int32_t max = (int32_t)((1U << (sat - 1U)) - 1U); - const int32_t min = -1 - max ; - if (val > max) - { - return max; - } - else if (val < min) - { - return min; - } - } - return val; -} - -/** - \brief Unsigned Saturate - \details Saturates an unsigned value. - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (0..31) - \return Saturated value - */ -__STATIC_FORCEINLINE uint32_t __USAT(int32_t val, uint32_t sat) -{ - if (sat <= 31U) - { - const uint32_t max = ((1U << sat) - 1U); - if (val > (int32_t)max) - { - return max; - } - else if (val < 0) - { - return 0U; - } - } - return (uint32_t)val; -} - -#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ - - -#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) -/** - \brief Load-Acquire (8 bit) - \details Executes a LDAB instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -__STATIC_FORCEINLINE uint8_t __LDAB(volatile uint8_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldab %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint8_t) result); -} - - -/** - \brief Load-Acquire (16 bit) - \details Executes a LDAH instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -__STATIC_FORCEINLINE uint16_t __LDAH(volatile uint16_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldah %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint16_t) result); -} - - -/** - \brief Load-Acquire (32 bit) - \details Executes a LDA instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -__STATIC_FORCEINLINE uint32_t __LDA(volatile uint32_t *ptr) -{ - uint32_t result; - - __ASM volatile ("lda %0, %1" : "=r" (result) : "Q" (*ptr) ); - return(result); -} - - -/** - \brief Store-Release (8 bit) - \details Executes a STLB instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STLB(uint8_t value, volatile uint8_t *ptr) -{ - __ASM volatile ("stlb %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief Store-Release (16 bit) - \details Executes a STLH instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STLH(uint16_t value, volatile uint16_t *ptr) -{ - __ASM volatile ("stlh %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief Store-Release (32 bit) - \details Executes a STL instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STL(uint32_t value, volatile uint32_t *ptr) -{ - __ASM volatile ("stl %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief Load-Acquire Exclusive (8 bit) - \details Executes a LDAB exclusive instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -__STATIC_FORCEINLINE uint8_t __LDAEXB(volatile uint8_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldaexb %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint8_t) result); -} - - -/** - \brief Load-Acquire Exclusive (16 bit) - \details Executes a LDAH exclusive instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -__STATIC_FORCEINLINE uint16_t __LDAEXH(volatile uint16_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldaexh %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint16_t) result); -} - - -/** - \brief Load-Acquire Exclusive (32 bit) - \details Executes a LDA exclusive instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -__STATIC_FORCEINLINE uint32_t __LDAEX(volatile uint32_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldaex %0, %1" : "=r" (result) : "Q" (*ptr) ); - return(result); -} - - -/** - \brief Store-Release Exclusive (8 bit) - \details Executes a STLB exclusive instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__STATIC_FORCEINLINE uint32_t __STLEXB(uint8_t value, volatile uint8_t *ptr) -{ - uint32_t result; - - __ASM volatile ("stlexb %0, %2, %1" : "=&r" (result), "=Q" (*ptr) : "r" ((uint32_t)value) ); - return(result); -} - - -/** - \brief Store-Release Exclusive (16 bit) - \details Executes a STLH exclusive instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__STATIC_FORCEINLINE uint32_t __STLEXH(uint16_t value, volatile uint16_t *ptr) -{ - uint32_t result; - - __ASM volatile ("stlexh %0, %2, %1" : "=&r" (result), "=Q" (*ptr) : "r" ((uint32_t)value) ); - return(result); -} - - -/** - \brief Store-Release Exclusive (32 bit) - \details Executes a STL exclusive instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__STATIC_FORCEINLINE uint32_t __STLEX(uint32_t value, volatile uint32_t *ptr) -{ - uint32_t result; - - __ASM volatile ("stlex %0, %2, %1" : "=&r" (result), "=Q" (*ptr) : "r" ((uint32_t)value) ); - return(result); -} - -#endif /* ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ - -/*@}*/ /* end of group CMSIS_Core_InstructionInterface */ - - -/* ################### Compiler specific Intrinsics ########################### */ -/** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics - Access to dedicated SIMD instructions - @{ -*/ - -#if (defined (__ARM_FEATURE_DSP) && (__ARM_FEATURE_DSP == 1)) - -__STATIC_FORCEINLINE uint32_t __SADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - - -__STATIC_FORCEINLINE uint32_t __SSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("ssub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - - -__STATIC_FORCEINLINE uint32_t __SADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("ssub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("ssax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USAD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usad8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USADA8(uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("usada8 %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -#define __SSAT16(ARG1,ARG2) \ -({ \ - int32_t __RES, __ARG1 = (ARG1); \ - __ASM ("ssat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) - -#define __USAT16(ARG1,ARG2) \ -({ \ - uint32_t __RES, __ARG1 = (ARG1); \ - __ASM ("usat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) - -__STATIC_FORCEINLINE uint32_t __UXTB16(uint32_t op1) -{ - uint32_t result; - - __ASM volatile ("uxtb16 %0, %1" : "=r" (result) : "r" (op1)); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UXTAB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SXTB16(uint32_t op1) -{ - uint32_t result; - - __ASM volatile ("sxtb16 %0, %1" : "=r" (result) : "r" (op1)); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SXTAB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMUAD (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smuad %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMUADX (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smuadx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMLAD (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smlad %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMLADX (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smladx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__STATIC_FORCEINLINE uint64_t __SMLALD (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__STATIC_FORCEINLINE uint64_t __SMLALDX (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__STATIC_FORCEINLINE uint32_t __SMUSD (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smusd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMUSDX (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smusdx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMLSD (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smlsd %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMLSDX (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smlsdx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__STATIC_FORCEINLINE uint64_t __SMLSLD (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__STATIC_FORCEINLINE uint64_t __SMLSLDX (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__STATIC_FORCEINLINE uint32_t __SEL (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sel %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE int32_t __QADD( int32_t op1, int32_t op2) -{ - int32_t result; - - __ASM volatile ("qadd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE int32_t __QSUB( int32_t op1, int32_t op2) -{ - int32_t result; - - __ASM volatile ("qsub %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -#if 0 -#define __PKHBT(ARG1,ARG2,ARG3) \ -({ \ - uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \ - __ASM ("pkhbt %0, %1, %2, lsl %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \ - __RES; \ - }) - -#define __PKHTB(ARG1,ARG2,ARG3) \ -({ \ - uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \ - if (ARG3 == 0) \ - __ASM ("pkhtb %0, %1, %2" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2) ); \ - else \ - __ASM ("pkhtb %0, %1, %2, asr %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \ - __RES; \ - }) -#endif - -#define __PKHBT(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0x0000FFFFUL) | \ - ((((uint32_t)(ARG2)) << (ARG3)) & 0xFFFF0000UL) ) - -#define __PKHTB(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0xFFFF0000UL) | \ - ((((uint32_t)(ARG2)) >> (ARG3)) & 0x0000FFFFUL) ) - -__STATIC_FORCEINLINE int32_t __SMMLA (int32_t op1, int32_t op2, int32_t op3) -{ - int32_t result; - - __ASM volatile ("smmla %0, %1, %2, %3" : "=r" (result): "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -#endif /* (__ARM_FEATURE_DSP == 1) */ -/*@} end of group CMSIS_SIMD_intrinsics */ - - -#pragma GCC diagnostic pop - -#endif /* __CMSIS_GCC_H */ - diff --git a/panda/board/stm32fx/inc/cmsis_version.h b/panda/board/stm32fx/inc/cmsis_version.h deleted file mode 100644 index bf57cf3..0000000 --- a/panda/board/stm32fx/inc/cmsis_version.h +++ /dev/null @@ -1,40 +0,0 @@ -/**************************************************************************//** - * @file cmsis_version.h - * @brief CMSIS Core(M) Version definitions - * @version V5.0.3 - * @date 24. June 2019 - ******************************************************************************/ -/* - * Copyright (c) 2009-2019 ARM Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef __CMSIS_VERSION_H -#define __CMSIS_VERSION_H - -/* CMSIS Version definitions */ -#define __CM_CMSIS_VERSION_MAIN ( 5U) /*!< [31:16] CMSIS Core(M) main version */ -#define __CM_CMSIS_VERSION_SUB ( 3U) /*!< [15:0] CMSIS Core(M) sub version */ -#define __CM_CMSIS_VERSION ((__CM_CMSIS_VERSION_MAIN << 16U) | \ - __CM_CMSIS_VERSION_SUB ) /*!< CMSIS Core(M) version number */ -#endif - diff --git a/panda/board/stm32fx/inc/core_cm3.h b/panda/board/stm32fx/inc/core_cm3.h deleted file mode 100644 index 0918c5e..0000000 --- a/panda/board/stm32fx/inc/core_cm3.h +++ /dev/null @@ -1,1938 +0,0 @@ -/**************************************************************************//** - * @file core_cm3.h - * @brief CMSIS Cortex-M3 Core Peripheral Access Layer Header File - * @version V5.1.0 - * @date 13. March 2019 - ******************************************************************************/ -/* - * Copyright (c) 2009-2019 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef __CORE_CM3_H_GENERIC -#define __CORE_CM3_H_GENERIC - -#include - -#ifdef __cplusplus - extern "C" { -#endif - -/** - \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions - CMSIS violates the following MISRA-C:2004 rules: - - \li Required Rule 8.5, object/function definition in header file.
- Function definitions in header files are used to allow 'inlining'. - - \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
- Unions are used for effective representation of core registers. - - \li Advisory Rule 19.7, Function-like macro defined.
- Function-like macros are used to allow more efficient code. - */ - - -/******************************************************************************* - * CMSIS definitions - ******************************************************************************/ -/** - \ingroup Cortex_M3 - @{ - */ - -#include "cmsis_version.h" - -/* CMSIS CM3 definitions */ -#define __CM3_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */ -#define __CM3_CMSIS_VERSION_SUB (__CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */ -#define __CM3_CMSIS_VERSION ((__CM3_CMSIS_VERSION_MAIN << 16U) | \ - __CM3_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */ - -#define __CORTEX_M (3U) /*!< Cortex-M Core */ - -/** __FPU_USED indicates whether an FPU is used or not. - This core does not support an FPU at all -*/ -#define __FPU_USED 0U - -#if defined ( __CC_ARM ) - #if defined __TARGET_FPU_VFP - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #if defined __ARM_FP - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __GNUC__ ) - #if defined (__VFP_FP__) && !defined(__SOFTFP__) - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __ICCARM__ ) - #if defined __ARMVFP__ - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __TI_ARM__ ) - #if defined __TI_VFP_SUPPORT__ - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __TASKING__ ) - #if defined __FPU_VFP__ - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#elif defined ( __CSMC__ ) - #if ( __CSMC__ & 0x400U) - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #endif - -#endif - -#include "cmsis_compiler.h" /* CMSIS compiler specific defines */ - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_CM3_H_GENERIC */ - -#ifndef __CMSIS_GENERIC - -#ifndef __CORE_CM3_H_DEPENDANT -#define __CORE_CM3_H_DEPENDANT - -#ifdef __cplusplus - extern "C" { -#endif - -/* check device defines and use defaults */ -#if defined __CHECK_DEVICE_DEFINES - #ifndef __CM3_REV - #define __CM3_REV 0x0200U - #warning "__CM3_REV not defined in device header file; using default!" - #endif - - #ifndef __MPU_PRESENT - #define __MPU_PRESENT 0U - #warning "__MPU_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __NVIC_PRIO_BITS - #define __NVIC_PRIO_BITS 3U - #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" - #endif - - #ifndef __Vendor_SysTickConfig - #define __Vendor_SysTickConfig 0U - #warning "__Vendor_SysTickConfig not defined in device header file; using default!" - #endif -#endif - -/* IO definitions (access restrictions to peripheral registers) */ -/** - \defgroup CMSIS_glob_defs CMSIS Global Defines - - IO Type Qualifiers are used - \li to specify the access to peripheral variables. - \li for automatic generation of peripheral register debug information. -*/ -#ifdef __cplusplus - #define __I volatile /*!< Defines 'read only' permissions */ -#else - #define __I volatile const /*!< Defines 'read only' permissions */ -#endif -#define __O volatile /*!< Defines 'write only' permissions */ -#define __IO volatile /*!< Defines 'read / write' permissions */ - -/* following defines should be used for structure members */ -#define __IM volatile const /*! Defines 'read only' structure member permissions */ -#define __OM volatile /*! Defines 'write only' structure member permissions */ -#define __IOM volatile /*! Defines 'read / write' structure member permissions */ - -/*@} end of group Cortex_M3 */ - - - -/******************************************************************************* - * Register Abstraction - Core Register contain: - - Core Register - - Core NVIC Register - - Core SCB Register - - Core SysTick Register - - Core Debug Register - - Core MPU Register - ******************************************************************************/ -/** - \defgroup CMSIS_core_register Defines and Type Definitions - \brief Type definitions and defines for Cortex-M processor based devices. -*/ - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CORE Status and Control Registers - \brief Core Register type definitions. - @{ - */ - -/** - \brief Union type to access the Application Program Status Register (APSR). - */ -typedef union -{ - struct - { - uint32_t _reserved0:27; /*!< bit: 0..26 Reserved */ - uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} APSR_Type; - -/* APSR Register Definitions */ -#define APSR_N_Pos 31U /*!< APSR: N Position */ -#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ - -#define APSR_Z_Pos 30U /*!< APSR: Z Position */ -#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ - -#define APSR_C_Pos 29U /*!< APSR: C Position */ -#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ - -#define APSR_V_Pos 28U /*!< APSR: V Position */ -#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ - -#define APSR_Q_Pos 27U /*!< APSR: Q Position */ -#define APSR_Q_Msk (1UL << APSR_Q_Pos) /*!< APSR: Q Mask */ - - -/** - \brief Union type to access the Interrupt Program Status Register (IPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} IPSR_Type; - -/* IPSR Register Definitions */ -#define IPSR_ISR_Pos 0U /*!< IPSR: ISR Position */ -#define IPSR_ISR_Msk (0x1FFUL /*<< IPSR_ISR_Pos*/) /*!< IPSR: ISR Mask */ - - -/** - \brief Union type to access the Special-Purpose Program Status Registers (xPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:1; /*!< bit: 9 Reserved */ - uint32_t ICI_IT_1:6; /*!< bit: 10..15 ICI/IT part 1 */ - uint32_t _reserved1:8; /*!< bit: 16..23 Reserved */ - uint32_t T:1; /*!< bit: 24 Thumb bit */ - uint32_t ICI_IT_2:2; /*!< bit: 25..26 ICI/IT part 2 */ - uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} xPSR_Type; - -/* xPSR Register Definitions */ -#define xPSR_N_Pos 31U /*!< xPSR: N Position */ -#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ - -#define xPSR_Z_Pos 30U /*!< xPSR: Z Position */ -#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ - -#define xPSR_C_Pos 29U /*!< xPSR: C Position */ -#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ - -#define xPSR_V_Pos 28U /*!< xPSR: V Position */ -#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ - -#define xPSR_Q_Pos 27U /*!< xPSR: Q Position */ -#define xPSR_Q_Msk (1UL << xPSR_Q_Pos) /*!< xPSR: Q Mask */ - -#define xPSR_ICI_IT_2_Pos 25U /*!< xPSR: ICI/IT part 2 Position */ -#define xPSR_ICI_IT_2_Msk (3UL << xPSR_ICI_IT_2_Pos) /*!< xPSR: ICI/IT part 2 Mask */ - -#define xPSR_T_Pos 24U /*!< xPSR: T Position */ -#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ - -#define xPSR_ICI_IT_1_Pos 10U /*!< xPSR: ICI/IT part 1 Position */ -#define xPSR_ICI_IT_1_Msk (0x3FUL << xPSR_ICI_IT_1_Pos) /*!< xPSR: ICI/IT part 1 Mask */ - -#define xPSR_ISR_Pos 0U /*!< xPSR: ISR Position */ -#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ - - -/** - \brief Union type to access the Control Registers (CONTROL). - */ -typedef union -{ - struct - { - uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ - uint32_t SPSEL:1; /*!< bit: 1 Stack to be used */ - uint32_t _reserved1:30; /*!< bit: 2..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} CONTROL_Type; - -/* CONTROL Register Definitions */ -#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */ -#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ - -#define CONTROL_nPRIV_Pos 0U /*!< CONTROL: nPRIV Position */ -#define CONTROL_nPRIV_Msk (1UL /*<< CONTROL_nPRIV_Pos*/) /*!< CONTROL: nPRIV Mask */ - -/*@} end of group CMSIS_CORE */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC) - \brief Type definitions for the NVIC Registers - @{ - */ - -/** - \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). - */ -typedef struct -{ - __IOM uint32_t ISER[8U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ - uint32_t RESERVED0[24U]; - __IOM uint32_t ICER[8U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ - uint32_t RESERVED1[24U]; - __IOM uint32_t ISPR[8U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ - uint32_t RESERVED2[24U]; - __IOM uint32_t ICPR[8U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ - uint32_t RESERVED3[24U]; - __IOM uint32_t IABR[8U]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */ - uint32_t RESERVED4[56U]; - __IOM uint8_t IP[240U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register (8Bit wide) */ - uint32_t RESERVED5[644U]; - __OM uint32_t STIR; /*!< Offset: 0xE00 ( /W) Software Trigger Interrupt Register */ -} NVIC_Type; - -/* Software Triggered Interrupt Register Definitions */ -#define NVIC_STIR_INTID_Pos 0U /*!< STIR: INTLINESNUM Position */ -#define NVIC_STIR_INTID_Msk (0x1FFUL /*<< NVIC_STIR_INTID_Pos*/) /*!< STIR: INTLINESNUM Mask */ - -/*@} end of group CMSIS_NVIC */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SCB System Control Block (SCB) - \brief Type definitions for the System Control Block Registers - @{ - */ - -/** - \brief Structure type to access the System Control Block (SCB). - */ -typedef struct -{ - __IM uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ - __IOM uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ - __IOM uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ - __IOM uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ - __IOM uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ - __IOM uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ - __IOM uint8_t SHP[12U]; /*!< Offset: 0x018 (R/W) System Handlers Priority Registers (4-7, 8-11, 12-15) */ - __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ - __IOM uint32_t CFSR; /*!< Offset: 0x028 (R/W) Configurable Fault Status Register */ - __IOM uint32_t HFSR; /*!< Offset: 0x02C (R/W) HardFault Status Register */ - __IOM uint32_t DFSR; /*!< Offset: 0x030 (R/W) Debug Fault Status Register */ - __IOM uint32_t MMFAR; /*!< Offset: 0x034 (R/W) MemManage Fault Address Register */ - __IOM uint32_t BFAR; /*!< Offset: 0x038 (R/W) BusFault Address Register */ - __IOM uint32_t AFSR; /*!< Offset: 0x03C (R/W) Auxiliary Fault Status Register */ - __IM uint32_t PFR[2U]; /*!< Offset: 0x040 (R/ ) Processor Feature Register */ - __IM uint32_t DFR; /*!< Offset: 0x048 (R/ ) Debug Feature Register */ - __IM uint32_t ADR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */ - __IM uint32_t MMFR[4U]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */ - __IM uint32_t ISAR[5U]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */ - uint32_t RESERVED0[5U]; - __IOM uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control Register */ -} SCB_Type; - -/* SCB CPUID Register Definitions */ -#define SCB_CPUID_IMPLEMENTER_Pos 24U /*!< SCB CPUID: IMPLEMENTER Position */ -#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ - -#define SCB_CPUID_VARIANT_Pos 20U /*!< SCB CPUID: VARIANT Position */ -#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ - -#define SCB_CPUID_ARCHITECTURE_Pos 16U /*!< SCB CPUID: ARCHITECTURE Position */ -#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ - -#define SCB_CPUID_PARTNO_Pos 4U /*!< SCB CPUID: PARTNO Position */ -#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ - -#define SCB_CPUID_REVISION_Pos 0U /*!< SCB CPUID: REVISION Position */ -#define SCB_CPUID_REVISION_Msk (0xFUL /*<< SCB_CPUID_REVISION_Pos*/) /*!< SCB CPUID: REVISION Mask */ - -/* SCB Interrupt Control State Register Definitions */ -#define SCB_ICSR_NMIPENDSET_Pos 31U /*!< SCB ICSR: NMIPENDSET Position */ -#define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */ - -#define SCB_ICSR_PENDSVSET_Pos 28U /*!< SCB ICSR: PENDSVSET Position */ -#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ - -#define SCB_ICSR_PENDSVCLR_Pos 27U /*!< SCB ICSR: PENDSVCLR Position */ -#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ - -#define SCB_ICSR_PENDSTSET_Pos 26U /*!< SCB ICSR: PENDSTSET Position */ -#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ - -#define SCB_ICSR_PENDSTCLR_Pos 25U /*!< SCB ICSR: PENDSTCLR Position */ -#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ - -#define SCB_ICSR_ISRPREEMPT_Pos 23U /*!< SCB ICSR: ISRPREEMPT Position */ -#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ - -#define SCB_ICSR_ISRPENDING_Pos 22U /*!< SCB ICSR: ISRPENDING Position */ -#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ - -#define SCB_ICSR_VECTPENDING_Pos 12U /*!< SCB ICSR: VECTPENDING Position */ -#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ - -#define SCB_ICSR_RETTOBASE_Pos 11U /*!< SCB ICSR: RETTOBASE Position */ -#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */ - -#define SCB_ICSR_VECTACTIVE_Pos 0U /*!< SCB ICSR: VECTACTIVE Position */ -#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ - -/* SCB Vector Table Offset Register Definitions */ -#if defined (__CM3_REV) && (__CM3_REV < 0x0201U) /* core r2p1 */ -#define SCB_VTOR_TBLBASE_Pos 29U /*!< SCB VTOR: TBLBASE Position */ -#define SCB_VTOR_TBLBASE_Msk (1UL << SCB_VTOR_TBLBASE_Pos) /*!< SCB VTOR: TBLBASE Mask */ - -#define SCB_VTOR_TBLOFF_Pos 7U /*!< SCB VTOR: TBLOFF Position */ -#define SCB_VTOR_TBLOFF_Msk (0x3FFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ -#else -#define SCB_VTOR_TBLOFF_Pos 7U /*!< SCB VTOR: TBLOFF Position */ -#define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ -#endif - -/* SCB Application Interrupt and Reset Control Register Definitions */ -#define SCB_AIRCR_VECTKEY_Pos 16U /*!< SCB AIRCR: VECTKEY Position */ -#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ - -#define SCB_AIRCR_VECTKEYSTAT_Pos 16U /*!< SCB AIRCR: VECTKEYSTAT Position */ -#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ - -#define SCB_AIRCR_ENDIANESS_Pos 15U /*!< SCB AIRCR: ENDIANESS Position */ -#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ - -#define SCB_AIRCR_PRIGROUP_Pos 8U /*!< SCB AIRCR: PRIGROUP Position */ -#define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */ - -#define SCB_AIRCR_SYSRESETREQ_Pos 2U /*!< SCB AIRCR: SYSRESETREQ Position */ -#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ - -#define SCB_AIRCR_VECTCLRACTIVE_Pos 1U /*!< SCB AIRCR: VECTCLRACTIVE Position */ -#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ - -#define SCB_AIRCR_VECTRESET_Pos 0U /*!< SCB AIRCR: VECTRESET Position */ -#define SCB_AIRCR_VECTRESET_Msk (1UL /*<< SCB_AIRCR_VECTRESET_Pos*/) /*!< SCB AIRCR: VECTRESET Mask */ - -/* SCB System Control Register Definitions */ -#define SCB_SCR_SEVONPEND_Pos 4U /*!< SCB SCR: SEVONPEND Position */ -#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ - -#define SCB_SCR_SLEEPDEEP_Pos 2U /*!< SCB SCR: SLEEPDEEP Position */ -#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ - -#define SCB_SCR_SLEEPONEXIT_Pos 1U /*!< SCB SCR: SLEEPONEXIT Position */ -#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ - -/* SCB Configuration Control Register Definitions */ -#define SCB_CCR_STKALIGN_Pos 9U /*!< SCB CCR: STKALIGN Position */ -#define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */ - -#define SCB_CCR_BFHFNMIGN_Pos 8U /*!< SCB CCR: BFHFNMIGN Position */ -#define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */ - -#define SCB_CCR_DIV_0_TRP_Pos 4U /*!< SCB CCR: DIV_0_TRP Position */ -#define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */ - -#define SCB_CCR_UNALIGN_TRP_Pos 3U /*!< SCB CCR: UNALIGN_TRP Position */ -#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ - -#define SCB_CCR_USERSETMPEND_Pos 1U /*!< SCB CCR: USERSETMPEND Position */ -#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */ - -#define SCB_CCR_NONBASETHRDENA_Pos 0U /*!< SCB CCR: NONBASETHRDENA Position */ -#define SCB_CCR_NONBASETHRDENA_Msk (1UL /*<< SCB_CCR_NONBASETHRDENA_Pos*/) /*!< SCB CCR: NONBASETHRDENA Mask */ - -/* SCB System Handler Control and State Register Definitions */ -#define SCB_SHCSR_USGFAULTENA_Pos 18U /*!< SCB SHCSR: USGFAULTENA Position */ -#define SCB_SHCSR_USGFAULTENA_Msk (1UL << SCB_SHCSR_USGFAULTENA_Pos) /*!< SCB SHCSR: USGFAULTENA Mask */ - -#define SCB_SHCSR_BUSFAULTENA_Pos 17U /*!< SCB SHCSR: BUSFAULTENA Position */ -#define SCB_SHCSR_BUSFAULTENA_Msk (1UL << SCB_SHCSR_BUSFAULTENA_Pos) /*!< SCB SHCSR: BUSFAULTENA Mask */ - -#define SCB_SHCSR_MEMFAULTENA_Pos 16U /*!< SCB SHCSR: MEMFAULTENA Position */ -#define SCB_SHCSR_MEMFAULTENA_Msk (1UL << SCB_SHCSR_MEMFAULTENA_Pos) /*!< SCB SHCSR: MEMFAULTENA Mask */ - -#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */ -#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ - -#define SCB_SHCSR_BUSFAULTPENDED_Pos 14U /*!< SCB SHCSR: BUSFAULTPENDED Position */ -#define SCB_SHCSR_BUSFAULTPENDED_Msk (1UL << SCB_SHCSR_BUSFAULTPENDED_Pos) /*!< SCB SHCSR: BUSFAULTPENDED Mask */ - -#define SCB_SHCSR_MEMFAULTPENDED_Pos 13U /*!< SCB SHCSR: MEMFAULTPENDED Position */ -#define SCB_SHCSR_MEMFAULTPENDED_Msk (1UL << SCB_SHCSR_MEMFAULTPENDED_Pos) /*!< SCB SHCSR: MEMFAULTPENDED Mask */ - -#define SCB_SHCSR_USGFAULTPENDED_Pos 12U /*!< SCB SHCSR: USGFAULTPENDED Position */ -#define SCB_SHCSR_USGFAULTPENDED_Msk (1UL << SCB_SHCSR_USGFAULTPENDED_Pos) /*!< SCB SHCSR: USGFAULTPENDED Mask */ - -#define SCB_SHCSR_SYSTICKACT_Pos 11U /*!< SCB SHCSR: SYSTICKACT Position */ -#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */ - -#define SCB_SHCSR_PENDSVACT_Pos 10U /*!< SCB SHCSR: PENDSVACT Position */ -#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */ - -#define SCB_SHCSR_MONITORACT_Pos 8U /*!< SCB SHCSR: MONITORACT Position */ -#define SCB_SHCSR_MONITORACT_Msk (1UL << SCB_SHCSR_MONITORACT_Pos) /*!< SCB SHCSR: MONITORACT Mask */ - -#define SCB_SHCSR_SVCALLACT_Pos 7U /*!< SCB SHCSR: SVCALLACT Position */ -#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */ - -#define SCB_SHCSR_USGFAULTACT_Pos 3U /*!< SCB SHCSR: USGFAULTACT Position */ -#define SCB_SHCSR_USGFAULTACT_Msk (1UL << SCB_SHCSR_USGFAULTACT_Pos) /*!< SCB SHCSR: USGFAULTACT Mask */ - -#define SCB_SHCSR_BUSFAULTACT_Pos 1U /*!< SCB SHCSR: BUSFAULTACT Position */ -#define SCB_SHCSR_BUSFAULTACT_Msk (1UL << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */ - -#define SCB_SHCSR_MEMFAULTACT_Pos 0U /*!< SCB SHCSR: MEMFAULTACT Position */ -#define SCB_SHCSR_MEMFAULTACT_Msk (1UL /*<< SCB_SHCSR_MEMFAULTACT_Pos*/) /*!< SCB SHCSR: MEMFAULTACT Mask */ - -/* SCB Configurable Fault Status Register Definitions */ -#define SCB_CFSR_USGFAULTSR_Pos 16U /*!< SCB CFSR: Usage Fault Status Register Position */ -#define SCB_CFSR_USGFAULTSR_Msk (0xFFFFUL << SCB_CFSR_USGFAULTSR_Pos) /*!< SCB CFSR: Usage Fault Status Register Mask */ - -#define SCB_CFSR_BUSFAULTSR_Pos 8U /*!< SCB CFSR: Bus Fault Status Register Position */ -#define SCB_CFSR_BUSFAULTSR_Msk (0xFFUL << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */ - -#define SCB_CFSR_MEMFAULTSR_Pos 0U /*!< SCB CFSR: Memory Manage Fault Status Register Position */ -#define SCB_CFSR_MEMFAULTSR_Msk (0xFFUL /*<< SCB_CFSR_MEMFAULTSR_Pos*/) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */ - -/* MemManage Fault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_MMARVALID_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 7U) /*!< SCB CFSR (MMFSR): MMARVALID Position */ -#define SCB_CFSR_MMARVALID_Msk (1UL << SCB_CFSR_MMARVALID_Pos) /*!< SCB CFSR (MMFSR): MMARVALID Mask */ - -#define SCB_CFSR_MSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 4U) /*!< SCB CFSR (MMFSR): MSTKERR Position */ -#define SCB_CFSR_MSTKERR_Msk (1UL << SCB_CFSR_MSTKERR_Pos) /*!< SCB CFSR (MMFSR): MSTKERR Mask */ - -#define SCB_CFSR_MUNSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 3U) /*!< SCB CFSR (MMFSR): MUNSTKERR Position */ -#define SCB_CFSR_MUNSTKERR_Msk (1UL << SCB_CFSR_MUNSTKERR_Pos) /*!< SCB CFSR (MMFSR): MUNSTKERR Mask */ - -#define SCB_CFSR_DACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 1U) /*!< SCB CFSR (MMFSR): DACCVIOL Position */ -#define SCB_CFSR_DACCVIOL_Msk (1UL << SCB_CFSR_DACCVIOL_Pos) /*!< SCB CFSR (MMFSR): DACCVIOL Mask */ - -#define SCB_CFSR_IACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 0U) /*!< SCB CFSR (MMFSR): IACCVIOL Position */ -#define SCB_CFSR_IACCVIOL_Msk (1UL /*<< SCB_CFSR_IACCVIOL_Pos*/) /*!< SCB CFSR (MMFSR): IACCVIOL Mask */ - -/* BusFault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_BFARVALID_Pos (SCB_CFSR_BUSFAULTSR_Pos + 7U) /*!< SCB CFSR (BFSR): BFARVALID Position */ -#define SCB_CFSR_BFARVALID_Msk (1UL << SCB_CFSR_BFARVALID_Pos) /*!< SCB CFSR (BFSR): BFARVALID Mask */ - -#define SCB_CFSR_STKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 4U) /*!< SCB CFSR (BFSR): STKERR Position */ -#define SCB_CFSR_STKERR_Msk (1UL << SCB_CFSR_STKERR_Pos) /*!< SCB CFSR (BFSR): STKERR Mask */ - -#define SCB_CFSR_UNSTKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 3U) /*!< SCB CFSR (BFSR): UNSTKERR Position */ -#define SCB_CFSR_UNSTKERR_Msk (1UL << SCB_CFSR_UNSTKERR_Pos) /*!< SCB CFSR (BFSR): UNSTKERR Mask */ - -#define SCB_CFSR_IMPRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 2U) /*!< SCB CFSR (BFSR): IMPRECISERR Position */ -#define SCB_CFSR_IMPRECISERR_Msk (1UL << SCB_CFSR_IMPRECISERR_Pos) /*!< SCB CFSR (BFSR): IMPRECISERR Mask */ - -#define SCB_CFSR_PRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 1U) /*!< SCB CFSR (BFSR): PRECISERR Position */ -#define SCB_CFSR_PRECISERR_Msk (1UL << SCB_CFSR_PRECISERR_Pos) /*!< SCB CFSR (BFSR): PRECISERR Mask */ - -#define SCB_CFSR_IBUSERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 0U) /*!< SCB CFSR (BFSR): IBUSERR Position */ -#define SCB_CFSR_IBUSERR_Msk (1UL << SCB_CFSR_IBUSERR_Pos) /*!< SCB CFSR (BFSR): IBUSERR Mask */ - -/* UsageFault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_DIVBYZERO_Pos (SCB_CFSR_USGFAULTSR_Pos + 9U) /*!< SCB CFSR (UFSR): DIVBYZERO Position */ -#define SCB_CFSR_DIVBYZERO_Msk (1UL << SCB_CFSR_DIVBYZERO_Pos) /*!< SCB CFSR (UFSR): DIVBYZERO Mask */ - -#define SCB_CFSR_UNALIGNED_Pos (SCB_CFSR_USGFAULTSR_Pos + 8U) /*!< SCB CFSR (UFSR): UNALIGNED Position */ -#define SCB_CFSR_UNALIGNED_Msk (1UL << SCB_CFSR_UNALIGNED_Pos) /*!< SCB CFSR (UFSR): UNALIGNED Mask */ - -#define SCB_CFSR_NOCP_Pos (SCB_CFSR_USGFAULTSR_Pos + 3U) /*!< SCB CFSR (UFSR): NOCP Position */ -#define SCB_CFSR_NOCP_Msk (1UL << SCB_CFSR_NOCP_Pos) /*!< SCB CFSR (UFSR): NOCP Mask */ - -#define SCB_CFSR_INVPC_Pos (SCB_CFSR_USGFAULTSR_Pos + 2U) /*!< SCB CFSR (UFSR): INVPC Position */ -#define SCB_CFSR_INVPC_Msk (1UL << SCB_CFSR_INVPC_Pos) /*!< SCB CFSR (UFSR): INVPC Mask */ - -#define SCB_CFSR_INVSTATE_Pos (SCB_CFSR_USGFAULTSR_Pos + 1U) /*!< SCB CFSR (UFSR): INVSTATE Position */ -#define SCB_CFSR_INVSTATE_Msk (1UL << SCB_CFSR_INVSTATE_Pos) /*!< SCB CFSR (UFSR): INVSTATE Mask */ - -#define SCB_CFSR_UNDEFINSTR_Pos (SCB_CFSR_USGFAULTSR_Pos + 0U) /*!< SCB CFSR (UFSR): UNDEFINSTR Position */ -#define SCB_CFSR_UNDEFINSTR_Msk (1UL << SCB_CFSR_UNDEFINSTR_Pos) /*!< SCB CFSR (UFSR): UNDEFINSTR Mask */ - -/* SCB Hard Fault Status Register Definitions */ -#define SCB_HFSR_DEBUGEVT_Pos 31U /*!< SCB HFSR: DEBUGEVT Position */ -#define SCB_HFSR_DEBUGEVT_Msk (1UL << SCB_HFSR_DEBUGEVT_Pos) /*!< SCB HFSR: DEBUGEVT Mask */ - -#define SCB_HFSR_FORCED_Pos 30U /*!< SCB HFSR: FORCED Position */ -#define SCB_HFSR_FORCED_Msk (1UL << SCB_HFSR_FORCED_Pos) /*!< SCB HFSR: FORCED Mask */ - -#define SCB_HFSR_VECTTBL_Pos 1U /*!< SCB HFSR: VECTTBL Position */ -#define SCB_HFSR_VECTTBL_Msk (1UL << SCB_HFSR_VECTTBL_Pos) /*!< SCB HFSR: VECTTBL Mask */ - -/* SCB Debug Fault Status Register Definitions */ -#define SCB_DFSR_EXTERNAL_Pos 4U /*!< SCB DFSR: EXTERNAL Position */ -#define SCB_DFSR_EXTERNAL_Msk (1UL << SCB_DFSR_EXTERNAL_Pos) /*!< SCB DFSR: EXTERNAL Mask */ - -#define SCB_DFSR_VCATCH_Pos 3U /*!< SCB DFSR: VCATCH Position */ -#define SCB_DFSR_VCATCH_Msk (1UL << SCB_DFSR_VCATCH_Pos) /*!< SCB DFSR: VCATCH Mask */ - -#define SCB_DFSR_DWTTRAP_Pos 2U /*!< SCB DFSR: DWTTRAP Position */ -#define SCB_DFSR_DWTTRAP_Msk (1UL << SCB_DFSR_DWTTRAP_Pos) /*!< SCB DFSR: DWTTRAP Mask */ - -#define SCB_DFSR_BKPT_Pos 1U /*!< SCB DFSR: BKPT Position */ -#define SCB_DFSR_BKPT_Msk (1UL << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */ - -#define SCB_DFSR_HALTED_Pos 0U /*!< SCB DFSR: HALTED Position */ -#define SCB_DFSR_HALTED_Msk (1UL /*<< SCB_DFSR_HALTED_Pos*/) /*!< SCB DFSR: HALTED Mask */ - -/*@} end of group CMSIS_SCB */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SCnSCB System Controls not in SCB (SCnSCB) - \brief Type definitions for the System Control and ID Register not in the SCB - @{ - */ - -/** - \brief Structure type to access the System Control and ID Register not in the SCB. - */ -typedef struct -{ - uint32_t RESERVED0[1U]; - __IM uint32_t ICTR; /*!< Offset: 0x004 (R/ ) Interrupt Controller Type Register */ -#if defined (__CM3_REV) && (__CM3_REV >= 0x200U) - __IOM uint32_t ACTLR; /*!< Offset: 0x008 (R/W) Auxiliary Control Register */ -#else - uint32_t RESERVED1[1U]; -#endif -} SCnSCB_Type; - -/* Interrupt Controller Type Register Definitions */ -#define SCnSCB_ICTR_INTLINESNUM_Pos 0U /*!< ICTR: INTLINESNUM Position */ -#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL /*<< SCnSCB_ICTR_INTLINESNUM_Pos*/) /*!< ICTR: INTLINESNUM Mask */ - -/* Auxiliary Control Register Definitions */ -#if defined (__CM3_REV) && (__CM3_REV >= 0x200U) -#define SCnSCB_ACTLR_DISOOFP_Pos 9U /*!< ACTLR: DISOOFP Position */ -#define SCnSCB_ACTLR_DISOOFP_Msk (1UL << SCnSCB_ACTLR_DISOOFP_Pos) /*!< ACTLR: DISOOFP Mask */ - -#define SCnSCB_ACTLR_DISFPCA_Pos 8U /*!< ACTLR: DISFPCA Position */ -#define SCnSCB_ACTLR_DISFPCA_Msk (1UL << SCnSCB_ACTLR_DISFPCA_Pos) /*!< ACTLR: DISFPCA Mask */ - -#define SCnSCB_ACTLR_DISFOLD_Pos 2U /*!< ACTLR: DISFOLD Position */ -#define SCnSCB_ACTLR_DISFOLD_Msk (1UL << SCnSCB_ACTLR_DISFOLD_Pos) /*!< ACTLR: DISFOLD Mask */ - -#define SCnSCB_ACTLR_DISDEFWBUF_Pos 1U /*!< ACTLR: DISDEFWBUF Position */ -#define SCnSCB_ACTLR_DISDEFWBUF_Msk (1UL << SCnSCB_ACTLR_DISDEFWBUF_Pos) /*!< ACTLR: DISDEFWBUF Mask */ - -#define SCnSCB_ACTLR_DISMCYCINT_Pos 0U /*!< ACTLR: DISMCYCINT Position */ -#define SCnSCB_ACTLR_DISMCYCINT_Msk (1UL /*<< SCnSCB_ACTLR_DISMCYCINT_Pos*/) /*!< ACTLR: DISMCYCINT Mask */ -#endif - -/*@} end of group CMSIS_SCnotSCB */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SysTick System Tick Timer (SysTick) - \brief Type definitions for the System Timer Registers. - @{ - */ - -/** - \brief Structure type to access the System Timer (SysTick). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ - __IOM uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ - __IOM uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ - __IM uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ -} SysTick_Type; - -/* SysTick Control / Status Register Definitions */ -#define SysTick_CTRL_COUNTFLAG_Pos 16U /*!< SysTick CTRL: COUNTFLAG Position */ -#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ - -#define SysTick_CTRL_CLKSOURCE_Pos 2U /*!< SysTick CTRL: CLKSOURCE Position */ -#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ - -#define SysTick_CTRL_TICKINT_Pos 1U /*!< SysTick CTRL: TICKINT Position */ -#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ - -#define SysTick_CTRL_ENABLE_Pos 0U /*!< SysTick CTRL: ENABLE Position */ -#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ - -/* SysTick Reload Register Definitions */ -#define SysTick_LOAD_RELOAD_Pos 0U /*!< SysTick LOAD: RELOAD Position */ -#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ - -/* SysTick Current Register Definitions */ -#define SysTick_VAL_CURRENT_Pos 0U /*!< SysTick VAL: CURRENT Position */ -#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ - -/* SysTick Calibration Register Definitions */ -#define SysTick_CALIB_NOREF_Pos 31U /*!< SysTick CALIB: NOREF Position */ -#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ - -#define SysTick_CALIB_SKEW_Pos 30U /*!< SysTick CALIB: SKEW Position */ -#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ - -#define SysTick_CALIB_TENMS_Pos 0U /*!< SysTick CALIB: TENMS Position */ -#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ - -/*@} end of group CMSIS_SysTick */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_ITM Instrumentation Trace Macrocell (ITM) - \brief Type definitions for the Instrumentation Trace Macrocell (ITM) - @{ - */ - -/** - \brief Structure type to access the Instrumentation Trace Macrocell Register (ITM). - */ -typedef struct -{ - __OM union - { - __OM uint8_t u8; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 8-bit */ - __OM uint16_t u16; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 16-bit */ - __OM uint32_t u32; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 32-bit */ - } PORT [32U]; /*!< Offset: 0x000 ( /W) ITM Stimulus Port Registers */ - uint32_t RESERVED0[864U]; - __IOM uint32_t TER; /*!< Offset: 0xE00 (R/W) ITM Trace Enable Register */ - uint32_t RESERVED1[15U]; - __IOM uint32_t TPR; /*!< Offset: 0xE40 (R/W) ITM Trace Privilege Register */ - uint32_t RESERVED2[15U]; - __IOM uint32_t TCR; /*!< Offset: 0xE80 (R/W) ITM Trace Control Register */ - uint32_t RESERVED3[32U]; - uint32_t RESERVED4[43U]; - __OM uint32_t LAR; /*!< Offset: 0xFB0 ( /W) ITM Lock Access Register */ - __IM uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) ITM Lock Status Register */ - uint32_t RESERVED5[6U]; - __IM uint32_t PID4; /*!< Offset: 0xFD0 (R/ ) ITM Peripheral Identification Register #4 */ - __IM uint32_t PID5; /*!< Offset: 0xFD4 (R/ ) ITM Peripheral Identification Register #5 */ - __IM uint32_t PID6; /*!< Offset: 0xFD8 (R/ ) ITM Peripheral Identification Register #6 */ - __IM uint32_t PID7; /*!< Offset: 0xFDC (R/ ) ITM Peripheral Identification Register #7 */ - __IM uint32_t PID0; /*!< Offset: 0xFE0 (R/ ) ITM Peripheral Identification Register #0 */ - __IM uint32_t PID1; /*!< Offset: 0xFE4 (R/ ) ITM Peripheral Identification Register #1 */ - __IM uint32_t PID2; /*!< Offset: 0xFE8 (R/ ) ITM Peripheral Identification Register #2 */ - __IM uint32_t PID3; /*!< Offset: 0xFEC (R/ ) ITM Peripheral Identification Register #3 */ - __IM uint32_t CID0; /*!< Offset: 0xFF0 (R/ ) ITM Component Identification Register #0 */ - __IM uint32_t CID1; /*!< Offset: 0xFF4 (R/ ) ITM Component Identification Register #1 */ - __IM uint32_t CID2; /*!< Offset: 0xFF8 (R/ ) ITM Component Identification Register #2 */ - __IM uint32_t CID3; /*!< Offset: 0xFFC (R/ ) ITM Component Identification Register #3 */ -} ITM_Type; - -/* ITM Trace Privilege Register Definitions */ -#define ITM_TPR_PRIVMASK_Pos 0U /*!< ITM TPR: PRIVMASK Position */ -#define ITM_TPR_PRIVMASK_Msk (0xFFFFFFFFUL /*<< ITM_TPR_PRIVMASK_Pos*/) /*!< ITM TPR: PRIVMASK Mask */ - -/* ITM Trace Control Register Definitions */ -#define ITM_TCR_BUSY_Pos 23U /*!< ITM TCR: BUSY Position */ -#define ITM_TCR_BUSY_Msk (1UL << ITM_TCR_BUSY_Pos) /*!< ITM TCR: BUSY Mask */ - -#define ITM_TCR_TraceBusID_Pos 16U /*!< ITM TCR: ATBID Position */ -#define ITM_TCR_TraceBusID_Msk (0x7FUL << ITM_TCR_TraceBusID_Pos) /*!< ITM TCR: ATBID Mask */ - -#define ITM_TCR_GTSFREQ_Pos 10U /*!< ITM TCR: Global timestamp frequency Position */ -#define ITM_TCR_GTSFREQ_Msk (3UL << ITM_TCR_GTSFREQ_Pos) /*!< ITM TCR: Global timestamp frequency Mask */ - -#define ITM_TCR_TSPrescale_Pos 8U /*!< ITM TCR: TSPrescale Position */ -#define ITM_TCR_TSPrescale_Msk (3UL << ITM_TCR_TSPrescale_Pos) /*!< ITM TCR: TSPrescale Mask */ - -#define ITM_TCR_SWOENA_Pos 4U /*!< ITM TCR: SWOENA Position */ -#define ITM_TCR_SWOENA_Msk (1UL << ITM_TCR_SWOENA_Pos) /*!< ITM TCR: SWOENA Mask */ - -#define ITM_TCR_DWTENA_Pos 3U /*!< ITM TCR: DWTENA Position */ -#define ITM_TCR_DWTENA_Msk (1UL << ITM_TCR_DWTENA_Pos) /*!< ITM TCR: DWTENA Mask */ - -#define ITM_TCR_SYNCENA_Pos 2U /*!< ITM TCR: SYNCENA Position */ -#define ITM_TCR_SYNCENA_Msk (1UL << ITM_TCR_SYNCENA_Pos) /*!< ITM TCR: SYNCENA Mask */ - -#define ITM_TCR_TSENA_Pos 1U /*!< ITM TCR: TSENA Position */ -#define ITM_TCR_TSENA_Msk (1UL << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */ - -#define ITM_TCR_ITMENA_Pos 0U /*!< ITM TCR: ITM Enable bit Position */ -#define ITM_TCR_ITMENA_Msk (1UL /*<< ITM_TCR_ITMENA_Pos*/) /*!< ITM TCR: ITM Enable bit Mask */ - -/* ITM Lock Status Register Definitions */ -#define ITM_LSR_ByteAcc_Pos 2U /*!< ITM LSR: ByteAcc Position */ -#define ITM_LSR_ByteAcc_Msk (1UL << ITM_LSR_ByteAcc_Pos) /*!< ITM LSR: ByteAcc Mask */ - -#define ITM_LSR_Access_Pos 1U /*!< ITM LSR: Access Position */ -#define ITM_LSR_Access_Msk (1UL << ITM_LSR_Access_Pos) /*!< ITM LSR: Access Mask */ - -#define ITM_LSR_Present_Pos 0U /*!< ITM LSR: Present Position */ -#define ITM_LSR_Present_Msk (1UL /*<< ITM_LSR_Present_Pos*/) /*!< ITM LSR: Present Mask */ - -/*@}*/ /* end of group CMSIS_ITM */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_DWT Data Watchpoint and Trace (DWT) - \brief Type definitions for the Data Watchpoint and Trace (DWT) - @{ - */ - -/** - \brief Structure type to access the Data Watchpoint and Trace Register (DWT). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) Control Register */ - __IOM uint32_t CYCCNT; /*!< Offset: 0x004 (R/W) Cycle Count Register */ - __IOM uint32_t CPICNT; /*!< Offset: 0x008 (R/W) CPI Count Register */ - __IOM uint32_t EXCCNT; /*!< Offset: 0x00C (R/W) Exception Overhead Count Register */ - __IOM uint32_t SLEEPCNT; /*!< Offset: 0x010 (R/W) Sleep Count Register */ - __IOM uint32_t LSUCNT; /*!< Offset: 0x014 (R/W) LSU Count Register */ - __IOM uint32_t FOLDCNT; /*!< Offset: 0x018 (R/W) Folded-instruction Count Register */ - __IM uint32_t PCSR; /*!< Offset: 0x01C (R/ ) Program Counter Sample Register */ - __IOM uint32_t COMP0; /*!< Offset: 0x020 (R/W) Comparator Register 0 */ - __IOM uint32_t MASK0; /*!< Offset: 0x024 (R/W) Mask Register 0 */ - __IOM uint32_t FUNCTION0; /*!< Offset: 0x028 (R/W) Function Register 0 */ - uint32_t RESERVED0[1U]; - __IOM uint32_t COMP1; /*!< Offset: 0x030 (R/W) Comparator Register 1 */ - __IOM uint32_t MASK1; /*!< Offset: 0x034 (R/W) Mask Register 1 */ - __IOM uint32_t FUNCTION1; /*!< Offset: 0x038 (R/W) Function Register 1 */ - uint32_t RESERVED1[1U]; - __IOM uint32_t COMP2; /*!< Offset: 0x040 (R/W) Comparator Register 2 */ - __IOM uint32_t MASK2; /*!< Offset: 0x044 (R/W) Mask Register 2 */ - __IOM uint32_t FUNCTION2; /*!< Offset: 0x048 (R/W) Function Register 2 */ - uint32_t RESERVED2[1U]; - __IOM uint32_t COMP3; /*!< Offset: 0x050 (R/W) Comparator Register 3 */ - __IOM uint32_t MASK3; /*!< Offset: 0x054 (R/W) Mask Register 3 */ - __IOM uint32_t FUNCTION3; /*!< Offset: 0x058 (R/W) Function Register 3 */ -} DWT_Type; - -/* DWT Control Register Definitions */ -#define DWT_CTRL_NUMCOMP_Pos 28U /*!< DWT CTRL: NUMCOMP Position */ -#define DWT_CTRL_NUMCOMP_Msk (0xFUL << DWT_CTRL_NUMCOMP_Pos) /*!< DWT CTRL: NUMCOMP Mask */ - -#define DWT_CTRL_NOTRCPKT_Pos 27U /*!< DWT CTRL: NOTRCPKT Position */ -#define DWT_CTRL_NOTRCPKT_Msk (0x1UL << DWT_CTRL_NOTRCPKT_Pos) /*!< DWT CTRL: NOTRCPKT Mask */ - -#define DWT_CTRL_NOEXTTRIG_Pos 26U /*!< DWT CTRL: NOEXTTRIG Position */ -#define DWT_CTRL_NOEXTTRIG_Msk (0x1UL << DWT_CTRL_NOEXTTRIG_Pos) /*!< DWT CTRL: NOEXTTRIG Mask */ - -#define DWT_CTRL_NOCYCCNT_Pos 25U /*!< DWT CTRL: NOCYCCNT Position */ -#define DWT_CTRL_NOCYCCNT_Msk (0x1UL << DWT_CTRL_NOCYCCNT_Pos) /*!< DWT CTRL: NOCYCCNT Mask */ - -#define DWT_CTRL_NOPRFCNT_Pos 24U /*!< DWT CTRL: NOPRFCNT Position */ -#define DWT_CTRL_NOPRFCNT_Msk (0x1UL << DWT_CTRL_NOPRFCNT_Pos) /*!< DWT CTRL: NOPRFCNT Mask */ - -#define DWT_CTRL_CYCEVTENA_Pos 22U /*!< DWT CTRL: CYCEVTENA Position */ -#define DWT_CTRL_CYCEVTENA_Msk (0x1UL << DWT_CTRL_CYCEVTENA_Pos) /*!< DWT CTRL: CYCEVTENA Mask */ - -#define DWT_CTRL_FOLDEVTENA_Pos 21U /*!< DWT CTRL: FOLDEVTENA Position */ -#define DWT_CTRL_FOLDEVTENA_Msk (0x1UL << DWT_CTRL_FOLDEVTENA_Pos) /*!< DWT CTRL: FOLDEVTENA Mask */ - -#define DWT_CTRL_LSUEVTENA_Pos 20U /*!< DWT CTRL: LSUEVTENA Position */ -#define DWT_CTRL_LSUEVTENA_Msk (0x1UL << DWT_CTRL_LSUEVTENA_Pos) /*!< DWT CTRL: LSUEVTENA Mask */ - -#define DWT_CTRL_SLEEPEVTENA_Pos 19U /*!< DWT CTRL: SLEEPEVTENA Position */ -#define DWT_CTRL_SLEEPEVTENA_Msk (0x1UL << DWT_CTRL_SLEEPEVTENA_Pos) /*!< DWT CTRL: SLEEPEVTENA Mask */ - -#define DWT_CTRL_EXCEVTENA_Pos 18U /*!< DWT CTRL: EXCEVTENA Position */ -#define DWT_CTRL_EXCEVTENA_Msk (0x1UL << DWT_CTRL_EXCEVTENA_Pos) /*!< DWT CTRL: EXCEVTENA Mask */ - -#define DWT_CTRL_CPIEVTENA_Pos 17U /*!< DWT CTRL: CPIEVTENA Position */ -#define DWT_CTRL_CPIEVTENA_Msk (0x1UL << DWT_CTRL_CPIEVTENA_Pos) /*!< DWT CTRL: CPIEVTENA Mask */ - -#define DWT_CTRL_EXCTRCENA_Pos 16U /*!< DWT CTRL: EXCTRCENA Position */ -#define DWT_CTRL_EXCTRCENA_Msk (0x1UL << DWT_CTRL_EXCTRCENA_Pos) /*!< DWT CTRL: EXCTRCENA Mask */ - -#define DWT_CTRL_PCSAMPLENA_Pos 12U /*!< DWT CTRL: PCSAMPLENA Position */ -#define DWT_CTRL_PCSAMPLENA_Msk (0x1UL << DWT_CTRL_PCSAMPLENA_Pos) /*!< DWT CTRL: PCSAMPLENA Mask */ - -#define DWT_CTRL_SYNCTAP_Pos 10U /*!< DWT CTRL: SYNCTAP Position */ -#define DWT_CTRL_SYNCTAP_Msk (0x3UL << DWT_CTRL_SYNCTAP_Pos) /*!< DWT CTRL: SYNCTAP Mask */ - -#define DWT_CTRL_CYCTAP_Pos 9U /*!< DWT CTRL: CYCTAP Position */ -#define DWT_CTRL_CYCTAP_Msk (0x1UL << DWT_CTRL_CYCTAP_Pos) /*!< DWT CTRL: CYCTAP Mask */ - -#define DWT_CTRL_POSTINIT_Pos 5U /*!< DWT CTRL: POSTINIT Position */ -#define DWT_CTRL_POSTINIT_Msk (0xFUL << DWT_CTRL_POSTINIT_Pos) /*!< DWT CTRL: POSTINIT Mask */ - -#define DWT_CTRL_POSTPRESET_Pos 1U /*!< DWT CTRL: POSTPRESET Position */ -#define DWT_CTRL_POSTPRESET_Msk (0xFUL << DWT_CTRL_POSTPRESET_Pos) /*!< DWT CTRL: POSTPRESET Mask */ - -#define DWT_CTRL_CYCCNTENA_Pos 0U /*!< DWT CTRL: CYCCNTENA Position */ -#define DWT_CTRL_CYCCNTENA_Msk (0x1UL /*<< DWT_CTRL_CYCCNTENA_Pos*/) /*!< DWT CTRL: CYCCNTENA Mask */ - -/* DWT CPI Count Register Definitions */ -#define DWT_CPICNT_CPICNT_Pos 0U /*!< DWT CPICNT: CPICNT Position */ -#define DWT_CPICNT_CPICNT_Msk (0xFFUL /*<< DWT_CPICNT_CPICNT_Pos*/) /*!< DWT CPICNT: CPICNT Mask */ - -/* DWT Exception Overhead Count Register Definitions */ -#define DWT_EXCCNT_EXCCNT_Pos 0U /*!< DWT EXCCNT: EXCCNT Position */ -#define DWT_EXCCNT_EXCCNT_Msk (0xFFUL /*<< DWT_EXCCNT_EXCCNT_Pos*/) /*!< DWT EXCCNT: EXCCNT Mask */ - -/* DWT Sleep Count Register Definitions */ -#define DWT_SLEEPCNT_SLEEPCNT_Pos 0U /*!< DWT SLEEPCNT: SLEEPCNT Position */ -#define DWT_SLEEPCNT_SLEEPCNT_Msk (0xFFUL /*<< DWT_SLEEPCNT_SLEEPCNT_Pos*/) /*!< DWT SLEEPCNT: SLEEPCNT Mask */ - -/* DWT LSU Count Register Definitions */ -#define DWT_LSUCNT_LSUCNT_Pos 0U /*!< DWT LSUCNT: LSUCNT Position */ -#define DWT_LSUCNT_LSUCNT_Msk (0xFFUL /*<< DWT_LSUCNT_LSUCNT_Pos*/) /*!< DWT LSUCNT: LSUCNT Mask */ - -/* DWT Folded-instruction Count Register Definitions */ -#define DWT_FOLDCNT_FOLDCNT_Pos 0U /*!< DWT FOLDCNT: FOLDCNT Position */ -#define DWT_FOLDCNT_FOLDCNT_Msk (0xFFUL /*<< DWT_FOLDCNT_FOLDCNT_Pos*/) /*!< DWT FOLDCNT: FOLDCNT Mask */ - -/* DWT Comparator Mask Register Definitions */ -#define DWT_MASK_MASK_Pos 0U /*!< DWT MASK: MASK Position */ -#define DWT_MASK_MASK_Msk (0x1FUL /*<< DWT_MASK_MASK_Pos*/) /*!< DWT MASK: MASK Mask */ - -/* DWT Comparator Function Register Definitions */ -#define DWT_FUNCTION_MATCHED_Pos 24U /*!< DWT FUNCTION: MATCHED Position */ -#define DWT_FUNCTION_MATCHED_Msk (0x1UL << DWT_FUNCTION_MATCHED_Pos) /*!< DWT FUNCTION: MATCHED Mask */ - -#define DWT_FUNCTION_DATAVADDR1_Pos 16U /*!< DWT FUNCTION: DATAVADDR1 Position */ -#define DWT_FUNCTION_DATAVADDR1_Msk (0xFUL << DWT_FUNCTION_DATAVADDR1_Pos) /*!< DWT FUNCTION: DATAVADDR1 Mask */ - -#define DWT_FUNCTION_DATAVADDR0_Pos 12U /*!< DWT FUNCTION: DATAVADDR0 Position */ -#define DWT_FUNCTION_DATAVADDR0_Msk (0xFUL << DWT_FUNCTION_DATAVADDR0_Pos) /*!< DWT FUNCTION: DATAVADDR0 Mask */ - -#define DWT_FUNCTION_DATAVSIZE_Pos 10U /*!< DWT FUNCTION: DATAVSIZE Position */ -#define DWT_FUNCTION_DATAVSIZE_Msk (0x3UL << DWT_FUNCTION_DATAVSIZE_Pos) /*!< DWT FUNCTION: DATAVSIZE Mask */ - -#define DWT_FUNCTION_LNK1ENA_Pos 9U /*!< DWT FUNCTION: LNK1ENA Position */ -#define DWT_FUNCTION_LNK1ENA_Msk (0x1UL << DWT_FUNCTION_LNK1ENA_Pos) /*!< DWT FUNCTION: LNK1ENA Mask */ - -#define DWT_FUNCTION_DATAVMATCH_Pos 8U /*!< DWT FUNCTION: DATAVMATCH Position */ -#define DWT_FUNCTION_DATAVMATCH_Msk (0x1UL << DWT_FUNCTION_DATAVMATCH_Pos) /*!< DWT FUNCTION: DATAVMATCH Mask */ - -#define DWT_FUNCTION_CYCMATCH_Pos 7U /*!< DWT FUNCTION: CYCMATCH Position */ -#define DWT_FUNCTION_CYCMATCH_Msk (0x1UL << DWT_FUNCTION_CYCMATCH_Pos) /*!< DWT FUNCTION: CYCMATCH Mask */ - -#define DWT_FUNCTION_EMITRANGE_Pos 5U /*!< DWT FUNCTION: EMITRANGE Position */ -#define DWT_FUNCTION_EMITRANGE_Msk (0x1UL << DWT_FUNCTION_EMITRANGE_Pos) /*!< DWT FUNCTION: EMITRANGE Mask */ - -#define DWT_FUNCTION_FUNCTION_Pos 0U /*!< DWT FUNCTION: FUNCTION Position */ -#define DWT_FUNCTION_FUNCTION_Msk (0xFUL /*<< DWT_FUNCTION_FUNCTION_Pos*/) /*!< DWT FUNCTION: FUNCTION Mask */ - -/*@}*/ /* end of group CMSIS_DWT */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_TPI Trace Port Interface (TPI) - \brief Type definitions for the Trace Port Interface (TPI) - @{ - */ - -/** - \brief Structure type to access the Trace Port Interface Register (TPI). - */ -typedef struct -{ - __IM uint32_t SSPSR; /*!< Offset: 0x000 (R/ ) Supported Parallel Port Size Register */ - __IOM uint32_t CSPSR; /*!< Offset: 0x004 (R/W) Current Parallel Port Size Register */ - uint32_t RESERVED0[2U]; - __IOM uint32_t ACPR; /*!< Offset: 0x010 (R/W) Asynchronous Clock Prescaler Register */ - uint32_t RESERVED1[55U]; - __IOM uint32_t SPPR; /*!< Offset: 0x0F0 (R/W) Selected Pin Protocol Register */ - uint32_t RESERVED2[131U]; - __IM uint32_t FFSR; /*!< Offset: 0x300 (R/ ) Formatter and Flush Status Register */ - __IOM uint32_t FFCR; /*!< Offset: 0x304 (R/W) Formatter and Flush Control Register */ - __IM uint32_t FSCR; /*!< Offset: 0x308 (R/ ) Formatter Synchronization Counter Register */ - uint32_t RESERVED3[759U]; - __IM uint32_t TRIGGER; /*!< Offset: 0xEE8 (R/ ) TRIGGER Register */ - __IM uint32_t FIFO0; /*!< Offset: 0xEEC (R/ ) Integration ETM Data */ - __IM uint32_t ITATBCTR2; /*!< Offset: 0xEF0 (R/ ) ITATBCTR2 */ - uint32_t RESERVED4[1U]; - __IM uint32_t ITATBCTR0; /*!< Offset: 0xEF8 (R/ ) ITATBCTR0 */ - __IM uint32_t FIFO1; /*!< Offset: 0xEFC (R/ ) Integration ITM Data */ - __IOM uint32_t ITCTRL; /*!< Offset: 0xF00 (R/W) Integration Mode Control */ - uint32_t RESERVED5[39U]; - __IOM uint32_t CLAIMSET; /*!< Offset: 0xFA0 (R/W) Claim tag set */ - __IOM uint32_t CLAIMCLR; /*!< Offset: 0xFA4 (R/W) Claim tag clear */ - uint32_t RESERVED7[8U]; - __IM uint32_t DEVID; /*!< Offset: 0xFC8 (R/ ) TPIU_DEVID */ - __IM uint32_t DEVTYPE; /*!< Offset: 0xFCC (R/ ) TPIU_DEVTYPE */ -} TPI_Type; - -/* TPI Asynchronous Clock Prescaler Register Definitions */ -#define TPI_ACPR_PRESCALER_Pos 0U /*!< TPI ACPR: PRESCALER Position */ -#define TPI_ACPR_PRESCALER_Msk (0x1FFFUL /*<< TPI_ACPR_PRESCALER_Pos*/) /*!< TPI ACPR: PRESCALER Mask */ - -/* TPI Selected Pin Protocol Register Definitions */ -#define TPI_SPPR_TXMODE_Pos 0U /*!< TPI SPPR: TXMODE Position */ -#define TPI_SPPR_TXMODE_Msk (0x3UL /*<< TPI_SPPR_TXMODE_Pos*/) /*!< TPI SPPR: TXMODE Mask */ - -/* TPI Formatter and Flush Status Register Definitions */ -#define TPI_FFSR_FtNonStop_Pos 3U /*!< TPI FFSR: FtNonStop Position */ -#define TPI_FFSR_FtNonStop_Msk (0x1UL << TPI_FFSR_FtNonStop_Pos) /*!< TPI FFSR: FtNonStop Mask */ - -#define TPI_FFSR_TCPresent_Pos 2U /*!< TPI FFSR: TCPresent Position */ -#define TPI_FFSR_TCPresent_Msk (0x1UL << TPI_FFSR_TCPresent_Pos) /*!< TPI FFSR: TCPresent Mask */ - -#define TPI_FFSR_FtStopped_Pos 1U /*!< TPI FFSR: FtStopped Position */ -#define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */ - -#define TPI_FFSR_FlInProg_Pos 0U /*!< TPI FFSR: FlInProg Position */ -#define TPI_FFSR_FlInProg_Msk (0x1UL /*<< TPI_FFSR_FlInProg_Pos*/) /*!< TPI FFSR: FlInProg Mask */ - -/* TPI Formatter and Flush Control Register Definitions */ -#define TPI_FFCR_TrigIn_Pos 8U /*!< TPI FFCR: TrigIn Position */ -#define TPI_FFCR_TrigIn_Msk (0x1UL << TPI_FFCR_TrigIn_Pos) /*!< TPI FFCR: TrigIn Mask */ - -#define TPI_FFCR_EnFCont_Pos 1U /*!< TPI FFCR: EnFCont Position */ -#define TPI_FFCR_EnFCont_Msk (0x1UL << TPI_FFCR_EnFCont_Pos) /*!< TPI FFCR: EnFCont Mask */ - -/* TPI TRIGGER Register Definitions */ -#define TPI_TRIGGER_TRIGGER_Pos 0U /*!< TPI TRIGGER: TRIGGER Position */ -#define TPI_TRIGGER_TRIGGER_Msk (0x1UL /*<< TPI_TRIGGER_TRIGGER_Pos*/) /*!< TPI TRIGGER: TRIGGER Mask */ - -/* TPI Integration ETM Data Register Definitions (FIFO0) */ -#define TPI_FIFO0_ITM_ATVALID_Pos 29U /*!< TPI FIFO0: ITM_ATVALID Position */ -#define TPI_FIFO0_ITM_ATVALID_Msk (0x1UL << TPI_FIFO0_ITM_ATVALID_Pos) /*!< TPI FIFO0: ITM_ATVALID Mask */ - -#define TPI_FIFO0_ITM_bytecount_Pos 27U /*!< TPI FIFO0: ITM_bytecount Position */ -#define TPI_FIFO0_ITM_bytecount_Msk (0x3UL << TPI_FIFO0_ITM_bytecount_Pos) /*!< TPI FIFO0: ITM_bytecount Mask */ - -#define TPI_FIFO0_ETM_ATVALID_Pos 26U /*!< TPI FIFO0: ETM_ATVALID Position */ -#define TPI_FIFO0_ETM_ATVALID_Msk (0x1UL << TPI_FIFO0_ETM_ATVALID_Pos) /*!< TPI FIFO0: ETM_ATVALID Mask */ - -#define TPI_FIFO0_ETM_bytecount_Pos 24U /*!< TPI FIFO0: ETM_bytecount Position */ -#define TPI_FIFO0_ETM_bytecount_Msk (0x3UL << TPI_FIFO0_ETM_bytecount_Pos) /*!< TPI FIFO0: ETM_bytecount Mask */ - -#define TPI_FIFO0_ETM2_Pos 16U /*!< TPI FIFO0: ETM2 Position */ -#define TPI_FIFO0_ETM2_Msk (0xFFUL << TPI_FIFO0_ETM2_Pos) /*!< TPI FIFO0: ETM2 Mask */ - -#define TPI_FIFO0_ETM1_Pos 8U /*!< TPI FIFO0: ETM1 Position */ -#define TPI_FIFO0_ETM1_Msk (0xFFUL << TPI_FIFO0_ETM1_Pos) /*!< TPI FIFO0: ETM1 Mask */ - -#define TPI_FIFO0_ETM0_Pos 0U /*!< TPI FIFO0: ETM0 Position */ -#define TPI_FIFO0_ETM0_Msk (0xFFUL /*<< TPI_FIFO0_ETM0_Pos*/) /*!< TPI FIFO0: ETM0 Mask */ - -/* TPI ITATBCTR2 Register Definitions */ -#define TPI_ITATBCTR2_ATREADY2_Pos 0U /*!< TPI ITATBCTR2: ATREADY2 Position */ -#define TPI_ITATBCTR2_ATREADY2_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY2_Pos*/) /*!< TPI ITATBCTR2: ATREADY2 Mask */ - -#define TPI_ITATBCTR2_ATREADY1_Pos 0U /*!< TPI ITATBCTR2: ATREADY1 Position */ -#define TPI_ITATBCTR2_ATREADY1_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY1_Pos*/) /*!< TPI ITATBCTR2: ATREADY1 Mask */ - -/* TPI Integration ITM Data Register Definitions (FIFO1) */ -#define TPI_FIFO1_ITM_ATVALID_Pos 29U /*!< TPI FIFO1: ITM_ATVALID Position */ -#define TPI_FIFO1_ITM_ATVALID_Msk (0x1UL << TPI_FIFO1_ITM_ATVALID_Pos) /*!< TPI FIFO1: ITM_ATVALID Mask */ - -#define TPI_FIFO1_ITM_bytecount_Pos 27U /*!< TPI FIFO1: ITM_bytecount Position */ -#define TPI_FIFO1_ITM_bytecount_Msk (0x3UL << TPI_FIFO1_ITM_bytecount_Pos) /*!< TPI FIFO1: ITM_bytecount Mask */ - -#define TPI_FIFO1_ETM_ATVALID_Pos 26U /*!< TPI FIFO1: ETM_ATVALID Position */ -#define TPI_FIFO1_ETM_ATVALID_Msk (0x1UL << TPI_FIFO1_ETM_ATVALID_Pos) /*!< TPI FIFO1: ETM_ATVALID Mask */ - -#define TPI_FIFO1_ETM_bytecount_Pos 24U /*!< TPI FIFO1: ETM_bytecount Position */ -#define TPI_FIFO1_ETM_bytecount_Msk (0x3UL << TPI_FIFO1_ETM_bytecount_Pos) /*!< TPI FIFO1: ETM_bytecount Mask */ - -#define TPI_FIFO1_ITM2_Pos 16U /*!< TPI FIFO1: ITM2 Position */ -#define TPI_FIFO1_ITM2_Msk (0xFFUL << TPI_FIFO1_ITM2_Pos) /*!< TPI FIFO1: ITM2 Mask */ - -#define TPI_FIFO1_ITM1_Pos 8U /*!< TPI FIFO1: ITM1 Position */ -#define TPI_FIFO1_ITM1_Msk (0xFFUL << TPI_FIFO1_ITM1_Pos) /*!< TPI FIFO1: ITM1 Mask */ - -#define TPI_FIFO1_ITM0_Pos 0U /*!< TPI FIFO1: ITM0 Position */ -#define TPI_FIFO1_ITM0_Msk (0xFFUL /*<< TPI_FIFO1_ITM0_Pos*/) /*!< TPI FIFO1: ITM0 Mask */ - -/* TPI ITATBCTR0 Register Definitions */ -#define TPI_ITATBCTR0_ATREADY2_Pos 0U /*!< TPI ITATBCTR0: ATREADY2 Position */ -#define TPI_ITATBCTR0_ATREADY2_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY2_Pos*/) /*!< TPI ITATBCTR0: ATREADY2 Mask */ - -#define TPI_ITATBCTR0_ATREADY1_Pos 0U /*!< TPI ITATBCTR0: ATREADY1 Position */ -#define TPI_ITATBCTR0_ATREADY1_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY1_Pos*/) /*!< TPI ITATBCTR0: ATREADY1 Mask */ - -/* TPI Integration Mode Control Register Definitions */ -#define TPI_ITCTRL_Mode_Pos 0U /*!< TPI ITCTRL: Mode Position */ -#define TPI_ITCTRL_Mode_Msk (0x3UL /*<< TPI_ITCTRL_Mode_Pos*/) /*!< TPI ITCTRL: Mode Mask */ - -/* TPI DEVID Register Definitions */ -#define TPI_DEVID_NRZVALID_Pos 11U /*!< TPI DEVID: NRZVALID Position */ -#define TPI_DEVID_NRZVALID_Msk (0x1UL << TPI_DEVID_NRZVALID_Pos) /*!< TPI DEVID: NRZVALID Mask */ - -#define TPI_DEVID_MANCVALID_Pos 10U /*!< TPI DEVID: MANCVALID Position */ -#define TPI_DEVID_MANCVALID_Msk (0x1UL << TPI_DEVID_MANCVALID_Pos) /*!< TPI DEVID: MANCVALID Mask */ - -#define TPI_DEVID_PTINVALID_Pos 9U /*!< TPI DEVID: PTINVALID Position */ -#define TPI_DEVID_PTINVALID_Msk (0x1UL << TPI_DEVID_PTINVALID_Pos) /*!< TPI DEVID: PTINVALID Mask */ - -#define TPI_DEVID_MinBufSz_Pos 6U /*!< TPI DEVID: MinBufSz Position */ -#define TPI_DEVID_MinBufSz_Msk (0x7UL << TPI_DEVID_MinBufSz_Pos) /*!< TPI DEVID: MinBufSz Mask */ - -#define TPI_DEVID_AsynClkIn_Pos 5U /*!< TPI DEVID: AsynClkIn Position */ -#define TPI_DEVID_AsynClkIn_Msk (0x1UL << TPI_DEVID_AsynClkIn_Pos) /*!< TPI DEVID: AsynClkIn Mask */ - -#define TPI_DEVID_NrTraceInput_Pos 0U /*!< TPI DEVID: NrTraceInput Position */ -#define TPI_DEVID_NrTraceInput_Msk (0x1FUL /*<< TPI_DEVID_NrTraceInput_Pos*/) /*!< TPI DEVID: NrTraceInput Mask */ - -/* TPI DEVTYPE Register Definitions */ -#define TPI_DEVTYPE_SubType_Pos 4U /*!< TPI DEVTYPE: SubType Position */ -#define TPI_DEVTYPE_SubType_Msk (0xFUL /*<< TPI_DEVTYPE_SubType_Pos*/) /*!< TPI DEVTYPE: SubType Mask */ - -#define TPI_DEVTYPE_MajorType_Pos 0U /*!< TPI DEVTYPE: MajorType Position */ -#define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */ - -/*@}*/ /* end of group CMSIS_TPI */ - - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_MPU Memory Protection Unit (MPU) - \brief Type definitions for the Memory Protection Unit (MPU) - @{ - */ - -/** - \brief Structure type to access the Memory Protection Unit (MPU). - */ -typedef struct -{ - __IM uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */ - __IOM uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */ - __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region RNRber Register */ - __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */ - __IOM uint32_t RASR; /*!< Offset: 0x010 (R/W) MPU Region Attribute and Size Register */ - __IOM uint32_t RBAR_A1; /*!< Offset: 0x014 (R/W) MPU Alias 1 Region Base Address Register */ - __IOM uint32_t RASR_A1; /*!< Offset: 0x018 (R/W) MPU Alias 1 Region Attribute and Size Register */ - __IOM uint32_t RBAR_A2; /*!< Offset: 0x01C (R/W) MPU Alias 2 Region Base Address Register */ - __IOM uint32_t RASR_A2; /*!< Offset: 0x020 (R/W) MPU Alias 2 Region Attribute and Size Register */ - __IOM uint32_t RBAR_A3; /*!< Offset: 0x024 (R/W) MPU Alias 3 Region Base Address Register */ - __IOM uint32_t RASR_A3; /*!< Offset: 0x028 (R/W) MPU Alias 3 Region Attribute and Size Register */ -} MPU_Type; - -#define MPU_TYPE_RALIASES 4U - -/* MPU Type Register Definitions */ -#define MPU_TYPE_IREGION_Pos 16U /*!< MPU TYPE: IREGION Position */ -#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ - -#define MPU_TYPE_DREGION_Pos 8U /*!< MPU TYPE: DREGION Position */ -#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ - -#define MPU_TYPE_SEPARATE_Pos 0U /*!< MPU TYPE: SEPARATE Position */ -#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */ - -/* MPU Control Register Definitions */ -#define MPU_CTRL_PRIVDEFENA_Pos 2U /*!< MPU CTRL: PRIVDEFENA Position */ -#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ - -#define MPU_CTRL_HFNMIENA_Pos 1U /*!< MPU CTRL: HFNMIENA Position */ -#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ - -#define MPU_CTRL_ENABLE_Pos 0U /*!< MPU CTRL: ENABLE Position */ -#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */ - -/* MPU Region Number Register Definitions */ -#define MPU_RNR_REGION_Pos 0U /*!< MPU RNR: REGION Position */ -#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */ - -/* MPU Region Base Address Register Definitions */ -#define MPU_RBAR_ADDR_Pos 5U /*!< MPU RBAR: ADDR Position */ -#define MPU_RBAR_ADDR_Msk (0x7FFFFFFUL << MPU_RBAR_ADDR_Pos) /*!< MPU RBAR: ADDR Mask */ - -#define MPU_RBAR_VALID_Pos 4U /*!< MPU RBAR: VALID Position */ -#define MPU_RBAR_VALID_Msk (1UL << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */ - -#define MPU_RBAR_REGION_Pos 0U /*!< MPU RBAR: REGION Position */ -#define MPU_RBAR_REGION_Msk (0xFUL /*<< MPU_RBAR_REGION_Pos*/) /*!< MPU RBAR: REGION Mask */ - -/* MPU Region Attribute and Size Register Definitions */ -#define MPU_RASR_ATTRS_Pos 16U /*!< MPU RASR: MPU Region Attribute field Position */ -#define MPU_RASR_ATTRS_Msk (0xFFFFUL << MPU_RASR_ATTRS_Pos) /*!< MPU RASR: MPU Region Attribute field Mask */ - -#define MPU_RASR_XN_Pos 28U /*!< MPU RASR: ATTRS.XN Position */ -#define MPU_RASR_XN_Msk (1UL << MPU_RASR_XN_Pos) /*!< MPU RASR: ATTRS.XN Mask */ - -#define MPU_RASR_AP_Pos 24U /*!< MPU RASR: ATTRS.AP Position */ -#define MPU_RASR_AP_Msk (0x7UL << MPU_RASR_AP_Pos) /*!< MPU RASR: ATTRS.AP Mask */ - -#define MPU_RASR_TEX_Pos 19U /*!< MPU RASR: ATTRS.TEX Position */ -#define MPU_RASR_TEX_Msk (0x7UL << MPU_RASR_TEX_Pos) /*!< MPU RASR: ATTRS.TEX Mask */ - -#define MPU_RASR_S_Pos 18U /*!< MPU RASR: ATTRS.S Position */ -#define MPU_RASR_S_Msk (1UL << MPU_RASR_S_Pos) /*!< MPU RASR: ATTRS.S Mask */ - -#define MPU_RASR_C_Pos 17U /*!< MPU RASR: ATTRS.C Position */ -#define MPU_RASR_C_Msk (1UL << MPU_RASR_C_Pos) /*!< MPU RASR: ATTRS.C Mask */ - -#define MPU_RASR_B_Pos 16U /*!< MPU RASR: ATTRS.B Position */ -#define MPU_RASR_B_Msk (1UL << MPU_RASR_B_Pos) /*!< MPU RASR: ATTRS.B Mask */ - -#define MPU_RASR_SRD_Pos 8U /*!< MPU RASR: Sub-Region Disable Position */ -#define MPU_RASR_SRD_Msk (0xFFUL << MPU_RASR_SRD_Pos) /*!< MPU RASR: Sub-Region Disable Mask */ - -#define MPU_RASR_SIZE_Pos 1U /*!< MPU RASR: Region Size Field Position */ -#define MPU_RASR_SIZE_Msk (0x1FUL << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */ - -#define MPU_RASR_ENABLE_Pos 0U /*!< MPU RASR: Region enable bit Position */ -#define MPU_RASR_ENABLE_Msk (1UL /*<< MPU_RASR_ENABLE_Pos*/) /*!< MPU RASR: Region enable bit Disable Mask */ - -/*@} end of group CMSIS_MPU */ -#endif - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug) - \brief Type definitions for the Core Debug Registers - @{ - */ - -/** - \brief Structure type to access the Core Debug Register (CoreDebug). - */ -typedef struct -{ - __IOM uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */ - __OM uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */ - __IOM uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */ - __IOM uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */ -} CoreDebug_Type; - -/* Debug Halting Control and Status Register Definitions */ -#define CoreDebug_DHCSR_DBGKEY_Pos 16U /*!< CoreDebug DHCSR: DBGKEY Position */ -#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */ - -#define CoreDebug_DHCSR_S_RESET_ST_Pos 25U /*!< CoreDebug DHCSR: S_RESET_ST Position */ -#define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */ - -#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24U /*!< CoreDebug DHCSR: S_RETIRE_ST Position */ -#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */ - -#define CoreDebug_DHCSR_S_LOCKUP_Pos 19U /*!< CoreDebug DHCSR: S_LOCKUP Position */ -#define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */ - -#define CoreDebug_DHCSR_S_SLEEP_Pos 18U /*!< CoreDebug DHCSR: S_SLEEP Position */ -#define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */ - -#define CoreDebug_DHCSR_S_HALT_Pos 17U /*!< CoreDebug DHCSR: S_HALT Position */ -#define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */ - -#define CoreDebug_DHCSR_S_REGRDY_Pos 16U /*!< CoreDebug DHCSR: S_REGRDY Position */ -#define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */ - -#define CoreDebug_DHCSR_C_SNAPSTALL_Pos 5U /*!< CoreDebug DHCSR: C_SNAPSTALL Position */ -#define CoreDebug_DHCSR_C_SNAPSTALL_Msk (1UL << CoreDebug_DHCSR_C_SNAPSTALL_Pos) /*!< CoreDebug DHCSR: C_SNAPSTALL Mask */ - -#define CoreDebug_DHCSR_C_MASKINTS_Pos 3U /*!< CoreDebug DHCSR: C_MASKINTS Position */ -#define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */ - -#define CoreDebug_DHCSR_C_STEP_Pos 2U /*!< CoreDebug DHCSR: C_STEP Position */ -#define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */ - -#define CoreDebug_DHCSR_C_HALT_Pos 1U /*!< CoreDebug DHCSR: C_HALT Position */ -#define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */ - -#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0U /*!< CoreDebug DHCSR: C_DEBUGEN Position */ -#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL /*<< CoreDebug_DHCSR_C_DEBUGEN_Pos*/) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ - -/* Debug Core Register Selector Register Definitions */ -#define CoreDebug_DCRSR_REGWnR_Pos 16U /*!< CoreDebug DCRSR: REGWnR Position */ -#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */ - -#define CoreDebug_DCRSR_REGSEL_Pos 0U /*!< CoreDebug DCRSR: REGSEL Position */ -#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL /*<< CoreDebug_DCRSR_REGSEL_Pos*/) /*!< CoreDebug DCRSR: REGSEL Mask */ - -/* Debug Exception and Monitor Control Register Definitions */ -#define CoreDebug_DEMCR_TRCENA_Pos 24U /*!< CoreDebug DEMCR: TRCENA Position */ -#define CoreDebug_DEMCR_TRCENA_Msk (1UL << CoreDebug_DEMCR_TRCENA_Pos) /*!< CoreDebug DEMCR: TRCENA Mask */ - -#define CoreDebug_DEMCR_MON_REQ_Pos 19U /*!< CoreDebug DEMCR: MON_REQ Position */ -#define CoreDebug_DEMCR_MON_REQ_Msk (1UL << CoreDebug_DEMCR_MON_REQ_Pos) /*!< CoreDebug DEMCR: MON_REQ Mask */ - -#define CoreDebug_DEMCR_MON_STEP_Pos 18U /*!< CoreDebug DEMCR: MON_STEP Position */ -#define CoreDebug_DEMCR_MON_STEP_Msk (1UL << CoreDebug_DEMCR_MON_STEP_Pos) /*!< CoreDebug DEMCR: MON_STEP Mask */ - -#define CoreDebug_DEMCR_MON_PEND_Pos 17U /*!< CoreDebug DEMCR: MON_PEND Position */ -#define CoreDebug_DEMCR_MON_PEND_Msk (1UL << CoreDebug_DEMCR_MON_PEND_Pos) /*!< CoreDebug DEMCR: MON_PEND Mask */ - -#define CoreDebug_DEMCR_MON_EN_Pos 16U /*!< CoreDebug DEMCR: MON_EN Position */ -#define CoreDebug_DEMCR_MON_EN_Msk (1UL << CoreDebug_DEMCR_MON_EN_Pos) /*!< CoreDebug DEMCR: MON_EN Mask */ - -#define CoreDebug_DEMCR_VC_HARDERR_Pos 10U /*!< CoreDebug DEMCR: VC_HARDERR Position */ -#define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */ - -#define CoreDebug_DEMCR_VC_INTERR_Pos 9U /*!< CoreDebug DEMCR: VC_INTERR Position */ -#define CoreDebug_DEMCR_VC_INTERR_Msk (1UL << CoreDebug_DEMCR_VC_INTERR_Pos) /*!< CoreDebug DEMCR: VC_INTERR Mask */ - -#define CoreDebug_DEMCR_VC_BUSERR_Pos 8U /*!< CoreDebug DEMCR: VC_BUSERR Position */ -#define CoreDebug_DEMCR_VC_BUSERR_Msk (1UL << CoreDebug_DEMCR_VC_BUSERR_Pos) /*!< CoreDebug DEMCR: VC_BUSERR Mask */ - -#define CoreDebug_DEMCR_VC_STATERR_Pos 7U /*!< CoreDebug DEMCR: VC_STATERR Position */ -#define CoreDebug_DEMCR_VC_STATERR_Msk (1UL << CoreDebug_DEMCR_VC_STATERR_Pos) /*!< CoreDebug DEMCR: VC_STATERR Mask */ - -#define CoreDebug_DEMCR_VC_CHKERR_Pos 6U /*!< CoreDebug DEMCR: VC_CHKERR Position */ -#define CoreDebug_DEMCR_VC_CHKERR_Msk (1UL << CoreDebug_DEMCR_VC_CHKERR_Pos) /*!< CoreDebug DEMCR: VC_CHKERR Mask */ - -#define CoreDebug_DEMCR_VC_NOCPERR_Pos 5U /*!< CoreDebug DEMCR: VC_NOCPERR Position */ -#define CoreDebug_DEMCR_VC_NOCPERR_Msk (1UL << CoreDebug_DEMCR_VC_NOCPERR_Pos) /*!< CoreDebug DEMCR: VC_NOCPERR Mask */ - -#define CoreDebug_DEMCR_VC_MMERR_Pos 4U /*!< CoreDebug DEMCR: VC_MMERR Position */ -#define CoreDebug_DEMCR_VC_MMERR_Msk (1UL << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */ - -#define CoreDebug_DEMCR_VC_CORERESET_Pos 0U /*!< CoreDebug DEMCR: VC_CORERESET Position */ -#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL /*<< CoreDebug_DEMCR_VC_CORERESET_Pos*/) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ - -/*@} end of group CMSIS_CoreDebug */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_bitfield Core register bit field macros - \brief Macros for use with bit field definitions (xxx_Pos, xxx_Msk). - @{ - */ - -/** - \brief Mask and shift a bit field value for use in a register bit range. - \param[in] field Name of the register bit field. - \param[in] value Value of the bit field. This parameter is interpreted as an uint32_t type. - \return Masked and shifted value. -*/ -#define _VAL2FLD(field, value) (((uint32_t)(value) << field ## _Pos) & field ## _Msk) - -/** - \brief Mask and shift a register value to extract a bit filed value. - \param[in] field Name of the register bit field. - \param[in] value Value of register. This parameter is interpreted as an uint32_t type. - \return Masked and shifted bit field value. -*/ -#define _FLD2VAL(field, value) (((uint32_t)(value) & field ## _Msk) >> field ## _Pos) - -/*@} end of group CMSIS_core_bitfield */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_base Core Definitions - \brief Definitions for base addresses, unions, and structures. - @{ - */ - -/* Memory mapping of Core Hardware */ -#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ -#define ITM_BASE (0xE0000000UL) /*!< ITM Base Address */ -#define DWT_BASE (0xE0001000UL) /*!< DWT Base Address */ -#define TPI_BASE (0xE0040000UL) /*!< TPI Base Address */ -#define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug Base Address */ -#define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ -#define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ -#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ - -#define SCnSCB ((SCnSCB_Type *) SCS_BASE ) /*!< System control Register not in SCB */ -#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ -#define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ -#define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ -#define ITM ((ITM_Type *) ITM_BASE ) /*!< ITM configuration struct */ -#define DWT ((DWT_Type *) DWT_BASE ) /*!< DWT configuration struct */ -#define TPI ((TPI_Type *) TPI_BASE ) /*!< TPI configuration struct */ -#define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE) /*!< Core Debug configuration struct */ - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */ - #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */ -#endif - -/*@} */ - - - -/******************************************************************************* - * Hardware Abstraction Layer - Core Function Interface contains: - - Core NVIC Functions - - Core SysTick Functions - - Core Debug Functions - - Core Register Access Functions - ******************************************************************************/ -/** - \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference -*/ - - - -/* ########################## NVIC functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_NVICFunctions NVIC Functions - \brief Functions that manage interrupts and exceptions via the NVIC. - @{ - */ - -#ifdef CMSIS_NVIC_VIRTUAL - #ifndef CMSIS_NVIC_VIRTUAL_HEADER_FILE - #define CMSIS_NVIC_VIRTUAL_HEADER_FILE "cmsis_nvic_virtual.h" - #endif - #include CMSIS_NVIC_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetPriorityGrouping __NVIC_SetPriorityGrouping - #define NVIC_GetPriorityGrouping __NVIC_GetPriorityGrouping - #define NVIC_EnableIRQ __NVIC_EnableIRQ - #define NVIC_GetEnableIRQ __NVIC_GetEnableIRQ - #define NVIC_DisableIRQ __NVIC_DisableIRQ - #define NVIC_GetPendingIRQ __NVIC_GetPendingIRQ - #define NVIC_SetPendingIRQ __NVIC_SetPendingIRQ - #define NVIC_ClearPendingIRQ __NVIC_ClearPendingIRQ - #define NVIC_GetActive __NVIC_GetActive - #define NVIC_SetPriority __NVIC_SetPriority - #define NVIC_GetPriority __NVIC_GetPriority - #define NVIC_SystemReset __NVIC_SystemReset -#endif /* CMSIS_NVIC_VIRTUAL */ - -#ifdef CMSIS_VECTAB_VIRTUAL - #ifndef CMSIS_VECTAB_VIRTUAL_HEADER_FILE - #define CMSIS_VECTAB_VIRTUAL_HEADER_FILE "cmsis_vectab_virtual.h" - #endif - #include CMSIS_VECTAB_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetVector __NVIC_SetVector - #define NVIC_GetVector __NVIC_GetVector -#endif /* (CMSIS_VECTAB_VIRTUAL) */ - -#define NVIC_USER_IRQ_OFFSET 16 - - -/* The following EXC_RETURN values are saved the LR on exception entry */ -#define EXC_RETURN_HANDLER (0xFFFFFFF1UL) /* return to Handler mode, uses MSP after return */ -#define EXC_RETURN_THREAD_MSP (0xFFFFFFF9UL) /* return to Thread mode, uses MSP after return */ -#define EXC_RETURN_THREAD_PSP (0xFFFFFFFDUL) /* return to Thread mode, uses PSP after return */ - - -/** - \brief Set Priority Grouping - \details Sets the priority grouping field using the required unlock sequence. - The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field. - Only values from 0..7 are used. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Priority grouping field. - */ -__STATIC_INLINE void __NVIC_SetPriorityGrouping(uint32_t PriorityGroup) -{ - uint32_t reg_value; - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - - reg_value = SCB->AIRCR; /* read old register configuration */ - reg_value &= ~((uint32_t)(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk)); /* clear bits to change */ - reg_value = (reg_value | - ((uint32_t)0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - (PriorityGroupTmp << SCB_AIRCR_PRIGROUP_Pos) ); /* Insert write key and priority group */ - SCB->AIRCR = reg_value; -} - - -/** - \brief Get Priority Grouping - \details Reads the priority grouping field from the NVIC Interrupt Controller. - \return Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field). - */ -__STATIC_INLINE uint32_t __NVIC_GetPriorityGrouping(void) -{ - return ((uint32_t)((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos)); -} - - -/** - \brief Enable Interrupt - \details Enables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_EnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - __COMPILER_BARRIER(); - NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - __COMPILER_BARRIER(); - } -} - - -/** - \brief Get Interrupt Enable status - \details Returns a device specific interrupt enable status from the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt is not enabled. - \return 1 Interrupt is enabled. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetEnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Disable Interrupt - \details Disables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_DisableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - __DSB(); - __ISB(); - } -} - - -/** - \brief Get Pending Interrupt - \details Reads the NVIC pending register and returns the pending bit for the specified device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not pending. - \return 1 Interrupt status is pending. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Pending Interrupt - \details Sets the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_SetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Clear Pending Interrupt - \details Clears the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_ClearPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Active Interrupt - \details Reads the active register in the NVIC and returns the active bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not active. - \return 1 Interrupt status is active. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetActive(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Interrupt Priority - \details Sets the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \param [in] priority Priority to set. - \note The priority cannot be set for every processor exception. - */ -__STATIC_INLINE void __NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->IP[((uint32_t)IRQn)] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); - } - else - { - SCB->SHP[(((uint32_t)IRQn) & 0xFUL)-4UL] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); - } -} - - -/** - \brief Get Interrupt Priority - \details Reads the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Interrupt Priority. - Value is aligned automatically to the implemented priority bits of the microcontroller. - */ -__STATIC_INLINE uint32_t __NVIC_GetPriority(IRQn_Type IRQn) -{ - - if ((int32_t)(IRQn) >= 0) - { - return(((uint32_t)NVIC->IP[((uint32_t)IRQn)] >> (8U - __NVIC_PRIO_BITS))); - } - else - { - return(((uint32_t)SCB->SHP[(((uint32_t)IRQn) & 0xFUL)-4UL] >> (8U - __NVIC_PRIO_BITS))); - } -} - - -/** - \brief Encode Priority - \details Encodes the priority for an interrupt with the given priority group, - preemptive priority value, and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Used priority group. - \param [in] PreemptPriority Preemptive priority value (starting from 0). - \param [in] SubPriority Subpriority value (starting from 0). - \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority(). - */ -__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - return ( - ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | - ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) - ); -} - - -/** - \brief Decode Priority - \details Decodes an interrupt priority value with a given priority group to - preemptive priority value and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. - \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority(). - \param [in] PriorityGroup Used priority group. - \param [out] pPreemptPriority Preemptive priority value (starting from 0). - \param [out] pSubPriority Subpriority value (starting from 0). - */ -__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* const pPreemptPriority, uint32_t* const pSubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL); - *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL); -} - - -/** - \brief Set Interrupt Vector - \details Sets an interrupt vector in SRAM based interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - VTOR must been relocated to SRAM before. - \param [in] IRQn Interrupt number - \param [in] vector Address of interrupt handler function - */ -__STATIC_INLINE void __NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) -{ - uint32_t vectors = (uint32_t )SCB->VTOR; - (* (int *) (vectors + ((int32_t)IRQn + NVIC_USER_IRQ_OFFSET) * 4)) = vector; - /* ARM Application Note 321 states that the M3 does not require the architectural barrier */ -} - - -/** - \brief Get Interrupt Vector - \details Reads an interrupt vector from interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Address of interrupt handler function - */ -__STATIC_INLINE uint32_t __NVIC_GetVector(IRQn_Type IRQn) -{ - uint32_t vectors = (uint32_t )SCB->VTOR; - return (uint32_t)(* (int *) (vectors + ((int32_t)IRQn + NVIC_USER_IRQ_OFFSET) * 4)); -} - - -/** - \brief System Reset - \details Initiates a system reset request to reset the MCU. - */ -__NO_RETURN __STATIC_INLINE void __NVIC_SystemReset(void) -{ - __DSB(); /* Ensure all outstanding memory accesses included - buffered write are completed before reset */ - SCB->AIRCR = (uint32_t)((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) | - SCB_AIRCR_SYSRESETREQ_Msk ); /* Keep priority group unchanged */ - __DSB(); /* Ensure completion of memory access */ - - for(;;) /* wait until reset */ - { - __NOP(); - } -} - -/*@} end of CMSIS_Core_NVICFunctions */ - -/* ########################## MPU functions #################################### */ - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - -#include "mpu_armv7.h" - -#endif - - -/* ########################## FPU functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_FpuFunctions FPU Functions - \brief Function that provides FPU type. - @{ - */ - -/** - \brief get FPU type - \details returns the FPU type - \returns - - \b 0: No FPU - - \b 1: Single precision FPU - - \b 2: Double + Single precision FPU - */ -__STATIC_INLINE uint32_t SCB_GetFPUType(void) -{ - return 0U; /* No FPU */ -} - - -/*@} end of CMSIS_Core_FpuFunctions */ - - - -/* ################################## SysTick function ############################################ */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_SysTickFunctions SysTick Functions - \brief Functions that configure the System. - @{ - */ - -#if defined (__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U) - -/** - \brief System Tick Configuration - \details Initializes the System Timer and its interrupt, and starts the System Tick Timer. - Counter is in free running mode to generate periodic interrupts. - \param [in] ticks Number of ticks between two interrupts. - \return 0 Function succeeded. - \return 1 Function failed. - \note When the variable __Vendor_SysTickConfig is set to 1, then the - function SysTick_Config is not included. In this case, the file device.h - must contain a vendor-specific implementation of this function. - */ -__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) -{ - if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) - { - return (1UL); /* Reload value impossible */ - } - - SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ - NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ - SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ - SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | - SysTick_CTRL_TICKINT_Msk | - SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ - return (0UL); /* Function successful */ -} - -#endif - -/*@} end of CMSIS_Core_SysTickFunctions */ - - - -/* ##################################### Debug In/Output function ########################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_core_DebugFunctions ITM Functions - \brief Functions that access the ITM debug interface. - @{ - */ - -extern volatile int32_t ITM_RxBuffer; /*!< External variable to receive characters. */ -#define ITM_RXBUFFER_EMPTY ((int32_t)0x5AA55AA5U) /*!< Value identifying \ref ITM_RxBuffer is ready for next character. */ - - -/** - \brief ITM Send Character - \details Transmits a character via the ITM channel 0, and - \li Just returns when no debugger is connected that has booked the output. - \li Is blocking when a debugger is connected, but the previous character sent has not been transmitted. - \param [in] ch Character to transmit. - \returns Character to transmit. - */ -__STATIC_INLINE uint32_t ITM_SendChar (uint32_t ch) -{ - if (((ITM->TCR & ITM_TCR_ITMENA_Msk) != 0UL) && /* ITM enabled */ - ((ITM->TER & 1UL ) != 0UL) ) /* ITM Port #0 enabled */ - { - while (ITM->PORT[0U].u32 == 0UL) - { - __NOP(); - } - ITM->PORT[0U].u8 = (uint8_t)ch; - } - return (ch); -} - - -/** - \brief ITM Receive Character - \details Inputs a character via the external variable \ref ITM_RxBuffer. - \return Received character. - \return -1 No character pending. - */ -__STATIC_INLINE int32_t ITM_ReceiveChar (void) -{ - int32_t ch = -1; /* no character available */ - - if (ITM_RxBuffer != ITM_RXBUFFER_EMPTY) - { - ch = ITM_RxBuffer; - ITM_RxBuffer = ITM_RXBUFFER_EMPTY; /* ready for next character */ - } - - return (ch); -} - - -/** - \brief ITM Check Character - \details Checks whether a character is pending for reading in the variable \ref ITM_RxBuffer. - \return 0 No character available. - \return 1 Character available. - */ -__STATIC_INLINE int32_t ITM_CheckChar (void) -{ - - if (ITM_RxBuffer == ITM_RXBUFFER_EMPTY) - { - return (0); /* no character available */ - } - else - { - return (1); /* character available */ - } -} - -/*@} end of CMSIS_core_DebugFunctions */ - - - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_CM3_H_DEPENDANT */ - -#endif /* __CMSIS_GENERIC */ - diff --git a/panda/board/stm32fx/inc/core_cm4.h b/panda/board/stm32fx/inc/core_cm4.h deleted file mode 100644 index 0d40081..0000000 --- a/panda/board/stm32fx/inc/core_cm4.h +++ /dev/null @@ -1,2125 +0,0 @@ -/**************************************************************************//** - * @file core_cm4.h - * @brief CMSIS Cortex-M4 Core Peripheral Access Layer Header File - * @version V5.1.0 - * @date 13. March 2019 - ******************************************************************************/ -/* - * Copyright (c) 2009-2019 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef __CORE_CM4_H_GENERIC -#define __CORE_CM4_H_GENERIC - -#include - -#ifdef __cplusplus - extern "C" { -#endif - -/** - \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions - CMSIS violates the following MISRA-C:2004 rules: - - \li Required Rule 8.5, object/function definition in header file.
- Function definitions in header files are used to allow 'inlining'. - - \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
- Unions are used for effective representation of core registers. - - \li Advisory Rule 19.7, Function-like macro defined.
- Function-like macros are used to allow more efficient code. - */ - - -/******************************************************************************* - * CMSIS definitions - ******************************************************************************/ -/** - \ingroup Cortex_M4 - @{ - */ - -#include "cmsis_version.h" - -/* CMSIS CM4 definitions */ -#define __CM4_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */ -#define __CM4_CMSIS_VERSION_SUB (__CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */ -#define __CM4_CMSIS_VERSION ((__CM4_CMSIS_VERSION_MAIN << 16U) | \ - __CM4_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */ - -#define __CORTEX_M (4U) /*!< Cortex-M Core */ - -/** __FPU_USED indicates whether an FPU is used or not. - For this, __FPU_PRESENT has to be checked prior to making use of FPU specific registers and functions. -*/ -#if defined ( __CC_ARM ) - #if defined __TARGET_FPU_VFP - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #if defined __ARM_FP - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __GNUC__ ) - #if defined (__VFP_FP__) && !defined(__SOFTFP__) - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __ICCARM__ ) - #if defined __ARMVFP__ - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __TI_ARM__ ) - #if defined __TI_VFP_SUPPORT__ - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __TASKING__ ) - #if defined __FPU_VFP__ - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __CSMC__ ) - #if ( __CSMC__ & 0x400U) - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#endif - -#include "cmsis_compiler.h" /* CMSIS compiler specific defines */ - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_CM4_H_GENERIC */ - -#ifndef __CMSIS_GENERIC - -#ifndef __CORE_CM4_H_DEPENDANT -#define __CORE_CM4_H_DEPENDANT - -#ifdef __cplusplus - extern "C" { -#endif - -/* check device defines and use defaults */ -#if defined __CHECK_DEVICE_DEFINES - #ifndef __CM4_REV - #define __CM4_REV 0x0000U - #warning "__CM4_REV not defined in device header file; using default!" - #endif - - #ifndef __FPU_PRESENT - #define __FPU_PRESENT 0U - #warning "__FPU_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __MPU_PRESENT - #define __MPU_PRESENT 0U - #warning "__MPU_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __NVIC_PRIO_BITS - #define __NVIC_PRIO_BITS 3U - #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" - #endif - - #ifndef __Vendor_SysTickConfig - #define __Vendor_SysTickConfig 0U - #warning "__Vendor_SysTickConfig not defined in device header file; using default!" - #endif -#endif - -/* IO definitions (access restrictions to peripheral registers) */ -/** - \defgroup CMSIS_glob_defs CMSIS Global Defines - - IO Type Qualifiers are used - \li to specify the access to peripheral variables. - \li for automatic generation of peripheral register debug information. -*/ -#ifdef __cplusplus - #define __I volatile /*!< Defines 'read only' permissions */ -#else - #define __I volatile const /*!< Defines 'read only' permissions */ -#endif -#define __O volatile /*!< Defines 'write only' permissions */ -#define __IO volatile /*!< Defines 'read / write' permissions */ - -/* following defines should be used for structure members */ -#define __IM volatile const /*! Defines 'read only' structure member permissions */ -#define __OM volatile /*! Defines 'write only' structure member permissions */ -#define __IOM volatile /*! Defines 'read / write' structure member permissions */ - -/*@} end of group Cortex_M4 */ - - - -/******************************************************************************* - * Register Abstraction - Core Register contain: - - Core Register - - Core NVIC Register - - Core SCB Register - - Core SysTick Register - - Core Debug Register - - Core MPU Register - - Core FPU Register - ******************************************************************************/ -/** - \defgroup CMSIS_core_register Defines and Type Definitions - \brief Type definitions and defines for Cortex-M processor based devices. -*/ - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CORE Status and Control Registers - \brief Core Register type definitions. - @{ - */ - -/** - \brief Union type to access the Application Program Status Register (APSR). - */ -typedef union -{ - struct - { - uint32_t _reserved0:16; /*!< bit: 0..15 Reserved */ - uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ - uint32_t _reserved1:7; /*!< bit: 20..26 Reserved */ - uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} APSR_Type; - -/* APSR Register Definitions */ -#define APSR_N_Pos 31U /*!< APSR: N Position */ -#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ - -#define APSR_Z_Pos 30U /*!< APSR: Z Position */ -#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ - -#define APSR_C_Pos 29U /*!< APSR: C Position */ -#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ - -#define APSR_V_Pos 28U /*!< APSR: V Position */ -#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ - -#define APSR_Q_Pos 27U /*!< APSR: Q Position */ -#define APSR_Q_Msk (1UL << APSR_Q_Pos) /*!< APSR: Q Mask */ - -#define APSR_GE_Pos 16U /*!< APSR: GE Position */ -#define APSR_GE_Msk (0xFUL << APSR_GE_Pos) /*!< APSR: GE Mask */ - - -/** - \brief Union type to access the Interrupt Program Status Register (IPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} IPSR_Type; - -/* IPSR Register Definitions */ -#define IPSR_ISR_Pos 0U /*!< IPSR: ISR Position */ -#define IPSR_ISR_Msk (0x1FFUL /*<< IPSR_ISR_Pos*/) /*!< IPSR: ISR Mask */ - - -/** - \brief Union type to access the Special-Purpose Program Status Registers (xPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:1; /*!< bit: 9 Reserved */ - uint32_t ICI_IT_1:6; /*!< bit: 10..15 ICI/IT part 1 */ - uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ - uint32_t _reserved1:4; /*!< bit: 20..23 Reserved */ - uint32_t T:1; /*!< bit: 24 Thumb bit */ - uint32_t ICI_IT_2:2; /*!< bit: 25..26 ICI/IT part 2 */ - uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} xPSR_Type; - -/* xPSR Register Definitions */ -#define xPSR_N_Pos 31U /*!< xPSR: N Position */ -#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ - -#define xPSR_Z_Pos 30U /*!< xPSR: Z Position */ -#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ - -#define xPSR_C_Pos 29U /*!< xPSR: C Position */ -#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ - -#define xPSR_V_Pos 28U /*!< xPSR: V Position */ -#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ - -#define xPSR_Q_Pos 27U /*!< xPSR: Q Position */ -#define xPSR_Q_Msk (1UL << xPSR_Q_Pos) /*!< xPSR: Q Mask */ - -#define xPSR_ICI_IT_2_Pos 25U /*!< xPSR: ICI/IT part 2 Position */ -#define xPSR_ICI_IT_2_Msk (3UL << xPSR_ICI_IT_2_Pos) /*!< xPSR: ICI/IT part 2 Mask */ - -#define xPSR_T_Pos 24U /*!< xPSR: T Position */ -#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ - -#define xPSR_GE_Pos 16U /*!< xPSR: GE Position */ -#define xPSR_GE_Msk (0xFUL << xPSR_GE_Pos) /*!< xPSR: GE Mask */ - -#define xPSR_ICI_IT_1_Pos 10U /*!< xPSR: ICI/IT part 1 Position */ -#define xPSR_ICI_IT_1_Msk (0x3FUL << xPSR_ICI_IT_1_Pos) /*!< xPSR: ICI/IT part 1 Mask */ - -#define xPSR_ISR_Pos 0U /*!< xPSR: ISR Position */ -#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ - - -/** - \brief Union type to access the Control Registers (CONTROL). - */ -typedef union -{ - struct - { - uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ - uint32_t SPSEL:1; /*!< bit: 1 Stack to be used */ - uint32_t FPCA:1; /*!< bit: 2 FP extension active flag */ - uint32_t _reserved0:29; /*!< bit: 3..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} CONTROL_Type; - -/* CONTROL Register Definitions */ -#define CONTROL_FPCA_Pos 2U /*!< CONTROL: FPCA Position */ -#define CONTROL_FPCA_Msk (1UL << CONTROL_FPCA_Pos) /*!< CONTROL: FPCA Mask */ - -#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */ -#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ - -#define CONTROL_nPRIV_Pos 0U /*!< CONTROL: nPRIV Position */ -#define CONTROL_nPRIV_Msk (1UL /*<< CONTROL_nPRIV_Pos*/) /*!< CONTROL: nPRIV Mask */ - -/*@} end of group CMSIS_CORE */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC) - \brief Type definitions for the NVIC Registers - @{ - */ - -/** - \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). - */ -typedef struct -{ - __IOM uint32_t ISER[8U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ - uint32_t RESERVED0[24U]; - __IOM uint32_t ICER[8U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ - uint32_t RESERVED1[24U]; - __IOM uint32_t ISPR[8U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ - uint32_t RESERVED2[24U]; - __IOM uint32_t ICPR[8U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ - uint32_t RESERVED3[24U]; - __IOM uint32_t IABR[8U]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */ - uint32_t RESERVED4[56U]; - __IOM uint8_t IP[240U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register (8Bit wide) */ - uint32_t RESERVED5[644U]; - __OM uint32_t STIR; /*!< Offset: 0xE00 ( /W) Software Trigger Interrupt Register */ -} NVIC_Type; - -/* Software Triggered Interrupt Register Definitions */ -#define NVIC_STIR_INTID_Pos 0U /*!< STIR: INTLINESNUM Position */ -#define NVIC_STIR_INTID_Msk (0x1FFUL /*<< NVIC_STIR_INTID_Pos*/) /*!< STIR: INTLINESNUM Mask */ - -/*@} end of group CMSIS_NVIC */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SCB System Control Block (SCB) - \brief Type definitions for the System Control Block Registers - @{ - */ - -/** - \brief Structure type to access the System Control Block (SCB). - */ -typedef struct -{ - __IM uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ - __IOM uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ - __IOM uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ - __IOM uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ - __IOM uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ - __IOM uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ - __IOM uint8_t SHP[12U]; /*!< Offset: 0x018 (R/W) System Handlers Priority Registers (4-7, 8-11, 12-15) */ - __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ - __IOM uint32_t CFSR; /*!< Offset: 0x028 (R/W) Configurable Fault Status Register */ - __IOM uint32_t HFSR; /*!< Offset: 0x02C (R/W) HardFault Status Register */ - __IOM uint32_t DFSR; /*!< Offset: 0x030 (R/W) Debug Fault Status Register */ - __IOM uint32_t MMFAR; /*!< Offset: 0x034 (R/W) MemManage Fault Address Register */ - __IOM uint32_t BFAR; /*!< Offset: 0x038 (R/W) BusFault Address Register */ - __IOM uint32_t AFSR; /*!< Offset: 0x03C (R/W) Auxiliary Fault Status Register */ - __IM uint32_t PFR[2U]; /*!< Offset: 0x040 (R/ ) Processor Feature Register */ - __IM uint32_t DFR; /*!< Offset: 0x048 (R/ ) Debug Feature Register */ - __IM uint32_t ADR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */ - __IM uint32_t MMFR[4U]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */ - __IM uint32_t ISAR[5U]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */ - uint32_t RESERVED0[5U]; - __IOM uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control Register */ -} SCB_Type; - -/* SCB CPUID Register Definitions */ -#define SCB_CPUID_IMPLEMENTER_Pos 24U /*!< SCB CPUID: IMPLEMENTER Position */ -#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ - -#define SCB_CPUID_VARIANT_Pos 20U /*!< SCB CPUID: VARIANT Position */ -#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ - -#define SCB_CPUID_ARCHITECTURE_Pos 16U /*!< SCB CPUID: ARCHITECTURE Position */ -#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ - -#define SCB_CPUID_PARTNO_Pos 4U /*!< SCB CPUID: PARTNO Position */ -#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ - -#define SCB_CPUID_REVISION_Pos 0U /*!< SCB CPUID: REVISION Position */ -#define SCB_CPUID_REVISION_Msk (0xFUL /*<< SCB_CPUID_REVISION_Pos*/) /*!< SCB CPUID: REVISION Mask */ - -/* SCB Interrupt Control State Register Definitions */ -#define SCB_ICSR_NMIPENDSET_Pos 31U /*!< SCB ICSR: NMIPENDSET Position */ -#define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */ - -#define SCB_ICSR_PENDSVSET_Pos 28U /*!< SCB ICSR: PENDSVSET Position */ -#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ - -#define SCB_ICSR_PENDSVCLR_Pos 27U /*!< SCB ICSR: PENDSVCLR Position */ -#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ - -#define SCB_ICSR_PENDSTSET_Pos 26U /*!< SCB ICSR: PENDSTSET Position */ -#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ - -#define SCB_ICSR_PENDSTCLR_Pos 25U /*!< SCB ICSR: PENDSTCLR Position */ -#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ - -#define SCB_ICSR_ISRPREEMPT_Pos 23U /*!< SCB ICSR: ISRPREEMPT Position */ -#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ - -#define SCB_ICSR_ISRPENDING_Pos 22U /*!< SCB ICSR: ISRPENDING Position */ -#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ - -#define SCB_ICSR_VECTPENDING_Pos 12U /*!< SCB ICSR: VECTPENDING Position */ -#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ - -#define SCB_ICSR_RETTOBASE_Pos 11U /*!< SCB ICSR: RETTOBASE Position */ -#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */ - -#define SCB_ICSR_VECTACTIVE_Pos 0U /*!< SCB ICSR: VECTACTIVE Position */ -#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ - -/* SCB Vector Table Offset Register Definitions */ -#define SCB_VTOR_TBLOFF_Pos 7U /*!< SCB VTOR: TBLOFF Position */ -#define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ - -/* SCB Application Interrupt and Reset Control Register Definitions */ -#define SCB_AIRCR_VECTKEY_Pos 16U /*!< SCB AIRCR: VECTKEY Position */ -#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ - -#define SCB_AIRCR_VECTKEYSTAT_Pos 16U /*!< SCB AIRCR: VECTKEYSTAT Position */ -#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ - -#define SCB_AIRCR_ENDIANESS_Pos 15U /*!< SCB AIRCR: ENDIANESS Position */ -#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ - -#define SCB_AIRCR_PRIGROUP_Pos 8U /*!< SCB AIRCR: PRIGROUP Position */ -#define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */ - -#define SCB_AIRCR_SYSRESETREQ_Pos 2U /*!< SCB AIRCR: SYSRESETREQ Position */ -#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ - -#define SCB_AIRCR_VECTCLRACTIVE_Pos 1U /*!< SCB AIRCR: VECTCLRACTIVE Position */ -#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ - -#define SCB_AIRCR_VECTRESET_Pos 0U /*!< SCB AIRCR: VECTRESET Position */ -#define SCB_AIRCR_VECTRESET_Msk (1UL /*<< SCB_AIRCR_VECTRESET_Pos*/) /*!< SCB AIRCR: VECTRESET Mask */ - -/* SCB System Control Register Definitions */ -#define SCB_SCR_SEVONPEND_Pos 4U /*!< SCB SCR: SEVONPEND Position */ -#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ - -#define SCB_SCR_SLEEPDEEP_Pos 2U /*!< SCB SCR: SLEEPDEEP Position */ -#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ - -#define SCB_SCR_SLEEPONEXIT_Pos 1U /*!< SCB SCR: SLEEPONEXIT Position */ -#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ - -/* SCB Configuration Control Register Definitions */ -#define SCB_CCR_STKALIGN_Pos 9U /*!< SCB CCR: STKALIGN Position */ -#define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */ - -#define SCB_CCR_BFHFNMIGN_Pos 8U /*!< SCB CCR: BFHFNMIGN Position */ -#define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */ - -#define SCB_CCR_DIV_0_TRP_Pos 4U /*!< SCB CCR: DIV_0_TRP Position */ -#define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */ - -#define SCB_CCR_UNALIGN_TRP_Pos 3U /*!< SCB CCR: UNALIGN_TRP Position */ -#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ - -#define SCB_CCR_USERSETMPEND_Pos 1U /*!< SCB CCR: USERSETMPEND Position */ -#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */ - -#define SCB_CCR_NONBASETHRDENA_Pos 0U /*!< SCB CCR: NONBASETHRDENA Position */ -#define SCB_CCR_NONBASETHRDENA_Msk (1UL /*<< SCB_CCR_NONBASETHRDENA_Pos*/) /*!< SCB CCR: NONBASETHRDENA Mask */ - -/* SCB System Handler Control and State Register Definitions */ -#define SCB_SHCSR_USGFAULTENA_Pos 18U /*!< SCB SHCSR: USGFAULTENA Position */ -#define SCB_SHCSR_USGFAULTENA_Msk (1UL << SCB_SHCSR_USGFAULTENA_Pos) /*!< SCB SHCSR: USGFAULTENA Mask */ - -#define SCB_SHCSR_BUSFAULTENA_Pos 17U /*!< SCB SHCSR: BUSFAULTENA Position */ -#define SCB_SHCSR_BUSFAULTENA_Msk (1UL << SCB_SHCSR_BUSFAULTENA_Pos) /*!< SCB SHCSR: BUSFAULTENA Mask */ - -#define SCB_SHCSR_MEMFAULTENA_Pos 16U /*!< SCB SHCSR: MEMFAULTENA Position */ -#define SCB_SHCSR_MEMFAULTENA_Msk (1UL << SCB_SHCSR_MEMFAULTENA_Pos) /*!< SCB SHCSR: MEMFAULTENA Mask */ - -#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */ -#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ - -#define SCB_SHCSR_BUSFAULTPENDED_Pos 14U /*!< SCB SHCSR: BUSFAULTPENDED Position */ -#define SCB_SHCSR_BUSFAULTPENDED_Msk (1UL << SCB_SHCSR_BUSFAULTPENDED_Pos) /*!< SCB SHCSR: BUSFAULTPENDED Mask */ - -#define SCB_SHCSR_MEMFAULTPENDED_Pos 13U /*!< SCB SHCSR: MEMFAULTPENDED Position */ -#define SCB_SHCSR_MEMFAULTPENDED_Msk (1UL << SCB_SHCSR_MEMFAULTPENDED_Pos) /*!< SCB SHCSR: MEMFAULTPENDED Mask */ - -#define SCB_SHCSR_USGFAULTPENDED_Pos 12U /*!< SCB SHCSR: USGFAULTPENDED Position */ -#define SCB_SHCSR_USGFAULTPENDED_Msk (1UL << SCB_SHCSR_USGFAULTPENDED_Pos) /*!< SCB SHCSR: USGFAULTPENDED Mask */ - -#define SCB_SHCSR_SYSTICKACT_Pos 11U /*!< SCB SHCSR: SYSTICKACT Position */ -#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */ - -#define SCB_SHCSR_PENDSVACT_Pos 10U /*!< SCB SHCSR: PENDSVACT Position */ -#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */ - -#define SCB_SHCSR_MONITORACT_Pos 8U /*!< SCB SHCSR: MONITORACT Position */ -#define SCB_SHCSR_MONITORACT_Msk (1UL << SCB_SHCSR_MONITORACT_Pos) /*!< SCB SHCSR: MONITORACT Mask */ - -#define SCB_SHCSR_SVCALLACT_Pos 7U /*!< SCB SHCSR: SVCALLACT Position */ -#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */ - -#define SCB_SHCSR_USGFAULTACT_Pos 3U /*!< SCB SHCSR: USGFAULTACT Position */ -#define SCB_SHCSR_USGFAULTACT_Msk (1UL << SCB_SHCSR_USGFAULTACT_Pos) /*!< SCB SHCSR: USGFAULTACT Mask */ - -#define SCB_SHCSR_BUSFAULTACT_Pos 1U /*!< SCB SHCSR: BUSFAULTACT Position */ -#define SCB_SHCSR_BUSFAULTACT_Msk (1UL << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */ - -#define SCB_SHCSR_MEMFAULTACT_Pos 0U /*!< SCB SHCSR: MEMFAULTACT Position */ -#define SCB_SHCSR_MEMFAULTACT_Msk (1UL /*<< SCB_SHCSR_MEMFAULTACT_Pos*/) /*!< SCB SHCSR: MEMFAULTACT Mask */ - -/* SCB Configurable Fault Status Register Definitions */ -#define SCB_CFSR_USGFAULTSR_Pos 16U /*!< SCB CFSR: Usage Fault Status Register Position */ -#define SCB_CFSR_USGFAULTSR_Msk (0xFFFFUL << SCB_CFSR_USGFAULTSR_Pos) /*!< SCB CFSR: Usage Fault Status Register Mask */ - -#define SCB_CFSR_BUSFAULTSR_Pos 8U /*!< SCB CFSR: Bus Fault Status Register Position */ -#define SCB_CFSR_BUSFAULTSR_Msk (0xFFUL << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */ - -#define SCB_CFSR_MEMFAULTSR_Pos 0U /*!< SCB CFSR: Memory Manage Fault Status Register Position */ -#define SCB_CFSR_MEMFAULTSR_Msk (0xFFUL /*<< SCB_CFSR_MEMFAULTSR_Pos*/) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */ - -/* MemManage Fault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_MMARVALID_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 7U) /*!< SCB CFSR (MMFSR): MMARVALID Position */ -#define SCB_CFSR_MMARVALID_Msk (1UL << SCB_CFSR_MMARVALID_Pos) /*!< SCB CFSR (MMFSR): MMARVALID Mask */ - -#define SCB_CFSR_MLSPERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 5U) /*!< SCB CFSR (MMFSR): MLSPERR Position */ -#define SCB_CFSR_MLSPERR_Msk (1UL << SCB_CFSR_MLSPERR_Pos) /*!< SCB CFSR (MMFSR): MLSPERR Mask */ - -#define SCB_CFSR_MSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 4U) /*!< SCB CFSR (MMFSR): MSTKERR Position */ -#define SCB_CFSR_MSTKERR_Msk (1UL << SCB_CFSR_MSTKERR_Pos) /*!< SCB CFSR (MMFSR): MSTKERR Mask */ - -#define SCB_CFSR_MUNSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 3U) /*!< SCB CFSR (MMFSR): MUNSTKERR Position */ -#define SCB_CFSR_MUNSTKERR_Msk (1UL << SCB_CFSR_MUNSTKERR_Pos) /*!< SCB CFSR (MMFSR): MUNSTKERR Mask */ - -#define SCB_CFSR_DACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 1U) /*!< SCB CFSR (MMFSR): DACCVIOL Position */ -#define SCB_CFSR_DACCVIOL_Msk (1UL << SCB_CFSR_DACCVIOL_Pos) /*!< SCB CFSR (MMFSR): DACCVIOL Mask */ - -#define SCB_CFSR_IACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 0U) /*!< SCB CFSR (MMFSR): IACCVIOL Position */ -#define SCB_CFSR_IACCVIOL_Msk (1UL /*<< SCB_CFSR_IACCVIOL_Pos*/) /*!< SCB CFSR (MMFSR): IACCVIOL Mask */ - -/* BusFault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_BFARVALID_Pos (SCB_CFSR_BUSFAULTSR_Pos + 7U) /*!< SCB CFSR (BFSR): BFARVALID Position */ -#define SCB_CFSR_BFARVALID_Msk (1UL << SCB_CFSR_BFARVALID_Pos) /*!< SCB CFSR (BFSR): BFARVALID Mask */ - -#define SCB_CFSR_LSPERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 5U) /*!< SCB CFSR (BFSR): LSPERR Position */ -#define SCB_CFSR_LSPERR_Msk (1UL << SCB_CFSR_LSPERR_Pos) /*!< SCB CFSR (BFSR): LSPERR Mask */ - -#define SCB_CFSR_STKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 4U) /*!< SCB CFSR (BFSR): STKERR Position */ -#define SCB_CFSR_STKERR_Msk (1UL << SCB_CFSR_STKERR_Pos) /*!< SCB CFSR (BFSR): STKERR Mask */ - -#define SCB_CFSR_UNSTKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 3U) /*!< SCB CFSR (BFSR): UNSTKERR Position */ -#define SCB_CFSR_UNSTKERR_Msk (1UL << SCB_CFSR_UNSTKERR_Pos) /*!< SCB CFSR (BFSR): UNSTKERR Mask */ - -#define SCB_CFSR_IMPRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 2U) /*!< SCB CFSR (BFSR): IMPRECISERR Position */ -#define SCB_CFSR_IMPRECISERR_Msk (1UL << SCB_CFSR_IMPRECISERR_Pos) /*!< SCB CFSR (BFSR): IMPRECISERR Mask */ - -#define SCB_CFSR_PRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 1U) /*!< SCB CFSR (BFSR): PRECISERR Position */ -#define SCB_CFSR_PRECISERR_Msk (1UL << SCB_CFSR_PRECISERR_Pos) /*!< SCB CFSR (BFSR): PRECISERR Mask */ - -#define SCB_CFSR_IBUSERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 0U) /*!< SCB CFSR (BFSR): IBUSERR Position */ -#define SCB_CFSR_IBUSERR_Msk (1UL << SCB_CFSR_IBUSERR_Pos) /*!< SCB CFSR (BFSR): IBUSERR Mask */ - -/* UsageFault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_DIVBYZERO_Pos (SCB_CFSR_USGFAULTSR_Pos + 9U) /*!< SCB CFSR (UFSR): DIVBYZERO Position */ -#define SCB_CFSR_DIVBYZERO_Msk (1UL << SCB_CFSR_DIVBYZERO_Pos) /*!< SCB CFSR (UFSR): DIVBYZERO Mask */ - -#define SCB_CFSR_UNALIGNED_Pos (SCB_CFSR_USGFAULTSR_Pos + 8U) /*!< SCB CFSR (UFSR): UNALIGNED Position */ -#define SCB_CFSR_UNALIGNED_Msk (1UL << SCB_CFSR_UNALIGNED_Pos) /*!< SCB CFSR (UFSR): UNALIGNED Mask */ - -#define SCB_CFSR_NOCP_Pos (SCB_CFSR_USGFAULTSR_Pos + 3U) /*!< SCB CFSR (UFSR): NOCP Position */ -#define SCB_CFSR_NOCP_Msk (1UL << SCB_CFSR_NOCP_Pos) /*!< SCB CFSR (UFSR): NOCP Mask */ - -#define SCB_CFSR_INVPC_Pos (SCB_CFSR_USGFAULTSR_Pos + 2U) /*!< SCB CFSR (UFSR): INVPC Position */ -#define SCB_CFSR_INVPC_Msk (1UL << SCB_CFSR_INVPC_Pos) /*!< SCB CFSR (UFSR): INVPC Mask */ - -#define SCB_CFSR_INVSTATE_Pos (SCB_CFSR_USGFAULTSR_Pos + 1U) /*!< SCB CFSR (UFSR): INVSTATE Position */ -#define SCB_CFSR_INVSTATE_Msk (1UL << SCB_CFSR_INVSTATE_Pos) /*!< SCB CFSR (UFSR): INVSTATE Mask */ - -#define SCB_CFSR_UNDEFINSTR_Pos (SCB_CFSR_USGFAULTSR_Pos + 0U) /*!< SCB CFSR (UFSR): UNDEFINSTR Position */ -#define SCB_CFSR_UNDEFINSTR_Msk (1UL << SCB_CFSR_UNDEFINSTR_Pos) /*!< SCB CFSR (UFSR): UNDEFINSTR Mask */ - -/* SCB Hard Fault Status Register Definitions */ -#define SCB_HFSR_DEBUGEVT_Pos 31U /*!< SCB HFSR: DEBUGEVT Position */ -#define SCB_HFSR_DEBUGEVT_Msk (1UL << SCB_HFSR_DEBUGEVT_Pos) /*!< SCB HFSR: DEBUGEVT Mask */ - -#define SCB_HFSR_FORCED_Pos 30U /*!< SCB HFSR: FORCED Position */ -#define SCB_HFSR_FORCED_Msk (1UL << SCB_HFSR_FORCED_Pos) /*!< SCB HFSR: FORCED Mask */ - -#define SCB_HFSR_VECTTBL_Pos 1U /*!< SCB HFSR: VECTTBL Position */ -#define SCB_HFSR_VECTTBL_Msk (1UL << SCB_HFSR_VECTTBL_Pos) /*!< SCB HFSR: VECTTBL Mask */ - -/* SCB Debug Fault Status Register Definitions */ -#define SCB_DFSR_EXTERNAL_Pos 4U /*!< SCB DFSR: EXTERNAL Position */ -#define SCB_DFSR_EXTERNAL_Msk (1UL << SCB_DFSR_EXTERNAL_Pos) /*!< SCB DFSR: EXTERNAL Mask */ - -#define SCB_DFSR_VCATCH_Pos 3U /*!< SCB DFSR: VCATCH Position */ -#define SCB_DFSR_VCATCH_Msk (1UL << SCB_DFSR_VCATCH_Pos) /*!< SCB DFSR: VCATCH Mask */ - -#define SCB_DFSR_DWTTRAP_Pos 2U /*!< SCB DFSR: DWTTRAP Position */ -#define SCB_DFSR_DWTTRAP_Msk (1UL << SCB_DFSR_DWTTRAP_Pos) /*!< SCB DFSR: DWTTRAP Mask */ - -#define SCB_DFSR_BKPT_Pos 1U /*!< SCB DFSR: BKPT Position */ -#define SCB_DFSR_BKPT_Msk (1UL << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */ - -#define SCB_DFSR_HALTED_Pos 0U /*!< SCB DFSR: HALTED Position */ -#define SCB_DFSR_HALTED_Msk (1UL /*<< SCB_DFSR_HALTED_Pos*/) /*!< SCB DFSR: HALTED Mask */ - -/*@} end of group CMSIS_SCB */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SCnSCB System Controls not in SCB (SCnSCB) - \brief Type definitions for the System Control and ID Register not in the SCB - @{ - */ - -/** - \brief Structure type to access the System Control and ID Register not in the SCB. - */ -typedef struct -{ - uint32_t RESERVED0[1U]; - __IM uint32_t ICTR; /*!< Offset: 0x004 (R/ ) Interrupt Controller Type Register */ - __IOM uint32_t ACTLR; /*!< Offset: 0x008 (R/W) Auxiliary Control Register */ -} SCnSCB_Type; - -/* Interrupt Controller Type Register Definitions */ -#define SCnSCB_ICTR_INTLINESNUM_Pos 0U /*!< ICTR: INTLINESNUM Position */ -#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL /*<< SCnSCB_ICTR_INTLINESNUM_Pos*/) /*!< ICTR: INTLINESNUM Mask */ - -/* Auxiliary Control Register Definitions */ -#define SCnSCB_ACTLR_DISOOFP_Pos 9U /*!< ACTLR: DISOOFP Position */ -#define SCnSCB_ACTLR_DISOOFP_Msk (1UL << SCnSCB_ACTLR_DISOOFP_Pos) /*!< ACTLR: DISOOFP Mask */ - -#define SCnSCB_ACTLR_DISFPCA_Pos 8U /*!< ACTLR: DISFPCA Position */ -#define SCnSCB_ACTLR_DISFPCA_Msk (1UL << SCnSCB_ACTLR_DISFPCA_Pos) /*!< ACTLR: DISFPCA Mask */ - -#define SCnSCB_ACTLR_DISFOLD_Pos 2U /*!< ACTLR: DISFOLD Position */ -#define SCnSCB_ACTLR_DISFOLD_Msk (1UL << SCnSCB_ACTLR_DISFOLD_Pos) /*!< ACTLR: DISFOLD Mask */ - -#define SCnSCB_ACTLR_DISDEFWBUF_Pos 1U /*!< ACTLR: DISDEFWBUF Position */ -#define SCnSCB_ACTLR_DISDEFWBUF_Msk (1UL << SCnSCB_ACTLR_DISDEFWBUF_Pos) /*!< ACTLR: DISDEFWBUF Mask */ - -#define SCnSCB_ACTLR_DISMCYCINT_Pos 0U /*!< ACTLR: DISMCYCINT Position */ -#define SCnSCB_ACTLR_DISMCYCINT_Msk (1UL /*<< SCnSCB_ACTLR_DISMCYCINT_Pos*/) /*!< ACTLR: DISMCYCINT Mask */ - -/*@} end of group CMSIS_SCnotSCB */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SysTick System Tick Timer (SysTick) - \brief Type definitions for the System Timer Registers. - @{ - */ - -/** - \brief Structure type to access the System Timer (SysTick). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ - __IOM uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ - __IOM uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ - __IM uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ -} SysTick_Type; - -/* SysTick Control / Status Register Definitions */ -#define SysTick_CTRL_COUNTFLAG_Pos 16U /*!< SysTick CTRL: COUNTFLAG Position */ -#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ - -#define SysTick_CTRL_CLKSOURCE_Pos 2U /*!< SysTick CTRL: CLKSOURCE Position */ -#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ - -#define SysTick_CTRL_TICKINT_Pos 1U /*!< SysTick CTRL: TICKINT Position */ -#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ - -#define SysTick_CTRL_ENABLE_Pos 0U /*!< SysTick CTRL: ENABLE Position */ -#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ - -/* SysTick Reload Register Definitions */ -#define SysTick_LOAD_RELOAD_Pos 0U /*!< SysTick LOAD: RELOAD Position */ -#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ - -/* SysTick Current Register Definitions */ -#define SysTick_VAL_CURRENT_Pos 0U /*!< SysTick VAL: CURRENT Position */ -#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ - -/* SysTick Calibration Register Definitions */ -#define SysTick_CALIB_NOREF_Pos 31U /*!< SysTick CALIB: NOREF Position */ -#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ - -#define SysTick_CALIB_SKEW_Pos 30U /*!< SysTick CALIB: SKEW Position */ -#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ - -#define SysTick_CALIB_TENMS_Pos 0U /*!< SysTick CALIB: TENMS Position */ -#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ - -/*@} end of group CMSIS_SysTick */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_ITM Instrumentation Trace Macrocell (ITM) - \brief Type definitions for the Instrumentation Trace Macrocell (ITM) - @{ - */ - -/** - \brief Structure type to access the Instrumentation Trace Macrocell Register (ITM). - */ -typedef struct -{ - __OM union - { - __OM uint8_t u8; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 8-bit */ - __OM uint16_t u16; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 16-bit */ - __OM uint32_t u32; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 32-bit */ - } PORT [32U]; /*!< Offset: 0x000 ( /W) ITM Stimulus Port Registers */ - uint32_t RESERVED0[864U]; - __IOM uint32_t TER; /*!< Offset: 0xE00 (R/W) ITM Trace Enable Register */ - uint32_t RESERVED1[15U]; - __IOM uint32_t TPR; /*!< Offset: 0xE40 (R/W) ITM Trace Privilege Register */ - uint32_t RESERVED2[15U]; - __IOM uint32_t TCR; /*!< Offset: 0xE80 (R/W) ITM Trace Control Register */ - uint32_t RESERVED3[32U]; - uint32_t RESERVED4[43U]; - __OM uint32_t LAR; /*!< Offset: 0xFB0 ( /W) ITM Lock Access Register */ - __IM uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) ITM Lock Status Register */ - uint32_t RESERVED5[6U]; - __IM uint32_t PID4; /*!< Offset: 0xFD0 (R/ ) ITM Peripheral Identification Register #4 */ - __IM uint32_t PID5; /*!< Offset: 0xFD4 (R/ ) ITM Peripheral Identification Register #5 */ - __IM uint32_t PID6; /*!< Offset: 0xFD8 (R/ ) ITM Peripheral Identification Register #6 */ - __IM uint32_t PID7; /*!< Offset: 0xFDC (R/ ) ITM Peripheral Identification Register #7 */ - __IM uint32_t PID0; /*!< Offset: 0xFE0 (R/ ) ITM Peripheral Identification Register #0 */ - __IM uint32_t PID1; /*!< Offset: 0xFE4 (R/ ) ITM Peripheral Identification Register #1 */ - __IM uint32_t PID2; /*!< Offset: 0xFE8 (R/ ) ITM Peripheral Identification Register #2 */ - __IM uint32_t PID3; /*!< Offset: 0xFEC (R/ ) ITM Peripheral Identification Register #3 */ - __IM uint32_t CID0; /*!< Offset: 0xFF0 (R/ ) ITM Component Identification Register #0 */ - __IM uint32_t CID1; /*!< Offset: 0xFF4 (R/ ) ITM Component Identification Register #1 */ - __IM uint32_t CID2; /*!< Offset: 0xFF8 (R/ ) ITM Component Identification Register #2 */ - __IM uint32_t CID3; /*!< Offset: 0xFFC (R/ ) ITM Component Identification Register #3 */ -} ITM_Type; - -/* ITM Trace Privilege Register Definitions */ -#define ITM_TPR_PRIVMASK_Pos 0U /*!< ITM TPR: PRIVMASK Position */ -#define ITM_TPR_PRIVMASK_Msk (0xFFFFFFFFUL /*<< ITM_TPR_PRIVMASK_Pos*/) /*!< ITM TPR: PRIVMASK Mask */ - -/* ITM Trace Control Register Definitions */ -#define ITM_TCR_BUSY_Pos 23U /*!< ITM TCR: BUSY Position */ -#define ITM_TCR_BUSY_Msk (1UL << ITM_TCR_BUSY_Pos) /*!< ITM TCR: BUSY Mask */ - -#define ITM_TCR_TraceBusID_Pos 16U /*!< ITM TCR: ATBID Position */ -#define ITM_TCR_TraceBusID_Msk (0x7FUL << ITM_TCR_TraceBusID_Pos) /*!< ITM TCR: ATBID Mask */ - -#define ITM_TCR_GTSFREQ_Pos 10U /*!< ITM TCR: Global timestamp frequency Position */ -#define ITM_TCR_GTSFREQ_Msk (3UL << ITM_TCR_GTSFREQ_Pos) /*!< ITM TCR: Global timestamp frequency Mask */ - -#define ITM_TCR_TSPrescale_Pos 8U /*!< ITM TCR: TSPrescale Position */ -#define ITM_TCR_TSPrescale_Msk (3UL << ITM_TCR_TSPrescale_Pos) /*!< ITM TCR: TSPrescale Mask */ - -#define ITM_TCR_SWOENA_Pos 4U /*!< ITM TCR: SWOENA Position */ -#define ITM_TCR_SWOENA_Msk (1UL << ITM_TCR_SWOENA_Pos) /*!< ITM TCR: SWOENA Mask */ - -#define ITM_TCR_DWTENA_Pos 3U /*!< ITM TCR: DWTENA Position */ -#define ITM_TCR_DWTENA_Msk (1UL << ITM_TCR_DWTENA_Pos) /*!< ITM TCR: DWTENA Mask */ - -#define ITM_TCR_SYNCENA_Pos 2U /*!< ITM TCR: SYNCENA Position */ -#define ITM_TCR_SYNCENA_Msk (1UL << ITM_TCR_SYNCENA_Pos) /*!< ITM TCR: SYNCENA Mask */ - -#define ITM_TCR_TSENA_Pos 1U /*!< ITM TCR: TSENA Position */ -#define ITM_TCR_TSENA_Msk (1UL << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */ - -#define ITM_TCR_ITMENA_Pos 0U /*!< ITM TCR: ITM Enable bit Position */ -#define ITM_TCR_ITMENA_Msk (1UL /*<< ITM_TCR_ITMENA_Pos*/) /*!< ITM TCR: ITM Enable bit Mask */ - -/* ITM Lock Status Register Definitions */ -#define ITM_LSR_ByteAcc_Pos 2U /*!< ITM LSR: ByteAcc Position */ -#define ITM_LSR_ByteAcc_Msk (1UL << ITM_LSR_ByteAcc_Pos) /*!< ITM LSR: ByteAcc Mask */ - -#define ITM_LSR_Access_Pos 1U /*!< ITM LSR: Access Position */ -#define ITM_LSR_Access_Msk (1UL << ITM_LSR_Access_Pos) /*!< ITM LSR: Access Mask */ - -#define ITM_LSR_Present_Pos 0U /*!< ITM LSR: Present Position */ -#define ITM_LSR_Present_Msk (1UL /*<< ITM_LSR_Present_Pos*/) /*!< ITM LSR: Present Mask */ - -/*@}*/ /* end of group CMSIS_ITM */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_DWT Data Watchpoint and Trace (DWT) - \brief Type definitions for the Data Watchpoint and Trace (DWT) - @{ - */ - -/** - \brief Structure type to access the Data Watchpoint and Trace Register (DWT). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) Control Register */ - __IOM uint32_t CYCCNT; /*!< Offset: 0x004 (R/W) Cycle Count Register */ - __IOM uint32_t CPICNT; /*!< Offset: 0x008 (R/W) CPI Count Register */ - __IOM uint32_t EXCCNT; /*!< Offset: 0x00C (R/W) Exception Overhead Count Register */ - __IOM uint32_t SLEEPCNT; /*!< Offset: 0x010 (R/W) Sleep Count Register */ - __IOM uint32_t LSUCNT; /*!< Offset: 0x014 (R/W) LSU Count Register */ - __IOM uint32_t FOLDCNT; /*!< Offset: 0x018 (R/W) Folded-instruction Count Register */ - __IM uint32_t PCSR; /*!< Offset: 0x01C (R/ ) Program Counter Sample Register */ - __IOM uint32_t COMP0; /*!< Offset: 0x020 (R/W) Comparator Register 0 */ - __IOM uint32_t MASK0; /*!< Offset: 0x024 (R/W) Mask Register 0 */ - __IOM uint32_t FUNCTION0; /*!< Offset: 0x028 (R/W) Function Register 0 */ - uint32_t RESERVED0[1U]; - __IOM uint32_t COMP1; /*!< Offset: 0x030 (R/W) Comparator Register 1 */ - __IOM uint32_t MASK1; /*!< Offset: 0x034 (R/W) Mask Register 1 */ - __IOM uint32_t FUNCTION1; /*!< Offset: 0x038 (R/W) Function Register 1 */ - uint32_t RESERVED1[1U]; - __IOM uint32_t COMP2; /*!< Offset: 0x040 (R/W) Comparator Register 2 */ - __IOM uint32_t MASK2; /*!< Offset: 0x044 (R/W) Mask Register 2 */ - __IOM uint32_t FUNCTION2; /*!< Offset: 0x048 (R/W) Function Register 2 */ - uint32_t RESERVED2[1U]; - __IOM uint32_t COMP3; /*!< Offset: 0x050 (R/W) Comparator Register 3 */ - __IOM uint32_t MASK3; /*!< Offset: 0x054 (R/W) Mask Register 3 */ - __IOM uint32_t FUNCTION3; /*!< Offset: 0x058 (R/W) Function Register 3 */ -} DWT_Type; - -/* DWT Control Register Definitions */ -#define DWT_CTRL_NUMCOMP_Pos 28U /*!< DWT CTRL: NUMCOMP Position */ -#define DWT_CTRL_NUMCOMP_Msk (0xFUL << DWT_CTRL_NUMCOMP_Pos) /*!< DWT CTRL: NUMCOMP Mask */ - -#define DWT_CTRL_NOTRCPKT_Pos 27U /*!< DWT CTRL: NOTRCPKT Position */ -#define DWT_CTRL_NOTRCPKT_Msk (0x1UL << DWT_CTRL_NOTRCPKT_Pos) /*!< DWT CTRL: NOTRCPKT Mask */ - -#define DWT_CTRL_NOEXTTRIG_Pos 26U /*!< DWT CTRL: NOEXTTRIG Position */ -#define DWT_CTRL_NOEXTTRIG_Msk (0x1UL << DWT_CTRL_NOEXTTRIG_Pos) /*!< DWT CTRL: NOEXTTRIG Mask */ - -#define DWT_CTRL_NOCYCCNT_Pos 25U /*!< DWT CTRL: NOCYCCNT Position */ -#define DWT_CTRL_NOCYCCNT_Msk (0x1UL << DWT_CTRL_NOCYCCNT_Pos) /*!< DWT CTRL: NOCYCCNT Mask */ - -#define DWT_CTRL_NOPRFCNT_Pos 24U /*!< DWT CTRL: NOPRFCNT Position */ -#define DWT_CTRL_NOPRFCNT_Msk (0x1UL << DWT_CTRL_NOPRFCNT_Pos) /*!< DWT CTRL: NOPRFCNT Mask */ - -#define DWT_CTRL_CYCEVTENA_Pos 22U /*!< DWT CTRL: CYCEVTENA Position */ -#define DWT_CTRL_CYCEVTENA_Msk (0x1UL << DWT_CTRL_CYCEVTENA_Pos) /*!< DWT CTRL: CYCEVTENA Mask */ - -#define DWT_CTRL_FOLDEVTENA_Pos 21U /*!< DWT CTRL: FOLDEVTENA Position */ -#define DWT_CTRL_FOLDEVTENA_Msk (0x1UL << DWT_CTRL_FOLDEVTENA_Pos) /*!< DWT CTRL: FOLDEVTENA Mask */ - -#define DWT_CTRL_LSUEVTENA_Pos 20U /*!< DWT CTRL: LSUEVTENA Position */ -#define DWT_CTRL_LSUEVTENA_Msk (0x1UL << DWT_CTRL_LSUEVTENA_Pos) /*!< DWT CTRL: LSUEVTENA Mask */ - -#define DWT_CTRL_SLEEPEVTENA_Pos 19U /*!< DWT CTRL: SLEEPEVTENA Position */ -#define DWT_CTRL_SLEEPEVTENA_Msk (0x1UL << DWT_CTRL_SLEEPEVTENA_Pos) /*!< DWT CTRL: SLEEPEVTENA Mask */ - -#define DWT_CTRL_EXCEVTENA_Pos 18U /*!< DWT CTRL: EXCEVTENA Position */ -#define DWT_CTRL_EXCEVTENA_Msk (0x1UL << DWT_CTRL_EXCEVTENA_Pos) /*!< DWT CTRL: EXCEVTENA Mask */ - -#define DWT_CTRL_CPIEVTENA_Pos 17U /*!< DWT CTRL: CPIEVTENA Position */ -#define DWT_CTRL_CPIEVTENA_Msk (0x1UL << DWT_CTRL_CPIEVTENA_Pos) /*!< DWT CTRL: CPIEVTENA Mask */ - -#define DWT_CTRL_EXCTRCENA_Pos 16U /*!< DWT CTRL: EXCTRCENA Position */ -#define DWT_CTRL_EXCTRCENA_Msk (0x1UL << DWT_CTRL_EXCTRCENA_Pos) /*!< DWT CTRL: EXCTRCENA Mask */ - -#define DWT_CTRL_PCSAMPLENA_Pos 12U /*!< DWT CTRL: PCSAMPLENA Position */ -#define DWT_CTRL_PCSAMPLENA_Msk (0x1UL << DWT_CTRL_PCSAMPLENA_Pos) /*!< DWT CTRL: PCSAMPLENA Mask */ - -#define DWT_CTRL_SYNCTAP_Pos 10U /*!< DWT CTRL: SYNCTAP Position */ -#define DWT_CTRL_SYNCTAP_Msk (0x3UL << DWT_CTRL_SYNCTAP_Pos) /*!< DWT CTRL: SYNCTAP Mask */ - -#define DWT_CTRL_CYCTAP_Pos 9U /*!< DWT CTRL: CYCTAP Position */ -#define DWT_CTRL_CYCTAP_Msk (0x1UL << DWT_CTRL_CYCTAP_Pos) /*!< DWT CTRL: CYCTAP Mask */ - -#define DWT_CTRL_POSTINIT_Pos 5U /*!< DWT CTRL: POSTINIT Position */ -#define DWT_CTRL_POSTINIT_Msk (0xFUL << DWT_CTRL_POSTINIT_Pos) /*!< DWT CTRL: POSTINIT Mask */ - -#define DWT_CTRL_POSTPRESET_Pos 1U /*!< DWT CTRL: POSTPRESET Position */ -#define DWT_CTRL_POSTPRESET_Msk (0xFUL << DWT_CTRL_POSTPRESET_Pos) /*!< DWT CTRL: POSTPRESET Mask */ - -#define DWT_CTRL_CYCCNTENA_Pos 0U /*!< DWT CTRL: CYCCNTENA Position */ -#define DWT_CTRL_CYCCNTENA_Msk (0x1UL /*<< DWT_CTRL_CYCCNTENA_Pos*/) /*!< DWT CTRL: CYCCNTENA Mask */ - -/* DWT CPI Count Register Definitions */ -#define DWT_CPICNT_CPICNT_Pos 0U /*!< DWT CPICNT: CPICNT Position */ -#define DWT_CPICNT_CPICNT_Msk (0xFFUL /*<< DWT_CPICNT_CPICNT_Pos*/) /*!< DWT CPICNT: CPICNT Mask */ - -/* DWT Exception Overhead Count Register Definitions */ -#define DWT_EXCCNT_EXCCNT_Pos 0U /*!< DWT EXCCNT: EXCCNT Position */ -#define DWT_EXCCNT_EXCCNT_Msk (0xFFUL /*<< DWT_EXCCNT_EXCCNT_Pos*/) /*!< DWT EXCCNT: EXCCNT Mask */ - -/* DWT Sleep Count Register Definitions */ -#define DWT_SLEEPCNT_SLEEPCNT_Pos 0U /*!< DWT SLEEPCNT: SLEEPCNT Position */ -#define DWT_SLEEPCNT_SLEEPCNT_Msk (0xFFUL /*<< DWT_SLEEPCNT_SLEEPCNT_Pos*/) /*!< DWT SLEEPCNT: SLEEPCNT Mask */ - -/* DWT LSU Count Register Definitions */ -#define DWT_LSUCNT_LSUCNT_Pos 0U /*!< DWT LSUCNT: LSUCNT Position */ -#define DWT_LSUCNT_LSUCNT_Msk (0xFFUL /*<< DWT_LSUCNT_LSUCNT_Pos*/) /*!< DWT LSUCNT: LSUCNT Mask */ - -/* DWT Folded-instruction Count Register Definitions */ -#define DWT_FOLDCNT_FOLDCNT_Pos 0U /*!< DWT FOLDCNT: FOLDCNT Position */ -#define DWT_FOLDCNT_FOLDCNT_Msk (0xFFUL /*<< DWT_FOLDCNT_FOLDCNT_Pos*/) /*!< DWT FOLDCNT: FOLDCNT Mask */ - -/* DWT Comparator Mask Register Definitions */ -#define DWT_MASK_MASK_Pos 0U /*!< DWT MASK: MASK Position */ -#define DWT_MASK_MASK_Msk (0x1FUL /*<< DWT_MASK_MASK_Pos*/) /*!< DWT MASK: MASK Mask */ - -/* DWT Comparator Function Register Definitions */ -#define DWT_FUNCTION_MATCHED_Pos 24U /*!< DWT FUNCTION: MATCHED Position */ -#define DWT_FUNCTION_MATCHED_Msk (0x1UL << DWT_FUNCTION_MATCHED_Pos) /*!< DWT FUNCTION: MATCHED Mask */ - -#define DWT_FUNCTION_DATAVADDR1_Pos 16U /*!< DWT FUNCTION: DATAVADDR1 Position */ -#define DWT_FUNCTION_DATAVADDR1_Msk (0xFUL << DWT_FUNCTION_DATAVADDR1_Pos) /*!< DWT FUNCTION: DATAVADDR1 Mask */ - -#define DWT_FUNCTION_DATAVADDR0_Pos 12U /*!< DWT FUNCTION: DATAVADDR0 Position */ -#define DWT_FUNCTION_DATAVADDR0_Msk (0xFUL << DWT_FUNCTION_DATAVADDR0_Pos) /*!< DWT FUNCTION: DATAVADDR0 Mask */ - -#define DWT_FUNCTION_DATAVSIZE_Pos 10U /*!< DWT FUNCTION: DATAVSIZE Position */ -#define DWT_FUNCTION_DATAVSIZE_Msk (0x3UL << DWT_FUNCTION_DATAVSIZE_Pos) /*!< DWT FUNCTION: DATAVSIZE Mask */ - -#define DWT_FUNCTION_LNK1ENA_Pos 9U /*!< DWT FUNCTION: LNK1ENA Position */ -#define DWT_FUNCTION_LNK1ENA_Msk (0x1UL << DWT_FUNCTION_LNK1ENA_Pos) /*!< DWT FUNCTION: LNK1ENA Mask */ - -#define DWT_FUNCTION_DATAVMATCH_Pos 8U /*!< DWT FUNCTION: DATAVMATCH Position */ -#define DWT_FUNCTION_DATAVMATCH_Msk (0x1UL << DWT_FUNCTION_DATAVMATCH_Pos) /*!< DWT FUNCTION: DATAVMATCH Mask */ - -#define DWT_FUNCTION_CYCMATCH_Pos 7U /*!< DWT FUNCTION: CYCMATCH Position */ -#define DWT_FUNCTION_CYCMATCH_Msk (0x1UL << DWT_FUNCTION_CYCMATCH_Pos) /*!< DWT FUNCTION: CYCMATCH Mask */ - -#define DWT_FUNCTION_EMITRANGE_Pos 5U /*!< DWT FUNCTION: EMITRANGE Position */ -#define DWT_FUNCTION_EMITRANGE_Msk (0x1UL << DWT_FUNCTION_EMITRANGE_Pos) /*!< DWT FUNCTION: EMITRANGE Mask */ - -#define DWT_FUNCTION_FUNCTION_Pos 0U /*!< DWT FUNCTION: FUNCTION Position */ -#define DWT_FUNCTION_FUNCTION_Msk (0xFUL /*<< DWT_FUNCTION_FUNCTION_Pos*/) /*!< DWT FUNCTION: FUNCTION Mask */ - -/*@}*/ /* end of group CMSIS_DWT */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_TPI Trace Port Interface (TPI) - \brief Type definitions for the Trace Port Interface (TPI) - @{ - */ - -/** - \brief Structure type to access the Trace Port Interface Register (TPI). - */ -typedef struct -{ - __IM uint32_t SSPSR; /*!< Offset: 0x000 (R/ ) Supported Parallel Port Size Register */ - __IOM uint32_t CSPSR; /*!< Offset: 0x004 (R/W) Current Parallel Port Size Register */ - uint32_t RESERVED0[2U]; - __IOM uint32_t ACPR; /*!< Offset: 0x010 (R/W) Asynchronous Clock Prescaler Register */ - uint32_t RESERVED1[55U]; - __IOM uint32_t SPPR; /*!< Offset: 0x0F0 (R/W) Selected Pin Protocol Register */ - uint32_t RESERVED2[131U]; - __IM uint32_t FFSR; /*!< Offset: 0x300 (R/ ) Formatter and Flush Status Register */ - __IOM uint32_t FFCR; /*!< Offset: 0x304 (R/W) Formatter and Flush Control Register */ - __IM uint32_t FSCR; /*!< Offset: 0x308 (R/ ) Formatter Synchronization Counter Register */ - uint32_t RESERVED3[759U]; - __IM uint32_t TRIGGER; /*!< Offset: 0xEE8 (R/ ) TRIGGER Register */ - __IM uint32_t FIFO0; /*!< Offset: 0xEEC (R/ ) Integration ETM Data */ - __IM uint32_t ITATBCTR2; /*!< Offset: 0xEF0 (R/ ) ITATBCTR2 */ - uint32_t RESERVED4[1U]; - __IM uint32_t ITATBCTR0; /*!< Offset: 0xEF8 (R/ ) ITATBCTR0 */ - __IM uint32_t FIFO1; /*!< Offset: 0xEFC (R/ ) Integration ITM Data */ - __IOM uint32_t ITCTRL; /*!< Offset: 0xF00 (R/W) Integration Mode Control */ - uint32_t RESERVED5[39U]; - __IOM uint32_t CLAIMSET; /*!< Offset: 0xFA0 (R/W) Claim tag set */ - __IOM uint32_t CLAIMCLR; /*!< Offset: 0xFA4 (R/W) Claim tag clear */ - uint32_t RESERVED7[8U]; - __IM uint32_t DEVID; /*!< Offset: 0xFC8 (R/ ) TPIU_DEVID */ - __IM uint32_t DEVTYPE; /*!< Offset: 0xFCC (R/ ) TPIU_DEVTYPE */ -} TPI_Type; - -/* TPI Asynchronous Clock Prescaler Register Definitions */ -#define TPI_ACPR_PRESCALER_Pos 0U /*!< TPI ACPR: PRESCALER Position */ -#define TPI_ACPR_PRESCALER_Msk (0x1FFFUL /*<< TPI_ACPR_PRESCALER_Pos*/) /*!< TPI ACPR: PRESCALER Mask */ - -/* TPI Selected Pin Protocol Register Definitions */ -#define TPI_SPPR_TXMODE_Pos 0U /*!< TPI SPPR: TXMODE Position */ -#define TPI_SPPR_TXMODE_Msk (0x3UL /*<< TPI_SPPR_TXMODE_Pos*/) /*!< TPI SPPR: TXMODE Mask */ - -/* TPI Formatter and Flush Status Register Definitions */ -#define TPI_FFSR_FtNonStop_Pos 3U /*!< TPI FFSR: FtNonStop Position */ -#define TPI_FFSR_FtNonStop_Msk (0x1UL << TPI_FFSR_FtNonStop_Pos) /*!< TPI FFSR: FtNonStop Mask */ - -#define TPI_FFSR_TCPresent_Pos 2U /*!< TPI FFSR: TCPresent Position */ -#define TPI_FFSR_TCPresent_Msk (0x1UL << TPI_FFSR_TCPresent_Pos) /*!< TPI FFSR: TCPresent Mask */ - -#define TPI_FFSR_FtStopped_Pos 1U /*!< TPI FFSR: FtStopped Position */ -#define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */ - -#define TPI_FFSR_FlInProg_Pos 0U /*!< TPI FFSR: FlInProg Position */ -#define TPI_FFSR_FlInProg_Msk (0x1UL /*<< TPI_FFSR_FlInProg_Pos*/) /*!< TPI FFSR: FlInProg Mask */ - -/* TPI Formatter and Flush Control Register Definitions */ -#define TPI_FFCR_TrigIn_Pos 8U /*!< TPI FFCR: TrigIn Position */ -#define TPI_FFCR_TrigIn_Msk (0x1UL << TPI_FFCR_TrigIn_Pos) /*!< TPI FFCR: TrigIn Mask */ - -#define TPI_FFCR_EnFCont_Pos 1U /*!< TPI FFCR: EnFCont Position */ -#define TPI_FFCR_EnFCont_Msk (0x1UL << TPI_FFCR_EnFCont_Pos) /*!< TPI FFCR: EnFCont Mask */ - -/* TPI TRIGGER Register Definitions */ -#define TPI_TRIGGER_TRIGGER_Pos 0U /*!< TPI TRIGGER: TRIGGER Position */ -#define TPI_TRIGGER_TRIGGER_Msk (0x1UL /*<< TPI_TRIGGER_TRIGGER_Pos*/) /*!< TPI TRIGGER: TRIGGER Mask */ - -/* TPI Integration ETM Data Register Definitions (FIFO0) */ -#define TPI_FIFO0_ITM_ATVALID_Pos 29U /*!< TPI FIFO0: ITM_ATVALID Position */ -#define TPI_FIFO0_ITM_ATVALID_Msk (0x1UL << TPI_FIFO0_ITM_ATVALID_Pos) /*!< TPI FIFO0: ITM_ATVALID Mask */ - -#define TPI_FIFO0_ITM_bytecount_Pos 27U /*!< TPI FIFO0: ITM_bytecount Position */ -#define TPI_FIFO0_ITM_bytecount_Msk (0x3UL << TPI_FIFO0_ITM_bytecount_Pos) /*!< TPI FIFO0: ITM_bytecount Mask */ - -#define TPI_FIFO0_ETM_ATVALID_Pos 26U /*!< TPI FIFO0: ETM_ATVALID Position */ -#define TPI_FIFO0_ETM_ATVALID_Msk (0x1UL << TPI_FIFO0_ETM_ATVALID_Pos) /*!< TPI FIFO0: ETM_ATVALID Mask */ - -#define TPI_FIFO0_ETM_bytecount_Pos 24U /*!< TPI FIFO0: ETM_bytecount Position */ -#define TPI_FIFO0_ETM_bytecount_Msk (0x3UL << TPI_FIFO0_ETM_bytecount_Pos) /*!< TPI FIFO0: ETM_bytecount Mask */ - -#define TPI_FIFO0_ETM2_Pos 16U /*!< TPI FIFO0: ETM2 Position */ -#define TPI_FIFO0_ETM2_Msk (0xFFUL << TPI_FIFO0_ETM2_Pos) /*!< TPI FIFO0: ETM2 Mask */ - -#define TPI_FIFO0_ETM1_Pos 8U /*!< TPI FIFO0: ETM1 Position */ -#define TPI_FIFO0_ETM1_Msk (0xFFUL << TPI_FIFO0_ETM1_Pos) /*!< TPI FIFO0: ETM1 Mask */ - -#define TPI_FIFO0_ETM0_Pos 0U /*!< TPI FIFO0: ETM0 Position */ -#define TPI_FIFO0_ETM0_Msk (0xFFUL /*<< TPI_FIFO0_ETM0_Pos*/) /*!< TPI FIFO0: ETM0 Mask */ - -/* TPI ITATBCTR2 Register Definitions */ -#define TPI_ITATBCTR2_ATREADY2_Pos 0U /*!< TPI ITATBCTR2: ATREADY2 Position */ -#define TPI_ITATBCTR2_ATREADY2_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY2_Pos*/) /*!< TPI ITATBCTR2: ATREADY2 Mask */ - -#define TPI_ITATBCTR2_ATREADY1_Pos 0U /*!< TPI ITATBCTR2: ATREADY1 Position */ -#define TPI_ITATBCTR2_ATREADY1_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY1_Pos*/) /*!< TPI ITATBCTR2: ATREADY1 Mask */ - -/* TPI Integration ITM Data Register Definitions (FIFO1) */ -#define TPI_FIFO1_ITM_ATVALID_Pos 29U /*!< TPI FIFO1: ITM_ATVALID Position */ -#define TPI_FIFO1_ITM_ATVALID_Msk (0x1UL << TPI_FIFO1_ITM_ATVALID_Pos) /*!< TPI FIFO1: ITM_ATVALID Mask */ - -#define TPI_FIFO1_ITM_bytecount_Pos 27U /*!< TPI FIFO1: ITM_bytecount Position */ -#define TPI_FIFO1_ITM_bytecount_Msk (0x3UL << TPI_FIFO1_ITM_bytecount_Pos) /*!< TPI FIFO1: ITM_bytecount Mask */ - -#define TPI_FIFO1_ETM_ATVALID_Pos 26U /*!< TPI FIFO1: ETM_ATVALID Position */ -#define TPI_FIFO1_ETM_ATVALID_Msk (0x1UL << TPI_FIFO1_ETM_ATVALID_Pos) /*!< TPI FIFO1: ETM_ATVALID Mask */ - -#define TPI_FIFO1_ETM_bytecount_Pos 24U /*!< TPI FIFO1: ETM_bytecount Position */ -#define TPI_FIFO1_ETM_bytecount_Msk (0x3UL << TPI_FIFO1_ETM_bytecount_Pos) /*!< TPI FIFO1: ETM_bytecount Mask */ - -#define TPI_FIFO1_ITM2_Pos 16U /*!< TPI FIFO1: ITM2 Position */ -#define TPI_FIFO1_ITM2_Msk (0xFFUL << TPI_FIFO1_ITM2_Pos) /*!< TPI FIFO1: ITM2 Mask */ - -#define TPI_FIFO1_ITM1_Pos 8U /*!< TPI FIFO1: ITM1 Position */ -#define TPI_FIFO1_ITM1_Msk (0xFFUL << TPI_FIFO1_ITM1_Pos) /*!< TPI FIFO1: ITM1 Mask */ - -#define TPI_FIFO1_ITM0_Pos 0U /*!< TPI FIFO1: ITM0 Position */ -#define TPI_FIFO1_ITM0_Msk (0xFFUL /*<< TPI_FIFO1_ITM0_Pos*/) /*!< TPI FIFO1: ITM0 Mask */ - -/* TPI ITATBCTR0 Register Definitions */ -#define TPI_ITATBCTR0_ATREADY2_Pos 0U /*!< TPI ITATBCTR0: ATREADY2 Position */ -#define TPI_ITATBCTR0_ATREADY2_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY2_Pos*/) /*!< TPI ITATBCTR0: ATREADY2 Mask */ - -#define TPI_ITATBCTR0_ATREADY1_Pos 0U /*!< TPI ITATBCTR0: ATREADY1 Position */ -#define TPI_ITATBCTR0_ATREADY1_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY1_Pos*/) /*!< TPI ITATBCTR0: ATREADY1 Mask */ - -/* TPI Integration Mode Control Register Definitions */ -#define TPI_ITCTRL_Mode_Pos 0U /*!< TPI ITCTRL: Mode Position */ -#define TPI_ITCTRL_Mode_Msk (0x3UL /*<< TPI_ITCTRL_Mode_Pos*/) /*!< TPI ITCTRL: Mode Mask */ - -/* TPI DEVID Register Definitions */ -#define TPI_DEVID_NRZVALID_Pos 11U /*!< TPI DEVID: NRZVALID Position */ -#define TPI_DEVID_NRZVALID_Msk (0x1UL << TPI_DEVID_NRZVALID_Pos) /*!< TPI DEVID: NRZVALID Mask */ - -#define TPI_DEVID_MANCVALID_Pos 10U /*!< TPI DEVID: MANCVALID Position */ -#define TPI_DEVID_MANCVALID_Msk (0x1UL << TPI_DEVID_MANCVALID_Pos) /*!< TPI DEVID: MANCVALID Mask */ - -#define TPI_DEVID_PTINVALID_Pos 9U /*!< TPI DEVID: PTINVALID Position */ -#define TPI_DEVID_PTINVALID_Msk (0x1UL << TPI_DEVID_PTINVALID_Pos) /*!< TPI DEVID: PTINVALID Mask */ - -#define TPI_DEVID_MinBufSz_Pos 6U /*!< TPI DEVID: MinBufSz Position */ -#define TPI_DEVID_MinBufSz_Msk (0x7UL << TPI_DEVID_MinBufSz_Pos) /*!< TPI DEVID: MinBufSz Mask */ - -#define TPI_DEVID_AsynClkIn_Pos 5U /*!< TPI DEVID: AsynClkIn Position */ -#define TPI_DEVID_AsynClkIn_Msk (0x1UL << TPI_DEVID_AsynClkIn_Pos) /*!< TPI DEVID: AsynClkIn Mask */ - -#define TPI_DEVID_NrTraceInput_Pos 0U /*!< TPI DEVID: NrTraceInput Position */ -#define TPI_DEVID_NrTraceInput_Msk (0x1FUL /*<< TPI_DEVID_NrTraceInput_Pos*/) /*!< TPI DEVID: NrTraceInput Mask */ - -/* TPI DEVTYPE Register Definitions */ -#define TPI_DEVTYPE_SubType_Pos 4U /*!< TPI DEVTYPE: SubType Position */ -#define TPI_DEVTYPE_SubType_Msk (0xFUL /*<< TPI_DEVTYPE_SubType_Pos*/) /*!< TPI DEVTYPE: SubType Mask */ - -#define TPI_DEVTYPE_MajorType_Pos 0U /*!< TPI DEVTYPE: MajorType Position */ -#define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */ - -/*@}*/ /* end of group CMSIS_TPI */ - - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_MPU Memory Protection Unit (MPU) - \brief Type definitions for the Memory Protection Unit (MPU) - @{ - */ - -/** - \brief Structure type to access the Memory Protection Unit (MPU). - */ -typedef struct -{ - __IM uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */ - __IOM uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */ - __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region RNRber Register */ - __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */ - __IOM uint32_t RASR; /*!< Offset: 0x010 (R/W) MPU Region Attribute and Size Register */ - __IOM uint32_t RBAR_A1; /*!< Offset: 0x014 (R/W) MPU Alias 1 Region Base Address Register */ - __IOM uint32_t RASR_A1; /*!< Offset: 0x018 (R/W) MPU Alias 1 Region Attribute and Size Register */ - __IOM uint32_t RBAR_A2; /*!< Offset: 0x01C (R/W) MPU Alias 2 Region Base Address Register */ - __IOM uint32_t RASR_A2; /*!< Offset: 0x020 (R/W) MPU Alias 2 Region Attribute and Size Register */ - __IOM uint32_t RBAR_A3; /*!< Offset: 0x024 (R/W) MPU Alias 3 Region Base Address Register */ - __IOM uint32_t RASR_A3; /*!< Offset: 0x028 (R/W) MPU Alias 3 Region Attribute and Size Register */ -} MPU_Type; - -#define MPU_TYPE_RALIASES 4U - -/* MPU Type Register Definitions */ -#define MPU_TYPE_IREGION_Pos 16U /*!< MPU TYPE: IREGION Position */ -#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ - -#define MPU_TYPE_DREGION_Pos 8U /*!< MPU TYPE: DREGION Position */ -#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ - -#define MPU_TYPE_SEPARATE_Pos 0U /*!< MPU TYPE: SEPARATE Position */ -#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */ - -/* MPU Control Register Definitions */ -#define MPU_CTRL_PRIVDEFENA_Pos 2U /*!< MPU CTRL: PRIVDEFENA Position */ -#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ - -#define MPU_CTRL_HFNMIENA_Pos 1U /*!< MPU CTRL: HFNMIENA Position */ -#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ - -#define MPU_CTRL_ENABLE_Pos 0U /*!< MPU CTRL: ENABLE Position */ -#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */ - -/* MPU Region Number Register Definitions */ -#define MPU_RNR_REGION_Pos 0U /*!< MPU RNR: REGION Position */ -#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */ - -/* MPU Region Base Address Register Definitions */ -#define MPU_RBAR_ADDR_Pos 5U /*!< MPU RBAR: ADDR Position */ -#define MPU_RBAR_ADDR_Msk (0x7FFFFFFUL << MPU_RBAR_ADDR_Pos) /*!< MPU RBAR: ADDR Mask */ - -#define MPU_RBAR_VALID_Pos 4U /*!< MPU RBAR: VALID Position */ -#define MPU_RBAR_VALID_Msk (1UL << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */ - -#define MPU_RBAR_REGION_Pos 0U /*!< MPU RBAR: REGION Position */ -#define MPU_RBAR_REGION_Msk (0xFUL /*<< MPU_RBAR_REGION_Pos*/) /*!< MPU RBAR: REGION Mask */ - -/* MPU Region Attribute and Size Register Definitions */ -#define MPU_RASR_ATTRS_Pos 16U /*!< MPU RASR: MPU Region Attribute field Position */ -#define MPU_RASR_ATTRS_Msk (0xFFFFUL << MPU_RASR_ATTRS_Pos) /*!< MPU RASR: MPU Region Attribute field Mask */ - -#define MPU_RASR_XN_Pos 28U /*!< MPU RASR: ATTRS.XN Position */ -#define MPU_RASR_XN_Msk (1UL << MPU_RASR_XN_Pos) /*!< MPU RASR: ATTRS.XN Mask */ - -#define MPU_RASR_AP_Pos 24U /*!< MPU RASR: ATTRS.AP Position */ -#define MPU_RASR_AP_Msk (0x7UL << MPU_RASR_AP_Pos) /*!< MPU RASR: ATTRS.AP Mask */ - -#define MPU_RASR_TEX_Pos 19U /*!< MPU RASR: ATTRS.TEX Position */ -#define MPU_RASR_TEX_Msk (0x7UL << MPU_RASR_TEX_Pos) /*!< MPU RASR: ATTRS.TEX Mask */ - -#define MPU_RASR_S_Pos 18U /*!< MPU RASR: ATTRS.S Position */ -#define MPU_RASR_S_Msk (1UL << MPU_RASR_S_Pos) /*!< MPU RASR: ATTRS.S Mask */ - -#define MPU_RASR_C_Pos 17U /*!< MPU RASR: ATTRS.C Position */ -#define MPU_RASR_C_Msk (1UL << MPU_RASR_C_Pos) /*!< MPU RASR: ATTRS.C Mask */ - -#define MPU_RASR_B_Pos 16U /*!< MPU RASR: ATTRS.B Position */ -#define MPU_RASR_B_Msk (1UL << MPU_RASR_B_Pos) /*!< MPU RASR: ATTRS.B Mask */ - -#define MPU_RASR_SRD_Pos 8U /*!< MPU RASR: Sub-Region Disable Position */ -#define MPU_RASR_SRD_Msk (0xFFUL << MPU_RASR_SRD_Pos) /*!< MPU RASR: Sub-Region Disable Mask */ - -#define MPU_RASR_SIZE_Pos 1U /*!< MPU RASR: Region Size Field Position */ -#define MPU_RASR_SIZE_Msk (0x1FUL << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */ - -#define MPU_RASR_ENABLE_Pos 0U /*!< MPU RASR: Region enable bit Position */ -#define MPU_RASR_ENABLE_Msk (1UL /*<< MPU_RASR_ENABLE_Pos*/) /*!< MPU RASR: Region enable bit Disable Mask */ - -/*@} end of group CMSIS_MPU */ -#endif /* defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_FPU Floating Point Unit (FPU) - \brief Type definitions for the Floating Point Unit (FPU) - @{ - */ - -/** - \brief Structure type to access the Floating Point Unit (FPU). - */ -typedef struct -{ - uint32_t RESERVED0[1U]; - __IOM uint32_t FPCCR; /*!< Offset: 0x004 (R/W) Floating-Point Context Control Register */ - __IOM uint32_t FPCAR; /*!< Offset: 0x008 (R/W) Floating-Point Context Address Register */ - __IOM uint32_t FPDSCR; /*!< Offset: 0x00C (R/W) Floating-Point Default Status Control Register */ - __IM uint32_t MVFR0; /*!< Offset: 0x010 (R/ ) Media and FP Feature Register 0 */ - __IM uint32_t MVFR1; /*!< Offset: 0x014 (R/ ) Media and FP Feature Register 1 */ - __IM uint32_t MVFR2; /*!< Offset: 0x018 (R/ ) Media and FP Feature Register 2 */ -} FPU_Type; - -/* Floating-Point Context Control Register Definitions */ -#define FPU_FPCCR_ASPEN_Pos 31U /*!< FPCCR: ASPEN bit Position */ -#define FPU_FPCCR_ASPEN_Msk (1UL << FPU_FPCCR_ASPEN_Pos) /*!< FPCCR: ASPEN bit Mask */ - -#define FPU_FPCCR_LSPEN_Pos 30U /*!< FPCCR: LSPEN Position */ -#define FPU_FPCCR_LSPEN_Msk (1UL << FPU_FPCCR_LSPEN_Pos) /*!< FPCCR: LSPEN bit Mask */ - -#define FPU_FPCCR_MONRDY_Pos 8U /*!< FPCCR: MONRDY Position */ -#define FPU_FPCCR_MONRDY_Msk (1UL << FPU_FPCCR_MONRDY_Pos) /*!< FPCCR: MONRDY bit Mask */ - -#define FPU_FPCCR_BFRDY_Pos 6U /*!< FPCCR: BFRDY Position */ -#define FPU_FPCCR_BFRDY_Msk (1UL << FPU_FPCCR_BFRDY_Pos) /*!< FPCCR: BFRDY bit Mask */ - -#define FPU_FPCCR_MMRDY_Pos 5U /*!< FPCCR: MMRDY Position */ -#define FPU_FPCCR_MMRDY_Msk (1UL << FPU_FPCCR_MMRDY_Pos) /*!< FPCCR: MMRDY bit Mask */ - -#define FPU_FPCCR_HFRDY_Pos 4U /*!< FPCCR: HFRDY Position */ -#define FPU_FPCCR_HFRDY_Msk (1UL << FPU_FPCCR_HFRDY_Pos) /*!< FPCCR: HFRDY bit Mask */ - -#define FPU_FPCCR_THREAD_Pos 3U /*!< FPCCR: processor mode bit Position */ -#define FPU_FPCCR_THREAD_Msk (1UL << FPU_FPCCR_THREAD_Pos) /*!< FPCCR: processor mode active bit Mask */ - -#define FPU_FPCCR_USER_Pos 1U /*!< FPCCR: privilege level bit Position */ -#define FPU_FPCCR_USER_Msk (1UL << FPU_FPCCR_USER_Pos) /*!< FPCCR: privilege level bit Mask */ - -#define FPU_FPCCR_LSPACT_Pos 0U /*!< FPCCR: Lazy state preservation active bit Position */ -#define FPU_FPCCR_LSPACT_Msk (1UL /*<< FPU_FPCCR_LSPACT_Pos*/) /*!< FPCCR: Lazy state preservation active bit Mask */ - -/* Floating-Point Context Address Register Definitions */ -#define FPU_FPCAR_ADDRESS_Pos 3U /*!< FPCAR: ADDRESS bit Position */ -#define FPU_FPCAR_ADDRESS_Msk (0x1FFFFFFFUL << FPU_FPCAR_ADDRESS_Pos) /*!< FPCAR: ADDRESS bit Mask */ - -/* Floating-Point Default Status Control Register Definitions */ -#define FPU_FPDSCR_AHP_Pos 26U /*!< FPDSCR: AHP bit Position */ -#define FPU_FPDSCR_AHP_Msk (1UL << FPU_FPDSCR_AHP_Pos) /*!< FPDSCR: AHP bit Mask */ - -#define FPU_FPDSCR_DN_Pos 25U /*!< FPDSCR: DN bit Position */ -#define FPU_FPDSCR_DN_Msk (1UL << FPU_FPDSCR_DN_Pos) /*!< FPDSCR: DN bit Mask */ - -#define FPU_FPDSCR_FZ_Pos 24U /*!< FPDSCR: FZ bit Position */ -#define FPU_FPDSCR_FZ_Msk (1UL << FPU_FPDSCR_FZ_Pos) /*!< FPDSCR: FZ bit Mask */ - -#define FPU_FPDSCR_RMode_Pos 22U /*!< FPDSCR: RMode bit Position */ -#define FPU_FPDSCR_RMode_Msk (3UL << FPU_FPDSCR_RMode_Pos) /*!< FPDSCR: RMode bit Mask */ - -/* Media and FP Feature Register 0 Definitions */ -#define FPU_MVFR0_FP_rounding_modes_Pos 28U /*!< MVFR0: FP rounding modes bits Position */ -#define FPU_MVFR0_FP_rounding_modes_Msk (0xFUL << FPU_MVFR0_FP_rounding_modes_Pos) /*!< MVFR0: FP rounding modes bits Mask */ - -#define FPU_MVFR0_Short_vectors_Pos 24U /*!< MVFR0: Short vectors bits Position */ -#define FPU_MVFR0_Short_vectors_Msk (0xFUL << FPU_MVFR0_Short_vectors_Pos) /*!< MVFR0: Short vectors bits Mask */ - -#define FPU_MVFR0_Square_root_Pos 20U /*!< MVFR0: Square root bits Position */ -#define FPU_MVFR0_Square_root_Msk (0xFUL << FPU_MVFR0_Square_root_Pos) /*!< MVFR0: Square root bits Mask */ - -#define FPU_MVFR0_Divide_Pos 16U /*!< MVFR0: Divide bits Position */ -#define FPU_MVFR0_Divide_Msk (0xFUL << FPU_MVFR0_Divide_Pos) /*!< MVFR0: Divide bits Mask */ - -#define FPU_MVFR0_FP_excep_trapping_Pos 12U /*!< MVFR0: FP exception trapping bits Position */ -#define FPU_MVFR0_FP_excep_trapping_Msk (0xFUL << FPU_MVFR0_FP_excep_trapping_Pos) /*!< MVFR0: FP exception trapping bits Mask */ - -#define FPU_MVFR0_Double_precision_Pos 8U /*!< MVFR0: Double-precision bits Position */ -#define FPU_MVFR0_Double_precision_Msk (0xFUL << FPU_MVFR0_Double_precision_Pos) /*!< MVFR0: Double-precision bits Mask */ - -#define FPU_MVFR0_Single_precision_Pos 4U /*!< MVFR0: Single-precision bits Position */ -#define FPU_MVFR0_Single_precision_Msk (0xFUL << FPU_MVFR0_Single_precision_Pos) /*!< MVFR0: Single-precision bits Mask */ - -#define FPU_MVFR0_A_SIMD_registers_Pos 0U /*!< MVFR0: A_SIMD registers bits Position */ -#define FPU_MVFR0_A_SIMD_registers_Msk (0xFUL /*<< FPU_MVFR0_A_SIMD_registers_Pos*/) /*!< MVFR0: A_SIMD registers bits Mask */ - -/* Media and FP Feature Register 1 Definitions */ -#define FPU_MVFR1_FP_fused_MAC_Pos 28U /*!< MVFR1: FP fused MAC bits Position */ -#define FPU_MVFR1_FP_fused_MAC_Msk (0xFUL << FPU_MVFR1_FP_fused_MAC_Pos) /*!< MVFR1: FP fused MAC bits Mask */ - -#define FPU_MVFR1_FP_HPFP_Pos 24U /*!< MVFR1: FP HPFP bits Position */ -#define FPU_MVFR1_FP_HPFP_Msk (0xFUL << FPU_MVFR1_FP_HPFP_Pos) /*!< MVFR1: FP HPFP bits Mask */ - -#define FPU_MVFR1_D_NaN_mode_Pos 4U /*!< MVFR1: D_NaN mode bits Position */ -#define FPU_MVFR1_D_NaN_mode_Msk (0xFUL << FPU_MVFR1_D_NaN_mode_Pos) /*!< MVFR1: D_NaN mode bits Mask */ - -#define FPU_MVFR1_FtZ_mode_Pos 0U /*!< MVFR1: FtZ mode bits Position */ -#define FPU_MVFR1_FtZ_mode_Msk (0xFUL /*<< FPU_MVFR1_FtZ_mode_Pos*/) /*!< MVFR1: FtZ mode bits Mask */ - -/* Media and FP Feature Register 2 Definitions */ - -#define FPU_MVFR2_VFP_Misc_Pos 4U /*!< MVFR2: VFP Misc bits Position */ -#define FPU_MVFR2_VFP_Misc_Msk (0xFUL << FPU_MVFR2_VFP_Misc_Pos) /*!< MVFR2: VFP Misc bits Mask */ - -/*@} end of group CMSIS_FPU */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug) - \brief Type definitions for the Core Debug Registers - @{ - */ - -/** - \brief Structure type to access the Core Debug Register (CoreDebug). - */ -typedef struct -{ - __IOM uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */ - __OM uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */ - __IOM uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */ - __IOM uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */ -} CoreDebug_Type; - -/* Debug Halting Control and Status Register Definitions */ -#define CoreDebug_DHCSR_DBGKEY_Pos 16U /*!< CoreDebug DHCSR: DBGKEY Position */ -#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */ - -#define CoreDebug_DHCSR_S_RESET_ST_Pos 25U /*!< CoreDebug DHCSR: S_RESET_ST Position */ -#define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */ - -#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24U /*!< CoreDebug DHCSR: S_RETIRE_ST Position */ -#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */ - -#define CoreDebug_DHCSR_S_LOCKUP_Pos 19U /*!< CoreDebug DHCSR: S_LOCKUP Position */ -#define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */ - -#define CoreDebug_DHCSR_S_SLEEP_Pos 18U /*!< CoreDebug DHCSR: S_SLEEP Position */ -#define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */ - -#define CoreDebug_DHCSR_S_HALT_Pos 17U /*!< CoreDebug DHCSR: S_HALT Position */ -#define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */ - -#define CoreDebug_DHCSR_S_REGRDY_Pos 16U /*!< CoreDebug DHCSR: S_REGRDY Position */ -#define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */ - -#define CoreDebug_DHCSR_C_SNAPSTALL_Pos 5U /*!< CoreDebug DHCSR: C_SNAPSTALL Position */ -#define CoreDebug_DHCSR_C_SNAPSTALL_Msk (1UL << CoreDebug_DHCSR_C_SNAPSTALL_Pos) /*!< CoreDebug DHCSR: C_SNAPSTALL Mask */ - -#define CoreDebug_DHCSR_C_MASKINTS_Pos 3U /*!< CoreDebug DHCSR: C_MASKINTS Position */ -#define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */ - -#define CoreDebug_DHCSR_C_STEP_Pos 2U /*!< CoreDebug DHCSR: C_STEP Position */ -#define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */ - -#define CoreDebug_DHCSR_C_HALT_Pos 1U /*!< CoreDebug DHCSR: C_HALT Position */ -#define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */ - -#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0U /*!< CoreDebug DHCSR: C_DEBUGEN Position */ -#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL /*<< CoreDebug_DHCSR_C_DEBUGEN_Pos*/) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ - -/* Debug Core Register Selector Register Definitions */ -#define CoreDebug_DCRSR_REGWnR_Pos 16U /*!< CoreDebug DCRSR: REGWnR Position */ -#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */ - -#define CoreDebug_DCRSR_REGSEL_Pos 0U /*!< CoreDebug DCRSR: REGSEL Position */ -#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL /*<< CoreDebug_DCRSR_REGSEL_Pos*/) /*!< CoreDebug DCRSR: REGSEL Mask */ - -/* Debug Exception and Monitor Control Register Definitions */ -#define CoreDebug_DEMCR_TRCENA_Pos 24U /*!< CoreDebug DEMCR: TRCENA Position */ -#define CoreDebug_DEMCR_TRCENA_Msk (1UL << CoreDebug_DEMCR_TRCENA_Pos) /*!< CoreDebug DEMCR: TRCENA Mask */ - -#define CoreDebug_DEMCR_MON_REQ_Pos 19U /*!< CoreDebug DEMCR: MON_REQ Position */ -#define CoreDebug_DEMCR_MON_REQ_Msk (1UL << CoreDebug_DEMCR_MON_REQ_Pos) /*!< CoreDebug DEMCR: MON_REQ Mask */ - -#define CoreDebug_DEMCR_MON_STEP_Pos 18U /*!< CoreDebug DEMCR: MON_STEP Position */ -#define CoreDebug_DEMCR_MON_STEP_Msk (1UL << CoreDebug_DEMCR_MON_STEP_Pos) /*!< CoreDebug DEMCR: MON_STEP Mask */ - -#define CoreDebug_DEMCR_MON_PEND_Pos 17U /*!< CoreDebug DEMCR: MON_PEND Position */ -#define CoreDebug_DEMCR_MON_PEND_Msk (1UL << CoreDebug_DEMCR_MON_PEND_Pos) /*!< CoreDebug DEMCR: MON_PEND Mask */ - -#define CoreDebug_DEMCR_MON_EN_Pos 16U /*!< CoreDebug DEMCR: MON_EN Position */ -#define CoreDebug_DEMCR_MON_EN_Msk (1UL << CoreDebug_DEMCR_MON_EN_Pos) /*!< CoreDebug DEMCR: MON_EN Mask */ - -#define CoreDebug_DEMCR_VC_HARDERR_Pos 10U /*!< CoreDebug DEMCR: VC_HARDERR Position */ -#define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */ - -#define CoreDebug_DEMCR_VC_INTERR_Pos 9U /*!< CoreDebug DEMCR: VC_INTERR Position */ -#define CoreDebug_DEMCR_VC_INTERR_Msk (1UL << CoreDebug_DEMCR_VC_INTERR_Pos) /*!< CoreDebug DEMCR: VC_INTERR Mask */ - -#define CoreDebug_DEMCR_VC_BUSERR_Pos 8U /*!< CoreDebug DEMCR: VC_BUSERR Position */ -#define CoreDebug_DEMCR_VC_BUSERR_Msk (1UL << CoreDebug_DEMCR_VC_BUSERR_Pos) /*!< CoreDebug DEMCR: VC_BUSERR Mask */ - -#define CoreDebug_DEMCR_VC_STATERR_Pos 7U /*!< CoreDebug DEMCR: VC_STATERR Position */ -#define CoreDebug_DEMCR_VC_STATERR_Msk (1UL << CoreDebug_DEMCR_VC_STATERR_Pos) /*!< CoreDebug DEMCR: VC_STATERR Mask */ - -#define CoreDebug_DEMCR_VC_CHKERR_Pos 6U /*!< CoreDebug DEMCR: VC_CHKERR Position */ -#define CoreDebug_DEMCR_VC_CHKERR_Msk (1UL << CoreDebug_DEMCR_VC_CHKERR_Pos) /*!< CoreDebug DEMCR: VC_CHKERR Mask */ - -#define CoreDebug_DEMCR_VC_NOCPERR_Pos 5U /*!< CoreDebug DEMCR: VC_NOCPERR Position */ -#define CoreDebug_DEMCR_VC_NOCPERR_Msk (1UL << CoreDebug_DEMCR_VC_NOCPERR_Pos) /*!< CoreDebug DEMCR: VC_NOCPERR Mask */ - -#define CoreDebug_DEMCR_VC_MMERR_Pos 4U /*!< CoreDebug DEMCR: VC_MMERR Position */ -#define CoreDebug_DEMCR_VC_MMERR_Msk (1UL << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */ - -#define CoreDebug_DEMCR_VC_CORERESET_Pos 0U /*!< CoreDebug DEMCR: VC_CORERESET Position */ -#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL /*<< CoreDebug_DEMCR_VC_CORERESET_Pos*/) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ - -/*@} end of group CMSIS_CoreDebug */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_bitfield Core register bit field macros - \brief Macros for use with bit field definitions (xxx_Pos, xxx_Msk). - @{ - */ - -/** - \brief Mask and shift a bit field value for use in a register bit range. - \param[in] field Name of the register bit field. - \param[in] value Value of the bit field. This parameter is interpreted as an uint32_t type. - \return Masked and shifted value. -*/ -#define _VAL2FLD(field, value) (((uint32_t)(value) << field ## _Pos) & field ## _Msk) - -/** - \brief Mask and shift a register value to extract a bit filed value. - \param[in] field Name of the register bit field. - \param[in] value Value of register. This parameter is interpreted as an uint32_t type. - \return Masked and shifted bit field value. -*/ -#define _FLD2VAL(field, value) (((uint32_t)(value) & field ## _Msk) >> field ## _Pos) - -/*@} end of group CMSIS_core_bitfield */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_base Core Definitions - \brief Definitions for base addresses, unions, and structures. - @{ - */ - -/* Memory mapping of Core Hardware */ -#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ -#define ITM_BASE (0xE0000000UL) /*!< ITM Base Address */ -#define DWT_BASE (0xE0001000UL) /*!< DWT Base Address */ -#define TPI_BASE (0xE0040000UL) /*!< TPI Base Address */ -#define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug Base Address */ -#define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ -#define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ -#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ - -#define SCnSCB ((SCnSCB_Type *) SCS_BASE ) /*!< System control Register not in SCB */ -#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ -#define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ -#define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ -#define ITM ((ITM_Type *) ITM_BASE ) /*!< ITM configuration struct */ -#define DWT ((DWT_Type *) DWT_BASE ) /*!< DWT configuration struct */ -#define TPI ((TPI_Type *) TPI_BASE ) /*!< TPI configuration struct */ -#define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE) /*!< Core Debug configuration struct */ - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */ - #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */ -#endif - -#define FPU_BASE (SCS_BASE + 0x0F30UL) /*!< Floating Point Unit */ -#define FPU ((FPU_Type *) FPU_BASE ) /*!< Floating Point Unit */ - -/*@} */ - - - -/******************************************************************************* - * Hardware Abstraction Layer - Core Function Interface contains: - - Core NVIC Functions - - Core SysTick Functions - - Core Debug Functions - - Core Register Access Functions - ******************************************************************************/ -/** - \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference -*/ - - - -/* ########################## NVIC functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_NVICFunctions NVIC Functions - \brief Functions that manage interrupts and exceptions via the NVIC. - @{ - */ - -#ifdef CMSIS_NVIC_VIRTUAL - #ifndef CMSIS_NVIC_VIRTUAL_HEADER_FILE - #define CMSIS_NVIC_VIRTUAL_HEADER_FILE "cmsis_nvic_virtual.h" - #endif - #include CMSIS_NVIC_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetPriorityGrouping __NVIC_SetPriorityGrouping - #define NVIC_GetPriorityGrouping __NVIC_GetPriorityGrouping - #define NVIC_EnableIRQ __NVIC_EnableIRQ - #define NVIC_GetEnableIRQ __NVIC_GetEnableIRQ - #define NVIC_DisableIRQ __NVIC_DisableIRQ - #define NVIC_GetPendingIRQ __NVIC_GetPendingIRQ - #define NVIC_SetPendingIRQ __NVIC_SetPendingIRQ - #define NVIC_ClearPendingIRQ __NVIC_ClearPendingIRQ - #define NVIC_GetActive __NVIC_GetActive - #define NVIC_SetPriority __NVIC_SetPriority - #define NVIC_GetPriority __NVIC_GetPriority - #define NVIC_SystemReset __NVIC_SystemReset -#endif /* CMSIS_NVIC_VIRTUAL */ - -#ifdef CMSIS_VECTAB_VIRTUAL - #ifndef CMSIS_VECTAB_VIRTUAL_HEADER_FILE - #define CMSIS_VECTAB_VIRTUAL_HEADER_FILE "cmsis_vectab_virtual.h" - #endif - #include CMSIS_VECTAB_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetVector __NVIC_SetVector - #define NVIC_GetVector __NVIC_GetVector -#endif /* (CMSIS_VECTAB_VIRTUAL) */ - -#define NVIC_USER_IRQ_OFFSET 16 - - -/* The following EXC_RETURN values are saved the LR on exception entry */ -#define EXC_RETURN_HANDLER (0xFFFFFFF1UL) /* return to Handler mode, uses MSP after return */ -#define EXC_RETURN_THREAD_MSP (0xFFFFFFF9UL) /* return to Thread mode, uses MSP after return */ -#define EXC_RETURN_THREAD_PSP (0xFFFFFFFDUL) /* return to Thread mode, uses PSP after return */ -#define EXC_RETURN_HANDLER_FPU (0xFFFFFFE1UL) /* return to Handler mode, uses MSP after return, restore floating-point state */ -#define EXC_RETURN_THREAD_MSP_FPU (0xFFFFFFE9UL) /* return to Thread mode, uses MSP after return, restore floating-point state */ -#define EXC_RETURN_THREAD_PSP_FPU (0xFFFFFFEDUL) /* return to Thread mode, uses PSP after return, restore floating-point state */ - - -/** - \brief Set Priority Grouping - \details Sets the priority grouping field using the required unlock sequence. - The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field. - Only values from 0..7 are used. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Priority grouping field. - */ -__STATIC_INLINE void __NVIC_SetPriorityGrouping(uint32_t PriorityGroup) -{ - uint32_t reg_value; - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - - reg_value = SCB->AIRCR; /* read old register configuration */ - reg_value &= ~((uint32_t)(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk)); /* clear bits to change */ - reg_value = (reg_value | - ((uint32_t)0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - (PriorityGroupTmp << SCB_AIRCR_PRIGROUP_Pos) ); /* Insert write key and priority group */ - SCB->AIRCR = reg_value; -} - - -/** - \brief Get Priority Grouping - \details Reads the priority grouping field from the NVIC Interrupt Controller. - \return Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field). - */ -__STATIC_INLINE uint32_t __NVIC_GetPriorityGrouping(void) -{ - return ((uint32_t)((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos)); -} - - -/** - \brief Enable Interrupt - \details Enables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_EnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - __COMPILER_BARRIER(); - NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - __COMPILER_BARRIER(); - } -} - - -/** - \brief Get Interrupt Enable status - \details Returns a device specific interrupt enable status from the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt is not enabled. - \return 1 Interrupt is enabled. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetEnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Disable Interrupt - \details Disables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_DisableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - __DSB(); - __ISB(); - } -} - - -/** - \brief Get Pending Interrupt - \details Reads the NVIC pending register and returns the pending bit for the specified device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not pending. - \return 1 Interrupt status is pending. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Pending Interrupt - \details Sets the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_SetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Clear Pending Interrupt - \details Clears the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_ClearPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Active Interrupt - \details Reads the active register in the NVIC and returns the active bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not active. - \return 1 Interrupt status is active. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetActive(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Interrupt Priority - \details Sets the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \param [in] priority Priority to set. - \note The priority cannot be set for every processor exception. - */ -__STATIC_INLINE void __NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->IP[((uint32_t)IRQn)] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); - } - else - { - SCB->SHP[(((uint32_t)IRQn) & 0xFUL)-4UL] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); - } -} - - -/** - \brief Get Interrupt Priority - \details Reads the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Interrupt Priority. - Value is aligned automatically to the implemented priority bits of the microcontroller. - */ -__STATIC_INLINE uint32_t __NVIC_GetPriority(IRQn_Type IRQn) -{ - - if ((int32_t)(IRQn) >= 0) - { - return(((uint32_t)NVIC->IP[((uint32_t)IRQn)] >> (8U - __NVIC_PRIO_BITS))); - } - else - { - return(((uint32_t)SCB->SHP[(((uint32_t)IRQn) & 0xFUL)-4UL] >> (8U - __NVIC_PRIO_BITS))); - } -} - - -/** - \brief Encode Priority - \details Encodes the priority for an interrupt with the given priority group, - preemptive priority value, and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Used priority group. - \param [in] PreemptPriority Preemptive priority value (starting from 0). - \param [in] SubPriority Subpriority value (starting from 0). - \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority(). - */ -__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - return ( - ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | - ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) - ); -} - - -/** - \brief Decode Priority - \details Decodes an interrupt priority value with a given priority group to - preemptive priority value and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. - \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority(). - \param [in] PriorityGroup Used priority group. - \param [out] pPreemptPriority Preemptive priority value (starting from 0). - \param [out] pSubPriority Subpriority value (starting from 0). - */ -__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* const pPreemptPriority, uint32_t* const pSubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL); - *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL); -} - - -/** - \brief Set Interrupt Vector - \details Sets an interrupt vector in SRAM based interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - VTOR must been relocated to SRAM before. - \param [in] IRQn Interrupt number - \param [in] vector Address of interrupt handler function - */ -__STATIC_INLINE void __NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) -{ - uint32_t vectors = (uint32_t )SCB->VTOR; - (* (int *) (vectors + ((int32_t)IRQn + NVIC_USER_IRQ_OFFSET) * 4)) = vector; - /* ARM Application Note 321 states that the M4 does not require the architectural barrier */ -} - - -/** - \brief Get Interrupt Vector - \details Reads an interrupt vector from interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Address of interrupt handler function - */ -__STATIC_INLINE uint32_t __NVIC_GetVector(IRQn_Type IRQn) -{ - uint32_t vectors = (uint32_t )SCB->VTOR; - return (uint32_t)(* (int *) (vectors + ((int32_t)IRQn + NVIC_USER_IRQ_OFFSET) * 4)); -} - - -/** - \brief System Reset - \details Initiates a system reset request to reset the MCU. - */ -__NO_RETURN __STATIC_INLINE void __NVIC_SystemReset(void) -{ - __DSB(); /* Ensure all outstanding memory accesses included - buffered write are completed before reset */ - SCB->AIRCR = (uint32_t)((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) | - SCB_AIRCR_SYSRESETREQ_Msk ); /* Keep priority group unchanged */ - __DSB(); /* Ensure completion of memory access */ - - for(;;) /* wait until reset */ - { - __NOP(); - } -} - -/*@} end of CMSIS_Core_NVICFunctions */ - - -/* ########################## MPU functions #################################### */ - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - -#include "mpu_armv7.h" - -#endif - - -/* ########################## FPU functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_FpuFunctions FPU Functions - \brief Function that provides FPU type. - @{ - */ - -/** - \brief get FPU type - \details returns the FPU type - \returns - - \b 0: No FPU - - \b 1: Single precision FPU - - \b 2: Double + Single precision FPU - */ -__STATIC_INLINE uint32_t SCB_GetFPUType(void) -{ - uint32_t mvfr0; - - mvfr0 = FPU->MVFR0; - if ((mvfr0 & (FPU_MVFR0_Single_precision_Msk | FPU_MVFR0_Double_precision_Msk)) == 0x020U) - { - return 1U; /* Single precision FPU */ - } - else - { - return 0U; /* No FPU */ - } -} - - -/*@} end of CMSIS_Core_FpuFunctions */ - - - -/* ################################## SysTick function ############################################ */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_SysTickFunctions SysTick Functions - \brief Functions that configure the System. - @{ - */ - -#if defined (__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U) - -/** - \brief System Tick Configuration - \details Initializes the System Timer and its interrupt, and starts the System Tick Timer. - Counter is in free running mode to generate periodic interrupts. - \param [in] ticks Number of ticks between two interrupts. - \return 0 Function succeeded. - \return 1 Function failed. - \note When the variable __Vendor_SysTickConfig is set to 1, then the - function SysTick_Config is not included. In this case, the file device.h - must contain a vendor-specific implementation of this function. - */ -__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) -{ - if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) - { - return (1UL); /* Reload value impossible */ - } - - SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ - NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ - SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ - SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | - SysTick_CTRL_TICKINT_Msk | - SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ - return (0UL); /* Function successful */ -} - -#endif - -/*@} end of CMSIS_Core_SysTickFunctions */ - - - -/* ##################################### Debug In/Output function ########################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_core_DebugFunctions ITM Functions - \brief Functions that access the ITM debug interface. - @{ - */ - -extern volatile int32_t ITM_RxBuffer; /*!< External variable to receive characters. */ -#define ITM_RXBUFFER_EMPTY ((int32_t)0x5AA55AA5U) /*!< Value identifying \ref ITM_RxBuffer is ready for next character. */ - - -/** - \brief ITM Send Character - \details Transmits a character via the ITM channel 0, and - \li Just returns when no debugger is connected that has booked the output. - \li Is blocking when a debugger is connected, but the previous character sent has not been transmitted. - \param [in] ch Character to transmit. - \returns Character to transmit. - */ -__STATIC_INLINE uint32_t ITM_SendChar (uint32_t ch) -{ - if (((ITM->TCR & ITM_TCR_ITMENA_Msk) != 0UL) && /* ITM enabled */ - ((ITM->TER & 1UL ) != 0UL) ) /* ITM Port #0 enabled */ - { - while (ITM->PORT[0U].u32 == 0UL) - { - __NOP(); - } - ITM->PORT[0U].u8 = (uint8_t)ch; - } - return (ch); -} - - -/** - \brief ITM Receive Character - \details Inputs a character via the external variable \ref ITM_RxBuffer. - \return Received character. - \return -1 No character pending. - */ -__STATIC_INLINE int32_t ITM_ReceiveChar (void) -{ - int32_t ch = -1; /* no character available */ - - if (ITM_RxBuffer != ITM_RXBUFFER_EMPTY) - { - ch = ITM_RxBuffer; - ITM_RxBuffer = ITM_RXBUFFER_EMPTY; /* ready for next character */ - } - - return (ch); -} - - -/** - \brief ITM Check Character - \details Checks whether a character is pending for reading in the variable \ref ITM_RxBuffer. - \return 0 No character available. - \return 1 Character available. - */ -__STATIC_INLINE int32_t ITM_CheckChar (void) -{ - - if (ITM_RxBuffer == ITM_RXBUFFER_EMPTY) - { - return (0); /* no character available */ - } - else - { - return (1); /* character available */ - } -} - -/*@} end of CMSIS_core_DebugFunctions */ - - - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_CM4_H_DEPENDANT */ - -#endif /* __CMSIS_GENERIC */ - diff --git a/panda/board/stm32fx/inc/mpu_armv7.h b/panda/board/stm32fx/inc/mpu_armv7.h deleted file mode 100644 index e72cc46..0000000 --- a/panda/board/stm32fx/inc/mpu_armv7.h +++ /dev/null @@ -1,273 +0,0 @@ -/****************************************************************************** - * @file mpu_armv7.h - * @brief CMSIS MPU API for Armv7-M MPU - * @version V5.1.0 - * @date 08. March 2019 - ******************************************************************************/ -/* - * Copyright (c) 2017-2019 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef ARM_MPU_ARMV7_H -#define ARM_MPU_ARMV7_H - -#define ARM_MPU_REGION_SIZE_32B ((uint8_t)0x04U) ///!< MPU Region Size 32 Bytes -#define ARM_MPU_REGION_SIZE_64B ((uint8_t)0x05U) ///!< MPU Region Size 64 Bytes -#define ARM_MPU_REGION_SIZE_128B ((uint8_t)0x06U) ///!< MPU Region Size 128 Bytes -#define ARM_MPU_REGION_SIZE_256B ((uint8_t)0x07U) ///!< MPU Region Size 256 Bytes -#define ARM_MPU_REGION_SIZE_512B ((uint8_t)0x08U) ///!< MPU Region Size 512 Bytes -#define ARM_MPU_REGION_SIZE_1KB ((uint8_t)0x09U) ///!< MPU Region Size 1 KByte -#define ARM_MPU_REGION_SIZE_2KB ((uint8_t)0x0AU) ///!< MPU Region Size 2 KBytes -#define ARM_MPU_REGION_SIZE_4KB ((uint8_t)0x0BU) ///!< MPU Region Size 4 KBytes -#define ARM_MPU_REGION_SIZE_8KB ((uint8_t)0x0CU) ///!< MPU Region Size 8 KBytes -#define ARM_MPU_REGION_SIZE_16KB ((uint8_t)0x0DU) ///!< MPU Region Size 16 KBytes -#define ARM_MPU_REGION_SIZE_32KB ((uint8_t)0x0EU) ///!< MPU Region Size 32 KBytes -#define ARM_MPU_REGION_SIZE_64KB ((uint8_t)0x0FU) ///!< MPU Region Size 64 KBytes -#define ARM_MPU_REGION_SIZE_128KB ((uint8_t)0x10U) ///!< MPU Region Size 128 KBytes -#define ARM_MPU_REGION_SIZE_256KB ((uint8_t)0x11U) ///!< MPU Region Size 256 KBytes -#define ARM_MPU_REGION_SIZE_512KB ((uint8_t)0x12U) ///!< MPU Region Size 512 KBytes -#define ARM_MPU_REGION_SIZE_1MB ((uint8_t)0x13U) ///!< MPU Region Size 1 MByte -#define ARM_MPU_REGION_SIZE_2MB ((uint8_t)0x14U) ///!< MPU Region Size 2 MBytes -#define ARM_MPU_REGION_SIZE_4MB ((uint8_t)0x15U) ///!< MPU Region Size 4 MBytes -#define ARM_MPU_REGION_SIZE_8MB ((uint8_t)0x16U) ///!< MPU Region Size 8 MBytes -#define ARM_MPU_REGION_SIZE_16MB ((uint8_t)0x17U) ///!< MPU Region Size 16 MBytes -#define ARM_MPU_REGION_SIZE_32MB ((uint8_t)0x18U) ///!< MPU Region Size 32 MBytes -#define ARM_MPU_REGION_SIZE_64MB ((uint8_t)0x19U) ///!< MPU Region Size 64 MBytes -#define ARM_MPU_REGION_SIZE_128MB ((uint8_t)0x1AU) ///!< MPU Region Size 128 MBytes -#define ARM_MPU_REGION_SIZE_256MB ((uint8_t)0x1BU) ///!< MPU Region Size 256 MBytes -#define ARM_MPU_REGION_SIZE_512MB ((uint8_t)0x1CU) ///!< MPU Region Size 512 MBytes -#define ARM_MPU_REGION_SIZE_1GB ((uint8_t)0x1DU) ///!< MPU Region Size 1 GByte -#define ARM_MPU_REGION_SIZE_2GB ((uint8_t)0x1EU) ///!< MPU Region Size 2 GBytes -#define ARM_MPU_REGION_SIZE_4GB ((uint8_t)0x1FU) ///!< MPU Region Size 4 GBytes - -#define ARM_MPU_AP_NONE 0U ///!< MPU Access Permission no access -#define ARM_MPU_AP_PRIV 1U ///!< MPU Access Permission privileged access only -#define ARM_MPU_AP_URO 2U ///!< MPU Access Permission unprivileged access read-only -#define ARM_MPU_AP_FULL 3U ///!< MPU Access Permission full access -#define ARM_MPU_AP_PRO 5U ///!< MPU Access Permission privileged access read-only -#define ARM_MPU_AP_RO 6U ///!< MPU Access Permission read-only access - -/** MPU Region Base Address Register Value -* -* \param Region The region to be configured, number 0 to 15. -* \param BaseAddress The base address for the region. -*/ -#define ARM_MPU_RBAR(Region, BaseAddress) \ - (((BaseAddress) & MPU_RBAR_ADDR_Msk) | \ - ((Region) & MPU_RBAR_REGION_Msk) | \ - (MPU_RBAR_VALID_Msk)) - -/** -* MPU Memory Access Attributes -* -* \param TypeExtField Type extension field, allows you to configure memory access type, for example strongly ordered, peripheral. -* \param IsShareable Region is shareable between multiple bus masters. -* \param IsCacheable Region is cacheable, i.e. its value may be kept in cache. -* \param IsBufferable Region is bufferable, i.e. using write-back caching. Cacheable but non-bufferable regions use write-through policy. -*/ -#define ARM_MPU_ACCESS_(TypeExtField, IsShareable, IsCacheable, IsBufferable) \ - ((((TypeExtField) << MPU_RASR_TEX_Pos) & MPU_RASR_TEX_Msk) | \ - (((IsShareable) << MPU_RASR_S_Pos) & MPU_RASR_S_Msk) | \ - (((IsCacheable) << MPU_RASR_C_Pos) & MPU_RASR_C_Msk) | \ - (((IsBufferable) << MPU_RASR_B_Pos) & MPU_RASR_B_Msk)) - -/** -* MPU Region Attribute and Size Register Value -* -* \param DisableExec Instruction access disable bit, 1= disable instruction fetches. -* \param AccessPermission Data access permissions, allows you to configure read/write access for User and Privileged mode. -* \param AccessAttributes Memory access attribution, see \ref ARM_MPU_ACCESS_. -* \param SubRegionDisable Sub-region disable field. -* \param Size Region size of the region to be configured, for example 4K, 8K. -*/ -#define ARM_MPU_RASR_EX(DisableExec, AccessPermission, AccessAttributes, SubRegionDisable, Size) \ - ((((DisableExec) << MPU_RASR_XN_Pos) & MPU_RASR_XN_Msk) | \ - (((AccessPermission) << MPU_RASR_AP_Pos) & MPU_RASR_AP_Msk) | \ - (((AccessAttributes) & (MPU_RASR_TEX_Msk | MPU_RASR_S_Msk | MPU_RASR_C_Msk | MPU_RASR_B_Msk))) | \ - (((SubRegionDisable) << MPU_RASR_SRD_Pos) & MPU_RASR_SRD_Msk) | \ - (((Size) << MPU_RASR_SIZE_Pos) & MPU_RASR_SIZE_Msk) | \ - (((MPU_RASR_ENABLE_Msk)))) - -/** -* MPU Region Attribute and Size Register Value -* -* \param DisableExec Instruction access disable bit, 1= disable instruction fetches. -* \param AccessPermission Data access permissions, allows you to configure read/write access for User and Privileged mode. -* \param TypeExtField Type extension field, allows you to configure memory access type, for example strongly ordered, peripheral. -* \param IsShareable Region is shareable between multiple bus masters. -* \param IsCacheable Region is cacheable, i.e. its value may be kept in cache. -* \param IsBufferable Region is bufferable, i.e. using write-back caching. Cacheable but non-bufferable regions use write-through policy. -* \param SubRegionDisable Sub-region disable field. -* \param Size Region size of the region to be configured, for example 4K, 8K. -*/ -#define ARM_MPU_RASR(DisableExec, AccessPermission, TypeExtField, IsShareable, IsCacheable, IsBufferable, SubRegionDisable, Size) \ - ARM_MPU_RASR_EX(DisableExec, AccessPermission, ARM_MPU_ACCESS_(TypeExtField, IsShareable, IsCacheable, IsBufferable), SubRegionDisable, Size) - -/** -* MPU Memory Access Attribute for strongly ordered memory. -* - TEX: 000b -* - Shareable -* - Non-cacheable -* - Non-bufferable -*/ -#define ARM_MPU_ACCESS_ORDERED ARM_MPU_ACCESS_(0U, 1U, 0U, 0U) - -/** -* MPU Memory Access Attribute for device memory. -* - TEX: 000b (if shareable) or 010b (if non-shareable) -* - Shareable or non-shareable -* - Non-cacheable -* - Bufferable (if shareable) or non-bufferable (if non-shareable) -* -* \param IsShareable Configures the device memory as shareable or non-shareable. -*/ -#define ARM_MPU_ACCESS_DEVICE(IsShareable) ((IsShareable) ? ARM_MPU_ACCESS_(0U, 1U, 0U, 1U) : ARM_MPU_ACCESS_(2U, 0U, 0U, 0U)) - -/** -* MPU Memory Access Attribute for normal memory. -* - TEX: 1BBb (reflecting outer cacheability rules) -* - Shareable or non-shareable -* - Cacheable or non-cacheable (reflecting inner cacheability rules) -* - Bufferable or non-bufferable (reflecting inner cacheability rules) -* -* \param OuterCp Configures the outer cache policy. -* \param InnerCp Configures the inner cache policy. -* \param IsShareable Configures the memory as shareable or non-shareable. -*/ -#define ARM_MPU_ACCESS_NORMAL(OuterCp, InnerCp, IsShareable) ARM_MPU_ACCESS_((4U | (OuterCp)), IsShareable, ((InnerCp) & 2U), ((InnerCp) & 1U)) - -/** -* MPU Memory Access Attribute non-cacheable policy. -*/ -#define ARM_MPU_CACHEP_NOCACHE 0U - -/** -* MPU Memory Access Attribute write-back, write and read allocate policy. -*/ -#define ARM_MPU_CACHEP_WB_WRA 1U - -/** -* MPU Memory Access Attribute write-through, no write allocate policy. -*/ -#define ARM_MPU_CACHEP_WT_NWA 2U - -/** -* MPU Memory Access Attribute write-back, no write allocate policy. -*/ -#define ARM_MPU_CACHEP_WB_NWA 3U - - -/** -* Struct for a single MPU Region -*/ -typedef struct { - uint32_t RBAR; //!< The region base address register value (RBAR) - uint32_t RASR; //!< The region attribute and size register value (RASR) \ref MPU_RASR -} ARM_MPU_Region_t; - -/** Enable the MPU. -* \param MPU_Control Default access permissions for unconfigured regions. -*/ -__STATIC_INLINE void ARM_MPU_Enable(uint32_t MPU_Control) -{ - MPU->CTRL = MPU_Control | MPU_CTRL_ENABLE_Msk; -#ifdef SCB_SHCSR_MEMFAULTENA_Msk - SCB->SHCSR |= SCB_SHCSR_MEMFAULTENA_Msk; -#endif - __DSB(); - __ISB(); -} - -/** Disable the MPU. -*/ -__STATIC_INLINE void ARM_MPU_Disable(void) -{ - __DMB(); -#ifdef SCB_SHCSR_MEMFAULTENA_Msk - SCB->SHCSR &= ~SCB_SHCSR_MEMFAULTENA_Msk; -#endif - MPU->CTRL &= ~MPU_CTRL_ENABLE_Msk; -} - -/** Clear and disable the given MPU region. -* \param rnr Region number to be cleared. -*/ -__STATIC_INLINE void ARM_MPU_ClrRegion(uint32_t rnr) -{ - MPU->RNR = rnr; - MPU->RASR = 0U; -} - -/** Configure an MPU region. -* \param rbar Value for RBAR register. -* \param rsar Value for RSAR register. -*/ -__STATIC_INLINE void ARM_MPU_SetRegion(uint32_t rbar, uint32_t rasr) -{ - MPU->RBAR = rbar; - MPU->RASR = rasr; -} - -/** Configure the given MPU region. -* \param rnr Region number to be configured. -* \param rbar Value for RBAR register. -* \param rsar Value for RSAR register. -*/ -__STATIC_INLINE void ARM_MPU_SetRegionEx(uint32_t rnr, uint32_t rbar, uint32_t rasr) -{ - MPU->RNR = rnr; - MPU->RBAR = rbar; - MPU->RASR = rasr; -} - -/** Memcopy with strictly ordered memory access, e.g. for register targets. -* \param dst Destination data is copied to. -* \param src Source data is copied from. -* \param len Amount of data words to be copied. -*/ -__STATIC_INLINE void ARM_MPU_OrderedMemcpy(volatile uint32_t* dst, const uint32_t* __RESTRICT src, uint32_t len) -{ - uint32_t i; - for (i = 0U; i < len; ++i) - { - dst[i] = src[i]; - } -} - -/** Load the given number of MPU regions from a table. -* \param table Pointer to the MPU configuration table. -* \param cnt Amount of regions to be configured. -*/ -__STATIC_INLINE void ARM_MPU_Load(ARM_MPU_Region_t const* table, uint32_t cnt) -{ - const uint32_t rowWordSize = sizeof(ARM_MPU_Region_t)/4U; - while (cnt > MPU_TYPE_RALIASES) { - ARM_MPU_OrderedMemcpy(&(MPU->RBAR), &(table->RBAR), MPU_TYPE_RALIASES*rowWordSize); - table += MPU_TYPE_RALIASES; - cnt -= MPU_TYPE_RALIASES; - } - ARM_MPU_OrderedMemcpy(&(MPU->RBAR), &(table->RBAR), cnt*rowWordSize); -} - -#endif - diff --git a/panda/board/stm32fx/inc/stm32f413xx.h b/panda/board/stm32fx/inc/stm32f413xx.h deleted file mode 100644 index 0962a8d..0000000 --- a/panda/board/stm32fx/inc/stm32f413xx.h +++ /dev/null @@ -1,14995 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f413xx.h - * @author MCD Application Team - * @version V2.6.0 - * @date 04-November-2016 - * @brief CMSIS STM32F413xx Device Peripheral Access Layer Header File. - * - * This file contains: - * - Data structures and the address mapping for all peripherals - * - peripherals registers declarations and bits definition - * - Macros to access peripheral’s registers hardware - * - ****************************************************************************** - * @attention - * - *

© COPYRIGHT(c) 2016 STMicroelectronics

- * - * Redistribution and use in source and binary forms, with or without modification, - * are permitted provided that the following conditions are met: - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE - * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL - * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR - * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, - * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE - * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************** - */ - -/** @addtogroup CMSIS_Device - * @{ - */ - -/** @addtogroup stm32f413xx - * @{ - */ - -#ifndef __STM32F413xx_H -#define __STM32F413xx_H - -#ifdef __cplusplus - extern "C" { -#endif /* __cplusplus */ - -/** @addtogroup Configuration_section_for_CMSIS - * @{ - */ - -/** - * @brief Configuration of the Cortex-M4 Processor and Core Peripherals - */ -#define __CM4_REV 0x0001U /*!< Core revision r0p1 */ -#define __MPU_PRESENT 1U /*!< STM32F4XX provides an MPU */ -#define __NVIC_PRIO_BITS 4U /*!< STM32F4XX uses 4 Bits for the Priority Levels */ -#define __Vendor_SysTickConfig 0U /*!< Set to 1 if different SysTick Config is used */ -#define __FPU_PRESENT 1U /*!< FPU present */ - -/** - * @} - */ - -/** @addtogroup Peripheral_interrupt_number_definition - * @{ - */ - -/** - * @brief STM32F4XX Interrupt Number Definition, according to the selected device - * in @ref Library_configuration_section - */ -typedef enum -{ -/****** Cortex-M4 Processor Exceptions Numbers ****************************************************************/ - NonMaskableInt_IRQn = -14, /*!< 2 Non Maskable Interrupt */ - MemoryManagement_IRQn = -12, /*!< 4 Cortex-M4 Memory Management Interrupt */ - BusFault_IRQn = -11, /*!< 5 Cortex-M4 Bus Fault Interrupt */ - UsageFault_IRQn = -10, /*!< 6 Cortex-M4 Usage Fault Interrupt */ - SVCall_IRQn = -5, /*!< 11 Cortex-M4 SV Call Interrupt */ - DebugMonitor_IRQn = -4, /*!< 12 Cortex-M4 Debug Monitor Interrupt */ - PendSV_IRQn = -2, /*!< 14 Cortex-M4 Pend SV Interrupt */ - SysTick_IRQn = -1, /*!< 15 Cortex-M4 System Tick Interrupt */ -/****** STM32 specific Interrupt Numbers **********************************************************************/ - WWDG_IRQn = 0, /*!< Window WatchDog Interrupt */ - PVD_IRQn = 1, /*!< PVD through EXTI Line detection Interrupt */ - TAMP_STAMP_IRQn = 2, /*!< Tamper and TimeStamp interrupts through the EXTI line */ - RTC_WKUP_IRQn = 3, /*!< RTC Wakeup interrupt through the EXTI line */ - FLASH_IRQn = 4, /*!< FLASH global Interrupt */ - RCC_IRQn = 5, /*!< RCC global Interrupt */ - EXTI0_IRQn = 6, /*!< EXTI Line0 Interrupt */ - EXTI1_IRQn = 7, /*!< EXTI Line1 Interrupt */ - EXTI2_IRQn = 8, /*!< EXTI Line2 Interrupt */ - EXTI3_IRQn = 9, /*!< EXTI Line3 Interrupt */ - EXTI4_IRQn = 10, /*!< EXTI Line4 Interrupt */ - DMA1_Stream0_IRQn = 11, /*!< DMA1 Stream 0 global Interrupt */ - DMA1_Stream1_IRQn = 12, /*!< DMA1 Stream 1 global Interrupt */ - DMA1_Stream2_IRQn = 13, /*!< DMA1 Stream 2 global Interrupt */ - DMA1_Stream3_IRQn = 14, /*!< DMA1 Stream 3 global Interrupt */ - DMA1_Stream4_IRQn = 15, /*!< DMA1 Stream 4 global Interrupt */ - DMA1_Stream5_IRQn = 16, /*!< DMA1 Stream 5 global Interrupt */ - DMA1_Stream6_IRQn = 17, /*!< DMA1 Stream 6 global Interrupt */ - ADC_IRQn = 18, /*!< ADC1, ADC2 and ADC3 global Interrupts */ - CAN1_TX_IRQn = 19, /*!< CAN1 TX Interrupt */ - CAN1_RX0_IRQn = 20, /*!< CAN1 RX0 Interrupt */ - CAN1_RX1_IRQn = 21, /*!< CAN1 RX1 Interrupt */ - CAN1_SCE_IRQn = 22, /*!< CAN1 SCE Interrupt */ - EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ - TIM1_BRK_TIM9_IRQn = 24, /*!< TIM1 Break interrupt and TIM9 global interrupt */ - TIM1_UP_TIM10_IRQn = 25, /*!< TIM1 Update Interrupt and TIM10 global interrupt */ - TIM1_TRG_COM_TIM11_IRQn = 26, /*!< TIM1 Trigger and Commutation Interrupt and TIM11 global interrupt */ - TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ - TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ - TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ - TIM4_IRQn = 30, /*!< TIM4 global Interrupt */ - I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ - I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ - I2C2_EV_IRQn = 33, /*!< I2C2 Event Interrupt */ - I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */ - SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ - SPI2_IRQn = 36, /*!< SPI2 global Interrupt */ - USART1_IRQn = 37, /*!< USART1 global Interrupt */ - USART2_IRQn = 38, /*!< USART2 global Interrupt */ - USART3_IRQn = 39, /*!< USART3 global Interrupt */ - EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ - RTC_Alarm_IRQn = 41, /*!< RTC Alarm (A and B) through EXTI Line Interrupt */ - OTG_FS_WKUP_IRQn = 42, /*!< USB OTG FS Wakeup through EXTI line interrupt */ - TIM8_BRK_TIM12_IRQn = 43, /*!< TIM8 Break Interrupt and TIM12 global interrupt */ - TIM8_UP_TIM13_IRQn = 44, /*!< TIM8 Update Interrupt and TIM13 global interrupt */ - TIM8_TRG_COM_TIM14_IRQn = 45, /*!< TIM8 Trigger and Commutation Interrupt and TIM14 global interrupt */ - TIM8_CC_IRQn = 46, /*!< TIM8 Capture Compare global interrupt */ - DMA1_Stream7_IRQn = 47, /*!< DMA1 Stream7 Interrupt */ - FSMC_IRQn = 48, /*!< FSMC global Interrupt */ - SDIO_IRQn = 49, /*!< SDIO global Interrupt */ - TIM5_IRQn = 50, /*!< TIM5 global Interrupt */ - SPI3_IRQn = 51, /*!< SPI3 global Interrupt */ - UART4_IRQn = 52, /*!< UART4 global Interrupt */ - UART5_IRQn = 53, /*!< UART5 global Interrupt */ - TIM6_DAC_IRQn = 54, /*!< TIM6 global and DAC1&2 underrun error interrupts */ - TIM7_IRQn = 55, /*!< TIM7 global interrupt */ - DMA2_Stream0_IRQn = 56, /*!< DMA2 Stream 0 global Interrupt */ - DMA2_Stream1_IRQn = 57, /*!< DMA2 Stream 1 global Interrupt */ - DMA2_Stream2_IRQn = 58, /*!< DMA2 Stream 2 global Interrupt */ - DMA2_Stream3_IRQn = 59, /*!< DMA2 Stream 3 global Interrupt */ - DMA2_Stream4_IRQn = 60, /*!< DMA2 Stream 4 global Interrupt */ - DFSDM1_FLT0_IRQn = 61, /*!< DFSDM1 Filter 0 global Interrupt */ - DFSDM1_FLT1_IRQn = 62, /*!< DFSDM1 Filter 1 global Interrupt */ - CAN2_TX_IRQn = 63, /*!< CAN2 TX Interrupt */ - CAN2_RX0_IRQn = 64, /*!< CAN2 RX0 Interrupt */ - CAN2_RX1_IRQn = 65, /*!< CAN2 RX1 Interrupt */ - CAN2_SCE_IRQn = 66, /*!< CAN2 SCE Interrupt */ - OTG_FS_IRQn = 67, /*!< USB OTG FS global Interrupt */ - DMA2_Stream5_IRQn = 68, /*!< DMA2 Stream 5 global interrupt */ - DMA2_Stream6_IRQn = 69, /*!< DMA2 Stream 6 global interrupt */ - DMA2_Stream7_IRQn = 70, /*!< DMA2 Stream 7 global interrupt */ - USART6_IRQn = 71, /*!< USART6 global interrupt */ - I2C3_EV_IRQn = 72, /*!< I2C3 event interrupt */ - I2C3_ER_IRQn = 73, /*!< I2C3 error interrupt */ - CAN3_TX_IRQn = 74, /*!< CAN3 TX Interrupt */ - CAN3_RX0_IRQn = 75, /*!< CAN3 RX0 Interrupt */ - CAN3_RX1_IRQn = 76, /*!< CAN3 RX1 Interrupt */ - CAN3_SCE_IRQn = 77, /*!< CAN3 SCE Interrupt */ - RNG_IRQn = 80, /*!< RNG global Interrupt */ - FPU_IRQn = 81, /*!< FPU global interrupt */ - UART7_IRQn = 82, /*!< UART7 global interrupt */ - UART8_IRQn = 83, /*!< UART8 global interrupt */ - SPI4_IRQn = 84, /*!< SPI4 global Interrupt */ - SPI5_IRQn = 85, /*!< SPI5 global Interrupt */ - SAI1_IRQn = 87, /*!< SAI1 global Interrupt */ - UART9_IRQn = 88, /*!< UART9 global Interrupt */ - UART10_IRQn = 89, /*!< UART10 global Interrupt */ - QUADSPI_IRQn = 92, /*!< QuadSPI global Interrupt */ - FMPI2C1_EV_IRQn = 95, /*!< FMPI2C1 Event Interrupt */ - FMPI2C1_ER_IRQn = 96, /*!< FMPI2C1 Error Interrupt */ - LPTIM1_IRQn = 97, /*!< LP TIM1 interrupt */ - DFSDM2_FLT0_IRQn = 98, /*!< DFSDM2 Filter 0 global Interrupt */ - DFSDM2_FLT1_IRQn = 99, /*!< DFSDM2 Filter 1 global Interrupt */ - DFSDM2_FLT2_IRQn = 100, /*!< DFSDM2 Filter 2 global Interrupt */ - DFSDM2_FLT3_IRQn = 101 /*!< DFSDM2 Filter 3 global Interrupt */ -} IRQn_Type; - -/** - * @} - */ - -#include "core_cm4.h" /* Cortex-M4 processor and core peripherals */ -#include "system_stm32f4xx.h" -#include - -/** @addtogroup Peripheral_registers_structures - * @{ - */ - -/** - * @brief Analog to Digital Converter - */ - -typedef struct -{ - __IO uint32_t SR; /*!< ADC status register, Address offset: 0x00 */ - __IO uint32_t CR1; /*!< ADC control register 1, Address offset: 0x04 */ - __IO uint32_t CR2; /*!< ADC control register 2, Address offset: 0x08 */ - __IO uint32_t SMPR1; /*!< ADC sample time register 1, Address offset: 0x0C */ - __IO uint32_t SMPR2; /*!< ADC sample time register 2, Address offset: 0x10 */ - __IO uint32_t JOFR1; /*!< ADC injected channel data offset register 1, Address offset: 0x14 */ - __IO uint32_t JOFR2; /*!< ADC injected channel data offset register 2, Address offset: 0x18 */ - __IO uint32_t JOFR3; /*!< ADC injected channel data offset register 3, Address offset: 0x1C */ - __IO uint32_t JOFR4; /*!< ADC injected channel data offset register 4, Address offset: 0x20 */ - __IO uint32_t HTR; /*!< ADC watchdog higher threshold register, Address offset: 0x24 */ - __IO uint32_t LTR; /*!< ADC watchdog lower threshold register, Address offset: 0x28 */ - __IO uint32_t SQR1; /*!< ADC regular sequence register 1, Address offset: 0x2C */ - __IO uint32_t SQR2; /*!< ADC regular sequence register 2, Address offset: 0x30 */ - __IO uint32_t SQR3; /*!< ADC regular sequence register 3, Address offset: 0x34 */ - __IO uint32_t JSQR; /*!< ADC injected sequence register, Address offset: 0x38*/ - __IO uint32_t JDR1; /*!< ADC injected data register 1, Address offset: 0x3C */ - __IO uint32_t JDR2; /*!< ADC injected data register 2, Address offset: 0x40 */ - __IO uint32_t JDR3; /*!< ADC injected data register 3, Address offset: 0x44 */ - __IO uint32_t JDR4; /*!< ADC injected data register 4, Address offset: 0x48 */ - __IO uint32_t DR; /*!< ADC regular data register, Address offset: 0x4C */ -} ADC_TypeDef; - -typedef struct -{ - __IO uint32_t CSR; /*!< ADC Common status register, Address offset: ADC1 base address + 0x300 */ - __IO uint32_t CCR; /*!< ADC common control register, Address offset: ADC1 base address + 0x304 */ - __IO uint32_t CDR; /*!< ADC common regular data register for dual - AND triple modes, Address offset: ADC1 base address + 0x308 */ -} ADC_Common_TypeDef; - - -/** - * @brief Controller Area Network TxMailBox - */ - -typedef struct -{ - __IO uint32_t TIR; /*!< CAN TX mailbox identifier register */ - __IO uint32_t TDTR; /*!< CAN mailbox data length control and time stamp register */ - __IO uint32_t TDLR; /*!< CAN mailbox data low register */ - __IO uint32_t TDHR; /*!< CAN mailbox data high register */ -} CAN_TxMailBox_TypeDef; - -/** - * @brief Controller Area Network FIFOMailBox - */ - -typedef struct -{ - __IO uint32_t RIR; /*!< CAN receive FIFO mailbox identifier register */ - __IO uint32_t RDTR; /*!< CAN receive FIFO mailbox data length control and time stamp register */ - __IO uint32_t RDLR; /*!< CAN receive FIFO mailbox data low register */ - __IO uint32_t RDHR; /*!< CAN receive FIFO mailbox data high register */ -} CAN_FIFOMailBox_TypeDef; - -/** - * @brief Controller Area Network FilterRegister - */ - -typedef struct -{ - __IO uint32_t FR1; /*!< CAN Filter bank register 1 */ - __IO uint32_t FR2; /*!< CAN Filter bank register 1 */ -} CAN_FilterRegister_TypeDef; - -/** - * @brief Controller Area Network - */ - -typedef struct -{ - __IO uint32_t MCR; /*!< CAN master control register, Address offset: 0x00 */ - __IO uint32_t MSR; /*!< CAN master status register, Address offset: 0x04 */ - __IO uint32_t TSR; /*!< CAN transmit status register, Address offset: 0x08 */ - __IO uint32_t RF0R; /*!< CAN receive FIFO 0 register, Address offset: 0x0C */ - __IO uint32_t RF1R; /*!< CAN receive FIFO 1 register, Address offset: 0x10 */ - __IO uint32_t IER; /*!< CAN interrupt enable register, Address offset: 0x14 */ - __IO uint32_t ESR; /*!< CAN error status register, Address offset: 0x18 */ - __IO uint32_t BTR; /*!< CAN bit timing register, Address offset: 0x1C */ - uint32_t RESERVED0[88]; /*!< Reserved, 0x020 - 0x17F */ - CAN_TxMailBox_TypeDef sTxMailBox[3]; /*!< CAN Tx MailBox, Address offset: 0x180 - 0x1AC */ - CAN_FIFOMailBox_TypeDef sFIFOMailBox[2]; /*!< CAN FIFO MailBox, Address offset: 0x1B0 - 0x1CC */ - uint32_t RESERVED1[12]; /*!< Reserved, 0x1D0 - 0x1FF */ - __IO uint32_t FMR; /*!< CAN filter master register, Address offset: 0x200 */ - __IO uint32_t FM1R; /*!< CAN filter mode register, Address offset: 0x204 */ - uint32_t RESERVED2; /*!< Reserved, 0x208 */ - __IO uint32_t FS1R; /*!< CAN filter scale register, Address offset: 0x20C */ - uint32_t RESERVED3; /*!< Reserved, 0x210 */ - __IO uint32_t FFA1R; /*!< CAN filter FIFO assignment register, Address offset: 0x214 */ - uint32_t RESERVED4; /*!< Reserved, 0x218 */ - __IO uint32_t FA1R; /*!< CAN filter activation register, Address offset: 0x21C */ - uint32_t RESERVED5[8]; /*!< Reserved, 0x220-0x23F */ - CAN_FilterRegister_TypeDef sFilterRegister[28]; /*!< CAN Filter Register, Address offset: 0x240-0x31C */ -} CAN_TypeDef; - -/** - * @brief CRC calculation unit - */ - -typedef struct -{ - __IO uint32_t DR; /*!< CRC Data register, Address offset: 0x00 */ - __IO uint8_t IDR; /*!< CRC Independent data register, Address offset: 0x04 */ - uint8_t RESERVED0; /*!< Reserved, 0x05 */ - uint16_t RESERVED1; /*!< Reserved, 0x06 */ - __IO uint32_t CR; /*!< CRC Control register, Address offset: 0x08 */ -} CRC_TypeDef; - -/** - * @brief DFSDM module registers - */ -typedef struct -{ - __IO uint32_t FLTCR1; /*!< DFSDM control register1, Address offset: 0x100 */ - __IO uint32_t FLTCR2; /*!< DFSDM control register2, Address offset: 0x104 */ - __IO uint32_t FLTISR; /*!< DFSDM interrupt and status register, Address offset: 0x108 */ - __IO uint32_t FLTICR; /*!< DFSDM interrupt flag clear register, Address offset: 0x10C */ - __IO uint32_t FLTJCHGR; /*!< DFSDM injected channel group selection register, Address offset: 0x110 */ - __IO uint32_t FLTFCR; /*!< DFSDM filter control register, Address offset: 0x114 */ - __IO uint32_t FLTJDATAR; /*!< DFSDM data register for injected group, Address offset: 0x118 */ - __IO uint32_t FLTRDATAR; /*!< DFSDM data register for regular group, Address offset: 0x11C */ - __IO uint32_t FLTAWHTR; /*!< DFSDM analog watchdog high threshold register, Address offset: 0x120 */ - __IO uint32_t FLTAWLTR; /*!< DFSDM analog watchdog low threshold register, Address offset: 0x124 */ - __IO uint32_t FLTAWSR; /*!< DFSDM analog watchdog status register Address offset: 0x128 */ - __IO uint32_t FLTAWCFR; /*!< DFSDM analog watchdog clear flag register Address offset: 0x12C */ - __IO uint32_t FLTEXMAX; /*!< DFSDM extreme detector maximum register, Address offset: 0x130 */ - __IO uint32_t FLTEXMIN; /*!< DFSDM extreme detector minimum register Address offset: 0x134 */ - __IO uint32_t FLTCNVTIMR; /*!< DFSDM conversion timer, Address offset: 0x138 */ -} DFSDM_Filter_TypeDef; - -/** - * @brief DFSDM channel configuration registers - */ -typedef struct -{ - __IO uint32_t CHCFGR1; /*!< DFSDM channel configuration register1, Address offset: 0x00 */ - __IO uint32_t CHCFGR2; /*!< DFSDM channel configuration register2, Address offset: 0x04 */ - __IO uint32_t CHAWSCDR; /*!< DFSDM channel analog watchdog and - short circuit detector register, Address offset: 0x08 */ - __IO uint32_t CHWDATAR; /*!< DFSDM channel watchdog filter data register, Address offset: 0x0C */ - __IO uint32_t CHDATINR; /*!< DFSDM channel data input register, Address offset: 0x10 */ -} DFSDM_Channel_TypeDef; - -/** - * @brief Digital to Analog Converter - */ - -typedef struct -{ - __IO uint32_t CR; /*!< DAC control register, Address offset: 0x00 */ - __IO uint32_t SWTRIGR; /*!< DAC software trigger register, Address offset: 0x04 */ - __IO uint32_t DHR12R1; /*!< DAC channel1 12-bit right-aligned data holding register, Address offset: 0x08 */ - __IO uint32_t DHR12L1; /*!< DAC channel1 12-bit left aligned data holding register, Address offset: 0x0C */ - __IO uint32_t DHR8R1; /*!< DAC channel1 8-bit right aligned data holding register, Address offset: 0x10 */ - __IO uint32_t DHR12R2; /*!< DAC channel2 12-bit right aligned data holding register, Address offset: 0x14 */ - __IO uint32_t DHR12L2; /*!< DAC channel2 12-bit left aligned data holding register, Address offset: 0x18 */ - __IO uint32_t DHR8R2; /*!< DAC channel2 8-bit right-aligned data holding register, Address offset: 0x1C */ - __IO uint32_t DHR12RD; /*!< Dual DAC 12-bit right-aligned data holding register, Address offset: 0x20 */ - __IO uint32_t DHR12LD; /*!< DUAL DAC 12-bit left aligned data holding register, Address offset: 0x24 */ - __IO uint32_t DHR8RD; /*!< DUAL DAC 8-bit right aligned data holding register, Address offset: 0x28 */ - __IO uint32_t DOR1; /*!< DAC channel1 data output register, Address offset: 0x2C */ - __IO uint32_t DOR2; /*!< DAC channel2 data output register, Address offset: 0x30 */ - __IO uint32_t SR; /*!< DAC status register, Address offset: 0x34 */ -} DAC_TypeDef; - -/** - * @brief Debug MCU - */ - -typedef struct -{ - __IO uint32_t IDCODE; /*!< MCU device ID code, Address offset: 0x00 */ - __IO uint32_t CR; /*!< Debug MCU configuration register, Address offset: 0x04 */ - __IO uint32_t APB1FZ; /*!< Debug MCU APB1 freeze register, Address offset: 0x08 */ - __IO uint32_t APB2FZ; /*!< Debug MCU APB2 freeze register, Address offset: 0x0C */ -}DBGMCU_TypeDef; - - -/** - * @brief DMA Controller - */ - -typedef struct -{ - __IO uint32_t CR; /*!< DMA stream x configuration register */ - __IO uint32_t NDTR; /*!< DMA stream x number of data register */ - __IO uint32_t PAR; /*!< DMA stream x peripheral address register */ - __IO uint32_t M0AR; /*!< DMA stream x memory 0 address register */ - __IO uint32_t M1AR; /*!< DMA stream x memory 1 address register */ - __IO uint32_t FCR; /*!< DMA stream x FIFO control register */ -} DMA_Stream_TypeDef; - -typedef struct -{ - __IO uint32_t LISR; /*!< DMA low interrupt status register, Address offset: 0x00 */ - __IO uint32_t HISR; /*!< DMA high interrupt status register, Address offset: 0x04 */ - __IO uint32_t LIFCR; /*!< DMA low interrupt flag clear register, Address offset: 0x08 */ - __IO uint32_t HIFCR; /*!< DMA high interrupt flag clear register, Address offset: 0x0C */ -} DMA_TypeDef; - -/** - * @brief External Interrupt/Event Controller - */ - -typedef struct -{ - __IO uint32_t IMR; /*!< EXTI Interrupt mask register, Address offset: 0x00 */ - __IO uint32_t EMR; /*!< EXTI Event mask register, Address offset: 0x04 */ - __IO uint32_t RTSR; /*!< EXTI Rising trigger selection register, Address offset: 0x08 */ - __IO uint32_t FTSR; /*!< EXTI Falling trigger selection register, Address offset: 0x0C */ - __IO uint32_t SWIER; /*!< EXTI Software interrupt event register, Address offset: 0x10 */ - __IO uint32_t PR; /*!< EXTI Pending register, Address offset: 0x14 */ -} EXTI_TypeDef; - -/** - * @brief FLASH Registers - */ - -typedef struct -{ - __IO uint32_t ACR; /*!< FLASH access control register, Address offset: 0x00 */ - __IO uint32_t KEYR; /*!< FLASH key register, Address offset: 0x04 */ - __IO uint32_t OPTKEYR; /*!< FLASH option key register, Address offset: 0x08 */ - __IO uint32_t SR; /*!< FLASH status register, Address offset: 0x0C */ - __IO uint32_t CR; /*!< FLASH control register, Address offset: 0x10 */ - __IO uint32_t OPTCR; /*!< FLASH option control register , Address offset: 0x14 */ - __IO uint32_t OPTCR1; /*!< FLASH option control register 1, Address offset: 0x18 */ -} FLASH_TypeDef; - - - -/** - * @brief Flexible Static Memory Controller - */ - -typedef struct -{ - __IO uint32_t BTCR[8]; /*!< NOR/PSRAM chip-select control register(BCR) and chip-select timing register(BTR), Address offset: 0x00-1C */ -} FSMC_Bank1_TypeDef; - -/** - * @brief Flexible Static Memory Controller Bank1E - */ - -typedef struct -{ - __IO uint32_t BWTR[7]; /*!< NOR/PSRAM write timing registers, Address offset: 0x104-0x11C */ -} FSMC_Bank1E_TypeDef; -/** - * @brief General Purpose I/O - */ - -typedef struct -{ - __IO uint32_t MODER; /*!< GPIO port mode register, Address offset: 0x00 */ - __IO uint32_t OTYPER; /*!< GPIO port output type register, Address offset: 0x04 */ - __IO uint32_t OSPEEDR; /*!< GPIO port output speed register, Address offset: 0x08 */ - __IO uint32_t PUPDR; /*!< GPIO port pull-up/pull-down register, Address offset: 0x0C */ - __IO uint32_t IDR; /*!< GPIO port input data register, Address offset: 0x10 */ - __IO uint32_t ODR; /*!< GPIO port output data register, Address offset: 0x14 */ - __IO uint32_t BSRR; /*!< GPIO port bit set/reset register, Address offset: 0x18 */ - __IO uint32_t LCKR; /*!< GPIO port configuration lock register, Address offset: 0x1C */ - __IO uint32_t AFR[2]; /*!< GPIO alternate function registers, Address offset: 0x20-0x24 */ -} GPIO_TypeDef; - -/** - * @brief System configuration controller - */ - -typedef struct -{ - __IO uint32_t MEMRMP; /*!< SYSCFG memory remap register, Address offset: 0x00 */ - __IO uint32_t PMC; /*!< SYSCFG peripheral mode configuration register, Address offset: 0x04 */ - __IO uint32_t EXTICR[4]; /*!< SYSCFG external interrupt configuration registers, Address offset: 0x08-0x14 */ - uint32_t RESERVED; /*!< Reserved, 0x18 */ - __IO uint32_t CFGR2; /*!< SYSCFG Configuration register2, Address offset: 0x1C */ - __IO uint32_t CMPCR; /*!< SYSCFG Compensation cell control register, Address offset: 0x20 */ - uint32_t RESERVED1[2]; /*!< Reserved, 0x24-0x28 */ - __IO uint32_t CFGR; /*!< SYSCFG Configuration register, Address offset: 0x2C */ - __IO uint32_t MCHDLYCR; /*!< SYSCFG multi-channel delay register, Address offset: 0x30 */ -} SYSCFG_TypeDef; - -/** - * @brief Inter-integrated Circuit Interface - */ - -typedef struct -{ - __IO uint32_t CR1; /*!< I2C Control register 1, Address offset: 0x00 */ - __IO uint32_t CR2; /*!< I2C Control register 2, Address offset: 0x04 */ - __IO uint32_t OAR1; /*!< I2C Own address register 1, Address offset: 0x08 */ - __IO uint32_t OAR2; /*!< I2C Own address register 2, Address offset: 0x0C */ - __IO uint32_t DR; /*!< I2C Data register, Address offset: 0x10 */ - __IO uint32_t SR1; /*!< I2C Status register 1, Address offset: 0x14 */ - __IO uint32_t SR2; /*!< I2C Status register 2, Address offset: 0x18 */ - __IO uint32_t CCR; /*!< I2C Clock control register, Address offset: 0x1C */ - __IO uint32_t TRISE; /*!< I2C TRISE register, Address offset: 0x20 */ - __IO uint32_t FLTR; /*!< I2C FLTR register, Address offset: 0x24 */ -} I2C_TypeDef; - -/** - * @brief Inter-integrated Circuit Interface - */ - -typedef struct -{ - __IO uint32_t CR1; /*!< FMPI2C Control register 1, Address offset: 0x00 */ - __IO uint32_t CR2; /*!< FMPI2C Control register 2, Address offset: 0x04 */ - __IO uint32_t OAR1; /*!< FMPI2C Own address 1 register, Address offset: 0x08 */ - __IO uint32_t OAR2; /*!< FMPI2C Own address 2 register, Address offset: 0x0C */ - __IO uint32_t TIMINGR; /*!< FMPI2C Timing register, Address offset: 0x10 */ - __IO uint32_t TIMEOUTR; /*!< FMPI2C Timeout register, Address offset: 0x14 */ - __IO uint32_t ISR; /*!< FMPI2C Interrupt and status register, Address offset: 0x18 */ - __IO uint32_t ICR; /*!< FMPI2C Interrupt clear register, Address offset: 0x1C */ - __IO uint32_t PECR; /*!< FMPI2C PEC register, Address offset: 0x20 */ - __IO uint32_t RXDR; /*!< FMPI2C Receive data register, Address offset: 0x24 */ - __IO uint32_t TXDR; /*!< FMPI2C Transmit data register, Address offset: 0x28 */ -} FMPI2C_TypeDef; - -/** - * @brief Independent WATCHDOG - */ - -typedef struct -{ - __IO uint32_t KR; /*!< IWDG Key register, Address offset: 0x00 */ - __IO uint32_t PR; /*!< IWDG Prescaler register, Address offset: 0x04 */ - __IO uint32_t RLR; /*!< IWDG Reload register, Address offset: 0x08 */ - __IO uint32_t SR; /*!< IWDG Status register, Address offset: 0x0C */ -} IWDG_TypeDef; - - -/** - * @brief Power Control - */ - -typedef struct -{ - __IO uint32_t CR; /*!< PWR power control register, Address offset: 0x00 */ - __IO uint32_t CSR; /*!< PWR power control/status register, Address offset: 0x04 */ -} PWR_TypeDef; - -/** - * @brief Reset and Clock Control - */ - -typedef struct -{ - __IO uint32_t CR; /*!< RCC clock control register, Address offset: 0x00 */ - __IO uint32_t PLLCFGR; /*!< RCC PLL configuration register, Address offset: 0x04 */ - __IO uint32_t CFGR; /*!< RCC clock configuration register, Address offset: 0x08 */ - __IO uint32_t CIR; /*!< RCC clock interrupt register, Address offset: 0x0C */ - __IO uint32_t AHB1RSTR; /*!< RCC AHB1 peripheral reset register, Address offset: 0x10 */ - __IO uint32_t AHB2RSTR; /*!< RCC AHB2 peripheral reset register, Address offset: 0x14 */ - __IO uint32_t AHB3RSTR; /*!< RCC AHB3 peripheral reset register, Address offset: 0x18 */ - uint32_t RESERVED0; /*!< Reserved, 0x1C */ - __IO uint32_t APB1RSTR; /*!< RCC APB1 peripheral reset register, Address offset: 0x20 */ - __IO uint32_t APB2RSTR; /*!< RCC APB2 peripheral reset register, Address offset: 0x24 */ - uint32_t RESERVED1[2]; /*!< Reserved, 0x28-0x2C */ - __IO uint32_t AHB1ENR; /*!< RCC AHB1 peripheral clock register, Address offset: 0x30 */ - __IO uint32_t AHB2ENR; /*!< RCC AHB2 peripheral clock register, Address offset: 0x34 */ - __IO uint32_t AHB3ENR; /*!< RCC AHB3 peripheral clock register, Address offset: 0x38 */ - uint32_t RESERVED2; /*!< Reserved, 0x3C */ - __IO uint32_t APB1ENR; /*!< RCC APB1 peripheral clock enable register, Address offset: 0x40 */ - __IO uint32_t APB2ENR; /*!< RCC APB2 peripheral clock enable register, Address offset: 0x44 */ - uint32_t RESERVED3[2]; /*!< Reserved, 0x48-0x4C */ - __IO uint32_t AHB1LPENR; /*!< RCC AHB1 peripheral clock enable in low power mode register, Address offset: 0x50 */ - __IO uint32_t AHB2LPENR; /*!< RCC AHB2 peripheral clock enable in low power mode register, Address offset: 0x54 */ - __IO uint32_t AHB3LPENR; /*!< RCC AHB3 peripheral clock enable in low power mode register, Address offset: 0x58 */ - uint32_t RESERVED4; /*!< Reserved, 0x5C */ - __IO uint32_t APB1LPENR; /*!< RCC APB1 peripheral clock enable in low power mode register, Address offset: 0x60 */ - __IO uint32_t APB2LPENR; /*!< RCC APB2 peripheral clock enable in low power mode register, Address offset: 0x64 */ - uint32_t RESERVED5[2]; /*!< Reserved, 0x68-0x6C */ - __IO uint32_t BDCR; /*!< RCC Backup domain control register, Address offset: 0x70 */ - __IO uint32_t CSR; /*!< RCC clock control & status register, Address offset: 0x74 */ - uint32_t RESERVED6[2]; /*!< Reserved, 0x78-0x7C */ - __IO uint32_t SSCGR; /*!< RCC spread spectrum clock generation register, Address offset: 0x80 */ - __IO uint32_t PLLI2SCFGR; /*!< RCC PLLI2S configuration register, Address offset: 0x84 */ - uint32_t RESERVED7; /*!< Reserved, 0x84 */ - __IO uint32_t DCKCFGR; /*!< RCC Dedicated Clocks configuration register, Address offset: 0x8C */ - __IO uint32_t CKGATENR; /*!< RCC Clocks Gated ENable Register, Address offset: 0x90 */ - __IO uint32_t DCKCFGR2; /*!< RCC Dedicated Clocks configuration register 2, Address offset: 0x94 */ -} RCC_TypeDef; - -/** - * @brief Real-Time Clock - */ - -typedef struct -{ - __IO uint32_t TR; /*!< RTC time register, Address offset: 0x00 */ - __IO uint32_t DR; /*!< RTC date register, Address offset: 0x04 */ - __IO uint32_t CR; /*!< RTC control register, Address offset: 0x08 */ - __IO uint32_t ISR; /*!< RTC initialization and status register, Address offset: 0x0C */ - __IO uint32_t PRER; /*!< RTC prescaler register, Address offset: 0x10 */ - __IO uint32_t WUTR; /*!< RTC wakeup timer register, Address offset: 0x14 */ - __IO uint32_t CALIBR; /*!< RTC calibration register, Address offset: 0x18 */ - __IO uint32_t ALRMAR; /*!< RTC alarm A register, Address offset: 0x1C */ - __IO uint32_t ALRMBR; /*!< RTC alarm B register, Address offset: 0x20 */ - __IO uint32_t WPR; /*!< RTC write protection register, Address offset: 0x24 */ - __IO uint32_t SSR; /*!< RTC sub second register, Address offset: 0x28 */ - __IO uint32_t SHIFTR; /*!< RTC shift control register, Address offset: 0x2C */ - __IO uint32_t TSTR; /*!< RTC time stamp time register, Address offset: 0x30 */ - __IO uint32_t TSDR; /*!< RTC time stamp date register, Address offset: 0x34 */ - __IO uint32_t TSSSR; /*!< RTC time-stamp sub second register, Address offset: 0x38 */ - __IO uint32_t CALR; /*!< RTC calibration register, Address offset: 0x3C */ - __IO uint32_t TAFCR; /*!< RTC tamper and alternate function configuration register, Address offset: 0x40 */ - __IO uint32_t ALRMASSR;/*!< RTC alarm A sub second register, Address offset: 0x44 */ - __IO uint32_t ALRMBSSR;/*!< RTC alarm B sub second register, Address offset: 0x48 */ - uint32_t RESERVED7; /*!< Reserved, 0x4C */ - __IO uint32_t BKP0R; /*!< RTC backup register 1, Address offset: 0x50 */ - __IO uint32_t BKP1R; /*!< RTC backup register 1, Address offset: 0x54 */ - __IO uint32_t BKP2R; /*!< RTC backup register 2, Address offset: 0x58 */ - __IO uint32_t BKP3R; /*!< RTC backup register 3, Address offset: 0x5C */ - __IO uint32_t BKP4R; /*!< RTC backup register 4, Address offset: 0x60 */ - __IO uint32_t BKP5R; /*!< RTC backup register 5, Address offset: 0x64 */ - __IO uint32_t BKP6R; /*!< RTC backup register 6, Address offset: 0x68 */ - __IO uint32_t BKP7R; /*!< RTC backup register 7, Address offset: 0x6C */ - __IO uint32_t BKP8R; /*!< RTC backup register 8, Address offset: 0x70 */ - __IO uint32_t BKP9R; /*!< RTC backup register 9, Address offset: 0x74 */ - __IO uint32_t BKP10R; /*!< RTC backup register 10, Address offset: 0x78 */ - __IO uint32_t BKP11R; /*!< RTC backup register 11, Address offset: 0x7C */ - __IO uint32_t BKP12R; /*!< RTC backup register 12, Address offset: 0x80 */ - __IO uint32_t BKP13R; /*!< RTC backup register 13, Address offset: 0x84 */ - __IO uint32_t BKP14R; /*!< RTC backup register 14, Address offset: 0x88 */ - __IO uint32_t BKP15R; /*!< RTC backup register 15, Address offset: 0x8C */ - __IO uint32_t BKP16R; /*!< RTC backup register 16, Address offset: 0x90 */ - __IO uint32_t BKP17R; /*!< RTC backup register 17, Address offset: 0x94 */ - __IO uint32_t BKP18R; /*!< RTC backup register 18, Address offset: 0x98 */ - __IO uint32_t BKP19R; /*!< RTC backup register 19, Address offset: 0x9C */ -} RTC_TypeDef; - -/** - * @brief Serial Audio Interface - */ - -typedef struct -{ - __IO uint32_t GCR; /*!< SAI global configuration register, Address offset: 0x00 */ -} SAI_TypeDef; - -typedef struct -{ - __IO uint32_t CR1; /*!< SAI block x configuration register 1, Address offset: 0x04 */ - __IO uint32_t CR2; /*!< SAI block x configuration register 2, Address offset: 0x08 */ - __IO uint32_t FRCR; /*!< SAI block x frame configuration register, Address offset: 0x0C */ - __IO uint32_t SLOTR; /*!< SAI block x slot register, Address offset: 0x10 */ - __IO uint32_t IMR; /*!< SAI block x interrupt mask register, Address offset: 0x14 */ - __IO uint32_t SR; /*!< SAI block x status register, Address offset: 0x18 */ - __IO uint32_t CLRFR; /*!< SAI block x clear flag register, Address offset: 0x1C */ - __IO uint32_t DR; /*!< SAI block x data register, Address offset: 0x20 */ -} SAI_Block_TypeDef; - -/** - * @brief SD host Interface - */ - -typedef struct -{ - __IO uint32_t POWER; /*!< SDIO power control register, Address offset: 0x00 */ - __IO uint32_t CLKCR; /*!< SDI clock control register, Address offset: 0x04 */ - __IO uint32_t ARG; /*!< SDIO argument register, Address offset: 0x08 */ - __IO uint32_t CMD; /*!< SDIO command register, Address offset: 0x0C */ - __IO const uint32_t RESPCMD; /*!< SDIO command response register, Address offset: 0x10 */ - __IO const uint32_t RESP1; /*!< SDIO response 1 register, Address offset: 0x14 */ - __IO const uint32_t RESP2; /*!< SDIO response 2 register, Address offset: 0x18 */ - __IO const uint32_t RESP3; /*!< SDIO response 3 register, Address offset: 0x1C */ - __IO const uint32_t RESP4; /*!< SDIO response 4 register, Address offset: 0x20 */ - __IO uint32_t DTIMER; /*!< SDIO data timer register, Address offset: 0x24 */ - __IO uint32_t DLEN; /*!< SDIO data length register, Address offset: 0x28 */ - __IO uint32_t DCTRL; /*!< SDIO data control register, Address offset: 0x2C */ - __IO const uint32_t DCOUNT; /*!< SDIO data counter register, Address offset: 0x30 */ - __IO const uint32_t STA; /*!< SDIO status register, Address offset: 0x34 */ - __IO uint32_t ICR; /*!< SDIO interrupt clear register, Address offset: 0x38 */ - __IO uint32_t MASK; /*!< SDIO mask register, Address offset: 0x3C */ - uint32_t RESERVED0[2]; /*!< Reserved, 0x40-0x44 */ - __IO const uint32_t FIFOCNT; /*!< SDIO FIFO counter register, Address offset: 0x48 */ - uint32_t RESERVED1[13]; /*!< Reserved, 0x4C-0x7C */ - __IO uint32_t FIFO; /*!< SDIO data FIFO register, Address offset: 0x80 */ -} SDIO_TypeDef; - -/** - * @brief Serial Peripheral Interface - */ - -typedef struct -{ - __IO uint32_t CR1; /*!< SPI control register 1 (not used in I2S mode), Address offset: 0x00 */ - __IO uint32_t CR2; /*!< SPI control register 2, Address offset: 0x04 */ - __IO uint32_t SR; /*!< SPI status register, Address offset: 0x08 */ - __IO uint32_t DR; /*!< SPI data register, Address offset: 0x0C */ - __IO uint32_t CRCPR; /*!< SPI CRC polynomial register (not used in I2S mode), Address offset: 0x10 */ - __IO uint32_t RXCRCR; /*!< SPI RX CRC register (not used in I2S mode), Address offset: 0x14 */ - __IO uint32_t TXCRCR; /*!< SPI TX CRC register (not used in I2S mode), Address offset: 0x18 */ - __IO uint32_t I2SCFGR; /*!< SPI_I2S configuration register, Address offset: 0x1C */ - __IO uint32_t I2SPR; /*!< SPI_I2S prescaler register, Address offset: 0x20 */ -} SPI_TypeDef; - -/** - * @brief QUAD Serial Peripheral Interface - */ - -typedef struct -{ - __IO uint32_t CR; /*!< QUADSPI Control register, Address offset: 0x00 */ - __IO uint32_t DCR; /*!< QUADSPI Device Configuration register, Address offset: 0x04 */ - __IO uint32_t SR; /*!< QUADSPI Status register, Address offset: 0x08 */ - __IO uint32_t FCR; /*!< QUADSPI Flag Clear register, Address offset: 0x0C */ - __IO uint32_t DLR; /*!< QUADSPI Data Length register, Address offset: 0x10 */ - __IO uint32_t CCR; /*!< QUADSPI Communication Configuration register, Address offset: 0x14 */ - __IO uint32_t AR; /*!< QUADSPI Address register, Address offset: 0x18 */ - __IO uint32_t ABR; /*!< QUADSPI Alternate Bytes register, Address offset: 0x1C */ - __IO uint32_t DR; /*!< QUADSPI Data register, Address offset: 0x20 */ - __IO uint32_t PSMKR; /*!< QUADSPI Polling Status Mask register, Address offset: 0x24 */ - __IO uint32_t PSMAR; /*!< QUADSPI Polling Status Match register, Address offset: 0x28 */ - __IO uint32_t PIR; /*!< QUADSPI Polling Interval register, Address offset: 0x2C */ - __IO uint32_t LPTR; /*!< QUADSPI Low Power Timeout register, Address offset: 0x30 */ -} QUADSPI_TypeDef; - -/** - * @brief TIM - */ - -typedef struct -{ - __IO uint32_t CR1; /*!< TIM control register 1, Address offset: 0x00 */ - __IO uint32_t CR2; /*!< TIM control register 2, Address offset: 0x04 */ - __IO uint32_t SMCR; /*!< TIM slave mode control register, Address offset: 0x08 */ - __IO uint32_t DIER; /*!< TIM DMA/interrupt enable register, Address offset: 0x0C */ - __IO uint32_t SR; /*!< TIM status register, Address offset: 0x10 */ - __IO uint32_t EGR; /*!< TIM event generation register, Address offset: 0x14 */ - __IO uint32_t CCMR1; /*!< TIM capture/compare mode register 1, Address offset: 0x18 */ - __IO uint32_t CCMR2; /*!< TIM capture/compare mode register 2, Address offset: 0x1C */ - __IO uint32_t CCER; /*!< TIM capture/compare enable register, Address offset: 0x20 */ - __IO uint32_t CNT; /*!< TIM counter register, Address offset: 0x24 */ - __IO uint32_t PSC; /*!< TIM prescaler, Address offset: 0x28 */ - __IO uint32_t ARR; /*!< TIM auto-reload register, Address offset: 0x2C */ - __IO uint32_t RCR; /*!< TIM repetition counter register, Address offset: 0x30 */ - __IO uint32_t CCR1; /*!< TIM capture/compare register 1, Address offset: 0x34 */ - __IO uint32_t CCR2; /*!< TIM capture/compare register 2, Address offset: 0x38 */ - __IO uint32_t CCR3; /*!< TIM capture/compare register 3, Address offset: 0x3C */ - __IO uint32_t CCR4; /*!< TIM capture/compare register 4, Address offset: 0x40 */ - __IO uint32_t BDTR; /*!< TIM break and dead-time register, Address offset: 0x44 */ - __IO uint32_t DCR; /*!< TIM DMA control register, Address offset: 0x48 */ - __IO uint32_t DMAR; /*!< TIM DMA address for full transfer, Address offset: 0x4C */ - __IO uint32_t OR; /*!< TIM option register, Address offset: 0x50 */ -} TIM_TypeDef; - -/** - * @brief Universal Synchronous Asynchronous Receiver Transmitter - */ - -typedef struct -{ - __IO uint32_t SR; /*!< USART Status register, Address offset: 0x00 */ - __IO uint32_t DR; /*!< USART Data register, Address offset: 0x04 */ - __IO uint32_t BRR; /*!< USART Baud rate register, Address offset: 0x08 */ - __IO uint32_t CR1; /*!< USART Control register 1, Address offset: 0x0C */ - __IO uint32_t CR2; /*!< USART Control register 2, Address offset: 0x10 */ - __IO uint32_t CR3; /*!< USART Control register 3, Address offset: 0x14 */ - __IO uint32_t GTPR; /*!< USART Guard time and prescaler register, Address offset: 0x18 */ -} USART_TypeDef; - -/** - * @brief Window WATCHDOG - */ - -typedef struct -{ - __IO uint32_t CR; /*!< WWDG Control register, Address offset: 0x00 */ - __IO uint32_t CFR; /*!< WWDG Configuration register, Address offset: 0x04 */ - __IO uint32_t SR; /*!< WWDG Status register, Address offset: 0x08 */ -} WWDG_TypeDef; - -/** - * @brief RNG - */ - -typedef struct -{ - __IO uint32_t CR; /*!< RNG control register, Address offset: 0x00 */ - __IO uint32_t SR; /*!< RNG status register, Address offset: 0x04 */ - __IO uint32_t DR; /*!< RNG data register, Address offset: 0x08 */ -} RNG_TypeDef; - -/** - * @brief USB_OTG_Core_Registers - */ -typedef struct -{ - __IO uint32_t GOTGCTL; /*!< USB_OTG Control and Status Register 000h */ - __IO uint32_t GOTGINT; /*!< USB_OTG Interrupt Register 004h */ - __IO uint32_t GAHBCFG; /*!< Core AHB Configuration Register 008h */ - __IO uint32_t GUSBCFG; /*!< Core USB Configuration Register 00Ch */ - __IO uint32_t GRSTCTL; /*!< Core Reset Register 010h */ - __IO uint32_t GINTSTS; /*!< Core Interrupt Register 014h */ - __IO uint32_t GINTMSK; /*!< Core Interrupt Mask Register 018h */ - __IO uint32_t GRXSTSR; /*!< Receive Sts Q Read Register 01Ch */ - __IO uint32_t GRXSTSP; /*!< Receive Sts Q Read & POP Register 020h */ - __IO uint32_t GRXFSIZ; /*!< Receive FIFO Size Register 024h */ - __IO uint32_t DIEPTXF0_HNPTXFSIZ; /*!< EP0 / Non Periodic Tx FIFO Size Register 028h */ - __IO uint32_t HNPTXSTS; /*!< Non Periodic Tx FIFO/Queue Sts reg 02Ch */ - uint32_t Reserved30[2]; /*!< Reserved 030h */ - __IO uint32_t GCCFG; /*!< General Purpose IO Register 038h */ - __IO uint32_t CID; /*!< User ID Register 03Ch */ - uint32_t Reserved5[3]; /*!< Reserved 040h-048h */ - __IO uint32_t GHWCFG3; /*!< User HW config3 04Ch */ - uint32_t Reserved6; /*!< Reserved 050h */ - __IO uint32_t GLPMCFG; /*!< LPM Register 054h */ - uint32_t Reserved; /*!< Reserved 058h */ - __IO uint32_t GDFIFOCFG; /*!< DFIFO Software Config Register 05Ch */ - uint32_t Reserved43[40]; /*!< Reserved 058h-0FFh */ - __IO uint32_t HPTXFSIZ; /*!< Host Periodic Tx FIFO Size Reg 100h */ - __IO uint32_t DIEPTXF[0x0F]; /*!< dev Periodic Transmit FIFO */ -} USB_OTG_GlobalTypeDef; - -/** - * @brief USB_OTG_device_Registers - */ -typedef struct -{ - __IO uint32_t DCFG; /*!< dev Configuration Register 800h */ - __IO uint32_t DCTL; /*!< dev Control Register 804h */ - __IO uint32_t DSTS; /*!< dev Status Register (RO) 808h */ - uint32_t Reserved0C; /*!< Reserved 80Ch */ - __IO uint32_t DIEPMSK; /*!< dev IN Endpoint Mask 810h */ - __IO uint32_t DOEPMSK; /*!< dev OUT Endpoint Mask 814h */ - __IO uint32_t DAINT; /*!< dev All Endpoints Itr Reg 818h */ - __IO uint32_t DAINTMSK; /*!< dev All Endpoints Itr Mask 81Ch */ - uint32_t Reserved20; /*!< Reserved 820h */ - uint32_t Reserved9; /*!< Reserved 824h */ - __IO uint32_t DVBUSDIS; /*!< dev VBUS discharge Register 828h */ - __IO uint32_t DVBUSPULSE; /*!< dev VBUS Pulse Register 82Ch */ - __IO uint32_t DTHRCTL; /*!< dev threshold 830h */ - __IO uint32_t DIEPEMPMSK; /*!< dev empty msk 834h */ - __IO uint32_t DEACHINT; /*!< dedicated EP interrupt 838h */ - __IO uint32_t DEACHMSK; /*!< dedicated EP msk 83Ch */ - uint32_t Reserved40; /*!< dedicated EP mask 840h */ - __IO uint32_t DINEP1MSK; /*!< dedicated EP mask 844h */ - uint32_t Reserved44[15]; /*!< Reserved 844-87Ch */ - __IO uint32_t DOUTEP1MSK; /*!< dedicated EP msk 884h */ -} USB_OTG_DeviceTypeDef; - -/** - * @brief USB_OTG_IN_Endpoint-Specific_Register - */ -typedef struct -{ - __IO uint32_t DIEPCTL; /*!< dev IN Endpoint Control Reg 900h + (ep_num * 20h) + 00h */ - uint32_t Reserved04; /*!< Reserved 900h + (ep_num * 20h) + 04h */ - __IO uint32_t DIEPINT; /*!< dev IN Endpoint Itr Reg 900h + (ep_num * 20h) + 08h */ - uint32_t Reserved0C; /*!< Reserved 900h + (ep_num * 20h) + 0Ch */ - __IO uint32_t DIEPTSIZ; /*!< IN Endpoint Txfer Size 900h + (ep_num * 20h) + 10h */ - __IO uint32_t DIEPDMA; /*!< IN Endpoint DMA Address Reg 900h + (ep_num * 20h) + 14h */ - __IO uint32_t DTXFSTS; /*!< IN Endpoint Tx FIFO Status Reg 900h + (ep_num * 20h) + 18h */ - uint32_t Reserved18; /*!< Reserved 900h+(ep_num*20h)+1Ch-900h+ (ep_num * 20h) + 1Ch */ -} USB_OTG_INEndpointTypeDef; - -/** - * @brief USB_OTG_OUT_Endpoint-Specific_Registers - */ -typedef struct -{ - __IO uint32_t DOEPCTL; /*!< dev OUT Endpoint Control Reg B00h + (ep_num * 20h) + 00h */ - uint32_t Reserved04; /*!< Reserved B00h + (ep_num * 20h) + 04h */ - __IO uint32_t DOEPINT; /*!< dev OUT Endpoint Itr Reg B00h + (ep_num * 20h) + 08h */ - uint32_t Reserved0C; /*!< Reserved B00h + (ep_num * 20h) + 0Ch */ - __IO uint32_t DOEPTSIZ; /*!< dev OUT Endpoint Txfer Size B00h + (ep_num * 20h) + 10h */ - __IO uint32_t DOEPDMA; /*!< dev OUT Endpoint DMA Address B00h + (ep_num * 20h) + 14h */ - uint32_t Reserved18[2]; /*!< Reserved B00h + (ep_num * 20h) + 18h - B00h + (ep_num * 20h) + 1Ch */ -} USB_OTG_OUTEndpointTypeDef; - -/** - * @brief USB_OTG_Host_Mode_Register_Structures - */ -typedef struct -{ - __IO uint32_t HCFG; /*!< Host Configuration Register 400h */ - __IO uint32_t HFIR; /*!< Host Frame Interval Register 404h */ - __IO uint32_t HFNUM; /*!< Host Frame Nbr/Frame Remaining 408h */ - uint32_t Reserved40C; /*!< Reserved 40Ch */ - __IO uint32_t HPTXSTS; /*!< Host Periodic Tx FIFO/ Queue Status 410h */ - __IO uint32_t HAINT; /*!< Host All Channels Interrupt Register 414h */ - __IO uint32_t HAINTMSK; /*!< Host All Channels Interrupt Mask 418h */ -} USB_OTG_HostTypeDef; - -/** - * @brief USB_OTG_Host_Channel_Specific_Registers - */ -typedef struct -{ - __IO uint32_t HCCHAR; /*!< Host Channel Characteristics Register 500h */ - __IO uint32_t HCSPLT; /*!< Host Channel Split Control Register 504h */ - __IO uint32_t HCINT; /*!< Host Channel Interrupt Register 508h */ - __IO uint32_t HCINTMSK; /*!< Host Channel Interrupt Mask Register 50Ch */ - __IO uint32_t HCTSIZ; /*!< Host Channel Transfer Size Register 510h */ - __IO uint32_t HCDMA; /*!< Host Channel DMA Address Register 514h */ - uint32_t Reserved[2]; /*!< Reserved */ -} USB_OTG_HostChannelTypeDef; - -/** - * @brief LPTIMER - */ -typedef struct -{ - __IO uint32_t ISR; /*!< LPTIM Interrupt and Status register, Address offset: 0x00 */ - __IO uint32_t ICR; /*!< LPTIM Interrupt Clear register, Address offset: 0x04 */ - __IO uint32_t IER; /*!< LPTIM Interrupt Enable register, Address offset: 0x08 */ - __IO uint32_t CFGR; /*!< LPTIM Configuration register, Address offset: 0x0C */ - __IO uint32_t CR; /*!< LPTIM Control register, Address offset: 0x10 */ - __IO uint32_t CMP; /*!< LPTIM Compare register, Address offset: 0x14 */ - __IO uint32_t ARR; /*!< LPTIM Autoreload register, Address offset: 0x18 */ - __IO uint32_t CNT; /*!< LPTIM Counter register, Address offset: 0x1C */ - __IO uint32_t OR; /*!< LPTIM Option register, Address offset: 0x20 */ -} LPTIM_TypeDef; - -/** - * @} - */ - -/** @addtogroup Peripheral_memory_map - * @{ - */ -#define FLASH_BASE 0x08000000U /*!< FLASH (up to 1.5 MB) base address in the alias region */ -#define SRAM1_BASE 0x20000000U /*!< SRAM1(256 KB) base address in the alias region */ -#define SRAM2_BASE 0x20040000U /*!< SRAM2(64 KB) base address in the alias region */ -#define PERIPH_BASE 0x40000000U /*!< Peripheral base address in the alias region */ -#define FSMC_R_BASE 0xA0000000U /*!< FSMC registers base address */ -#define QSPI_R_BASE 0xA0001000U /*!< QuadSPI registers base address */ -#define SRAM1_BB_BASE 0x22000000U /*!< SRAM1(256 KB) base address in the bit-band region */ -#define SRAM2_BB_BASE 0x22800000U /*!< SRAM2(64 KB) base address in the bit-band region */ -#define PERIPH_BB_BASE 0x42000000U /*!< Peripheral base address in the bit-band region */ -#define FLASH_END 0x0817FFFFU /*!< FLASH end address */ - -/* Legacy defines */ -#define SRAM_BASE SRAM1_BASE -#define SRAM_BB_BASE SRAM1_BB_BASE - - -/*!< Peripheral memory map */ -#define APB1PERIPH_BASE PERIPH_BASE -#define APB2PERIPH_BASE (PERIPH_BASE + 0x00010000U) -#define AHB1PERIPH_BASE (PERIPH_BASE + 0x00020000U) -#define AHB2PERIPH_BASE (PERIPH_BASE + 0x10000000U) - -/*!< APB1 peripherals */ -#define TIM2_BASE (APB1PERIPH_BASE + 0x0000U) -#define TIM3_BASE (APB1PERIPH_BASE + 0x0400U) -#define TIM4_BASE (APB1PERIPH_BASE + 0x0800U) -#define TIM5_BASE (APB1PERIPH_BASE + 0x0C00U) -#define TIM6_BASE (APB1PERIPH_BASE + 0x1000U) -#define TIM7_BASE (APB1PERIPH_BASE + 0x1400U) -#define TIM12_BASE (APB1PERIPH_BASE + 0x1800U) -#define TIM13_BASE (APB1PERIPH_BASE + 0x1C00U) -#define TIM14_BASE (APB1PERIPH_BASE + 0x2000U) -#define LPTIM1_BASE (APB1PERIPH_BASE + 0x2400U) -#define RTC_BASE (APB1PERIPH_BASE + 0x2800U) -#define WWDG_BASE (APB1PERIPH_BASE + 0x2C00U) -#define IWDG_BASE (APB1PERIPH_BASE + 0x3000U) -#define I2S2ext_BASE (APB1PERIPH_BASE + 0x3400U) -#define SPI2_BASE (APB1PERIPH_BASE + 0x3800U) -#define SPI3_BASE (APB1PERIPH_BASE + 0x3C00U) -#define I2S3ext_BASE (APB1PERIPH_BASE + 0x4000U) -#define USART2_BASE (APB1PERIPH_BASE + 0x4400U) -#define USART3_BASE (APB1PERIPH_BASE + 0x4800U) -#define UART4_BASE (APB1PERIPH_BASE + 0x4C00U) -#define UART5_BASE (APB1PERIPH_BASE + 0x5000U) -#define I2C1_BASE (APB1PERIPH_BASE + 0x5400U) -#define I2C2_BASE (APB1PERIPH_BASE + 0x5800U) -#define I2C3_BASE (APB1PERIPH_BASE + 0x5C00U) -#define FMPI2C1_BASE (APB1PERIPH_BASE + 0x6000U) -#define CAN1_BASE (APB1PERIPH_BASE + 0x6400U) -#define CAN2_BASE (APB1PERIPH_BASE + 0x6800U) -#define CAN3_BASE (APB1PERIPH_BASE + 0x6C00U) -#define PWR_BASE (APB1PERIPH_BASE + 0x7000U) -#define DAC_BASE (APB1PERIPH_BASE + 0x7400U) -#define UART7_BASE (APB1PERIPH_BASE + 0x7800U) -#define UART8_BASE (APB1PERIPH_BASE + 0x7C00U) - -/*!< APB2 peripherals */ -#define TIM1_BASE (APB2PERIPH_BASE + 0x0000U) -#define TIM8_BASE (APB2PERIPH_BASE + 0x0400U) -#define USART1_BASE (APB2PERIPH_BASE + 0x1000U) -#define USART6_BASE (APB2PERIPH_BASE + 0x1400U) -#define UART9_BASE (APB2PERIPH_BASE + 0x1800U) -#define UART10_BASE (APB2PERIPH_BASE + 0x1C00U) -#define ADC1_BASE (APB2PERIPH_BASE + 0x2000U) -#define ADC_BASE (APB2PERIPH_BASE + 0x2300U) -#define SDIO_BASE (APB2PERIPH_BASE + 0x2C00U) -#define SPI1_BASE (APB2PERIPH_BASE + 0x3000U) -#define SPI4_BASE (APB2PERIPH_BASE + 0x3400U) -#define SYSCFG_BASE (APB2PERIPH_BASE + 0x3800U) -#define EXTI_BASE (APB2PERIPH_BASE + 0x3C00U) -#define TIM9_BASE (APB2PERIPH_BASE + 0x4000U) -#define TIM10_BASE (APB2PERIPH_BASE + 0x4400U) -#define TIM11_BASE (APB2PERIPH_BASE + 0x4800U) -#define SPI5_BASE (APB2PERIPH_BASE + 0x5000U) -#define DFSDM1_BASE (APB2PERIPH_BASE + 0x6000U) -#define DFSDM2_BASE (APB2PERIPH_BASE + 0x6400U) -#define DFSDM1_Channel0_BASE (DFSDM1_BASE + 0x00U) -#define DFSDM1_Channel1_BASE (DFSDM1_BASE + 0x20U) -#define DFSDM1_Channel2_BASE (DFSDM1_BASE + 0x40U) -#define DFSDM1_Channel3_BASE (DFSDM1_BASE + 0x60U) -#define DFSDM1_Filter0_BASE (DFSDM1_BASE + 0x100U) -#define DFSDM1_Filter1_BASE (DFSDM1_BASE + 0x180U) -#define DFSDM2_Channel0_BASE (DFSDM2_BASE + 0x00U) -#define DFSDM2_Channel1_BASE (DFSDM2_BASE + 0x20U) -#define DFSDM2_Channel2_BASE (DFSDM2_BASE + 0x40U) -#define DFSDM2_Channel3_BASE (DFSDM2_BASE + 0x60U) -#define DFSDM2_Channel4_BASE (DFSDM2_BASE + 0x80U) -#define DFSDM2_Channel5_BASE (DFSDM2_BASE + 0xA0U) -#define DFSDM2_Channel6_BASE (DFSDM2_BASE + 0xC0U) -#define DFSDM2_Channel7_BASE (DFSDM2_BASE + 0xE0U) -#define DFSDM2_Filter0_BASE (DFSDM2_BASE + 0x100U) -#define DFSDM2_Filter1_BASE (DFSDM2_BASE + 0x180U) -#define DFSDM2_Filter2_BASE (DFSDM2_BASE + 0x200U) -#define DFSDM2_Filter3_BASE (DFSDM2_BASE + 0x280U) -#define SAI1_BASE (APB2PERIPH_BASE + 0x5800U) -#define SAI1_Block_A_BASE (SAI1_BASE + 0x004U) -#define SAI1_Block_B_BASE (SAI1_BASE + 0x024U) - -/*!< AHB1 peripherals */ -#define GPIOA_BASE (AHB1PERIPH_BASE + 0x0000U) -#define GPIOB_BASE (AHB1PERIPH_BASE + 0x0400U) -#define GPIOC_BASE (AHB1PERIPH_BASE + 0x0800U) -#define GPIOD_BASE (AHB1PERIPH_BASE + 0x0C00U) -#define GPIOE_BASE (AHB1PERIPH_BASE + 0x1000U) -#define GPIOF_BASE (AHB1PERIPH_BASE + 0x1400U) -#define GPIOG_BASE (AHB1PERIPH_BASE + 0x1800U) -#define GPIOH_BASE (AHB1PERIPH_BASE + 0x1C00U) -#define CRC_BASE (AHB1PERIPH_BASE + 0x3000U) -#define RCC_BASE (AHB1PERIPH_BASE + 0x3800U) -#define FLASH_R_BASE (AHB1PERIPH_BASE + 0x3C00U) -#define DMA1_BASE (AHB1PERIPH_BASE + 0x6000U) -#define DMA1_Stream0_BASE (DMA1_BASE + 0x010U) -#define DMA1_Stream1_BASE (DMA1_BASE + 0x028U) -#define DMA1_Stream2_BASE (DMA1_BASE + 0x040U) -#define DMA1_Stream3_BASE (DMA1_BASE + 0x058U) -#define DMA1_Stream4_BASE (DMA1_BASE + 0x070U) -#define DMA1_Stream5_BASE (DMA1_BASE + 0x088U) -#define DMA1_Stream6_BASE (DMA1_BASE + 0x0A0U) -#define DMA1_Stream7_BASE (DMA1_BASE + 0x0B8U) -#define DMA2_BASE (AHB1PERIPH_BASE + 0x6400U) -#define DMA2_Stream0_BASE (DMA2_BASE + 0x010U) -#define DMA2_Stream1_BASE (DMA2_BASE + 0x028U) -#define DMA2_Stream2_BASE (DMA2_BASE + 0x040U) -#define DMA2_Stream3_BASE (DMA2_BASE + 0x058U) -#define DMA2_Stream4_BASE (DMA2_BASE + 0x070U) -#define DMA2_Stream5_BASE (DMA2_BASE + 0x088U) -#define DMA2_Stream6_BASE (DMA2_BASE + 0x0A0U) -#define DMA2_Stream7_BASE (DMA2_BASE + 0x0B8U) - -/*!< AHB2 peripherals */ -#define RNG_BASE (AHB2PERIPH_BASE + 0x60800U) - - -/*!< FSMC Bankx registers base address */ -#define FSMC_Bank1_R_BASE (FSMC_R_BASE + 0x0000U) -#define FSMC_Bank1E_R_BASE (FSMC_R_BASE + 0x0104U) - -/*!< Debug MCU registers base address */ -#define DBGMCU_BASE 0xE0042000U -/*!< USB registers base address */ -#define USB_OTG_FS_PERIPH_BASE 0x50000000U - -#define USB_OTG_GLOBAL_BASE 0x000U -#define USB_OTG_DEVICE_BASE 0x800U -#define USB_OTG_IN_ENDPOINT_BASE 0x900U -#define USB_OTG_OUT_ENDPOINT_BASE 0xB00U -#define USB_OTG_EP_REG_SIZE 0x20U -#define USB_OTG_HOST_BASE 0x400U -#define USB_OTG_HOST_PORT_BASE 0x440U -#define USB_OTG_HOST_CHANNEL_BASE 0x500U -#define USB_OTG_HOST_CHANNEL_SIZE 0x20U -#define USB_OTG_PCGCCTL_BASE 0xE00U -#define USB_OTG_FIFO_BASE 0x1000U -#define USB_OTG_FIFO_SIZE 0x1000U - -#define UID_BASE 0x1FFF7A10U /*!< Unique device ID register base address */ -#define FLASHSIZE_BASE 0x1FFF7A22U /*!< FLASH Size register base address */ -#define PACKAGE_BASE 0x1FFF7BF0U /*!< Package size register base address */ -/** - * @} - */ - -/** @addtogroup Peripheral_declaration - * @{ - */ -#define TIM2 ((TIM_TypeDef *) TIM2_BASE) -#define TIM3 ((TIM_TypeDef *) TIM3_BASE) -#define TIM4 ((TIM_TypeDef *) TIM4_BASE) -#define TIM5 ((TIM_TypeDef *) TIM5_BASE) -#define TIM6 ((TIM_TypeDef *) TIM6_BASE) -#define TIM7 ((TIM_TypeDef *) TIM7_BASE) -#define TIM12 ((TIM_TypeDef *) TIM12_BASE) -#define TIM13 ((TIM_TypeDef *) TIM13_BASE) -#define TIM14 ((TIM_TypeDef *) TIM14_BASE) -#define LPTIM1 ((LPTIM_TypeDef *) LPTIM1_BASE) -#define RTC ((RTC_TypeDef *) RTC_BASE) -#define WWDG ((WWDG_TypeDef *) WWDG_BASE) -#define IWDG ((IWDG_TypeDef *) IWDG_BASE) -#define I2S2ext ((SPI_TypeDef *) I2S2ext_BASE) -#define SPI2 ((SPI_TypeDef *) SPI2_BASE) -#define SPI3 ((SPI_TypeDef *) SPI3_BASE) -#define I2S3ext ((SPI_TypeDef *) I2S3ext_BASE) -#define USART2 ((USART_TypeDef *) USART2_BASE) -#define USART3 ((USART_TypeDef *) USART3_BASE) -#define UART4 ((USART_TypeDef *) UART4_BASE) -#define UART5 ((USART_TypeDef *) UART5_BASE) -#define I2C1 ((I2C_TypeDef *) I2C1_BASE) -#define I2C2 ((I2C_TypeDef *) I2C2_BASE) -#define I2C3 ((I2C_TypeDef *) I2C3_BASE) -#define FMPI2C1 ((FMPI2C_TypeDef *) FMPI2C1_BASE) -#define CAN1 ((CAN_TypeDef *) CAN1_BASE) -#define CAN2 ((CAN_TypeDef *) CAN2_BASE) -#define CAN3 ((CAN_TypeDef *) CAN3_BASE) -#define PWR ((PWR_TypeDef *) PWR_BASE) -#define DAC1 ((DAC_TypeDef *) DAC_BASE) -#define DAC ((DAC_TypeDef *) DAC_BASE) /* Kept for legacy purpose */ -#define UART7 ((USART_TypeDef *) UART7_BASE) -#define UART8 ((USART_TypeDef *) UART8_BASE) -#define TIM1 ((TIM_TypeDef *) TIM1_BASE) -#define TIM8 ((TIM_TypeDef *) TIM8_BASE) -#define USART1 ((USART_TypeDef *) USART1_BASE) -#define USART6 ((USART_TypeDef *) USART6_BASE) -#define UART9 ((USART_TypeDef *) UART9_BASE) -#define UART10 ((USART_TypeDef *) UART10_BASE) -#define ADC ((ADC_Common_TypeDef *) ADC_BASE) -#define ADC1 ((ADC_TypeDef *) ADC1_BASE) -#define SDIO ((SDIO_TypeDef *) SDIO_BASE) -#define SPI1 ((SPI_TypeDef *) SPI1_BASE) -#define SPI4 ((SPI_TypeDef *) SPI4_BASE) -#define SYSCFG ((SYSCFG_TypeDef *) SYSCFG_BASE) -#define EXTI ((EXTI_TypeDef *) EXTI_BASE) -#define TIM9 ((TIM_TypeDef *) TIM9_BASE) -#define TIM10 ((TIM_TypeDef *) TIM10_BASE) -#define TIM11 ((TIM_TypeDef *) TIM11_BASE) -#define SPI5 ((SPI_TypeDef *) SPI5_BASE) -#define DFSDM1_Channel0 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel0_BASE) -#define DFSDM1_Channel1 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel1_BASE) -#define DFSDM1_Channel2 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel2_BASE) -#define DFSDM1_Channel3 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel3_BASE) -#define DFSDM1_Filter0 ((DFSDM_Filter_TypeDef *) DFSDM1_Filter0_BASE) -#define DFSDM1_Filter1 ((DFSDM_Filter_TypeDef *) DFSDM1_Filter1_BASE) -#define DFSDM2_Channel0 ((DFSDM_Channel_TypeDef *) DFSDM2_Channel0_BASE) -#define DFSDM2_Channel1 ((DFSDM_Channel_TypeDef *) DFSDM2_Channel1_BASE) -#define DFSDM2_Channel2 ((DFSDM_Channel_TypeDef *) DFSDM2_Channel2_BASE) -#define DFSDM2_Channel3 ((DFSDM_Channel_TypeDef *) DFSDM2_Channel3_BASE) -#define DFSDM2_Channel4 ((DFSDM_Channel_TypeDef *) DFSDM2_Channel4_BASE) -#define DFSDM2_Channel5 ((DFSDM_Channel_TypeDef *) DFSDM2_Channel5_BASE) -#define DFSDM2_Channel6 ((DFSDM_Channel_TypeDef *) DFSDM2_Channel6_BASE) -#define DFSDM2_Channel7 ((DFSDM_Channel_TypeDef *) DFSDM2_Channel7_BASE) -#define DFSDM2_Filter0 ((DFSDM_Filter_TypeDef *) DFSDM2_Filter0_BASE) -#define DFSDM2_Filter1 ((DFSDM_Filter_TypeDef *) DFSDM2_Filter1_BASE) -#define DFSDM2_Filter2 ((DFSDM_Filter_TypeDef *) DFSDM2_Filter2_BASE) -#define DFSDM2_Filter3 ((DFSDM_Filter_TypeDef *) DFSDM2_Filter3_BASE) -#define SAI1 ((SAI_TypeDef *) SAI1_BASE) -#define SAI1_Block_A ((SAI_Block_TypeDef *)SAI1_Block_A_BASE) -#define SAI1_Block_B ((SAI_Block_TypeDef *)SAI1_Block_B_BASE) -#define GPIOA ((GPIO_TypeDef *) GPIOA_BASE) -#define GPIOB ((GPIO_TypeDef *) GPIOB_BASE) -#define GPIOC ((GPIO_TypeDef *) GPIOC_BASE) -#define GPIOD ((GPIO_TypeDef *) GPIOD_BASE) -#define GPIOE ((GPIO_TypeDef *) GPIOE_BASE) -#define GPIOF ((GPIO_TypeDef *) GPIOF_BASE) -#define GPIOG ((GPIO_TypeDef *) GPIOG_BASE) -#define GPIOH ((GPIO_TypeDef *) GPIOH_BASE) -#define CRC ((CRC_TypeDef *) CRC_BASE) -#define RCC ((RCC_TypeDef *) RCC_BASE) -#define FLASH ((FLASH_TypeDef *) FLASH_R_BASE) -#define DMA1 ((DMA_TypeDef *) DMA1_BASE) -#define DMA1_Stream0 ((DMA_Stream_TypeDef *) DMA1_Stream0_BASE) -#define DMA1_Stream1 ((DMA_Stream_TypeDef *) DMA1_Stream1_BASE) -#define DMA1_Stream2 ((DMA_Stream_TypeDef *) DMA1_Stream2_BASE) -#define DMA1_Stream3 ((DMA_Stream_TypeDef *) DMA1_Stream3_BASE) -#define DMA1_Stream4 ((DMA_Stream_TypeDef *) DMA1_Stream4_BASE) -#define DMA1_Stream5 ((DMA_Stream_TypeDef *) DMA1_Stream5_BASE) -#define DMA1_Stream6 ((DMA_Stream_TypeDef *) DMA1_Stream6_BASE) -#define DMA1_Stream7 ((DMA_Stream_TypeDef *) DMA1_Stream7_BASE) -#define DMA2 ((DMA_TypeDef *) DMA2_BASE) -#define DMA2_Stream0 ((DMA_Stream_TypeDef *) DMA2_Stream0_BASE) -#define DMA2_Stream1 ((DMA_Stream_TypeDef *) DMA2_Stream1_BASE) -#define DMA2_Stream2 ((DMA_Stream_TypeDef *) DMA2_Stream2_BASE) -#define DMA2_Stream3 ((DMA_Stream_TypeDef *) DMA2_Stream3_BASE) -#define DMA2_Stream4 ((DMA_Stream_TypeDef *) DMA2_Stream4_BASE) -#define DMA2_Stream5 ((DMA_Stream_TypeDef *) DMA2_Stream5_BASE) -#define DMA2_Stream6 ((DMA_Stream_TypeDef *) DMA2_Stream6_BASE) -#define DMA2_Stream7 ((DMA_Stream_TypeDef *) DMA2_Stream7_BASE) -#define RNG ((RNG_TypeDef *) RNG_BASE) -#define FSMC_Bank1 ((FSMC_Bank1_TypeDef *) FSMC_Bank1_R_BASE) -#define FSMC_Bank1E ((FSMC_Bank1E_TypeDef *) FSMC_Bank1E_R_BASE) -#define QUADSPI ((QUADSPI_TypeDef *) QSPI_R_BASE) -#define DBGMCU ((DBGMCU_TypeDef *) DBGMCU_BASE) -#define USB_OTG_FS ((USB_OTG_GlobalTypeDef *) USB_OTG_FS_PERIPH_BASE) - -/** - * @} - */ - -/** @addtogroup Exported_constants - * @{ - */ - - /** @addtogroup Peripheral_Registers_Bits_Definition - * @{ - */ - -/******************************************************************************/ -/* Peripheral Registers_Bits_Definition */ -/******************************************************************************/ - -/******************************************************************************/ -/* */ -/* Analog to Digital Converter */ -/* */ -/******************************************************************************/ -/******************** Bit definition for ADC_SR register ********************/ -#define ADC_SR_AWD_Pos (0U) -#define ADC_SR_AWD_Msk (0x1U << ADC_SR_AWD_Pos) /*!< 0x00000001 */ -#define ADC_SR_AWD ADC_SR_AWD_Msk /*!
© COPYRIGHT(c) 2016 STMicroelectronics
- * - * Redistribution and use in source and binary forms, with or without modification, - * are permitted provided that the following conditions are met: - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE - * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL - * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR - * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, - * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE - * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************** - */ - -/** @addtogroup CMSIS - * @{ - */ - -/** @addtogroup stm32f4xx - * @{ - */ - -#ifndef __STM32F4xx_H -#define __STM32F4xx_H - -#ifdef __cplusplus - extern "C" { -#endif /* __cplusplus */ - -/** @addtogroup Library_configuration_section - * @{ - */ - -/** - * @brief STM32 Family - */ -#if !defined (STM32F4) -#define STM32F4 -#endif /* STM32F4 */ - -/* Uncomment the line below according to the target STM32 device used in your - application - */ -/* #if !defined (STM32F405xx) && !defined (STM32F415xx) && !defined (STM32F407xx) && !defined (STM32F417xx) && \ - !defined (STM32F427xx) && !defined (STM32F437xx) && !defined (STM32F429xx) && !defined (STM32F439xx) && \ - !defined (STM32F401xC) && !defined (STM32F401xE) && !defined (STM32F410Tx) && !defined (STM32F410Cx) && \ - !defined (STM32F410Rx) && !defined (STM32F411xE) && !defined (STM32F446xx) && !defined (STM32F469xx) && \ - !defined (STM32F479xx) && !defined (STM32F412Cx) && !defined (STM32F412Rx) && !defined (STM32F412Vx) && \ - !defined (STM32F412Zx) && !defined (STM32F413xx) && !defined (STM32F423xx) */ - /* #define STM32F405xx */ /*!< STM32F405RG, STM32F405VG and STM32F405ZG Devices */ - /* #define STM32F415xx */ /*!< STM32F415RG, STM32F415VG and STM32F415ZG Devices */ - /* #define STM32F407xx */ /*!< STM32F407VG, STM32F407VE, STM32F407ZG, STM32F407ZE, STM32F407IG and STM32F407IE Devices */ - /* #define STM32F417xx */ /*!< STM32F417VG, STM32F417VE, STM32F417ZG, STM32F417ZE, STM32F417IG and STM32F417IE Devices */ - /* #define STM32F427xx */ /*!< STM32F427VG, STM32F427VI, STM32F427ZG, STM32F427ZI, STM32F427IG and STM32F427II Devices */ - /* #define STM32F437xx */ /*!< STM32F437VG, STM32F437VI, STM32F437ZG, STM32F437ZI, STM32F437IG and STM32F437II Devices */ - /* #define STM32F429xx */ /*!< STM32F429VG, STM32F429VI, STM32F429ZG, STM32F429ZI, STM32F429BG, STM32F429BI, STM32F429NG, - STM32F439NI, STM32F429IG and STM32F429II Devices */ - /* #define STM32F439xx */ /*!< STM32F439VG, STM32F439VI, STM32F439ZG, STM32F439ZI, STM32F439BG, STM32F439BI, STM32F439NG, - STM32F439NI, STM32F439IG and STM32F439II Devices */ - /* #define STM32F401xC */ /*!< STM32F401CB, STM32F401CC, STM32F401RB, STM32F401RC, STM32F401VB and STM32F401VC Devices */ - /* #define STM32F401xE */ /*!< STM32F401CD, STM32F401RD, STM32F401VD, STM32F401CE, STM32F401RE and STM32F401VE Devices */ - /* #define STM32F410Tx */ /*!< STM32F410T8 and STM32F410TB Devices */ - /* #define STM32F410Cx */ /*!< STM32F410C8 and STM32F410CB Devices */ - /* #define STM32F410Rx */ /*!< STM32F410R8 and STM32F410RB Devices */ - /* #define STM32F411xE */ /*!< STM32F411CC, STM32F411RC, STM32F411VC, STM32F411CE, STM32F411RE and STM32F411VE Devices */ - /* #define STM32F446xx */ /*!< STM32F446MC, STM32F446ME, STM32F446RC, STM32F446RE, STM32F446VC, STM32F446VE, STM32F446ZC, - and STM32F446ZE Devices */ - /* #define STM32F469xx */ /*!< STM32F469AI, STM32F469II, STM32F469BI, STM32F469NI, STM32F469AG, STM32F469IG, STM32F469BG, - STM32F469NG, STM32F469AE, STM32F469IE, STM32F469BE and STM32F469NE Devices */ - /* #define STM32F479xx */ /*!< STM32F479AI, STM32F479II, STM32F479BI, STM32F479NI, STM32F479AG, STM32F479IG, STM32F479BG - and STM32F479NG Devices */ - /* #define STM32F412Cx */ /*!< STM32F412CEU and STM32F412CGU Devices */ - /* #define STM32F412Zx */ /*!< STM32F412ZET, STM32F412ZGT, STM32F412ZEJ and STM32F412ZGJ Devices */ - /* #define STM32F412Vx */ /*!< STM32F412VET, STM32F412VGT, STM32F412VEH and STM32F412VGH Devices */ - /* #define STM32F412Rx */ /*!< STM32F412RET, STM32F412RGT, STM32F412REY and STM32F412RGY Devices */ - /* #define STM32F413xx */ /*!< STM32F413CH, STM32F413MH, STM32F413RH, STM32F413VH, STM32F413ZH, STM32F413CG, STM32F413MG, - STM32F413RG, STM32F413VG and STM32F413ZG Devices */ - /* #define STM32F423xx */ /*!< STM32F423CH, STM32F423RH, STM32F423VH and STM32F423ZH Devices */ -//#endif - -/* Tip: To avoid modifying this file each time you need to switch between these - devices, you can define the device in your toolchain compiler preprocessor. - */ -#if !defined (USE_HAL_DRIVER) -/** - * @brief Comment the line below if you will not use the peripherals drivers. - In this case, these drivers will not be included and the application code will - be based on direct access to peripherals registers - */ - /*#define USE_HAL_DRIVER */ -#endif /* USE_HAL_DRIVER */ - -/** - * @brief CMSIS version number V2.6.0 - */ -#define __STM32F4xx_CMSIS_VERSION_MAIN (0x02U) /*!< [31:24] main version */ -#define __STM32F4xx_CMSIS_VERSION_SUB1 (0x06U) /*!< [23:16] sub1 version */ -#define __STM32F4xx_CMSIS_VERSION_SUB2 (0x00U) /*!< [15:8] sub2 version */ -#define __STM32F4xx_CMSIS_VERSION_RC (0x00U) /*!< [7:0] release candidate */ -#define __STM32F4xx_CMSIS_VERSION ((__STM32F4xx_CMSIS_VERSION_MAIN << 24)\ - |(__STM32F4xx_CMSIS_VERSION_SUB1 << 16)\ - |(__STM32F4xx_CMSIS_VERSION_SUB2 << 8 )\ - |(__STM32F4xx_CMSIS_VERSION)) - -/** - * @} - */ - -/** @addtogroup Device_Included - * @{ - */ - -// #if defined(STM32F405xx) -// #include "stm32f405xx.h" -// #elif defined(STM32F415xx) -// #include "stm32f415xx.h" -// #elif defined(STM32F407xx) -// #include "stm32f407xx.h" -// #elif defined(STM32F417xx) -// #include "stm32f417xx.h" -// #elif defined(STM32F427xx) -// #include "stm32f427xx.h" -// #elif defined(STM32F437xx) -// #include "stm32f437xx.h" -// #elif defined(STM32F429xx) -// #include "stm32f429xx.h" -// #elif defined(STM32F439xx) -// #include "stm32f439xx.h" -// #elif defined(STM32F401xC) -// #include "stm32f401xc.h" -// #elif defined(STM32F401xE) -// #include "stm32f401xe.h" -// #elif defined(STM32F410Tx) -// #include "stm32f410tx.h" -// #elif defined(STM32F410Cx) -// #include "stm32f410cx.h" -// #elif defined(STM32F410Rx) -// #include "stm32f410rx.h" -// #elif defined(STM32F411xE) -// #include "stm32f411xe.h" -// #elif defined(STM32F446xx) -// #include "stm32f446xx.h" -// #elif defined(STM32F469xx) -// #include "stm32f469xx.h" -// #elif defined(STM32F479xx) -// #include "stm32f479xx.h" -// #elif defined(STM32F412Cx) -// #include "stm32f412cx.h" -// #elif defined(STM32F412Zx) -// #include "stm32f412zx.h" -// #elif defined(STM32F412Rx) -// #include "stm32f412rx.h" -// #elif defined(STM32F412Vx) -// #include "stm32f412vx.h" -#if defined(STM32F413xx) - #include "stm32f413xx.h" - #elif defined(STM32F423xx) - #include "stm32f423xx.h" -#else - #error "Please select first the target STM32F4xx device used in your application (in stm32f4xx.h file)" -#endif - -/** - * @} - */ - -/** @addtogroup Exported_types - * @{ - */ -typedef enum -{ - RESET = 0U, - SET = !RESET -} FlagStatus, ITStatus; - -typedef enum -{ - DISABLE = 0U, - ENABLE = !DISABLE -} FunctionalState; -#define IS_FUNCTIONAL_STATE(STATE) (((STATE) == DISABLE) || ((STATE) == ENABLE)) - -typedef enum -{ - ERROR = 0U, - SUCCESS = !ERROR -} ErrorStatus; - -/** - * @} - */ - - -/** @addtogroup Exported_macro - * @{ - */ -#define SET_BIT(REG, BIT) ((REG) |= (BIT)) - -#define CLEAR_BIT(REG, BIT) ((REG) &= ~(BIT)) - -#define READ_BIT(REG, BIT) ((REG) & (BIT)) - -#define CLEAR_REG(REG) ((REG) = (0x0)) - -#define WRITE_REG(REG, VAL) ((REG) = (VAL)) - -#define READ_REG(REG) ((REG)) - -#define MODIFY_REG(REG, CLEARMASK, SETMASK) WRITE_REG((REG), (((READ_REG(REG)) & (~(CLEARMASK))) | (SETMASK))) - -#define POSITION_VAL(VAL) (__CLZ(__RBIT(VAL))) - - -/** - * @} - */ - -#if defined (USE_HAL_DRIVER) - #include "stm32f4xx_hal.h" -#endif /* USE_HAL_DRIVER */ - -#ifdef __cplusplus -} -#endif /* __cplusplus */ - -#endif /* __STM32F4xx_H */ -/** - * @} - */ - -/** - * @} - */ - - - - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/panda/board/stm32fx/inc/stm32f4xx_hal_def.h b/panda/board/stm32fx/inc/stm32f4xx_hal_def.h deleted file mode 100644 index b77f179..0000000 --- a/panda/board/stm32fx/inc/stm32f4xx_hal_def.h +++ /dev/null @@ -1,214 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_def.h - * @author MCD Application Team - * @version V1.6.0 - * @date 04-November-2016 - * @brief This file contains HAL common defines, enumeration, macros and - * structures definitions. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT(c) 2016 STMicroelectronics

- * - * Redistribution and use in source and binary forms, with or without modification, - * are permitted provided that the following conditions are met: - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE - * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL - * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR - * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, - * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE - * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_DEF -#define __STM32F4xx_HAL_DEF - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" -//#include "Legacy/stm32_hal_legacy.h" -//#include - -/* Exported types ------------------------------------------------------------*/ - -/** - * @brief HAL Status structures definition - */ -typedef enum -{ - HAL_OK = 0x00U, - HAL_ERROR = 0x01U, - HAL_BUSY = 0x02U, - HAL_TIMEOUT = 0x03U -} HAL_StatusTypeDef; - -/** - * @brief HAL Lock structures definition - */ -typedef enum -{ - HAL_UNLOCKED = 0x00U, - HAL_LOCKED = 0x01U -} HAL_LockTypeDef; - -/* Exported macro ------------------------------------------------------------*/ -#define HAL_MAX_DELAY 0xFFFFFFFFU - -#define HAL_IS_BIT_SET(REG, BIT) (((REG) & (BIT)) != RESET) -#define HAL_IS_BIT_CLR(REG, BIT) (((REG) & (BIT)) == RESET) - -#define __HAL_LINKDMA(__HANDLE__, __PPP_DMA_FIELD__, __DMA_HANDLE__) \ - do{ \ - (__HANDLE__)->__PPP_DMA_FIELD__ = &(__DMA_HANDLE__); \ - (__DMA_HANDLE__).Parent = (__HANDLE__); \ - } while(0) - -#define UNUSED(x) ((void)(x)) - -/** @brief Reset the Handle's State field. - * @param __HANDLE__: specifies the Peripheral Handle. - * @note This macro can be used for the following purpose: - * - When the Handle is declared as local variable; before passing it as parameter - * to HAL_PPP_Init() for the first time, it is mandatory to use this macro - * to set to 0 the Handle's "State" field. - * Otherwise, "State" field may have any random value and the first time the function - * HAL_PPP_Init() is called, the low level hardware initialization will be missed - * (i.e. HAL_PPP_MspInit() will not be executed). - * - When there is a need to reconfigure the low level hardware: instead of calling - * HAL_PPP_DeInit() then HAL_PPP_Init(), user can make a call to this macro then HAL_PPP_Init(). - * In this later function, when the Handle's "State" field is set to 0, it will execute the function - * HAL_PPP_MspInit() which will reconfigure the low level hardware. - * @retval None - */ -#define __HAL_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = 0U) - -#if (USE_RTOS == 1) - /* Reserved for future use */ - #error "USE_RTOS should be 0 in the current HAL release" -#else - #define __HAL_LOCK(__HANDLE__) \ - do{ \ - if((__HANDLE__)->Lock == HAL_LOCKED) \ - { \ - return HAL_BUSY; \ - } \ - else \ - { \ - (__HANDLE__)->Lock = HAL_LOCKED; \ - } \ - }while (0) - - #define __HAL_UNLOCK(__HANDLE__) \ - do{ \ - (__HANDLE__)->Lock = HAL_UNLOCKED; \ - }while (0) -#endif /* USE_RTOS */ - -#if defined ( __GNUC__ ) - #ifndef __weak - #define __weak __attribute__((weak)) - #endif /* __weak */ - #ifndef __packed - #define __packed __attribute__((__packed__)) - #endif /* __packed */ -#endif /* __GNUC__ */ - - -/* Macro to get variable aligned on 4-bytes, for __ICCARM__ the directive "#pragma data_alignment=4" must be used instead */ -#if defined (__GNUC__) /* GNU Compiler */ - #ifndef __ALIGN_END - #define __ALIGN_END __attribute__ ((aligned (4))) - #endif /* __ALIGN_END */ - #ifndef __ALIGN_BEGIN - #define __ALIGN_BEGIN - #endif /* __ALIGN_BEGIN */ -#else - #ifndef __ALIGN_END - #define __ALIGN_END - #endif /* __ALIGN_END */ - #ifndef __ALIGN_BEGIN - #if defined (__CC_ARM) /* ARM Compiler */ - #define __ALIGN_BEGIN __align(4) - #elif defined (__ICCARM__) /* IAR Compiler */ - #define __ALIGN_BEGIN - #endif /* __CC_ARM */ - #endif /* __ALIGN_BEGIN */ -#endif /* __GNUC__ */ - - -/** - * @brief __RAM_FUNC definition - */ -#if defined ( __CC_ARM ) -/* ARM Compiler - ------------ - RAM functions are defined using the toolchain options. - Functions that are executed in RAM should reside in a separate source module. - Using the 'Options for File' dialog you can simply change the 'Code / Const' - area of a module to a memory space in physical RAM. - Available memory areas are declared in the 'Target' tab of the 'Options for Target' - dialog. -*/ -#define __RAM_FUNC HAL_StatusTypeDef - -#elif defined ( __ICCARM__ ) -/* ICCARM Compiler - --------------- - RAM functions are defined using a specific toolchain keyword "__ramfunc". -*/ -#define __RAM_FUNC __ramfunc HAL_StatusTypeDef - -#elif defined ( __GNUC__ ) -/* GNU Compiler - ------------ - RAM functions are defined using a specific toolchain attribute - "__attribute__((section(".RamFunc")))". -*/ -#define __RAM_FUNC HAL_StatusTypeDef __attribute__((section(".RamFunc"))) - -#endif - -/** - * @brief __NOINLINE definition - */ -#if defined ( __CC_ARM ) || defined ( __GNUC__ ) -/* ARM & GNUCompiler - ---------------- -*/ -#define __NOINLINE __attribute__ ( (noinline) ) - -#elif defined ( __ICCARM__ ) -/* ICCARM Compiler - --------------- -*/ -#define __NOINLINE _Pragma("optimize = no_inline") - -#endif - -#ifdef __cplusplus -} -#endif - -#endif /* ___STM32F4xx_HAL_DEF */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/panda/board/stm32fx/inc/stm32f4xx_hal_gpio_ex.h b/panda/board/stm32fx/inc/stm32f4xx_hal_gpio_ex.h deleted file mode 100644 index 6c5f34d..0000000 --- a/panda/board/stm32fx/inc/stm32f4xx_hal_gpio_ex.h +++ /dev/null @@ -1,1591 +0,0 @@ -/** - ****************************************************************************** - * @file stm32f4xx_hal_gpio_ex.h - * @author MCD Application Team - * @version V1.6.0 - * @date 04-November-2016 - * @brief Header file of GPIO HAL Extension module. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT(c) 2016 STMicroelectronics

- * - * Redistribution and use in source and binary forms, with or without modification, - * are permitted provided that the following conditions are met: - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE - * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL - * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR - * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, - * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE - * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __STM32F4xx_HAL_GPIO_EX_H -#define __STM32F4xx_HAL_GPIO_EX_H - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx_hal_def.h" - -/** @addtogroup STM32F4xx_HAL_Driver - * @{ - */ - -/** @defgroup GPIOEx GPIOEx - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ -/* Exported constants --------------------------------------------------------*/ -/** @defgroup GPIOEx_Exported_Constants GPIO Exported Constants - * @{ - */ - -/** @defgroup GPIO_Alternate_function_selection GPIO Alternate Function Selection - * @{ - */ - -/*------------------------------------------ STM32F429xx/STM32F439xx ---------*/ -#if defined(STM32F429xx) || defined(STM32F439xx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00U) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00U) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00U) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00U) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00U) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01U) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01U) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02U) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02U) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02U) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM8 ((uint8_t)0x03U) /* TIM8 Alternate Function mapping */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03U) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03U) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03U) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04U) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04U) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04U) /* I2C3 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05U) /* SPI1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05U) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_SPI3 ((uint8_t)0x05U) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF5_SPI4 ((uint8_t)0x05U) /* SPI4 Alternate Function mapping */ -#define GPIO_AF5_SPI5 ((uint8_t)0x05U) /* SPI5 Alternate Function mapping */ -#define GPIO_AF5_SPI6 ((uint8_t)0x05U) /* SPI6 Alternate Function mapping */ -#define GPIO_AF5_I2S3ext ((uint8_t)0x05U) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06U) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06U) /* I2S2ext_SD Alternate Function mapping */ -#define GPIO_AF6_SAI1 ((uint8_t)0x06U) /* SAI1 Alternate Function mapping */ - -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_USART1 ((uint8_t)0x07U) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07U) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07U) /* USART3 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07U) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_UART4 ((uint8_t)0x08U) /* UART4 Alternate Function mapping */ -#define GPIO_AF8_UART5 ((uint8_t)0x08U) /* UART5 Alternate Function mapping */ -#define GPIO_AF8_USART6 ((uint8_t)0x08U) /* USART6 Alternate Function mapping */ -#define GPIO_AF8_UART7 ((uint8_t)0x08U) /* UART7 Alternate Function mapping */ -#define GPIO_AF8_UART8 ((uint8_t)0x08U) /* UART8 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_CAN1 ((uint8_t)0x09U) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_CAN2 ((uint8_t)0x09U) /* CAN2 Alternate Function mapping */ -#define GPIO_AF9_TIM12 ((uint8_t)0x09U) /* TIM12 Alternate Function mapping */ -#define GPIO_AF9_TIM13 ((uint8_t)0x09U) /* TIM13 Alternate Function mapping */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09U) /* TIM14 Alternate Function mapping */ -#define GPIO_AF9_LTDC ((uint8_t)0x09U) /* LCD-TFT Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0AU) /* OTG_FS Alternate Function mapping */ -#define GPIO_AF10_OTG_HS ((uint8_t)0x0AU) /* OTG_HS Alternate Function mapping */ - -/** - * @brief AF 11 selection - */ -#define GPIO_AF11_ETH ((uint8_t)0x0BU) /* ETHERNET Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_FMC ((uint8_t)0x0CU) /* FMC Alternate Function mapping */ -#define GPIO_AF12_OTG_HS_FS ((uint8_t)0x0CU) /* OTG HS configured in FS, Alternate Function mapping */ -#define GPIO_AF12_SDIO ((uint8_t)0x0CU) /* SDIO Alternate Function mapping */ - -/** - * @brief AF 13 selection - */ -#define GPIO_AF13_DCMI ((uint8_t)0x0DU) /* DCMI Alternate Function mapping */ - -/** - * @brief AF 14 selection - */ -#define GPIO_AF14_LTDC ((uint8_t)0x0EU) /* LCD-TFT Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0FU) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F429xx || STM32F439xx */ -/*----------------------------------------------------------------------------*/ - -/*---------------------------------- STM32F427xx/STM32F437xx------------------*/ -#if defined(STM32F427xx) || defined(STM32F437xx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00U) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00U) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00U) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00U) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00U) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01U) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01U) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02U) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02U) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02U) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM8 ((uint8_t)0x03U) /* TIM8 Alternate Function mapping */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03U) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03U) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03U) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04U) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04U) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04U) /* I2C3 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05U) /* SPI1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05U) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_SPI3 ((uint8_t)0x05U) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF5_SPI4 ((uint8_t)0x05U) /* SPI4 Alternate Function mapping */ -#define GPIO_AF5_SPI5 ((uint8_t)0x05U) /* SPI5 Alternate Function mapping */ -#define GPIO_AF5_SPI6 ((uint8_t)0x05U) /* SPI6 Alternate Function mapping */ -/** @brief GPIO_Legacy - */ -#define GPIO_AF5_I2S3ext GPIO_AF5_SPI3 /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06U) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06U) /* I2S2ext_SD Alternate Function mapping */ -#define GPIO_AF6_SAI1 ((uint8_t)0x06U) /* SAI1 Alternate Function mapping */ - -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_USART1 ((uint8_t)0x07U) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07U) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07U) /* USART3 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07U) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_UART4 ((uint8_t)0x08U) /* UART4 Alternate Function mapping */ -#define GPIO_AF8_UART5 ((uint8_t)0x08U) /* UART5 Alternate Function mapping */ -#define GPIO_AF8_USART6 ((uint8_t)0x08U) /* USART6 Alternate Function mapping */ -#define GPIO_AF8_UART7 ((uint8_t)0x08U) /* UART7 Alternate Function mapping */ -#define GPIO_AF8_UART8 ((uint8_t)0x08U) /* UART8 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_CAN1 ((uint8_t)0x09U) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_CAN2 ((uint8_t)0x09U) /* CAN2 Alternate Function mapping */ -#define GPIO_AF9_TIM12 ((uint8_t)0x09U) /* TIM12 Alternate Function mapping */ -#define GPIO_AF9_TIM13 ((uint8_t)0x09U) /* TIM13 Alternate Function mapping */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09U) /* TIM14 Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0AU) /* OTG_FS Alternate Function mapping */ -#define GPIO_AF10_OTG_HS ((uint8_t)0x0AU) /* OTG_HS Alternate Function mapping */ - -/** - * @brief AF 11 selection - */ -#define GPIO_AF11_ETH ((uint8_t)0x0BU) /* ETHERNET Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_FMC ((uint8_t)0x0CU) /* FMC Alternate Function mapping */ -#define GPIO_AF12_OTG_HS_FS ((uint8_t)0x0CU) /* OTG HS configured in FS, Alternate Function mapping */ -#define GPIO_AF12_SDIO ((uint8_t)0x0CU) /* SDIO Alternate Function mapping */ - -/** - * @brief AF 13 selection - */ -#define GPIO_AF13_DCMI ((uint8_t)0x0DU) /* DCMI Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0FU) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F427xx || STM32F437xx */ -/*----------------------------------------------------------------------------*/ - -/*---------------------------------- STM32F407xx/STM32F417xx------------------*/ -#if defined(STM32F407xx) || defined(STM32F417xx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00U) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00U) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00U) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00U) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00U) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01U) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01U) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02U) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02U) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02U) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM8 ((uint8_t)0x03U) /* TIM8 Alternate Function mapping */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03U) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03U) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03U) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04U) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04U) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04U) /* I2C3 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05U) /* SPI1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05U) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_I2S3ext ((uint8_t)0x05U) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06U) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06U) /* I2S2ext_SD Alternate Function mapping */ - -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_USART1 ((uint8_t)0x07U) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07U) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07U) /* USART3 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07U) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_UART4 ((uint8_t)0x08U) /* UART4 Alternate Function mapping */ -#define GPIO_AF8_UART5 ((uint8_t)0x08U) /* UART5 Alternate Function mapping */ -#define GPIO_AF8_USART6 ((uint8_t)0x08U) /* USART6 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_CAN1 ((uint8_t)0x09U) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_CAN2 ((uint8_t)0x09U) /* CAN2 Alternate Function mapping */ -#define GPIO_AF9_TIM12 ((uint8_t)0x09U) /* TIM12 Alternate Function mapping */ -#define GPIO_AF9_TIM13 ((uint8_t)0x09U) /* TIM13 Alternate Function mapping */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09U) /* TIM14 Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0AU) /* OTG_FS Alternate Function mapping */ -#define GPIO_AF10_OTG_HS ((uint8_t)0x0AU) /* OTG_HS Alternate Function mapping */ - -/** - * @brief AF 11 selection - */ -#define GPIO_AF11_ETH ((uint8_t)0x0BU) /* ETHERNET Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_FSMC ((uint8_t)0x0CU) /* FSMC Alternate Function mapping */ -#define GPIO_AF12_OTG_HS_FS ((uint8_t)0x0CU) /* OTG HS configured in FS, Alternate Function mapping */ -#define GPIO_AF12_SDIO ((uint8_t)0x0CU) /* SDIO Alternate Function mapping */ - -/** - * @brief AF 13 selection - */ -#define GPIO_AF13_DCMI ((uint8_t)0x0DU) /* DCMI Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0FU) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F407xx || STM32F417xx */ -/*----------------------------------------------------------------------------*/ - -/*---------------------------------- STM32F405xx/STM32F415xx------------------*/ -#if defined(STM32F405xx) || defined(STM32F415xx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00U) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00U) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00U) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00U) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00U) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01U) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01U) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02U) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02U) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02U) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM8 ((uint8_t)0x03U) /* TIM8 Alternate Function mapping */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03U) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03U) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03U) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04U) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04U) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04U) /* I2C3 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05U) /* SPI1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05U) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_I2S3ext ((uint8_t)0x05U) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06U) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06U) /* I2S2ext_SD Alternate Function mapping */ - -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_USART1 ((uint8_t)0x07U) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07U) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07U) /* USART3 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07U) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_UART4 ((uint8_t)0x08U) /* UART4 Alternate Function mapping */ -#define GPIO_AF8_UART5 ((uint8_t)0x08U) /* UART5 Alternate Function mapping */ -#define GPIO_AF8_USART6 ((uint8_t)0x08U) /* USART6 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_CAN1 ((uint8_t)0x09U) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_CAN2 ((uint8_t)0x09U) /* CAN2 Alternate Function mapping */ -#define GPIO_AF9_TIM12 ((uint8_t)0x09U) /* TIM12 Alternate Function mapping */ -#define GPIO_AF9_TIM13 ((uint8_t)0x09U) /* TIM13 Alternate Function mapping */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09U) /* TIM14 Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0AU) /* OTG_FS Alternate Function mapping */ -#define GPIO_AF10_OTG_HS ((uint8_t)0x0AU) /* OTG_HS Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_FSMC ((uint8_t)0x0CU) /* FSMC Alternate Function mapping */ -#define GPIO_AF12_OTG_HS_FS ((uint8_t)0x0CU) /* OTG HS configured in FS, Alternate Function mapping */ -#define GPIO_AF12_SDIO ((uint8_t)0x0CU) /* SDIO Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0FU) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F405xx || STM32F415xx */ - -/*----------------------------------------------------------------------------*/ - -/*---------------------------------------- STM32F401xx------------------------*/ -#if defined(STM32F401xC) || defined(STM32F401xE) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00U) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00U) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00U) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00U) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00U) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01U) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01U) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02U) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02U) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02U) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03U) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03U) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03U) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04U) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04U) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04U) /* I2C3 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05U) /* SPI1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05U) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_SPI4 ((uint8_t)0x05U) /* SPI4 Alternate Function mapping */ -#define GPIO_AF5_I2S3ext ((uint8_t)0x05U) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06U) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06U) /* I2S2ext_SD Alternate Function mapping */ - -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_USART1 ((uint8_t)0x07U) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07U) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07U) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_USART6 ((uint8_t)0x08U) /* USART6 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09U) /* TIM14 Alternate Function mapping */ -#define GPIO_AF9_I2C2 ((uint8_t)0x09U) /* I2C2 Alternate Function mapping */ -#define GPIO_AF9_I2C3 ((uint8_t)0x09U) /* I2C3 Alternate Function mapping */ - - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0AU) /* OTG_FS Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_SDIO ((uint8_t)0x0CU) /* SDIO Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0FU) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F401xC || STM32F401xE */ -/*----------------------------------------------------------------------------*/ - -/*--------------- STM32F412Zx/STM32F412Vx/STM32F412Rx/STM32F412Cx-------------*/ -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00U) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00U) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00U) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00U) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00U) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01U) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01U) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02U) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02U) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02U) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM8 ((uint8_t)0x03U) /* TIM8 Alternate Function mapping */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03U) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03U) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03U) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04U) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04U) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04U) /* I2C3 Alternate Function mapping */ -#define GPIO_AF4_FMPI2C1 ((uint8_t)0x04U) /* FMPI2C1 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05U) /* SPI1/I2S1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05U) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_SPI3 ((uint8_t)0x05U) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF5_SPI4 ((uint8_t)0x05U) /* SPI4/I2S4 Alternate Function mapping */ -#define GPIO_AF5_I2S3ext ((uint8_t)0x05U) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI2 ((uint8_t)0x06U) /* I2S2 Alternate Function mapping */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06U) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_SPI4 ((uint8_t)0x06U) /* SPI4/I2S4 Alternate Function mapping */ -#define GPIO_AF6_SPI5 ((uint8_t)0x06U) /* SPI5/I2S5 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06U) /* I2S2ext_SD Alternate Function mapping */ -#define GPIO_AF6_DFSDM1 ((uint8_t)0x06U) /* DFSDM1 Alternate Function mapping */ -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_SPI3 ((uint8_t)0x07U) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF7_USART1 ((uint8_t)0x07U) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07U) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07U) /* USART3 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07U) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_USART6 ((uint8_t)0x08U) /* USART6 Alternate Function mapping */ -#define GPIO_AF8_USART3 ((uint8_t)0x08U) /* USART3 Alternate Function mapping */ -#define GPIO_AF8_DFSDM1 ((uint8_t)0x08U) /* DFSDM1 Alternate Function mapping */ -#define GPIO_AF8_CAN1 ((uint8_t)0x08U) /* CAN1 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_TIM13 ((uint8_t)0x09U) /* TIM13 Alternate Function mapping */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09U) /* TIM14 Alternate Function mapping */ -#define GPIO_AF9_I2C2 ((uint8_t)0x09U) /* I2C2 Alternate Function mapping */ -#define GPIO_AF9_I2C3 ((uint8_t)0x09U) /* I2C3 Alternate Function mapping */ -#define GPIO_AF9_FMPI2C1 ((uint8_t)0x09U) /* FMPI2C1 Alternate Function mapping */ -#define GPIO_AF9_CAN1 ((uint8_t)0x09U) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_CAN2 ((uint8_t)0x09U) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_QSPI ((uint8_t)0x09U) /* QSPI Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0AU) /* OTG_FS Alternate Function mapping */ -#define GPIO_AF10_DFSDM1 ((uint8_t)0x0AU) /* DFSDM1 Alternate Function mapping */ -#define GPIO_AF10_QSPI ((uint8_t)0x0AU) /* QSPI Alternate Function mapping */ -#define GPIO_AF10_FMC ((uint8_t)0x0AU) /* FMC Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_SDIO ((uint8_t)0x0CU) /* SDIO Alternate Function mapping */ -#define GPIO_AF12_FSMC ((uint8_t)0x0CU) /* FMC Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0FU) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ - -/*----------------------------------------------------------------------------*/ - -/*--------------- STM32F413xx/STM32F423xx-------------------------------------*/ -#if defined(STM32F413xx) || defined(STM32F423xx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00U) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00U) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00U) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00U) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01U) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01U) /* TIM2 Alternate Function mapping */ -#define GPIO_AF1_LPTIM1 ((uint8_t)0x01U) /* LPTIM1 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02U) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02U) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02U) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM8 ((uint8_t)0x03U) /* TIM8 Alternate Function mapping */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03U) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03U) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03U) /* TIM11 Alternate Function mapping */ -#define GPIO_AF3_DFSDM2 ((uint8_t)0x03U) /* DFSDM2 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04U) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04U) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04U) /* I2C3 Alternate Function mapping */ -#define GPIO_AF4_FMPI2C1 ((uint8_t)0x04U) /* FMPI2C1 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05U) /* SPI1/I2S1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05U) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_SPI3 ((uint8_t)0x05U) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF5_SPI4 ((uint8_t)0x05U) /* SPI4/I2S4 Alternate Function mapping */ -#define GPIO_AF5_I2S3ext ((uint8_t)0x05U) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI2 ((uint8_t)0x06U) /* I2S2 Alternate Function mapping */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06U) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_SPI4 ((uint8_t)0x06U) /* SPI4/I2S4 Alternate Function mapping */ -#define GPIO_AF6_SPI5 ((uint8_t)0x06U) /* SPI5/I2S5 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06U) /* I2S2ext_SD Alternate Function mapping */ -#define GPIO_AF6_DFSDM1 ((uint8_t)0x06U) /* DFSDM1 Alternate Function mapping */ -#define GPIO_AF6_DFSDM2 ((uint8_t)0x06U) /* DFSDM2 Alternate Function mapping */ -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_SPI3 ((uint8_t)0x07U) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF7_SAI1 ((uint8_t)0x07U) /* SAI1 Alternate Function mapping */ -#define GPIO_AF7_USART1 ((uint8_t)0x07U) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07U) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07U) /* USART3 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07U) /* I2S3ext_SD Alternate Function mapping */ -#define GPIO_AF7_DFSDM2 ((uint8_t)0x07U) /* DFSDM2 Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_USART6 ((uint8_t)0x08U) /* USART6 Alternate Function mapping */ -#define GPIO_AF8_USART3 ((uint8_t)0x08U) /* USART3 Alternate Function mapping */ -#define GPIO_AF8_UART4 ((uint8_t)0x08U) /* UART4 Alternate Function mapping */ -#define GPIO_AF8_UART5 ((uint8_t)0x08U) /* UART5 Alternate Function mapping */ -#define GPIO_AF8_UART7 ((uint8_t)0x08U) /* UART8 Alternate Function mapping */ -#define GPIO_AF8_UART8 ((uint8_t)0x08U) /* UART8 Alternate Function mapping */ -#define GPIO_AF8_DFSDM1 ((uint8_t)0x08U) /* DFSDM1 Alternate Function mapping */ -#define GPIO_AF8_CAN1 ((uint8_t)0x08U) /* CAN1 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_TIM12 ((uint8_t)0x09U) /* TIM12 Alternate Function mapping */ -#define GPIO_AF9_TIM13 ((uint8_t)0x09U) /* TIM13 Alternate Function mapping */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09U) /* TIM14 Alternate Function mapping */ -#define GPIO_AF9_I2C2 ((uint8_t)0x09U) /* I2C2 Alternate Function mapping */ -#define GPIO_AF9_I2C3 ((uint8_t)0x09U) /* I2C3 Alternate Function mapping */ -#define GPIO_AF9_FMPI2C1 ((uint8_t)0x09U) /* FMPI2C1 Alternate Function mapping */ -#define GPIO_AF9_CAN1 ((uint8_t)0x09U) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_CAN2 ((uint8_t)0x09U) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_QSPI ((uint8_t)0x09U) /* QSPI Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_SAI1 ((uint8_t)0x0AU) /* SAI1 Alternate Function mapping */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0AU) /* OTG_FS Alternate Function mapping */ -#define GPIO_AF10_DFSDM1 ((uint8_t)0x0AU) /* DFSDM1 Alternate Function mapping */ -#define GPIO_AF10_DFSDM2 ((uint8_t)0x0AU) /* DFSDM2 Alternate Function mapping */ -#define GPIO_AF10_QSPI ((uint8_t)0x0AU) /* QSPI Alternate Function mapping */ -#define GPIO_AF10_FSMC ((uint8_t)0x0AU) /* FSMC Alternate Function mapping */ - -/** - * @brief AF 11 selection - */ -#define GPIO_AF11_UART4 ((uint8_t)0x0BU) /* UART4 Alternate Function mapping */ -#define GPIO_AF11_UART5 ((uint8_t)0x0BU) /* UART5 Alternate Function mapping */ -#define GPIO_AF11_UART9 ((uint8_t)0x0BU) /* UART9 Alternate Function mapping */ -#define GPIO_AF11_UART10 ((uint8_t)0x0BU) /* UART10 Alternate Function mapping */ -#define GPIO_AF11_CAN3 ((uint8_t)0x0BU) /* CAN3 Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_SDIO ((uint8_t)0x0CU) /* SDIO Alternate Function mapping */ -#define GPIO_AF12_FSMC ((uint8_t)0x0CU) /* FMC Alternate Function mapping */ - -/** - * @brief AF 14 selection - */ -#define GPIO_AF14_RNG ((uint8_t)0x0EU) /* RNG Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0FU) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F413xx || STM32F423xx */ - -/*---------------------------------------- STM32F411xx------------------------*/ -#if defined(STM32F411xE) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00U) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00U) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00U) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00U) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00U) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01U) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01U) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02U) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02U) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02U) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03U) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03U) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03U) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04U) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04U) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04U) /* I2C3 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05U) /* SPI1/I2S1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05U) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_SPI3 ((uint8_t)0x05U) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF5_SPI4 ((uint8_t)0x05U) /* SPI4 Alternate Function mapping */ -#define GPIO_AF5_I2S3ext ((uint8_t)0x05U) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI2 ((uint8_t)0x06U) /* I2S2 Alternate Function mapping */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06U) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_SPI4 ((uint8_t)0x06U) /* SPI4/I2S4 Alternate Function mapping */ -#define GPIO_AF6_SPI5 ((uint8_t)0x06U) /* SPI5/I2S5 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06U) /* I2S2ext_SD Alternate Function mapping */ - -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_SPI3 ((uint8_t)0x07U) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF7_USART1 ((uint8_t)0x07U) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07U) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07U) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_USART6 ((uint8_t)0x08U) /* USART6 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09U) /* TIM14 Alternate Function mapping */ -#define GPIO_AF9_I2C2 ((uint8_t)0x09U) /* I2C2 Alternate Function mapping */ -#define GPIO_AF9_I2C3 ((uint8_t)0x09U) /* I2C3 Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0AU) /* OTG_FS Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_SDIO ((uint8_t)0x0CU) /* SDIO Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0FU) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F411xE */ - -/*---------------------------------------- STM32F410xx------------------------*/ -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00U) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00U) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00U) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00U) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00U) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01U) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_LPTIM1 ((uint8_t)0x01U) /* LPTIM1 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02U) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03U) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03U) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04U) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04U) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_FMPI2C1 ((uint8_t)0x04U) /* FMPI2C1 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05U) /* SPI1/I2S1 Alternate Function mapping */ -#if defined(STM32F410Cx) || defined(STM32F410Rx) -#define GPIO_AF5_SPI2 ((uint8_t)0x05U) /* SPI2/I2S2 Alternate Function mapping */ -#endif /* STM32F410Cx || STM32F410Rx */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI1 ((uint8_t)0x06U) /* SPI1 Alternate Function mapping */ -#if defined(STM32F410Cx) || defined(STM32F410Rx) -#define GPIO_AF6_SPI2 ((uint8_t)0x06U) /* I2S2 Alternate Function mapping */ -#endif /* STM32F410Cx || STM32F410Rx */ -#define GPIO_AF6_SPI5 ((uint8_t)0x06U) /* SPI5/I2S5 Alternate Function mapping */ -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_USART1 ((uint8_t)0x07U) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07U) /* USART2 Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_USART6 ((uint8_t)0x08U) /* USART6 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_I2C2 ((uint8_t)0x09U) /* I2C2 Alternate Function mapping */ -#define GPIO_AF9_FMPI2C1 ((uint8_t)0x09U) /* FMPI2C1 Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0FU) /* EVENTOUT Alternate Function mapping */ -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -/*---------------------------------------- STM32F446xx -----------------------*/ -#if defined(STM32F446xx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00U) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00U) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00U) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00U) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00U) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01U) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01U) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02U) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02U) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02U) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM8 ((uint8_t)0x03U) /* TIM8 Alternate Function mapping */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03U) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03U) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03U) /* TIM11 Alternate Function mapping */ -#define GPIO_AF3_CEC ((uint8_t)0x03U) /* CEC Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04U) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04U) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04U) /* I2C3 Alternate Function mapping */ -#define GPIO_AF4_FMPI2C1 ((uint8_t)0x04U) /* FMPI2C1 Alternate Function mapping */ -#define GPIO_AF4_CEC ((uint8_t)0x04U) /* CEC Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05U) /* SPI1/I2S1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05U) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_SPI3 ((uint8_t)0x05U) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF5_SPI4 ((uint8_t)0x05U) /* SPI4 Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI2 ((uint8_t)0x06U) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06U) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_SPI4 ((uint8_t)0x06U) /* SPI4 Alternate Function mapping */ -#define GPIO_AF6_SAI1 ((uint8_t)0x06U) /* SAI1 Alternate Function mapping */ - -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_USART1 ((uint8_t)0x07U) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07U) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07U) /* USART3 Alternate Function mapping */ -#define GPIO_AF7_UART5 ((uint8_t)0x07U) /* UART5 Alternate Function mapping */ -#define GPIO_AF7_SPI2 ((uint8_t)0x07U) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF7_SPI3 ((uint8_t)0x07U) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF7_SPDIFRX ((uint8_t)0x07U) /* SPDIFRX Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_UART4 ((uint8_t)0x08U) /* UART4 Alternate Function mapping */ -#define GPIO_AF8_UART5 ((uint8_t)0x08U) /* UART5 Alternate Function mapping */ -#define GPIO_AF8_USART6 ((uint8_t)0x08U) /* USART6 Alternate Function mapping */ -#define GPIO_AF8_SPDIFRX ((uint8_t)0x08U) /* SPDIFRX Alternate Function mapping */ -#define GPIO_AF8_SAI2 ((uint8_t)0x08U) /* SAI2 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_CAN1 ((uint8_t)0x09U) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_CAN2 ((uint8_t)0x09U) /* CAN2 Alternate Function mapping */ -#define GPIO_AF9_TIM12 ((uint8_t)0x09U) /* TIM12 Alternate Function mapping */ -#define GPIO_AF9_TIM13 ((uint8_t)0x09U) /* TIM13 Alternate Function mapping */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09U) /* TIM14 Alternate Function mapping */ -#define GPIO_AF9_QSPI ((uint8_t)0x09U) /* QSPI Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0AU) /* OTG_FS Alternate Function mapping */ -#define GPIO_AF10_OTG_HS ((uint8_t)0x0AU) /* OTG_HS Alternate Function mapping */ -#define GPIO_AF10_SAI2 ((uint8_t)0x0AU) /* SAI2 Alternate Function mapping */ -#define GPIO_AF10_QSPI ((uint8_t)0x0AU) /* QSPI Alternate Function mapping */ - -/** - * @brief AF 11 selection - */ -#define GPIO_AF11_ETH ((uint8_t)0x0BU) /* ETHERNET Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_FMC ((uint8_t)0x0CU) /* FMC Alternate Function mapping */ -#define GPIO_AF12_OTG_HS_FS ((uint8_t)0x0CU) /* OTG HS configured in FS, Alternate Function mapping */ -#define GPIO_AF12_SDIO ((uint8_t)0x0CU) /* SDIO Alternate Function mapping */ - -/** - * @brief AF 13 selection - */ -#define GPIO_AF13_DCMI ((uint8_t)0x0DU) /* DCMI Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0FU) /* EVENTOUT Alternate Function mapping */ - -#endif /* STM32F446xx */ -/*----------------------------------------------------------------------------*/ - -/*-------------------------------- STM32F469xx/STM32F479xx--------------------*/ -#if defined(STM32F469xx) || defined(STM32F479xx) -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00U) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00U) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_TAMPER ((uint8_t)0x00U) /* TAMPER (TAMPER_1 and TAMPER_2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00U) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00U) /* TRACE Alternate Function mapping */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01U) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01U) /* TIM2 Alternate Function mapping */ - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02U) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02U) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02U) /* TIM5 Alternate Function mapping */ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM8 ((uint8_t)0x03U) /* TIM8 Alternate Function mapping */ -#define GPIO_AF3_TIM9 ((uint8_t)0x03U) /* TIM9 Alternate Function mapping */ -#define GPIO_AF3_TIM10 ((uint8_t)0x03U) /* TIM10 Alternate Function mapping */ -#define GPIO_AF3_TIM11 ((uint8_t)0x03U) /* TIM11 Alternate Function mapping */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04U) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04U) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04U) /* I2C3 Alternate Function mapping */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05U) /* SPI1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05U) /* SPI2/I2S2 Alternate Function mapping */ -#define GPIO_AF5_SPI3 ((uint8_t)0x05U) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF5_SPI4 ((uint8_t)0x05U) /* SPI4 Alternate Function mapping */ -#define GPIO_AF5_SPI5 ((uint8_t)0x05U) /* SPI5 Alternate Function mapping */ -#define GPIO_AF5_SPI6 ((uint8_t)0x05U) /* SPI6 Alternate Function mapping */ -#define GPIO_AF5_I2S3ext ((uint8_t)0x05U) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06U) /* SPI3/I2S3 Alternate Function mapping */ -#define GPIO_AF6_I2S2ext ((uint8_t)0x06U) /* I2S2ext_SD Alternate Function mapping */ -#define GPIO_AF6_SAI1 ((uint8_t)0x06U) /* SAI1 Alternate Function mapping */ - -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_USART1 ((uint8_t)0x07U) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07U) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07U) /* USART3 Alternate Function mapping */ -#define GPIO_AF7_I2S3ext ((uint8_t)0x07U) /* I2S3ext_SD Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_UART4 ((uint8_t)0x08U) /* UART4 Alternate Function mapping */ -#define GPIO_AF8_UART5 ((uint8_t)0x08U) /* UART5 Alternate Function mapping */ -#define GPIO_AF8_USART6 ((uint8_t)0x08U) /* USART6 Alternate Function mapping */ -#define GPIO_AF8_UART7 ((uint8_t)0x08U) /* UART7 Alternate Function mapping */ -#define GPIO_AF8_UART8 ((uint8_t)0x08U) /* UART8 Alternate Function mapping */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_CAN1 ((uint8_t)0x09U) /* CAN1 Alternate Function mapping */ -#define GPIO_AF9_CAN2 ((uint8_t)0x09U) /* CAN2 Alternate Function mapping */ -#define GPIO_AF9_TIM12 ((uint8_t)0x09U) /* TIM12 Alternate Function mapping */ -#define GPIO_AF9_TIM13 ((uint8_t)0x09U) /* TIM13 Alternate Function mapping */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09U) /* TIM14 Alternate Function mapping */ -#define GPIO_AF9_LTDC ((uint8_t)0x09U) /* LCD-TFT Alternate Function mapping */ -#define GPIO_AF9_QSPI ((uint8_t)0x09U) /* QSPI Alternate Function mapping */ - -/** - * @brief AF 10 selection - */ -#define GPIO_AF10_OTG_FS ((uint8_t)0x0AU) /* OTG_FS Alternate Function mapping */ -#define GPIO_AF10_OTG_HS ((uint8_t)0x0AU) /* OTG_HS Alternate Function mapping */ -#define GPIO_AF10_QSPI ((uint8_t)0x0AU) /* QSPI Alternate Function mapping */ - -/** - * @brief AF 11 selection - */ -#define GPIO_AF11_ETH ((uint8_t)0x0BU) /* ETHERNET Alternate Function mapping */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_FMC ((uint8_t)0x0CU) /* FMC Alternate Function mapping */ -#define GPIO_AF12_OTG_HS_FS ((uint8_t)0x0CU) /* OTG HS configured in FS, Alternate Function mapping */ -#define GPIO_AF12_SDIO ((uint8_t)0x0CU) /* SDIO Alternate Function mapping */ - -/** - * @brief AF 13 selection - */ -#define GPIO_AF13_DCMI ((uint8_t)0x0DU) /* DCMI Alternate Function mapping */ -#define GPIO_AF13_DSI ((uint8_t)0x0DU) /* DSI Alternate Function mapping */ - -/** - * @brief AF 14 selection - */ -#define GPIO_AF14_LTDC ((uint8_t)0x0EU) /* LCD-TFT Alternate Function mapping */ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0FU) /* EVENTOUT Alternate Function mapping */ - -#endif /* STM32F469xx || STM32F479xx */ -/*----------------------------------------------------------------------------*/ -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup GPIOEx_Exported_Macros GPIO Exported Macros - * @{ - */ -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup GPIOEx_Exported_Functions GPIO Exported Functions - * @{ - */ -/** - * @} - */ - -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup GPIOEx_Private_Constants GPIO Private Constants - * @{ - */ -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup GPIOEx_Private_Macros GPIO Private Macros - * @{ - */ -/** @defgroup GPIOEx_Get_Port_Index GPIO Get Port Index - * @{ - */ -#if defined(STM32F405xx) || defined(STM32F415xx) || defined(STM32F407xx) || defined(STM32F417xx) -#define GPIO_GET_INDEX(__GPIOx__) (uint8_t)(((__GPIOx__) == (GPIOA))? 0U :\ - ((__GPIOx__) == (GPIOB))? 1U :\ - ((__GPIOx__) == (GPIOC))? 2U :\ - ((__GPIOx__) == (GPIOD))? 3U :\ - ((__GPIOx__) == (GPIOE))? 4U :\ - ((__GPIOx__) == (GPIOF))? 5U :\ - ((__GPIOx__) == (GPIOG))? 6U :\ - ((__GPIOx__) == (GPIOH))? 7U : 8U) -#endif /* STM32F405xx || STM32F415xx || STM32F407xx || STM32F417xx */ - -#if defined(STM32F427xx) || defined(STM32F437xx) || defined(STM32F429xx) || defined(STM32F439xx) ||\ - defined(STM32F469xx) || defined(STM32F479xx) -#define GPIO_GET_INDEX(__GPIOx__) (uint8_t)(((__GPIOx__) == (GPIOA))? 0U :\ - ((__GPIOx__) == (GPIOB))? 1U :\ - ((__GPIOx__) == (GPIOC))? 2U :\ - ((__GPIOx__) == (GPIOD))? 3U :\ - ((__GPIOx__) == (GPIOE))? 4U :\ - ((__GPIOx__) == (GPIOF))? 5U :\ - ((__GPIOx__) == (GPIOG))? 6U :\ - ((__GPIOx__) == (GPIOH))? 7U :\ - ((__GPIOx__) == (GPIOI))? 8U :\ - ((__GPIOx__) == (GPIOJ))? 9U : 10U) -#endif /* STM32F427xx || STM32F437xx || STM32F429xx || STM32F439xx || STM32F469xx || STM32F479xx */ - -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -#define GPIO_GET_INDEX(__GPIOx__) (uint8_t)(((__GPIOx__) == (GPIOA))? 0U :\ - ((__GPIOx__) == (GPIOB))? 1U :\ - ((__GPIOx__) == (GPIOC))? 2U : 7U) -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -#if defined(STM32F401xC) || defined(STM32F401xE) || defined(STM32F411xE) -#define GPIO_GET_INDEX(__GPIOx__) (uint8_t)(((__GPIOx__) == (GPIOA))? 0U :\ - ((__GPIOx__) == (GPIOB))? 1U :\ - ((__GPIOx__) == (GPIOC))? 2U :\ - ((__GPIOx__) == (GPIOD))? 3U :\ - ((__GPIOx__) == (GPIOE))? 4U : 7U) -#endif /* STM32F401xC || STM32F401xE || STM32F411xE */ - -#if defined(STM32F446xx) || defined(STM32F412Zx) ||defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) || defined(STM32F413xx) || defined(STM32F423xx) -#define GPIO_GET_INDEX(__GPIOx__) (uint8_t)(((__GPIOx__) == (GPIOA))? 0U :\ - ((__GPIOx__) == (GPIOB))? 1U :\ - ((__GPIOx__) == (GPIOC))? 2U :\ - ((__GPIOx__) == (GPIOD))? 3U :\ - ((__GPIOx__) == (GPIOE))? 4U :\ - ((__GPIOx__) == (GPIOF))? 5U :\ - ((__GPIOx__) == (GPIOG))? 6U : 7U) -#endif /* STM32F446xx || STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx || STM32F413xx || STM32F423xx */ - -/** - * @} - */ - -/** @defgroup GPIOEx_IS_Alternat_function_selection GPIO Check Alternate Function - * @{ - */ -/*------------------------- STM32F429xx/STM32F439xx---------------------------*/ -#if defined(STM32F429xx) || defined(STM32F439xx) -#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ - ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ - ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ - ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ - ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ - ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM8) || \ - ((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \ - ((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \ - ((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF9_TIM13) || \ - ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF9_TIM12) || \ - ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ - ((AF) == GPIO_AF7_USART3) || ((AF) == GPIO_AF8_UART4) || \ - ((AF) == GPIO_AF8_UART5) || ((AF) == GPIO_AF8_USART6) || \ - ((AF) == GPIO_AF9_CAN1) || ((AF) == GPIO_AF9_CAN2) || \ - ((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF10_OTG_HS) || \ - ((AF) == GPIO_AF11_ETH) || ((AF) == GPIO_AF12_OTG_HS_FS) || \ - ((AF) == GPIO_AF12_SDIO) || ((AF) == GPIO_AF13_DCMI) || \ - ((AF) == GPIO_AF15_EVENTOUT) || ((AF) == GPIO_AF5_SPI4) || \ - ((AF) == GPIO_AF5_SPI5) || ((AF) == GPIO_AF5_SPI6) || \ - ((AF) == GPIO_AF8_UART7) || ((AF) == GPIO_AF8_UART8) || \ - ((AF) == GPIO_AF12_FMC) || ((AF) == GPIO_AF6_SAI1) || \ - ((AF) == GPIO_AF14_LTDC)) - -#endif /* STM32F429xx || STM32F439xx */ -/*----------------------------------------------------------------------------*/ - -/*---------------------------------- STM32F427xx/STM32F437xx------------------*/ -#if defined(STM32F427xx) || defined(STM32F437xx) -#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ - ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ - ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ - ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ - ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ - ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM8) || \ - ((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \ - ((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \ - ((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF9_TIM13) || \ - ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF9_TIM12) || \ - ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ - ((AF) == GPIO_AF7_USART3) || ((AF) == GPIO_AF8_UART4) || \ - ((AF) == GPIO_AF8_UART5) || ((AF) == GPIO_AF8_USART6) || \ - ((AF) == GPIO_AF9_CAN1) || ((AF) == GPIO_AF9_CAN2) || \ - ((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF10_OTG_HS) || \ - ((AF) == GPIO_AF11_ETH) || ((AF) == GPIO_AF12_OTG_HS_FS) || \ - ((AF) == GPIO_AF12_SDIO) || ((AF) == GPIO_AF13_DCMI) || \ - ((AF) == GPIO_AF15_EVENTOUT) || ((AF) == GPIO_AF5_SPI4) || \ - ((AF) == GPIO_AF5_SPI5) || ((AF) == GPIO_AF5_SPI6) || \ - ((AF) == GPIO_AF8_UART7) || ((AF) == GPIO_AF8_UART8) || \ - ((AF) == GPIO_AF12_FMC) || ((AF) == GPIO_AF6_SAI1)) - -#endif /* STM32F427xx || STM32F437xx */ -/*----------------------------------------------------------------------------*/ - -/*---------------------------------- STM32F407xx/STM32F417xx------------------*/ -#if defined(STM32F407xx) || defined(STM32F417xx) -#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ - ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ - ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ - ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ - ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ - ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM8) || \ - ((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \ - ((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \ - ((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF9_TIM13) || \ - ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF9_TIM12) || \ - ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ - ((AF) == GPIO_AF7_USART3) || ((AF) == GPIO_AF8_UART4) || \ - ((AF) == GPIO_AF8_UART5) || ((AF) == GPIO_AF8_USART6) || \ - ((AF) == GPIO_AF9_CAN1) || ((AF) == GPIO_AF9_CAN2) || \ - ((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF10_OTG_HS) || \ - ((AF) == GPIO_AF11_ETH) || ((AF) == GPIO_AF12_OTG_HS_FS) || \ - ((AF) == GPIO_AF12_SDIO) || ((AF) == GPIO_AF13_DCMI) || \ - ((AF) == GPIO_AF12_FSMC) || ((AF) == GPIO_AF15_EVENTOUT)) - -#endif /* STM32F407xx || STM32F417xx */ -/*----------------------------------------------------------------------------*/ - -/*---------------------------------- STM32F405xx/STM32F415xx------------------*/ -#if defined(STM32F405xx) || defined(STM32F415xx) -#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ - ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ - ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ - ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ - ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ - ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM8) || \ - ((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \ - ((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \ - ((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF9_TIM13) || \ - ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF9_TIM12) || \ - ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ - ((AF) == GPIO_AF7_USART3) || ((AF) == GPIO_AF8_UART4) || \ - ((AF) == GPIO_AF8_UART5) || ((AF) == GPIO_AF8_USART6) || \ - ((AF) == GPIO_AF9_CAN1) || ((AF) == GPIO_AF9_CAN2) || \ - ((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF10_OTG_HS) || \ - ((AF) == GPIO_AF12_OTG_HS_FS) || ((AF) == GPIO_AF12_SDIO) || \ - ((AF) == GPIO_AF12_FSMC) || ((AF) == GPIO_AF15_EVENTOUT)) - -#endif /* STM32F405xx || STM32F415xx */ - -/*----------------------------------------------------------------------------*/ - -/*---------------------------------------- STM32F401xx------------------------*/ -#if defined(STM32F401xC) || defined(STM32F401xE) -#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ - ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ - ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ - ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ - ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ - ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF4_I2C1) || \ - ((AF) == GPIO_AF4_I2C2) || ((AF) == GPIO_AF4_I2C3) || \ - ((AF) == GPIO_AF5_SPI1) || ((AF) == GPIO_AF5_SPI2) || \ - ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF5_SPI4) || \ - ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ - ((AF) == GPIO_AF8_USART6) || ((AF) == GPIO_AF10_OTG_FS) || \ - ((AF) == GPIO_AF9_I2C2) || ((AF) == GPIO_AF9_I2C3) || \ - ((AF) == GPIO_AF12_SDIO) || ((AF) == GPIO_AF15_EVENTOUT)) - -#endif /* STM32F401xC || STM32F401xE */ -/*----------------------------------------------------------------------------*/ -/*---------------------------------------- STM32F410xx------------------------*/ -#if defined(STM32F410Tx) || defined(STM32F410Cx) || defined(STM32F410Rx) -#define IS_GPIO_AF(AF) (((AF) < 10U) || ((AF) == 15U)) -#endif /* STM32F410Tx || STM32F410Cx || STM32F410Rx */ - -/*---------------------------------------- STM32F411xx------------------------*/ -#if defined(STM32F411xE) -#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ - ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ - ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ - ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ - ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ - ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF4_I2C1) || \ - ((AF) == GPIO_AF4_I2C2) || ((AF) == GPIO_AF4_I2C3) || \ - ((AF) == GPIO_AF5_SPI1) || ((AF) == GPIO_AF5_SPI2) || \ - ((AF) == GPIO_AF5_SPI3) || ((AF) == GPIO_AF6_SPI4) || \ - ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF5_SPI4) || \ - ((AF) == GPIO_AF6_SPI5) || ((AF) == GPIO_AF7_SPI3) || \ - ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ - ((AF) == GPIO_AF8_USART6) || ((AF) == GPIO_AF10_OTG_FS) || \ - ((AF) == GPIO_AF9_I2C2) || ((AF) == GPIO_AF9_I2C3) || \ - ((AF) == GPIO_AF12_SDIO) || ((AF) == GPIO_AF15_EVENTOUT)) - -#endif /* STM32F411xE */ -/*----------------------------------------------------------------------------*/ - -/*----------------------------------------------- STM32F446xx ----------------*/ -#if defined(STM32F446xx) -#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ - ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ - ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ - ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ - ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ - ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM8) || \ - ((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \ - ((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \ - ((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF9_TIM13) || \ - ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF9_TIM12) || \ - ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ - ((AF) == GPIO_AF7_USART3) || ((AF) == GPIO_AF8_UART4) || \ - ((AF) == GPIO_AF8_UART5) || ((AF) == GPIO_AF8_USART6) || \ - ((AF) == GPIO_AF9_CAN1) || ((AF) == GPIO_AF9_CAN2) || \ - ((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF10_OTG_HS) || \ - ((AF) == GPIO_AF11_ETH) || ((AF) == GPIO_AF12_OTG_HS_FS) || \ - ((AF) == GPIO_AF12_SDIO) || ((AF) == GPIO_AF13_DCMI) || \ - ((AF) == GPIO_AF15_EVENTOUT) || ((AF) == GPIO_AF5_SPI4) || \ - ((AF) == GPIO_AF12_FMC) || ((AF) == GPIO_AF6_SAI1) || \ - ((AF) == GPIO_AF3_CEC) || ((AF) == GPIO_AF4_CEC) || \ - ((AF) == GPIO_AF5_SPI3) || ((AF) == GPIO_AF6_SPI2) || \ - ((AF) == GPIO_AF6_SPI4) || ((AF) == GPIO_AF7_UART5) || \ - ((AF) == GPIO_AF7_SPI2) || ((AF) == GPIO_AF7_SPI3) || \ - ((AF) == GPIO_AF7_SPDIFRX) || ((AF) == GPIO_AF8_SPDIFRX) || \ - ((AF) == GPIO_AF8_SAI2) || ((AF) == GPIO_AF9_QSPI) || \ - ((AF) == GPIO_AF10_SAI2) || ((AF) == GPIO_AF10_QSPI)) - -#endif /* STM32F446xx */ -/*----------------------------------------------------------------------------*/ - -/*------------------------------------------- STM32F469xx/STM32F479xx --------*/ -#if defined(STM32F469xx) || defined(STM32F479xx) -#define IS_GPIO_AF(AF) (((AF) == GPIO_AF0_RTC_50Hz) || ((AF) == GPIO_AF9_TIM14) || \ - ((AF) == GPIO_AF0_MCO) || ((AF) == GPIO_AF0_TAMPER) || \ - ((AF) == GPIO_AF0_SWJ) || ((AF) == GPIO_AF0_TRACE) || \ - ((AF) == GPIO_AF1_TIM1) || ((AF) == GPIO_AF1_TIM2) || \ - ((AF) == GPIO_AF2_TIM3) || ((AF) == GPIO_AF2_TIM4) || \ - ((AF) == GPIO_AF2_TIM5) || ((AF) == GPIO_AF3_TIM8) || \ - ((AF) == GPIO_AF4_I2C1) || ((AF) == GPIO_AF4_I2C2) || \ - ((AF) == GPIO_AF4_I2C3) || ((AF) == GPIO_AF5_SPI1) || \ - ((AF) == GPIO_AF5_SPI2) || ((AF) == GPIO_AF9_TIM13) || \ - ((AF) == GPIO_AF6_SPI3) || ((AF) == GPIO_AF9_TIM12) || \ - ((AF) == GPIO_AF7_USART1) || ((AF) == GPIO_AF7_USART2) || \ - ((AF) == GPIO_AF7_USART3) || ((AF) == GPIO_AF8_UART4) || \ - ((AF) == GPIO_AF8_UART5) || ((AF) == GPIO_AF8_USART6) || \ - ((AF) == GPIO_AF9_CAN1) || ((AF) == GPIO_AF9_CAN2) || \ - ((AF) == GPIO_AF10_OTG_FS) || ((AF) == GPIO_AF10_OTG_HS) || \ - ((AF) == GPIO_AF11_ETH) || ((AF) == GPIO_AF12_OTG_HS_FS) || \ - ((AF) == GPIO_AF12_SDIO) || ((AF) == GPIO_AF13_DCMI) || \ - ((AF) == GPIO_AF15_EVENTOUT) || ((AF) == GPIO_AF5_SPI4) || \ - ((AF) == GPIO_AF5_SPI5) || ((AF) == GPIO_AF5_SPI6) || \ - ((AF) == GPIO_AF8_UART7) || ((AF) == GPIO_AF8_UART8) || \ - ((AF) == GPIO_AF12_FMC) || ((AF) == GPIO_AF6_SAI1) || \ - ((AF) == GPIO_AF14_LTDC) || ((AF) == GPIO_AF13_DSI) || \ - ((AF) == GPIO_AF9_QSPI) || ((AF) == GPIO_AF10_QSPI)) - -#endif /* STM32F469xx || STM32F479xx */ -/*----------------------------------------------------------------------------*/ - -/*------------------STM32F412Zx/STM32F412Vx/STM32F412Rx/STM32F412Cx-----------*/ -#if defined(STM32F412Zx) || defined(STM32F412Vx) || defined(STM32F412Rx) || defined(STM32F412Cx) -#define IS_GPIO_AF(AF) (((AF) < 16U) && ((AF) != 11U) && ((AF) != 14U) && ((AF) != 13U)) -#endif /* STM32F412Zx || STM32F412Vx || STM32F412Rx || STM32F412Cx */ -/*----------------------------------------------------------------------------*/ - -/*------------------STM32F413xx/STM32F423xx-----------------------------------*/ -#if defined(STM32F413xx) || defined(STM32F423xx) -#define IS_GPIO_AF(AF) (((AF) < 16U) && ((AF) != 13U)) -#endif /* STM32F413xx || STM32F423xx */ -/*----------------------------------------------------------------------------*/ - -/** - * @} - */ - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup GPIOEx_Private_Functions GPIO Private Functions - * @{ - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* __STM32F4xx_HAL_GPIO_EX_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/panda/board/stm32fx/inc/system_stm32f4xx.h b/panda/board/stm32fx/inc/system_stm32f4xx.h deleted file mode 100644 index 7978dab..0000000 --- a/panda/board/stm32fx/inc/system_stm32f4xx.h +++ /dev/null @@ -1,124 +0,0 @@ -/** - ****************************************************************************** - * @file system_stm32f4xx.h - * @author MCD Application Team - * @version V2.6.0 - * @date 04-November-2016 - * @brief CMSIS Cortex-M4 Device System Source File for STM32F4xx devices. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT(c) 2016 STMicroelectronics

- * - * Redistribution and use in source and binary forms, with or without modification, - * are permitted provided that the following conditions are met: - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE - * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL - * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR - * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, - * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE - * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************** - */ - -/** @addtogroup CMSIS - * @{ - */ - -/** @addtogroup stm32f4xx_system - * @{ - */ - -/** - * @brief Define to prevent recursive inclusion - */ -#ifndef __SYSTEM_STM32F4XX_H -#define __SYSTEM_STM32F4XX_H - -#ifdef __cplusplus - extern "C" { -#endif - -/** @addtogroup STM32F4xx_System_Includes - * @{ - */ - -/** - * @} - */ - - -/** @addtogroup STM32F4xx_System_Exported_types - * @{ - */ - /* This variable is updated in three ways: - 1) by calling CMSIS function SystemCoreClockUpdate() - 2) by calling HAL API function HAL_RCC_GetSysClockFreq() - 3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency - Note: If you use this function to configure the system clock; then there - is no need to call the 2 first functions listed above, since SystemCoreClock - variable is updated automatically. - */ -extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */ - -extern const uint8_t AHBPrescTable[16]; /*!< AHB prescalers table values */ -extern const uint8_t APBPrescTable[8]; /*!< APB prescalers table values */ - -/** - * @} - */ - -/** @addtogroup STM32F4xx_System_Exported_Constants - * @{ - */ - -/** - * @} - */ - -/** @addtogroup STM32F4xx_System_Exported_Macros - * @{ - */ - -/** - * @} - */ - -/** @addtogroup STM32F4xx_System_Exported_Functions - * @{ - */ - -extern void SystemInit(void); -extern void SystemCoreClockUpdate(void); -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /*__SYSTEM_STM32F4XX_H */ - -/** - * @} - */ - -/** - * @} - */ -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/panda/board/stm32fx/interrupt_handlers.h b/panda/board/stm32fx/interrupt_handlers.h deleted file mode 100644 index 41d7427..0000000 --- a/panda/board/stm32fx/interrupt_handlers.h +++ /dev/null @@ -1,98 +0,0 @@ -// ********************* Bare interrupt handlers ********************* -// Only implemented the STM32F413 interrupts for now - -void WWDG_IRQHandler(void) {handle_interrupt(WWDG_IRQn);} -void PVD_IRQHandler(void) {handle_interrupt(PVD_IRQn);} -void TAMP_STAMP_IRQHandler(void) {handle_interrupt(TAMP_STAMP_IRQn);} -void RTC_WKUP_IRQHandler(void) {handle_interrupt(RTC_WKUP_IRQn);} -void FLASH_IRQHandler(void) {handle_interrupt(FLASH_IRQn);} -void RCC_IRQHandler(void) {handle_interrupt(RCC_IRQn);} -void EXTI0_IRQHandler(void) {handle_interrupt(EXTI0_IRQn);} -void EXTI1_IRQHandler(void) {handle_interrupt(EXTI1_IRQn);} -void EXTI2_IRQHandler(void) {handle_interrupt(EXTI2_IRQn);} -void EXTI3_IRQHandler(void) {handle_interrupt(EXTI3_IRQn);} -void EXTI4_IRQHandler(void) {handle_interrupt(EXTI4_IRQn);} -void DMA1_Stream0_IRQHandler(void) {handle_interrupt(DMA1_Stream0_IRQn);} -void DMA1_Stream1_IRQHandler(void) {handle_interrupt(DMA1_Stream1_IRQn);} -void DMA1_Stream2_IRQHandler(void) {handle_interrupt(DMA1_Stream2_IRQn);} -void DMA1_Stream3_IRQHandler(void) {handle_interrupt(DMA1_Stream3_IRQn);} -void DMA1_Stream4_IRQHandler(void) {handle_interrupt(DMA1_Stream4_IRQn);} -void DMA1_Stream5_IRQHandler(void) {handle_interrupt(DMA1_Stream5_IRQn);} -void DMA1_Stream6_IRQHandler(void) {handle_interrupt(DMA1_Stream6_IRQn);} -void ADC_IRQHandler(void) {handle_interrupt(ADC_IRQn);} -void CAN1_TX_IRQHandler(void) {handle_interrupt(CAN1_TX_IRQn);} -void CAN1_RX0_IRQHandler(void) {handle_interrupt(CAN1_RX0_IRQn);} -void CAN1_RX1_IRQHandler(void) {handle_interrupt(CAN1_RX1_IRQn);} -void CAN1_SCE_IRQHandler(void) {handle_interrupt(CAN1_SCE_IRQn);} -void EXTI9_5_IRQHandler(void) {handle_interrupt(EXTI9_5_IRQn);} -void TIM1_BRK_TIM9_IRQHandler(void) {handle_interrupt(TIM1_BRK_TIM9_IRQn);} -void TIM1_UP_TIM10_IRQHandler(void) {handle_interrupt(TIM1_UP_TIM10_IRQn);} -void TIM1_TRG_COM_TIM11_IRQHandler(void) {handle_interrupt(TIM1_TRG_COM_TIM11_IRQn);} -void TIM1_CC_IRQHandler(void) {handle_interrupt(TIM1_CC_IRQn);} -void TIM2_IRQHandler(void) {handle_interrupt(TIM2_IRQn);} -void TIM3_IRQHandler(void) {handle_interrupt(TIM3_IRQn);} -void TIM4_IRQHandler(void) {handle_interrupt(TIM4_IRQn);} -void I2C1_EV_IRQHandler(void) {handle_interrupt(I2C1_EV_IRQn);} -void I2C1_ER_IRQHandler(void) {handle_interrupt(I2C1_ER_IRQn);} -void I2C2_EV_IRQHandler(void) {handle_interrupt(I2C2_EV_IRQn);} -void I2C2_ER_IRQHandler(void) {handle_interrupt(I2C2_ER_IRQn);} -void SPI1_IRQHandler(void) {handle_interrupt(SPI1_IRQn);} -void SPI2_IRQHandler(void) {handle_interrupt(SPI2_IRQn);} -void USART1_IRQHandler(void) {handle_interrupt(USART1_IRQn);} -void USART2_IRQHandler(void) {handle_interrupt(USART2_IRQn);} -void USART3_IRQHandler(void) {handle_interrupt(USART3_IRQn);} -void EXTI15_10_IRQHandler(void) {handle_interrupt(EXTI15_10_IRQn);} -void RTC_Alarm_IRQHandler(void) {handle_interrupt(RTC_Alarm_IRQn);} -void OTG_FS_WKUP_IRQHandler(void) {handle_interrupt(OTG_FS_WKUP_IRQn);} -void TIM8_BRK_TIM12_IRQHandler(void) {handle_interrupt(TIM8_BRK_TIM12_IRQn);} -void TIM8_UP_TIM13_IRQHandler(void) {handle_interrupt(TIM8_UP_TIM13_IRQn);} -void TIM8_TRG_COM_TIM14_IRQHandler(void) {handle_interrupt(TIM8_TRG_COM_TIM14_IRQn);} -void TIM8_CC_IRQHandler(void) {handle_interrupt(TIM8_CC_IRQn);} -void DMA1_Stream7_IRQHandler(void) {handle_interrupt(DMA1_Stream7_IRQn);} -void FSMC_IRQHandler(void) {handle_interrupt(FSMC_IRQn);} -void SDIO_IRQHandler(void) {handle_interrupt(SDIO_IRQn);} -void TIM5_IRQHandler(void) {handle_interrupt(TIM5_IRQn);} -void SPI3_IRQHandler(void) {handle_interrupt(SPI3_IRQn);} -void UART4_IRQHandler(void) {handle_interrupt(UART4_IRQn);} -void UART5_IRQHandler(void) {handle_interrupt(UART5_IRQn);} -void TIM6_DAC_IRQHandler(void) {handle_interrupt(TIM6_DAC_IRQn);} -void TIM7_IRQHandler(void) {handle_interrupt(TIM7_IRQn);} -void DMA2_Stream0_IRQHandler(void) {handle_interrupt(DMA2_Stream0_IRQn);} -void DMA2_Stream1_IRQHandler(void) {handle_interrupt(DMA2_Stream1_IRQn);} -void DMA2_Stream2_IRQHandler(void) {handle_interrupt(DMA2_Stream2_IRQn);} -void DMA2_Stream3_IRQHandler(void) {handle_interrupt(DMA2_Stream3_IRQn);} -void DMA2_Stream4_IRQHandler(void) {handle_interrupt(DMA2_Stream4_IRQn);} -void CAN2_TX_IRQHandler(void) {handle_interrupt(CAN2_TX_IRQn);} -void CAN2_RX0_IRQHandler(void) {handle_interrupt(CAN2_RX0_IRQn);} -void CAN2_RX1_IRQHandler(void) {handle_interrupt(CAN2_RX1_IRQn);} -void CAN2_SCE_IRQHandler(void) {handle_interrupt(CAN2_SCE_IRQn);} -void OTG_FS_IRQHandler(void) {handle_interrupt(OTG_FS_IRQn);} -void DMA2_Stream5_IRQHandler(void) {handle_interrupt(DMA2_Stream5_IRQn);} -void DMA2_Stream6_IRQHandler(void) {handle_interrupt(DMA2_Stream6_IRQn);} -void DMA2_Stream7_IRQHandler(void) {handle_interrupt(DMA2_Stream7_IRQn);} -void USART6_IRQHandler(void) {handle_interrupt(USART6_IRQn);} -void I2C3_EV_IRQHandler(void) {handle_interrupt(I2C3_EV_IRQn);} -void I2C3_ER_IRQHandler(void) {handle_interrupt(I2C3_ER_IRQn);} -void DFSDM1_FLT0_IRQHandler(void) {handle_interrupt(DFSDM1_FLT0_IRQn);} -void DFSDM1_FLT1_IRQHandler(void) {handle_interrupt(DFSDM1_FLT1_IRQn);} -void CAN3_TX_IRQHandler(void) {handle_interrupt(CAN3_TX_IRQn);} -void CAN3_RX0_IRQHandler(void) {handle_interrupt(CAN3_RX0_IRQn);} -void CAN3_RX1_IRQHandler(void) {handle_interrupt(CAN3_RX1_IRQn);} -void CAN3_SCE_IRQHandler(void) {handle_interrupt(CAN3_SCE_IRQn);} -void RNG_IRQHandler(void) {handle_interrupt(RNG_IRQn);} -void FPU_IRQHandler(void) {handle_interrupt(FPU_IRQn);} -void UART7_IRQHandler(void) {handle_interrupt(UART7_IRQn);} -void UART8_IRQHandler(void) {handle_interrupt(UART8_IRQn);} -void SPI4_IRQHandler(void) {handle_interrupt(SPI4_IRQn);} -void SPI5_IRQHandler(void) {handle_interrupt(SPI5_IRQn);} -void SAI1_IRQHandler(void) {handle_interrupt(SAI1_IRQn);} -void UART9_IRQHandler(void) {handle_interrupt(UART9_IRQn);} -void UART10_IRQHandler(void) {handle_interrupt(UART10_IRQn);} -void QUADSPI_IRQHandler(void) {handle_interrupt(QUADSPI_IRQn);} -void FMPI2C1_EV_IRQHandler(void) {handle_interrupt(FMPI2C1_EV_IRQn);} -void FMPI2C1_ER_IRQHandler(void) {handle_interrupt(FMPI2C1_ER_IRQn);} -void LPTIM1_IRQHandler(void) {handle_interrupt(LPTIM1_IRQn);} -void DFSDM2_FLT0_IRQHandler(void) {handle_interrupt(DFSDM2_FLT0_IRQn);} -void DFSDM2_FLT1_IRQHandler(void) {handle_interrupt(DFSDM2_FLT1_IRQn);} -void DFSDM2_FLT2_IRQHandler(void) {handle_interrupt(DFSDM2_FLT2_IRQn);} -void DFSDM2_FLT3_IRQHandler(void) {handle_interrupt(DFSDM2_FLT3_IRQn);} diff --git a/panda/board/stm32fx/lladc.h b/panda/board/stm32fx/lladc.h deleted file mode 100644 index c2df10f..0000000 --- a/panda/board/stm32fx/lladc.h +++ /dev/null @@ -1,24 +0,0 @@ - -void register_set(volatile uint32_t *addr, uint32_t val, uint32_t mask); - -void adc_init(void) { - register_set(&(ADC->CCR), ADC_CCR_TSVREFE | ADC_CCR_VBATE, 0xC30000U); - register_set(&(ADC1->CR2), ADC_CR2_ADON, 0xFF7F0F03U); - register_set(&(ADC1->SMPR1), ADC_SMPR1_SMP12 | ADC_SMPR1_SMP13, 0x7FFFFFFU); -} - -uint16_t adc_get_raw(uint8_t channel) { - // Select channel - register_set(&(ADC1->JSQR), ((uint32_t) channel << 15U), 0x3FFFFFU); - - // Start conversion - ADC1->SR &= ~(ADC_SR_JEOC); - ADC1->CR2 |= ADC_CR2_JSWSTART; - while (!(ADC1->SR & ADC_SR_JEOC)); - - return ADC1->JDR1; -} - -uint16_t adc_get_mV(uint8_t channel) { - return (adc_get_raw(channel) * current_board->avdd_mV) / 4095U; -} diff --git a/panda/board/stm32fx/llbxcan.h b/panda/board/stm32fx/llbxcan.h deleted file mode 100644 index 72523cf..0000000 --- a/panda/board/stm32fx/llbxcan.h +++ /dev/null @@ -1,158 +0,0 @@ -// Flasher and pedal use raw mailbox access -#define GET_MAILBOX_BYTE(msg, b) (((int)(b) > 3) ? (((msg)->RDHR >> (8U * ((unsigned int)(b) % 4U))) & 0xFFU) : (((msg)->RDLR >> (8U * (unsigned int)(b))) & 0xFFU)) -#define GET_MAILBOX_BYTES_04(msg) ((msg)->RDLR) -#define GET_MAILBOX_BYTES_48(msg) ((msg)->RDHR) - -// SAE 2284-3 : minimum 16 tq, SJW 3, sample point at 81.3% -#define CAN_QUANTA 16U -#define CAN_SEQ1 12U -#define CAN_SEQ2 3U -#define CAN_SJW 3U - -#define CAN_PCLK 48000U -// 333 = 33.3 kbps -// 5000 = 500 kbps -#define can_speed_to_prescaler(x) (CAN_PCLK / CAN_QUANTA * 10U / (x)) - -#define CAN_NAME_FROM_CANIF(CAN_DEV) (((CAN_DEV)==CAN1) ? "CAN1" : (((CAN_DEV) == CAN2) ? "CAN2" : "CAN3")) - -void print(const char *a); - -// kbps multiplied by 10 -const uint32_t speeds[] = {100U, 200U, 500U, 1000U, 1250U, 2500U, 5000U, 10000U}; -const uint32_t data_speeds[] = {0U}; // No separate data speed, dummy - -bool llcan_set_speed(CAN_TypeDef *CANx, uint32_t speed, bool loopback, bool silent) { - bool ret = true; - - // initialization mode - register_set(&(CANx->MCR), CAN_MCR_TTCM | CAN_MCR_INRQ, 0x180FFU); - uint32_t timeout_counter = 0U; - while((CANx->MSR & CAN_MSR_INAK) != CAN_MSR_INAK){ - // Delay for about 1ms - delay(10000); - timeout_counter++; - - if(timeout_counter >= CAN_INIT_TIMEOUT_MS){ - print(CAN_NAME_FROM_CANIF(CANx)); print(" set_speed timed out (1)!\n"); - ret = false; - break; - } - } - - if(ret){ - // set time quanta from defines - register_set(&(CANx->BTR), ((CAN_BTR_TS1_0 * (CAN_SEQ1-1U)) | - (CAN_BTR_TS2_0 * (CAN_SEQ2-1U)) | - (CAN_BTR_SJW_0 * (CAN_SJW-1U)) | - (can_speed_to_prescaler(speed) - 1U)), 0xC37F03FFU); - - // silent loopback mode for debugging - if (loopback) { - register_set_bits(&(CANx->BTR), CAN_BTR_SILM | CAN_BTR_LBKM); - } - if (silent) { - register_set_bits(&(CANx->BTR), CAN_BTR_SILM); - } - - // reset - register_set(&(CANx->MCR), CAN_MCR_TTCM | CAN_MCR_ABOM, 0x180FFU); - - timeout_counter = 0U; - while(((CANx->MSR & CAN_MSR_INAK) == CAN_MSR_INAK)) { - // Delay for about 1ms - delay(10000); - timeout_counter++; - - if(timeout_counter >= CAN_INIT_TIMEOUT_MS){ - print(CAN_NAME_FROM_CANIF(CANx)); print(" set_speed timed out (2)!\n"); - ret = false; - break; - } - } - } - - return ret; -} - -void llcan_irq_disable(const CAN_TypeDef *CANx) { - if (CANx == CAN1) { - NVIC_DisableIRQ(CAN1_TX_IRQn); - NVIC_DisableIRQ(CAN1_RX0_IRQn); - NVIC_DisableIRQ(CAN1_SCE_IRQn); - } else if (CANx == CAN2) { - NVIC_DisableIRQ(CAN2_TX_IRQn); - NVIC_DisableIRQ(CAN2_RX0_IRQn); - NVIC_DisableIRQ(CAN2_SCE_IRQn); - } else if (CANx == CAN3) { - NVIC_DisableIRQ(CAN3_TX_IRQn); - NVIC_DisableIRQ(CAN3_RX0_IRQn); - NVIC_DisableIRQ(CAN3_SCE_IRQn); - } else { - } -} - -void llcan_irq_enable(const CAN_TypeDef *CANx) { - if (CANx == CAN1) { - NVIC_EnableIRQ(CAN1_TX_IRQn); - NVIC_EnableIRQ(CAN1_RX0_IRQn); - NVIC_EnableIRQ(CAN1_SCE_IRQn); - } else if (CANx == CAN2) { - NVIC_EnableIRQ(CAN2_TX_IRQn); - NVIC_EnableIRQ(CAN2_RX0_IRQn); - NVIC_EnableIRQ(CAN2_SCE_IRQn); - } else if (CANx == CAN3) { - NVIC_EnableIRQ(CAN3_TX_IRQn); - NVIC_EnableIRQ(CAN3_RX0_IRQn); - NVIC_EnableIRQ(CAN3_SCE_IRQn); - } else { - } -} - -bool llcan_init(CAN_TypeDef *CANx) { - bool ret = true; - - // Enter init mode - register_set_bits(&(CANx->FMR), CAN_FMR_FINIT); - - // Wait for INAK bit to be set - uint32_t timeout_counter = 0U; - while(((CANx->MSR & CAN_MSR_INAK) == CAN_MSR_INAK)) { - // Delay for about 1ms - delay(10000); - timeout_counter++; - - if(timeout_counter >= CAN_INIT_TIMEOUT_MS){ - print(CAN_NAME_FROM_CANIF(CANx)); print(" initialization timed out!\n"); - ret = false; - break; - } - } - - if(ret){ - // no mask - // For some weird reason some of these registers do not want to set properly on CAN2 and CAN3. Probably something to do with the single/dual mode and their different filters. - CANx->sFilterRegister[0].FR1 = 0U; - CANx->sFilterRegister[0].FR2 = 0U; - CANx->sFilterRegister[14].FR1 = 0U; - CANx->sFilterRegister[14].FR2 = 0U; - CANx->FA1R |= 1U | (1UL << 14); - - // Exit init mode, do not wait - register_clear_bits(&(CANx->FMR), CAN_FMR_FINIT); - - // enable certain CAN interrupts - register_set_bits(&(CANx->IER), CAN_IER_TMEIE | CAN_IER_FMPIE0 | CAN_IER_ERRIE | CAN_IER_LECIE | CAN_IER_BOFIE | CAN_IER_EPVIE | CAN_IER_EWGIE | CAN_IER_FOVIE0 | CAN_IER_FFIE0); - - // clear overrun flag on init - CANx->RF0R &= ~(CAN_RF0R_FOVR0); - - llcan_irq_enable(CANx); - } - return ret; -} - -void llcan_clear_send(CAN_TypeDef *CANx) { - CANx->TSR |= CAN_TSR_ABRQ0; // Abort message transmission on error interrupt - CANx->MSR |= CAN_MSR_ERRI; // Clear error interrupt -} diff --git a/panda/board/stm32fx/llexti.h b/panda/board/stm32fx/llexti.h deleted file mode 100644 index 6de13ab..0000000 --- a/panda/board/stm32fx/llexti.h +++ /dev/null @@ -1,56 +0,0 @@ -void EXTI_IRQ_Handler(void); - -void exti_irq_init(void) { - SYSCFG->EXTICR[2] &= ~(SYSCFG_EXTICR3_EXTI8_Msk); - if (harness.status == HARNESS_STATUS_FLIPPED) { - // CAN2_RX - current_board->enable_can_transceiver(3U, false); - SYSCFG->EXTICR[2] |= (SYSCFG_EXTICR3_EXTI8_PA); - - // IRQ on falling edge for PC3 (SBU2, EXTI3) - SYSCFG->EXTICR[0] &= ~(SYSCFG_EXTICR1_EXTI3_Msk); - SYSCFG->EXTICR[0] |= (SYSCFG_EXTICR1_EXTI3_PC); - EXTI->IMR |= EXTI_IMR_MR3; - EXTI->RTSR &= ~EXTI_RTSR_TR3; // rising edge - EXTI->FTSR |= EXTI_FTSR_TR3; // falling edge - REGISTER_INTERRUPT(EXTI3_IRQn, EXTI_IRQ_Handler, 100U, FAULT_INTERRUPT_RATE_EXTI) - NVIC_EnableIRQ(EXTI3_IRQn); - } else { - // CAN0_RX - current_board->enable_can_transceiver(1U, false); - SYSCFG->EXTICR[2] |= (SYSCFG_EXTICR3_EXTI8_PB); - - // IRQ on falling edge for PC0 (SBU1, EXTI0) - SYSCFG->EXTICR[0] &= ~(SYSCFG_EXTICR1_EXTI0_Msk); - SYSCFG->EXTICR[0] |= (SYSCFG_EXTICR1_EXTI0_PC); - EXTI->IMR |= EXTI_IMR_MR0; - EXTI->RTSR &= ~EXTI_RTSR_TR0; // rising edge - EXTI->FTSR |= EXTI_FTSR_TR0; // falling edge - REGISTER_INTERRUPT(EXTI0_IRQn, EXTI_IRQ_Handler, 100U, FAULT_INTERRUPT_RATE_EXTI) - NVIC_EnableIRQ(EXTI0_IRQn); - } - // CAN0 or CAN2 IRQ on falling edge (EXTI8) - EXTI->IMR |= EXTI_IMR_MR8; - EXTI->RTSR &= ~EXTI_RTSR_TR8; // rising edge - EXTI->FTSR |= EXTI_FTSR_TR8; // falling edge - REGISTER_INTERRUPT(EXTI9_5_IRQn, EXTI_IRQ_Handler, 100U, FAULT_INTERRUPT_RATE_EXTI) - NVIC_EnableIRQ(EXTI9_5_IRQn); -} - -bool check_exti_irq(void) { - return ((EXTI->PR & EXTI_PR_PR8) || (EXTI->PR & EXTI_PR_PR3) || (EXTI->PR & EXTI_PR_PR0)); -} - -void exti_irq_clear(void) { - // Clear pending bits - EXTI->PR |= EXTI_PR_PR8; - EXTI->PR |= EXTI_PR_PR0; - EXTI->PR |= EXTI_PR_PR3; - EXTI->PR |= EXTI_PR_PR22; - - // Disable all active EXTI IRQs - EXTI->IMR &= ~EXTI_IMR_MR8; - EXTI->IMR &= ~EXTI_IMR_MR0; - EXTI->IMR &= ~EXTI_IMR_MR3; - EXTI->IMR &= ~EXTI_IMR_MR22; -} diff --git a/panda/board/stm32fx/llfan.h b/panda/board/stm32fx/llfan.h deleted file mode 100644 index 9e3f0c6..0000000 --- a/panda/board/stm32fx/llfan.h +++ /dev/null @@ -1,23 +0,0 @@ -// TACH interrupt handler -void EXTI2_IRQ_Handler(void) { - volatile unsigned int pr = EXTI->PR & (1U << 2); - if ((pr & (1U << 2)) != 0U) { - fan_state.tach_counter++; - } - EXTI->PR = (1U << 2); -} - -void llfan_init(void) { - // 5000RPM * 4 tach edges / 60 seconds - REGISTER_INTERRUPT(EXTI2_IRQn, EXTI2_IRQ_Handler, 700U, FAULT_INTERRUPT_RATE_TACH) - - // Init PWM speed control - pwm_init(TIM3, 3); - - // Init TACH interrupt - register_set(&(SYSCFG->EXTICR[0]), SYSCFG_EXTICR1_EXTI2_PD, 0xF00U); - register_set_bits(&(EXTI->IMR), (1U << 2)); - register_set_bits(&(EXTI->RTSR), (1U << 2)); - register_set_bits(&(EXTI->FTSR), (1U << 2)); - NVIC_EnableIRQ(EXTI2_IRQn); -} diff --git a/panda/board/stm32fx/llflash.h b/panda/board/stm32fx/llflash.h deleted file mode 100644 index 61adcd4..0000000 --- a/panda/board/stm32fx/llflash.h +++ /dev/null @@ -1,28 +0,0 @@ -bool flash_is_locked(void) { - return (FLASH->CR & FLASH_CR_LOCK); -} - -void flash_unlock(void) { - FLASH->KEYR = 0x45670123; - FLASH->KEYR = 0xCDEF89AB; -} - -bool flash_erase_sector(uint8_t sector, bool unlocked) { - // don't erase the bootloader(sector 0) - if (sector != 0 && sector < 12 && unlocked) { - FLASH->CR = (sector << 3) | FLASH_CR_SER; - FLASH->CR |= FLASH_CR_STRT; - while (FLASH->SR & FLASH_SR_BSY); - return true; - } - return false; -} - -void flash_write_word(void *prog_ptr, uint32_t data) { - uint32_t *pp = prog_ptr; - FLASH->CR = FLASH_CR_PSIZE_1 | FLASH_CR_PG; - *pp = data; - while (FLASH->SR & FLASH_SR_BSY); -} - -void flush_write_buffer(void) { } diff --git a/panda/board/stm32fx/llrtc.h b/panda/board/stm32fx/llrtc.h deleted file mode 100644 index a9b6191..0000000 --- a/panda/board/stm32fx/llrtc.h +++ /dev/null @@ -1,69 +0,0 @@ -void enable_bdomain_protection(void) { - register_clear_bits(&(PWR->CR), PWR_CR_DBP); -} - -void disable_bdomain_protection(void) { - register_set_bits(&(PWR->CR), PWR_CR_DBP); -} - -void rtc_init(void){ - uint32_t bdcr_opts = RCC_BDCR_RTCEN; - uint32_t bdcr_mask = (RCC_BDCR_RTCEN | RCC_BDCR_RTCSEL); - if (current_board->has_rtc_battery) { - bdcr_opts |= (RCC_BDCR_RTCSEL_0 | RCC_BDCR_LSEON); - bdcr_mask |= (RCC_BDCR_LSEMOD | RCC_BDCR_LSEBYP | RCC_BDCR_LSEON); - } else { - bdcr_opts |= RCC_BDCR_RTCSEL_1; - RCC->CSR |= RCC_CSR_LSION; - while((RCC->CSR & RCC_CSR_LSIRDY) == 0){} - } - - // Initialize RTC module and clock if not done already. - if((RCC->BDCR & bdcr_mask) != bdcr_opts){ - print("Initializing RTC\n"); - // Reset backup domain - register_set_bits(&(RCC->BDCR), RCC_BDCR_BDRST); - - // Disable write protection - disable_bdomain_protection(); - - // Clear backup domain reset - register_clear_bits(&(RCC->BDCR), RCC_BDCR_BDRST); - - // Set RTC options - register_set(&(RCC->BDCR), bdcr_opts, bdcr_mask); - - // Enable write protection - enable_bdomain_protection(); - } -} - -void rtc_wakeup_init(void) { - EXTI->IMR |= EXTI_IMR_MR22; - EXTI->RTSR |= EXTI_RTSR_TR22; // rising edge - EXTI->FTSR &= ~EXTI_FTSR_TR22; // falling edge - - NVIC_DisableIRQ(RTC_WKUP_IRQn); - - // Disable write protection - disable_bdomain_protection(); - RTC->WPR = 0xCA; - RTC->WPR = 0x53; - - RTC->CR &= ~RTC_CR_WUTE; - while((RTC->ISR & RTC_ISR_WUTWF) == 0){} - - RTC->CR &= ~RTC_CR_WUTIE; - RTC->ISR &= ~RTC_ISR_WUTF; - //PWR->CR |= PWR_CR_CWUF; - - RTC->WUTR = DEEPSLEEP_WAKEUP_DELAY; - // Wakeup timer interrupt enable, wakeup timer enable, select 1Hz rate - RTC->CR |= RTC_CR_WUTE | RTC_CR_WUTIE | RTC_CR_WUCKSEL_2; - - // Re-enable write protection - RTC->WPR = 0x00; - enable_bdomain_protection(); - - NVIC_EnableIRQ(RTC_WKUP_IRQn); -} diff --git a/panda/board/stm32fx/llspi.h b/panda/board/stm32fx/llspi.h deleted file mode 100644 index 31e419b..0000000 --- a/panda/board/stm32fx/llspi.h +++ /dev/null @@ -1,90 +0,0 @@ -void llspi_miso_dma(uint8_t *addr, int len) { - // disable DMA - DMA2_Stream3->CR &= ~DMA_SxCR_EN; - register_clear_bits(&(SPI1->CR2), SPI_CR2_TXDMAEN); - - // setup source and length - register_set(&(DMA2_Stream3->M0AR), (uint32_t)addr, 0xFFFFFFFFU); - DMA2_Stream3->NDTR = len; - - // enable DMA - register_set_bits(&(SPI1->CR2), SPI_CR2_TXDMAEN); - DMA2_Stream3->CR |= DMA_SxCR_EN; -} - -void llspi_mosi_dma(uint8_t *addr, int len) { - // disable DMA - register_clear_bits(&(SPI1->CR2), SPI_CR2_RXDMAEN); - DMA2_Stream2->CR &= ~DMA_SxCR_EN; - - // drain the bus - volatile uint8_t dat = SPI1->DR; - (void)dat; - - // setup destination and length - register_set(&(DMA2_Stream2->M0AR), (uint32_t)addr, 0xFFFFFFFFU); - DMA2_Stream2->NDTR = len; - - // enable DMA - DMA2_Stream2->CR |= DMA_SxCR_EN; - register_set_bits(&(SPI1->CR2), SPI_CR2_RXDMAEN); -} - -// SPI MOSI DMA FINISHED -void DMA2_Stream2_IRQ_Handler(void) { - // Clear interrupt flag - ENTER_CRITICAL(); - DMA2->LIFCR = DMA_LIFCR_CTCIF2; - - spi_rx_done(); - - EXIT_CRITICAL(); -} - -// SPI MISO DMA FINISHED -void DMA2_Stream3_IRQ_Handler(void) { - // Clear interrupt flag - DMA2->LIFCR = DMA_LIFCR_CTCIF3; - - // Wait until the transaction is actually finished and clear the DR - // Timeout to prevent hang when the master clock stops. - bool timed_out = false; - uint32_t start_time = microsecond_timer_get(); - while (!(SPI1->SR & SPI_SR_TXE)) { - if (get_ts_elapsed(microsecond_timer_get(), start_time) > SPI_TIMEOUT_US) { - timed_out = true; - break; - } - } - volatile uint8_t dat = SPI1->DR; - (void)dat; - SPI1->DR = 0U; - - if (timed_out) { - print("SPI: TX timeout\n"); - } - - spi_tx_done(timed_out); -} - -// ***************************** SPI init ***************************** -void llspi_init(void) { - REGISTER_INTERRUPT(DMA2_Stream2_IRQn, DMA2_Stream2_IRQ_Handler, SPI_IRQ_RATE, FAULT_INTERRUPT_RATE_SPI_DMA) - REGISTER_INTERRUPT(DMA2_Stream3_IRQn, DMA2_Stream3_IRQ_Handler, SPI_IRQ_RATE, FAULT_INTERRUPT_RATE_SPI_DMA) - - // Setup MOSI DMA - register_set(&(DMA2_Stream2->CR), (DMA_SxCR_CHSEL_1 | DMA_SxCR_CHSEL_0 | DMA_SxCR_MINC | DMA_SxCR_TCIE), 0x1E077EFEU); - register_set(&(DMA2_Stream2->PAR), (uint32_t)&(SPI1->DR), 0xFFFFFFFFU); - - // Setup MISO DMA - register_set(&(DMA2_Stream3->CR), (DMA_SxCR_CHSEL_1 | DMA_SxCR_CHSEL_0 | DMA_SxCR_MINC | DMA_SxCR_DIR_0 | DMA_SxCR_TCIE), 0x1E077EFEU); - register_set(&(DMA2_Stream3->PAR), (uint32_t)&(SPI1->DR), 0xFFFFFFFFU); - - // Enable SPI and the error interrupts - // TODO: verify clock phase and polarity - register_set(&(SPI1->CR1), SPI_CR1_SPE, 0xFFFFU); - register_set(&(SPI1->CR2), 0U, 0xF7U); - - NVIC_EnableIRQ(DMA2_Stream2_IRQn); - NVIC_EnableIRQ(DMA2_Stream3_IRQn); -} diff --git a/panda/board/stm32fx/lluart.h b/panda/board/stm32fx/lluart.h deleted file mode 100644 index ffe7e74..0000000 --- a/panda/board/stm32fx/lluart.h +++ /dev/null @@ -1,92 +0,0 @@ -// ***************************** Interrupt handlers ***************************** - -void uart_tx_ring(uart_ring *q){ - ENTER_CRITICAL(); - // Send out next byte of TX buffer - if (q->w_ptr_tx != q->r_ptr_tx) { - // Only send if transmit register is empty (aka last byte has been sent) - if ((q->uart->SR & USART_SR_TXE) != 0) { - q->uart->DR = q->elems_tx[q->r_ptr_tx]; // This clears TXE - q->r_ptr_tx = (q->r_ptr_tx + 1U) % q->tx_fifo_size; - } - - // Enable TXE interrupt if there is still data to be sent - if(q->r_ptr_tx != q->w_ptr_tx){ - q->uart->CR1 |= USART_CR1_TXEIE; - } else { - q->uart->CR1 &= ~USART_CR1_TXEIE; - } - } - EXIT_CRITICAL(); -} - -void uart_rx_ring(uart_ring *q){ - ENTER_CRITICAL(); - - // Read out RX buffer - uint8_t c = q->uart->DR; // This read after reading SR clears a bunch of interrupts - - uint16_t next_w_ptr = (q->w_ptr_rx + 1U) % q->rx_fifo_size; - - if ((next_w_ptr == q->r_ptr_rx) && q->overwrite) { - // overwrite mode: drop oldest byte - q->r_ptr_rx = (q->r_ptr_rx + 1U) % q->rx_fifo_size; - } - - // Do not overwrite buffer data - if (next_w_ptr != q->r_ptr_rx) { - q->elems_rx[q->w_ptr_rx] = c; - q->w_ptr_rx = next_w_ptr; - if (q->callback != NULL) { - q->callback(q); - } - } - - EXIT_CRITICAL(); -} - -void uart_send_break(uart_ring *u) { - while ((u->uart->CR1 & USART_CR1_SBK) != 0); - u->uart->CR1 |= USART_CR1_SBK; -} - -// This read after reading SR clears all error interrupts. We don't want compiler warnings, nor optimizations -#define UART_READ_DR(uart) volatile uint8_t t = (uart)->DR; UNUSED(t); - -void uart_interrupt_handler(uart_ring *q) { - ENTER_CRITICAL(); - - // Read UART status. This is also the first step necessary in clearing most interrupts - uint32_t status = q->uart->SR; - - // If RXNE is set, perform a read. This clears RXNE, ORE, IDLE, NF and FE - if((status & USART_SR_RXNE) != 0U){ - uart_rx_ring(q); - } - - // Detect errors and clear them - uint32_t err = (status & USART_SR_ORE) | (status & USART_SR_NE) | (status & USART_SR_FE) | (status & USART_SR_PE); - if(err != 0U){ - #ifdef DEBUG_UART - print("Encountered UART error: "); puth(err); print("\n"); - #endif - UART_READ_DR(q->uart) - } - // Send if necessary - uart_tx_ring(q); - - EXIT_CRITICAL(); -} - -void USART2_IRQ_Handler(void) { uart_interrupt_handler(&uart_ring_debug); } - -// ***************************** Hardware setup ***************************** - -#define DIV_(_PCLK_, _BAUD_) (((_PCLK_) * 25U) / (4U * (_BAUD_))) -#define DIVMANT_(_PCLK_, _BAUD_) (DIV_((_PCLK_), (_BAUD_)) / 100U) -#define DIVFRAQ_(_PCLK_, _BAUD_) ((((DIV_((_PCLK_), (_BAUD_)) - (DIVMANT_((_PCLK_), (_BAUD_)) * 100U)) * 16U) + 50U) / 100U) -#define USART_BRR_(_PCLK_, _BAUD_) ((DIVMANT_((_PCLK_), (_BAUD_)) << 4) | (DIVFRAQ_((_PCLK_), (_BAUD_)) & 0x0FU)) - -void uart_set_baud(USART_TypeDef *u, unsigned int baud) { - u->BRR = USART_BRR_(APB1_FREQ*1000000U, baud); -} diff --git a/panda/board/stm32fx/llusb.h b/panda/board/stm32fx/llusb.h deleted file mode 100644 index 20c9808..0000000 --- a/panda/board/stm32fx/llusb.h +++ /dev/null @@ -1,91 +0,0 @@ -USB_OTG_GlobalTypeDef *USBx = USB_OTG_FS; - -#define USBx_HOST ((USB_OTG_HostTypeDef *)((uint32_t)USBx + USB_OTG_HOST_BASE)) -#define USBx_DEVICE ((USB_OTG_DeviceTypeDef *)((uint32_t)USBx + USB_OTG_DEVICE_BASE)) -#define USBx_INEP(i) ((USB_OTG_INEndpointTypeDef *)((uint32_t)USBx + USB_OTG_IN_ENDPOINT_BASE + ((i) * USB_OTG_EP_REG_SIZE))) -#define USBx_OUTEP(i) ((USB_OTG_OUTEndpointTypeDef *)((uint32_t)USBx + USB_OTG_OUT_ENDPOINT_BASE + ((i) * USB_OTG_EP_REG_SIZE))) -#define USBx_DFIFO(i) *(__IO uint32_t *)((uint32_t)USBx + USB_OTG_FIFO_BASE + ((i) * USB_OTG_FIFO_SIZE)) -#define USBx_PCGCCTL *(__IO uint32_t *)((uint32_t)USBx + USB_OTG_PCGCCTL_BASE) - -#define USBD_FS_TRDT_VALUE 5UL -#define USB_OTG_SPEED_FULL 3 - - -void usb_irqhandler(void); - -void OTG_FS_IRQ_Handler(void) { - NVIC_DisableIRQ(OTG_FS_IRQn); - //__disable_irq(); - usb_irqhandler(); - //__enable_irq(); - NVIC_EnableIRQ(OTG_FS_IRQn); -} - -void usb_init(void) { - REGISTER_INTERRUPT(OTG_FS_IRQn, OTG_FS_IRQ_Handler, 1500000U, FAULT_INTERRUPT_RATE_USB) //TODO: Find out a better rate limit for USB. Now it's the 1.5MB/s rate - - // full speed PHY, do reset and remove power down - /*puth(USBx->GRSTCTL); - print(" resetting PHY\n");*/ - while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_AHBIDL) == 0); - //print("AHB idle\n"); - - // reset PHY here - USBx->GRSTCTL |= USB_OTG_GRSTCTL_CSRST; - while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_CSRST) == USB_OTG_GRSTCTL_CSRST); - //print("reset done\n"); - - // internal PHY, force device mode - USBx->GUSBCFG = USB_OTG_GUSBCFG_PHYSEL | USB_OTG_GUSBCFG_FDMOD; - - // slowest timings - USBx->GUSBCFG |= ((USBD_FS_TRDT_VALUE << 10) & USB_OTG_GUSBCFG_TRDT); - - // power up the PHY - USBx->GCCFG = USB_OTG_GCCFG_PWRDWN; - - //USBx->GCCFG |= USB_OTG_GCCFG_VBDEN | USB_OTG_GCCFG_SDEN |USB_OTG_GCCFG_PDEN | USB_OTG_GCCFG_DCDEN; - - /* B-peripheral session valid override enable*/ - USBx->GOTGCTL |= USB_OTG_GOTGCTL_BVALOVAL; - USBx->GOTGCTL |= USB_OTG_GOTGCTL_BVALOEN; - - // be a device, slowest timings - //USBx->GUSBCFG = USB_OTG_GUSBCFG_FDMOD | USB_OTG_GUSBCFG_PHYSEL | USB_OTG_GUSBCFG_TRDT | USB_OTG_GUSBCFG_TOCAL; - //USBx->GUSBCFG |= (uint32_t)((USBD_FS_TRDT_VALUE << 10) & USB_OTG_GUSBCFG_TRDT); - //USBx->GUSBCFG = USB_OTG_GUSBCFG_PHYSEL | USB_OTG_GUSBCFG_TRDT | USB_OTG_GUSBCFG_TOCAL; - - // **** for debugging, doesn't seem to work **** - //USBx->GUSBCFG |= USB_OTG_GUSBCFG_CTXPKT; - - // reset PHY clock - USBx_PCGCCTL = 0; - - // enable the fancy OTG things - // DCFG_FRAME_INTERVAL_80 is 0 - //USBx->GUSBCFG |= USB_OTG_GUSBCFG_HNPCAP | USB_OTG_GUSBCFG_SRPCAP; - USBx_DEVICE->DCFG |= USB_OTG_SPEED_FULL | USB_OTG_DCFG_NZLSOHSK; - - //USBx_DEVICE->DCFG = USB_OTG_DCFG_NZLSOHSK | USB_OTG_DCFG_DSPD; - //USBx_DEVICE->DCFG = USB_OTG_DCFG_DSPD; - - // clear pending interrupts - USBx->GINTSTS = 0xBFFFFFFFU; - - // setup USB interrupts - // all interrupts except TXFIFO EMPTY - //USBx->GINTMSK = 0xFFFFFFFF & ~(USB_OTG_GINTMSK_NPTXFEM | USB_OTG_GINTMSK_PTXFEM | USB_OTG_GINTSTS_SOF | USB_OTG_GINTSTS_EOPF); - //USBx->GINTMSK = 0xFFFFFFFF & ~(USB_OTG_GINTMSK_NPTXFEM | USB_OTG_GINTMSK_PTXFEM); - USBx->GINTMSK = USB_OTG_GINTMSK_USBRST | USB_OTG_GINTMSK_ENUMDNEM | USB_OTG_GINTMSK_OTGINT | - USB_OTG_GINTMSK_RXFLVLM | USB_OTG_GINTMSK_GONAKEFFM | USB_OTG_GINTMSK_GINAKEFFM | - USB_OTG_GINTMSK_OEPINT | USB_OTG_GINTMSK_IEPINT | USB_OTG_GINTMSK_USBSUSPM | - USB_OTG_GINTMSK_CIDSCHGM | USB_OTG_GINTMSK_SRQIM | USB_OTG_GINTMSK_MMISM | USB_OTG_GINTMSK_EOPFM; - - USBx->GAHBCFG = USB_OTG_GAHBCFG_GINT; - - // DCTL startup value is 2 on new chip, 0 on old chip - USBx_DEVICE->DCTL = 0; - - // enable the IRQ - NVIC_EnableIRQ(OTG_FS_IRQn); -} diff --git a/panda/board/stm32fx/peripherals.h b/panda/board/stm32fx/peripherals.h deleted file mode 100644 index 79ac3c6..0000000 --- a/panda/board/stm32fx/peripherals.h +++ /dev/null @@ -1,91 +0,0 @@ -void gpio_usb_init(void) { - // A11,A12: USB - set_gpio_alternate(GPIOA, 11, GPIO_AF10_OTG_FS); - set_gpio_alternate(GPIOA, 12, GPIO_AF10_OTG_FS); - GPIOA->OSPEEDR = GPIO_OSPEEDER_OSPEEDR11 | GPIO_OSPEEDER_OSPEEDR12; -} - -void gpio_spi_init(void) { - // A4-A7: SPI - set_gpio_alternate(GPIOA, 4, GPIO_AF5_SPI1); - set_gpio_alternate(GPIOA, 5, GPIO_AF5_SPI1); - set_gpio_alternate(GPIOA, 6, GPIO_AF5_SPI1); - set_gpio_alternate(GPIOA, 7, GPIO_AF5_SPI1); - register_set_bits(&(GPIOA->OSPEEDR), GPIO_OSPEEDER_OSPEEDR4 | GPIO_OSPEEDER_OSPEEDR5 | GPIO_OSPEEDER_OSPEEDR6 | GPIO_OSPEEDER_OSPEEDR7); -} - -void gpio_usart2_init(void) { - // A2,A3: USART 2 for debugging - set_gpio_alternate(GPIOA, 2, GPIO_AF7_USART2); - set_gpio_alternate(GPIOA, 3, GPIO_AF7_USART2); -} - -// Common GPIO initialization -void common_init_gpio(void) { - // TODO: Is this block actually doing something??? - // pull low to hold ESP in reset?? - // enable OTG out tied to ground - GPIOA->ODR = 0; - GPIOB->ODR = 0; - GPIOA->PUPDR = 0; - GPIOB->AFR[0] = 0; - GPIOB->AFR[1] = 0; - - // C2: Voltage sense line - set_gpio_mode(GPIOC, 2, MODE_ANALOG); - - gpio_usb_init(); - - // B8,B9: CAN 1 - set_gpio_alternate(GPIOB, 8, GPIO_AF8_CAN1); - set_gpio_alternate(GPIOB, 9, GPIO_AF8_CAN1); -} - -void flasher_peripherals_init(void) { - RCC->AHB1ENR |= RCC_AHB1ENR_DMA2EN; - RCC->APB2ENR |= RCC_APB2ENR_SPI1EN; - RCC->AHB2ENR |= RCC_AHB2ENR_OTGFSEN; - RCC->APB1ENR |= RCC_APB1ENR_USART2EN; -} - -// Peripheral initialization -void peripherals_init(void) { - // enable GPIO(A,B,C,D) - RCC->AHB1ENR |= RCC_AHB1ENR_GPIOAEN; - RCC->AHB1ENR |= RCC_AHB1ENR_GPIOBEN; - RCC->AHB1ENR |= RCC_AHB1ENR_GPIOCEN; - RCC->AHB1ENR |= RCC_AHB1ENR_GPIODEN; - - // Supplemental - RCC->AHB1ENR |= RCC_AHB1ENR_DMA2EN; - RCC->APB1ENR |= RCC_APB1ENR_PWREN; // for RTC config - RCC->APB2ENR |= RCC_APB2ENR_SYSCFGEN; - - // Connectivity - RCC->APB2ENR |= RCC_APB2ENR_SPI1EN; - RCC->AHB2ENR |= RCC_AHB2ENR_OTGFSEN; - RCC->APB1ENR |= RCC_APB1ENR_USART2EN; - RCC->APB1ENR |= RCC_APB1ENR_USART3EN; - RCC->APB1ENR |= RCC_APB1ENR_UART5EN; - RCC->APB1ENR |= RCC_APB1ENR_CAN1EN; - RCC->APB1ENR |= RCC_APB1ENR_CAN2EN; - RCC->APB1ENR |= RCC_APB1ENR_CAN3EN; - - // Analog - RCC->APB2ENR |= RCC_APB2ENR_ADC1EN; - RCC->APB1ENR |= RCC_APB1ENR_DACEN; - - // Timers - RCC->APB2ENR |= RCC_APB2ENR_TIM1EN; // clock source timer - RCC->APB1ENR |= RCC_APB1ENR_TIM2EN; // main counter - RCC->APB1ENR |= RCC_APB1ENR_TIM3EN; // pedal and fan PWM - RCC->APB1ENR |= RCC_APB1ENR_TIM4EN; // IR PWM - RCC->APB1ENR |= RCC_APB1ENR_TIM5EN; // k-line init - RCC->APB1ENR |= RCC_APB1ENR_TIM6EN; // interrupt timer - RCC->APB2ENR |= RCC_APB2ENR_TIM9EN; // slow loop - RCC->APB1ENR |= RCC_APB1ENR_TIM12EN; // gmlan_alt -} - -void enable_interrupt_timer(void) { - register_set_bits(&(RCC->APB1ENR), RCC_APB1ENR_TIM6EN); // Enable interrupt timer peripheral -} diff --git a/panda/board/stm32fx/stm32fx_config.h b/panda/board/stm32fx/stm32fx_config.h deleted file mode 100644 index 8b59da2..0000000 --- a/panda/board/stm32fx/stm32fx_config.h +++ /dev/null @@ -1,86 +0,0 @@ -#include "stm32fx/inc/stm32f4xx.h" -#include "stm32fx/inc/stm32f4xx_hal_gpio_ex.h" -#define MCU_IDCODE 0x463U - -// from the linker script -#define APP_START_ADDRESS 0x8004000U - -#define CORE_FREQ 96U // in MHz -#define APB1_FREQ (CORE_FREQ/2U) -#define APB1_TIMER_FREQ (APB1_FREQ*2U) // APB1 is multiplied by 2 for the timer peripherals -#define APB2_FREQ (CORE_FREQ/2U) -#define APB2_TIMER_FREQ (APB2_FREQ*2U) // APB2 is multiplied by 2 for the timer peripherals - -#define BOOTLOADER_ADDRESS 0x1FFF0004U - -// Around (1Mbps / 8 bits/byte / 12 bytes per message) -#define CAN_INTERRUPT_RATE 12000U - -#define MAX_LED_FADE 8192U - -#define NUM_INTERRUPTS 102U // There are 102 external interrupt sources (see stm32f413.h) - -#define TICK_TIMER_IRQ TIM1_BRK_TIM9_IRQn -#define TICK_TIMER TIM9 - -#define MICROSECOND_TIMER TIM2 - -#define INTERRUPT_TIMER_IRQ TIM6_DAC_IRQn -#define INTERRUPT_TIMER TIM6 - -#define IND_WDG IWDG - -#define PROVISION_CHUNK_ADDRESS 0x1FFF79E0U -#define DEVICE_SERIAL_NUMBER_ADDRESS 0x1FFF79C0U - -#include "can_definitions.h" -#include "comms_definitions.h" - -#ifndef BOOTSTUB - #include "main_declarations.h" -#else - #include "bootstub_declarations.h" -#endif - -#include "libc.h" -#include "critical.h" -#include "faults.h" -#include "utils.h" - -#include "drivers/registers.h" -#include "drivers/interrupts.h" -#include "drivers/gpio.h" -#include "stm32fx/peripherals.h" -#include "stm32fx/interrupt_handlers.h" -#include "drivers/timers.h" -#include "stm32fx/board.h" -#include "stm32fx/clock.h" -#include "drivers/watchdog.h" - -#include "drivers/spi.h" -#include "stm32fx/llspi.h" - -#if !defined(BOOTSTUB) - #include "drivers/uart.h" - #include "stm32fx/lluart.h" -#endif - -#if defined(PANDA) && !defined(BOOTSTUB) - #include "stm32fx/llexti.h" -#endif - -#ifdef BOOTSTUB - #include "stm32fx/llflash.h" -#else - #include "stm32fx/llbxcan.h" -#endif - -#include "stm32fx/llusb.h" - -void early_gpio_float(void) { - RCC->AHB1ENR = RCC_AHB1ENR_GPIOAEN | RCC_AHB1ENR_GPIOBEN | RCC_AHB1ENR_GPIOCEN; - - GPIOA->MODER = 0; GPIOB->MODER = 0; GPIOC->MODER = 0; - GPIOA->ODR = 0; GPIOB->ODR = 0; GPIOC->ODR = 0; - GPIOA->PUPDR = 0; GPIOB->PUPDR = 0; GPIOC->PUPDR = 0; -} diff --git a/panda/board/stm32h7/board.h b/panda/board/stm32h7/board.h deleted file mode 100644 index d293a54..0000000 --- a/panda/board/stm32h7/board.h +++ /dev/null @@ -1,55 +0,0 @@ -// ///////////////////////////////////////////////////////////// // -// Hardware abstraction layer for all different supported boards // -// ///////////////////////////////////////////////////////////// // -#include "boards/board_declarations.h" -#include "boards/unused_funcs.h" - -// ///// Board definition and detection ///// // -#include "stm32h7/lladc.h" -#include "drivers/harness.h" -#include "drivers/fan.h" -#include "stm32h7/llfan.h" -#include "stm32h7/llrtc.h" -#include "stm32h7/lldac.h" -#include "drivers/fake_siren.h" -#include "drivers/rtc.h" -#include "drivers/clock_source.h" -#include "boards/red.h" -#include "boards/red_chiplet.h" -#include "boards/tres.h" -#include "boards/cuatro.h" - - -uint8_t get_board_id(void) { - return detect_with_pull(GPIOF, 7, PULL_UP) | - (detect_with_pull(GPIOF, 8, PULL_UP) << 1U) | - (detect_with_pull(GPIOF, 9, PULL_UP) << 2U) | - (detect_with_pull(GPIOF, 10, PULL_UP) << 3U); -} - -void detect_board_type(void) { - const uint8_t board_id = get_board_id(); - - if (board_id == 0U) { - hw_type = HW_TYPE_RED_PANDA; - current_board = &board_red; - } else if (board_id == 1U) { - // deprecated - //hw_type = HW_TYPE_RED_PANDA_V2; - } else if (board_id == 2U) { - hw_type = HW_TYPE_TRES; - current_board = &board_tres; - } else if (board_id == 3U) { - hw_type = HW_TYPE_CUATRO; - current_board = &board_tres; - } else { - hw_type = HW_TYPE_UNKNOWN; - print("Hardware type is UNKNOWN!\n"); - } - - // TODO: detect this live -#ifdef STM32H723 - hw_type = HW_TYPE_CUATRO; - current_board = &board_cuatro; -#endif -} diff --git a/panda/board/stm32h7/clock.h b/panda/board/stm32h7/clock.h deleted file mode 100644 index 7d65d08..0000000 --- a/panda/board/stm32h7/clock.h +++ /dev/null @@ -1,74 +0,0 @@ -/* -HSE: 25MHz -PLL1Q: 80MHz (for FDCAN) -HSI48 enabled (for USB) -CPU: 240MHz -CPU Systick: 240MHz -AXI: 120MHz -HCLK3: 60MHz -APB3 per: 60MHz -AHB1,2 per: 120MHz -APB1 per: 60MHz -APB1 tim: 120MHz -APB2 per: 60MHz -APB2 tim: 120MHz -AHB4 per: 120MHz -APB4 per: 60MHz -PCLK1: 60MHz (for USART2,3,4,5,7,8) -*/ - -void clock_init(void) { - // Set power mode to direct SMPS power supply(depends on the board layout) -#ifndef STM32H723 - register_set(&(PWR->CR3), PWR_CR3_SMPSEN, 0xFU); // powered only by SMPS -#endif - // Set VOS level (VOS3 to 170Mhz, VOS2 to 300Mhz, VOS1 to 400Mhz, VOS0 to 550Mhz) - register_set(&(PWR->D3CR), PWR_D3CR_VOS_1 | PWR_D3CR_VOS_0, 0xC000U); //VOS1, needed for 80Mhz CAN FD - while ((PWR->CSR1 & PWR_CSR1_ACTVOSRDY) == 0); - while ((PWR->CSR1 & PWR_CSR1_ACTVOS) != (PWR->D3CR & PWR_D3CR_VOS)); // check that VOS level was actually set - - // Configure Flash ACR register LATENCY and WRHIGHFREQ (VOS0 range!) - register_set(&(FLASH->ACR), FLASH_ACR_LATENCY_2WS | 0x20U, 0x3FU); // VOS2, AXI 100MHz-150MHz - // enable external oscillator HSE - register_set_bits(&(RCC->CR), RCC_CR_HSEON); - while ((RCC->CR & RCC_CR_HSERDY) == 0); - // enable internal HSI48 for USB FS kernel - register_set_bits(&(RCC->CR), RCC_CR_HSI48ON); - while ((RCC->CR & RCC_CR_HSI48RDY) == 0); - // Specify the frequency source for PLL1, divider for DIVM1, DIVM2, DIVM3 : HSE, 5, 5, 5 - register_set(&(RCC->PLLCKSELR), RCC_PLLCKSELR_PLLSRC_HSE | RCC_PLLCKSELR_DIVM1_0 | RCC_PLLCKSELR_DIVM1_2 | RCC_PLLCKSELR_DIVM2_0 | RCC_PLLCKSELR_DIVM2_2 | RCC_PLLCKSELR_DIVM3_0 | RCC_PLLCKSELR_DIVM3_2, 0x3F3F3F3U); - - // *** PLL1 start *** - // Specify multiplier N and dividers P, Q, R for PLL1 : 48, 1, 3, 2 (clock 240Mhz, PLL1Q 80Mhz for CAN FD) - register_set(&(RCC->PLL1DIVR), 0x102002FU, 0x7F7FFFFFU); - // Specify the input and output frequency ranges, enable dividers for PLL1 - register_set(&(RCC->PLLCFGR), RCC_PLLCFGR_PLL1RGE_2 | RCC_PLLCFGR_DIVP1EN | RCC_PLLCFGR_DIVQ1EN | RCC_PLLCFGR_DIVR1EN, 0x7000CU); - // Enable PLL1 - register_set_bits(&(RCC->CR), RCC_CR_PLL1ON); - while((RCC->CR & RCC_CR_PLL1RDY) == 0); - // *** PLL1 end *** - - //////////////OTHER CLOCKS//////////////////// - // RCC HCLK Clock Source / RCC APB3 Clock Source / RCC SYS Clock Source - register_set(&(RCC->D1CFGR), RCC_D1CFGR_HPRE_DIV2 | RCC_D1CFGR_D1PPRE_DIV2 | RCC_D1CFGR_D1CPRE_DIV1, 0xF7FU); - // RCC APB1 Clock Source / RCC APB2 Clock Source - register_set(&(RCC->D2CFGR), RCC_D2CFGR_D2PPRE1_DIV2 | RCC_D2CFGR_D2PPRE2_DIV2, 0x770U); - // RCC APB4 Clock Source - register_set(&(RCC->D3CFGR), RCC_D3CFGR_D3PPRE_DIV2, 0x70U); - - // Set SysClock source to PLL - register_set(&(RCC->CFGR), RCC_CFGR_SW_PLL1, 0x7U); - while((RCC->CFGR & RCC_CFGR_SWS) != RCC_CFGR_SWS_PLL1); - //////////////END OTHER CLOCKS//////////////////// - - // Configure clock source for USB (HSI48) - register_set(&(RCC->D2CCIP2R), RCC_D2CCIP2R_USBSEL_1 | RCC_D2CCIP2R_USBSEL_0, RCC_D2CCIP2R_USBSEL); - // Configure clock source for FDCAN (PLL1Q at 80Mhz) - register_set(&(RCC->D2CCIP1R), RCC_D2CCIP1R_FDCANSEL_0, RCC_D2CCIP1R_FDCANSEL); - // Configure clock source for ADC1,2,3 (per_ck(currently HSE)) - register_set(&(RCC->D3CCIPR), RCC_D3CCIPR_ADCSEL_1, RCC_D3CCIPR_ADCSEL); - //Enable the Clock Security System - register_set_bits(&(RCC->CR), RCC_CR_CSSHSEON); - //Enable Vdd33usb supply level detector - register_set_bits(&(PWR->CR3), PWR_CR3_USB33DEN); -} diff --git a/panda/board/stm32h7/inc/cmsis_compiler.h b/panda/board/stm32h7/inc/cmsis_compiler.h deleted file mode 100644 index d0f39ee..0000000 --- a/panda/board/stm32h7/inc/cmsis_compiler.h +++ /dev/null @@ -1,284 +0,0 @@ -/**************************************************************************//** - * @file cmsis_compiler.h - * @brief CMSIS compiler generic header file - * @version V5.1.0 - * @date 09. October 2018 - ******************************************************************************/ -/* - * Copyright (c) 2009-2018 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#ifndef __CMSIS_COMPILER_H -#define __CMSIS_COMPILER_H - -#include - -/* - * Arm Compiler 4/5 - */ -#if defined ( __CC_ARM ) - #include "cmsis_armcc.h" - - -/* - * Arm Compiler 6.6 LTM (armclang) - */ -#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) && (__ARMCC_VERSION < 6100100) - #include "cmsis_armclang_ltm.h" - - /* - * Arm Compiler above 6.10.1 (armclang) - */ -#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6100100) - #include "cmsis_armclang.h" - - -/* - * GNU Compiler - */ -#elif defined ( __GNUC__ ) - #include "cmsis_gcc.h" - - -/* - * IAR Compiler - */ -#elif defined ( __ICCARM__ ) - #include - - -/* - * TI Arm Compiler - */ -#elif defined ( __TI_ARM__ ) - #include - - #ifndef __ASM - #define __ASM __asm - #endif - #ifndef __INLINE - #define __INLINE inline - #endif - #ifndef __STATIC_INLINE - #define __STATIC_INLINE static inline - #endif - #ifndef __STATIC_FORCEINLINE - #define __STATIC_FORCEINLINE __STATIC_INLINE - #endif - #ifndef __NO_RETURN - #define __NO_RETURN __attribute__((noreturn)) - #endif - #ifndef __USED - #define __USED __attribute__((used)) - #endif - #ifndef __WEAK - #define __WEAK __attribute__((weak)) - #endif - #ifndef __PACKED - #define __PACKED __attribute__((packed)) - #endif - #ifndef __PACKED_STRUCT - #define __PACKED_STRUCT struct __attribute__((packed)) - #endif - #ifndef __PACKED_UNION - #define __PACKED_UNION union __attribute__((packed)) - #endif - #ifndef __UNALIGNED_UINT32 /* deprecated */ - struct __attribute__((packed)) T_UINT32 { uint32_t v; }; - #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) - #endif - #ifndef __UNALIGNED_UINT16_WRITE - __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; - #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void*)(addr))->v) = (val)) - #endif - #ifndef __UNALIGNED_UINT16_READ - __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; - #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) - #endif - #ifndef __UNALIGNED_UINT32_WRITE - __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; - #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) - #endif - #ifndef __UNALIGNED_UINT32_READ - __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; - #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) - #endif - #ifndef __ALIGNED - #define __ALIGNED(x) __attribute__((aligned(x))) - #endif - #ifndef __RESTRICT - #define __RESTRICT __restrict - #endif - #ifndef __COMPILER_BARRIER - #warning No compiler specific solution for __COMPILER_BARRIER. __COMPILER_BARRIER is ignored. - #define __COMPILER_BARRIER() (void)0 - #endif - - -/* - * TASKING Compiler - */ -#elif defined ( __TASKING__ ) - /* - * The CMSIS functions have been implemented as intrinsics in the compiler. - * Please use "carm -?i" to get an up to date list of all intrinsics, - * Including the CMSIS ones. - */ - - #ifndef __ASM - #define __ASM __asm - #endif - #ifndef __INLINE - #define __INLINE inline - #endif - #ifndef __STATIC_INLINE - #define __STATIC_INLINE static inline - #endif - #ifndef __STATIC_FORCEINLINE - #define __STATIC_FORCEINLINE __STATIC_INLINE - #endif - #ifndef __NO_RETURN - #define __NO_RETURN __attribute__((noreturn)) - #endif - #ifndef __USED - #define __USED __attribute__((used)) - #endif - #ifndef __WEAK - #define __WEAK __attribute__((weak)) - #endif - #ifndef __PACKED - #define __PACKED __packed__ - #endif - #ifndef __PACKED_STRUCT - #define __PACKED_STRUCT struct __packed__ - #endif - #ifndef __PACKED_UNION - #define __PACKED_UNION union __packed__ - #endif - #ifndef __UNALIGNED_UINT32 /* deprecated */ - struct __packed__ T_UINT32 { uint32_t v; }; - #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) - #endif - #ifndef __UNALIGNED_UINT16_WRITE - __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; - #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val)) - #endif - #ifndef __UNALIGNED_UINT16_READ - __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; - #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) - #endif - #ifndef __UNALIGNED_UINT32_WRITE - __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; - #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) - #endif - #ifndef __UNALIGNED_UINT32_READ - __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; - #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) - #endif - #ifndef __ALIGNED - #define __ALIGNED(x) __align(x) - #endif - #ifndef __RESTRICT - #warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored. - #define __RESTRICT - #endif - #ifndef __COMPILER_BARRIER - #warning No compiler specific solution for __COMPILER_BARRIER. __COMPILER_BARRIER is ignored. - #define __COMPILER_BARRIER() (void)0 - #endif - - -/* - * COSMIC Compiler - */ -#elif defined ( __CSMC__ ) - #include - - #ifndef __ASM - #define __ASM _asm - #endif - #ifndef __INLINE - #define __INLINE inline - #endif - #ifndef __STATIC_INLINE - #define __STATIC_INLINE static inline - #endif - #ifndef __STATIC_FORCEINLINE - #define __STATIC_FORCEINLINE __STATIC_INLINE - #endif - #ifndef __NO_RETURN - // NO RETURN is automatically detected hence no warning here - #define __NO_RETURN - #endif - #ifndef __USED - #warning No compiler specific solution for __USED. __USED is ignored. - #define __USED - #endif - #ifndef __WEAK - #define __WEAK __weak - #endif - #ifndef __PACKED - #define __PACKED @packed - #endif - #ifndef __PACKED_STRUCT - #define __PACKED_STRUCT @packed struct - #endif - #ifndef __PACKED_UNION - #define __PACKED_UNION @packed union - #endif - #ifndef __UNALIGNED_UINT32 /* deprecated */ - @packed struct T_UINT32 { uint32_t v; }; - #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) - #endif - #ifndef __UNALIGNED_UINT16_WRITE - __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; - #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val)) - #endif - #ifndef __UNALIGNED_UINT16_READ - __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; - #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) - #endif - #ifndef __UNALIGNED_UINT32_WRITE - __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; - #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) - #endif - #ifndef __UNALIGNED_UINT32_READ - __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; - #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) - #endif - #ifndef __ALIGNED - #warning No compiler specific solution for __ALIGNED. __ALIGNED is ignored. - #define __ALIGNED(x) - #endif - #ifndef __RESTRICT - #warning No compiler specific solution for __RESTRICT. __RESTRICT is ignored. - #define __RESTRICT - #endif - #ifndef __COMPILER_BARRIER - #warning No compiler specific solution for __COMPILER_BARRIER. __COMPILER_BARRIER is ignored. - #define __COMPILER_BARRIER() (void)0 - #endif - - -#else - #error Unknown compiler. -#endif - - -#endif /* __CMSIS_COMPILER_H */ - - diff --git a/panda/board/stm32h7/inc/cmsis_gcc.h b/panda/board/stm32h7/inc/cmsis_gcc.h deleted file mode 100644 index 2f68473..0000000 --- a/panda/board/stm32h7/inc/cmsis_gcc.h +++ /dev/null @@ -1,2169 +0,0 @@ -/**************************************************************************//** - * @file cmsis_gcc.h - * @brief CMSIS compiler GCC header file - * @version V5.2.0 - * @date 08. May 2019 - ******************************************************************************/ -/* - * Copyright (c) 2009-2019 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#ifndef __CMSIS_GCC_H -#define __CMSIS_GCC_H - -/* ignore some GCC warnings */ -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wsign-conversion" -#pragma GCC diagnostic ignored "-Wconversion" -#pragma GCC diagnostic ignored "-Wunused-parameter" - -/* Fallback for __has_builtin */ -#ifndef __has_builtin - #define __has_builtin(x) (0) -#endif - -/* CMSIS compiler specific defines */ -#ifndef __ASM - #define __ASM __asm -#endif -#ifndef __INLINE - #define __INLINE inline -#endif -#ifndef __STATIC_INLINE - #define __STATIC_INLINE static inline -#endif -#ifndef __STATIC_FORCEINLINE - #define __STATIC_FORCEINLINE __attribute__((always_inline)) static inline -#endif -#ifndef __NO_RETURN - #define __NO_RETURN __attribute__((__noreturn__)) -#endif -#ifndef __USED - #define __USED __attribute__((used)) -#endif -#ifndef __WEAK - #define __WEAK __attribute__((weak)) -#endif -#ifndef __PACKED - #define __PACKED __attribute__((packed, aligned(1))) -#endif -#ifndef __PACKED_STRUCT - #define __PACKED_STRUCT struct __attribute__((packed, aligned(1))) -#endif -#ifndef __PACKED_UNION - #define __PACKED_UNION union __attribute__((packed, aligned(1))) -#endif -#ifndef __UNALIGNED_UINT32 /* deprecated */ - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wpacked" - #pragma GCC diagnostic ignored "-Wattributes" - struct __attribute__((packed)) T_UINT32 { uint32_t v; }; - #pragma GCC diagnostic pop - #define __UNALIGNED_UINT32(x) (((struct T_UINT32 *)(x))->v) -#endif -#ifndef __UNALIGNED_UINT16_WRITE - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wpacked" - #pragma GCC diagnostic ignored "-Wattributes" - __PACKED_STRUCT T_UINT16_WRITE { uint16_t v; }; - #pragma GCC diagnostic pop - #define __UNALIGNED_UINT16_WRITE(addr, val) (void)((((struct T_UINT16_WRITE *)(void *)(addr))->v) = (val)) -#endif -#ifndef __UNALIGNED_UINT16_READ - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wpacked" - #pragma GCC diagnostic ignored "-Wattributes" - __PACKED_STRUCT T_UINT16_READ { uint16_t v; }; - #pragma GCC diagnostic pop - #define __UNALIGNED_UINT16_READ(addr) (((const struct T_UINT16_READ *)(const void *)(addr))->v) -#endif -#ifndef __UNALIGNED_UINT32_WRITE - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wpacked" - #pragma GCC diagnostic ignored "-Wattributes" - __PACKED_STRUCT T_UINT32_WRITE { uint32_t v; }; - #pragma GCC diagnostic pop - #define __UNALIGNED_UINT32_WRITE(addr, val) (void)((((struct T_UINT32_WRITE *)(void *)(addr))->v) = (val)) -#endif -#ifndef __UNALIGNED_UINT32_READ - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wpacked" - #pragma GCC diagnostic ignored "-Wattributes" - __PACKED_STRUCT T_UINT32_READ { uint32_t v; }; - #pragma GCC diagnostic pop - #define __UNALIGNED_UINT32_READ(addr) (((const struct T_UINT32_READ *)(const void *)(addr))->v) -#endif -#ifndef __ALIGNED - #define __ALIGNED(x) __attribute__((aligned(x))) -#endif -#ifndef __RESTRICT - #define __RESTRICT __restrict -#endif -#ifndef __COMPILER_BARRIER - #define __COMPILER_BARRIER() __ASM volatile("":::"memory") -#endif - -/* ######################### Startup and Lowlevel Init ######################## */ - -#ifndef __PROGRAM_START - -/** - \brief Initializes data and bss sections - \details This default implementations initialized all data and additional bss - sections relying on .copy.table and .zero.table specified properly - in the used linker script. - - */ -__STATIC_FORCEINLINE __NO_RETURN void __cmsis_start(void) -{ - extern void _start(void) __NO_RETURN; - - typedef struct { - uint32_t const* src; - uint32_t* dest; - uint32_t wlen; - } __copy_table_t; - - typedef struct { - uint32_t* dest; - uint32_t wlen; - } __zero_table_t; - - extern const __copy_table_t __copy_table_start__; - extern const __copy_table_t __copy_table_end__; - extern const __zero_table_t __zero_table_start__; - extern const __zero_table_t __zero_table_end__; - - for (__copy_table_t const* pTable = &__copy_table_start__; pTable < &__copy_table_end__; ++pTable) { - for(uint32_t i=0u; iwlen; ++i) { - pTable->dest[i] = pTable->src[i]; - } - } - - for (__zero_table_t const* pTable = &__zero_table_start__; pTable < &__zero_table_end__; ++pTable) { - for(uint32_t i=0u; iwlen; ++i) { - pTable->dest[i] = 0u; - } - } - - _start(); -} - -#define __PROGRAM_START __cmsis_start -#endif - -#ifndef __INITIAL_SP -#define __INITIAL_SP __StackTop -#endif - -#ifndef __STACK_LIMIT -#define __STACK_LIMIT __StackLimit -#endif - -#ifndef __VECTOR_TABLE -#define __VECTOR_TABLE __Vectors -#endif - -#ifndef __VECTOR_TABLE_ATTRIBUTE -#define __VECTOR_TABLE_ATTRIBUTE __attribute((used, section(".vectors"))) -#endif - -/* ########################### Core Function Access ########################### */ -/** \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions - @{ - */ - -/** - \brief Enable IRQ Interrupts - \details Enables IRQ interrupts by clearing the I-bit in the CPSR. - Can only be executed in Privileged modes. - */ -__STATIC_FORCEINLINE void __enable_irq(void) -{ - __ASM volatile ("cpsie i" : : : "memory"); -} - - -/** - \brief Disable IRQ Interrupts - \details Disables IRQ interrupts by setting the I-bit in the CPSR. - Can only be executed in Privileged modes. - */ -__STATIC_FORCEINLINE void __disable_irq(void) -{ - __ASM volatile ("cpsid i" : : : "memory"); -} - - -/** - \brief Get Control Register - \details Returns the content of the Control Register. - \return Control Register value - */ -__STATIC_FORCEINLINE uint32_t __get_CONTROL(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, control" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Control Register (non-secure) - \details Returns the content of the non-secure Control Register when in secure mode. - \return non-secure Control Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_CONTROL_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, control_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Control Register - \details Writes the given value to the Control Register. - \param [in] control Control Register value to set - */ -__STATIC_FORCEINLINE void __set_CONTROL(uint32_t control) -{ - __ASM volatile ("MSR control, %0" : : "r" (control) : "memory"); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Control Register (non-secure) - \details Writes the given value to the non-secure Control Register when in secure state. - \param [in] control Control Register value to set - */ -__STATIC_FORCEINLINE void __TZ_set_CONTROL_NS(uint32_t control) -{ - __ASM volatile ("MSR control_ns, %0" : : "r" (control) : "memory"); -} -#endif - - -/** - \brief Get IPSR Register - \details Returns the content of the IPSR Register. - \return IPSR Register value - */ -__STATIC_FORCEINLINE uint32_t __get_IPSR(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, ipsr" : "=r" (result) ); - return(result); -} - - -/** - \brief Get APSR Register - \details Returns the content of the APSR Register. - \return APSR Register value - */ -__STATIC_FORCEINLINE uint32_t __get_APSR(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, apsr" : "=r" (result) ); - return(result); -} - - -/** - \brief Get xPSR Register - \details Returns the content of the xPSR Register. - \return xPSR Register value - */ -__STATIC_FORCEINLINE uint32_t __get_xPSR(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, xpsr" : "=r" (result) ); - return(result); -} - - -/** - \brief Get Process Stack Pointer - \details Returns the current value of the Process Stack Pointer (PSP). - \return PSP Register value - */ -__STATIC_FORCEINLINE uint32_t __get_PSP(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, psp" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Process Stack Pointer (non-secure) - \details Returns the current value of the non-secure Process Stack Pointer (PSP) when in secure state. - \return PSP Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_PSP_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, psp_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Process Stack Pointer - \details Assigns the given value to the Process Stack Pointer (PSP). - \param [in] topOfProcStack Process Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __set_PSP(uint32_t topOfProcStack) -{ - __ASM volatile ("MSR psp, %0" : : "r" (topOfProcStack) : ); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Process Stack Pointer (non-secure) - \details Assigns the given value to the non-secure Process Stack Pointer (PSP) when in secure state. - \param [in] topOfProcStack Process Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __TZ_set_PSP_NS(uint32_t topOfProcStack) -{ - __ASM volatile ("MSR psp_ns, %0" : : "r" (topOfProcStack) : ); -} -#endif - - -/** - \brief Get Main Stack Pointer - \details Returns the current value of the Main Stack Pointer (MSP). - \return MSP Register value - */ -__STATIC_FORCEINLINE uint32_t __get_MSP(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, msp" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Main Stack Pointer (non-secure) - \details Returns the current value of the non-secure Main Stack Pointer (MSP) when in secure state. - \return MSP Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_MSP_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, msp_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Main Stack Pointer - \details Assigns the given value to the Main Stack Pointer (MSP). - \param [in] topOfMainStack Main Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __set_MSP(uint32_t topOfMainStack) -{ - __ASM volatile ("MSR msp, %0" : : "r" (topOfMainStack) : ); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Main Stack Pointer (non-secure) - \details Assigns the given value to the non-secure Main Stack Pointer (MSP) when in secure state. - \param [in] topOfMainStack Main Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __TZ_set_MSP_NS(uint32_t topOfMainStack) -{ - __ASM volatile ("MSR msp_ns, %0" : : "r" (topOfMainStack) : ); -} -#endif - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Stack Pointer (non-secure) - \details Returns the current value of the non-secure Stack Pointer (SP) when in secure state. - \return SP Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_SP_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, sp_ns" : "=r" (result) ); - return(result); -} - - -/** - \brief Set Stack Pointer (non-secure) - \details Assigns the given value to the non-secure Stack Pointer (SP) when in secure state. - \param [in] topOfStack Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __TZ_set_SP_NS(uint32_t topOfStack) -{ - __ASM volatile ("MSR sp_ns, %0" : : "r" (topOfStack) : ); -} -#endif - - -/** - \brief Get Priority Mask - \details Returns the current state of the priority mask bit from the Priority Mask Register. - \return Priority Mask value - */ -__STATIC_FORCEINLINE uint32_t __get_PRIMASK(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, primask" : "=r" (result) :: "memory"); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Priority Mask (non-secure) - \details Returns the current state of the non-secure priority mask bit from the Priority Mask Register when in secure state. - \return Priority Mask value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_PRIMASK_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, primask_ns" : "=r" (result) :: "memory"); - return(result); -} -#endif - - -/** - \brief Set Priority Mask - \details Assigns the given value to the Priority Mask Register. - \param [in] priMask Priority Mask - */ -__STATIC_FORCEINLINE void __set_PRIMASK(uint32_t priMask) -{ - __ASM volatile ("MSR primask, %0" : : "r" (priMask) : "memory"); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Priority Mask (non-secure) - \details Assigns the given value to the non-secure Priority Mask Register when in secure state. - \param [in] priMask Priority Mask - */ -__STATIC_FORCEINLINE void __TZ_set_PRIMASK_NS(uint32_t priMask) -{ - __ASM volatile ("MSR primask_ns, %0" : : "r" (priMask) : "memory"); -} -#endif - - -#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) -/** - \brief Enable FIQ - \details Enables FIQ interrupts by clearing the F-bit in the CPSR. - Can only be executed in Privileged modes. - */ -__STATIC_FORCEINLINE void __enable_fault_irq(void) -{ - __ASM volatile ("cpsie f" : : : "memory"); -} - - -/** - \brief Disable FIQ - \details Disables FIQ interrupts by setting the F-bit in the CPSR. - Can only be executed in Privileged modes. - */ -__STATIC_FORCEINLINE void __disable_fault_irq(void) -{ - __ASM volatile ("cpsid f" : : : "memory"); -} - - -/** - \brief Get Base Priority - \details Returns the current value of the Base Priority register. - \return Base Priority register value - */ -__STATIC_FORCEINLINE uint32_t __get_BASEPRI(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, basepri" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Base Priority (non-secure) - \details Returns the current value of the non-secure Base Priority register when in secure state. - \return Base Priority register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_BASEPRI_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, basepri_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Base Priority - \details Assigns the given value to the Base Priority register. - \param [in] basePri Base Priority value to set - */ -__STATIC_FORCEINLINE void __set_BASEPRI(uint32_t basePri) -{ - __ASM volatile ("MSR basepri, %0" : : "r" (basePri) : "memory"); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Base Priority (non-secure) - \details Assigns the given value to the non-secure Base Priority register when in secure state. - \param [in] basePri Base Priority value to set - */ -__STATIC_FORCEINLINE void __TZ_set_BASEPRI_NS(uint32_t basePri) -{ - __ASM volatile ("MSR basepri_ns, %0" : : "r" (basePri) : "memory"); -} -#endif - - -/** - \brief Set Base Priority with condition - \details Assigns the given value to the Base Priority register only if BASEPRI masking is disabled, - or the new value increases the BASEPRI priority level. - \param [in] basePri Base Priority value to set - */ -__STATIC_FORCEINLINE void __set_BASEPRI_MAX(uint32_t basePri) -{ - __ASM volatile ("MSR basepri_max, %0" : : "r" (basePri) : "memory"); -} - - -/** - \brief Get Fault Mask - \details Returns the current value of the Fault Mask register. - \return Fault Mask register value - */ -__STATIC_FORCEINLINE uint32_t __get_FAULTMASK(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, faultmask" : "=r" (result) ); - return(result); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Fault Mask (non-secure) - \details Returns the current value of the non-secure Fault Mask register when in secure state. - \return Fault Mask register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_FAULTMASK_NS(void) -{ - uint32_t result; - - __ASM volatile ("MRS %0, faultmask_ns" : "=r" (result) ); - return(result); -} -#endif - - -/** - \brief Set Fault Mask - \details Assigns the given value to the Fault Mask register. - \param [in] faultMask Fault Mask value to set - */ -__STATIC_FORCEINLINE void __set_FAULTMASK(uint32_t faultMask) -{ - __ASM volatile ("MSR faultmask, %0" : : "r" (faultMask) : "memory"); -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Fault Mask (non-secure) - \details Assigns the given value to the non-secure Fault Mask register when in secure state. - \param [in] faultMask Fault Mask value to set - */ -__STATIC_FORCEINLINE void __TZ_set_FAULTMASK_NS(uint32_t faultMask) -{ - __ASM volatile ("MSR faultmask_ns, %0" : : "r" (faultMask) : "memory"); -} -#endif - -#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ - - -#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) - -/** - \brief Get Process Stack Pointer Limit - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence zero is returned always in non-secure - mode. - - \details Returns the current value of the Process Stack Pointer Limit (PSPLIM). - \return PSPLIM Register value - */ -__STATIC_FORCEINLINE uint32_t __get_PSPLIM(void) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - return 0U; -#else - uint32_t result; - __ASM volatile ("MRS %0, psplim" : "=r" (result) ); - return result; -#endif -} - -#if (defined (__ARM_FEATURE_CMSE) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Process Stack Pointer Limit (non-secure) - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence zero is returned always. - - \details Returns the current value of the non-secure Process Stack Pointer Limit (PSPLIM) when in secure state. - \return PSPLIM Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_PSPLIM_NS(void) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - return 0U; -#else - uint32_t result; - __ASM volatile ("MRS %0, psplim_ns" : "=r" (result) ); - return result; -#endif -} -#endif - - -/** - \brief Set Process Stack Pointer Limit - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence the write is silently ignored in non-secure - mode. - - \details Assigns the given value to the Process Stack Pointer Limit (PSPLIM). - \param [in] ProcStackPtrLimit Process Stack Pointer Limit value to set - */ -__STATIC_FORCEINLINE void __set_PSPLIM(uint32_t ProcStackPtrLimit) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - (void)ProcStackPtrLimit; -#else - __ASM volatile ("MSR psplim, %0" : : "r" (ProcStackPtrLimit)); -#endif -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Process Stack Pointer (non-secure) - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence the write is silently ignored. - - \details Assigns the given value to the non-secure Process Stack Pointer Limit (PSPLIM) when in secure state. - \param [in] ProcStackPtrLimit Process Stack Pointer Limit value to set - */ -__STATIC_FORCEINLINE void __TZ_set_PSPLIM_NS(uint32_t ProcStackPtrLimit) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) - // without main extensions, the non-secure PSPLIM is RAZ/WI - (void)ProcStackPtrLimit; -#else - __ASM volatile ("MSR psplim_ns, %0\n" : : "r" (ProcStackPtrLimit)); -#endif -} -#endif - - -/** - \brief Get Main Stack Pointer Limit - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence zero is returned always in non-secure - mode. - - \details Returns the current value of the Main Stack Pointer Limit (MSPLIM). - \return MSPLIM Register value - */ -__STATIC_FORCEINLINE uint32_t __get_MSPLIM(void) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - return 0U; -#else - uint32_t result; - __ASM volatile ("MRS %0, msplim" : "=r" (result) ); - return result; -#endif -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Get Main Stack Pointer Limit (non-secure) - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence zero is returned always. - - \details Returns the current value of the non-secure Main Stack Pointer Limit(MSPLIM) when in secure state. - \return MSPLIM Register value - */ -__STATIC_FORCEINLINE uint32_t __TZ_get_MSPLIM_NS(void) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - return 0U; -#else - uint32_t result; - __ASM volatile ("MRS %0, msplim_ns" : "=r" (result) ); - return result; -#endif -} -#endif - - -/** - \brief Set Main Stack Pointer Limit - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence the write is silently ignored in non-secure - mode. - - \details Assigns the given value to the Main Stack Pointer Limit (MSPLIM). - \param [in] MainStackPtrLimit Main Stack Pointer Limit value to set - */ -__STATIC_FORCEINLINE void __set_MSPLIM(uint32_t MainStackPtrLimit) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) && \ - (!defined (__ARM_FEATURE_CMSE) || (__ARM_FEATURE_CMSE < 3))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - (void)MainStackPtrLimit; -#else - __ASM volatile ("MSR msplim, %0" : : "r" (MainStackPtrLimit)); -#endif -} - - -#if (defined (__ARM_FEATURE_CMSE ) && (__ARM_FEATURE_CMSE == 3)) -/** - \brief Set Main Stack Pointer Limit (non-secure) - Devices without ARMv8-M Main Extensions (i.e. Cortex-M23) lack the non-secure - Stack Pointer Limit register hence the write is silently ignored. - - \details Assigns the given value to the non-secure Main Stack Pointer Limit (MSPLIM) when in secure state. - \param [in] MainStackPtrLimit Main Stack Pointer value to set - */ -__STATIC_FORCEINLINE void __TZ_set_MSPLIM_NS(uint32_t MainStackPtrLimit) -{ -#if (!(defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1))) - // without main extensions, the non-secure MSPLIM is RAZ/WI - (void)MainStackPtrLimit; -#else - __ASM volatile ("MSR msplim_ns, %0" : : "r" (MainStackPtrLimit)); -#endif -} -#endif - -#endif /* ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ - - -/** - \brief Get FPSCR - \details Returns the current value of the Floating Point Status/Control register. - \return Floating Point Status/Control register value - */ -__STATIC_FORCEINLINE uint32_t __get_FPSCR(void) -{ -#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ - (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) -#if __has_builtin(__builtin_arm_get_fpscr) -// Re-enable using built-in when GCC has been fixed -// || (__GNUC__ > 7) || (__GNUC__ == 7 && __GNUC_MINOR__ >= 2) - /* see https://gcc.gnu.org/ml/gcc-patches/2017-04/msg00443.html */ - return __builtin_arm_get_fpscr(); -#else - uint32_t result; - - __ASM volatile ("VMRS %0, fpscr" : "=r" (result) ); - return(result); -#endif -#else - return(0U); -#endif -} - - -/** - \brief Set FPSCR - \details Assigns the given value to the Floating Point Status/Control register. - \param [in] fpscr Floating Point Status/Control value to set - */ -__STATIC_FORCEINLINE void __set_FPSCR(uint32_t fpscr) -{ -#if ((defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U)) && \ - (defined (__FPU_USED ) && (__FPU_USED == 1U)) ) -#if __has_builtin(__builtin_arm_set_fpscr) -// Re-enable using built-in when GCC has been fixed -// || (__GNUC__ > 7) || (__GNUC__ == 7 && __GNUC_MINOR__ >= 2) - /* see https://gcc.gnu.org/ml/gcc-patches/2017-04/msg00443.html */ - __builtin_arm_set_fpscr(fpscr); -#else - __ASM volatile ("VMSR fpscr, %0" : : "r" (fpscr) : "vfpcc", "memory"); -#endif -#else - (void)fpscr; -#endif -} - - -/*@} end of CMSIS_Core_RegAccFunctions */ - - -/* ########################## Core Instruction Access ######################### */ -/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface - Access to dedicated instructions - @{ -*/ - -/* Define macros for porting to both thumb1 and thumb2. - * For thumb1, use low register (r0-r7), specified by constraint "l" - * Otherwise, use general registers, specified by constraint "r" */ -#if defined (__thumb__) && !defined (__thumb2__) -#define __CMSIS_GCC_OUT_REG(r) "=l" (r) -#define __CMSIS_GCC_RW_REG(r) "+l" (r) -#define __CMSIS_GCC_USE_REG(r) "l" (r) -#else -#define __CMSIS_GCC_OUT_REG(r) "=r" (r) -#define __CMSIS_GCC_RW_REG(r) "+r" (r) -#define __CMSIS_GCC_USE_REG(r) "r" (r) -#endif - -/** - \brief No Operation - \details No Operation does nothing. This instruction can be used for code alignment purposes. - */ -#define __NOP() __ASM volatile ("nop") - -/** - \brief Wait For Interrupt - \details Wait For Interrupt is a hint instruction that suspends execution until one of a number of events occurs. - */ -#define __WFI() __ASM volatile ("wfi") - - -/** - \brief Wait For Event - \details Wait For Event is a hint instruction that permits the processor to enter - a low-power state until one of a number of events occurs. - */ -#define __WFE() __ASM volatile ("wfe") - - -/** - \brief Send Event - \details Send Event is a hint instruction. It causes an event to be signaled to the CPU. - */ -#define __SEV() __ASM volatile ("sev") - - -/** - \brief Instruction Synchronization Barrier - \details Instruction Synchronization Barrier flushes the pipeline in the processor, - so that all instructions following the ISB are fetched from cache or memory, - after the instruction has been completed. - */ -__STATIC_FORCEINLINE void __ISB(void) -{ - __ASM volatile ("isb 0xF":::"memory"); -} - - -/** - \brief Data Synchronization Barrier - \details Acts as a special kind of Data Memory Barrier. - It completes when all explicit memory accesses before this instruction complete. - */ -__STATIC_FORCEINLINE void __DSB(void) -{ - __ASM volatile ("dsb 0xF":::"memory"); -} - - -/** - \brief Data Memory Barrier - \details Ensures the apparent order of the explicit memory operations before - and after the instruction, without ensuring their completion. - */ -__STATIC_FORCEINLINE void __DMB(void) -{ - __ASM volatile ("dmb 0xF":::"memory"); -} - - -/** - \brief Reverse byte order (32 bit) - \details Reverses the byte order in unsigned integer value. For example, 0x12345678 becomes 0x78563412. - \param [in] value Value to reverse - \return Reversed value - */ -__STATIC_FORCEINLINE uint32_t __REV(uint32_t value) -{ -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 5) - return __builtin_bswap32(value); -#else - uint32_t result; - - __ASM volatile ("rev %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return result; -#endif -} - - -/** - \brief Reverse byte order (16 bit) - \details Reverses the byte order within each halfword of a word. For example, 0x12345678 becomes 0x34127856. - \param [in] value Value to reverse - \return Reversed value - */ -__STATIC_FORCEINLINE uint32_t __REV16(uint32_t value) -{ - uint32_t result; - - __ASM volatile ("rev16 %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return result; -} - - -/** - \brief Reverse byte order (16 bit) - \details Reverses the byte order in a 16-bit value and returns the signed 16-bit result. For example, 0x0080 becomes 0x8000. - \param [in] value Value to reverse - \return Reversed value - */ -__STATIC_FORCEINLINE int16_t __REVSH(int16_t value) -{ -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - return (int16_t)__builtin_bswap16(value); -#else - int16_t result; - - __ASM volatile ("revsh %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return result; -#endif -} - - -/** - \brief Rotate Right in unsigned value (32 bit) - \details Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits. - \param [in] op1 Value to rotate - \param [in] op2 Number of Bits to rotate - \return Rotated value - */ -__STATIC_FORCEINLINE uint32_t __ROR(uint32_t op1, uint32_t op2) -{ - op2 %= 32U; - if (op2 == 0U) - { - return op1; - } - return (op1 >> op2) | (op1 << (32U - op2)); -} - - -/** - \brief Breakpoint - \details Causes the processor to enter Debug state. - Debug tools can use this to investigate system state when the instruction at a particular address is reached. - \param [in] value is ignored by the processor. - If required, a debugger can use it to store additional information about the breakpoint. - */ -#define __BKPT(value) __ASM volatile ("bkpt "#value) - - -/** - \brief Reverse bit order of value - \details Reverses the bit order of the given value. - \param [in] value Value to reverse - \return Reversed value - */ -__STATIC_FORCEINLINE uint32_t __RBIT(uint32_t value) -{ - uint32_t result; - -#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) - __ASM volatile ("rbit %0, %1" : "=r" (result) : "r" (value) ); -#else - uint32_t s = (4U /*sizeof(v)*/ * 8U) - 1U; /* extra shift needed at end */ - - result = value; /* r will be reversed bits of v; first get LSB of v */ - for (value >>= 1U; value != 0U; value >>= 1U) - { - result <<= 1U; - result |= value & 1U; - s--; - } - result <<= s; /* shift when v's highest bits are zero */ -#endif - return result; -} - - -/** - \brief Count leading zeros - \details Counts the number of leading zeros of a data value. - \param [in] value Value to count the leading zeros - \return number of leading zeros in value - */ -__STATIC_FORCEINLINE uint8_t __CLZ(uint32_t value) -{ - /* Even though __builtin_clz produces a CLZ instruction on ARM, formally - __builtin_clz(0) is undefined behaviour, so handle this case specially. - This guarantees ARM-compatible results if happening to compile on a non-ARM - target, and ensures the compiler doesn't decide to activate any - optimisations using the logic "value was passed to __builtin_clz, so it - is non-zero". - ARM GCC 7.3 and possibly earlier will optimise this test away, leaving a - single CLZ instruction. - */ - if (value == 0U) - { - return 32U; - } - return __builtin_clz(value); -} - - -#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) -/** - \brief LDR Exclusive (8 bit) - \details Executes a exclusive LDR instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -__STATIC_FORCEINLINE uint8_t __LDREXB(volatile uint8_t *addr) -{ - uint32_t result; - -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - __ASM volatile ("ldrexb %0, %1" : "=r" (result) : "Q" (*addr) ); -#else - /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not - accepted by assembler. So has to use following less efficient pattern. - */ - __ASM volatile ("ldrexb %0, [%1]" : "=r" (result) : "r" (addr) : "memory" ); -#endif - return ((uint8_t) result); /* Add explicit type cast here */ -} - - -/** - \brief LDR Exclusive (16 bit) - \details Executes a exclusive LDR instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -__STATIC_FORCEINLINE uint16_t __LDREXH(volatile uint16_t *addr) -{ - uint32_t result; - -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - __ASM volatile ("ldrexh %0, %1" : "=r" (result) : "Q" (*addr) ); -#else - /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not - accepted by assembler. So has to use following less efficient pattern. - */ - __ASM volatile ("ldrexh %0, [%1]" : "=r" (result) : "r" (addr) : "memory" ); -#endif - return ((uint16_t) result); /* Add explicit type cast here */ -} - - -/** - \brief LDR Exclusive (32 bit) - \details Executes a exclusive LDR instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -__STATIC_FORCEINLINE uint32_t __LDREXW(volatile uint32_t *addr) -{ - uint32_t result; - - __ASM volatile ("ldrex %0, %1" : "=r" (result) : "Q" (*addr) ); - return(result); -} - - -/** - \brief STR Exclusive (8 bit) - \details Executes a exclusive STR instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__STATIC_FORCEINLINE uint32_t __STREXB(uint8_t value, volatile uint8_t *addr) -{ - uint32_t result; - - __ASM volatile ("strexb %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" ((uint32_t)value) ); - return(result); -} - - -/** - \brief STR Exclusive (16 bit) - \details Executes a exclusive STR instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__STATIC_FORCEINLINE uint32_t __STREXH(uint16_t value, volatile uint16_t *addr) -{ - uint32_t result; - - __ASM volatile ("strexh %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" ((uint32_t)value) ); - return(result); -} - - -/** - \brief STR Exclusive (32 bit) - \details Executes a exclusive STR instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__STATIC_FORCEINLINE uint32_t __STREXW(uint32_t value, volatile uint32_t *addr) -{ - uint32_t result; - - __ASM volatile ("strex %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" (value) ); - return(result); -} - - -/** - \brief Remove the exclusive lock - \details Removes the exclusive lock which is created by LDREX. - */ -__STATIC_FORCEINLINE void __CLREX(void) -{ - __ASM volatile ("clrex" ::: "memory"); -} - -#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ - - -#if ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) -/** - \brief Signed Saturate - \details Saturates a signed value. - \param [in] ARG1 Value to be saturated - \param [in] ARG2 Bit position to saturate to (1..32) - \return Saturated value - */ -#define __SSAT(ARG1,ARG2) \ -__extension__ \ -({ \ - int32_t __RES, __ARG1 = (ARG1); \ - __ASM ("ssat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) - - -/** - \brief Unsigned Saturate - \details Saturates an unsigned value. - \param [in] ARG1 Value to be saturated - \param [in] ARG2 Bit position to saturate to (0..31) - \return Saturated value - */ -#define __USAT(ARG1,ARG2) \ - __extension__ \ -({ \ - uint32_t __RES, __ARG1 = (ARG1); \ - __ASM ("usat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) - - -/** - \brief Rotate Right with Extend (32 bit) - \details Moves each bit of a bitstring right by one bit. - The carry input is shifted in at the left end of the bitstring. - \param [in] value Value to rotate - \return Rotated value - */ -__STATIC_FORCEINLINE uint32_t __RRX(uint32_t value) -{ - uint32_t result; - - __ASM volatile ("rrx %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) ); - return(result); -} - - -/** - \brief LDRT Unprivileged (8 bit) - \details Executes a Unprivileged LDRT instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -__STATIC_FORCEINLINE uint8_t __LDRBT(volatile uint8_t *ptr) -{ - uint32_t result; - -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - __ASM volatile ("ldrbt %0, %1" : "=r" (result) : "Q" (*ptr) ); -#else - /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not - accepted by assembler. So has to use following less efficient pattern. - */ - __ASM volatile ("ldrbt %0, [%1]" : "=r" (result) : "r" (ptr) : "memory" ); -#endif - return ((uint8_t) result); /* Add explicit type cast here */ -} - - -/** - \brief LDRT Unprivileged (16 bit) - \details Executes a Unprivileged LDRT instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -__STATIC_FORCEINLINE uint16_t __LDRHT(volatile uint16_t *ptr) -{ - uint32_t result; - -#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8) - __ASM volatile ("ldrht %0, %1" : "=r" (result) : "Q" (*ptr) ); -#else - /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not - accepted by assembler. So has to use following less efficient pattern. - */ - __ASM volatile ("ldrht %0, [%1]" : "=r" (result) : "r" (ptr) : "memory" ); -#endif - return ((uint16_t) result); /* Add explicit type cast here */ -} - - -/** - \brief LDRT Unprivileged (32 bit) - \details Executes a Unprivileged LDRT instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -__STATIC_FORCEINLINE uint32_t __LDRT(volatile uint32_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldrt %0, %1" : "=r" (result) : "Q" (*ptr) ); - return(result); -} - - -/** - \brief STRT Unprivileged (8 bit) - \details Executes a Unprivileged STRT instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STRBT(uint8_t value, volatile uint8_t *ptr) -{ - __ASM volatile ("strbt %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief STRT Unprivileged (16 bit) - \details Executes a Unprivileged STRT instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STRHT(uint16_t value, volatile uint16_t *ptr) -{ - __ASM volatile ("strht %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief STRT Unprivileged (32 bit) - \details Executes a Unprivileged STRT instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STRT(uint32_t value, volatile uint32_t *ptr) -{ - __ASM volatile ("strt %1, %0" : "=Q" (*ptr) : "r" (value) ); -} - -#else /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ - -/** - \brief Signed Saturate - \details Saturates a signed value. - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (1..32) - \return Saturated value - */ -__STATIC_FORCEINLINE int32_t __SSAT(int32_t val, uint32_t sat) -{ - if ((sat >= 1U) && (sat <= 32U)) - { - const int32_t max = (int32_t)((1U << (sat - 1U)) - 1U); - const int32_t min = -1 - max ; - if (val > max) - { - return max; - } - else if (val < min) - { - return min; - } - } - return val; -} - -/** - \brief Unsigned Saturate - \details Saturates an unsigned value. - \param [in] value Value to be saturated - \param [in] sat Bit position to saturate to (0..31) - \return Saturated value - */ -__STATIC_FORCEINLINE uint32_t __USAT(int32_t val, uint32_t sat) -{ - if (sat <= 31U) - { - const uint32_t max = ((1U << sat) - 1U); - if (val > (int32_t)max) - { - return max; - } - else if (val < 0) - { - return 0U; - } - } - return (uint32_t)val; -} - -#endif /* ((defined (__ARM_ARCH_7M__ ) && (__ARM_ARCH_7M__ == 1)) || \ - (defined (__ARM_ARCH_7EM__ ) && (__ARM_ARCH_7EM__ == 1)) || \ - (defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) ) */ - - -#if ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) -/** - \brief Load-Acquire (8 bit) - \details Executes a LDAB instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -__STATIC_FORCEINLINE uint8_t __LDAB(volatile uint8_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldab %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint8_t) result); -} - - -/** - \brief Load-Acquire (16 bit) - \details Executes a LDAH instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -__STATIC_FORCEINLINE uint16_t __LDAH(volatile uint16_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldah %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint16_t) result); -} - - -/** - \brief Load-Acquire (32 bit) - \details Executes a LDA instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -__STATIC_FORCEINLINE uint32_t __LDA(volatile uint32_t *ptr) -{ - uint32_t result; - - __ASM volatile ("lda %0, %1" : "=r" (result) : "Q" (*ptr) ); - return(result); -} - - -/** - \brief Store-Release (8 bit) - \details Executes a STLB instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STLB(uint8_t value, volatile uint8_t *ptr) -{ - __ASM volatile ("stlb %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief Store-Release (16 bit) - \details Executes a STLH instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STLH(uint16_t value, volatile uint16_t *ptr) -{ - __ASM volatile ("stlh %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief Store-Release (32 bit) - \details Executes a STL instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - */ -__STATIC_FORCEINLINE void __STL(uint32_t value, volatile uint32_t *ptr) -{ - __ASM volatile ("stl %1, %0" : "=Q" (*ptr) : "r" ((uint32_t)value) ); -} - - -/** - \brief Load-Acquire Exclusive (8 bit) - \details Executes a LDAB exclusive instruction for 8 bit value. - \param [in] ptr Pointer to data - \return value of type uint8_t at (*ptr) - */ -__STATIC_FORCEINLINE uint8_t __LDAEXB(volatile uint8_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldaexb %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint8_t) result); -} - - -/** - \brief Load-Acquire Exclusive (16 bit) - \details Executes a LDAH exclusive instruction for 16 bit values. - \param [in] ptr Pointer to data - \return value of type uint16_t at (*ptr) - */ -__STATIC_FORCEINLINE uint16_t __LDAEXH(volatile uint16_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldaexh %0, %1" : "=r" (result) : "Q" (*ptr) ); - return ((uint16_t) result); -} - - -/** - \brief Load-Acquire Exclusive (32 bit) - \details Executes a LDA exclusive instruction for 32 bit values. - \param [in] ptr Pointer to data - \return value of type uint32_t at (*ptr) - */ -__STATIC_FORCEINLINE uint32_t __LDAEX(volatile uint32_t *ptr) -{ - uint32_t result; - - __ASM volatile ("ldaex %0, %1" : "=r" (result) : "Q" (*ptr) ); - return(result); -} - - -/** - \brief Store-Release Exclusive (8 bit) - \details Executes a STLB exclusive instruction for 8 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__STATIC_FORCEINLINE uint32_t __STLEXB(uint8_t value, volatile uint8_t *ptr) -{ - uint32_t result; - - __ASM volatile ("stlexb %0, %2, %1" : "=&r" (result), "=Q" (*ptr) : "r" ((uint32_t)value) ); - return(result); -} - - -/** - \brief Store-Release Exclusive (16 bit) - \details Executes a STLH exclusive instruction for 16 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__STATIC_FORCEINLINE uint32_t __STLEXH(uint16_t value, volatile uint16_t *ptr) -{ - uint32_t result; - - __ASM volatile ("stlexh %0, %2, %1" : "=&r" (result), "=Q" (*ptr) : "r" ((uint32_t)value) ); - return(result); -} - - -/** - \brief Store-Release Exclusive (32 bit) - \details Executes a STL exclusive instruction for 32 bit values. - \param [in] value Value to store - \param [in] ptr Pointer to location - \return 0 Function succeeded - \return 1 Function failed - */ -__STATIC_FORCEINLINE uint32_t __STLEX(uint32_t value, volatile uint32_t *ptr) -{ - uint32_t result; - - __ASM volatile ("stlex %0, %2, %1" : "=&r" (result), "=Q" (*ptr) : "r" ((uint32_t)value) ); - return(result); -} - -#endif /* ((defined (__ARM_ARCH_8M_MAIN__ ) && (__ARM_ARCH_8M_MAIN__ == 1)) || \ - (defined (__ARM_ARCH_8M_BASE__ ) && (__ARM_ARCH_8M_BASE__ == 1)) ) */ - -/*@}*/ /* end of group CMSIS_Core_InstructionInterface */ - - -/* ################### Compiler specific Intrinsics ########################### */ -/** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics - Access to dedicated SIMD instructions - @{ -*/ - -#if (defined (__ARM_FEATURE_DSP) && (__ARM_FEATURE_DSP == 1)) - -__STATIC_FORCEINLINE uint32_t __SADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHADD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - - -__STATIC_FORCEINLINE uint32_t __SSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("ssub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHSUB8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - - -__STATIC_FORCEINLINE uint32_t __SADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHADD16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("ssub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHSUB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHASX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("ssax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __QSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("qsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SHSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("shsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UQSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uqsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UHSAX(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uhsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USAD8(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("usad8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __USADA8(uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("usada8 %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -#define __SSAT16(ARG1,ARG2) \ -({ \ - int32_t __RES, __ARG1 = (ARG1); \ - __ASM ("ssat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) - -#define __USAT16(ARG1,ARG2) \ -({ \ - uint32_t __RES, __ARG1 = (ARG1); \ - __ASM ("usat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \ - __RES; \ - }) - -__STATIC_FORCEINLINE uint32_t __UXTB16(uint32_t op1) -{ - uint32_t result; - - __ASM volatile ("uxtb16 %0, %1" : "=r" (result) : "r" (op1)); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __UXTAB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("uxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SXTB16(uint32_t op1) -{ - uint32_t result; - - __ASM volatile ("sxtb16 %0, %1" : "=r" (result) : "r" (op1)); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SXTAB16(uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMUAD (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smuad %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMUADX (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smuadx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMLAD (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smlad %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMLADX (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smladx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__STATIC_FORCEINLINE uint64_t __SMLALD (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__STATIC_FORCEINLINE uint64_t __SMLALDX (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__STATIC_FORCEINLINE uint32_t __SMUSD (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smusd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMUSDX (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("smusdx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMLSD (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smlsd %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__STATIC_FORCEINLINE uint32_t __SMLSDX (uint32_t op1, uint32_t op2, uint32_t op3) -{ - uint32_t result; - - __ASM volatile ("smlsdx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -__STATIC_FORCEINLINE uint64_t __SMLSLD (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__STATIC_FORCEINLINE uint64_t __SMLSLDX (uint32_t op1, uint32_t op2, uint64_t acc) -{ - union llreg_u{ - uint32_t w32[2]; - uint64_t w64; - } llr; - llr.w64 = acc; - -#ifndef __ARMEB__ /* Little endian */ - __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (llr.w32[0]), "=r" (llr.w32[1]): "r" (op1), "r" (op2) , "0" (llr.w32[0]), "1" (llr.w32[1]) ); -#else /* Big endian */ - __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (llr.w32[1]), "=r" (llr.w32[0]): "r" (op1), "r" (op2) , "0" (llr.w32[1]), "1" (llr.w32[0]) ); -#endif - - return(llr.w64); -} - -__STATIC_FORCEINLINE uint32_t __SEL (uint32_t op1, uint32_t op2) -{ - uint32_t result; - - __ASM volatile ("sel %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE int32_t __QADD( int32_t op1, int32_t op2) -{ - int32_t result; - - __ASM volatile ("qadd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -__STATIC_FORCEINLINE int32_t __QSUB( int32_t op1, int32_t op2) -{ - int32_t result; - - __ASM volatile ("qsub %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) ); - return(result); -} - -#if 0 -#define __PKHBT(ARG1,ARG2,ARG3) \ -({ \ - uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \ - __ASM ("pkhbt %0, %1, %2, lsl %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \ - __RES; \ - }) - -#define __PKHTB(ARG1,ARG2,ARG3) \ -({ \ - uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \ - if (ARG3 == 0) \ - __ASM ("pkhtb %0, %1, %2" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2) ); \ - else \ - __ASM ("pkhtb %0, %1, %2, asr %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \ - __RES; \ - }) -#endif - -#define __PKHBT(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0x0000FFFFUL) | \ - ((((uint32_t)(ARG2)) << (ARG3)) & 0xFFFF0000UL) ) - -#define __PKHTB(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0xFFFF0000UL) | \ - ((((uint32_t)(ARG2)) >> (ARG3)) & 0x0000FFFFUL) ) - -__STATIC_FORCEINLINE int32_t __SMMLA (int32_t op1, int32_t op2, int32_t op3) -{ - int32_t result; - - __ASM volatile ("smmla %0, %1, %2, %3" : "=r" (result): "r" (op1), "r" (op2), "r" (op3) ); - return(result); -} - -#endif /* (__ARM_FEATURE_DSP == 1) */ -/*@} end of group CMSIS_SIMD_intrinsics */ - - -#pragma GCC diagnostic pop - -#endif /* __CMSIS_GCC_H */ - diff --git a/panda/board/stm32h7/inc/cmsis_version.h b/panda/board/stm32h7/inc/cmsis_version.h deleted file mode 100644 index bf57cf3..0000000 --- a/panda/board/stm32h7/inc/cmsis_version.h +++ /dev/null @@ -1,40 +0,0 @@ -/**************************************************************************//** - * @file cmsis_version.h - * @brief CMSIS Core(M) Version definitions - * @version V5.0.3 - * @date 24. June 2019 - ******************************************************************************/ -/* - * Copyright (c) 2009-2019 ARM Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef __CMSIS_VERSION_H -#define __CMSIS_VERSION_H - -/* CMSIS Version definitions */ -#define __CM_CMSIS_VERSION_MAIN ( 5U) /*!< [31:16] CMSIS Core(M) main version */ -#define __CM_CMSIS_VERSION_SUB ( 3U) /*!< [15:0] CMSIS Core(M) sub version */ -#define __CM_CMSIS_VERSION ((__CM_CMSIS_VERSION_MAIN << 16U) | \ - __CM_CMSIS_VERSION_SUB ) /*!< CMSIS Core(M) version number */ -#endif - diff --git a/panda/board/stm32h7/inc/core_cm7.h b/panda/board/stm32h7/inc/core_cm7.h deleted file mode 100644 index 3da3c43..0000000 --- a/panda/board/stm32h7/inc/core_cm7.h +++ /dev/null @@ -1,2725 +0,0 @@ -/**************************************************************************//** - * @file core_cm7.h - * @brief CMSIS Cortex-M7 Core Peripheral Access Layer Header File - * @version V5.1.1 - * @date 28. March 2019 - ******************************************************************************/ -/* - * Copyright (c) 2009-2019 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef __CORE_CM7_H_GENERIC -#define __CORE_CM7_H_GENERIC - -#include - -#ifdef __cplusplus - extern "C" { -#endif - -/** - \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions - CMSIS violates the following MISRA-C:2004 rules: - - \li Required Rule 8.5, object/function definition in header file.
- Function definitions in header files are used to allow 'inlining'. - - \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.
- Unions are used for effective representation of core registers. - - \li Advisory Rule 19.7, Function-like macro defined.
- Function-like macros are used to allow more efficient code. - */ - - -/******************************************************************************* - * CMSIS definitions - ******************************************************************************/ -/** - \ingroup Cortex_M7 - @{ - */ - -#include "cmsis_version.h" - -/* CMSIS CM7 definitions */ -#define __CM7_CMSIS_VERSION_MAIN (__CM_CMSIS_VERSION_MAIN) /*!< \deprecated [31:16] CMSIS HAL main version */ -#define __CM7_CMSIS_VERSION_SUB ( __CM_CMSIS_VERSION_SUB) /*!< \deprecated [15:0] CMSIS HAL sub version */ -#define __CM7_CMSIS_VERSION ((__CM7_CMSIS_VERSION_MAIN << 16U) | \ - __CM7_CMSIS_VERSION_SUB ) /*!< \deprecated CMSIS HAL version number */ - -#define __CORTEX_M (7U) /*!< Cortex-M Core */ - -/** __FPU_USED indicates whether an FPU is used or not. - For this, __FPU_PRESENT has to be checked prior to making use of FPU specific registers and functions. -*/ -#if defined ( __CC_ARM ) - #if defined __TARGET_FPU_VFP - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) - #if defined __ARM_FP - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __GNUC__ ) - #if defined (__VFP_FP__) && !defined(__SOFTFP__) - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __ICCARM__ ) - #if defined __ARMVFP__ - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __TI_ARM__ ) - #if defined __TI_VFP_SUPPORT__ - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __TASKING__ ) - #if defined __FPU_VFP__ - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#elif defined ( __CSMC__ ) - #if ( __CSMC__ & 0x400U) - #if defined (__FPU_PRESENT) && (__FPU_PRESENT == 1U) - #define __FPU_USED 1U - #else - #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)" - #define __FPU_USED 0U - #endif - #else - #define __FPU_USED 0U - #endif - -#endif - -#include "cmsis_compiler.h" /* CMSIS compiler specific defines */ - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_CM7_H_GENERIC */ - -#ifndef __CMSIS_GENERIC - -#ifndef __CORE_CM7_H_DEPENDANT -#define __CORE_CM7_H_DEPENDANT - -#ifdef __cplusplus - extern "C" { -#endif - -/* check device defines and use defaults */ -#if defined __CHECK_DEVICE_DEFINES - #ifndef __CM7_REV - #define __CM7_REV 0x0000U - #warning "__CM7_REV not defined in device header file; using default!" - #endif - - #ifndef __FPU_PRESENT - #define __FPU_PRESENT 0U - #warning "__FPU_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __MPU_PRESENT - #define __MPU_PRESENT 0U - #warning "__MPU_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __ICACHE_PRESENT - #define __ICACHE_PRESENT 0U - #warning "__ICACHE_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __DCACHE_PRESENT - #define __DCACHE_PRESENT 0U - #warning "__DCACHE_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __DTCM_PRESENT - #define __DTCM_PRESENT 0U - #warning "__DTCM_PRESENT not defined in device header file; using default!" - #endif - - #ifndef __NVIC_PRIO_BITS - #define __NVIC_PRIO_BITS 3U - #warning "__NVIC_PRIO_BITS not defined in device header file; using default!" - #endif - - #ifndef __Vendor_SysTickConfig - #define __Vendor_SysTickConfig 0U - #warning "__Vendor_SysTickConfig not defined in device header file; using default!" - #endif -#endif - -/* IO definitions (access restrictions to peripheral registers) */ -/** - \defgroup CMSIS_glob_defs CMSIS Global Defines - - IO Type Qualifiers are used - \li to specify the access to peripheral variables. - \li for automatic generation of peripheral register debug information. -*/ -#ifdef __cplusplus - #define __I volatile /*!< Defines 'read only' permissions */ -#else - #define __I volatile const /*!< Defines 'read only' permissions */ -#endif -#define __O volatile /*!< Defines 'write only' permissions */ -#define __IO volatile /*!< Defines 'read / write' permissions */ - -/* following defines should be used for structure members */ -#define __IM volatile const /*! Defines 'read only' structure member permissions */ -#define __OM volatile /*! Defines 'write only' structure member permissions */ -#define __IOM volatile /*! Defines 'read / write' structure member permissions */ - -/*@} end of group Cortex_M7 */ - - - -/******************************************************************************* - * Register Abstraction - Core Register contain: - - Core Register - - Core NVIC Register - - Core SCB Register - - Core SysTick Register - - Core Debug Register - - Core MPU Register - - Core FPU Register - ******************************************************************************/ -/** - \defgroup CMSIS_core_register Defines and Type Definitions - \brief Type definitions and defines for Cortex-M processor based devices. -*/ - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CORE Status and Control Registers - \brief Core Register type definitions. - @{ - */ - -/** - \brief Union type to access the Application Program Status Register (APSR). - */ -typedef union -{ - struct - { - uint32_t _reserved0:16; /*!< bit: 0..15 Reserved */ - uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ - uint32_t _reserved1:7; /*!< bit: 20..26 Reserved */ - uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} APSR_Type; - -/* APSR Register Definitions */ -#define APSR_N_Pos 31U /*!< APSR: N Position */ -#define APSR_N_Msk (1UL << APSR_N_Pos) /*!< APSR: N Mask */ - -#define APSR_Z_Pos 30U /*!< APSR: Z Position */ -#define APSR_Z_Msk (1UL << APSR_Z_Pos) /*!< APSR: Z Mask */ - -#define APSR_C_Pos 29U /*!< APSR: C Position */ -#define APSR_C_Msk (1UL << APSR_C_Pos) /*!< APSR: C Mask */ - -#define APSR_V_Pos 28U /*!< APSR: V Position */ -#define APSR_V_Msk (1UL << APSR_V_Pos) /*!< APSR: V Mask */ - -#define APSR_Q_Pos 27U /*!< APSR: Q Position */ -#define APSR_Q_Msk (1UL << APSR_Q_Pos) /*!< APSR: Q Mask */ - -#define APSR_GE_Pos 16U /*!< APSR: GE Position */ -#define APSR_GE_Msk (0xFUL << APSR_GE_Pos) /*!< APSR: GE Mask */ - - -/** - \brief Union type to access the Interrupt Program Status Register (IPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} IPSR_Type; - -/* IPSR Register Definitions */ -#define IPSR_ISR_Pos 0U /*!< IPSR: ISR Position */ -#define IPSR_ISR_Msk (0x1FFUL /*<< IPSR_ISR_Pos*/) /*!< IPSR: ISR Mask */ - - -/** - \brief Union type to access the Special-Purpose Program Status Registers (xPSR). - */ -typedef union -{ - struct - { - uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */ - uint32_t _reserved0:1; /*!< bit: 9 Reserved */ - uint32_t ICI_IT_1:6; /*!< bit: 10..15 ICI/IT part 1 */ - uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */ - uint32_t _reserved1:4; /*!< bit: 20..23 Reserved */ - uint32_t T:1; /*!< bit: 24 Thumb bit */ - uint32_t ICI_IT_2:2; /*!< bit: 25..26 ICI/IT part 2 */ - uint32_t Q:1; /*!< bit: 27 Saturation condition flag */ - uint32_t V:1; /*!< bit: 28 Overflow condition code flag */ - uint32_t C:1; /*!< bit: 29 Carry condition code flag */ - uint32_t Z:1; /*!< bit: 30 Zero condition code flag */ - uint32_t N:1; /*!< bit: 31 Negative condition code flag */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} xPSR_Type; - -/* xPSR Register Definitions */ -#define xPSR_N_Pos 31U /*!< xPSR: N Position */ -#define xPSR_N_Msk (1UL << xPSR_N_Pos) /*!< xPSR: N Mask */ - -#define xPSR_Z_Pos 30U /*!< xPSR: Z Position */ -#define xPSR_Z_Msk (1UL << xPSR_Z_Pos) /*!< xPSR: Z Mask */ - -#define xPSR_C_Pos 29U /*!< xPSR: C Position */ -#define xPSR_C_Msk (1UL << xPSR_C_Pos) /*!< xPSR: C Mask */ - -#define xPSR_V_Pos 28U /*!< xPSR: V Position */ -#define xPSR_V_Msk (1UL << xPSR_V_Pos) /*!< xPSR: V Mask */ - -#define xPSR_Q_Pos 27U /*!< xPSR: Q Position */ -#define xPSR_Q_Msk (1UL << xPSR_Q_Pos) /*!< xPSR: Q Mask */ - -#define xPSR_ICI_IT_2_Pos 25U /*!< xPSR: ICI/IT part 2 Position */ -#define xPSR_ICI_IT_2_Msk (3UL << xPSR_ICI_IT_2_Pos) /*!< xPSR: ICI/IT part 2 Mask */ - -#define xPSR_T_Pos 24U /*!< xPSR: T Position */ -#define xPSR_T_Msk (1UL << xPSR_T_Pos) /*!< xPSR: T Mask */ - -#define xPSR_GE_Pos 16U /*!< xPSR: GE Position */ -#define xPSR_GE_Msk (0xFUL << xPSR_GE_Pos) /*!< xPSR: GE Mask */ - -#define xPSR_ICI_IT_1_Pos 10U /*!< xPSR: ICI/IT part 1 Position */ -#define xPSR_ICI_IT_1_Msk (0x3FUL << xPSR_ICI_IT_1_Pos) /*!< xPSR: ICI/IT part 1 Mask */ - -#define xPSR_ISR_Pos 0U /*!< xPSR: ISR Position */ -#define xPSR_ISR_Msk (0x1FFUL /*<< xPSR_ISR_Pos*/) /*!< xPSR: ISR Mask */ - - -/** - \brief Union type to access the Control Registers (CONTROL). - */ -typedef union -{ - struct - { - uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */ - uint32_t SPSEL:1; /*!< bit: 1 Stack to be used */ - uint32_t FPCA:1; /*!< bit: 2 FP extension active flag */ - uint32_t _reserved0:29; /*!< bit: 3..31 Reserved */ - } b; /*!< Structure used for bit access */ - uint32_t w; /*!< Type used for word access */ -} CONTROL_Type; - -/* CONTROL Register Definitions */ -#define CONTROL_FPCA_Pos 2U /*!< CONTROL: FPCA Position */ -#define CONTROL_FPCA_Msk (1UL << CONTROL_FPCA_Pos) /*!< CONTROL: FPCA Mask */ - -#define CONTROL_SPSEL_Pos 1U /*!< CONTROL: SPSEL Position */ -#define CONTROL_SPSEL_Msk (1UL << CONTROL_SPSEL_Pos) /*!< CONTROL: SPSEL Mask */ - -#define CONTROL_nPRIV_Pos 0U /*!< CONTROL: nPRIV Position */ -#define CONTROL_nPRIV_Msk (1UL /*<< CONTROL_nPRIV_Pos*/) /*!< CONTROL: nPRIV Mask */ - -/*@} end of group CMSIS_CORE */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC) - \brief Type definitions for the NVIC Registers - @{ - */ - -/** - \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC). - */ -typedef struct -{ - __IOM uint32_t ISER[8U]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */ - uint32_t RESERVED0[24U]; - __IOM uint32_t ICER[8U]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */ - uint32_t RESERVED1[24U]; - __IOM uint32_t ISPR[8U]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */ - uint32_t RESERVED2[24U]; - __IOM uint32_t ICPR[8U]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */ - uint32_t RESERVED3[24U]; - __IOM uint32_t IABR[8U]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */ - uint32_t RESERVED4[56U]; - __IOM uint8_t IP[240U]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register (8Bit wide) */ - uint32_t RESERVED5[644U]; - __OM uint32_t STIR; /*!< Offset: 0xE00 ( /W) Software Trigger Interrupt Register */ -} NVIC_Type; - -/* Software Triggered Interrupt Register Definitions */ -#define NVIC_STIR_INTID_Pos 0U /*!< STIR: INTLINESNUM Position */ -#define NVIC_STIR_INTID_Msk (0x1FFUL /*<< NVIC_STIR_INTID_Pos*/) /*!< STIR: INTLINESNUM Mask */ - -/*@} end of group CMSIS_NVIC */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SCB System Control Block (SCB) - \brief Type definitions for the System Control Block Registers - @{ - */ - -/** - \brief Structure type to access the System Control Block (SCB). - */ -typedef struct -{ - __IM uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ - __IOM uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ - __IOM uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ - __IOM uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ - __IOM uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ - __IOM uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ - __IOM uint8_t SHPR[12U]; /*!< Offset: 0x018 (R/W) System Handlers Priority Registers (4-7, 8-11, 12-15) */ - __IOM uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ - __IOM uint32_t CFSR; /*!< Offset: 0x028 (R/W) Configurable Fault Status Register */ - __IOM uint32_t HFSR; /*!< Offset: 0x02C (R/W) HardFault Status Register */ - __IOM uint32_t DFSR; /*!< Offset: 0x030 (R/W) Debug Fault Status Register */ - __IOM uint32_t MMFAR; /*!< Offset: 0x034 (R/W) MemManage Fault Address Register */ - __IOM uint32_t BFAR; /*!< Offset: 0x038 (R/W) BusFault Address Register */ - __IOM uint32_t AFSR; /*!< Offset: 0x03C (R/W) Auxiliary Fault Status Register */ - __IM uint32_t ID_PFR[2U]; /*!< Offset: 0x040 (R/ ) Processor Feature Register */ - __IM uint32_t ID_DFR; /*!< Offset: 0x048 (R/ ) Debug Feature Register */ - __IM uint32_t ID_AFR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */ - __IM uint32_t ID_MFR[4U]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */ - __IM uint32_t ID_ISAR[5U]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */ - uint32_t RESERVED0[1U]; - __IM uint32_t CLIDR; /*!< Offset: 0x078 (R/ ) Cache Level ID register */ - __IM uint32_t CTR; /*!< Offset: 0x07C (R/ ) Cache Type register */ - __IM uint32_t CCSIDR; /*!< Offset: 0x080 (R/ ) Cache Size ID Register */ - __IOM uint32_t CSSELR; /*!< Offset: 0x084 (R/W) Cache Size Selection Register */ - __IOM uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control Register */ - uint32_t RESERVED3[93U]; - __OM uint32_t STIR; /*!< Offset: 0x200 ( /W) Software Triggered Interrupt Register */ - uint32_t RESERVED4[15U]; - __IM uint32_t MVFR0; /*!< Offset: 0x240 (R/ ) Media and VFP Feature Register 0 */ - __IM uint32_t MVFR1; /*!< Offset: 0x244 (R/ ) Media and VFP Feature Register 1 */ - __IM uint32_t MVFR2; /*!< Offset: 0x248 (R/ ) Media and VFP Feature Register 2 */ - uint32_t RESERVED5[1U]; - __OM uint32_t ICIALLU; /*!< Offset: 0x250 ( /W) I-Cache Invalidate All to PoU */ - uint32_t RESERVED6[1U]; - __OM uint32_t ICIMVAU; /*!< Offset: 0x258 ( /W) I-Cache Invalidate by MVA to PoU */ - __OM uint32_t DCIMVAC; /*!< Offset: 0x25C ( /W) D-Cache Invalidate by MVA to PoC */ - __OM uint32_t DCISW; /*!< Offset: 0x260 ( /W) D-Cache Invalidate by Set-way */ - __OM uint32_t DCCMVAU; /*!< Offset: 0x264 ( /W) D-Cache Clean by MVA to PoU */ - __OM uint32_t DCCMVAC; /*!< Offset: 0x268 ( /W) D-Cache Clean by MVA to PoC */ - __OM uint32_t DCCSW; /*!< Offset: 0x26C ( /W) D-Cache Clean by Set-way */ - __OM uint32_t DCCIMVAC; /*!< Offset: 0x270 ( /W) D-Cache Clean and Invalidate by MVA to PoC */ - __OM uint32_t DCCISW; /*!< Offset: 0x274 ( /W) D-Cache Clean and Invalidate by Set-way */ - uint32_t RESERVED7[6U]; - __IOM uint32_t ITCMCR; /*!< Offset: 0x290 (R/W) Instruction Tightly-Coupled Memory Control Register */ - __IOM uint32_t DTCMCR; /*!< Offset: 0x294 (R/W) Data Tightly-Coupled Memory Control Registers */ - __IOM uint32_t AHBPCR; /*!< Offset: 0x298 (R/W) AHBP Control Register */ - __IOM uint32_t CACR; /*!< Offset: 0x29C (R/W) L1 Cache Control Register */ - __IOM uint32_t AHBSCR; /*!< Offset: 0x2A0 (R/W) AHB Slave Control Register */ - uint32_t RESERVED8[1U]; - __IOM uint32_t ABFSR; /*!< Offset: 0x2A8 (R/W) Auxiliary Bus Fault Status Register */ -} SCB_Type; - -/* SCB CPUID Register Definitions */ -#define SCB_CPUID_IMPLEMENTER_Pos 24U /*!< SCB CPUID: IMPLEMENTER Position */ -#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */ - -#define SCB_CPUID_VARIANT_Pos 20U /*!< SCB CPUID: VARIANT Position */ -#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */ - -#define SCB_CPUID_ARCHITECTURE_Pos 16U /*!< SCB CPUID: ARCHITECTURE Position */ -#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */ - -#define SCB_CPUID_PARTNO_Pos 4U /*!< SCB CPUID: PARTNO Position */ -#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */ - -#define SCB_CPUID_REVISION_Pos 0U /*!< SCB CPUID: REVISION Position */ -#define SCB_CPUID_REVISION_Msk (0xFUL /*<< SCB_CPUID_REVISION_Pos*/) /*!< SCB CPUID: REVISION Mask */ - -/* SCB Interrupt Control State Register Definitions */ -#define SCB_ICSR_NMIPENDSET_Pos 31U /*!< SCB ICSR: NMIPENDSET Position */ -#define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */ - -#define SCB_ICSR_PENDSVSET_Pos 28U /*!< SCB ICSR: PENDSVSET Position */ -#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */ - -#define SCB_ICSR_PENDSVCLR_Pos 27U /*!< SCB ICSR: PENDSVCLR Position */ -#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */ - -#define SCB_ICSR_PENDSTSET_Pos 26U /*!< SCB ICSR: PENDSTSET Position */ -#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */ - -#define SCB_ICSR_PENDSTCLR_Pos 25U /*!< SCB ICSR: PENDSTCLR Position */ -#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */ - -#define SCB_ICSR_ISRPREEMPT_Pos 23U /*!< SCB ICSR: ISRPREEMPT Position */ -#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */ - -#define SCB_ICSR_ISRPENDING_Pos 22U /*!< SCB ICSR: ISRPENDING Position */ -#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */ - -#define SCB_ICSR_VECTPENDING_Pos 12U /*!< SCB ICSR: VECTPENDING Position */ -#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */ - -#define SCB_ICSR_RETTOBASE_Pos 11U /*!< SCB ICSR: RETTOBASE Position */ -#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */ - -#define SCB_ICSR_VECTACTIVE_Pos 0U /*!< SCB ICSR: VECTACTIVE Position */ -#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL /*<< SCB_ICSR_VECTACTIVE_Pos*/) /*!< SCB ICSR: VECTACTIVE Mask */ - -/* SCB Vector Table Offset Register Definitions */ -#define SCB_VTOR_TBLOFF_Pos 7U /*!< SCB VTOR: TBLOFF Position */ -#define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */ - -/* SCB Application Interrupt and Reset Control Register Definitions */ -#define SCB_AIRCR_VECTKEY_Pos 16U /*!< SCB AIRCR: VECTKEY Position */ -#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ - -#define SCB_AIRCR_VECTKEYSTAT_Pos 16U /*!< SCB AIRCR: VECTKEYSTAT Position */ -#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */ - -#define SCB_AIRCR_ENDIANESS_Pos 15U /*!< SCB AIRCR: ENDIANESS Position */ -#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */ - -#define SCB_AIRCR_PRIGROUP_Pos 8U /*!< SCB AIRCR: PRIGROUP Position */ -#define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */ - -#define SCB_AIRCR_SYSRESETREQ_Pos 2U /*!< SCB AIRCR: SYSRESETREQ Position */ -#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */ - -#define SCB_AIRCR_VECTCLRACTIVE_Pos 1U /*!< SCB AIRCR: VECTCLRACTIVE Position */ -#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */ - -#define SCB_AIRCR_VECTRESET_Pos 0U /*!< SCB AIRCR: VECTRESET Position */ -#define SCB_AIRCR_VECTRESET_Msk (1UL /*<< SCB_AIRCR_VECTRESET_Pos*/) /*!< SCB AIRCR: VECTRESET Mask */ - -/* SCB System Control Register Definitions */ -#define SCB_SCR_SEVONPEND_Pos 4U /*!< SCB SCR: SEVONPEND Position */ -#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */ - -#define SCB_SCR_SLEEPDEEP_Pos 2U /*!< SCB SCR: SLEEPDEEP Position */ -#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */ - -#define SCB_SCR_SLEEPONEXIT_Pos 1U /*!< SCB SCR: SLEEPONEXIT Position */ -#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */ - -/* SCB Configuration Control Register Definitions */ -#define SCB_CCR_BP_Pos 18U /*!< SCB CCR: Branch prediction enable bit Position */ -#define SCB_CCR_BP_Msk (1UL << SCB_CCR_BP_Pos) /*!< SCB CCR: Branch prediction enable bit Mask */ - -#define SCB_CCR_IC_Pos 17U /*!< SCB CCR: Instruction cache enable bit Position */ -#define SCB_CCR_IC_Msk (1UL << SCB_CCR_IC_Pos) /*!< SCB CCR: Instruction cache enable bit Mask */ - -#define SCB_CCR_DC_Pos 16U /*!< SCB CCR: Cache enable bit Position */ -#define SCB_CCR_DC_Msk (1UL << SCB_CCR_DC_Pos) /*!< SCB CCR: Cache enable bit Mask */ - -#define SCB_CCR_STKALIGN_Pos 9U /*!< SCB CCR: STKALIGN Position */ -#define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */ - -#define SCB_CCR_BFHFNMIGN_Pos 8U /*!< SCB CCR: BFHFNMIGN Position */ -#define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */ - -#define SCB_CCR_DIV_0_TRP_Pos 4U /*!< SCB CCR: DIV_0_TRP Position */ -#define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */ - -#define SCB_CCR_UNALIGN_TRP_Pos 3U /*!< SCB CCR: UNALIGN_TRP Position */ -#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */ - -#define SCB_CCR_USERSETMPEND_Pos 1U /*!< SCB CCR: USERSETMPEND Position */ -#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */ - -#define SCB_CCR_NONBASETHRDENA_Pos 0U /*!< SCB CCR: NONBASETHRDENA Position */ -#define SCB_CCR_NONBASETHRDENA_Msk (1UL /*<< SCB_CCR_NONBASETHRDENA_Pos*/) /*!< SCB CCR: NONBASETHRDENA Mask */ - -/* SCB System Handler Control and State Register Definitions */ -#define SCB_SHCSR_USGFAULTENA_Pos 18U /*!< SCB SHCSR: USGFAULTENA Position */ -#define SCB_SHCSR_USGFAULTENA_Msk (1UL << SCB_SHCSR_USGFAULTENA_Pos) /*!< SCB SHCSR: USGFAULTENA Mask */ - -#define SCB_SHCSR_BUSFAULTENA_Pos 17U /*!< SCB SHCSR: BUSFAULTENA Position */ -#define SCB_SHCSR_BUSFAULTENA_Msk (1UL << SCB_SHCSR_BUSFAULTENA_Pos) /*!< SCB SHCSR: BUSFAULTENA Mask */ - -#define SCB_SHCSR_MEMFAULTENA_Pos 16U /*!< SCB SHCSR: MEMFAULTENA Position */ -#define SCB_SHCSR_MEMFAULTENA_Msk (1UL << SCB_SHCSR_MEMFAULTENA_Pos) /*!< SCB SHCSR: MEMFAULTENA Mask */ - -#define SCB_SHCSR_SVCALLPENDED_Pos 15U /*!< SCB SHCSR: SVCALLPENDED Position */ -#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */ - -#define SCB_SHCSR_BUSFAULTPENDED_Pos 14U /*!< SCB SHCSR: BUSFAULTPENDED Position */ -#define SCB_SHCSR_BUSFAULTPENDED_Msk (1UL << SCB_SHCSR_BUSFAULTPENDED_Pos) /*!< SCB SHCSR: BUSFAULTPENDED Mask */ - -#define SCB_SHCSR_MEMFAULTPENDED_Pos 13U /*!< SCB SHCSR: MEMFAULTPENDED Position */ -#define SCB_SHCSR_MEMFAULTPENDED_Msk (1UL << SCB_SHCSR_MEMFAULTPENDED_Pos) /*!< SCB SHCSR: MEMFAULTPENDED Mask */ - -#define SCB_SHCSR_USGFAULTPENDED_Pos 12U /*!< SCB SHCSR: USGFAULTPENDED Position */ -#define SCB_SHCSR_USGFAULTPENDED_Msk (1UL << SCB_SHCSR_USGFAULTPENDED_Pos) /*!< SCB SHCSR: USGFAULTPENDED Mask */ - -#define SCB_SHCSR_SYSTICKACT_Pos 11U /*!< SCB SHCSR: SYSTICKACT Position */ -#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */ - -#define SCB_SHCSR_PENDSVACT_Pos 10U /*!< SCB SHCSR: PENDSVACT Position */ -#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */ - -#define SCB_SHCSR_MONITORACT_Pos 8U /*!< SCB SHCSR: MONITORACT Position */ -#define SCB_SHCSR_MONITORACT_Msk (1UL << SCB_SHCSR_MONITORACT_Pos) /*!< SCB SHCSR: MONITORACT Mask */ - -#define SCB_SHCSR_SVCALLACT_Pos 7U /*!< SCB SHCSR: SVCALLACT Position */ -#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */ - -#define SCB_SHCSR_USGFAULTACT_Pos 3U /*!< SCB SHCSR: USGFAULTACT Position */ -#define SCB_SHCSR_USGFAULTACT_Msk (1UL << SCB_SHCSR_USGFAULTACT_Pos) /*!< SCB SHCSR: USGFAULTACT Mask */ - -#define SCB_SHCSR_BUSFAULTACT_Pos 1U /*!< SCB SHCSR: BUSFAULTACT Position */ -#define SCB_SHCSR_BUSFAULTACT_Msk (1UL << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */ - -#define SCB_SHCSR_MEMFAULTACT_Pos 0U /*!< SCB SHCSR: MEMFAULTACT Position */ -#define SCB_SHCSR_MEMFAULTACT_Msk (1UL /*<< SCB_SHCSR_MEMFAULTACT_Pos*/) /*!< SCB SHCSR: MEMFAULTACT Mask */ - -/* SCB Configurable Fault Status Register Definitions */ -#define SCB_CFSR_USGFAULTSR_Pos 16U /*!< SCB CFSR: Usage Fault Status Register Position */ -#define SCB_CFSR_USGFAULTSR_Msk (0xFFFFUL << SCB_CFSR_USGFAULTSR_Pos) /*!< SCB CFSR: Usage Fault Status Register Mask */ - -#define SCB_CFSR_BUSFAULTSR_Pos 8U /*!< SCB CFSR: Bus Fault Status Register Position */ -#define SCB_CFSR_BUSFAULTSR_Msk (0xFFUL << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */ - -#define SCB_CFSR_MEMFAULTSR_Pos 0U /*!< SCB CFSR: Memory Manage Fault Status Register Position */ -#define SCB_CFSR_MEMFAULTSR_Msk (0xFFUL /*<< SCB_CFSR_MEMFAULTSR_Pos*/) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */ - -/* MemManage Fault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_MMARVALID_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 7U) /*!< SCB CFSR (MMFSR): MMARVALID Position */ -#define SCB_CFSR_MMARVALID_Msk (1UL << SCB_CFSR_MMARVALID_Pos) /*!< SCB CFSR (MMFSR): MMARVALID Mask */ - -#define SCB_CFSR_MLSPERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 5U) /*!< SCB CFSR (MMFSR): MLSPERR Position */ -#define SCB_CFSR_MLSPERR_Msk (1UL << SCB_CFSR_MLSPERR_Pos) /*!< SCB CFSR (MMFSR): MLSPERR Mask */ - -#define SCB_CFSR_MSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 4U) /*!< SCB CFSR (MMFSR): MSTKERR Position */ -#define SCB_CFSR_MSTKERR_Msk (1UL << SCB_CFSR_MSTKERR_Pos) /*!< SCB CFSR (MMFSR): MSTKERR Mask */ - -#define SCB_CFSR_MUNSTKERR_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 3U) /*!< SCB CFSR (MMFSR): MUNSTKERR Position */ -#define SCB_CFSR_MUNSTKERR_Msk (1UL << SCB_CFSR_MUNSTKERR_Pos) /*!< SCB CFSR (MMFSR): MUNSTKERR Mask */ - -#define SCB_CFSR_DACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 1U) /*!< SCB CFSR (MMFSR): DACCVIOL Position */ -#define SCB_CFSR_DACCVIOL_Msk (1UL << SCB_CFSR_DACCVIOL_Pos) /*!< SCB CFSR (MMFSR): DACCVIOL Mask */ - -#define SCB_CFSR_IACCVIOL_Pos (SCB_SHCSR_MEMFAULTACT_Pos + 0U) /*!< SCB CFSR (MMFSR): IACCVIOL Position */ -#define SCB_CFSR_IACCVIOL_Msk (1UL /*<< SCB_CFSR_IACCVIOL_Pos*/) /*!< SCB CFSR (MMFSR): IACCVIOL Mask */ - -/* BusFault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_BFARVALID_Pos (SCB_CFSR_BUSFAULTSR_Pos + 7U) /*!< SCB CFSR (BFSR): BFARVALID Position */ -#define SCB_CFSR_BFARVALID_Msk (1UL << SCB_CFSR_BFARVALID_Pos) /*!< SCB CFSR (BFSR): BFARVALID Mask */ - -#define SCB_CFSR_LSPERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 5U) /*!< SCB CFSR (BFSR): LSPERR Position */ -#define SCB_CFSR_LSPERR_Msk (1UL << SCB_CFSR_LSPERR_Pos) /*!< SCB CFSR (BFSR): LSPERR Mask */ - -#define SCB_CFSR_STKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 4U) /*!< SCB CFSR (BFSR): STKERR Position */ -#define SCB_CFSR_STKERR_Msk (1UL << SCB_CFSR_STKERR_Pos) /*!< SCB CFSR (BFSR): STKERR Mask */ - -#define SCB_CFSR_UNSTKERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 3U) /*!< SCB CFSR (BFSR): UNSTKERR Position */ -#define SCB_CFSR_UNSTKERR_Msk (1UL << SCB_CFSR_UNSTKERR_Pos) /*!< SCB CFSR (BFSR): UNSTKERR Mask */ - -#define SCB_CFSR_IMPRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 2U) /*!< SCB CFSR (BFSR): IMPRECISERR Position */ -#define SCB_CFSR_IMPRECISERR_Msk (1UL << SCB_CFSR_IMPRECISERR_Pos) /*!< SCB CFSR (BFSR): IMPRECISERR Mask */ - -#define SCB_CFSR_PRECISERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 1U) /*!< SCB CFSR (BFSR): PRECISERR Position */ -#define SCB_CFSR_PRECISERR_Msk (1UL << SCB_CFSR_PRECISERR_Pos) /*!< SCB CFSR (BFSR): PRECISERR Mask */ - -#define SCB_CFSR_IBUSERR_Pos (SCB_CFSR_BUSFAULTSR_Pos + 0U) /*!< SCB CFSR (BFSR): IBUSERR Position */ -#define SCB_CFSR_IBUSERR_Msk (1UL << SCB_CFSR_IBUSERR_Pos) /*!< SCB CFSR (BFSR): IBUSERR Mask */ - -/* UsageFault Status Register (part of SCB Configurable Fault Status Register) */ -#define SCB_CFSR_DIVBYZERO_Pos (SCB_CFSR_USGFAULTSR_Pos + 9U) /*!< SCB CFSR (UFSR): DIVBYZERO Position */ -#define SCB_CFSR_DIVBYZERO_Msk (1UL << SCB_CFSR_DIVBYZERO_Pos) /*!< SCB CFSR (UFSR): DIVBYZERO Mask */ - -#define SCB_CFSR_UNALIGNED_Pos (SCB_CFSR_USGFAULTSR_Pos + 8U) /*!< SCB CFSR (UFSR): UNALIGNED Position */ -#define SCB_CFSR_UNALIGNED_Msk (1UL << SCB_CFSR_UNALIGNED_Pos) /*!< SCB CFSR (UFSR): UNALIGNED Mask */ - -#define SCB_CFSR_NOCP_Pos (SCB_CFSR_USGFAULTSR_Pos + 3U) /*!< SCB CFSR (UFSR): NOCP Position */ -#define SCB_CFSR_NOCP_Msk (1UL << SCB_CFSR_NOCP_Pos) /*!< SCB CFSR (UFSR): NOCP Mask */ - -#define SCB_CFSR_INVPC_Pos (SCB_CFSR_USGFAULTSR_Pos + 2U) /*!< SCB CFSR (UFSR): INVPC Position */ -#define SCB_CFSR_INVPC_Msk (1UL << SCB_CFSR_INVPC_Pos) /*!< SCB CFSR (UFSR): INVPC Mask */ - -#define SCB_CFSR_INVSTATE_Pos (SCB_CFSR_USGFAULTSR_Pos + 1U) /*!< SCB CFSR (UFSR): INVSTATE Position */ -#define SCB_CFSR_INVSTATE_Msk (1UL << SCB_CFSR_INVSTATE_Pos) /*!< SCB CFSR (UFSR): INVSTATE Mask */ - -#define SCB_CFSR_UNDEFINSTR_Pos (SCB_CFSR_USGFAULTSR_Pos + 0U) /*!< SCB CFSR (UFSR): UNDEFINSTR Position */ -#define SCB_CFSR_UNDEFINSTR_Msk (1UL << SCB_CFSR_UNDEFINSTR_Pos) /*!< SCB CFSR (UFSR): UNDEFINSTR Mask */ - -/* SCB Hard Fault Status Register Definitions */ -#define SCB_HFSR_DEBUGEVT_Pos 31U /*!< SCB HFSR: DEBUGEVT Position */ -#define SCB_HFSR_DEBUGEVT_Msk (1UL << SCB_HFSR_DEBUGEVT_Pos) /*!< SCB HFSR: DEBUGEVT Mask */ - -#define SCB_HFSR_FORCED_Pos 30U /*!< SCB HFSR: FORCED Position */ -#define SCB_HFSR_FORCED_Msk (1UL << SCB_HFSR_FORCED_Pos) /*!< SCB HFSR: FORCED Mask */ - -#define SCB_HFSR_VECTTBL_Pos 1U /*!< SCB HFSR: VECTTBL Position */ -#define SCB_HFSR_VECTTBL_Msk (1UL << SCB_HFSR_VECTTBL_Pos) /*!< SCB HFSR: VECTTBL Mask */ - -/* SCB Debug Fault Status Register Definitions */ -#define SCB_DFSR_EXTERNAL_Pos 4U /*!< SCB DFSR: EXTERNAL Position */ -#define SCB_DFSR_EXTERNAL_Msk (1UL << SCB_DFSR_EXTERNAL_Pos) /*!< SCB DFSR: EXTERNAL Mask */ - -#define SCB_DFSR_VCATCH_Pos 3U /*!< SCB DFSR: VCATCH Position */ -#define SCB_DFSR_VCATCH_Msk (1UL << SCB_DFSR_VCATCH_Pos) /*!< SCB DFSR: VCATCH Mask */ - -#define SCB_DFSR_DWTTRAP_Pos 2U /*!< SCB DFSR: DWTTRAP Position */ -#define SCB_DFSR_DWTTRAP_Msk (1UL << SCB_DFSR_DWTTRAP_Pos) /*!< SCB DFSR: DWTTRAP Mask */ - -#define SCB_DFSR_BKPT_Pos 1U /*!< SCB DFSR: BKPT Position */ -#define SCB_DFSR_BKPT_Msk (1UL << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */ - -#define SCB_DFSR_HALTED_Pos 0U /*!< SCB DFSR: HALTED Position */ -#define SCB_DFSR_HALTED_Msk (1UL /*<< SCB_DFSR_HALTED_Pos*/) /*!< SCB DFSR: HALTED Mask */ - -/* SCB Cache Level ID Register Definitions */ -#define SCB_CLIDR_LOUU_Pos 27U /*!< SCB CLIDR: LoUU Position */ -#define SCB_CLIDR_LOUU_Msk (7UL << SCB_CLIDR_LOUU_Pos) /*!< SCB CLIDR: LoUU Mask */ - -#define SCB_CLIDR_LOC_Pos 24U /*!< SCB CLIDR: LoC Position */ -#define SCB_CLIDR_LOC_Msk (7UL << SCB_CLIDR_LOC_Pos) /*!< SCB CLIDR: LoC Mask */ - -/* SCB Cache Type Register Definitions */ -#define SCB_CTR_FORMAT_Pos 29U /*!< SCB CTR: Format Position */ -#define SCB_CTR_FORMAT_Msk (7UL << SCB_CTR_FORMAT_Pos) /*!< SCB CTR: Format Mask */ - -#define SCB_CTR_CWG_Pos 24U /*!< SCB CTR: CWG Position */ -#define SCB_CTR_CWG_Msk (0xFUL << SCB_CTR_CWG_Pos) /*!< SCB CTR: CWG Mask */ - -#define SCB_CTR_ERG_Pos 20U /*!< SCB CTR: ERG Position */ -#define SCB_CTR_ERG_Msk (0xFUL << SCB_CTR_ERG_Pos) /*!< SCB CTR: ERG Mask */ - -#define SCB_CTR_DMINLINE_Pos 16U /*!< SCB CTR: DminLine Position */ -#define SCB_CTR_DMINLINE_Msk (0xFUL << SCB_CTR_DMINLINE_Pos) /*!< SCB CTR: DminLine Mask */ - -#define SCB_CTR_IMINLINE_Pos 0U /*!< SCB CTR: ImInLine Position */ -#define SCB_CTR_IMINLINE_Msk (0xFUL /*<< SCB_CTR_IMINLINE_Pos*/) /*!< SCB CTR: ImInLine Mask */ - -/* SCB Cache Size ID Register Definitions */ -#define SCB_CCSIDR_WT_Pos 31U /*!< SCB CCSIDR: WT Position */ -#define SCB_CCSIDR_WT_Msk (1UL << SCB_CCSIDR_WT_Pos) /*!< SCB CCSIDR: WT Mask */ - -#define SCB_CCSIDR_WB_Pos 30U /*!< SCB CCSIDR: WB Position */ -#define SCB_CCSIDR_WB_Msk (1UL << SCB_CCSIDR_WB_Pos) /*!< SCB CCSIDR: WB Mask */ - -#define SCB_CCSIDR_RA_Pos 29U /*!< SCB CCSIDR: RA Position */ -#define SCB_CCSIDR_RA_Msk (1UL << SCB_CCSIDR_RA_Pos) /*!< SCB CCSIDR: RA Mask */ - -#define SCB_CCSIDR_WA_Pos 28U /*!< SCB CCSIDR: WA Position */ -#define SCB_CCSIDR_WA_Msk (1UL << SCB_CCSIDR_WA_Pos) /*!< SCB CCSIDR: WA Mask */ - -#define SCB_CCSIDR_NUMSETS_Pos 13U /*!< SCB CCSIDR: NumSets Position */ -#define SCB_CCSIDR_NUMSETS_Msk (0x7FFFUL << SCB_CCSIDR_NUMSETS_Pos) /*!< SCB CCSIDR: NumSets Mask */ - -#define SCB_CCSIDR_ASSOCIATIVITY_Pos 3U /*!< SCB CCSIDR: Associativity Position */ -#define SCB_CCSIDR_ASSOCIATIVITY_Msk (0x3FFUL << SCB_CCSIDR_ASSOCIATIVITY_Pos) /*!< SCB CCSIDR: Associativity Mask */ - -#define SCB_CCSIDR_LINESIZE_Pos 0U /*!< SCB CCSIDR: LineSize Position */ -#define SCB_CCSIDR_LINESIZE_Msk (7UL /*<< SCB_CCSIDR_LINESIZE_Pos*/) /*!< SCB CCSIDR: LineSize Mask */ - -/* SCB Cache Size Selection Register Definitions */ -#define SCB_CSSELR_LEVEL_Pos 1U /*!< SCB CSSELR: Level Position */ -#define SCB_CSSELR_LEVEL_Msk (7UL << SCB_CSSELR_LEVEL_Pos) /*!< SCB CSSELR: Level Mask */ - -#define SCB_CSSELR_IND_Pos 0U /*!< SCB CSSELR: InD Position */ -#define SCB_CSSELR_IND_Msk (1UL /*<< SCB_CSSELR_IND_Pos*/) /*!< SCB CSSELR: InD Mask */ - -/* SCB Software Triggered Interrupt Register Definitions */ -#define SCB_STIR_INTID_Pos 0U /*!< SCB STIR: INTID Position */ -#define SCB_STIR_INTID_Msk (0x1FFUL /*<< SCB_STIR_INTID_Pos*/) /*!< SCB STIR: INTID Mask */ - -/* SCB D-Cache Invalidate by Set-way Register Definitions */ -#define SCB_DCISW_WAY_Pos 30U /*!< SCB DCISW: Way Position */ -#define SCB_DCISW_WAY_Msk (3UL << SCB_DCISW_WAY_Pos) /*!< SCB DCISW: Way Mask */ - -#define SCB_DCISW_SET_Pos 5U /*!< SCB DCISW: Set Position */ -#define SCB_DCISW_SET_Msk (0x1FFUL << SCB_DCISW_SET_Pos) /*!< SCB DCISW: Set Mask */ - -/* SCB D-Cache Clean by Set-way Register Definitions */ -#define SCB_DCCSW_WAY_Pos 30U /*!< SCB DCCSW: Way Position */ -#define SCB_DCCSW_WAY_Msk (3UL << SCB_DCCSW_WAY_Pos) /*!< SCB DCCSW: Way Mask */ - -#define SCB_DCCSW_SET_Pos 5U /*!< SCB DCCSW: Set Position */ -#define SCB_DCCSW_SET_Msk (0x1FFUL << SCB_DCCSW_SET_Pos) /*!< SCB DCCSW: Set Mask */ - -/* SCB D-Cache Clean and Invalidate by Set-way Register Definitions */ -#define SCB_DCCISW_WAY_Pos 30U /*!< SCB DCCISW: Way Position */ -#define SCB_DCCISW_WAY_Msk (3UL << SCB_DCCISW_WAY_Pos) /*!< SCB DCCISW: Way Mask */ - -#define SCB_DCCISW_SET_Pos 5U /*!< SCB DCCISW: Set Position */ -#define SCB_DCCISW_SET_Msk (0x1FFUL << SCB_DCCISW_SET_Pos) /*!< SCB DCCISW: Set Mask */ - -/* Instruction Tightly-Coupled Memory Control Register Definitions */ -#define SCB_ITCMCR_SZ_Pos 3U /*!< SCB ITCMCR: SZ Position */ -#define SCB_ITCMCR_SZ_Msk (0xFUL << SCB_ITCMCR_SZ_Pos) /*!< SCB ITCMCR: SZ Mask */ - -#define SCB_ITCMCR_RETEN_Pos 2U /*!< SCB ITCMCR: RETEN Position */ -#define SCB_ITCMCR_RETEN_Msk (1UL << SCB_ITCMCR_RETEN_Pos) /*!< SCB ITCMCR: RETEN Mask */ - -#define SCB_ITCMCR_RMW_Pos 1U /*!< SCB ITCMCR: RMW Position */ -#define SCB_ITCMCR_RMW_Msk (1UL << SCB_ITCMCR_RMW_Pos) /*!< SCB ITCMCR: RMW Mask */ - -#define SCB_ITCMCR_EN_Pos 0U /*!< SCB ITCMCR: EN Position */ -#define SCB_ITCMCR_EN_Msk (1UL /*<< SCB_ITCMCR_EN_Pos*/) /*!< SCB ITCMCR: EN Mask */ - -/* Data Tightly-Coupled Memory Control Register Definitions */ -#define SCB_DTCMCR_SZ_Pos 3U /*!< SCB DTCMCR: SZ Position */ -#define SCB_DTCMCR_SZ_Msk (0xFUL << SCB_DTCMCR_SZ_Pos) /*!< SCB DTCMCR: SZ Mask */ - -#define SCB_DTCMCR_RETEN_Pos 2U /*!< SCB DTCMCR: RETEN Position */ -#define SCB_DTCMCR_RETEN_Msk (1UL << SCB_DTCMCR_RETEN_Pos) /*!< SCB DTCMCR: RETEN Mask */ - -#define SCB_DTCMCR_RMW_Pos 1U /*!< SCB DTCMCR: RMW Position */ -#define SCB_DTCMCR_RMW_Msk (1UL << SCB_DTCMCR_RMW_Pos) /*!< SCB DTCMCR: RMW Mask */ - -#define SCB_DTCMCR_EN_Pos 0U /*!< SCB DTCMCR: EN Position */ -#define SCB_DTCMCR_EN_Msk (1UL /*<< SCB_DTCMCR_EN_Pos*/) /*!< SCB DTCMCR: EN Mask */ - -/* AHBP Control Register Definitions */ -#define SCB_AHBPCR_SZ_Pos 1U /*!< SCB AHBPCR: SZ Position */ -#define SCB_AHBPCR_SZ_Msk (7UL << SCB_AHBPCR_SZ_Pos) /*!< SCB AHBPCR: SZ Mask */ - -#define SCB_AHBPCR_EN_Pos 0U /*!< SCB AHBPCR: EN Position */ -#define SCB_AHBPCR_EN_Msk (1UL /*<< SCB_AHBPCR_EN_Pos*/) /*!< SCB AHBPCR: EN Mask */ - -/* L1 Cache Control Register Definitions */ -#define SCB_CACR_FORCEWT_Pos 2U /*!< SCB CACR: FORCEWT Position */ -#define SCB_CACR_FORCEWT_Msk (1UL << SCB_CACR_FORCEWT_Pos) /*!< SCB CACR: FORCEWT Mask */ - -#define SCB_CACR_ECCEN_Pos 1U /*!< SCB CACR: ECCEN Position */ -#define SCB_CACR_ECCEN_Msk (1UL << SCB_CACR_ECCEN_Pos) /*!< SCB CACR: ECCEN Mask */ - -#define SCB_CACR_SIWT_Pos 0U /*!< SCB CACR: SIWT Position */ -#define SCB_CACR_SIWT_Msk (1UL /*<< SCB_CACR_SIWT_Pos*/) /*!< SCB CACR: SIWT Mask */ - -/* AHBS Control Register Definitions */ -#define SCB_AHBSCR_INITCOUNT_Pos 11U /*!< SCB AHBSCR: INITCOUNT Position */ -#define SCB_AHBSCR_INITCOUNT_Msk (0x1FUL << SCB_AHBPCR_INITCOUNT_Pos) /*!< SCB AHBSCR: INITCOUNT Mask */ - -#define SCB_AHBSCR_TPRI_Pos 2U /*!< SCB AHBSCR: TPRI Position */ -#define SCB_AHBSCR_TPRI_Msk (0x1FFUL << SCB_AHBPCR_TPRI_Pos) /*!< SCB AHBSCR: TPRI Mask */ - -#define SCB_AHBSCR_CTL_Pos 0U /*!< SCB AHBSCR: CTL Position*/ -#define SCB_AHBSCR_CTL_Msk (3UL /*<< SCB_AHBPCR_CTL_Pos*/) /*!< SCB AHBSCR: CTL Mask */ - -/* Auxiliary Bus Fault Status Register Definitions */ -#define SCB_ABFSR_AXIMTYPE_Pos 8U /*!< SCB ABFSR: AXIMTYPE Position*/ -#define SCB_ABFSR_AXIMTYPE_Msk (3UL << SCB_ABFSR_AXIMTYPE_Pos) /*!< SCB ABFSR: AXIMTYPE Mask */ - -#define SCB_ABFSR_EPPB_Pos 4U /*!< SCB ABFSR: EPPB Position*/ -#define SCB_ABFSR_EPPB_Msk (1UL << SCB_ABFSR_EPPB_Pos) /*!< SCB ABFSR: EPPB Mask */ - -#define SCB_ABFSR_AXIM_Pos 3U /*!< SCB ABFSR: AXIM Position*/ -#define SCB_ABFSR_AXIM_Msk (1UL << SCB_ABFSR_AXIM_Pos) /*!< SCB ABFSR: AXIM Mask */ - -#define SCB_ABFSR_AHBP_Pos 2U /*!< SCB ABFSR: AHBP Position*/ -#define SCB_ABFSR_AHBP_Msk (1UL << SCB_ABFSR_AHBP_Pos) /*!< SCB ABFSR: AHBP Mask */ - -#define SCB_ABFSR_DTCM_Pos 1U /*!< SCB ABFSR: DTCM Position*/ -#define SCB_ABFSR_DTCM_Msk (1UL << SCB_ABFSR_DTCM_Pos) /*!< SCB ABFSR: DTCM Mask */ - -#define SCB_ABFSR_ITCM_Pos 0U /*!< SCB ABFSR: ITCM Position*/ -#define SCB_ABFSR_ITCM_Msk (1UL /*<< SCB_ABFSR_ITCM_Pos*/) /*!< SCB ABFSR: ITCM Mask */ - -/*@} end of group CMSIS_SCB */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SCnSCB System Controls not in SCB (SCnSCB) - \brief Type definitions for the System Control and ID Register not in the SCB - @{ - */ - -/** - \brief Structure type to access the System Control and ID Register not in the SCB. - */ -typedef struct -{ - uint32_t RESERVED0[1U]; - __IM uint32_t ICTR; /*!< Offset: 0x004 (R/ ) Interrupt Controller Type Register */ - __IOM uint32_t ACTLR; /*!< Offset: 0x008 (R/W) Auxiliary Control Register */ -} SCnSCB_Type; - -/* Interrupt Controller Type Register Definitions */ -#define SCnSCB_ICTR_INTLINESNUM_Pos 0U /*!< ICTR: INTLINESNUM Position */ -#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL /*<< SCnSCB_ICTR_INTLINESNUM_Pos*/) /*!< ICTR: INTLINESNUM Mask */ - -/* Auxiliary Control Register Definitions */ -#define SCnSCB_ACTLR_DISDYNADD_Pos 26U /*!< ACTLR: DISDYNADD Position */ -#define SCnSCB_ACTLR_DISDYNADD_Msk (1UL << SCnSCB_ACTLR_DISDYNADD_Pos) /*!< ACTLR: DISDYNADD Mask */ - -#define SCnSCB_ACTLR_DISISSCH1_Pos 21U /*!< ACTLR: DISISSCH1 Position */ -#define SCnSCB_ACTLR_DISISSCH1_Msk (0x1FUL << SCnSCB_ACTLR_DISISSCH1_Pos) /*!< ACTLR: DISISSCH1 Mask */ - -#define SCnSCB_ACTLR_DISDI_Pos 16U /*!< ACTLR: DISDI Position */ -#define SCnSCB_ACTLR_DISDI_Msk (0x1FUL << SCnSCB_ACTLR_DISDI_Pos) /*!< ACTLR: DISDI Mask */ - -#define SCnSCB_ACTLR_DISCRITAXIRUR_Pos 15U /*!< ACTLR: DISCRITAXIRUR Position */ -#define SCnSCB_ACTLR_DISCRITAXIRUR_Msk (1UL << SCnSCB_ACTLR_DISCRITAXIRUR_Pos) /*!< ACTLR: DISCRITAXIRUR Mask */ - -#define SCnSCB_ACTLR_DISBTACALLOC_Pos 14U /*!< ACTLR: DISBTACALLOC Position */ -#define SCnSCB_ACTLR_DISBTACALLOC_Msk (1UL << SCnSCB_ACTLR_DISBTACALLOC_Pos) /*!< ACTLR: DISBTACALLOC Mask */ - -#define SCnSCB_ACTLR_DISBTACREAD_Pos 13U /*!< ACTLR: DISBTACREAD Position */ -#define SCnSCB_ACTLR_DISBTACREAD_Msk (1UL << SCnSCB_ACTLR_DISBTACREAD_Pos) /*!< ACTLR: DISBTACREAD Mask */ - -#define SCnSCB_ACTLR_DISITMATBFLUSH_Pos 12U /*!< ACTLR: DISITMATBFLUSH Position */ -#define SCnSCB_ACTLR_DISITMATBFLUSH_Msk (1UL << SCnSCB_ACTLR_DISITMATBFLUSH_Pos) /*!< ACTLR: DISITMATBFLUSH Mask */ - -#define SCnSCB_ACTLR_DISRAMODE_Pos 11U /*!< ACTLR: DISRAMODE Position */ -#define SCnSCB_ACTLR_DISRAMODE_Msk (1UL << SCnSCB_ACTLR_DISRAMODE_Pos) /*!< ACTLR: DISRAMODE Mask */ - -#define SCnSCB_ACTLR_FPEXCODIS_Pos 10U /*!< ACTLR: FPEXCODIS Position */ -#define SCnSCB_ACTLR_FPEXCODIS_Msk (1UL << SCnSCB_ACTLR_FPEXCODIS_Pos) /*!< ACTLR: FPEXCODIS Mask */ - -#define SCnSCB_ACTLR_DISFOLD_Pos 2U /*!< ACTLR: DISFOLD Position */ -#define SCnSCB_ACTLR_DISFOLD_Msk (1UL << SCnSCB_ACTLR_DISFOLD_Pos) /*!< ACTLR: DISFOLD Mask */ - -#define SCnSCB_ACTLR_DISMCYCINT_Pos 0U /*!< ACTLR: DISMCYCINT Position */ -#define SCnSCB_ACTLR_DISMCYCINT_Msk (1UL /*<< SCnSCB_ACTLR_DISMCYCINT_Pos*/) /*!< ACTLR: DISMCYCINT Mask */ - -/*@} end of group CMSIS_SCnotSCB */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_SysTick System Tick Timer (SysTick) - \brief Type definitions for the System Timer Registers. - @{ - */ - -/** - \brief Structure type to access the System Timer (SysTick). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */ - __IOM uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */ - __IOM uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */ - __IM uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */ -} SysTick_Type; - -/* SysTick Control / Status Register Definitions */ -#define SysTick_CTRL_COUNTFLAG_Pos 16U /*!< SysTick CTRL: COUNTFLAG Position */ -#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */ - -#define SysTick_CTRL_CLKSOURCE_Pos 2U /*!< SysTick CTRL: CLKSOURCE Position */ -#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */ - -#define SysTick_CTRL_TICKINT_Pos 1U /*!< SysTick CTRL: TICKINT Position */ -#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */ - -#define SysTick_CTRL_ENABLE_Pos 0U /*!< SysTick CTRL: ENABLE Position */ -#define SysTick_CTRL_ENABLE_Msk (1UL /*<< SysTick_CTRL_ENABLE_Pos*/) /*!< SysTick CTRL: ENABLE Mask */ - -/* SysTick Reload Register Definitions */ -#define SysTick_LOAD_RELOAD_Pos 0U /*!< SysTick LOAD: RELOAD Position */ -#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL /*<< SysTick_LOAD_RELOAD_Pos*/) /*!< SysTick LOAD: RELOAD Mask */ - -/* SysTick Current Register Definitions */ -#define SysTick_VAL_CURRENT_Pos 0U /*!< SysTick VAL: CURRENT Position */ -#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL /*<< SysTick_VAL_CURRENT_Pos*/) /*!< SysTick VAL: CURRENT Mask */ - -/* SysTick Calibration Register Definitions */ -#define SysTick_CALIB_NOREF_Pos 31U /*!< SysTick CALIB: NOREF Position */ -#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */ - -#define SysTick_CALIB_SKEW_Pos 30U /*!< SysTick CALIB: SKEW Position */ -#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */ - -#define SysTick_CALIB_TENMS_Pos 0U /*!< SysTick CALIB: TENMS Position */ -#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL /*<< SysTick_CALIB_TENMS_Pos*/) /*!< SysTick CALIB: TENMS Mask */ - -/*@} end of group CMSIS_SysTick */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_ITM Instrumentation Trace Macrocell (ITM) - \brief Type definitions for the Instrumentation Trace Macrocell (ITM) - @{ - */ - -/** - \brief Structure type to access the Instrumentation Trace Macrocell Register (ITM). - */ -typedef struct -{ - __OM union - { - __OM uint8_t u8; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 8-bit */ - __OM uint16_t u16; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 16-bit */ - __OM uint32_t u32; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 32-bit */ - } PORT [32U]; /*!< Offset: 0x000 ( /W) ITM Stimulus Port Registers */ - uint32_t RESERVED0[864U]; - __IOM uint32_t TER; /*!< Offset: 0xE00 (R/W) ITM Trace Enable Register */ - uint32_t RESERVED1[15U]; - __IOM uint32_t TPR; /*!< Offset: 0xE40 (R/W) ITM Trace Privilege Register */ - uint32_t RESERVED2[15U]; - __IOM uint32_t TCR; /*!< Offset: 0xE80 (R/W) ITM Trace Control Register */ - uint32_t RESERVED3[32U]; - uint32_t RESERVED4[43U]; - __OM uint32_t LAR; /*!< Offset: 0xFB0 ( /W) ITM Lock Access Register */ - __IM uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) ITM Lock Status Register */ - uint32_t RESERVED5[6U]; - __IM uint32_t PID4; /*!< Offset: 0xFD0 (R/ ) ITM Peripheral Identification Register #4 */ - __IM uint32_t PID5; /*!< Offset: 0xFD4 (R/ ) ITM Peripheral Identification Register #5 */ - __IM uint32_t PID6; /*!< Offset: 0xFD8 (R/ ) ITM Peripheral Identification Register #6 */ - __IM uint32_t PID7; /*!< Offset: 0xFDC (R/ ) ITM Peripheral Identification Register #7 */ - __IM uint32_t PID0; /*!< Offset: 0xFE0 (R/ ) ITM Peripheral Identification Register #0 */ - __IM uint32_t PID1; /*!< Offset: 0xFE4 (R/ ) ITM Peripheral Identification Register #1 */ - __IM uint32_t PID2; /*!< Offset: 0xFE8 (R/ ) ITM Peripheral Identification Register #2 */ - __IM uint32_t PID3; /*!< Offset: 0xFEC (R/ ) ITM Peripheral Identification Register #3 */ - __IM uint32_t CID0; /*!< Offset: 0xFF0 (R/ ) ITM Component Identification Register #0 */ - __IM uint32_t CID1; /*!< Offset: 0xFF4 (R/ ) ITM Component Identification Register #1 */ - __IM uint32_t CID2; /*!< Offset: 0xFF8 (R/ ) ITM Component Identification Register #2 */ - __IM uint32_t CID3; /*!< Offset: 0xFFC (R/ ) ITM Component Identification Register #3 */ -} ITM_Type; - -/* ITM Trace Privilege Register Definitions */ -#define ITM_TPR_PRIVMASK_Pos 0U /*!< ITM TPR: PRIVMASK Position */ -#define ITM_TPR_PRIVMASK_Msk (0xFFFFFFFFUL /*<< ITM_TPR_PRIVMASK_Pos*/) /*!< ITM TPR: PRIVMASK Mask */ - -/* ITM Trace Control Register Definitions */ -#define ITM_TCR_BUSY_Pos 23U /*!< ITM TCR: BUSY Position */ -#define ITM_TCR_BUSY_Msk (1UL << ITM_TCR_BUSY_Pos) /*!< ITM TCR: BUSY Mask */ - -#define ITM_TCR_TraceBusID_Pos 16U /*!< ITM TCR: ATBID Position */ -#define ITM_TCR_TraceBusID_Msk (0x7FUL << ITM_TCR_TraceBusID_Pos) /*!< ITM TCR: ATBID Mask */ - -#define ITM_TCR_GTSFREQ_Pos 10U /*!< ITM TCR: Global timestamp frequency Position */ -#define ITM_TCR_GTSFREQ_Msk (3UL << ITM_TCR_GTSFREQ_Pos) /*!< ITM TCR: Global timestamp frequency Mask */ - -#define ITM_TCR_TSPrescale_Pos 8U /*!< ITM TCR: TSPrescale Position */ -#define ITM_TCR_TSPrescale_Msk (3UL << ITM_TCR_TSPrescale_Pos) /*!< ITM TCR: TSPrescale Mask */ - -#define ITM_TCR_SWOENA_Pos 4U /*!< ITM TCR: SWOENA Position */ -#define ITM_TCR_SWOENA_Msk (1UL << ITM_TCR_SWOENA_Pos) /*!< ITM TCR: SWOENA Mask */ - -#define ITM_TCR_DWTENA_Pos 3U /*!< ITM TCR: DWTENA Position */ -#define ITM_TCR_DWTENA_Msk (1UL << ITM_TCR_DWTENA_Pos) /*!< ITM TCR: DWTENA Mask */ - -#define ITM_TCR_SYNCENA_Pos 2U /*!< ITM TCR: SYNCENA Position */ -#define ITM_TCR_SYNCENA_Msk (1UL << ITM_TCR_SYNCENA_Pos) /*!< ITM TCR: SYNCENA Mask */ - -#define ITM_TCR_TSENA_Pos 1U /*!< ITM TCR: TSENA Position */ -#define ITM_TCR_TSENA_Msk (1UL << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */ - -#define ITM_TCR_ITMENA_Pos 0U /*!< ITM TCR: ITM Enable bit Position */ -#define ITM_TCR_ITMENA_Msk (1UL /*<< ITM_TCR_ITMENA_Pos*/) /*!< ITM TCR: ITM Enable bit Mask */ - -/* ITM Lock Status Register Definitions */ -#define ITM_LSR_ByteAcc_Pos 2U /*!< ITM LSR: ByteAcc Position */ -#define ITM_LSR_ByteAcc_Msk (1UL << ITM_LSR_ByteAcc_Pos) /*!< ITM LSR: ByteAcc Mask */ - -#define ITM_LSR_Access_Pos 1U /*!< ITM LSR: Access Position */ -#define ITM_LSR_Access_Msk (1UL << ITM_LSR_Access_Pos) /*!< ITM LSR: Access Mask */ - -#define ITM_LSR_Present_Pos 0U /*!< ITM LSR: Present Position */ -#define ITM_LSR_Present_Msk (1UL /*<< ITM_LSR_Present_Pos*/) /*!< ITM LSR: Present Mask */ - -/*@}*/ /* end of group CMSIS_ITM */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_DWT Data Watchpoint and Trace (DWT) - \brief Type definitions for the Data Watchpoint and Trace (DWT) - @{ - */ - -/** - \brief Structure type to access the Data Watchpoint and Trace Register (DWT). - */ -typedef struct -{ - __IOM uint32_t CTRL; /*!< Offset: 0x000 (R/W) Control Register */ - __IOM uint32_t CYCCNT; /*!< Offset: 0x004 (R/W) Cycle Count Register */ - __IOM uint32_t CPICNT; /*!< Offset: 0x008 (R/W) CPI Count Register */ - __IOM uint32_t EXCCNT; /*!< Offset: 0x00C (R/W) Exception Overhead Count Register */ - __IOM uint32_t SLEEPCNT; /*!< Offset: 0x010 (R/W) Sleep Count Register */ - __IOM uint32_t LSUCNT; /*!< Offset: 0x014 (R/W) LSU Count Register */ - __IOM uint32_t FOLDCNT; /*!< Offset: 0x018 (R/W) Folded-instruction Count Register */ - __IM uint32_t PCSR; /*!< Offset: 0x01C (R/ ) Program Counter Sample Register */ - __IOM uint32_t COMP0; /*!< Offset: 0x020 (R/W) Comparator Register 0 */ - __IOM uint32_t MASK0; /*!< Offset: 0x024 (R/W) Mask Register 0 */ - __IOM uint32_t FUNCTION0; /*!< Offset: 0x028 (R/W) Function Register 0 */ - uint32_t RESERVED0[1U]; - __IOM uint32_t COMP1; /*!< Offset: 0x030 (R/W) Comparator Register 1 */ - __IOM uint32_t MASK1; /*!< Offset: 0x034 (R/W) Mask Register 1 */ - __IOM uint32_t FUNCTION1; /*!< Offset: 0x038 (R/W) Function Register 1 */ - uint32_t RESERVED1[1U]; - __IOM uint32_t COMP2; /*!< Offset: 0x040 (R/W) Comparator Register 2 */ - __IOM uint32_t MASK2; /*!< Offset: 0x044 (R/W) Mask Register 2 */ - __IOM uint32_t FUNCTION2; /*!< Offset: 0x048 (R/W) Function Register 2 */ - uint32_t RESERVED2[1U]; - __IOM uint32_t COMP3; /*!< Offset: 0x050 (R/W) Comparator Register 3 */ - __IOM uint32_t MASK3; /*!< Offset: 0x054 (R/W) Mask Register 3 */ - __IOM uint32_t FUNCTION3; /*!< Offset: 0x058 (R/W) Function Register 3 */ - uint32_t RESERVED3[981U]; - __OM uint32_t LAR; /*!< Offset: 0xFB0 ( W) Lock Access Register */ - __IM uint32_t LSR; /*!< Offset: 0xFB4 (R ) Lock Status Register */ -} DWT_Type; - -/* DWT Control Register Definitions */ -#define DWT_CTRL_NUMCOMP_Pos 28U /*!< DWT CTRL: NUMCOMP Position */ -#define DWT_CTRL_NUMCOMP_Msk (0xFUL << DWT_CTRL_NUMCOMP_Pos) /*!< DWT CTRL: NUMCOMP Mask */ - -#define DWT_CTRL_NOTRCPKT_Pos 27U /*!< DWT CTRL: NOTRCPKT Position */ -#define DWT_CTRL_NOTRCPKT_Msk (0x1UL << DWT_CTRL_NOTRCPKT_Pos) /*!< DWT CTRL: NOTRCPKT Mask */ - -#define DWT_CTRL_NOEXTTRIG_Pos 26U /*!< DWT CTRL: NOEXTTRIG Position */ -#define DWT_CTRL_NOEXTTRIG_Msk (0x1UL << DWT_CTRL_NOEXTTRIG_Pos) /*!< DWT CTRL: NOEXTTRIG Mask */ - -#define DWT_CTRL_NOCYCCNT_Pos 25U /*!< DWT CTRL: NOCYCCNT Position */ -#define DWT_CTRL_NOCYCCNT_Msk (0x1UL << DWT_CTRL_NOCYCCNT_Pos) /*!< DWT CTRL: NOCYCCNT Mask */ - -#define DWT_CTRL_NOPRFCNT_Pos 24U /*!< DWT CTRL: NOPRFCNT Position */ -#define DWT_CTRL_NOPRFCNT_Msk (0x1UL << DWT_CTRL_NOPRFCNT_Pos) /*!< DWT CTRL: NOPRFCNT Mask */ - -#define DWT_CTRL_CYCEVTENA_Pos 22U /*!< DWT CTRL: CYCEVTENA Position */ -#define DWT_CTRL_CYCEVTENA_Msk (0x1UL << DWT_CTRL_CYCEVTENA_Pos) /*!< DWT CTRL: CYCEVTENA Mask */ - -#define DWT_CTRL_FOLDEVTENA_Pos 21U /*!< DWT CTRL: FOLDEVTENA Position */ -#define DWT_CTRL_FOLDEVTENA_Msk (0x1UL << DWT_CTRL_FOLDEVTENA_Pos) /*!< DWT CTRL: FOLDEVTENA Mask */ - -#define DWT_CTRL_LSUEVTENA_Pos 20U /*!< DWT CTRL: LSUEVTENA Position */ -#define DWT_CTRL_LSUEVTENA_Msk (0x1UL << DWT_CTRL_LSUEVTENA_Pos) /*!< DWT CTRL: LSUEVTENA Mask */ - -#define DWT_CTRL_SLEEPEVTENA_Pos 19U /*!< DWT CTRL: SLEEPEVTENA Position */ -#define DWT_CTRL_SLEEPEVTENA_Msk (0x1UL << DWT_CTRL_SLEEPEVTENA_Pos) /*!< DWT CTRL: SLEEPEVTENA Mask */ - -#define DWT_CTRL_EXCEVTENA_Pos 18U /*!< DWT CTRL: EXCEVTENA Position */ -#define DWT_CTRL_EXCEVTENA_Msk (0x1UL << DWT_CTRL_EXCEVTENA_Pos) /*!< DWT CTRL: EXCEVTENA Mask */ - -#define DWT_CTRL_CPIEVTENA_Pos 17U /*!< DWT CTRL: CPIEVTENA Position */ -#define DWT_CTRL_CPIEVTENA_Msk (0x1UL << DWT_CTRL_CPIEVTENA_Pos) /*!< DWT CTRL: CPIEVTENA Mask */ - -#define DWT_CTRL_EXCTRCENA_Pos 16U /*!< DWT CTRL: EXCTRCENA Position */ -#define DWT_CTRL_EXCTRCENA_Msk (0x1UL << DWT_CTRL_EXCTRCENA_Pos) /*!< DWT CTRL: EXCTRCENA Mask */ - -#define DWT_CTRL_PCSAMPLENA_Pos 12U /*!< DWT CTRL: PCSAMPLENA Position */ -#define DWT_CTRL_PCSAMPLENA_Msk (0x1UL << DWT_CTRL_PCSAMPLENA_Pos) /*!< DWT CTRL: PCSAMPLENA Mask */ - -#define DWT_CTRL_SYNCTAP_Pos 10U /*!< DWT CTRL: SYNCTAP Position */ -#define DWT_CTRL_SYNCTAP_Msk (0x3UL << DWT_CTRL_SYNCTAP_Pos) /*!< DWT CTRL: SYNCTAP Mask */ - -#define DWT_CTRL_CYCTAP_Pos 9U /*!< DWT CTRL: CYCTAP Position */ -#define DWT_CTRL_CYCTAP_Msk (0x1UL << DWT_CTRL_CYCTAP_Pos) /*!< DWT CTRL: CYCTAP Mask */ - -#define DWT_CTRL_POSTINIT_Pos 5U /*!< DWT CTRL: POSTINIT Position */ -#define DWT_CTRL_POSTINIT_Msk (0xFUL << DWT_CTRL_POSTINIT_Pos) /*!< DWT CTRL: POSTINIT Mask */ - -#define DWT_CTRL_POSTPRESET_Pos 1U /*!< DWT CTRL: POSTPRESET Position */ -#define DWT_CTRL_POSTPRESET_Msk (0xFUL << DWT_CTRL_POSTPRESET_Pos) /*!< DWT CTRL: POSTPRESET Mask */ - -#define DWT_CTRL_CYCCNTENA_Pos 0U /*!< DWT CTRL: CYCCNTENA Position */ -#define DWT_CTRL_CYCCNTENA_Msk (0x1UL /*<< DWT_CTRL_CYCCNTENA_Pos*/) /*!< DWT CTRL: CYCCNTENA Mask */ - -/* DWT CPI Count Register Definitions */ -#define DWT_CPICNT_CPICNT_Pos 0U /*!< DWT CPICNT: CPICNT Position */ -#define DWT_CPICNT_CPICNT_Msk (0xFFUL /*<< DWT_CPICNT_CPICNT_Pos*/) /*!< DWT CPICNT: CPICNT Mask */ - -/* DWT Exception Overhead Count Register Definitions */ -#define DWT_EXCCNT_EXCCNT_Pos 0U /*!< DWT EXCCNT: EXCCNT Position */ -#define DWT_EXCCNT_EXCCNT_Msk (0xFFUL /*<< DWT_EXCCNT_EXCCNT_Pos*/) /*!< DWT EXCCNT: EXCCNT Mask */ - -/* DWT Sleep Count Register Definitions */ -#define DWT_SLEEPCNT_SLEEPCNT_Pos 0U /*!< DWT SLEEPCNT: SLEEPCNT Position */ -#define DWT_SLEEPCNT_SLEEPCNT_Msk (0xFFUL /*<< DWT_SLEEPCNT_SLEEPCNT_Pos*/) /*!< DWT SLEEPCNT: SLEEPCNT Mask */ - -/* DWT LSU Count Register Definitions */ -#define DWT_LSUCNT_LSUCNT_Pos 0U /*!< DWT LSUCNT: LSUCNT Position */ -#define DWT_LSUCNT_LSUCNT_Msk (0xFFUL /*<< DWT_LSUCNT_LSUCNT_Pos*/) /*!< DWT LSUCNT: LSUCNT Mask */ - -/* DWT Folded-instruction Count Register Definitions */ -#define DWT_FOLDCNT_FOLDCNT_Pos 0U /*!< DWT FOLDCNT: FOLDCNT Position */ -#define DWT_FOLDCNT_FOLDCNT_Msk (0xFFUL /*<< DWT_FOLDCNT_FOLDCNT_Pos*/) /*!< DWT FOLDCNT: FOLDCNT Mask */ - -/* DWT Comparator Mask Register Definitions */ -#define DWT_MASK_MASK_Pos 0U /*!< DWT MASK: MASK Position */ -#define DWT_MASK_MASK_Msk (0x1FUL /*<< DWT_MASK_MASK_Pos*/) /*!< DWT MASK: MASK Mask */ - -/* DWT Comparator Function Register Definitions */ -#define DWT_FUNCTION_MATCHED_Pos 24U /*!< DWT FUNCTION: MATCHED Position */ -#define DWT_FUNCTION_MATCHED_Msk (0x1UL << DWT_FUNCTION_MATCHED_Pos) /*!< DWT FUNCTION: MATCHED Mask */ - -#define DWT_FUNCTION_DATAVADDR1_Pos 16U /*!< DWT FUNCTION: DATAVADDR1 Position */ -#define DWT_FUNCTION_DATAVADDR1_Msk (0xFUL << DWT_FUNCTION_DATAVADDR1_Pos) /*!< DWT FUNCTION: DATAVADDR1 Mask */ - -#define DWT_FUNCTION_DATAVADDR0_Pos 12U /*!< DWT FUNCTION: DATAVADDR0 Position */ -#define DWT_FUNCTION_DATAVADDR0_Msk (0xFUL << DWT_FUNCTION_DATAVADDR0_Pos) /*!< DWT FUNCTION: DATAVADDR0 Mask */ - -#define DWT_FUNCTION_DATAVSIZE_Pos 10U /*!< DWT FUNCTION: DATAVSIZE Position */ -#define DWT_FUNCTION_DATAVSIZE_Msk (0x3UL << DWT_FUNCTION_DATAVSIZE_Pos) /*!< DWT FUNCTION: DATAVSIZE Mask */ - -#define DWT_FUNCTION_LNK1ENA_Pos 9U /*!< DWT FUNCTION: LNK1ENA Position */ -#define DWT_FUNCTION_LNK1ENA_Msk (0x1UL << DWT_FUNCTION_LNK1ENA_Pos) /*!< DWT FUNCTION: LNK1ENA Mask */ - -#define DWT_FUNCTION_DATAVMATCH_Pos 8U /*!< DWT FUNCTION: DATAVMATCH Position */ -#define DWT_FUNCTION_DATAVMATCH_Msk (0x1UL << DWT_FUNCTION_DATAVMATCH_Pos) /*!< DWT FUNCTION: DATAVMATCH Mask */ - -#define DWT_FUNCTION_CYCMATCH_Pos 7U /*!< DWT FUNCTION: CYCMATCH Position */ -#define DWT_FUNCTION_CYCMATCH_Msk (0x1UL << DWT_FUNCTION_CYCMATCH_Pos) /*!< DWT FUNCTION: CYCMATCH Mask */ - -#define DWT_FUNCTION_EMITRANGE_Pos 5U /*!< DWT FUNCTION: EMITRANGE Position */ -#define DWT_FUNCTION_EMITRANGE_Msk (0x1UL << DWT_FUNCTION_EMITRANGE_Pos) /*!< DWT FUNCTION: EMITRANGE Mask */ - -#define DWT_FUNCTION_FUNCTION_Pos 0U /*!< DWT FUNCTION: FUNCTION Position */ -#define DWT_FUNCTION_FUNCTION_Msk (0xFUL /*<< DWT_FUNCTION_FUNCTION_Pos*/) /*!< DWT FUNCTION: FUNCTION Mask */ - -/*@}*/ /* end of group CMSIS_DWT */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_TPI Trace Port Interface (TPI) - \brief Type definitions for the Trace Port Interface (TPI) - @{ - */ - -/** - \brief Structure type to access the Trace Port Interface Register (TPI). - */ -typedef struct -{ - __IM uint32_t SSPSR; /*!< Offset: 0x000 (R/ ) Supported Parallel Port Size Register */ - __IOM uint32_t CSPSR; /*!< Offset: 0x004 (R/W) Current Parallel Port Size Register */ - uint32_t RESERVED0[2U]; - __IOM uint32_t ACPR; /*!< Offset: 0x010 (R/W) Asynchronous Clock Prescaler Register */ - uint32_t RESERVED1[55U]; - __IOM uint32_t SPPR; /*!< Offset: 0x0F0 (R/W) Selected Pin Protocol Register */ - uint32_t RESERVED2[131U]; - __IM uint32_t FFSR; /*!< Offset: 0x300 (R/ ) Formatter and Flush Status Register */ - __IOM uint32_t FFCR; /*!< Offset: 0x304 (R/W) Formatter and Flush Control Register */ - __IM uint32_t FSCR; /*!< Offset: 0x308 (R/ ) Formatter Synchronization Counter Register */ - uint32_t RESERVED3[759U]; - __IM uint32_t TRIGGER; /*!< Offset: 0xEE8 (R/ ) TRIGGER Register */ - __IM uint32_t FIFO0; /*!< Offset: 0xEEC (R/ ) Integration ETM Data */ - __IM uint32_t ITATBCTR2; /*!< Offset: 0xEF0 (R/ ) ITATBCTR2 */ - uint32_t RESERVED4[1U]; - __IM uint32_t ITATBCTR0; /*!< Offset: 0xEF8 (R/ ) ITATBCTR0 */ - __IM uint32_t FIFO1; /*!< Offset: 0xEFC (R/ ) Integration ITM Data */ - __IOM uint32_t ITCTRL; /*!< Offset: 0xF00 (R/W) Integration Mode Control */ - uint32_t RESERVED5[39U]; - __IOM uint32_t CLAIMSET; /*!< Offset: 0xFA0 (R/W) Claim tag set */ - __IOM uint32_t CLAIMCLR; /*!< Offset: 0xFA4 (R/W) Claim tag clear */ - uint32_t RESERVED7[8U]; - __IM uint32_t DEVID; /*!< Offset: 0xFC8 (R/ ) TPIU_DEVID */ - __IM uint32_t DEVTYPE; /*!< Offset: 0xFCC (R/ ) TPIU_DEVTYPE */ -} TPI_Type; - -/* TPI Asynchronous Clock Prescaler Register Definitions */ -#define TPI_ACPR_PRESCALER_Pos 0U /*!< TPI ACPR: PRESCALER Position */ -#define TPI_ACPR_PRESCALER_Msk (0x1FFFUL /*<< TPI_ACPR_PRESCALER_Pos*/) /*!< TPI ACPR: PRESCALER Mask */ - -/* TPI Selected Pin Protocol Register Definitions */ -#define TPI_SPPR_TXMODE_Pos 0U /*!< TPI SPPR: TXMODE Position */ -#define TPI_SPPR_TXMODE_Msk (0x3UL /*<< TPI_SPPR_TXMODE_Pos*/) /*!< TPI SPPR: TXMODE Mask */ - -/* TPI Formatter and Flush Status Register Definitions */ -#define TPI_FFSR_FtNonStop_Pos 3U /*!< TPI FFSR: FtNonStop Position */ -#define TPI_FFSR_FtNonStop_Msk (0x1UL << TPI_FFSR_FtNonStop_Pos) /*!< TPI FFSR: FtNonStop Mask */ - -#define TPI_FFSR_TCPresent_Pos 2U /*!< TPI FFSR: TCPresent Position */ -#define TPI_FFSR_TCPresent_Msk (0x1UL << TPI_FFSR_TCPresent_Pos) /*!< TPI FFSR: TCPresent Mask */ - -#define TPI_FFSR_FtStopped_Pos 1U /*!< TPI FFSR: FtStopped Position */ -#define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */ - -#define TPI_FFSR_FlInProg_Pos 0U /*!< TPI FFSR: FlInProg Position */ -#define TPI_FFSR_FlInProg_Msk (0x1UL /*<< TPI_FFSR_FlInProg_Pos*/) /*!< TPI FFSR: FlInProg Mask */ - -/* TPI Formatter and Flush Control Register Definitions */ -#define TPI_FFCR_TrigIn_Pos 8U /*!< TPI FFCR: TrigIn Position */ -#define TPI_FFCR_TrigIn_Msk (0x1UL << TPI_FFCR_TrigIn_Pos) /*!< TPI FFCR: TrigIn Mask */ - -#define TPI_FFCR_EnFCont_Pos 1U /*!< TPI FFCR: EnFCont Position */ -#define TPI_FFCR_EnFCont_Msk (0x1UL << TPI_FFCR_EnFCont_Pos) /*!< TPI FFCR: EnFCont Mask */ - -/* TPI TRIGGER Register Definitions */ -#define TPI_TRIGGER_TRIGGER_Pos 0U /*!< TPI TRIGGER: TRIGGER Position */ -#define TPI_TRIGGER_TRIGGER_Msk (0x1UL /*<< TPI_TRIGGER_TRIGGER_Pos*/) /*!< TPI TRIGGER: TRIGGER Mask */ - -/* TPI Integration ETM Data Register Definitions (FIFO0) */ -#define TPI_FIFO0_ITM_ATVALID_Pos 29U /*!< TPI FIFO0: ITM_ATVALID Position */ -#define TPI_FIFO0_ITM_ATVALID_Msk (0x1UL << TPI_FIFO0_ITM_ATVALID_Pos) /*!< TPI FIFO0: ITM_ATVALID Mask */ - -#define TPI_FIFO0_ITM_bytecount_Pos 27U /*!< TPI FIFO0: ITM_bytecount Position */ -#define TPI_FIFO0_ITM_bytecount_Msk (0x3UL << TPI_FIFO0_ITM_bytecount_Pos) /*!< TPI FIFO0: ITM_bytecount Mask */ - -#define TPI_FIFO0_ETM_ATVALID_Pos 26U /*!< TPI FIFO0: ETM_ATVALID Position */ -#define TPI_FIFO0_ETM_ATVALID_Msk (0x1UL << TPI_FIFO0_ETM_ATVALID_Pos) /*!< TPI FIFO0: ETM_ATVALID Mask */ - -#define TPI_FIFO0_ETM_bytecount_Pos 24U /*!< TPI FIFO0: ETM_bytecount Position */ -#define TPI_FIFO0_ETM_bytecount_Msk (0x3UL << TPI_FIFO0_ETM_bytecount_Pos) /*!< TPI FIFO0: ETM_bytecount Mask */ - -#define TPI_FIFO0_ETM2_Pos 16U /*!< TPI FIFO0: ETM2 Position */ -#define TPI_FIFO0_ETM2_Msk (0xFFUL << TPI_FIFO0_ETM2_Pos) /*!< TPI FIFO0: ETM2 Mask */ - -#define TPI_FIFO0_ETM1_Pos 8U /*!< TPI FIFO0: ETM1 Position */ -#define TPI_FIFO0_ETM1_Msk (0xFFUL << TPI_FIFO0_ETM1_Pos) /*!< TPI FIFO0: ETM1 Mask */ - -#define TPI_FIFO0_ETM0_Pos 0U /*!< TPI FIFO0: ETM0 Position */ -#define TPI_FIFO0_ETM0_Msk (0xFFUL /*<< TPI_FIFO0_ETM0_Pos*/) /*!< TPI FIFO0: ETM0 Mask */ - -/* TPI ITATBCTR2 Register Definitions */ -#define TPI_ITATBCTR2_ATREADY2_Pos 0U /*!< TPI ITATBCTR2: ATREADY2 Position */ -#define TPI_ITATBCTR2_ATREADY2_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY2_Pos*/) /*!< TPI ITATBCTR2: ATREADY2 Mask */ - -#define TPI_ITATBCTR2_ATREADY1_Pos 0U /*!< TPI ITATBCTR2: ATREADY1 Position */ -#define TPI_ITATBCTR2_ATREADY1_Msk (0x1UL /*<< TPI_ITATBCTR2_ATREADY1_Pos*/) /*!< TPI ITATBCTR2: ATREADY1 Mask */ - -/* TPI Integration ITM Data Register Definitions (FIFO1) */ -#define TPI_FIFO1_ITM_ATVALID_Pos 29U /*!< TPI FIFO1: ITM_ATVALID Position */ -#define TPI_FIFO1_ITM_ATVALID_Msk (0x1UL << TPI_FIFO1_ITM_ATVALID_Pos) /*!< TPI FIFO1: ITM_ATVALID Mask */ - -#define TPI_FIFO1_ITM_bytecount_Pos 27U /*!< TPI FIFO1: ITM_bytecount Position */ -#define TPI_FIFO1_ITM_bytecount_Msk (0x3UL << TPI_FIFO1_ITM_bytecount_Pos) /*!< TPI FIFO1: ITM_bytecount Mask */ - -#define TPI_FIFO1_ETM_ATVALID_Pos 26U /*!< TPI FIFO1: ETM_ATVALID Position */ -#define TPI_FIFO1_ETM_ATVALID_Msk (0x1UL << TPI_FIFO1_ETM_ATVALID_Pos) /*!< TPI FIFO1: ETM_ATVALID Mask */ - -#define TPI_FIFO1_ETM_bytecount_Pos 24U /*!< TPI FIFO1: ETM_bytecount Position */ -#define TPI_FIFO1_ETM_bytecount_Msk (0x3UL << TPI_FIFO1_ETM_bytecount_Pos) /*!< TPI FIFO1: ETM_bytecount Mask */ - -#define TPI_FIFO1_ITM2_Pos 16U /*!< TPI FIFO1: ITM2 Position */ -#define TPI_FIFO1_ITM2_Msk (0xFFUL << TPI_FIFO1_ITM2_Pos) /*!< TPI FIFO1: ITM2 Mask */ - -#define TPI_FIFO1_ITM1_Pos 8U /*!< TPI FIFO1: ITM1 Position */ -#define TPI_FIFO1_ITM1_Msk (0xFFUL << TPI_FIFO1_ITM1_Pos) /*!< TPI FIFO1: ITM1 Mask */ - -#define TPI_FIFO1_ITM0_Pos 0U /*!< TPI FIFO1: ITM0 Position */ -#define TPI_FIFO1_ITM0_Msk (0xFFUL /*<< TPI_FIFO1_ITM0_Pos*/) /*!< TPI FIFO1: ITM0 Mask */ - -/* TPI ITATBCTR0 Register Definitions */ -#define TPI_ITATBCTR0_ATREADY2_Pos 0U /*!< TPI ITATBCTR0: ATREADY2 Position */ -#define TPI_ITATBCTR0_ATREADY2_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY2_Pos*/) /*!< TPI ITATBCTR0: ATREADY2 Mask */ - -#define TPI_ITATBCTR0_ATREADY1_Pos 0U /*!< TPI ITATBCTR0: ATREADY1 Position */ -#define TPI_ITATBCTR0_ATREADY1_Msk (0x1UL /*<< TPI_ITATBCTR0_ATREADY1_Pos*/) /*!< TPI ITATBCTR0: ATREADY1 Mask */ - -/* TPI Integration Mode Control Register Definitions */ -#define TPI_ITCTRL_Mode_Pos 0U /*!< TPI ITCTRL: Mode Position */ -#define TPI_ITCTRL_Mode_Msk (0x3UL /*<< TPI_ITCTRL_Mode_Pos*/) /*!< TPI ITCTRL: Mode Mask */ - -/* TPI DEVID Register Definitions */ -#define TPI_DEVID_NRZVALID_Pos 11U /*!< TPI DEVID: NRZVALID Position */ -#define TPI_DEVID_NRZVALID_Msk (0x1UL << TPI_DEVID_NRZVALID_Pos) /*!< TPI DEVID: NRZVALID Mask */ - -#define TPI_DEVID_MANCVALID_Pos 10U /*!< TPI DEVID: MANCVALID Position */ -#define TPI_DEVID_MANCVALID_Msk (0x1UL << TPI_DEVID_MANCVALID_Pos) /*!< TPI DEVID: MANCVALID Mask */ - -#define TPI_DEVID_PTINVALID_Pos 9U /*!< TPI DEVID: PTINVALID Position */ -#define TPI_DEVID_PTINVALID_Msk (0x1UL << TPI_DEVID_PTINVALID_Pos) /*!< TPI DEVID: PTINVALID Mask */ - -#define TPI_DEVID_MinBufSz_Pos 6U /*!< TPI DEVID: MinBufSz Position */ -#define TPI_DEVID_MinBufSz_Msk (0x7UL << TPI_DEVID_MinBufSz_Pos) /*!< TPI DEVID: MinBufSz Mask */ - -#define TPI_DEVID_AsynClkIn_Pos 5U /*!< TPI DEVID: AsynClkIn Position */ -#define TPI_DEVID_AsynClkIn_Msk (0x1UL << TPI_DEVID_AsynClkIn_Pos) /*!< TPI DEVID: AsynClkIn Mask */ - -#define TPI_DEVID_NrTraceInput_Pos 0U /*!< TPI DEVID: NrTraceInput Position */ -#define TPI_DEVID_NrTraceInput_Msk (0x1FUL /*<< TPI_DEVID_NrTraceInput_Pos*/) /*!< TPI DEVID: NrTraceInput Mask */ - -/* TPI DEVTYPE Register Definitions */ -#define TPI_DEVTYPE_SubType_Pos 4U /*!< TPI DEVTYPE: SubType Position */ -#define TPI_DEVTYPE_SubType_Msk (0xFUL /*<< TPI_DEVTYPE_SubType_Pos*/) /*!< TPI DEVTYPE: SubType Mask */ - -#define TPI_DEVTYPE_MajorType_Pos 0U /*!< TPI DEVTYPE: MajorType Position */ -#define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */ - -/*@}*/ /* end of group CMSIS_TPI */ - - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_MPU Memory Protection Unit (MPU) - \brief Type definitions for the Memory Protection Unit (MPU) - @{ - */ - -/** - \brief Structure type to access the Memory Protection Unit (MPU). - */ -typedef struct -{ - __IM uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */ - __IOM uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */ - __IOM uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region RNRber Register */ - __IOM uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */ - __IOM uint32_t RASR; /*!< Offset: 0x010 (R/W) MPU Region Attribute and Size Register */ - __IOM uint32_t RBAR_A1; /*!< Offset: 0x014 (R/W) MPU Alias 1 Region Base Address Register */ - __IOM uint32_t RASR_A1; /*!< Offset: 0x018 (R/W) MPU Alias 1 Region Attribute and Size Register */ - __IOM uint32_t RBAR_A2; /*!< Offset: 0x01C (R/W) MPU Alias 2 Region Base Address Register */ - __IOM uint32_t RASR_A2; /*!< Offset: 0x020 (R/W) MPU Alias 2 Region Attribute and Size Register */ - __IOM uint32_t RBAR_A3; /*!< Offset: 0x024 (R/W) MPU Alias 3 Region Base Address Register */ - __IOM uint32_t RASR_A3; /*!< Offset: 0x028 (R/W) MPU Alias 3 Region Attribute and Size Register */ -} MPU_Type; - -#define MPU_TYPE_RALIASES 4U - -/* MPU Type Register Definitions */ -#define MPU_TYPE_IREGION_Pos 16U /*!< MPU TYPE: IREGION Position */ -#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */ - -#define MPU_TYPE_DREGION_Pos 8U /*!< MPU TYPE: DREGION Position */ -#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */ - -#define MPU_TYPE_SEPARATE_Pos 0U /*!< MPU TYPE: SEPARATE Position */ -#define MPU_TYPE_SEPARATE_Msk (1UL /*<< MPU_TYPE_SEPARATE_Pos*/) /*!< MPU TYPE: SEPARATE Mask */ - -/* MPU Control Register Definitions */ -#define MPU_CTRL_PRIVDEFENA_Pos 2U /*!< MPU CTRL: PRIVDEFENA Position */ -#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */ - -#define MPU_CTRL_HFNMIENA_Pos 1U /*!< MPU CTRL: HFNMIENA Position */ -#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */ - -#define MPU_CTRL_ENABLE_Pos 0U /*!< MPU CTRL: ENABLE Position */ -#define MPU_CTRL_ENABLE_Msk (1UL /*<< MPU_CTRL_ENABLE_Pos*/) /*!< MPU CTRL: ENABLE Mask */ - -/* MPU Region Number Register Definitions */ -#define MPU_RNR_REGION_Pos 0U /*!< MPU RNR: REGION Position */ -#define MPU_RNR_REGION_Msk (0xFFUL /*<< MPU_RNR_REGION_Pos*/) /*!< MPU RNR: REGION Mask */ - -/* MPU Region Base Address Register Definitions */ -#define MPU_RBAR_ADDR_Pos 5U /*!< MPU RBAR: ADDR Position */ -#define MPU_RBAR_ADDR_Msk (0x7FFFFFFUL << MPU_RBAR_ADDR_Pos) /*!< MPU RBAR: ADDR Mask */ - -#define MPU_RBAR_VALID_Pos 4U /*!< MPU RBAR: VALID Position */ -#define MPU_RBAR_VALID_Msk (1UL << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */ - -#define MPU_RBAR_REGION_Pos 0U /*!< MPU RBAR: REGION Position */ -#define MPU_RBAR_REGION_Msk (0xFUL /*<< MPU_RBAR_REGION_Pos*/) /*!< MPU RBAR: REGION Mask */ - -/* MPU Region Attribute and Size Register Definitions */ -#define MPU_RASR_ATTRS_Pos 16U /*!< MPU RASR: MPU Region Attribute field Position */ -#define MPU_RASR_ATTRS_Msk (0xFFFFUL << MPU_RASR_ATTRS_Pos) /*!< MPU RASR: MPU Region Attribute field Mask */ - -#define MPU_RASR_XN_Pos 28U /*!< MPU RASR: ATTRS.XN Position */ -#define MPU_RASR_XN_Msk (1UL << MPU_RASR_XN_Pos) /*!< MPU RASR: ATTRS.XN Mask */ - -#define MPU_RASR_AP_Pos 24U /*!< MPU RASR: ATTRS.AP Position */ -#define MPU_RASR_AP_Msk (0x7UL << MPU_RASR_AP_Pos) /*!< MPU RASR: ATTRS.AP Mask */ - -#define MPU_RASR_TEX_Pos 19U /*!< MPU RASR: ATTRS.TEX Position */ -#define MPU_RASR_TEX_Msk (0x7UL << MPU_RASR_TEX_Pos) /*!< MPU RASR: ATTRS.TEX Mask */ - -#define MPU_RASR_S_Pos 18U /*!< MPU RASR: ATTRS.S Position */ -#define MPU_RASR_S_Msk (1UL << MPU_RASR_S_Pos) /*!< MPU RASR: ATTRS.S Mask */ - -#define MPU_RASR_C_Pos 17U /*!< MPU RASR: ATTRS.C Position */ -#define MPU_RASR_C_Msk (1UL << MPU_RASR_C_Pos) /*!< MPU RASR: ATTRS.C Mask */ - -#define MPU_RASR_B_Pos 16U /*!< MPU RASR: ATTRS.B Position */ -#define MPU_RASR_B_Msk (1UL << MPU_RASR_B_Pos) /*!< MPU RASR: ATTRS.B Mask */ - -#define MPU_RASR_SRD_Pos 8U /*!< MPU RASR: Sub-Region Disable Position */ -#define MPU_RASR_SRD_Msk (0xFFUL << MPU_RASR_SRD_Pos) /*!< MPU RASR: Sub-Region Disable Mask */ - -#define MPU_RASR_SIZE_Pos 1U /*!< MPU RASR: Region Size Field Position */ -#define MPU_RASR_SIZE_Msk (0x1FUL << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */ - -#define MPU_RASR_ENABLE_Pos 0U /*!< MPU RASR: Region enable bit Position */ -#define MPU_RASR_ENABLE_Msk (1UL /*<< MPU_RASR_ENABLE_Pos*/) /*!< MPU RASR: Region enable bit Disable Mask */ - -/*@} end of group CMSIS_MPU */ -#endif /* defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_FPU Floating Point Unit (FPU) - \brief Type definitions for the Floating Point Unit (FPU) - @{ - */ - -/** - \brief Structure type to access the Floating Point Unit (FPU). - */ -typedef struct -{ - uint32_t RESERVED0[1U]; - __IOM uint32_t FPCCR; /*!< Offset: 0x004 (R/W) Floating-Point Context Control Register */ - __IOM uint32_t FPCAR; /*!< Offset: 0x008 (R/W) Floating-Point Context Address Register */ - __IOM uint32_t FPDSCR; /*!< Offset: 0x00C (R/W) Floating-Point Default Status Control Register */ - __IM uint32_t MVFR0; /*!< Offset: 0x010 (R/ ) Media and FP Feature Register 0 */ - __IM uint32_t MVFR1; /*!< Offset: 0x014 (R/ ) Media and FP Feature Register 1 */ - __IM uint32_t MVFR2; /*!< Offset: 0x018 (R/ ) Media and FP Feature Register 2 */ -} FPU_Type; - -/* Floating-Point Context Control Register Definitions */ -#define FPU_FPCCR_ASPEN_Pos 31U /*!< FPCCR: ASPEN bit Position */ -#define FPU_FPCCR_ASPEN_Msk (1UL << FPU_FPCCR_ASPEN_Pos) /*!< FPCCR: ASPEN bit Mask */ - -#define FPU_FPCCR_LSPEN_Pos 30U /*!< FPCCR: LSPEN Position */ -#define FPU_FPCCR_LSPEN_Msk (1UL << FPU_FPCCR_LSPEN_Pos) /*!< FPCCR: LSPEN bit Mask */ - -#define FPU_FPCCR_MONRDY_Pos 8U /*!< FPCCR: MONRDY Position */ -#define FPU_FPCCR_MONRDY_Msk (1UL << FPU_FPCCR_MONRDY_Pos) /*!< FPCCR: MONRDY bit Mask */ - -#define FPU_FPCCR_BFRDY_Pos 6U /*!< FPCCR: BFRDY Position */ -#define FPU_FPCCR_BFRDY_Msk (1UL << FPU_FPCCR_BFRDY_Pos) /*!< FPCCR: BFRDY bit Mask */ - -#define FPU_FPCCR_MMRDY_Pos 5U /*!< FPCCR: MMRDY Position */ -#define FPU_FPCCR_MMRDY_Msk (1UL << FPU_FPCCR_MMRDY_Pos) /*!< FPCCR: MMRDY bit Mask */ - -#define FPU_FPCCR_HFRDY_Pos 4U /*!< FPCCR: HFRDY Position */ -#define FPU_FPCCR_HFRDY_Msk (1UL << FPU_FPCCR_HFRDY_Pos) /*!< FPCCR: HFRDY bit Mask */ - -#define FPU_FPCCR_THREAD_Pos 3U /*!< FPCCR: processor mode bit Position */ -#define FPU_FPCCR_THREAD_Msk (1UL << FPU_FPCCR_THREAD_Pos) /*!< FPCCR: processor mode active bit Mask */ - -#define FPU_FPCCR_USER_Pos 1U /*!< FPCCR: privilege level bit Position */ -#define FPU_FPCCR_USER_Msk (1UL << FPU_FPCCR_USER_Pos) /*!< FPCCR: privilege level bit Mask */ - -#define FPU_FPCCR_LSPACT_Pos 0U /*!< FPCCR: Lazy state preservation active bit Position */ -#define FPU_FPCCR_LSPACT_Msk (1UL /*<< FPU_FPCCR_LSPACT_Pos*/) /*!< FPCCR: Lazy state preservation active bit Mask */ - -/* Floating-Point Context Address Register Definitions */ -#define FPU_FPCAR_ADDRESS_Pos 3U /*!< FPCAR: ADDRESS bit Position */ -#define FPU_FPCAR_ADDRESS_Msk (0x1FFFFFFFUL << FPU_FPCAR_ADDRESS_Pos) /*!< FPCAR: ADDRESS bit Mask */ - -/* Floating-Point Default Status Control Register Definitions */ -#define FPU_FPDSCR_AHP_Pos 26U /*!< FPDSCR: AHP bit Position */ -#define FPU_FPDSCR_AHP_Msk (1UL << FPU_FPDSCR_AHP_Pos) /*!< FPDSCR: AHP bit Mask */ - -#define FPU_FPDSCR_DN_Pos 25U /*!< FPDSCR: DN bit Position */ -#define FPU_FPDSCR_DN_Msk (1UL << FPU_FPDSCR_DN_Pos) /*!< FPDSCR: DN bit Mask */ - -#define FPU_FPDSCR_FZ_Pos 24U /*!< FPDSCR: FZ bit Position */ -#define FPU_FPDSCR_FZ_Msk (1UL << FPU_FPDSCR_FZ_Pos) /*!< FPDSCR: FZ bit Mask */ - -#define FPU_FPDSCR_RMode_Pos 22U /*!< FPDSCR: RMode bit Position */ -#define FPU_FPDSCR_RMode_Msk (3UL << FPU_FPDSCR_RMode_Pos) /*!< FPDSCR: RMode bit Mask */ - -/* Media and FP Feature Register 0 Definitions */ -#define FPU_MVFR0_FP_rounding_modes_Pos 28U /*!< MVFR0: FP rounding modes bits Position */ -#define FPU_MVFR0_FP_rounding_modes_Msk (0xFUL << FPU_MVFR0_FP_rounding_modes_Pos) /*!< MVFR0: FP rounding modes bits Mask */ - -#define FPU_MVFR0_Short_vectors_Pos 24U /*!< MVFR0: Short vectors bits Position */ -#define FPU_MVFR0_Short_vectors_Msk (0xFUL << FPU_MVFR0_Short_vectors_Pos) /*!< MVFR0: Short vectors bits Mask */ - -#define FPU_MVFR0_Square_root_Pos 20U /*!< MVFR0: Square root bits Position */ -#define FPU_MVFR0_Square_root_Msk (0xFUL << FPU_MVFR0_Square_root_Pos) /*!< MVFR0: Square root bits Mask */ - -#define FPU_MVFR0_Divide_Pos 16U /*!< MVFR0: Divide bits Position */ -#define FPU_MVFR0_Divide_Msk (0xFUL << FPU_MVFR0_Divide_Pos) /*!< MVFR0: Divide bits Mask */ - -#define FPU_MVFR0_FP_excep_trapping_Pos 12U /*!< MVFR0: FP exception trapping bits Position */ -#define FPU_MVFR0_FP_excep_trapping_Msk (0xFUL << FPU_MVFR0_FP_excep_trapping_Pos) /*!< MVFR0: FP exception trapping bits Mask */ - -#define FPU_MVFR0_Double_precision_Pos 8U /*!< MVFR0: Double-precision bits Position */ -#define FPU_MVFR0_Double_precision_Msk (0xFUL << FPU_MVFR0_Double_precision_Pos) /*!< MVFR0: Double-precision bits Mask */ - -#define FPU_MVFR0_Single_precision_Pos 4U /*!< MVFR0: Single-precision bits Position */ -#define FPU_MVFR0_Single_precision_Msk (0xFUL << FPU_MVFR0_Single_precision_Pos) /*!< MVFR0: Single-precision bits Mask */ - -#define FPU_MVFR0_A_SIMD_registers_Pos 0U /*!< MVFR0: A_SIMD registers bits Position */ -#define FPU_MVFR0_A_SIMD_registers_Msk (0xFUL /*<< FPU_MVFR0_A_SIMD_registers_Pos*/) /*!< MVFR0: A_SIMD registers bits Mask */ - -/* Media and FP Feature Register 1 Definitions */ -#define FPU_MVFR1_FP_fused_MAC_Pos 28U /*!< MVFR1: FP fused MAC bits Position */ -#define FPU_MVFR1_FP_fused_MAC_Msk (0xFUL << FPU_MVFR1_FP_fused_MAC_Pos) /*!< MVFR1: FP fused MAC bits Mask */ - -#define FPU_MVFR1_FP_HPFP_Pos 24U /*!< MVFR1: FP HPFP bits Position */ -#define FPU_MVFR1_FP_HPFP_Msk (0xFUL << FPU_MVFR1_FP_HPFP_Pos) /*!< MVFR1: FP HPFP bits Mask */ - -#define FPU_MVFR1_D_NaN_mode_Pos 4U /*!< MVFR1: D_NaN mode bits Position */ -#define FPU_MVFR1_D_NaN_mode_Msk (0xFUL << FPU_MVFR1_D_NaN_mode_Pos) /*!< MVFR1: D_NaN mode bits Mask */ - -#define FPU_MVFR1_FtZ_mode_Pos 0U /*!< MVFR1: FtZ mode bits Position */ -#define FPU_MVFR1_FtZ_mode_Msk (0xFUL /*<< FPU_MVFR1_FtZ_mode_Pos*/) /*!< MVFR1: FtZ mode bits Mask */ - -/* Media and FP Feature Register 2 Definitions */ - -#define FPU_MVFR2_VFP_Misc_Pos 4U /*!< MVFR2: VFP Misc bits Position */ -#define FPU_MVFR2_VFP_Misc_Msk (0xFUL << FPU_MVFR2_VFP_Misc_Pos) /*!< MVFR2: VFP Misc bits Mask */ - -/*@} end of group CMSIS_FPU */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug) - \brief Type definitions for the Core Debug Registers - @{ - */ - -/** - \brief Structure type to access the Core Debug Register (CoreDebug). - */ -typedef struct -{ - __IOM uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */ - __OM uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */ - __IOM uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */ - __IOM uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */ -} CoreDebug_Type; - -/* Debug Halting Control and Status Register Definitions */ -#define CoreDebug_DHCSR_DBGKEY_Pos 16U /*!< CoreDebug DHCSR: DBGKEY Position */ -#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */ - -#define CoreDebug_DHCSR_S_RESET_ST_Pos 25U /*!< CoreDebug DHCSR: S_RESET_ST Position */ -#define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */ - -#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24U /*!< CoreDebug DHCSR: S_RETIRE_ST Position */ -#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */ - -#define CoreDebug_DHCSR_S_LOCKUP_Pos 19U /*!< CoreDebug DHCSR: S_LOCKUP Position */ -#define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */ - -#define CoreDebug_DHCSR_S_SLEEP_Pos 18U /*!< CoreDebug DHCSR: S_SLEEP Position */ -#define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */ - -#define CoreDebug_DHCSR_S_HALT_Pos 17U /*!< CoreDebug DHCSR: S_HALT Position */ -#define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */ - -#define CoreDebug_DHCSR_S_REGRDY_Pos 16U /*!< CoreDebug DHCSR: S_REGRDY Position */ -#define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */ - -#define CoreDebug_DHCSR_C_SNAPSTALL_Pos 5U /*!< CoreDebug DHCSR: C_SNAPSTALL Position */ -#define CoreDebug_DHCSR_C_SNAPSTALL_Msk (1UL << CoreDebug_DHCSR_C_SNAPSTALL_Pos) /*!< CoreDebug DHCSR: C_SNAPSTALL Mask */ - -#define CoreDebug_DHCSR_C_MASKINTS_Pos 3U /*!< CoreDebug DHCSR: C_MASKINTS Position */ -#define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */ - -#define CoreDebug_DHCSR_C_STEP_Pos 2U /*!< CoreDebug DHCSR: C_STEP Position */ -#define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */ - -#define CoreDebug_DHCSR_C_HALT_Pos 1U /*!< CoreDebug DHCSR: C_HALT Position */ -#define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */ - -#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0U /*!< CoreDebug DHCSR: C_DEBUGEN Position */ -#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL /*<< CoreDebug_DHCSR_C_DEBUGEN_Pos*/) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */ - -/* Debug Core Register Selector Register Definitions */ -#define CoreDebug_DCRSR_REGWnR_Pos 16U /*!< CoreDebug DCRSR: REGWnR Position */ -#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */ - -#define CoreDebug_DCRSR_REGSEL_Pos 0U /*!< CoreDebug DCRSR: REGSEL Position */ -#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL /*<< CoreDebug_DCRSR_REGSEL_Pos*/) /*!< CoreDebug DCRSR: REGSEL Mask */ - -/* Debug Exception and Monitor Control Register Definitions */ -#define CoreDebug_DEMCR_TRCENA_Pos 24U /*!< CoreDebug DEMCR: TRCENA Position */ -#define CoreDebug_DEMCR_TRCENA_Msk (1UL << CoreDebug_DEMCR_TRCENA_Pos) /*!< CoreDebug DEMCR: TRCENA Mask */ - -#define CoreDebug_DEMCR_MON_REQ_Pos 19U /*!< CoreDebug DEMCR: MON_REQ Position */ -#define CoreDebug_DEMCR_MON_REQ_Msk (1UL << CoreDebug_DEMCR_MON_REQ_Pos) /*!< CoreDebug DEMCR: MON_REQ Mask */ - -#define CoreDebug_DEMCR_MON_STEP_Pos 18U /*!< CoreDebug DEMCR: MON_STEP Position */ -#define CoreDebug_DEMCR_MON_STEP_Msk (1UL << CoreDebug_DEMCR_MON_STEP_Pos) /*!< CoreDebug DEMCR: MON_STEP Mask */ - -#define CoreDebug_DEMCR_MON_PEND_Pos 17U /*!< CoreDebug DEMCR: MON_PEND Position */ -#define CoreDebug_DEMCR_MON_PEND_Msk (1UL << CoreDebug_DEMCR_MON_PEND_Pos) /*!< CoreDebug DEMCR: MON_PEND Mask */ - -#define CoreDebug_DEMCR_MON_EN_Pos 16U /*!< CoreDebug DEMCR: MON_EN Position */ -#define CoreDebug_DEMCR_MON_EN_Msk (1UL << CoreDebug_DEMCR_MON_EN_Pos) /*!< CoreDebug DEMCR: MON_EN Mask */ - -#define CoreDebug_DEMCR_VC_HARDERR_Pos 10U /*!< CoreDebug DEMCR: VC_HARDERR Position */ -#define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */ - -#define CoreDebug_DEMCR_VC_INTERR_Pos 9U /*!< CoreDebug DEMCR: VC_INTERR Position */ -#define CoreDebug_DEMCR_VC_INTERR_Msk (1UL << CoreDebug_DEMCR_VC_INTERR_Pos) /*!< CoreDebug DEMCR: VC_INTERR Mask */ - -#define CoreDebug_DEMCR_VC_BUSERR_Pos 8U /*!< CoreDebug DEMCR: VC_BUSERR Position */ -#define CoreDebug_DEMCR_VC_BUSERR_Msk (1UL << CoreDebug_DEMCR_VC_BUSERR_Pos) /*!< CoreDebug DEMCR: VC_BUSERR Mask */ - -#define CoreDebug_DEMCR_VC_STATERR_Pos 7U /*!< CoreDebug DEMCR: VC_STATERR Position */ -#define CoreDebug_DEMCR_VC_STATERR_Msk (1UL << CoreDebug_DEMCR_VC_STATERR_Pos) /*!< CoreDebug DEMCR: VC_STATERR Mask */ - -#define CoreDebug_DEMCR_VC_CHKERR_Pos 6U /*!< CoreDebug DEMCR: VC_CHKERR Position */ -#define CoreDebug_DEMCR_VC_CHKERR_Msk (1UL << CoreDebug_DEMCR_VC_CHKERR_Pos) /*!< CoreDebug DEMCR: VC_CHKERR Mask */ - -#define CoreDebug_DEMCR_VC_NOCPERR_Pos 5U /*!< CoreDebug DEMCR: VC_NOCPERR Position */ -#define CoreDebug_DEMCR_VC_NOCPERR_Msk (1UL << CoreDebug_DEMCR_VC_NOCPERR_Pos) /*!< CoreDebug DEMCR: VC_NOCPERR Mask */ - -#define CoreDebug_DEMCR_VC_MMERR_Pos 4U /*!< CoreDebug DEMCR: VC_MMERR Position */ -#define CoreDebug_DEMCR_VC_MMERR_Msk (1UL << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */ - -#define CoreDebug_DEMCR_VC_CORERESET_Pos 0U /*!< CoreDebug DEMCR: VC_CORERESET Position */ -#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL /*<< CoreDebug_DEMCR_VC_CORERESET_Pos*/) /*!< CoreDebug DEMCR: VC_CORERESET Mask */ - -/*@} end of group CMSIS_CoreDebug */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_bitfield Core register bit field macros - \brief Macros for use with bit field definitions (xxx_Pos, xxx_Msk). - @{ - */ - -/** - \brief Mask and shift a bit field value for use in a register bit range. - \param[in] field Name of the register bit field. - \param[in] value Value of the bit field. This parameter is interpreted as an uint32_t type. - \return Masked and shifted value. -*/ -#define _VAL2FLD(field, value) (((uint32_t)(value) << field ## _Pos) & field ## _Msk) - -/** - \brief Mask and shift a register value to extract a bit filed value. - \param[in] field Name of the register bit field. - \param[in] value Value of register. This parameter is interpreted as an uint32_t type. - \return Masked and shifted bit field value. -*/ -#define _FLD2VAL(field, value) (((uint32_t)(value) & field ## _Msk) >> field ## _Pos) - -/*@} end of group CMSIS_core_bitfield */ - - -/** - \ingroup CMSIS_core_register - \defgroup CMSIS_core_base Core Definitions - \brief Definitions for base addresses, unions, and structures. - @{ - */ - -/* Memory mapping of Core Hardware */ -#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ -#define ITM_BASE (0xE0000000UL) /*!< ITM Base Address */ -#define DWT_BASE (0xE0001000UL) /*!< DWT Base Address */ -#define TPI_BASE (0xE0040000UL) /*!< TPI Base Address */ -#define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug Base Address */ -#define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */ -#define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */ -#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ - -#define SCnSCB ((SCnSCB_Type *) SCS_BASE ) /*!< System control Register not in SCB */ -#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ -#define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */ -#define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */ -#define ITM ((ITM_Type *) ITM_BASE ) /*!< ITM configuration struct */ -#define DWT ((DWT_Type *) DWT_BASE ) /*!< DWT configuration struct */ -#define TPI ((TPI_Type *) TPI_BASE ) /*!< TPI configuration struct */ -#define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE) /*!< Core Debug configuration struct */ - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */ - #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */ -#endif - -#define FPU_BASE (SCS_BASE + 0x0F30UL) /*!< Floating Point Unit */ -#define FPU ((FPU_Type *) FPU_BASE ) /*!< Floating Point Unit */ - -/*@} */ - - - -/******************************************************************************* - * Hardware Abstraction Layer - Core Function Interface contains: - - Core NVIC Functions - - Core SysTick Functions - - Core Debug Functions - - Core Register Access Functions - ******************************************************************************/ -/** - \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference -*/ - - - -/* ########################## NVIC functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_NVICFunctions NVIC Functions - \brief Functions that manage interrupts and exceptions via the NVIC. - @{ - */ - -#ifdef CMSIS_NVIC_VIRTUAL - #ifndef CMSIS_NVIC_VIRTUAL_HEADER_FILE - #define CMSIS_NVIC_VIRTUAL_HEADER_FILE "cmsis_nvic_virtual.h" - #endif - #include CMSIS_NVIC_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetPriorityGrouping __NVIC_SetPriorityGrouping - #define NVIC_GetPriorityGrouping __NVIC_GetPriorityGrouping - #define NVIC_EnableIRQ __NVIC_EnableIRQ - #define NVIC_GetEnableIRQ __NVIC_GetEnableIRQ - #define NVIC_DisableIRQ __NVIC_DisableIRQ - #define NVIC_GetPendingIRQ __NVIC_GetPendingIRQ - #define NVIC_SetPendingIRQ __NVIC_SetPendingIRQ - #define NVIC_ClearPendingIRQ __NVIC_ClearPendingIRQ - #define NVIC_GetActive __NVIC_GetActive - #define NVIC_SetPriority __NVIC_SetPriority - #define NVIC_GetPriority __NVIC_GetPriority - #define NVIC_SystemReset __NVIC_SystemReset -#endif /* CMSIS_NVIC_VIRTUAL */ - -#ifdef CMSIS_VECTAB_VIRTUAL - #ifndef CMSIS_VECTAB_VIRTUAL_HEADER_FILE - #define CMSIS_VECTAB_VIRTUAL_HEADER_FILE "cmsis_vectab_virtual.h" - #endif - #include CMSIS_VECTAB_VIRTUAL_HEADER_FILE -#else - #define NVIC_SetVector __NVIC_SetVector - #define NVIC_GetVector __NVIC_GetVector -#endif /* (CMSIS_VECTAB_VIRTUAL) */ - -#define NVIC_USER_IRQ_OFFSET 16 - - -/* The following EXC_RETURN values are saved the LR on exception entry */ -#define EXC_RETURN_HANDLER (0xFFFFFFF1UL) /* return to Handler mode, uses MSP after return */ -#define EXC_RETURN_THREAD_MSP (0xFFFFFFF9UL) /* return to Thread mode, uses MSP after return */ -#define EXC_RETURN_THREAD_PSP (0xFFFFFFFDUL) /* return to Thread mode, uses PSP after return */ -#define EXC_RETURN_HANDLER_FPU (0xFFFFFFE1UL) /* return to Handler mode, uses MSP after return, restore floating-point state */ -#define EXC_RETURN_THREAD_MSP_FPU (0xFFFFFFE9UL) /* return to Thread mode, uses MSP after return, restore floating-point state */ -#define EXC_RETURN_THREAD_PSP_FPU (0xFFFFFFEDUL) /* return to Thread mode, uses PSP after return, restore floating-point state */ - - -/** - \brief Set Priority Grouping - \details Sets the priority grouping field using the required unlock sequence. - The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field. - Only values from 0..7 are used. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Priority grouping field. - */ -__STATIC_INLINE void __NVIC_SetPriorityGrouping(uint32_t PriorityGroup) -{ - uint32_t reg_value; - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - - reg_value = SCB->AIRCR; /* read old register configuration */ - reg_value &= ~((uint32_t)(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk)); /* clear bits to change */ - reg_value = (reg_value | - ((uint32_t)0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - (PriorityGroupTmp << SCB_AIRCR_PRIGROUP_Pos) ); /* Insert write key and priority group */ - SCB->AIRCR = reg_value; -} - - -/** - \brief Get Priority Grouping - \details Reads the priority grouping field from the NVIC Interrupt Controller. - \return Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field). - */ -__STATIC_INLINE uint32_t __NVIC_GetPriorityGrouping(void) -{ - return ((uint32_t)((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos)); -} - - -/** - \brief Enable Interrupt - \details Enables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_EnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - __COMPILER_BARRIER(); - NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - __COMPILER_BARRIER(); - } -} - - -/** - \brief Get Interrupt Enable status - \details Returns a device specific interrupt enable status from the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt is not enabled. - \return 1 Interrupt is enabled. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetEnableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISER[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Disable Interrupt - \details Disables a device specific interrupt in the NVIC interrupt controller. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_DisableIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICER[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - __DSB(); - __ISB(); - } -} - - -/** - \brief Get Pending Interrupt - \details Reads the NVIC pending register and returns the pending bit for the specified device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not pending. - \return 1 Interrupt status is pending. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Pending Interrupt - \details Sets the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_SetPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ISPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Clear Pending Interrupt - \details Clears the pending bit of a device specific interrupt in the NVIC pending register. - \param [in] IRQn Device specific interrupt number. - \note IRQn must not be negative. - */ -__STATIC_INLINE void __NVIC_ClearPendingIRQ(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->ICPR[(((uint32_t)IRQn) >> 5UL)] = (uint32_t)(1UL << (((uint32_t)IRQn) & 0x1FUL)); - } -} - - -/** - \brief Get Active Interrupt - \details Reads the active register in the NVIC and returns the active bit for the device specific interrupt. - \param [in] IRQn Device specific interrupt number. - \return 0 Interrupt status is not active. - \return 1 Interrupt status is active. - \note IRQn must not be negative. - */ -__STATIC_INLINE uint32_t __NVIC_GetActive(IRQn_Type IRQn) -{ - if ((int32_t)(IRQn) >= 0) - { - return((uint32_t)(((NVIC->IABR[(((uint32_t)IRQn) >> 5UL)] & (1UL << (((uint32_t)IRQn) & 0x1FUL))) != 0UL) ? 1UL : 0UL)); - } - else - { - return(0U); - } -} - - -/** - \brief Set Interrupt Priority - \details Sets the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \param [in] priority Priority to set. - \note The priority cannot be set for every processor exception. - */ -__STATIC_INLINE void __NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority) -{ - if ((int32_t)(IRQn) >= 0) - { - NVIC->IP[((uint32_t)IRQn)] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); - } - else - { - SCB->SHPR[(((uint32_t)IRQn) & 0xFUL)-4UL] = (uint8_t)((priority << (8U - __NVIC_PRIO_BITS)) & (uint32_t)0xFFUL); - } -} - - -/** - \brief Get Interrupt Priority - \details Reads the priority of a device specific interrupt or a processor exception. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Interrupt Priority. - Value is aligned automatically to the implemented priority bits of the microcontroller. - */ -__STATIC_INLINE uint32_t __NVIC_GetPriority(IRQn_Type IRQn) -{ - - if ((int32_t)(IRQn) >= 0) - { - return(((uint32_t)NVIC->IP[((uint32_t)IRQn)] >> (8U - __NVIC_PRIO_BITS))); - } - else - { - return(((uint32_t)SCB->SHPR[(((uint32_t)IRQn) & 0xFUL)-4UL] >> (8U - __NVIC_PRIO_BITS))); - } -} - - -/** - \brief Encode Priority - \details Encodes the priority for an interrupt with the given priority group, - preemptive priority value, and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set. - \param [in] PriorityGroup Used priority group. - \param [in] PreemptPriority Preemptive priority value (starting from 0). - \param [in] SubPriority Subpriority value (starting from 0). - \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority(). - */ -__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - return ( - ((PreemptPriority & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL)) << SubPriorityBits) | - ((SubPriority & (uint32_t)((1UL << (SubPriorityBits )) - 1UL))) - ); -} - - -/** - \brief Decode Priority - \details Decodes an interrupt priority value with a given priority group to - preemptive priority value and subpriority value. - In case of a conflict between priority grouping and available - priority bits (__NVIC_PRIO_BITS) the smallest possible priority group is set. - \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority(). - \param [in] PriorityGroup Used priority group. - \param [out] pPreemptPriority Preemptive priority value (starting from 0). - \param [out] pSubPriority Subpriority value (starting from 0). - */ -__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* const pPreemptPriority, uint32_t* const pSubPriority) -{ - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07UL); /* only values 0..7 are used */ - uint32_t PreemptPriorityBits; - uint32_t SubPriorityBits; - - PreemptPriorityBits = ((7UL - PriorityGroupTmp) > (uint32_t)(__NVIC_PRIO_BITS)) ? (uint32_t)(__NVIC_PRIO_BITS) : (uint32_t)(7UL - PriorityGroupTmp); - SubPriorityBits = ((PriorityGroupTmp + (uint32_t)(__NVIC_PRIO_BITS)) < (uint32_t)7UL) ? (uint32_t)0UL : (uint32_t)((PriorityGroupTmp - 7UL) + (uint32_t)(__NVIC_PRIO_BITS)); - - *pPreemptPriority = (Priority >> SubPriorityBits) & (uint32_t)((1UL << (PreemptPriorityBits)) - 1UL); - *pSubPriority = (Priority ) & (uint32_t)((1UL << (SubPriorityBits )) - 1UL); -} - - -/** - \brief Set Interrupt Vector - \details Sets an interrupt vector in SRAM based interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - VTOR must been relocated to SRAM before. - \param [in] IRQn Interrupt number - \param [in] vector Address of interrupt handler function - */ -__STATIC_INLINE void __NVIC_SetVector(IRQn_Type IRQn, uint32_t vector) -{ - uint32_t vectors = (uint32_t )SCB->VTOR; - (* (int *) (vectors + ((int32_t)IRQn + NVIC_USER_IRQ_OFFSET) * 4)) = vector; - __DSB(); -} - - -/** - \brief Get Interrupt Vector - \details Reads an interrupt vector from interrupt vector table. - The interrupt number can be positive to specify a device specific interrupt, - or negative to specify a processor exception. - \param [in] IRQn Interrupt number. - \return Address of interrupt handler function - */ -__STATIC_INLINE uint32_t __NVIC_GetVector(IRQn_Type IRQn) -{ - uint32_t vectors = (uint32_t )SCB->VTOR; - return (uint32_t)(* (int *) (vectors + ((int32_t)IRQn + NVIC_USER_IRQ_OFFSET) * 4)); -} - - -/** - \brief System Reset - \details Initiates a system reset request to reset the MCU. - */ -__NO_RETURN __STATIC_INLINE void __NVIC_SystemReset(void) -{ - __DSB(); /* Ensure all outstanding memory accesses included - buffered write are completed before reset */ - SCB->AIRCR = (uint32_t)((0x5FAUL << SCB_AIRCR_VECTKEY_Pos) | - (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) | - SCB_AIRCR_SYSRESETREQ_Msk ); /* Keep priority group unchanged */ - __DSB(); /* Ensure completion of memory access */ - - for(;;) /* wait until reset */ - { - __NOP(); - } -} - -/*@} end of CMSIS_Core_NVICFunctions */ - - -/* ########################## MPU functions #################################### */ - -#if defined (__MPU_PRESENT) && (__MPU_PRESENT == 1U) - -#include "mpu_armv7.h" - -#endif - - -/* ########################## FPU functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_FpuFunctions FPU Functions - \brief Function that provides FPU type. - @{ - */ - -/** - \brief get FPU type - \details returns the FPU type - \returns - - \b 0: No FPU - - \b 1: Single precision FPU - - \b 2: Double + Single precision FPU - */ -__STATIC_INLINE uint32_t SCB_GetFPUType(void) -{ - uint32_t mvfr0; - - mvfr0 = SCB->MVFR0; - if ((mvfr0 & (FPU_MVFR0_Single_precision_Msk | FPU_MVFR0_Double_precision_Msk)) == 0x220U) - { - return 2U; /* Double + Single precision FPU */ - } - else if ((mvfr0 & (FPU_MVFR0_Single_precision_Msk | FPU_MVFR0_Double_precision_Msk)) == 0x020U) - { - return 1U; /* Single precision FPU */ - } - else - { - return 0U; /* No FPU */ - } -} - -/*@} end of CMSIS_Core_FpuFunctions */ - - - -/* ########################## Cache functions #################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_CacheFunctions Cache Functions - \brief Functions that configure Instruction and Data cache. - @{ - */ - -/* Cache Size ID Register Macros */ -#define CCSIDR_WAYS(x) (((x) & SCB_CCSIDR_ASSOCIATIVITY_Msk) >> SCB_CCSIDR_ASSOCIATIVITY_Pos) -#define CCSIDR_SETS(x) (((x) & SCB_CCSIDR_NUMSETS_Msk ) >> SCB_CCSIDR_NUMSETS_Pos ) - -#define __SCB_DCACHE_LINE_SIZE 32U /*!< Cortex-M7 cache line size is fixed to 32 bytes (8 words). See also register SCB_CCSIDR */ -#define __SCB_ICACHE_LINE_SIZE 32U /*!< Cortex-M7 cache line size is fixed to 32 bytes (8 words). See also register SCB_CCSIDR */ - -/** - \brief Enable I-Cache - \details Turns on I-Cache - */ -__STATIC_FORCEINLINE void SCB_EnableICache (void) -{ - #if defined (__ICACHE_PRESENT) && (__ICACHE_PRESENT == 1U) - if (SCB->CCR & SCB_CCR_IC_Msk) return; /* return if ICache is already enabled */ - - __DSB(); - __ISB(); - SCB->ICIALLU = 0UL; /* invalidate I-Cache */ - __DSB(); - __ISB(); - SCB->CCR |= (uint32_t)SCB_CCR_IC_Msk; /* enable I-Cache */ - __DSB(); - __ISB(); - #endif -} - - -/** - \brief Disable I-Cache - \details Turns off I-Cache - */ -__STATIC_FORCEINLINE void SCB_DisableICache (void) -{ - #if defined (__ICACHE_PRESENT) && (__ICACHE_PRESENT == 1U) - __DSB(); - __ISB(); - SCB->CCR &= ~(uint32_t)SCB_CCR_IC_Msk; /* disable I-Cache */ - SCB->ICIALLU = 0UL; /* invalidate I-Cache */ - __DSB(); - __ISB(); - #endif -} - - -/** - \brief Invalidate I-Cache - \details Invalidates I-Cache - */ -__STATIC_FORCEINLINE void SCB_InvalidateICache (void) -{ - #if defined (__ICACHE_PRESENT) && (__ICACHE_PRESENT == 1U) - __DSB(); - __ISB(); - SCB->ICIALLU = 0UL; - __DSB(); - __ISB(); - #endif -} - - -/** - \brief I-Cache Invalidate by address - \details Invalidates I-Cache for the given address. - I-Cache is invalidated starting from a 32 byte aligned address in 32 byte granularity. - I-Cache memory blocks which are part of given address + given size are invalidated. - \param[in] addr address - \param[in] isize size of memory block (in number of bytes) -*/ -__STATIC_FORCEINLINE void SCB_InvalidateICache_by_Addr (void *addr, int32_t isize) -{ - #if defined (__ICACHE_PRESENT) && (__ICACHE_PRESENT == 1U) - if ( isize > 0 ) { - int32_t op_size = isize + (((uint32_t)addr) & (__SCB_ICACHE_LINE_SIZE - 1U)); - uint32_t op_addr = (uint32_t)addr /* & ~(__SCB_ICACHE_LINE_SIZE - 1U) */; - - __DSB(); - - do { - SCB->ICIMVAU = op_addr; /* register accepts only 32byte aligned values, only bits 31..5 are valid */ - op_addr += __SCB_ICACHE_LINE_SIZE; - op_size -= __SCB_ICACHE_LINE_SIZE; - } while ( op_size > 0 ); - - __DSB(); - __ISB(); - } - #endif -} - - -/** - \brief Enable D-Cache - \details Turns on D-Cache - */ -__STATIC_FORCEINLINE void SCB_EnableDCache (void) -{ - #if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U) - uint32_t ccsidr; - uint32_t sets; - uint32_t ways; - - if (SCB->CCR & SCB_CCR_DC_Msk) return; /* return if DCache is already enabled */ - - SCB->CSSELR = 0U; /* select Level 1 data cache */ - __DSB(); - - ccsidr = SCB->CCSIDR; - - /* invalidate D-Cache */ - sets = (uint32_t)(CCSIDR_SETS(ccsidr)); - do { - ways = (uint32_t)(CCSIDR_WAYS(ccsidr)); - do { - SCB->DCISW = (((sets << SCB_DCISW_SET_Pos) & SCB_DCISW_SET_Msk) | - ((ways << SCB_DCISW_WAY_Pos) & SCB_DCISW_WAY_Msk) ); - #if defined ( __CC_ARM ) - __schedule_barrier(); - #endif - } while (ways-- != 0U); - } while(sets-- != 0U); - __DSB(); - - SCB->CCR |= (uint32_t)SCB_CCR_DC_Msk; /* enable D-Cache */ - - __DSB(); - __ISB(); - #endif -} - - -/** - \brief Disable D-Cache - \details Turns off D-Cache - */ -__STATIC_FORCEINLINE void SCB_DisableDCache (void) -{ - #if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U) - uint32_t ccsidr; - uint32_t sets; - uint32_t ways; - - SCB->CSSELR = 0U; /* select Level 1 data cache */ - __DSB(); - - SCB->CCR &= ~(uint32_t)SCB_CCR_DC_Msk; /* disable D-Cache */ - __DSB(); - - ccsidr = SCB->CCSIDR; - - /* clean & invalidate D-Cache */ - sets = (uint32_t)(CCSIDR_SETS(ccsidr)); - do { - ways = (uint32_t)(CCSIDR_WAYS(ccsidr)); - do { - SCB->DCCISW = (((sets << SCB_DCCISW_SET_Pos) & SCB_DCCISW_SET_Msk) | - ((ways << SCB_DCCISW_WAY_Pos) & SCB_DCCISW_WAY_Msk) ); - #if defined ( __CC_ARM ) - __schedule_barrier(); - #endif - } while (ways-- != 0U); - } while(sets-- != 0U); - - __DSB(); - __ISB(); - #endif -} - - -/** - \brief Invalidate D-Cache - \details Invalidates D-Cache - */ -__STATIC_FORCEINLINE void SCB_InvalidateDCache (void) -{ - #if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U) - uint32_t ccsidr; - uint32_t sets; - uint32_t ways; - - SCB->CSSELR = 0U; /* select Level 1 data cache */ - __DSB(); - - ccsidr = SCB->CCSIDR; - - /* invalidate D-Cache */ - sets = (uint32_t)(CCSIDR_SETS(ccsidr)); - do { - ways = (uint32_t)(CCSIDR_WAYS(ccsidr)); - do { - SCB->DCISW = (((sets << SCB_DCISW_SET_Pos) & SCB_DCISW_SET_Msk) | - ((ways << SCB_DCISW_WAY_Pos) & SCB_DCISW_WAY_Msk) ); - #if defined ( __CC_ARM ) - __schedule_barrier(); - #endif - } while (ways-- != 0U); - } while(sets-- != 0U); - - __DSB(); - __ISB(); - #endif -} - - -/** - \brief Clean D-Cache - \details Cleans D-Cache - */ -__STATIC_FORCEINLINE void SCB_CleanDCache (void) -{ - #if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U) - uint32_t ccsidr; - uint32_t sets; - uint32_t ways; - - SCB->CSSELR = 0U; /* select Level 1 data cache */ - __DSB(); - - ccsidr = SCB->CCSIDR; - - /* clean D-Cache */ - sets = (uint32_t)(CCSIDR_SETS(ccsidr)); - do { - ways = (uint32_t)(CCSIDR_WAYS(ccsidr)); - do { - SCB->DCCSW = (((sets << SCB_DCCSW_SET_Pos) & SCB_DCCSW_SET_Msk) | - ((ways << SCB_DCCSW_WAY_Pos) & SCB_DCCSW_WAY_Msk) ); - #if defined ( __CC_ARM ) - __schedule_barrier(); - #endif - } while (ways-- != 0U); - } while(sets-- != 0U); - - __DSB(); - __ISB(); - #endif -} - - -/** - \brief Clean & Invalidate D-Cache - \details Cleans and Invalidates D-Cache - */ -__STATIC_FORCEINLINE void SCB_CleanInvalidateDCache (void) -{ - #if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U) - uint32_t ccsidr; - uint32_t sets; - uint32_t ways; - - SCB->CSSELR = 0U; /* select Level 1 data cache */ - __DSB(); - - ccsidr = SCB->CCSIDR; - - /* clean & invalidate D-Cache */ - sets = (uint32_t)(CCSIDR_SETS(ccsidr)); - do { - ways = (uint32_t)(CCSIDR_WAYS(ccsidr)); - do { - SCB->DCCISW = (((sets << SCB_DCCISW_SET_Pos) & SCB_DCCISW_SET_Msk) | - ((ways << SCB_DCCISW_WAY_Pos) & SCB_DCCISW_WAY_Msk) ); - #if defined ( __CC_ARM ) - __schedule_barrier(); - #endif - } while (ways-- != 0U); - } while(sets-- != 0U); - - __DSB(); - __ISB(); - #endif -} - - -/** - \brief D-Cache Invalidate by address - \details Invalidates D-Cache for the given address. - D-Cache is invalidated starting from a 32 byte aligned address in 32 byte granularity. - D-Cache memory blocks which are part of given address + given size are invalidated. - \param[in] addr address - \param[in] dsize size of memory block (in number of bytes) -*/ -__STATIC_FORCEINLINE void SCB_InvalidateDCache_by_Addr (void *addr, int32_t dsize) -{ - #if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U) - if ( dsize > 0 ) { - int32_t op_size = dsize + (((uint32_t)addr) & (__SCB_DCACHE_LINE_SIZE - 1U)); - uint32_t op_addr = (uint32_t)addr /* & ~(__SCB_DCACHE_LINE_SIZE - 1U) */; - - __DSB(); - - do { - SCB->DCIMVAC = op_addr; /* register accepts only 32byte aligned values, only bits 31..5 are valid */ - op_addr += __SCB_DCACHE_LINE_SIZE; - op_size -= __SCB_DCACHE_LINE_SIZE; - } while ( op_size > 0 ); - - __DSB(); - __ISB(); - } - #endif -} - - -/** - \brief D-Cache Clean by address - \details Cleans D-Cache for the given address - D-Cache is cleaned starting from a 32 byte aligned address in 32 byte granularity. - D-Cache memory blocks which are part of given address + given size are cleaned. - \param[in] addr address - \param[in] dsize size of memory block (in number of bytes) -*/ -__STATIC_FORCEINLINE void SCB_CleanDCache_by_Addr (uint32_t *addr, int32_t dsize) -{ - #if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U) - if ( dsize > 0 ) { - int32_t op_size = dsize + (((uint32_t)addr) & (__SCB_DCACHE_LINE_SIZE - 1U)); - uint32_t op_addr = (uint32_t)addr /* & ~(__SCB_DCACHE_LINE_SIZE - 1U) */; - - __DSB(); - - do { - SCB->DCCMVAC = op_addr; /* register accepts only 32byte aligned values, only bits 31..5 are valid */ - op_addr += __SCB_DCACHE_LINE_SIZE; - op_size -= __SCB_DCACHE_LINE_SIZE; - } while ( op_size > 0 ); - - __DSB(); - __ISB(); - } - #endif -} - - -/** - \brief D-Cache Clean and Invalidate by address - \details Cleans and invalidates D_Cache for the given address - D-Cache is cleaned and invalidated starting from a 32 byte aligned address in 32 byte granularity. - D-Cache memory blocks which are part of given address + given size are cleaned and invalidated. - \param[in] addr address (aligned to 32-byte boundary) - \param[in] dsize size of memory block (in number of bytes) -*/ -__STATIC_FORCEINLINE void SCB_CleanInvalidateDCache_by_Addr (uint32_t *addr, int32_t dsize) -{ - #if defined (__DCACHE_PRESENT) && (__DCACHE_PRESENT == 1U) - if ( dsize > 0 ) { - int32_t op_size = dsize + (((uint32_t)addr) & (__SCB_DCACHE_LINE_SIZE - 1U)); - uint32_t op_addr = (uint32_t)addr /* & ~(__SCB_DCACHE_LINE_SIZE - 1U) */; - - __DSB(); - - do { - SCB->DCCIMVAC = op_addr; /* register accepts only 32byte aligned values, only bits 31..5 are valid */ - op_addr += __SCB_DCACHE_LINE_SIZE; - op_size -= __SCB_DCACHE_LINE_SIZE; - } while ( op_size > 0 ); - - __DSB(); - __ISB(); - } - #endif -} - -/*@} end of CMSIS_Core_CacheFunctions */ - - - -/* ################################## SysTick function ############################################ */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_Core_SysTickFunctions SysTick Functions - \brief Functions that configure the System. - @{ - */ - -#if defined (__Vendor_SysTickConfig) && (__Vendor_SysTickConfig == 0U) - -/** - \brief System Tick Configuration - \details Initializes the System Timer and its interrupt, and starts the System Tick Timer. - Counter is in free running mode to generate periodic interrupts. - \param [in] ticks Number of ticks between two interrupts. - \return 0 Function succeeded. - \return 1 Function failed. - \note When the variable __Vendor_SysTickConfig is set to 1, then the - function SysTick_Config is not included. In this case, the file device.h - must contain a vendor-specific implementation of this function. - */ -__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks) -{ - if ((ticks - 1UL) > SysTick_LOAD_RELOAD_Msk) - { - return (1UL); /* Reload value impossible */ - } - - SysTick->LOAD = (uint32_t)(ticks - 1UL); /* set reload register */ - NVIC_SetPriority (SysTick_IRQn, (1UL << __NVIC_PRIO_BITS) - 1UL); /* set Priority for Systick Interrupt */ - SysTick->VAL = 0UL; /* Load the SysTick Counter Value */ - SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk | - SysTick_CTRL_TICKINT_Msk | - SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */ - return (0UL); /* Function successful */ -} - -#endif - -/*@} end of CMSIS_Core_SysTickFunctions */ - - - -/* ##################################### Debug In/Output function ########################################### */ -/** - \ingroup CMSIS_Core_FunctionInterface - \defgroup CMSIS_core_DebugFunctions ITM Functions - \brief Functions that access the ITM debug interface. - @{ - */ - -extern volatile int32_t ITM_RxBuffer; /*!< External variable to receive characters. */ -#define ITM_RXBUFFER_EMPTY ((int32_t)0x5AA55AA5U) /*!< Value identifying \ref ITM_RxBuffer is ready for next character. */ - - -/** - \brief ITM Send Character - \details Transmits a character via the ITM channel 0, and - \li Just returns when no debugger is connected that has booked the output. - \li Is blocking when a debugger is connected, but the previous character sent has not been transmitted. - \param [in] ch Character to transmit. - \returns Character to transmit. - */ -__STATIC_INLINE uint32_t ITM_SendChar (uint32_t ch) -{ - if (((ITM->TCR & ITM_TCR_ITMENA_Msk) != 0UL) && /* ITM enabled */ - ((ITM->TER & 1UL ) != 0UL) ) /* ITM Port #0 enabled */ - { - while (ITM->PORT[0U].u32 == 0UL) - { - __NOP(); - } - ITM->PORT[0U].u8 = (uint8_t)ch; - } - return (ch); -} - - -/** - \brief ITM Receive Character - \details Inputs a character via the external variable \ref ITM_RxBuffer. - \return Received character. - \return -1 No character pending. - */ -__STATIC_INLINE int32_t ITM_ReceiveChar (void) -{ - int32_t ch = -1; /* no character available */ - - if (ITM_RxBuffer != ITM_RXBUFFER_EMPTY) - { - ch = ITM_RxBuffer; - ITM_RxBuffer = ITM_RXBUFFER_EMPTY; /* ready for next character */ - } - - return (ch); -} - - -/** - \brief ITM Check Character - \details Checks whether a character is pending for reading in the variable \ref ITM_RxBuffer. - \return 0 No character available. - \return 1 Character available. - */ -__STATIC_INLINE int32_t ITM_CheckChar (void) -{ - - if (ITM_RxBuffer == ITM_RXBUFFER_EMPTY) - { - return (0); /* no character available */ - } - else - { - return (1); /* character available */ - } -} - -/*@} end of CMSIS_core_DebugFunctions */ - - - - -#ifdef __cplusplus -} -#endif - -#endif /* __CORE_CM7_H_DEPENDANT */ - -#endif /* __CMSIS_GENERIC */ diff --git a/panda/board/stm32h7/inc/mpu_armv8.h b/panda/board/stm32h7/inc/mpu_armv8.h deleted file mode 100644 index 2fe28b6..0000000 --- a/panda/board/stm32h7/inc/mpu_armv8.h +++ /dev/null @@ -1,346 +0,0 @@ -/****************************************************************************** - * @file mpu_armv8.h - * @brief CMSIS MPU API for Armv8-M and Armv8.1-M MPU - * @version V5.1.0 - * @date 08. March 2019 - ******************************************************************************/ -/* - * Copyright (c) 2017-2019 Arm Limited. All rights reserved. - * - * SPDX-License-Identifier: Apache-2.0 - * - * Licensed under the Apache License, Version 2.0 (the License); you may - * not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an AS IS BASIS, WITHOUT - * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - */ - -#if defined ( __ICCARM__ ) - #pragma system_include /* treat file as system include file for MISRA check */ -#elif defined (__clang__) - #pragma clang system_header /* treat file as system include file */ -#endif - -#ifndef ARM_MPU_ARMV8_H -#define ARM_MPU_ARMV8_H - -/** \brief Attribute for device memory (outer only) */ -#define ARM_MPU_ATTR_DEVICE ( 0U ) - -/** \brief Attribute for non-cacheable, normal memory */ -#define ARM_MPU_ATTR_NON_CACHEABLE ( 4U ) - -/** \brief Attribute for normal memory (outer and inner) -* \param NT Non-Transient: Set to 1 for non-transient data. -* \param WB Write-Back: Set to 1 to use write-back update policy. -* \param RA Read Allocation: Set to 1 to use cache allocation on read miss. -* \param WA Write Allocation: Set to 1 to use cache allocation on write miss. -*/ -#define ARM_MPU_ATTR_MEMORY_(NT, WB, RA, WA) \ - (((NT & 1U) << 3U) | ((WB & 1U) << 2U) | ((RA & 1U) << 1U) | (WA & 1U)) - -/** \brief Device memory type non Gathering, non Re-ordering, non Early Write Acknowledgement */ -#define ARM_MPU_ATTR_DEVICE_nGnRnE (0U) - -/** \brief Device memory type non Gathering, non Re-ordering, Early Write Acknowledgement */ -#define ARM_MPU_ATTR_DEVICE_nGnRE (1U) - -/** \brief Device memory type non Gathering, Re-ordering, Early Write Acknowledgement */ -#define ARM_MPU_ATTR_DEVICE_nGRE (2U) - -/** \brief Device memory type Gathering, Re-ordering, Early Write Acknowledgement */ -#define ARM_MPU_ATTR_DEVICE_GRE (3U) - -/** \brief Memory Attribute -* \param O Outer memory attributes -* \param I O == ARM_MPU_ATTR_DEVICE: Device memory attributes, else: Inner memory attributes -*/ -#define ARM_MPU_ATTR(O, I) (((O & 0xFU) << 4U) | (((O & 0xFU) != 0U) ? (I & 0xFU) : ((I & 0x3U) << 2U))) - -/** \brief Normal memory non-shareable */ -#define ARM_MPU_SH_NON (0U) - -/** \brief Normal memory outer shareable */ -#define ARM_MPU_SH_OUTER (2U) - -/** \brief Normal memory inner shareable */ -#define ARM_MPU_SH_INNER (3U) - -/** \brief Memory access permissions -* \param RO Read-Only: Set to 1 for read-only memory. -* \param NP Non-Privileged: Set to 1 for non-privileged memory. -*/ -#define ARM_MPU_AP_(RO, NP) (((RO & 1U) << 1U) | (NP & 1U)) - -/** \brief Region Base Address Register value -* \param BASE The base address bits [31:5] of a memory region. The value is zero extended. Effective address gets 32 byte aligned. -* \param SH Defines the Shareability domain for this memory region. -* \param RO Read-Only: Set to 1 for a read-only memory region. -* \param NP Non-Privileged: Set to 1 for a non-privileged memory region. -* \oaram XN eXecute Never: Set to 1 for a non-executable memory region. -*/ -#define ARM_MPU_RBAR(BASE, SH, RO, NP, XN) \ - ((BASE & MPU_RBAR_BASE_Msk) | \ - ((SH << MPU_RBAR_SH_Pos) & MPU_RBAR_SH_Msk) | \ - ((ARM_MPU_AP_(RO, NP) << MPU_RBAR_AP_Pos) & MPU_RBAR_AP_Msk) | \ - ((XN << MPU_RBAR_XN_Pos) & MPU_RBAR_XN_Msk)) - -/** \brief Region Limit Address Register value -* \param LIMIT The limit address bits [31:5] for this memory region. The value is one extended. -* \param IDX The attribute index to be associated with this memory region. -*/ -#define ARM_MPU_RLAR(LIMIT, IDX) \ - ((LIMIT & MPU_RLAR_LIMIT_Msk) | \ - ((IDX << MPU_RLAR_AttrIndx_Pos) & MPU_RLAR_AttrIndx_Msk) | \ - (MPU_RLAR_EN_Msk)) - -#if defined(MPU_RLAR_PXN_Pos) - -/** \brief Region Limit Address Register with PXN value -* \param LIMIT The limit address bits [31:5] for this memory region. The value is one extended. -* \param PXN Privileged execute never. Defines whether code can be executed from this privileged region. -* \param IDX The attribute index to be associated with this memory region. -*/ -#define ARM_MPU_RLAR_PXN(LIMIT, PXN, IDX) \ - ((LIMIT & MPU_RLAR_LIMIT_Msk) | \ - ((PXN << MPU_RLAR_PXN_Pos) & MPU_RLAR_PXN_Msk) | \ - ((IDX << MPU_RLAR_AttrIndx_Pos) & MPU_RLAR_AttrIndx_Msk) | \ - (MPU_RLAR_EN_Msk)) - -#endif - -/** -* Struct for a single MPU Region -*/ -typedef struct { - uint32_t RBAR; /*!< Region Base Address Register value */ - uint32_t RLAR; /*!< Region Limit Address Register value */ -} ARM_MPU_Region_t; - -/** Enable the MPU. -* \param MPU_Control Default access permissions for unconfigured regions. -*/ -__STATIC_INLINE void ARM_MPU_Enable(uint32_t MPU_Control) -{ - MPU->CTRL = MPU_Control | MPU_CTRL_ENABLE_Msk; -#ifdef SCB_SHCSR_MEMFAULTENA_Msk - SCB->SHCSR |= SCB_SHCSR_MEMFAULTENA_Msk; -#endif - __DSB(); - __ISB(); -} - -/** Disable the MPU. -*/ -__STATIC_INLINE void ARM_MPU_Disable(void) -{ - __DMB(); -#ifdef SCB_SHCSR_MEMFAULTENA_Msk - SCB->SHCSR &= ~SCB_SHCSR_MEMFAULTENA_Msk; -#endif - MPU->CTRL &= ~MPU_CTRL_ENABLE_Msk; -} - -#ifdef MPU_NS -/** Enable the Non-secure MPU. -* \param MPU_Control Default access permissions for unconfigured regions. -*/ -__STATIC_INLINE void ARM_MPU_Enable_NS(uint32_t MPU_Control) -{ - MPU_NS->CTRL = MPU_Control | MPU_CTRL_ENABLE_Msk; -#ifdef SCB_SHCSR_MEMFAULTENA_Msk - SCB_NS->SHCSR |= SCB_SHCSR_MEMFAULTENA_Msk; -#endif - __DSB(); - __ISB(); -} - -/** Disable the Non-secure MPU. -*/ -__STATIC_INLINE void ARM_MPU_Disable_NS(void) -{ - __DMB(); -#ifdef SCB_SHCSR_MEMFAULTENA_Msk - SCB_NS->SHCSR &= ~SCB_SHCSR_MEMFAULTENA_Msk; -#endif - MPU_NS->CTRL &= ~MPU_CTRL_ENABLE_Msk; -} -#endif - -/** Set the memory attribute encoding to the given MPU. -* \param mpu Pointer to the MPU to be configured. -* \param idx The attribute index to be set [0-7] -* \param attr The attribute value to be set. -*/ -__STATIC_INLINE void ARM_MPU_SetMemAttrEx(MPU_Type* mpu, uint8_t idx, uint8_t attr) -{ - const uint8_t reg = idx / 4U; - const uint32_t pos = ((idx % 4U) * 8U); - const uint32_t mask = 0xFFU << pos; - - if (reg >= (sizeof(mpu->MAIR) / sizeof(mpu->MAIR[0]))) { - return; // invalid index - } - - mpu->MAIR[reg] = ((mpu->MAIR[reg] & ~mask) | ((attr << pos) & mask)); -} - -/** Set the memory attribute encoding. -* \param idx The attribute index to be set [0-7] -* \param attr The attribute value to be set. -*/ -__STATIC_INLINE void ARM_MPU_SetMemAttr(uint8_t idx, uint8_t attr) -{ - ARM_MPU_SetMemAttrEx(MPU, idx, attr); -} - -#ifdef MPU_NS -/** Set the memory attribute encoding to the Non-secure MPU. -* \param idx The attribute index to be set [0-7] -* \param attr The attribute value to be set. -*/ -__STATIC_INLINE void ARM_MPU_SetMemAttr_NS(uint8_t idx, uint8_t attr) -{ - ARM_MPU_SetMemAttrEx(MPU_NS, idx, attr); -} -#endif - -/** Clear and disable the given MPU region of the given MPU. -* \param mpu Pointer to MPU to be used. -* \param rnr Region number to be cleared. -*/ -__STATIC_INLINE void ARM_MPU_ClrRegionEx(MPU_Type* mpu, uint32_t rnr) -{ - mpu->RNR = rnr; - mpu->RLAR = 0U; -} - -/** Clear and disable the given MPU region. -* \param rnr Region number to be cleared. -*/ -__STATIC_INLINE void ARM_MPU_ClrRegion(uint32_t rnr) -{ - ARM_MPU_ClrRegionEx(MPU, rnr); -} - -#ifdef MPU_NS -/** Clear and disable the given Non-secure MPU region. -* \param rnr Region number to be cleared. -*/ -__STATIC_INLINE void ARM_MPU_ClrRegion_NS(uint32_t rnr) -{ - ARM_MPU_ClrRegionEx(MPU_NS, rnr); -} -#endif - -/** Configure the given MPU region of the given MPU. -* \param mpu Pointer to MPU to be used. -* \param rnr Region number to be configured. -* \param rbar Value for RBAR register. -* \param rlar Value for RLAR register. -*/ -__STATIC_INLINE void ARM_MPU_SetRegionEx(MPU_Type* mpu, uint32_t rnr, uint32_t rbar, uint32_t rlar) -{ - mpu->RNR = rnr; - mpu->RBAR = rbar; - mpu->RLAR = rlar; -} - -/** Configure the given MPU region. -* \param rnr Region number to be configured. -* \param rbar Value for RBAR register. -* \param rlar Value for RLAR register. -*/ -__STATIC_INLINE void ARM_MPU_SetRegion(uint32_t rnr, uint32_t rbar, uint32_t rlar) -{ - ARM_MPU_SetRegionEx(MPU, rnr, rbar, rlar); -} - -#ifdef MPU_NS -/** Configure the given Non-secure MPU region. -* \param rnr Region number to be configured. -* \param rbar Value for RBAR register. -* \param rlar Value for RLAR register. -*/ -__STATIC_INLINE void ARM_MPU_SetRegion_NS(uint32_t rnr, uint32_t rbar, uint32_t rlar) -{ - ARM_MPU_SetRegionEx(MPU_NS, rnr, rbar, rlar); -} -#endif - -/** Memcopy with strictly ordered memory access, e.g. for register targets. -* \param dst Destination data is copied to. -* \param src Source data is copied from. -* \param len Amount of data words to be copied. -*/ -__STATIC_INLINE void ARM_MPU_OrderedMemcpy(volatile uint32_t* dst, const uint32_t* __RESTRICT src, uint32_t len) -{ - uint32_t i; - for (i = 0U; i < len; ++i) - { - dst[i] = src[i]; - } -} - -/** Load the given number of MPU regions from a table to the given MPU. -* \param mpu Pointer to the MPU registers to be used. -* \param rnr First region number to be configured. -* \param table Pointer to the MPU configuration table. -* \param cnt Amount of regions to be configured. -*/ -__STATIC_INLINE void ARM_MPU_LoadEx(MPU_Type* mpu, uint32_t rnr, ARM_MPU_Region_t const* table, uint32_t cnt) -{ - const uint32_t rowWordSize = sizeof(ARM_MPU_Region_t)/4U; - if (cnt == 1U) { - mpu->RNR = rnr; - ARM_MPU_OrderedMemcpy(&(mpu->RBAR), &(table->RBAR), rowWordSize); - } else { - uint32_t rnrBase = rnr & ~(MPU_TYPE_RALIASES-1U); - uint32_t rnrOffset = rnr % MPU_TYPE_RALIASES; - - mpu->RNR = rnrBase; - while ((rnrOffset + cnt) > MPU_TYPE_RALIASES) { - uint32_t c = MPU_TYPE_RALIASES - rnrOffset; - ARM_MPU_OrderedMemcpy(&(mpu->RBAR)+(rnrOffset*2U), &(table->RBAR), c*rowWordSize); - table += c; - cnt -= c; - rnrOffset = 0U; - rnrBase += MPU_TYPE_RALIASES; - mpu->RNR = rnrBase; - } - - ARM_MPU_OrderedMemcpy(&(mpu->RBAR)+(rnrOffset*2U), &(table->RBAR), cnt*rowWordSize); - } -} - -/** Load the given number of MPU regions from a table. -* \param rnr First region number to be configured. -* \param table Pointer to the MPU configuration table. -* \param cnt Amount of regions to be configured. -*/ -__STATIC_INLINE void ARM_MPU_Load(uint32_t rnr, ARM_MPU_Region_t const* table, uint32_t cnt) -{ - ARM_MPU_LoadEx(MPU, rnr, table, cnt); -} - -#ifdef MPU_NS -/** Load the given number of MPU regions from a table to the Non-secure MPU. -* \param rnr First region number to be configured. -* \param table Pointer to the MPU configuration table. -* \param cnt Amount of regions to be configured. -*/ -__STATIC_INLINE void ARM_MPU_Load_NS(uint32_t rnr, ARM_MPU_Region_t const* table, uint32_t cnt) -{ - ARM_MPU_LoadEx(MPU_NS, rnr, table, cnt); -} -#endif - -#endif - diff --git a/panda/board/stm32h7/inc/stm32h725xx.h b/panda/board/stm32h7/inc/stm32h725xx.h deleted file mode 100644 index 0e0d4a9..0000000 --- a/panda/board/stm32h7/inc/stm32h725xx.h +++ /dev/null @@ -1,24740 +0,0 @@ -/** - ****************************************************************************** - * @file stm32h735xx.h - * @author MCD Application Team - * @brief CMSIS STM32H735xx Device Peripheral Access Layer Header File. - * - * This file contains: - * - Data structures and the address mapping for all peripherals - * - Peripheral's registers declarations and bits definition - * - Macros to access peripheral's registers hardware - * - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2019 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/** @addtogroup CMSIS_Device - * @{ - */ - -/** @addtogroup stm32h735xx - * @{ - */ - -#ifndef STM32H735xx_H -#define STM32H735xx_H - -#ifdef __cplusplus - extern "C" { -#endif /* __cplusplus */ - -/** @addtogroup Peripheral_interrupt_number_definition - * @{ - */ - -/** - * @brief STM32H7XX Interrupt Number Definition, according to the selected device - * in @ref Library_configuration_section - */ -typedef enum -{ -/****** Cortex-M Processor Exceptions Numbers *****************************************************************/ - NonMaskableInt_IRQn = -14, /*!< 2 Non Maskable Interrupt */ - HardFault_IRQn = -13, /*!< 4 Cortex-M Memory Management Interrupt */ - MemoryManagement_IRQn = -12, /*!< 4 Cortex-M Memory Management Interrupt */ - BusFault_IRQn = -11, /*!< 5 Cortex-M Bus Fault Interrupt */ - UsageFault_IRQn = -10, /*!< 6 Cortex-M Usage Fault Interrupt */ - SVCall_IRQn = -5, /*!< 11 Cortex-M SV Call Interrupt */ - DebugMonitor_IRQn = -4, /*!< 12 Cortex-M Debug Monitor Interrupt */ - PendSV_IRQn = -2, /*!< 14 Cortex-M Pend SV Interrupt */ - SysTick_IRQn = -1, /*!< 15 Cortex-M System Tick Interrupt */ -/****** STM32 specific Interrupt Numbers **********************************************************************/ - WWDG_IRQn = 0, /*!< Window WatchDog Interrupt ( wwdg1_it, wwdg2_it) */ - PVD_AVD_IRQn = 1, /*!< PVD/AVD through EXTI Line detection Interrupt */ - TAMP_STAMP_IRQn = 2, /*!< Tamper and TimeStamp interrupts through the EXTI line */ - RTC_WKUP_IRQn = 3, /*!< RTC Wakeup interrupt through the EXTI line */ - FLASH_IRQn = 4, /*!< FLASH global Interrupt */ - RCC_IRQn = 5, /*!< RCC global Interrupt */ - EXTI0_IRQn = 6, /*!< EXTI Line0 Interrupt */ - EXTI1_IRQn = 7, /*!< EXTI Line1 Interrupt */ - EXTI2_IRQn = 8, /*!< EXTI Line2 Interrupt */ - EXTI3_IRQn = 9, /*!< EXTI Line3 Interrupt */ - EXTI4_IRQn = 10, /*!< EXTI Line4 Interrupt */ - DMA1_Stream0_IRQn = 11, /*!< DMA1 Stream 0 global Interrupt */ - DMA1_Stream1_IRQn = 12, /*!< DMA1 Stream 1 global Interrupt */ - DMA1_Stream2_IRQn = 13, /*!< DMA1 Stream 2 global Interrupt */ - DMA1_Stream3_IRQn = 14, /*!< DMA1 Stream 3 global Interrupt */ - DMA1_Stream4_IRQn = 15, /*!< DMA1 Stream 4 global Interrupt */ - DMA1_Stream5_IRQn = 16, /*!< DMA1 Stream 5 global Interrupt */ - DMA1_Stream6_IRQn = 17, /*!< DMA1 Stream 6 global Interrupt */ - ADC_IRQn = 18, /*!< ADC1 and ADC2 global Interrupts */ - FDCAN1_IT0_IRQn = 19, /*!< FDCAN1 Interrupt line 0 */ - FDCAN2_IT0_IRQn = 20, /*!< FDCAN2 Interrupt line 0 */ - FDCAN1_IT1_IRQn = 21, /*!< FDCAN1 Interrupt line 1 */ - FDCAN2_IT1_IRQn = 22, /*!< FDCAN2 Interrupt line 1 */ - EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ - TIM1_BRK_IRQn = 24, /*!< TIM1 Break Interrupt */ - TIM1_UP_IRQn = 25, /*!< TIM1 Update Interrupt */ - TIM1_TRG_COM_IRQn = 26, /*!< TIM1 Trigger and Commutation Interrupt */ - TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ - TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ - TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ - TIM4_IRQn = 30, /*!< TIM4 global Interrupt */ - I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ - I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ - I2C2_EV_IRQn = 33, /*!< I2C2 Event Interrupt */ - I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */ - SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ - SPI2_IRQn = 36, /*!< SPI2 global Interrupt */ - USART1_IRQn = 37, /*!< USART1 global Interrupt */ - USART2_IRQn = 38, /*!< USART2 global Interrupt */ - USART3_IRQn = 39, /*!< USART3 global Interrupt */ - EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ - RTC_Alarm_IRQn = 41, /*!< RTC Alarm (A and B) through EXTI Line Interrupt */ - TIM8_BRK_TIM12_IRQn = 43, /*!< TIM8 Break Interrupt and TIM12 global interrupt */ - TIM8_UP_TIM13_IRQn = 44, /*!< TIM8 Update Interrupt and TIM13 global interrupt */ - TIM8_TRG_COM_TIM14_IRQn = 45, /*!< TIM8 Trigger and Commutation Interrupt and TIM14 global interrupt */ - TIM8_CC_IRQn = 46, /*!< TIM8 Capture Compare Interrupt */ - DMA1_Stream7_IRQn = 47, /*!< DMA1 Stream7 Interrupt */ - FMC_IRQn = 48, /*!< FMC global Interrupt */ - SDMMC1_IRQn = 49, /*!< SDMMC1 global Interrupt */ - TIM5_IRQn = 50, /*!< TIM5 global Interrupt */ - SPI3_IRQn = 51, /*!< SPI3 global Interrupt */ - UART4_IRQn = 52, /*!< UART4 global Interrupt */ - UART5_IRQn = 53, /*!< UART5 global Interrupt */ - TIM6_DAC_IRQn = 54, /*!< TIM6 global and DAC1&2 underrun error interrupts */ - TIM7_IRQn = 55, /*!< TIM7 global interrupt */ - DMA2_Stream0_IRQn = 56, /*!< DMA2 Stream 0 global Interrupt */ - DMA2_Stream1_IRQn = 57, /*!< DMA2 Stream 1 global Interrupt */ - DMA2_Stream2_IRQn = 58, /*!< DMA2 Stream 2 global Interrupt */ - DMA2_Stream3_IRQn = 59, /*!< DMA2 Stream 3 global Interrupt */ - DMA2_Stream4_IRQn = 60, /*!< DMA2 Stream 4 global Interrupt */ - ETH_IRQn = 61, /*!< Ethernet global Interrupt */ - ETH_WKUP_IRQn = 62, /*!< Ethernet Wakeup through EXTI line Interrupt */ - FDCAN_CAL_IRQn = 63, /*!< FDCAN Calibration unit Interrupt */ - DMA2_Stream5_IRQn = 68, /*!< DMA2 Stream 5 global interrupt */ - DMA2_Stream6_IRQn = 69, /*!< DMA2 Stream 6 global interrupt */ - DMA2_Stream7_IRQn = 70, /*!< DMA2 Stream 7 global interrupt */ - USART6_IRQn = 71, /*!< USART6 global interrupt */ - I2C3_EV_IRQn = 72, /*!< I2C3 event interrupt */ - I2C3_ER_IRQn = 73, /*!< I2C3 error interrupt */ - OTG_HS_EP1_OUT_IRQn = 74, /*!< USB OTG HS End Point 1 Out global interrupt */ - OTG_HS_EP1_IN_IRQn = 75, /*!< USB OTG HS End Point 1 In global interrupt */ - OTG_HS_WKUP_IRQn = 76, /*!< USB OTG HS Wakeup through EXTI interrupt */ - OTG_HS_IRQn = 77, /*!< USB OTG HS global interrupt */ - DCMI_PSSI_IRQn = 78, /*!< DCMI and PSSI global interrupt */ - CRYP_IRQn = 79, /*!< CRYP crypto global interrupt */ - HASH_RNG_IRQn = 80, /*!< HASH and RNG global interrupt */ - FPU_IRQn = 81, /*!< FPU global interrupt */ - UART7_IRQn = 82, /*!< UART7 global interrupt */ - UART8_IRQn = 83, /*!< UART8 global interrupt */ - SPI4_IRQn = 84, /*!< SPI4 global Interrupt */ - SPI5_IRQn = 85, /*!< SPI5 global Interrupt */ - SPI6_IRQn = 86, /*!< SPI6 global Interrupt */ - SAI1_IRQn = 87, /*!< SAI1 global Interrupt */ - LTDC_IRQn = 88, /*!< LTDC global Interrupt */ - LTDC_ER_IRQn = 89, /*!< LTDC Error global Interrupt */ - DMA2D_IRQn = 90, /*!< DMA2D global Interrupt */ - OCTOSPI1_IRQn = 92, /*!< OCTOSPI1 global interrupt */ - LPTIM1_IRQn = 93, /*!< LP TIM1 interrupt */ - CEC_IRQn = 94, /*!< HDMI-CEC global Interrupt */ - I2C4_EV_IRQn = 95, /*!< I2C4 Event Interrupt */ - I2C4_ER_IRQn = 96, /*!< I2C4 Error Interrupt */ - SPDIF_RX_IRQn = 97, /*!< SPDIF-RX global Interrupt */ - DMAMUX1_OVR_IRQn = 102, /*! - -/** @addtogroup Peripheral_registers_structures - * @{ - */ - -/** - * @brief Analog to Digital Converter - */ - -typedef struct -{ - __IO uint32_t ISR; /*!< ADC Interrupt and Status Register, Address offset: 0x00 */ - __IO uint32_t IER; /*!< ADC Interrupt Enable Register, Address offset: 0x04 */ - __IO uint32_t CR; /*!< ADC control register, Address offset: 0x08 */ - __IO uint32_t CFGR; /*!< ADC Configuration register, Address offset: 0x0C */ - __IO uint32_t CFGR2; /*!< ADC Configuration register 2, Address offset: 0x10 */ - __IO uint32_t SMPR1; /*!< ADC sample time register 1, Address offset: 0x14 */ - __IO uint32_t SMPR2; /*!< ADC sample time register 2, Address offset: 0x18 */ - __IO uint32_t PCSEL_RES0; /*!< Rserved for ADC3, ADC1/2 pre-channel selection, Address offset: 0x1C */ - __IO uint32_t LTR1_TR1; /*!< ADC watchdog Lower threshold register 1, Address offset: 0x20 */ - __IO uint32_t HTR1_TR2; /*!< ADC watchdog higher threshold register 1, Address offset: 0x24 */ - __IO uint32_t RES1_TR3; /*!< Rserved for ADC1/2, ADC3 threshold register, Address offset: 0x28 */ - uint32_t RESERVED2; /*!< Reserved, 0x02C */ - __IO uint32_t SQR1; /*!< ADC regular sequence register 1, Address offset: 0x30 */ - __IO uint32_t SQR2; /*!< ADC regular sequence register 2, Address offset: 0x34 */ - __IO uint32_t SQR3; /*!< ADC regular sequence register 3, Address offset: 0x38 */ - __IO uint32_t SQR4; /*!< ADC regular sequence register 4, Address offset: 0x3C */ - __IO uint32_t DR; /*!< ADC regular data register, Address offset: 0x40 */ - uint32_t RESERVED3; /*!< Reserved, 0x044 */ - uint32_t RESERVED4; /*!< Reserved, 0x048 */ - __IO uint32_t JSQR; /*!< ADC injected sequence register, Address offset: 0x4C */ - uint32_t RESERVED5[4]; /*!< Reserved, 0x050 - 0x05C */ - __IO uint32_t OFR1; /*!< ADC offset register 1, Address offset: 0x60 */ - __IO uint32_t OFR2; /*!< ADC offset register 2, Address offset: 0x64 */ - __IO uint32_t OFR3; /*!< ADC offset register 3, Address offset: 0x68 */ - __IO uint32_t OFR4; /*!< ADC offset register 4, Address offset: 0x6C */ - uint32_t RESERVED6[4]; /*!< Reserved, 0x070 - 0x07C */ - __IO uint32_t JDR1; /*!< ADC injected data register 1, Address offset: 0x80 */ - __IO uint32_t JDR2; /*!< ADC injected data register 2, Address offset: 0x84 */ - __IO uint32_t JDR3; /*!< ADC injected data register 3, Address offset: 0x88 */ - __IO uint32_t JDR4; /*!< ADC injected data register 4, Address offset: 0x8C */ - uint32_t RESERVED7[4]; /*!< Reserved, 0x090 - 0x09C */ - __IO uint32_t AWD2CR; /*!< ADC Analog Watchdog 2 Configuration Register, Address offset: 0xA0 */ - __IO uint32_t AWD3CR; /*!< ADC Analog Watchdog 3 Configuration Register, Address offset: 0xA4 */ - uint32_t RESERVED8; /*!< Reserved, 0x0A8 */ - uint32_t RESERVED9; /*!< Reserved, 0x0AC */ - __IO uint32_t LTR2_DIFSEL; /*!< ADC watchdog Lower threshold register 2, Difsel for ADC3, Address offset: 0xB0 */ - __IO uint32_t HTR2_CALFACT; /*!< ADC watchdog Higher threshold register 2, Calfact for ADC3, Address offset: 0xB4 */ - __IO uint32_t LTR3_RES10; /*!< ADC watchdog Lower threshold register 3, specific ADC1/2, Address offset: 0xB8 */ - __IO uint32_t HTR3_RES11; /*!< ADC watchdog Higher threshold register 3, specific ADC1/2, Address offset: 0xBC */ - __IO uint32_t DIFSEL_RES12; /*!< ADC Differential Mode Selection Register specific ADC1/2, Address offset: 0xC0 */ - __IO uint32_t CALFACT_RES13; /*!< ADC Calibration Factors specific ADC1/2, Address offset: 0xC4 */ - __IO uint32_t CALFACT2_RES14; /*!< ADC Linearity Calibration Factors specific ADC1/2, Address offset: 0xC8 */ -} ADC_TypeDef; - - -typedef struct -{ -__IO uint32_t CSR; /*!< ADC Common status register, Address offset: ADC1/3 base address + 0x300 */ -uint32_t RESERVED; /*!< Reserved, ADC1/3 base address + 0x304 */ -__IO uint32_t CCR; /*!< ADC common control register, Address offset: ADC1/3 base address + 0x308 */ -__IO uint32_t CDR; /*!< ADC common regular data register for dual Address offset: ADC1/3 base address + 0x30C */ -__IO uint32_t CDR2; /*!< ADC common regular data register for 32-bit dual mode Address offset: ADC1/3 base address + 0x310 */ - -} ADC_Common_TypeDef; - - -/** - * @brief VREFBUF - */ - -typedef struct -{ - __IO uint32_t CSR; /*!< VREFBUF control and status register, Address offset: 0x00 */ - __IO uint32_t CCR; /*!< VREFBUF calibration and control register, Address offset: 0x04 */ -} VREFBUF_TypeDef; - - -/** - * @brief FD Controller Area Network - */ - -typedef struct -{ - __IO uint32_t CREL; /*!< FDCAN Core Release register, Address offset: 0x000 */ - __IO uint32_t ENDN; /*!< FDCAN Endian register, Address offset: 0x004 */ - __IO uint32_t RESERVED1; /*!< Reserved, 0x008 */ - __IO uint32_t DBTP; /*!< FDCAN Data Bit Timing & Prescaler register, Address offset: 0x00C */ - __IO uint32_t TEST; /*!< FDCAN Test register, Address offset: 0x010 */ - __IO uint32_t RWD; /*!< FDCAN RAM Watchdog register, Address offset: 0x014 */ - __IO uint32_t CCCR; /*!< FDCAN CC Control register, Address offset: 0x018 */ - __IO uint32_t NBTP; /*!< FDCAN Nominal Bit Timing & Prescaler register, Address offset: 0x01C */ - __IO uint32_t TSCC; /*!< FDCAN Timestamp Counter Configuration register, Address offset: 0x020 */ - __IO uint32_t TSCV; /*!< FDCAN Timestamp Counter Value register, Address offset: 0x024 */ - __IO uint32_t TOCC; /*!< FDCAN Timeout Counter Configuration register, Address offset: 0x028 */ - __IO uint32_t TOCV; /*!< FDCAN Timeout Counter Value register, Address offset: 0x02C */ - __IO uint32_t RESERVED2[4]; /*!< Reserved, 0x030 - 0x03C */ - __IO uint32_t ECR; /*!< FDCAN Error Counter register, Address offset: 0x040 */ - __IO uint32_t PSR; /*!< FDCAN Protocol Status register, Address offset: 0x044 */ - __IO uint32_t TDCR; /*!< FDCAN Transmitter Delay Compensation register, Address offset: 0x048 */ - __IO uint32_t RESERVED3; /*!< Reserved, 0x04C */ - __IO uint32_t IR; /*!< FDCAN Interrupt register, Address offset: 0x050 */ - __IO uint32_t IE; /*!< FDCAN Interrupt Enable register, Address offset: 0x054 */ - __IO uint32_t ILS; /*!< FDCAN Interrupt Line Select register, Address offset: 0x058 */ - __IO uint32_t ILE; /*!< FDCAN Interrupt Line Enable register, Address offset: 0x05C */ - __IO uint32_t RESERVED4[8]; /*!< Reserved, 0x060 - 0x07C */ - __IO uint32_t GFC; /*!< FDCAN Global Filter Configuration register, Address offset: 0x080 */ - __IO uint32_t SIDFC; /*!< FDCAN Standard ID Filter Configuration register, Address offset: 0x084 */ - __IO uint32_t XIDFC; /*!< FDCAN Extended ID Filter Configuration register, Address offset: 0x088 */ - __IO uint32_t RESERVED5; /*!< Reserved, 0x08C */ - __IO uint32_t XIDAM; /*!< FDCAN Extended ID AND Mask register, Address offset: 0x090 */ - __IO uint32_t HPMS; /*!< FDCAN High Priority Message Status register, Address offset: 0x094 */ - __IO uint32_t NDAT1; /*!< FDCAN New Data 1 register, Address offset: 0x098 */ - __IO uint32_t NDAT2; /*!< FDCAN New Data 2 register, Address offset: 0x09C */ - __IO uint32_t RXF0C; /*!< FDCAN Rx FIFO 0 Configuration register, Address offset: 0x0A0 */ - __IO uint32_t RXF0S; /*!< FDCAN Rx FIFO 0 Status register, Address offset: 0x0A4 */ - __IO uint32_t RXF0A; /*!< FDCAN Rx FIFO 0 Acknowledge register, Address offset: 0x0A8 */ - __IO uint32_t RXBC; /*!< FDCAN Rx Buffer Configuration register, Address offset: 0x0AC */ - __IO uint32_t RXF1C; /*!< FDCAN Rx FIFO 1 Configuration register, Address offset: 0x0B0 */ - __IO uint32_t RXF1S; /*!< FDCAN Rx FIFO 1 Status register, Address offset: 0x0B4 */ - __IO uint32_t RXF1A; /*!< FDCAN Rx FIFO 1 Acknowledge register, Address offset: 0x0B8 */ - __IO uint32_t RXESC; /*!< FDCAN Rx Buffer/FIFO Element Size Configuration register, Address offset: 0x0BC */ - __IO uint32_t TXBC; /*!< FDCAN Tx Buffer Configuration register, Address offset: 0x0C0 */ - __IO uint32_t TXFQS; /*!< FDCAN Tx FIFO/Queue Status register, Address offset: 0x0C4 */ - __IO uint32_t TXESC; /*!< FDCAN Tx Buffer Element Size Configuration register, Address offset: 0x0C8 */ - __IO uint32_t TXBRP; /*!< FDCAN Tx Buffer Request Pending register, Address offset: 0x0CC */ - __IO uint32_t TXBAR; /*!< FDCAN Tx Buffer Add Request register, Address offset: 0x0D0 */ - __IO uint32_t TXBCR; /*!< FDCAN Tx Buffer Cancellation Request register, Address offset: 0x0D4 */ - __IO uint32_t TXBTO; /*!< FDCAN Tx Buffer Transmission Occurred register, Address offset: 0x0D8 */ - __IO uint32_t TXBCF; /*!< FDCAN Tx Buffer Cancellation Finished register, Address offset: 0x0DC */ - __IO uint32_t TXBTIE; /*!< FDCAN Tx Buffer Transmission Interrupt Enable register, Address offset: 0x0E0 */ - __IO uint32_t TXBCIE; /*!< FDCAN Tx Buffer Cancellation Finished Interrupt Enable register, Address offset: 0x0E4 */ - __IO uint32_t RESERVED6[2]; /*!< Reserved, 0x0E8 - 0x0EC */ - __IO uint32_t TXEFC; /*!< FDCAN Tx Event FIFO Configuration register, Address offset: 0x0F0 */ - __IO uint32_t TXEFS; /*!< FDCAN Tx Event FIFO Status register, Address offset: 0x0F4 */ - __IO uint32_t TXEFA; /*!< FDCAN Tx Event FIFO Acknowledge register, Address offset: 0x0F8 */ - __IO uint32_t RESERVED7; /*!< Reserved, 0x0FC */ -} FDCAN_GlobalTypeDef; - -/** - * @brief TTFD Controller Area Network - */ - -typedef struct -{ - __IO uint32_t TTTMC; /*!< TT Trigger Memory Configuration register, Address offset: 0x100 */ - __IO uint32_t TTRMC; /*!< TT Reference Message Configuration register, Address offset: 0x104 */ - __IO uint32_t TTOCF; /*!< TT Operation Configuration register, Address offset: 0x108 */ - __IO uint32_t TTMLM; /*!< TT Matrix Limits register, Address offset: 0x10C */ - __IO uint32_t TURCF; /*!< TUR Configuration register, Address offset: 0x110 */ - __IO uint32_t TTOCN; /*!< TT Operation Control register, Address offset: 0x114 */ - __IO uint32_t TTGTP; /*!< TT Global Time Preset register, Address offset: 0x118 */ - __IO uint32_t TTTMK; /*!< TT Time Mark register, Address offset: 0x11C */ - __IO uint32_t TTIR; /*!< TT Interrupt register, Address offset: 0x120 */ - __IO uint32_t TTIE; /*!< TT Interrupt Enable register, Address offset: 0x124 */ - __IO uint32_t TTILS; /*!< TT Interrupt Line Select register, Address offset: 0x128 */ - __IO uint32_t TTOST; /*!< TT Operation Status register, Address offset: 0x12C */ - __IO uint32_t TURNA; /*!< TT TUR Numerator Actual register, Address offset: 0x130 */ - __IO uint32_t TTLGT; /*!< TT Local and Global Time register, Address offset: 0x134 */ - __IO uint32_t TTCTC; /*!< TT Cycle Time and Count register, Address offset: 0x138 */ - __IO uint32_t TTCPT; /*!< TT Capture Time register, Address offset: 0x13C */ - __IO uint32_t TTCSM; /*!< TT Cycle Sync Mark register, Address offset: 0x140 */ - __IO uint32_t RESERVED1[111]; /*!< Reserved, 0x144 - 0x2FC */ - __IO uint32_t TTTS; /*!< TT Trigger Select register, Address offset: 0x300 */ -} TTCAN_TypeDef; - -/** - * @brief FD Controller Area Network - */ - -typedef struct -{ - __IO uint32_t CREL; /*!< Clock Calibration Unit Core Release register, Address offset: 0x00 */ - __IO uint32_t CCFG; /*!< Calibration Configuration register, Address offset: 0x04 */ - __IO uint32_t CSTAT; /*!< Calibration Status register, Address offset: 0x08 */ - __IO uint32_t CWD; /*!< Calibration Watchdog register, Address offset: 0x0C */ - __IO uint32_t IR; /*!< CCU Interrupt register, Address offset: 0x10 */ - __IO uint32_t IE; /*!< CCU Interrupt Enable register, Address offset: 0x14 */ -} FDCAN_ClockCalibrationUnit_TypeDef; - - -/** - * @brief Consumer Electronics Control - */ - -typedef struct -{ - __IO uint32_t CR; /*!< CEC control register, Address offset:0x00 */ - __IO uint32_t CFGR; /*!< CEC configuration register, Address offset:0x04 */ - __IO uint32_t TXDR; /*!< CEC Tx data register , Address offset:0x08 */ - __IO uint32_t RXDR; /*!< CEC Rx Data Register, Address offset:0x0C */ - __IO uint32_t ISR; /*!< CEC Interrupt and Status Register, Address offset:0x10 */ - __IO uint32_t IER; /*!< CEC interrupt enable register, Address offset:0x14 */ -}CEC_TypeDef; - -/** - * @brief COordincate Rotation DIgital Computer - */ -typedef struct -{ - __IO uint32_t CSR; /*!< CORDIC control and status register, Address offset: 0x00 */ - __IO uint32_t WDATA; /*!< CORDIC argument register, Address offset: 0x04 */ - __IO uint32_t RDATA; /*!< CORDIC result register, Address offset: 0x08 */ -} CORDIC_TypeDef; - -/** - * @brief CRC calculation unit - */ - -typedef struct -{ - __IO uint32_t DR; /*!< CRC Data register, Address offset: 0x00 */ - __IO uint32_t IDR; /*!< CRC Independent data register, Address offset: 0x04 */ - __IO uint32_t CR; /*!< CRC Control register, Address offset: 0x08 */ - uint32_t RESERVED2; /*!< Reserved, 0x0C */ - __IO uint32_t INIT; /*!< Initial CRC value register, Address offset: 0x10 */ - __IO uint32_t POL; /*!< CRC polynomial register, Address offset: 0x14 */ -} CRC_TypeDef; - - -/** - * @brief Clock Recovery System - */ -typedef struct -{ -__IO uint32_t CR; /*!< CRS ccontrol register, Address offset: 0x00 */ -__IO uint32_t CFGR; /*!< CRS configuration register, Address offset: 0x04 */ -__IO uint32_t ISR; /*!< CRS interrupt and status register, Address offset: 0x08 */ -__IO uint32_t ICR; /*!< CRS interrupt flag clear register, Address offset: 0x0C */ -} CRS_TypeDef; - - -/** - * @brief Digital to Analog Converter - */ - -typedef struct -{ - __IO uint32_t CR; /*!< DAC control register, Address offset: 0x00 */ - __IO uint32_t SWTRIGR; /*!< DAC software trigger register, Address offset: 0x04 */ - __IO uint32_t DHR12R1; /*!< DAC channel1 12-bit right-aligned data holding register, Address offset: 0x08 */ - __IO uint32_t DHR12L1; /*!< DAC channel1 12-bit left aligned data holding register, Address offset: 0x0C */ - __IO uint32_t DHR8R1; /*!< DAC channel1 8-bit right aligned data holding register, Address offset: 0x10 */ - __IO uint32_t DHR12R2; /*!< DAC channel2 12-bit right aligned data holding register, Address offset: 0x14 */ - __IO uint32_t DHR12L2; /*!< DAC channel2 12-bit left aligned data holding register, Address offset: 0x18 */ - __IO uint32_t DHR8R2; /*!< DAC channel2 8-bit right-aligned data holding register, Address offset: 0x1C */ - __IO uint32_t DHR12RD; /*!< Dual DAC 12-bit right-aligned data holding register, Address offset: 0x20 */ - __IO uint32_t DHR12LD; /*!< DUAL DAC 12-bit left aligned data holding register, Address offset: 0x24 */ - __IO uint32_t DHR8RD; /*!< DUAL DAC 8-bit right aligned data holding register, Address offset: 0x28 */ - __IO uint32_t DOR1; /*!< DAC channel1 data output register, Address offset: 0x2C */ - __IO uint32_t DOR2; /*!< DAC channel2 data output register, Address offset: 0x30 */ - __IO uint32_t SR; /*!< DAC status register, Address offset: 0x34 */ - __IO uint32_t CCR; /*!< DAC calibration control register, Address offset: 0x38 */ - __IO uint32_t MCR; /*!< DAC mode control register, Address offset: 0x3C */ - __IO uint32_t SHSR1; /*!< DAC Sample and Hold sample time register 1, Address offset: 0x40 */ - __IO uint32_t SHSR2; /*!< DAC Sample and Hold sample time register 2, Address offset: 0x44 */ - __IO uint32_t SHHR; /*!< DAC Sample and Hold hold time register, Address offset: 0x48 */ - __IO uint32_t SHRR; /*!< DAC Sample and Hold refresh time register, Address offset: 0x4C */ -} DAC_TypeDef; - -/** - * @brief DFSDM module registers - */ -typedef struct -{ - __IO uint32_t FLTCR1; /*!< DFSDM control register1, Address offset: 0x100 */ - __IO uint32_t FLTCR2; /*!< DFSDM control register2, Address offset: 0x104 */ - __IO uint32_t FLTISR; /*!< DFSDM interrupt and status register, Address offset: 0x108 */ - __IO uint32_t FLTICR; /*!< DFSDM interrupt flag clear register, Address offset: 0x10C */ - __IO uint32_t FLTJCHGR; /*!< DFSDM injected channel group selection register, Address offset: 0x110 */ - __IO uint32_t FLTFCR; /*!< DFSDM filter control register, Address offset: 0x114 */ - __IO uint32_t FLTJDATAR; /*!< DFSDM data register for injected group, Address offset: 0x118 */ - __IO uint32_t FLTRDATAR; /*!< DFSDM data register for regular group, Address offset: 0x11C */ - __IO uint32_t FLTAWHTR; /*!< DFSDM analog watchdog high threshold register, Address offset: 0x120 */ - __IO uint32_t FLTAWLTR; /*!< DFSDM analog watchdog low threshold register, Address offset: 0x124 */ - __IO uint32_t FLTAWSR; /*!< DFSDM analog watchdog status register Address offset: 0x128 */ - __IO uint32_t FLTAWCFR; /*!< DFSDM analog watchdog clear flag register Address offset: 0x12C */ - __IO uint32_t FLTEXMAX; /*!< DFSDM extreme detector maximum register, Address offset: 0x130 */ - __IO uint32_t FLTEXMIN; /*!< DFSDM extreme detector minimum register Address offset: 0x134 */ - __IO uint32_t FLTCNVTIMR; /*!< DFSDM conversion timer, Address offset: 0x138 */ -} DFSDM_Filter_TypeDef; - -/** - * @brief DFSDM channel configuration registers - */ -typedef struct -{ - __IO uint32_t CHCFGR1; /*!< DFSDM channel configuration register1, Address offset: 0x00 */ - __IO uint32_t CHCFGR2; /*!< DFSDM channel configuration register2, Address offset: 0x04 */ - __IO uint32_t CHAWSCDR; /*!< DFSDM channel analog watchdog and - short circuit detector register, Address offset: 0x08 */ - __IO uint32_t CHWDATAR; /*!< DFSDM channel watchdog filter data register, Address offset: 0x0C */ - __IO uint32_t CHDATINR; /*!< DFSDM channel data input register, Address offset: 0x10 */ -} DFSDM_Channel_TypeDef; - -/** - * @brief Debug MCU - */ -typedef struct -{ - __IO uint32_t IDCODE; /*!< MCU device ID code, Address offset: 0x00 */ - __IO uint32_t CR; /*!< Debug MCU configuration register, Address offset: 0x04 */ - uint32_t RESERVED4[11]; /*!< Reserved, Address offset: 0x08 */ - __IO uint32_t APB3FZ1; /*!< Debug MCU APB3FZ1 freeze register, Address offset: 0x34 */ - uint32_t RESERVED5; /*!< Reserved, Address offset: 0x38 */ - __IO uint32_t APB1LFZ1; /*!< Debug MCU APB1LFZ1 freeze register, Address offset: 0x3C */ - uint32_t RESERVED6; /*!< Reserved, Address offset: 0x40 */ - __IO uint32_t APB1HFZ1; /*!< Debug MCU APB1LFZ1 freeze register, Address offset: 0x44 */ - uint32_t RESERVED7; /*!< Reserved, Address offset: 0x48 */ - __IO uint32_t APB2FZ1; /*!< Debug MCU APB2FZ1 freeze register, Address offset: 0x4C */ - uint32_t RESERVED8; /*!< Reserved, Address offset: 0x50 */ - __IO uint32_t APB4FZ1; /*!< Debug MCU APB4FZ1 freeze register, Address offset: 0x54 */ - __IO uint32_t RESERVED9[990]; /*!< Reserved, Address offset: 0x58-0xFCC */ - __IO uint32_t PIDR4; /*!< Debug MCU peripheral identity register 4, Address offset: 0xFD0 */ - __IO uint32_t RESERVED10[3];/*!< Reserved, Address offset: 0xFD4-0xFDC */ - __IO uint32_t PIDR0; /*!< Debug MCU peripheral identity register 0, Address offset: 0xFE0 */ - __IO uint32_t PIDR1; /*!< Debug MCU peripheral identity register 1, Address offset: 0xFE4 */ - __IO uint32_t PIDR2; /*!< Debug MCU peripheral identity register 2, Address offset: 0xFE8 */ - __IO uint32_t PIDR3; /*!< Debug MCU peripheral identity register 3, Address offset: 0xFEC */ - __IO uint32_t CIDR0; /*!< Debug MCU component identity register 0, Address offset: 0xFF0 */ - __IO uint32_t CIDR1; /*!< Debug MCU component identity register 1, Address offset: 0xFF4 */ - __IO uint32_t CIDR2; /*!< Debug MCU component identity register 2, Address offset: 0xFF8 */ - __IO uint32_t CIDR3; /*!< Debug MCU component identity register 3, Address offset: 0xFFC */ -}DBGMCU_TypeDef; -/** - * @brief DCMI - */ - -typedef struct -{ - __IO uint32_t CR; /*!< DCMI control register 1, Address offset: 0x00 */ - __IO uint32_t SR; /*!< DCMI status register, Address offset: 0x04 */ - __IO uint32_t RISR; /*!< DCMI raw interrupt status register, Address offset: 0x08 */ - __IO uint32_t IER; /*!< DCMI interrupt enable register, Address offset: 0x0C */ - __IO uint32_t MISR; /*!< DCMI masked interrupt status register, Address offset: 0x10 */ - __IO uint32_t ICR; /*!< DCMI interrupt clear register, Address offset: 0x14 */ - __IO uint32_t ESCR; /*!< DCMI embedded synchronization code register, Address offset: 0x18 */ - __IO uint32_t ESUR; /*!< DCMI embedded synchronization unmask register, Address offset: 0x1C */ - __IO uint32_t CWSTRTR; /*!< DCMI crop window start, Address offset: 0x20 */ - __IO uint32_t CWSIZER; /*!< DCMI crop window size, Address offset: 0x24 */ - __IO uint32_t DR; /*!< DCMI data register, Address offset: 0x28 */ -} DCMI_TypeDef; - -/** - * @brief PSSI - */ - -typedef struct -{ - __IO uint32_t CR; /*!< PSSI control register 1, Address offset: 0x000 */ - __IO uint32_t SR; /*!< PSSI status register, Address offset: 0x004 */ - __IO uint32_t RIS; /*!< PSSI raw interrupt status register, Address offset: 0x008 */ - __IO uint32_t IER; /*!< PSSI interrupt enable register, Address offset: 0x00C */ - __IO uint32_t MIS; /*!< PSSI masked interrupt status register, Address offset: 0x010 */ - __IO uint32_t ICR; /*!< PSSI interrupt clear register, Address offset: 0x014 */ - __IO uint32_t RESERVED1[4]; /*!< Reserved, 0x018 - 0x024 */ - __IO uint32_t DR; /*!< PSSI data register, Address offset: 0x028 */ - __IO uint32_t RESERVED2[241]; /*!< Reserved, 0x02C - 0x3EC */ - __IO uint32_t HWCFGR; /*!< PSSI IP HW configuration register, Address offset: 0x3F0 */ - __IO uint32_t VERR; /*!< PSSI IP version register, Address offset: 0x3F4 */ - __IO uint32_t IPIDR; /*!< PSSI IP ID register, Address offset: 0x3F8 */ - __IO uint32_t SIDR; /*!< PSSI SIZE ID register, Address offset: 0x3FC */ -} PSSI_TypeDef; - -/** - * @brief DMA Controller - */ - -typedef struct -{ - __IO uint32_t CR; /*!< DMA stream x configuration register */ - __IO uint32_t NDTR; /*!< DMA stream x number of data register */ - __IO uint32_t PAR; /*!< DMA stream x peripheral address register */ - __IO uint32_t M0AR; /*!< DMA stream x memory 0 address register */ - __IO uint32_t M1AR; /*!< DMA stream x memory 1 address register */ - __IO uint32_t FCR; /*!< DMA stream x FIFO control register */ -} DMA_Stream_TypeDef; - -typedef struct -{ - __IO uint32_t LISR; /*!< DMA low interrupt status register, Address offset: 0x00 */ - __IO uint32_t HISR; /*!< DMA high interrupt status register, Address offset: 0x04 */ - __IO uint32_t LIFCR; /*!< DMA low interrupt flag clear register, Address offset: 0x08 */ - __IO uint32_t HIFCR; /*!< DMA high interrupt flag clear register, Address offset: 0x0C */ -} DMA_TypeDef; - -typedef struct -{ - __IO uint32_t CCR; /*!< DMA channel x configuration register */ - __IO uint32_t CNDTR; /*!< DMA channel x number of data register */ - __IO uint32_t CPAR; /*!< DMA channel x peripheral address register */ - __IO uint32_t CM0AR; /*!< DMA channel x memory 0 address register */ - __IO uint32_t CM1AR; /*!< DMA channel x memory 1 address register */ -} BDMA_Channel_TypeDef; - -typedef struct -{ - __IO uint32_t ISR; /*!< DMA interrupt status register, Address offset: 0x00 */ - __IO uint32_t IFCR; /*!< DMA interrupt flag clear register, Address offset: 0x04 */ -} BDMA_TypeDef; - -typedef struct -{ - __IO uint32_t CCR; /*!< DMA Multiplexer Channel x Control Register */ -}DMAMUX_Channel_TypeDef; - -typedef struct -{ - __IO uint32_t CSR; /*!< DMA Channel Status Register */ - __IO uint32_t CFR; /*!< DMA Channel Clear Flag Register */ -}DMAMUX_ChannelStatus_TypeDef; - -typedef struct -{ - __IO uint32_t RGCR; /*!< DMA Request Generator x Control Register */ -}DMAMUX_RequestGen_TypeDef; - -typedef struct -{ - __IO uint32_t RGSR; /*!< DMA Request Generator Status Register */ - __IO uint32_t RGCFR; /*!< DMA Request Generator Clear Flag Register */ -}DMAMUX_RequestGenStatus_TypeDef; - -/** - * @brief MDMA Controller - */ -typedef struct -{ - __IO uint32_t GISR0; /*!< MDMA Global Interrupt/Status Register 0, Address offset: 0x00 */ -}MDMA_TypeDef; - -typedef struct -{ - __IO uint32_t CISR; /*!< MDMA channel x interrupt/status register, Address offset: 0x40 */ - __IO uint32_t CIFCR; /*!< MDMA channel x interrupt flag clear register, Address offset: 0x44 */ - __IO uint32_t CESR; /*!< MDMA Channel x error status register, Address offset: 0x48 */ - __IO uint32_t CCR; /*!< MDMA channel x control register, Address offset: 0x4C */ - __IO uint32_t CTCR; /*!< MDMA channel x Transfer Configuration register, Address offset: 0x50 */ - __IO uint32_t CBNDTR; /*!< MDMA Channel x block number of data register, Address offset: 0x54 */ - __IO uint32_t CSAR; /*!< MDMA channel x source address register, Address offset: 0x58 */ - __IO uint32_t CDAR; /*!< MDMA channel x destination address register, Address offset: 0x5C */ - __IO uint32_t CBRUR; /*!< MDMA channel x Block Repeat address Update register, Address offset: 0x60 */ - __IO uint32_t CLAR; /*!< MDMA channel x Link Address register, Address offset: 0x64 */ - __IO uint32_t CTBR; /*!< MDMA channel x Trigger and Bus selection Register, Address offset: 0x68 */ - uint32_t RESERVED0; /*!< Reserved, 0x6C */ - __IO uint32_t CMAR; /*!< MDMA channel x Mask address register, Address offset: 0x70 */ - __IO uint32_t CMDR; /*!< MDMA channel x Mask Data register, Address offset: 0x74 */ -}MDMA_Channel_TypeDef; - -/** - * @brief DMA2D Controller - */ - -typedef struct -{ - __IO uint32_t CR; /*!< DMA2D Control Register, Address offset: 0x00 */ - __IO uint32_t ISR; /*!< DMA2D Interrupt Status Register, Address offset: 0x04 */ - __IO uint32_t IFCR; /*!< DMA2D Interrupt Flag Clear Register, Address offset: 0x08 */ - __IO uint32_t FGMAR; /*!< DMA2D Foreground Memory Address Register, Address offset: 0x0C */ - __IO uint32_t FGOR; /*!< DMA2D Foreground Offset Register, Address offset: 0x10 */ - __IO uint32_t BGMAR; /*!< DMA2D Background Memory Address Register, Address offset: 0x14 */ - __IO uint32_t BGOR; /*!< DMA2D Background Offset Register, Address offset: 0x18 */ - __IO uint32_t FGPFCCR; /*!< DMA2D Foreground PFC Control Register, Address offset: 0x1C */ - __IO uint32_t FGCOLR; /*!< DMA2D Foreground Color Register, Address offset: 0x20 */ - __IO uint32_t BGPFCCR; /*!< DMA2D Background PFC Control Register, Address offset: 0x24 */ - __IO uint32_t BGCOLR; /*!< DMA2D Background Color Register, Address offset: 0x28 */ - __IO uint32_t FGCMAR; /*!< DMA2D Foreground CLUT Memory Address Register, Address offset: 0x2C */ - __IO uint32_t BGCMAR; /*!< DMA2D Background CLUT Memory Address Register, Address offset: 0x30 */ - __IO uint32_t OPFCCR; /*!< DMA2D Output PFC Control Register, Address offset: 0x34 */ - __IO uint32_t OCOLR; /*!< DMA2D Output Color Register, Address offset: 0x38 */ - __IO uint32_t OMAR; /*!< DMA2D Output Memory Address Register, Address offset: 0x3C */ - __IO uint32_t OOR; /*!< DMA2D Output Offset Register, Address offset: 0x40 */ - __IO uint32_t NLR; /*!< DMA2D Number of Line Register, Address offset: 0x44 */ - __IO uint32_t LWR; /*!< DMA2D Line Watermark Register, Address offset: 0x48 */ - __IO uint32_t AMTCR; /*!< DMA2D AHB Master Timer Configuration Register, Address offset: 0x4C */ - uint32_t RESERVED[236]; /*!< Reserved, 0x50-0x3FF */ - __IO uint32_t FGCLUT[256]; /*!< DMA2D Foreground CLUT, Address offset:400-7FF */ - __IO uint32_t BGCLUT[256]; /*!< DMA2D Background CLUT, Address offset:800-BFF */ -} DMA2D_TypeDef; - - -/** - * @brief Ethernet MAC - */ -typedef struct -{ - __IO uint32_t MACCR; - __IO uint32_t MACECR; - __IO uint32_t MACPFR; - __IO uint32_t MACWTR; - __IO uint32_t MACHT0R; - __IO uint32_t MACHT1R; - uint32_t RESERVED1[14]; - __IO uint32_t MACVTR; - uint32_t RESERVED2; - __IO uint32_t MACVHTR; - uint32_t RESERVED3; - __IO uint32_t MACVIR; - __IO uint32_t MACIVIR; - uint32_t RESERVED4[2]; - __IO uint32_t MACTFCR; - uint32_t RESERVED5[7]; - __IO uint32_t MACRFCR; - uint32_t RESERVED6[7]; - __IO uint32_t MACISR; - __IO uint32_t MACIER; - __IO uint32_t MACRXTXSR; - uint32_t RESERVED7; - __IO uint32_t MACPCSR; - __IO uint32_t MACRWKPFR; - uint32_t RESERVED8[2]; - __IO uint32_t MACLCSR; - __IO uint32_t MACLTCR; - __IO uint32_t MACLETR; - __IO uint32_t MAC1USTCR; - uint32_t RESERVED9[12]; - __IO uint32_t MACVR; - __IO uint32_t MACDR; - uint32_t RESERVED10; - __IO uint32_t MACHWF0R; - __IO uint32_t MACHWF1R; - __IO uint32_t MACHWF2R; - uint32_t RESERVED11[54]; - __IO uint32_t MACMDIOAR; - __IO uint32_t MACMDIODR; - uint32_t RESERVED12[2]; - __IO uint32_t MACARPAR; - uint32_t RESERVED13[59]; - __IO uint32_t MACA0HR; - __IO uint32_t MACA0LR; - __IO uint32_t MACA1HR; - __IO uint32_t MACA1LR; - __IO uint32_t MACA2HR; - __IO uint32_t MACA2LR; - __IO uint32_t MACA3HR; - __IO uint32_t MACA3LR; - uint32_t RESERVED14[248]; - __IO uint32_t MMCCR; - __IO uint32_t MMCRIR; - __IO uint32_t MMCTIR; - __IO uint32_t MMCRIMR; - __IO uint32_t MMCTIMR; - uint32_t RESERVED15[14]; - __IO uint32_t MMCTSCGPR; - __IO uint32_t MMCTMCGPR; - uint32_t RESERVED16[5]; - __IO uint32_t MMCTPCGR; - uint32_t RESERVED17[10]; - __IO uint32_t MMCRCRCEPR; - __IO uint32_t MMCRAEPR; - uint32_t RESERVED18[10]; - __IO uint32_t MMCRUPGR; - uint32_t RESERVED19[9]; - __IO uint32_t MMCTLPIMSTR; - __IO uint32_t MMCTLPITCR; - __IO uint32_t MMCRLPIMSTR; - __IO uint32_t MMCRLPITCR; - uint32_t RESERVED20[65]; - __IO uint32_t MACL3L4C0R; - __IO uint32_t MACL4A0R; - uint32_t RESERVED21[2]; - __IO uint32_t MACL3A0R0R; - __IO uint32_t MACL3A1R0R; - __IO uint32_t MACL3A2R0R; - __IO uint32_t MACL3A3R0R; - uint32_t RESERVED22[4]; - __IO uint32_t MACL3L4C1R; - __IO uint32_t MACL4A1R; - uint32_t RESERVED23[2]; - __IO uint32_t MACL3A0R1R; - __IO uint32_t MACL3A1R1R; - __IO uint32_t MACL3A2R1R; - __IO uint32_t MACL3A3R1R; - uint32_t RESERVED24[108]; - __IO uint32_t MACTSCR; - __IO uint32_t MACSSIR; - __IO uint32_t MACSTSR; - __IO uint32_t MACSTNR; - __IO uint32_t MACSTSUR; - __IO uint32_t MACSTNUR; - __IO uint32_t MACTSAR; - uint32_t RESERVED25; - __IO uint32_t MACTSSR; - uint32_t RESERVED26[3]; - __IO uint32_t MACTTSSNR; - __IO uint32_t MACTTSSSR; - uint32_t RESERVED27[2]; - __IO uint32_t MACACR; - uint32_t RESERVED28; - __IO uint32_t MACATSNR; - __IO uint32_t MACATSSR; - __IO uint32_t MACTSIACR; - __IO uint32_t MACTSEACR; - __IO uint32_t MACTSICNR; - __IO uint32_t MACTSECNR; - uint32_t RESERVED29[4]; - __IO uint32_t MACPPSCR; - uint32_t RESERVED30[3]; - __IO uint32_t MACPPSTTSR; - __IO uint32_t MACPPSTTNR; - __IO uint32_t MACPPSIR; - __IO uint32_t MACPPSWR; - uint32_t RESERVED31[12]; - __IO uint32_t MACPOCR; - __IO uint32_t MACSPI0R; - __IO uint32_t MACSPI1R; - __IO uint32_t MACSPI2R; - __IO uint32_t MACLMIR; - uint32_t RESERVED32[11]; - __IO uint32_t MTLOMR; - uint32_t RESERVED33[7]; - __IO uint32_t MTLISR; - uint32_t RESERVED34[55]; - __IO uint32_t MTLTQOMR; - __IO uint32_t MTLTQUR; - __IO uint32_t MTLTQDR; - uint32_t RESERVED35[8]; - __IO uint32_t MTLQICSR; - __IO uint32_t MTLRQOMR; - __IO uint32_t MTLRQMPOCR; - __IO uint32_t MTLRQDR; - uint32_t RESERVED36[177]; - __IO uint32_t DMAMR; - __IO uint32_t DMASBMR; - __IO uint32_t DMAISR; - __IO uint32_t DMADSR; - uint32_t RESERVED37[60]; - __IO uint32_t DMACCR; - __IO uint32_t DMACTCR; - __IO uint32_t DMACRCR; - uint32_t RESERVED38[2]; - __IO uint32_t DMACTDLAR; - uint32_t RESERVED39; - __IO uint32_t DMACRDLAR; - __IO uint32_t DMACTDTPR; - uint32_t RESERVED40; - __IO uint32_t DMACRDTPR; - __IO uint32_t DMACTDRLR; - __IO uint32_t DMACRDRLR; - __IO uint32_t DMACIER; - __IO uint32_t DMACRIWTR; -__IO uint32_t DMACSFCSR; - uint32_t RESERVED41; - __IO uint32_t DMACCATDR; - uint32_t RESERVED42; - __IO uint32_t DMACCARDR; - uint32_t RESERVED43; - __IO uint32_t DMACCATBR; - uint32_t RESERVED44; - __IO uint32_t DMACCARBR; - __IO uint32_t DMACSR; -uint32_t RESERVED45[2]; -__IO uint32_t DMACMFCR; -}ETH_TypeDef; -/** - * @brief External Interrupt/Event Controller - */ - -typedef struct -{ -__IO uint32_t RTSR1; /*!< EXTI Rising trigger selection register, Address offset: 0x00 */ -__IO uint32_t FTSR1; /*!< EXTI Falling trigger selection register, Address offset: 0x04 */ -__IO uint32_t SWIER1; /*!< EXTI Software interrupt event register, Address offset: 0x08 */ -__IO uint32_t D3PMR1; /*!< EXTI D3 Pending mask register, (same register as to SRDPMR1) Address offset: 0x0C */ -__IO uint32_t D3PCR1L; /*!< EXTI D3 Pending clear selection register low, (same register as to SRDPCR1L) Address offset: 0x10 */ -__IO uint32_t D3PCR1H; /*!< EXTI D3 Pending clear selection register High, (same register as to SRDPCR1H) Address offset: 0x14 */ -uint32_t RESERVED1[2]; /*!< Reserved, 0x18 to 0x1C */ -__IO uint32_t RTSR2; /*!< EXTI Rising trigger selection register, Address offset: 0x20 */ -__IO uint32_t FTSR2; /*!< EXTI Falling trigger selection register, Address offset: 0x24 */ -__IO uint32_t SWIER2; /*!< EXTI Software interrupt event register, Address offset: 0x28 */ -__IO uint32_t D3PMR2; /*!< EXTI D3 Pending mask register, (same register as to SRDPMR2) Address offset: 0x2C */ -__IO uint32_t D3PCR2L; /*!< EXTI D3 Pending clear selection register low, (same register as to SRDPCR2L) Address offset: 0x30 */ -__IO uint32_t D3PCR2H; /*!< EXTI D3 Pending clear selection register High, (same register as to SRDPCR2H) Address offset: 0x34 */ -uint32_t RESERVED2[2]; /*!< Reserved, 0x38 to 0x3C */ -__IO uint32_t RTSR3; /*!< EXTI Rising trigger selection register, Address offset: 0x40 */ -__IO uint32_t FTSR3; /*!< EXTI Falling trigger selection register, Address offset: 0x44 */ -__IO uint32_t SWIER3; /*!< EXTI Software interrupt event register, Address offset: 0x48 */ -__IO uint32_t D3PMR3; /*!< EXTI D3 Pending mask register, (same register as to SRDPMR3) Address offset: 0x4C */ -__IO uint32_t D3PCR3L; /*!< EXTI D3 Pending clear selection register low, (same register as to SRDPCR3L) Address offset: 0x50 */ -__IO uint32_t D3PCR3H; /*!< EXTI D3 Pending clear selection register High, (same register as to SRDPCR3H) Address offset: 0x54 */ -uint32_t RESERVED3[10]; /*!< Reserved, 0x58 to 0x7C */ -__IO uint32_t IMR1; /*!< EXTI Interrupt mask register, Address offset: 0x80 */ -__IO uint32_t EMR1; /*!< EXTI Event mask register, Address offset: 0x84 */ -__IO uint32_t PR1; /*!< EXTI Pending register, Address offset: 0x88 */ -uint32_t RESERVED4; /*!< Reserved, 0x8C */ -__IO uint32_t IMR2; /*!< EXTI Interrupt mask register, Address offset: 0x90 */ -__IO uint32_t EMR2; /*!< EXTI Event mask register, Address offset: 0x94 */ -__IO uint32_t PR2; /*!< EXTI Pending register, Address offset: 0x98 */ -uint32_t RESERVED5; /*!< Reserved, 0x9C */ -__IO uint32_t IMR3; /*!< EXTI Interrupt mask register, Address offset: 0xA0 */ -__IO uint32_t EMR3; /*!< EXTI Event mask register, Address offset: 0xA4 */ -__IO uint32_t PR3; /*!< EXTI Pending register, Address offset: 0xA8 */ -}EXTI_TypeDef; - -/** - * @brief This structure registers corresponds to EXTI_Typdef CPU1/CPU2 registers subset (IMRx, EMRx and PRx), allowing to define EXTI_D1/EXTI_D2 - * with rapid/common access to these IMRx, EMRx, PRx registers for CPU1 and CPU2. - * Note that EXTI_D1 and EXTI_D2 bases addresses are calculated to point to CPUx first register: - * IMR1 in case of EXTI_D1 that is addressing CPU1 (Coretx-M7) - * C2IMR1 in case of EXTI_D2 that is addressing CPU2 (Coretx-M4) - * Note: EXTI_D2 and corresponding C2IMRx, C2EMRx and C2PRx registers are available for Dual Core devices only - */ - -typedef struct -{ -__IO uint32_t IMR1; /*!< EXTI Interrupt mask register, Address offset: 0x00 */ -__IO uint32_t EMR1; /*!< EXTI Event mask register, Address offset: 0x04 */ -__IO uint32_t PR1; /*!< EXTI Pending register, Address offset: 0x08 */ -uint32_t RESERVED1; /*!< Reserved, 0x0C */ -__IO uint32_t IMR2; /*!< EXTI Interrupt mask register, Address offset: 0x10 */ -__IO uint32_t EMR2; /*!< EXTI Event mask register, Address offset: 0x14 */ -__IO uint32_t PR2; /*!< EXTI Pending register, Address offset: 0x18 */ -uint32_t RESERVED2; /*!< Reserved, 0x1C */ -__IO uint32_t IMR3; /*!< EXTI Interrupt mask register, Address offset: 0x20 */ -__IO uint32_t EMR3; /*!< EXTI Event mask register, Address offset: 0x24 */ -__IO uint32_t PR3; /*!< EXTI Pending register, Address offset: 0x28 */ -}EXTI_Core_TypeDef; - - -/** - * @brief FLASH Registers - */ - -typedef struct -{ - __IO uint32_t ACR; /*!< FLASH access control register, Address offset: 0x00 */ - __IO uint32_t KEYR1; /*!< Flash Key Register for bank1, Address offset: 0x04 */ - __IO uint32_t OPTKEYR; /*!< Flash Option Key Register, Address offset: 0x08 */ - __IO uint32_t CR1; /*!< Flash Control Register for bank1, Address offset: 0x0C */ - __IO uint32_t SR1; /*!< Flash Status Register for bank1, Address offset: 0x10 */ - __IO uint32_t CCR1; /*!< Flash Control Register for bank1, Address offset: 0x14 */ - __IO uint32_t OPTCR; /*!< Flash Option Control Register, Address offset: 0x18 */ - __IO uint32_t OPTSR_CUR; /*!< Flash Option Status Current Register, Address offset: 0x1C */ - __IO uint32_t OPTSR_PRG; /*!< Flash Option Status to Program Register, Address offset: 0x20 */ - __IO uint32_t OPTCCR; /*!< Flash Option Clear Control Register, Address offset: 0x24 */ - __IO uint32_t PRAR_CUR1; /*!< Flash Current Protection Address Register for bank1, Address offset: 0x28 */ - __IO uint32_t PRAR_PRG1; /*!< Flash Protection Address to Program Register for bank1, Address offset: 0x2C */ - __IO uint32_t SCAR_CUR1; /*!< Flash Current Secure Address Register for bank1, Address offset: 0x30 */ - __IO uint32_t SCAR_PRG1; /*!< Flash Secure Address to Program Register for bank1, Address offset: 0x34 */ - __IO uint32_t WPSN_CUR1; /*!< Flash Current Write Protection Register on bank1, Address offset: 0x38 */ - __IO uint32_t WPSN_PRG1; /*!< Flash Write Protection to Program Register on bank1, Address offset: 0x3C */ - __IO uint32_t BOOT_CUR; /*!< Flash Current Boot Address for Pelican Core Register, Address offset: 0x40 */ - __IO uint32_t BOOT_PRG; /*!< Flash Boot Address to Program for Pelican Core Register, Address offset: 0x44 */ - uint32_t RESERVED0[2]; /*!< Reserved, 0x48 to 0x4C */ - __IO uint32_t CRCCR1; /*!< Flash CRC Control register For Bank1 Register , Address offset: 0x50 */ - __IO uint32_t CRCSADD1; /*!< Flash CRC Start Address Register for Bank1 , Address offset: 0x54 */ - __IO uint32_t CRCEADD1; /*!< Flash CRC End Address Register for Bank1 , Address offset: 0x58 */ - __IO uint32_t CRCDATA; /*!< Flash CRC Data Register for Bank1 , Address offset: 0x5C */ - __IO uint32_t ECC_FA1; /*!< Flash ECC Fail Address For Bank1 Register , Address offset: 0x60 */ - uint32_t RESERVED[3]; /*!< Reserved, 0x64 to 0x6C */ - __IO uint32_t OPTSR2_CUR; /*!< Flash Option Status Current Register 2, Address offset: 0x70 */ - __IO uint32_t OPTSR2_PRG; /*!< Flash Option Status to Program Register 2, Address offset: 0x74 */ -} FLASH_TypeDef; - -/** - * @brief Filter and Mathematical ACcelerator - */ -typedef struct -{ - __IO uint32_t X1BUFCFG; /*!< FMAC X1 Buffer Configuration register, Address offset: 0x00 */ - __IO uint32_t X2BUFCFG; /*!< FMAC X2 Buffer Configuration register, Address offset: 0x04 */ - __IO uint32_t YBUFCFG; /*!< FMAC Y Buffer Configuration register, Address offset: 0x08 */ - __IO uint32_t PARAM; /*!< FMAC Parameter register, Address offset: 0x0C */ - __IO uint32_t CR; /*!< FMAC Control register, Address offset: 0x10 */ - __IO uint32_t SR; /*!< FMAC Status register, Address offset: 0x14 */ - __IO uint32_t WDATA; /*!< FMAC Write Data register, Address offset: 0x18 */ - __IO uint32_t RDATA; /*!< FMAC Read Data register, Address offset: 0x1C */ -} FMAC_TypeDef; - -/** - * @brief Flexible Memory Controller - */ - -typedef struct -{ - __IO uint32_t BTCR[8]; /*!< NOR/PSRAM chip-select control register(BCR) and chip-select timing register(BTR), Address offset: 0x00-1C */ -} FMC_Bank1_TypeDef; - -/** - * @brief Flexible Memory Controller Bank1E - */ - -typedef struct -{ - __IO uint32_t BWTR[7]; /*!< NOR/PSRAM write timing registers, Address offset: 0x104-0x11C */ -} FMC_Bank1E_TypeDef; - -/** - * @brief Flexible Memory Controller Bank2 - */ - -typedef struct -{ - __IO uint32_t PCR2; /*!< NAND Flash control register 2, Address offset: 0x60 */ - __IO uint32_t SR2; /*!< NAND Flash FIFO status and interrupt register 2, Address offset: 0x64 */ - __IO uint32_t PMEM2; /*!< NAND Flash Common memory space timing register 2, Address offset: 0x68 */ - __IO uint32_t PATT2; /*!< NAND Flash Attribute memory space timing register 2, Address offset: 0x6C */ - uint32_t RESERVED0; /*!< Reserved, 0x70 */ - __IO uint32_t ECCR2; /*!< NAND Flash ECC result registers 2, Address offset: 0x74 */ -} FMC_Bank2_TypeDef; - -/** - * @brief Flexible Memory Controller Bank3 - */ - -typedef struct -{ - __IO uint32_t PCR; /*!< NAND Flash control register 3, Address offset: 0x80 */ - __IO uint32_t SR; /*!< NAND Flash FIFO status and interrupt register 3, Address offset: 0x84 */ - __IO uint32_t PMEM; /*!< NAND Flash Common memory space timing register 3, Address offset: 0x88 */ - __IO uint32_t PATT; /*!< NAND Flash Attribute memory space timing register 3, Address offset: 0x8C */ - uint32_t RESERVED; /*!< Reserved, 0x90 */ - __IO uint32_t ECCR; /*!< NAND Flash ECC result registers 3, Address offset: 0x94 */ -} FMC_Bank3_TypeDef; - -/** - * @brief Flexible Memory Controller Bank5 and 6 - */ - - -typedef struct -{ - __IO uint32_t SDCR[2]; /*!< SDRAM Control registers , Address offset: 0x140-0x144 */ - __IO uint32_t SDTR[2]; /*!< SDRAM Timing registers , Address offset: 0x148-0x14C */ - __IO uint32_t SDCMR; /*!< SDRAM Command Mode register, Address offset: 0x150 */ - __IO uint32_t SDRTR; /*!< SDRAM Refresh Timer register, Address offset: 0x154 */ - __IO uint32_t SDSR; /*!< SDRAM Status register, Address offset: 0x158 */ -} FMC_Bank5_6_TypeDef; - -/** - * @brief General Purpose I/O - */ - -typedef struct -{ - __IO uint32_t MODER; /*!< GPIO port mode register, Address offset: 0x00 */ - __IO uint32_t OTYPER; /*!< GPIO port output type register, Address offset: 0x04 */ - __IO uint32_t OSPEEDR; /*!< GPIO port output speed register, Address offset: 0x08 */ - __IO uint32_t PUPDR; /*!< GPIO port pull-up/pull-down register, Address offset: 0x0C */ - __IO uint32_t IDR; /*!< GPIO port input data register, Address offset: 0x10 */ - __IO uint32_t ODR; /*!< GPIO port output data register, Address offset: 0x14 */ - __IO uint32_t BSRR; /*!< GPIO port bit set/reset, Address offset: 0x18 */ - __IO uint32_t LCKR; /*!< GPIO port configuration lock register, Address offset: 0x1C */ - __IO uint32_t AFR[2]; /*!< GPIO alternate function registers, Address offset: 0x20-0x24 */ -} GPIO_TypeDef; - -/** - * @brief Operational Amplifier (OPAMP) - */ - -typedef struct -{ - __IO uint32_t CSR; /*!< OPAMP control/status register, Address offset: 0x00 */ - __IO uint32_t OTR; /*!< OPAMP offset trimming register for normal mode, Address offset: 0x04 */ - __IO uint32_t HSOTR; /*!< OPAMP offset trimming register for high speed mode, Address offset: 0x08 */ -} OPAMP_TypeDef; - -/** - * @brief System configuration controller - */ - -typedef struct -{ - uint32_t RESERVED1; /*!< Reserved, Address offset: 0x00 */ - __IO uint32_t PMCR; /*!< SYSCFG peripheral mode configuration register, Address offset: 0x04 */ - __IO uint32_t EXTICR[4]; /*!< SYSCFG external interrupt configuration registers, Address offset: 0x08-0x14 */ - __IO uint32_t CFGR; /*!< SYSCFG configuration registers, Address offset: 0x18 */ - uint32_t RESERVED2; /*!< Reserved, Address offset: 0x1C */ - __IO uint32_t CCCSR; /*!< SYSCFG compensation cell control/status register, Address offset: 0x20 */ - __IO uint32_t CCVR; /*!< SYSCFG compensation cell value register, Address offset: 0x24 */ - __IO uint32_t CCCR; /*!< SYSCFG compensation cell code register, Address offset: 0x28 */ - uint32_t RESERVED3; /*!< Reserved, Address offset: 0x2C */ - __IO uint32_t ADC2ALT; /*!< ADC2 internal input alternate connection register, Address offset: 0x30 */ - uint32_t RESERVED4[60]; /*!< Reserved, 0x34-0x120 */ - __IO uint32_t PKGR; /*!< SYSCFG package register, Address offset: 0x124 */ - uint32_t RESERVED5[118]; /*!< Reserved, 0x128-0x2FC */ - __IO uint32_t UR0; /*!< SYSCFG user register 0, Address offset: 0x300 */ - __IO uint32_t UR1; /*!< SYSCFG user register 1, Address offset: 0x304 */ - __IO uint32_t UR2; /*!< SYSCFG user register 2, Address offset: 0x308 */ - __IO uint32_t UR3; /*!< SYSCFG user register 3, Address offset: 0x30C */ - __IO uint32_t UR4; /*!< SYSCFG user register 4, Address offset: 0x310 */ - __IO uint32_t UR5; /*!< SYSCFG user register 5, Address offset: 0x314 */ - __IO uint32_t UR6; /*!< SYSCFG user register 6, Address offset: 0x318 */ - __IO uint32_t UR7; /*!< SYSCFG user register 7, Address offset: 0x31C */ - uint32_t RESERVED6[3]; /*!< Reserved, Address offset: 0x320-0x328 */ - __IO uint32_t UR11; /*!< SYSCFG user register 11, Address offset: 0x32C */ - __IO uint32_t UR12; /*!< SYSCFG user register 12, Address offset: 0x330 */ - __IO uint32_t UR13; /*!< SYSCFG user register 13, Address offset: 0x334 */ - __IO uint32_t UR14; /*!< SYSCFG user register 14, Address offset: 0x338 */ - __IO uint32_t UR15; /*!< SYSCFG user register 15, Address offset: 0x33C */ - __IO uint32_t UR16; /*!< SYSCFG user register 16, Address offset: 0x340 */ - __IO uint32_t UR17; /*!< SYSCFG user register 17, Address offset: 0x344 */ - __IO uint32_t UR18; /*!< SYSCFG user register 18, Address offset: 0x348 */ - -} SYSCFG_TypeDef; - -/** - * @brief Inter-integrated Circuit Interface - */ - -typedef struct -{ - __IO uint32_t CR1; /*!< I2C Control register 1, Address offset: 0x00 */ - __IO uint32_t CR2; /*!< I2C Control register 2, Address offset: 0x04 */ - __IO uint32_t OAR1; /*!< I2C Own address 1 register, Address offset: 0x08 */ - __IO uint32_t OAR2; /*!< I2C Own address 2 register, Address offset: 0x0C */ - __IO uint32_t TIMINGR; /*!< I2C Timing register, Address offset: 0x10 */ - __IO uint32_t TIMEOUTR; /*!< I2C Timeout register, Address offset: 0x14 */ - __IO uint32_t ISR; /*!< I2C Interrupt and status register, Address offset: 0x18 */ - __IO uint32_t ICR; /*!< I2C Interrupt clear register, Address offset: 0x1C */ - __IO uint32_t PECR; /*!< I2C PEC register, Address offset: 0x20 */ - __IO uint32_t RXDR; /*!< I2C Receive data register, Address offset: 0x24 */ - __IO uint32_t TXDR; /*!< I2C Transmit data register, Address offset: 0x28 */ -} I2C_TypeDef; - -/** - * @brief Independent WATCHDOG - */ - -typedef struct -{ - __IO uint32_t KR; /*!< IWDG Key register, Address offset: 0x00 */ - __IO uint32_t PR; /*!< IWDG Prescaler register, Address offset: 0x04 */ - __IO uint32_t RLR; /*!< IWDG Reload register, Address offset: 0x08 */ - __IO uint32_t SR; /*!< IWDG Status register, Address offset: 0x0C */ - __IO uint32_t WINR; /*!< IWDG Window register, Address offset: 0x10 */ -} IWDG_TypeDef; - - -/** - * @brief LCD-TFT Display Controller - */ - -typedef struct -{ - uint32_t RESERVED0[2]; /*!< Reserved, 0x00-0x04 */ - __IO uint32_t SSCR; /*!< LTDC Synchronization Size Configuration Register, Address offset: 0x08 */ - __IO uint32_t BPCR; /*!< LTDC Back Porch Configuration Register, Address offset: 0x0C */ - __IO uint32_t AWCR; /*!< LTDC Active Width Configuration Register, Address offset: 0x10 */ - __IO uint32_t TWCR; /*!< LTDC Total Width Configuration Register, Address offset: 0x14 */ - __IO uint32_t GCR; /*!< LTDC Global Control Register, Address offset: 0x18 */ - uint32_t RESERVED1[2]; /*!< Reserved, 0x1C-0x20 */ - __IO uint32_t SRCR; /*!< LTDC Shadow Reload Configuration Register, Address offset: 0x24 */ - uint32_t RESERVED2[1]; /*!< Reserved, 0x28 */ - __IO uint32_t BCCR; /*!< LTDC Background Color Configuration Register, Address offset: 0x2C */ - uint32_t RESERVED3[1]; /*!< Reserved, 0x30 */ - __IO uint32_t IER; /*!< LTDC Interrupt Enable Register, Address offset: 0x34 */ - __IO uint32_t ISR; /*!< LTDC Interrupt Status Register, Address offset: 0x38 */ - __IO uint32_t ICR; /*!< LTDC Interrupt Clear Register, Address offset: 0x3C */ - __IO uint32_t LIPCR; /*!< LTDC Line Interrupt Position Configuration Register, Address offset: 0x40 */ - __IO uint32_t CPSR; /*!< LTDC Current Position Status Register, Address offset: 0x44 */ - __IO uint32_t CDSR; /*!< LTDC Current Display Status Register, Address offset: 0x48 */ -} LTDC_TypeDef; - -/** - * @brief LCD-TFT Display layer x Controller - */ - -typedef struct -{ - __IO uint32_t CR; /*!< LTDC Layerx Control Register Address offset: 0x84 */ - __IO uint32_t WHPCR; /*!< LTDC Layerx Window Horizontal Position Configuration Register Address offset: 0x88 */ - __IO uint32_t WVPCR; /*!< LTDC Layerx Window Vertical Position Configuration Register Address offset: 0x8C */ - __IO uint32_t CKCR; /*!< LTDC Layerx Color Keying Configuration Register Address offset: 0x90 */ - __IO uint32_t PFCR; /*!< LTDC Layerx Pixel Format Configuration Register Address offset: 0x94 */ - __IO uint32_t CACR; /*!< LTDC Layerx Constant Alpha Configuration Register Address offset: 0x98 */ - __IO uint32_t DCCR; /*!< LTDC Layerx Default Color Configuration Register Address offset: 0x9C */ - __IO uint32_t BFCR; /*!< LTDC Layerx Blending Factors Configuration Register Address offset: 0xA0 */ - uint32_t RESERVED0[2]; /*!< Reserved */ - __IO uint32_t CFBAR; /*!< LTDC Layerx Color Frame Buffer Address Register Address offset: 0xAC */ - __IO uint32_t CFBLR; /*!< LTDC Layerx Color Frame Buffer Length Register Address offset: 0xB0 */ - __IO uint32_t CFBLNR; /*!< LTDC Layerx ColorFrame Buffer Line Number Register Address offset: 0xB4 */ - uint32_t RESERVED1[3]; /*!< Reserved */ - __IO uint32_t CLUTWR; /*!< LTDC Layerx CLUT Write Register Address offset: 0x144 */ - -} LTDC_Layer_TypeDef; - -/** - * @brief Power Control - */ - -typedef struct -{ - __IO uint32_t CR1; /*!< PWR power control register 1, Address offset: 0x00 */ - __IO uint32_t CSR1; /*!< PWR power control status register 1, Address offset: 0x04 */ - __IO uint32_t CR2; /*!< PWR power control register 2, Address offset: 0x08 */ - __IO uint32_t CR3; /*!< PWR power control register 3, Address offset: 0x0C */ - __IO uint32_t CPUCR; /*!< PWR CPU control register, Address offset: 0x10 */ - uint32_t RESERVED0; /*!< Reserved, Address offset: 0x14 */ - __IO uint32_t D3CR; /*!< PWR D3 domain control register, Address offset: 0x18 */ - uint32_t RESERVED1; /*!< Reserved, Address offset: 0x1C */ - __IO uint32_t WKUPCR; /*!< PWR wakeup clear register, Address offset: 0x20 */ - __IO uint32_t WKUPFR; /*!< PWR wakeup flag register, Address offset: 0x24 */ - __IO uint32_t WKUPEPR; /*!< PWR wakeup enable and polarity register, Address offset: 0x28 */ -} PWR_TypeDef; - -/** - * @brief Reset and Clock Control - */ - -typedef struct -{ - __IO uint32_t CR; /*!< RCC clock control register, Address offset: 0x00 */ - __IO uint32_t HSICFGR; /*!< HSI Clock Calibration Register, Address offset: 0x04 */ - __IO uint32_t CRRCR; /*!< Clock Recovery RC Register, Address offset: 0x08 */ - __IO uint32_t CSICFGR; /*!< CSI Clock Calibration Register, Address offset: 0x0C */ - __IO uint32_t CFGR; /*!< RCC clock configuration register, Address offset: 0x10 */ - uint32_t RESERVED1; /*!< Reserved, Address offset: 0x14 */ - __IO uint32_t D1CFGR; /*!< RCC Domain 1 configuration register, Address offset: 0x18 */ - __IO uint32_t D2CFGR; /*!< RCC Domain 2 configuration register, Address offset: 0x1C */ - __IO uint32_t D3CFGR; /*!< RCC Domain 3 configuration register, Address offset: 0x20 */ - uint32_t RESERVED2; /*!< Reserved, Address offset: 0x24 */ - __IO uint32_t PLLCKSELR; /*!< RCC PLLs Clock Source Selection Register, Address offset: 0x28 */ - __IO uint32_t PLLCFGR; /*!< RCC PLLs Configuration Register, Address offset: 0x2C */ - __IO uint32_t PLL1DIVR; /*!< RCC PLL1 Dividers Configuration Register, Address offset: 0x30 */ - __IO uint32_t PLL1FRACR; /*!< RCC PLL1 Fractional Divider Configuration Register, Address offset: 0x34 */ - __IO uint32_t PLL2DIVR; /*!< RCC PLL2 Dividers Configuration Register, Address offset: 0x38 */ - __IO uint32_t PLL2FRACR; /*!< RCC PLL2 Fractional Divider Configuration Register, Address offset: 0x3C */ - __IO uint32_t PLL3DIVR; /*!< RCC PLL3 Dividers Configuration Register, Address offset: 0x40 */ - __IO uint32_t PLL3FRACR; /*!< RCC PLL3 Fractional Divider Configuration Register, Address offset: 0x44 */ - uint32_t RESERVED3; /*!< Reserved, Address offset: 0x48 */ - __IO uint32_t D1CCIPR; /*!< RCC Domain 1 Kernel Clock Configuration Register Address offset: 0x4C */ - __IO uint32_t D2CCIP1R; /*!< RCC Domain 2 Kernel Clock Configuration Register Address offset: 0x50 */ - __IO uint32_t D2CCIP2R; /*!< RCC Domain 2 Kernel Clock Configuration Register Address offset: 0x54 */ - __IO uint32_t D3CCIPR; /*!< RCC Domain 3 Kernel Clock Configuration Register Address offset: 0x58 */ - uint32_t RESERVED4; /*!< Reserved, Address offset: 0x5C */ - __IO uint32_t CIER; /*!< RCC Clock Source Interrupt Enable Register Address offset: 0x60 */ - __IO uint32_t CIFR; /*!< RCC Clock Source Interrupt Flag Register Address offset: 0x64 */ - __IO uint32_t CICR; /*!< RCC Clock Source Interrupt Clear Register Address offset: 0x68 */ - uint32_t RESERVED5; /*!< Reserved, Address offset: 0x6C */ - __IO uint32_t BDCR; /*!< RCC Vswitch Backup Domain Control Register, Address offset: 0x70 */ - __IO uint32_t CSR; /*!< RCC clock control & status register, Address offset: 0x74 */ - uint32_t RESERVED6; /*!< Reserved, Address offset: 0x78 */ - __IO uint32_t AHB3RSTR; /*!< RCC AHB3 peripheral reset register, Address offset: 0x7C */ - __IO uint32_t AHB1RSTR; /*!< RCC AHB1 peripheral reset register, Address offset: 0x80 */ - __IO uint32_t AHB2RSTR; /*!< RCC AHB2 peripheral reset register, Address offset: 0x84 */ - __IO uint32_t AHB4RSTR; /*!< RCC AHB4 peripheral reset register, Address offset: 0x88 */ - __IO uint32_t APB3RSTR; /*!< RCC APB3 peripheral reset register, Address offset: 0x8C */ - __IO uint32_t APB1LRSTR; /*!< RCC APB1 peripheral reset Low Word register, Address offset: 0x90 */ - __IO uint32_t APB1HRSTR; /*!< RCC APB1 peripheral reset High Word register, Address offset: 0x94 */ - __IO uint32_t APB2RSTR; /*!< RCC APB2 peripheral reset register, Address offset: 0x98 */ - __IO uint32_t APB4RSTR; /*!< RCC APB4 peripheral reset register, Address offset: 0x9C */ - __IO uint32_t GCR; /*!< RCC RCC Global Control Register, Address offset: 0xA0 */ - uint32_t RESERVED8; /*!< Reserved, Address offset: 0xA4 */ - __IO uint32_t D3AMR; /*!< RCC Domain 3 Autonomous Mode Register, Address offset: 0xA8 */ - uint32_t RESERVED11[9]; /*!< Reserved, 0xAC-0xCC Address offset: 0xAC */ - __IO uint32_t RSR; /*!< RCC Reset status register, Address offset: 0xD0 */ - __IO uint32_t AHB3ENR; /*!< RCC AHB3 peripheral clock register, Address offset: 0xD4 */ - __IO uint32_t AHB1ENR; /*!< RCC AHB1 peripheral clock register, Address offset: 0xD8 */ - __IO uint32_t AHB2ENR; /*!< RCC AHB2 peripheral clock register, Address offset: 0xDC */ - __IO uint32_t AHB4ENR; /*!< RCC AHB4 peripheral clock register, Address offset: 0xE0 */ - __IO uint32_t APB3ENR; /*!< RCC APB3 peripheral clock register, Address offset: 0xE4 */ - __IO uint32_t APB1LENR; /*!< RCC APB1 peripheral clock Low Word register, Address offset: 0xE8 */ - __IO uint32_t APB1HENR; /*!< RCC APB1 peripheral clock High Word register, Address offset: 0xEC */ - __IO uint32_t APB2ENR; /*!< RCC APB2 peripheral clock register, Address offset: 0xF0 */ - __IO uint32_t APB4ENR; /*!< RCC APB4 peripheral clock register, Address offset: 0xF4 */ - uint32_t RESERVED12; /*!< Reserved, Address offset: 0xF8 */ - __IO uint32_t AHB3LPENR; /*!< RCC AHB3 peripheral sleep clock register, Address offset: 0xFC */ - __IO uint32_t AHB1LPENR; /*!< RCC AHB1 peripheral sleep clock register, Address offset: 0x100 */ - __IO uint32_t AHB2LPENR; /*!< RCC AHB2 peripheral sleep clock register, Address offset: 0x104 */ - __IO uint32_t AHB4LPENR; /*!< RCC AHB4 peripheral sleep clock register, Address offset: 0x108 */ - __IO uint32_t APB3LPENR; /*!< RCC APB3 peripheral sleep clock register, Address offset: 0x10C */ - __IO uint32_t APB1LLPENR; /*!< RCC APB1 peripheral sleep clock Low Word register, Address offset: 0x110 */ - __IO uint32_t APB1HLPENR; /*!< RCC APB1 peripheral sleep clock High Word register, Address offset: 0x114 */ - __IO uint32_t APB2LPENR; /*!< RCC APB2 peripheral sleep clock register, Address offset: 0x118 */ - __IO uint32_t APB4LPENR; /*!< RCC APB4 peripheral sleep clock register, Address offset: 0x11C */ - uint32_t RESERVED13[4]; /*!< Reserved, 0x120-0x12C Address offset: 0x120 */ - -} RCC_TypeDef; - - -/** - * @brief Real-Time Clock - */ -typedef struct -{ - __IO uint32_t TR; /*!< RTC time register, Address offset: 0x00 */ - __IO uint32_t DR; /*!< RTC date register, Address offset: 0x04 */ - __IO uint32_t CR; /*!< RTC control register, Address offset: 0x08 */ - __IO uint32_t ISR; /*!< RTC initialization and status register, Address offset: 0x0C */ - __IO uint32_t PRER; /*!< RTC prescaler register, Address offset: 0x10 */ - __IO uint32_t WUTR; /*!< RTC wakeup timer register, Address offset: 0x14 */ - uint32_t RESERVED; /*!< Reserved, Address offset: 0x18 */ - __IO uint32_t ALRMAR; /*!< RTC alarm A register, Address offset: 0x1C */ - __IO uint32_t ALRMBR; /*!< RTC alarm B register, Address offset: 0x20 */ - __IO uint32_t WPR; /*!< RTC write protection register, Address offset: 0x24 */ - __IO uint32_t SSR; /*!< RTC sub second register, Address offset: 0x28 */ - __IO uint32_t SHIFTR; /*!< RTC shift control register, Address offset: 0x2C */ - __IO uint32_t TSTR; /*!< RTC time stamp time register, Address offset: 0x30 */ - __IO uint32_t TSDR; /*!< RTC time stamp date register, Address offset: 0x34 */ - __IO uint32_t TSSSR; /*!< RTC time-stamp sub second register, Address offset: 0x38 */ - __IO uint32_t CALR; /*!< RTC calibration register, Address offset: 0x3C */ - __IO uint32_t TAMPCR; /*!< RTC tamper configuration register, Address offset: 0x40 */ - __IO uint32_t ALRMASSR; /*!< RTC alarm A sub second register, Address offset: 0x44 */ - __IO uint32_t ALRMBSSR; /*!< RTC alarm B sub second register, Address offset: 0x48 */ - __IO uint32_t OR; /*!< RTC option register, Address offset: 0x4C */ - __IO uint32_t BKP0R; /*!< RTC backup register 0, Address offset: 0x50 */ - __IO uint32_t BKP1R; /*!< RTC backup register 1, Address offset: 0x54 */ - __IO uint32_t BKP2R; /*!< RTC backup register 2, Address offset: 0x58 */ - __IO uint32_t BKP3R; /*!< RTC backup register 3, Address offset: 0x5C */ - __IO uint32_t BKP4R; /*!< RTC backup register 4, Address offset: 0x60 */ - __IO uint32_t BKP5R; /*!< RTC backup register 5, Address offset: 0x64 */ - __IO uint32_t BKP6R; /*!< RTC backup register 6, Address offset: 0x68 */ - __IO uint32_t BKP7R; /*!< RTC backup register 7, Address offset: 0x6C */ - __IO uint32_t BKP8R; /*!< RTC backup register 8, Address offset: 0x70 */ - __IO uint32_t BKP9R; /*!< RTC backup register 9, Address offset: 0x74 */ - __IO uint32_t BKP10R; /*!< RTC backup register 10, Address offset: 0x78 */ - __IO uint32_t BKP11R; /*!< RTC backup register 11, Address offset: 0x7C */ - __IO uint32_t BKP12R; /*!< RTC backup register 12, Address offset: 0x80 */ - __IO uint32_t BKP13R; /*!< RTC backup register 13, Address offset: 0x84 */ - __IO uint32_t BKP14R; /*!< RTC backup register 14, Address offset: 0x88 */ - __IO uint32_t BKP15R; /*!< RTC backup register 15, Address offset: 0x8C */ - __IO uint32_t BKP16R; /*!< RTC backup register 16, Address offset: 0x90 */ - __IO uint32_t BKP17R; /*!< RTC backup register 17, Address offset: 0x94 */ - __IO uint32_t BKP18R; /*!< RTC backup register 18, Address offset: 0x98 */ - __IO uint32_t BKP19R; /*!< RTC backup register 19, Address offset: 0x9C */ - __IO uint32_t BKP20R; /*!< RTC backup register 20, Address offset: 0xA0 */ - __IO uint32_t BKP21R; /*!< RTC backup register 21, Address offset: 0xA4 */ - __IO uint32_t BKP22R; /*!< RTC backup register 22, Address offset: 0xA8 */ - __IO uint32_t BKP23R; /*!< RTC backup register 23, Address offset: 0xAC */ - __IO uint32_t BKP24R; /*!< RTC backup register 24, Address offset: 0xB0 */ - __IO uint32_t BKP25R; /*!< RTC backup register 25, Address offset: 0xB4 */ - __IO uint32_t BKP26R; /*!< RTC backup register 26, Address offset: 0xB8 */ - __IO uint32_t BKP27R; /*!< RTC backup register 27, Address offset: 0xBC */ - __IO uint32_t BKP28R; /*!< RTC backup register 28, Address offset: 0xC0 */ - __IO uint32_t BKP29R; /*!< RTC backup register 29, Address offset: 0xC4 */ - __IO uint32_t BKP30R; /*!< RTC backup register 30, Address offset: 0xC8 */ - __IO uint32_t BKP31R; /*!< RTC backup register 31, Address offset: 0xCC */ -} RTC_TypeDef; - -/** - * @brief Serial Audio Interface - */ - -typedef struct -{ - __IO uint32_t GCR; /*!< SAI global configuration register, Address offset: 0x00 */ - uint32_t RESERVED0[16]; /*!< Reserved, 0x04 - 0x43 */ - __IO uint32_t PDMCR; /*!< SAI PDM control register, Address offset: 0x44 */ - __IO uint32_t PDMDLY; /*!< SAI PDM delay register, Address offset: 0x48 */ -} SAI_TypeDef; - -typedef struct -{ - __IO uint32_t CR1; /*!< SAI block x configuration register 1, Address offset: 0x04 */ - __IO uint32_t CR2; /*!< SAI block x configuration register 2, Address offset: 0x08 */ - __IO uint32_t FRCR; /*!< SAI block x frame configuration register, Address offset: 0x0C */ - __IO uint32_t SLOTR; /*!< SAI block x slot register, Address offset: 0x10 */ - __IO uint32_t IMR; /*!< SAI block x interrupt mask register, Address offset: 0x14 */ - __IO uint32_t SR; /*!< SAI block x status register, Address offset: 0x18 */ - __IO uint32_t CLRFR; /*!< SAI block x clear flag register, Address offset: 0x1C */ - __IO uint32_t DR; /*!< SAI block x data register, Address offset: 0x20 */ -} SAI_Block_TypeDef; - -/** - * @brief SPDIF-RX Interface - */ - -typedef struct -{ - __IO uint32_t CR; /*!< Control register, Address offset: 0x00 */ - __IO uint32_t IMR; /*!< Interrupt mask register, Address offset: 0x04 */ - __IO uint32_t SR; /*!< Status register, Address offset: 0x08 */ - __IO uint32_t IFCR; /*!< Interrupt Flag Clear register, Address offset: 0x0C */ - __IO uint32_t DR; /*!< Data input register, Address offset: 0x10 */ - __IO uint32_t CSR; /*!< Channel Status register, Address offset: 0x14 */ - __IO uint32_t DIR; /*!< Debug Information register, Address offset: 0x18 */ - uint32_t RESERVED2; /*!< Reserved, 0x1A */ -} SPDIFRX_TypeDef; - - -/** - * @brief Secure digital input/output Interface - */ - -typedef struct -{ - __IO uint32_t POWER; /*!< SDMMC power control register, Address offset: 0x00 */ - __IO uint32_t CLKCR; /*!< SDMMC clock control register, Address offset: 0x04 */ - __IO uint32_t ARG; /*!< SDMMC argument register, Address offset: 0x08 */ - __IO uint32_t CMD; /*!< SDMMC command register, Address offset: 0x0C */ - __I uint32_t RESPCMD; /*!< SDMMC command response register, Address offset: 0x10 */ - __I uint32_t RESP1; /*!< SDMMC response 1 register, Address offset: 0x14 */ - __I uint32_t RESP2; /*!< SDMMC response 2 register, Address offset: 0x18 */ - __I uint32_t RESP3; /*!< SDMMC response 3 register, Address offset: 0x1C */ - __I uint32_t RESP4; /*!< SDMMC response 4 register, Address offset: 0x20 */ - __IO uint32_t DTIMER; /*!< SDMMC data timer register, Address offset: 0x24 */ - __IO uint32_t DLEN; /*!< SDMMC data length register, Address offset: 0x28 */ - __IO uint32_t DCTRL; /*!< SDMMC data control register, Address offset: 0x2C */ - __I uint32_t DCOUNT; /*!< SDMMC data counter register, Address offset: 0x30 */ - __I uint32_t STA; /*!< SDMMC status register, Address offset: 0x34 */ - __IO uint32_t ICR; /*!< SDMMC interrupt clear register, Address offset: 0x38 */ - __IO uint32_t MASK; /*!< SDMMC mask register, Address offset: 0x3C */ - __IO uint32_t ACKTIME; /*!< SDMMC Acknowledgement timer register, Address offset: 0x40 */ - uint32_t RESERVED0[3]; /*!< Reserved, 0x44 - 0x4C - 0x4C */ - __IO uint32_t IDMACTRL; /*!< SDMMC DMA control register, Address offset: 0x50 */ - __IO uint32_t IDMABSIZE; /*!< SDMMC DMA buffer size register, Address offset: 0x54 */ - __IO uint32_t IDMABASE0; /*!< SDMMC DMA buffer 0 base address register, Address offset: 0x58 */ - __IO uint32_t IDMABASE1; /*!< SDMMC DMA buffer 1 base address register, Address offset: 0x5C */ - uint32_t RESERVED1[8]; /*!< Reserved, 0x60-0x7C */ - __IO uint32_t FIFO; /*!< SDMMC data FIFO register, Address offset: 0x80 */ - uint32_t RESERVED2[222]; /*!< Reserved, 0x84-0x3F8 */ - __IO uint32_t IPVR; /*!< SDMMC data FIFO register, Address offset: 0x3FC */ -} SDMMC_TypeDef; - - -/** - * @brief Delay Block DLYB - */ - -typedef struct -{ - __IO uint32_t CR; /*!< DELAY BLOCK control register, Address offset: 0x00 */ - __IO uint32_t CFGR; /*!< DELAY BLOCK configuration register, Address offset: 0x04 */ -} DLYB_TypeDef; - -/** - * @brief HW Semaphore HSEM - */ - -typedef struct -{ - __IO uint32_t R[32]; /*!< 2-step write lock and read back registers, Address offset: 00h-7Ch */ - __IO uint32_t RLR[32]; /*!< 1-step read lock registers, Address offset: 80h-FCh */ - __IO uint32_t C1IER; /*!< HSEM Interrupt enable register , Address offset: 100h */ - __IO uint32_t C1ICR; /*!< HSEM Interrupt clear register , Address offset: 104h */ - __IO uint32_t C1ISR; /*!< HSEM Interrupt Status register , Address offset: 108h */ - __IO uint32_t C1MISR; /*!< HSEM Interrupt Masked Status register , Address offset: 10Ch */ - uint32_t Reserved[12]; /* Reserved Address offset: 110h-13Ch */ - __IO uint32_t CR; /*!< HSEM Semaphore clear register , Address offset: 140h */ - __IO uint32_t KEYR; /*!< HSEM Semaphore clear key register , Address offset: 144h */ - -} HSEM_TypeDef; - -typedef struct -{ - __IO uint32_t IER; /*!< HSEM interrupt enable register , Address offset: 0h */ - __IO uint32_t ICR; /*!< HSEM interrupt clear register , Address offset: 4h */ - __IO uint32_t ISR; /*!< HSEM interrupt status register , Address offset: 8h */ - __IO uint32_t MISR; /*!< HSEM masked interrupt status register , Address offset: Ch */ -} HSEM_Common_TypeDef; - -/** - * @brief Serial Peripheral Interface - */ - -typedef struct -{ - __IO uint32_t CR1; /*!< SPI/I2S Control register 1, Address offset: 0x00 */ - __IO uint32_t CR2; /*!< SPI Control register 2, Address offset: 0x04 */ - __IO uint32_t CFG1; /*!< SPI Configuration register 1, Address offset: 0x08 */ - __IO uint32_t CFG2; /*!< SPI Configuration register 2, Address offset: 0x0C */ - __IO uint32_t IER; /*!< SPI/I2S Interrupt Enable register, Address offset: 0x10 */ - __IO uint32_t SR; /*!< SPI/I2S Status register, Address offset: 0x14 */ - __IO uint32_t IFCR; /*!< SPI/I2S Interrupt/Status flags clear register, Address offset: 0x18 */ - uint32_t RESERVED0; /*!< Reserved, 0x1C */ - __IO uint32_t TXDR; /*!< SPI/I2S Transmit data register, Address offset: 0x20 */ - uint32_t RESERVED1[3]; /*!< Reserved, 0x24-0x2C */ - __IO uint32_t RXDR; /*!< SPI/I2S Receive data register, Address offset: 0x30 */ - uint32_t RESERVED2[3]; /*!< Reserved, 0x34-0x3C */ - __IO uint32_t CRCPOLY; /*!< SPI CRC Polynomial register, Address offset: 0x40 */ - __IO uint32_t TXCRC; /*!< SPI Transmitter CRC register, Address offset: 0x44 */ - __IO uint32_t RXCRC; /*!< SPI Receiver CRC register, Address offset: 0x48 */ - __IO uint32_t UDRDR; /*!< SPI Underrun data register, Address offset: 0x4C */ - __IO uint32_t I2SCFGR; /*!< I2S Configuration register, Address offset: 0x50 */ - -} SPI_TypeDef; - -/** - * @brief DTS - */ -typedef struct -{ - __IO uint32_t CFGR1; /*!< DTS configuration register, Address offset: 0x00 */ - uint32_t RESERVED0; /*!< Reserved, Address offset: 0x04 */ - __IO uint32_t T0VALR1; /*!< DTS T0 Value register, Address offset: 0x08 */ - uint32_t RESERVED1; /*!< Reserved, Address offset: 0x0C */ - __IO uint32_t RAMPVALR; /*!< DTS Ramp value register, Address offset: 0x10 */ - __IO uint32_t ITR1; /*!< DTS Interrupt threshold register, Address offset: 0x14 */ - uint32_t RESERVED2; /*!< Reserved, Address offset: 0x18 */ - __IO uint32_t DR; /*!< DTS data register, Address offset: 0x1C */ - __IO uint32_t SR; /*!< DTS status register Address offset: 0x20 */ - __IO uint32_t ITENR; /*!< DTS Interrupt enable register, Address offset: 0x24 */ - __IO uint32_t ICIFR; /*!< DTS Clear Interrupt flag register, Address offset: 0x28 */ - __IO uint32_t OR; /*!< DTS option register 1, Address offset: 0x2C */ -} -DTS_TypeDef; - -/** - * @brief TIM - */ - -typedef struct -{ - __IO uint32_t CR1; /*!< TIM control register 1, Address offset: 0x00 */ - __IO uint32_t CR2; /*!< TIM control register 2, Address offset: 0x04 */ - __IO uint32_t SMCR; /*!< TIM slave mode control register, Address offset: 0x08 */ - __IO uint32_t DIER; /*!< TIM DMA/interrupt enable register, Address offset: 0x0C */ - __IO uint32_t SR; /*!< TIM status register, Address offset: 0x10 */ - __IO uint32_t EGR; /*!< TIM event generation register, Address offset: 0x14 */ - __IO uint32_t CCMR1; /*!< TIM capture/compare mode register 1, Address offset: 0x18 */ - __IO uint32_t CCMR2; /*!< TIM capture/compare mode register 2, Address offset: 0x1C */ - __IO uint32_t CCER; /*!< TIM capture/compare enable register, Address offset: 0x20 */ - __IO uint32_t CNT; /*!< TIM counter register, Address offset: 0x24 */ - __IO uint32_t PSC; /*!< TIM prescaler, Address offset: 0x28 */ - __IO uint32_t ARR; /*!< TIM auto-reload register, Address offset: 0x2C */ - __IO uint32_t RCR; /*!< TIM repetition counter register, Address offset: 0x30 */ - __IO uint32_t CCR1; /*!< TIM capture/compare register 1, Address offset: 0x34 */ - __IO uint32_t CCR2; /*!< TIM capture/compare register 2, Address offset: 0x38 */ - __IO uint32_t CCR3; /*!< TIM capture/compare register 3, Address offset: 0x3C */ - __IO uint32_t CCR4; /*!< TIM capture/compare register 4, Address offset: 0x40 */ - __IO uint32_t BDTR; /*!< TIM break and dead-time register, Address offset: 0x44 */ - __IO uint32_t DCR; /*!< TIM DMA control register, Address offset: 0x48 */ - __IO uint32_t DMAR; /*!< TIM DMA address for full transfer, Address offset: 0x4C */ - uint32_t RESERVED1; /*!< Reserved, 0x50 */ - __IO uint32_t CCMR3; /*!< TIM capture/compare mode register 3, Address offset: 0x54 */ - __IO uint32_t CCR5; /*!< TIM capture/compare register5, Address offset: 0x58 */ - __IO uint32_t CCR6; /*!< TIM capture/compare register6, Address offset: 0x5C */ - __IO uint32_t AF1; /*!< TIM alternate function option register 1, Address offset: 0x60 */ - __IO uint32_t AF2; /*!< TIM alternate function option register 2, Address offset: 0x64 */ - __IO uint32_t TISEL; /*!< TIM Input Selection register, Address offset: 0x68 */ -} TIM_TypeDef; - -/** - * @brief LPTIMIMER - */ -typedef struct -{ - __IO uint32_t ISR; /*!< LPTIM Interrupt and Status register, Address offset: 0x00 */ - __IO uint32_t ICR; /*!< LPTIM Interrupt Clear register, Address offset: 0x04 */ - __IO uint32_t IER; /*!< LPTIM Interrupt Enable register, Address offset: 0x08 */ - __IO uint32_t CFGR; /*!< LPTIM Configuration register, Address offset: 0x0C */ - __IO uint32_t CR; /*!< LPTIM Control register, Address offset: 0x10 */ - __IO uint32_t CMP; /*!< LPTIM Compare register, Address offset: 0x14 */ - __IO uint32_t ARR; /*!< LPTIM Autoreload register, Address offset: 0x18 */ - __IO uint32_t CNT; /*!< LPTIM Counter register, Address offset: 0x1C */ - uint32_t RESERVED1; /*!< Reserved, 0x20 */ - __IO uint32_t CFGR2; /*!< LPTIM Configuration register, Address offset: 0x24 */ -} LPTIM_TypeDef; - -/** - * @brief Comparator - */ -typedef struct -{ - __IO uint32_t SR; /*!< Comparator status register, Address offset: 0x00 */ - __IO uint32_t ICFR; /*!< Comparator interrupt clear flag register, Address offset: 0x04 */ - __IO uint32_t OR; /*!< Comparator option register, Address offset: 0x08 */ -} COMPOPT_TypeDef; - -typedef struct -{ - __IO uint32_t CFGR; /*!< Comparator configuration register , Address offset: 0x00 */ -} COMP_TypeDef; - -typedef struct -{ - __IO uint32_t CFGR; /*!< COMP control and status register, used for bits common to several COMP instances, Address offset: 0x00 */ -} COMP_Common_TypeDef; -/** - * @brief Universal Synchronous Asynchronous Receiver Transmitter - */ - -typedef struct -{ - __IO uint32_t CR1; /*!< USART Control register 1, Address offset: 0x00 */ - __IO uint32_t CR2; /*!< USART Control register 2, Address offset: 0x04 */ - __IO uint32_t CR3; /*!< USART Control register 3, Address offset: 0x08 */ - __IO uint32_t BRR; /*!< USART Baud rate register, Address offset: 0x0C */ - __IO uint32_t GTPR; /*!< USART Guard time and prescaler register, Address offset: 0x10 */ - __IO uint32_t RTOR; /*!< USART Receiver Time Out register, Address offset: 0x14 */ - __IO uint32_t RQR; /*!< USART Request register, Address offset: 0x18 */ - __IO uint32_t ISR; /*!< USART Interrupt and status register, Address offset: 0x1C */ - __IO uint32_t ICR; /*!< USART Interrupt flag Clear register, Address offset: 0x20 */ - __IO uint32_t RDR; /*!< USART Receive Data register, Address offset: 0x24 */ - __IO uint32_t TDR; /*!< USART Transmit Data register, Address offset: 0x28 */ - __IO uint32_t PRESC; /*!< USART clock Prescaler register, Address offset: 0x2C */ -} USART_TypeDef; - -/** - * @brief Single Wire Protocol Master Interface SPWMI - */ -typedef struct -{ - __IO uint32_t CR; /*!< SWPMI Configuration/Control register, Address offset: 0x00 */ - __IO uint32_t BRR; /*!< SWPMI bitrate register, Address offset: 0x04 */ - uint32_t RESERVED1; /*!< Reserved, 0x08 */ - __IO uint32_t ISR; /*!< SWPMI Interrupt and Status register, Address offset: 0x0C */ - __IO uint32_t ICR; /*!< SWPMI Interrupt Flag Clear register, Address offset: 0x10 */ - __IO uint32_t IER; /*!< SWPMI Interrupt Enable register, Address offset: 0x14 */ - __IO uint32_t RFL; /*!< SWPMI Receive Frame Length register, Address offset: 0x18 */ - __IO uint32_t TDR; /*!< SWPMI Transmit data register, Address offset: 0x1C */ - __IO uint32_t RDR; /*!< SWPMI Receive data register, Address offset: 0x20 */ - __IO uint32_t OR; /*!< SWPMI Option register, Address offset: 0x24 */ -} SWPMI_TypeDef; - -/** - * @brief Window WATCHDOG - */ - -typedef struct -{ - __IO uint32_t CR; /*!< WWDG Control register, Address offset: 0x00 */ - __IO uint32_t CFR; /*!< WWDG Configuration register, Address offset: 0x04 */ - __IO uint32_t SR; /*!< WWDG Status register, Address offset: 0x08 */ -} WWDG_TypeDef; - - -/** - * @brief RAM_ECC_Specific_Registers - */ -typedef struct -{ - __IO uint32_t CR; /*!< RAMECC monitor configuration register */ - __IO uint32_t SR; /*!< RAMECC monitor status register */ - __IO uint32_t FAR; /*!< RAMECC monitor failing address register */ - __IO uint32_t FDRL; /*!< RAMECC monitor failing data low register */ - __IO uint32_t FDRH; /*!< RAMECC monitor failing data high register */ - __IO uint32_t FECR; /*!< RAMECC monitor failing ECC error code register */ -} RAMECC_MonitorTypeDef; - -typedef struct -{ - __IO uint32_t IER; /*!< RAMECC interrupt enable register */ -} RAMECC_TypeDef; -/** - * @} - */ - - -/** - * @brief Crypto Processor - */ - -typedef struct -{ - __IO uint32_t CR; /*!< CRYP control register, Address offset: 0x00 */ - __IO uint32_t SR; /*!< CRYP status register, Address offset: 0x04 */ - __IO uint32_t DIN; /*!< CRYP data input register, Address offset: 0x08 */ - __IO uint32_t DOUT; /*!< CRYP data output register, Address offset: 0x0C */ - __IO uint32_t DMACR; /*!< CRYP DMA control register, Address offset: 0x10 */ - __IO uint32_t IMSCR; /*!< CRYP interrupt mask set/clear register, Address offset: 0x14 */ - __IO uint32_t RISR; /*!< CRYP raw interrupt status register, Address offset: 0x18 */ - __IO uint32_t MISR; /*!< CRYP masked interrupt status register, Address offset: 0x1C */ - __IO uint32_t K0LR; /*!< CRYP key left register 0, Address offset: 0x20 */ - __IO uint32_t K0RR; /*!< CRYP key right register 0, Address offset: 0x24 */ - __IO uint32_t K1LR; /*!< CRYP key left register 1, Address offset: 0x28 */ - __IO uint32_t K1RR; /*!< CRYP key right register 1, Address offset: 0x2C */ - __IO uint32_t K2LR; /*!< CRYP key left register 2, Address offset: 0x30 */ - __IO uint32_t K2RR; /*!< CRYP key right register 2, Address offset: 0x34 */ - __IO uint32_t K3LR; /*!< CRYP key left register 3, Address offset: 0x38 */ - __IO uint32_t K3RR; /*!< CRYP key right register 3, Address offset: 0x3C */ - __IO uint32_t IV0LR; /*!< CRYP initialization vector left-word register 0, Address offset: 0x40 */ - __IO uint32_t IV0RR; /*!< CRYP initialization vector right-word register 0, Address offset: 0x44 */ - __IO uint32_t IV1LR; /*!< CRYP initialization vector left-word register 1, Address offset: 0x48 */ - __IO uint32_t IV1RR; /*!< CRYP initialization vector right-word register 1, Address offset: 0x4C */ - __IO uint32_t CSGCMCCM0R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 0, Address offset: 0x50 */ - __IO uint32_t CSGCMCCM1R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 1, Address offset: 0x54 */ - __IO uint32_t CSGCMCCM2R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 2, Address offset: 0x58 */ - __IO uint32_t CSGCMCCM3R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 3, Address offset: 0x5C */ - __IO uint32_t CSGCMCCM4R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 4, Address offset: 0x60 */ - __IO uint32_t CSGCMCCM5R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 5, Address offset: 0x64 */ - __IO uint32_t CSGCMCCM6R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 6, Address offset: 0x68 */ - __IO uint32_t CSGCMCCM7R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 7, Address offset: 0x6C */ - __IO uint32_t CSGCM0R; /*!< CRYP GCM/GMAC context swap register 0, Address offset: 0x70 */ - __IO uint32_t CSGCM1R; /*!< CRYP GCM/GMAC context swap register 1, Address offset: 0x74 */ - __IO uint32_t CSGCM2R; /*!< CRYP GCM/GMAC context swap register 2, Address offset: 0x78 */ - __IO uint32_t CSGCM3R; /*!< CRYP GCM/GMAC context swap register 3, Address offset: 0x7C */ - __IO uint32_t CSGCM4R; /*!< CRYP GCM/GMAC context swap register 4, Address offset: 0x80 */ - __IO uint32_t CSGCM5R; /*!< CRYP GCM/GMAC context swap register 5, Address offset: 0x84 */ - __IO uint32_t CSGCM6R; /*!< CRYP GCM/GMAC context swap register 6, Address offset: 0x88 */ - __IO uint32_t CSGCM7R; /*!< CRYP GCM/GMAC context swap register 7, Address offset: 0x8C */ -} CRYP_TypeDef; - -/** - * @brief HASH - */ - -typedef struct -{ - __IO uint32_t CR; /*!< HASH control register, Address offset: 0x00 */ - __IO uint32_t DIN; /*!< HASH data input register, Address offset: 0x04 */ - __IO uint32_t STR; /*!< HASH start register, Address offset: 0x08 */ - __IO uint32_t HR[5]; /*!< HASH digest registers, Address offset: 0x0C-0x1C */ - __IO uint32_t IMR; /*!< HASH interrupt enable register, Address offset: 0x20 */ - __IO uint32_t SR; /*!< HASH status register, Address offset: 0x24 */ - uint32_t RESERVED[52]; /*!< Reserved, 0x28-0xF4 */ - __IO uint32_t CSR[54]; /*!< HASH context swap registers, Address offset: 0x0F8-0x1CC */ -} HASH_TypeDef; - -/** - * @brief HASH_DIGEST - */ - -typedef struct -{ - __IO uint32_t HR[8]; /*!< HASH digest registers, Address offset: 0x310-0x32C */ -} HASH_DIGEST_TypeDef; - - -/** - * @brief RNG - */ - -typedef struct -{ - __IO uint32_t CR; /*!< RNG control register, Address offset: 0x00 */ - __IO uint32_t SR; /*!< RNG status register, Address offset: 0x04 */ - __IO uint32_t DR; /*!< RNG data register, Address offset: 0x08 */ - uint32_t RESERVED; - __IO uint32_t HTCR; /*!< RNG health test configuration register, Address offset: 0x10 */ -} RNG_TypeDef; - -/** - * @brief MDIOS - */ - -typedef struct -{ - __IO uint32_t CR; - __IO uint32_t WRFR; - __IO uint32_t CWRFR; - __IO uint32_t RDFR; - __IO uint32_t CRDFR; - __IO uint32_t SR; - __IO uint32_t CLRFR; - uint32_t RESERVED[57]; - __IO uint32_t DINR0; - __IO uint32_t DINR1; - __IO uint32_t DINR2; - __IO uint32_t DINR3; - __IO uint32_t DINR4; - __IO uint32_t DINR5; - __IO uint32_t DINR6; - __IO uint32_t DINR7; - __IO uint32_t DINR8; - __IO uint32_t DINR9; - __IO uint32_t DINR10; - __IO uint32_t DINR11; - __IO uint32_t DINR12; - __IO uint32_t DINR13; - __IO uint32_t DINR14; - __IO uint32_t DINR15; - __IO uint32_t DINR16; - __IO uint32_t DINR17; - __IO uint32_t DINR18; - __IO uint32_t DINR19; - __IO uint32_t DINR20; - __IO uint32_t DINR21; - __IO uint32_t DINR22; - __IO uint32_t DINR23; - __IO uint32_t DINR24; - __IO uint32_t DINR25; - __IO uint32_t DINR26; - __IO uint32_t DINR27; - __IO uint32_t DINR28; - __IO uint32_t DINR29; - __IO uint32_t DINR30; - __IO uint32_t DINR31; - __IO uint32_t DOUTR0; - __IO uint32_t DOUTR1; - __IO uint32_t DOUTR2; - __IO uint32_t DOUTR3; - __IO uint32_t DOUTR4; - __IO uint32_t DOUTR5; - __IO uint32_t DOUTR6; - __IO uint32_t DOUTR7; - __IO uint32_t DOUTR8; - __IO uint32_t DOUTR9; - __IO uint32_t DOUTR10; - __IO uint32_t DOUTR11; - __IO uint32_t DOUTR12; - __IO uint32_t DOUTR13; - __IO uint32_t DOUTR14; - __IO uint32_t DOUTR15; - __IO uint32_t DOUTR16; - __IO uint32_t DOUTR17; - __IO uint32_t DOUTR18; - __IO uint32_t DOUTR19; - __IO uint32_t DOUTR20; - __IO uint32_t DOUTR21; - __IO uint32_t DOUTR22; - __IO uint32_t DOUTR23; - __IO uint32_t DOUTR24; - __IO uint32_t DOUTR25; - __IO uint32_t DOUTR26; - __IO uint32_t DOUTR27; - __IO uint32_t DOUTR28; - __IO uint32_t DOUTR29; - __IO uint32_t DOUTR30; - __IO uint32_t DOUTR31; -} MDIOS_TypeDef; - - -/** - * @brief USB_OTG_Core_Registers - */ -typedef struct -{ - __IO uint32_t GOTGCTL; /*!< USB_OTG Control and Status Register 000h */ - __IO uint32_t GOTGINT; /*!< USB_OTG Interrupt Register 004h */ - __IO uint32_t GAHBCFG; /*!< Core AHB Configuration Register 008h */ - __IO uint32_t GUSBCFG; /*!< Core USB Configuration Register 00Ch */ - __IO uint32_t GRSTCTL; /*!< Core Reset Register 010h */ - __IO uint32_t GINTSTS; /*!< Core Interrupt Register 014h */ - __IO uint32_t GINTMSK; /*!< Core Interrupt Mask Register 018h */ - __IO uint32_t GRXSTSR; /*!< Receive Sts Q Read Register 01Ch */ - __IO uint32_t GRXSTSP; /*!< Receive Sts Q Read & POP Register 020h */ - __IO uint32_t GRXFSIZ; /*!< Receive FIFO Size Register 024h */ - __IO uint32_t DIEPTXF0_HNPTXFSIZ; /*!< EP0 / Non Periodic Tx FIFO Size Register 028h */ - __IO uint32_t HNPTXSTS; /*!< Non Periodic Tx FIFO/Queue Sts reg 02Ch */ - uint32_t Reserved30[2]; /*!< Reserved 030h */ - __IO uint32_t GCCFG; /*!< General Purpose IO Register 038h */ - __IO uint32_t CID; /*!< User ID Register 03Ch */ - __IO uint32_t GSNPSID; /* USB_OTG core ID 040h*/ - __IO uint32_t GHWCFG1; /* User HW config1 044h*/ - __IO uint32_t GHWCFG2; /* User HW config2 048h*/ - __IO uint32_t GHWCFG3; /*!< User HW config3 04Ch */ - uint32_t Reserved6; /*!< Reserved 050h */ - __IO uint32_t GLPMCFG; /*!< LPM Register 054h */ - __IO uint32_t GPWRDN; /*!< Power Down Register 058h */ - __IO uint32_t GDFIFOCFG; /*!< DFIFO Software Config Register 05Ch */ - __IO uint32_t GADPCTL; /*!< ADP Timer, Control and Status Register 60Ch */ - uint32_t Reserved43[39]; /*!< Reserved 058h-0FFh */ - __IO uint32_t HPTXFSIZ; /*!< Host Periodic Tx FIFO Size Reg 100h */ - __IO uint32_t DIEPTXF[0x0F]; /*!< dev Periodic Transmit FIFO */ -} USB_OTG_GlobalTypeDef; - - -/** - * @brief USB_OTG_device_Registers - */ -typedef struct -{ - __IO uint32_t DCFG; /*!< dev Configuration Register 800h */ - __IO uint32_t DCTL; /*!< dev Control Register 804h */ - __IO uint32_t DSTS; /*!< dev Status Register (RO) 808h */ - uint32_t Reserved0C; /*!< Reserved 80Ch */ - __IO uint32_t DIEPMSK; /*!< dev IN Endpoint Mask 810h */ - __IO uint32_t DOEPMSK; /*!< dev OUT Endpoint Mask 814h */ - __IO uint32_t DAINT; /*!< dev All Endpoints Itr Reg 818h */ - __IO uint32_t DAINTMSK; /*!< dev All Endpoints Itr Mask 81Ch */ - uint32_t Reserved20; /*!< Reserved 820h */ - uint32_t Reserved9; /*!< Reserved 824h */ - __IO uint32_t DVBUSDIS; /*!< dev VBUS discharge Register 828h */ - __IO uint32_t DVBUSPULSE; /*!< dev VBUS Pulse Register 82Ch */ - __IO uint32_t DTHRCTL; /*!< dev threshold 830h */ - __IO uint32_t DIEPEMPMSK; /*!< dev empty msk 834h */ - __IO uint32_t DEACHINT; /*!< dedicated EP interrupt 838h */ - __IO uint32_t DEACHMSK; /*!< dedicated EP msk 83Ch */ - uint32_t Reserved40; /*!< dedicated EP mask 840h */ - __IO uint32_t DINEP1MSK; /*!< dedicated EP mask 844h */ - uint32_t Reserved44[15]; /*!< Reserved 844-87Ch */ - __IO uint32_t DOUTEP1MSK; /*!< dedicated EP msk 884h */ -} USB_OTG_DeviceTypeDef; - - -/** - * @brief USB_OTG_IN_Endpoint-Specific_Register - */ -typedef struct -{ - __IO uint32_t DIEPCTL; /*!< dev IN Endpoint Control Reg 900h + (ep_num * 20h) + 00h */ - uint32_t Reserved04; /*!< Reserved 900h + (ep_num * 20h) + 04h */ - __IO uint32_t DIEPINT; /*!< dev IN Endpoint Itr Reg 900h + (ep_num * 20h) + 08h */ - uint32_t Reserved0C; /*!< Reserved 900h + (ep_num * 20h) + 0Ch */ - __IO uint32_t DIEPTSIZ; /*!< IN Endpoint Txfer Size 900h + (ep_num * 20h) + 10h */ - __IO uint32_t DIEPDMA; /*!< IN Endpoint DMA Address Reg 900h + (ep_num * 20h) + 14h */ - __IO uint32_t DTXFSTS; /*!< IN Endpoint Tx FIFO Status Reg 900h + (ep_num * 20h) + 18h */ - uint32_t Reserved18; /*!< Reserved 900h+(ep_num*20h)+1Ch-900h+ (ep_num * 20h) + 1Ch */ -} USB_OTG_INEndpointTypeDef; - - -/** - * @brief USB_OTG_OUT_Endpoint-Specific_Registers - */ -typedef struct -{ - __IO uint32_t DOEPCTL; /*!< dev OUT Endpoint Control Reg B00h + (ep_num * 20h) + 00h */ - uint32_t Reserved04; /*!< Reserved B00h + (ep_num * 20h) + 04h */ - __IO uint32_t DOEPINT; /*!< dev OUT Endpoint Itr Reg B00h + (ep_num * 20h) + 08h */ - uint32_t Reserved0C; /*!< Reserved B00h + (ep_num * 20h) + 0Ch */ - __IO uint32_t DOEPTSIZ; /*!< dev OUT Endpoint Txfer Size B00h + (ep_num * 20h) + 10h */ - __IO uint32_t DOEPDMA; /*!< dev OUT Endpoint DMA Address B00h + (ep_num * 20h) + 14h */ - uint32_t Reserved18[2]; /*!< Reserved B00h + (ep_num * 20h) + 18h - B00h + (ep_num * 20h) + 1Ch */ -} USB_OTG_OUTEndpointTypeDef; - - -/** - * @brief USB_OTG_Host_Mode_Register_Structures - */ -typedef struct -{ - __IO uint32_t HCFG; /*!< Host Configuration Register 400h */ - __IO uint32_t HFIR; /*!< Host Frame Interval Register 404h */ - __IO uint32_t HFNUM; /*!< Host Frame Nbr/Frame Remaining 408h */ - uint32_t Reserved40C; /*!< Reserved 40Ch */ - __IO uint32_t HPTXSTS; /*!< Host Periodic Tx FIFO/ Queue Status 410h */ - __IO uint32_t HAINT; /*!< Host All Channels Interrupt Register 414h */ - __IO uint32_t HAINTMSK; /*!< Host All Channels Interrupt Mask 418h */ -} USB_OTG_HostTypeDef; - -/** - * @brief USB_OTG_Host_Channel_Specific_Registers - */ -typedef struct -{ - __IO uint32_t HCCHAR; /*!< Host Channel Characteristics Register 500h */ - __IO uint32_t HCSPLT; /*!< Host Channel Split Control Register 504h */ - __IO uint32_t HCINT; /*!< Host Channel Interrupt Register 508h */ - __IO uint32_t HCINTMSK; /*!< Host Channel Interrupt Mask Register 50Ch */ - __IO uint32_t HCTSIZ; /*!< Host Channel Transfer Size Register 510h */ - __IO uint32_t HCDMA; /*!< Host Channel DMA Address Register 514h */ - uint32_t Reserved[2]; /*!< Reserved */ -} USB_OTG_HostChannelTypeDef; -/** - * @} - */ - -/** - * @brief OCTO Serial Peripheral Interface - */ - -typedef struct -{ - __IO uint32_t CR; /*!< OCTOSPI Control register, Address offset: 0x000 */ - uint32_t RESERVED; /*!< Reserved, Address offset: 0x004 */ - __IO uint32_t DCR1; /*!< OCTOSPI Device Configuration register 1, Address offset: 0x008 */ - __IO uint32_t DCR2; /*!< OCTOSPI Device Configuration register 2, Address offset: 0x00C */ - __IO uint32_t DCR3; /*!< OCTOSPI Device Configuration register 3, Address offset: 0x010 */ - __IO uint32_t DCR4; /*!< OCTOSPI Device Configuration register 4, Address offset: 0x014 */ - uint32_t RESERVED1[2]; /*!< Reserved, Address offset: 0x018-0x01C */ - __IO uint32_t SR; /*!< OCTOSPI Status register, Address offset: 0x020 */ - __IO uint32_t FCR; /*!< OCTOSPI Flag Clear register, Address offset: 0x024 */ - uint32_t RESERVED2[6]; /*!< Reserved, Address offset: 0x028-0x03C */ - __IO uint32_t DLR; /*!< OCTOSPI Data Length register, Address offset: 0x040 */ - uint32_t RESERVED3; /*!< Reserved, Address offset: 0x044 */ - __IO uint32_t AR; /*!< OCTOSPI Address register, Address offset: 0x048 */ - uint32_t RESERVED4; /*!< Reserved, Address offset: 0x04C */ - __IO uint32_t DR; /*!< OCTOSPI Data register, Address offset: 0x050 */ - uint32_t RESERVED5[11]; /*!< Reserved, Address offset: 0x054-0x07C */ - __IO uint32_t PSMKR; /*!< OCTOSPI Polling Status Mask register, Address offset: 0x080 */ - uint32_t RESERVED6; /*!< Reserved, Address offset: 0x084 */ - __IO uint32_t PSMAR; /*!< OCTOSPI Polling Status Match register, Address offset: 0x088 */ - uint32_t RESERVED7; /*!< Reserved, Address offset: 0x08C */ - __IO uint32_t PIR; /*!< OCTOSPI Polling Interval register, Address offset: 0x090 */ - uint32_t RESERVED8[27]; /*!< Reserved, Address offset: 0x094-0x0FC */ - __IO uint32_t CCR; /*!< OCTOSPI Communication Configuration register, Address offset: 0x100 */ - uint32_t RESERVED9; /*!< Reserved, Address offset: 0x104 */ - __IO uint32_t TCR; /*!< OCTOSPI Timing Configuration register, Address offset: 0x108 */ - uint32_t RESERVED10; /*!< Reserved, Address offset: 0x10C */ - __IO uint32_t IR; /*!< OCTOSPI Instruction register, Address offset: 0x110 */ - uint32_t RESERVED11[3]; /*!< Reserved, Address offset: 0x114-0x11C */ - __IO uint32_t ABR; /*!< OCTOSPI Alternate Bytes register, Address offset: 0x120 */ - uint32_t RESERVED12[3]; /*!< Reserved, Address offset: 0x124-0x12C */ - __IO uint32_t LPTR; /*!< OCTOSPI Low Power Timeout register, Address offset: 0x130 */ - uint32_t RESERVED13[3]; /*!< Reserved, Address offset: 0x134-0x13C */ - __IO uint32_t WPCCR; /*!< OCTOSPI Wrap Communication Configuration register, Address offset: 0x140 */ - uint32_t RESERVED14; /*!< Reserved, Address offset: 0x144 */ - __IO uint32_t WPTCR; /*!< OCTOSPI Wrap Timing Configuration register, Address offset: 0x148 */ - uint32_t RESERVED15; /*!< Reserved, Address offset: 0x14C */ - __IO uint32_t WPIR; /*!< OCTOSPI Wrap Instruction register, Address offset: 0x150 */ - uint32_t RESERVED16[3]; /*!< Reserved, Address offset: 0x154-0x15C */ - __IO uint32_t WPABR; /*!< OCTOSPI Wrap Alternate Bytes register, Address offset: 0x160 */ - uint32_t RESERVED17[7]; /*!< Reserved, Address offset: 0x164-0x17C */ - __IO uint32_t WCCR; /*!< OCTOSPI Write Communication Configuration register, Address offset: 0x180 */ - uint32_t RESERVED18; /*!< Reserved, Address offset: 0x184 */ - __IO uint32_t WTCR; /*!< OCTOSPI Write Timing Configuration register, Address offset: 0x188 */ - uint32_t RESERVED19; /*!< Reserved, Address offset: 0x18C */ - __IO uint32_t WIR; /*!< OCTOSPI Write Instruction register, Address offset: 0x190 */ - uint32_t RESERVED20[3]; /*!< Reserved, Address offset: 0x194-0x19C */ - __IO uint32_t WABR; /*!< OCTOSPI Write Alternate Bytes register, Address offset: 0x1A0 */ - uint32_t RESERVED21[23]; /*!< Reserved, Address offset: 0x1A4-0x1FC */ - __IO uint32_t HLCR; /*!< OCTOSPI Hyperbus Latency Configuration register, Address offset: 0x200 */ - uint32_t RESERVED22[122]; /*!< Reserved, Address offset: 0x204-0x3EC */ - __IO uint32_t HWCFGR; /*!< OCTOSPI HW Configuration register, Address offset: 0x3F0 */ - __IO uint32_t VER; /*!< OCTOSPI Version register, Address offset: 0x3F4 */ - __IO uint32_t ID; /*!< OCTOSPI Identification register, Address offset: 0x3F8 */ - __IO uint32_t MID; /*!< OCTOPSI HW Magic ID register, Address offset: 0x3FC */ -} OCTOSPI_TypeDef; - -/** - * @} - */ -/** - * @brief OCTO Serial Peripheral Interface IO Manager - */ - -typedef struct -{ - __IO uint32_t CR; /*!< OCTOSPI IO Manager Control register, Address offset: 0x00 */ - __IO uint32_t PCR[3]; /*!< OCTOSPI IO Manager Port[1:3] Configuration register, Address offset: 0x04-0x20 */ -} OCTOSPIM_TypeDef; - -/** - * @} - */ - -/** - * @brief OTFD register - */ -typedef struct -{ - __IO uint32_t REG_CONFIGR; - __IO uint32_t REG_START_ADDR; - __IO uint32_t REG_END_ADDR; - __IO uint32_t REG_NONCER0; - __IO uint32_t REG_NONCER1; - __IO uint32_t REG_KEYR0; - __IO uint32_t REG_KEYR1; - __IO uint32_t REG_KEYR2; - __IO uint32_t REG_KEYR3; -} OTFDEC_Region_TypeDef; - -typedef struct -{ - __IO uint32_t CR; - uint32_t RESERVED1[191]; - __IO uint32_t ISR; - __IO uint32_t ICR; - __IO uint32_t IER; - uint32_t RESERVED2[56]; - __IO uint32_t HWCFGR2; - __IO uint32_t HWCFGR1; - __IO uint32_t VERR; - __IO uint32_t IPIDR; - __IO uint32_t SIDR; -} OTFDEC_TypeDef; -/** - * @} - */ - -/** - * @brief Global Programmer View - */ - -typedef struct -{ - uint32_t RESERVED0[2036]; /*!< Reserved, Address offset: 0x00-0x1FCC */ - __IO uint32_t AXI_PERIPH_ID_4; /*!< AXI interconnect - peripheral ID4 register, Address offset: 0x1FD0 */ - uint32_t AXI_PERIPH_ID_5; /*!< Reserved, Address offset: 0x1FD4 */ - uint32_t AXI_PERIPH_ID_6; /*!< Reserved, Address offset: 0x1FD8 */ - uint32_t AXI_PERIPH_ID_7; /*!< Reserved, Address offset: 0x1FDC */ - __IO uint32_t AXI_PERIPH_ID_0; /*!< AXI interconnect - peripheral ID0 register, Address offset: 0x1FE0 */ - __IO uint32_t AXI_PERIPH_ID_1; /*!< AXI interconnect - peripheral ID1 register, Address offset: 0x1FE4 */ - __IO uint32_t AXI_PERIPH_ID_2; /*!< AXI interconnect - peripheral ID2 register, Address offset: 0x1FE8 */ - __IO uint32_t AXI_PERIPH_ID_3; /*!< AXI interconnect - peripheral ID3 register, Address offset: 0x1FEC */ - __IO uint32_t AXI_COMP_ID_0; /*!< AXI interconnect - component ID0 register, Address offset: 0x1FF0 */ - __IO uint32_t AXI_COMP_ID_1; /*!< AXI interconnect - component ID1 register, Address offset: 0x1FF4 */ - __IO uint32_t AXI_COMP_ID_2; /*!< AXI interconnect - component ID2 register, Address offset: 0x1FF8 */ - __IO uint32_t AXI_COMP_ID_3; /*!< AXI interconnect - component ID3 register, Address offset: 0x1FFC */ - uint32_t RESERVED1[2]; /*!< Reserved, Address offset: 0x2000-0x2004 */ - __IO uint32_t AXI_TARG1_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 1 bus matrix issuing functionality register, Address offset: 0x2008 */ - uint32_t RESERVED2[6]; /*!< Reserved, Address offset: 0x200C-0x2020 */ - __IO uint32_t AXI_TARG1_FN_MOD2; /*!< AXI interconnect - TARG 1 bus matrix functionality 2 register, Address offset: 0x2024 */ - uint32_t RESERVED3; /*!< Reserved, Address offset: 0x2028 */ - __IO uint32_t AXI_TARG1_FN_MOD_LB; /*!< AXI interconnect - TARG 1 long burst functionality modification register, Address offset: 0x202C */ - uint32_t RESERVED4[54]; /*!< Reserved, Address offset: 0x2030-0x2104 */ - __IO uint32_t AXI_TARG1_FN_MOD; /*!< AXI interconnect - TARG 1 issuing functionality modification register, Address offset: 0x2108 */ - uint32_t RESERVED5[959]; /*!< Reserved, Address offset: 0x210C-0x3004 */ - __IO uint32_t AXI_TARG2_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 2 bus matrix issuing functionality register, Address offset: 0x3008 */ - uint32_t RESERVED6[6]; /*!< Reserved, Address offset: 0x300C-0x3020 */ - __IO uint32_t AXI_TARG2_FN_MOD2; /*!< AXI interconnect - TARG 2 bus matrix functionality 2 register, Address offset: 0x3024 */ - uint32_t RESERVED7; /*!< Reserved, Address offset: 0x3028 */ - __IO uint32_t AXI_TARG2_FN_MOD_LB; /*!< AXI interconnect - TARG 2 long burst functionality modification register, Address offset: 0x302C */ - uint32_t RESERVED8[54]; /*!< Reserved, Address offset: 0x3030-0x3104 */ - __IO uint32_t AXI_TARG2_FN_MOD; /*!< AXI interconnect - TARG 2 issuing functionality modification register, Address offset: 0x3108 */ - uint32_t RESERVED9[959]; /*!< Reserved, Address offset: 0x310C-0x4004 */ - __IO uint32_t AXI_TARG3_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 3 bus matrix issuing functionality register, Address offset: 0x4008 */ - uint32_t RESERVED10[1023]; /*!< Reserved, Address offset: 0x400C-0x5004 */ - __IO uint32_t AXI_TARG4_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 4 bus matrix issuing functionality register, Address offset: 0x5008 */ - uint32_t RESERVED11[1023]; /*!< Reserved, Address offset: 0x500C-0x6004 */ - __IO uint32_t AXI_TARG5_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 5 bus matrix issuing functionality register, Address offset: 0x6008 */ - uint32_t RESERVED12[1023]; /*!< Reserved, Address offset: 0x600C-0x7004 */ - __IO uint32_t AXI_TARG6_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 6 bus matrix issuing functionality register, Address offset: 0x7008 */ - uint32_t RESERVED13[1023]; /*!< Reserved, Address offset: 0x700C-0x8004 */ - __IO uint32_t AXI_TARG7_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 7 bus matrix issuing functionality register, Address offset: 0x8008 */ - uint32_t RESERVED14[6]; /*!< Reserved, Address offset: 0x800C-0x8020 */ - __IO uint32_t AXI_TARG7_FN_MOD2; /*!< AXI interconnect - TARG 7 bus matrix functionality 2 register, Address offset: 0x8024 */ - uint32_t RESERVED15; /*!< Reserved, Address offset: 0x8028 */ - __IO uint32_t AXI_TARG7_FN_MOD_LB; /*!< AXI interconnect - TARG 7 long burst functionality modification register, Address offset: 0x802C */ - uint32_t RESERVED16[54]; /*!< Reserved, Address offset: 0x8030-0x8104 */ - __IO uint32_t AXI_TARG7_FN_MOD; /*!< AXI interconnect - TARG 7 issuing functionality modification register, Address offset: 0x8108 */ - uint32_t RESERVED17[959]; /*!< Reserved, Address offset: 0x810C-0x9004 */ - __IO uint32_t AXI_TARG8_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 8 bus matrix issuing functionality register, Address offset: 0x9008 */ - uint32_t RESERVED117[6]; /*!< Reserved, Address offset: 0x900C-0x9020 */ - __IO uint32_t AXI_TARG8_FN_MOD2; /*!< AXI interconnect - TARG 8 bus matrix functionality 2 register, Address offset: 0x9024 */ - uint32_t RESERVED118[56]; /*!< Reserved, Address offset: 0x9028-0x9104 */ - __IO uint32_t AXI_TARG8_FN_MOD; /*!< AXI interconnect - TARG 8 issuing functionality modification register, Address offset: 0x9108 */ - uint32_t RESERVED119[58310]; /*!< Reserved, Address offset: 0x910C-0x42020 */ - __IO uint32_t AXI_INI1_FN_MOD2; /*!< AXI interconnect - INI 1 functionality modification 2 register, Address offset: 0x42024 */ - __IO uint32_t AXI_INI1_FN_MOD_AHB; /*!< AXI interconnect - INI 1 AHB functionality modification register, Address offset: 0x42028 */ - uint32_t RESERVED18[53]; /*!< Reserved, Address offset: 0x4202C-0x420FC */ - __IO uint32_t AXI_INI1_READ_QOS; /*!< AXI interconnect - INI 1 read QoS register, Address offset: 0x42100 */ - __IO uint32_t AXI_INI1_WRITE_QOS; /*!< AXI interconnect - INI 1 write QoS register, Address offset: 0x42104 */ - __IO uint32_t AXI_INI1_FN_MOD; /*!< AXI interconnect - INI 1 issuing functionality modification register, Address offset: 0x42108 */ - uint32_t RESERVED19[1021]; /*!< Reserved, Address offset: 0x4210C-0x430FC */ - __IO uint32_t AXI_INI2_READ_QOS; /*!< AXI interconnect - INI 2 read QoS register, Address offset: 0x43100 */ - __IO uint32_t AXI_INI2_WRITE_QOS; /*!< AXI interconnect - INI 2 write QoS register, Address offset: 0x43104 */ - __IO uint32_t AXI_INI2_FN_MOD; /*!< AXI interconnect - INI 2 issuing functionality modification register, Address offset: 0x43108 */ - uint32_t RESERVED20[966]; /*!< Reserved, Address offset: 0x4310C-0x44020 */ - __IO uint32_t AXI_INI3_FN_MOD2; /*!< AXI interconnect - INI 3 functionality modification 2 register, Address offset: 0x44024 */ - __IO uint32_t AXI_INI3_FN_MOD_AHB; /*!< AXI interconnect - INI 3 AHB functionality modification register, Address offset: 0x44028 */ - uint32_t RESERVED21[53]; /*!< Reserved, Address offset: 0x4402C-0x440FC */ - __IO uint32_t AXI_INI3_READ_QOS; /*!< AXI interconnect - INI 3 read QoS register, Address offset: 0x44100 */ - __IO uint32_t AXI_INI3_WRITE_QOS; /*!< AXI interconnect - INI 3 write QoS register, Address offset: 0x44104 */ - __IO uint32_t AXI_INI3_FN_MOD; /*!< AXI interconnect - INI 3 issuing functionality modification register, Address offset: 0x44108 */ - uint32_t RESERVED22[1021]; /*!< Reserved, Address offset: 0x4410C-0x450FC */ - __IO uint32_t AXI_INI4_READ_QOS; /*!< AXI interconnect - INI 4 read QoS register, Address offset: 0x45100 */ - __IO uint32_t AXI_INI4_WRITE_QOS; /*!< AXI interconnect - INI 4 write QoS register, Address offset: 0x45104 */ - __IO uint32_t AXI_INI4_FN_MOD; /*!< AXI interconnect - INI 4 issuing functionality modification register, Address offset: 0x45108 */ - uint32_t RESERVED23[1021]; /*!< Reserved, Address offset: 0x4510C-0x460FC */ - __IO uint32_t AXI_INI5_READ_QOS; /*!< AXI interconnect - INI 5 read QoS register, Address offset: 0x46100 */ - __IO uint32_t AXI_INI5_WRITE_QOS; /*!< AXI interconnect - INI 5 write QoS register, Address offset: 0x46104 */ - __IO uint32_t AXI_INI5_FN_MOD; /*!< AXI interconnect - INI 5 issuing functionality modification register, Address offset: 0x46108 */ - uint32_t RESERVED24[1021]; /*!< Reserved, Address offset: 0x4610C-0x470FC */ - __IO uint32_t AXI_INI6_READ_QOS; /*!< AXI interconnect - INI 6 read QoS register, Address offset: 0x47100 */ - __IO uint32_t AXI_INI6_WRITE_QOS; /*!< AXI interconnect - INI 6 write QoS register, Address offset: 0x47104 */ - __IO uint32_t AXI_INI6_FN_MOD; /*!< AXI interconnect - INI 6 issuing functionality modification register, Address offset: 0x47108 */ - -} GPV_TypeDef; - -/** @addtogroup Peripheral_memory_map - * @{ - */ -#define D1_ITCMRAM_BASE (0x00000000UL) /*!< Base address of : 64KB RAM reserved for CPU execution/instruction accessible over ITCM */ -#define D1_ITCMICP_BASE (0x00100000UL) /*!< Base address of : (up to 128KB) embedded Test FLASH memory accessible over ITCM */ -#define D1_DTCMRAM_BASE (0x20000000UL) /*!< Base address of : 128KB system data RAM accessible over DTCM */ -#define D1_AXIFLASH_BASE (0x08000000UL) /*!< Base address of : (up to 1 MB) embedded FLASH memory accessible over AXI */ -#define D1_AXIICP_BASE (0x1FF00000UL) /*!< Base address of : (up to 128KB) embedded Test FLASH memory accessible over AXI */ -#define D1_AXISRAM1_BASE (0x24000000UL) /*!< Base address of : (up to 128KB) system data RAM1 accessible over over AXI */ -#define D1_AXISRAM2_BASE (0x24020000UL) /*!< Base address of : (up to 192KB) system data RAM2 accessible over over AXI to be shared with ITCM (64K granularity) */ -#define D1_AXISRAM_BASE D1_AXISRAM1_BASE /*!< Base address of : (up to 320KB) system data RAM1/2 accessible over over AXI */ - -#define D2_AHBSRAM1_BASE (0x30000000UL) /*!< Base address of : (up to 16KB) system data RAM accessible over over AXI->AHB Bridge */ -#define D2_AHBSRAM2_BASE (0x30004000UL) /*!< Base address of : (up to 16KB) system data RAM accessible over over AXI->AHB Bridge */ -#define D2_AHBSRAM_BASE D2_AHBSRAM1_BASE /*!< Base address of : (up to 32KB) system data RAM1/2 accessible over over AXI->AHB Bridge */ - -#define D3_BKPSRAM_BASE (0x38800000UL) /*!< Base address of : Backup SRAM(4 KB) over AXI->AHB Bridge */ -#define D3_SRAM_BASE (0x38000000UL) /*!< Base address of : Backup SRAM(16 KB) over AXI->AHB Bridge */ - -#define PERIPH_BASE (0x40000000UL) /*!< Base address of : AHB/APB Peripherals */ -#define OCTOSPI1_BASE (0x90000000UL) /*!< Base address of : OCTOSPI1 memories accessible over AXI */ -#define OCTOSPI2_BASE (0x70000000UL) /*!< Base address of : OCTOSPI2 memories accessible over AXI */ - -#define FLASH_BANK1_BASE (0x08000000UL) /*!< Base address of : (up to 1 MB) Flash Bank1 accessible over AXI */ -#define FLASH_END (0x080FFFFFUL) /*!< FLASH end address */ - - -/* Legacy define */ -#define FLASH_BASE FLASH_BANK1_BASE - -/*!< Device electronic signature memory map */ -#define UID_BASE (0x1FF1E800UL) /*!< Unique device ID register base address */ -#define FLASHSIZE_BASE (0x1FF1E880UL) /*!< FLASH Size register base address */ - - -/*!< Peripheral memory map */ -#define D2_APB1PERIPH_BASE PERIPH_BASE -#define D2_APB2PERIPH_BASE (PERIPH_BASE + 0x00010000UL) -#define D2_AHB1PERIPH_BASE (PERIPH_BASE + 0x00020000UL) -#define D2_AHB2PERIPH_BASE (PERIPH_BASE + 0x08020000UL) - -#define D1_APB1PERIPH_BASE (PERIPH_BASE + 0x10000000UL) -#define D1_AHB1PERIPH_BASE (PERIPH_BASE + 0x12000000UL) - -#define D3_APB1PERIPH_BASE (PERIPH_BASE + 0x18000000UL) -#define D3_AHB1PERIPH_BASE (PERIPH_BASE + 0x18020000UL) - -/*!< Legacy Peripheral memory map */ -#define APB1PERIPH_BASE PERIPH_BASE -#define APB2PERIPH_BASE (PERIPH_BASE + 0x00010000UL) -#define AHB1PERIPH_BASE (PERIPH_BASE + 0x00020000UL) -#define AHB2PERIPH_BASE (PERIPH_BASE + 0x08000000UL) - - -/*!< D1_AHB1PERIPH peripherals */ - -#define MDMA_BASE (D1_AHB1PERIPH_BASE + 0x0000UL) -#define DMA2D_BASE (D1_AHB1PERIPH_BASE + 0x1000UL) -#define FLASH_R_BASE (D1_AHB1PERIPH_BASE + 0x2000UL) -#define FMC_R_BASE (D1_AHB1PERIPH_BASE + 0x4000UL) -#define OCTOSPI1_R_BASE (D1_AHB1PERIPH_BASE + 0x5000UL) -#define DLYB_OCTOSPI1_BASE (D1_AHB1PERIPH_BASE + 0x6000UL) -#define SDMMC1_BASE (D1_AHB1PERIPH_BASE + 0x7000UL) -#define DLYB_SDMMC1_BASE (D1_AHB1PERIPH_BASE + 0x8000UL) -#define RAMECC1_BASE (D1_AHB1PERIPH_BASE + 0x9000UL) -#define OCTOSPI2_R_BASE (D1_AHB1PERIPH_BASE + 0xA000UL) -#define DLYB_OCTOSPI2_BASE (D1_AHB1PERIPH_BASE + 0xB000UL) -#define OCTOSPIM_BASE (D1_AHB1PERIPH_BASE + 0xB400UL) - -#define OTFDEC1_BASE (D1_AHB1PERIPH_BASE + 0xB800UL) -#define OTFDEC1_REGION1_BASE (OTFDEC1_BASE + 0x20UL) -#define OTFDEC1_REGION2_BASE (OTFDEC1_BASE + 0x50UL) -#define OTFDEC1_REGION3_BASE (OTFDEC1_BASE + 0x80UL) -#define OTFDEC1_REGION4_BASE (OTFDEC1_BASE + 0xB0UL) -#define OTFDEC2_BASE (D1_AHB1PERIPH_BASE + 0xBC00UL) -#define OTFDEC2_REGION1_BASE (OTFDEC2_BASE + 0x20UL) -#define OTFDEC2_REGION2_BASE (OTFDEC2_BASE + 0x50UL) -#define OTFDEC2_REGION3_BASE (OTFDEC2_BASE + 0x80UL) -#define OTFDEC2_REGION4_BASE (OTFDEC2_BASE + 0xB0UL) - -/*!< D2_AHB1PERIPH peripherals */ - -#define DMA1_BASE (D2_AHB1PERIPH_BASE + 0x0000UL) -#define DMA2_BASE (D2_AHB1PERIPH_BASE + 0x0400UL) -#define DMAMUX1_BASE (D2_AHB1PERIPH_BASE + 0x0800UL) -#define ADC1_BASE (D2_AHB1PERIPH_BASE + 0x2000UL) -#define ADC2_BASE (D2_AHB1PERIPH_BASE + 0x2100UL) -#define ADC12_COMMON_BASE (D2_AHB1PERIPH_BASE + 0x2300UL) -#define ETH_BASE (D2_AHB1PERIPH_BASE + 0x8000UL) -#define ETH_MAC_BASE (ETH_BASE) - -/*!< USB registers base address */ -#define USB1_OTG_HS_PERIPH_BASE (0x40040000UL) -#define USB_OTG_GLOBAL_BASE (0x000UL) -#define USB_OTG_DEVICE_BASE (0x800UL) -#define USB_OTG_IN_ENDPOINT_BASE (0x900UL) -#define USB_OTG_OUT_ENDPOINT_BASE (0xB00UL) -#define USB_OTG_EP_REG_SIZE (0x20UL) -#define USB_OTG_HOST_BASE (0x400UL) -#define USB_OTG_HOST_PORT_BASE (0x440UL) -#define USB_OTG_HOST_CHANNEL_BASE (0x500UL) -#define USB_OTG_HOST_CHANNEL_SIZE (0x20UL) -#define USB_OTG_PCGCCTL_BASE (0xE00UL) -#define USB_OTG_FIFO_BASE (0x1000UL) -#define USB_OTG_FIFO_SIZE (0x1000UL) - -/*!< D2_AHB2PERIPH peripherals */ - -#define DCMI_BASE (D2_AHB2PERIPH_BASE + 0x0000UL) -#define PSSI_BASE (D2_AHB2PERIPH_BASE + 0x0400UL) -#define CRYP_BASE (D2_AHB2PERIPH_BASE + 0x1000UL) -#define HASH_BASE (D2_AHB2PERIPH_BASE + 0x1400UL) -#define HASH_DIGEST_BASE (D2_AHB2PERIPH_BASE + 0x1710UL) -#define RNG_BASE (D2_AHB2PERIPH_BASE + 0x1800UL) -#define SDMMC2_BASE (D2_AHB2PERIPH_BASE + 0x2400UL) -#define DLYB_SDMMC2_BASE (D2_AHB2PERIPH_BASE + 0x2800UL) -#define RAMECC2_BASE (D2_AHB2PERIPH_BASE + 0x3000UL) -#define FMAC_BASE (D2_AHB2PERIPH_BASE + 0x4000UL) -#define CORDIC_BASE (D2_AHB2PERIPH_BASE + 0x4400UL) - -/*!< D3_AHB1PERIPH peripherals */ -#define GPIOA_BASE (D3_AHB1PERIPH_BASE + 0x0000UL) -#define GPIOB_BASE (D3_AHB1PERIPH_BASE + 0x0400UL) -#define GPIOC_BASE (D3_AHB1PERIPH_BASE + 0x0800UL) -#define GPIOD_BASE (D3_AHB1PERIPH_BASE + 0x0C00UL) -#define GPIOE_BASE (D3_AHB1PERIPH_BASE + 0x1000UL) -#define GPIOF_BASE (D3_AHB1PERIPH_BASE + 0x1400UL) -#define GPIOG_BASE (D3_AHB1PERIPH_BASE + 0x1800UL) -#define GPIOH_BASE (D3_AHB1PERIPH_BASE + 0x1C00UL) -#define GPIOJ_BASE (D3_AHB1PERIPH_BASE + 0x2400UL) -#define GPIOK_BASE (D3_AHB1PERIPH_BASE + 0x2800UL) -#define RCC_BASE (D3_AHB1PERIPH_BASE + 0x4400UL) -#define PWR_BASE (D3_AHB1PERIPH_BASE + 0x4800UL) -#define CRC_BASE (D3_AHB1PERIPH_BASE + 0x4C00UL) -#define BDMA_BASE (D3_AHB1PERIPH_BASE + 0x5400UL) -#define DMAMUX2_BASE (D3_AHB1PERIPH_BASE + 0x5800UL) -#define ADC3_BASE (D3_AHB1PERIPH_BASE + 0x6000UL) -#define ADC3_COMMON_BASE (D3_AHB1PERIPH_BASE + 0x6300UL) -#define HSEM_BASE (D3_AHB1PERIPH_BASE + 0x6400UL) -#define RAMECC3_BASE (D3_AHB1PERIPH_BASE + 0x7000UL) - -/*!< D1_APB1PERIPH peripherals */ -#define LTDC_BASE (D1_APB1PERIPH_BASE + 0x1000UL) -#define LTDC_Layer1_BASE (LTDC_BASE + 0x84UL) -#define LTDC_Layer2_BASE (LTDC_BASE + 0x104UL) -#define WWDG1_BASE (D1_APB1PERIPH_BASE + 0x3000UL) - -/*!< D2_APB1PERIPH peripherals */ -#define TIM2_BASE (D2_APB1PERIPH_BASE + 0x0000UL) -#define TIM3_BASE (D2_APB1PERIPH_BASE + 0x0400UL) -#define TIM4_BASE (D2_APB1PERIPH_BASE + 0x0800UL) -#define TIM5_BASE (D2_APB1PERIPH_BASE + 0x0C00UL) -#define TIM6_BASE (D2_APB1PERIPH_BASE + 0x1000UL) -#define TIM7_BASE (D2_APB1PERIPH_BASE + 0x1400UL) -#define TIM12_BASE (D2_APB1PERIPH_BASE + 0x1800UL) -#define TIM13_BASE (D2_APB1PERIPH_BASE + 0x1C00UL) -#define TIM14_BASE (D2_APB1PERIPH_BASE + 0x2000UL) -#define LPTIM1_BASE (D2_APB1PERIPH_BASE + 0x2400UL) - - -#define SPI2_BASE (D2_APB1PERIPH_BASE + 0x3800UL) -#define SPI3_BASE (D2_APB1PERIPH_BASE + 0x3C00UL) -#define SPDIFRX_BASE (D2_APB1PERIPH_BASE + 0x4000UL) -#define USART2_BASE (D2_APB1PERIPH_BASE + 0x4400UL) -#define USART3_BASE (D2_APB1PERIPH_BASE + 0x4800UL) -#define UART4_BASE (D2_APB1PERIPH_BASE + 0x4C00UL) -#define UART5_BASE (D2_APB1PERIPH_BASE + 0x5000UL) -#define I2C1_BASE (D2_APB1PERIPH_BASE + 0x5400UL) -#define I2C2_BASE (D2_APB1PERIPH_BASE + 0x5800UL) -#define I2C3_BASE (D2_APB1PERIPH_BASE + 0x5C00UL) -#define I2C5_BASE (D2_APB1PERIPH_BASE + 0x6400UL) -#define CEC_BASE (D2_APB1PERIPH_BASE + 0x6C00UL) -#define DAC1_BASE (D2_APB1PERIPH_BASE + 0x7400UL) -#define UART7_BASE (D2_APB1PERIPH_BASE + 0x7800UL) -#define UART8_BASE (D2_APB1PERIPH_BASE + 0x7C00UL) -#define CRS_BASE (D2_APB1PERIPH_BASE + 0x8400UL) -#define SWPMI1_BASE (D2_APB1PERIPH_BASE + 0x8800UL) -#define OPAMP_BASE (D2_APB1PERIPH_BASE + 0x9000UL) -#define OPAMP1_BASE (D2_APB1PERIPH_BASE + 0x9000UL) -#define OPAMP2_BASE (D2_APB1PERIPH_BASE + 0x9010UL) -#define MDIOS_BASE (D2_APB1PERIPH_BASE + 0x9400UL) -#define FDCAN1_BASE (D2_APB1PERIPH_BASE + 0xA000UL) -#define FDCAN2_BASE (D2_APB1PERIPH_BASE + 0xA400UL) -#define FDCAN_CCU_BASE (D2_APB1PERIPH_BASE + 0xA800UL) -#define SRAMCAN_BASE (D2_APB1PERIPH_BASE + 0xAC00UL) -#define FDCAN3_BASE (D2_APB1PERIPH_BASE + 0xD400UL) -#define TIM23_BASE (D2_APB1PERIPH_BASE + 0xE000UL) -#define TIM24_BASE (D2_APB1PERIPH_BASE + 0xE400UL) - -/*!< D2_APB2PERIPH peripherals */ - -#define TIM1_BASE (D2_APB2PERIPH_BASE + 0x0000UL) -#define TIM8_BASE (D2_APB2PERIPH_BASE + 0x0400UL) -#define USART1_BASE (D2_APB2PERIPH_BASE + 0x1000UL) -#define USART6_BASE (D2_APB2PERIPH_BASE + 0x1400UL) -#define UART9_BASE (D2_APB2PERIPH_BASE + 0x1800UL) -#define USART10_BASE (D2_APB2PERIPH_BASE + 0x1C00UL) -#define SPI1_BASE (D2_APB2PERIPH_BASE + 0x3000UL) -#define SPI4_BASE (D2_APB2PERIPH_BASE + 0x3400UL) -#define TIM15_BASE (D2_APB2PERIPH_BASE + 0x4000UL) -#define TIM16_BASE (D2_APB2PERIPH_BASE + 0x4400UL) -#define TIM17_BASE (D2_APB2PERIPH_BASE + 0x4800UL) -#define SPI5_BASE (D2_APB2PERIPH_BASE + 0x5000UL) -#define SAI1_BASE (D2_APB2PERIPH_BASE + 0x5800UL) -#define SAI1_Block_A_BASE (SAI1_BASE + 0x004UL) -#define SAI1_Block_B_BASE (SAI1_BASE + 0x024UL) -#define DFSDM1_BASE (D2_APB2PERIPH_BASE + 0x7800UL) -#define DFSDM1_Channel0_BASE (DFSDM1_BASE + 0x00UL) -#define DFSDM1_Channel1_BASE (DFSDM1_BASE + 0x20UL) -#define DFSDM1_Channel2_BASE (DFSDM1_BASE + 0x40UL) -#define DFSDM1_Channel3_BASE (DFSDM1_BASE + 0x60UL) -#define DFSDM1_Channel4_BASE (DFSDM1_BASE + 0x80UL) -#define DFSDM1_Channel5_BASE (DFSDM1_BASE + 0xA0UL) -#define DFSDM1_Channel6_BASE (DFSDM1_BASE + 0xC0UL) -#define DFSDM1_Channel7_BASE (DFSDM1_BASE + 0xE0UL) -#define DFSDM1_Filter0_BASE (DFSDM1_BASE + 0x100UL) -#define DFSDM1_Filter1_BASE (DFSDM1_BASE + 0x180UL) -#define DFSDM1_Filter2_BASE (DFSDM1_BASE + 0x200UL) -#define DFSDM1_Filter3_BASE (DFSDM1_BASE + 0x280UL) - - -/*!< D3_APB1PERIPH peripherals */ -#define EXTI_BASE (D3_APB1PERIPH_BASE + 0x0000UL) -#define EXTI_D1_BASE (EXTI_BASE + 0x0080UL) -#define EXTI_D2_BASE (EXTI_BASE + 0x00C0UL) -#define SYSCFG_BASE (D3_APB1PERIPH_BASE + 0x0400UL) -#define LPUART1_BASE (D3_APB1PERIPH_BASE + 0x0C00UL) -#define SPI6_BASE (D3_APB1PERIPH_BASE + 0x1400UL) -#define I2C4_BASE (D3_APB1PERIPH_BASE + 0x1C00UL) -#define LPTIM2_BASE (D3_APB1PERIPH_BASE + 0x2400UL) -#define LPTIM3_BASE (D3_APB1PERIPH_BASE + 0x2800UL) -#define LPTIM4_BASE (D3_APB1PERIPH_BASE + 0x2C00UL) -#define LPTIM5_BASE (D3_APB1PERIPH_BASE + 0x3000UL) -#define COMP12_BASE (D3_APB1PERIPH_BASE + 0x3800UL) -#define COMP1_BASE (COMP12_BASE + 0x0CUL) -#define COMP2_BASE (COMP12_BASE + 0x10UL) -#define VREFBUF_BASE (D3_APB1PERIPH_BASE + 0x3C00UL) -#define RTC_BASE (D3_APB1PERIPH_BASE + 0x4000UL) -#define IWDG1_BASE (D3_APB1PERIPH_BASE + 0x4800UL) - - -#define SAI4_BASE (D3_APB1PERIPH_BASE + 0x5400UL) -#define SAI4_Block_A_BASE (SAI4_BASE + 0x004UL) -#define SAI4_Block_B_BASE (SAI4_BASE + 0x024UL) - -#define DTS_BASE (D3_APB1PERIPH_BASE + 0x6800UL) - - - -#define BDMA_Channel0_BASE (BDMA_BASE + 0x0008UL) -#define BDMA_Channel1_BASE (BDMA_BASE + 0x001CUL) -#define BDMA_Channel2_BASE (BDMA_BASE + 0x0030UL) -#define BDMA_Channel3_BASE (BDMA_BASE + 0x0044UL) -#define BDMA_Channel4_BASE (BDMA_BASE + 0x0058UL) -#define BDMA_Channel5_BASE (BDMA_BASE + 0x006CUL) -#define BDMA_Channel6_BASE (BDMA_BASE + 0x0080UL) -#define BDMA_Channel7_BASE (BDMA_BASE + 0x0094UL) - -#define DMAMUX2_Channel0_BASE (DMAMUX2_BASE) -#define DMAMUX2_Channel1_BASE (DMAMUX2_BASE + 0x0004UL) -#define DMAMUX2_Channel2_BASE (DMAMUX2_BASE + 0x0008UL) -#define DMAMUX2_Channel3_BASE (DMAMUX2_BASE + 0x000CUL) -#define DMAMUX2_Channel4_BASE (DMAMUX2_BASE + 0x0010UL) -#define DMAMUX2_Channel5_BASE (DMAMUX2_BASE + 0x0014UL) -#define DMAMUX2_Channel6_BASE (DMAMUX2_BASE + 0x0018UL) -#define DMAMUX2_Channel7_BASE (DMAMUX2_BASE + 0x001CUL) - -#define DMAMUX2_RequestGenerator0_BASE (DMAMUX2_BASE + 0x0100UL) -#define DMAMUX2_RequestGenerator1_BASE (DMAMUX2_BASE + 0x0104UL) -#define DMAMUX2_RequestGenerator2_BASE (DMAMUX2_BASE + 0x0108UL) -#define DMAMUX2_RequestGenerator3_BASE (DMAMUX2_BASE + 0x010CUL) -#define DMAMUX2_RequestGenerator4_BASE (DMAMUX2_BASE + 0x0110UL) -#define DMAMUX2_RequestGenerator5_BASE (DMAMUX2_BASE + 0x0114UL) -#define DMAMUX2_RequestGenerator6_BASE (DMAMUX2_BASE + 0x0118UL) -#define DMAMUX2_RequestGenerator7_BASE (DMAMUX2_BASE + 0x011CUL) - -#define DMAMUX2_ChannelStatus_BASE (DMAMUX2_BASE + 0x0080UL) -#define DMAMUX2_RequestGenStatus_BASE (DMAMUX2_BASE + 0x0140UL) - -#define DMA1_Stream0_BASE (DMA1_BASE + 0x010UL) -#define DMA1_Stream1_BASE (DMA1_BASE + 0x028UL) -#define DMA1_Stream2_BASE (DMA1_BASE + 0x040UL) -#define DMA1_Stream3_BASE (DMA1_BASE + 0x058UL) -#define DMA1_Stream4_BASE (DMA1_BASE + 0x070UL) -#define DMA1_Stream5_BASE (DMA1_BASE + 0x088UL) -#define DMA1_Stream6_BASE (DMA1_BASE + 0x0A0UL) -#define DMA1_Stream7_BASE (DMA1_BASE + 0x0B8UL) - -#define DMA2_Stream0_BASE (DMA2_BASE + 0x010UL) -#define DMA2_Stream1_BASE (DMA2_BASE + 0x028UL) -#define DMA2_Stream2_BASE (DMA2_BASE + 0x040UL) -#define DMA2_Stream3_BASE (DMA2_BASE + 0x058UL) -#define DMA2_Stream4_BASE (DMA2_BASE + 0x070UL) -#define DMA2_Stream5_BASE (DMA2_BASE + 0x088UL) -#define DMA2_Stream6_BASE (DMA2_BASE + 0x0A0UL) -#define DMA2_Stream7_BASE (DMA2_BASE + 0x0B8UL) - -#define DMAMUX1_Channel0_BASE (DMAMUX1_BASE) -#define DMAMUX1_Channel1_BASE (DMAMUX1_BASE + 0x0004UL) -#define DMAMUX1_Channel2_BASE (DMAMUX1_BASE + 0x0008UL) -#define DMAMUX1_Channel3_BASE (DMAMUX1_BASE + 0x000CUL) -#define DMAMUX1_Channel4_BASE (DMAMUX1_BASE + 0x0010UL) -#define DMAMUX1_Channel5_BASE (DMAMUX1_BASE + 0x0014UL) -#define DMAMUX1_Channel6_BASE (DMAMUX1_BASE + 0x0018UL) -#define DMAMUX1_Channel7_BASE (DMAMUX1_BASE + 0x001CUL) -#define DMAMUX1_Channel8_BASE (DMAMUX1_BASE + 0x0020UL) -#define DMAMUX1_Channel9_BASE (DMAMUX1_BASE + 0x0024UL) -#define DMAMUX1_Channel10_BASE (DMAMUX1_BASE + 0x0028UL) -#define DMAMUX1_Channel11_BASE (DMAMUX1_BASE + 0x002CUL) -#define DMAMUX1_Channel12_BASE (DMAMUX1_BASE + 0x0030UL) -#define DMAMUX1_Channel13_BASE (DMAMUX1_BASE + 0x0034UL) -#define DMAMUX1_Channel14_BASE (DMAMUX1_BASE + 0x0038UL) -#define DMAMUX1_Channel15_BASE (DMAMUX1_BASE + 0x003CUL) - -#define DMAMUX1_RequestGenerator0_BASE (DMAMUX1_BASE + 0x0100UL) -#define DMAMUX1_RequestGenerator1_BASE (DMAMUX1_BASE + 0x0104UL) -#define DMAMUX1_RequestGenerator2_BASE (DMAMUX1_BASE + 0x0108UL) -#define DMAMUX1_RequestGenerator3_BASE (DMAMUX1_BASE + 0x010CUL) -#define DMAMUX1_RequestGenerator4_BASE (DMAMUX1_BASE + 0x0110UL) -#define DMAMUX1_RequestGenerator5_BASE (DMAMUX1_BASE + 0x0114UL) -#define DMAMUX1_RequestGenerator6_BASE (DMAMUX1_BASE + 0x0118UL) -#define DMAMUX1_RequestGenerator7_BASE (DMAMUX1_BASE + 0x011CUL) - -#define DMAMUX1_ChannelStatus_BASE (DMAMUX1_BASE + 0x0080UL) -#define DMAMUX1_RequestGenStatus_BASE (DMAMUX1_BASE + 0x0140UL) - -/*!< FMC Banks registers base address */ -#define FMC_Bank1_R_BASE (FMC_R_BASE + 0x0000UL) -#define FMC_Bank1E_R_BASE (FMC_R_BASE + 0x0104UL) -#define FMC_Bank2_R_BASE (FMC_R_BASE + 0x0060UL) -#define FMC_Bank3_R_BASE (FMC_R_BASE + 0x0080UL) -#define FMC_Bank5_6_R_BASE (FMC_R_BASE + 0x0140UL) - -/* Debug MCU registers base address */ -#define DBGMCU_BASE (0x5C001000UL) - -#define MDMA_Channel0_BASE (MDMA_BASE + 0x00000040UL) -#define MDMA_Channel1_BASE (MDMA_BASE + 0x00000080UL) -#define MDMA_Channel2_BASE (MDMA_BASE + 0x000000C0UL) -#define MDMA_Channel3_BASE (MDMA_BASE + 0x00000100UL) -#define MDMA_Channel4_BASE (MDMA_BASE + 0x00000140UL) -#define MDMA_Channel5_BASE (MDMA_BASE + 0x00000180UL) -#define MDMA_Channel6_BASE (MDMA_BASE + 0x000001C0UL) -#define MDMA_Channel7_BASE (MDMA_BASE + 0x00000200UL) -#define MDMA_Channel8_BASE (MDMA_BASE + 0x00000240UL) -#define MDMA_Channel9_BASE (MDMA_BASE + 0x00000280UL) -#define MDMA_Channel10_BASE (MDMA_BASE + 0x000002C0UL) -#define MDMA_Channel11_BASE (MDMA_BASE + 0x00000300UL) -#define MDMA_Channel12_BASE (MDMA_BASE + 0x00000340UL) -#define MDMA_Channel13_BASE (MDMA_BASE + 0x00000380UL) -#define MDMA_Channel14_BASE (MDMA_BASE + 0x000003C0UL) -#define MDMA_Channel15_BASE (MDMA_BASE + 0x00000400UL) - -#define RAMECC1_Monitor1_BASE (RAMECC1_BASE + 0x20UL) -#define RAMECC1_Monitor2_BASE (RAMECC1_BASE + 0x40UL) -#define RAMECC1_Monitor3_BASE (RAMECC1_BASE + 0x60UL) -#define RAMECC1_Monitor4_BASE (RAMECC1_BASE + 0x80UL) -#define RAMECC1_Monitor5_BASE (RAMECC1_BASE + 0xA0UL) -#define RAMECC1_Monitor6_BASE (RAMECC1_BASE + 0xC0UL) - -#define RAMECC2_Monitor1_BASE (RAMECC2_BASE + 0x20UL) -#define RAMECC2_Monitor2_BASE (RAMECC2_BASE + 0x40UL) -#define RAMECC2_Monitor3_BASE (RAMECC2_BASE + 0x60UL) - -#define RAMECC3_Monitor1_BASE (RAMECC3_BASE + 0x20UL) -#define RAMECC3_Monitor2_BASE (RAMECC3_BASE + 0x40UL) - - - -#define GPV_BASE (PERIPH_BASE + 0x11000000UL) /*!< GPV_BASE (PERIPH_BASE + 0x11000000UL) */ - -/** - * @} - */ - -/** @addtogroup Peripheral_declaration - * @{ - */ -#define TIM2 ((TIM_TypeDef *) TIM2_BASE) -#define TIM3 ((TIM_TypeDef *) TIM3_BASE) -#define TIM4 ((TIM_TypeDef *) TIM4_BASE) -#define TIM5 ((TIM_TypeDef *) TIM5_BASE) -#define TIM6 ((TIM_TypeDef *) TIM6_BASE) -#define TIM7 ((TIM_TypeDef *) TIM7_BASE) -#define TIM13 ((TIM_TypeDef *) TIM13_BASE) -#define TIM14 ((TIM_TypeDef *) TIM14_BASE) -#define VREFBUF ((VREFBUF_TypeDef *) VREFBUF_BASE) -#define RTC ((RTC_TypeDef *) RTC_BASE) -#define WWDG1 ((WWDG_TypeDef *) WWDG1_BASE) - - -#define IWDG1 ((IWDG_TypeDef *) IWDG1_BASE) -#define SPI2 ((SPI_TypeDef *) SPI2_BASE) -#define SPI3 ((SPI_TypeDef *) SPI3_BASE) -#define SPI4 ((SPI_TypeDef *) SPI4_BASE) -#define SPI5 ((SPI_TypeDef *) SPI5_BASE) -#define SPI6 ((SPI_TypeDef *) SPI6_BASE) -#define USART2 ((USART_TypeDef *) USART2_BASE) -#define USART3 ((USART_TypeDef *) USART3_BASE) -#define USART6 ((USART_TypeDef *) USART6_BASE) -#define USART10 ((USART_TypeDef *) USART10_BASE) -#define UART7 ((USART_TypeDef *) UART7_BASE) -#define UART8 ((USART_TypeDef *) UART8_BASE) -#define UART9 ((USART_TypeDef *) UART9_BASE) -#define CRS ((CRS_TypeDef *) CRS_BASE) -#define UART4 ((USART_TypeDef *) UART4_BASE) -#define UART5 ((USART_TypeDef *) UART5_BASE) -#define I2C1 ((I2C_TypeDef *) I2C1_BASE) -#define I2C2 ((I2C_TypeDef *) I2C2_BASE) -#define I2C3 ((I2C_TypeDef *) I2C3_BASE) -#define I2C4 ((I2C_TypeDef *) I2C4_BASE) -#define I2C5 ((I2C_TypeDef *) I2C5_BASE) -#define FDCAN1 ((FDCAN_GlobalTypeDef *) FDCAN1_BASE) -#define FDCAN2 ((FDCAN_GlobalTypeDef *) FDCAN2_BASE) -#define FDCAN_CCU ((FDCAN_ClockCalibrationUnit_TypeDef *) FDCAN_CCU_BASE) -#define FDCAN3 ((FDCAN_GlobalTypeDef *) FDCAN3_BASE) -#define TIM23 ((TIM_TypeDef *) TIM23_BASE) -#define TIM24 ((TIM_TypeDef *) TIM24_BASE) -#define CEC ((CEC_TypeDef *) CEC_BASE) -#define LPTIM1 ((LPTIM_TypeDef *) LPTIM1_BASE) -#define PWR ((PWR_TypeDef *) PWR_BASE) -#define DAC1 ((DAC_TypeDef *) DAC1_BASE) -#define LPUART1 ((USART_TypeDef *) LPUART1_BASE) -#define SWPMI1 ((SWPMI_TypeDef *) SWPMI1_BASE) -#define LPTIM2 ((LPTIM_TypeDef *) LPTIM2_BASE) -#define LPTIM3 ((LPTIM_TypeDef *) LPTIM3_BASE) -#define DTS ((DTS_TypeDef *) DTS_BASE) -#define LPTIM4 ((LPTIM_TypeDef *) LPTIM4_BASE) -#define LPTIM5 ((LPTIM_TypeDef *) LPTIM5_BASE) - -#define SYSCFG ((SYSCFG_TypeDef *) SYSCFG_BASE) -#define COMP12 ((COMPOPT_TypeDef *) COMP12_BASE) -#define COMP1 ((COMP_TypeDef *) COMP1_BASE) -#define COMP2 ((COMP_TypeDef *) COMP2_BASE) -#define COMP12_COMMON ((COMP_Common_TypeDef *) COMP2_BASE) -#define OPAMP ((OPAMP_TypeDef *) OPAMP_BASE) -#define OPAMP1 ((OPAMP_TypeDef *) OPAMP1_BASE) -#define OPAMP2 ((OPAMP_TypeDef *) OPAMP2_BASE) - - -#define EXTI ((EXTI_TypeDef *) EXTI_BASE) -#define EXTI_D1 ((EXTI_Core_TypeDef *) EXTI_D1_BASE) -#define EXTI_D2 ((EXTI_Core_TypeDef *) EXTI_D2_BASE) -#define TIM1 ((TIM_TypeDef *) TIM1_BASE) -#define SPI1 ((SPI_TypeDef *) SPI1_BASE) -#define TIM8 ((TIM_TypeDef *) TIM8_BASE) -#define USART1 ((USART_TypeDef *) USART1_BASE) -#define TIM12 ((TIM_TypeDef *) TIM12_BASE) -#define TIM15 ((TIM_TypeDef *) TIM15_BASE) -#define TIM16 ((TIM_TypeDef *) TIM16_BASE) -#define TIM17 ((TIM_TypeDef *) TIM17_BASE) -#define SAI1 ((SAI_TypeDef *) SAI1_BASE) -#define SAI1_Block_A ((SAI_Block_TypeDef *)SAI1_Block_A_BASE) -#define SAI1_Block_B ((SAI_Block_TypeDef *)SAI1_Block_B_BASE) -#define SAI4 ((SAI_TypeDef *) SAI4_BASE) -#define SAI4_Block_A ((SAI_Block_TypeDef *)SAI4_Block_A_BASE) -#define SAI4_Block_B ((SAI_Block_TypeDef *)SAI4_Block_B_BASE) - -#define SPDIFRX ((SPDIFRX_TypeDef *) SPDIFRX_BASE) -#define DFSDM1_Channel0 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel0_BASE) -#define DFSDM1_Channel1 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel1_BASE) -#define DFSDM1_Channel2 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel2_BASE) -#define DFSDM1_Channel3 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel3_BASE) -#define DFSDM1_Channel4 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel4_BASE) -#define DFSDM1_Channel5 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel5_BASE) -#define DFSDM1_Channel6 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel6_BASE) -#define DFSDM1_Channel7 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel7_BASE) -#define DFSDM1_Filter0 ((DFSDM_Filter_TypeDef *) DFSDM1_Filter0_BASE) -#define DFSDM1_Filter1 ((DFSDM_Filter_TypeDef *) DFSDM1_Filter1_BASE) -#define DFSDM1_Filter2 ((DFSDM_Filter_TypeDef *) DFSDM1_Filter2_BASE) -#define DFSDM1_Filter3 ((DFSDM_Filter_TypeDef *) DFSDM1_Filter3_BASE) -#define DMA2D ((DMA2D_TypeDef *) DMA2D_BASE) -#define DCMI ((DCMI_TypeDef *) DCMI_BASE) -#define PSSI ((PSSI_TypeDef *) PSSI_BASE) -#define RCC ((RCC_TypeDef *) RCC_BASE) -#define FLASH ((FLASH_TypeDef *) FLASH_R_BASE) -#define CRC ((CRC_TypeDef *) CRC_BASE) - -#define GPIOA ((GPIO_TypeDef *) GPIOA_BASE) -#define GPIOB ((GPIO_TypeDef *) GPIOB_BASE) -#define GPIOC ((GPIO_TypeDef *) GPIOC_BASE) -#define GPIOD ((GPIO_TypeDef *) GPIOD_BASE) -#define GPIOE ((GPIO_TypeDef *) GPIOE_BASE) -#define GPIOF ((GPIO_TypeDef *) GPIOF_BASE) -#define GPIOG ((GPIO_TypeDef *) GPIOG_BASE) -#define GPIOH ((GPIO_TypeDef *) GPIOH_BASE) -#define GPIOJ ((GPIO_TypeDef *) GPIOJ_BASE) -#define GPIOK ((GPIO_TypeDef *) GPIOK_BASE) - -#define ADC1 ((ADC_TypeDef *) ADC1_BASE) -#define ADC2 ((ADC_TypeDef *) ADC2_BASE) -#define ADC3 ((ADC_TypeDef *) ADC3_BASE) -#define ADC3_COMMON ((ADC_Common_TypeDef *) ADC3_COMMON_BASE) -#define ADC12_COMMON ((ADC_Common_TypeDef *) ADC12_COMMON_BASE) - -#define CRYP ((CRYP_TypeDef *) CRYP_BASE) -#define HASH ((HASH_TypeDef *) HASH_BASE) -#define HASH_DIGEST ((HASH_DIGEST_TypeDef *) HASH_DIGEST_BASE) -#define RNG ((RNG_TypeDef *) RNG_BASE) -#define SDMMC2 ((SDMMC_TypeDef *) SDMMC2_BASE) -#define DLYB_SDMMC2 ((DLYB_TypeDef *) DLYB_SDMMC2_BASE) -#define FMAC ((FMAC_TypeDef *) FMAC_BASE) -#define CORDIC ((CORDIC_TypeDef *) CORDIC_BASE) - -#define BDMA ((BDMA_TypeDef *) BDMA_BASE) -#define BDMA_Channel0 ((BDMA_Channel_TypeDef *) BDMA_Channel0_BASE) -#define BDMA_Channel1 ((BDMA_Channel_TypeDef *) BDMA_Channel1_BASE) -#define BDMA_Channel2 ((BDMA_Channel_TypeDef *) BDMA_Channel2_BASE) -#define BDMA_Channel3 ((BDMA_Channel_TypeDef *) BDMA_Channel3_BASE) -#define BDMA_Channel4 ((BDMA_Channel_TypeDef *) BDMA_Channel4_BASE) -#define BDMA_Channel5 ((BDMA_Channel_TypeDef *) BDMA_Channel5_BASE) -#define BDMA_Channel6 ((BDMA_Channel_TypeDef *) BDMA_Channel6_BASE) -#define BDMA_Channel7 ((BDMA_Channel_TypeDef *) BDMA_Channel7_BASE) - -#define RAMECC1 ((RAMECC_TypeDef *)RAMECC1_BASE) -#define RAMECC1_Monitor1 ((RAMECC_MonitorTypeDef *)RAMECC1_Monitor1_BASE) -#define RAMECC1_Monitor2 ((RAMECC_MonitorTypeDef *)RAMECC1_Monitor2_BASE) -#define RAMECC1_Monitor3 ((RAMECC_MonitorTypeDef *)RAMECC1_Monitor3_BASE) -#define RAMECC1_Monitor4 ((RAMECC_MonitorTypeDef *)RAMECC1_Monitor4_BASE) -#define RAMECC1_Monitor5 ((RAMECC_MonitorTypeDef *)RAMECC1_Monitor5_BASE) -#define RAMECC1_Monitor6 ((RAMECC_MonitorTypeDef *)RAMECC1_Monitor6_BASE) - -#define RAMECC2 ((RAMECC_TypeDef *)RAMECC2_BASE) -#define RAMECC2_Monitor1 ((RAMECC_MonitorTypeDef *)RAMECC2_Monitor1_BASE) -#define RAMECC2_Monitor2 ((RAMECC_MonitorTypeDef *)RAMECC2_Monitor2_BASE) -#define RAMECC2_Monitor3 ((RAMECC_MonitorTypeDef *)RAMECC2_Monitor3_BASE) - -#define RAMECC3 ((RAMECC_TypeDef *)RAMECC3_BASE) -#define RAMECC3_Monitor1 ((RAMECC_MonitorTypeDef *)RAMECC3_Monitor1_BASE) -#define RAMECC3_Monitor2 ((RAMECC_MonitorTypeDef *)RAMECC3_Monitor2_BASE) - -#define DMAMUX2 ((DMAMUX_Channel_TypeDef *) DMAMUX2_BASE) -#define DMAMUX2_Channel0 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel0_BASE) -#define DMAMUX2_Channel1 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel1_BASE) -#define DMAMUX2_Channel2 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel2_BASE) -#define DMAMUX2_Channel3 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel3_BASE) -#define DMAMUX2_Channel4 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel4_BASE) -#define DMAMUX2_Channel5 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel5_BASE) -#define DMAMUX2_Channel6 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel6_BASE) -#define DMAMUX2_Channel7 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel7_BASE) - - -#define DMAMUX2_RequestGenerator0 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator0_BASE) -#define DMAMUX2_RequestGenerator1 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator1_BASE) -#define DMAMUX2_RequestGenerator2 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator2_BASE) -#define DMAMUX2_RequestGenerator3 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator3_BASE) -#define DMAMUX2_RequestGenerator4 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator4_BASE) -#define DMAMUX2_RequestGenerator5 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator5_BASE) -#define DMAMUX2_RequestGenerator6 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator6_BASE) -#define DMAMUX2_RequestGenerator7 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator7_BASE) - -#define DMAMUX2_ChannelStatus ((DMAMUX_ChannelStatus_TypeDef *) DMAMUX2_ChannelStatus_BASE) -#define DMAMUX2_RequestGenStatus ((DMAMUX_RequestGenStatus_TypeDef *) DMAMUX2_RequestGenStatus_BASE) - -#define DMA2 ((DMA_TypeDef *) DMA2_BASE) -#define DMA2_Stream0 ((DMA_Stream_TypeDef *) DMA2_Stream0_BASE) -#define DMA2_Stream1 ((DMA_Stream_TypeDef *) DMA2_Stream1_BASE) -#define DMA2_Stream2 ((DMA_Stream_TypeDef *) DMA2_Stream2_BASE) -#define DMA2_Stream3 ((DMA_Stream_TypeDef *) DMA2_Stream3_BASE) -#define DMA2_Stream4 ((DMA_Stream_TypeDef *) DMA2_Stream4_BASE) -#define DMA2_Stream5 ((DMA_Stream_TypeDef *) DMA2_Stream5_BASE) -#define DMA2_Stream6 ((DMA_Stream_TypeDef *) DMA2_Stream6_BASE) -#define DMA2_Stream7 ((DMA_Stream_TypeDef *) DMA2_Stream7_BASE) - -#define DMA1 ((DMA_TypeDef *) DMA1_BASE) -#define DMA1_Stream0 ((DMA_Stream_TypeDef *) DMA1_Stream0_BASE) -#define DMA1_Stream1 ((DMA_Stream_TypeDef *) DMA1_Stream1_BASE) -#define DMA1_Stream2 ((DMA_Stream_TypeDef *) DMA1_Stream2_BASE) -#define DMA1_Stream3 ((DMA_Stream_TypeDef *) DMA1_Stream3_BASE) -#define DMA1_Stream4 ((DMA_Stream_TypeDef *) DMA1_Stream4_BASE) -#define DMA1_Stream5 ((DMA_Stream_TypeDef *) DMA1_Stream5_BASE) -#define DMA1_Stream6 ((DMA_Stream_TypeDef *) DMA1_Stream6_BASE) -#define DMA1_Stream7 ((DMA_Stream_TypeDef *) DMA1_Stream7_BASE) - - -#define DMAMUX1 ((DMAMUX_Channel_TypeDef *) DMAMUX1_BASE) -#define DMAMUX1_Channel0 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel0_BASE) -#define DMAMUX1_Channel1 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel1_BASE) -#define DMAMUX1_Channel2 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel2_BASE) -#define DMAMUX1_Channel3 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel3_BASE) -#define DMAMUX1_Channel4 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel4_BASE) -#define DMAMUX1_Channel5 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel5_BASE) -#define DMAMUX1_Channel6 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel6_BASE) -#define DMAMUX1_Channel7 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel7_BASE) -#define DMAMUX1_Channel8 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel8_BASE) -#define DMAMUX1_Channel9 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel9_BASE) -#define DMAMUX1_Channel10 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel10_BASE) -#define DMAMUX1_Channel11 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel11_BASE) -#define DMAMUX1_Channel12 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel12_BASE) -#define DMAMUX1_Channel13 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel13_BASE) -#define DMAMUX1_Channel14 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel14_BASE) -#define DMAMUX1_Channel15 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel15_BASE) - -#define DMAMUX1_RequestGenerator0 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator0_BASE) -#define DMAMUX1_RequestGenerator1 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator1_BASE) -#define DMAMUX1_RequestGenerator2 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator2_BASE) -#define DMAMUX1_RequestGenerator3 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator3_BASE) -#define DMAMUX1_RequestGenerator4 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator4_BASE) -#define DMAMUX1_RequestGenerator5 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator5_BASE) -#define DMAMUX1_RequestGenerator6 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator6_BASE) -#define DMAMUX1_RequestGenerator7 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator7_BASE) - -#define DMAMUX1_ChannelStatus ((DMAMUX_ChannelStatus_TypeDef *) DMAMUX1_ChannelStatus_BASE) -#define DMAMUX1_RequestGenStatus ((DMAMUX_RequestGenStatus_TypeDef *) DMAMUX1_RequestGenStatus_BASE) - - -#define FMC_Bank1_R ((FMC_Bank1_TypeDef *) FMC_Bank1_R_BASE) -#define FMC_Bank1E_R ((FMC_Bank1E_TypeDef *) FMC_Bank1E_R_BASE) -#define FMC_Bank2_R ((FMC_Bank2_TypeDef *) FMC_Bank2_R_BASE) -#define FMC_Bank3_R ((FMC_Bank3_TypeDef *) FMC_Bank3_R_BASE) -#define FMC_Bank5_6_R ((FMC_Bank5_6_TypeDef *) FMC_Bank5_6_R_BASE) - -#define OCTOSPI1 ((OCTOSPI_TypeDef *) OCTOSPI1_R_BASE) -#define DLYB_OCTOSPI1 ((DLYB_TypeDef *) DLYB_OCTOSPI1_BASE) -#define OCTOSPI2 ((OCTOSPI_TypeDef *) OCTOSPI2_R_BASE) -#define DLYB_OCTOSPI2 ((DLYB_TypeDef *) DLYB_OCTOSPI2_BASE) -#define OCTOSPIM ((OCTOSPIM_TypeDef *) OCTOSPIM_BASE) - -#define OTFDEC1 ((OTFDEC_TypeDef *) OTFDEC1_BASE) -#define OTFDEC1_REGION1 ((OTFDEC_Region_TypeDef *) OTFDEC1_REGION1_BASE) -#define OTFDEC1_REGION2 ((OTFDEC_Region_TypeDef *) OTFDEC1_REGION2_BASE) -#define OTFDEC1_REGION3 ((OTFDEC_Region_TypeDef *) OTFDEC1_REGION3_BASE) -#define OTFDEC1_REGION4 ((OTFDEC_Region_TypeDef *) OTFDEC1_REGION4_BASE) - -#define OTFDEC2 ((OTFDEC_TypeDef *) OTFDEC2_BASE) -#define OTFDEC2_REGION1 ((OTFDEC_Region_TypeDef *) OTFDEC2_REGION1_BASE) -#define OTFDEC2_REGION2 ((OTFDEC_Region_TypeDef *) OTFDEC2_REGION2_BASE) -#define OTFDEC2_REGION3 ((OTFDEC_Region_TypeDef *) OTFDEC2_REGION3_BASE) -#define OTFDEC2_REGION4 ((OTFDEC_Region_TypeDef *) OTFDEC2_REGION4_BASE) - -#define SDMMC1 ((SDMMC_TypeDef *) SDMMC1_BASE) -#define DLYB_SDMMC1 ((DLYB_TypeDef *) DLYB_SDMMC1_BASE) - -#define DBGMCU ((DBGMCU_TypeDef *) DBGMCU_BASE) - -#define HSEM ((HSEM_TypeDef *) HSEM_BASE) -#define HSEM_COMMON ((HSEM_Common_TypeDef *) (HSEM_BASE + 0x100UL)) - -#define LTDC ((LTDC_TypeDef *)LTDC_BASE) -#define LTDC_Layer1 ((LTDC_Layer_TypeDef *)LTDC_Layer1_BASE) -#define LTDC_Layer2 ((LTDC_Layer_TypeDef *)LTDC_Layer2_BASE) - -#define MDIOS ((MDIOS_TypeDef *) MDIOS_BASE) - -#define ETH ((ETH_TypeDef *)ETH_BASE) -#define MDMA ((MDMA_TypeDef *)MDMA_BASE) -#define MDMA_Channel0 ((MDMA_Channel_TypeDef *)MDMA_Channel0_BASE) -#define MDMA_Channel1 ((MDMA_Channel_TypeDef *)MDMA_Channel1_BASE) -#define MDMA_Channel2 ((MDMA_Channel_TypeDef *)MDMA_Channel2_BASE) -#define MDMA_Channel3 ((MDMA_Channel_TypeDef *)MDMA_Channel3_BASE) -#define MDMA_Channel4 ((MDMA_Channel_TypeDef *)MDMA_Channel4_BASE) -#define MDMA_Channel5 ((MDMA_Channel_TypeDef *)MDMA_Channel5_BASE) -#define MDMA_Channel6 ((MDMA_Channel_TypeDef *)MDMA_Channel6_BASE) -#define MDMA_Channel7 ((MDMA_Channel_TypeDef *)MDMA_Channel7_BASE) -#define MDMA_Channel8 ((MDMA_Channel_TypeDef *)MDMA_Channel8_BASE) -#define MDMA_Channel9 ((MDMA_Channel_TypeDef *)MDMA_Channel9_BASE) -#define MDMA_Channel10 ((MDMA_Channel_TypeDef *)MDMA_Channel10_BASE) -#define MDMA_Channel11 ((MDMA_Channel_TypeDef *)MDMA_Channel11_BASE) -#define MDMA_Channel12 ((MDMA_Channel_TypeDef *)MDMA_Channel12_BASE) -#define MDMA_Channel13 ((MDMA_Channel_TypeDef *)MDMA_Channel13_BASE) -#define MDMA_Channel14 ((MDMA_Channel_TypeDef *)MDMA_Channel14_BASE) -#define MDMA_Channel15 ((MDMA_Channel_TypeDef *)MDMA_Channel15_BASE) - - -#define USB1_OTG_HS ((USB_OTG_GlobalTypeDef *) USB1_OTG_HS_PERIPH_BASE) - -/* Legacy defines */ -#define USB_OTG_HS USB1_OTG_HS -#define USB_OTG_HS_PERIPH_BASE USB1_OTG_HS_PERIPH_BASE - -#define GPV ((GPV_TypeDef *) GPV_BASE) - -/** - * @} - */ - -/** @addtogroup Exported_constants - * @{ - */ - - /** @addtogroup Peripheral_Registers_Bits_Definition - * @{ - */ - -/******************************************************************************/ -/* Peripheral Registers_Bits_Definition */ -/******************************************************************************/ - -/******************************************************************************/ -/* */ -/* Analog to Digital Converter */ -/* */ -/******************************************************************************/ -/******************************* ADC VERSION ********************************/ -#define ADC_VER_V5_V90 -/******************** Bit definition for ADC_ISR register ********************/ -#define ADC_ISR_ADRDY_Pos (0U) -#define ADC_ISR_ADRDY_Msk (0x1UL << ADC_ISR_ADRDY_Pos) /*!< 0x00000001 */ -#define ADC_ISR_ADRDY ADC_ISR_ADRDY_Msk /*!< ADC Ready (ADRDY) flag */ -#define ADC_ISR_EOSMP_Pos (1U) -#define ADC_ISR_EOSMP_Msk (0x1UL << ADC_ISR_EOSMP_Pos) /*!< 0x00000002 */ -#define ADC_ISR_EOSMP ADC_ISR_EOSMP_Msk /*!< ADC End of Sampling flag */ -#define ADC_ISR_EOC_Pos (2U) -#define ADC_ISR_EOC_Msk (0x1UL << ADC_ISR_EOC_Pos) /*!< 0x00000004 */ -#define ADC_ISR_EOC ADC_ISR_EOC_Msk /*!< ADC End of Regular Conversion flag */ -#define ADC_ISR_EOS_Pos (3U) -#define ADC_ISR_EOS_Msk (0x1UL << ADC_ISR_EOS_Pos) /*!< 0x00000008 */ -#define ADC_ISR_EOS ADC_ISR_EOS_Msk /*!< ADC End of Regular sequence of Conversions flag */ -#define ADC_ISR_OVR_Pos (4U) -#define ADC_ISR_OVR_Msk (0x1UL << ADC_ISR_OVR_Pos) /*!< 0x00000010 */ -#define ADC_ISR_OVR ADC_ISR_OVR_Msk /*!< ADC overrun flag */ -#define ADC_ISR_JEOC_Pos (5U) -#define ADC_ISR_JEOC_Msk (0x1UL << ADC_ISR_JEOC_Pos) /*!< 0x00000020 */ -#define ADC_ISR_JEOC ADC_ISR_JEOC_Msk /*!< ADC End of Injected Conversion flag */ -#define ADC_ISR_JEOS_Pos (6U) -#define ADC_ISR_JEOS_Msk (0x1UL << ADC_ISR_JEOS_Pos) /*!< 0x00000040 */ -#define ADC_ISR_JEOS ADC_ISR_JEOS_Msk /*!< ADC End of Injected sequence of Conversions flag */ -#define ADC_ISR_AWD1_Pos (7U) -#define ADC_ISR_AWD1_Msk (0x1UL << ADC_ISR_AWD1_Pos) /*!< 0x00000080 */ -#define ADC_ISR_AWD1 ADC_ISR_AWD1_Msk /*!< ADC Analog watchdog 1 flag */ -#define ADC_ISR_AWD2_Pos (8U) -#define ADC_ISR_AWD2_Msk (0x1UL << ADC_ISR_AWD2_Pos) /*!< 0x00000100 */ -#define ADC_ISR_AWD2 ADC_ISR_AWD2_Msk /*!< ADC Analog watchdog 2 flag */ -#define ADC_ISR_AWD3_Pos (9U) -#define ADC_ISR_AWD3_Msk (0x1UL << ADC_ISR_AWD3_Pos) /*!< 0x00000200 */ -#define ADC_ISR_AWD3 ADC_ISR_AWD3_Msk /*!< ADC Analog watchdog 3 flag */ -#define ADC_ISR_JQOVF_Pos (10U) -#define ADC_ISR_JQOVF_Msk (0x1UL << ADC_ISR_JQOVF_Pos) /*!< 0x00000400 */ -#define ADC_ISR_JQOVF ADC_ISR_JQOVF_Msk /*!< ADC Injected Context Queue Overflow flag */ -#define ADC_ISR_LDORDY_Pos (12U) -#define ADC_ISR_LDORDY_Msk (0x1UL << ADC_ISR_LDORDY_Pos) /*!< 0x00001000 */ -#define ADC_ISR_LDORDY ADC_ISR_LDORDY_Msk /*!< ADC LDO Ready (LDORDY) flag */ - -/******************** Bit definition for ADC_IER register ********************/ -#define ADC_IER_ADRDYIE_Pos (0U) -#define ADC_IER_ADRDYIE_Msk (0x1UL << ADC_IER_ADRDYIE_Pos) /*!< 0x00000001 */ -#define ADC_IER_ADRDYIE ADC_IER_ADRDYIE_Msk /*!< ADC Ready (ADRDY) interrupt source */ -#define ADC_IER_EOSMPIE_Pos (1U) -#define ADC_IER_EOSMPIE_Msk (0x1UL << ADC_IER_EOSMPIE_Pos) /*!< 0x00000002 */ -#define ADC_IER_EOSMPIE ADC_IER_EOSMPIE_Msk /*!< ADC End of Sampling interrupt source */ -#define ADC_IER_EOCIE_Pos (2U) -#define ADC_IER_EOCIE_Msk (0x1UL << ADC_IER_EOCIE_Pos) /*!< 0x00000004 */ -#define ADC_IER_EOCIE ADC_IER_EOCIE_Msk /*!< ADC End of Regular Conversion interrupt source */ -#define ADC_IER_EOSIE_Pos (3U) -#define ADC_IER_EOSIE_Msk (0x1UL << ADC_IER_EOSIE_Pos) /*!< 0x00000008 */ -#define ADC_IER_EOSIE ADC_IER_EOSIE_Msk /*!< ADC End of Regular sequence of Conversions interrupt source */ -#define ADC_IER_OVRIE_Pos (4U) -#define ADC_IER_OVRIE_Msk (0x1UL << ADC_IER_OVRIE_Pos) /*!< 0x00000010 */ -#define ADC_IER_OVRIE ADC_IER_OVRIE_Msk /*!< ADC overrun interrupt source */ -#define ADC_IER_JEOCIE_Pos (5U) -#define ADC_IER_JEOCIE_Msk (0x1UL << ADC_IER_JEOCIE_Pos) /*!< 0x00000020 */ -#define ADC_IER_JEOCIE ADC_IER_JEOCIE_Msk /*!< ADC End of Injected Conversion interrupt source */ -#define ADC_IER_JEOSIE_Pos (6U) -#define ADC_IER_JEOSIE_Msk (0x1UL << ADC_IER_JEOSIE_Pos) /*!< 0x00000040 */ -#define ADC_IER_JEOSIE ADC_IER_JEOSIE_Msk /*!< ADC End of Injected sequence of Conversions interrupt source */ -#define ADC_IER_AWD1IE_Pos (7U) -#define ADC_IER_AWD1IE_Msk (0x1UL << ADC_IER_AWD1IE_Pos) /*!< 0x00000080 */ -#define ADC_IER_AWD1IE ADC_IER_AWD1IE_Msk /*!< ADC Analog watchdog 1 interrupt source */ -#define ADC_IER_AWD2IE_Pos (8U) -#define ADC_IER_AWD2IE_Msk (0x1UL << ADC_IER_AWD2IE_Pos) /*!< 0x00000100 */ -#define ADC_IER_AWD2IE ADC_IER_AWD2IE_Msk /*!< ADC Analog watchdog 2 interrupt source */ -#define ADC_IER_AWD3IE_Pos (9U) -#define ADC_IER_AWD3IE_Msk (0x1UL << ADC_IER_AWD3IE_Pos) /*!< 0x00000200 */ -#define ADC_IER_AWD3IE ADC_IER_AWD3IE_Msk /*!< ADC Analog watchdog 3 interrupt source */ -#define ADC_IER_JQOVFIE_Pos (10U) -#define ADC_IER_JQOVFIE_Msk (0x1UL << ADC_IER_JQOVFIE_Pos) /*!< 0x00000400 */ -#define ADC_IER_JQOVFIE ADC_IER_JQOVFIE_Msk /*!< ADC Injected Context Queue Overflow interrupt source */ - -/******************** Bit definition for ADC_CR register ********************/ -#define ADC_CR_ADEN_Pos (0U) -#define ADC_CR_ADEN_Msk (0x1UL << ADC_CR_ADEN_Pos) /*!< 0x00000001 */ -#define ADC_CR_ADEN ADC_CR_ADEN_Msk /*!< ADC Enable control */ -#define ADC_CR_ADDIS_Pos (1U) -#define ADC_CR_ADDIS_Msk (0x1UL << ADC_CR_ADDIS_Pos) /*!< 0x00000002 */ -#define ADC_CR_ADDIS ADC_CR_ADDIS_Msk /*!< ADC Disable command */ -#define ADC_CR_ADSTART_Pos (2U) -#define ADC_CR_ADSTART_Msk (0x1UL << ADC_CR_ADSTART_Pos) /*!< 0x00000004 */ -#define ADC_CR_ADSTART ADC_CR_ADSTART_Msk /*!< ADC Start of Regular conversion */ -#define ADC_CR_JADSTART_Pos (3U) -#define ADC_CR_JADSTART_Msk (0x1UL << ADC_CR_JADSTART_Pos) /*!< 0x00000008 */ -#define ADC_CR_JADSTART ADC_CR_JADSTART_Msk /*!< ADC Start of injected conversion */ -#define ADC_CR_ADSTP_Pos (4U) -#define ADC_CR_ADSTP_Msk (0x1UL << ADC_CR_ADSTP_Pos) /*!< 0x00000010 */ -#define ADC_CR_ADSTP ADC_CR_ADSTP_Msk /*!< ADC Stop of Regular conversion */ -#define ADC_CR_JADSTP_Pos (5U) -#define ADC_CR_JADSTP_Msk (0x1UL << ADC_CR_JADSTP_Pos) /*!< 0x00000020 */ -#define ADC_CR_JADSTP ADC_CR_JADSTP_Msk /*!< ADC Stop of injected conversion */ -#define ADC_CR_BOOST_Pos (8U) -#define ADC_CR_BOOST_Msk (0x3UL << ADC_CR_BOOST_Pos) /*!< 0x00000300 */ -#define ADC_CR_BOOST ADC_CR_BOOST_Msk /*!< ADC Boost Mode configuration */ -#define ADC_CR_BOOST_0 (0x1UL << ADC_CR_BOOST_Pos) /*!< 0x00000100 */ -#define ADC_CR_BOOST_1 (0x2UL << ADC_CR_BOOST_Pos) /*!< 0x00000200 */ -#define ADC_CR_ADCALLIN_Pos (16U) -#define ADC_CR_ADCALLIN_Msk (0x1UL << ADC_CR_ADCALLIN_Pos) /*!< 0x00010000 */ -#define ADC_CR_ADCALLIN ADC_CR_ADCALLIN_Msk /*!< ADC Linearity calibration */ -#define ADC_CR_LINCALRDYW1_Pos (22U) -#define ADC_CR_LINCALRDYW1_Msk (0x1UL << ADC_CR_LINCALRDYW1_Pos) /*!< 0x00400000 */ -#define ADC_CR_LINCALRDYW1 ADC_CR_LINCALRDYW1_Msk /*!< ADC Linearity calibration ready Word 1 */ -#define ADC_CR_LINCALRDYW2_Pos (23U) -#define ADC_CR_LINCALRDYW2_Msk (0x1UL << ADC_CR_LINCALRDYW2_Pos) /*!< 0x00800000 */ -#define ADC_CR_LINCALRDYW2 ADC_CR_LINCALRDYW2_Msk /*!< ADC Linearity calibration ready Word 2 */ -#define ADC_CR_LINCALRDYW3_Pos (24U) -#define ADC_CR_LINCALRDYW3_Msk (0x1UL << ADC_CR_LINCALRDYW3_Pos) /*!< 0x01000000 */ -#define ADC_CR_LINCALRDYW3 ADC_CR_LINCALRDYW3_Msk /*!< ADC Linearity calibration ready Word 3 */ -#define ADC_CR_LINCALRDYW4_Pos (25U) -#define ADC_CR_LINCALRDYW4_Msk (0x1UL << ADC_CR_LINCALRDYW4_Pos) /*!< 0x02000000 */ -#define ADC_CR_LINCALRDYW4 ADC_CR_LINCALRDYW4_Msk /*!< ADC Linearity calibration ready Word 4 */ -#define ADC_CR_LINCALRDYW5_Pos (26U) -#define ADC_CR_LINCALRDYW5_Msk (0x1UL << ADC_CR_LINCALRDYW5_Pos) /*!< 0x04000000 */ -#define ADC_CR_LINCALRDYW5 ADC_CR_LINCALRDYW5_Msk /*!< ADC Linearity calibration ready Word 5 */ -#define ADC_CR_LINCALRDYW6_Pos (27U) -#define ADC_CR_LINCALRDYW6_Msk (0x1UL << ADC_CR_LINCALRDYW6_Pos) /*!< 0x08000000 */ -#define ADC_CR_LINCALRDYW6 ADC_CR_LINCALRDYW6_Msk /*!< ADC Linearity calibration ready Word 6 */ -#define ADC_CR_ADVREGEN_Pos (28U) -#define ADC_CR_ADVREGEN_Msk (0x1UL << ADC_CR_ADVREGEN_Pos) /*!< 0x10000000 */ -#define ADC_CR_ADVREGEN ADC_CR_ADVREGEN_Msk /*!< ADC Voltage regulator Enable */ -#define ADC_CR_DEEPPWD_Pos (29U) -#define ADC_CR_DEEPPWD_Msk (0x1UL << ADC_CR_DEEPPWD_Pos) /*!< 0x20000000 */ -#define ADC_CR_DEEPPWD ADC_CR_DEEPPWD_Msk /*!< ADC Deep power down Enable */ -#define ADC_CR_ADCALDIF_Pos (30U) -#define ADC_CR_ADCALDIF_Msk (0x1UL << ADC_CR_ADCALDIF_Pos) /*!< 0x40000000 */ -#define ADC_CR_ADCALDIF ADC_CR_ADCALDIF_Msk /*!< ADC Differential Mode for calibration */ -#define ADC_CR_ADCAL_Pos (31U) -#define ADC_CR_ADCAL_Msk (0x1UL << ADC_CR_ADCAL_Pos) /*!< 0x80000000 */ -#define ADC_CR_ADCAL ADC_CR_ADCAL_Msk /*!< ADC Calibration */ - -/******************** Bit definition for ADC_CFGR register ********************/ -#define ADC_CFGR_DMNGT_Pos (0U) -#define ADC_CFGR_DMNGT_Msk (0x3UL << ADC_CFGR_DMNGT_Pos) /*!< 0x00000003 */ -#define ADC_CFGR_DMNGT ADC_CFGR_DMNGT_Msk /*!< ADC Data Management configuration */ -#define ADC_CFGR_DMNGT_0 (0x1UL << ADC_CFGR_DMNGT_Pos) /*!< 0x00000001 */ -#define ADC_CFGR_DMNGT_1 (0x2UL << ADC_CFGR_DMNGT_Pos) /*!< 0x00000002 */ - -#define ADC_CFGR_RES_Pos (2U) -#define ADC_CFGR_RES_Msk (0x7UL << ADC_CFGR_RES_Pos) /*!< 0x0000001C */ -#define ADC_CFGR_RES ADC_CFGR_RES_Msk /*!< ADC Data resolution */ -#define ADC_CFGR_RES_0 (0x1UL << ADC_CFGR_RES_Pos) /*!< 0x00000004 */ -#define ADC_CFGR_RES_1 (0x2UL << ADC_CFGR_RES_Pos) /*!< 0x00000008 */ -#define ADC_CFGR_RES_2 (0x4UL << ADC_CFGR_RES_Pos) /*!< 0x00000010 */ - -#define ADC_CFGR_EXTSEL_Pos (5U) -#define ADC_CFGR_EXTSEL_Msk (0x1FUL << ADC_CFGR_EXTSEL_Pos) /*!< 0x000003E0 */ -#define ADC_CFGR_EXTSEL ADC_CFGR_EXTSEL_Msk /*!< ADC External trigger selection for regular group */ -#define ADC_CFGR_EXTSEL_0 (0x01UL << ADC_CFGR_EXTSEL_Pos) /*!< 0x00000020 */ -#define ADC_CFGR_EXTSEL_1 (0x02UL << ADC_CFGR_EXTSEL_Pos) /*!< 0x00000040 */ -#define ADC_CFGR_EXTSEL_2 (0x04UL << ADC_CFGR_EXTSEL_Pos) /*!< 0x00000080 */ -#define ADC_CFGR_EXTSEL_3 (0x08UL << ADC_CFGR_EXTSEL_Pos) /*!< 0x00000100 */ -#define ADC_CFGR_EXTSEL_4 (0x10UL << ADC_CFGR_EXTSEL_Pos) /*!< 0x00000200 */ - -#define ADC_CFGR_EXTEN_Pos (10U) -#define ADC_CFGR_EXTEN_Msk (0x3UL << ADC_CFGR_EXTEN_Pos) /*!< 0x00000C00 */ -#define ADC_CFGR_EXTEN ADC_CFGR_EXTEN_Msk /*!< ADC External trigger enable and polarity selection for regular channels */ -#define ADC_CFGR_EXTEN_0 (0x1UL << ADC_CFGR_EXTEN_Pos) /*!< 0x00000400 */ -#define ADC_CFGR_EXTEN_1 (0x2UL << ADC_CFGR_EXTEN_Pos) /*!< 0x00000800 */ - -#define ADC_CFGR_OVRMOD_Pos (12U) -#define ADC_CFGR_OVRMOD_Msk (0x1UL << ADC_CFGR_OVRMOD_Pos) /*!< 0x00001000 */ -#define ADC_CFGR_OVRMOD ADC_CFGR_OVRMOD_Msk /*!< ADC overrun mode */ -#define ADC_CFGR_CONT_Pos (13U) -#define ADC_CFGR_CONT_Msk (0x1UL << ADC_CFGR_CONT_Pos) /*!< 0x00002000 */ -#define ADC_CFGR_CONT ADC_CFGR_CONT_Msk /*!< ADC Single/continuous conversion mode for regular conversion */ -#define ADC_CFGR_AUTDLY_Pos (14U) -#define ADC_CFGR_AUTDLY_Msk (0x1UL << ADC_CFGR_AUTDLY_Pos) /*!< 0x00004000 */ -#define ADC_CFGR_AUTDLY ADC_CFGR_AUTDLY_Msk /*!< ADC Delayed conversion mode */ - -#define ADC_CFGR_DISCEN_Pos (16U) -#define ADC_CFGR_DISCEN_Msk (0x1UL << ADC_CFGR_DISCEN_Pos) /*!< 0x00010000 */ -#define ADC_CFGR_DISCEN ADC_CFGR_DISCEN_Msk /*!< ADC Discontinuous mode for regular channels */ - -#define ADC_CFGR_DISCNUM_Pos (17U) -#define ADC_CFGR_DISCNUM_Msk (0x7UL << ADC_CFGR_DISCNUM_Pos) /*!< 0x000E0000 */ -#define ADC_CFGR_DISCNUM ADC_CFGR_DISCNUM_Msk /*!< ADC Discontinuous mode channel count */ -#define ADC_CFGR_DISCNUM_0 (0x1UL << ADC_CFGR_DISCNUM_Pos) /*!< 0x00020000 */ -#define ADC_CFGR_DISCNUM_1 (0x2UL << ADC_CFGR_DISCNUM_Pos) /*!< 0x00040000 */ -#define ADC_CFGR_DISCNUM_2 (0x4UL << ADC_CFGR_DISCNUM_Pos) /*!< 0x00080000 */ - -#define ADC_CFGR_JDISCEN_Pos (20U) -#define ADC_CFGR_JDISCEN_Msk (0x1UL << ADC_CFGR_JDISCEN_Pos) /*!< 0x00100000 */ -#define ADC_CFGR_JDISCEN ADC_CFGR_JDISCEN_Msk /*!< ADC Discontinuous mode on injected channels */ -#define ADC_CFGR_JQM_Pos (21U) -#define ADC_CFGR_JQM_Msk (0x1UL << ADC_CFGR_JQM_Pos) /*!< 0x00200000 */ -#define ADC_CFGR_JQM ADC_CFGR_JQM_Msk /*!< ADC JSQR Queue mode */ -#define ADC_CFGR_AWD1SGL_Pos (22U) -#define ADC_CFGR_AWD1SGL_Msk (0x1UL << ADC_CFGR_AWD1SGL_Pos) /*!< 0x00400000 */ -#define ADC_CFGR_AWD1SGL ADC_CFGR_AWD1SGL_Msk /*!< Enable the watchdog 1 on a single channel or on all channels */ -#define ADC_CFGR_AWD1EN_Pos (23U) -#define ADC_CFGR_AWD1EN_Msk (0x1UL << ADC_CFGR_AWD1EN_Pos) /*!< 0x00800000 */ -#define ADC_CFGR_AWD1EN ADC_CFGR_AWD1EN_Msk /*!< ADC Analog watchdog 1 enable on regular Channels */ -#define ADC_CFGR_JAWD1EN_Pos (24U) -#define ADC_CFGR_JAWD1EN_Msk (0x1UL << ADC_CFGR_JAWD1EN_Pos) /*!< 0x01000000 */ -#define ADC_CFGR_JAWD1EN ADC_CFGR_JAWD1EN_Msk /*!< ADC Analog watchdog 1 enable on injected Channels */ -#define ADC_CFGR_JAUTO_Pos (25U) -#define ADC_CFGR_JAUTO_Msk (0x1UL << ADC_CFGR_JAUTO_Pos) /*!< 0x02000000 */ -#define ADC_CFGR_JAUTO ADC_CFGR_JAUTO_Msk /*!< ADC Automatic injected group conversion */ - -#define ADC_CFGR_AWD1CH_Pos (26U) -#define ADC_CFGR_AWD1CH_Msk (0x1FUL << ADC_CFGR_AWD1CH_Pos) /*!< 0x7C000000 */ -#define ADC_CFGR_AWD1CH ADC_CFGR_AWD1CH_Msk /*!< ADC Analog watchdog 1 Channel selection */ -#define ADC_CFGR_AWD1CH_0 (0x01UL << ADC_CFGR_AWD1CH_Pos) /*!< 0x04000000 */ -#define ADC_CFGR_AWD1CH_1 (0x02UL << ADC_CFGR_AWD1CH_Pos) /*!< 0x08000000 */ -#define ADC_CFGR_AWD1CH_2 (0x04UL << ADC_CFGR_AWD1CH_Pos) /*!< 0x10000000 */ -#define ADC_CFGR_AWD1CH_3 (0x08UL << ADC_CFGR_AWD1CH_Pos) /*!< 0x20000000 */ -#define ADC_CFGR_AWD1CH_4 (0x10UL << ADC_CFGR_AWD1CH_Pos) /*!< 0x40000000 */ - -#define ADC_CFGR_JQDIS_Pos (31U) -#define ADC_CFGR_JQDIS_Msk (0x1UL << ADC_CFGR_JQDIS_Pos) /*!< 0x80000000 */ -#define ADC_CFGR_JQDIS ADC_CFGR_JQDIS_Msk /*!< ADC Injected queue disable */ - -#define ADC3_CFGR_DMAEN_Pos (0U) -#define ADC3_CFGR_DMAEN_Msk (0x1UL << ADC3_CFGR_DMAEN_Pos) /*!< 0x00000001 */ -#define ADC3_CFGR_DMAEN ADC3_CFGR_DMAEN_Msk /*!< ADC DMA transfer enable */ -#define ADC3_CFGR_DMACFG_Pos (1U) -#define ADC3_CFGR_DMACFG_Msk (0x1UL << ADC3_CFGR_DMACFG_Pos) /*!< 0x00000002 */ -#define ADC3_CFGR_DMACFG ADC3_CFGR_DMACFG_Msk /*!< ADC DMA transfer configuration */ - -#define ADC3_CFGR_RES_Pos (3U) -#define ADC3_CFGR_RES_Msk (0x3UL << ADC3_CFGR_RES_Pos) /*!< 0x00000018 */ -#define ADC3_CFGR_RES ADC3_CFGR_RES_Msk /*!< ADC data resolution */ -#define ADC3_CFGR_RES_0 (0x1UL << ADC3_CFGR_RES_Pos) /*!< 0x00000008 */ -#define ADC3_CFGR_RES_1 (0x2UL << ADC3_CFGR_RES_Pos) /*!< 0x00000010 */ - -#define ADC3_CFGR_ALIGN_Pos (15U) -#define ADC3_CFGR_ALIGN_Msk (0x1UL << ADC3_CFGR_ALIGN_Pos) /*!< 0x00008000 */ -#define ADC3_CFGR_ALIGN ADC3_CFGR_ALIGN_Msk /*!< ADC data alignment */ -/******************** Bit definition for ADC_CFGR2 register ********************/ -#define ADC_CFGR2_ROVSE_Pos (0U) -#define ADC_CFGR2_ROVSE_Msk (0x1UL << ADC_CFGR2_ROVSE_Pos) /*!< 0x00000001 */ -#define ADC_CFGR2_ROVSE ADC_CFGR2_ROVSE_Msk /*!< ADC Regular group oversampler enable */ -#define ADC_CFGR2_JOVSE_Pos (1U) -#define ADC_CFGR2_JOVSE_Msk (0x1UL << ADC_CFGR2_JOVSE_Pos) /*!< 0x00000002 */ -#define ADC_CFGR2_JOVSE ADC_CFGR2_JOVSE_Msk /*!< ADC Injected group oversampler enable */ - -#define ADC_CFGR2_OVSS_Pos (5U) -#define ADC_CFGR2_OVSS_Msk (0xFUL << ADC_CFGR2_OVSS_Pos) /*!< 0x000001E0 */ -#define ADC_CFGR2_OVSS ADC_CFGR2_OVSS_Msk /*!< ADC Regular Oversampling shift */ -#define ADC_CFGR2_OVSS_0 (0x1UL << ADC_CFGR2_OVSS_Pos) /*!< 0x00000020 */ -#define ADC_CFGR2_OVSS_1 (0x2UL << ADC_CFGR2_OVSS_Pos) /*!< 0x00000040 */ -#define ADC_CFGR2_OVSS_2 (0x4UL << ADC_CFGR2_OVSS_Pos) /*!< 0x00000080 */ -#define ADC_CFGR2_OVSS_3 (0x8UL << ADC_CFGR2_OVSS_Pos) /*!< 0x00000100 */ - -#define ADC_CFGR2_TROVS_Pos (9U) -#define ADC_CFGR2_TROVS_Msk (0x1UL << ADC_CFGR2_TROVS_Pos) /*!< 0x00000200 */ -#define ADC_CFGR2_TROVS ADC_CFGR2_TROVS_Msk /*!< ADC Triggered regular Oversampling */ -#define ADC_CFGR2_ROVSM_Pos (10U) -#define ADC_CFGR2_ROVSM_Msk (0x1UL << ADC_CFGR2_ROVSM_Pos) /*!< 0x00000400 */ -#define ADC_CFGR2_ROVSM ADC_CFGR2_ROVSM_Msk /*!< ADC Regular oversampling mode */ - -#define ADC_CFGR2_RSHIFT1_Pos (11U) -#define ADC_CFGR2_RSHIFT1_Msk (0x1UL << ADC_CFGR2_RSHIFT1_Pos) /*!< 0x00000800 */ -#define ADC_CFGR2_RSHIFT1 ADC_CFGR2_RSHIFT1_Msk /*!< ADC Right-shift data after Offset 1 correction */ -#define ADC_CFGR2_RSHIFT2_Pos (12U) -#define ADC_CFGR2_RSHIFT2_Msk (0x1UL << ADC_CFGR2_RSHIFT2_Pos) /*!< 0x00001000 */ -#define ADC_CFGR2_RSHIFT2 ADC_CFGR2_RSHIFT2_Msk /*!< ADC Right-shift data after Offset 2 correction */ -#define ADC_CFGR2_RSHIFT3_Pos (13U) -#define ADC_CFGR2_RSHIFT3_Msk (0x1UL << ADC_CFGR2_RSHIFT3_Pos) /*!< 0x00002000 */ -#define ADC_CFGR2_RSHIFT3 ADC_CFGR2_RSHIFT3_Msk /*!< ADC Right-shift data after Offset 3 correction */ -#define ADC_CFGR2_RSHIFT4_Pos (14U) -#define ADC_CFGR2_RSHIFT4_Msk (0x1UL << ADC_CFGR2_RSHIFT4_Pos) /*!< 0x00004000 */ -#define ADC_CFGR2_RSHIFT4 ADC_CFGR2_RSHIFT4_Msk /*!< ADC Right-shift data after Offset 4 correction */ - -#define ADC_CFGR2_OVSR_Pos (16U) -#define ADC_CFGR2_OVSR_Msk (0x3FFUL << ADC_CFGR2_OVSR_Pos) /*!< 0x03FF0000 */ -#define ADC_CFGR2_OVSR ADC_CFGR2_OVSR_Msk /*!< ADC oversampling Ratio */ -#define ADC_CFGR2_OVSR_0 (0x001UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00010000 */ -#define ADC_CFGR2_OVSR_1 (0x002UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00020000 */ -#define ADC_CFGR2_OVSR_2 (0x004UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00040000 */ -#define ADC_CFGR2_OVSR_3 (0x008UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00080000 */ -#define ADC_CFGR2_OVSR_4 (0x010UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00100000 */ -#define ADC_CFGR2_OVSR_5 (0x020UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00200000 */ -#define ADC_CFGR2_OVSR_6 (0x040UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00400000 */ -#define ADC_CFGR2_OVSR_7 (0x080UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00800000 */ -#define ADC_CFGR2_OVSR_8 (0x100UL << ADC_CFGR2_OVSR_Pos) /*!< 0x01000000 */ -#define ADC_CFGR2_OVSR_9 (0x200UL << ADC_CFGR2_OVSR_Pos) /*!< 0x02000000 */ - -#define ADC_CFGR2_LSHIFT_Pos (28U) -#define ADC_CFGR2_LSHIFT_Msk (0xFUL << ADC_CFGR2_LSHIFT_Pos) /*!< 0xF0000000 */ -#define ADC_CFGR2_LSHIFT ADC_CFGR2_LSHIFT_Msk /*!< ADC Left shift factor */ -#define ADC_CFGR2_LSHIFT_0 (0x1UL << ADC_CFGR2_LSHIFT_Pos) /*!< 0x10000000 */ -#define ADC_CFGR2_LSHIFT_1 (0x2UL << ADC_CFGR2_LSHIFT_Pos) /*!< 0x20000000 */ -#define ADC_CFGR2_LSHIFT_2 (0x4UL << ADC_CFGR2_LSHIFT_Pos) /*!< 0x40000000 */ -#define ADC_CFGR2_LSHIFT_3 (0x8UL << ADC_CFGR2_LSHIFT_Pos) /*!< 0x80000000 */ - -#define ADC3_CFGR2_OVSR_Pos (2U) -#define ADC3_CFGR2_OVSR_Msk (0x7UL << ADC3_CFGR2_OVSR_Pos) /*!< 0x0000001C */ -#define ADC3_CFGR2_OVSR ADC3_CFGR2_OVSR_Msk /*!< ADC oversampling ratio */ -#define ADC3_CFGR2_OVSR_0 (0x1UL << ADC3_CFGR2_OVSR_Pos) /*!< 0x00000004 */ -#define ADC3_CFGR2_OVSR_1 (0x2UL << ADC3_CFGR2_OVSR_Pos) /*!< 0x00000008 */ -#define ADC3_CFGR2_OVSR_2 (0x4UL << ADC3_CFGR2_OVSR_Pos) /*!< 0x00000010 */ - -#define ADC3_CFGR2_SWTRIG_Pos (25U) -#define ADC3_CFGR2_SWTRIG_Msk (0x1UL << ADC3_CFGR2_SWTRIG_Pos) /*!< 0x02000000 */ -#define ADC3_CFGR2_SWTRIG ADC3_CFGR2_SWTRIG_Msk /*!< ADC Software Trigger Bit for Sample time control trigger mode */ -#define ADC3_CFGR2_BULB_Pos (26U) -#define ADC3_CFGR2_BULB_Msk (0x1UL << ADC3_CFGR2_BULB_Pos) /*!< 0x04000000 */ -#define ADC3_CFGR2_BULB ADC3_CFGR2_BULB_Msk /*!< ADC Bulb sampling mode */ -#define ADC3_CFGR2_SMPTRIG_Pos (27U) -#define ADC3_CFGR2_SMPTRIG_Msk (0x1UL << ADC3_CFGR2_SMPTRIG_Pos) /*!< 0x08000000 */ -#define ADC3_CFGR2_SMPTRIG ADC3_CFGR2_SMPTRIG_Msk /*!< ADC Sample Time Control Trigger mode */ -/******************** Bit definition for ADC_SMPR1 register ********************/ -#define ADC_SMPR1_SMP0_Pos (0U) -#define ADC_SMPR1_SMP0_Msk (0x7UL << ADC_SMPR1_SMP0_Pos) /*!< 0x00000007 */ -#define ADC_SMPR1_SMP0 ADC_SMPR1_SMP0_Msk /*!< ADC Channel 0 Sampling time selection */ -#define ADC_SMPR1_SMP0_0 (0x1UL << ADC_SMPR1_SMP0_Pos) /*!< 0x00000001 */ -#define ADC_SMPR1_SMP0_1 (0x2UL << ADC_SMPR1_SMP0_Pos) /*!< 0x00000002 */ -#define ADC_SMPR1_SMP0_2 (0x4UL << ADC_SMPR1_SMP0_Pos) /*!< 0x00000004 */ - -#define ADC_SMPR1_SMP1_Pos (3U) -#define ADC_SMPR1_SMP1_Msk (0x7UL << ADC_SMPR1_SMP1_Pos) /*!< 0x00000038 */ -#define ADC_SMPR1_SMP1 ADC_SMPR1_SMP1_Msk /*!< ADC Channel 1 Sampling time selection */ -#define ADC_SMPR1_SMP1_0 (0x1UL << ADC_SMPR1_SMP1_Pos) /*!< 0x00000008 */ -#define ADC_SMPR1_SMP1_1 (0x2UL << ADC_SMPR1_SMP1_Pos) /*!< 0x00000010 */ -#define ADC_SMPR1_SMP1_2 (0x4UL << ADC_SMPR1_SMP1_Pos) /*!< 0x00000020 */ - -#define ADC_SMPR1_SMP2_Pos (6U) -#define ADC_SMPR1_SMP2_Msk (0x7UL << ADC_SMPR1_SMP2_Pos) /*!< 0x000001C0 */ -#define ADC_SMPR1_SMP2 ADC_SMPR1_SMP2_Msk /*!< ADC Channel 2 Sampling time selection */ -#define ADC_SMPR1_SMP2_0 (0x1UL << ADC_SMPR1_SMP2_Pos) /*!< 0x00000040 */ -#define ADC_SMPR1_SMP2_1 (0x2UL << ADC_SMPR1_SMP2_Pos) /*!< 0x00000080 */ -#define ADC_SMPR1_SMP2_2 (0x4UL << ADC_SMPR1_SMP2_Pos) /*!< 0x00000100 */ - -#define ADC_SMPR1_SMP3_Pos (9U) -#define ADC_SMPR1_SMP3_Msk (0x7UL << ADC_SMPR1_SMP3_Pos) /*!< 0x00000E00 */ -#define ADC_SMPR1_SMP3 ADC_SMPR1_SMP3_Msk /*!< ADC Channel 3 Sampling time selection */ -#define ADC_SMPR1_SMP3_0 (0x1UL << ADC_SMPR1_SMP3_Pos) /*!< 0x00000200 */ -#define ADC_SMPR1_SMP3_1 (0x2UL << ADC_SMPR1_SMP3_Pos) /*!< 0x00000400 */ -#define ADC_SMPR1_SMP3_2 (0x4UL << ADC_SMPR1_SMP3_Pos) /*!< 0x00000800 */ - -#define ADC_SMPR1_SMP4_Pos (12U) -#define ADC_SMPR1_SMP4_Msk (0x7UL << ADC_SMPR1_SMP4_Pos) /*!< 0x00007000 */ -#define ADC_SMPR1_SMP4 ADC_SMPR1_SMP4_Msk /*!< ADC Channel 4 Sampling time selection */ -#define ADC_SMPR1_SMP4_0 (0x1UL << ADC_SMPR1_SMP4_Pos) /*!< 0x00001000 */ -#define ADC_SMPR1_SMP4_1 (0x2UL << ADC_SMPR1_SMP4_Pos) /*!< 0x00002000 */ -#define ADC_SMPR1_SMP4_2 (0x4UL << ADC_SMPR1_SMP4_Pos) /*!< 0x00004000 */ - -#define ADC_SMPR1_SMP5_Pos (15U) -#define ADC_SMPR1_SMP5_Msk (0x7UL << ADC_SMPR1_SMP5_Pos) /*!< 0x00038000 */ -#define ADC_SMPR1_SMP5 ADC_SMPR1_SMP5_Msk /*!< ADC Channel 5 Sampling time selection */ -#define ADC_SMPR1_SMP5_0 (0x1UL << ADC_SMPR1_SMP5_Pos) /*!< 0x00008000 */ -#define ADC_SMPR1_SMP5_1 (0x2UL << ADC_SMPR1_SMP5_Pos) /*!< 0x00010000 */ -#define ADC_SMPR1_SMP5_2 (0x4UL << ADC_SMPR1_SMP5_Pos) /*!< 0x00020000 */ - -#define ADC_SMPR1_SMP6_Pos (18U) -#define ADC_SMPR1_SMP6_Msk (0x7UL << ADC_SMPR1_SMP6_Pos) /*!< 0x001C0000 */ -#define ADC_SMPR1_SMP6 ADC_SMPR1_SMP6_Msk /*!< ADC Channel 6 Sampling time selection */ -#define ADC_SMPR1_SMP6_0 (0x1UL << ADC_SMPR1_SMP6_Pos) /*!< 0x00040000 */ -#define ADC_SMPR1_SMP6_1 (0x2UL << ADC_SMPR1_SMP6_Pos) /*!< 0x00080000 */ -#define ADC_SMPR1_SMP6_2 (0x4UL << ADC_SMPR1_SMP6_Pos) /*!< 0x00100000 */ - -#define ADC_SMPR1_SMP7_Pos (21U) -#define ADC_SMPR1_SMP7_Msk (0x7UL << ADC_SMPR1_SMP7_Pos) /*!< 0x00E00000 */ -#define ADC_SMPR1_SMP7 ADC_SMPR1_SMP7_Msk /*!< ADC Channel 7 Sampling time selection */ -#define ADC_SMPR1_SMP7_0 (0x1UL << ADC_SMPR1_SMP7_Pos) /*!< 0x00200000 */ -#define ADC_SMPR1_SMP7_1 (0x2UL << ADC_SMPR1_SMP7_Pos) /*!< 0x00400000 */ -#define ADC_SMPR1_SMP7_2 (0x4UL << ADC_SMPR1_SMP7_Pos) /*!< 0x00800000 */ - -#define ADC_SMPR1_SMP8_Pos (24U) -#define ADC_SMPR1_SMP8_Msk (0x7UL << ADC_SMPR1_SMP8_Pos) /*!< 0x07000000 */ -#define ADC_SMPR1_SMP8 ADC_SMPR1_SMP8_Msk /*!< ADC Channel 8 Sampling time selection */ -#define ADC_SMPR1_SMP8_0 (0x1UL << ADC_SMPR1_SMP8_Pos) /*!< 0x01000000 */ -#define ADC_SMPR1_SMP8_1 (0x2UL << ADC_SMPR1_SMP8_Pos) /*!< 0x02000000 */ -#define ADC_SMPR1_SMP8_2 (0x4UL << ADC_SMPR1_SMP8_Pos) /*!< 0x04000000 */ - -#define ADC_SMPR1_SMP9_Pos (27U) -#define ADC_SMPR1_SMP9_Msk (0x7UL << ADC_SMPR1_SMP9_Pos) /*!< 0x38000000 */ -#define ADC_SMPR1_SMP9 ADC_SMPR1_SMP9_Msk /*!< ADC Channel 9 Sampling time selection */ -#define ADC_SMPR1_SMP9_0 (0x1UL << ADC_SMPR1_SMP9_Pos) /*!< 0x08000000 */ -#define ADC_SMPR1_SMP9_1 (0x2UL << ADC_SMPR1_SMP9_Pos) /*!< 0x10000000 */ -#define ADC_SMPR1_SMP9_2 (0x4UL << ADC_SMPR1_SMP9_Pos) /*!< 0x20000000 */ - -/******************** Bit definition for ADC_SMPR2 register ********************/ -#define ADC_SMPR2_SMP10_Pos (0U) -#define ADC_SMPR2_SMP10_Msk (0x7UL << ADC_SMPR2_SMP10_Pos) /*!< 0x00000007 */ -#define ADC_SMPR2_SMP10 ADC_SMPR2_SMP10_Msk /*!< ADC Channel 10 Sampling time selection */ -#define ADC_SMPR2_SMP10_0 (0x1UL << ADC_SMPR2_SMP10_Pos) /*!< 0x00000001 */ -#define ADC_SMPR2_SMP10_1 (0x2UL << ADC_SMPR2_SMP10_Pos) /*!< 0x00000002 */ -#define ADC_SMPR2_SMP10_2 (0x4UL << ADC_SMPR2_SMP10_Pos) /*!< 0x00000004 */ - -#define ADC_SMPR2_SMP11_Pos (3U) -#define ADC_SMPR2_SMP11_Msk (0x7UL << ADC_SMPR2_SMP11_Pos) /*!< 0x00000038 */ -#define ADC_SMPR2_SMP11 ADC_SMPR2_SMP11_Msk /*!< ADC Channel 11 Sampling time selection */ -#define ADC_SMPR2_SMP11_0 (0x1UL << ADC_SMPR2_SMP11_Pos) /*!< 0x00000008 */ -#define ADC_SMPR2_SMP11_1 (0x2UL << ADC_SMPR2_SMP11_Pos) /*!< 0x00000010 */ -#define ADC_SMPR2_SMP11_2 (0x4UL << ADC_SMPR2_SMP11_Pos) /*!< 0x00000020 */ - -#define ADC_SMPR2_SMP12_Pos (6U) -#define ADC_SMPR2_SMP12_Msk (0x7UL << ADC_SMPR2_SMP12_Pos) /*!< 0x000001C0 */ -#define ADC_SMPR2_SMP12 ADC_SMPR2_SMP12_Msk /*!< ADC Channel 12 Sampling time selection */ -#define ADC_SMPR2_SMP12_0 (0x1UL << ADC_SMPR2_SMP12_Pos) /*!< 0x00000040 */ -#define ADC_SMPR2_SMP12_1 (0x2UL << ADC_SMPR2_SMP12_Pos) /*!< 0x00000080 */ -#define ADC_SMPR2_SMP12_2 (0x4UL << ADC_SMPR2_SMP12_Pos) /*!< 0x00000100 */ - -#define ADC_SMPR2_SMP13_Pos (9U) -#define ADC_SMPR2_SMP13_Msk (0x7UL << ADC_SMPR2_SMP13_Pos) /*!< 0x00000E00 */ -#define ADC_SMPR2_SMP13 ADC_SMPR2_SMP13_Msk /*!< ADC Channel 13 Sampling time selection */ -#define ADC_SMPR2_SMP13_0 (0x1UL << ADC_SMPR2_SMP13_Pos) /*!< 0x00000200 */ -#define ADC_SMPR2_SMP13_1 (0x2UL << ADC_SMPR2_SMP13_Pos) /*!< 0x00000400 */ -#define ADC_SMPR2_SMP13_2 (0x4UL << ADC_SMPR2_SMP13_Pos) /*!< 0x00000800 */ - -#define ADC_SMPR2_SMP14_Pos (12U) -#define ADC_SMPR2_SMP14_Msk (0x7UL << ADC_SMPR2_SMP14_Pos) /*!< 0x00007000 */ -#define ADC_SMPR2_SMP14 ADC_SMPR2_SMP14_Msk /*!< ADC Channel 14 Sampling time selection */ -#define ADC_SMPR2_SMP14_0 (0x1UL << ADC_SMPR2_SMP14_Pos) /*!< 0x00001000 */ -#define ADC_SMPR2_SMP14_1 (0x2UL << ADC_SMPR2_SMP14_Pos) /*!< 0x00002000 */ -#define ADC_SMPR2_SMP14_2 (0x4UL << ADC_SMPR2_SMP14_Pos) /*!< 0x00004000 */ - -#define ADC_SMPR2_SMP15_Pos (15U) -#define ADC_SMPR2_SMP15_Msk (0x7UL << ADC_SMPR2_SMP15_Pos) /*!< 0x00038000 */ -#define ADC_SMPR2_SMP15 ADC_SMPR2_SMP15_Msk /*!< ADC Channel 15 Sampling time selection */ -#define ADC_SMPR2_SMP15_0 (0x1UL << ADC_SMPR2_SMP15_Pos) /*!< 0x00008000 */ -#define ADC_SMPR2_SMP15_1 (0x2UL << ADC_SMPR2_SMP15_Pos) /*!< 0x00010000 */ -#define ADC_SMPR2_SMP15_2 (0x4UL << ADC_SMPR2_SMP15_Pos) /*!< 0x00020000 */ - -#define ADC_SMPR2_SMP16_Pos (18U) -#define ADC_SMPR2_SMP16_Msk (0x7UL << ADC_SMPR2_SMP16_Pos) /*!< 0x001C0000 */ -#define ADC_SMPR2_SMP16 ADC_SMPR2_SMP16_Msk /*!< ADC Channel 16 Sampling time selection */ -#define ADC_SMPR2_SMP16_0 (0x1UL << ADC_SMPR2_SMP16_Pos) /*!< 0x00040000 */ -#define ADC_SMPR2_SMP16_1 (0x2UL << ADC_SMPR2_SMP16_Pos) /*!< 0x00080000 */ -#define ADC_SMPR2_SMP16_2 (0x4UL << ADC_SMPR2_SMP16_Pos) /*!< 0x00100000 */ - -#define ADC_SMPR2_SMP17_Pos (21U) -#define ADC_SMPR2_SMP17_Msk (0x7UL << ADC_SMPR2_SMP17_Pos) /*!< 0x00E00000 */ -#define ADC_SMPR2_SMP17 ADC_SMPR2_SMP17_Msk /*!< ADC Channel 17 Sampling time selection */ -#define ADC_SMPR2_SMP17_0 (0x1UL << ADC_SMPR2_SMP17_Pos) /*!< 0x00200000 */ -#define ADC_SMPR2_SMP17_1 (0x2UL << ADC_SMPR2_SMP17_Pos) /*!< 0x00400000 */ -#define ADC_SMPR2_SMP17_2 (0x4UL << ADC_SMPR2_SMP17_Pos) /*!< 0x00800000 */ - -#define ADC_SMPR2_SMP18_Pos (24U) -#define ADC_SMPR2_SMP18_Msk (0x7UL << ADC_SMPR2_SMP18_Pos) /*!< 0x07000000 */ -#define ADC_SMPR2_SMP18 ADC_SMPR2_SMP18_Msk /*!< ADC Channel 18 Sampling time selection */ -#define ADC_SMPR2_SMP18_0 (0x1UL << ADC_SMPR2_SMP18_Pos) /*!< 0x01000000 */ -#define ADC_SMPR2_SMP18_1 (0x2UL << ADC_SMPR2_SMP18_Pos) /*!< 0x02000000 */ -#define ADC_SMPR2_SMP18_2 (0x4UL << ADC_SMPR2_SMP18_Pos) /*!< 0x04000000 */ - -#define ADC_SMPR2_SMP19_Pos (27U) -#define ADC_SMPR2_SMP19_Msk (0x7UL << ADC_SMPR2_SMP19_Pos) /*!< 0x38000000 */ -#define ADC_SMPR2_SMP19 ADC_SMPR2_SMP19_Msk /*!< ADC Channel 19 Sampling time selection */ -#define ADC_SMPR2_SMP19_0 (0x1UL << ADC_SMPR2_SMP19_Pos) /*!< 0x08000000 */ -#define ADC_SMPR2_SMP19_1 (0x2UL << ADC_SMPR2_SMP19_Pos) /*!< 0x10000000 */ -#define ADC_SMPR2_SMP19_2 (0x4UL << ADC_SMPR2_SMP19_Pos) /*!< 0x20000000 */ - -/******************** Bit definition for ADC_PCSEL register ********************/ -#define ADC_PCSEL_PCSEL_Pos (0U) -#define ADC_PCSEL_PCSEL_Msk (0xFFFFFUL << ADC_PCSEL_PCSEL_Pos) /*!< 0x000FFFFF */ -#define ADC_PCSEL_PCSEL ADC_PCSEL_PCSEL_Msk /*!< ADC pre channel selection */ -#define ADC_PCSEL_PCSEL_0 (0x00001UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000001 */ -#define ADC_PCSEL_PCSEL_1 (0x00002UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000002 */ -#define ADC_PCSEL_PCSEL_2 (0x00004UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000004 */ -#define ADC_PCSEL_PCSEL_3 (0x00008UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000008 */ -#define ADC_PCSEL_PCSEL_4 (0x00010UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000010 */ -#define ADC_PCSEL_PCSEL_5 (0x00020UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000020 */ -#define ADC_PCSEL_PCSEL_6 (0x00040UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000040 */ -#define ADC_PCSEL_PCSEL_7 (0x00080UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000080 */ -#define ADC_PCSEL_PCSEL_8 (0x00100UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000100 */ -#define ADC_PCSEL_PCSEL_9 (0x00200UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000200 */ -#define ADC_PCSEL_PCSEL_10 (0x00400UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000400 */ -#define ADC_PCSEL_PCSEL_11 (0x00800UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000800 */ -#define ADC_PCSEL_PCSEL_12 (0x01000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00001000 */ -#define ADC_PCSEL_PCSEL_13 (0x02000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00002000 */ -#define ADC_PCSEL_PCSEL_14 (0x04000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00004000 */ -#define ADC_PCSEL_PCSEL_15 (0x08000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00008000 */ -#define ADC_PCSEL_PCSEL_16 (0x10000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00010000 */ -#define ADC_PCSEL_PCSEL_17 (0x20000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00020000 */ -#define ADC_PCSEL_PCSEL_18 (0x40000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00040000 */ -#define ADC_PCSEL_PCSEL_19 (0x80000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00080000 */ - -/***************** Bit definition for ADC_LTR1, 2, 3 registers *****************/ -#define ADC_LTR_LT_Pos (0U) -#define ADC_LTR_LT_Msk (0x3FFFFFFUL << ADC_LTR_LT_Pos) /*!< 0x03FFFFFF */ -#define ADC_LTR_LT ADC_LTR_LT_Msk /*!< ADC Analog watchdog 1, 2 and 3 lower threshold */ - -/***************** Bit definition for ADC_HTR1, 2, 3 registers ****************/ -#define ADC_HTR_HT_Pos (0U) -#define ADC_HTR_HT_Msk (0x3FFFFFFUL << ADC_HTR_HT_Pos) /*!< 0x03FFFFFF */ -#define ADC_HTR_HT ADC_HTR_HT_Msk /*!< ADC Analog watchdog 1,2 and 3 higher threshold */ - -/******************** Bit definition for ADC3_TR1 register *******************/ -#define ADC3_TR1_LT1_Pos (0U) -#define ADC3_TR1_LT1_Msk (0xFFFUL << ADC3_TR1_LT1_Pos) /*!< 0x00000FFF */ -#define ADC3_TR1_LT1 ADC3_TR1_LT1_Msk /*!< ADC analog watchdog 1 threshold low */ - -#define ADC3_TR1_AWDFILT_Pos (12U) -#define ADC3_TR1_AWDFILT_Msk (0x7UL << ADC3_TR1_AWDFILT_Pos) /*!< 0x00007000 */ -#define ADC3_TR1_AWDFILT ADC3_TR1_AWDFILT_Msk /*!< ADC analog watchdog filtering parameter */ -#define ADC3_TR1_AWDFILT_0 (0x1UL << ADC3_TR1_AWDFILT_Pos) /*!< 0x00001000 */ -#define ADC3_TR1_AWDFILT_1 (0x2UL << ADC3_TR1_AWDFILT_Pos) /*!< 0x00002000 */ -#define ADC3_TR1_AWDFILT_2 (0x4UL << ADC3_TR1_AWDFILT_Pos) /*!< 0x00004000 */ - -#define ADC3_TR1_HT1_Pos (16U) -#define ADC3_TR1_HT1_Msk (0xFFFUL << ADC3_TR1_HT1_Pos) /*!< 0x0FFF0000 */ -#define ADC3_TR1_HT1 ADC3_TR1_HT1_Msk /*!< ADC analog watchdog 1 threshold high */ - -/******************** Bit definition for ADC3_TR2 register *******************/ -#define ADC3_TR2_LT2_Pos (0U) -#define ADC3_TR2_LT2_Msk (0xFFUL << ADC3_TR2_LT2_Pos) /*!< 0x000000FF */ -#define ADC3_TR2_LT2 ADC3_TR2_LT2_Msk /*!< ADC analog watchdog 2 threshold low */ - -#define ADC3_TR2_HT2_Pos (16U) -#define ADC3_TR2_HT2_Msk (0xFFUL << ADC3_TR2_HT2_Pos) /*!< 0x00FF0000 */ -#define ADC3_TR2_HT2 ADC3_TR2_HT2_Msk /*!< ADC analog watchdog 2 threshold high */ - -/******************** Bit definition for ADC3_TR3 register *******************/ -#define ADC3_TR3_LT3_Pos (0U) -#define ADC3_TR3_LT3_Msk (0xFFUL << ADC3_TR3_LT3_Pos) /*!< 0x000000FF */ -#define ADC3_TR3_LT3 ADC3_TR3_LT3_Msk /*!< ADC analog watchdog 3 threshold low */ - -#define ADC3_TR3_HT3_Pos (16U) -#define ADC3_TR3_HT3_Msk (0xFFUL << ADC3_TR3_HT3_Pos) /*!< 0x00FF0000 */ -#define ADC3_TR3_HT3 ADC3_TR3_HT3_Msk /*!< ADC analog watchdog 3 threshold high */ - -/******************** Bit definition for ADC_SQR1 register ********************/ -#define ADC_SQR1_L_Pos (0U) -#define ADC_SQR1_L_Msk (0xFUL << ADC_SQR1_L_Pos) /*!< 0x0000000F */ -#define ADC_SQR1_L ADC_SQR1_L_Msk /*!< ADC regular channel sequence length */ -#define ADC_SQR1_L_0 (0x1UL << ADC_SQR1_L_Pos) /*!< 0x00000001 */ -#define ADC_SQR1_L_1 (0x2UL << ADC_SQR1_L_Pos) /*!< 0x00000002 */ -#define ADC_SQR1_L_2 (0x4UL << ADC_SQR1_L_Pos) /*!< 0x00000004 */ -#define ADC_SQR1_L_3 (0x8UL << ADC_SQR1_L_Pos) /*!< 0x00000008 */ - -#define ADC_SQR1_SQ1_Pos (6U) -#define ADC_SQR1_SQ1_Msk (0x1FUL << ADC_SQR1_SQ1_Pos) /*!< 0x000007C0 */ -#define ADC_SQR1_SQ1 ADC_SQR1_SQ1_Msk /*!< ADC 1st conversion in regular sequence */ -#define ADC_SQR1_SQ1_0 (0x01UL << ADC_SQR1_SQ1_Pos) /*!< 0x00000040 */ -#define ADC_SQR1_SQ1_1 (0x02UL << ADC_SQR1_SQ1_Pos) /*!< 0x00000080 */ -#define ADC_SQR1_SQ1_2 (0x04UL << ADC_SQR1_SQ1_Pos) /*!< 0x00000100 */ -#define ADC_SQR1_SQ1_3 (0x08UL << ADC_SQR1_SQ1_Pos) /*!< 0x00000200 */ -#define ADC_SQR1_SQ1_4 (0x10UL << ADC_SQR1_SQ1_Pos) /*!< 0x00000400 */ - -#define ADC_SQR1_SQ2_Pos (12U) -#define ADC_SQR1_SQ2_Msk (0x1FUL << ADC_SQR1_SQ2_Pos) /*!< 0x0001F000 */ -#define ADC_SQR1_SQ2 ADC_SQR1_SQ2_Msk /*!< ADC 2nd conversion in regular sequence */ -#define ADC_SQR1_SQ2_0 (0x01UL << ADC_SQR1_SQ2_Pos) /*!< 0x00001000 */ -#define ADC_SQR1_SQ2_1 (0x02UL << ADC_SQR1_SQ2_Pos) /*!< 0x00002000 */ -#define ADC_SQR1_SQ2_2 (0x04UL << ADC_SQR1_SQ2_Pos) /*!< 0x00004000 */ -#define ADC_SQR1_SQ2_3 (0x08UL << ADC_SQR1_SQ2_Pos) /*!< 0x00008000 */ -#define ADC_SQR1_SQ2_4 (0x10UL << ADC_SQR1_SQ2_Pos) /*!< 0x00010000 */ - -#define ADC_SQR1_SQ3_Pos (18U) -#define ADC_SQR1_SQ3_Msk (0x1FUL << ADC_SQR1_SQ3_Pos) /*!< 0x007C0000 */ -#define ADC_SQR1_SQ3 ADC_SQR1_SQ3_Msk /*!< ADC 3rd conversion in regular sequence */ -#define ADC_SQR1_SQ3_0 (0x01UL << ADC_SQR1_SQ3_Pos) /*!< 0x00040000 */ -#define ADC_SQR1_SQ3_1 (0x02UL << ADC_SQR1_SQ3_Pos) /*!< 0x00080000 */ -#define ADC_SQR1_SQ3_2 (0x04UL << ADC_SQR1_SQ3_Pos) /*!< 0x00100000 */ -#define ADC_SQR1_SQ3_3 (0x08UL << ADC_SQR1_SQ3_Pos) /*!< 0x00200000 */ -#define ADC_SQR1_SQ3_4 (0x10UL << ADC_SQR1_SQ3_Pos) /*!< 0x00400000 */ - -#define ADC_SQR1_SQ4_Pos (24U) -#define ADC_SQR1_SQ4_Msk (0x1FUL << ADC_SQR1_SQ4_Pos) /*!< 0x1F000000 */ -#define ADC_SQR1_SQ4 ADC_SQR1_SQ4_Msk /*!< ADC 4th conversion in regular sequence */ -#define ADC_SQR1_SQ4_0 (0x01UL << ADC_SQR1_SQ4_Pos) /*!< 0x01000000 */ -#define ADC_SQR1_SQ4_1 (0x02UL << ADC_SQR1_SQ4_Pos) /*!< 0x02000000 */ -#define ADC_SQR1_SQ4_2 (0x04UL << ADC_SQR1_SQ4_Pos) /*!< 0x04000000 */ -#define ADC_SQR1_SQ4_3 (0x08UL << ADC_SQR1_SQ4_Pos) /*!< 0x08000000 */ -#define ADC_SQR1_SQ4_4 (0x10UL << ADC_SQR1_SQ4_Pos) /*!< 0x10000000 */ - -/******************** Bit definition for ADC_SQR2 register ********************/ -#define ADC_SQR2_SQ5_Pos (0U) -#define ADC_SQR2_SQ5_Msk (0x1FUL << ADC_SQR2_SQ5_Pos) /*!< 0x0000001F */ -#define ADC_SQR2_SQ5 ADC_SQR2_SQ5_Msk /*!< ADC 5th conversion in regular sequence */ -#define ADC_SQR2_SQ5_0 (0x01UL << ADC_SQR2_SQ5_Pos) /*!< 0x00000001 */ -#define ADC_SQR2_SQ5_1 (0x02UL << ADC_SQR2_SQ5_Pos) /*!< 0x00000002 */ -#define ADC_SQR2_SQ5_2 (0x04UL << ADC_SQR2_SQ5_Pos) /*!< 0x00000004 */ -#define ADC_SQR2_SQ5_3 (0x08UL << ADC_SQR2_SQ5_Pos) /*!< 0x00000008 */ -#define ADC_SQR2_SQ5_4 (0x10UL << ADC_SQR2_SQ5_Pos) /*!< 0x00000010 */ - -#define ADC_SQR2_SQ6_Pos (6U) -#define ADC_SQR2_SQ6_Msk (0x1FUL << ADC_SQR2_SQ6_Pos) /*!< 0x000007C0 */ -#define ADC_SQR2_SQ6 ADC_SQR2_SQ6_Msk /*!< ADC 6th conversion in regular sequence */ -#define ADC_SQR2_SQ6_0 (0x01UL << ADC_SQR2_SQ6_Pos) /*!< 0x00000040 */ -#define ADC_SQR2_SQ6_1 (0x02UL << ADC_SQR2_SQ6_Pos) /*!< 0x00000080 */ -#define ADC_SQR2_SQ6_2 (0x04UL << ADC_SQR2_SQ6_Pos) /*!< 0x00000100 */ -#define ADC_SQR2_SQ6_3 (0x08UL << ADC_SQR2_SQ6_Pos) /*!< 0x00000200 */ -#define ADC_SQR2_SQ6_4 (0x10UL << ADC_SQR2_SQ6_Pos) /*!< 0x00000400 */ - -#define ADC_SQR2_SQ7_Pos (12U) -#define ADC_SQR2_SQ7_Msk (0x1FUL << ADC_SQR2_SQ7_Pos) /*!< 0x0001F000 */ -#define ADC_SQR2_SQ7 ADC_SQR2_SQ7_Msk /*!< ADC 7th conversion in regular sequence */ -#define ADC_SQR2_SQ7_0 (0x01UL << ADC_SQR2_SQ7_Pos) /*!< 0x00001000 */ -#define ADC_SQR2_SQ7_1 (0x02UL << ADC_SQR2_SQ7_Pos) /*!< 0x00002000 */ -#define ADC_SQR2_SQ7_2 (0x04UL << ADC_SQR2_SQ7_Pos) /*!< 0x00004000 */ -#define ADC_SQR2_SQ7_3 (0x08UL << ADC_SQR2_SQ7_Pos) /*!< 0x00008000 */ -#define ADC_SQR2_SQ7_4 (0x10UL << ADC_SQR2_SQ7_Pos) /*!< 0x00010000 */ - -#define ADC_SQR2_SQ8_Pos (18U) -#define ADC_SQR2_SQ8_Msk (0x1FUL << ADC_SQR2_SQ8_Pos) /*!< 0x007C0000 */ -#define ADC_SQR2_SQ8 ADC_SQR2_SQ8_Msk /*!< ADC 8th conversion in regular sequence */ -#define ADC_SQR2_SQ8_0 (0x01UL << ADC_SQR2_SQ8_Pos) /*!< 0x00040000 */ -#define ADC_SQR2_SQ8_1 (0x02UL << ADC_SQR2_SQ8_Pos) /*!< 0x00080000 */ -#define ADC_SQR2_SQ8_2 (0x04UL << ADC_SQR2_SQ8_Pos) /*!< 0x00100000 */ -#define ADC_SQR2_SQ8_3 (0x08UL << ADC_SQR2_SQ8_Pos) /*!< 0x00200000 */ -#define ADC_SQR2_SQ8_4 (0x10UL << ADC_SQR2_SQ8_Pos) /*!< 0x00400000 */ - -#define ADC_SQR2_SQ9_Pos (24U) -#define ADC_SQR2_SQ9_Msk (0x1FUL << ADC_SQR2_SQ9_Pos) /*!< 0x1F000000 */ -#define ADC_SQR2_SQ9 ADC_SQR2_SQ9_Msk /*!< ADC 9th conversion in regular sequence */ -#define ADC_SQR2_SQ9_0 (0x01UL << ADC_SQR2_SQ9_Pos) /*!< 0x01000000 */ -#define ADC_SQR2_SQ9_1 (0x02UL << ADC_SQR2_SQ9_Pos) /*!< 0x02000000 */ -#define ADC_SQR2_SQ9_2 (0x04UL << ADC_SQR2_SQ9_Pos) /*!< 0x04000000 */ -#define ADC_SQR2_SQ9_3 (0x08UL << ADC_SQR2_SQ9_Pos) /*!< 0x08000000 */ -#define ADC_SQR2_SQ9_4 (0x10UL << ADC_SQR2_SQ9_Pos) /*!< 0x10000000 */ - -/******************** Bit definition for ADC_SQR3 register ********************/ -#define ADC_SQR3_SQ10_Pos (0U) -#define ADC_SQR3_SQ10_Msk (0x1FUL << ADC_SQR3_SQ10_Pos) /*!< 0x0000001F */ -#define ADC_SQR3_SQ10 ADC_SQR3_SQ10_Msk /*!< ADC 10th conversion in regular sequence */ -#define ADC_SQR3_SQ10_0 (0x01UL << ADC_SQR3_SQ10_Pos) /*!< 0x00000001 */ -#define ADC_SQR3_SQ10_1 (0x02UL << ADC_SQR3_SQ10_Pos) /*!< 0x00000002 */ -#define ADC_SQR3_SQ10_2 (0x04UL << ADC_SQR3_SQ10_Pos) /*!< 0x00000004 */ -#define ADC_SQR3_SQ10_3 (0x08UL << ADC_SQR3_SQ10_Pos) /*!< 0x00000008 */ -#define ADC_SQR3_SQ10_4 (0x10UL << ADC_SQR3_SQ10_Pos) /*!< 0x00000010 */ - -#define ADC_SQR3_SQ11_Pos (6U) -#define ADC_SQR3_SQ11_Msk (0x1FUL << ADC_SQR3_SQ11_Pos) /*!< 0x000007C0 */ -#define ADC_SQR3_SQ11 ADC_SQR3_SQ11_Msk /*!< ADC 11th conversion in regular sequence */ -#define ADC_SQR3_SQ11_0 (0x01UL << ADC_SQR3_SQ11_Pos) /*!< 0x00000040 */ -#define ADC_SQR3_SQ11_1 (0x02UL << ADC_SQR3_SQ11_Pos) /*!< 0x00000080 */ -#define ADC_SQR3_SQ11_2 (0x04UL << ADC_SQR3_SQ11_Pos) /*!< 0x00000100 */ -#define ADC_SQR3_SQ11_3 (0x08UL << ADC_SQR3_SQ11_Pos) /*!< 0x00000200 */ -#define ADC_SQR3_SQ11_4 (0x10UL << ADC_SQR3_SQ11_Pos) /*!< 0x00000400 */ - -#define ADC_SQR3_SQ12_Pos (12U) -#define ADC_SQR3_SQ12_Msk (0x1FUL << ADC_SQR3_SQ12_Pos) /*!< 0x0001F000 */ -#define ADC_SQR3_SQ12 ADC_SQR3_SQ12_Msk /*!< ADC 12th conversion in regular sequence */ -#define ADC_SQR3_SQ12_0 (0x01UL << ADC_SQR3_SQ12_Pos) /*!< 0x00001000 */ -#define ADC_SQR3_SQ12_1 (0x02UL << ADC_SQR3_SQ12_Pos) /*!< 0x00002000 */ -#define ADC_SQR3_SQ12_2 (0x04UL << ADC_SQR3_SQ12_Pos) /*!< 0x00004000 */ -#define ADC_SQR3_SQ12_3 (0x08UL << ADC_SQR3_SQ12_Pos) /*!< 0x00008000 */ -#define ADC_SQR3_SQ12_4 (0x10UL << ADC_SQR3_SQ12_Pos) /*!< 0x00010000 */ - -#define ADC_SQR3_SQ13_Pos (18U) -#define ADC_SQR3_SQ13_Msk (0x1FUL << ADC_SQR3_SQ13_Pos) /*!< 0x007C0000 */ -#define ADC_SQR3_SQ13 ADC_SQR3_SQ13_Msk /*!< ADC 13th conversion in regular sequence */ -#define ADC_SQR3_SQ13_0 (0x01UL << ADC_SQR3_SQ13_Pos) /*!< 0x00040000 */ -#define ADC_SQR3_SQ13_1 (0x02UL << ADC_SQR3_SQ13_Pos) /*!< 0x00080000 */ -#define ADC_SQR3_SQ13_2 (0x04UL << ADC_SQR3_SQ13_Pos) /*!< 0x00100000 */ -#define ADC_SQR3_SQ13_3 (0x08UL << ADC_SQR3_SQ13_Pos) /*!< 0x00200000 */ -#define ADC_SQR3_SQ13_4 (0x10UL << ADC_SQR3_SQ13_Pos) /*!< 0x00400000 */ - -#define ADC_SQR3_SQ14_Pos (24U) -#define ADC_SQR3_SQ14_Msk (0x1FUL << ADC_SQR3_SQ14_Pos) /*!< 0x1F000000 */ -#define ADC_SQR3_SQ14 ADC_SQR3_SQ14_Msk /*!< ADC 14th conversion in regular sequence */ -#define ADC_SQR3_SQ14_0 (0x01UL << ADC_SQR3_SQ14_Pos) /*!< 0x01000000 */ -#define ADC_SQR3_SQ14_1 (0x02UL << ADC_SQR3_SQ14_Pos) /*!< 0x02000000 */ -#define ADC_SQR3_SQ14_2 (0x04UL << ADC_SQR3_SQ14_Pos) /*!< 0x04000000 */ -#define ADC_SQR3_SQ14_3 (0x08UL << ADC_SQR3_SQ14_Pos) /*!< 0x08000000 */ -#define ADC_SQR3_SQ14_4 (0x10UL << ADC_SQR3_SQ14_Pos) /*!< 0x10000000 */ - -/******************** Bit definition for ADC_SQR4 register ********************/ -#define ADC_SQR4_SQ15_Pos (0U) -#define ADC_SQR4_SQ15_Msk (0x1FUL << ADC_SQR4_SQ15_Pos) /*!< 0x0000001F */ -#define ADC_SQR4_SQ15 ADC_SQR4_SQ15_Msk /*!< ADC 15th conversion in regular sequence */ -#define ADC_SQR4_SQ15_0 (0x01UL << ADC_SQR4_SQ15_Pos) /*!< 0x00000001 */ -#define ADC_SQR4_SQ15_1 (0x02UL << ADC_SQR4_SQ15_Pos) /*!< 0x00000002 */ -#define ADC_SQR4_SQ15_2 (0x04UL << ADC_SQR4_SQ15_Pos) /*!< 0x00000004 */ -#define ADC_SQR4_SQ15_3 (0x08UL << ADC_SQR4_SQ15_Pos) /*!< 0x00000008 */ -#define ADC_SQR4_SQ15_4 (0x10UL << ADC_SQR4_SQ15_Pos) /*!< 0x00000010 */ - -#define ADC_SQR4_SQ16_Pos (6U) -#define ADC_SQR4_SQ16_Msk (0x1FUL << ADC_SQR4_SQ16_Pos) /*!< 0x000007C0 */ -#define ADC_SQR4_SQ16 ADC_SQR4_SQ16_Msk /*!< ADC 16th conversion in regular sequence */ -#define ADC_SQR4_SQ16_0 (0x01UL << ADC_SQR4_SQ16_Pos) /*!< 0x00000040 */ -#define ADC_SQR4_SQ16_1 (0x02UL << ADC_SQR4_SQ16_Pos) /*!< 0x00000080 */ -#define ADC_SQR4_SQ16_2 (0x04UL << ADC_SQR4_SQ16_Pos) /*!< 0x00000100 */ -#define ADC_SQR4_SQ16_3 (0x08UL << ADC_SQR4_SQ16_Pos) /*!< 0x00000200 */ -#define ADC_SQR4_SQ16_4 (0x10UL << ADC_SQR4_SQ16_Pos) /*!< 0x00000400 */ -/******************** Bit definition for ADC_DR register ********************/ -#define ADC_DR_RDATA_Pos (0U) -#define ADC_DR_RDATA_Msk (0xFFFFFFFFUL << ADC_DR_RDATA_Pos) /*!< 0xFFFFFFFF */ -#define ADC_DR_RDATA ADC_DR_RDATA_Msk /*!< ADC regular Data converted */ - -/******************** Bit definition for ADC_JSQR register ********************/ -#define ADC_JSQR_JL_Pos (0U) -#define ADC_JSQR_JL_Msk (0x3UL << ADC_JSQR_JL_Pos) /*!< 0x00000003 */ -#define ADC_JSQR_JL ADC_JSQR_JL_Msk /*!< ADC injected channel sequence length */ -#define ADC_JSQR_JL_0 (0x1UL << ADC_JSQR_JL_Pos) /*!< 0x00000001 */ -#define ADC_JSQR_JL_1 (0x2UL << ADC_JSQR_JL_Pos) /*!< 0x00000002 */ - -#define ADC_JSQR_JEXTSEL_Pos (2U) -#define ADC_JSQR_JEXTSEL_Msk (0x1FUL << ADC_JSQR_JEXTSEL_Pos) /*!< 0x0000007C */ -#define ADC_JSQR_JEXTSEL ADC_JSQR_JEXTSEL_Msk /*!< ADC external trigger selection for injected group */ -#define ADC_JSQR_JEXTSEL_0 (0x01UL << ADC_JSQR_JEXTSEL_Pos) /*!< 0x00000004 */ -#define ADC_JSQR_JEXTSEL_1 (0x02UL << ADC_JSQR_JEXTSEL_Pos) /*!< 0x00000008 */ -#define ADC_JSQR_JEXTSEL_2 (0x04UL << ADC_JSQR_JEXTSEL_Pos) /*!< 0x00000010 */ -#define ADC_JSQR_JEXTSEL_3 (0x08UL << ADC_JSQR_JEXTSEL_Pos) /*!< 0x00000020 */ -#define ADC_JSQR_JEXTSEL_4 (0x10UL << ADC_JSQR_JEXTSEL_Pos) /*!< 0x00000040 */ - -#define ADC_JSQR_JEXTEN_Pos (7U) -#define ADC_JSQR_JEXTEN_Msk (0x3UL << ADC_JSQR_JEXTEN_Pos) /*!< 0x00000180 */ -#define ADC_JSQR_JEXTEN ADC_JSQR_JEXTEN_Msk /*!< ADC external trigger enable and polarity selection for injected channels */ -#define ADC_JSQR_JEXTEN_0 (0x1UL << ADC_JSQR_JEXTEN_Pos) /*!< 0x00000080 */ -#define ADC_JSQR_JEXTEN_1 (0x2UL << ADC_JSQR_JEXTEN_Pos) /*!< 0x00000100 */ - -#define ADC_JSQR_JSQ1_Pos (9U) -#define ADC_JSQR_JSQ1_Msk (0x1FUL << ADC_JSQR_JSQ1_Pos) /*!< 0x00003E00 */ -#define ADC_JSQR_JSQ1 ADC_JSQR_JSQ1_Msk /*!< ADC 1st conversion in injected sequence */ -#define ADC_JSQR_JSQ1_0 (0x01UL << ADC_JSQR_JSQ1_Pos) /*!< 0x00000200 */ -#define ADC_JSQR_JSQ1_1 (0x02UL << ADC_JSQR_JSQ1_Pos) /*!< 0x00000400 */ -#define ADC_JSQR_JSQ1_2 (0x04UL << ADC_JSQR_JSQ1_Pos) /*!< 0x00000800 */ -#define ADC_JSQR_JSQ1_3 (0x08UL << ADC_JSQR_JSQ1_Pos) /*!< 0x00001000 */ -#define ADC_JSQR_JSQ1_4 (0x10UL << ADC_JSQR_JSQ1_Pos) /*!< 0x00002000 */ - -#define ADC_JSQR_JSQ2_Pos (15U) -#define ADC_JSQR_JSQ2_Msk (0x1FUL << ADC_JSQR_JSQ2_Pos) /*!< 0x000F8000 */ -#define ADC_JSQR_JSQ2 ADC_JSQR_JSQ2_Msk /*!< ADC 2nd conversion in injected sequence */ -#define ADC_JSQR_JSQ2_0 (0x01UL << ADC_JSQR_JSQ2_Pos) /*!< 0x00008000 */ -#define ADC_JSQR_JSQ2_1 (0x02UL << ADC_JSQR_JSQ2_Pos) /*!< 0x00010000 */ -#define ADC_JSQR_JSQ2_2 (0x04UL << ADC_JSQR_JSQ2_Pos) /*!< 0x00020000 */ -#define ADC_JSQR_JSQ2_3 (0x08UL << ADC_JSQR_JSQ2_Pos) /*!< 0x00040000 */ -#define ADC_JSQR_JSQ2_4 (0x10UL << ADC_JSQR_JSQ2_Pos) /*!< 0x00080000 */ - -#define ADC_JSQR_JSQ3_Pos (21U) -#define ADC_JSQR_JSQ3_Msk (0x1FUL << ADC_JSQR_JSQ3_Pos) /*!< 0x03E00000 */ -#define ADC_JSQR_JSQ3 ADC_JSQR_JSQ3_Msk /*!< ADC 3rd conversion in injected sequence */ -#define ADC_JSQR_JSQ3_0 (0x01UL << ADC_JSQR_JSQ3_Pos) /*!< 0x00200000 */ -#define ADC_JSQR_JSQ3_1 (0x02UL << ADC_JSQR_JSQ3_Pos) /*!< 0x00400000 */ -#define ADC_JSQR_JSQ3_2 (0x04UL << ADC_JSQR_JSQ3_Pos) /*!< 0x00800000 */ -#define ADC_JSQR_JSQ3_3 (0x08UL << ADC_JSQR_JSQ3_Pos) /*!< 0x01000000 */ -#define ADC_JSQR_JSQ3_4 (0x10UL << ADC_JSQR_JSQ3_Pos) /*!< 0x02000000 */ - -#define ADC_JSQR_JSQ4_Pos (27U) -#define ADC_JSQR_JSQ4_Msk (0x1FUL << ADC_JSQR_JSQ4_Pos) /*!< 0xF8000000 */ -#define ADC_JSQR_JSQ4 ADC_JSQR_JSQ4_Msk /*!< ADC 4th conversion in injected sequence */ -#define ADC_JSQR_JSQ4_0 (0x01UL << ADC_JSQR_JSQ4_Pos) /*!< 0x08000000 */ -#define ADC_JSQR_JSQ4_1 (0x02UL << ADC_JSQR_JSQ4_Pos) /*!< 0x10000000 */ -#define ADC_JSQR_JSQ4_2 (0x04UL << ADC_JSQR_JSQ4_Pos) /*!< 0x20000000 */ -#define ADC_JSQR_JSQ4_3 (0x08UL << ADC_JSQR_JSQ4_Pos) /*!< 0x40000000 */ -#define ADC_JSQR_JSQ4_4 (0x10UL << ADC_JSQR_JSQ4_Pos) /*!< 0x80000000 */ - -/******************** Bit definition for ADC_OFR1 register ********************/ -#define ADC_OFR1_OFFSET1_Pos (0U) -#define ADC_OFR1_OFFSET1_Msk (0x3FFFFFFUL << ADC_OFR1_OFFSET1_Pos) /*!< 0x03FFFFFF */ -#define ADC_OFR1_OFFSET1 ADC_OFR1_OFFSET1_Msk /*!< ADC data offset 1 for channel programmed into bits OFFSET1_CH[4:0] */ -#define ADC_OFR1_OFFSET1_0 (0x0000001UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000001 */ -#define ADC_OFR1_OFFSET1_1 (0x0000002UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000002 */ -#define ADC_OFR1_OFFSET1_2 (0x0000004UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000004 */ -#define ADC_OFR1_OFFSET1_3 (0x0000008UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000008 */ -#define ADC_OFR1_OFFSET1_4 (0x0000010UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000010 */ -#define ADC_OFR1_OFFSET1_5 (0x0000020UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000020 */ -#define ADC_OFR1_OFFSET1_6 (0x0000040UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000040 */ -#define ADC_OFR1_OFFSET1_7 (0x0000080UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000080 */ -#define ADC_OFR1_OFFSET1_8 (0x0000100UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000100 */ -#define ADC_OFR1_OFFSET1_9 (0x0000200UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000200 */ -#define ADC_OFR1_OFFSET1_10 (0x0000400UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000400 */ -#define ADC_OFR1_OFFSET1_11 (0x0000800UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000800 */ -#define ADC_OFR1_OFFSET1_12 (0x0001000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00001000 */ -#define ADC_OFR1_OFFSET1_13 (0x0002000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00002000 */ -#define ADC_OFR1_OFFSET1_14 (0x0004000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00004000 */ -#define ADC_OFR1_OFFSET1_15 (0x0008000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00008000 */ -#define ADC_OFR1_OFFSET1_16 (0x0010000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00010000 */ -#define ADC_OFR1_OFFSET1_17 (0x0020000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00020000 */ -#define ADC_OFR1_OFFSET1_18 (0x0040000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00040000 */ -#define ADC_OFR1_OFFSET1_19 (0x0080000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00080000 */ -#define ADC_OFR1_OFFSET1_20 (0x0100000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00100000 */ -#define ADC_OFR1_OFFSET1_21 (0x0200000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00200000 */ -#define ADC_OFR1_OFFSET1_22 (0x0400000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00400000 */ -#define ADC_OFR1_OFFSET1_23 (0x0800000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00800000 */ -#define ADC_OFR1_OFFSET1_24 (0x1000000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x01000000 */ -#define ADC_OFR1_OFFSET1_25 (0x2000000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x02000000 */ - -#define ADC_OFR1_OFFSET1_CH_Pos (26U) -#define ADC_OFR1_OFFSET1_CH_Msk (0x1FUL << ADC_OFR1_OFFSET1_CH_Pos) /*!< 0x7C000000 */ -#define ADC_OFR1_OFFSET1_CH ADC_OFR1_OFFSET1_CH_Msk /*!< ADC Channel selection for the data offset 1 */ -#define ADC_OFR1_OFFSET1_CH_0 (0x01UL << ADC_OFR1_OFFSET1_CH_Pos) /*!< 0x04000000 */ -#define ADC_OFR1_OFFSET1_CH_1 (0x02UL << ADC_OFR1_OFFSET1_CH_Pos) /*!< 0x08000000 */ -#define ADC_OFR1_OFFSET1_CH_2 (0x04UL << ADC_OFR1_OFFSET1_CH_Pos) /*!< 0x10000000 */ -#define ADC_OFR1_OFFSET1_CH_3 (0x08UL << ADC_OFR1_OFFSET1_CH_Pos) /*!< 0x20000000 */ -#define ADC_OFR1_OFFSET1_CH_4 (0x10UL << ADC_OFR1_OFFSET1_CH_Pos) /*!< 0x40000000 */ - -#define ADC_OFR1_SSATE_Pos (31U) -#define ADC_OFR1_SSATE_Msk (0x1UL << ADC_OFR1_SSATE_Pos) /*!< 0x80000000 */ -#define ADC_OFR1_SSATE ADC_OFR1_SSATE_Msk /*!< ADC Signed saturation Enable */ - -#define ADC3_OFR1_OFFSET1_Pos (0U) -#define ADC3_OFR1_OFFSET1_Msk (0xFFFUL << ADC3_OFR1_OFFSET1_Pos) /*!< 0x00000FFF */ -#define ADC3_OFR1_OFFSET1 ADC3_OFR1_OFFSET1_Msk /*!< ADC data offset 1 for channel programmed into bits OFFSET1_CH[4:0] */ - -#define ADC3_OFR1_OFFSETPOS_Pos (24U) -#define ADC3_OFR1_OFFSETPOS_Msk (0x1UL << ADC3_OFR1_OFFSETPOS_Pos) /*!< 0x01000000 */ -#define ADC3_OFR1_OFFSETPOS ADC3_OFR1_OFFSETPOS_Msk /*!< ADC offset number 1 positive */ -#define ADC3_OFR1_SATEN_Pos (25U) -#define ADC3_OFR1_SATEN_Msk (0x1UL << ADC3_OFR1_SATEN_Pos) /*!< 0x02000000 */ -#define ADC3_OFR1_SATEN ADC3_OFR1_SATEN_Msk /*!< ADC offset number 1 saturation enable */ - -#define ADC3_OFR1_OFFSET1_EN_Pos (31U) -#define ADC3_OFR1_OFFSET1_EN_Msk (0x1UL << ADC3_OFR1_OFFSET1_EN_Pos) /*!< 0x80000000 */ -#define ADC3_OFR1_OFFSET1_EN ADC3_OFR1_OFFSET1_EN_Msk /*!< ADC offset number 1 enable */ - -/******************** Bit definition for ADC_OFR2 register ********************/ -#define ADC_OFR2_OFFSET2_Pos (0U) -#define ADC_OFR2_OFFSET2_Msk (0x3FFFFFFUL << ADC_OFR2_OFFSET2_Pos) /*!< 0x03FFFFFF */ -#define ADC_OFR2_OFFSET2 ADC_OFR2_OFFSET2_Msk /*!< ADC data offset 2 for channel programmed into bits OFFSET2_CH[4:0] */ -#define ADC_OFR2_OFFSET2_0 (0x0000001UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000001 */ -#define ADC_OFR2_OFFSET2_1 (0x0000002UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000002 */ -#define ADC_OFR2_OFFSET2_2 (0x0000004UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000004 */ -#define ADC_OFR2_OFFSET2_3 (0x0000008UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000008 */ -#define ADC_OFR2_OFFSET2_4 (0x0000010UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000010 */ -#define ADC_OFR2_OFFSET2_5 (0x0000020UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000020 */ -#define ADC_OFR2_OFFSET2_6 (0x0000040UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000040 */ -#define ADC_OFR2_OFFSET2_7 (0x0000080UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000080 */ -#define ADC_OFR2_OFFSET2_8 (0x0000100UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000100 */ -#define ADC_OFR2_OFFSET2_9 (0x0000200UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000200 */ -#define ADC_OFR2_OFFSET2_10 (0x0000400UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000400 */ -#define ADC_OFR2_OFFSET2_11 (0x0000800UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000800 */ -#define ADC_OFR2_OFFSET2_12 (0x0001000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00001000 */ -#define ADC_OFR2_OFFSET2_13 (0x0002000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00002000 */ -#define ADC_OFR2_OFFSET2_14 (0x0004000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00004000 */ -#define ADC_OFR2_OFFSET2_15 (0x0008000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00008000 */ -#define ADC_OFR2_OFFSET2_16 (0x0010000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00010000 */ -#define ADC_OFR2_OFFSET2_17 (0x0020000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00020000 */ -#define ADC_OFR2_OFFSET2_18 (0x0040000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00040000 */ -#define ADC_OFR2_OFFSET2_19 (0x0080000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00080000 */ -#define ADC_OFR2_OFFSET2_20 (0x0100000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00100000 */ -#define ADC_OFR2_OFFSET2_21 (0x0200000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00200000 */ -#define ADC_OFR2_OFFSET2_22 (0x0400000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00400000 */ -#define ADC_OFR2_OFFSET2_23 (0x0800000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00800000 */ -#define ADC_OFR2_OFFSET2_24 (0x1000000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x01000000 */ -#define ADC_OFR2_OFFSET2_25 (0x2000000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x02000000 */ - -#define ADC_OFR2_OFFSET2_CH_Pos (26U) -#define ADC_OFR2_OFFSET2_CH_Msk (0x1FUL << ADC_OFR2_OFFSET2_CH_Pos) /*!< 0x7C000000 */ -#define ADC_OFR2_OFFSET2_CH ADC_OFR2_OFFSET2_CH_Msk /*!< ADC Channel selection for the data offset 2 */ -#define ADC_OFR2_OFFSET2_CH_0 (0x01UL << ADC_OFR2_OFFSET2_CH_Pos) /*!< 0x04000000 */ -#define ADC_OFR2_OFFSET2_CH_1 (0x02UL << ADC_OFR2_OFFSET2_CH_Pos) /*!< 0x08000000 */ -#define ADC_OFR2_OFFSET2_CH_2 (0x04UL << ADC_OFR2_OFFSET2_CH_Pos) /*!< 0x10000000 */ -#define ADC_OFR2_OFFSET2_CH_3 (0x08UL << ADC_OFR2_OFFSET2_CH_Pos) /*!< 0x20000000 */ -#define ADC_OFR2_OFFSET2_CH_4 (0x10UL << ADC_OFR2_OFFSET2_CH_Pos) /*!< 0x40000000 */ - -#define ADC_OFR2_SSATE_Pos (31U) -#define ADC_OFR2_SSATE_Msk (0x1UL << ADC_OFR2_SSATE_Pos) /*!< 0x80000000 */ -#define ADC_OFR2_SSATE ADC_OFR2_SSATE_Msk /*!< ADC Signed saturation Enable */ - -#define ADC3_OFR2_OFFSET2_Pos (0U) -#define ADC3_OFR2_OFFSET2_Msk (0xFFFUL << ADC3_OFR2_OFFSET2_Pos) /*!< 0x00000FFF */ -#define ADC3_OFR2_OFFSET2 ADC3_OFR2_OFFSET2_Msk /*!< ADC data offset 2 for channel programmed into bits OFFSET1_CH[4:0] */ - -#define ADC3_OFR2_OFFSETPOS_Pos (24U) -#define ADC3_OFR2_OFFSETPOS_Msk (0x1UL << ADC3_OFR2_OFFSETPOS_Pos) /*!< 0x01000000 */ -#define ADC3_OFR2_OFFSETPOS ADC3_OFR2_OFFSETPOS_Msk /*!< ADC offset number 2 positive */ -#define ADC3_OFR2_SATEN_Pos (25U) -#define ADC3_OFR2_SATEN_Msk (0x1UL << ADC3_OFR2_SATEN_Pos) /*!< 0x02000000 */ -#define ADC3_OFR2_SATEN ADC3_OFR2_SATEN_Msk /*!< ADC offset number 2 saturation enable */ - -#define ADC3_OFR2_OFFSET2_EN_Pos (31U) -#define ADC3_OFR2_OFFSET2_EN_Msk (0x1UL << ADC3_OFR2_OFFSET2_EN_Pos) /*!< 0x80000000 */ -#define ADC3_OFR2_OFFSET2_EN ADC3_OFR2_OFFSET2_EN_Msk /*!< ADC offset number 2 enable */ - -/******************** Bit definition for ADC_OFR3 register ********************/ -#define ADC_OFR3_OFFSET3_Pos (0U) -#define ADC_OFR3_OFFSET3_Msk (0x3FFFFFFUL << ADC_OFR3_OFFSET3_Pos) /*!< 0x03FFFFFF */ -#define ADC_OFR3_OFFSET3 ADC_OFR3_OFFSET3_Msk /*!< ADC data offset 3 for channel programmed into bits OFFSET3_CH[4:0] */ -#define ADC_OFR3_OFFSET3_0 (0x0000001UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000001 */ -#define ADC_OFR3_OFFSET3_1 (0x0000002UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000002 */ -#define ADC_OFR3_OFFSET3_2 (0x0000004UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000004 */ -#define ADC_OFR3_OFFSET3_3 (0x0000008UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000008 */ -#define ADC_OFR3_OFFSET3_4 (0x0000010UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000010 */ -#define ADC_OFR3_OFFSET3_5 (0x0000020UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000020 */ -#define ADC_OFR3_OFFSET3_6 (0x0000040UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000040 */ -#define ADC_OFR3_OFFSET3_7 (0x0000080UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000080 */ -#define ADC_OFR3_OFFSET3_8 (0x0000100UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000100 */ -#define ADC_OFR3_OFFSET3_9 (0x0000200UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000200 */ -#define ADC_OFR3_OFFSET3_10 (0x0000400UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000400 */ -#define ADC_OFR3_OFFSET3_11 (0x0000800UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000800 */ -#define ADC_OFR3_OFFSET3_12 (0x0001000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00001000 */ -#define ADC_OFR3_OFFSET3_13 (0x0002000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00002000 */ -#define ADC_OFR3_OFFSET3_14 (0x0004000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00004000 */ -#define ADC_OFR3_OFFSET3_15 (0x0008000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00008000 */ -#define ADC_OFR3_OFFSET3_16 (0x0010000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00010000 */ -#define ADC_OFR3_OFFSET3_17 (0x0020000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00020000 */ -#define ADC_OFR3_OFFSET3_18 (0x0040000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00040000 */ -#define ADC_OFR3_OFFSET3_19 (0x0080000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00080000 */ -#define ADC_OFR3_OFFSET3_20 (0x0100000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00100000 */ -#define ADC_OFR3_OFFSET3_21 (0x0200000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00200000 */ -#define ADC_OFR3_OFFSET3_22 (0x0400000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00400000 */ -#define ADC_OFR3_OFFSET3_23 (0x0800000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00800000 */ -#define ADC_OFR3_OFFSET3_24 (0x1000000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x01000000 */ -#define ADC_OFR3_OFFSET3_25 (0x2000000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x02000000 */ - -#define ADC_OFR3_OFFSET3_CH_Pos (26U) -#define ADC_OFR3_OFFSET3_CH_Msk (0x1FUL << ADC_OFR3_OFFSET3_CH_Pos) /*!< 0x7C000000 */ -#define ADC_OFR3_OFFSET3_CH ADC_OFR3_OFFSET3_CH_Msk /*!< ADC Channel selection for the data offset 3 */ -#define ADC_OFR3_OFFSET3_CH_0 (0x01UL << ADC_OFR3_OFFSET3_CH_Pos) /*!< 0x04000000 */ -#define ADC_OFR3_OFFSET3_CH_1 (0x02UL << ADC_OFR3_OFFSET3_CH_Pos) /*!< 0x08000000 */ -#define ADC_OFR3_OFFSET3_CH_2 (0x04UL << ADC_OFR3_OFFSET3_CH_Pos) /*!< 0x10000000 */ -#define ADC_OFR3_OFFSET3_CH_3 (0x08UL << ADC_OFR3_OFFSET3_CH_Pos) /*!< 0x20000000 */ -#define ADC_OFR3_OFFSET3_CH_4 (0x10UL << ADC_OFR3_OFFSET3_CH_Pos) /*!< 0x40000000 */ - -#define ADC_OFR3_SSATE_Pos (31U) -#define ADC_OFR3_SSATE_Msk (0x1UL << ADC_OFR3_SSATE_Pos) /*!< 0x80000000 */ -#define ADC_OFR3_SSATE ADC_OFR3_SSATE_Msk /*!< ADC Signed saturation Enable */ - -#define ADC3_OFR3_OFFSET3_Pos (0U) -#define ADC3_OFR3_OFFSET3_Msk (0xFFFUL << ADC3_OFR3_OFFSET3_Pos) /*!< 0x00000FFF */ -#define ADC3_OFR3_OFFSET3 ADC3_OFR3_OFFSET3_Msk /*!< ADC data offset 3 for channel programmed into bits OFFSET1_CH[4:0] */ - -#define ADC3_OFR3_OFFSETPOS_Pos (24U) -#define ADC3_OFR3_OFFSETPOS_Msk (0x1UL << ADC3_OFR3_OFFSETPOS_Pos) /*!< 0x01000000 */ -#define ADC3_OFR3_OFFSETPOS ADC3_OFR3_OFFSETPOS_Msk /*!< ADC offset number 3 positive */ -#define ADC3_OFR3_SATEN_Pos (25U) -#define ADC3_OFR3_SATEN_Msk (0x1UL << ADC3_OFR3_SATEN_Pos) /*!< 0x02000000 */ -#define ADC3_OFR3_SATEN ADC3_OFR3_SATEN_Msk /*!< ADC offset number 3 saturation enable */ - -#define ADC3_OFR3_OFFSET3_EN_Pos (31U) -#define ADC3_OFR3_OFFSET3_EN_Msk (0x1UL << ADC3_OFR3_OFFSET3_EN_Pos) /*!< 0x80000000 */ -#define ADC3_OFR3_OFFSET3_EN ADC3_OFR3_OFFSET3_EN_Msk /*!< ADC offset number 3 enable */ - -/******************** Bit definition for ADC_OFR4 register ********************/ -#define ADC_OFR4_OFFSET4_Pos (0U) -#define ADC_OFR4_OFFSET4_Msk (0x3FFFFFFUL << ADC_OFR4_OFFSET4_Pos) /*!< 0x03FFFFFF */ -#define ADC_OFR4_OFFSET4 ADC_OFR4_OFFSET4_Msk /*!< ADC data offset 4 for channel programmed into bits OFFSET4_CH[4:0] */ -#define ADC_OFR4_OFFSET4_0 (0x0000001UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000001 */ -#define ADC_OFR4_OFFSET4_1 (0x0000002UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000002 */ -#define ADC_OFR4_OFFSET4_2 (0x0000004UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000004 */ -#define ADC_OFR4_OFFSET4_3 (0x0000008UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000008 */ -#define ADC_OFR4_OFFSET4_4 (0x0000010UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000010 */ -#define ADC_OFR4_OFFSET4_5 (0x0000020UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000020 */ -#define ADC_OFR4_OFFSET4_6 (0x0000040UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000040 */ -#define ADC_OFR4_OFFSET4_7 (0x0000080UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000080 */ -#define ADC_OFR4_OFFSET4_8 (0x0000100UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000100 */ -#define ADC_OFR4_OFFSET4_9 (0x0000200UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000200 */ -#define ADC_OFR4_OFFSET4_10 (0x0000400UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000400 */ -#define ADC_OFR4_OFFSET4_11 (0x0000800UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000800 */ -#define ADC_OFR4_OFFSET4_12 (0x0001000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00001000 */ -#define ADC_OFR4_OFFSET4_13 (0x0002000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00002000 */ -#define ADC_OFR4_OFFSET4_14 (0x0004000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00004000 */ -#define ADC_OFR4_OFFSET4_15 (0x0008000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00008000 */ -#define ADC_OFR4_OFFSET4_16 (0x0010000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00010000 */ -#define ADC_OFR4_OFFSET4_17 (0x0020000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00020000 */ -#define ADC_OFR4_OFFSET4_18 (0x0040000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00040000 */ -#define ADC_OFR4_OFFSET4_19 (0x0080000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00080000 */ -#define ADC_OFR4_OFFSET4_20 (0x0100000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00100000 */ -#define ADC_OFR4_OFFSET4_21 (0x0200000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00200000 */ -#define ADC_OFR4_OFFSET4_22 (0x0400000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00400000 */ -#define ADC_OFR4_OFFSET4_23 (0x0800000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00800000 */ -#define ADC_OFR4_OFFSET4_24 (0x1000000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x01000000 */ -#define ADC_OFR4_OFFSET4_25 (0x2000000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x02000000 */ - -#define ADC_OFR4_OFFSET4_CH_Pos (26U) -#define ADC_OFR4_OFFSET4_CH_Msk (0x1FUL << ADC_OFR4_OFFSET4_CH_Pos) /*!< 0x7C000000 */ -#define ADC_OFR4_OFFSET4_CH ADC_OFR4_OFFSET4_CH_Msk /*!< ADC Channel selection for the data offset 4 */ -#define ADC_OFR4_OFFSET4_CH_0 (0x01UL << ADC_OFR4_OFFSET4_CH_Pos) /*!< 0x04000000 */ -#define ADC_OFR4_OFFSET4_CH_1 (0x02UL << ADC_OFR4_OFFSET4_CH_Pos) /*!< 0x08000000 */ -#define ADC_OFR4_OFFSET4_CH_2 (0x04UL << ADC_OFR4_OFFSET4_CH_Pos) /*!< 0x10000000 */ -#define ADC_OFR4_OFFSET4_CH_3 (0x08UL << ADC_OFR4_OFFSET4_CH_Pos) /*!< 0x20000000 */ -#define ADC_OFR4_OFFSET4_CH_4 (0x10UL << ADC_OFR4_OFFSET4_CH_Pos) /*!< 0x40000000 */ - -#define ADC_OFR4_SSATE_Pos (31U) -#define ADC_OFR4_SSATE_Msk (0x1UL << ADC_OFR4_SSATE_Pos) /*!< 0x80000000 */ -#define ADC_OFR4_SSATE ADC_OFR4_SSATE_Msk /*!< ADC Signed saturation Enable */ - -#define ADC3_OFR4_OFFSET4_Pos (0U) -#define ADC3_OFR4_OFFSET4_Msk (0xFFFUL << ADC3_OFR4_OFFSET4_Pos) /*!< 0x00000FFF */ -#define ADC3_OFR4_OFFSET4 ADC3_OFR4_OFFSET4_Msk /*!< ADC data offset 4 for channel programmed into bits OFFSET1_CH[4:0] */ - -#define ADC3_OFR4_OFFSETPOS_Pos (24U) -#define ADC3_OFR4_OFFSETPOS_Msk (0x1UL << ADC3_OFR4_OFFSETPOS_Pos) /*!< 0x01000000 */ -#define ADC3_OFR4_OFFSETPOS ADC3_OFR4_OFFSETPOS_Msk /*!< ADC offset number 4 positive */ -#define ADC3_OFR4_SATEN_Pos (25U) -#define ADC3_OFR4_SATEN_Msk (0x1UL << ADC3_OFR4_SATEN_Pos) /*!< 0x02000000 */ -#define ADC3_OFR4_SATEN ADC3_OFR4_SATEN_Msk /*!< ADC offset number 4 saturation enable */ - -#define ADC3_OFR4_OFFSET4_EN_Pos (31U) -#define ADC3_OFR4_OFFSET4_EN_Msk (0x1UL << ADC3_OFR4_OFFSET4_EN_Pos) /*!< 0x80000000 */ -#define ADC3_OFR4_OFFSET4_EN ADC3_OFR4_OFFSET4_EN_Msk /*!< ADC offset number 4 enable */ - -/******************** Bit definition for ADC_JDR1 register ********************/ -#define ADC_JDR1_JDATA_Pos (0U) -#define ADC_JDR1_JDATA_Msk (0xFFFFFFFFUL << ADC_JDR1_JDATA_Pos) /*!< 0xFFFFFFFF */ -#define ADC_JDR1_JDATA ADC_JDR1_JDATA_Msk /*!< ADC Injected DATA */ -#define ADC_JDR1_JDATA_0 (0x00000001UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000001 */ -#define ADC_JDR1_JDATA_1 (0x00000002UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000002 */ -#define ADC_JDR1_JDATA_2 (0x00000004UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000004 */ -#define ADC_JDR1_JDATA_3 (0x00000008UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000008 */ -#define ADC_JDR1_JDATA_4 (0x00000010UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000010 */ -#define ADC_JDR1_JDATA_5 (0x00000020UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000020 */ -#define ADC_JDR1_JDATA_6 (0x00000040UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000040 */ -#define ADC_JDR1_JDATA_7 (0x00000080UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000080 */ -#define ADC_JDR1_JDATA_8 (0x00000100UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000100 */ -#define ADC_JDR1_JDATA_9 (0x00000200UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000200 */ -#define ADC_JDR1_JDATA_10 (0x00000400UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000400 */ -#define ADC_JDR1_JDATA_11 (0x00000800UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000800 */ -#define ADC_JDR1_JDATA_12 (0x00001000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00001000 */ -#define ADC_JDR1_JDATA_13 (0x00002000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00002000 */ -#define ADC_JDR1_JDATA_14 (0x00004000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00004000 */ -#define ADC_JDR1_JDATA_15 (0x00008000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00008000 */ -#define ADC_JDR1_JDATA_16 (0x00010000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00010000 */ -#define ADC_JDR1_JDATA_17 (0x00020000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00020000 */ -#define ADC_JDR1_JDATA_18 (0x00040000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00040000 */ -#define ADC_JDR1_JDATA_19 (0x00080000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00080000 */ -#define ADC_JDR1_JDATA_20 (0x00100000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00100000 */ -#define ADC_JDR1_JDATA_21 (0x00200000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00200000 */ -#define ADC_JDR1_JDATA_22 (0x00400000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00400000 */ -#define ADC_JDR1_JDATA_23 (0x00800000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00800000 */ -#define ADC_JDR1_JDATA_24 (0x01000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x01000000 */ -#define ADC_JDR1_JDATA_25 (0x02000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x02000000 */ -#define ADC_JDR1_JDATA_26 (0x04000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x04000000 */ -#define ADC_JDR1_JDATA_27 (0x08000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x08000000 */ -#define ADC_JDR1_JDATA_28 (0x10000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x10000000 */ -#define ADC_JDR1_JDATA_29 (0x20000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x20000000 */ -#define ADC_JDR1_JDATA_30 (0x40000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x40000000 */ -#define ADC_JDR1_JDATA_31 (0x80000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x80000000 */ - -/******************** Bit definition for ADC_JDR2 register ********************/ -#define ADC_JDR2_JDATA_Pos (0U) -#define ADC_JDR2_JDATA_Msk (0xFFFFFFFFUL << ADC_JDR2_JDATA_Pos) /*!< 0xFFFFFFFF */ -#define ADC_JDR2_JDATA ADC_JDR2_JDATA_Msk /*!< ADC Injected DATA */ -#define ADC_JDR2_JDATA_0 (0x00000001UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000001 */ -#define ADC_JDR2_JDATA_1 (0x00000002UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000002 */ -#define ADC_JDR2_JDATA_2 (0x00000004UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000004 */ -#define ADC_JDR2_JDATA_3 (0x00000008UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000008 */ -#define ADC_JDR2_JDATA_4 (0x00000010UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000010 */ -#define ADC_JDR2_JDATA_5 (0x00000020UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000020 */ -#define ADC_JDR2_JDATA_6 (0x00000040UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000040 */ -#define ADC_JDR2_JDATA_7 (0x00000080UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000080 */ -#define ADC_JDR2_JDATA_8 (0x00000100UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000100 */ -#define ADC_JDR2_JDATA_9 (0x00000200UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000200 */ -#define ADC_JDR2_JDATA_10 (0x00000400UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000400 */ -#define ADC_JDR2_JDATA_11 (0x00000800UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000800 */ -#define ADC_JDR2_JDATA_12 (0x00001000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00001000 */ -#define ADC_JDR2_JDATA_13 (0x00002000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00002000 */ -#define ADC_JDR2_JDATA_14 (0x00004000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00004000 */ -#define ADC_JDR2_JDATA_15 (0x00008000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00008000 */ -#define ADC_JDR2_JDATA_16 (0x00010000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00010000 */ -#define ADC_JDR2_JDATA_17 (0x00020000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00020000 */ -#define ADC_JDR2_JDATA_18 (0x00040000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00040000 */ -#define ADC_JDR2_JDATA_19 (0x00080000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00080000 */ -#define ADC_JDR2_JDATA_20 (0x00100000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00100000 */ -#define ADC_JDR2_JDATA_21 (0x00200000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00200000 */ -#define ADC_JDR2_JDATA_22 (0x00400000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00400000 */ -#define ADC_JDR2_JDATA_23 (0x00800000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00800000 */ -#define ADC_JDR2_JDATA_24 (0x01000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x01000000 */ -#define ADC_JDR2_JDATA_25 (0x02000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x02000000 */ -#define ADC_JDR2_JDATA_26 (0x04000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x04000000 */ -#define ADC_JDR2_JDATA_27 (0x08000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x08000000 */ -#define ADC_JDR2_JDATA_28 (0x10000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x10000000 */ -#define ADC_JDR2_JDATA_29 (0x20000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x20000000 */ -#define ADC_JDR2_JDATA_30 (0x40000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x40000000 */ -#define ADC_JDR2_JDATA_31 (0x80000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x80000000 */ - -/******************** Bit definition for ADC_JDR3 register ********************/ -#define ADC_JDR3_JDATA_Pos (0U) -#define ADC_JDR3_JDATA_Msk (0xFFFFFFFFUL << ADC_JDR3_JDATA_Pos) /*!< 0xFFFFFFFF */ -#define ADC_JDR3_JDATA ADC_JDR3_JDATA_Msk /*!< ADC Injected DATA */ -#define ADC_JDR3_JDATA_0 (0x00000001UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000001 */ -#define ADC_JDR3_JDATA_1 (0x00000002UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000002 */ -#define ADC_JDR3_JDATA_2 (0x00000004UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000004 */ -#define ADC_JDR3_JDATA_3 (0x00000008UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000008 */ -#define ADC_JDR3_JDATA_4 (0x00000010UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000010 */ -#define ADC_JDR3_JDATA_5 (0x00000020UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000020 */ -#define ADC_JDR3_JDATA_6 (0x00000040UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000040 */ -#define ADC_JDR3_JDATA_7 (0x00000080UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000080 */ -#define ADC_JDR3_JDATA_8 (0x00000100UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000100 */ -#define ADC_JDR3_JDATA_9 (0x00000200UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000200 */ -#define ADC_JDR3_JDATA_10 (0x00000400UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000400 */ -#define ADC_JDR3_JDATA_11 (0x00000800UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000800 */ -#define ADC_JDR3_JDATA_12 (0x00001000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00001000 */ -#define ADC_JDR3_JDATA_13 (0x00002000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00002000 */ -#define ADC_JDR3_JDATA_14 (0x00004000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00004000 */ -#define ADC_JDR3_JDATA_15 (0x00008000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00008000 */ -#define ADC_JDR3_JDATA_16 (0x00010000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00010000 */ -#define ADC_JDR3_JDATA_17 (0x00020000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00020000 */ -#define ADC_JDR3_JDATA_18 (0x00040000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00040000 */ -#define ADC_JDR3_JDATA_19 (0x00080000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00080000 */ -#define ADC_JDR3_JDATA_20 (0x00100000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00100000 */ -#define ADC_JDR3_JDATA_21 (0x00200000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00200000 */ -#define ADC_JDR3_JDATA_22 (0x00400000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00400000 */ -#define ADC_JDR3_JDATA_23 (0x00800000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00800000 */ -#define ADC_JDR3_JDATA_24 (0x01000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x01000000 */ -#define ADC_JDR3_JDATA_25 (0x02000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x02000000 */ -#define ADC_JDR3_JDATA_26 (0x04000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x04000000 */ -#define ADC_JDR3_JDATA_27 (0x08000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x08000000 */ -#define ADC_JDR3_JDATA_28 (0x10000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x10000000 */ -#define ADC_JDR3_JDATA_29 (0x20000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x20000000 */ -#define ADC_JDR3_JDATA_30 (0x40000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x40000000 */ -#define ADC_JDR3_JDATA_31 (0x80000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x80000000 */ - -/******************** Bit definition for ADC_JDR4 register ********************/ -#define ADC_JDR4_JDATA_Pos (0U) -#define ADC_JDR4_JDATA_Msk (0xFFFFFFFFUL << ADC_JDR4_JDATA_Pos) /*!< 0xFFFFFFFF */ -#define ADC_JDR4_JDATA ADC_JDR4_JDATA_Msk /*!< ADC Injected DATA */ -#define ADC_JDR4_JDATA_0 (0x00000001UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000001 */ -#define ADC_JDR4_JDATA_1 (0x00000002UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000002 */ -#define ADC_JDR4_JDATA_2 (0x00000004UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000004 */ -#define ADC_JDR4_JDATA_3 (0x00000008UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000008 */ -#define ADC_JDR4_JDATA_4 (0x00000010UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000010 */ -#define ADC_JDR4_JDATA_5 (0x00000020UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000020 */ -#define ADC_JDR4_JDATA_6 (0x00000040UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000040 */ -#define ADC_JDR4_JDATA_7 (0x00000080UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000080 */ -#define ADC_JDR4_JDATA_8 (0x00000100UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000100 */ -#define ADC_JDR4_JDATA_9 (0x00000200UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000200 */ -#define ADC_JDR4_JDATA_10 (0x00000400UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000400 */ -#define ADC_JDR4_JDATA_11 (0x00000800UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000800 */ -#define ADC_JDR4_JDATA_12 (0x00001000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00001000 */ -#define ADC_JDR4_JDATA_13 (0x00002000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00002000 */ -#define ADC_JDR4_JDATA_14 (0x00004000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00004000 */ -#define ADC_JDR4_JDATA_15 (0x00008000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00008000 */ -#define ADC_JDR4_JDATA_16 (0x00010000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00010000 */ -#define ADC_JDR4_JDATA_17 (0x00020000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00020000 */ -#define ADC_JDR4_JDATA_18 (0x00040000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00040000 */ -#define ADC_JDR4_JDATA_19 (0x00080000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00080000 */ -#define ADC_JDR4_JDATA_20 (0x00100000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00100000 */ -#define ADC_JDR4_JDATA_21 (0x00200000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00200000 */ -#define ADC_JDR4_JDATA_22 (0x00400000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00400000 */ -#define ADC_JDR4_JDATA_23 (0x00800000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00800000 */ -#define ADC_JDR4_JDATA_24 (0x01000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x01000000 */ -#define ADC_JDR4_JDATA_25 (0x02000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x02000000 */ -#define ADC_JDR4_JDATA_26 (0x04000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x04000000 */ -#define ADC_JDR4_JDATA_27 (0x08000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x08000000 */ -#define ADC_JDR4_JDATA_28 (0x10000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x10000000 */ -#define ADC_JDR4_JDATA_29 (0x20000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x20000000 */ -#define ADC_JDR4_JDATA_30 (0x40000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x40000000 */ -#define ADC_JDR4_JDATA_31 (0x80000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x80000000 */ - -/******************** Bit definition for ADC_AWD2CR register ********************/ -#define ADC_AWD2CR_AWD2CH_Pos (0U) -#define ADC_AWD2CR_AWD2CH_Msk (0xFFFFFUL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x000FFFFF */ -#define ADC_AWD2CR_AWD2CH ADC_AWD2CR_AWD2CH_Msk /*!< ADC Analog watchdog 2 channel selection */ -#define ADC_AWD2CR_AWD2CH_0 (0x00001UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000001 */ -#define ADC_AWD2CR_AWD2CH_1 (0x00002UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000002 */ -#define ADC_AWD2CR_AWD2CH_2 (0x00004UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000004 */ -#define ADC_AWD2CR_AWD2CH_3 (0x00008UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000008 */ -#define ADC_AWD2CR_AWD2CH_4 (0x00010UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000010 */ -#define ADC_AWD2CR_AWD2CH_5 (0x00020UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000020 */ -#define ADC_AWD2CR_AWD2CH_6 (0x00040UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000040 */ -#define ADC_AWD2CR_AWD2CH_7 (0x00080UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000080 */ -#define ADC_AWD2CR_AWD2CH_8 (0x00100UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000100 */ -#define ADC_AWD2CR_AWD2CH_9 (0x00200UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000200 */ -#define ADC_AWD2CR_AWD2CH_10 (0x00400UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000400 */ -#define ADC_AWD2CR_AWD2CH_11 (0x00800UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000800 */ -#define ADC_AWD2CR_AWD2CH_12 (0x01000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00001000 */ -#define ADC_AWD2CR_AWD2CH_13 (0x02000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00002000 */ -#define ADC_AWD2CR_AWD2CH_14 (0x04000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00004000 */ -#define ADC_AWD2CR_AWD2CH_15 (0x08000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00008000 */ -#define ADC_AWD2CR_AWD2CH_16 (0x10000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00010000 */ -#define ADC_AWD2CR_AWD2CH_17 (0x20000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00020000 */ -#define ADC_AWD2CR_AWD2CH_18 (0x40000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00040000 */ -#define ADC_AWD2CR_AWD2CH_19 (0x80000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00080000 */ - -/******************** Bit definition for ADC_AWD3CR register ********************/ -#define ADC_AWD3CR_AWD3CH_Pos (0U) -#define ADC_AWD3CR_AWD3CH_Msk (0xFFFFFUL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x000FFFFF */ -#define ADC_AWD3CR_AWD3CH ADC_AWD3CR_AWD3CH_Msk /*!< ADC Analog watchdog 2 channel selection */ -#define ADC_AWD3CR_AWD3CH_0 (0x00001UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000001 */ -#define ADC_AWD3CR_AWD3CH_1 (0x00002UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000002 */ -#define ADC_AWD3CR_AWD3CH_2 (0x00004UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000004 */ -#define ADC_AWD3CR_AWD3CH_3 (0x00008UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000008 */ -#define ADC_AWD3CR_AWD3CH_4 (0x00010UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000010 */ -#define ADC_AWD3CR_AWD3CH_5 (0x00020UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000020 */ -#define ADC_AWD3CR_AWD3CH_6 (0x00040UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000040 */ -#define ADC_AWD3CR_AWD3CH_7 (0x00080UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000080 */ -#define ADC_AWD3CR_AWD3CH_8 (0x00100UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000100 */ -#define ADC_AWD3CR_AWD3CH_9 (0x00200UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000200 */ -#define ADC_AWD3CR_AWD3CH_10 (0x00400UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000400 */ -#define ADC_AWD3CR_AWD3CH_11 (0x00800UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000800 */ -#define ADC_AWD3CR_AWD3CH_12 (0x01000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00001000 */ -#define ADC_AWD3CR_AWD3CH_13 (0x02000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00002000 */ -#define ADC_AWD3CR_AWD3CH_14 (0x04000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00004000 */ -#define ADC_AWD3CR_AWD3CH_15 (0x08000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00008000 */ -#define ADC_AWD3CR_AWD3CH_16 (0x10000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00010000 */ -#define ADC_AWD3CR_AWD3CH_17 (0x20000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00020000 */ -#define ADC_AWD3CR_AWD3CH_18 (0x40000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00040000 */ -#define ADC_AWD3CR_AWD3CH_19 (0x80000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00080000 */ - -/******************** Bit definition for ADC_DIFSEL register ********************/ -#define ADC_DIFSEL_DIFSEL_Pos (0U) -#define ADC_DIFSEL_DIFSEL_Msk (0xFFFFFUL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x000FFFFF */ -#define ADC_DIFSEL_DIFSEL ADC_DIFSEL_DIFSEL_Msk /*!< ADC differential modes for channels 1 to 18 */ -#define ADC_DIFSEL_DIFSEL_0 (0x00001UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000001 */ -#define ADC_DIFSEL_DIFSEL_1 (0x00002UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000002 */ -#define ADC_DIFSEL_DIFSEL_2 (0x00004UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000004 */ -#define ADC_DIFSEL_DIFSEL_3 (0x00008UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000008 */ -#define ADC_DIFSEL_DIFSEL_4 (0x00010UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000010 */ -#define ADC_DIFSEL_DIFSEL_5 (0x00020UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000020 */ -#define ADC_DIFSEL_DIFSEL_6 (0x00040UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000040 */ -#define ADC_DIFSEL_DIFSEL_7 (0x00080UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000080 */ -#define ADC_DIFSEL_DIFSEL_8 (0x00100UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000100 */ -#define ADC_DIFSEL_DIFSEL_9 (0x00200UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000200 */ -#define ADC_DIFSEL_DIFSEL_10 (0x00400UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000400 */ -#define ADC_DIFSEL_DIFSEL_11 (0x00800UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000800 */ -#define ADC_DIFSEL_DIFSEL_12 (0x01000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00001000 */ -#define ADC_DIFSEL_DIFSEL_13 (0x02000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00002000 */ -#define ADC_DIFSEL_DIFSEL_14 (0x04000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00004000 */ -#define ADC_DIFSEL_DIFSEL_15 (0x08000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00008000 */ -#define ADC_DIFSEL_DIFSEL_16 (0x10000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00010000 */ -#define ADC_DIFSEL_DIFSEL_17 (0x20000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00020000 */ -#define ADC_DIFSEL_DIFSEL_18 (0x40000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00040000 */ -#define ADC_DIFSEL_DIFSEL_19 (0x80000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00080000 */ - -/******************** Bit definition for ADC_CALFACT register ********************/ -#define ADC_CALFACT_CALFACT_S_Pos (0U) -#define ADC_CALFACT_CALFACT_S_Msk (0x7FFUL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x000007FF */ -#define ADC_CALFACT_CALFACT_S ADC_CALFACT_CALFACT_S_Msk /*!< ADC calibration factors in single-ended mode */ -#define ADC_CALFACT_CALFACT_S_0 (0x001UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000001 */ -#define ADC_CALFACT_CALFACT_S_1 (0x002UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000002 */ -#define ADC_CALFACT_CALFACT_S_2 (0x004UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000004 */ -#define ADC_CALFACT_CALFACT_S_3 (0x008UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000008 */ -#define ADC_CALFACT_CALFACT_S_4 (0x010UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000010 */ -#define ADC_CALFACT_CALFACT_S_5 (0x020UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000020 */ -#define ADC_CALFACT_CALFACT_S_6 (0x040UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000040 */ -#define ADC_CALFACT_CALFACT_S_7 (0x080UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000080 */ -#define ADC_CALFACT_CALFACT_S_8 (0x100UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000100 */ -#define ADC_CALFACT_CALFACT_S_9 (0x200UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000200 */ -#define ADC_CALFACT_CALFACT_S_10 (0x400UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000400 */ -#define ADC_CALFACT_CALFACT_D_Pos (16U) -#define ADC_CALFACT_CALFACT_D_Msk (0x7FFUL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x07FF0000 */ -#define ADC_CALFACT_CALFACT_D ADC_CALFACT_CALFACT_D_Msk /*!< ADC calibration factors in differential mode */ -#define ADC_CALFACT_CALFACT_D_0 (0x001UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00010000 */ -#define ADC_CALFACT_CALFACT_D_1 (0x002UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00020000 */ -#define ADC_CALFACT_CALFACT_D_2 (0x004UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00040000 */ -#define ADC_CALFACT_CALFACT_D_3 (0x008UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00080000 */ -#define ADC_CALFACT_CALFACT_D_4 (0x010UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00100000 */ -#define ADC_CALFACT_CALFACT_D_5 (0x020UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00200000 */ -#define ADC_CALFACT_CALFACT_D_6 (0x040UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00400000 */ -#define ADC_CALFACT_CALFACT_D_7 (0x080UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00800000 */ -#define ADC_CALFACT_CALFACT_D_8 (0x100UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x01000000 */ -#define ADC_CALFACT_CALFACT_D_9 (0x200UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x02000000 */ -#define ADC_CALFACT_CALFACT_D_10 (0x400UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x04000000 */ - -/******************** Bit definition for ADC_CALFACT2 register ********************/ -#define ADC_CALFACT2_LINCALFACT_Pos (0U) -#define ADC_CALFACT2_LINCALFACT_Msk (0x3FFFFFFFUL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x3FFFFFFF */ -#define ADC_CALFACT2_LINCALFACT ADC_CALFACT2_LINCALFACT_Msk /*!< ADC Linearity calibration factors */ -#define ADC_CALFACT2_LINCALFACT_0 (0x00000001UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000001 */ -#define ADC_CALFACT2_LINCALFACT_1 (0x00000002UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000002 */ -#define ADC_CALFACT2_LINCALFACT_2 (0x00000004UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000004 */ -#define ADC_CALFACT2_LINCALFACT_3 (0x00000008UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000008 */ -#define ADC_CALFACT2_LINCALFACT_4 (0x00000010UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000010 */ -#define ADC_CALFACT2_LINCALFACT_5 (0x00000020UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000020 */ -#define ADC_CALFACT2_LINCALFACT_6 (0x00000040UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000040 */ -#define ADC_CALFACT2_LINCALFACT_7 (0x00000080UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000080 */ -#define ADC_CALFACT2_LINCALFACT_8 (0x00000100UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000100 */ -#define ADC_CALFACT2_LINCALFACT_9 (0x00000200UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000200 */ -#define ADC_CALFACT2_LINCALFACT_10 (0x00000400UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000400 */ -#define ADC_CALFACT2_LINCALFACT_11 (0x00000800UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000800 */ -#define ADC_CALFACT2_LINCALFACT_12 (0x00001000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00001000 */ -#define ADC_CALFACT2_LINCALFACT_13 (0x00002000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00002000 */ -#define ADC_CALFACT2_LINCALFACT_14 (0x00004000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00004000 */ -#define ADC_CALFACT2_LINCALFACT_15 (0x00008000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00008000 */ -#define ADC_CALFACT2_LINCALFACT_16 (0x00010000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00010000 */ -#define ADC_CALFACT2_LINCALFACT_17 (0x00020000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00020000 */ -#define ADC_CALFACT2_LINCALFACT_18 (0x00040000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00040000 */ -#define ADC_CALFACT2_LINCALFACT_19 (0x00080000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00080000 */ -#define ADC_CALFACT2_LINCALFACT_20 (0x00100000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00100000 */ -#define ADC_CALFACT2_LINCALFACT_21 (0x00200000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00200000 */ -#define ADC_CALFACT2_LINCALFACT_22 (0x00400000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00400000 */ -#define ADC_CALFACT2_LINCALFACT_23 (0x00800000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00800000 */ -#define ADC_CALFACT2_LINCALFACT_24 (0x01000000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x01000000 */ -#define ADC_CALFACT2_LINCALFACT_25 (0x02000000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x02000000 */ -#define ADC_CALFACT2_LINCALFACT_26 (0x04000000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x04000000 */ -#define ADC_CALFACT2_LINCALFACT_27 (0x08000000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x08000000 */ -#define ADC_CALFACT2_LINCALFACT_28 (0x10000000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x10000000 */ -#define ADC_CALFACT2_LINCALFACT_29 (0x20000000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x20000000 */ - -/************************* ADC Common registers *****************************/ -/******************** Bit definition for ADC_CSR register ********************/ -#define ADC_CSR_ADRDY_MST_Pos (0U) -#define ADC_CSR_ADRDY_MST_Msk (0x1UL << ADC_CSR_ADRDY_MST_Pos) /*!< 0x00000001 */ -#define ADC_CSR_ADRDY_MST ADC_CSR_ADRDY_MST_Msk /*!< Master ADC ready */ -#define ADC_CSR_EOSMP_MST_Pos (1U) -#define ADC_CSR_EOSMP_MST_Msk (0x1UL << ADC_CSR_EOSMP_MST_Pos) /*!< 0x00000002 */ -#define ADC_CSR_EOSMP_MST ADC_CSR_EOSMP_MST_Msk /*!< End of sampling phase flag of the master ADC */ -#define ADC_CSR_EOC_MST_Pos (2U) -#define ADC_CSR_EOC_MST_Msk (0x1UL << ADC_CSR_EOC_MST_Pos) /*!< 0x00000004 */ -#define ADC_CSR_EOC_MST ADC_CSR_EOC_MST_Msk /*!< End of regular conversion of the master ADC */ -#define ADC_CSR_EOS_MST_Pos (3U) -#define ADC_CSR_EOS_MST_Msk (0x1UL << ADC_CSR_EOS_MST_Pos) /*!< 0x00000008 */ -#define ADC_CSR_EOS_MST ADC_CSR_EOS_MST_Msk /*!< End of regular sequence flag of the master ADC */ -#define ADC_CSR_OVR_MST_Pos (4U) -#define ADC_CSR_OVR_MST_Msk (0x1UL << ADC_CSR_OVR_MST_Pos) /*!< 0x00000010 */ -#define ADC_CSR_OVR_MST ADC_CSR_OVR_MST_Msk /*!< Overrun flag of the master ADC */ -#define ADC_CSR_JEOC_MST_Pos (5U) -#define ADC_CSR_JEOC_MST_Msk (0x1UL << ADC_CSR_JEOC_MST_Pos) /*!< 0x00000020 */ -#define ADC_CSR_JEOC_MST ADC_CSR_JEOC_MST_Msk /*!< End of injected conversion of the master ADC */ -#define ADC_CSR_JEOS_MST_Pos (6U) -#define ADC_CSR_JEOS_MST_Msk (0x1UL << ADC_CSR_JEOS_MST_Pos) /*!< 0x00000040 */ -#define ADC_CSR_JEOS_MST ADC_CSR_JEOS_MST_Msk /*!< End of injected sequence flag of the master ADC */ -#define ADC_CSR_AWD1_MST_Pos (7U) -#define ADC_CSR_AWD1_MST_Msk (0x1UL << ADC_CSR_AWD1_MST_Pos) /*!< 0x00000080 */ -#define ADC_CSR_AWD1_MST ADC_CSR_AWD1_MST_Msk /*!< Analog watchdog 1 flag of the master ADC */ -#define ADC_CSR_AWD2_MST_Pos (8U) -#define ADC_CSR_AWD2_MST_Msk (0x1UL << ADC_CSR_AWD2_MST_Pos) /*!< 0x00000100 */ -#define ADC_CSR_AWD2_MST ADC_CSR_AWD2_MST_Msk /*!< Analog watchdog 2 flag of the master ADC */ -#define ADC_CSR_AWD3_MST_Pos (9U) -#define ADC_CSR_AWD3_MST_Msk (0x1UL << ADC_CSR_AWD3_MST_Pos) /*!< 0x00000200 */ -#define ADC_CSR_AWD3_MST ADC_CSR_AWD3_MST_Msk /*!< Analog watchdog 3 flag of the master ADC */ -#define ADC_CSR_JQOVF_MST_Pos (10U) -#define ADC_CSR_JQOVF_MST_Msk (0x1UL << ADC_CSR_JQOVF_MST_Pos) /*!< 0x00000400 */ -#define ADC_CSR_JQOVF_MST ADC_CSR_JQOVF_MST_Msk /*!< Injected context queue overflow flag of the master ADC */ -#define ADC_CSR_ADRDY_SLV_Pos (16U) -#define ADC_CSR_ADRDY_SLV_Msk (0x1UL << ADC_CSR_ADRDY_SLV_Pos) /*!< 0x00010000 */ -#define ADC_CSR_ADRDY_SLV ADC_CSR_ADRDY_SLV_Msk /*!< Slave ADC ready */ -#define ADC_CSR_EOSMP_SLV_Pos (17U) -#define ADC_CSR_EOSMP_SLV_Msk (0x1UL << ADC_CSR_EOSMP_SLV_Pos) /*!< 0x00020000 */ -#define ADC_CSR_EOSMP_SLV ADC_CSR_EOSMP_SLV_Msk /*!< End of sampling phase flag of the slave ADC */ -#define ADC_CSR_EOC_SLV_Pos (18U) -#define ADC_CSR_EOC_SLV_Msk (0x1UL << ADC_CSR_EOC_SLV_Pos) /*!< 0x00040000 */ -#define ADC_CSR_EOC_SLV ADC_CSR_EOC_SLV_Msk /*!< End of regular conversion of the slave ADC */ -#define ADC_CSR_EOS_SLV_Pos (19U) -#define ADC_CSR_EOS_SLV_Msk (0x1UL << ADC_CSR_EOS_SLV_Pos) /*!< 0x00080000 */ -#define ADC_CSR_EOS_SLV ADC_CSR_EOS_SLV_Msk /*!< End of regular sequence flag of the slave ADC */ -#define ADC_CSR_OVR_SLV_Pos (20U) -#define ADC_CSR_OVR_SLV_Msk (0x1UL << ADC_CSR_OVR_SLV_Pos) /*!< 0x00100000 */ -#define ADC_CSR_OVR_SLV ADC_CSR_OVR_SLV_Msk /*!< Overrun flag of the slave ADC */ -#define ADC_CSR_JEOC_SLV_Pos (21U) -#define ADC_CSR_JEOC_SLV_Msk (0x1UL << ADC_CSR_JEOC_SLV_Pos) /*!< 0x00200000 */ -#define ADC_CSR_JEOC_SLV ADC_CSR_JEOC_SLV_Msk /*!< End of injected conversion of the slave ADC */ -#define ADC_CSR_JEOS_SLV_Pos (22U) -#define ADC_CSR_JEOS_SLV_Msk (0x1UL << ADC_CSR_JEOS_SLV_Pos) /*!< 0x00400000 */ -#define ADC_CSR_JEOS_SLV ADC_CSR_JEOS_SLV_Msk /*!< End of injected sequence flag of the slave ADC */ -#define ADC_CSR_AWD1_SLV_Pos (23U) -#define ADC_CSR_AWD1_SLV_Msk (0x1UL << ADC_CSR_AWD1_SLV_Pos) /*!< 0x00800000 */ -#define ADC_CSR_AWD1_SLV ADC_CSR_AWD1_SLV_Msk /*!< Analog watchdog 1 flag of the slave ADC */ -#define ADC_CSR_AWD2_SLV_Pos (24U) -#define ADC_CSR_AWD2_SLV_Msk (0x1UL << ADC_CSR_AWD2_SLV_Pos) /*!< 0x01000000 */ -#define ADC_CSR_AWD2_SLV ADC_CSR_AWD2_SLV_Msk /*!< Analog watchdog 2 flag of the slave ADC */ -#define ADC_CSR_AWD3_SLV_Pos (25U) -#define ADC_CSR_AWD3_SLV_Msk (0x1UL << ADC_CSR_AWD3_SLV_Pos) /*!< 0x02000000 */ -#define ADC_CSR_AWD3_SLV ADC_CSR_AWD3_SLV_Msk /*!< Analog watchdog 3 flag of the slave ADC */ -#define ADC_CSR_JQOVF_SLV_Pos (26U) -#define ADC_CSR_JQOVF_SLV_Msk (0x1UL << ADC_CSR_JQOVF_SLV_Pos) /*!< 0x04000000 */ -#define ADC_CSR_JQOVF_SLV ADC_CSR_JQOVF_SLV_Msk /*!< Injected context queue overflow flag of the slave ADC */ - -/******************** Bit definition for ADC_CCR register ********************/ -#define ADC_CCR_DUAL_Pos (0U) -#define ADC_CCR_DUAL_Msk (0x1FUL << ADC_CCR_DUAL_Pos) /*!< 0x0000001F */ -#define ADC_CCR_DUAL ADC_CCR_DUAL_Msk /*!< Dual ADC mode selection */ -#define ADC_CCR_DUAL_0 (0x01UL << ADC_CCR_DUAL_Pos) /*!< 0x00000001 */ -#define ADC_CCR_DUAL_1 (0x02UL << ADC_CCR_DUAL_Pos) /*!< 0x00000002 */ -#define ADC_CCR_DUAL_2 (0x04UL << ADC_CCR_DUAL_Pos) /*!< 0x00000004 */ -#define ADC_CCR_DUAL_3 (0x08UL << ADC_CCR_DUAL_Pos) /*!< 0x00000008 */ -#define ADC_CCR_DUAL_4 (0x10UL << ADC_CCR_DUAL_Pos) /*!< 0x00000010 */ - -#define ADC_CCR_DELAY_Pos (8U) -#define ADC_CCR_DELAY_Msk (0xFUL << ADC_CCR_DELAY_Pos) /*!< 0x00000F00 */ -#define ADC_CCR_DELAY ADC_CCR_DELAY_Msk /*!< Delay between 2 sampling phases */ -#define ADC_CCR_DELAY_0 (0x1UL << ADC_CCR_DELAY_Pos) /*!< 0x00000100 */ -#define ADC_CCR_DELAY_1 (0x2UL << ADC_CCR_DELAY_Pos) /*!< 0x00000200 */ -#define ADC_CCR_DELAY_2 (0x4UL << ADC_CCR_DELAY_Pos) /*!< 0x00000400 */ -#define ADC_CCR_DELAY_3 (0x8UL << ADC_CCR_DELAY_Pos) /*!< 0x00000800 */ - - -#define ADC_CCR_DAMDF_Pos (14U) -#define ADC_CCR_DAMDF_Msk (0x3UL << ADC_CCR_DAMDF_Pos) /*!< 0x0000C000 */ -#define ADC_CCR_DAMDF ADC_CCR_DAMDF_Msk /*!< Dual ADC mode Data format */ -#define ADC_CCR_DAMDF_0 (0x1UL << ADC_CCR_DAMDF_Pos) /*!< 0x00004000 */ -#define ADC_CCR_DAMDF_1 (0x2UL << ADC_CCR_DAMDF_Pos) /*!< 0x00008000 */ - -#define ADC_CCR_CKMODE_Pos (16U) -#define ADC_CCR_CKMODE_Msk (0x3UL << ADC_CCR_CKMODE_Pos) /*!< 0x00030000 */ -#define ADC_CCR_CKMODE ADC_CCR_CKMODE_Msk /*!< ADC clock mode */ -#define ADC_CCR_CKMODE_0 (0x1UL << ADC_CCR_CKMODE_Pos) /*!< 0x00010000 */ -#define ADC_CCR_CKMODE_1 (0x2UL << ADC_CCR_CKMODE_Pos) /*!< 0x00020000 */ - -#define ADC_CCR_PRESC_Pos (18U) -#define ADC_CCR_PRESC_Msk (0xFUL << ADC_CCR_PRESC_Pos) /*!< 0x003C0000 */ -#define ADC_CCR_PRESC ADC_CCR_PRESC_Msk /*!< ADC prescaler */ -#define ADC_CCR_PRESC_0 (0x1UL << ADC_CCR_PRESC_Pos) /*!< 0x00040000 */ -#define ADC_CCR_PRESC_1 (0x2UL << ADC_CCR_PRESC_Pos) /*!< 0x00080000 */ -#define ADC_CCR_PRESC_2 (0x4UL << ADC_CCR_PRESC_Pos) /*!< 0x00100000 */ -#define ADC_CCR_PRESC_3 (0x8UL << ADC_CCR_PRESC_Pos) /*!< 0x00200000 */ - -#define ADC_CCR_VREFEN_Pos (22U) -#define ADC_CCR_VREFEN_Msk (0x1UL << ADC_CCR_VREFEN_Pos) /*!< 0x00400000 */ -#define ADC_CCR_VREFEN ADC_CCR_VREFEN_Msk /*!< VREFINT enable */ -#define ADC_CCR_TSEN_Pos (23U) -#define ADC_CCR_TSEN_Msk (0x1UL << ADC_CCR_TSEN_Pos) /*!< 0x00800000 */ -#define ADC_CCR_TSEN ADC_CCR_TSEN_Msk /*!< Temperature sensor enable */ -#define ADC_CCR_VBATEN_Pos (24U) -#define ADC_CCR_VBATEN_Msk (0x1UL << ADC_CCR_VBATEN_Pos) /*!< 0x01000000 */ -#define ADC_CCR_VBATEN ADC_CCR_VBATEN_Msk /*!< VBAT enable */ - -/******************** Bit definition for ADC_CDR register *******************/ -#define ADC_CDR_RDATA_MST_Pos (0U) -#define ADC_CDR_RDATA_MST_Msk (0xFFFFUL << ADC_CDR_RDATA_MST_Pos) /*!< 0x0000FFFF */ -#define ADC_CDR_RDATA_MST ADC_CDR_RDATA_MST_Msk /*!< ADC multimode master group regular conversion data */ - -#define ADC_CDR_RDATA_SLV_Pos (16U) -#define ADC_CDR_RDATA_SLV_Msk (0xFFFFUL << ADC_CDR_RDATA_SLV_Pos) /*!< 0xFFFF0000 */ -#define ADC_CDR_RDATA_SLV ADC_CDR_RDATA_SLV_Msk /*!< ADC multimode slave group regular conversion data */ - -/******************** Bit definition for ADC_CDR2 register ******************/ -#define ADC_CDR2_RDATA_ALT_Pos (0U) -#define ADC_CDR2_RDATA_ALT_Msk (0xFFFFFFFFUL << ADC_CDR2_RDATA_ALT_Pos) /*!< 0xFFFFFFFF */ -#define ADC_CDR2_RDATA_ALT ADC_CDR2_RDATA_ALT_Msk /*!< Regular data of the master/slave alternated ADCs */ - - -/******************************************************************************/ -/* */ -/* VREFBUF */ -/* */ -/******************************************************************************/ -/******************* Bit definition for VREFBUF_CSR register ****************/ -#define VREFBUF_CSR_ENVR_Pos (0U) -#define VREFBUF_CSR_ENVR_Msk (0x1UL << VREFBUF_CSR_ENVR_Pos) /*!< 0x00000001 */ -#define VREFBUF_CSR_ENVR VREFBUF_CSR_ENVR_Msk /*!*/ -#define DAC_CR_CEN1_Pos (14U) -#define DAC_CR_CEN1_Msk (0x1UL << DAC_CR_CEN1_Pos) /*!< 0x00004000 */ -#define DAC_CR_CEN1 DAC_CR_CEN1_Msk /*!*/ - -#define DAC_CR_EN2_Pos (16U) -#define DAC_CR_EN2_Msk (0x1UL << DAC_CR_EN2_Pos) /*!< 0x00010000 */ -#define DAC_CR_EN2 DAC_CR_EN2_Msk /*!*/ -#define DAC_CR_CEN2_Pos (30U) -#define DAC_CR_CEN2_Msk (0x1UL << DAC_CR_CEN2_Pos) /*!< 0x40000000 */ -#define DAC_CR_CEN2 DAC_CR_CEN2_Msk /*!*/ - -/***************** Bit definition for DAC_SWTRIGR register ******************/ -#define DAC_SWTRIGR_SWTRIG1_Pos (0U) -#define DAC_SWTRIGR_SWTRIG1_Msk (0x1UL << DAC_SWTRIGR_SWTRIG1_Pos) /*!< 0x00000001 */ -#define DAC_SWTRIGR_SWTRIG1 DAC_SWTRIGR_SWTRIG1_Msk /*!
© Copyright (c) 2019 STMicroelectronics. - * All rights reserved.
- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/** @addtogroup CMSIS_Device - * @{ - */ - -/** @addtogroup stm32h735xx - * @{ - */ - -#ifndef STM32H735xx_H -#define STM32H735xx_H - -#ifdef __cplusplus - extern "C" { -#endif /* __cplusplus */ - -/** @addtogroup Peripheral_interrupt_number_definition - * @{ - */ - -/** - * @brief STM32H7XX Interrupt Number Definition, according to the selected device - * in @ref Library_configuration_section - */ -typedef enum -{ -/****** Cortex-M Processor Exceptions Numbers *****************************************************************/ - NonMaskableInt_IRQn = -14, /*!< 2 Non Maskable Interrupt */ - HardFault_IRQn = -13, /*!< 4 Cortex-M Memory Management Interrupt */ - MemoryManagement_IRQn = -12, /*!< 4 Cortex-M Memory Management Interrupt */ - BusFault_IRQn = -11, /*!< 5 Cortex-M Bus Fault Interrupt */ - UsageFault_IRQn = -10, /*!< 6 Cortex-M Usage Fault Interrupt */ - SVCall_IRQn = -5, /*!< 11 Cortex-M SV Call Interrupt */ - DebugMonitor_IRQn = -4, /*!< 12 Cortex-M Debug Monitor Interrupt */ - PendSV_IRQn = -2, /*!< 14 Cortex-M Pend SV Interrupt */ - SysTick_IRQn = -1, /*!< 15 Cortex-M System Tick Interrupt */ -/****** STM32 specific Interrupt Numbers **********************************************************************/ - WWDG_IRQn = 0, /*!< Window WatchDog Interrupt ( wwdg1_it, wwdg2_it) */ - PVD_AVD_IRQn = 1, /*!< PVD/AVD through EXTI Line detection Interrupt */ - TAMP_STAMP_IRQn = 2, /*!< Tamper and TimeStamp interrupts through the EXTI line */ - RTC_WKUP_IRQn = 3, /*!< RTC Wakeup interrupt through the EXTI line */ - FLASH_IRQn = 4, /*!< FLASH global Interrupt */ - RCC_IRQn = 5, /*!< RCC global Interrupt */ - EXTI0_IRQn = 6, /*!< EXTI Line0 Interrupt */ - EXTI1_IRQn = 7, /*!< EXTI Line1 Interrupt */ - EXTI2_IRQn = 8, /*!< EXTI Line2 Interrupt */ - EXTI3_IRQn = 9, /*!< EXTI Line3 Interrupt */ - EXTI4_IRQn = 10, /*!< EXTI Line4 Interrupt */ - DMA1_Stream0_IRQn = 11, /*!< DMA1 Stream 0 global Interrupt */ - DMA1_Stream1_IRQn = 12, /*!< DMA1 Stream 1 global Interrupt */ - DMA1_Stream2_IRQn = 13, /*!< DMA1 Stream 2 global Interrupt */ - DMA1_Stream3_IRQn = 14, /*!< DMA1 Stream 3 global Interrupt */ - DMA1_Stream4_IRQn = 15, /*!< DMA1 Stream 4 global Interrupt */ - DMA1_Stream5_IRQn = 16, /*!< DMA1 Stream 5 global Interrupt */ - DMA1_Stream6_IRQn = 17, /*!< DMA1 Stream 6 global Interrupt */ - ADC_IRQn = 18, /*!< ADC1 and ADC2 global Interrupts */ - FDCAN1_IT0_IRQn = 19, /*!< FDCAN1 Interrupt line 0 */ - FDCAN2_IT0_IRQn = 20, /*!< FDCAN2 Interrupt line 0 */ - FDCAN1_IT1_IRQn = 21, /*!< FDCAN1 Interrupt line 1 */ - FDCAN2_IT1_IRQn = 22, /*!< FDCAN2 Interrupt line 1 */ - EXTI9_5_IRQn = 23, /*!< External Line[9:5] Interrupts */ - TIM1_BRK_IRQn = 24, /*!< TIM1 Break Interrupt */ - TIM1_UP_IRQn = 25, /*!< TIM1 Update Interrupt */ - TIM1_TRG_COM_IRQn = 26, /*!< TIM1 Trigger and Commutation Interrupt */ - TIM1_CC_IRQn = 27, /*!< TIM1 Capture Compare Interrupt */ - TIM2_IRQn = 28, /*!< TIM2 global Interrupt */ - TIM3_IRQn = 29, /*!< TIM3 global Interrupt */ - TIM4_IRQn = 30, /*!< TIM4 global Interrupt */ - I2C1_EV_IRQn = 31, /*!< I2C1 Event Interrupt */ - I2C1_ER_IRQn = 32, /*!< I2C1 Error Interrupt */ - I2C2_EV_IRQn = 33, /*!< I2C2 Event Interrupt */ - I2C2_ER_IRQn = 34, /*!< I2C2 Error Interrupt */ - SPI1_IRQn = 35, /*!< SPI1 global Interrupt */ - SPI2_IRQn = 36, /*!< SPI2 global Interrupt */ - USART1_IRQn = 37, /*!< USART1 global Interrupt */ - USART2_IRQn = 38, /*!< USART2 global Interrupt */ - USART3_IRQn = 39, /*!< USART3 global Interrupt */ - EXTI15_10_IRQn = 40, /*!< External Line[15:10] Interrupts */ - RTC_Alarm_IRQn = 41, /*!< RTC Alarm (A and B) through EXTI Line Interrupt */ - TIM8_BRK_TIM12_IRQn = 43, /*!< TIM8 Break Interrupt and TIM12 global interrupt */ - TIM8_UP_TIM13_IRQn = 44, /*!< TIM8 Update Interrupt and TIM13 global interrupt */ - TIM8_TRG_COM_TIM14_IRQn = 45, /*!< TIM8 Trigger and Commutation Interrupt and TIM14 global interrupt */ - TIM8_CC_IRQn = 46, /*!< TIM8 Capture Compare Interrupt */ - DMA1_Stream7_IRQn = 47, /*!< DMA1 Stream7 Interrupt */ - FMC_IRQn = 48, /*!< FMC global Interrupt */ - SDMMC1_IRQn = 49, /*!< SDMMC1 global Interrupt */ - TIM5_IRQn = 50, /*!< TIM5 global Interrupt */ - SPI3_IRQn = 51, /*!< SPI3 global Interrupt */ - UART4_IRQn = 52, /*!< UART4 global Interrupt */ - UART5_IRQn = 53, /*!< UART5 global Interrupt */ - TIM6_DAC_IRQn = 54, /*!< TIM6 global and DAC1&2 underrun error interrupts */ - TIM7_IRQn = 55, /*!< TIM7 global interrupt */ - DMA2_Stream0_IRQn = 56, /*!< DMA2 Stream 0 global Interrupt */ - DMA2_Stream1_IRQn = 57, /*!< DMA2 Stream 1 global Interrupt */ - DMA2_Stream2_IRQn = 58, /*!< DMA2 Stream 2 global Interrupt */ - DMA2_Stream3_IRQn = 59, /*!< DMA2 Stream 3 global Interrupt */ - DMA2_Stream4_IRQn = 60, /*!< DMA2 Stream 4 global Interrupt */ - ETH_IRQn = 61, /*!< Ethernet global Interrupt */ - ETH_WKUP_IRQn = 62, /*!< Ethernet Wakeup through EXTI line Interrupt */ - FDCAN_CAL_IRQn = 63, /*!< FDCAN Calibration unit Interrupt */ - DMA2_Stream5_IRQn = 68, /*!< DMA2 Stream 5 global interrupt */ - DMA2_Stream6_IRQn = 69, /*!< DMA2 Stream 6 global interrupt */ - DMA2_Stream7_IRQn = 70, /*!< DMA2 Stream 7 global interrupt */ - USART6_IRQn = 71, /*!< USART6 global interrupt */ - I2C3_EV_IRQn = 72, /*!< I2C3 event interrupt */ - I2C3_ER_IRQn = 73, /*!< I2C3 error interrupt */ - OTG_HS_EP1_OUT_IRQn = 74, /*!< USB OTG HS End Point 1 Out global interrupt */ - OTG_HS_EP1_IN_IRQn = 75, /*!< USB OTG HS End Point 1 In global interrupt */ - OTG_HS_WKUP_IRQn = 76, /*!< USB OTG HS Wakeup through EXTI interrupt */ - OTG_HS_IRQn = 77, /*!< USB OTG HS global interrupt */ - DCMI_PSSI_IRQn = 78, /*!< DCMI and PSSI global interrupt */ - CRYP_IRQn = 79, /*!< CRYP crypto global interrupt */ - HASH_RNG_IRQn = 80, /*!< HASH and RNG global interrupt */ - FPU_IRQn = 81, /*!< FPU global interrupt */ - UART7_IRQn = 82, /*!< UART7 global interrupt */ - UART8_IRQn = 83, /*!< UART8 global interrupt */ - SPI4_IRQn = 84, /*!< SPI4 global Interrupt */ - SPI5_IRQn = 85, /*!< SPI5 global Interrupt */ - SPI6_IRQn = 86, /*!< SPI6 global Interrupt */ - SAI1_IRQn = 87, /*!< SAI1 global Interrupt */ - LTDC_IRQn = 88, /*!< LTDC global Interrupt */ - LTDC_ER_IRQn = 89, /*!< LTDC Error global Interrupt */ - DMA2D_IRQn = 90, /*!< DMA2D global Interrupt */ - OCTOSPI1_IRQn = 92, /*!< OCTOSPI1 global interrupt */ - LPTIM1_IRQn = 93, /*!< LP TIM1 interrupt */ - CEC_IRQn = 94, /*!< HDMI-CEC global Interrupt */ - I2C4_EV_IRQn = 95, /*!< I2C4 Event Interrupt */ - I2C4_ER_IRQn = 96, /*!< I2C4 Error Interrupt */ - SPDIF_RX_IRQn = 97, /*!< SPDIF-RX global Interrupt */ - DMAMUX1_OVR_IRQn = 102, /*! - -/** @addtogroup Peripheral_registers_structures - * @{ - */ - -/** - * @brief Analog to Digital Converter - */ - -typedef struct -{ - __IO uint32_t ISR; /*!< ADC Interrupt and Status Register, Address offset: 0x00 */ - __IO uint32_t IER; /*!< ADC Interrupt Enable Register, Address offset: 0x04 */ - __IO uint32_t CR; /*!< ADC control register, Address offset: 0x08 */ - __IO uint32_t CFGR; /*!< ADC Configuration register, Address offset: 0x0C */ - __IO uint32_t CFGR2; /*!< ADC Configuration register 2, Address offset: 0x10 */ - __IO uint32_t SMPR1; /*!< ADC sample time register 1, Address offset: 0x14 */ - __IO uint32_t SMPR2; /*!< ADC sample time register 2, Address offset: 0x18 */ - __IO uint32_t PCSEL_RES0; /*!< Rserved for ADC3, ADC1/2 pre-channel selection, Address offset: 0x1C */ - __IO uint32_t LTR1_TR1; /*!< ADC watchdog Lower threshold register 1, Address offset: 0x20 */ - __IO uint32_t HTR1_TR2; /*!< ADC watchdog higher threshold register 1, Address offset: 0x24 */ - __IO uint32_t RES1_TR3; /*!< Rserved for ADC1/2, ADC3 threshold register, Address offset: 0x28 */ - uint32_t RESERVED2; /*!< Reserved, 0x02C */ - __IO uint32_t SQR1; /*!< ADC regular sequence register 1, Address offset: 0x30 */ - __IO uint32_t SQR2; /*!< ADC regular sequence register 2, Address offset: 0x34 */ - __IO uint32_t SQR3; /*!< ADC regular sequence register 3, Address offset: 0x38 */ - __IO uint32_t SQR4; /*!< ADC regular sequence register 4, Address offset: 0x3C */ - __IO uint32_t DR; /*!< ADC regular data register, Address offset: 0x40 */ - uint32_t RESERVED3; /*!< Reserved, 0x044 */ - uint32_t RESERVED4; /*!< Reserved, 0x048 */ - __IO uint32_t JSQR; /*!< ADC injected sequence register, Address offset: 0x4C */ - uint32_t RESERVED5[4]; /*!< Reserved, 0x050 - 0x05C */ - __IO uint32_t OFR1; /*!< ADC offset register 1, Address offset: 0x60 */ - __IO uint32_t OFR2; /*!< ADC offset register 2, Address offset: 0x64 */ - __IO uint32_t OFR3; /*!< ADC offset register 3, Address offset: 0x68 */ - __IO uint32_t OFR4; /*!< ADC offset register 4, Address offset: 0x6C */ - uint32_t RESERVED6[4]; /*!< Reserved, 0x070 - 0x07C */ - __IO uint32_t JDR1; /*!< ADC injected data register 1, Address offset: 0x80 */ - __IO uint32_t JDR2; /*!< ADC injected data register 2, Address offset: 0x84 */ - __IO uint32_t JDR3; /*!< ADC injected data register 3, Address offset: 0x88 */ - __IO uint32_t JDR4; /*!< ADC injected data register 4, Address offset: 0x8C */ - uint32_t RESERVED7[4]; /*!< Reserved, 0x090 - 0x09C */ - __IO uint32_t AWD2CR; /*!< ADC Analog Watchdog 2 Configuration Register, Address offset: 0xA0 */ - __IO uint32_t AWD3CR; /*!< ADC Analog Watchdog 3 Configuration Register, Address offset: 0xA4 */ - uint32_t RESERVED8; /*!< Reserved, 0x0A8 */ - uint32_t RESERVED9; /*!< Reserved, 0x0AC */ - __IO uint32_t LTR2_DIFSEL; /*!< ADC watchdog Lower threshold register 2, Difsel for ADC3, Address offset: 0xB0 */ - __IO uint32_t HTR2_CALFACT; /*!< ADC watchdog Higher threshold register 2, Calfact for ADC3, Address offset: 0xB4 */ - __IO uint32_t LTR3_RES10; /*!< ADC watchdog Lower threshold register 3, specific ADC1/2, Address offset: 0xB8 */ - __IO uint32_t HTR3_RES11; /*!< ADC watchdog Higher threshold register 3, specific ADC1/2, Address offset: 0xBC */ - __IO uint32_t DIFSEL_RES12; /*!< ADC Differential Mode Selection Register specific ADC1/2, Address offset: 0xC0 */ - __IO uint32_t CALFACT_RES13; /*!< ADC Calibration Factors specific ADC1/2, Address offset: 0xC4 */ - __IO uint32_t CALFACT2_RES14; /*!< ADC Linearity Calibration Factors specific ADC1/2, Address offset: 0xC8 */ -} ADC_TypeDef; - - -typedef struct -{ -__IO uint32_t CSR; /*!< ADC Common status register, Address offset: ADC1/3 base address + 0x300 */ -uint32_t RESERVED; /*!< Reserved, ADC1/3 base address + 0x304 */ -__IO uint32_t CCR; /*!< ADC common control register, Address offset: ADC1/3 base address + 0x308 */ -__IO uint32_t CDR; /*!< ADC common regular data register for dual Address offset: ADC1/3 base address + 0x30C */ -__IO uint32_t CDR2; /*!< ADC common regular data register for 32-bit dual mode Address offset: ADC1/3 base address + 0x310 */ - -} ADC_Common_TypeDef; - - -/** - * @brief VREFBUF - */ - -typedef struct -{ - __IO uint32_t CSR; /*!< VREFBUF control and status register, Address offset: 0x00 */ - __IO uint32_t CCR; /*!< VREFBUF calibration and control register, Address offset: 0x04 */ -} VREFBUF_TypeDef; - - -/** - * @brief FD Controller Area Network - */ - -typedef struct -{ - __IO uint32_t CREL; /*!< FDCAN Core Release register, Address offset: 0x000 */ - __IO uint32_t ENDN; /*!< FDCAN Endian register, Address offset: 0x004 */ - __IO uint32_t RESERVED1; /*!< Reserved, 0x008 */ - __IO uint32_t DBTP; /*!< FDCAN Data Bit Timing & Prescaler register, Address offset: 0x00C */ - __IO uint32_t TEST; /*!< FDCAN Test register, Address offset: 0x010 */ - __IO uint32_t RWD; /*!< FDCAN RAM Watchdog register, Address offset: 0x014 */ - __IO uint32_t CCCR; /*!< FDCAN CC Control register, Address offset: 0x018 */ - __IO uint32_t NBTP; /*!< FDCAN Nominal Bit Timing & Prescaler register, Address offset: 0x01C */ - __IO uint32_t TSCC; /*!< FDCAN Timestamp Counter Configuration register, Address offset: 0x020 */ - __IO uint32_t TSCV; /*!< FDCAN Timestamp Counter Value register, Address offset: 0x024 */ - __IO uint32_t TOCC; /*!< FDCAN Timeout Counter Configuration register, Address offset: 0x028 */ - __IO uint32_t TOCV; /*!< FDCAN Timeout Counter Value register, Address offset: 0x02C */ - __IO uint32_t RESERVED2[4]; /*!< Reserved, 0x030 - 0x03C */ - __IO uint32_t ECR; /*!< FDCAN Error Counter register, Address offset: 0x040 */ - __IO uint32_t PSR; /*!< FDCAN Protocol Status register, Address offset: 0x044 */ - __IO uint32_t TDCR; /*!< FDCAN Transmitter Delay Compensation register, Address offset: 0x048 */ - __IO uint32_t RESERVED3; /*!< Reserved, 0x04C */ - __IO uint32_t IR; /*!< FDCAN Interrupt register, Address offset: 0x050 */ - __IO uint32_t IE; /*!< FDCAN Interrupt Enable register, Address offset: 0x054 */ - __IO uint32_t ILS; /*!< FDCAN Interrupt Line Select register, Address offset: 0x058 */ - __IO uint32_t ILE; /*!< FDCAN Interrupt Line Enable register, Address offset: 0x05C */ - __IO uint32_t RESERVED4[8]; /*!< Reserved, 0x060 - 0x07C */ - __IO uint32_t GFC; /*!< FDCAN Global Filter Configuration register, Address offset: 0x080 */ - __IO uint32_t SIDFC; /*!< FDCAN Standard ID Filter Configuration register, Address offset: 0x084 */ - __IO uint32_t XIDFC; /*!< FDCAN Extended ID Filter Configuration register, Address offset: 0x088 */ - __IO uint32_t RESERVED5; /*!< Reserved, 0x08C */ - __IO uint32_t XIDAM; /*!< FDCAN Extended ID AND Mask register, Address offset: 0x090 */ - __IO uint32_t HPMS; /*!< FDCAN High Priority Message Status register, Address offset: 0x094 */ - __IO uint32_t NDAT1; /*!< FDCAN New Data 1 register, Address offset: 0x098 */ - __IO uint32_t NDAT2; /*!< FDCAN New Data 2 register, Address offset: 0x09C */ - __IO uint32_t RXF0C; /*!< FDCAN Rx FIFO 0 Configuration register, Address offset: 0x0A0 */ - __IO uint32_t RXF0S; /*!< FDCAN Rx FIFO 0 Status register, Address offset: 0x0A4 */ - __IO uint32_t RXF0A; /*!< FDCAN Rx FIFO 0 Acknowledge register, Address offset: 0x0A8 */ - __IO uint32_t RXBC; /*!< FDCAN Rx Buffer Configuration register, Address offset: 0x0AC */ - __IO uint32_t RXF1C; /*!< FDCAN Rx FIFO 1 Configuration register, Address offset: 0x0B0 */ - __IO uint32_t RXF1S; /*!< FDCAN Rx FIFO 1 Status register, Address offset: 0x0B4 */ - __IO uint32_t RXF1A; /*!< FDCAN Rx FIFO 1 Acknowledge register, Address offset: 0x0B8 */ - __IO uint32_t RXESC; /*!< FDCAN Rx Buffer/FIFO Element Size Configuration register, Address offset: 0x0BC */ - __IO uint32_t TXBC; /*!< FDCAN Tx Buffer Configuration register, Address offset: 0x0C0 */ - __IO uint32_t TXFQS; /*!< FDCAN Tx FIFO/Queue Status register, Address offset: 0x0C4 */ - __IO uint32_t TXESC; /*!< FDCAN Tx Buffer Element Size Configuration register, Address offset: 0x0C8 */ - __IO uint32_t TXBRP; /*!< FDCAN Tx Buffer Request Pending register, Address offset: 0x0CC */ - __IO uint32_t TXBAR; /*!< FDCAN Tx Buffer Add Request register, Address offset: 0x0D0 */ - __IO uint32_t TXBCR; /*!< FDCAN Tx Buffer Cancellation Request register, Address offset: 0x0D4 */ - __IO uint32_t TXBTO; /*!< FDCAN Tx Buffer Transmission Occurred register, Address offset: 0x0D8 */ - __IO uint32_t TXBCF; /*!< FDCAN Tx Buffer Cancellation Finished register, Address offset: 0x0DC */ - __IO uint32_t TXBTIE; /*!< FDCAN Tx Buffer Transmission Interrupt Enable register, Address offset: 0x0E0 */ - __IO uint32_t TXBCIE; /*!< FDCAN Tx Buffer Cancellation Finished Interrupt Enable register, Address offset: 0x0E4 */ - __IO uint32_t RESERVED6[2]; /*!< Reserved, 0x0E8 - 0x0EC */ - __IO uint32_t TXEFC; /*!< FDCAN Tx Event FIFO Configuration register, Address offset: 0x0F0 */ - __IO uint32_t TXEFS; /*!< FDCAN Tx Event FIFO Status register, Address offset: 0x0F4 */ - __IO uint32_t TXEFA; /*!< FDCAN Tx Event FIFO Acknowledge register, Address offset: 0x0F8 */ - __IO uint32_t RESERVED7; /*!< Reserved, 0x0FC */ -} FDCAN_GlobalTypeDef; - -/** - * @brief TTFD Controller Area Network - */ - -typedef struct -{ - __IO uint32_t TTTMC; /*!< TT Trigger Memory Configuration register, Address offset: 0x100 */ - __IO uint32_t TTRMC; /*!< TT Reference Message Configuration register, Address offset: 0x104 */ - __IO uint32_t TTOCF; /*!< TT Operation Configuration register, Address offset: 0x108 */ - __IO uint32_t TTMLM; /*!< TT Matrix Limits register, Address offset: 0x10C */ - __IO uint32_t TURCF; /*!< TUR Configuration register, Address offset: 0x110 */ - __IO uint32_t TTOCN; /*!< TT Operation Control register, Address offset: 0x114 */ - __IO uint32_t TTGTP; /*!< TT Global Time Preset register, Address offset: 0x118 */ - __IO uint32_t TTTMK; /*!< TT Time Mark register, Address offset: 0x11C */ - __IO uint32_t TTIR; /*!< TT Interrupt register, Address offset: 0x120 */ - __IO uint32_t TTIE; /*!< TT Interrupt Enable register, Address offset: 0x124 */ - __IO uint32_t TTILS; /*!< TT Interrupt Line Select register, Address offset: 0x128 */ - __IO uint32_t TTOST; /*!< TT Operation Status register, Address offset: 0x12C */ - __IO uint32_t TURNA; /*!< TT TUR Numerator Actual register, Address offset: 0x130 */ - __IO uint32_t TTLGT; /*!< TT Local and Global Time register, Address offset: 0x134 */ - __IO uint32_t TTCTC; /*!< TT Cycle Time and Count register, Address offset: 0x138 */ - __IO uint32_t TTCPT; /*!< TT Capture Time register, Address offset: 0x13C */ - __IO uint32_t TTCSM; /*!< TT Cycle Sync Mark register, Address offset: 0x140 */ - __IO uint32_t RESERVED1[111]; /*!< Reserved, 0x144 - 0x2FC */ - __IO uint32_t TTTS; /*!< TT Trigger Select register, Address offset: 0x300 */ -} TTCAN_TypeDef; - -/** - * @brief FD Controller Area Network - */ - -typedef struct -{ - __IO uint32_t CREL; /*!< Clock Calibration Unit Core Release register, Address offset: 0x00 */ - __IO uint32_t CCFG; /*!< Calibration Configuration register, Address offset: 0x04 */ - __IO uint32_t CSTAT; /*!< Calibration Status register, Address offset: 0x08 */ - __IO uint32_t CWD; /*!< Calibration Watchdog register, Address offset: 0x0C */ - __IO uint32_t IR; /*!< CCU Interrupt register, Address offset: 0x10 */ - __IO uint32_t IE; /*!< CCU Interrupt Enable register, Address offset: 0x14 */ -} FDCAN_ClockCalibrationUnit_TypeDef; - - -/** - * @brief Consumer Electronics Control - */ - -typedef struct -{ - __IO uint32_t CR; /*!< CEC control register, Address offset:0x00 */ - __IO uint32_t CFGR; /*!< CEC configuration register, Address offset:0x04 */ - __IO uint32_t TXDR; /*!< CEC Tx data register , Address offset:0x08 */ - __IO uint32_t RXDR; /*!< CEC Rx Data Register, Address offset:0x0C */ - __IO uint32_t ISR; /*!< CEC Interrupt and Status Register, Address offset:0x10 */ - __IO uint32_t IER; /*!< CEC interrupt enable register, Address offset:0x14 */ -}CEC_TypeDef; - -/** - * @brief COordincate Rotation DIgital Computer - */ -typedef struct -{ - __IO uint32_t CSR; /*!< CORDIC control and status register, Address offset: 0x00 */ - __IO uint32_t WDATA; /*!< CORDIC argument register, Address offset: 0x04 */ - __IO uint32_t RDATA; /*!< CORDIC result register, Address offset: 0x08 */ -} CORDIC_TypeDef; - -/** - * @brief CRC calculation unit - */ - -typedef struct -{ - __IO uint32_t DR; /*!< CRC Data register, Address offset: 0x00 */ - __IO uint32_t IDR; /*!< CRC Independent data register, Address offset: 0x04 */ - __IO uint32_t CR; /*!< CRC Control register, Address offset: 0x08 */ - uint32_t RESERVED2; /*!< Reserved, 0x0C */ - __IO uint32_t INIT; /*!< Initial CRC value register, Address offset: 0x10 */ - __IO uint32_t POL; /*!< CRC polynomial register, Address offset: 0x14 */ -} CRC_TypeDef; - - -/** - * @brief Clock Recovery System - */ -typedef struct -{ -__IO uint32_t CR; /*!< CRS ccontrol register, Address offset: 0x00 */ -__IO uint32_t CFGR; /*!< CRS configuration register, Address offset: 0x04 */ -__IO uint32_t ISR; /*!< CRS interrupt and status register, Address offset: 0x08 */ -__IO uint32_t ICR; /*!< CRS interrupt flag clear register, Address offset: 0x0C */ -} CRS_TypeDef; - - -/** - * @brief Digital to Analog Converter - */ - -typedef struct -{ - __IO uint32_t CR; /*!< DAC control register, Address offset: 0x00 */ - __IO uint32_t SWTRIGR; /*!< DAC software trigger register, Address offset: 0x04 */ - __IO uint32_t DHR12R1; /*!< DAC channel1 12-bit right-aligned data holding register, Address offset: 0x08 */ - __IO uint32_t DHR12L1; /*!< DAC channel1 12-bit left aligned data holding register, Address offset: 0x0C */ - __IO uint32_t DHR8R1; /*!< DAC channel1 8-bit right aligned data holding register, Address offset: 0x10 */ - __IO uint32_t DHR12R2; /*!< DAC channel2 12-bit right aligned data holding register, Address offset: 0x14 */ - __IO uint32_t DHR12L2; /*!< DAC channel2 12-bit left aligned data holding register, Address offset: 0x18 */ - __IO uint32_t DHR8R2; /*!< DAC channel2 8-bit right-aligned data holding register, Address offset: 0x1C */ - __IO uint32_t DHR12RD; /*!< Dual DAC 12-bit right-aligned data holding register, Address offset: 0x20 */ - __IO uint32_t DHR12LD; /*!< DUAL DAC 12-bit left aligned data holding register, Address offset: 0x24 */ - __IO uint32_t DHR8RD; /*!< DUAL DAC 8-bit right aligned data holding register, Address offset: 0x28 */ - __IO uint32_t DOR1; /*!< DAC channel1 data output register, Address offset: 0x2C */ - __IO uint32_t DOR2; /*!< DAC channel2 data output register, Address offset: 0x30 */ - __IO uint32_t SR; /*!< DAC status register, Address offset: 0x34 */ - __IO uint32_t CCR; /*!< DAC calibration control register, Address offset: 0x38 */ - __IO uint32_t MCR; /*!< DAC mode control register, Address offset: 0x3C */ - __IO uint32_t SHSR1; /*!< DAC Sample and Hold sample time register 1, Address offset: 0x40 */ - __IO uint32_t SHSR2; /*!< DAC Sample and Hold sample time register 2, Address offset: 0x44 */ - __IO uint32_t SHHR; /*!< DAC Sample and Hold hold time register, Address offset: 0x48 */ - __IO uint32_t SHRR; /*!< DAC Sample and Hold refresh time register, Address offset: 0x4C */ -} DAC_TypeDef; - -/** - * @brief DFSDM module registers - */ -typedef struct -{ - __IO uint32_t FLTCR1; /*!< DFSDM control register1, Address offset: 0x100 */ - __IO uint32_t FLTCR2; /*!< DFSDM control register2, Address offset: 0x104 */ - __IO uint32_t FLTISR; /*!< DFSDM interrupt and status register, Address offset: 0x108 */ - __IO uint32_t FLTICR; /*!< DFSDM interrupt flag clear register, Address offset: 0x10C */ - __IO uint32_t FLTJCHGR; /*!< DFSDM injected channel group selection register, Address offset: 0x110 */ - __IO uint32_t FLTFCR; /*!< DFSDM filter control register, Address offset: 0x114 */ - __IO uint32_t FLTJDATAR; /*!< DFSDM data register for injected group, Address offset: 0x118 */ - __IO uint32_t FLTRDATAR; /*!< DFSDM data register for regular group, Address offset: 0x11C */ - __IO uint32_t FLTAWHTR; /*!< DFSDM analog watchdog high threshold register, Address offset: 0x120 */ - __IO uint32_t FLTAWLTR; /*!< DFSDM analog watchdog low threshold register, Address offset: 0x124 */ - __IO uint32_t FLTAWSR; /*!< DFSDM analog watchdog status register Address offset: 0x128 */ - __IO uint32_t FLTAWCFR; /*!< DFSDM analog watchdog clear flag register Address offset: 0x12C */ - __IO uint32_t FLTEXMAX; /*!< DFSDM extreme detector maximum register, Address offset: 0x130 */ - __IO uint32_t FLTEXMIN; /*!< DFSDM extreme detector minimum register Address offset: 0x134 */ - __IO uint32_t FLTCNVTIMR; /*!< DFSDM conversion timer, Address offset: 0x138 */ -} DFSDM_Filter_TypeDef; - -/** - * @brief DFSDM channel configuration registers - */ -typedef struct -{ - __IO uint32_t CHCFGR1; /*!< DFSDM channel configuration register1, Address offset: 0x00 */ - __IO uint32_t CHCFGR2; /*!< DFSDM channel configuration register2, Address offset: 0x04 */ - __IO uint32_t CHAWSCDR; /*!< DFSDM channel analog watchdog and - short circuit detector register, Address offset: 0x08 */ - __IO uint32_t CHWDATAR; /*!< DFSDM channel watchdog filter data register, Address offset: 0x0C */ - __IO uint32_t CHDATINR; /*!< DFSDM channel data input register, Address offset: 0x10 */ -} DFSDM_Channel_TypeDef; - -/** - * @brief Debug MCU - */ -typedef struct -{ - __IO uint32_t IDCODE; /*!< MCU device ID code, Address offset: 0x00 */ - __IO uint32_t CR; /*!< Debug MCU configuration register, Address offset: 0x04 */ - uint32_t RESERVED4[11]; /*!< Reserved, Address offset: 0x08 */ - __IO uint32_t APB3FZ1; /*!< Debug MCU APB3FZ1 freeze register, Address offset: 0x34 */ - uint32_t RESERVED5; /*!< Reserved, Address offset: 0x38 */ - __IO uint32_t APB1LFZ1; /*!< Debug MCU APB1LFZ1 freeze register, Address offset: 0x3C */ - uint32_t RESERVED6; /*!< Reserved, Address offset: 0x40 */ - __IO uint32_t APB1HFZ1; /*!< Debug MCU APB1LFZ1 freeze register, Address offset: 0x44 */ - uint32_t RESERVED7; /*!< Reserved, Address offset: 0x48 */ - __IO uint32_t APB2FZ1; /*!< Debug MCU APB2FZ1 freeze register, Address offset: 0x4C */ - uint32_t RESERVED8; /*!< Reserved, Address offset: 0x50 */ - __IO uint32_t APB4FZ1; /*!< Debug MCU APB4FZ1 freeze register, Address offset: 0x54 */ - __IO uint32_t RESERVED9[990]; /*!< Reserved, Address offset: 0x58-0xFCC */ - __IO uint32_t PIDR4; /*!< Debug MCU peripheral identity register 4, Address offset: 0xFD0 */ - __IO uint32_t RESERVED10[3];/*!< Reserved, Address offset: 0xFD4-0xFDC */ - __IO uint32_t PIDR0; /*!< Debug MCU peripheral identity register 0, Address offset: 0xFE0 */ - __IO uint32_t PIDR1; /*!< Debug MCU peripheral identity register 1, Address offset: 0xFE4 */ - __IO uint32_t PIDR2; /*!< Debug MCU peripheral identity register 2, Address offset: 0xFE8 */ - __IO uint32_t PIDR3; /*!< Debug MCU peripheral identity register 3, Address offset: 0xFEC */ - __IO uint32_t CIDR0; /*!< Debug MCU component identity register 0, Address offset: 0xFF0 */ - __IO uint32_t CIDR1; /*!< Debug MCU component identity register 1, Address offset: 0xFF4 */ - __IO uint32_t CIDR2; /*!< Debug MCU component identity register 2, Address offset: 0xFF8 */ - __IO uint32_t CIDR3; /*!< Debug MCU component identity register 3, Address offset: 0xFFC */ -}DBGMCU_TypeDef; -/** - * @brief DCMI - */ - -typedef struct -{ - __IO uint32_t CR; /*!< DCMI control register 1, Address offset: 0x00 */ - __IO uint32_t SR; /*!< DCMI status register, Address offset: 0x04 */ - __IO uint32_t RISR; /*!< DCMI raw interrupt status register, Address offset: 0x08 */ - __IO uint32_t IER; /*!< DCMI interrupt enable register, Address offset: 0x0C */ - __IO uint32_t MISR; /*!< DCMI masked interrupt status register, Address offset: 0x10 */ - __IO uint32_t ICR; /*!< DCMI interrupt clear register, Address offset: 0x14 */ - __IO uint32_t ESCR; /*!< DCMI embedded synchronization code register, Address offset: 0x18 */ - __IO uint32_t ESUR; /*!< DCMI embedded synchronization unmask register, Address offset: 0x1C */ - __IO uint32_t CWSTRTR; /*!< DCMI crop window start, Address offset: 0x20 */ - __IO uint32_t CWSIZER; /*!< DCMI crop window size, Address offset: 0x24 */ - __IO uint32_t DR; /*!< DCMI data register, Address offset: 0x28 */ -} DCMI_TypeDef; - -/** - * @brief PSSI - */ - -typedef struct -{ - __IO uint32_t CR; /*!< PSSI control register 1, Address offset: 0x000 */ - __IO uint32_t SR; /*!< PSSI status register, Address offset: 0x004 */ - __IO uint32_t RIS; /*!< PSSI raw interrupt status register, Address offset: 0x008 */ - __IO uint32_t IER; /*!< PSSI interrupt enable register, Address offset: 0x00C */ - __IO uint32_t MIS; /*!< PSSI masked interrupt status register, Address offset: 0x010 */ - __IO uint32_t ICR; /*!< PSSI interrupt clear register, Address offset: 0x014 */ - __IO uint32_t RESERVED1[4]; /*!< Reserved, 0x018 - 0x024 */ - __IO uint32_t DR; /*!< PSSI data register, Address offset: 0x028 */ - __IO uint32_t RESERVED2[241]; /*!< Reserved, 0x02C - 0x3EC */ - __IO uint32_t HWCFGR; /*!< PSSI IP HW configuration register, Address offset: 0x3F0 */ - __IO uint32_t VERR; /*!< PSSI IP version register, Address offset: 0x3F4 */ - __IO uint32_t IPIDR; /*!< PSSI IP ID register, Address offset: 0x3F8 */ - __IO uint32_t SIDR; /*!< PSSI SIZE ID register, Address offset: 0x3FC */ -} PSSI_TypeDef; - -/** - * @brief DMA Controller - */ - -typedef struct -{ - __IO uint32_t CR; /*!< DMA stream x configuration register */ - __IO uint32_t NDTR; /*!< DMA stream x number of data register */ - __IO uint32_t PAR; /*!< DMA stream x peripheral address register */ - __IO uint32_t M0AR; /*!< DMA stream x memory 0 address register */ - __IO uint32_t M1AR; /*!< DMA stream x memory 1 address register */ - __IO uint32_t FCR; /*!< DMA stream x FIFO control register */ -} DMA_Stream_TypeDef; - -typedef struct -{ - __IO uint32_t LISR; /*!< DMA low interrupt status register, Address offset: 0x00 */ - __IO uint32_t HISR; /*!< DMA high interrupt status register, Address offset: 0x04 */ - __IO uint32_t LIFCR; /*!< DMA low interrupt flag clear register, Address offset: 0x08 */ - __IO uint32_t HIFCR; /*!< DMA high interrupt flag clear register, Address offset: 0x0C */ -} DMA_TypeDef; - -typedef struct -{ - __IO uint32_t CCR; /*!< DMA channel x configuration register */ - __IO uint32_t CNDTR; /*!< DMA channel x number of data register */ - __IO uint32_t CPAR; /*!< DMA channel x peripheral address register */ - __IO uint32_t CM0AR; /*!< DMA channel x memory 0 address register */ - __IO uint32_t CM1AR; /*!< DMA channel x memory 1 address register */ -} BDMA_Channel_TypeDef; - -typedef struct -{ - __IO uint32_t ISR; /*!< DMA interrupt status register, Address offset: 0x00 */ - __IO uint32_t IFCR; /*!< DMA interrupt flag clear register, Address offset: 0x04 */ -} BDMA_TypeDef; - -typedef struct -{ - __IO uint32_t CCR; /*!< DMA Multiplexer Channel x Control Register */ -}DMAMUX_Channel_TypeDef; - -typedef struct -{ - __IO uint32_t CSR; /*!< DMA Channel Status Register */ - __IO uint32_t CFR; /*!< DMA Channel Clear Flag Register */ -}DMAMUX_ChannelStatus_TypeDef; - -typedef struct -{ - __IO uint32_t RGCR; /*!< DMA Request Generator x Control Register */ -}DMAMUX_RequestGen_TypeDef; - -typedef struct -{ - __IO uint32_t RGSR; /*!< DMA Request Generator Status Register */ - __IO uint32_t RGCFR; /*!< DMA Request Generator Clear Flag Register */ -}DMAMUX_RequestGenStatus_TypeDef; - -/** - * @brief MDMA Controller - */ -typedef struct -{ - __IO uint32_t GISR0; /*!< MDMA Global Interrupt/Status Register 0, Address offset: 0x00 */ -}MDMA_TypeDef; - -typedef struct -{ - __IO uint32_t CISR; /*!< MDMA channel x interrupt/status register, Address offset: 0x40 */ - __IO uint32_t CIFCR; /*!< MDMA channel x interrupt flag clear register, Address offset: 0x44 */ - __IO uint32_t CESR; /*!< MDMA Channel x error status register, Address offset: 0x48 */ - __IO uint32_t CCR; /*!< MDMA channel x control register, Address offset: 0x4C */ - __IO uint32_t CTCR; /*!< MDMA channel x Transfer Configuration register, Address offset: 0x50 */ - __IO uint32_t CBNDTR; /*!< MDMA Channel x block number of data register, Address offset: 0x54 */ - __IO uint32_t CSAR; /*!< MDMA channel x source address register, Address offset: 0x58 */ - __IO uint32_t CDAR; /*!< MDMA channel x destination address register, Address offset: 0x5C */ - __IO uint32_t CBRUR; /*!< MDMA channel x Block Repeat address Update register, Address offset: 0x60 */ - __IO uint32_t CLAR; /*!< MDMA channel x Link Address register, Address offset: 0x64 */ - __IO uint32_t CTBR; /*!< MDMA channel x Trigger and Bus selection Register, Address offset: 0x68 */ - uint32_t RESERVED0; /*!< Reserved, 0x6C */ - __IO uint32_t CMAR; /*!< MDMA channel x Mask address register, Address offset: 0x70 */ - __IO uint32_t CMDR; /*!< MDMA channel x Mask Data register, Address offset: 0x74 */ -}MDMA_Channel_TypeDef; - -/** - * @brief DMA2D Controller - */ - -typedef struct -{ - __IO uint32_t CR; /*!< DMA2D Control Register, Address offset: 0x00 */ - __IO uint32_t ISR; /*!< DMA2D Interrupt Status Register, Address offset: 0x04 */ - __IO uint32_t IFCR; /*!< DMA2D Interrupt Flag Clear Register, Address offset: 0x08 */ - __IO uint32_t FGMAR; /*!< DMA2D Foreground Memory Address Register, Address offset: 0x0C */ - __IO uint32_t FGOR; /*!< DMA2D Foreground Offset Register, Address offset: 0x10 */ - __IO uint32_t BGMAR; /*!< DMA2D Background Memory Address Register, Address offset: 0x14 */ - __IO uint32_t BGOR; /*!< DMA2D Background Offset Register, Address offset: 0x18 */ - __IO uint32_t FGPFCCR; /*!< DMA2D Foreground PFC Control Register, Address offset: 0x1C */ - __IO uint32_t FGCOLR; /*!< DMA2D Foreground Color Register, Address offset: 0x20 */ - __IO uint32_t BGPFCCR; /*!< DMA2D Background PFC Control Register, Address offset: 0x24 */ - __IO uint32_t BGCOLR; /*!< DMA2D Background Color Register, Address offset: 0x28 */ - __IO uint32_t FGCMAR; /*!< DMA2D Foreground CLUT Memory Address Register, Address offset: 0x2C */ - __IO uint32_t BGCMAR; /*!< DMA2D Background CLUT Memory Address Register, Address offset: 0x30 */ - __IO uint32_t OPFCCR; /*!< DMA2D Output PFC Control Register, Address offset: 0x34 */ - __IO uint32_t OCOLR; /*!< DMA2D Output Color Register, Address offset: 0x38 */ - __IO uint32_t OMAR; /*!< DMA2D Output Memory Address Register, Address offset: 0x3C */ - __IO uint32_t OOR; /*!< DMA2D Output Offset Register, Address offset: 0x40 */ - __IO uint32_t NLR; /*!< DMA2D Number of Line Register, Address offset: 0x44 */ - __IO uint32_t LWR; /*!< DMA2D Line Watermark Register, Address offset: 0x48 */ - __IO uint32_t AMTCR; /*!< DMA2D AHB Master Timer Configuration Register, Address offset: 0x4C */ - uint32_t RESERVED[236]; /*!< Reserved, 0x50-0x3FF */ - __IO uint32_t FGCLUT[256]; /*!< DMA2D Foreground CLUT, Address offset:400-7FF */ - __IO uint32_t BGCLUT[256]; /*!< DMA2D Background CLUT, Address offset:800-BFF */ -} DMA2D_TypeDef; - - -/** - * @brief Ethernet MAC - */ -typedef struct -{ - __IO uint32_t MACCR; - __IO uint32_t MACECR; - __IO uint32_t MACPFR; - __IO uint32_t MACWTR; - __IO uint32_t MACHT0R; - __IO uint32_t MACHT1R; - uint32_t RESERVED1[14]; - __IO uint32_t MACVTR; - uint32_t RESERVED2; - __IO uint32_t MACVHTR; - uint32_t RESERVED3; - __IO uint32_t MACVIR; - __IO uint32_t MACIVIR; - uint32_t RESERVED4[2]; - __IO uint32_t MACTFCR; - uint32_t RESERVED5[7]; - __IO uint32_t MACRFCR; - uint32_t RESERVED6[7]; - __IO uint32_t MACISR; - __IO uint32_t MACIER; - __IO uint32_t MACRXTXSR; - uint32_t RESERVED7; - __IO uint32_t MACPCSR; - __IO uint32_t MACRWKPFR; - uint32_t RESERVED8[2]; - __IO uint32_t MACLCSR; - __IO uint32_t MACLTCR; - __IO uint32_t MACLETR; - __IO uint32_t MAC1USTCR; - uint32_t RESERVED9[12]; - __IO uint32_t MACVR; - __IO uint32_t MACDR; - uint32_t RESERVED10; - __IO uint32_t MACHWF0R; - __IO uint32_t MACHWF1R; - __IO uint32_t MACHWF2R; - uint32_t RESERVED11[54]; - __IO uint32_t MACMDIOAR; - __IO uint32_t MACMDIODR; - uint32_t RESERVED12[2]; - __IO uint32_t MACARPAR; - uint32_t RESERVED13[59]; - __IO uint32_t MACA0HR; - __IO uint32_t MACA0LR; - __IO uint32_t MACA1HR; - __IO uint32_t MACA1LR; - __IO uint32_t MACA2HR; - __IO uint32_t MACA2LR; - __IO uint32_t MACA3HR; - __IO uint32_t MACA3LR; - uint32_t RESERVED14[248]; - __IO uint32_t MMCCR; - __IO uint32_t MMCRIR; - __IO uint32_t MMCTIR; - __IO uint32_t MMCRIMR; - __IO uint32_t MMCTIMR; - uint32_t RESERVED15[14]; - __IO uint32_t MMCTSCGPR; - __IO uint32_t MMCTMCGPR; - uint32_t RESERVED16[5]; - __IO uint32_t MMCTPCGR; - uint32_t RESERVED17[10]; - __IO uint32_t MMCRCRCEPR; - __IO uint32_t MMCRAEPR; - uint32_t RESERVED18[10]; - __IO uint32_t MMCRUPGR; - uint32_t RESERVED19[9]; - __IO uint32_t MMCTLPIMSTR; - __IO uint32_t MMCTLPITCR; - __IO uint32_t MMCRLPIMSTR; - __IO uint32_t MMCRLPITCR; - uint32_t RESERVED20[65]; - __IO uint32_t MACL3L4C0R; - __IO uint32_t MACL4A0R; - uint32_t RESERVED21[2]; - __IO uint32_t MACL3A0R0R; - __IO uint32_t MACL3A1R0R; - __IO uint32_t MACL3A2R0R; - __IO uint32_t MACL3A3R0R; - uint32_t RESERVED22[4]; - __IO uint32_t MACL3L4C1R; - __IO uint32_t MACL4A1R; - uint32_t RESERVED23[2]; - __IO uint32_t MACL3A0R1R; - __IO uint32_t MACL3A1R1R; - __IO uint32_t MACL3A2R1R; - __IO uint32_t MACL3A3R1R; - uint32_t RESERVED24[108]; - __IO uint32_t MACTSCR; - __IO uint32_t MACSSIR; - __IO uint32_t MACSTSR; - __IO uint32_t MACSTNR; - __IO uint32_t MACSTSUR; - __IO uint32_t MACSTNUR; - __IO uint32_t MACTSAR; - uint32_t RESERVED25; - __IO uint32_t MACTSSR; - uint32_t RESERVED26[3]; - __IO uint32_t MACTTSSNR; - __IO uint32_t MACTTSSSR; - uint32_t RESERVED27[2]; - __IO uint32_t MACACR; - uint32_t RESERVED28; - __IO uint32_t MACATSNR; - __IO uint32_t MACATSSR; - __IO uint32_t MACTSIACR; - __IO uint32_t MACTSEACR; - __IO uint32_t MACTSICNR; - __IO uint32_t MACTSECNR; - uint32_t RESERVED29[4]; - __IO uint32_t MACPPSCR; - uint32_t RESERVED30[3]; - __IO uint32_t MACPPSTTSR; - __IO uint32_t MACPPSTTNR; - __IO uint32_t MACPPSIR; - __IO uint32_t MACPPSWR; - uint32_t RESERVED31[12]; - __IO uint32_t MACPOCR; - __IO uint32_t MACSPI0R; - __IO uint32_t MACSPI1R; - __IO uint32_t MACSPI2R; - __IO uint32_t MACLMIR; - uint32_t RESERVED32[11]; - __IO uint32_t MTLOMR; - uint32_t RESERVED33[7]; - __IO uint32_t MTLISR; - uint32_t RESERVED34[55]; - __IO uint32_t MTLTQOMR; - __IO uint32_t MTLTQUR; - __IO uint32_t MTLTQDR; - uint32_t RESERVED35[8]; - __IO uint32_t MTLQICSR; - __IO uint32_t MTLRQOMR; - __IO uint32_t MTLRQMPOCR; - __IO uint32_t MTLRQDR; - uint32_t RESERVED36[177]; - __IO uint32_t DMAMR; - __IO uint32_t DMASBMR; - __IO uint32_t DMAISR; - __IO uint32_t DMADSR; - uint32_t RESERVED37[60]; - __IO uint32_t DMACCR; - __IO uint32_t DMACTCR; - __IO uint32_t DMACRCR; - uint32_t RESERVED38[2]; - __IO uint32_t DMACTDLAR; - uint32_t RESERVED39; - __IO uint32_t DMACRDLAR; - __IO uint32_t DMACTDTPR; - uint32_t RESERVED40; - __IO uint32_t DMACRDTPR; - __IO uint32_t DMACTDRLR; - __IO uint32_t DMACRDRLR; - __IO uint32_t DMACIER; - __IO uint32_t DMACRIWTR; -__IO uint32_t DMACSFCSR; - uint32_t RESERVED41; - __IO uint32_t DMACCATDR; - uint32_t RESERVED42; - __IO uint32_t DMACCARDR; - uint32_t RESERVED43; - __IO uint32_t DMACCATBR; - uint32_t RESERVED44; - __IO uint32_t DMACCARBR; - __IO uint32_t DMACSR; -uint32_t RESERVED45[2]; -__IO uint32_t DMACMFCR; -}ETH_TypeDef; -/** - * @brief External Interrupt/Event Controller - */ - -typedef struct -{ -__IO uint32_t RTSR1; /*!< EXTI Rising trigger selection register, Address offset: 0x00 */ -__IO uint32_t FTSR1; /*!< EXTI Falling trigger selection register, Address offset: 0x04 */ -__IO uint32_t SWIER1; /*!< EXTI Software interrupt event register, Address offset: 0x08 */ -__IO uint32_t D3PMR1; /*!< EXTI D3 Pending mask register, (same register as to SRDPMR1) Address offset: 0x0C */ -__IO uint32_t D3PCR1L; /*!< EXTI D3 Pending clear selection register low, (same register as to SRDPCR1L) Address offset: 0x10 */ -__IO uint32_t D3PCR1H; /*!< EXTI D3 Pending clear selection register High, (same register as to SRDPCR1H) Address offset: 0x14 */ -uint32_t RESERVED1[2]; /*!< Reserved, 0x18 to 0x1C */ -__IO uint32_t RTSR2; /*!< EXTI Rising trigger selection register, Address offset: 0x20 */ -__IO uint32_t FTSR2; /*!< EXTI Falling trigger selection register, Address offset: 0x24 */ -__IO uint32_t SWIER2; /*!< EXTI Software interrupt event register, Address offset: 0x28 */ -__IO uint32_t D3PMR2; /*!< EXTI D3 Pending mask register, (same register as to SRDPMR2) Address offset: 0x2C */ -__IO uint32_t D3PCR2L; /*!< EXTI D3 Pending clear selection register low, (same register as to SRDPCR2L) Address offset: 0x30 */ -__IO uint32_t D3PCR2H; /*!< EXTI D3 Pending clear selection register High, (same register as to SRDPCR2H) Address offset: 0x34 */ -uint32_t RESERVED2[2]; /*!< Reserved, 0x38 to 0x3C */ -__IO uint32_t RTSR3; /*!< EXTI Rising trigger selection register, Address offset: 0x40 */ -__IO uint32_t FTSR3; /*!< EXTI Falling trigger selection register, Address offset: 0x44 */ -__IO uint32_t SWIER3; /*!< EXTI Software interrupt event register, Address offset: 0x48 */ -__IO uint32_t D3PMR3; /*!< EXTI D3 Pending mask register, (same register as to SRDPMR3) Address offset: 0x4C */ -__IO uint32_t D3PCR3L; /*!< EXTI D3 Pending clear selection register low, (same register as to SRDPCR3L) Address offset: 0x50 */ -__IO uint32_t D3PCR3H; /*!< EXTI D3 Pending clear selection register High, (same register as to SRDPCR3H) Address offset: 0x54 */ -uint32_t RESERVED3[10]; /*!< Reserved, 0x58 to 0x7C */ -__IO uint32_t IMR1; /*!< EXTI Interrupt mask register, Address offset: 0x80 */ -__IO uint32_t EMR1; /*!< EXTI Event mask register, Address offset: 0x84 */ -__IO uint32_t PR1; /*!< EXTI Pending register, Address offset: 0x88 */ -uint32_t RESERVED4; /*!< Reserved, 0x8C */ -__IO uint32_t IMR2; /*!< EXTI Interrupt mask register, Address offset: 0x90 */ -__IO uint32_t EMR2; /*!< EXTI Event mask register, Address offset: 0x94 */ -__IO uint32_t PR2; /*!< EXTI Pending register, Address offset: 0x98 */ -uint32_t RESERVED5; /*!< Reserved, 0x9C */ -__IO uint32_t IMR3; /*!< EXTI Interrupt mask register, Address offset: 0xA0 */ -__IO uint32_t EMR3; /*!< EXTI Event mask register, Address offset: 0xA4 */ -__IO uint32_t PR3; /*!< EXTI Pending register, Address offset: 0xA8 */ -}EXTI_TypeDef; - -/** - * @brief This structure registers corresponds to EXTI_Typdef CPU1/CPU2 registers subset (IMRx, EMRx and PRx), allowing to define EXTI_D1/EXTI_D2 - * with rapid/common access to these IMRx, EMRx, PRx registers for CPU1 and CPU2. - * Note that EXTI_D1 and EXTI_D2 bases addresses are calculated to point to CPUx first register: - * IMR1 in case of EXTI_D1 that is addressing CPU1 (Coretx-M7) - * C2IMR1 in case of EXTI_D2 that is addressing CPU2 (Coretx-M4) - * Note: EXTI_D2 and corresponding C2IMRx, C2EMRx and C2PRx registers are available for Dual Core devices only - */ - -typedef struct -{ -__IO uint32_t IMR1; /*!< EXTI Interrupt mask register, Address offset: 0x00 */ -__IO uint32_t EMR1; /*!< EXTI Event mask register, Address offset: 0x04 */ -__IO uint32_t PR1; /*!< EXTI Pending register, Address offset: 0x08 */ -uint32_t RESERVED1; /*!< Reserved, 0x0C */ -__IO uint32_t IMR2; /*!< EXTI Interrupt mask register, Address offset: 0x10 */ -__IO uint32_t EMR2; /*!< EXTI Event mask register, Address offset: 0x14 */ -__IO uint32_t PR2; /*!< EXTI Pending register, Address offset: 0x18 */ -uint32_t RESERVED2; /*!< Reserved, 0x1C */ -__IO uint32_t IMR3; /*!< EXTI Interrupt mask register, Address offset: 0x20 */ -__IO uint32_t EMR3; /*!< EXTI Event mask register, Address offset: 0x24 */ -__IO uint32_t PR3; /*!< EXTI Pending register, Address offset: 0x28 */ -}EXTI_Core_TypeDef; - - -/** - * @brief FLASH Registers - */ - -typedef struct -{ - __IO uint32_t ACR; /*!< FLASH access control register, Address offset: 0x00 */ - __IO uint32_t KEYR1; /*!< Flash Key Register for bank1, Address offset: 0x04 */ - __IO uint32_t OPTKEYR; /*!< Flash Option Key Register, Address offset: 0x08 */ - __IO uint32_t CR1; /*!< Flash Control Register for bank1, Address offset: 0x0C */ - __IO uint32_t SR1; /*!< Flash Status Register for bank1, Address offset: 0x10 */ - __IO uint32_t CCR1; /*!< Flash Control Register for bank1, Address offset: 0x14 */ - __IO uint32_t OPTCR; /*!< Flash Option Control Register, Address offset: 0x18 */ - __IO uint32_t OPTSR_CUR; /*!< Flash Option Status Current Register, Address offset: 0x1C */ - __IO uint32_t OPTSR_PRG; /*!< Flash Option Status to Program Register, Address offset: 0x20 */ - __IO uint32_t OPTCCR; /*!< Flash Option Clear Control Register, Address offset: 0x24 */ - __IO uint32_t PRAR_CUR1; /*!< Flash Current Protection Address Register for bank1, Address offset: 0x28 */ - __IO uint32_t PRAR_PRG1; /*!< Flash Protection Address to Program Register for bank1, Address offset: 0x2C */ - __IO uint32_t SCAR_CUR1; /*!< Flash Current Secure Address Register for bank1, Address offset: 0x30 */ - __IO uint32_t SCAR_PRG1; /*!< Flash Secure Address to Program Register for bank1, Address offset: 0x34 */ - __IO uint32_t WPSN_CUR1; /*!< Flash Current Write Protection Register on bank1, Address offset: 0x38 */ - __IO uint32_t WPSN_PRG1; /*!< Flash Write Protection to Program Register on bank1, Address offset: 0x3C */ - __IO uint32_t BOOT_CUR; /*!< Flash Current Boot Address for Pelican Core Register, Address offset: 0x40 */ - __IO uint32_t BOOT_PRG; /*!< Flash Boot Address to Program for Pelican Core Register, Address offset: 0x44 */ - uint32_t RESERVED0[2]; /*!< Reserved, 0x48 to 0x4C */ - __IO uint32_t CRCCR1; /*!< Flash CRC Control register For Bank1 Register , Address offset: 0x50 */ - __IO uint32_t CRCSADD1; /*!< Flash CRC Start Address Register for Bank1 , Address offset: 0x54 */ - __IO uint32_t CRCEADD1; /*!< Flash CRC End Address Register for Bank1 , Address offset: 0x58 */ - __IO uint32_t CRCDATA; /*!< Flash CRC Data Register for Bank1 , Address offset: 0x5C */ - __IO uint32_t ECC_FA1; /*!< Flash ECC Fail Address For Bank1 Register , Address offset: 0x60 */ - uint32_t RESERVED[3]; /*!< Reserved, 0x64 to 0x6C */ - __IO uint32_t OPTSR2_CUR; /*!< Flash Option Status Current Register 2, Address offset: 0x70 */ - __IO uint32_t OPTSR2_PRG; /*!< Flash Option Status to Program Register 2, Address offset: 0x74 */ -} FLASH_TypeDef; - -/** - * @brief Filter and Mathematical ACcelerator - */ -typedef struct -{ - __IO uint32_t X1BUFCFG; /*!< FMAC X1 Buffer Configuration register, Address offset: 0x00 */ - __IO uint32_t X2BUFCFG; /*!< FMAC X2 Buffer Configuration register, Address offset: 0x04 */ - __IO uint32_t YBUFCFG; /*!< FMAC Y Buffer Configuration register, Address offset: 0x08 */ - __IO uint32_t PARAM; /*!< FMAC Parameter register, Address offset: 0x0C */ - __IO uint32_t CR; /*!< FMAC Control register, Address offset: 0x10 */ - __IO uint32_t SR; /*!< FMAC Status register, Address offset: 0x14 */ - __IO uint32_t WDATA; /*!< FMAC Write Data register, Address offset: 0x18 */ - __IO uint32_t RDATA; /*!< FMAC Read Data register, Address offset: 0x1C */ -} FMAC_TypeDef; - -/** - * @brief Flexible Memory Controller - */ - -typedef struct -{ - __IO uint32_t BTCR[8]; /*!< NOR/PSRAM chip-select control register(BCR) and chip-select timing register(BTR), Address offset: 0x00-1C */ -} FMC_Bank1_TypeDef; - -/** - * @brief Flexible Memory Controller Bank1E - */ - -typedef struct -{ - __IO uint32_t BWTR[7]; /*!< NOR/PSRAM write timing registers, Address offset: 0x104-0x11C */ -} FMC_Bank1E_TypeDef; - -/** - * @brief Flexible Memory Controller Bank2 - */ - -typedef struct -{ - __IO uint32_t PCR2; /*!< NAND Flash control register 2, Address offset: 0x60 */ - __IO uint32_t SR2; /*!< NAND Flash FIFO status and interrupt register 2, Address offset: 0x64 */ - __IO uint32_t PMEM2; /*!< NAND Flash Common memory space timing register 2, Address offset: 0x68 */ - __IO uint32_t PATT2; /*!< NAND Flash Attribute memory space timing register 2, Address offset: 0x6C */ - uint32_t RESERVED0; /*!< Reserved, 0x70 */ - __IO uint32_t ECCR2; /*!< NAND Flash ECC result registers 2, Address offset: 0x74 */ -} FMC_Bank2_TypeDef; - -/** - * @brief Flexible Memory Controller Bank3 - */ - -typedef struct -{ - __IO uint32_t PCR; /*!< NAND Flash control register 3, Address offset: 0x80 */ - __IO uint32_t SR; /*!< NAND Flash FIFO status and interrupt register 3, Address offset: 0x84 */ - __IO uint32_t PMEM; /*!< NAND Flash Common memory space timing register 3, Address offset: 0x88 */ - __IO uint32_t PATT; /*!< NAND Flash Attribute memory space timing register 3, Address offset: 0x8C */ - uint32_t RESERVED; /*!< Reserved, 0x90 */ - __IO uint32_t ECCR; /*!< NAND Flash ECC result registers 3, Address offset: 0x94 */ -} FMC_Bank3_TypeDef; - -/** - * @brief Flexible Memory Controller Bank5 and 6 - */ - - -typedef struct -{ - __IO uint32_t SDCR[2]; /*!< SDRAM Control registers , Address offset: 0x140-0x144 */ - __IO uint32_t SDTR[2]; /*!< SDRAM Timing registers , Address offset: 0x148-0x14C */ - __IO uint32_t SDCMR; /*!< SDRAM Command Mode register, Address offset: 0x150 */ - __IO uint32_t SDRTR; /*!< SDRAM Refresh Timer register, Address offset: 0x154 */ - __IO uint32_t SDSR; /*!< SDRAM Status register, Address offset: 0x158 */ -} FMC_Bank5_6_TypeDef; - -/** - * @brief General Purpose I/O - */ - -typedef struct -{ - __IO uint32_t MODER; /*!< GPIO port mode register, Address offset: 0x00 */ - __IO uint32_t OTYPER; /*!< GPIO port output type register, Address offset: 0x04 */ - __IO uint32_t OSPEEDR; /*!< GPIO port output speed register, Address offset: 0x08 */ - __IO uint32_t PUPDR; /*!< GPIO port pull-up/pull-down register, Address offset: 0x0C */ - __IO uint32_t IDR; /*!< GPIO port input data register, Address offset: 0x10 */ - __IO uint32_t ODR; /*!< GPIO port output data register, Address offset: 0x14 */ - __IO uint32_t BSRR; /*!< GPIO port bit set/reset, Address offset: 0x18 */ - __IO uint32_t LCKR; /*!< GPIO port configuration lock register, Address offset: 0x1C */ - __IO uint32_t AFR[2]; /*!< GPIO alternate function registers, Address offset: 0x20-0x24 */ -} GPIO_TypeDef; - -/** - * @brief Operational Amplifier (OPAMP) - */ - -typedef struct -{ - __IO uint32_t CSR; /*!< OPAMP control/status register, Address offset: 0x00 */ - __IO uint32_t OTR; /*!< OPAMP offset trimming register for normal mode, Address offset: 0x04 */ - __IO uint32_t HSOTR; /*!< OPAMP offset trimming register for high speed mode, Address offset: 0x08 */ -} OPAMP_TypeDef; - -/** - * @brief System configuration controller - */ - -typedef struct -{ - uint32_t RESERVED1; /*!< Reserved, Address offset: 0x00 */ - __IO uint32_t PMCR; /*!< SYSCFG peripheral mode configuration register, Address offset: 0x04 */ - __IO uint32_t EXTICR[4]; /*!< SYSCFG external interrupt configuration registers, Address offset: 0x08-0x14 */ - __IO uint32_t CFGR; /*!< SYSCFG configuration registers, Address offset: 0x18 */ - uint32_t RESERVED2; /*!< Reserved, Address offset: 0x1C */ - __IO uint32_t CCCSR; /*!< SYSCFG compensation cell control/status register, Address offset: 0x20 */ - __IO uint32_t CCVR; /*!< SYSCFG compensation cell value register, Address offset: 0x24 */ - __IO uint32_t CCCR; /*!< SYSCFG compensation cell code register, Address offset: 0x28 */ - uint32_t RESERVED3; /*!< Reserved, Address offset: 0x2C */ - __IO uint32_t ADC2ALT; /*!< ADC2 internal input alternate connection register, Address offset: 0x30 */ - uint32_t RESERVED4[60]; /*!< Reserved, 0x34-0x120 */ - __IO uint32_t PKGR; /*!< SYSCFG package register, Address offset: 0x124 */ - uint32_t RESERVED5[118]; /*!< Reserved, 0x128-0x2FC */ - __IO uint32_t UR0; /*!< SYSCFG user register 0, Address offset: 0x300 */ - __IO uint32_t UR1; /*!< SYSCFG user register 1, Address offset: 0x304 */ - __IO uint32_t UR2; /*!< SYSCFG user register 2, Address offset: 0x308 */ - __IO uint32_t UR3; /*!< SYSCFG user register 3, Address offset: 0x30C */ - __IO uint32_t UR4; /*!< SYSCFG user register 4, Address offset: 0x310 */ - __IO uint32_t UR5; /*!< SYSCFG user register 5, Address offset: 0x314 */ - __IO uint32_t UR6; /*!< SYSCFG user register 6, Address offset: 0x318 */ - __IO uint32_t UR7; /*!< SYSCFG user register 7, Address offset: 0x31C */ - uint32_t RESERVED6[3]; /*!< Reserved, Address offset: 0x320-0x328 */ - __IO uint32_t UR11; /*!< SYSCFG user register 11, Address offset: 0x32C */ - __IO uint32_t UR12; /*!< SYSCFG user register 12, Address offset: 0x330 */ - __IO uint32_t UR13; /*!< SYSCFG user register 13, Address offset: 0x334 */ - __IO uint32_t UR14; /*!< SYSCFG user register 14, Address offset: 0x338 */ - __IO uint32_t UR15; /*!< SYSCFG user register 15, Address offset: 0x33C */ - __IO uint32_t UR16; /*!< SYSCFG user register 16, Address offset: 0x340 */ - __IO uint32_t UR17; /*!< SYSCFG user register 17, Address offset: 0x344 */ - __IO uint32_t UR18; /*!< SYSCFG user register 18, Address offset: 0x348 */ - -} SYSCFG_TypeDef; - -/** - * @brief Inter-integrated Circuit Interface - */ - -typedef struct -{ - __IO uint32_t CR1; /*!< I2C Control register 1, Address offset: 0x00 */ - __IO uint32_t CR2; /*!< I2C Control register 2, Address offset: 0x04 */ - __IO uint32_t OAR1; /*!< I2C Own address 1 register, Address offset: 0x08 */ - __IO uint32_t OAR2; /*!< I2C Own address 2 register, Address offset: 0x0C */ - __IO uint32_t TIMINGR; /*!< I2C Timing register, Address offset: 0x10 */ - __IO uint32_t TIMEOUTR; /*!< I2C Timeout register, Address offset: 0x14 */ - __IO uint32_t ISR; /*!< I2C Interrupt and status register, Address offset: 0x18 */ - __IO uint32_t ICR; /*!< I2C Interrupt clear register, Address offset: 0x1C */ - __IO uint32_t PECR; /*!< I2C PEC register, Address offset: 0x20 */ - __IO uint32_t RXDR; /*!< I2C Receive data register, Address offset: 0x24 */ - __IO uint32_t TXDR; /*!< I2C Transmit data register, Address offset: 0x28 */ -} I2C_TypeDef; - -/** - * @brief Independent WATCHDOG - */ - -typedef struct -{ - __IO uint32_t KR; /*!< IWDG Key register, Address offset: 0x00 */ - __IO uint32_t PR; /*!< IWDG Prescaler register, Address offset: 0x04 */ - __IO uint32_t RLR; /*!< IWDG Reload register, Address offset: 0x08 */ - __IO uint32_t SR; /*!< IWDG Status register, Address offset: 0x0C */ - __IO uint32_t WINR; /*!< IWDG Window register, Address offset: 0x10 */ -} IWDG_TypeDef; - - -/** - * @brief LCD-TFT Display Controller - */ - -typedef struct -{ - uint32_t RESERVED0[2]; /*!< Reserved, 0x00-0x04 */ - __IO uint32_t SSCR; /*!< LTDC Synchronization Size Configuration Register, Address offset: 0x08 */ - __IO uint32_t BPCR; /*!< LTDC Back Porch Configuration Register, Address offset: 0x0C */ - __IO uint32_t AWCR; /*!< LTDC Active Width Configuration Register, Address offset: 0x10 */ - __IO uint32_t TWCR; /*!< LTDC Total Width Configuration Register, Address offset: 0x14 */ - __IO uint32_t GCR; /*!< LTDC Global Control Register, Address offset: 0x18 */ - uint32_t RESERVED1[2]; /*!< Reserved, 0x1C-0x20 */ - __IO uint32_t SRCR; /*!< LTDC Shadow Reload Configuration Register, Address offset: 0x24 */ - uint32_t RESERVED2[1]; /*!< Reserved, 0x28 */ - __IO uint32_t BCCR; /*!< LTDC Background Color Configuration Register, Address offset: 0x2C */ - uint32_t RESERVED3[1]; /*!< Reserved, 0x30 */ - __IO uint32_t IER; /*!< LTDC Interrupt Enable Register, Address offset: 0x34 */ - __IO uint32_t ISR; /*!< LTDC Interrupt Status Register, Address offset: 0x38 */ - __IO uint32_t ICR; /*!< LTDC Interrupt Clear Register, Address offset: 0x3C */ - __IO uint32_t LIPCR; /*!< LTDC Line Interrupt Position Configuration Register, Address offset: 0x40 */ - __IO uint32_t CPSR; /*!< LTDC Current Position Status Register, Address offset: 0x44 */ - __IO uint32_t CDSR; /*!< LTDC Current Display Status Register, Address offset: 0x48 */ -} LTDC_TypeDef; - -/** - * @brief LCD-TFT Display layer x Controller - */ - -typedef struct -{ - __IO uint32_t CR; /*!< LTDC Layerx Control Register Address offset: 0x84 */ - __IO uint32_t WHPCR; /*!< LTDC Layerx Window Horizontal Position Configuration Register Address offset: 0x88 */ - __IO uint32_t WVPCR; /*!< LTDC Layerx Window Vertical Position Configuration Register Address offset: 0x8C */ - __IO uint32_t CKCR; /*!< LTDC Layerx Color Keying Configuration Register Address offset: 0x90 */ - __IO uint32_t PFCR; /*!< LTDC Layerx Pixel Format Configuration Register Address offset: 0x94 */ - __IO uint32_t CACR; /*!< LTDC Layerx Constant Alpha Configuration Register Address offset: 0x98 */ - __IO uint32_t DCCR; /*!< LTDC Layerx Default Color Configuration Register Address offset: 0x9C */ - __IO uint32_t BFCR; /*!< LTDC Layerx Blending Factors Configuration Register Address offset: 0xA0 */ - uint32_t RESERVED0[2]; /*!< Reserved */ - __IO uint32_t CFBAR; /*!< LTDC Layerx Color Frame Buffer Address Register Address offset: 0xAC */ - __IO uint32_t CFBLR; /*!< LTDC Layerx Color Frame Buffer Length Register Address offset: 0xB0 */ - __IO uint32_t CFBLNR; /*!< LTDC Layerx ColorFrame Buffer Line Number Register Address offset: 0xB4 */ - uint32_t RESERVED1[3]; /*!< Reserved */ - __IO uint32_t CLUTWR; /*!< LTDC Layerx CLUT Write Register Address offset: 0x144 */ - -} LTDC_Layer_TypeDef; - -/** - * @brief Power Control - */ - -typedef struct -{ - __IO uint32_t CR1; /*!< PWR power control register 1, Address offset: 0x00 */ - __IO uint32_t CSR1; /*!< PWR power control status register 1, Address offset: 0x04 */ - __IO uint32_t CR2; /*!< PWR power control register 2, Address offset: 0x08 */ - __IO uint32_t CR3; /*!< PWR power control register 3, Address offset: 0x0C */ - __IO uint32_t CPUCR; /*!< PWR CPU control register, Address offset: 0x10 */ - uint32_t RESERVED0; /*!< Reserved, Address offset: 0x14 */ - __IO uint32_t D3CR; /*!< PWR D3 domain control register, Address offset: 0x18 */ - uint32_t RESERVED1; /*!< Reserved, Address offset: 0x1C */ - __IO uint32_t WKUPCR; /*!< PWR wakeup clear register, Address offset: 0x20 */ - __IO uint32_t WKUPFR; /*!< PWR wakeup flag register, Address offset: 0x24 */ - __IO uint32_t WKUPEPR; /*!< PWR wakeup enable and polarity register, Address offset: 0x28 */ -} PWR_TypeDef; - -/** - * @brief Reset and Clock Control - */ - -typedef struct -{ - __IO uint32_t CR; /*!< RCC clock control register, Address offset: 0x00 */ - __IO uint32_t HSICFGR; /*!< HSI Clock Calibration Register, Address offset: 0x04 */ - __IO uint32_t CRRCR; /*!< Clock Recovery RC Register, Address offset: 0x08 */ - __IO uint32_t CSICFGR; /*!< CSI Clock Calibration Register, Address offset: 0x0C */ - __IO uint32_t CFGR; /*!< RCC clock configuration register, Address offset: 0x10 */ - uint32_t RESERVED1; /*!< Reserved, Address offset: 0x14 */ - __IO uint32_t D1CFGR; /*!< RCC Domain 1 configuration register, Address offset: 0x18 */ - __IO uint32_t D2CFGR; /*!< RCC Domain 2 configuration register, Address offset: 0x1C */ - __IO uint32_t D3CFGR; /*!< RCC Domain 3 configuration register, Address offset: 0x20 */ - uint32_t RESERVED2; /*!< Reserved, Address offset: 0x24 */ - __IO uint32_t PLLCKSELR; /*!< RCC PLLs Clock Source Selection Register, Address offset: 0x28 */ - __IO uint32_t PLLCFGR; /*!< RCC PLLs Configuration Register, Address offset: 0x2C */ - __IO uint32_t PLL1DIVR; /*!< RCC PLL1 Dividers Configuration Register, Address offset: 0x30 */ - __IO uint32_t PLL1FRACR; /*!< RCC PLL1 Fractional Divider Configuration Register, Address offset: 0x34 */ - __IO uint32_t PLL2DIVR; /*!< RCC PLL2 Dividers Configuration Register, Address offset: 0x38 */ - __IO uint32_t PLL2FRACR; /*!< RCC PLL2 Fractional Divider Configuration Register, Address offset: 0x3C */ - __IO uint32_t PLL3DIVR; /*!< RCC PLL3 Dividers Configuration Register, Address offset: 0x40 */ - __IO uint32_t PLL3FRACR; /*!< RCC PLL3 Fractional Divider Configuration Register, Address offset: 0x44 */ - uint32_t RESERVED3; /*!< Reserved, Address offset: 0x48 */ - __IO uint32_t D1CCIPR; /*!< RCC Domain 1 Kernel Clock Configuration Register Address offset: 0x4C */ - __IO uint32_t D2CCIP1R; /*!< RCC Domain 2 Kernel Clock Configuration Register Address offset: 0x50 */ - __IO uint32_t D2CCIP2R; /*!< RCC Domain 2 Kernel Clock Configuration Register Address offset: 0x54 */ - __IO uint32_t D3CCIPR; /*!< RCC Domain 3 Kernel Clock Configuration Register Address offset: 0x58 */ - uint32_t RESERVED4; /*!< Reserved, Address offset: 0x5C */ - __IO uint32_t CIER; /*!< RCC Clock Source Interrupt Enable Register Address offset: 0x60 */ - __IO uint32_t CIFR; /*!< RCC Clock Source Interrupt Flag Register Address offset: 0x64 */ - __IO uint32_t CICR; /*!< RCC Clock Source Interrupt Clear Register Address offset: 0x68 */ - uint32_t RESERVED5; /*!< Reserved, Address offset: 0x6C */ - __IO uint32_t BDCR; /*!< RCC Vswitch Backup Domain Control Register, Address offset: 0x70 */ - __IO uint32_t CSR; /*!< RCC clock control & status register, Address offset: 0x74 */ - uint32_t RESERVED6; /*!< Reserved, Address offset: 0x78 */ - __IO uint32_t AHB3RSTR; /*!< RCC AHB3 peripheral reset register, Address offset: 0x7C */ - __IO uint32_t AHB1RSTR; /*!< RCC AHB1 peripheral reset register, Address offset: 0x80 */ - __IO uint32_t AHB2RSTR; /*!< RCC AHB2 peripheral reset register, Address offset: 0x84 */ - __IO uint32_t AHB4RSTR; /*!< RCC AHB4 peripheral reset register, Address offset: 0x88 */ - __IO uint32_t APB3RSTR; /*!< RCC APB3 peripheral reset register, Address offset: 0x8C */ - __IO uint32_t APB1LRSTR; /*!< RCC APB1 peripheral reset Low Word register, Address offset: 0x90 */ - __IO uint32_t APB1HRSTR; /*!< RCC APB1 peripheral reset High Word register, Address offset: 0x94 */ - __IO uint32_t APB2RSTR; /*!< RCC APB2 peripheral reset register, Address offset: 0x98 */ - __IO uint32_t APB4RSTR; /*!< RCC APB4 peripheral reset register, Address offset: 0x9C */ - __IO uint32_t GCR; /*!< RCC RCC Global Control Register, Address offset: 0xA0 */ - uint32_t RESERVED8; /*!< Reserved, Address offset: 0xA4 */ - __IO uint32_t D3AMR; /*!< RCC Domain 3 Autonomous Mode Register, Address offset: 0xA8 */ - uint32_t RESERVED11[9]; /*!< Reserved, 0xAC-0xCC Address offset: 0xAC */ - __IO uint32_t RSR; /*!< RCC Reset status register, Address offset: 0xD0 */ - __IO uint32_t AHB3ENR; /*!< RCC AHB3 peripheral clock register, Address offset: 0xD4 */ - __IO uint32_t AHB1ENR; /*!< RCC AHB1 peripheral clock register, Address offset: 0xD8 */ - __IO uint32_t AHB2ENR; /*!< RCC AHB2 peripheral clock register, Address offset: 0xDC */ - __IO uint32_t AHB4ENR; /*!< RCC AHB4 peripheral clock register, Address offset: 0xE0 */ - __IO uint32_t APB3ENR; /*!< RCC APB3 peripheral clock register, Address offset: 0xE4 */ - __IO uint32_t APB1LENR; /*!< RCC APB1 peripheral clock Low Word register, Address offset: 0xE8 */ - __IO uint32_t APB1HENR; /*!< RCC APB1 peripheral clock High Word register, Address offset: 0xEC */ - __IO uint32_t APB2ENR; /*!< RCC APB2 peripheral clock register, Address offset: 0xF0 */ - __IO uint32_t APB4ENR; /*!< RCC APB4 peripheral clock register, Address offset: 0xF4 */ - uint32_t RESERVED12; /*!< Reserved, Address offset: 0xF8 */ - __IO uint32_t AHB3LPENR; /*!< RCC AHB3 peripheral sleep clock register, Address offset: 0xFC */ - __IO uint32_t AHB1LPENR; /*!< RCC AHB1 peripheral sleep clock register, Address offset: 0x100 */ - __IO uint32_t AHB2LPENR; /*!< RCC AHB2 peripheral sleep clock register, Address offset: 0x104 */ - __IO uint32_t AHB4LPENR; /*!< RCC AHB4 peripheral sleep clock register, Address offset: 0x108 */ - __IO uint32_t APB3LPENR; /*!< RCC APB3 peripheral sleep clock register, Address offset: 0x10C */ - __IO uint32_t APB1LLPENR; /*!< RCC APB1 peripheral sleep clock Low Word register, Address offset: 0x110 */ - __IO uint32_t APB1HLPENR; /*!< RCC APB1 peripheral sleep clock High Word register, Address offset: 0x114 */ - __IO uint32_t APB2LPENR; /*!< RCC APB2 peripheral sleep clock register, Address offset: 0x118 */ - __IO uint32_t APB4LPENR; /*!< RCC APB4 peripheral sleep clock register, Address offset: 0x11C */ - uint32_t RESERVED13[4]; /*!< Reserved, 0x120-0x12C Address offset: 0x120 */ - -} RCC_TypeDef; - - -/** - * @brief Real-Time Clock - */ -typedef struct -{ - __IO uint32_t TR; /*!< RTC time register, Address offset: 0x00 */ - __IO uint32_t DR; /*!< RTC date register, Address offset: 0x04 */ - __IO uint32_t CR; /*!< RTC control register, Address offset: 0x08 */ - __IO uint32_t ISR; /*!< RTC initialization and status register, Address offset: 0x0C */ - __IO uint32_t PRER; /*!< RTC prescaler register, Address offset: 0x10 */ - __IO uint32_t WUTR; /*!< RTC wakeup timer register, Address offset: 0x14 */ - uint32_t RESERVED; /*!< Reserved, Address offset: 0x18 */ - __IO uint32_t ALRMAR; /*!< RTC alarm A register, Address offset: 0x1C */ - __IO uint32_t ALRMBR; /*!< RTC alarm B register, Address offset: 0x20 */ - __IO uint32_t WPR; /*!< RTC write protection register, Address offset: 0x24 */ - __IO uint32_t SSR; /*!< RTC sub second register, Address offset: 0x28 */ - __IO uint32_t SHIFTR; /*!< RTC shift control register, Address offset: 0x2C */ - __IO uint32_t TSTR; /*!< RTC time stamp time register, Address offset: 0x30 */ - __IO uint32_t TSDR; /*!< RTC time stamp date register, Address offset: 0x34 */ - __IO uint32_t TSSSR; /*!< RTC time-stamp sub second register, Address offset: 0x38 */ - __IO uint32_t CALR; /*!< RTC calibration register, Address offset: 0x3C */ - __IO uint32_t TAMPCR; /*!< RTC tamper configuration register, Address offset: 0x40 */ - __IO uint32_t ALRMASSR; /*!< RTC alarm A sub second register, Address offset: 0x44 */ - __IO uint32_t ALRMBSSR; /*!< RTC alarm B sub second register, Address offset: 0x48 */ - __IO uint32_t OR; /*!< RTC option register, Address offset: 0x4C */ - __IO uint32_t BKP0R; /*!< RTC backup register 0, Address offset: 0x50 */ - __IO uint32_t BKP1R; /*!< RTC backup register 1, Address offset: 0x54 */ - __IO uint32_t BKP2R; /*!< RTC backup register 2, Address offset: 0x58 */ - __IO uint32_t BKP3R; /*!< RTC backup register 3, Address offset: 0x5C */ - __IO uint32_t BKP4R; /*!< RTC backup register 4, Address offset: 0x60 */ - __IO uint32_t BKP5R; /*!< RTC backup register 5, Address offset: 0x64 */ - __IO uint32_t BKP6R; /*!< RTC backup register 6, Address offset: 0x68 */ - __IO uint32_t BKP7R; /*!< RTC backup register 7, Address offset: 0x6C */ - __IO uint32_t BKP8R; /*!< RTC backup register 8, Address offset: 0x70 */ - __IO uint32_t BKP9R; /*!< RTC backup register 9, Address offset: 0x74 */ - __IO uint32_t BKP10R; /*!< RTC backup register 10, Address offset: 0x78 */ - __IO uint32_t BKP11R; /*!< RTC backup register 11, Address offset: 0x7C */ - __IO uint32_t BKP12R; /*!< RTC backup register 12, Address offset: 0x80 */ - __IO uint32_t BKP13R; /*!< RTC backup register 13, Address offset: 0x84 */ - __IO uint32_t BKP14R; /*!< RTC backup register 14, Address offset: 0x88 */ - __IO uint32_t BKP15R; /*!< RTC backup register 15, Address offset: 0x8C */ - __IO uint32_t BKP16R; /*!< RTC backup register 16, Address offset: 0x90 */ - __IO uint32_t BKP17R; /*!< RTC backup register 17, Address offset: 0x94 */ - __IO uint32_t BKP18R; /*!< RTC backup register 18, Address offset: 0x98 */ - __IO uint32_t BKP19R; /*!< RTC backup register 19, Address offset: 0x9C */ - __IO uint32_t BKP20R; /*!< RTC backup register 20, Address offset: 0xA0 */ - __IO uint32_t BKP21R; /*!< RTC backup register 21, Address offset: 0xA4 */ - __IO uint32_t BKP22R; /*!< RTC backup register 22, Address offset: 0xA8 */ - __IO uint32_t BKP23R; /*!< RTC backup register 23, Address offset: 0xAC */ - __IO uint32_t BKP24R; /*!< RTC backup register 24, Address offset: 0xB0 */ - __IO uint32_t BKP25R; /*!< RTC backup register 25, Address offset: 0xB4 */ - __IO uint32_t BKP26R; /*!< RTC backup register 26, Address offset: 0xB8 */ - __IO uint32_t BKP27R; /*!< RTC backup register 27, Address offset: 0xBC */ - __IO uint32_t BKP28R; /*!< RTC backup register 28, Address offset: 0xC0 */ - __IO uint32_t BKP29R; /*!< RTC backup register 29, Address offset: 0xC4 */ - __IO uint32_t BKP30R; /*!< RTC backup register 30, Address offset: 0xC8 */ - __IO uint32_t BKP31R; /*!< RTC backup register 31, Address offset: 0xCC */ -} RTC_TypeDef; - -/** - * @brief Serial Audio Interface - */ - -typedef struct -{ - __IO uint32_t GCR; /*!< SAI global configuration register, Address offset: 0x00 */ - uint32_t RESERVED0[16]; /*!< Reserved, 0x04 - 0x43 */ - __IO uint32_t PDMCR; /*!< SAI PDM control register, Address offset: 0x44 */ - __IO uint32_t PDMDLY; /*!< SAI PDM delay register, Address offset: 0x48 */ -} SAI_TypeDef; - -typedef struct -{ - __IO uint32_t CR1; /*!< SAI block x configuration register 1, Address offset: 0x04 */ - __IO uint32_t CR2; /*!< SAI block x configuration register 2, Address offset: 0x08 */ - __IO uint32_t FRCR; /*!< SAI block x frame configuration register, Address offset: 0x0C */ - __IO uint32_t SLOTR; /*!< SAI block x slot register, Address offset: 0x10 */ - __IO uint32_t IMR; /*!< SAI block x interrupt mask register, Address offset: 0x14 */ - __IO uint32_t SR; /*!< SAI block x status register, Address offset: 0x18 */ - __IO uint32_t CLRFR; /*!< SAI block x clear flag register, Address offset: 0x1C */ - __IO uint32_t DR; /*!< SAI block x data register, Address offset: 0x20 */ -} SAI_Block_TypeDef; - -/** - * @brief SPDIF-RX Interface - */ - -typedef struct -{ - __IO uint32_t CR; /*!< Control register, Address offset: 0x00 */ - __IO uint32_t IMR; /*!< Interrupt mask register, Address offset: 0x04 */ - __IO uint32_t SR; /*!< Status register, Address offset: 0x08 */ - __IO uint32_t IFCR; /*!< Interrupt Flag Clear register, Address offset: 0x0C */ - __IO uint32_t DR; /*!< Data input register, Address offset: 0x10 */ - __IO uint32_t CSR; /*!< Channel Status register, Address offset: 0x14 */ - __IO uint32_t DIR; /*!< Debug Information register, Address offset: 0x18 */ - uint32_t RESERVED2; /*!< Reserved, 0x1A */ -} SPDIFRX_TypeDef; - - -/** - * @brief Secure digital input/output Interface - */ - -typedef struct -{ - __IO uint32_t POWER; /*!< SDMMC power control register, Address offset: 0x00 */ - __IO uint32_t CLKCR; /*!< SDMMC clock control register, Address offset: 0x04 */ - __IO uint32_t ARG; /*!< SDMMC argument register, Address offset: 0x08 */ - __IO uint32_t CMD; /*!< SDMMC command register, Address offset: 0x0C */ - __I uint32_t RESPCMD; /*!< SDMMC command response register, Address offset: 0x10 */ - __I uint32_t RESP1; /*!< SDMMC response 1 register, Address offset: 0x14 */ - __I uint32_t RESP2; /*!< SDMMC response 2 register, Address offset: 0x18 */ - __I uint32_t RESP3; /*!< SDMMC response 3 register, Address offset: 0x1C */ - __I uint32_t RESP4; /*!< SDMMC response 4 register, Address offset: 0x20 */ - __IO uint32_t DTIMER; /*!< SDMMC data timer register, Address offset: 0x24 */ - __IO uint32_t DLEN; /*!< SDMMC data length register, Address offset: 0x28 */ - __IO uint32_t DCTRL; /*!< SDMMC data control register, Address offset: 0x2C */ - __I uint32_t DCOUNT; /*!< SDMMC data counter register, Address offset: 0x30 */ - __I uint32_t STA; /*!< SDMMC status register, Address offset: 0x34 */ - __IO uint32_t ICR; /*!< SDMMC interrupt clear register, Address offset: 0x38 */ - __IO uint32_t MASK; /*!< SDMMC mask register, Address offset: 0x3C */ - __IO uint32_t ACKTIME; /*!< SDMMC Acknowledgement timer register, Address offset: 0x40 */ - uint32_t RESERVED0[3]; /*!< Reserved, 0x44 - 0x4C - 0x4C */ - __IO uint32_t IDMACTRL; /*!< SDMMC DMA control register, Address offset: 0x50 */ - __IO uint32_t IDMABSIZE; /*!< SDMMC DMA buffer size register, Address offset: 0x54 */ - __IO uint32_t IDMABASE0; /*!< SDMMC DMA buffer 0 base address register, Address offset: 0x58 */ - __IO uint32_t IDMABASE1; /*!< SDMMC DMA buffer 1 base address register, Address offset: 0x5C */ - uint32_t RESERVED1[8]; /*!< Reserved, 0x60-0x7C */ - __IO uint32_t FIFO; /*!< SDMMC data FIFO register, Address offset: 0x80 */ - uint32_t RESERVED2[222]; /*!< Reserved, 0x84-0x3F8 */ - __IO uint32_t IPVR; /*!< SDMMC data FIFO register, Address offset: 0x3FC */ -} SDMMC_TypeDef; - - -/** - * @brief Delay Block DLYB - */ - -typedef struct -{ - __IO uint32_t CR; /*!< DELAY BLOCK control register, Address offset: 0x00 */ - __IO uint32_t CFGR; /*!< DELAY BLOCK configuration register, Address offset: 0x04 */ -} DLYB_TypeDef; - -/** - * @brief HW Semaphore HSEM - */ - -typedef struct -{ - __IO uint32_t R[32]; /*!< 2-step write lock and read back registers, Address offset: 00h-7Ch */ - __IO uint32_t RLR[32]; /*!< 1-step read lock registers, Address offset: 80h-FCh */ - __IO uint32_t C1IER; /*!< HSEM Interrupt enable register , Address offset: 100h */ - __IO uint32_t C1ICR; /*!< HSEM Interrupt clear register , Address offset: 104h */ - __IO uint32_t C1ISR; /*!< HSEM Interrupt Status register , Address offset: 108h */ - __IO uint32_t C1MISR; /*!< HSEM Interrupt Masked Status register , Address offset: 10Ch */ - uint32_t Reserved[12]; /* Reserved Address offset: 110h-13Ch */ - __IO uint32_t CR; /*!< HSEM Semaphore clear register , Address offset: 140h */ - __IO uint32_t KEYR; /*!< HSEM Semaphore clear key register , Address offset: 144h */ - -} HSEM_TypeDef; - -typedef struct -{ - __IO uint32_t IER; /*!< HSEM interrupt enable register , Address offset: 0h */ - __IO uint32_t ICR; /*!< HSEM interrupt clear register , Address offset: 4h */ - __IO uint32_t ISR; /*!< HSEM interrupt status register , Address offset: 8h */ - __IO uint32_t MISR; /*!< HSEM masked interrupt status register , Address offset: Ch */ -} HSEM_Common_TypeDef; - -/** - * @brief Serial Peripheral Interface - */ - -typedef struct -{ - __IO uint32_t CR1; /*!< SPI/I2S Control register 1, Address offset: 0x00 */ - __IO uint32_t CR2; /*!< SPI Control register 2, Address offset: 0x04 */ - __IO uint32_t CFG1; /*!< SPI Configuration register 1, Address offset: 0x08 */ - __IO uint32_t CFG2; /*!< SPI Configuration register 2, Address offset: 0x0C */ - __IO uint32_t IER; /*!< SPI/I2S Interrupt Enable register, Address offset: 0x10 */ - __IO uint32_t SR; /*!< SPI/I2S Status register, Address offset: 0x14 */ - __IO uint32_t IFCR; /*!< SPI/I2S Interrupt/Status flags clear register, Address offset: 0x18 */ - uint32_t RESERVED0; /*!< Reserved, 0x1C */ - __IO uint32_t TXDR; /*!< SPI/I2S Transmit data register, Address offset: 0x20 */ - uint32_t RESERVED1[3]; /*!< Reserved, 0x24-0x2C */ - __IO uint32_t RXDR; /*!< SPI/I2S Receive data register, Address offset: 0x30 */ - uint32_t RESERVED2[3]; /*!< Reserved, 0x34-0x3C */ - __IO uint32_t CRCPOLY; /*!< SPI CRC Polynomial register, Address offset: 0x40 */ - __IO uint32_t TXCRC; /*!< SPI Transmitter CRC register, Address offset: 0x44 */ - __IO uint32_t RXCRC; /*!< SPI Receiver CRC register, Address offset: 0x48 */ - __IO uint32_t UDRDR; /*!< SPI Underrun data register, Address offset: 0x4C */ - __IO uint32_t I2SCFGR; /*!< I2S Configuration register, Address offset: 0x50 */ - -} SPI_TypeDef; - -/** - * @brief DTS - */ -typedef struct -{ - __IO uint32_t CFGR1; /*!< DTS configuration register, Address offset: 0x00 */ - uint32_t RESERVED0; /*!< Reserved, Address offset: 0x04 */ - __IO uint32_t T0VALR1; /*!< DTS T0 Value register, Address offset: 0x08 */ - uint32_t RESERVED1; /*!< Reserved, Address offset: 0x0C */ - __IO uint32_t RAMPVALR; /*!< DTS Ramp value register, Address offset: 0x10 */ - __IO uint32_t ITR1; /*!< DTS Interrupt threshold register, Address offset: 0x14 */ - uint32_t RESERVED2; /*!< Reserved, Address offset: 0x18 */ - __IO uint32_t DR; /*!< DTS data register, Address offset: 0x1C */ - __IO uint32_t SR; /*!< DTS status register Address offset: 0x20 */ - __IO uint32_t ITENR; /*!< DTS Interrupt enable register, Address offset: 0x24 */ - __IO uint32_t ICIFR; /*!< DTS Clear Interrupt flag register, Address offset: 0x28 */ - __IO uint32_t OR; /*!< DTS option register 1, Address offset: 0x2C */ -} -DTS_TypeDef; - -/** - * @brief TIM - */ - -typedef struct -{ - __IO uint32_t CR1; /*!< TIM control register 1, Address offset: 0x00 */ - __IO uint32_t CR2; /*!< TIM control register 2, Address offset: 0x04 */ - __IO uint32_t SMCR; /*!< TIM slave mode control register, Address offset: 0x08 */ - __IO uint32_t DIER; /*!< TIM DMA/interrupt enable register, Address offset: 0x0C */ - __IO uint32_t SR; /*!< TIM status register, Address offset: 0x10 */ - __IO uint32_t EGR; /*!< TIM event generation register, Address offset: 0x14 */ - __IO uint32_t CCMR1; /*!< TIM capture/compare mode register 1, Address offset: 0x18 */ - __IO uint32_t CCMR2; /*!< TIM capture/compare mode register 2, Address offset: 0x1C */ - __IO uint32_t CCER; /*!< TIM capture/compare enable register, Address offset: 0x20 */ - __IO uint32_t CNT; /*!< TIM counter register, Address offset: 0x24 */ - __IO uint32_t PSC; /*!< TIM prescaler, Address offset: 0x28 */ - __IO uint32_t ARR; /*!< TIM auto-reload register, Address offset: 0x2C */ - __IO uint32_t RCR; /*!< TIM repetition counter register, Address offset: 0x30 */ - __IO uint32_t CCR1; /*!< TIM capture/compare register 1, Address offset: 0x34 */ - __IO uint32_t CCR2; /*!< TIM capture/compare register 2, Address offset: 0x38 */ - __IO uint32_t CCR3; /*!< TIM capture/compare register 3, Address offset: 0x3C */ - __IO uint32_t CCR4; /*!< TIM capture/compare register 4, Address offset: 0x40 */ - __IO uint32_t BDTR; /*!< TIM break and dead-time register, Address offset: 0x44 */ - __IO uint32_t DCR; /*!< TIM DMA control register, Address offset: 0x48 */ - __IO uint32_t DMAR; /*!< TIM DMA address for full transfer, Address offset: 0x4C */ - uint32_t RESERVED1; /*!< Reserved, 0x50 */ - __IO uint32_t CCMR3; /*!< TIM capture/compare mode register 3, Address offset: 0x54 */ - __IO uint32_t CCR5; /*!< TIM capture/compare register5, Address offset: 0x58 */ - __IO uint32_t CCR6; /*!< TIM capture/compare register6, Address offset: 0x5C */ - __IO uint32_t AF1; /*!< TIM alternate function option register 1, Address offset: 0x60 */ - __IO uint32_t AF2; /*!< TIM alternate function option register 2, Address offset: 0x64 */ - __IO uint32_t TISEL; /*!< TIM Input Selection register, Address offset: 0x68 */ -} TIM_TypeDef; - -/** - * @brief LPTIMIMER - */ -typedef struct -{ - __IO uint32_t ISR; /*!< LPTIM Interrupt and Status register, Address offset: 0x00 */ - __IO uint32_t ICR; /*!< LPTIM Interrupt Clear register, Address offset: 0x04 */ - __IO uint32_t IER; /*!< LPTIM Interrupt Enable register, Address offset: 0x08 */ - __IO uint32_t CFGR; /*!< LPTIM Configuration register, Address offset: 0x0C */ - __IO uint32_t CR; /*!< LPTIM Control register, Address offset: 0x10 */ - __IO uint32_t CMP; /*!< LPTIM Compare register, Address offset: 0x14 */ - __IO uint32_t ARR; /*!< LPTIM Autoreload register, Address offset: 0x18 */ - __IO uint32_t CNT; /*!< LPTIM Counter register, Address offset: 0x1C */ - uint32_t RESERVED1; /*!< Reserved, 0x20 */ - __IO uint32_t CFGR2; /*!< LPTIM Configuration register, Address offset: 0x24 */ -} LPTIM_TypeDef; - -/** - * @brief Comparator - */ -typedef struct -{ - __IO uint32_t SR; /*!< Comparator status register, Address offset: 0x00 */ - __IO uint32_t ICFR; /*!< Comparator interrupt clear flag register, Address offset: 0x04 */ - __IO uint32_t OR; /*!< Comparator option register, Address offset: 0x08 */ -} COMPOPT_TypeDef; - -typedef struct -{ - __IO uint32_t CFGR; /*!< Comparator configuration register , Address offset: 0x00 */ -} COMP_TypeDef; - -typedef struct -{ - __IO uint32_t CFGR; /*!< COMP control and status register, used for bits common to several COMP instances, Address offset: 0x00 */ -} COMP_Common_TypeDef; -/** - * @brief Universal Synchronous Asynchronous Receiver Transmitter - */ - -typedef struct -{ - __IO uint32_t CR1; /*!< USART Control register 1, Address offset: 0x00 */ - __IO uint32_t CR2; /*!< USART Control register 2, Address offset: 0x04 */ - __IO uint32_t CR3; /*!< USART Control register 3, Address offset: 0x08 */ - __IO uint32_t BRR; /*!< USART Baud rate register, Address offset: 0x0C */ - __IO uint32_t GTPR; /*!< USART Guard time and prescaler register, Address offset: 0x10 */ - __IO uint32_t RTOR; /*!< USART Receiver Time Out register, Address offset: 0x14 */ - __IO uint32_t RQR; /*!< USART Request register, Address offset: 0x18 */ - __IO uint32_t ISR; /*!< USART Interrupt and status register, Address offset: 0x1C */ - __IO uint32_t ICR; /*!< USART Interrupt flag Clear register, Address offset: 0x20 */ - __IO uint32_t RDR; /*!< USART Receive Data register, Address offset: 0x24 */ - __IO uint32_t TDR; /*!< USART Transmit Data register, Address offset: 0x28 */ - __IO uint32_t PRESC; /*!< USART clock Prescaler register, Address offset: 0x2C */ -} USART_TypeDef; - -/** - * @brief Single Wire Protocol Master Interface SPWMI - */ -typedef struct -{ - __IO uint32_t CR; /*!< SWPMI Configuration/Control register, Address offset: 0x00 */ - __IO uint32_t BRR; /*!< SWPMI bitrate register, Address offset: 0x04 */ - uint32_t RESERVED1; /*!< Reserved, 0x08 */ - __IO uint32_t ISR; /*!< SWPMI Interrupt and Status register, Address offset: 0x0C */ - __IO uint32_t ICR; /*!< SWPMI Interrupt Flag Clear register, Address offset: 0x10 */ - __IO uint32_t IER; /*!< SWPMI Interrupt Enable register, Address offset: 0x14 */ - __IO uint32_t RFL; /*!< SWPMI Receive Frame Length register, Address offset: 0x18 */ - __IO uint32_t TDR; /*!< SWPMI Transmit data register, Address offset: 0x1C */ - __IO uint32_t RDR; /*!< SWPMI Receive data register, Address offset: 0x20 */ - __IO uint32_t OR; /*!< SWPMI Option register, Address offset: 0x24 */ -} SWPMI_TypeDef; - -/** - * @brief Window WATCHDOG - */ - -typedef struct -{ - __IO uint32_t CR; /*!< WWDG Control register, Address offset: 0x00 */ - __IO uint32_t CFR; /*!< WWDG Configuration register, Address offset: 0x04 */ - __IO uint32_t SR; /*!< WWDG Status register, Address offset: 0x08 */ -} WWDG_TypeDef; - - -/** - * @brief RAM_ECC_Specific_Registers - */ -typedef struct -{ - __IO uint32_t CR; /*!< RAMECC monitor configuration register */ - __IO uint32_t SR; /*!< RAMECC monitor status register */ - __IO uint32_t FAR; /*!< RAMECC monitor failing address register */ - __IO uint32_t FDRL; /*!< RAMECC monitor failing data low register */ - __IO uint32_t FDRH; /*!< RAMECC monitor failing data high register */ - __IO uint32_t FECR; /*!< RAMECC monitor failing ECC error code register */ -} RAMECC_MonitorTypeDef; - -typedef struct -{ - __IO uint32_t IER; /*!< RAMECC interrupt enable register */ -} RAMECC_TypeDef; -/** - * @} - */ - - -/** - * @brief Crypto Processor - */ - -typedef struct -{ - __IO uint32_t CR; /*!< CRYP control register, Address offset: 0x00 */ - __IO uint32_t SR; /*!< CRYP status register, Address offset: 0x04 */ - __IO uint32_t DIN; /*!< CRYP data input register, Address offset: 0x08 */ - __IO uint32_t DOUT; /*!< CRYP data output register, Address offset: 0x0C */ - __IO uint32_t DMACR; /*!< CRYP DMA control register, Address offset: 0x10 */ - __IO uint32_t IMSCR; /*!< CRYP interrupt mask set/clear register, Address offset: 0x14 */ - __IO uint32_t RISR; /*!< CRYP raw interrupt status register, Address offset: 0x18 */ - __IO uint32_t MISR; /*!< CRYP masked interrupt status register, Address offset: 0x1C */ - __IO uint32_t K0LR; /*!< CRYP key left register 0, Address offset: 0x20 */ - __IO uint32_t K0RR; /*!< CRYP key right register 0, Address offset: 0x24 */ - __IO uint32_t K1LR; /*!< CRYP key left register 1, Address offset: 0x28 */ - __IO uint32_t K1RR; /*!< CRYP key right register 1, Address offset: 0x2C */ - __IO uint32_t K2LR; /*!< CRYP key left register 2, Address offset: 0x30 */ - __IO uint32_t K2RR; /*!< CRYP key right register 2, Address offset: 0x34 */ - __IO uint32_t K3LR; /*!< CRYP key left register 3, Address offset: 0x38 */ - __IO uint32_t K3RR; /*!< CRYP key right register 3, Address offset: 0x3C */ - __IO uint32_t IV0LR; /*!< CRYP initialization vector left-word register 0, Address offset: 0x40 */ - __IO uint32_t IV0RR; /*!< CRYP initialization vector right-word register 0, Address offset: 0x44 */ - __IO uint32_t IV1LR; /*!< CRYP initialization vector left-word register 1, Address offset: 0x48 */ - __IO uint32_t IV1RR; /*!< CRYP initialization vector right-word register 1, Address offset: 0x4C */ - __IO uint32_t CSGCMCCM0R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 0, Address offset: 0x50 */ - __IO uint32_t CSGCMCCM1R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 1, Address offset: 0x54 */ - __IO uint32_t CSGCMCCM2R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 2, Address offset: 0x58 */ - __IO uint32_t CSGCMCCM3R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 3, Address offset: 0x5C */ - __IO uint32_t CSGCMCCM4R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 4, Address offset: 0x60 */ - __IO uint32_t CSGCMCCM5R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 5, Address offset: 0x64 */ - __IO uint32_t CSGCMCCM6R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 6, Address offset: 0x68 */ - __IO uint32_t CSGCMCCM7R; /*!< CRYP GCM/GMAC or CCM/CMAC context swap register 7, Address offset: 0x6C */ - __IO uint32_t CSGCM0R; /*!< CRYP GCM/GMAC context swap register 0, Address offset: 0x70 */ - __IO uint32_t CSGCM1R; /*!< CRYP GCM/GMAC context swap register 1, Address offset: 0x74 */ - __IO uint32_t CSGCM2R; /*!< CRYP GCM/GMAC context swap register 2, Address offset: 0x78 */ - __IO uint32_t CSGCM3R; /*!< CRYP GCM/GMAC context swap register 3, Address offset: 0x7C */ - __IO uint32_t CSGCM4R; /*!< CRYP GCM/GMAC context swap register 4, Address offset: 0x80 */ - __IO uint32_t CSGCM5R; /*!< CRYP GCM/GMAC context swap register 5, Address offset: 0x84 */ - __IO uint32_t CSGCM6R; /*!< CRYP GCM/GMAC context swap register 6, Address offset: 0x88 */ - __IO uint32_t CSGCM7R; /*!< CRYP GCM/GMAC context swap register 7, Address offset: 0x8C */ -} CRYP_TypeDef; - -/** - * @brief HASH - */ - -typedef struct -{ - __IO uint32_t CR; /*!< HASH control register, Address offset: 0x00 */ - __IO uint32_t DIN; /*!< HASH data input register, Address offset: 0x04 */ - __IO uint32_t STR; /*!< HASH start register, Address offset: 0x08 */ - __IO uint32_t HR[5]; /*!< HASH digest registers, Address offset: 0x0C-0x1C */ - __IO uint32_t IMR; /*!< HASH interrupt enable register, Address offset: 0x20 */ - __IO uint32_t SR; /*!< HASH status register, Address offset: 0x24 */ - uint32_t RESERVED[52]; /*!< Reserved, 0x28-0xF4 */ - __IO uint32_t CSR[54]; /*!< HASH context swap registers, Address offset: 0x0F8-0x1CC */ -} HASH_TypeDef; - -/** - * @brief HASH_DIGEST - */ - -typedef struct -{ - __IO uint32_t HR[8]; /*!< HASH digest registers, Address offset: 0x310-0x32C */ -} HASH_DIGEST_TypeDef; - - -/** - * @brief RNG - */ - -typedef struct -{ - __IO uint32_t CR; /*!< RNG control register, Address offset: 0x00 */ - __IO uint32_t SR; /*!< RNG status register, Address offset: 0x04 */ - __IO uint32_t DR; /*!< RNG data register, Address offset: 0x08 */ - uint32_t RESERVED; - __IO uint32_t HTCR; /*!< RNG health test configuration register, Address offset: 0x10 */ -} RNG_TypeDef; - -/** - * @brief MDIOS - */ - -typedef struct -{ - __IO uint32_t CR; - __IO uint32_t WRFR; - __IO uint32_t CWRFR; - __IO uint32_t RDFR; - __IO uint32_t CRDFR; - __IO uint32_t SR; - __IO uint32_t CLRFR; - uint32_t RESERVED[57]; - __IO uint32_t DINR0; - __IO uint32_t DINR1; - __IO uint32_t DINR2; - __IO uint32_t DINR3; - __IO uint32_t DINR4; - __IO uint32_t DINR5; - __IO uint32_t DINR6; - __IO uint32_t DINR7; - __IO uint32_t DINR8; - __IO uint32_t DINR9; - __IO uint32_t DINR10; - __IO uint32_t DINR11; - __IO uint32_t DINR12; - __IO uint32_t DINR13; - __IO uint32_t DINR14; - __IO uint32_t DINR15; - __IO uint32_t DINR16; - __IO uint32_t DINR17; - __IO uint32_t DINR18; - __IO uint32_t DINR19; - __IO uint32_t DINR20; - __IO uint32_t DINR21; - __IO uint32_t DINR22; - __IO uint32_t DINR23; - __IO uint32_t DINR24; - __IO uint32_t DINR25; - __IO uint32_t DINR26; - __IO uint32_t DINR27; - __IO uint32_t DINR28; - __IO uint32_t DINR29; - __IO uint32_t DINR30; - __IO uint32_t DINR31; - __IO uint32_t DOUTR0; - __IO uint32_t DOUTR1; - __IO uint32_t DOUTR2; - __IO uint32_t DOUTR3; - __IO uint32_t DOUTR4; - __IO uint32_t DOUTR5; - __IO uint32_t DOUTR6; - __IO uint32_t DOUTR7; - __IO uint32_t DOUTR8; - __IO uint32_t DOUTR9; - __IO uint32_t DOUTR10; - __IO uint32_t DOUTR11; - __IO uint32_t DOUTR12; - __IO uint32_t DOUTR13; - __IO uint32_t DOUTR14; - __IO uint32_t DOUTR15; - __IO uint32_t DOUTR16; - __IO uint32_t DOUTR17; - __IO uint32_t DOUTR18; - __IO uint32_t DOUTR19; - __IO uint32_t DOUTR20; - __IO uint32_t DOUTR21; - __IO uint32_t DOUTR22; - __IO uint32_t DOUTR23; - __IO uint32_t DOUTR24; - __IO uint32_t DOUTR25; - __IO uint32_t DOUTR26; - __IO uint32_t DOUTR27; - __IO uint32_t DOUTR28; - __IO uint32_t DOUTR29; - __IO uint32_t DOUTR30; - __IO uint32_t DOUTR31; -} MDIOS_TypeDef; - - -/** - * @brief USB_OTG_Core_Registers - */ -typedef struct -{ - __IO uint32_t GOTGCTL; /*!< USB_OTG Control and Status Register 000h */ - __IO uint32_t GOTGINT; /*!< USB_OTG Interrupt Register 004h */ - __IO uint32_t GAHBCFG; /*!< Core AHB Configuration Register 008h */ - __IO uint32_t GUSBCFG; /*!< Core USB Configuration Register 00Ch */ - __IO uint32_t GRSTCTL; /*!< Core Reset Register 010h */ - __IO uint32_t GINTSTS; /*!< Core Interrupt Register 014h */ - __IO uint32_t GINTMSK; /*!< Core Interrupt Mask Register 018h */ - __IO uint32_t GRXSTSR; /*!< Receive Sts Q Read Register 01Ch */ - __IO uint32_t GRXSTSP; /*!< Receive Sts Q Read & POP Register 020h */ - __IO uint32_t GRXFSIZ; /*!< Receive FIFO Size Register 024h */ - __IO uint32_t DIEPTXF0_HNPTXFSIZ; /*!< EP0 / Non Periodic Tx FIFO Size Register 028h */ - __IO uint32_t HNPTXSTS; /*!< Non Periodic Tx FIFO/Queue Sts reg 02Ch */ - uint32_t Reserved30[2]; /*!< Reserved 030h */ - __IO uint32_t GCCFG; /*!< General Purpose IO Register 038h */ - __IO uint32_t CID; /*!< User ID Register 03Ch */ - __IO uint32_t GSNPSID; /* USB_OTG core ID 040h*/ - __IO uint32_t GHWCFG1; /* User HW config1 044h*/ - __IO uint32_t GHWCFG2; /* User HW config2 048h*/ - __IO uint32_t GHWCFG3; /*!< User HW config3 04Ch */ - uint32_t Reserved6; /*!< Reserved 050h */ - __IO uint32_t GLPMCFG; /*!< LPM Register 054h */ - __IO uint32_t GPWRDN; /*!< Power Down Register 058h */ - __IO uint32_t GDFIFOCFG; /*!< DFIFO Software Config Register 05Ch */ - __IO uint32_t GADPCTL; /*!< ADP Timer, Control and Status Register 60Ch */ - uint32_t Reserved43[39]; /*!< Reserved 058h-0FFh */ - __IO uint32_t HPTXFSIZ; /*!< Host Periodic Tx FIFO Size Reg 100h */ - __IO uint32_t DIEPTXF[0x0F]; /*!< dev Periodic Transmit FIFO */ -} USB_OTG_GlobalTypeDef; - - -/** - * @brief USB_OTG_device_Registers - */ -typedef struct -{ - __IO uint32_t DCFG; /*!< dev Configuration Register 800h */ - __IO uint32_t DCTL; /*!< dev Control Register 804h */ - __IO uint32_t DSTS; /*!< dev Status Register (RO) 808h */ - uint32_t Reserved0C; /*!< Reserved 80Ch */ - __IO uint32_t DIEPMSK; /*!< dev IN Endpoint Mask 810h */ - __IO uint32_t DOEPMSK; /*!< dev OUT Endpoint Mask 814h */ - __IO uint32_t DAINT; /*!< dev All Endpoints Itr Reg 818h */ - __IO uint32_t DAINTMSK; /*!< dev All Endpoints Itr Mask 81Ch */ - uint32_t Reserved20; /*!< Reserved 820h */ - uint32_t Reserved9; /*!< Reserved 824h */ - __IO uint32_t DVBUSDIS; /*!< dev VBUS discharge Register 828h */ - __IO uint32_t DVBUSPULSE; /*!< dev VBUS Pulse Register 82Ch */ - __IO uint32_t DTHRCTL; /*!< dev threshold 830h */ - __IO uint32_t DIEPEMPMSK; /*!< dev empty msk 834h */ - __IO uint32_t DEACHINT; /*!< dedicated EP interrupt 838h */ - __IO uint32_t DEACHMSK; /*!< dedicated EP msk 83Ch */ - uint32_t Reserved40; /*!< dedicated EP mask 840h */ - __IO uint32_t DINEP1MSK; /*!< dedicated EP mask 844h */ - uint32_t Reserved44[15]; /*!< Reserved 844-87Ch */ - __IO uint32_t DOUTEP1MSK; /*!< dedicated EP msk 884h */ -} USB_OTG_DeviceTypeDef; - - -/** - * @brief USB_OTG_IN_Endpoint-Specific_Register - */ -typedef struct -{ - __IO uint32_t DIEPCTL; /*!< dev IN Endpoint Control Reg 900h + (ep_num * 20h) + 00h */ - uint32_t Reserved04; /*!< Reserved 900h + (ep_num * 20h) + 04h */ - __IO uint32_t DIEPINT; /*!< dev IN Endpoint Itr Reg 900h + (ep_num * 20h) + 08h */ - uint32_t Reserved0C; /*!< Reserved 900h + (ep_num * 20h) + 0Ch */ - __IO uint32_t DIEPTSIZ; /*!< IN Endpoint Txfer Size 900h + (ep_num * 20h) + 10h */ - __IO uint32_t DIEPDMA; /*!< IN Endpoint DMA Address Reg 900h + (ep_num * 20h) + 14h */ - __IO uint32_t DTXFSTS; /*!< IN Endpoint Tx FIFO Status Reg 900h + (ep_num * 20h) + 18h */ - uint32_t Reserved18; /*!< Reserved 900h+(ep_num*20h)+1Ch-900h+ (ep_num * 20h) + 1Ch */ -} USB_OTG_INEndpointTypeDef; - - -/** - * @brief USB_OTG_OUT_Endpoint-Specific_Registers - */ -typedef struct -{ - __IO uint32_t DOEPCTL; /*!< dev OUT Endpoint Control Reg B00h + (ep_num * 20h) + 00h */ - uint32_t Reserved04; /*!< Reserved B00h + (ep_num * 20h) + 04h */ - __IO uint32_t DOEPINT; /*!< dev OUT Endpoint Itr Reg B00h + (ep_num * 20h) + 08h */ - uint32_t Reserved0C; /*!< Reserved B00h + (ep_num * 20h) + 0Ch */ - __IO uint32_t DOEPTSIZ; /*!< dev OUT Endpoint Txfer Size B00h + (ep_num * 20h) + 10h */ - __IO uint32_t DOEPDMA; /*!< dev OUT Endpoint DMA Address B00h + (ep_num * 20h) + 14h */ - uint32_t Reserved18[2]; /*!< Reserved B00h + (ep_num * 20h) + 18h - B00h + (ep_num * 20h) + 1Ch */ -} USB_OTG_OUTEndpointTypeDef; - - -/** - * @brief USB_OTG_Host_Mode_Register_Structures - */ -typedef struct -{ - __IO uint32_t HCFG; /*!< Host Configuration Register 400h */ - __IO uint32_t HFIR; /*!< Host Frame Interval Register 404h */ - __IO uint32_t HFNUM; /*!< Host Frame Nbr/Frame Remaining 408h */ - uint32_t Reserved40C; /*!< Reserved 40Ch */ - __IO uint32_t HPTXSTS; /*!< Host Periodic Tx FIFO/ Queue Status 410h */ - __IO uint32_t HAINT; /*!< Host All Channels Interrupt Register 414h */ - __IO uint32_t HAINTMSK; /*!< Host All Channels Interrupt Mask 418h */ -} USB_OTG_HostTypeDef; - -/** - * @brief USB_OTG_Host_Channel_Specific_Registers - */ -typedef struct -{ - __IO uint32_t HCCHAR; /*!< Host Channel Characteristics Register 500h */ - __IO uint32_t HCSPLT; /*!< Host Channel Split Control Register 504h */ - __IO uint32_t HCINT; /*!< Host Channel Interrupt Register 508h */ - __IO uint32_t HCINTMSK; /*!< Host Channel Interrupt Mask Register 50Ch */ - __IO uint32_t HCTSIZ; /*!< Host Channel Transfer Size Register 510h */ - __IO uint32_t HCDMA; /*!< Host Channel DMA Address Register 514h */ - uint32_t Reserved[2]; /*!< Reserved */ -} USB_OTG_HostChannelTypeDef; -/** - * @} - */ - -/** - * @brief OCTO Serial Peripheral Interface - */ - -typedef struct -{ - __IO uint32_t CR; /*!< OCTOSPI Control register, Address offset: 0x000 */ - uint32_t RESERVED; /*!< Reserved, Address offset: 0x004 */ - __IO uint32_t DCR1; /*!< OCTOSPI Device Configuration register 1, Address offset: 0x008 */ - __IO uint32_t DCR2; /*!< OCTOSPI Device Configuration register 2, Address offset: 0x00C */ - __IO uint32_t DCR3; /*!< OCTOSPI Device Configuration register 3, Address offset: 0x010 */ - __IO uint32_t DCR4; /*!< OCTOSPI Device Configuration register 4, Address offset: 0x014 */ - uint32_t RESERVED1[2]; /*!< Reserved, Address offset: 0x018-0x01C */ - __IO uint32_t SR; /*!< OCTOSPI Status register, Address offset: 0x020 */ - __IO uint32_t FCR; /*!< OCTOSPI Flag Clear register, Address offset: 0x024 */ - uint32_t RESERVED2[6]; /*!< Reserved, Address offset: 0x028-0x03C */ - __IO uint32_t DLR; /*!< OCTOSPI Data Length register, Address offset: 0x040 */ - uint32_t RESERVED3; /*!< Reserved, Address offset: 0x044 */ - __IO uint32_t AR; /*!< OCTOSPI Address register, Address offset: 0x048 */ - uint32_t RESERVED4; /*!< Reserved, Address offset: 0x04C */ - __IO uint32_t DR; /*!< OCTOSPI Data register, Address offset: 0x050 */ - uint32_t RESERVED5[11]; /*!< Reserved, Address offset: 0x054-0x07C */ - __IO uint32_t PSMKR; /*!< OCTOSPI Polling Status Mask register, Address offset: 0x080 */ - uint32_t RESERVED6; /*!< Reserved, Address offset: 0x084 */ - __IO uint32_t PSMAR; /*!< OCTOSPI Polling Status Match register, Address offset: 0x088 */ - uint32_t RESERVED7; /*!< Reserved, Address offset: 0x08C */ - __IO uint32_t PIR; /*!< OCTOSPI Polling Interval register, Address offset: 0x090 */ - uint32_t RESERVED8[27]; /*!< Reserved, Address offset: 0x094-0x0FC */ - __IO uint32_t CCR; /*!< OCTOSPI Communication Configuration register, Address offset: 0x100 */ - uint32_t RESERVED9; /*!< Reserved, Address offset: 0x104 */ - __IO uint32_t TCR; /*!< OCTOSPI Timing Configuration register, Address offset: 0x108 */ - uint32_t RESERVED10; /*!< Reserved, Address offset: 0x10C */ - __IO uint32_t IR; /*!< OCTOSPI Instruction register, Address offset: 0x110 */ - uint32_t RESERVED11[3]; /*!< Reserved, Address offset: 0x114-0x11C */ - __IO uint32_t ABR; /*!< OCTOSPI Alternate Bytes register, Address offset: 0x120 */ - uint32_t RESERVED12[3]; /*!< Reserved, Address offset: 0x124-0x12C */ - __IO uint32_t LPTR; /*!< OCTOSPI Low Power Timeout register, Address offset: 0x130 */ - uint32_t RESERVED13[3]; /*!< Reserved, Address offset: 0x134-0x13C */ - __IO uint32_t WPCCR; /*!< OCTOSPI Wrap Communication Configuration register, Address offset: 0x140 */ - uint32_t RESERVED14; /*!< Reserved, Address offset: 0x144 */ - __IO uint32_t WPTCR; /*!< OCTOSPI Wrap Timing Configuration register, Address offset: 0x148 */ - uint32_t RESERVED15; /*!< Reserved, Address offset: 0x14C */ - __IO uint32_t WPIR; /*!< OCTOSPI Wrap Instruction register, Address offset: 0x150 */ - uint32_t RESERVED16[3]; /*!< Reserved, Address offset: 0x154-0x15C */ - __IO uint32_t WPABR; /*!< OCTOSPI Wrap Alternate Bytes register, Address offset: 0x160 */ - uint32_t RESERVED17[7]; /*!< Reserved, Address offset: 0x164-0x17C */ - __IO uint32_t WCCR; /*!< OCTOSPI Write Communication Configuration register, Address offset: 0x180 */ - uint32_t RESERVED18; /*!< Reserved, Address offset: 0x184 */ - __IO uint32_t WTCR; /*!< OCTOSPI Write Timing Configuration register, Address offset: 0x188 */ - uint32_t RESERVED19; /*!< Reserved, Address offset: 0x18C */ - __IO uint32_t WIR; /*!< OCTOSPI Write Instruction register, Address offset: 0x190 */ - uint32_t RESERVED20[3]; /*!< Reserved, Address offset: 0x194-0x19C */ - __IO uint32_t WABR; /*!< OCTOSPI Write Alternate Bytes register, Address offset: 0x1A0 */ - uint32_t RESERVED21[23]; /*!< Reserved, Address offset: 0x1A4-0x1FC */ - __IO uint32_t HLCR; /*!< OCTOSPI Hyperbus Latency Configuration register, Address offset: 0x200 */ - uint32_t RESERVED22[122]; /*!< Reserved, Address offset: 0x204-0x3EC */ - __IO uint32_t HWCFGR; /*!< OCTOSPI HW Configuration register, Address offset: 0x3F0 */ - __IO uint32_t VER; /*!< OCTOSPI Version register, Address offset: 0x3F4 */ - __IO uint32_t ID; /*!< OCTOSPI Identification register, Address offset: 0x3F8 */ - __IO uint32_t MID; /*!< OCTOPSI HW Magic ID register, Address offset: 0x3FC */ -} OCTOSPI_TypeDef; - -/** - * @} - */ -/** - * @brief OCTO Serial Peripheral Interface IO Manager - */ - -typedef struct -{ - __IO uint32_t CR; /*!< OCTOSPI IO Manager Control register, Address offset: 0x00 */ - __IO uint32_t PCR[3]; /*!< OCTOSPI IO Manager Port[1:3] Configuration register, Address offset: 0x04-0x20 */ -} OCTOSPIM_TypeDef; - -/** - * @} - */ - -/** - * @brief OTFD register - */ -typedef struct -{ - __IO uint32_t REG_CONFIGR; - __IO uint32_t REG_START_ADDR; - __IO uint32_t REG_END_ADDR; - __IO uint32_t REG_NONCER0; - __IO uint32_t REG_NONCER1; - __IO uint32_t REG_KEYR0; - __IO uint32_t REG_KEYR1; - __IO uint32_t REG_KEYR2; - __IO uint32_t REG_KEYR3; -} OTFDEC_Region_TypeDef; - -typedef struct -{ - __IO uint32_t CR; - uint32_t RESERVED1[191]; - __IO uint32_t ISR; - __IO uint32_t ICR; - __IO uint32_t IER; - uint32_t RESERVED2[56]; - __IO uint32_t HWCFGR2; - __IO uint32_t HWCFGR1; - __IO uint32_t VERR; - __IO uint32_t IPIDR; - __IO uint32_t SIDR; -} OTFDEC_TypeDef; -/** - * @} - */ - -/** - * @brief Global Programmer View - */ - -typedef struct -{ - uint32_t RESERVED0[2036]; /*!< Reserved, Address offset: 0x00-0x1FCC */ - __IO uint32_t AXI_PERIPH_ID_4; /*!< AXI interconnect - peripheral ID4 register, Address offset: 0x1FD0 */ - uint32_t AXI_PERIPH_ID_5; /*!< Reserved, Address offset: 0x1FD4 */ - uint32_t AXI_PERIPH_ID_6; /*!< Reserved, Address offset: 0x1FD8 */ - uint32_t AXI_PERIPH_ID_7; /*!< Reserved, Address offset: 0x1FDC */ - __IO uint32_t AXI_PERIPH_ID_0; /*!< AXI interconnect - peripheral ID0 register, Address offset: 0x1FE0 */ - __IO uint32_t AXI_PERIPH_ID_1; /*!< AXI interconnect - peripheral ID1 register, Address offset: 0x1FE4 */ - __IO uint32_t AXI_PERIPH_ID_2; /*!< AXI interconnect - peripheral ID2 register, Address offset: 0x1FE8 */ - __IO uint32_t AXI_PERIPH_ID_3; /*!< AXI interconnect - peripheral ID3 register, Address offset: 0x1FEC */ - __IO uint32_t AXI_COMP_ID_0; /*!< AXI interconnect - component ID0 register, Address offset: 0x1FF0 */ - __IO uint32_t AXI_COMP_ID_1; /*!< AXI interconnect - component ID1 register, Address offset: 0x1FF4 */ - __IO uint32_t AXI_COMP_ID_2; /*!< AXI interconnect - component ID2 register, Address offset: 0x1FF8 */ - __IO uint32_t AXI_COMP_ID_3; /*!< AXI interconnect - component ID3 register, Address offset: 0x1FFC */ - uint32_t RESERVED1[2]; /*!< Reserved, Address offset: 0x2000-0x2004 */ - __IO uint32_t AXI_TARG1_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 1 bus matrix issuing functionality register, Address offset: 0x2008 */ - uint32_t RESERVED2[6]; /*!< Reserved, Address offset: 0x200C-0x2020 */ - __IO uint32_t AXI_TARG1_FN_MOD2; /*!< AXI interconnect - TARG 1 bus matrix functionality 2 register, Address offset: 0x2024 */ - uint32_t RESERVED3; /*!< Reserved, Address offset: 0x2028 */ - __IO uint32_t AXI_TARG1_FN_MOD_LB; /*!< AXI interconnect - TARG 1 long burst functionality modification register, Address offset: 0x202C */ - uint32_t RESERVED4[54]; /*!< Reserved, Address offset: 0x2030-0x2104 */ - __IO uint32_t AXI_TARG1_FN_MOD; /*!< AXI interconnect - TARG 1 issuing functionality modification register, Address offset: 0x2108 */ - uint32_t RESERVED5[959]; /*!< Reserved, Address offset: 0x210C-0x3004 */ - __IO uint32_t AXI_TARG2_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 2 bus matrix issuing functionality register, Address offset: 0x3008 */ - uint32_t RESERVED6[6]; /*!< Reserved, Address offset: 0x300C-0x3020 */ - __IO uint32_t AXI_TARG2_FN_MOD2; /*!< AXI interconnect - TARG 2 bus matrix functionality 2 register, Address offset: 0x3024 */ - uint32_t RESERVED7; /*!< Reserved, Address offset: 0x3028 */ - __IO uint32_t AXI_TARG2_FN_MOD_LB; /*!< AXI interconnect - TARG 2 long burst functionality modification register, Address offset: 0x302C */ - uint32_t RESERVED8[54]; /*!< Reserved, Address offset: 0x3030-0x3104 */ - __IO uint32_t AXI_TARG2_FN_MOD; /*!< AXI interconnect - TARG 2 issuing functionality modification register, Address offset: 0x3108 */ - uint32_t RESERVED9[959]; /*!< Reserved, Address offset: 0x310C-0x4004 */ - __IO uint32_t AXI_TARG3_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 3 bus matrix issuing functionality register, Address offset: 0x4008 */ - uint32_t RESERVED10[1023]; /*!< Reserved, Address offset: 0x400C-0x5004 */ - __IO uint32_t AXI_TARG4_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 4 bus matrix issuing functionality register, Address offset: 0x5008 */ - uint32_t RESERVED11[1023]; /*!< Reserved, Address offset: 0x500C-0x6004 */ - __IO uint32_t AXI_TARG5_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 5 bus matrix issuing functionality register, Address offset: 0x6008 */ - uint32_t RESERVED12[1023]; /*!< Reserved, Address offset: 0x600C-0x7004 */ - __IO uint32_t AXI_TARG6_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 6 bus matrix issuing functionality register, Address offset: 0x7008 */ - uint32_t RESERVED13[1023]; /*!< Reserved, Address offset: 0x700C-0x8004 */ - __IO uint32_t AXI_TARG7_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 7 bus matrix issuing functionality register, Address offset: 0x8008 */ - uint32_t RESERVED14[6]; /*!< Reserved, Address offset: 0x800C-0x8020 */ - __IO uint32_t AXI_TARG7_FN_MOD2; /*!< AXI interconnect - TARG 7 bus matrix functionality 2 register, Address offset: 0x8024 */ - uint32_t RESERVED15; /*!< Reserved, Address offset: 0x8028 */ - __IO uint32_t AXI_TARG7_FN_MOD_LB; /*!< AXI interconnect - TARG 7 long burst functionality modification register, Address offset: 0x802C */ - uint32_t RESERVED16[54]; /*!< Reserved, Address offset: 0x8030-0x8104 */ - __IO uint32_t AXI_TARG7_FN_MOD; /*!< AXI interconnect - TARG 7 issuing functionality modification register, Address offset: 0x8108 */ - uint32_t RESERVED17[959]; /*!< Reserved, Address offset: 0x810C-0x9004 */ - __IO uint32_t AXI_TARG8_FN_MOD_ISS_BM; /*!< AXI interconnect - TARG 8 bus matrix issuing functionality register, Address offset: 0x9008 */ - uint32_t RESERVED117[6]; /*!< Reserved, Address offset: 0x900C-0x9020 */ - __IO uint32_t AXI_TARG8_FN_MOD2; /*!< AXI interconnect - TARG 8 bus matrix functionality 2 register, Address offset: 0x9024 */ - uint32_t RESERVED118[56]; /*!< Reserved, Address offset: 0x9028-0x9104 */ - __IO uint32_t AXI_TARG8_FN_MOD; /*!< AXI interconnect - TARG 8 issuing functionality modification register, Address offset: 0x9108 */ - uint32_t RESERVED119[58310]; /*!< Reserved, Address offset: 0x910C-0x42020 */ - __IO uint32_t AXI_INI1_FN_MOD2; /*!< AXI interconnect - INI 1 functionality modification 2 register, Address offset: 0x42024 */ - __IO uint32_t AXI_INI1_FN_MOD_AHB; /*!< AXI interconnect - INI 1 AHB functionality modification register, Address offset: 0x42028 */ - uint32_t RESERVED18[53]; /*!< Reserved, Address offset: 0x4202C-0x420FC */ - __IO uint32_t AXI_INI1_READ_QOS; /*!< AXI interconnect - INI 1 read QoS register, Address offset: 0x42100 */ - __IO uint32_t AXI_INI1_WRITE_QOS; /*!< AXI interconnect - INI 1 write QoS register, Address offset: 0x42104 */ - __IO uint32_t AXI_INI1_FN_MOD; /*!< AXI interconnect - INI 1 issuing functionality modification register, Address offset: 0x42108 */ - uint32_t RESERVED19[1021]; /*!< Reserved, Address offset: 0x4210C-0x430FC */ - __IO uint32_t AXI_INI2_READ_QOS; /*!< AXI interconnect - INI 2 read QoS register, Address offset: 0x43100 */ - __IO uint32_t AXI_INI2_WRITE_QOS; /*!< AXI interconnect - INI 2 write QoS register, Address offset: 0x43104 */ - __IO uint32_t AXI_INI2_FN_MOD; /*!< AXI interconnect - INI 2 issuing functionality modification register, Address offset: 0x43108 */ - uint32_t RESERVED20[966]; /*!< Reserved, Address offset: 0x4310C-0x44020 */ - __IO uint32_t AXI_INI3_FN_MOD2; /*!< AXI interconnect - INI 3 functionality modification 2 register, Address offset: 0x44024 */ - __IO uint32_t AXI_INI3_FN_MOD_AHB; /*!< AXI interconnect - INI 3 AHB functionality modification register, Address offset: 0x44028 */ - uint32_t RESERVED21[53]; /*!< Reserved, Address offset: 0x4402C-0x440FC */ - __IO uint32_t AXI_INI3_READ_QOS; /*!< AXI interconnect - INI 3 read QoS register, Address offset: 0x44100 */ - __IO uint32_t AXI_INI3_WRITE_QOS; /*!< AXI interconnect - INI 3 write QoS register, Address offset: 0x44104 */ - __IO uint32_t AXI_INI3_FN_MOD; /*!< AXI interconnect - INI 3 issuing functionality modification register, Address offset: 0x44108 */ - uint32_t RESERVED22[1021]; /*!< Reserved, Address offset: 0x4410C-0x450FC */ - __IO uint32_t AXI_INI4_READ_QOS; /*!< AXI interconnect - INI 4 read QoS register, Address offset: 0x45100 */ - __IO uint32_t AXI_INI4_WRITE_QOS; /*!< AXI interconnect - INI 4 write QoS register, Address offset: 0x45104 */ - __IO uint32_t AXI_INI4_FN_MOD; /*!< AXI interconnect - INI 4 issuing functionality modification register, Address offset: 0x45108 */ - uint32_t RESERVED23[1021]; /*!< Reserved, Address offset: 0x4510C-0x460FC */ - __IO uint32_t AXI_INI5_READ_QOS; /*!< AXI interconnect - INI 5 read QoS register, Address offset: 0x46100 */ - __IO uint32_t AXI_INI5_WRITE_QOS; /*!< AXI interconnect - INI 5 write QoS register, Address offset: 0x46104 */ - __IO uint32_t AXI_INI5_FN_MOD; /*!< AXI interconnect - INI 5 issuing functionality modification register, Address offset: 0x46108 */ - uint32_t RESERVED24[1021]; /*!< Reserved, Address offset: 0x4610C-0x470FC */ - __IO uint32_t AXI_INI6_READ_QOS; /*!< AXI interconnect - INI 6 read QoS register, Address offset: 0x47100 */ - __IO uint32_t AXI_INI6_WRITE_QOS; /*!< AXI interconnect - INI 6 write QoS register, Address offset: 0x47104 */ - __IO uint32_t AXI_INI6_FN_MOD; /*!< AXI interconnect - INI 6 issuing functionality modification register, Address offset: 0x47108 */ - -} GPV_TypeDef; - -/** @addtogroup Peripheral_memory_map - * @{ - */ -#define D1_ITCMRAM_BASE (0x00000000UL) /*!< Base address of : 64KB RAM reserved for CPU execution/instruction accessible over ITCM */ -#define D1_ITCMICP_BASE (0x00100000UL) /*!< Base address of : (up to 128KB) embedded Test FLASH memory accessible over ITCM */ -#define D1_DTCMRAM_BASE (0x20000000UL) /*!< Base address of : 128KB system data RAM accessible over DTCM */ -#define D1_AXIFLASH_BASE (0x08000000UL) /*!< Base address of : (up to 1 MB) embedded FLASH memory accessible over AXI */ -#define D1_AXIICP_BASE (0x1FF00000UL) /*!< Base address of : (up to 128KB) embedded Test FLASH memory accessible over AXI */ -#define D1_AXISRAM1_BASE (0x24000000UL) /*!< Base address of : (up to 128KB) system data RAM1 accessible over over AXI */ -#define D1_AXISRAM2_BASE (0x24020000UL) /*!< Base address of : (up to 192KB) system data RAM2 accessible over over AXI to be shared with ITCM (64K granularity) */ -#define D1_AXISRAM_BASE D1_AXISRAM1_BASE /*!< Base address of : (up to 320KB) system data RAM1/2 accessible over over AXI */ - -#define D2_AHBSRAM1_BASE (0x30000000UL) /*!< Base address of : (up to 16KB) system data RAM accessible over over AXI->AHB Bridge */ -#define D2_AHBSRAM2_BASE (0x30004000UL) /*!< Base address of : (up to 16KB) system data RAM accessible over over AXI->AHB Bridge */ -#define D2_AHBSRAM_BASE D2_AHBSRAM1_BASE /*!< Base address of : (up to 32KB) system data RAM1/2 accessible over over AXI->AHB Bridge */ - -#define D3_BKPSRAM_BASE (0x38800000UL) /*!< Base address of : Backup SRAM(4 KB) over AXI->AHB Bridge */ -#define D3_SRAM_BASE (0x38000000UL) /*!< Base address of : Backup SRAM(16 KB) over AXI->AHB Bridge */ - -#define PERIPH_BASE (0x40000000UL) /*!< Base address of : AHB/APB Peripherals */ -#define OCTOSPI1_BASE (0x90000000UL) /*!< Base address of : OCTOSPI1 memories accessible over AXI */ -#define OCTOSPI2_BASE (0x70000000UL) /*!< Base address of : OCTOSPI2 memories accessible over AXI */ - -#define FLASH_BANK1_BASE (0x08000000UL) /*!< Base address of : (up to 1 MB) Flash Bank1 accessible over AXI */ -#define FLASH_END (0x080FFFFFUL) /*!< FLASH end address */ - - -/* Legacy define */ -#define FLASH_BASE FLASH_BANK1_BASE - -/*!< Device electronic signature memory map */ -#define UID_BASE (0x1FF1E800UL) /*!< Unique device ID register base address */ -#define FLASHSIZE_BASE (0x1FF1E880UL) /*!< FLASH Size register base address */ - - -/*!< Peripheral memory map */ -#define D2_APB1PERIPH_BASE PERIPH_BASE -#define D2_APB2PERIPH_BASE (PERIPH_BASE + 0x00010000UL) -#define D2_AHB1PERIPH_BASE (PERIPH_BASE + 0x00020000UL) -#define D2_AHB2PERIPH_BASE (PERIPH_BASE + 0x08020000UL) - -#define D1_APB1PERIPH_BASE (PERIPH_BASE + 0x10000000UL) -#define D1_AHB1PERIPH_BASE (PERIPH_BASE + 0x12000000UL) - -#define D3_APB1PERIPH_BASE (PERIPH_BASE + 0x18000000UL) -#define D3_AHB1PERIPH_BASE (PERIPH_BASE + 0x18020000UL) - -/*!< Legacy Peripheral memory map */ -#define APB1PERIPH_BASE PERIPH_BASE -#define APB2PERIPH_BASE (PERIPH_BASE + 0x00010000UL) -#define AHB1PERIPH_BASE (PERIPH_BASE + 0x00020000UL) -#define AHB2PERIPH_BASE (PERIPH_BASE + 0x08000000UL) - - -/*!< D1_AHB1PERIPH peripherals */ - -#define MDMA_BASE (D1_AHB1PERIPH_BASE + 0x0000UL) -#define DMA2D_BASE (D1_AHB1PERIPH_BASE + 0x1000UL) -#define FLASH_R_BASE (D1_AHB1PERIPH_BASE + 0x2000UL) -#define FMC_R_BASE (D1_AHB1PERIPH_BASE + 0x4000UL) -#define OCTOSPI1_R_BASE (D1_AHB1PERIPH_BASE + 0x5000UL) -#define DLYB_OCTOSPI1_BASE (D1_AHB1PERIPH_BASE + 0x6000UL) -#define SDMMC1_BASE (D1_AHB1PERIPH_BASE + 0x7000UL) -#define DLYB_SDMMC1_BASE (D1_AHB1PERIPH_BASE + 0x8000UL) -#define RAMECC1_BASE (D1_AHB1PERIPH_BASE + 0x9000UL) -#define OCTOSPI2_R_BASE (D1_AHB1PERIPH_BASE + 0xA000UL) -#define DLYB_OCTOSPI2_BASE (D1_AHB1PERIPH_BASE + 0xB000UL) -#define OCTOSPIM_BASE (D1_AHB1PERIPH_BASE + 0xB400UL) - -#define OTFDEC1_BASE (D1_AHB1PERIPH_BASE + 0xB800UL) -#define OTFDEC1_REGION1_BASE (OTFDEC1_BASE + 0x20UL) -#define OTFDEC1_REGION2_BASE (OTFDEC1_BASE + 0x50UL) -#define OTFDEC1_REGION3_BASE (OTFDEC1_BASE + 0x80UL) -#define OTFDEC1_REGION4_BASE (OTFDEC1_BASE + 0xB0UL) -#define OTFDEC2_BASE (D1_AHB1PERIPH_BASE + 0xBC00UL) -#define OTFDEC2_REGION1_BASE (OTFDEC2_BASE + 0x20UL) -#define OTFDEC2_REGION2_BASE (OTFDEC2_BASE + 0x50UL) -#define OTFDEC2_REGION3_BASE (OTFDEC2_BASE + 0x80UL) -#define OTFDEC2_REGION4_BASE (OTFDEC2_BASE + 0xB0UL) - -/*!< D2_AHB1PERIPH peripherals */ - -#define DMA1_BASE (D2_AHB1PERIPH_BASE + 0x0000UL) -#define DMA2_BASE (D2_AHB1PERIPH_BASE + 0x0400UL) -#define DMAMUX1_BASE (D2_AHB1PERIPH_BASE + 0x0800UL) -#define ADC1_BASE (D2_AHB1PERIPH_BASE + 0x2000UL) -#define ADC2_BASE (D2_AHB1PERIPH_BASE + 0x2100UL) -#define ADC12_COMMON_BASE (D2_AHB1PERIPH_BASE + 0x2300UL) -#define ETH_BASE (D2_AHB1PERIPH_BASE + 0x8000UL) -#define ETH_MAC_BASE (ETH_BASE) - -/*!< USB registers base address */ -#define USB1_OTG_HS_PERIPH_BASE (0x40040000UL) -#define USB_OTG_GLOBAL_BASE (0x000UL) -#define USB_OTG_DEVICE_BASE (0x800UL) -#define USB_OTG_IN_ENDPOINT_BASE (0x900UL) -#define USB_OTG_OUT_ENDPOINT_BASE (0xB00UL) -#define USB_OTG_EP_REG_SIZE (0x20UL) -#define USB_OTG_HOST_BASE (0x400UL) -#define USB_OTG_HOST_PORT_BASE (0x440UL) -#define USB_OTG_HOST_CHANNEL_BASE (0x500UL) -#define USB_OTG_HOST_CHANNEL_SIZE (0x20UL) -#define USB_OTG_PCGCCTL_BASE (0xE00UL) -#define USB_OTG_FIFO_BASE (0x1000UL) -#define USB_OTG_FIFO_SIZE (0x1000UL) - -/*!< D2_AHB2PERIPH peripherals */ - -#define DCMI_BASE (D2_AHB2PERIPH_BASE + 0x0000UL) -#define PSSI_BASE (D2_AHB2PERIPH_BASE + 0x0400UL) -#define CRYP_BASE (D2_AHB2PERIPH_BASE + 0x1000UL) -#define HASH_BASE (D2_AHB2PERIPH_BASE + 0x1400UL) -#define HASH_DIGEST_BASE (D2_AHB2PERIPH_BASE + 0x1710UL) -#define RNG_BASE (D2_AHB2PERIPH_BASE + 0x1800UL) -#define SDMMC2_BASE (D2_AHB2PERIPH_BASE + 0x2400UL) -#define DLYB_SDMMC2_BASE (D2_AHB2PERIPH_BASE + 0x2800UL) -#define RAMECC2_BASE (D2_AHB2PERIPH_BASE + 0x3000UL) -#define FMAC_BASE (D2_AHB2PERIPH_BASE + 0x4000UL) -#define CORDIC_BASE (D2_AHB2PERIPH_BASE + 0x4400UL) - -/*!< D3_AHB1PERIPH peripherals */ -#define GPIOA_BASE (D3_AHB1PERIPH_BASE + 0x0000UL) -#define GPIOB_BASE (D3_AHB1PERIPH_BASE + 0x0400UL) -#define GPIOC_BASE (D3_AHB1PERIPH_BASE + 0x0800UL) -#define GPIOD_BASE (D3_AHB1PERIPH_BASE + 0x0C00UL) -#define GPIOE_BASE (D3_AHB1PERIPH_BASE + 0x1000UL) -#define GPIOF_BASE (D3_AHB1PERIPH_BASE + 0x1400UL) -#define GPIOG_BASE (D3_AHB1PERIPH_BASE + 0x1800UL) -#define GPIOH_BASE (D3_AHB1PERIPH_BASE + 0x1C00UL) -#define GPIOJ_BASE (D3_AHB1PERIPH_BASE + 0x2400UL) -#define GPIOK_BASE (D3_AHB1PERIPH_BASE + 0x2800UL) -#define RCC_BASE (D3_AHB1PERIPH_BASE + 0x4400UL) -#define PWR_BASE (D3_AHB1PERIPH_BASE + 0x4800UL) -#define CRC_BASE (D3_AHB1PERIPH_BASE + 0x4C00UL) -#define BDMA_BASE (D3_AHB1PERIPH_BASE + 0x5400UL) -#define DMAMUX2_BASE (D3_AHB1PERIPH_BASE + 0x5800UL) -#define ADC3_BASE (D3_AHB1PERIPH_BASE + 0x6000UL) -#define ADC3_COMMON_BASE (D3_AHB1PERIPH_BASE + 0x6300UL) -#define HSEM_BASE (D3_AHB1PERIPH_BASE + 0x6400UL) -#define RAMECC3_BASE (D3_AHB1PERIPH_BASE + 0x7000UL) - -/*!< D1_APB1PERIPH peripherals */ -#define LTDC_BASE (D1_APB1PERIPH_BASE + 0x1000UL) -#define LTDC_Layer1_BASE (LTDC_BASE + 0x84UL) -#define LTDC_Layer2_BASE (LTDC_BASE + 0x104UL) -#define WWDG1_BASE (D1_APB1PERIPH_BASE + 0x3000UL) - -/*!< D2_APB1PERIPH peripherals */ -#define TIM2_BASE (D2_APB1PERIPH_BASE + 0x0000UL) -#define TIM3_BASE (D2_APB1PERIPH_BASE + 0x0400UL) -#define TIM4_BASE (D2_APB1PERIPH_BASE + 0x0800UL) -#define TIM5_BASE (D2_APB1PERIPH_BASE + 0x0C00UL) -#define TIM6_BASE (D2_APB1PERIPH_BASE + 0x1000UL) -#define TIM7_BASE (D2_APB1PERIPH_BASE + 0x1400UL) -#define TIM12_BASE (D2_APB1PERIPH_BASE + 0x1800UL) -#define TIM13_BASE (D2_APB1PERIPH_BASE + 0x1C00UL) -#define TIM14_BASE (D2_APB1PERIPH_BASE + 0x2000UL) -#define LPTIM1_BASE (D2_APB1PERIPH_BASE + 0x2400UL) - - -#define SPI2_BASE (D2_APB1PERIPH_BASE + 0x3800UL) -#define SPI3_BASE (D2_APB1PERIPH_BASE + 0x3C00UL) -#define SPDIFRX_BASE (D2_APB1PERIPH_BASE + 0x4000UL) -#define USART2_BASE (D2_APB1PERIPH_BASE + 0x4400UL) -#define USART3_BASE (D2_APB1PERIPH_BASE + 0x4800UL) -#define UART4_BASE (D2_APB1PERIPH_BASE + 0x4C00UL) -#define UART5_BASE (D2_APB1PERIPH_BASE + 0x5000UL) -#define I2C1_BASE (D2_APB1PERIPH_BASE + 0x5400UL) -#define I2C2_BASE (D2_APB1PERIPH_BASE + 0x5800UL) -#define I2C3_BASE (D2_APB1PERIPH_BASE + 0x5C00UL) -#define I2C5_BASE (D2_APB1PERIPH_BASE + 0x6400UL) -#define CEC_BASE (D2_APB1PERIPH_BASE + 0x6C00UL) -#define DAC1_BASE (D2_APB1PERIPH_BASE + 0x7400UL) -#define UART7_BASE (D2_APB1PERIPH_BASE + 0x7800UL) -#define UART8_BASE (D2_APB1PERIPH_BASE + 0x7C00UL) -#define CRS_BASE (D2_APB1PERIPH_BASE + 0x8400UL) -#define SWPMI1_BASE (D2_APB1PERIPH_BASE + 0x8800UL) -#define OPAMP_BASE (D2_APB1PERIPH_BASE + 0x9000UL) -#define OPAMP1_BASE (D2_APB1PERIPH_BASE + 0x9000UL) -#define OPAMP2_BASE (D2_APB1PERIPH_BASE + 0x9010UL) -#define MDIOS_BASE (D2_APB1PERIPH_BASE + 0x9400UL) -#define FDCAN1_BASE (D2_APB1PERIPH_BASE + 0xA000UL) -#define FDCAN2_BASE (D2_APB1PERIPH_BASE + 0xA400UL) -#define FDCAN_CCU_BASE (D2_APB1PERIPH_BASE + 0xA800UL) -#define SRAMCAN_BASE (D2_APB1PERIPH_BASE + 0xAC00UL) -#define FDCAN3_BASE (D2_APB1PERIPH_BASE + 0xD400UL) -#define TIM23_BASE (D2_APB1PERIPH_BASE + 0xE000UL) -#define TIM24_BASE (D2_APB1PERIPH_BASE + 0xE400UL) - -/*!< D2_APB2PERIPH peripherals */ - -#define TIM1_BASE (D2_APB2PERIPH_BASE + 0x0000UL) -#define TIM8_BASE (D2_APB2PERIPH_BASE + 0x0400UL) -#define USART1_BASE (D2_APB2PERIPH_BASE + 0x1000UL) -#define USART6_BASE (D2_APB2PERIPH_BASE + 0x1400UL) -#define UART9_BASE (D2_APB2PERIPH_BASE + 0x1800UL) -#define USART10_BASE (D2_APB2PERIPH_BASE + 0x1C00UL) -#define SPI1_BASE (D2_APB2PERIPH_BASE + 0x3000UL) -#define SPI4_BASE (D2_APB2PERIPH_BASE + 0x3400UL) -#define TIM15_BASE (D2_APB2PERIPH_BASE + 0x4000UL) -#define TIM16_BASE (D2_APB2PERIPH_BASE + 0x4400UL) -#define TIM17_BASE (D2_APB2PERIPH_BASE + 0x4800UL) -#define SPI5_BASE (D2_APB2PERIPH_BASE + 0x5000UL) -#define SAI1_BASE (D2_APB2PERIPH_BASE + 0x5800UL) -#define SAI1_Block_A_BASE (SAI1_BASE + 0x004UL) -#define SAI1_Block_B_BASE (SAI1_BASE + 0x024UL) -#define DFSDM1_BASE (D2_APB2PERIPH_BASE + 0x7800UL) -#define DFSDM1_Channel0_BASE (DFSDM1_BASE + 0x00UL) -#define DFSDM1_Channel1_BASE (DFSDM1_BASE + 0x20UL) -#define DFSDM1_Channel2_BASE (DFSDM1_BASE + 0x40UL) -#define DFSDM1_Channel3_BASE (DFSDM1_BASE + 0x60UL) -#define DFSDM1_Channel4_BASE (DFSDM1_BASE + 0x80UL) -#define DFSDM1_Channel5_BASE (DFSDM1_BASE + 0xA0UL) -#define DFSDM1_Channel6_BASE (DFSDM1_BASE + 0xC0UL) -#define DFSDM1_Channel7_BASE (DFSDM1_BASE + 0xE0UL) -#define DFSDM1_Filter0_BASE (DFSDM1_BASE + 0x100UL) -#define DFSDM1_Filter1_BASE (DFSDM1_BASE + 0x180UL) -#define DFSDM1_Filter2_BASE (DFSDM1_BASE + 0x200UL) -#define DFSDM1_Filter3_BASE (DFSDM1_BASE + 0x280UL) - - -/*!< D3_APB1PERIPH peripherals */ -#define EXTI_BASE (D3_APB1PERIPH_BASE + 0x0000UL) -#define EXTI_D1_BASE (EXTI_BASE + 0x0080UL) -#define EXTI_D2_BASE (EXTI_BASE + 0x00C0UL) -#define SYSCFG_BASE (D3_APB1PERIPH_BASE + 0x0400UL) -#define LPUART1_BASE (D3_APB1PERIPH_BASE + 0x0C00UL) -#define SPI6_BASE (D3_APB1PERIPH_BASE + 0x1400UL) -#define I2C4_BASE (D3_APB1PERIPH_BASE + 0x1C00UL) -#define LPTIM2_BASE (D3_APB1PERIPH_BASE + 0x2400UL) -#define LPTIM3_BASE (D3_APB1PERIPH_BASE + 0x2800UL) -#define LPTIM4_BASE (D3_APB1PERIPH_BASE + 0x2C00UL) -#define LPTIM5_BASE (D3_APB1PERIPH_BASE + 0x3000UL) -#define COMP12_BASE (D3_APB1PERIPH_BASE + 0x3800UL) -#define COMP1_BASE (COMP12_BASE + 0x0CUL) -#define COMP2_BASE (COMP12_BASE + 0x10UL) -#define VREFBUF_BASE (D3_APB1PERIPH_BASE + 0x3C00UL) -#define RTC_BASE (D3_APB1PERIPH_BASE + 0x4000UL) -#define IWDG1_BASE (D3_APB1PERIPH_BASE + 0x4800UL) - - -#define SAI4_BASE (D3_APB1PERIPH_BASE + 0x5400UL) -#define SAI4_Block_A_BASE (SAI4_BASE + 0x004UL) -#define SAI4_Block_B_BASE (SAI4_BASE + 0x024UL) - -#define DTS_BASE (D3_APB1PERIPH_BASE + 0x6800UL) - - - -#define BDMA_Channel0_BASE (BDMA_BASE + 0x0008UL) -#define BDMA_Channel1_BASE (BDMA_BASE + 0x001CUL) -#define BDMA_Channel2_BASE (BDMA_BASE + 0x0030UL) -#define BDMA_Channel3_BASE (BDMA_BASE + 0x0044UL) -#define BDMA_Channel4_BASE (BDMA_BASE + 0x0058UL) -#define BDMA_Channel5_BASE (BDMA_BASE + 0x006CUL) -#define BDMA_Channel6_BASE (BDMA_BASE + 0x0080UL) -#define BDMA_Channel7_BASE (BDMA_BASE + 0x0094UL) - -#define DMAMUX2_Channel0_BASE (DMAMUX2_BASE) -#define DMAMUX2_Channel1_BASE (DMAMUX2_BASE + 0x0004UL) -#define DMAMUX2_Channel2_BASE (DMAMUX2_BASE + 0x0008UL) -#define DMAMUX2_Channel3_BASE (DMAMUX2_BASE + 0x000CUL) -#define DMAMUX2_Channel4_BASE (DMAMUX2_BASE + 0x0010UL) -#define DMAMUX2_Channel5_BASE (DMAMUX2_BASE + 0x0014UL) -#define DMAMUX2_Channel6_BASE (DMAMUX2_BASE + 0x0018UL) -#define DMAMUX2_Channel7_BASE (DMAMUX2_BASE + 0x001CUL) - -#define DMAMUX2_RequestGenerator0_BASE (DMAMUX2_BASE + 0x0100UL) -#define DMAMUX2_RequestGenerator1_BASE (DMAMUX2_BASE + 0x0104UL) -#define DMAMUX2_RequestGenerator2_BASE (DMAMUX2_BASE + 0x0108UL) -#define DMAMUX2_RequestGenerator3_BASE (DMAMUX2_BASE + 0x010CUL) -#define DMAMUX2_RequestGenerator4_BASE (DMAMUX2_BASE + 0x0110UL) -#define DMAMUX2_RequestGenerator5_BASE (DMAMUX2_BASE + 0x0114UL) -#define DMAMUX2_RequestGenerator6_BASE (DMAMUX2_BASE + 0x0118UL) -#define DMAMUX2_RequestGenerator7_BASE (DMAMUX2_BASE + 0x011CUL) - -#define DMAMUX2_ChannelStatus_BASE (DMAMUX2_BASE + 0x0080UL) -#define DMAMUX2_RequestGenStatus_BASE (DMAMUX2_BASE + 0x0140UL) - -#define DMA1_Stream0_BASE (DMA1_BASE + 0x010UL) -#define DMA1_Stream1_BASE (DMA1_BASE + 0x028UL) -#define DMA1_Stream2_BASE (DMA1_BASE + 0x040UL) -#define DMA1_Stream3_BASE (DMA1_BASE + 0x058UL) -#define DMA1_Stream4_BASE (DMA1_BASE + 0x070UL) -#define DMA1_Stream5_BASE (DMA1_BASE + 0x088UL) -#define DMA1_Stream6_BASE (DMA1_BASE + 0x0A0UL) -#define DMA1_Stream7_BASE (DMA1_BASE + 0x0B8UL) - -#define DMA2_Stream0_BASE (DMA2_BASE + 0x010UL) -#define DMA2_Stream1_BASE (DMA2_BASE + 0x028UL) -#define DMA2_Stream2_BASE (DMA2_BASE + 0x040UL) -#define DMA2_Stream3_BASE (DMA2_BASE + 0x058UL) -#define DMA2_Stream4_BASE (DMA2_BASE + 0x070UL) -#define DMA2_Stream5_BASE (DMA2_BASE + 0x088UL) -#define DMA2_Stream6_BASE (DMA2_BASE + 0x0A0UL) -#define DMA2_Stream7_BASE (DMA2_BASE + 0x0B8UL) - -#define DMAMUX1_Channel0_BASE (DMAMUX1_BASE) -#define DMAMUX1_Channel1_BASE (DMAMUX1_BASE + 0x0004UL) -#define DMAMUX1_Channel2_BASE (DMAMUX1_BASE + 0x0008UL) -#define DMAMUX1_Channel3_BASE (DMAMUX1_BASE + 0x000CUL) -#define DMAMUX1_Channel4_BASE (DMAMUX1_BASE + 0x0010UL) -#define DMAMUX1_Channel5_BASE (DMAMUX1_BASE + 0x0014UL) -#define DMAMUX1_Channel6_BASE (DMAMUX1_BASE + 0x0018UL) -#define DMAMUX1_Channel7_BASE (DMAMUX1_BASE + 0x001CUL) -#define DMAMUX1_Channel8_BASE (DMAMUX1_BASE + 0x0020UL) -#define DMAMUX1_Channel9_BASE (DMAMUX1_BASE + 0x0024UL) -#define DMAMUX1_Channel10_BASE (DMAMUX1_BASE + 0x0028UL) -#define DMAMUX1_Channel11_BASE (DMAMUX1_BASE + 0x002CUL) -#define DMAMUX1_Channel12_BASE (DMAMUX1_BASE + 0x0030UL) -#define DMAMUX1_Channel13_BASE (DMAMUX1_BASE + 0x0034UL) -#define DMAMUX1_Channel14_BASE (DMAMUX1_BASE + 0x0038UL) -#define DMAMUX1_Channel15_BASE (DMAMUX1_BASE + 0x003CUL) - -#define DMAMUX1_RequestGenerator0_BASE (DMAMUX1_BASE + 0x0100UL) -#define DMAMUX1_RequestGenerator1_BASE (DMAMUX1_BASE + 0x0104UL) -#define DMAMUX1_RequestGenerator2_BASE (DMAMUX1_BASE + 0x0108UL) -#define DMAMUX1_RequestGenerator3_BASE (DMAMUX1_BASE + 0x010CUL) -#define DMAMUX1_RequestGenerator4_BASE (DMAMUX1_BASE + 0x0110UL) -#define DMAMUX1_RequestGenerator5_BASE (DMAMUX1_BASE + 0x0114UL) -#define DMAMUX1_RequestGenerator6_BASE (DMAMUX1_BASE + 0x0118UL) -#define DMAMUX1_RequestGenerator7_BASE (DMAMUX1_BASE + 0x011CUL) - -#define DMAMUX1_ChannelStatus_BASE (DMAMUX1_BASE + 0x0080UL) -#define DMAMUX1_RequestGenStatus_BASE (DMAMUX1_BASE + 0x0140UL) - -/*!< FMC Banks registers base address */ -#define FMC_Bank1_R_BASE (FMC_R_BASE + 0x0000UL) -#define FMC_Bank1E_R_BASE (FMC_R_BASE + 0x0104UL) -#define FMC_Bank2_R_BASE (FMC_R_BASE + 0x0060UL) -#define FMC_Bank3_R_BASE (FMC_R_BASE + 0x0080UL) -#define FMC_Bank5_6_R_BASE (FMC_R_BASE + 0x0140UL) - -/* Debug MCU registers base address */ -#define DBGMCU_BASE (0x5C001000UL) - -#define MDMA_Channel0_BASE (MDMA_BASE + 0x00000040UL) -#define MDMA_Channel1_BASE (MDMA_BASE + 0x00000080UL) -#define MDMA_Channel2_BASE (MDMA_BASE + 0x000000C0UL) -#define MDMA_Channel3_BASE (MDMA_BASE + 0x00000100UL) -#define MDMA_Channel4_BASE (MDMA_BASE + 0x00000140UL) -#define MDMA_Channel5_BASE (MDMA_BASE + 0x00000180UL) -#define MDMA_Channel6_BASE (MDMA_BASE + 0x000001C0UL) -#define MDMA_Channel7_BASE (MDMA_BASE + 0x00000200UL) -#define MDMA_Channel8_BASE (MDMA_BASE + 0x00000240UL) -#define MDMA_Channel9_BASE (MDMA_BASE + 0x00000280UL) -#define MDMA_Channel10_BASE (MDMA_BASE + 0x000002C0UL) -#define MDMA_Channel11_BASE (MDMA_BASE + 0x00000300UL) -#define MDMA_Channel12_BASE (MDMA_BASE + 0x00000340UL) -#define MDMA_Channel13_BASE (MDMA_BASE + 0x00000380UL) -#define MDMA_Channel14_BASE (MDMA_BASE + 0x000003C0UL) -#define MDMA_Channel15_BASE (MDMA_BASE + 0x00000400UL) - -#define RAMECC1_Monitor1_BASE (RAMECC1_BASE + 0x20UL) -#define RAMECC1_Monitor2_BASE (RAMECC1_BASE + 0x40UL) -#define RAMECC1_Monitor3_BASE (RAMECC1_BASE + 0x60UL) -#define RAMECC1_Monitor4_BASE (RAMECC1_BASE + 0x80UL) -#define RAMECC1_Monitor5_BASE (RAMECC1_BASE + 0xA0UL) -#define RAMECC1_Monitor6_BASE (RAMECC1_BASE + 0xC0UL) - -#define RAMECC2_Monitor1_BASE (RAMECC2_BASE + 0x20UL) -#define RAMECC2_Monitor2_BASE (RAMECC2_BASE + 0x40UL) -#define RAMECC2_Monitor3_BASE (RAMECC2_BASE + 0x60UL) - -#define RAMECC3_Monitor1_BASE (RAMECC3_BASE + 0x20UL) -#define RAMECC3_Monitor2_BASE (RAMECC3_BASE + 0x40UL) - - - -#define GPV_BASE (PERIPH_BASE + 0x11000000UL) /*!< GPV_BASE (PERIPH_BASE + 0x11000000UL) */ - -/** - * @} - */ - -/** @addtogroup Peripheral_declaration - * @{ - */ -#define TIM2 ((TIM_TypeDef *) TIM2_BASE) -#define TIM3 ((TIM_TypeDef *) TIM3_BASE) -#define TIM4 ((TIM_TypeDef *) TIM4_BASE) -#define TIM5 ((TIM_TypeDef *) TIM5_BASE) -#define TIM6 ((TIM_TypeDef *) TIM6_BASE) -#define TIM7 ((TIM_TypeDef *) TIM7_BASE) -#define TIM13 ((TIM_TypeDef *) TIM13_BASE) -#define TIM14 ((TIM_TypeDef *) TIM14_BASE) -#define VREFBUF ((VREFBUF_TypeDef *) VREFBUF_BASE) -#define RTC ((RTC_TypeDef *) RTC_BASE) -#define WWDG1 ((WWDG_TypeDef *) WWDG1_BASE) - - -#define IWDG1 ((IWDG_TypeDef *) IWDG1_BASE) -#define SPI2 ((SPI_TypeDef *) SPI2_BASE) -#define SPI3 ((SPI_TypeDef *) SPI3_BASE) -#define SPI4 ((SPI_TypeDef *) SPI4_BASE) -#define SPI5 ((SPI_TypeDef *) SPI5_BASE) -#define SPI6 ((SPI_TypeDef *) SPI6_BASE) -#define USART2 ((USART_TypeDef *) USART2_BASE) -#define USART3 ((USART_TypeDef *) USART3_BASE) -#define USART6 ((USART_TypeDef *) USART6_BASE) -#define USART10 ((USART_TypeDef *) USART10_BASE) -#define UART7 ((USART_TypeDef *) UART7_BASE) -#define UART8 ((USART_TypeDef *) UART8_BASE) -#define UART9 ((USART_TypeDef *) UART9_BASE) -#define CRS ((CRS_TypeDef *) CRS_BASE) -#define UART4 ((USART_TypeDef *) UART4_BASE) -#define UART5 ((USART_TypeDef *) UART5_BASE) -#define I2C1 ((I2C_TypeDef *) I2C1_BASE) -#define I2C2 ((I2C_TypeDef *) I2C2_BASE) -#define I2C3 ((I2C_TypeDef *) I2C3_BASE) -#define I2C4 ((I2C_TypeDef *) I2C4_BASE) -#define I2C5 ((I2C_TypeDef *) I2C5_BASE) -#define FDCAN1 ((FDCAN_GlobalTypeDef *) FDCAN1_BASE) -#define FDCAN2 ((FDCAN_GlobalTypeDef *) FDCAN2_BASE) -#define FDCAN_CCU ((FDCAN_ClockCalibrationUnit_TypeDef *) FDCAN_CCU_BASE) -#define FDCAN3 ((FDCAN_GlobalTypeDef *) FDCAN3_BASE) -#define TIM23 ((TIM_TypeDef *) TIM23_BASE) -#define TIM24 ((TIM_TypeDef *) TIM24_BASE) -#define CEC ((CEC_TypeDef *) CEC_BASE) -#define LPTIM1 ((LPTIM_TypeDef *) LPTIM1_BASE) -#define PWR ((PWR_TypeDef *) PWR_BASE) -#define DAC1 ((DAC_TypeDef *) DAC1_BASE) -#define LPUART1 ((USART_TypeDef *) LPUART1_BASE) -#define SWPMI1 ((SWPMI_TypeDef *) SWPMI1_BASE) -#define LPTIM2 ((LPTIM_TypeDef *) LPTIM2_BASE) -#define LPTIM3 ((LPTIM_TypeDef *) LPTIM3_BASE) -#define DTS ((DTS_TypeDef *) DTS_BASE) -#define LPTIM4 ((LPTIM_TypeDef *) LPTIM4_BASE) -#define LPTIM5 ((LPTIM_TypeDef *) LPTIM5_BASE) - -#define SYSCFG ((SYSCFG_TypeDef *) SYSCFG_BASE) -#define COMP12 ((COMPOPT_TypeDef *) COMP12_BASE) -#define COMP1 ((COMP_TypeDef *) COMP1_BASE) -#define COMP2 ((COMP_TypeDef *) COMP2_BASE) -#define COMP12_COMMON ((COMP_Common_TypeDef *) COMP2_BASE) -#define OPAMP ((OPAMP_TypeDef *) OPAMP_BASE) -#define OPAMP1 ((OPAMP_TypeDef *) OPAMP1_BASE) -#define OPAMP2 ((OPAMP_TypeDef *) OPAMP2_BASE) - - -#define EXTI ((EXTI_TypeDef *) EXTI_BASE) -#define EXTI_D1 ((EXTI_Core_TypeDef *) EXTI_D1_BASE) -#define EXTI_D2 ((EXTI_Core_TypeDef *) EXTI_D2_BASE) -#define TIM1 ((TIM_TypeDef *) TIM1_BASE) -#define SPI1 ((SPI_TypeDef *) SPI1_BASE) -#define TIM8 ((TIM_TypeDef *) TIM8_BASE) -#define USART1 ((USART_TypeDef *) USART1_BASE) -#define TIM12 ((TIM_TypeDef *) TIM12_BASE) -#define TIM15 ((TIM_TypeDef *) TIM15_BASE) -#define TIM16 ((TIM_TypeDef *) TIM16_BASE) -#define TIM17 ((TIM_TypeDef *) TIM17_BASE) -#define SAI1 ((SAI_TypeDef *) SAI1_BASE) -#define SAI1_Block_A ((SAI_Block_TypeDef *)SAI1_Block_A_BASE) -#define SAI1_Block_B ((SAI_Block_TypeDef *)SAI1_Block_B_BASE) -#define SAI4 ((SAI_TypeDef *) SAI4_BASE) -#define SAI4_Block_A ((SAI_Block_TypeDef *)SAI4_Block_A_BASE) -#define SAI4_Block_B ((SAI_Block_TypeDef *)SAI4_Block_B_BASE) - -#define SPDIFRX ((SPDIFRX_TypeDef *) SPDIFRX_BASE) -#define DFSDM1_Channel0 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel0_BASE) -#define DFSDM1_Channel1 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel1_BASE) -#define DFSDM1_Channel2 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel2_BASE) -#define DFSDM1_Channel3 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel3_BASE) -#define DFSDM1_Channel4 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel4_BASE) -#define DFSDM1_Channel5 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel5_BASE) -#define DFSDM1_Channel6 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel6_BASE) -#define DFSDM1_Channel7 ((DFSDM_Channel_TypeDef *) DFSDM1_Channel7_BASE) -#define DFSDM1_Filter0 ((DFSDM_Filter_TypeDef *) DFSDM1_Filter0_BASE) -#define DFSDM1_Filter1 ((DFSDM_Filter_TypeDef *) DFSDM1_Filter1_BASE) -#define DFSDM1_Filter2 ((DFSDM_Filter_TypeDef *) DFSDM1_Filter2_BASE) -#define DFSDM1_Filter3 ((DFSDM_Filter_TypeDef *) DFSDM1_Filter3_BASE) -#define DMA2D ((DMA2D_TypeDef *) DMA2D_BASE) -#define DCMI ((DCMI_TypeDef *) DCMI_BASE) -#define PSSI ((PSSI_TypeDef *) PSSI_BASE) -#define RCC ((RCC_TypeDef *) RCC_BASE) -#define FLASH ((FLASH_TypeDef *) FLASH_R_BASE) -#define CRC ((CRC_TypeDef *) CRC_BASE) - -#define GPIOA ((GPIO_TypeDef *) GPIOA_BASE) -#define GPIOB ((GPIO_TypeDef *) GPIOB_BASE) -#define GPIOC ((GPIO_TypeDef *) GPIOC_BASE) -#define GPIOD ((GPIO_TypeDef *) GPIOD_BASE) -#define GPIOE ((GPIO_TypeDef *) GPIOE_BASE) -#define GPIOF ((GPIO_TypeDef *) GPIOF_BASE) -#define GPIOG ((GPIO_TypeDef *) GPIOG_BASE) -#define GPIOH ((GPIO_TypeDef *) GPIOH_BASE) -#define GPIOJ ((GPIO_TypeDef *) GPIOJ_BASE) -#define GPIOK ((GPIO_TypeDef *) GPIOK_BASE) - -#define ADC1 ((ADC_TypeDef *) ADC1_BASE) -#define ADC2 ((ADC_TypeDef *) ADC2_BASE) -#define ADC3 ((ADC_TypeDef *) ADC3_BASE) -#define ADC3_COMMON ((ADC_Common_TypeDef *) ADC3_COMMON_BASE) -#define ADC12_COMMON ((ADC_Common_TypeDef *) ADC12_COMMON_BASE) - -#define CRYP ((CRYP_TypeDef *) CRYP_BASE) -#define HASH ((HASH_TypeDef *) HASH_BASE) -#define HASH_DIGEST ((HASH_DIGEST_TypeDef *) HASH_DIGEST_BASE) -#define RNG ((RNG_TypeDef *) RNG_BASE) -#define SDMMC2 ((SDMMC_TypeDef *) SDMMC2_BASE) -#define DLYB_SDMMC2 ((DLYB_TypeDef *) DLYB_SDMMC2_BASE) -#define FMAC ((FMAC_TypeDef *) FMAC_BASE) -#define CORDIC ((CORDIC_TypeDef *) CORDIC_BASE) - -#define BDMA ((BDMA_TypeDef *) BDMA_BASE) -#define BDMA_Channel0 ((BDMA_Channel_TypeDef *) BDMA_Channel0_BASE) -#define BDMA_Channel1 ((BDMA_Channel_TypeDef *) BDMA_Channel1_BASE) -#define BDMA_Channel2 ((BDMA_Channel_TypeDef *) BDMA_Channel2_BASE) -#define BDMA_Channel3 ((BDMA_Channel_TypeDef *) BDMA_Channel3_BASE) -#define BDMA_Channel4 ((BDMA_Channel_TypeDef *) BDMA_Channel4_BASE) -#define BDMA_Channel5 ((BDMA_Channel_TypeDef *) BDMA_Channel5_BASE) -#define BDMA_Channel6 ((BDMA_Channel_TypeDef *) BDMA_Channel6_BASE) -#define BDMA_Channel7 ((BDMA_Channel_TypeDef *) BDMA_Channel7_BASE) - -#define RAMECC1 ((RAMECC_TypeDef *)RAMECC1_BASE) -#define RAMECC1_Monitor1 ((RAMECC_MonitorTypeDef *)RAMECC1_Monitor1_BASE) -#define RAMECC1_Monitor2 ((RAMECC_MonitorTypeDef *)RAMECC1_Monitor2_BASE) -#define RAMECC1_Monitor3 ((RAMECC_MonitorTypeDef *)RAMECC1_Monitor3_BASE) -#define RAMECC1_Monitor4 ((RAMECC_MonitorTypeDef *)RAMECC1_Monitor4_BASE) -#define RAMECC1_Monitor5 ((RAMECC_MonitorTypeDef *)RAMECC1_Monitor5_BASE) -#define RAMECC1_Monitor6 ((RAMECC_MonitorTypeDef *)RAMECC1_Monitor6_BASE) - -#define RAMECC2 ((RAMECC_TypeDef *)RAMECC2_BASE) -#define RAMECC2_Monitor1 ((RAMECC_MonitorTypeDef *)RAMECC2_Monitor1_BASE) -#define RAMECC2_Monitor2 ((RAMECC_MonitorTypeDef *)RAMECC2_Monitor2_BASE) -#define RAMECC2_Monitor3 ((RAMECC_MonitorTypeDef *)RAMECC2_Monitor3_BASE) - -#define RAMECC3 ((RAMECC_TypeDef *)RAMECC3_BASE) -#define RAMECC3_Monitor1 ((RAMECC_MonitorTypeDef *)RAMECC3_Monitor1_BASE) -#define RAMECC3_Monitor2 ((RAMECC_MonitorTypeDef *)RAMECC3_Monitor2_BASE) - -#define DMAMUX2 ((DMAMUX_Channel_TypeDef *) DMAMUX2_BASE) -#define DMAMUX2_Channel0 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel0_BASE) -#define DMAMUX2_Channel1 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel1_BASE) -#define DMAMUX2_Channel2 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel2_BASE) -#define DMAMUX2_Channel3 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel3_BASE) -#define DMAMUX2_Channel4 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel4_BASE) -#define DMAMUX2_Channel5 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel5_BASE) -#define DMAMUX2_Channel6 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel6_BASE) -#define DMAMUX2_Channel7 ((DMAMUX_Channel_TypeDef *) DMAMUX2_Channel7_BASE) - - -#define DMAMUX2_RequestGenerator0 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator0_BASE) -#define DMAMUX2_RequestGenerator1 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator1_BASE) -#define DMAMUX2_RequestGenerator2 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator2_BASE) -#define DMAMUX2_RequestGenerator3 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator3_BASE) -#define DMAMUX2_RequestGenerator4 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator4_BASE) -#define DMAMUX2_RequestGenerator5 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator5_BASE) -#define DMAMUX2_RequestGenerator6 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator6_BASE) -#define DMAMUX2_RequestGenerator7 ((DMAMUX_RequestGen_TypeDef *) DMAMUX2_RequestGenerator7_BASE) - -#define DMAMUX2_ChannelStatus ((DMAMUX_ChannelStatus_TypeDef *) DMAMUX2_ChannelStatus_BASE) -#define DMAMUX2_RequestGenStatus ((DMAMUX_RequestGenStatus_TypeDef *) DMAMUX2_RequestGenStatus_BASE) - -#define DMA2 ((DMA_TypeDef *) DMA2_BASE) -#define DMA2_Stream0 ((DMA_Stream_TypeDef *) DMA2_Stream0_BASE) -#define DMA2_Stream1 ((DMA_Stream_TypeDef *) DMA2_Stream1_BASE) -#define DMA2_Stream2 ((DMA_Stream_TypeDef *) DMA2_Stream2_BASE) -#define DMA2_Stream3 ((DMA_Stream_TypeDef *) DMA2_Stream3_BASE) -#define DMA2_Stream4 ((DMA_Stream_TypeDef *) DMA2_Stream4_BASE) -#define DMA2_Stream5 ((DMA_Stream_TypeDef *) DMA2_Stream5_BASE) -#define DMA2_Stream6 ((DMA_Stream_TypeDef *) DMA2_Stream6_BASE) -#define DMA2_Stream7 ((DMA_Stream_TypeDef *) DMA2_Stream7_BASE) - -#define DMA1 ((DMA_TypeDef *) DMA1_BASE) -#define DMA1_Stream0 ((DMA_Stream_TypeDef *) DMA1_Stream0_BASE) -#define DMA1_Stream1 ((DMA_Stream_TypeDef *) DMA1_Stream1_BASE) -#define DMA1_Stream2 ((DMA_Stream_TypeDef *) DMA1_Stream2_BASE) -#define DMA1_Stream3 ((DMA_Stream_TypeDef *) DMA1_Stream3_BASE) -#define DMA1_Stream4 ((DMA_Stream_TypeDef *) DMA1_Stream4_BASE) -#define DMA1_Stream5 ((DMA_Stream_TypeDef *) DMA1_Stream5_BASE) -#define DMA1_Stream6 ((DMA_Stream_TypeDef *) DMA1_Stream6_BASE) -#define DMA1_Stream7 ((DMA_Stream_TypeDef *) DMA1_Stream7_BASE) - - -#define DMAMUX1 ((DMAMUX_Channel_TypeDef *) DMAMUX1_BASE) -#define DMAMUX1_Channel0 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel0_BASE) -#define DMAMUX1_Channel1 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel1_BASE) -#define DMAMUX1_Channel2 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel2_BASE) -#define DMAMUX1_Channel3 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel3_BASE) -#define DMAMUX1_Channel4 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel4_BASE) -#define DMAMUX1_Channel5 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel5_BASE) -#define DMAMUX1_Channel6 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel6_BASE) -#define DMAMUX1_Channel7 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel7_BASE) -#define DMAMUX1_Channel8 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel8_BASE) -#define DMAMUX1_Channel9 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel9_BASE) -#define DMAMUX1_Channel10 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel10_BASE) -#define DMAMUX1_Channel11 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel11_BASE) -#define DMAMUX1_Channel12 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel12_BASE) -#define DMAMUX1_Channel13 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel13_BASE) -#define DMAMUX1_Channel14 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel14_BASE) -#define DMAMUX1_Channel15 ((DMAMUX_Channel_TypeDef *) DMAMUX1_Channel15_BASE) - -#define DMAMUX1_RequestGenerator0 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator0_BASE) -#define DMAMUX1_RequestGenerator1 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator1_BASE) -#define DMAMUX1_RequestGenerator2 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator2_BASE) -#define DMAMUX1_RequestGenerator3 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator3_BASE) -#define DMAMUX1_RequestGenerator4 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator4_BASE) -#define DMAMUX1_RequestGenerator5 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator5_BASE) -#define DMAMUX1_RequestGenerator6 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator6_BASE) -#define DMAMUX1_RequestGenerator7 ((DMAMUX_RequestGen_TypeDef *) DMAMUX1_RequestGenerator7_BASE) - -#define DMAMUX1_ChannelStatus ((DMAMUX_ChannelStatus_TypeDef *) DMAMUX1_ChannelStatus_BASE) -#define DMAMUX1_RequestGenStatus ((DMAMUX_RequestGenStatus_TypeDef *) DMAMUX1_RequestGenStatus_BASE) - - -#define FMC_Bank1_R ((FMC_Bank1_TypeDef *) FMC_Bank1_R_BASE) -#define FMC_Bank1E_R ((FMC_Bank1E_TypeDef *) FMC_Bank1E_R_BASE) -#define FMC_Bank2_R ((FMC_Bank2_TypeDef *) FMC_Bank2_R_BASE) -#define FMC_Bank3_R ((FMC_Bank3_TypeDef *) FMC_Bank3_R_BASE) -#define FMC_Bank5_6_R ((FMC_Bank5_6_TypeDef *) FMC_Bank5_6_R_BASE) - -#define OCTOSPI1 ((OCTOSPI_TypeDef *) OCTOSPI1_R_BASE) -#define DLYB_OCTOSPI1 ((DLYB_TypeDef *) DLYB_OCTOSPI1_BASE) -#define OCTOSPI2 ((OCTOSPI_TypeDef *) OCTOSPI2_R_BASE) -#define DLYB_OCTOSPI2 ((DLYB_TypeDef *) DLYB_OCTOSPI2_BASE) -#define OCTOSPIM ((OCTOSPIM_TypeDef *) OCTOSPIM_BASE) - -#define OTFDEC1 ((OTFDEC_TypeDef *) OTFDEC1_BASE) -#define OTFDEC1_REGION1 ((OTFDEC_Region_TypeDef *) OTFDEC1_REGION1_BASE) -#define OTFDEC1_REGION2 ((OTFDEC_Region_TypeDef *) OTFDEC1_REGION2_BASE) -#define OTFDEC1_REGION3 ((OTFDEC_Region_TypeDef *) OTFDEC1_REGION3_BASE) -#define OTFDEC1_REGION4 ((OTFDEC_Region_TypeDef *) OTFDEC1_REGION4_BASE) - -#define OTFDEC2 ((OTFDEC_TypeDef *) OTFDEC2_BASE) -#define OTFDEC2_REGION1 ((OTFDEC_Region_TypeDef *) OTFDEC2_REGION1_BASE) -#define OTFDEC2_REGION2 ((OTFDEC_Region_TypeDef *) OTFDEC2_REGION2_BASE) -#define OTFDEC2_REGION3 ((OTFDEC_Region_TypeDef *) OTFDEC2_REGION3_BASE) -#define OTFDEC2_REGION4 ((OTFDEC_Region_TypeDef *) OTFDEC2_REGION4_BASE) - -#define SDMMC1 ((SDMMC_TypeDef *) SDMMC1_BASE) -#define DLYB_SDMMC1 ((DLYB_TypeDef *) DLYB_SDMMC1_BASE) - -#define DBGMCU ((DBGMCU_TypeDef *) DBGMCU_BASE) - -#define HSEM ((HSEM_TypeDef *) HSEM_BASE) -#define HSEM_COMMON ((HSEM_Common_TypeDef *) (HSEM_BASE + 0x100UL)) - -#define LTDC ((LTDC_TypeDef *)LTDC_BASE) -#define LTDC_Layer1 ((LTDC_Layer_TypeDef *)LTDC_Layer1_BASE) -#define LTDC_Layer2 ((LTDC_Layer_TypeDef *)LTDC_Layer2_BASE) - -#define MDIOS ((MDIOS_TypeDef *) MDIOS_BASE) - -#define ETH ((ETH_TypeDef *)ETH_BASE) -#define MDMA ((MDMA_TypeDef *)MDMA_BASE) -#define MDMA_Channel0 ((MDMA_Channel_TypeDef *)MDMA_Channel0_BASE) -#define MDMA_Channel1 ((MDMA_Channel_TypeDef *)MDMA_Channel1_BASE) -#define MDMA_Channel2 ((MDMA_Channel_TypeDef *)MDMA_Channel2_BASE) -#define MDMA_Channel3 ((MDMA_Channel_TypeDef *)MDMA_Channel3_BASE) -#define MDMA_Channel4 ((MDMA_Channel_TypeDef *)MDMA_Channel4_BASE) -#define MDMA_Channel5 ((MDMA_Channel_TypeDef *)MDMA_Channel5_BASE) -#define MDMA_Channel6 ((MDMA_Channel_TypeDef *)MDMA_Channel6_BASE) -#define MDMA_Channel7 ((MDMA_Channel_TypeDef *)MDMA_Channel7_BASE) -#define MDMA_Channel8 ((MDMA_Channel_TypeDef *)MDMA_Channel8_BASE) -#define MDMA_Channel9 ((MDMA_Channel_TypeDef *)MDMA_Channel9_BASE) -#define MDMA_Channel10 ((MDMA_Channel_TypeDef *)MDMA_Channel10_BASE) -#define MDMA_Channel11 ((MDMA_Channel_TypeDef *)MDMA_Channel11_BASE) -#define MDMA_Channel12 ((MDMA_Channel_TypeDef *)MDMA_Channel12_BASE) -#define MDMA_Channel13 ((MDMA_Channel_TypeDef *)MDMA_Channel13_BASE) -#define MDMA_Channel14 ((MDMA_Channel_TypeDef *)MDMA_Channel14_BASE) -#define MDMA_Channel15 ((MDMA_Channel_TypeDef *)MDMA_Channel15_BASE) - - -#define USB1_OTG_HS ((USB_OTG_GlobalTypeDef *) USB1_OTG_HS_PERIPH_BASE) - -/* Legacy defines */ -#define USB_OTG_HS USB1_OTG_HS -#define USB_OTG_HS_PERIPH_BASE USB1_OTG_HS_PERIPH_BASE - -#define GPV ((GPV_TypeDef *) GPV_BASE) - -/** - * @} - */ - -/** @addtogroup Exported_constants - * @{ - */ - - /** @addtogroup Peripheral_Registers_Bits_Definition - * @{ - */ - -/******************************************************************************/ -/* Peripheral Registers_Bits_Definition */ -/******************************************************************************/ - -/******************************************************************************/ -/* */ -/* Analog to Digital Converter */ -/* */ -/******************************************************************************/ -/******************************* ADC VERSION ********************************/ -#define ADC_VER_V5_V90 -/******************** Bit definition for ADC_ISR register ********************/ -#define ADC_ISR_ADRDY_Pos (0U) -#define ADC_ISR_ADRDY_Msk (0x1UL << ADC_ISR_ADRDY_Pos) /*!< 0x00000001 */ -#define ADC_ISR_ADRDY ADC_ISR_ADRDY_Msk /*!< ADC Ready (ADRDY) flag */ -#define ADC_ISR_EOSMP_Pos (1U) -#define ADC_ISR_EOSMP_Msk (0x1UL << ADC_ISR_EOSMP_Pos) /*!< 0x00000002 */ -#define ADC_ISR_EOSMP ADC_ISR_EOSMP_Msk /*!< ADC End of Sampling flag */ -#define ADC_ISR_EOC_Pos (2U) -#define ADC_ISR_EOC_Msk (0x1UL << ADC_ISR_EOC_Pos) /*!< 0x00000004 */ -#define ADC_ISR_EOC ADC_ISR_EOC_Msk /*!< ADC End of Regular Conversion flag */ -#define ADC_ISR_EOS_Pos (3U) -#define ADC_ISR_EOS_Msk (0x1UL << ADC_ISR_EOS_Pos) /*!< 0x00000008 */ -#define ADC_ISR_EOS ADC_ISR_EOS_Msk /*!< ADC End of Regular sequence of Conversions flag */ -#define ADC_ISR_OVR_Pos (4U) -#define ADC_ISR_OVR_Msk (0x1UL << ADC_ISR_OVR_Pos) /*!< 0x00000010 */ -#define ADC_ISR_OVR ADC_ISR_OVR_Msk /*!< ADC overrun flag */ -#define ADC_ISR_JEOC_Pos (5U) -#define ADC_ISR_JEOC_Msk (0x1UL << ADC_ISR_JEOC_Pos) /*!< 0x00000020 */ -#define ADC_ISR_JEOC ADC_ISR_JEOC_Msk /*!< ADC End of Injected Conversion flag */ -#define ADC_ISR_JEOS_Pos (6U) -#define ADC_ISR_JEOS_Msk (0x1UL << ADC_ISR_JEOS_Pos) /*!< 0x00000040 */ -#define ADC_ISR_JEOS ADC_ISR_JEOS_Msk /*!< ADC End of Injected sequence of Conversions flag */ -#define ADC_ISR_AWD1_Pos (7U) -#define ADC_ISR_AWD1_Msk (0x1UL << ADC_ISR_AWD1_Pos) /*!< 0x00000080 */ -#define ADC_ISR_AWD1 ADC_ISR_AWD1_Msk /*!< ADC Analog watchdog 1 flag */ -#define ADC_ISR_AWD2_Pos (8U) -#define ADC_ISR_AWD2_Msk (0x1UL << ADC_ISR_AWD2_Pos) /*!< 0x00000100 */ -#define ADC_ISR_AWD2 ADC_ISR_AWD2_Msk /*!< ADC Analog watchdog 2 flag */ -#define ADC_ISR_AWD3_Pos (9U) -#define ADC_ISR_AWD3_Msk (0x1UL << ADC_ISR_AWD3_Pos) /*!< 0x00000200 */ -#define ADC_ISR_AWD3 ADC_ISR_AWD3_Msk /*!< ADC Analog watchdog 3 flag */ -#define ADC_ISR_JQOVF_Pos (10U) -#define ADC_ISR_JQOVF_Msk (0x1UL << ADC_ISR_JQOVF_Pos) /*!< 0x00000400 */ -#define ADC_ISR_JQOVF ADC_ISR_JQOVF_Msk /*!< ADC Injected Context Queue Overflow flag */ -#define ADC_ISR_LDORDY_Pos (12U) -#define ADC_ISR_LDORDY_Msk (0x1UL << ADC_ISR_LDORDY_Pos) /*!< 0x00001000 */ -#define ADC_ISR_LDORDY ADC_ISR_LDORDY_Msk /*!< ADC LDO Ready (LDORDY) flag */ - -/******************** Bit definition for ADC_IER register ********************/ -#define ADC_IER_ADRDYIE_Pos (0U) -#define ADC_IER_ADRDYIE_Msk (0x1UL << ADC_IER_ADRDYIE_Pos) /*!< 0x00000001 */ -#define ADC_IER_ADRDYIE ADC_IER_ADRDYIE_Msk /*!< ADC Ready (ADRDY) interrupt source */ -#define ADC_IER_EOSMPIE_Pos (1U) -#define ADC_IER_EOSMPIE_Msk (0x1UL << ADC_IER_EOSMPIE_Pos) /*!< 0x00000002 */ -#define ADC_IER_EOSMPIE ADC_IER_EOSMPIE_Msk /*!< ADC End of Sampling interrupt source */ -#define ADC_IER_EOCIE_Pos (2U) -#define ADC_IER_EOCIE_Msk (0x1UL << ADC_IER_EOCIE_Pos) /*!< 0x00000004 */ -#define ADC_IER_EOCIE ADC_IER_EOCIE_Msk /*!< ADC End of Regular Conversion interrupt source */ -#define ADC_IER_EOSIE_Pos (3U) -#define ADC_IER_EOSIE_Msk (0x1UL << ADC_IER_EOSIE_Pos) /*!< 0x00000008 */ -#define ADC_IER_EOSIE ADC_IER_EOSIE_Msk /*!< ADC End of Regular sequence of Conversions interrupt source */ -#define ADC_IER_OVRIE_Pos (4U) -#define ADC_IER_OVRIE_Msk (0x1UL << ADC_IER_OVRIE_Pos) /*!< 0x00000010 */ -#define ADC_IER_OVRIE ADC_IER_OVRIE_Msk /*!< ADC overrun interrupt source */ -#define ADC_IER_JEOCIE_Pos (5U) -#define ADC_IER_JEOCIE_Msk (0x1UL << ADC_IER_JEOCIE_Pos) /*!< 0x00000020 */ -#define ADC_IER_JEOCIE ADC_IER_JEOCIE_Msk /*!< ADC End of Injected Conversion interrupt source */ -#define ADC_IER_JEOSIE_Pos (6U) -#define ADC_IER_JEOSIE_Msk (0x1UL << ADC_IER_JEOSIE_Pos) /*!< 0x00000040 */ -#define ADC_IER_JEOSIE ADC_IER_JEOSIE_Msk /*!< ADC End of Injected sequence of Conversions interrupt source */ -#define ADC_IER_AWD1IE_Pos (7U) -#define ADC_IER_AWD1IE_Msk (0x1UL << ADC_IER_AWD1IE_Pos) /*!< 0x00000080 */ -#define ADC_IER_AWD1IE ADC_IER_AWD1IE_Msk /*!< ADC Analog watchdog 1 interrupt source */ -#define ADC_IER_AWD2IE_Pos (8U) -#define ADC_IER_AWD2IE_Msk (0x1UL << ADC_IER_AWD2IE_Pos) /*!< 0x00000100 */ -#define ADC_IER_AWD2IE ADC_IER_AWD2IE_Msk /*!< ADC Analog watchdog 2 interrupt source */ -#define ADC_IER_AWD3IE_Pos (9U) -#define ADC_IER_AWD3IE_Msk (0x1UL << ADC_IER_AWD3IE_Pos) /*!< 0x00000200 */ -#define ADC_IER_AWD3IE ADC_IER_AWD3IE_Msk /*!< ADC Analog watchdog 3 interrupt source */ -#define ADC_IER_JQOVFIE_Pos (10U) -#define ADC_IER_JQOVFIE_Msk (0x1UL << ADC_IER_JQOVFIE_Pos) /*!< 0x00000400 */ -#define ADC_IER_JQOVFIE ADC_IER_JQOVFIE_Msk /*!< ADC Injected Context Queue Overflow interrupt source */ - -/******************** Bit definition for ADC_CR register ********************/ -#define ADC_CR_ADEN_Pos (0U) -#define ADC_CR_ADEN_Msk (0x1UL << ADC_CR_ADEN_Pos) /*!< 0x00000001 */ -#define ADC_CR_ADEN ADC_CR_ADEN_Msk /*!< ADC Enable control */ -#define ADC_CR_ADDIS_Pos (1U) -#define ADC_CR_ADDIS_Msk (0x1UL << ADC_CR_ADDIS_Pos) /*!< 0x00000002 */ -#define ADC_CR_ADDIS ADC_CR_ADDIS_Msk /*!< ADC Disable command */ -#define ADC_CR_ADSTART_Pos (2U) -#define ADC_CR_ADSTART_Msk (0x1UL << ADC_CR_ADSTART_Pos) /*!< 0x00000004 */ -#define ADC_CR_ADSTART ADC_CR_ADSTART_Msk /*!< ADC Start of Regular conversion */ -#define ADC_CR_JADSTART_Pos (3U) -#define ADC_CR_JADSTART_Msk (0x1UL << ADC_CR_JADSTART_Pos) /*!< 0x00000008 */ -#define ADC_CR_JADSTART ADC_CR_JADSTART_Msk /*!< ADC Start of injected conversion */ -#define ADC_CR_ADSTP_Pos (4U) -#define ADC_CR_ADSTP_Msk (0x1UL << ADC_CR_ADSTP_Pos) /*!< 0x00000010 */ -#define ADC_CR_ADSTP ADC_CR_ADSTP_Msk /*!< ADC Stop of Regular conversion */ -#define ADC_CR_JADSTP_Pos (5U) -#define ADC_CR_JADSTP_Msk (0x1UL << ADC_CR_JADSTP_Pos) /*!< 0x00000020 */ -#define ADC_CR_JADSTP ADC_CR_JADSTP_Msk /*!< ADC Stop of injected conversion */ -#define ADC_CR_BOOST_Pos (8U) -#define ADC_CR_BOOST_Msk (0x3UL << ADC_CR_BOOST_Pos) /*!< 0x00000300 */ -#define ADC_CR_BOOST ADC_CR_BOOST_Msk /*!< ADC Boost Mode configuration */ -#define ADC_CR_BOOST_0 (0x1UL << ADC_CR_BOOST_Pos) /*!< 0x00000100 */ -#define ADC_CR_BOOST_1 (0x2UL << ADC_CR_BOOST_Pos) /*!< 0x00000200 */ -#define ADC_CR_ADCALLIN_Pos (16U) -#define ADC_CR_ADCALLIN_Msk (0x1UL << ADC_CR_ADCALLIN_Pos) /*!< 0x00010000 */ -#define ADC_CR_ADCALLIN ADC_CR_ADCALLIN_Msk /*!< ADC Linearity calibration */ -#define ADC_CR_LINCALRDYW1_Pos (22U) -#define ADC_CR_LINCALRDYW1_Msk (0x1UL << ADC_CR_LINCALRDYW1_Pos) /*!< 0x00400000 */ -#define ADC_CR_LINCALRDYW1 ADC_CR_LINCALRDYW1_Msk /*!< ADC Linearity calibration ready Word 1 */ -#define ADC_CR_LINCALRDYW2_Pos (23U) -#define ADC_CR_LINCALRDYW2_Msk (0x1UL << ADC_CR_LINCALRDYW2_Pos) /*!< 0x00800000 */ -#define ADC_CR_LINCALRDYW2 ADC_CR_LINCALRDYW2_Msk /*!< ADC Linearity calibration ready Word 2 */ -#define ADC_CR_LINCALRDYW3_Pos (24U) -#define ADC_CR_LINCALRDYW3_Msk (0x1UL << ADC_CR_LINCALRDYW3_Pos) /*!< 0x01000000 */ -#define ADC_CR_LINCALRDYW3 ADC_CR_LINCALRDYW3_Msk /*!< ADC Linearity calibration ready Word 3 */ -#define ADC_CR_LINCALRDYW4_Pos (25U) -#define ADC_CR_LINCALRDYW4_Msk (0x1UL << ADC_CR_LINCALRDYW4_Pos) /*!< 0x02000000 */ -#define ADC_CR_LINCALRDYW4 ADC_CR_LINCALRDYW4_Msk /*!< ADC Linearity calibration ready Word 4 */ -#define ADC_CR_LINCALRDYW5_Pos (26U) -#define ADC_CR_LINCALRDYW5_Msk (0x1UL << ADC_CR_LINCALRDYW5_Pos) /*!< 0x04000000 */ -#define ADC_CR_LINCALRDYW5 ADC_CR_LINCALRDYW5_Msk /*!< ADC Linearity calibration ready Word 5 */ -#define ADC_CR_LINCALRDYW6_Pos (27U) -#define ADC_CR_LINCALRDYW6_Msk (0x1UL << ADC_CR_LINCALRDYW6_Pos) /*!< 0x08000000 */ -#define ADC_CR_LINCALRDYW6 ADC_CR_LINCALRDYW6_Msk /*!< ADC Linearity calibration ready Word 6 */ -#define ADC_CR_ADVREGEN_Pos (28U) -#define ADC_CR_ADVREGEN_Msk (0x1UL << ADC_CR_ADVREGEN_Pos) /*!< 0x10000000 */ -#define ADC_CR_ADVREGEN ADC_CR_ADVREGEN_Msk /*!< ADC Voltage regulator Enable */ -#define ADC_CR_DEEPPWD_Pos (29U) -#define ADC_CR_DEEPPWD_Msk (0x1UL << ADC_CR_DEEPPWD_Pos) /*!< 0x20000000 */ -#define ADC_CR_DEEPPWD ADC_CR_DEEPPWD_Msk /*!< ADC Deep power down Enable */ -#define ADC_CR_ADCALDIF_Pos (30U) -#define ADC_CR_ADCALDIF_Msk (0x1UL << ADC_CR_ADCALDIF_Pos) /*!< 0x40000000 */ -#define ADC_CR_ADCALDIF ADC_CR_ADCALDIF_Msk /*!< ADC Differential Mode for calibration */ -#define ADC_CR_ADCAL_Pos (31U) -#define ADC_CR_ADCAL_Msk (0x1UL << ADC_CR_ADCAL_Pos) /*!< 0x80000000 */ -#define ADC_CR_ADCAL ADC_CR_ADCAL_Msk /*!< ADC Calibration */ - -/******************** Bit definition for ADC_CFGR register ********************/ -#define ADC_CFGR_DMNGT_Pos (0U) -#define ADC_CFGR_DMNGT_Msk (0x3UL << ADC_CFGR_DMNGT_Pos) /*!< 0x00000003 */ -#define ADC_CFGR_DMNGT ADC_CFGR_DMNGT_Msk /*!< ADC Data Management configuration */ -#define ADC_CFGR_DMNGT_0 (0x1UL << ADC_CFGR_DMNGT_Pos) /*!< 0x00000001 */ -#define ADC_CFGR_DMNGT_1 (0x2UL << ADC_CFGR_DMNGT_Pos) /*!< 0x00000002 */ - -#define ADC_CFGR_RES_Pos (2U) -#define ADC_CFGR_RES_Msk (0x7UL << ADC_CFGR_RES_Pos) /*!< 0x0000001C */ -#define ADC_CFGR_RES ADC_CFGR_RES_Msk /*!< ADC Data resolution */ -#define ADC_CFGR_RES_0 (0x1UL << ADC_CFGR_RES_Pos) /*!< 0x00000004 */ -#define ADC_CFGR_RES_1 (0x2UL << ADC_CFGR_RES_Pos) /*!< 0x00000008 */ -#define ADC_CFGR_RES_2 (0x4UL << ADC_CFGR_RES_Pos) /*!< 0x00000010 */ - -#define ADC_CFGR_EXTSEL_Pos (5U) -#define ADC_CFGR_EXTSEL_Msk (0x1FUL << ADC_CFGR_EXTSEL_Pos) /*!< 0x000003E0 */ -#define ADC_CFGR_EXTSEL ADC_CFGR_EXTSEL_Msk /*!< ADC External trigger selection for regular group */ -#define ADC_CFGR_EXTSEL_0 (0x01UL << ADC_CFGR_EXTSEL_Pos) /*!< 0x00000020 */ -#define ADC_CFGR_EXTSEL_1 (0x02UL << ADC_CFGR_EXTSEL_Pos) /*!< 0x00000040 */ -#define ADC_CFGR_EXTSEL_2 (0x04UL << ADC_CFGR_EXTSEL_Pos) /*!< 0x00000080 */ -#define ADC_CFGR_EXTSEL_3 (0x08UL << ADC_CFGR_EXTSEL_Pos) /*!< 0x00000100 */ -#define ADC_CFGR_EXTSEL_4 (0x10UL << ADC_CFGR_EXTSEL_Pos) /*!< 0x00000200 */ - -#define ADC_CFGR_EXTEN_Pos (10U) -#define ADC_CFGR_EXTEN_Msk (0x3UL << ADC_CFGR_EXTEN_Pos) /*!< 0x00000C00 */ -#define ADC_CFGR_EXTEN ADC_CFGR_EXTEN_Msk /*!< ADC External trigger enable and polarity selection for regular channels */ -#define ADC_CFGR_EXTEN_0 (0x1UL << ADC_CFGR_EXTEN_Pos) /*!< 0x00000400 */ -#define ADC_CFGR_EXTEN_1 (0x2UL << ADC_CFGR_EXTEN_Pos) /*!< 0x00000800 */ - -#define ADC_CFGR_OVRMOD_Pos (12U) -#define ADC_CFGR_OVRMOD_Msk (0x1UL << ADC_CFGR_OVRMOD_Pos) /*!< 0x00001000 */ -#define ADC_CFGR_OVRMOD ADC_CFGR_OVRMOD_Msk /*!< ADC overrun mode */ -#define ADC_CFGR_CONT_Pos (13U) -#define ADC_CFGR_CONT_Msk (0x1UL << ADC_CFGR_CONT_Pos) /*!< 0x00002000 */ -#define ADC_CFGR_CONT ADC_CFGR_CONT_Msk /*!< ADC Single/continuous conversion mode for regular conversion */ -#define ADC_CFGR_AUTDLY_Pos (14U) -#define ADC_CFGR_AUTDLY_Msk (0x1UL << ADC_CFGR_AUTDLY_Pos) /*!< 0x00004000 */ -#define ADC_CFGR_AUTDLY ADC_CFGR_AUTDLY_Msk /*!< ADC Delayed conversion mode */ - -#define ADC_CFGR_DISCEN_Pos (16U) -#define ADC_CFGR_DISCEN_Msk (0x1UL << ADC_CFGR_DISCEN_Pos) /*!< 0x00010000 */ -#define ADC_CFGR_DISCEN ADC_CFGR_DISCEN_Msk /*!< ADC Discontinuous mode for regular channels */ - -#define ADC_CFGR_DISCNUM_Pos (17U) -#define ADC_CFGR_DISCNUM_Msk (0x7UL << ADC_CFGR_DISCNUM_Pos) /*!< 0x000E0000 */ -#define ADC_CFGR_DISCNUM ADC_CFGR_DISCNUM_Msk /*!< ADC Discontinuous mode channel count */ -#define ADC_CFGR_DISCNUM_0 (0x1UL << ADC_CFGR_DISCNUM_Pos) /*!< 0x00020000 */ -#define ADC_CFGR_DISCNUM_1 (0x2UL << ADC_CFGR_DISCNUM_Pos) /*!< 0x00040000 */ -#define ADC_CFGR_DISCNUM_2 (0x4UL << ADC_CFGR_DISCNUM_Pos) /*!< 0x00080000 */ - -#define ADC_CFGR_JDISCEN_Pos (20U) -#define ADC_CFGR_JDISCEN_Msk (0x1UL << ADC_CFGR_JDISCEN_Pos) /*!< 0x00100000 */ -#define ADC_CFGR_JDISCEN ADC_CFGR_JDISCEN_Msk /*!< ADC Discontinuous mode on injected channels */ -#define ADC_CFGR_JQM_Pos (21U) -#define ADC_CFGR_JQM_Msk (0x1UL << ADC_CFGR_JQM_Pos) /*!< 0x00200000 */ -#define ADC_CFGR_JQM ADC_CFGR_JQM_Msk /*!< ADC JSQR Queue mode */ -#define ADC_CFGR_AWD1SGL_Pos (22U) -#define ADC_CFGR_AWD1SGL_Msk (0x1UL << ADC_CFGR_AWD1SGL_Pos) /*!< 0x00400000 */ -#define ADC_CFGR_AWD1SGL ADC_CFGR_AWD1SGL_Msk /*!< Enable the watchdog 1 on a single channel or on all channels */ -#define ADC_CFGR_AWD1EN_Pos (23U) -#define ADC_CFGR_AWD1EN_Msk (0x1UL << ADC_CFGR_AWD1EN_Pos) /*!< 0x00800000 */ -#define ADC_CFGR_AWD1EN ADC_CFGR_AWD1EN_Msk /*!< ADC Analog watchdog 1 enable on regular Channels */ -#define ADC_CFGR_JAWD1EN_Pos (24U) -#define ADC_CFGR_JAWD1EN_Msk (0x1UL << ADC_CFGR_JAWD1EN_Pos) /*!< 0x01000000 */ -#define ADC_CFGR_JAWD1EN ADC_CFGR_JAWD1EN_Msk /*!< ADC Analog watchdog 1 enable on injected Channels */ -#define ADC_CFGR_JAUTO_Pos (25U) -#define ADC_CFGR_JAUTO_Msk (0x1UL << ADC_CFGR_JAUTO_Pos) /*!< 0x02000000 */ -#define ADC_CFGR_JAUTO ADC_CFGR_JAUTO_Msk /*!< ADC Automatic injected group conversion */ - -#define ADC_CFGR_AWD1CH_Pos (26U) -#define ADC_CFGR_AWD1CH_Msk (0x1FUL << ADC_CFGR_AWD1CH_Pos) /*!< 0x7C000000 */ -#define ADC_CFGR_AWD1CH ADC_CFGR_AWD1CH_Msk /*!< ADC Analog watchdog 1 Channel selection */ -#define ADC_CFGR_AWD1CH_0 (0x01UL << ADC_CFGR_AWD1CH_Pos) /*!< 0x04000000 */ -#define ADC_CFGR_AWD1CH_1 (0x02UL << ADC_CFGR_AWD1CH_Pos) /*!< 0x08000000 */ -#define ADC_CFGR_AWD1CH_2 (0x04UL << ADC_CFGR_AWD1CH_Pos) /*!< 0x10000000 */ -#define ADC_CFGR_AWD1CH_3 (0x08UL << ADC_CFGR_AWD1CH_Pos) /*!< 0x20000000 */ -#define ADC_CFGR_AWD1CH_4 (0x10UL << ADC_CFGR_AWD1CH_Pos) /*!< 0x40000000 */ - -#define ADC_CFGR_JQDIS_Pos (31U) -#define ADC_CFGR_JQDIS_Msk (0x1UL << ADC_CFGR_JQDIS_Pos) /*!< 0x80000000 */ -#define ADC_CFGR_JQDIS ADC_CFGR_JQDIS_Msk /*!< ADC Injected queue disable */ - -#define ADC3_CFGR_DMAEN_Pos (0U) -#define ADC3_CFGR_DMAEN_Msk (0x1UL << ADC3_CFGR_DMAEN_Pos) /*!< 0x00000001 */ -#define ADC3_CFGR_DMAEN ADC3_CFGR_DMAEN_Msk /*!< ADC DMA transfer enable */ -#define ADC3_CFGR_DMACFG_Pos (1U) -#define ADC3_CFGR_DMACFG_Msk (0x1UL << ADC3_CFGR_DMACFG_Pos) /*!< 0x00000002 */ -#define ADC3_CFGR_DMACFG ADC3_CFGR_DMACFG_Msk /*!< ADC DMA transfer configuration */ - -#define ADC3_CFGR_RES_Pos (3U) -#define ADC3_CFGR_RES_Msk (0x3UL << ADC3_CFGR_RES_Pos) /*!< 0x00000018 */ -#define ADC3_CFGR_RES ADC3_CFGR_RES_Msk /*!< ADC data resolution */ -#define ADC3_CFGR_RES_0 (0x1UL << ADC3_CFGR_RES_Pos) /*!< 0x00000008 */ -#define ADC3_CFGR_RES_1 (0x2UL << ADC3_CFGR_RES_Pos) /*!< 0x00000010 */ - -#define ADC3_CFGR_ALIGN_Pos (15U) -#define ADC3_CFGR_ALIGN_Msk (0x1UL << ADC3_CFGR_ALIGN_Pos) /*!< 0x00008000 */ -#define ADC3_CFGR_ALIGN ADC3_CFGR_ALIGN_Msk /*!< ADC data alignment */ -/******************** Bit definition for ADC_CFGR2 register ********************/ -#define ADC_CFGR2_ROVSE_Pos (0U) -#define ADC_CFGR2_ROVSE_Msk (0x1UL << ADC_CFGR2_ROVSE_Pos) /*!< 0x00000001 */ -#define ADC_CFGR2_ROVSE ADC_CFGR2_ROVSE_Msk /*!< ADC Regular group oversampler enable */ -#define ADC_CFGR2_JOVSE_Pos (1U) -#define ADC_CFGR2_JOVSE_Msk (0x1UL << ADC_CFGR2_JOVSE_Pos) /*!< 0x00000002 */ -#define ADC_CFGR2_JOVSE ADC_CFGR2_JOVSE_Msk /*!< ADC Injected group oversampler enable */ - -#define ADC_CFGR2_OVSS_Pos (5U) -#define ADC_CFGR2_OVSS_Msk (0xFUL << ADC_CFGR2_OVSS_Pos) /*!< 0x000001E0 */ -#define ADC_CFGR2_OVSS ADC_CFGR2_OVSS_Msk /*!< ADC Regular Oversampling shift */ -#define ADC_CFGR2_OVSS_0 (0x1UL << ADC_CFGR2_OVSS_Pos) /*!< 0x00000020 */ -#define ADC_CFGR2_OVSS_1 (0x2UL << ADC_CFGR2_OVSS_Pos) /*!< 0x00000040 */ -#define ADC_CFGR2_OVSS_2 (0x4UL << ADC_CFGR2_OVSS_Pos) /*!< 0x00000080 */ -#define ADC_CFGR2_OVSS_3 (0x8UL << ADC_CFGR2_OVSS_Pos) /*!< 0x00000100 */ - -#define ADC_CFGR2_TROVS_Pos (9U) -#define ADC_CFGR2_TROVS_Msk (0x1UL << ADC_CFGR2_TROVS_Pos) /*!< 0x00000200 */ -#define ADC_CFGR2_TROVS ADC_CFGR2_TROVS_Msk /*!< ADC Triggered regular Oversampling */ -#define ADC_CFGR2_ROVSM_Pos (10U) -#define ADC_CFGR2_ROVSM_Msk (0x1UL << ADC_CFGR2_ROVSM_Pos) /*!< 0x00000400 */ -#define ADC_CFGR2_ROVSM ADC_CFGR2_ROVSM_Msk /*!< ADC Regular oversampling mode */ - -#define ADC_CFGR2_RSHIFT1_Pos (11U) -#define ADC_CFGR2_RSHIFT1_Msk (0x1UL << ADC_CFGR2_RSHIFT1_Pos) /*!< 0x00000800 */ -#define ADC_CFGR2_RSHIFT1 ADC_CFGR2_RSHIFT1_Msk /*!< ADC Right-shift data after Offset 1 correction */ -#define ADC_CFGR2_RSHIFT2_Pos (12U) -#define ADC_CFGR2_RSHIFT2_Msk (0x1UL << ADC_CFGR2_RSHIFT2_Pos) /*!< 0x00001000 */ -#define ADC_CFGR2_RSHIFT2 ADC_CFGR2_RSHIFT2_Msk /*!< ADC Right-shift data after Offset 2 correction */ -#define ADC_CFGR2_RSHIFT3_Pos (13U) -#define ADC_CFGR2_RSHIFT3_Msk (0x1UL << ADC_CFGR2_RSHIFT3_Pos) /*!< 0x00002000 */ -#define ADC_CFGR2_RSHIFT3 ADC_CFGR2_RSHIFT3_Msk /*!< ADC Right-shift data after Offset 3 correction */ -#define ADC_CFGR2_RSHIFT4_Pos (14U) -#define ADC_CFGR2_RSHIFT4_Msk (0x1UL << ADC_CFGR2_RSHIFT4_Pos) /*!< 0x00004000 */ -#define ADC_CFGR2_RSHIFT4 ADC_CFGR2_RSHIFT4_Msk /*!< ADC Right-shift data after Offset 4 correction */ - -#define ADC_CFGR2_OVSR_Pos (16U) -#define ADC_CFGR2_OVSR_Msk (0x3FFUL << ADC_CFGR2_OVSR_Pos) /*!< 0x03FF0000 */ -#define ADC_CFGR2_OVSR ADC_CFGR2_OVSR_Msk /*!< ADC oversampling Ratio */ -#define ADC_CFGR2_OVSR_0 (0x001UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00010000 */ -#define ADC_CFGR2_OVSR_1 (0x002UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00020000 */ -#define ADC_CFGR2_OVSR_2 (0x004UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00040000 */ -#define ADC_CFGR2_OVSR_3 (0x008UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00080000 */ -#define ADC_CFGR2_OVSR_4 (0x010UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00100000 */ -#define ADC_CFGR2_OVSR_5 (0x020UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00200000 */ -#define ADC_CFGR2_OVSR_6 (0x040UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00400000 */ -#define ADC_CFGR2_OVSR_7 (0x080UL << ADC_CFGR2_OVSR_Pos) /*!< 0x00800000 */ -#define ADC_CFGR2_OVSR_8 (0x100UL << ADC_CFGR2_OVSR_Pos) /*!< 0x01000000 */ -#define ADC_CFGR2_OVSR_9 (0x200UL << ADC_CFGR2_OVSR_Pos) /*!< 0x02000000 */ - -#define ADC_CFGR2_LSHIFT_Pos (28U) -#define ADC_CFGR2_LSHIFT_Msk (0xFUL << ADC_CFGR2_LSHIFT_Pos) /*!< 0xF0000000 */ -#define ADC_CFGR2_LSHIFT ADC_CFGR2_LSHIFT_Msk /*!< ADC Left shift factor */ -#define ADC_CFGR2_LSHIFT_0 (0x1UL << ADC_CFGR2_LSHIFT_Pos) /*!< 0x10000000 */ -#define ADC_CFGR2_LSHIFT_1 (0x2UL << ADC_CFGR2_LSHIFT_Pos) /*!< 0x20000000 */ -#define ADC_CFGR2_LSHIFT_2 (0x4UL << ADC_CFGR2_LSHIFT_Pos) /*!< 0x40000000 */ -#define ADC_CFGR2_LSHIFT_3 (0x8UL << ADC_CFGR2_LSHIFT_Pos) /*!< 0x80000000 */ - -#define ADC3_CFGR2_OVSR_Pos (2U) -#define ADC3_CFGR2_OVSR_Msk (0x7UL << ADC3_CFGR2_OVSR_Pos) /*!< 0x0000001C */ -#define ADC3_CFGR2_OVSR ADC3_CFGR2_OVSR_Msk /*!< ADC oversampling ratio */ -#define ADC3_CFGR2_OVSR_0 (0x1UL << ADC3_CFGR2_OVSR_Pos) /*!< 0x00000004 */ -#define ADC3_CFGR2_OVSR_1 (0x2UL << ADC3_CFGR2_OVSR_Pos) /*!< 0x00000008 */ -#define ADC3_CFGR2_OVSR_2 (0x4UL << ADC3_CFGR2_OVSR_Pos) /*!< 0x00000010 */ - -#define ADC3_CFGR2_SWTRIG_Pos (25U) -#define ADC3_CFGR2_SWTRIG_Msk (0x1UL << ADC3_CFGR2_SWTRIG_Pos) /*!< 0x02000000 */ -#define ADC3_CFGR2_SWTRIG ADC3_CFGR2_SWTRIG_Msk /*!< ADC Software Trigger Bit for Sample time control trigger mode */ -#define ADC3_CFGR2_BULB_Pos (26U) -#define ADC3_CFGR2_BULB_Msk (0x1UL << ADC3_CFGR2_BULB_Pos) /*!< 0x04000000 */ -#define ADC3_CFGR2_BULB ADC3_CFGR2_BULB_Msk /*!< ADC Bulb sampling mode */ -#define ADC3_CFGR2_SMPTRIG_Pos (27U) -#define ADC3_CFGR2_SMPTRIG_Msk (0x1UL << ADC3_CFGR2_SMPTRIG_Pos) /*!< 0x08000000 */ -#define ADC3_CFGR2_SMPTRIG ADC3_CFGR2_SMPTRIG_Msk /*!< ADC Sample Time Control Trigger mode */ -/******************** Bit definition for ADC_SMPR1 register ********************/ -#define ADC_SMPR1_SMP0_Pos (0U) -#define ADC_SMPR1_SMP0_Msk (0x7UL << ADC_SMPR1_SMP0_Pos) /*!< 0x00000007 */ -#define ADC_SMPR1_SMP0 ADC_SMPR1_SMP0_Msk /*!< ADC Channel 0 Sampling time selection */ -#define ADC_SMPR1_SMP0_0 (0x1UL << ADC_SMPR1_SMP0_Pos) /*!< 0x00000001 */ -#define ADC_SMPR1_SMP0_1 (0x2UL << ADC_SMPR1_SMP0_Pos) /*!< 0x00000002 */ -#define ADC_SMPR1_SMP0_2 (0x4UL << ADC_SMPR1_SMP0_Pos) /*!< 0x00000004 */ - -#define ADC_SMPR1_SMP1_Pos (3U) -#define ADC_SMPR1_SMP1_Msk (0x7UL << ADC_SMPR1_SMP1_Pos) /*!< 0x00000038 */ -#define ADC_SMPR1_SMP1 ADC_SMPR1_SMP1_Msk /*!< ADC Channel 1 Sampling time selection */ -#define ADC_SMPR1_SMP1_0 (0x1UL << ADC_SMPR1_SMP1_Pos) /*!< 0x00000008 */ -#define ADC_SMPR1_SMP1_1 (0x2UL << ADC_SMPR1_SMP1_Pos) /*!< 0x00000010 */ -#define ADC_SMPR1_SMP1_2 (0x4UL << ADC_SMPR1_SMP1_Pos) /*!< 0x00000020 */ - -#define ADC_SMPR1_SMP2_Pos (6U) -#define ADC_SMPR1_SMP2_Msk (0x7UL << ADC_SMPR1_SMP2_Pos) /*!< 0x000001C0 */ -#define ADC_SMPR1_SMP2 ADC_SMPR1_SMP2_Msk /*!< ADC Channel 2 Sampling time selection */ -#define ADC_SMPR1_SMP2_0 (0x1UL << ADC_SMPR1_SMP2_Pos) /*!< 0x00000040 */ -#define ADC_SMPR1_SMP2_1 (0x2UL << ADC_SMPR1_SMP2_Pos) /*!< 0x00000080 */ -#define ADC_SMPR1_SMP2_2 (0x4UL << ADC_SMPR1_SMP2_Pos) /*!< 0x00000100 */ - -#define ADC_SMPR1_SMP3_Pos (9U) -#define ADC_SMPR1_SMP3_Msk (0x7UL << ADC_SMPR1_SMP3_Pos) /*!< 0x00000E00 */ -#define ADC_SMPR1_SMP3 ADC_SMPR1_SMP3_Msk /*!< ADC Channel 3 Sampling time selection */ -#define ADC_SMPR1_SMP3_0 (0x1UL << ADC_SMPR1_SMP3_Pos) /*!< 0x00000200 */ -#define ADC_SMPR1_SMP3_1 (0x2UL << ADC_SMPR1_SMP3_Pos) /*!< 0x00000400 */ -#define ADC_SMPR1_SMP3_2 (0x4UL << ADC_SMPR1_SMP3_Pos) /*!< 0x00000800 */ - -#define ADC_SMPR1_SMP4_Pos (12U) -#define ADC_SMPR1_SMP4_Msk (0x7UL << ADC_SMPR1_SMP4_Pos) /*!< 0x00007000 */ -#define ADC_SMPR1_SMP4 ADC_SMPR1_SMP4_Msk /*!< ADC Channel 4 Sampling time selection */ -#define ADC_SMPR1_SMP4_0 (0x1UL << ADC_SMPR1_SMP4_Pos) /*!< 0x00001000 */ -#define ADC_SMPR1_SMP4_1 (0x2UL << ADC_SMPR1_SMP4_Pos) /*!< 0x00002000 */ -#define ADC_SMPR1_SMP4_2 (0x4UL << ADC_SMPR1_SMP4_Pos) /*!< 0x00004000 */ - -#define ADC_SMPR1_SMP5_Pos (15U) -#define ADC_SMPR1_SMP5_Msk (0x7UL << ADC_SMPR1_SMP5_Pos) /*!< 0x00038000 */ -#define ADC_SMPR1_SMP5 ADC_SMPR1_SMP5_Msk /*!< ADC Channel 5 Sampling time selection */ -#define ADC_SMPR1_SMP5_0 (0x1UL << ADC_SMPR1_SMP5_Pos) /*!< 0x00008000 */ -#define ADC_SMPR1_SMP5_1 (0x2UL << ADC_SMPR1_SMP5_Pos) /*!< 0x00010000 */ -#define ADC_SMPR1_SMP5_2 (0x4UL << ADC_SMPR1_SMP5_Pos) /*!< 0x00020000 */ - -#define ADC_SMPR1_SMP6_Pos (18U) -#define ADC_SMPR1_SMP6_Msk (0x7UL << ADC_SMPR1_SMP6_Pos) /*!< 0x001C0000 */ -#define ADC_SMPR1_SMP6 ADC_SMPR1_SMP6_Msk /*!< ADC Channel 6 Sampling time selection */ -#define ADC_SMPR1_SMP6_0 (0x1UL << ADC_SMPR1_SMP6_Pos) /*!< 0x00040000 */ -#define ADC_SMPR1_SMP6_1 (0x2UL << ADC_SMPR1_SMP6_Pos) /*!< 0x00080000 */ -#define ADC_SMPR1_SMP6_2 (0x4UL << ADC_SMPR1_SMP6_Pos) /*!< 0x00100000 */ - -#define ADC_SMPR1_SMP7_Pos (21U) -#define ADC_SMPR1_SMP7_Msk (0x7UL << ADC_SMPR1_SMP7_Pos) /*!< 0x00E00000 */ -#define ADC_SMPR1_SMP7 ADC_SMPR1_SMP7_Msk /*!< ADC Channel 7 Sampling time selection */ -#define ADC_SMPR1_SMP7_0 (0x1UL << ADC_SMPR1_SMP7_Pos) /*!< 0x00200000 */ -#define ADC_SMPR1_SMP7_1 (0x2UL << ADC_SMPR1_SMP7_Pos) /*!< 0x00400000 */ -#define ADC_SMPR1_SMP7_2 (0x4UL << ADC_SMPR1_SMP7_Pos) /*!< 0x00800000 */ - -#define ADC_SMPR1_SMP8_Pos (24U) -#define ADC_SMPR1_SMP8_Msk (0x7UL << ADC_SMPR1_SMP8_Pos) /*!< 0x07000000 */ -#define ADC_SMPR1_SMP8 ADC_SMPR1_SMP8_Msk /*!< ADC Channel 8 Sampling time selection */ -#define ADC_SMPR1_SMP8_0 (0x1UL << ADC_SMPR1_SMP8_Pos) /*!< 0x01000000 */ -#define ADC_SMPR1_SMP8_1 (0x2UL << ADC_SMPR1_SMP8_Pos) /*!< 0x02000000 */ -#define ADC_SMPR1_SMP8_2 (0x4UL << ADC_SMPR1_SMP8_Pos) /*!< 0x04000000 */ - -#define ADC_SMPR1_SMP9_Pos (27U) -#define ADC_SMPR1_SMP9_Msk (0x7UL << ADC_SMPR1_SMP9_Pos) /*!< 0x38000000 */ -#define ADC_SMPR1_SMP9 ADC_SMPR1_SMP9_Msk /*!< ADC Channel 9 Sampling time selection */ -#define ADC_SMPR1_SMP9_0 (0x1UL << ADC_SMPR1_SMP9_Pos) /*!< 0x08000000 */ -#define ADC_SMPR1_SMP9_1 (0x2UL << ADC_SMPR1_SMP9_Pos) /*!< 0x10000000 */ -#define ADC_SMPR1_SMP9_2 (0x4UL << ADC_SMPR1_SMP9_Pos) /*!< 0x20000000 */ - -/******************** Bit definition for ADC_SMPR2 register ********************/ -#define ADC_SMPR2_SMP10_Pos (0U) -#define ADC_SMPR2_SMP10_Msk (0x7UL << ADC_SMPR2_SMP10_Pos) /*!< 0x00000007 */ -#define ADC_SMPR2_SMP10 ADC_SMPR2_SMP10_Msk /*!< ADC Channel 10 Sampling time selection */ -#define ADC_SMPR2_SMP10_0 (0x1UL << ADC_SMPR2_SMP10_Pos) /*!< 0x00000001 */ -#define ADC_SMPR2_SMP10_1 (0x2UL << ADC_SMPR2_SMP10_Pos) /*!< 0x00000002 */ -#define ADC_SMPR2_SMP10_2 (0x4UL << ADC_SMPR2_SMP10_Pos) /*!< 0x00000004 */ - -#define ADC_SMPR2_SMP11_Pos (3U) -#define ADC_SMPR2_SMP11_Msk (0x7UL << ADC_SMPR2_SMP11_Pos) /*!< 0x00000038 */ -#define ADC_SMPR2_SMP11 ADC_SMPR2_SMP11_Msk /*!< ADC Channel 11 Sampling time selection */ -#define ADC_SMPR2_SMP11_0 (0x1UL << ADC_SMPR2_SMP11_Pos) /*!< 0x00000008 */ -#define ADC_SMPR2_SMP11_1 (0x2UL << ADC_SMPR2_SMP11_Pos) /*!< 0x00000010 */ -#define ADC_SMPR2_SMP11_2 (0x4UL << ADC_SMPR2_SMP11_Pos) /*!< 0x00000020 */ - -#define ADC_SMPR2_SMP12_Pos (6U) -#define ADC_SMPR2_SMP12_Msk (0x7UL << ADC_SMPR2_SMP12_Pos) /*!< 0x000001C0 */ -#define ADC_SMPR2_SMP12 ADC_SMPR2_SMP12_Msk /*!< ADC Channel 12 Sampling time selection */ -#define ADC_SMPR2_SMP12_0 (0x1UL << ADC_SMPR2_SMP12_Pos) /*!< 0x00000040 */ -#define ADC_SMPR2_SMP12_1 (0x2UL << ADC_SMPR2_SMP12_Pos) /*!< 0x00000080 */ -#define ADC_SMPR2_SMP12_2 (0x4UL << ADC_SMPR2_SMP12_Pos) /*!< 0x00000100 */ - -#define ADC_SMPR2_SMP13_Pos (9U) -#define ADC_SMPR2_SMP13_Msk (0x7UL << ADC_SMPR2_SMP13_Pos) /*!< 0x00000E00 */ -#define ADC_SMPR2_SMP13 ADC_SMPR2_SMP13_Msk /*!< ADC Channel 13 Sampling time selection */ -#define ADC_SMPR2_SMP13_0 (0x1UL << ADC_SMPR2_SMP13_Pos) /*!< 0x00000200 */ -#define ADC_SMPR2_SMP13_1 (0x2UL << ADC_SMPR2_SMP13_Pos) /*!< 0x00000400 */ -#define ADC_SMPR2_SMP13_2 (0x4UL << ADC_SMPR2_SMP13_Pos) /*!< 0x00000800 */ - -#define ADC_SMPR2_SMP14_Pos (12U) -#define ADC_SMPR2_SMP14_Msk (0x7UL << ADC_SMPR2_SMP14_Pos) /*!< 0x00007000 */ -#define ADC_SMPR2_SMP14 ADC_SMPR2_SMP14_Msk /*!< ADC Channel 14 Sampling time selection */ -#define ADC_SMPR2_SMP14_0 (0x1UL << ADC_SMPR2_SMP14_Pos) /*!< 0x00001000 */ -#define ADC_SMPR2_SMP14_1 (0x2UL << ADC_SMPR2_SMP14_Pos) /*!< 0x00002000 */ -#define ADC_SMPR2_SMP14_2 (0x4UL << ADC_SMPR2_SMP14_Pos) /*!< 0x00004000 */ - -#define ADC_SMPR2_SMP15_Pos (15U) -#define ADC_SMPR2_SMP15_Msk (0x7UL << ADC_SMPR2_SMP15_Pos) /*!< 0x00038000 */ -#define ADC_SMPR2_SMP15 ADC_SMPR2_SMP15_Msk /*!< ADC Channel 15 Sampling time selection */ -#define ADC_SMPR2_SMP15_0 (0x1UL << ADC_SMPR2_SMP15_Pos) /*!< 0x00008000 */ -#define ADC_SMPR2_SMP15_1 (0x2UL << ADC_SMPR2_SMP15_Pos) /*!< 0x00010000 */ -#define ADC_SMPR2_SMP15_2 (0x4UL << ADC_SMPR2_SMP15_Pos) /*!< 0x00020000 */ - -#define ADC_SMPR2_SMP16_Pos (18U) -#define ADC_SMPR2_SMP16_Msk (0x7UL << ADC_SMPR2_SMP16_Pos) /*!< 0x001C0000 */ -#define ADC_SMPR2_SMP16 ADC_SMPR2_SMP16_Msk /*!< ADC Channel 16 Sampling time selection */ -#define ADC_SMPR2_SMP16_0 (0x1UL << ADC_SMPR2_SMP16_Pos) /*!< 0x00040000 */ -#define ADC_SMPR2_SMP16_1 (0x2UL << ADC_SMPR2_SMP16_Pos) /*!< 0x00080000 */ -#define ADC_SMPR2_SMP16_2 (0x4UL << ADC_SMPR2_SMP16_Pos) /*!< 0x00100000 */ - -#define ADC_SMPR2_SMP17_Pos (21U) -#define ADC_SMPR2_SMP17_Msk (0x7UL << ADC_SMPR2_SMP17_Pos) /*!< 0x00E00000 */ -#define ADC_SMPR2_SMP17 ADC_SMPR2_SMP17_Msk /*!< ADC Channel 17 Sampling time selection */ -#define ADC_SMPR2_SMP17_0 (0x1UL << ADC_SMPR2_SMP17_Pos) /*!< 0x00200000 */ -#define ADC_SMPR2_SMP17_1 (0x2UL << ADC_SMPR2_SMP17_Pos) /*!< 0x00400000 */ -#define ADC_SMPR2_SMP17_2 (0x4UL << ADC_SMPR2_SMP17_Pos) /*!< 0x00800000 */ - -#define ADC_SMPR2_SMP18_Pos (24U) -#define ADC_SMPR2_SMP18_Msk (0x7UL << ADC_SMPR2_SMP18_Pos) /*!< 0x07000000 */ -#define ADC_SMPR2_SMP18 ADC_SMPR2_SMP18_Msk /*!< ADC Channel 18 Sampling time selection */ -#define ADC_SMPR2_SMP18_0 (0x1UL << ADC_SMPR2_SMP18_Pos) /*!< 0x01000000 */ -#define ADC_SMPR2_SMP18_1 (0x2UL << ADC_SMPR2_SMP18_Pos) /*!< 0x02000000 */ -#define ADC_SMPR2_SMP18_2 (0x4UL << ADC_SMPR2_SMP18_Pos) /*!< 0x04000000 */ - -#define ADC_SMPR2_SMP19_Pos (27U) -#define ADC_SMPR2_SMP19_Msk (0x7UL << ADC_SMPR2_SMP19_Pos) /*!< 0x38000000 */ -#define ADC_SMPR2_SMP19 ADC_SMPR2_SMP19_Msk /*!< ADC Channel 19 Sampling time selection */ -#define ADC_SMPR2_SMP19_0 (0x1UL << ADC_SMPR2_SMP19_Pos) /*!< 0x08000000 */ -#define ADC_SMPR2_SMP19_1 (0x2UL << ADC_SMPR2_SMP19_Pos) /*!< 0x10000000 */ -#define ADC_SMPR2_SMP19_2 (0x4UL << ADC_SMPR2_SMP19_Pos) /*!< 0x20000000 */ - -/******************** Bit definition for ADC_PCSEL register ********************/ -#define ADC_PCSEL_PCSEL_Pos (0U) -#define ADC_PCSEL_PCSEL_Msk (0xFFFFFUL << ADC_PCSEL_PCSEL_Pos) /*!< 0x000FFFFF */ -#define ADC_PCSEL_PCSEL ADC_PCSEL_PCSEL_Msk /*!< ADC pre channel selection */ -#define ADC_PCSEL_PCSEL_0 (0x00001UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000001 */ -#define ADC_PCSEL_PCSEL_1 (0x00002UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000002 */ -#define ADC_PCSEL_PCSEL_2 (0x00004UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000004 */ -#define ADC_PCSEL_PCSEL_3 (0x00008UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000008 */ -#define ADC_PCSEL_PCSEL_4 (0x00010UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000010 */ -#define ADC_PCSEL_PCSEL_5 (0x00020UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000020 */ -#define ADC_PCSEL_PCSEL_6 (0x00040UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000040 */ -#define ADC_PCSEL_PCSEL_7 (0x00080UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000080 */ -#define ADC_PCSEL_PCSEL_8 (0x00100UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000100 */ -#define ADC_PCSEL_PCSEL_9 (0x00200UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000200 */ -#define ADC_PCSEL_PCSEL_10 (0x00400UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000400 */ -#define ADC_PCSEL_PCSEL_11 (0x00800UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00000800 */ -#define ADC_PCSEL_PCSEL_12 (0x01000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00001000 */ -#define ADC_PCSEL_PCSEL_13 (0x02000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00002000 */ -#define ADC_PCSEL_PCSEL_14 (0x04000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00004000 */ -#define ADC_PCSEL_PCSEL_15 (0x08000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00008000 */ -#define ADC_PCSEL_PCSEL_16 (0x10000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00010000 */ -#define ADC_PCSEL_PCSEL_17 (0x20000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00020000 */ -#define ADC_PCSEL_PCSEL_18 (0x40000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00040000 */ -#define ADC_PCSEL_PCSEL_19 (0x80000UL << ADC_PCSEL_PCSEL_Pos) /*!< 0x00080000 */ - -/***************** Bit definition for ADC_LTR1, 2, 3 registers *****************/ -#define ADC_LTR_LT_Pos (0U) -#define ADC_LTR_LT_Msk (0x3FFFFFFUL << ADC_LTR_LT_Pos) /*!< 0x03FFFFFF */ -#define ADC_LTR_LT ADC_LTR_LT_Msk /*!< ADC Analog watchdog 1, 2 and 3 lower threshold */ - -/***************** Bit definition for ADC_HTR1, 2, 3 registers ****************/ -#define ADC_HTR_HT_Pos (0U) -#define ADC_HTR_HT_Msk (0x3FFFFFFUL << ADC_HTR_HT_Pos) /*!< 0x03FFFFFF */ -#define ADC_HTR_HT ADC_HTR_HT_Msk /*!< ADC Analog watchdog 1,2 and 3 higher threshold */ - -/******************** Bit definition for ADC3_TR1 register *******************/ -#define ADC3_TR1_LT1_Pos (0U) -#define ADC3_TR1_LT1_Msk (0xFFFUL << ADC3_TR1_LT1_Pos) /*!< 0x00000FFF */ -#define ADC3_TR1_LT1 ADC3_TR1_LT1_Msk /*!< ADC analog watchdog 1 threshold low */ - -#define ADC3_TR1_AWDFILT_Pos (12U) -#define ADC3_TR1_AWDFILT_Msk (0x7UL << ADC3_TR1_AWDFILT_Pos) /*!< 0x00007000 */ -#define ADC3_TR1_AWDFILT ADC3_TR1_AWDFILT_Msk /*!< ADC analog watchdog filtering parameter */ -#define ADC3_TR1_AWDFILT_0 (0x1UL << ADC3_TR1_AWDFILT_Pos) /*!< 0x00001000 */ -#define ADC3_TR1_AWDFILT_1 (0x2UL << ADC3_TR1_AWDFILT_Pos) /*!< 0x00002000 */ -#define ADC3_TR1_AWDFILT_2 (0x4UL << ADC3_TR1_AWDFILT_Pos) /*!< 0x00004000 */ - -#define ADC3_TR1_HT1_Pos (16U) -#define ADC3_TR1_HT1_Msk (0xFFFUL << ADC3_TR1_HT1_Pos) /*!< 0x0FFF0000 */ -#define ADC3_TR1_HT1 ADC3_TR1_HT1_Msk /*!< ADC analog watchdog 1 threshold high */ - -/******************** Bit definition for ADC3_TR2 register *******************/ -#define ADC3_TR2_LT2_Pos (0U) -#define ADC3_TR2_LT2_Msk (0xFFUL << ADC3_TR2_LT2_Pos) /*!< 0x000000FF */ -#define ADC3_TR2_LT2 ADC3_TR2_LT2_Msk /*!< ADC analog watchdog 2 threshold low */ - -#define ADC3_TR2_HT2_Pos (16U) -#define ADC3_TR2_HT2_Msk (0xFFUL << ADC3_TR2_HT2_Pos) /*!< 0x00FF0000 */ -#define ADC3_TR2_HT2 ADC3_TR2_HT2_Msk /*!< ADC analog watchdog 2 threshold high */ - -/******************** Bit definition for ADC3_TR3 register *******************/ -#define ADC3_TR3_LT3_Pos (0U) -#define ADC3_TR3_LT3_Msk (0xFFUL << ADC3_TR3_LT3_Pos) /*!< 0x000000FF */ -#define ADC3_TR3_LT3 ADC3_TR3_LT3_Msk /*!< ADC analog watchdog 3 threshold low */ - -#define ADC3_TR3_HT3_Pos (16U) -#define ADC3_TR3_HT3_Msk (0xFFUL << ADC3_TR3_HT3_Pos) /*!< 0x00FF0000 */ -#define ADC3_TR3_HT3 ADC3_TR3_HT3_Msk /*!< ADC analog watchdog 3 threshold high */ - -/******************** Bit definition for ADC_SQR1 register ********************/ -#define ADC_SQR1_L_Pos (0U) -#define ADC_SQR1_L_Msk (0xFUL << ADC_SQR1_L_Pos) /*!< 0x0000000F */ -#define ADC_SQR1_L ADC_SQR1_L_Msk /*!< ADC regular channel sequence length */ -#define ADC_SQR1_L_0 (0x1UL << ADC_SQR1_L_Pos) /*!< 0x00000001 */ -#define ADC_SQR1_L_1 (0x2UL << ADC_SQR1_L_Pos) /*!< 0x00000002 */ -#define ADC_SQR1_L_2 (0x4UL << ADC_SQR1_L_Pos) /*!< 0x00000004 */ -#define ADC_SQR1_L_3 (0x8UL << ADC_SQR1_L_Pos) /*!< 0x00000008 */ - -#define ADC_SQR1_SQ1_Pos (6U) -#define ADC_SQR1_SQ1_Msk (0x1FUL << ADC_SQR1_SQ1_Pos) /*!< 0x000007C0 */ -#define ADC_SQR1_SQ1 ADC_SQR1_SQ1_Msk /*!< ADC 1st conversion in regular sequence */ -#define ADC_SQR1_SQ1_0 (0x01UL << ADC_SQR1_SQ1_Pos) /*!< 0x00000040 */ -#define ADC_SQR1_SQ1_1 (0x02UL << ADC_SQR1_SQ1_Pos) /*!< 0x00000080 */ -#define ADC_SQR1_SQ1_2 (0x04UL << ADC_SQR1_SQ1_Pos) /*!< 0x00000100 */ -#define ADC_SQR1_SQ1_3 (0x08UL << ADC_SQR1_SQ1_Pos) /*!< 0x00000200 */ -#define ADC_SQR1_SQ1_4 (0x10UL << ADC_SQR1_SQ1_Pos) /*!< 0x00000400 */ - -#define ADC_SQR1_SQ2_Pos (12U) -#define ADC_SQR1_SQ2_Msk (0x1FUL << ADC_SQR1_SQ2_Pos) /*!< 0x0001F000 */ -#define ADC_SQR1_SQ2 ADC_SQR1_SQ2_Msk /*!< ADC 2nd conversion in regular sequence */ -#define ADC_SQR1_SQ2_0 (0x01UL << ADC_SQR1_SQ2_Pos) /*!< 0x00001000 */ -#define ADC_SQR1_SQ2_1 (0x02UL << ADC_SQR1_SQ2_Pos) /*!< 0x00002000 */ -#define ADC_SQR1_SQ2_2 (0x04UL << ADC_SQR1_SQ2_Pos) /*!< 0x00004000 */ -#define ADC_SQR1_SQ2_3 (0x08UL << ADC_SQR1_SQ2_Pos) /*!< 0x00008000 */ -#define ADC_SQR1_SQ2_4 (0x10UL << ADC_SQR1_SQ2_Pos) /*!< 0x00010000 */ - -#define ADC_SQR1_SQ3_Pos (18U) -#define ADC_SQR1_SQ3_Msk (0x1FUL << ADC_SQR1_SQ3_Pos) /*!< 0x007C0000 */ -#define ADC_SQR1_SQ3 ADC_SQR1_SQ3_Msk /*!< ADC 3rd conversion in regular sequence */ -#define ADC_SQR1_SQ3_0 (0x01UL << ADC_SQR1_SQ3_Pos) /*!< 0x00040000 */ -#define ADC_SQR1_SQ3_1 (0x02UL << ADC_SQR1_SQ3_Pos) /*!< 0x00080000 */ -#define ADC_SQR1_SQ3_2 (0x04UL << ADC_SQR1_SQ3_Pos) /*!< 0x00100000 */ -#define ADC_SQR1_SQ3_3 (0x08UL << ADC_SQR1_SQ3_Pos) /*!< 0x00200000 */ -#define ADC_SQR1_SQ3_4 (0x10UL << ADC_SQR1_SQ3_Pos) /*!< 0x00400000 */ - -#define ADC_SQR1_SQ4_Pos (24U) -#define ADC_SQR1_SQ4_Msk (0x1FUL << ADC_SQR1_SQ4_Pos) /*!< 0x1F000000 */ -#define ADC_SQR1_SQ4 ADC_SQR1_SQ4_Msk /*!< ADC 4th conversion in regular sequence */ -#define ADC_SQR1_SQ4_0 (0x01UL << ADC_SQR1_SQ4_Pos) /*!< 0x01000000 */ -#define ADC_SQR1_SQ4_1 (0x02UL << ADC_SQR1_SQ4_Pos) /*!< 0x02000000 */ -#define ADC_SQR1_SQ4_2 (0x04UL << ADC_SQR1_SQ4_Pos) /*!< 0x04000000 */ -#define ADC_SQR1_SQ4_3 (0x08UL << ADC_SQR1_SQ4_Pos) /*!< 0x08000000 */ -#define ADC_SQR1_SQ4_4 (0x10UL << ADC_SQR1_SQ4_Pos) /*!< 0x10000000 */ - -/******************** Bit definition for ADC_SQR2 register ********************/ -#define ADC_SQR2_SQ5_Pos (0U) -#define ADC_SQR2_SQ5_Msk (0x1FUL << ADC_SQR2_SQ5_Pos) /*!< 0x0000001F */ -#define ADC_SQR2_SQ5 ADC_SQR2_SQ5_Msk /*!< ADC 5th conversion in regular sequence */ -#define ADC_SQR2_SQ5_0 (0x01UL << ADC_SQR2_SQ5_Pos) /*!< 0x00000001 */ -#define ADC_SQR2_SQ5_1 (0x02UL << ADC_SQR2_SQ5_Pos) /*!< 0x00000002 */ -#define ADC_SQR2_SQ5_2 (0x04UL << ADC_SQR2_SQ5_Pos) /*!< 0x00000004 */ -#define ADC_SQR2_SQ5_3 (0x08UL << ADC_SQR2_SQ5_Pos) /*!< 0x00000008 */ -#define ADC_SQR2_SQ5_4 (0x10UL << ADC_SQR2_SQ5_Pos) /*!< 0x00000010 */ - -#define ADC_SQR2_SQ6_Pos (6U) -#define ADC_SQR2_SQ6_Msk (0x1FUL << ADC_SQR2_SQ6_Pos) /*!< 0x000007C0 */ -#define ADC_SQR2_SQ6 ADC_SQR2_SQ6_Msk /*!< ADC 6th conversion in regular sequence */ -#define ADC_SQR2_SQ6_0 (0x01UL << ADC_SQR2_SQ6_Pos) /*!< 0x00000040 */ -#define ADC_SQR2_SQ6_1 (0x02UL << ADC_SQR2_SQ6_Pos) /*!< 0x00000080 */ -#define ADC_SQR2_SQ6_2 (0x04UL << ADC_SQR2_SQ6_Pos) /*!< 0x00000100 */ -#define ADC_SQR2_SQ6_3 (0x08UL << ADC_SQR2_SQ6_Pos) /*!< 0x00000200 */ -#define ADC_SQR2_SQ6_4 (0x10UL << ADC_SQR2_SQ6_Pos) /*!< 0x00000400 */ - -#define ADC_SQR2_SQ7_Pos (12U) -#define ADC_SQR2_SQ7_Msk (0x1FUL << ADC_SQR2_SQ7_Pos) /*!< 0x0001F000 */ -#define ADC_SQR2_SQ7 ADC_SQR2_SQ7_Msk /*!< ADC 7th conversion in regular sequence */ -#define ADC_SQR2_SQ7_0 (0x01UL << ADC_SQR2_SQ7_Pos) /*!< 0x00001000 */ -#define ADC_SQR2_SQ7_1 (0x02UL << ADC_SQR2_SQ7_Pos) /*!< 0x00002000 */ -#define ADC_SQR2_SQ7_2 (0x04UL << ADC_SQR2_SQ7_Pos) /*!< 0x00004000 */ -#define ADC_SQR2_SQ7_3 (0x08UL << ADC_SQR2_SQ7_Pos) /*!< 0x00008000 */ -#define ADC_SQR2_SQ7_4 (0x10UL << ADC_SQR2_SQ7_Pos) /*!< 0x00010000 */ - -#define ADC_SQR2_SQ8_Pos (18U) -#define ADC_SQR2_SQ8_Msk (0x1FUL << ADC_SQR2_SQ8_Pos) /*!< 0x007C0000 */ -#define ADC_SQR2_SQ8 ADC_SQR2_SQ8_Msk /*!< ADC 8th conversion in regular sequence */ -#define ADC_SQR2_SQ8_0 (0x01UL << ADC_SQR2_SQ8_Pos) /*!< 0x00040000 */ -#define ADC_SQR2_SQ8_1 (0x02UL << ADC_SQR2_SQ8_Pos) /*!< 0x00080000 */ -#define ADC_SQR2_SQ8_2 (0x04UL << ADC_SQR2_SQ8_Pos) /*!< 0x00100000 */ -#define ADC_SQR2_SQ8_3 (0x08UL << ADC_SQR2_SQ8_Pos) /*!< 0x00200000 */ -#define ADC_SQR2_SQ8_4 (0x10UL << ADC_SQR2_SQ8_Pos) /*!< 0x00400000 */ - -#define ADC_SQR2_SQ9_Pos (24U) -#define ADC_SQR2_SQ9_Msk (0x1FUL << ADC_SQR2_SQ9_Pos) /*!< 0x1F000000 */ -#define ADC_SQR2_SQ9 ADC_SQR2_SQ9_Msk /*!< ADC 9th conversion in regular sequence */ -#define ADC_SQR2_SQ9_0 (0x01UL << ADC_SQR2_SQ9_Pos) /*!< 0x01000000 */ -#define ADC_SQR2_SQ9_1 (0x02UL << ADC_SQR2_SQ9_Pos) /*!< 0x02000000 */ -#define ADC_SQR2_SQ9_2 (0x04UL << ADC_SQR2_SQ9_Pos) /*!< 0x04000000 */ -#define ADC_SQR2_SQ9_3 (0x08UL << ADC_SQR2_SQ9_Pos) /*!< 0x08000000 */ -#define ADC_SQR2_SQ9_4 (0x10UL << ADC_SQR2_SQ9_Pos) /*!< 0x10000000 */ - -/******************** Bit definition for ADC_SQR3 register ********************/ -#define ADC_SQR3_SQ10_Pos (0U) -#define ADC_SQR3_SQ10_Msk (0x1FUL << ADC_SQR3_SQ10_Pos) /*!< 0x0000001F */ -#define ADC_SQR3_SQ10 ADC_SQR3_SQ10_Msk /*!< ADC 10th conversion in regular sequence */ -#define ADC_SQR3_SQ10_0 (0x01UL << ADC_SQR3_SQ10_Pos) /*!< 0x00000001 */ -#define ADC_SQR3_SQ10_1 (0x02UL << ADC_SQR3_SQ10_Pos) /*!< 0x00000002 */ -#define ADC_SQR3_SQ10_2 (0x04UL << ADC_SQR3_SQ10_Pos) /*!< 0x00000004 */ -#define ADC_SQR3_SQ10_3 (0x08UL << ADC_SQR3_SQ10_Pos) /*!< 0x00000008 */ -#define ADC_SQR3_SQ10_4 (0x10UL << ADC_SQR3_SQ10_Pos) /*!< 0x00000010 */ - -#define ADC_SQR3_SQ11_Pos (6U) -#define ADC_SQR3_SQ11_Msk (0x1FUL << ADC_SQR3_SQ11_Pos) /*!< 0x000007C0 */ -#define ADC_SQR3_SQ11 ADC_SQR3_SQ11_Msk /*!< ADC 11th conversion in regular sequence */ -#define ADC_SQR3_SQ11_0 (0x01UL << ADC_SQR3_SQ11_Pos) /*!< 0x00000040 */ -#define ADC_SQR3_SQ11_1 (0x02UL << ADC_SQR3_SQ11_Pos) /*!< 0x00000080 */ -#define ADC_SQR3_SQ11_2 (0x04UL << ADC_SQR3_SQ11_Pos) /*!< 0x00000100 */ -#define ADC_SQR3_SQ11_3 (0x08UL << ADC_SQR3_SQ11_Pos) /*!< 0x00000200 */ -#define ADC_SQR3_SQ11_4 (0x10UL << ADC_SQR3_SQ11_Pos) /*!< 0x00000400 */ - -#define ADC_SQR3_SQ12_Pos (12U) -#define ADC_SQR3_SQ12_Msk (0x1FUL << ADC_SQR3_SQ12_Pos) /*!< 0x0001F000 */ -#define ADC_SQR3_SQ12 ADC_SQR3_SQ12_Msk /*!< ADC 12th conversion in regular sequence */ -#define ADC_SQR3_SQ12_0 (0x01UL << ADC_SQR3_SQ12_Pos) /*!< 0x00001000 */ -#define ADC_SQR3_SQ12_1 (0x02UL << ADC_SQR3_SQ12_Pos) /*!< 0x00002000 */ -#define ADC_SQR3_SQ12_2 (0x04UL << ADC_SQR3_SQ12_Pos) /*!< 0x00004000 */ -#define ADC_SQR3_SQ12_3 (0x08UL << ADC_SQR3_SQ12_Pos) /*!< 0x00008000 */ -#define ADC_SQR3_SQ12_4 (0x10UL << ADC_SQR3_SQ12_Pos) /*!< 0x00010000 */ - -#define ADC_SQR3_SQ13_Pos (18U) -#define ADC_SQR3_SQ13_Msk (0x1FUL << ADC_SQR3_SQ13_Pos) /*!< 0x007C0000 */ -#define ADC_SQR3_SQ13 ADC_SQR3_SQ13_Msk /*!< ADC 13th conversion in regular sequence */ -#define ADC_SQR3_SQ13_0 (0x01UL << ADC_SQR3_SQ13_Pos) /*!< 0x00040000 */ -#define ADC_SQR3_SQ13_1 (0x02UL << ADC_SQR3_SQ13_Pos) /*!< 0x00080000 */ -#define ADC_SQR3_SQ13_2 (0x04UL << ADC_SQR3_SQ13_Pos) /*!< 0x00100000 */ -#define ADC_SQR3_SQ13_3 (0x08UL << ADC_SQR3_SQ13_Pos) /*!< 0x00200000 */ -#define ADC_SQR3_SQ13_4 (0x10UL << ADC_SQR3_SQ13_Pos) /*!< 0x00400000 */ - -#define ADC_SQR3_SQ14_Pos (24U) -#define ADC_SQR3_SQ14_Msk (0x1FUL << ADC_SQR3_SQ14_Pos) /*!< 0x1F000000 */ -#define ADC_SQR3_SQ14 ADC_SQR3_SQ14_Msk /*!< ADC 14th conversion in regular sequence */ -#define ADC_SQR3_SQ14_0 (0x01UL << ADC_SQR3_SQ14_Pos) /*!< 0x01000000 */ -#define ADC_SQR3_SQ14_1 (0x02UL << ADC_SQR3_SQ14_Pos) /*!< 0x02000000 */ -#define ADC_SQR3_SQ14_2 (0x04UL << ADC_SQR3_SQ14_Pos) /*!< 0x04000000 */ -#define ADC_SQR3_SQ14_3 (0x08UL << ADC_SQR3_SQ14_Pos) /*!< 0x08000000 */ -#define ADC_SQR3_SQ14_4 (0x10UL << ADC_SQR3_SQ14_Pos) /*!< 0x10000000 */ - -/******************** Bit definition for ADC_SQR4 register ********************/ -#define ADC_SQR4_SQ15_Pos (0U) -#define ADC_SQR4_SQ15_Msk (0x1FUL << ADC_SQR4_SQ15_Pos) /*!< 0x0000001F */ -#define ADC_SQR4_SQ15 ADC_SQR4_SQ15_Msk /*!< ADC 15th conversion in regular sequence */ -#define ADC_SQR4_SQ15_0 (0x01UL << ADC_SQR4_SQ15_Pos) /*!< 0x00000001 */ -#define ADC_SQR4_SQ15_1 (0x02UL << ADC_SQR4_SQ15_Pos) /*!< 0x00000002 */ -#define ADC_SQR4_SQ15_2 (0x04UL << ADC_SQR4_SQ15_Pos) /*!< 0x00000004 */ -#define ADC_SQR4_SQ15_3 (0x08UL << ADC_SQR4_SQ15_Pos) /*!< 0x00000008 */ -#define ADC_SQR4_SQ15_4 (0x10UL << ADC_SQR4_SQ15_Pos) /*!< 0x00000010 */ - -#define ADC_SQR4_SQ16_Pos (6U) -#define ADC_SQR4_SQ16_Msk (0x1FUL << ADC_SQR4_SQ16_Pos) /*!< 0x000007C0 */ -#define ADC_SQR4_SQ16 ADC_SQR4_SQ16_Msk /*!< ADC 16th conversion in regular sequence */ -#define ADC_SQR4_SQ16_0 (0x01UL << ADC_SQR4_SQ16_Pos) /*!< 0x00000040 */ -#define ADC_SQR4_SQ16_1 (0x02UL << ADC_SQR4_SQ16_Pos) /*!< 0x00000080 */ -#define ADC_SQR4_SQ16_2 (0x04UL << ADC_SQR4_SQ16_Pos) /*!< 0x00000100 */ -#define ADC_SQR4_SQ16_3 (0x08UL << ADC_SQR4_SQ16_Pos) /*!< 0x00000200 */ -#define ADC_SQR4_SQ16_4 (0x10UL << ADC_SQR4_SQ16_Pos) /*!< 0x00000400 */ -/******************** Bit definition for ADC_DR register ********************/ -#define ADC_DR_RDATA_Pos (0U) -#define ADC_DR_RDATA_Msk (0xFFFFFFFFUL << ADC_DR_RDATA_Pos) /*!< 0xFFFFFFFF */ -#define ADC_DR_RDATA ADC_DR_RDATA_Msk /*!< ADC regular Data converted */ - -/******************** Bit definition for ADC_JSQR register ********************/ -#define ADC_JSQR_JL_Pos (0U) -#define ADC_JSQR_JL_Msk (0x3UL << ADC_JSQR_JL_Pos) /*!< 0x00000003 */ -#define ADC_JSQR_JL ADC_JSQR_JL_Msk /*!< ADC injected channel sequence length */ -#define ADC_JSQR_JL_0 (0x1UL << ADC_JSQR_JL_Pos) /*!< 0x00000001 */ -#define ADC_JSQR_JL_1 (0x2UL << ADC_JSQR_JL_Pos) /*!< 0x00000002 */ - -#define ADC_JSQR_JEXTSEL_Pos (2U) -#define ADC_JSQR_JEXTSEL_Msk (0x1FUL << ADC_JSQR_JEXTSEL_Pos) /*!< 0x0000007C */ -#define ADC_JSQR_JEXTSEL ADC_JSQR_JEXTSEL_Msk /*!< ADC external trigger selection for injected group */ -#define ADC_JSQR_JEXTSEL_0 (0x01UL << ADC_JSQR_JEXTSEL_Pos) /*!< 0x00000004 */ -#define ADC_JSQR_JEXTSEL_1 (0x02UL << ADC_JSQR_JEXTSEL_Pos) /*!< 0x00000008 */ -#define ADC_JSQR_JEXTSEL_2 (0x04UL << ADC_JSQR_JEXTSEL_Pos) /*!< 0x00000010 */ -#define ADC_JSQR_JEXTSEL_3 (0x08UL << ADC_JSQR_JEXTSEL_Pos) /*!< 0x00000020 */ -#define ADC_JSQR_JEXTSEL_4 (0x10UL << ADC_JSQR_JEXTSEL_Pos) /*!< 0x00000040 */ - -#define ADC_JSQR_JEXTEN_Pos (7U) -#define ADC_JSQR_JEXTEN_Msk (0x3UL << ADC_JSQR_JEXTEN_Pos) /*!< 0x00000180 */ -#define ADC_JSQR_JEXTEN ADC_JSQR_JEXTEN_Msk /*!< ADC external trigger enable and polarity selection for injected channels */ -#define ADC_JSQR_JEXTEN_0 (0x1UL << ADC_JSQR_JEXTEN_Pos) /*!< 0x00000080 */ -#define ADC_JSQR_JEXTEN_1 (0x2UL << ADC_JSQR_JEXTEN_Pos) /*!< 0x00000100 */ - -#define ADC_JSQR_JSQ1_Pos (9U) -#define ADC_JSQR_JSQ1_Msk (0x1FUL << ADC_JSQR_JSQ1_Pos) /*!< 0x00003E00 */ -#define ADC_JSQR_JSQ1 ADC_JSQR_JSQ1_Msk /*!< ADC 1st conversion in injected sequence */ -#define ADC_JSQR_JSQ1_0 (0x01UL << ADC_JSQR_JSQ1_Pos) /*!< 0x00000200 */ -#define ADC_JSQR_JSQ1_1 (0x02UL << ADC_JSQR_JSQ1_Pos) /*!< 0x00000400 */ -#define ADC_JSQR_JSQ1_2 (0x04UL << ADC_JSQR_JSQ1_Pos) /*!< 0x00000800 */ -#define ADC_JSQR_JSQ1_3 (0x08UL << ADC_JSQR_JSQ1_Pos) /*!< 0x00001000 */ -#define ADC_JSQR_JSQ1_4 (0x10UL << ADC_JSQR_JSQ1_Pos) /*!< 0x00002000 */ - -#define ADC_JSQR_JSQ2_Pos (15U) -#define ADC_JSQR_JSQ2_Msk (0x1FUL << ADC_JSQR_JSQ2_Pos) /*!< 0x000F8000 */ -#define ADC_JSQR_JSQ2 ADC_JSQR_JSQ2_Msk /*!< ADC 2nd conversion in injected sequence */ -#define ADC_JSQR_JSQ2_0 (0x01UL << ADC_JSQR_JSQ2_Pos) /*!< 0x00008000 */ -#define ADC_JSQR_JSQ2_1 (0x02UL << ADC_JSQR_JSQ2_Pos) /*!< 0x00010000 */ -#define ADC_JSQR_JSQ2_2 (0x04UL << ADC_JSQR_JSQ2_Pos) /*!< 0x00020000 */ -#define ADC_JSQR_JSQ2_3 (0x08UL << ADC_JSQR_JSQ2_Pos) /*!< 0x00040000 */ -#define ADC_JSQR_JSQ2_4 (0x10UL << ADC_JSQR_JSQ2_Pos) /*!< 0x00080000 */ - -#define ADC_JSQR_JSQ3_Pos (21U) -#define ADC_JSQR_JSQ3_Msk (0x1FUL << ADC_JSQR_JSQ3_Pos) /*!< 0x03E00000 */ -#define ADC_JSQR_JSQ3 ADC_JSQR_JSQ3_Msk /*!< ADC 3rd conversion in injected sequence */ -#define ADC_JSQR_JSQ3_0 (0x01UL << ADC_JSQR_JSQ3_Pos) /*!< 0x00200000 */ -#define ADC_JSQR_JSQ3_1 (0x02UL << ADC_JSQR_JSQ3_Pos) /*!< 0x00400000 */ -#define ADC_JSQR_JSQ3_2 (0x04UL << ADC_JSQR_JSQ3_Pos) /*!< 0x00800000 */ -#define ADC_JSQR_JSQ3_3 (0x08UL << ADC_JSQR_JSQ3_Pos) /*!< 0x01000000 */ -#define ADC_JSQR_JSQ3_4 (0x10UL << ADC_JSQR_JSQ3_Pos) /*!< 0x02000000 */ - -#define ADC_JSQR_JSQ4_Pos (27U) -#define ADC_JSQR_JSQ4_Msk (0x1FUL << ADC_JSQR_JSQ4_Pos) /*!< 0xF8000000 */ -#define ADC_JSQR_JSQ4 ADC_JSQR_JSQ4_Msk /*!< ADC 4th conversion in injected sequence */ -#define ADC_JSQR_JSQ4_0 (0x01UL << ADC_JSQR_JSQ4_Pos) /*!< 0x08000000 */ -#define ADC_JSQR_JSQ4_1 (0x02UL << ADC_JSQR_JSQ4_Pos) /*!< 0x10000000 */ -#define ADC_JSQR_JSQ4_2 (0x04UL << ADC_JSQR_JSQ4_Pos) /*!< 0x20000000 */ -#define ADC_JSQR_JSQ4_3 (0x08UL << ADC_JSQR_JSQ4_Pos) /*!< 0x40000000 */ -#define ADC_JSQR_JSQ4_4 (0x10UL << ADC_JSQR_JSQ4_Pos) /*!< 0x80000000 */ - -/******************** Bit definition for ADC_OFR1 register ********************/ -#define ADC_OFR1_OFFSET1_Pos (0U) -#define ADC_OFR1_OFFSET1_Msk (0x3FFFFFFUL << ADC_OFR1_OFFSET1_Pos) /*!< 0x03FFFFFF */ -#define ADC_OFR1_OFFSET1 ADC_OFR1_OFFSET1_Msk /*!< ADC data offset 1 for channel programmed into bits OFFSET1_CH[4:0] */ -#define ADC_OFR1_OFFSET1_0 (0x0000001UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000001 */ -#define ADC_OFR1_OFFSET1_1 (0x0000002UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000002 */ -#define ADC_OFR1_OFFSET1_2 (0x0000004UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000004 */ -#define ADC_OFR1_OFFSET1_3 (0x0000008UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000008 */ -#define ADC_OFR1_OFFSET1_4 (0x0000010UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000010 */ -#define ADC_OFR1_OFFSET1_5 (0x0000020UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000020 */ -#define ADC_OFR1_OFFSET1_6 (0x0000040UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000040 */ -#define ADC_OFR1_OFFSET1_7 (0x0000080UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000080 */ -#define ADC_OFR1_OFFSET1_8 (0x0000100UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000100 */ -#define ADC_OFR1_OFFSET1_9 (0x0000200UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000200 */ -#define ADC_OFR1_OFFSET1_10 (0x0000400UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000400 */ -#define ADC_OFR1_OFFSET1_11 (0x0000800UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00000800 */ -#define ADC_OFR1_OFFSET1_12 (0x0001000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00001000 */ -#define ADC_OFR1_OFFSET1_13 (0x0002000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00002000 */ -#define ADC_OFR1_OFFSET1_14 (0x0004000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00004000 */ -#define ADC_OFR1_OFFSET1_15 (0x0008000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00008000 */ -#define ADC_OFR1_OFFSET1_16 (0x0010000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00010000 */ -#define ADC_OFR1_OFFSET1_17 (0x0020000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00020000 */ -#define ADC_OFR1_OFFSET1_18 (0x0040000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00040000 */ -#define ADC_OFR1_OFFSET1_19 (0x0080000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00080000 */ -#define ADC_OFR1_OFFSET1_20 (0x0100000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00100000 */ -#define ADC_OFR1_OFFSET1_21 (0x0200000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00200000 */ -#define ADC_OFR1_OFFSET1_22 (0x0400000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00400000 */ -#define ADC_OFR1_OFFSET1_23 (0x0800000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x00800000 */ -#define ADC_OFR1_OFFSET1_24 (0x1000000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x01000000 */ -#define ADC_OFR1_OFFSET1_25 (0x2000000UL << ADC_OFR1_OFFSET1_Pos) /*!< 0x02000000 */ - -#define ADC_OFR1_OFFSET1_CH_Pos (26U) -#define ADC_OFR1_OFFSET1_CH_Msk (0x1FUL << ADC_OFR1_OFFSET1_CH_Pos) /*!< 0x7C000000 */ -#define ADC_OFR1_OFFSET1_CH ADC_OFR1_OFFSET1_CH_Msk /*!< ADC Channel selection for the data offset 1 */ -#define ADC_OFR1_OFFSET1_CH_0 (0x01UL << ADC_OFR1_OFFSET1_CH_Pos) /*!< 0x04000000 */ -#define ADC_OFR1_OFFSET1_CH_1 (0x02UL << ADC_OFR1_OFFSET1_CH_Pos) /*!< 0x08000000 */ -#define ADC_OFR1_OFFSET1_CH_2 (0x04UL << ADC_OFR1_OFFSET1_CH_Pos) /*!< 0x10000000 */ -#define ADC_OFR1_OFFSET1_CH_3 (0x08UL << ADC_OFR1_OFFSET1_CH_Pos) /*!< 0x20000000 */ -#define ADC_OFR1_OFFSET1_CH_4 (0x10UL << ADC_OFR1_OFFSET1_CH_Pos) /*!< 0x40000000 */ - -#define ADC_OFR1_SSATE_Pos (31U) -#define ADC_OFR1_SSATE_Msk (0x1UL << ADC_OFR1_SSATE_Pos) /*!< 0x80000000 */ -#define ADC_OFR1_SSATE ADC_OFR1_SSATE_Msk /*!< ADC Signed saturation Enable */ - -#define ADC3_OFR1_OFFSET1_Pos (0U) -#define ADC3_OFR1_OFFSET1_Msk (0xFFFUL << ADC3_OFR1_OFFSET1_Pos) /*!< 0x00000FFF */ -#define ADC3_OFR1_OFFSET1 ADC3_OFR1_OFFSET1_Msk /*!< ADC data offset 1 for channel programmed into bits OFFSET1_CH[4:0] */ - -#define ADC3_OFR1_OFFSETPOS_Pos (24U) -#define ADC3_OFR1_OFFSETPOS_Msk (0x1UL << ADC3_OFR1_OFFSETPOS_Pos) /*!< 0x01000000 */ -#define ADC3_OFR1_OFFSETPOS ADC3_OFR1_OFFSETPOS_Msk /*!< ADC offset number 1 positive */ -#define ADC3_OFR1_SATEN_Pos (25U) -#define ADC3_OFR1_SATEN_Msk (0x1UL << ADC3_OFR1_SATEN_Pos) /*!< 0x02000000 */ -#define ADC3_OFR1_SATEN ADC3_OFR1_SATEN_Msk /*!< ADC offset number 1 saturation enable */ - -#define ADC3_OFR1_OFFSET1_EN_Pos (31U) -#define ADC3_OFR1_OFFSET1_EN_Msk (0x1UL << ADC3_OFR1_OFFSET1_EN_Pos) /*!< 0x80000000 */ -#define ADC3_OFR1_OFFSET1_EN ADC3_OFR1_OFFSET1_EN_Msk /*!< ADC offset number 1 enable */ - -/******************** Bit definition for ADC_OFR2 register ********************/ -#define ADC_OFR2_OFFSET2_Pos (0U) -#define ADC_OFR2_OFFSET2_Msk (0x3FFFFFFUL << ADC_OFR2_OFFSET2_Pos) /*!< 0x03FFFFFF */ -#define ADC_OFR2_OFFSET2 ADC_OFR2_OFFSET2_Msk /*!< ADC data offset 2 for channel programmed into bits OFFSET2_CH[4:0] */ -#define ADC_OFR2_OFFSET2_0 (0x0000001UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000001 */ -#define ADC_OFR2_OFFSET2_1 (0x0000002UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000002 */ -#define ADC_OFR2_OFFSET2_2 (0x0000004UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000004 */ -#define ADC_OFR2_OFFSET2_3 (0x0000008UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000008 */ -#define ADC_OFR2_OFFSET2_4 (0x0000010UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000010 */ -#define ADC_OFR2_OFFSET2_5 (0x0000020UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000020 */ -#define ADC_OFR2_OFFSET2_6 (0x0000040UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000040 */ -#define ADC_OFR2_OFFSET2_7 (0x0000080UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000080 */ -#define ADC_OFR2_OFFSET2_8 (0x0000100UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000100 */ -#define ADC_OFR2_OFFSET2_9 (0x0000200UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000200 */ -#define ADC_OFR2_OFFSET2_10 (0x0000400UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000400 */ -#define ADC_OFR2_OFFSET2_11 (0x0000800UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00000800 */ -#define ADC_OFR2_OFFSET2_12 (0x0001000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00001000 */ -#define ADC_OFR2_OFFSET2_13 (0x0002000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00002000 */ -#define ADC_OFR2_OFFSET2_14 (0x0004000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00004000 */ -#define ADC_OFR2_OFFSET2_15 (0x0008000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00008000 */ -#define ADC_OFR2_OFFSET2_16 (0x0010000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00010000 */ -#define ADC_OFR2_OFFSET2_17 (0x0020000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00020000 */ -#define ADC_OFR2_OFFSET2_18 (0x0040000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00040000 */ -#define ADC_OFR2_OFFSET2_19 (0x0080000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00080000 */ -#define ADC_OFR2_OFFSET2_20 (0x0100000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00100000 */ -#define ADC_OFR2_OFFSET2_21 (0x0200000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00200000 */ -#define ADC_OFR2_OFFSET2_22 (0x0400000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00400000 */ -#define ADC_OFR2_OFFSET2_23 (0x0800000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x00800000 */ -#define ADC_OFR2_OFFSET2_24 (0x1000000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x01000000 */ -#define ADC_OFR2_OFFSET2_25 (0x2000000UL << ADC_OFR2_OFFSET2_Pos) /*!< 0x02000000 */ - -#define ADC_OFR2_OFFSET2_CH_Pos (26U) -#define ADC_OFR2_OFFSET2_CH_Msk (0x1FUL << ADC_OFR2_OFFSET2_CH_Pos) /*!< 0x7C000000 */ -#define ADC_OFR2_OFFSET2_CH ADC_OFR2_OFFSET2_CH_Msk /*!< ADC Channel selection for the data offset 2 */ -#define ADC_OFR2_OFFSET2_CH_0 (0x01UL << ADC_OFR2_OFFSET2_CH_Pos) /*!< 0x04000000 */ -#define ADC_OFR2_OFFSET2_CH_1 (0x02UL << ADC_OFR2_OFFSET2_CH_Pos) /*!< 0x08000000 */ -#define ADC_OFR2_OFFSET2_CH_2 (0x04UL << ADC_OFR2_OFFSET2_CH_Pos) /*!< 0x10000000 */ -#define ADC_OFR2_OFFSET2_CH_3 (0x08UL << ADC_OFR2_OFFSET2_CH_Pos) /*!< 0x20000000 */ -#define ADC_OFR2_OFFSET2_CH_4 (0x10UL << ADC_OFR2_OFFSET2_CH_Pos) /*!< 0x40000000 */ - -#define ADC_OFR2_SSATE_Pos (31U) -#define ADC_OFR2_SSATE_Msk (0x1UL << ADC_OFR2_SSATE_Pos) /*!< 0x80000000 */ -#define ADC_OFR2_SSATE ADC_OFR2_SSATE_Msk /*!< ADC Signed saturation Enable */ - -#define ADC3_OFR2_OFFSET2_Pos (0U) -#define ADC3_OFR2_OFFSET2_Msk (0xFFFUL << ADC3_OFR2_OFFSET2_Pos) /*!< 0x00000FFF */ -#define ADC3_OFR2_OFFSET2 ADC3_OFR2_OFFSET2_Msk /*!< ADC data offset 2 for channel programmed into bits OFFSET1_CH[4:0] */ - -#define ADC3_OFR2_OFFSETPOS_Pos (24U) -#define ADC3_OFR2_OFFSETPOS_Msk (0x1UL << ADC3_OFR2_OFFSETPOS_Pos) /*!< 0x01000000 */ -#define ADC3_OFR2_OFFSETPOS ADC3_OFR2_OFFSETPOS_Msk /*!< ADC offset number 2 positive */ -#define ADC3_OFR2_SATEN_Pos (25U) -#define ADC3_OFR2_SATEN_Msk (0x1UL << ADC3_OFR2_SATEN_Pos) /*!< 0x02000000 */ -#define ADC3_OFR2_SATEN ADC3_OFR2_SATEN_Msk /*!< ADC offset number 2 saturation enable */ - -#define ADC3_OFR2_OFFSET2_EN_Pos (31U) -#define ADC3_OFR2_OFFSET2_EN_Msk (0x1UL << ADC3_OFR2_OFFSET2_EN_Pos) /*!< 0x80000000 */ -#define ADC3_OFR2_OFFSET2_EN ADC3_OFR2_OFFSET2_EN_Msk /*!< ADC offset number 2 enable */ - -/******************** Bit definition for ADC_OFR3 register ********************/ -#define ADC_OFR3_OFFSET3_Pos (0U) -#define ADC_OFR3_OFFSET3_Msk (0x3FFFFFFUL << ADC_OFR3_OFFSET3_Pos) /*!< 0x03FFFFFF */ -#define ADC_OFR3_OFFSET3 ADC_OFR3_OFFSET3_Msk /*!< ADC data offset 3 for channel programmed into bits OFFSET3_CH[4:0] */ -#define ADC_OFR3_OFFSET3_0 (0x0000001UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000001 */ -#define ADC_OFR3_OFFSET3_1 (0x0000002UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000002 */ -#define ADC_OFR3_OFFSET3_2 (0x0000004UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000004 */ -#define ADC_OFR3_OFFSET3_3 (0x0000008UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000008 */ -#define ADC_OFR3_OFFSET3_4 (0x0000010UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000010 */ -#define ADC_OFR3_OFFSET3_5 (0x0000020UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000020 */ -#define ADC_OFR3_OFFSET3_6 (0x0000040UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000040 */ -#define ADC_OFR3_OFFSET3_7 (0x0000080UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000080 */ -#define ADC_OFR3_OFFSET3_8 (0x0000100UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000100 */ -#define ADC_OFR3_OFFSET3_9 (0x0000200UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000200 */ -#define ADC_OFR3_OFFSET3_10 (0x0000400UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000400 */ -#define ADC_OFR3_OFFSET3_11 (0x0000800UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00000800 */ -#define ADC_OFR3_OFFSET3_12 (0x0001000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00001000 */ -#define ADC_OFR3_OFFSET3_13 (0x0002000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00002000 */ -#define ADC_OFR3_OFFSET3_14 (0x0004000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00004000 */ -#define ADC_OFR3_OFFSET3_15 (0x0008000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00008000 */ -#define ADC_OFR3_OFFSET3_16 (0x0010000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00010000 */ -#define ADC_OFR3_OFFSET3_17 (0x0020000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00020000 */ -#define ADC_OFR3_OFFSET3_18 (0x0040000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00040000 */ -#define ADC_OFR3_OFFSET3_19 (0x0080000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00080000 */ -#define ADC_OFR3_OFFSET3_20 (0x0100000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00100000 */ -#define ADC_OFR3_OFFSET3_21 (0x0200000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00200000 */ -#define ADC_OFR3_OFFSET3_22 (0x0400000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00400000 */ -#define ADC_OFR3_OFFSET3_23 (0x0800000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x00800000 */ -#define ADC_OFR3_OFFSET3_24 (0x1000000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x01000000 */ -#define ADC_OFR3_OFFSET3_25 (0x2000000UL << ADC_OFR3_OFFSET3_Pos) /*!< 0x02000000 */ - -#define ADC_OFR3_OFFSET3_CH_Pos (26U) -#define ADC_OFR3_OFFSET3_CH_Msk (0x1FUL << ADC_OFR3_OFFSET3_CH_Pos) /*!< 0x7C000000 */ -#define ADC_OFR3_OFFSET3_CH ADC_OFR3_OFFSET3_CH_Msk /*!< ADC Channel selection for the data offset 3 */ -#define ADC_OFR3_OFFSET3_CH_0 (0x01UL << ADC_OFR3_OFFSET3_CH_Pos) /*!< 0x04000000 */ -#define ADC_OFR3_OFFSET3_CH_1 (0x02UL << ADC_OFR3_OFFSET3_CH_Pos) /*!< 0x08000000 */ -#define ADC_OFR3_OFFSET3_CH_2 (0x04UL << ADC_OFR3_OFFSET3_CH_Pos) /*!< 0x10000000 */ -#define ADC_OFR3_OFFSET3_CH_3 (0x08UL << ADC_OFR3_OFFSET3_CH_Pos) /*!< 0x20000000 */ -#define ADC_OFR3_OFFSET3_CH_4 (0x10UL << ADC_OFR3_OFFSET3_CH_Pos) /*!< 0x40000000 */ - -#define ADC_OFR3_SSATE_Pos (31U) -#define ADC_OFR3_SSATE_Msk (0x1UL << ADC_OFR3_SSATE_Pos) /*!< 0x80000000 */ -#define ADC_OFR3_SSATE ADC_OFR3_SSATE_Msk /*!< ADC Signed saturation Enable */ - -#define ADC3_OFR3_OFFSET3_Pos (0U) -#define ADC3_OFR3_OFFSET3_Msk (0xFFFUL << ADC3_OFR3_OFFSET3_Pos) /*!< 0x00000FFF */ -#define ADC3_OFR3_OFFSET3 ADC3_OFR3_OFFSET3_Msk /*!< ADC data offset 3 for channel programmed into bits OFFSET1_CH[4:0] */ - -#define ADC3_OFR3_OFFSETPOS_Pos (24U) -#define ADC3_OFR3_OFFSETPOS_Msk (0x1UL << ADC3_OFR3_OFFSETPOS_Pos) /*!< 0x01000000 */ -#define ADC3_OFR3_OFFSETPOS ADC3_OFR3_OFFSETPOS_Msk /*!< ADC offset number 3 positive */ -#define ADC3_OFR3_SATEN_Pos (25U) -#define ADC3_OFR3_SATEN_Msk (0x1UL << ADC3_OFR3_SATEN_Pos) /*!< 0x02000000 */ -#define ADC3_OFR3_SATEN ADC3_OFR3_SATEN_Msk /*!< ADC offset number 3 saturation enable */ - -#define ADC3_OFR3_OFFSET3_EN_Pos (31U) -#define ADC3_OFR3_OFFSET3_EN_Msk (0x1UL << ADC3_OFR3_OFFSET3_EN_Pos) /*!< 0x80000000 */ -#define ADC3_OFR3_OFFSET3_EN ADC3_OFR3_OFFSET3_EN_Msk /*!< ADC offset number 3 enable */ - -/******************** Bit definition for ADC_OFR4 register ********************/ -#define ADC_OFR4_OFFSET4_Pos (0U) -#define ADC_OFR4_OFFSET4_Msk (0x3FFFFFFUL << ADC_OFR4_OFFSET4_Pos) /*!< 0x03FFFFFF */ -#define ADC_OFR4_OFFSET4 ADC_OFR4_OFFSET4_Msk /*!< ADC data offset 4 for channel programmed into bits OFFSET4_CH[4:0] */ -#define ADC_OFR4_OFFSET4_0 (0x0000001UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000001 */ -#define ADC_OFR4_OFFSET4_1 (0x0000002UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000002 */ -#define ADC_OFR4_OFFSET4_2 (0x0000004UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000004 */ -#define ADC_OFR4_OFFSET4_3 (0x0000008UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000008 */ -#define ADC_OFR4_OFFSET4_4 (0x0000010UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000010 */ -#define ADC_OFR4_OFFSET4_5 (0x0000020UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000020 */ -#define ADC_OFR4_OFFSET4_6 (0x0000040UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000040 */ -#define ADC_OFR4_OFFSET4_7 (0x0000080UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000080 */ -#define ADC_OFR4_OFFSET4_8 (0x0000100UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000100 */ -#define ADC_OFR4_OFFSET4_9 (0x0000200UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000200 */ -#define ADC_OFR4_OFFSET4_10 (0x0000400UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000400 */ -#define ADC_OFR4_OFFSET4_11 (0x0000800UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00000800 */ -#define ADC_OFR4_OFFSET4_12 (0x0001000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00001000 */ -#define ADC_OFR4_OFFSET4_13 (0x0002000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00002000 */ -#define ADC_OFR4_OFFSET4_14 (0x0004000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00004000 */ -#define ADC_OFR4_OFFSET4_15 (0x0008000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00008000 */ -#define ADC_OFR4_OFFSET4_16 (0x0010000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00010000 */ -#define ADC_OFR4_OFFSET4_17 (0x0020000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00020000 */ -#define ADC_OFR4_OFFSET4_18 (0x0040000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00040000 */ -#define ADC_OFR4_OFFSET4_19 (0x0080000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00080000 */ -#define ADC_OFR4_OFFSET4_20 (0x0100000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00100000 */ -#define ADC_OFR4_OFFSET4_21 (0x0200000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00200000 */ -#define ADC_OFR4_OFFSET4_22 (0x0400000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00400000 */ -#define ADC_OFR4_OFFSET4_23 (0x0800000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x00800000 */ -#define ADC_OFR4_OFFSET4_24 (0x1000000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x01000000 */ -#define ADC_OFR4_OFFSET4_25 (0x2000000UL << ADC_OFR4_OFFSET4_Pos) /*!< 0x02000000 */ - -#define ADC_OFR4_OFFSET4_CH_Pos (26U) -#define ADC_OFR4_OFFSET4_CH_Msk (0x1FUL << ADC_OFR4_OFFSET4_CH_Pos) /*!< 0x7C000000 */ -#define ADC_OFR4_OFFSET4_CH ADC_OFR4_OFFSET4_CH_Msk /*!< ADC Channel selection for the data offset 4 */ -#define ADC_OFR4_OFFSET4_CH_0 (0x01UL << ADC_OFR4_OFFSET4_CH_Pos) /*!< 0x04000000 */ -#define ADC_OFR4_OFFSET4_CH_1 (0x02UL << ADC_OFR4_OFFSET4_CH_Pos) /*!< 0x08000000 */ -#define ADC_OFR4_OFFSET4_CH_2 (0x04UL << ADC_OFR4_OFFSET4_CH_Pos) /*!< 0x10000000 */ -#define ADC_OFR4_OFFSET4_CH_3 (0x08UL << ADC_OFR4_OFFSET4_CH_Pos) /*!< 0x20000000 */ -#define ADC_OFR4_OFFSET4_CH_4 (0x10UL << ADC_OFR4_OFFSET4_CH_Pos) /*!< 0x40000000 */ - -#define ADC_OFR4_SSATE_Pos (31U) -#define ADC_OFR4_SSATE_Msk (0x1UL << ADC_OFR4_SSATE_Pos) /*!< 0x80000000 */ -#define ADC_OFR4_SSATE ADC_OFR4_SSATE_Msk /*!< ADC Signed saturation Enable */ - -#define ADC3_OFR4_OFFSET4_Pos (0U) -#define ADC3_OFR4_OFFSET4_Msk (0xFFFUL << ADC3_OFR4_OFFSET4_Pos) /*!< 0x00000FFF */ -#define ADC3_OFR4_OFFSET4 ADC3_OFR4_OFFSET4_Msk /*!< ADC data offset 4 for channel programmed into bits OFFSET1_CH[4:0] */ - -#define ADC3_OFR4_OFFSETPOS_Pos (24U) -#define ADC3_OFR4_OFFSETPOS_Msk (0x1UL << ADC3_OFR4_OFFSETPOS_Pos) /*!< 0x01000000 */ -#define ADC3_OFR4_OFFSETPOS ADC3_OFR4_OFFSETPOS_Msk /*!< ADC offset number 4 positive */ -#define ADC3_OFR4_SATEN_Pos (25U) -#define ADC3_OFR4_SATEN_Msk (0x1UL << ADC3_OFR4_SATEN_Pos) /*!< 0x02000000 */ -#define ADC3_OFR4_SATEN ADC3_OFR4_SATEN_Msk /*!< ADC offset number 4 saturation enable */ - -#define ADC3_OFR4_OFFSET4_EN_Pos (31U) -#define ADC3_OFR4_OFFSET4_EN_Msk (0x1UL << ADC3_OFR4_OFFSET4_EN_Pos) /*!< 0x80000000 */ -#define ADC3_OFR4_OFFSET4_EN ADC3_OFR4_OFFSET4_EN_Msk /*!< ADC offset number 4 enable */ - -/******************** Bit definition for ADC_JDR1 register ********************/ -#define ADC_JDR1_JDATA_Pos (0U) -#define ADC_JDR1_JDATA_Msk (0xFFFFFFFFUL << ADC_JDR1_JDATA_Pos) /*!< 0xFFFFFFFF */ -#define ADC_JDR1_JDATA ADC_JDR1_JDATA_Msk /*!< ADC Injected DATA */ -#define ADC_JDR1_JDATA_0 (0x00000001UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000001 */ -#define ADC_JDR1_JDATA_1 (0x00000002UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000002 */ -#define ADC_JDR1_JDATA_2 (0x00000004UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000004 */ -#define ADC_JDR1_JDATA_3 (0x00000008UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000008 */ -#define ADC_JDR1_JDATA_4 (0x00000010UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000010 */ -#define ADC_JDR1_JDATA_5 (0x00000020UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000020 */ -#define ADC_JDR1_JDATA_6 (0x00000040UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000040 */ -#define ADC_JDR1_JDATA_7 (0x00000080UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000080 */ -#define ADC_JDR1_JDATA_8 (0x00000100UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000100 */ -#define ADC_JDR1_JDATA_9 (0x00000200UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000200 */ -#define ADC_JDR1_JDATA_10 (0x00000400UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000400 */ -#define ADC_JDR1_JDATA_11 (0x00000800UL << ADC_JDR1_JDATA_Pos) /*!< 0x00000800 */ -#define ADC_JDR1_JDATA_12 (0x00001000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00001000 */ -#define ADC_JDR1_JDATA_13 (0x00002000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00002000 */ -#define ADC_JDR1_JDATA_14 (0x00004000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00004000 */ -#define ADC_JDR1_JDATA_15 (0x00008000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00008000 */ -#define ADC_JDR1_JDATA_16 (0x00010000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00010000 */ -#define ADC_JDR1_JDATA_17 (0x00020000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00020000 */ -#define ADC_JDR1_JDATA_18 (0x00040000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00040000 */ -#define ADC_JDR1_JDATA_19 (0x00080000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00080000 */ -#define ADC_JDR1_JDATA_20 (0x00100000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00100000 */ -#define ADC_JDR1_JDATA_21 (0x00200000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00200000 */ -#define ADC_JDR1_JDATA_22 (0x00400000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00400000 */ -#define ADC_JDR1_JDATA_23 (0x00800000UL << ADC_JDR1_JDATA_Pos) /*!< 0x00800000 */ -#define ADC_JDR1_JDATA_24 (0x01000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x01000000 */ -#define ADC_JDR1_JDATA_25 (0x02000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x02000000 */ -#define ADC_JDR1_JDATA_26 (0x04000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x04000000 */ -#define ADC_JDR1_JDATA_27 (0x08000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x08000000 */ -#define ADC_JDR1_JDATA_28 (0x10000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x10000000 */ -#define ADC_JDR1_JDATA_29 (0x20000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x20000000 */ -#define ADC_JDR1_JDATA_30 (0x40000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x40000000 */ -#define ADC_JDR1_JDATA_31 (0x80000000UL << ADC_JDR1_JDATA_Pos) /*!< 0x80000000 */ - -/******************** Bit definition for ADC_JDR2 register ********************/ -#define ADC_JDR2_JDATA_Pos (0U) -#define ADC_JDR2_JDATA_Msk (0xFFFFFFFFUL << ADC_JDR2_JDATA_Pos) /*!< 0xFFFFFFFF */ -#define ADC_JDR2_JDATA ADC_JDR2_JDATA_Msk /*!< ADC Injected DATA */ -#define ADC_JDR2_JDATA_0 (0x00000001UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000001 */ -#define ADC_JDR2_JDATA_1 (0x00000002UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000002 */ -#define ADC_JDR2_JDATA_2 (0x00000004UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000004 */ -#define ADC_JDR2_JDATA_3 (0x00000008UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000008 */ -#define ADC_JDR2_JDATA_4 (0x00000010UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000010 */ -#define ADC_JDR2_JDATA_5 (0x00000020UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000020 */ -#define ADC_JDR2_JDATA_6 (0x00000040UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000040 */ -#define ADC_JDR2_JDATA_7 (0x00000080UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000080 */ -#define ADC_JDR2_JDATA_8 (0x00000100UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000100 */ -#define ADC_JDR2_JDATA_9 (0x00000200UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000200 */ -#define ADC_JDR2_JDATA_10 (0x00000400UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000400 */ -#define ADC_JDR2_JDATA_11 (0x00000800UL << ADC_JDR2_JDATA_Pos) /*!< 0x00000800 */ -#define ADC_JDR2_JDATA_12 (0x00001000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00001000 */ -#define ADC_JDR2_JDATA_13 (0x00002000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00002000 */ -#define ADC_JDR2_JDATA_14 (0x00004000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00004000 */ -#define ADC_JDR2_JDATA_15 (0x00008000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00008000 */ -#define ADC_JDR2_JDATA_16 (0x00010000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00010000 */ -#define ADC_JDR2_JDATA_17 (0x00020000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00020000 */ -#define ADC_JDR2_JDATA_18 (0x00040000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00040000 */ -#define ADC_JDR2_JDATA_19 (0x00080000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00080000 */ -#define ADC_JDR2_JDATA_20 (0x00100000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00100000 */ -#define ADC_JDR2_JDATA_21 (0x00200000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00200000 */ -#define ADC_JDR2_JDATA_22 (0x00400000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00400000 */ -#define ADC_JDR2_JDATA_23 (0x00800000UL << ADC_JDR2_JDATA_Pos) /*!< 0x00800000 */ -#define ADC_JDR2_JDATA_24 (0x01000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x01000000 */ -#define ADC_JDR2_JDATA_25 (0x02000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x02000000 */ -#define ADC_JDR2_JDATA_26 (0x04000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x04000000 */ -#define ADC_JDR2_JDATA_27 (0x08000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x08000000 */ -#define ADC_JDR2_JDATA_28 (0x10000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x10000000 */ -#define ADC_JDR2_JDATA_29 (0x20000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x20000000 */ -#define ADC_JDR2_JDATA_30 (0x40000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x40000000 */ -#define ADC_JDR2_JDATA_31 (0x80000000UL << ADC_JDR2_JDATA_Pos) /*!< 0x80000000 */ - -/******************** Bit definition for ADC_JDR3 register ********************/ -#define ADC_JDR3_JDATA_Pos (0U) -#define ADC_JDR3_JDATA_Msk (0xFFFFFFFFUL << ADC_JDR3_JDATA_Pos) /*!< 0xFFFFFFFF */ -#define ADC_JDR3_JDATA ADC_JDR3_JDATA_Msk /*!< ADC Injected DATA */ -#define ADC_JDR3_JDATA_0 (0x00000001UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000001 */ -#define ADC_JDR3_JDATA_1 (0x00000002UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000002 */ -#define ADC_JDR3_JDATA_2 (0x00000004UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000004 */ -#define ADC_JDR3_JDATA_3 (0x00000008UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000008 */ -#define ADC_JDR3_JDATA_4 (0x00000010UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000010 */ -#define ADC_JDR3_JDATA_5 (0x00000020UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000020 */ -#define ADC_JDR3_JDATA_6 (0x00000040UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000040 */ -#define ADC_JDR3_JDATA_7 (0x00000080UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000080 */ -#define ADC_JDR3_JDATA_8 (0x00000100UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000100 */ -#define ADC_JDR3_JDATA_9 (0x00000200UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000200 */ -#define ADC_JDR3_JDATA_10 (0x00000400UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000400 */ -#define ADC_JDR3_JDATA_11 (0x00000800UL << ADC_JDR3_JDATA_Pos) /*!< 0x00000800 */ -#define ADC_JDR3_JDATA_12 (0x00001000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00001000 */ -#define ADC_JDR3_JDATA_13 (0x00002000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00002000 */ -#define ADC_JDR3_JDATA_14 (0x00004000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00004000 */ -#define ADC_JDR3_JDATA_15 (0x00008000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00008000 */ -#define ADC_JDR3_JDATA_16 (0x00010000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00010000 */ -#define ADC_JDR3_JDATA_17 (0x00020000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00020000 */ -#define ADC_JDR3_JDATA_18 (0x00040000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00040000 */ -#define ADC_JDR3_JDATA_19 (0x00080000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00080000 */ -#define ADC_JDR3_JDATA_20 (0x00100000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00100000 */ -#define ADC_JDR3_JDATA_21 (0x00200000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00200000 */ -#define ADC_JDR3_JDATA_22 (0x00400000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00400000 */ -#define ADC_JDR3_JDATA_23 (0x00800000UL << ADC_JDR3_JDATA_Pos) /*!< 0x00800000 */ -#define ADC_JDR3_JDATA_24 (0x01000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x01000000 */ -#define ADC_JDR3_JDATA_25 (0x02000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x02000000 */ -#define ADC_JDR3_JDATA_26 (0x04000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x04000000 */ -#define ADC_JDR3_JDATA_27 (0x08000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x08000000 */ -#define ADC_JDR3_JDATA_28 (0x10000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x10000000 */ -#define ADC_JDR3_JDATA_29 (0x20000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x20000000 */ -#define ADC_JDR3_JDATA_30 (0x40000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x40000000 */ -#define ADC_JDR3_JDATA_31 (0x80000000UL << ADC_JDR3_JDATA_Pos) /*!< 0x80000000 */ - -/******************** Bit definition for ADC_JDR4 register ********************/ -#define ADC_JDR4_JDATA_Pos (0U) -#define ADC_JDR4_JDATA_Msk (0xFFFFFFFFUL << ADC_JDR4_JDATA_Pos) /*!< 0xFFFFFFFF */ -#define ADC_JDR4_JDATA ADC_JDR4_JDATA_Msk /*!< ADC Injected DATA */ -#define ADC_JDR4_JDATA_0 (0x00000001UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000001 */ -#define ADC_JDR4_JDATA_1 (0x00000002UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000002 */ -#define ADC_JDR4_JDATA_2 (0x00000004UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000004 */ -#define ADC_JDR4_JDATA_3 (0x00000008UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000008 */ -#define ADC_JDR4_JDATA_4 (0x00000010UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000010 */ -#define ADC_JDR4_JDATA_5 (0x00000020UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000020 */ -#define ADC_JDR4_JDATA_6 (0x00000040UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000040 */ -#define ADC_JDR4_JDATA_7 (0x00000080UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000080 */ -#define ADC_JDR4_JDATA_8 (0x00000100UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000100 */ -#define ADC_JDR4_JDATA_9 (0x00000200UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000200 */ -#define ADC_JDR4_JDATA_10 (0x00000400UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000400 */ -#define ADC_JDR4_JDATA_11 (0x00000800UL << ADC_JDR4_JDATA_Pos) /*!< 0x00000800 */ -#define ADC_JDR4_JDATA_12 (0x00001000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00001000 */ -#define ADC_JDR4_JDATA_13 (0x00002000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00002000 */ -#define ADC_JDR4_JDATA_14 (0x00004000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00004000 */ -#define ADC_JDR4_JDATA_15 (0x00008000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00008000 */ -#define ADC_JDR4_JDATA_16 (0x00010000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00010000 */ -#define ADC_JDR4_JDATA_17 (0x00020000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00020000 */ -#define ADC_JDR4_JDATA_18 (0x00040000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00040000 */ -#define ADC_JDR4_JDATA_19 (0x00080000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00080000 */ -#define ADC_JDR4_JDATA_20 (0x00100000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00100000 */ -#define ADC_JDR4_JDATA_21 (0x00200000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00200000 */ -#define ADC_JDR4_JDATA_22 (0x00400000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00400000 */ -#define ADC_JDR4_JDATA_23 (0x00800000UL << ADC_JDR4_JDATA_Pos) /*!< 0x00800000 */ -#define ADC_JDR4_JDATA_24 (0x01000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x01000000 */ -#define ADC_JDR4_JDATA_25 (0x02000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x02000000 */ -#define ADC_JDR4_JDATA_26 (0x04000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x04000000 */ -#define ADC_JDR4_JDATA_27 (0x08000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x08000000 */ -#define ADC_JDR4_JDATA_28 (0x10000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x10000000 */ -#define ADC_JDR4_JDATA_29 (0x20000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x20000000 */ -#define ADC_JDR4_JDATA_30 (0x40000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x40000000 */ -#define ADC_JDR4_JDATA_31 (0x80000000UL << ADC_JDR4_JDATA_Pos) /*!< 0x80000000 */ - -/******************** Bit definition for ADC_AWD2CR register ********************/ -#define ADC_AWD2CR_AWD2CH_Pos (0U) -#define ADC_AWD2CR_AWD2CH_Msk (0xFFFFFUL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x000FFFFF */ -#define ADC_AWD2CR_AWD2CH ADC_AWD2CR_AWD2CH_Msk /*!< ADC Analog watchdog 2 channel selection */ -#define ADC_AWD2CR_AWD2CH_0 (0x00001UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000001 */ -#define ADC_AWD2CR_AWD2CH_1 (0x00002UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000002 */ -#define ADC_AWD2CR_AWD2CH_2 (0x00004UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000004 */ -#define ADC_AWD2CR_AWD2CH_3 (0x00008UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000008 */ -#define ADC_AWD2CR_AWD2CH_4 (0x00010UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000010 */ -#define ADC_AWD2CR_AWD2CH_5 (0x00020UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000020 */ -#define ADC_AWD2CR_AWD2CH_6 (0x00040UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000040 */ -#define ADC_AWD2CR_AWD2CH_7 (0x00080UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000080 */ -#define ADC_AWD2CR_AWD2CH_8 (0x00100UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000100 */ -#define ADC_AWD2CR_AWD2CH_9 (0x00200UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000200 */ -#define ADC_AWD2CR_AWD2CH_10 (0x00400UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000400 */ -#define ADC_AWD2CR_AWD2CH_11 (0x00800UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00000800 */ -#define ADC_AWD2CR_AWD2CH_12 (0x01000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00001000 */ -#define ADC_AWD2CR_AWD2CH_13 (0x02000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00002000 */ -#define ADC_AWD2CR_AWD2CH_14 (0x04000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00004000 */ -#define ADC_AWD2CR_AWD2CH_15 (0x08000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00008000 */ -#define ADC_AWD2CR_AWD2CH_16 (0x10000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00010000 */ -#define ADC_AWD2CR_AWD2CH_17 (0x20000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00020000 */ -#define ADC_AWD2CR_AWD2CH_18 (0x40000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00040000 */ -#define ADC_AWD2CR_AWD2CH_19 (0x80000UL << ADC_AWD2CR_AWD2CH_Pos) /*!< 0x00080000 */ - -/******************** Bit definition for ADC_AWD3CR register ********************/ -#define ADC_AWD3CR_AWD3CH_Pos (0U) -#define ADC_AWD3CR_AWD3CH_Msk (0xFFFFFUL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x000FFFFF */ -#define ADC_AWD3CR_AWD3CH ADC_AWD3CR_AWD3CH_Msk /*!< ADC Analog watchdog 2 channel selection */ -#define ADC_AWD3CR_AWD3CH_0 (0x00001UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000001 */ -#define ADC_AWD3CR_AWD3CH_1 (0x00002UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000002 */ -#define ADC_AWD3CR_AWD3CH_2 (0x00004UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000004 */ -#define ADC_AWD3CR_AWD3CH_3 (0x00008UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000008 */ -#define ADC_AWD3CR_AWD3CH_4 (0x00010UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000010 */ -#define ADC_AWD3CR_AWD3CH_5 (0x00020UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000020 */ -#define ADC_AWD3CR_AWD3CH_6 (0x00040UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000040 */ -#define ADC_AWD3CR_AWD3CH_7 (0x00080UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000080 */ -#define ADC_AWD3CR_AWD3CH_8 (0x00100UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000100 */ -#define ADC_AWD3CR_AWD3CH_9 (0x00200UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000200 */ -#define ADC_AWD3CR_AWD3CH_10 (0x00400UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000400 */ -#define ADC_AWD3CR_AWD3CH_11 (0x00800UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00000800 */ -#define ADC_AWD3CR_AWD3CH_12 (0x01000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00001000 */ -#define ADC_AWD3CR_AWD3CH_13 (0x02000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00002000 */ -#define ADC_AWD3CR_AWD3CH_14 (0x04000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00004000 */ -#define ADC_AWD3CR_AWD3CH_15 (0x08000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00008000 */ -#define ADC_AWD3CR_AWD3CH_16 (0x10000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00010000 */ -#define ADC_AWD3CR_AWD3CH_17 (0x20000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00020000 */ -#define ADC_AWD3CR_AWD3CH_18 (0x40000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00040000 */ -#define ADC_AWD3CR_AWD3CH_19 (0x80000UL << ADC_AWD3CR_AWD3CH_Pos) /*!< 0x00080000 */ - -/******************** Bit definition for ADC_DIFSEL register ********************/ -#define ADC_DIFSEL_DIFSEL_Pos (0U) -#define ADC_DIFSEL_DIFSEL_Msk (0xFFFFFUL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x000FFFFF */ -#define ADC_DIFSEL_DIFSEL ADC_DIFSEL_DIFSEL_Msk /*!< ADC differential modes for channels 1 to 18 */ -#define ADC_DIFSEL_DIFSEL_0 (0x00001UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000001 */ -#define ADC_DIFSEL_DIFSEL_1 (0x00002UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000002 */ -#define ADC_DIFSEL_DIFSEL_2 (0x00004UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000004 */ -#define ADC_DIFSEL_DIFSEL_3 (0x00008UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000008 */ -#define ADC_DIFSEL_DIFSEL_4 (0x00010UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000010 */ -#define ADC_DIFSEL_DIFSEL_5 (0x00020UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000020 */ -#define ADC_DIFSEL_DIFSEL_6 (0x00040UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000040 */ -#define ADC_DIFSEL_DIFSEL_7 (0x00080UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000080 */ -#define ADC_DIFSEL_DIFSEL_8 (0x00100UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000100 */ -#define ADC_DIFSEL_DIFSEL_9 (0x00200UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000200 */ -#define ADC_DIFSEL_DIFSEL_10 (0x00400UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000400 */ -#define ADC_DIFSEL_DIFSEL_11 (0x00800UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00000800 */ -#define ADC_DIFSEL_DIFSEL_12 (0x01000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00001000 */ -#define ADC_DIFSEL_DIFSEL_13 (0x02000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00002000 */ -#define ADC_DIFSEL_DIFSEL_14 (0x04000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00004000 */ -#define ADC_DIFSEL_DIFSEL_15 (0x08000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00008000 */ -#define ADC_DIFSEL_DIFSEL_16 (0x10000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00010000 */ -#define ADC_DIFSEL_DIFSEL_17 (0x20000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00020000 */ -#define ADC_DIFSEL_DIFSEL_18 (0x40000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00040000 */ -#define ADC_DIFSEL_DIFSEL_19 (0x80000UL << ADC_DIFSEL_DIFSEL_Pos) /*!< 0x00080000 */ - -/******************** Bit definition for ADC_CALFACT register ********************/ -#define ADC_CALFACT_CALFACT_S_Pos (0U) -#define ADC_CALFACT_CALFACT_S_Msk (0x7FFUL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x000007FF */ -#define ADC_CALFACT_CALFACT_S ADC_CALFACT_CALFACT_S_Msk /*!< ADC calibration factors in single-ended mode */ -#define ADC_CALFACT_CALFACT_S_0 (0x001UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000001 */ -#define ADC_CALFACT_CALFACT_S_1 (0x002UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000002 */ -#define ADC_CALFACT_CALFACT_S_2 (0x004UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000004 */ -#define ADC_CALFACT_CALFACT_S_3 (0x008UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000008 */ -#define ADC_CALFACT_CALFACT_S_4 (0x010UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000010 */ -#define ADC_CALFACT_CALFACT_S_5 (0x020UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000020 */ -#define ADC_CALFACT_CALFACT_S_6 (0x040UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000040 */ -#define ADC_CALFACT_CALFACT_S_7 (0x080UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000080 */ -#define ADC_CALFACT_CALFACT_S_8 (0x100UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000100 */ -#define ADC_CALFACT_CALFACT_S_9 (0x200UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000200 */ -#define ADC_CALFACT_CALFACT_S_10 (0x400UL << ADC_CALFACT_CALFACT_S_Pos) /*!< 0x00000400 */ -#define ADC_CALFACT_CALFACT_D_Pos (16U) -#define ADC_CALFACT_CALFACT_D_Msk (0x7FFUL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x07FF0000 */ -#define ADC_CALFACT_CALFACT_D ADC_CALFACT_CALFACT_D_Msk /*!< ADC calibration factors in differential mode */ -#define ADC_CALFACT_CALFACT_D_0 (0x001UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00010000 */ -#define ADC_CALFACT_CALFACT_D_1 (0x002UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00020000 */ -#define ADC_CALFACT_CALFACT_D_2 (0x004UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00040000 */ -#define ADC_CALFACT_CALFACT_D_3 (0x008UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00080000 */ -#define ADC_CALFACT_CALFACT_D_4 (0x010UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00100000 */ -#define ADC_CALFACT_CALFACT_D_5 (0x020UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00200000 */ -#define ADC_CALFACT_CALFACT_D_6 (0x040UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00400000 */ -#define ADC_CALFACT_CALFACT_D_7 (0x080UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x00800000 */ -#define ADC_CALFACT_CALFACT_D_8 (0x100UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x01000000 */ -#define ADC_CALFACT_CALFACT_D_9 (0x200UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x02000000 */ -#define ADC_CALFACT_CALFACT_D_10 (0x400UL << ADC_CALFACT_CALFACT_D_Pos) /*!< 0x04000000 */ - -/******************** Bit definition for ADC_CALFACT2 register ********************/ -#define ADC_CALFACT2_LINCALFACT_Pos (0U) -#define ADC_CALFACT2_LINCALFACT_Msk (0x3FFFFFFFUL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x3FFFFFFF */ -#define ADC_CALFACT2_LINCALFACT ADC_CALFACT2_LINCALFACT_Msk /*!< ADC Linearity calibration factors */ -#define ADC_CALFACT2_LINCALFACT_0 (0x00000001UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000001 */ -#define ADC_CALFACT2_LINCALFACT_1 (0x00000002UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000002 */ -#define ADC_CALFACT2_LINCALFACT_2 (0x00000004UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000004 */ -#define ADC_CALFACT2_LINCALFACT_3 (0x00000008UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000008 */ -#define ADC_CALFACT2_LINCALFACT_4 (0x00000010UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000010 */ -#define ADC_CALFACT2_LINCALFACT_5 (0x00000020UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000020 */ -#define ADC_CALFACT2_LINCALFACT_6 (0x00000040UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000040 */ -#define ADC_CALFACT2_LINCALFACT_7 (0x00000080UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000080 */ -#define ADC_CALFACT2_LINCALFACT_8 (0x00000100UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000100 */ -#define ADC_CALFACT2_LINCALFACT_9 (0x00000200UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000200 */ -#define ADC_CALFACT2_LINCALFACT_10 (0x00000400UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000400 */ -#define ADC_CALFACT2_LINCALFACT_11 (0x00000800UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00000800 */ -#define ADC_CALFACT2_LINCALFACT_12 (0x00001000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00001000 */ -#define ADC_CALFACT2_LINCALFACT_13 (0x00002000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00002000 */ -#define ADC_CALFACT2_LINCALFACT_14 (0x00004000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00004000 */ -#define ADC_CALFACT2_LINCALFACT_15 (0x00008000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00008000 */ -#define ADC_CALFACT2_LINCALFACT_16 (0x00010000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00010000 */ -#define ADC_CALFACT2_LINCALFACT_17 (0x00020000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00020000 */ -#define ADC_CALFACT2_LINCALFACT_18 (0x00040000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00040000 */ -#define ADC_CALFACT2_LINCALFACT_19 (0x00080000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00080000 */ -#define ADC_CALFACT2_LINCALFACT_20 (0x00100000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00100000 */ -#define ADC_CALFACT2_LINCALFACT_21 (0x00200000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00200000 */ -#define ADC_CALFACT2_LINCALFACT_22 (0x00400000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00400000 */ -#define ADC_CALFACT2_LINCALFACT_23 (0x00800000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x00800000 */ -#define ADC_CALFACT2_LINCALFACT_24 (0x01000000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x01000000 */ -#define ADC_CALFACT2_LINCALFACT_25 (0x02000000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x02000000 */ -#define ADC_CALFACT2_LINCALFACT_26 (0x04000000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x04000000 */ -#define ADC_CALFACT2_LINCALFACT_27 (0x08000000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x08000000 */ -#define ADC_CALFACT2_LINCALFACT_28 (0x10000000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x10000000 */ -#define ADC_CALFACT2_LINCALFACT_29 (0x20000000UL << ADC_CALFACT2_LINCALFACT_Pos) /*!< 0x20000000 */ - -/************************* ADC Common registers *****************************/ -/******************** Bit definition for ADC_CSR register ********************/ -#define ADC_CSR_ADRDY_MST_Pos (0U) -#define ADC_CSR_ADRDY_MST_Msk (0x1UL << ADC_CSR_ADRDY_MST_Pos) /*!< 0x00000001 */ -#define ADC_CSR_ADRDY_MST ADC_CSR_ADRDY_MST_Msk /*!< Master ADC ready */ -#define ADC_CSR_EOSMP_MST_Pos (1U) -#define ADC_CSR_EOSMP_MST_Msk (0x1UL << ADC_CSR_EOSMP_MST_Pos) /*!< 0x00000002 */ -#define ADC_CSR_EOSMP_MST ADC_CSR_EOSMP_MST_Msk /*!< End of sampling phase flag of the master ADC */ -#define ADC_CSR_EOC_MST_Pos (2U) -#define ADC_CSR_EOC_MST_Msk (0x1UL << ADC_CSR_EOC_MST_Pos) /*!< 0x00000004 */ -#define ADC_CSR_EOC_MST ADC_CSR_EOC_MST_Msk /*!< End of regular conversion of the master ADC */ -#define ADC_CSR_EOS_MST_Pos (3U) -#define ADC_CSR_EOS_MST_Msk (0x1UL << ADC_CSR_EOS_MST_Pos) /*!< 0x00000008 */ -#define ADC_CSR_EOS_MST ADC_CSR_EOS_MST_Msk /*!< End of regular sequence flag of the master ADC */ -#define ADC_CSR_OVR_MST_Pos (4U) -#define ADC_CSR_OVR_MST_Msk (0x1UL << ADC_CSR_OVR_MST_Pos) /*!< 0x00000010 */ -#define ADC_CSR_OVR_MST ADC_CSR_OVR_MST_Msk /*!< Overrun flag of the master ADC */ -#define ADC_CSR_JEOC_MST_Pos (5U) -#define ADC_CSR_JEOC_MST_Msk (0x1UL << ADC_CSR_JEOC_MST_Pos) /*!< 0x00000020 */ -#define ADC_CSR_JEOC_MST ADC_CSR_JEOC_MST_Msk /*!< End of injected conversion of the master ADC */ -#define ADC_CSR_JEOS_MST_Pos (6U) -#define ADC_CSR_JEOS_MST_Msk (0x1UL << ADC_CSR_JEOS_MST_Pos) /*!< 0x00000040 */ -#define ADC_CSR_JEOS_MST ADC_CSR_JEOS_MST_Msk /*!< End of injected sequence flag of the master ADC */ -#define ADC_CSR_AWD1_MST_Pos (7U) -#define ADC_CSR_AWD1_MST_Msk (0x1UL << ADC_CSR_AWD1_MST_Pos) /*!< 0x00000080 */ -#define ADC_CSR_AWD1_MST ADC_CSR_AWD1_MST_Msk /*!< Analog watchdog 1 flag of the master ADC */ -#define ADC_CSR_AWD2_MST_Pos (8U) -#define ADC_CSR_AWD2_MST_Msk (0x1UL << ADC_CSR_AWD2_MST_Pos) /*!< 0x00000100 */ -#define ADC_CSR_AWD2_MST ADC_CSR_AWD2_MST_Msk /*!< Analog watchdog 2 flag of the master ADC */ -#define ADC_CSR_AWD3_MST_Pos (9U) -#define ADC_CSR_AWD3_MST_Msk (0x1UL << ADC_CSR_AWD3_MST_Pos) /*!< 0x00000200 */ -#define ADC_CSR_AWD3_MST ADC_CSR_AWD3_MST_Msk /*!< Analog watchdog 3 flag of the master ADC */ -#define ADC_CSR_JQOVF_MST_Pos (10U) -#define ADC_CSR_JQOVF_MST_Msk (0x1UL << ADC_CSR_JQOVF_MST_Pos) /*!< 0x00000400 */ -#define ADC_CSR_JQOVF_MST ADC_CSR_JQOVF_MST_Msk /*!< Injected context queue overflow flag of the master ADC */ -#define ADC_CSR_ADRDY_SLV_Pos (16U) -#define ADC_CSR_ADRDY_SLV_Msk (0x1UL << ADC_CSR_ADRDY_SLV_Pos) /*!< 0x00010000 */ -#define ADC_CSR_ADRDY_SLV ADC_CSR_ADRDY_SLV_Msk /*!< Slave ADC ready */ -#define ADC_CSR_EOSMP_SLV_Pos (17U) -#define ADC_CSR_EOSMP_SLV_Msk (0x1UL << ADC_CSR_EOSMP_SLV_Pos) /*!< 0x00020000 */ -#define ADC_CSR_EOSMP_SLV ADC_CSR_EOSMP_SLV_Msk /*!< End of sampling phase flag of the slave ADC */ -#define ADC_CSR_EOC_SLV_Pos (18U) -#define ADC_CSR_EOC_SLV_Msk (0x1UL << ADC_CSR_EOC_SLV_Pos) /*!< 0x00040000 */ -#define ADC_CSR_EOC_SLV ADC_CSR_EOC_SLV_Msk /*!< End of regular conversion of the slave ADC */ -#define ADC_CSR_EOS_SLV_Pos (19U) -#define ADC_CSR_EOS_SLV_Msk (0x1UL << ADC_CSR_EOS_SLV_Pos) /*!< 0x00080000 */ -#define ADC_CSR_EOS_SLV ADC_CSR_EOS_SLV_Msk /*!< End of regular sequence flag of the slave ADC */ -#define ADC_CSR_OVR_SLV_Pos (20U) -#define ADC_CSR_OVR_SLV_Msk (0x1UL << ADC_CSR_OVR_SLV_Pos) /*!< 0x00100000 */ -#define ADC_CSR_OVR_SLV ADC_CSR_OVR_SLV_Msk /*!< Overrun flag of the slave ADC */ -#define ADC_CSR_JEOC_SLV_Pos (21U) -#define ADC_CSR_JEOC_SLV_Msk (0x1UL << ADC_CSR_JEOC_SLV_Pos) /*!< 0x00200000 */ -#define ADC_CSR_JEOC_SLV ADC_CSR_JEOC_SLV_Msk /*!< End of injected conversion of the slave ADC */ -#define ADC_CSR_JEOS_SLV_Pos (22U) -#define ADC_CSR_JEOS_SLV_Msk (0x1UL << ADC_CSR_JEOS_SLV_Pos) /*!< 0x00400000 */ -#define ADC_CSR_JEOS_SLV ADC_CSR_JEOS_SLV_Msk /*!< End of injected sequence flag of the slave ADC */ -#define ADC_CSR_AWD1_SLV_Pos (23U) -#define ADC_CSR_AWD1_SLV_Msk (0x1UL << ADC_CSR_AWD1_SLV_Pos) /*!< 0x00800000 */ -#define ADC_CSR_AWD1_SLV ADC_CSR_AWD1_SLV_Msk /*!< Analog watchdog 1 flag of the slave ADC */ -#define ADC_CSR_AWD2_SLV_Pos (24U) -#define ADC_CSR_AWD2_SLV_Msk (0x1UL << ADC_CSR_AWD2_SLV_Pos) /*!< 0x01000000 */ -#define ADC_CSR_AWD2_SLV ADC_CSR_AWD2_SLV_Msk /*!< Analog watchdog 2 flag of the slave ADC */ -#define ADC_CSR_AWD3_SLV_Pos (25U) -#define ADC_CSR_AWD3_SLV_Msk (0x1UL << ADC_CSR_AWD3_SLV_Pos) /*!< 0x02000000 */ -#define ADC_CSR_AWD3_SLV ADC_CSR_AWD3_SLV_Msk /*!< Analog watchdog 3 flag of the slave ADC */ -#define ADC_CSR_JQOVF_SLV_Pos (26U) -#define ADC_CSR_JQOVF_SLV_Msk (0x1UL << ADC_CSR_JQOVF_SLV_Pos) /*!< 0x04000000 */ -#define ADC_CSR_JQOVF_SLV ADC_CSR_JQOVF_SLV_Msk /*!< Injected context queue overflow flag of the slave ADC */ - -/******************** Bit definition for ADC_CCR register ********************/ -#define ADC_CCR_DUAL_Pos (0U) -#define ADC_CCR_DUAL_Msk (0x1FUL << ADC_CCR_DUAL_Pos) /*!< 0x0000001F */ -#define ADC_CCR_DUAL ADC_CCR_DUAL_Msk /*!< Dual ADC mode selection */ -#define ADC_CCR_DUAL_0 (0x01UL << ADC_CCR_DUAL_Pos) /*!< 0x00000001 */ -#define ADC_CCR_DUAL_1 (0x02UL << ADC_CCR_DUAL_Pos) /*!< 0x00000002 */ -#define ADC_CCR_DUAL_2 (0x04UL << ADC_CCR_DUAL_Pos) /*!< 0x00000004 */ -#define ADC_CCR_DUAL_3 (0x08UL << ADC_CCR_DUAL_Pos) /*!< 0x00000008 */ -#define ADC_CCR_DUAL_4 (0x10UL << ADC_CCR_DUAL_Pos) /*!< 0x00000010 */ - -#define ADC_CCR_DELAY_Pos (8U) -#define ADC_CCR_DELAY_Msk (0xFUL << ADC_CCR_DELAY_Pos) /*!< 0x00000F00 */ -#define ADC_CCR_DELAY ADC_CCR_DELAY_Msk /*!< Delay between 2 sampling phases */ -#define ADC_CCR_DELAY_0 (0x1UL << ADC_CCR_DELAY_Pos) /*!< 0x00000100 */ -#define ADC_CCR_DELAY_1 (0x2UL << ADC_CCR_DELAY_Pos) /*!< 0x00000200 */ -#define ADC_CCR_DELAY_2 (0x4UL << ADC_CCR_DELAY_Pos) /*!< 0x00000400 */ -#define ADC_CCR_DELAY_3 (0x8UL << ADC_CCR_DELAY_Pos) /*!< 0x00000800 */ - - -#define ADC_CCR_DAMDF_Pos (14U) -#define ADC_CCR_DAMDF_Msk (0x3UL << ADC_CCR_DAMDF_Pos) /*!< 0x0000C000 */ -#define ADC_CCR_DAMDF ADC_CCR_DAMDF_Msk /*!< Dual ADC mode Data format */ -#define ADC_CCR_DAMDF_0 (0x1UL << ADC_CCR_DAMDF_Pos) /*!< 0x00004000 */ -#define ADC_CCR_DAMDF_1 (0x2UL << ADC_CCR_DAMDF_Pos) /*!< 0x00008000 */ - -#define ADC_CCR_CKMODE_Pos (16U) -#define ADC_CCR_CKMODE_Msk (0x3UL << ADC_CCR_CKMODE_Pos) /*!< 0x00030000 */ -#define ADC_CCR_CKMODE ADC_CCR_CKMODE_Msk /*!< ADC clock mode */ -#define ADC_CCR_CKMODE_0 (0x1UL << ADC_CCR_CKMODE_Pos) /*!< 0x00010000 */ -#define ADC_CCR_CKMODE_1 (0x2UL << ADC_CCR_CKMODE_Pos) /*!< 0x00020000 */ - -#define ADC_CCR_PRESC_Pos (18U) -#define ADC_CCR_PRESC_Msk (0xFUL << ADC_CCR_PRESC_Pos) /*!< 0x003C0000 */ -#define ADC_CCR_PRESC ADC_CCR_PRESC_Msk /*!< ADC prescaler */ -#define ADC_CCR_PRESC_0 (0x1UL << ADC_CCR_PRESC_Pos) /*!< 0x00040000 */ -#define ADC_CCR_PRESC_1 (0x2UL << ADC_CCR_PRESC_Pos) /*!< 0x00080000 */ -#define ADC_CCR_PRESC_2 (0x4UL << ADC_CCR_PRESC_Pos) /*!< 0x00100000 */ -#define ADC_CCR_PRESC_3 (0x8UL << ADC_CCR_PRESC_Pos) /*!< 0x00200000 */ - -#define ADC_CCR_VREFEN_Pos (22U) -#define ADC_CCR_VREFEN_Msk (0x1UL << ADC_CCR_VREFEN_Pos) /*!< 0x00400000 */ -#define ADC_CCR_VREFEN ADC_CCR_VREFEN_Msk /*!< VREFINT enable */ -#define ADC_CCR_TSEN_Pos (23U) -#define ADC_CCR_TSEN_Msk (0x1UL << ADC_CCR_TSEN_Pos) /*!< 0x00800000 */ -#define ADC_CCR_TSEN ADC_CCR_TSEN_Msk /*!< Temperature sensor enable */ -#define ADC_CCR_VBATEN_Pos (24U) -#define ADC_CCR_VBATEN_Msk (0x1UL << ADC_CCR_VBATEN_Pos) /*!< 0x01000000 */ -#define ADC_CCR_VBATEN ADC_CCR_VBATEN_Msk /*!< VBAT enable */ - -/******************** Bit definition for ADC_CDR register *******************/ -#define ADC_CDR_RDATA_MST_Pos (0U) -#define ADC_CDR_RDATA_MST_Msk (0xFFFFUL << ADC_CDR_RDATA_MST_Pos) /*!< 0x0000FFFF */ -#define ADC_CDR_RDATA_MST ADC_CDR_RDATA_MST_Msk /*!< ADC multimode master group regular conversion data */ - -#define ADC_CDR_RDATA_SLV_Pos (16U) -#define ADC_CDR_RDATA_SLV_Msk (0xFFFFUL << ADC_CDR_RDATA_SLV_Pos) /*!< 0xFFFF0000 */ -#define ADC_CDR_RDATA_SLV ADC_CDR_RDATA_SLV_Msk /*!< ADC multimode slave group regular conversion data */ - -/******************** Bit definition for ADC_CDR2 register ******************/ -#define ADC_CDR2_RDATA_ALT_Pos (0U) -#define ADC_CDR2_RDATA_ALT_Msk (0xFFFFFFFFUL << ADC_CDR2_RDATA_ALT_Pos) /*!< 0xFFFFFFFF */ -#define ADC_CDR2_RDATA_ALT ADC_CDR2_RDATA_ALT_Msk /*!< Regular data of the master/slave alternated ADCs */ - - -/******************************************************************************/ -/* */ -/* VREFBUF */ -/* */ -/******************************************************************************/ -/******************* Bit definition for VREFBUF_CSR register ****************/ -#define VREFBUF_CSR_ENVR_Pos (0U) -#define VREFBUF_CSR_ENVR_Msk (0x1UL << VREFBUF_CSR_ENVR_Pos) /*!< 0x00000001 */ -#define VREFBUF_CSR_ENVR VREFBUF_CSR_ENVR_Msk /*!*/ -#define DAC_CR_CEN1_Pos (14U) -#define DAC_CR_CEN1_Msk (0x1UL << DAC_CR_CEN1_Pos) /*!< 0x00004000 */ -#define DAC_CR_CEN1 DAC_CR_CEN1_Msk /*!*/ - -#define DAC_CR_EN2_Pos (16U) -#define DAC_CR_EN2_Msk (0x1UL << DAC_CR_EN2_Pos) /*!< 0x00010000 */ -#define DAC_CR_EN2 DAC_CR_EN2_Msk /*!*/ -#define DAC_CR_CEN2_Pos (30U) -#define DAC_CR_CEN2_Msk (0x1UL << DAC_CR_CEN2_Pos) /*!< 0x40000000 */ -#define DAC_CR_CEN2 DAC_CR_CEN2_Msk /*!*/ - -/***************** Bit definition for DAC_SWTRIGR register ******************/ -#define DAC_SWTRIGR_SWTRIG1_Pos (0U) -#define DAC_SWTRIGR_SWTRIG1_Msk (0x1UL << DAC_SWTRIGR_SWTRIG1_Pos) /*!< 0x00000001 */ -#define DAC_SWTRIGR_SWTRIG1 DAC_SWTRIGR_SWTRIG1_Msk /*!
© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.
- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/** @addtogroup CMSIS - * @{ - */ - -/** @addtogroup stm32h7xx - * @{ - */ - -#ifndef STM32H7xx_H -#define STM32H7xx_H - -#ifdef __cplusplus - extern "C" { -#endif /* __cplusplus */ - -/** @addtogroup Library_configuration_section - * @{ - */ - -/** - * @brief STM32 Family - */ -#if !defined (STM32H7) -#define STM32H7 -#endif /* STM32H7 */ - - -/* Uncomment the line below according to the target STM32H7 device used in your - application - */ - -/* #if !defined (STM32H743xx) && !defined (STM32H753xx) && !defined (STM32H750xx) && !defined (STM32H742xx) && \ - !defined (STM32H745xx) && !defined (STM32H755xx) && !defined (STM32H747xx) && !defined (STM32H757xx) && \ - !defined (STM32H7A3xx) && !defined (STM32H7A3xxQ) && !defined (STM32H7B3xx) && !defined (STM32H7B3xxQ) && !defined (STM32H7B0xx) && !defined (STM32H7B0xxQ) && \ - !defined (STM32H735xx) && !defined (STM32H733xx) && !defined (STM32H730xx) && !defined (STM32H730xxQ) && !defined (STM32H725xx) && !defined (STM32H723xx) */ - /* #define STM32H742xx */ /*!< STM32H742VI, STM32H742ZI, STM32H742AI, STM32H742II, STM32H742BI, STM32H742XI Devices */ - /* #define STM32H743xx */ /*!< STM32H743VI, STM32H743ZI, STM32H743AI, STM32H743II, STM32H743BI, STM32H743XI Devices */ - /* #define STM32H753xx */ /*!< STM32H753VI, STM32H753ZI, STM32H753AI, STM32H753II, STM32H753BI, STM32H753XI Devices */ - /* #define STM32H750xx */ /*!< STM32H750V, STM32H750I, STM32H750X Devices */ - /* #define STM32H747xx */ /*!< STM32H747ZI, STM32H747AI, STM32H747II, STM32H747BI, STM32H747XI Devices */ - /* #define STM32H757xx */ /*!< STM32H757ZI, STM32H757AI, STM32H757II, STM32H757BI, STM32H757XI Devices */ - /* #define STM32H745xx */ /*!< STM32H745ZI, STM32H745II, STM32H745BI, STM32H745XI Devices */ - /* #define STM32H755xx */ /*!< STM32H755ZI, STM32H755II, STM32H755BI, STM32H755XI Devices */ - /* #define STM32H7B0xx */ /*!< STM32H7B0ABIxQ, STM32H7B0IBTx, STM32H7B0RBTx, STM32H7B0VBTx, STM32H7B0ZBTx, STM32H7B0IBKxQ */ - /* #define STM32H7A3xx */ /*!< STM32H7A3IIK6, STM32H7A3IIT6, STM32H7A3NIH6, STM32H7A3RIT6, STM32H7A3VIH6, STM32H7A3VIT6, STM32H7A3ZIT6 */ - /* #define STM32H7A3xxQ */ /*!< STM32H7A3QIY6Q, STM32H7A3IIK6Q, STM32H7A3IIT6Q, STM32H7A3LIH6Q, STM32H7A3VIH6Q, STM32H7A3VIT6Q, STM32H7A3AII6Q, STM32H7A3ZIT6Q */ - /* #define STM32H7B3xx */ /*!< STM32H7B3IIK6, STM32H7B3IIT6, STM32H7B3NIH6, STM32H7B3RIT6, STM32H7B3VIH6, STM32H7B3VIT6, STM32H7B3ZIT6 */ - /* #define STM32H7B3xxQ */ /*!< STM32H7B3QIY6Q, STM32H7B3IIK6Q, STM32H7B3IIT6Q, STM32H7B3LIH6Q, STM32H7B3VIH6Q, STM32H7B3VIT6Q, STM32H7B3AII6Q, STM32H7B3ZIT6Q */ - /* #define STM32H735xx */ /*!< STM32H735AGI6, STM32H735IGK6, STM32H735RGV6, STM32H735VGT6, STM32H735VGY6, STM32H735ZGT6 Devices */ - /* #define STM32H733xx */ /*!< STM32H733VGH6, STM32H733VGT6, STM32H733ZGI6, STM32H733ZGT6, Devices */ - /* #define STM32H730xx */ /*!< STM32H730VBH6, STM32H730VBT6, STM32H730ZBT6, STM32H730ZBI6 Devices */ - /* #define STM32H730xxQ */ /*!< STM32H730IBT6Q, STM32H730ABI6Q, STM32H730IBK6Q Devices */ - /* #define STM32H725xx */ /*!< STM32H725AGI6, STM32H725IGK6, STM32H725IGT6, STM32H725RGV6, STM32H725VGT6, STM32H725VGY6, STM32H725ZGT6, STM32H725REV6, SM32H725VET6, STM32H725ZET6, STM32H725AEI6, STM32H725IET6, STM32H725IEK6 Devices */ - /* #define STM32H723xx */ /*!< STM32H723VGH6, STM32H723VGT6, STM32H723ZGI6, STM32H723ZGT6, STM32H723VET6, STM32H723VEH6, STM32H723ZET6, STM32H723ZEI6 Devices */ -/* #endif */ - -/* Tip: To avoid modifying this file each time you need to switch between these - devices, you can define the device in your toolchain compiler preprocessor. - */ - -#if defined(DUAL_CORE) && !defined(CORE_CM4) && !defined(CORE_CM7) - #error "Dual core device, please select CORE_CM4 or CORE_CM7" -#endif - -#if !defined (USE_HAL_DRIVER) -/** - * @brief Comment the line below if you will not use the peripherals drivers. - In this case, these drivers will not be included and the application code will - be based on direct access to peripherals registers - */ - /*#define USE_HAL_DRIVER */ -#endif /* USE_HAL_DRIVER */ - -/** - * @brief CMSIS Device version number V1.10.0 - */ -#define __STM32H7xx_CMSIS_DEVICE_VERSION_MAIN (0x01) /*!< [31:24] main version */ -#define __STM32H7xx_CMSIS_DEVICE_VERSION_SUB1 (0x0A) /*!< [23:16] sub1 version */ -#define __STM32H7xx_CMSIS_DEVICE_VERSION_SUB2 (0x00) /*!< [15:8] sub2 version */ -#define __STM32H7xx_CMSIS_DEVICE_VERSION_RC (0x00) /*!< [7:0] release candidate */ -#define __STM32H7xx_CMSIS_DEVICE_VERSION ((__STM32H7xx_CMSIS_DEVICE_VERSION_MAIN << 24)\ - |(__STM32H7xx_CMSIS_DEVICE_VERSION_SUB1 << 16)\ - |(__STM32H7xx_CMSIS_DEVICE_VERSION_SUB2 << 8 )\ - |(__STM32H7xx_CMSIS_DEVICE_VERSION_RC)) - -/** - * @} - */ - -/** @addtogroup Device_Included - * @{ - */ - -#if defined(STM32H743xx) - #include "stm32h743xx.h" -// #elif defined(STM32H753xx) -// #include "stm32h753xx.h" -// #elif defined(STM32H750xx) -// #include "stm32h750xx.h" -// #elif defined(STM32H742xx) -// #include "stm32h742xx.h" -// #elif defined(STM32H745xx) -// #include "stm32h745xx.h" -// #elif defined(STM32H755xx) -// #include "stm32h755xx.h" -// #elif defined(STM32H747xx) -// #include "stm32h747xx.h" -// #elif defined(STM32H757xx) -// #include "stm32h757xx.h" -// #elif defined(STM32H7B0xx) -// #include "stm32h7b0xx.h" -// #elif defined(STM32H7B0xxQ) -// #include "stm32h7b0xxq.h" -// #elif defined(STM32H7A3xx) -// #include "stm32h7a3xx.h" -// #elif defined(STM32H7B3xx) -// #include "stm32h7b3xx.h" -// #elif defined(STM32H7A3xxQ) -// #include "stm32h7a3xxq.h" -// #elif defined(STM32H7B3xxQ) -// #include "stm32h7b3xxq.h" -#elif defined(STM32H735xx) - #include "stm32h735xx.h" -// #elif defined(STM32H733xx) -// #include "stm32h733xx.h" -// #elif defined(STM32H730xx) -// #include "stm32h730xx.h" -// #elif defined(STM32H730xxQ) -// #include "stm32h730xxq.h" -#elif defined(STM32H725xx) - #include "stm32h725xx.h" -// #elif defined(STM32H723xx) -// #include "stm32h723xx.h" -#else - #error "Please select first the target STM32H7xx device used in your application (in stm32h7xx.h file)" -#endif - -/** - * @} - */ - -/** @addtogroup Exported_types - * @{ - */ -typedef enum -{ - RESET = 0, - SET = !RESET -} FlagStatus, ITStatus; - -typedef enum -{ - DISABLE = 0, - ENABLE = !DISABLE -} FunctionalState; -#define IS_FUNCTIONAL_STATE(STATE) (((STATE) == DISABLE) || ((STATE) == ENABLE)) - -typedef enum -{ - SUCCESS = 0, - ERROR = !SUCCESS -} ErrorStatus; - -/** - * @} - */ - - -/** @addtogroup Exported_macros - * @{ - */ -#define SET_BIT(REG, BIT) ((REG) |= (BIT)) - -#define CLEAR_BIT(REG, BIT) ((REG) &= ~(BIT)) - -#define READ_BIT(REG, BIT) ((REG) & (BIT)) - -#define CLEAR_REG(REG) ((REG) = (0x0)) - -#define WRITE_REG(REG, VAL) ((REG) = (VAL)) - -#define READ_REG(REG) ((REG)) - -#define MODIFY_REG(REG, CLEARMASK, SETMASK) WRITE_REG((REG), (((READ_REG(REG)) & (~(CLEARMASK))) | (SETMASK))) - -#define POSITION_VAL(VAL) (__CLZ(__RBIT(VAL))) - - -/** - * @} - */ - -#if defined (USE_HAL_DRIVER) - #include "stm32h7xx_hal.h" -#endif /* USE_HAL_DRIVER */ - - -#ifdef __cplusplus -} -#endif /* __cplusplus */ - -#endif /* STM32H7xx_H */ -/** - * @} - */ - -/** - * @} - */ - - - - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/panda/board/stm32h7/inc/stm32h7xx_hal_def.h b/panda/board/stm32h7/inc/stm32h7xx_hal_def.h deleted file mode 100644 index 3854b1c..0000000 --- a/panda/board/stm32h7/inc/stm32h7xx_hal_def.h +++ /dev/null @@ -1,221 +0,0 @@ -/** - ****************************************************************************** - * @file stm32h7xx_hal_def.h - * @author MCD Application Team - * @brief This file contains HAL common defines, enumeration, macros and - * structures definitions. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32H7xx_HAL_DEF -#define STM32H7xx_HAL_DEF - -#ifdef __cplusplus - extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32h7xx.h" -//#include "Legacy/stm32_hal_legacy.h" -//#include -//#include - -/* Exported types ------------------------------------------------------------*/ - -/** - * @brief HAL Status structures definition - */ -typedef enum -{ - HAL_OK = 0x00, - HAL_ERROR = 0x01, - HAL_BUSY = 0x02, - HAL_TIMEOUT = 0x03 -} HAL_StatusTypeDef; - -/** - * @brief HAL Lock structures definition - */ -typedef enum -{ - HAL_UNLOCKED = 0x00, - HAL_LOCKED = 0x01 -} HAL_LockTypeDef; - -/* Exported macro ------------------------------------------------------------*/ - -#define HAL_MAX_DELAY 0xFFFFFFFFU - -#define HAL_IS_BIT_SET(REG, BIT) (((REG) & (BIT)) == (BIT)) -#define HAL_IS_BIT_CLR(REG, BIT) (((REG) & (BIT)) == 0U) - -#define __HAL_LINKDMA(__HANDLE__, __PPP_DMA_FIELD__, __DMA_HANDLE__) \ - do{ \ - (__HANDLE__)->__PPP_DMA_FIELD__ = &(__DMA_HANDLE__); \ - (__DMA_HANDLE__).Parent = (__HANDLE__); \ - } while(0) - -#define UNUSED(x) ((void)(x)) - -/** @brief Reset the Handle's State field. - * @param __HANDLE__: specifies the Peripheral Handle. - * @note This macro can be used for the following purpose: - * - When the Handle is declared as local variable; before passing it as parameter - * to HAL_PPP_Init() for the first time, it is mandatory to use this macro - * to set to 0 the Handle's "State" field. - * Otherwise, "State" field may have any random value and the first time the function - * HAL_PPP_Init() is called, the low level hardware initialization will be missed - * (i.e. HAL_PPP_MspInit() will not be executed). - * - When there is a need to reconfigure the low level hardware: instead of calling - * HAL_PPP_DeInit() then HAL_PPP_Init(), user can make a call to this macro then HAL_PPP_Init(). - * In this later function, when the Handle's "State" field is set to 0, it will execute the function - * HAL_PPP_MspInit() which will reconfigure the low level hardware. - * @retval None - */ -#define __HAL_RESET_HANDLE_STATE(__HANDLE__) ((__HANDLE__)->State = 0) - -#if (USE_RTOS == 1) - #error " USE_RTOS should be 0 in the current HAL release " -#else - #define __HAL_LOCK(__HANDLE__) \ - do{ \ - if((__HANDLE__)->Lock == HAL_LOCKED) \ - { \ - return HAL_BUSY; \ - } \ - else \ - { \ - (__HANDLE__)->Lock = HAL_LOCKED; \ - } \ - }while (0) - - #define __HAL_UNLOCK(__HANDLE__) \ - do{ \ - (__HANDLE__)->Lock = HAL_UNLOCKED; \ - }while (0) -#endif /* USE_RTOS */ - - -#if defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) /* ARM Compiler V6 */ - #ifndef __weak - #define __weak __attribute__((weak)) - #endif - #ifndef __packed - #define __packed __attribute__((packed)) - #endif -#elif defined ( __GNUC__ ) && !defined (__CC_ARM) /* GNU Compiler */ - #ifndef __weak - #define __weak __attribute__((weak)) - #endif /* __weak */ - #ifndef __packed - #define __packed __attribute__((__packed__)) - #endif /* __packed */ -#endif /* __GNUC__ */ - - -/* Macro to get variable aligned on 4-bytes, for __ICCARM__ the directive "#pragma data_alignment=4" must be used instead */ -#if defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050) /* ARM Compiler V6 */ - #ifndef __ALIGN_BEGIN - #define __ALIGN_BEGIN - #endif - #ifndef __ALIGN_END - #define __ALIGN_END __attribute__ ((aligned (4))) - #endif -#elif defined ( __GNUC__ ) && !defined (__CC_ARM) /* GNU Compiler */ - #ifndef __ALIGN_END - #define __ALIGN_END __attribute__ ((aligned (4))) - #endif /* __ALIGN_END */ - #ifndef __ALIGN_BEGIN - #define __ALIGN_BEGIN - #endif /* __ALIGN_BEGIN */ -#else - #ifndef __ALIGN_END - #define __ALIGN_END - #endif /* __ALIGN_END */ - #ifndef __ALIGN_BEGIN - #if defined (__CC_ARM) /* ARM Compiler V5 */ - #define __ALIGN_BEGIN __align(4) - #elif defined (__ICCARM__) /* IAR Compiler */ - #define __ALIGN_BEGIN - #endif /* __CC_ARM */ - #endif /* __ALIGN_BEGIN */ -#endif /* __GNUC__ */ - -/* Macro to get variable aligned on 32-bytes,needed for cache maintenance purpose */ -#if defined (__GNUC__) /* GNU Compiler */ - #define ALIGN_32BYTES(buf) buf __attribute__ ((aligned (32))) -#elif defined (__ICCARM__) /* IAR Compiler */ - #define ALIGN_32BYTES(buf) _Pragma("data_alignment=32") buf -#elif defined (__CC_ARM) /* ARM Compiler */ - #define ALIGN_32BYTES(buf) __align(32) buf -#endif - -/** - * @brief __RAM_FUNC definition - */ -#if defined ( __CC_ARM ) || (defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)) -/* ARM Compiler V4/V5 and V6 - -------------------------- - RAM functions are defined using the toolchain options. - Functions that are executed in RAM should reside in a separate source module. - Using the 'Options for File' dialog you can simply change the 'Code / Const' - area of a module to a memory space in physical RAM. - Available memory areas are declared in the 'Target' tab of the 'Options for Target' - dialog. -*/ -#define __RAM_FUNC - -#elif defined ( __ICCARM__ ) -/* ICCARM Compiler - --------------- - RAM functions are defined using a specific toolchain keyword "__ramfunc". -*/ -#define __RAM_FUNC __ramfunc - -#elif defined ( __GNUC__ ) -/* GNU Compiler - ------------ - RAM functions are defined using a specific toolchain attribute - "__attribute__((section(".RamFunc")))". -*/ -#define __RAM_FUNC __attribute__((section(".RamFunc"))) - -#endif - -/** - * @brief __NOINLINE definition - */ -#if defined ( __CC_ARM ) || (defined (__ARMCC_VERSION) && (__ARMCC_VERSION >= 6010050)) || defined ( __GNUC__ ) -/* ARM V4/V5 and V6 & GNU Compiler - ------------------------------- -*/ -#define __NOINLINE __attribute__ ( (noinline) ) - -#elif defined ( __ICCARM__ ) -/* ICCARM Compiler - --------------- -*/ -#define __NOINLINE _Pragma("optimize = no_inline") - -#endif - - -#ifdef __cplusplus -} -#endif - -#endif /* STM32H7xx_HAL_DEF */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/panda/board/stm32h7/inc/stm32h7xx_hal_gpio_ex.h b/panda/board/stm32h7/inc/stm32h7xx_hal_gpio_ex.h deleted file mode 100644 index 14f576a..0000000 --- a/panda/board/stm32h7/inc/stm32h7xx_hal_gpio_ex.h +++ /dev/null @@ -1,489 +0,0 @@ -/** - ****************************************************************************** - * @file stm32h7xx_hal_gpio_ex.h - * @author MCD Application Team - * @brief Header file of GPIO HAL Extension module. - ****************************************************************************** - * @attention - * - *

© COPYRIGHT(c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef STM32H7xx_HAL_GPIO_EX_H -#define STM32H7xx_HAL_GPIO_EX_H - -#ifdef __cplusplus -extern "C" { -#endif - -/* Includes ------------------------------------------------------------------*/ -#include "stm32h7xx_hal_def.h" - -/** @addtogroup STM32H7xx_HAL_Driver - * @{ - */ - -/** @addtogroup GPIOEx GPIOEx - * @{ - */ - -/* Exported types ------------------------------------------------------------*/ - -/* Exported constants --------------------------------------------------------*/ -/** @defgroup GPIOEx_Exported_Constants GPIO Exported Constants - * @{ - */ - -/** @defgroup GPIO_Alternate_function_selection GPIO Alternate Function Selection - * @{ - */ - -/** - * @brief AF 0 selection - */ -#define GPIO_AF0_RTC_50Hz ((uint8_t)0x00) /* RTC_50Hz Alternate Function mapping */ -#define GPIO_AF0_MCO ((uint8_t)0x00) /* MCO (MCO1 and MCO2) Alternate Function mapping */ -#define GPIO_AF0_SWJ ((uint8_t)0x00) /* SWJ (SWD and JTAG) Alternate Function mapping */ -#define GPIO_AF0_LCDBIAS ((uint8_t)0x00) /* LCDBIAS Alternate Function mapping */ -#define GPIO_AF0_TRACE ((uint8_t)0x00) /* TRACE Alternate Function mapping */ -#if defined (PWR_CPUCR_PDDS_D2) /* PWR D1 and D2 domains exists */ -#define GPIO_AF0_C1DSLEEP ((uint8_t)0x00) /* Cortex-M7 Deep Sleep Alternate Function mapping : available on STM32H7 Rev.B and above */ -#define GPIO_AF0_C1SLEEP ((uint8_t)0x00) /* Cortex-M7 Sleep Alternate Function mapping : available on STM32H7 Rev.B and above */ -#define GPIO_AF0_D1PWREN ((uint8_t)0x00) /* Domain 1 PWR enable Alternate Function mapping : available on STM32H7 Rev.B and above */ -#define GPIO_AF0_D2PWREN ((uint8_t)0x00) /* Domain 2 PWR enable Alternate Function mapping : available on STM32H7 Rev.B and above */ -#if defined(DUAL_CORE) -#define GPIO_AF0_C2DSLEEP ((uint8_t)0x00) /* Cortex-M4 Deep Sleep Alternate Function mapping : available on STM32H7 Rev.B and above */ -#define GPIO_AF0_C2SLEEP ((uint8_t)0x00) /* Cortex-M4 Sleep Alternate Function mapping : available on STM32H7 Rev.B and above */ -#endif /* DUAL_CORE */ -#endif /* PWR_CPUCR_PDDS_D2 */ - -/** - * @brief AF 1 selection - */ -#define GPIO_AF1_TIM1 ((uint8_t)0x01) /* TIM1 Alternate Function mapping */ -#define GPIO_AF1_TIM2 ((uint8_t)0x01) /* TIM2 Alternate Function mapping */ -#define GPIO_AF1_TIM16 ((uint8_t)0x01) /* TIM16 Alternate Function mapping */ -#define GPIO_AF1_TIM17 ((uint8_t)0x01) /* TIM17 Alternate Function mapping */ -#define GPIO_AF1_LPTIM1 ((uint8_t)0x01) /* LPTIM1 Alternate Function mapping */ -#if defined(HRTIM1) -#define GPIO_AF1_HRTIM1 ((uint8_t)0x01) /* HRTIM1 Alternate Function mapping */ -#endif /* HRTIM1 */ -#if defined(SAI4) -#define GPIO_AF1_SAI4 ((uint8_t)0x01) /* SAI4 Alternate Function mapping : available on STM32H72xxx/STM32H73xxx */ -#endif /* SAI4 */ -#define GPIO_AF1_FMC ((uint8_t)0x01) /* FMC Alternate Function mapping : available on STM32H72xxx/STM32H73xxx */ - - -/** - * @brief AF 2 selection - */ -#define GPIO_AF2_TIM3 ((uint8_t)0x02) /* TIM3 Alternate Function mapping */ -#define GPIO_AF2_TIM4 ((uint8_t)0x02) /* TIM4 Alternate Function mapping */ -#define GPIO_AF2_TIM5 ((uint8_t)0x02) /* TIM5 Alternate Function mapping */ -#define GPIO_AF2_TIM12 ((uint8_t)0x02) /* TIM12 Alternate Function mapping */ -#define GPIO_AF2_SAI1 ((uint8_t)0x02) /* SAI1 Alternate Function mapping */ -#if defined(HRTIM1) -#define GPIO_AF2_HRTIM1 ((uint8_t)0x02) /* HRTIM1 Alternate Function mapping */ -#endif /* HRTIM1 */ -#define GPIO_AF2_TIM15 ((uint8_t)0x02) /* TIM15 Alternate Function mapping : available on STM32H7A3xxx/STM32H7B3xxx/STM32H7B0xxx and STM32H72xxx/STM32H73xxx */ -#if defined(FDCAN3) -#define GPIO_AF2_FDCAN3 ((uint8_t)0x02) /* FDCAN3 Alternate Function mapping */ -#endif /*FDCAN3*/ - -/** - * @brief AF 3 selection - */ -#define GPIO_AF3_TIM8 ((uint8_t)0x03) /* TIM8 Alternate Function mapping */ -#define GPIO_AF3_LPTIM2 ((uint8_t)0x03) /* LPTIM2 Alternate Function mapping */ -#define GPIO_AF3_DFSDM1 ((uint8_t)0x03) /* DFSDM Alternate Function mapping */ -#define GPIO_AF3_LPTIM3 ((uint8_t)0x03) /* LPTIM3 Alternate Function mapping */ -#define GPIO_AF3_LPTIM4 ((uint8_t)0x03) /* LPTIM4 Alternate Function mapping */ -#define GPIO_AF3_LPTIM5 ((uint8_t)0x03) /* LPTIM5 Alternate Function mapping */ -#define GPIO_AF3_LPUART ((uint8_t)0x03) /* LPUART Alternate Function mapping */ -#if defined(OCTOSPIM) -#define GPIO_AF3_OCTOSPIM_P1 ((uint8_t)0x03) /* OCTOSPI Manager Port 1 Alternate Function mapping */ -#define GPIO_AF3_OCTOSPIM_P2 ((uint8_t)0x03) /* OCTOSPI Manager Port 2 Alternate Function mapping */ -#endif /* OCTOSPIM */ -#if defined(HRTIM1) -#define GPIO_AF3_HRTIM1 ((uint8_t)0x03) /* HRTIM1 Alternate Function mapping */ -#endif /* HRTIM1 */ -#define GPIO_AF3_LTDC ((uint8_t)0x03) /* LTDC Alternate Function mapping : available on STM32H72xxx/STM32H73xxx */ - -/** - * @brief AF 4 selection - */ -#define GPIO_AF4_I2C1 ((uint8_t)0x04) /* I2C1 Alternate Function mapping */ -#define GPIO_AF4_I2C2 ((uint8_t)0x04) /* I2C2 Alternate Function mapping */ -#define GPIO_AF4_I2C3 ((uint8_t)0x04) /* I2C3 Alternate Function mapping */ -#define GPIO_AF4_I2C4 ((uint8_t)0x04) /* I2C4 Alternate Function mapping */ -#if defined(I2C5) -#define GPIO_AF4_I2C5 ((uint8_t)0x04) /* I2C5 Alternate Function mapping */ -#endif /* I2C5*/ -#define GPIO_AF4_TIM15 ((uint8_t)0x04) /* TIM15 Alternate Function mapping */ -#define GPIO_AF4_CEC ((uint8_t)0x04) /* CEC Alternate Function mapping */ -#define GPIO_AF4_LPTIM2 ((uint8_t)0x04) /* LPTIM2 Alternate Function mapping */ -#define GPIO_AF4_USART1 ((uint8_t)0x04) /* USART1 Alternate Function mapping */ -#if defined(USART10) -#define GPIO_AF4_USART10 ((uint8_t)0x04) /* USART10 Alternate Function mapping : available on STM32H72xxx/STM32H73xxx */ -#endif /*USART10*/ -#define GPIO_AF4_DFSDM1 ((uint8_t)0x04) /* DFSDM Alternate Function mapping */ -#if defined(DFSDM2_BASE) -#define GPIO_AF4_DFSDM2 ((uint8_t)0x04) /* DFSDM2 Alternate Function mapping */ -#endif /* DFSDM2_BASE */ -#define GPIO_AF4_DCMI ((uint8_t)0x04) /* DCMI Alternate Function mapping : available on STM32H7A3xxx/STM32H7B3xxx/STM32H7B0xxx and STM32H72xxx/STM32H73xxx */ -#if defined(PSSI) -#define GPIO_AF4_PSSI ((uint8_t)0x04) /* PSSI Alternate Function mapping */ -#endif /* PSSI */ -#if defined(OCTOSPIM) -#define GPIO_AF4_OCTOSPIM_P1 ((uint8_t)0x04) /* OCTOSPI Manager Port 1 Alternate Function mapping : available on STM32H72xxx/STM32H73xxx */ -#endif /* OCTOSPIM */ - -/** - * @brief AF 5 selection - */ -#define GPIO_AF5_SPI1 ((uint8_t)0x05) /* SPI1 Alternate Function mapping */ -#define GPIO_AF5_SPI2 ((uint8_t)0x05) /* SPI2 Alternate Function mapping */ -#define GPIO_AF5_SPI3 ((uint8_t)0x05) /* SPI3 Alternate Function mapping */ -#define GPIO_AF5_SPI4 ((uint8_t)0x05) /* SPI4 Alternate Function mapping */ -#define GPIO_AF5_SPI5 ((uint8_t)0x05) /* SPI5 Alternate Function mapping */ -#define GPIO_AF5_SPI6 ((uint8_t)0x05) /* SPI6 Alternate Function mapping */ -#define GPIO_AF5_CEC ((uint8_t)0x05) /* CEC Alternate Function mapping */ -#if defined(FDCAN3) -#define GPIO_AF5_FDCAN3 ((uint8_t)0x05) /* FDCAN3 Alternate Function mapping */ -#endif /*FDCAN3*/ - -/** - * @brief AF 6 selection - */ -#define GPIO_AF6_SPI2 ((uint8_t)0x06) /* SPI2 Alternate Function mapping */ -#define GPIO_AF6_SPI3 ((uint8_t)0x06) /* SPI3 Alternate Function mapping */ -#define GPIO_AF6_SAI1 ((uint8_t)0x06) /* SAI1 Alternate Function mapping */ -#define GPIO_AF6_I2C4 ((uint8_t)0x06) /* I2C4 Alternate Function mapping */ -#if defined(I2C5) -#define GPIO_AF6_I2C5 ((uint8_t)0x06) /* I2C5 Alternate Function mapping */ -#endif /* I2C5*/ -#define GPIO_AF6_DFSDM1 ((uint8_t)0x06) /* DFSDM Alternate Function mapping */ -#define GPIO_AF6_UART4 ((uint8_t)0x06) /* UART4 Alternate Function mapping */ -#if defined(DFSDM2_BASE) -#define GPIO_AF6_DFSDM2 ((uint8_t)0x06) /* DFSDM2 Alternate Function mapping */ -#endif /* DFSDM2_BASE */ -#if defined(SAI3) -#define GPIO_AF6_SAI3 ((uint8_t)0x06) /* SAI3 Alternate Function mapping */ -#endif /* SAI3 */ -#if defined(OCTOSPIM) -#define GPIO_AF6_OCTOSPIM_P1 ((uint8_t)0x06) /* OCTOSPI Manager Port 1 Alternate Function mapping */ -#endif /* OCTOSPIM */ - -/** - * @brief AF 7 selection - */ -#define GPIO_AF7_SPI2 ((uint8_t)0x07) /* SPI2 Alternate Function mapping */ -#define GPIO_AF7_SPI3 ((uint8_t)0x07) /* SPI3 Alternate Function mapping */ -#define GPIO_AF7_SPI6 ((uint8_t)0x07) /* SPI6 Alternate Function mapping */ -#define GPIO_AF7_USART1 ((uint8_t)0x07) /* USART1 Alternate Function mapping */ -#define GPIO_AF7_USART2 ((uint8_t)0x07) /* USART2 Alternate Function mapping */ -#define GPIO_AF7_USART3 ((uint8_t)0x07) /* USART3 Alternate Function mapping */ -#define GPIO_AF7_USART6 ((uint8_t)0x07) /* USART6 Alternate Function mapping */ -#define GPIO_AF7_UART7 ((uint8_t)0x07) /* UART7 Alternate Function mapping */ -#define GPIO_AF7_SDMMC1 ((uint8_t)0x07) /* SDMMC1 Alternate Function mapping */ - -/** - * @brief AF 8 selection - */ -#define GPIO_AF8_SPI6 ((uint8_t)0x08) /* SPI6 Alternate Function mapping */ -#if defined(SAI2) -#define GPIO_AF8_SAI2 ((uint8_t)0x08) /* SAI2 Alternate Function mapping */ -#endif /*SAI2*/ -#define GPIO_AF8_UART4 ((uint8_t)0x08) /* UART4 Alternate Function mapping */ -#define GPIO_AF8_UART5 ((uint8_t)0x08) /* UART5 Alternate Function mapping */ -#define GPIO_AF8_UART8 ((uint8_t)0x08) /* UART8 Alternate Function mapping */ -#define GPIO_AF8_SPDIF ((uint8_t)0x08) /* SPDIF Alternate Function mapping */ -#define GPIO_AF8_LPUART ((uint8_t)0x08) /* LPUART Alternate Function mapping */ -#define GPIO_AF8_SDMMC1 ((uint8_t)0x08) /* SDMMC1 Alternate Function mapping */ -#if defined(SAI4) -#define GPIO_AF8_SAI4 ((uint8_t)0x08) /* SAI4 Alternate Function mapping */ -#endif /* SAI4 */ - -/** - * @brief AF 9 selection - */ -#define GPIO_AF9_FDCAN1 ((uint8_t)0x09) /* FDCAN1 Alternate Function mapping */ -#define GPIO_AF9_FDCAN2 ((uint8_t)0x09) /* FDCAN2 Alternate Function mapping */ -#define GPIO_AF9_TIM13 ((uint8_t)0x09) /* TIM13 Alternate Function mapping */ -#define GPIO_AF9_TIM14 ((uint8_t)0x09) /* TIM14 Alternate Function mapping */ -#define GPIO_AF9_SDMMC2 ((uint8_t)0x09) /* SDMMC2 Alternate Function mapping */ -#define GPIO_AF9_LTDC ((uint8_t)0x09) /* LTDC Alternate Function mapping */ -#define GPIO_AF9_SPDIF ((uint8_t)0x09) /* SPDIF Alternate Function mapping */ -#define GPIO_AF9_FMC ((uint8_t)0x09) /* FMC Alternate Function mapping */ -#if defined(QUADSPI) -#define GPIO_AF9_QUADSPI ((uint8_t)0x09) /* QUADSPI Alternate Function mapping */ -#endif /* QUADSPI */ -#if defined(SAI4) -#define GPIO_AF9_SAI4 ((uint8_t)0x09) /* SAI4 Alternate Function mapping */ -#endif /* SAI4 */ -#if defined(OCTOSPIM) -#define GPIO_AF9_OCTOSPIM_P1 ((uint8_t)0x09) /* OCTOSPI Manager Port 1 Alternate Function mapping */ -#define GPIO_AF9_OCTOSPIM_P2 ((uint8_t)0x09) /* OCTOSPI Manager Port 2 Alternate Function mapping */ -#endif /* OCTOSPIM */ - -/** - * @brief AF 10 selection - */ -#if defined(SAI2) -#define GPIO_AF10_SAI2 ((uint8_t)0x0A) /* SAI2 Alternate Function mapping */ -#endif /*SAI2*/ -#define GPIO_AF10_SDMMC2 ((uint8_t)0x0A) /* SDMMC2 Alternate Function mapping */ -#if defined(USB2_OTG_FS) -#define GPIO_AF10_OTG2_FS ((uint8_t)0x0A) /* OTG2_FS Alternate Function mapping */ -#endif /*USB2_OTG_FS*/ -#define GPIO_AF10_COMP1 ((uint8_t)0x0A) /* COMP1 Alternate Function mapping */ -#define GPIO_AF10_COMP2 ((uint8_t)0x0A) /* COMP2 Alternate Function mapping */ -#if defined(LTDC) -#define GPIO_AF10_LTDC ((uint8_t)0x0A) /* LTDC Alternate Function mapping */ -#endif /*LTDC*/ -#define GPIO_AF10_CRS_SYNC ((uint8_t)0x0A) /* CRS Sync Alternate Function mapping : available on STM32H7 Rev.B and above */ -#if defined(QUADSPI) -#define GPIO_AF10_QUADSPI ((uint8_t)0x0A) /* QUADSPI Alternate Function mapping */ -#endif /* QUADSPI */ -#if defined(SAI4) -#define GPIO_AF10_SAI4 ((uint8_t)0x0A) /* SAI4 Alternate Function mapping */ -#endif /* SAI4 */ -#if !defined(USB2_OTG_FS) -#define GPIO_AF10_OTG1_FS ((uint8_t)0x0A) /* OTG1_FS Alternate Function mapping : available on STM32H7A3xxx/STM32H7B3xxx/STM32H7B0xxx and STM32H72xxx/STM32H73xxx */ -#endif /* !USB2_OTG_FS */ -#define GPIO_AF10_OTG1_HS ((uint8_t)0x0A) /* OTG1_HS Alternate Function mapping */ -#if defined(OCTOSPIM) -#define GPIO_AF10_OCTOSPIM_P1 ((uint8_t)0x0A) /* OCTOSPI Manager Port 1 Alternate Function mapping */ -#endif /* OCTOSPIM */ -#define GPIO_AF10_TIM8 ((uint8_t)0x0A) /* TIM8 Alternate Function mapping */ -#define GPIO_AF10_FMC ((uint8_t)0x0A) /* FMC Alternate Function mapping : available on STM32H7A3xxx/STM32H7B3xxx/STM32H7B0xxx and STM32H72xxx/STM32H73xxx */ - -/** - * @brief AF 11 selection - */ -#define GPIO_AF11_SWP ((uint8_t)0x0B) /* SWP Alternate Function mapping */ -#define GPIO_AF11_MDIOS ((uint8_t)0x0B) /* MDIOS Alternate Function mapping */ -#define GPIO_AF11_UART7 ((uint8_t)0x0B) /* UART7 Alternate Function mapping */ -#define GPIO_AF11_SDMMC2 ((uint8_t)0x0B) /* SDMMC2 Alternate Function mapping */ -#define GPIO_AF11_DFSDM1 ((uint8_t)0x0B) /* DFSDM1 Alternate Function mapping */ -#define GPIO_AF11_COMP1 ((uint8_t)0x0B) /* COMP1 Alternate Function mapping */ -#define GPIO_AF11_COMP2 ((uint8_t)0x0B) /* COMP2 Alternate Function mapping */ -#define GPIO_AF11_TIM1 ((uint8_t)0x0B) /* TIM1 Alternate Function mapping */ -#define GPIO_AF11_TIM8 ((uint8_t)0x0B) /* TIM8 Alternate Function mapping */ -#define GPIO_AF11_I2C4 ((uint8_t)0x0B) /* I2C4 Alternate Function mapping */ -#if defined(DFSDM2_BASE) -#define GPIO_AF11_DFSDM2 ((uint8_t)0x0B) /* DFSDM2 Alternate Function mapping */ -#endif /* DFSDM2_BASE */ -#if defined(USART10) -#define GPIO_AF11_USART10 ((uint8_t)0x0B) /* USART10 Alternate Function mapping */ -#endif /* USART10 */ -#if defined(UART9) -#define GPIO_AF11_UART9 ((uint8_t)0x0B) /* UART9 Alternate Function mapping */ -#endif /* UART9 */ -#if defined(ETH) -#define GPIO_AF11_ETH ((uint8_t)0x0B) /* ETH Alternate Function mapping */ -#endif /* ETH */ -#if defined(LTDC) -#define GPIO_AF11_LTDC ((uint8_t)0x0B) /* LTDC Alternate Function mapping : available on STM32H7A3xxx/STM32H7B3xxx/STM32H7B0xxx and STM32H72xxx/STM32H73xxx */ -#endif /*LTDC*/ -#if defined(OCTOSPIM) -#define GPIO_AF11_OCTOSPIM_P1 ((uint8_t)0x0B) /* OCTOSPI Manager Port 1 Alternate Function mapping */ -#endif /* OCTOSPIM */ - -/** - * @brief AF 12 selection - */ -#define GPIO_AF12_FMC ((uint8_t)0x0C) /* FMC Alternate Function mapping */ -#define GPIO_AF12_SDMMC1 ((uint8_t)0x0C) /* SDMMC1 Alternate Function mapping */ -#define GPIO_AF12_MDIOS ((uint8_t)0x0C) /* MDIOS Alternate Function mapping */ -#define GPIO_AF12_COMP1 ((uint8_t)0x0C) /* COMP1 Alternate Function mapping */ -#define GPIO_AF12_COMP2 ((uint8_t)0x0C) /* COMP2 Alternate Function mapping */ -#define GPIO_AF12_TIM1 ((uint8_t)0x0C) /* TIM1 Alternate Function mapping */ -#define GPIO_AF12_TIM8 ((uint8_t)0x0C) /* TIM8 Alternate Function mapping */ -#if defined(LTDC) -#define GPIO_AF12_LTDC ((uint8_t)0x0C) /* LTDC Alternate Function mapping */ -#endif /*LTDC*/ -#if defined(USB2_OTG_FS) -#define GPIO_AF12_OTG1_FS ((uint8_t)0x0C) /* OTG1_FS Alternate Function mapping */ -#endif /* USB2_OTG_FS */ -#if defined(OCTOSPIM) -#define GPIO_AF12_OCTOSPIM_P1 ((uint8_t)0x0C) /* OCTOSPI Manager Port 1 Alternate Function mapping */ -#endif /* OCTOSPIM */ - -/** - * @brief AF 13 selection - */ -#define GPIO_AF13_DCMI ((uint8_t)0x0D) /* DCMI Alternate Function mapping */ -#define GPIO_AF13_COMP1 ((uint8_t)0x0D) /* COMP1 Alternate Function mapping */ -#define GPIO_AF13_COMP2 ((uint8_t)0x0D) /* COMP2 Alternate Function mapping */ -#if defined(LTDC) -#define GPIO_AF13_LTDC ((uint8_t)0x0D) /* LTDC Alternate Function mapping */ -#endif /*LTDC*/ -#if defined(DSI) -#define GPIO_AF13_DSI ((uint8_t)0x0D) /* DSI Alternate Function mapping */ -#endif /* DSI */ -#if defined(PSSI) -#define GPIO_AF13_PSSI ((uint8_t)0x0D) /* PSSI Alternate Function mapping */ -#endif /* PSSI */ -#define GPIO_AF13_TIM1 ((uint8_t)0x0D) /* TIM1 Alternate Function mapping */ -#if defined(TIM23) -#define GPIO_AF13_TIM23 ((uint8_t)0x0D) /* TIM23 Alternate Function mapping */ -#endif /*TIM23*/ - -/** - * @brief AF 14 selection - */ -#define GPIO_AF14_LTDC ((uint8_t)0x0E) /* LTDC Alternate Function mapping */ -#define GPIO_AF14_UART5 ((uint8_t)0x0E) /* UART5 Alternate Function mapping */ -#if defined(TIM24) -#define GPIO_AF14_TIM24 ((uint8_t)0x0E) /* TIM24 Alternate Function mapping */ -#endif /*TIM24*/ - -/** - * @brief AF 15 selection - */ -#define GPIO_AF15_EVENTOUT ((uint8_t)0x0F) /* EVENTOUT Alternate Function mapping */ - -#define IS_GPIO_AF(AF) ((AF) <= (uint8_t)0x0F) - - - -/** - * @} - */ - -/** - * @} - */ - -/* Exported macro ------------------------------------------------------------*/ -/** @defgroup GPIOEx_Exported_Macros GPIO Exported Macros - * @{ - */ -/** - * @} - */ - -/* Exported functions --------------------------------------------------------*/ -/** @defgroup GPIOEx_Exported_Functions GPIO Exported Functions - * @{ - */ -/** - * @} - */ -/* Private types -------------------------------------------------------------*/ -/* Private variables ---------------------------------------------------------*/ -/* Private constants ---------------------------------------------------------*/ -/** @defgroup GPIOEx_Private_Constants GPIO Private Constants - * @{ - */ - -/** - * @brief GPIO pin available on the platform - */ -/* Defines the available pins per GPIOs */ -#define GPIOA_PIN_AVAILABLE GPIO_PIN_All -#define GPIOB_PIN_AVAILABLE GPIO_PIN_All -#define GPIOC_PIN_AVAILABLE GPIO_PIN_All -#define GPIOD_PIN_AVAILABLE GPIO_PIN_All -#define GPIOE_PIN_AVAILABLE GPIO_PIN_All -#define GPIOF_PIN_AVAILABLE GPIO_PIN_All -#define GPIOG_PIN_AVAILABLE GPIO_PIN_All -#if defined(GPIOI) -#define GPIOI_PIN_AVAILABLE GPIO_PIN_All -#endif /*GPIOI*/ -#if defined(GPIOI) -#define GPIOJ_PIN_AVAILABLE GPIO_PIN_All -#else -#define GPIOJ_PIN_AVAILABLE (GPIO_PIN_8 | GPIO_PIN_9 | GPIO_PIN_10 | GPIO_PIN_11 ) -#endif /* GPIOI */ -#define GPIOH_PIN_AVAILABLE GPIO_PIN_All -#if defined(GPIOI) -#define GPIOK_PIN_AVAILABLE (GPIO_PIN_0 | GPIO_PIN_1 | GPIO_PIN_2 | GPIO_PIN_3 | GPIO_PIN_4 | \ - GPIO_PIN_5 | GPIO_PIN_6 | GPIO_PIN_7) -#else -#define GPIOK_PIN_AVAILABLE (GPIO_PIN_0 | GPIO_PIN_1 | GPIO_PIN_2 ) -#endif /* GPIOI */ - -/** - * @} - */ - -/* Private macros ------------------------------------------------------------*/ -/** @defgroup GPIOEx_Private_Macros GPIO Private Macros - * @{ - */ -/** @defgroup GPIOEx_Get_Port_Index GPIO Get Port Index - * @{ - */ -#if defined(GPIOI) -#define GPIO_GET_INDEX(__GPIOx__) (((__GPIOx__) == (GPIOA))? 0UL :\ - ((__GPIOx__) == (GPIOB))? 1UL :\ - ((__GPIOx__) == (GPIOC))? 2UL :\ - ((__GPIOx__) == (GPIOD))? 3UL :\ - ((__GPIOx__) == (GPIOE))? 4UL :\ - ((__GPIOx__) == (GPIOF))? 5UL :\ - ((__GPIOx__) == (GPIOG))? 6UL :\ - ((__GPIOx__) == (GPIOH))? 7UL :\ - ((__GPIOx__) == (GPIOI))? 8UL :\ - ((__GPIOx__) == (GPIOJ))? 9UL : 10UL) -#else -#define GPIO_GET_INDEX(__GPIOx__) (((__GPIOx__) == (GPIOA))? 0UL :\ - ((__GPIOx__) == (GPIOB))? 1UL :\ - ((__GPIOx__) == (GPIOC))? 2UL :\ - ((__GPIOx__) == (GPIOD))? 3UL :\ - ((__GPIOx__) == (GPIOE))? 4UL :\ - ((__GPIOx__) == (GPIOF))? 5UL :\ - ((__GPIOx__) == (GPIOG))? 6UL :\ - ((__GPIOx__) == (GPIOH))? 7UL :\ - ((__GPIOx__) == (GPIOJ))? 9UL : 10UL) -#endif /* GPIOI */ - -/** - * @} - */ - -/** @defgroup GPIOEx_IS_Alternat_function_selection GPIO Check Alternate Function - * @{ - */ -/** - * @} - */ - -/** - * @} - */ - -/* Private functions ---------------------------------------------------------*/ -/** @defgroup GPIOEx_Private_Functions GPIO Private Functions - * @{ - */ - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* STM32H7xx_HAL_GPIO_EX_H */ - -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/panda/board/stm32h7/inc/system_stm32h7xx.h b/panda/board/stm32h7/inc/system_stm32h7xx.h deleted file mode 100644 index dd75af6..0000000 --- a/panda/board/stm32h7/inc/system_stm32h7xx.h +++ /dev/null @@ -1,105 +0,0 @@ -/** - ****************************************************************************** - * @file system_stm32h7xx.h - * @author MCD Application Team - * @brief CMSIS Cortex-Mx Device System Source File for STM32H7xx devices. - ****************************************************************************** - * @attention - * - *

© Copyright (c) 2017 STMicroelectronics. - * All rights reserved.

- * - * This software component is licensed by ST under BSD 3-Clause license, - * the "License"; You may not use this file except in compliance with the - * License. You may obtain a copy of the License at: - * opensource.org/licenses/BSD-3-Clause - * - ****************************************************************************** - */ - -/** @addtogroup CMSIS - * @{ - */ - -/** @addtogroup stm32h7xx_system - * @{ - */ - -/** - * @brief Define to prevent recursive inclusion - */ -#ifndef SYSTEM_STM32H7XX_H -#define SYSTEM_STM32H7XX_H - -#ifdef __cplusplus - extern "C" { -#endif - -/** @addtogroup STM32H7xx_System_Includes - * @{ - */ - -/** - * @} - */ - - -/** @addtogroup STM32H7xx_System_Exported_types - * @{ - */ - /* This variable is updated in three ways: - 1) by calling CMSIS function SystemCoreClockUpdate() - 2) by calling HAL API function HAL_RCC_GetSysClockFreq() - 3) each time HAL_RCC_ClockConfig() is called to configure the system clock frequency - Note: If you use this function to configure the system clock; then there - is no need to call the 2 first functions listed above, since SystemCoreClock - variable is updated automatically. - */ -extern uint32_t SystemCoreClock; /*!< System Domain1 Clock Frequency */ -extern uint32_t SystemD2Clock; /*!< System Domain2 Clock Frequency */ -extern const uint8_t D1CorePrescTable[16] ; /*!< D1CorePrescTable prescalers table values */ - -/** - * @} - */ - -/** @addtogroup STM32H7xx_System_Exported_Constants - * @{ - */ - -/** - * @} - */ - -/** @addtogroup STM32H7xx_System_Exported_Macros - * @{ - */ - -/** - * @} - */ - -/** @addtogroup STM32H7xx_System_Exported_Functions - * @{ - */ - -extern void SystemInit(void); -extern void SystemCoreClockUpdate(void); -/** - * @} - */ - -#ifdef __cplusplus -} -#endif - -#endif /* SYSTEM_STM32H7XX_H */ - -/** - * @} - */ - -/** - * @} - */ -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/panda/board/stm32h7/interrupt_handlers.h b/panda/board/stm32h7/interrupt_handlers.h deleted file mode 100644 index fb1298d..0000000 --- a/panda/board/stm32h7/interrupt_handlers.h +++ /dev/null @@ -1,76 +0,0 @@ -// ********************* Bare interrupt handlers ********************* -// Interrupts for STM32H7x5 - -void WWDG_IRQHandler(void) {handle_interrupt(WWDG_IRQn);} -void PVD_AVD_IRQHandler(void) {handle_interrupt(PVD_AVD_IRQn);} -void TAMP_STAMP_IRQHandler(void) {handle_interrupt(TAMP_STAMP_IRQn);} -void RTC_WKUP_IRQHandler(void) {handle_interrupt(RTC_WKUP_IRQn);} -void FLASH_IRQHandler(void) {handle_interrupt(FLASH_IRQn);} -void RCC_IRQHandler(void) {handle_interrupt(RCC_IRQn);} -void EXTI0_IRQHandler(void) {handle_interrupt(EXTI0_IRQn);} -void EXTI1_IRQHandler(void) {handle_interrupt(EXTI1_IRQn);} -void EXTI2_IRQHandler(void) {handle_interrupt(EXTI2_IRQn);} -void EXTI3_IRQHandler(void) {handle_interrupt(EXTI3_IRQn);} -void EXTI4_IRQHandler(void) {handle_interrupt(EXTI4_IRQn);} -void DMA1_Stream0_IRQHandler(void) {handle_interrupt(DMA1_Stream0_IRQn);} -void DMA1_Stream1_IRQHandler(void) {handle_interrupt(DMA1_Stream1_IRQn);} -void DMA1_Stream2_IRQHandler(void) {handle_interrupt(DMA1_Stream2_IRQn);} -void DMA1_Stream3_IRQHandler(void) {handle_interrupt(DMA1_Stream3_IRQn);} -void DMA1_Stream4_IRQHandler(void) {handle_interrupt(DMA1_Stream4_IRQn);} -void DMA1_Stream5_IRQHandler(void) {handle_interrupt(DMA1_Stream5_IRQn);} -void DMA1_Stream6_IRQHandler(void) {handle_interrupt(DMA1_Stream6_IRQn);} -void ADC_IRQHandler(void) {handle_interrupt(ADC_IRQn);} -void EXTI9_5_IRQHandler(void) {handle_interrupt(EXTI9_5_IRQn);} -void TIM1_BRK_IRQHandler(void) {handle_interrupt(TIM1_BRK_IRQn);} -void TIM1_UP_TIM10_IRQHandler(void) {handle_interrupt(TIM1_UP_TIM10_IRQn);} -void TIM1_TRG_COM_IRQHandler(void) {handle_interrupt(TIM1_TRG_COM_IRQn);} -void TIM1_CC_IRQHandler(void) {handle_interrupt(TIM1_CC_IRQn);} -void TIM2_IRQHandler(void) {handle_interrupt(TIM2_IRQn);} -void TIM3_IRQHandler(void) {handle_interrupt(TIM3_IRQn);} -void TIM4_IRQHandler(void) {handle_interrupt(TIM4_IRQn);} -void I2C1_EV_IRQHandler(void) {handle_interrupt(I2C1_EV_IRQn);} -void I2C1_ER_IRQHandler(void) {handle_interrupt(I2C1_ER_IRQn);} -void I2C2_EV_IRQHandler(void) {handle_interrupt(I2C2_EV_IRQn);} -void I2C2_ER_IRQHandler(void) {handle_interrupt(I2C2_ER_IRQn);} -void SPI1_IRQHandler(void) {handle_interrupt(SPI1_IRQn);} -void SPI2_IRQHandler(void) {handle_interrupt(SPI2_IRQn);} -void USART1_IRQHandler(void) {handle_interrupt(USART1_IRQn);} -void USART2_IRQHandler(void) {handle_interrupt(USART2_IRQn);} -void USART3_IRQHandler(void) {handle_interrupt(USART3_IRQn);} -void EXTI15_10_IRQHandler(void) {handle_interrupt(EXTI15_10_IRQn);} -void RTC_Alarm_IRQHandler(void) {handle_interrupt(RTC_Alarm_IRQn);} -void TIM8_BRK_TIM12_IRQHandler(void) {handle_interrupt(TIM8_BRK_TIM12_IRQn);} -void TIM8_UP_TIM13_IRQHandler(void) {handle_interrupt(TIM8_UP_TIM13_IRQn);} -void TIM8_TRG_COM_TIM14_IRQHandler(void) {handle_interrupt(TIM8_TRG_COM_TIM14_IRQn);} -void TIM8_CC_IRQHandler(void) {handle_interrupt(TIM8_CC_IRQn);} -void DMA1_Stream7_IRQHandler(void) {handle_interrupt(DMA1_Stream7_IRQn);} -void TIM5_IRQHandler(void) {handle_interrupt(TIM5_IRQn);} -void SPI3_IRQHandler(void) {handle_interrupt(SPI3_IRQn);} -void SPI4_IRQHandler(void) {handle_interrupt(SPI4_IRQn);} -void UART4_IRQHandler(void) {handle_interrupt(UART4_IRQn);} -void UART5_IRQHandler(void) {handle_interrupt(UART5_IRQn);} -void TIM6_DAC_IRQHandler(void) {handle_interrupt(TIM6_DAC_IRQn);} -void TIM7_IRQHandler(void) {handle_interrupt(TIM7_IRQn);} -void DMA2_Stream0_IRQHandler(void) {handle_interrupt(DMA2_Stream0_IRQn);} -void DMA2_Stream1_IRQHandler(void) {handle_interrupt(DMA2_Stream1_IRQn);} -void DMA2_Stream2_IRQHandler(void) {handle_interrupt(DMA2_Stream2_IRQn);} -void DMA2_Stream3_IRQHandler(void) {handle_interrupt(DMA2_Stream3_IRQn);} -void DMA2_Stream4_IRQHandler(void) {handle_interrupt(DMA2_Stream4_IRQn);} -void DMA2_Stream5_IRQHandler(void) {handle_interrupt(DMA2_Stream5_IRQn);} -void DMA2_Stream6_IRQHandler(void) {handle_interrupt(DMA2_Stream6_IRQn);} -void DMA2_Stream7_IRQHandler(void) {handle_interrupt(DMA2_Stream7_IRQn);} -void USART6_IRQHandler(void) {handle_interrupt(USART6_IRQn);} -void I2C3_EV_IRQHandler(void) {handle_interrupt(I2C3_EV_IRQn);} -void I2C3_ER_IRQHandler(void) {handle_interrupt(I2C3_ER_IRQn);} -void FDCAN1_IT0_IRQHandler(void) {handle_interrupt(FDCAN1_IT0_IRQn);} -void FDCAN1_IT1_IRQHandler(void) {handle_interrupt(FDCAN1_IT1_IRQn);} -void FDCAN2_IT0_IRQHandler(void) {handle_interrupt(FDCAN2_IT0_IRQn);} -void FDCAN2_IT1_IRQHandler(void) {handle_interrupt(FDCAN2_IT1_IRQn);} -void FDCAN3_IT0_IRQHandler(void) {handle_interrupt(FDCAN3_IT0_IRQn);} -void FDCAN3_IT1_IRQHandler(void) {handle_interrupt(FDCAN3_IT1_IRQn);} -void FDCAN_CAL_IRQHandler(void) {handle_interrupt(FDCAN_CAL_IRQn);} -void OTG_HS_EP1_OUT_IRQHandler(void) {handle_interrupt(OTG_HS_EP1_OUT_IRQn);} -void OTG_HS_EP1_IN_IRQHandler(void) {handle_interrupt(OTG_HS_EP1_IN_IRQn);} -void OTG_HS_WKUP_IRQHandler(void) {handle_interrupt(OTG_HS_WKUP_IRQn);} -void OTG_HS_IRQHandler(void) {handle_interrupt(OTG_HS_IRQn);} -void UART7_IRQHandler(void) {handle_interrupt(UART7_IRQn);} diff --git a/panda/board/stm32h7/lladc.h b/panda/board/stm32h7/lladc.h deleted file mode 100644 index 01342a4..0000000 --- a/panda/board/stm32h7/lladc.h +++ /dev/null @@ -1,39 +0,0 @@ - -void adc_init(void) { - ADC1->CR &= ~(ADC_CR_DEEPPWD); //Reset deep-power-down mode - ADC1->CR |= ADC_CR_ADVREGEN; // Enable ADC regulator - while(!(ADC1->ISR & ADC_ISR_LDORDY)); - - ADC1->CR &= ~(ADC_CR_ADCALDIF); // Choose single-ended calibration - ADC1->CR |= ADC_CR_ADCALLIN; // Lineriality calibration - ADC1->CR |= ADC_CR_ADCAL; // Start calibrtation - while((ADC1->CR & ADC_CR_ADCAL) != 0); - - ADC1->ISR |= ADC_ISR_ADRDY; - ADC1->CR |= ADC_CR_ADEN; - while(!(ADC1->ISR & ADC_ISR_ADRDY)); -} - -uint16_t adc_get_raw(uint8_t channel) { - uint16_t res = 0U; - ADC1->SQR1 &= ~(ADC_SQR1_L); - ADC1->SQR1 = ((uint32_t) channel << 6U); - - ADC1->SMPR1 = (0x2U << (channel * 3U)); - ADC1->PCSEL_RES0 = (0x1UL << channel); - ADC1->CFGR2 = (127U << ADC_CFGR2_OVSR_Pos) | (0x7U << ADC_CFGR2_OVSS_Pos) | ADC_CFGR2_ROVSE; - - ADC1->CR |= ADC_CR_ADSTART; - while (!(ADC1->ISR & ADC_ISR_EOC)); - - res = ADC1->DR; - - while (!(ADC1->ISR & ADC_ISR_EOS)); - ADC1->ISR |= ADC_ISR_EOS; - - return res; -} - -uint16_t adc_get_mV(uint8_t channel) { - return (adc_get_raw(channel) * current_board->avdd_mV) / 65535U; -} diff --git a/panda/board/stm32h7/lldac.h b/panda/board/stm32h7/lldac.h deleted file mode 100644 index 5726f62..0000000 --- a/panda/board/stm32h7/lldac.h +++ /dev/null @@ -1,42 +0,0 @@ -void dac_init(DAC_TypeDef *dac, uint8_t channel, bool dma) { - register_set(&dac->CR, 0U, 0xFFFFU); - register_set(&dac->MCR, 0U, 0xFFFFU); - - switch(channel) { - case 1: - if (dma) { - register_set_bits(&dac->CR, DAC_CR_DMAEN1); - // register_set(&DAC->CR, (6U << DAC_CR_TSEL1_Pos), DAC_CR_TSEL1); - register_set_bits(&dac->CR, DAC_CR_TEN1); - } else { - register_clear_bits(&dac->CR, DAC_CR_DMAEN1); - } - register_set_bits(&dac->CR, DAC_CR_EN1); - break; - case 2: - if (dma) { - register_set_bits(&dac->CR, DAC_CR_DMAEN2); - } else { - register_clear_bits(&dac->CR, DAC_CR_DMAEN2); - } - register_set_bits(&dac->CR, DAC_CR_EN2); - break; - default: - break; - } -} - -// Set channel 1 value, in mV -void dac_set(DAC_TypeDef *dac, uint8_t channel, uint32_t value) { - uint32_t raw_val = MAX(MIN(value * (1UL << 8U) / 3300U, (1UL << 8U)), 0U); - switch(channel) { - case 1: - register_set(&dac->DHR8R1, raw_val, 0xFFU); - break; - case 2: - register_set(&dac->DHR8R2, raw_val, 0xFFU); - break; - default: - break; - } -} diff --git a/panda/board/stm32h7/llexti.h b/panda/board/stm32h7/llexti.h deleted file mode 100644 index 46d0aca..0000000 --- a/panda/board/stm32h7/llexti.h +++ /dev/null @@ -1,63 +0,0 @@ -void EXTI_IRQ_Handler(void); - -void exti_irq_init(void) { - if (harness.status == HARNESS_STATUS_FLIPPED) { - // CAN2_RX IRQ on falling edge (EXTI10) - current_board->enable_can_transceiver(3U, false); - SYSCFG->EXTICR[2] &= ~(SYSCFG_EXTICR3_EXTI10_Msk); - SYSCFG->EXTICR[2] |= (SYSCFG_EXTICR3_EXTI10_PG); - EXTI->IMR1 |= EXTI_IMR1_IM10; - EXTI->RTSR1 &= ~EXTI_RTSR1_TR10; // rising edge - EXTI->FTSR1 |= EXTI_FTSR1_TR10; // falling edge - - // IRQ on falling edge for PA1 (SBU2, EXTI1) - SYSCFG->EXTICR[0] &= ~(SYSCFG_EXTICR1_EXTI1_Msk); - SYSCFG->EXTICR[0] |= (SYSCFG_EXTICR1_EXTI1_PA); - EXTI->IMR1 |= EXTI_IMR1_IM1; - EXTI->RTSR1 &= ~EXTI_RTSR1_TR1; // rising edge - EXTI->FTSR1 |= EXTI_FTSR1_TR1; // falling edge - REGISTER_INTERRUPT(EXTI1_IRQn, EXTI_IRQ_Handler, 100U, FAULT_INTERRUPT_RATE_EXTI) - NVIC_EnableIRQ(EXTI1_IRQn); - REGISTER_INTERRUPT(EXTI15_10_IRQn, EXTI_IRQ_Handler, 100U, FAULT_INTERRUPT_RATE_EXTI) - NVIC_EnableIRQ(EXTI15_10_IRQn); - } else { - // CAN0_RX IRQ on falling edge (EXTI8) - current_board->enable_can_transceiver(1U, false); - SYSCFG->EXTICR[2] &= ~(SYSCFG_EXTICR3_EXTI8_Msk); - SYSCFG->EXTICR[2] |= (SYSCFG_EXTICR3_EXTI8_PB); - EXTI->IMR1 |= EXTI_IMR1_IM8; - EXTI->RTSR1 &= ~EXTI_RTSR1_TR8; // rising edge - EXTI->FTSR1 |= EXTI_FTSR1_TR8; // falling edge - - // IRQ on falling edge for PC4 (SBU1, EXTI4) - SYSCFG->EXTICR[1] &= ~(SYSCFG_EXTICR2_EXTI4_Msk); - SYSCFG->EXTICR[1] |= (SYSCFG_EXTICR2_EXTI4_PC); - EXTI->IMR1 |= EXTI_IMR1_IM4; - EXTI->RTSR1 &= ~EXTI_RTSR1_TR4; // rising edge - EXTI->FTSR1 |= EXTI_FTSR1_TR4; // falling edge - REGISTER_INTERRUPT(EXTI4_IRQn, EXTI_IRQ_Handler, 100U, FAULT_INTERRUPT_RATE_EXTI) - NVIC_EnableIRQ(EXTI4_IRQn); - REGISTER_INTERRUPT(EXTI9_5_IRQn, EXTI_IRQ_Handler, 100U, FAULT_INTERRUPT_RATE_EXTI) - NVIC_EnableIRQ(EXTI9_5_IRQn); - } -} - -bool check_exti_irq(void) { - return ((EXTI->PR1 & EXTI_PR1_PR8) || (EXTI->PR1 & EXTI_PR1_PR10) || (EXTI->PR1 & EXTI_PR1_PR1) || (EXTI->PR1 & EXTI_PR1_PR4)); -} - -void exti_irq_clear(void) { - // Clear pending bits - EXTI->PR1 |= EXTI_PR1_PR8; - EXTI->PR1 |= EXTI_PR1_PR10; - EXTI->PR1 |= EXTI_PR1_PR4; - EXTI->PR1 |= EXTI_PR1_PR1; // works - EXTI->PR1 |= EXTI_PR1_PR19; // works - - // Disable all active EXTI IRQs - EXTI->IMR1 &= ~EXTI_IMR1_IM8; - EXTI->IMR1 &= ~EXTI_IMR1_IM10; - EXTI->IMR1 &= ~EXTI_IMR1_IM4; - EXTI->IMR1 &= ~EXTI_IMR1_IM1; - EXTI->IMR1 &= ~EXTI_IMR1_IM19; -} diff --git a/panda/board/stm32h7/llfan.h b/panda/board/stm32h7/llfan.h deleted file mode 100644 index dce6225..0000000 --- a/panda/board/stm32h7/llfan.h +++ /dev/null @@ -1,23 +0,0 @@ -// TACH interrupt handler -void EXTI2_IRQ_Handler(void) { - volatile unsigned int pr = EXTI->PR1 & (1U << 2); - if ((pr & (1U << 2)) != 0U) { - fan_state.tach_counter++; - } - EXTI->PR1 = (1U << 2); -} - -void llfan_init(void) { - // 5000RPM * 4 tach edges / 60 seconds - REGISTER_INTERRUPT(EXTI2_IRQn, EXTI2_IRQ_Handler, 700U, FAULT_INTERRUPT_RATE_TACH) - - // Init PWM speed control - pwm_init(TIM3, 3); - - // Init TACH interrupt - register_set(&(SYSCFG->EXTICR[0]), SYSCFG_EXTICR1_EXTI2_PD, 0xF00U); - register_set_bits(&(EXTI->IMR1), (1U << 2)); - register_set_bits(&(EXTI->RTSR1), (1U << 2)); - register_set_bits(&(EXTI->FTSR1), (1U << 2)); - NVIC_EnableIRQ(EXTI2_IRQn); -} diff --git a/panda/board/stm32h7/llfdcan.h b/panda/board/stm32h7/llfdcan.h deleted file mode 100644 index 4bb6d3d..0000000 --- a/panda/board/stm32h7/llfdcan.h +++ /dev/null @@ -1,269 +0,0 @@ -// SAE J2284-4 document specifies a bus-line network running at 2 Mbit/s -// SAE J2284-5 document specifies a point-to-point communication running at 5 Mbit/s - -#define CAN_PCLK 80000U // KHz, sourced from PLL1Q -#define BITRATE_PRESCALER 2U // Valid from 250Kbps to 5Mbps with 80Mhz clock -#define CAN_SP_NOMINAL 80U // 80% for both SAE J2284-4 and SAE J2284-5 -#define CAN_SP_DATA_2M 80U // 80% for SAE J2284-4 -#define CAN_SP_DATA_5M 75U // 75% for SAE J2284-5 -#define CAN_QUANTA(speed, prescaler) (CAN_PCLK / ((speed) / 10U * (prescaler))) -#define CAN_SEG1(tq, sp) (((tq) * (sp) / 100U)- 1U) -#define CAN_SEG2(tq, sp) ((tq) * (100U - (sp)) / 100U) - -// FDCAN core settings -#define FDCAN_MESSAGE_RAM_SIZE 0x2800UL -#define FDCAN_START_ADDRESS 0x4000AC00UL -#define FDCAN_OFFSET 3384UL // bytes for each FDCAN module, equally -#define FDCAN_OFFSET_W 846UL // words for each FDCAN module, equally -#define FDCAN_END_ADDRESS 0x4000D3FCUL // Message RAM has a width of 4 bytes - -// FDCAN_RX_FIFO_0_EL_CNT + FDCAN_TX_FIFO_EL_CNT can't exceed 47 elements (47 * 72 bytes = 3,384 bytes) per FDCAN module - -// RX FIFO 0 -#define FDCAN_RX_FIFO_0_EL_CNT 46UL -#define FDCAN_RX_FIFO_0_HEAD_SIZE 8UL // bytes -#define FDCAN_RX_FIFO_0_DATA_SIZE 64UL // bytes -#define FDCAN_RX_FIFO_0_EL_SIZE (FDCAN_RX_FIFO_0_HEAD_SIZE + FDCAN_RX_FIFO_0_DATA_SIZE) -#define FDCAN_RX_FIFO_0_EL_W_SIZE (FDCAN_RX_FIFO_0_EL_SIZE / 4UL) -#define FDCAN_RX_FIFO_0_OFFSET 0UL - -// TX FIFO -#define FDCAN_TX_FIFO_EL_CNT 1UL -#define FDCAN_TX_FIFO_HEAD_SIZE 8UL // bytes -#define FDCAN_TX_FIFO_DATA_SIZE 64UL // bytes -#define FDCAN_TX_FIFO_EL_SIZE (FDCAN_TX_FIFO_HEAD_SIZE + FDCAN_TX_FIFO_DATA_SIZE) -#define FDCAN_TX_FIFO_EL_W_SIZE (FDCAN_TX_FIFO_EL_SIZE / 4UL) -#define FDCAN_TX_FIFO_OFFSET (FDCAN_RX_FIFO_0_OFFSET + (FDCAN_RX_FIFO_0_EL_CNT * FDCAN_RX_FIFO_0_EL_W_SIZE)) - -#define CAN_NAME_FROM_CANIF(CAN_DEV) (((CAN_DEV)==FDCAN1) ? "FDCAN1" : (((CAN_DEV) == FDCAN2) ? "FDCAN2" : "FDCAN3")) -#define CAN_NUM_FROM_CANIF(CAN_DEV) (((CAN_DEV)==FDCAN1) ? 0UL : (((CAN_DEV) == FDCAN2) ? 1UL : 2UL)) - - -void print(const char *a); - -// kbps multiplied by 10 -const uint32_t speeds[] = {100U, 200U, 500U, 1000U, 1250U, 2500U, 5000U, 10000U}; -const uint32_t data_speeds[] = {100U, 200U, 500U, 1000U, 1250U, 2500U, 5000U, 10000U, 20000U, 50000U}; - - -bool fdcan_request_init(FDCAN_GlobalTypeDef *FDCANx) { - bool ret = true; - // Exit from sleep mode - FDCANx->CCCR &= ~(FDCAN_CCCR_CSR); - while ((FDCANx->CCCR & FDCAN_CCCR_CSA) == FDCAN_CCCR_CSA); - - // Request init - uint32_t timeout_counter = 0U; - FDCANx->CCCR |= FDCAN_CCCR_INIT; - while ((FDCANx->CCCR & FDCAN_CCCR_INIT) == 0) { - // Delay for about 1ms - delay(10000); - timeout_counter++; - - if (timeout_counter >= CAN_INIT_TIMEOUT_MS){ - ret = false; - break; - } - } - return ret; -} - -bool fdcan_exit_init(FDCAN_GlobalTypeDef *FDCANx) { - bool ret = true; - - FDCANx->CCCR &= ~(FDCAN_CCCR_INIT); - uint32_t timeout_counter = 0U; - while ((FDCANx->CCCR & FDCAN_CCCR_INIT) != 0) { - // Delay for about 1ms - delay(10000); - timeout_counter++; - - if (timeout_counter >= CAN_INIT_TIMEOUT_MS) { - ret = false; - break; - } - } - return ret; -} - -bool llcan_set_speed(FDCAN_GlobalTypeDef *FDCANx, uint32_t speed, uint32_t data_speed, bool non_iso, bool loopback, bool silent) { - UNUSED(speed); - bool ret = fdcan_request_init(FDCANx); - - if (ret) { - // Enable config change - FDCANx->CCCR |= FDCAN_CCCR_CCE; - - //Reset operation mode to Normal - FDCANx->CCCR &= ~(FDCAN_CCCR_TEST); - FDCANx->TEST &= ~(FDCAN_TEST_LBCK); - FDCANx->CCCR &= ~(FDCAN_CCCR_MON); - FDCANx->CCCR &= ~(FDCAN_CCCR_ASM); - FDCANx->CCCR &= ~(FDCAN_CCCR_NISO); - - // TODO: add as a separate safety mode - // Enable ASM restricted operation(for debug or automatic bitrate switching) - //FDCANx->CCCR |= FDCAN_CCCR_ASM; - - uint8_t prescaler = BITRATE_PRESCALER; - if (speed < 2500U) { - // The only way to support speeds lower than 250Kbit/s (down to 10Kbit/s) - prescaler = BITRATE_PRESCALER * 16U; - } - - // Set the nominal bit timing values - uint32_t tq = CAN_QUANTA(speed, prescaler); - uint32_t sp = CAN_SP_NOMINAL; - uint32_t seg1 = CAN_SEG1(tq, sp); - uint32_t seg2 = CAN_SEG2(tq, sp); - uint8_t sjw = MIN(127U, seg2); - - FDCANx->NBTP = (((sjw & 0x7FU)-1U)<DBTP = (((sjw & 0xFU)-1U)<CCCR |= FDCAN_CCCR_NISO; - } - - // Silent loopback is known as internal loopback in the docs - if (loopback) { - FDCANx->CCCR |= FDCAN_CCCR_TEST; - FDCANx->TEST |= FDCAN_TEST_LBCK; - FDCANx->CCCR |= FDCAN_CCCR_MON; - } - // Silent is known as bus monitoring in the docs - if (silent) { - FDCANx->CCCR |= FDCAN_CCCR_MON; - } - ret = fdcan_exit_init(FDCANx); - if (!ret) { - print(CAN_NAME_FROM_CANIF(FDCANx)); print(" set_speed timed out! (2)\n"); - } - } else { - print(CAN_NAME_FROM_CANIF(FDCANx)); print(" set_speed timed out! (1)\n"); - } - return ret; -} - -void llcan_irq_disable(const FDCAN_GlobalTypeDef *FDCANx) { - if (FDCANx == FDCAN1) { - NVIC_DisableIRQ(FDCAN1_IT0_IRQn); - NVIC_DisableIRQ(FDCAN1_IT1_IRQn); - } else if (FDCANx == FDCAN2) { - NVIC_DisableIRQ(FDCAN2_IT0_IRQn); - NVIC_DisableIRQ(FDCAN2_IT1_IRQn); - } else if (FDCANx == FDCAN3) { - NVIC_DisableIRQ(FDCAN3_IT0_IRQn); - NVIC_DisableIRQ(FDCAN3_IT1_IRQn); - } else { - } -} - -void llcan_irq_enable(const FDCAN_GlobalTypeDef *FDCANx) { - if (FDCANx == FDCAN1) { - NVIC_EnableIRQ(FDCAN1_IT0_IRQn); - NVIC_EnableIRQ(FDCAN1_IT1_IRQn); - } else if (FDCANx == FDCAN2) { - NVIC_EnableIRQ(FDCAN2_IT0_IRQn); - NVIC_EnableIRQ(FDCAN2_IT1_IRQn); - } else if (FDCANx == FDCAN3) { - NVIC_EnableIRQ(FDCAN3_IT0_IRQn); - NVIC_EnableIRQ(FDCAN3_IT1_IRQn); - } else { - } -} - -bool llcan_init(FDCAN_GlobalTypeDef *FDCANx) { - uint32_t can_number = CAN_NUM_FROM_CANIF(FDCANx); - bool ret = fdcan_request_init(FDCANx); - - if (ret) { - // Enable config change - FDCANx->CCCR |= FDCAN_CCCR_CCE; - // Enable automatic retransmission - FDCANx->CCCR &= ~(FDCAN_CCCR_DAR); - // Enable transmission pause feature - FDCANx->CCCR |= FDCAN_CCCR_TXP; - // Disable protocol exception handling - FDCANx->CCCR |= FDCAN_CCCR_PXHD; - // FD with BRS - FDCANx->CCCR |= (FDCAN_CCCR_FDOE | FDCAN_CCCR_BRSE); - - // Set TX mode to FIFO - FDCANx->TXBC &= ~(FDCAN_TXBC_TFQM); - // Configure TX element data size - FDCANx->TXESC |= 0x7U << FDCAN_TXESC_TBDS_Pos; // 64 bytes - //Configure RX FIFO0 element data size - FDCANx->RXESC |= 0x7U << FDCAN_RXESC_F0DS_Pos; - // Disable filtering, accept all valid frames received - FDCANx->XIDFC &= ~(FDCAN_XIDFC_LSE); // No extended filters - FDCANx->SIDFC &= ~(FDCAN_SIDFC_LSS); // No standard filters - FDCANx->GFC &= ~(FDCAN_GFC_RRFE); // Accept extended remote frames - FDCANx->GFC &= ~(FDCAN_GFC_RRFS); // Accept standard remote frames - FDCANx->GFC &= ~(FDCAN_GFC_ANFE); // Accept extended frames to FIFO 0 - FDCANx->GFC &= ~(FDCAN_GFC_ANFS); // Accept standard frames to FIFO 0 - - uint32_t RxFIFO0SA = FDCAN_START_ADDRESS + (can_number * FDCAN_OFFSET); - uint32_t TxFIFOSA = RxFIFO0SA + (FDCAN_RX_FIFO_0_EL_CNT * FDCAN_RX_FIFO_0_EL_SIZE); - - // RX FIFO 0 - FDCANx->RXF0C |= (FDCAN_RX_FIFO_0_OFFSET + (can_number * FDCAN_OFFSET_W)) << FDCAN_RXF0C_F0SA_Pos; - FDCANx->RXF0C |= FDCAN_RX_FIFO_0_EL_CNT << FDCAN_RXF0C_F0S_Pos; - // RX FIFO 0 switch to non-blocking (overwrite) mode - FDCANx->RXF0C |= FDCAN_RXF0C_F0OM; - - // TX FIFO (mode set earlier) - FDCANx->TXBC |= (FDCAN_TX_FIFO_OFFSET + (can_number * FDCAN_OFFSET_W)) << FDCAN_TXBC_TBSA_Pos; - FDCANx->TXBC |= FDCAN_TX_FIFO_EL_CNT << FDCAN_TXBC_TFQS_Pos; - - // Flush allocated RAM - uint32_t EndAddress = TxFIFOSA + (FDCAN_TX_FIFO_EL_CNT * FDCAN_TX_FIFO_EL_SIZE); - for (uint32_t RAMcounter = RxFIFO0SA; RAMcounter < EndAddress; RAMcounter += 4U) { - *(uint32_t *)(RAMcounter) = 0x00000000; - } - - // Enable both interrupts for each module - FDCANx->ILE = (FDCAN_ILE_EINT0 | FDCAN_ILE_EINT1); - - FDCANx->IE &= 0x0U; // Reset all interrupts - // Messages for INT0 - FDCANx->IE |= FDCAN_IE_RF0NE; // Rx FIFO 0 new message - FDCANx->IE |= FDCAN_IE_PEDE | FDCAN_IE_PEAE | FDCAN_IE_BOE | FDCAN_IE_EPE | FDCAN_IE_RF0LE; - - // Messages for INT1 (Only TFE works??) - FDCANx->ILS |= FDCAN_ILS_TFEL; - FDCANx->IE |= FDCAN_IE_TFEE; // Tx FIFO empty - - ret = fdcan_exit_init(FDCANx); - if(!ret) { - print(CAN_NAME_FROM_CANIF(FDCANx)); print(" llcan_init timed out (2)!\n"); - } - - llcan_irq_enable(FDCANx); - - } else { - print(CAN_NAME_FROM_CANIF(FDCANx)); print(" llcan_init timed out (1)!\n"); - } - return ret; -} - -void llcan_clear_send(FDCAN_GlobalTypeDef *FDCANx) { - // from datasheet: "Transmit cancellation is not intended for Tx FIFO operation." - // so we need to clear pending transmission manually by resetting FDCAN core - FDCANx->IR |= 0x3FCFFFFFU; // clear all interrupts - bool ret = llcan_init(FDCANx); - UNUSED(ret); -} diff --git a/panda/board/stm32h7/llflash.h b/panda/board/stm32h7/llflash.h deleted file mode 100644 index b95011a..0000000 --- a/panda/board/stm32h7/llflash.h +++ /dev/null @@ -1,33 +0,0 @@ -bool flash_is_locked(void) { - return (FLASH->CR1 & FLASH_CR_LOCK); -} - -void flash_unlock(void) { - FLASH->KEYR1 = 0x45670123; - FLASH->KEYR1 = 0xCDEF89AB; -} - -bool flash_erase_sector(uint8_t sector, bool unlocked) { - // don't erase the bootloader(sector 0) - if (sector != 0 && sector < 8 && unlocked) { - FLASH->CR1 = (sector << 8) | FLASH_CR_SER; - FLASH->CR1 |= FLASH_CR_START; - while (FLASH->SR1 & FLASH_SR_QW); - return true; - } - return false; -} - -void flash_write_word(void *prog_ptr, uint32_t data) { - uint32_t *pp = prog_ptr; - FLASH->CR1 |= FLASH_CR_PG; - *pp = data; - while (FLASH->SR1 & FLASH_SR_QW); -} - -void flush_write_buffer(void) { - if (FLASH->SR1 & FLASH_SR_WBNE) { - FLASH->CR1 |= FLASH_CR_FW; - while (FLASH->SR1 & FLASH_CR_FW); - } -} diff --git a/panda/board/stm32h7/lli2c.h b/panda/board/stm32h7/lli2c.h deleted file mode 100644 index 1dd4b4c..0000000 --- a/panda/board/stm32h7/lli2c.h +++ /dev/null @@ -1,153 +0,0 @@ - -// TODO: this driver relies heavily on polling, -// if we want it to be more async, we should use interrupts - -#define I2C_TIMEOUT_US 100000U - -// cppcheck-suppress misra-c2012-2.7; not sure why it triggers here? -bool i2c_status_wait(const volatile uint32_t *reg, uint32_t mask, uint32_t val) { - uint32_t start_time = microsecond_timer_get(); - while(((*reg & mask) != val) && (get_ts_elapsed(microsecond_timer_get(), start_time) < I2C_TIMEOUT_US)); - return ((*reg & mask) == val); -} - -bool i2c_write_reg(I2C_TypeDef *I2C, uint8_t addr, uint8_t reg, uint8_t value) { - // Setup transfer and send START + addr - bool ret = false; - for(uint32_t i=0U; i<10U; i++) { - register_clear_bits(&I2C->CR2, I2C_CR2_ADD10); - I2C->CR2 = ((addr << 1U) & I2C_CR2_SADD_Msk); - register_clear_bits(&I2C->CR2, I2C_CR2_RD_WRN); - register_set_bits(&I2C->CR2, I2C_CR2_AUTOEND); - I2C->CR2 |= (2 << I2C_CR2_NBYTES_Pos); - - I2C->CR2 |= I2C_CR2_START; - if(!i2c_status_wait(&I2C->CR2, I2C_CR2_START, 0U)) { - continue; - } - - // check if we lost arbitration - if ((I2C->ISR & I2C_ISR_ARLO) != 0U) { - register_set_bits(&I2C->ICR, I2C_ICR_ARLOCF); - } else { - ret = true; - break; - } - } - - if (!ret) { - goto end; - } - - // Send data - ret = i2c_status_wait(&I2C->ISR, I2C_ISR_TXIS, I2C_ISR_TXIS); - if(!ret) { - goto end; - } - I2C->TXDR = reg; - - ret = i2c_status_wait(&I2C->ISR, I2C_ISR_TXIS, I2C_ISR_TXIS); - if(!ret) { - goto end; - } - I2C->TXDR = value; - -end: - return ret; -} - -bool i2c_read_reg(I2C_TypeDef *I2C, uint8_t addr, uint8_t reg, uint8_t *value) { - // Setup transfer and send START + addr - bool ret = false; - for(uint32_t i=0U; i<10U; i++) { - register_clear_bits(&I2C->CR2, I2C_CR2_ADD10); - I2C->CR2 = ((addr << 1U) & I2C_CR2_SADD_Msk); - register_clear_bits(&I2C->CR2, I2C_CR2_RD_WRN); - register_clear_bits(&I2C->CR2, I2C_CR2_AUTOEND); - I2C->CR2 |= (1 << I2C_CR2_NBYTES_Pos); - - I2C->CR2 |= I2C_CR2_START; - if(!i2c_status_wait(&I2C->CR2, I2C_CR2_START, 0U)) { - continue; - } - - // check if we lost arbitration - if ((I2C->ISR & I2C_ISR_ARLO) != 0U) { - register_set_bits(&I2C->ICR, I2C_ICR_ARLOCF); - } else { - ret = true; - break; - } - } - - if (!ret) { - goto end; - } - - // Send data - ret = i2c_status_wait(&I2C->ISR, I2C_ISR_TXIS, I2C_ISR_TXIS); - if(!ret) { - goto end; - } - I2C->TXDR = reg; - - // Restart - I2C->CR2 = (((addr << 1) | 0x1U) & I2C_CR2_SADD_Msk) | (1U << I2C_CR2_NBYTES_Pos) | I2C_CR2_RD_WRN | I2C_CR2_START; - ret = i2c_status_wait(&I2C->CR2, I2C_CR2_START, 0U); - if(!ret) { - goto end; - } - - // check if we lost arbitration - if ((I2C->ISR & I2C_ISR_ARLO) != 0U) { - register_set_bits(&I2C->ICR, I2C_ICR_ARLOCF); - ret = false; - goto end; - } - - // Read data - ret = i2c_status_wait(&I2C->ISR, I2C_ISR_RXNE, I2C_ISR_RXNE); - if(!ret) { - goto end; - } - *value = I2C->RXDR; - - // Stop - I2C->CR2 |= I2C_CR2_STOP; - -end: - return ret; -} - -bool i2c_set_reg_bits(I2C_TypeDef *I2C, uint8_t address, uint8_t regis, uint8_t bits) { - uint8_t value; - bool ret = i2c_read_reg(I2C, address, regis, &value); - if(ret) { - ret = i2c_write_reg(I2C, address, regis, value | bits); - } - return ret; -} - -bool i2c_clear_reg_bits(I2C_TypeDef *I2C, uint8_t address, uint8_t regis, uint8_t bits) { - uint8_t value; - bool ret = i2c_read_reg(I2C, address, regis, &value); - if(ret) { - ret = i2c_write_reg(I2C, address, regis, value & (uint8_t) (~bits)); - } - return ret; -} - -bool i2c_set_reg_mask(I2C_TypeDef *I2C, uint8_t address, uint8_t regis, uint8_t value, uint8_t mask) { - uint8_t old_value; - bool ret = i2c_read_reg(I2C, address, regis, &old_value); - if(ret) { - ret = i2c_write_reg(I2C, address, regis, (old_value & (uint8_t) (~mask)) | (value & mask)); - } - return ret; -} - -void i2c_init(I2C_TypeDef *I2C) { - // 100kHz clock speed - I2C->TIMINGR = 0x107075B0; - I2C->CR1 = I2C_CR1_PE; -} \ No newline at end of file diff --git a/panda/board/stm32h7/llrtc.h b/panda/board/stm32h7/llrtc.h deleted file mode 100644 index 03787d0..0000000 --- a/panda/board/stm32h7/llrtc.h +++ /dev/null @@ -1,69 +0,0 @@ -void enable_bdomain_protection(void) { - register_clear_bits(&(PWR->CR1), PWR_CR1_DBP); -} - -void disable_bdomain_protection(void) { - register_set_bits(&(PWR->CR1), PWR_CR1_DBP); -} - -void rtc_init(void){ - uint32_t bdcr_opts = RCC_BDCR_RTCEN; - uint32_t bdcr_mask = (RCC_BDCR_RTCEN | RCC_BDCR_RTCSEL); - if (current_board->has_rtc_battery) { - bdcr_opts |= (RCC_BDCR_LSEDRV_1 | RCC_BDCR_RTCSEL_0 | RCC_BDCR_LSEON); - bdcr_mask |= (RCC_BDCR_LSEDRV | RCC_BDCR_LSEBYP | RCC_BDCR_LSEON); - } else { - bdcr_opts |= RCC_BDCR_RTCSEL_1; - RCC->CSR |= RCC_CSR_LSION; - while((RCC->CSR & RCC_CSR_LSIRDY) == 0){} - } - - // Initialize RTC module and clock if not done already. - if((RCC->BDCR & bdcr_mask) != bdcr_opts){ - print("Initializing RTC\n"); - // Reset backup domain - register_set_bits(&(RCC->BDCR), RCC_BDCR_BDRST); - - // Disable write protection - disable_bdomain_protection(); - - // Clear backup domain reset - register_clear_bits(&(RCC->BDCR), RCC_BDCR_BDRST); - - // Set RTC options - register_set(&(RCC->BDCR), bdcr_opts, bdcr_mask); - - // Enable write protection - enable_bdomain_protection(); - } -} - -void rtc_wakeup_init(void) { - EXTI->IMR1 |= EXTI_IMR1_IM19; - EXTI->RTSR1 |= EXTI_RTSR1_TR19; // rising edge - EXTI->FTSR1 &= ~EXTI_FTSR1_TR19; // falling edge - - NVIC_DisableIRQ(RTC_WKUP_IRQn); - - // Disable write protection - disable_bdomain_protection(); - RTC->WPR = 0xCA; - RTC->WPR = 0x53; - - RTC->CR &= ~RTC_CR_WUTE; - while((RTC->ISR & RTC_ISR_WUTWF) == 0){} - - RTC->CR &= ~RTC_CR_WUTIE; - RTC->ISR &= ~RTC_ISR_WUTF; - //PWR->CR1 |= PWR_CR1_CWUF; - - RTC->WUTR = DEEPSLEEP_WAKEUP_DELAY; - // Wakeup timer interrupt enable, wakeup timer enable, select 1Hz rate - RTC->CR |= RTC_CR_WUTE | RTC_CR_WUTIE | RTC_CR_WUCKSEL_2; - - // Re-enable write protection - RTC->WPR = 0x00; - enable_bdomain_protection(); - - NVIC_EnableIRQ(RTC_WKUP_IRQn); -} diff --git a/panda/board/stm32h7/llspi.h b/panda/board/stm32h7/llspi.h deleted file mode 100644 index 1947803..0000000 --- a/panda/board/stm32h7/llspi.h +++ /dev/null @@ -1,106 +0,0 @@ -// master -> panda DMA start -void llspi_mosi_dma(uint8_t *addr, int len) { - // disable DMA + SPI - register_clear_bits(&(SPI4->CFG1), SPI_CFG1_RXDMAEN); - DMA2_Stream2->CR &= ~DMA_SxCR_EN; - register_clear_bits(&(SPI4->CR1), SPI_CR1_SPE); - - // drain the bus - while ((SPI4->SR & SPI_SR_RXP) != 0U) { - volatile uint8_t dat = SPI4->RXDR; - (void)dat; - } - - // clear all pending - SPI4->IFCR |= (0x1FFU << 3U); - register_set(&(SPI4->IER), 0, 0x3FFU); - - // setup destination and length - register_set(&(DMA2_Stream2->M0AR), (uint32_t)addr, 0xFFFFFFFFU); - DMA2_Stream2->NDTR = len; - - // enable DMA + SPI - DMA2_Stream2->CR |= DMA_SxCR_EN; - register_set_bits(&(SPI4->CFG1), SPI_CFG1_RXDMAEN); - register_set_bits(&(SPI4->CR1), SPI_CR1_SPE); -} - -// panda -> master DMA start -void llspi_miso_dma(uint8_t *addr, int len) { - // disable DMA + SPI - DMA2_Stream3->CR &= ~DMA_SxCR_EN; - register_clear_bits(&(SPI4->CFG1), SPI_CFG1_TXDMAEN); - register_clear_bits(&(SPI4->CR1), SPI_CR1_SPE); - - // setup source and length - register_set(&(DMA2_Stream3->M0AR), (uint32_t)addr, 0xFFFFFFFFU); - DMA2_Stream3->NDTR = len; - - // clear under-run while we were reading - SPI4->IFCR |= (0x1FFU << 3U); - - // setup interrupt on TXC - register_set(&(SPI4->IER), (1U << SPI_IER_EOTIE_Pos), 0x3FFU); - - // enable DMA + SPI - register_set_bits(&(SPI4->CFG1), SPI_CFG1_TXDMAEN); - DMA2_Stream3->CR |= DMA_SxCR_EN; - register_set_bits(&(SPI4->CR1), SPI_CR1_SPE); -} - -// master -> panda DMA finished -void DMA2_Stream2_IRQ_Handler(void) { - // Clear interrupt flag - DMA2->LIFCR = DMA_LIFCR_CTCIF2; - - spi_rx_done(); -} - -// panda -> master DMA finished -void DMA2_Stream3_IRQ_Handler(void) { - ENTER_CRITICAL(); - - DMA2->LIFCR = DMA_LIFCR_CTCIF3; - spi_tx_dma_done = true; - - EXIT_CRITICAL(); -} - -// panda TX finished -void SPI4_IRQ_Handler(void) { - // clear flag - SPI4->IFCR |= (0x1FFU << 3U); - - if (spi_tx_dma_done && ((SPI4->SR & SPI_SR_TXC) != 0)) { - spi_tx_dma_done = false; - spi_tx_done(false); - } -} - - -void llspi_init(void) { - REGISTER_INTERRUPT(SPI4_IRQn, SPI4_IRQ_Handler, (SPI_IRQ_RATE * 2U), FAULT_INTERRUPT_RATE_SPI) - REGISTER_INTERRUPT(DMA2_Stream2_IRQn, DMA2_Stream2_IRQ_Handler, SPI_IRQ_RATE, FAULT_INTERRUPT_RATE_SPI_DMA) - REGISTER_INTERRUPT(DMA2_Stream3_IRQn, DMA2_Stream3_IRQ_Handler, SPI_IRQ_RATE, FAULT_INTERRUPT_RATE_SPI_DMA) - - // Setup MOSI DMA - register_set(&(DMAMUX1_Channel10->CCR), 83U, 0xFFFFFFFFU); - register_set(&(DMA2_Stream2->CR), (DMA_SxCR_MINC | DMA_SxCR_TCIE), 0x1E077EFEU); - register_set(&(DMA2_Stream2->PAR), (uint32_t)&(SPI4->RXDR), 0xFFFFFFFFU); - - // Setup MISO DMA, memory -> peripheral - register_set(&(DMAMUX1_Channel11->CCR), 84U, 0xFFFFFFFFU); - register_set(&(DMA2_Stream3->CR), (DMA_SxCR_MINC | DMA_SxCR_DIR_0 | DMA_SxCR_TCIE), 0x1E077EFEU); - register_set(&(DMA2_Stream3->PAR), (uint32_t)&(SPI4->TXDR), 0xFFFFFFFFU); - - // Enable SPI - register_set(&(SPI4->IER), 0, 0x3FFU); - register_set(&(SPI4->CFG1), (7U << SPI_CFG1_DSIZE_Pos), SPI_CFG1_DSIZE_Msk); - register_set(&(SPI4->UDRDR), 0xcd, 0xFFFFU); // set under-run value for debugging - register_set(&(SPI4->CR1), SPI_CR1_SPE, 0xFFFFU); - register_set(&(SPI4->CR2), 0, 0xFFFFU); - - NVIC_EnableIRQ(DMA2_Stream2_IRQn); - NVIC_EnableIRQ(DMA2_Stream3_IRQn); - NVIC_EnableIRQ(SPI4_IRQn); -} diff --git a/panda/board/stm32h7/lluart.h b/panda/board/stm32h7/lluart.h deleted file mode 100644 index 0ad7b6a..0000000 --- a/panda/board/stm32h7/lluart.h +++ /dev/null @@ -1,106 +0,0 @@ -void uart_rx_ring(uart_ring *q){ - // Do not read out directly if DMA enabled - ENTER_CRITICAL(); - - // Read out RX buffer - uint8_t c = q->uart->RDR; // This read after reading SR clears a bunch of interrupts - - uint16_t next_w_ptr = (q->w_ptr_rx + 1U) % q->rx_fifo_size; - - if ((next_w_ptr == q->r_ptr_rx) && q->overwrite) { - // overwrite mode: drop oldest byte - q->r_ptr_rx = (q->r_ptr_rx + 1U) % q->rx_fifo_size; - } - - // Do not overwrite buffer data - if (next_w_ptr != q->r_ptr_rx) { - q->elems_rx[q->w_ptr_rx] = c; - q->w_ptr_rx = next_w_ptr; - if (q->callback != NULL) { - q->callback(q); - } - } - - EXIT_CRITICAL(); -} - -void uart_tx_ring(uart_ring *q){ - ENTER_CRITICAL(); - // Send out next byte of TX buffer - if (q->w_ptr_tx != q->r_ptr_tx) { - // Only send if transmit register is empty (aka last byte has been sent) - if ((q->uart->ISR & USART_ISR_TXE_TXFNF) != 0) { - q->uart->TDR = q->elems_tx[q->r_ptr_tx]; // This clears TXE - q->r_ptr_tx = (q->r_ptr_tx + 1U) % q->tx_fifo_size; - } - - // Enable TXE interrupt if there is still data to be sent - if(q->r_ptr_tx != q->w_ptr_tx){ - q->uart->CR1 |= USART_CR1_TXEIE; - } else { - q->uart->CR1 &= ~USART_CR1_TXEIE; - } - } - EXIT_CRITICAL(); -} - -void uart_set_baud(USART_TypeDef *u, unsigned int baud) { - // UART7 is connected to APB1 at 60MHz - u->BRR = 60000000U / baud; -} - -// This read after reading ISR clears all error interrupts. We don't want compiler warnings, nor optimizations -#define UART_READ_RDR(uart) volatile uint8_t t = (uart)->RDR; UNUSED(t); - -void uart_interrupt_handler(uart_ring *q) { - ENTER_CRITICAL(); - - // Read UART status. This is also the first step necessary in clearing most interrupts - uint32_t status = q->uart->ISR; - - // If RXFNE is set, perform a read. This clears RXFNE, ORE, IDLE, NF and FE - if((status & USART_ISR_RXNE_RXFNE) != 0U){ - uart_rx_ring(q); - } - - // Detect errors and clear them - uint32_t err = (status & USART_ISR_ORE) | (status & USART_ISR_NE) | (status & USART_ISR_FE) | (status & USART_ISR_PE); - if(err != 0U){ - #ifdef DEBUG_UART - print("Encountered UART error: "); puth(err); print("\n"); - #endif - UART_READ_RDR(q->uart) - } - - if ((err & USART_ISR_ORE) != 0U) { - q->uart->ICR |= USART_ICR_ORECF; - } else if ((err & USART_ISR_NE) != 0U) { - q->uart->ICR |= USART_ICR_NECF; - } else if ((err & USART_ISR_FE) != 0U) { - q->uart->ICR |= USART_ICR_FECF; - } else if ((err & USART_ISR_PE) != 0U) { - q->uart->ICR |= USART_ICR_PECF; - } else {} - - // Send if necessary - uart_tx_ring(q); - - EXIT_CRITICAL(); -} - -void UART7_IRQ_Handler(void) { uart_interrupt_handler(&uart_ring_som_debug); } - -void uart_init(uart_ring *q, int baud) { - if (q->uart == UART7) { - REGISTER_INTERRUPT(UART7_IRQn, UART7_IRQ_Handler, 150000U, FAULT_INTERRUPT_RATE_UART_7) - - uart_set_baud(q->uart, baud); - q->uart->CR1 = USART_CR1_UE | USART_CR1_TE | USART_CR1_RE; - - // Enable interrupt on RX not empty - q->uart->CR1 |= USART_CR1_RXNEIE; - - // Enable UART interrupts - NVIC_EnableIRQ(UART7_IRQn); - } -} diff --git a/panda/board/stm32h7/llusb.h b/panda/board/stm32h7/llusb.h deleted file mode 100644 index ada1630..0000000 --- a/panda/board/stm32h7/llusb.h +++ /dev/null @@ -1,91 +0,0 @@ -USB_OTG_GlobalTypeDef *USBx = USB_OTG_HS; - -#define USBx_HOST ((USB_OTG_HostTypeDef *)((uint32_t)USBx + USB_OTG_HOST_BASE)) -#define USBx_DEVICE ((USB_OTG_DeviceTypeDef *)((uint32_t)USBx + USB_OTG_DEVICE_BASE)) -#define USBx_INEP(i) ((USB_OTG_INEndpointTypeDef *)((uint32_t)USBx + USB_OTG_IN_ENDPOINT_BASE + ((i) * USB_OTG_EP_REG_SIZE))) -#define USBx_OUTEP(i) ((USB_OTG_OUTEndpointTypeDef *)((uint32_t)USBx + USB_OTG_OUT_ENDPOINT_BASE + ((i) * USB_OTG_EP_REG_SIZE))) -#define USBx_DFIFO(i) *(__IO uint32_t *)((uint32_t)USBx + USB_OTG_FIFO_BASE + ((i) * USB_OTG_FIFO_SIZE)) -#define USBx_PCGCCTL *(__IO uint32_t *)((uint32_t)USBx + USB_OTG_PCGCCTL_BASE) - -#define USBD_FS_TRDT_VALUE 6UL -#define USB_OTG_SPEED_FULL 3U -#define DCFG_FRAME_INTERVAL_80 0U - - -void usb_irqhandler(void); - -void OTG_HS_IRQ_Handler(void) { - NVIC_DisableIRQ(OTG_HS_IRQn); - usb_irqhandler(); - NVIC_EnableIRQ(OTG_HS_IRQn); -} - -void usb_init(void) { - REGISTER_INTERRUPT(OTG_HS_IRQn, OTG_HS_IRQ_Handler, 1500000U, FAULT_INTERRUPT_RATE_USB) // TODO: Find out a better rate limit for USB. Now it's the 1.5MB/s rate - - // Disable global interrupt - USBx->GAHBCFG &= ~(USB_OTG_GAHBCFG_GINT); - // Select FS Embedded PHY - USBx->GUSBCFG |= USB_OTG_GUSBCFG_PHYSEL; - // Force device mode - USBx->GUSBCFG &= ~(USB_OTG_GUSBCFG_FHMOD | USB_OTG_GUSBCFG_FDMOD); - USBx->GUSBCFG |= USB_OTG_GUSBCFG_FDMOD; - delay(250000); // Wait for about 25ms (explicitly stated in H7 ref manual) - // Wait for AHB master IDLE state. - while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_AHBIDL) == 0); - // Core Soft Reset - USBx->GRSTCTL |= USB_OTG_GRSTCTL_CSRST; - while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_CSRST) == USB_OTG_GRSTCTL_CSRST); - // Activate the USB Transceiver - USBx->GCCFG |= USB_OTG_GCCFG_PWRDWN; - - for (uint8_t i = 0U; i < 15U; i++) { - USBx->DIEPTXF[i] = 0U; - } - - // VBUS Sensing setup - USBx_DEVICE->DCTL |= USB_OTG_DCTL_SDIS; - // Deactivate VBUS Sensing B - USBx->GCCFG &= ~(USB_OTG_GCCFG_VBDEN); - // B-peripheral session valid override enable - USBx->GOTGCTL |= USB_OTG_GOTGCTL_BVALOEN; - USBx->GOTGCTL |= USB_OTG_GOTGCTL_BVALOVAL; - // Restart the Phy Clock - USBx_PCGCCTL = 0U; - // Device mode configuration - USBx_DEVICE->DCFG |= DCFG_FRAME_INTERVAL_80; - USBx_DEVICE->DCFG |= USB_OTG_SPEED_FULL | USB_OTG_DCFG_NZLSOHSK; - - // Flush FIFOs - USBx->GRSTCTL = (USB_OTG_GRSTCTL_TXFFLSH | (0x10U << 6)); - while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_TXFFLSH) == USB_OTG_GRSTCTL_TXFFLSH); - - USBx->GRSTCTL = USB_OTG_GRSTCTL_RXFFLSH; - while ((USBx->GRSTCTL & USB_OTG_GRSTCTL_RXFFLSH) == USB_OTG_GRSTCTL_RXFFLSH); - - // Clear all pending Device Interrupts - USBx_DEVICE->DIEPMSK = 0U; - USBx_DEVICE->DOEPMSK = 0U; - USBx_DEVICE->DAINTMSK = 0U; - USBx_DEVICE->DIEPMSK &= ~(USB_OTG_DIEPMSK_TXFURM); - - // Disable all interrupts. - USBx->GINTMSK = 0U; - // Clear any pending interrupts - USBx->GINTSTS = 0xBFFFFFFFU; - // Enable interrupts matching to the Device mode ONLY - USBx->GINTMSK = USB_OTG_GINTMSK_USBRST | USB_OTG_GINTMSK_ENUMDNEM | USB_OTG_GINTMSK_OTGINT | - USB_OTG_GINTMSK_RXFLVLM | USB_OTG_GINTMSK_GONAKEFFM | USB_OTG_GINTMSK_GINAKEFFM | - USB_OTG_GINTMSK_OEPINT | USB_OTG_GINTMSK_IEPINT | - USB_OTG_GINTMSK_CIDSCHGM | USB_OTG_GINTMSK_SRQIM | USB_OTG_GINTMSK_MMISM; - - // Set USB Turnaround time - USBx->GUSBCFG |= ((USBD_FS_TRDT_VALUE << 10) & USB_OTG_GUSBCFG_TRDT); - // Enables the controller's Global Int in the AHB Config reg - USBx->GAHBCFG |= USB_OTG_GAHBCFG_GINT; - // Soft disconnect disable: - USBx_DEVICE->DCTL &= ~(USB_OTG_DCTL_SDIS); - - // enable the IRQ - NVIC_EnableIRQ(OTG_HS_IRQn); -} diff --git a/panda/board/stm32h7/peripherals.h b/panda/board/stm32h7/peripherals.h deleted file mode 100644 index b60f190..0000000 --- a/panda/board/stm32h7/peripherals.h +++ /dev/null @@ -1,138 +0,0 @@ -void gpio_usb_init(void) { - // A11,A12: USB - set_gpio_alternate(GPIOA, 11, GPIO_AF10_OTG1_FS); - set_gpio_alternate(GPIOA, 12, GPIO_AF10_OTG1_FS); - GPIOA->OSPEEDR = GPIO_OSPEEDR_OSPEED11 | GPIO_OSPEEDR_OSPEED12; -} - -void gpio_spi_init(void) { - set_gpio_alternate(GPIOE, 11, GPIO_AF5_SPI4); - set_gpio_alternate(GPIOE, 12, GPIO_AF5_SPI4); - set_gpio_alternate(GPIOE, 13, GPIO_AF5_SPI4); - set_gpio_alternate(GPIOE, 14, GPIO_AF5_SPI4); - register_set_bits(&(GPIOE->OSPEEDR), GPIO_OSPEEDR_OSPEED11 | GPIO_OSPEEDR_OSPEED12 | GPIO_OSPEEDR_OSPEED13 | GPIO_OSPEEDR_OSPEED14); -} - -void gpio_usart2_init(void) { - // A2,A3: USART 2 for debugging - set_gpio_alternate(GPIOA, 2, GPIO_AF7_USART2); - set_gpio_alternate(GPIOA, 3, GPIO_AF7_USART2); -} - -void gpio_uart7_init(void) { - // E7,E8: UART 7 for debugging - set_gpio_alternate(GPIOE, 7, GPIO_AF7_UART7); - set_gpio_alternate(GPIOE, 8, GPIO_AF7_UART7); -} - -// Common GPIO initialization -void common_init_gpio(void) { - /// E2,E3,E4: RGB LED - set_gpio_pullup(GPIOE, 2, PULL_NONE); - set_gpio_mode(GPIOE, 2, MODE_OUTPUT); - set_gpio_output_type(GPIOE, 2, OUTPUT_TYPE_OPEN_DRAIN); - - set_gpio_pullup(GPIOE, 3, PULL_NONE); - set_gpio_mode(GPIOE, 3, MODE_OUTPUT); - set_gpio_output_type(GPIOE, 3, OUTPUT_TYPE_OPEN_DRAIN); - - set_gpio_pullup(GPIOE, 4, PULL_NONE); - set_gpio_mode(GPIOE, 4, MODE_OUTPUT); - set_gpio_output_type(GPIOE, 4, OUTPUT_TYPE_OPEN_DRAIN); - - //C4,A1: OBD_SBU1, OBD_SBU2 - set_gpio_pullup(GPIOC, 4, PULL_NONE); - set_gpio_mode(GPIOC, 4, MODE_ANALOG); - - set_gpio_pullup(GPIOA, 1, PULL_NONE); - set_gpio_mode(GPIOA, 1, MODE_ANALOG); - - //F11: VOLT_S - set_gpio_pullup(GPIOF, 11, PULL_NONE); - set_gpio_mode(GPIOF, 11, MODE_ANALOG); - - gpio_usb_init(); - - // B8,B9: FDCAN1 - set_gpio_pullup(GPIOB, 8, PULL_NONE); - set_gpio_alternate(GPIOB, 8, GPIO_AF9_FDCAN1); - - set_gpio_pullup(GPIOB, 9, PULL_NONE); - set_gpio_alternate(GPIOB, 9, GPIO_AF9_FDCAN1); - - // B5,B6 (mplex to B12,B13): FDCAN2 - set_gpio_pullup(GPIOB, 12, PULL_NONE); - set_gpio_pullup(GPIOB, 13, PULL_NONE); - - set_gpio_pullup(GPIOB, 5, PULL_NONE); - set_gpio_alternate(GPIOB, 5, GPIO_AF9_FDCAN2); - - set_gpio_pullup(GPIOB, 6, PULL_NONE); - set_gpio_alternate(GPIOB, 6, GPIO_AF9_FDCAN2); - - // G9,G10: FDCAN3 - set_gpio_pullup(GPIOG, 9, PULL_NONE); - set_gpio_alternate(GPIOG, 9, GPIO_AF2_FDCAN3); - - set_gpio_pullup(GPIOG, 10, PULL_NONE); - set_gpio_alternate(GPIOG, 10, GPIO_AF2_FDCAN3); -} - -void flasher_peripherals_init(void) { - RCC->AHB1ENR |= RCC_AHB1ENR_USB1OTGHSEN; - - // SPI + DMA - RCC->APB2ENR |= RCC_APB2ENR_SPI4EN; - RCC->AHB1ENR |= RCC_AHB1ENR_DMA2EN; -} - -// Peripheral initialization -void peripherals_init(void) { - // enable GPIO(A,B,C,D,E,F,G,H) - RCC->AHB4ENR |= RCC_AHB4ENR_GPIOAEN; - RCC->AHB4ENR |= RCC_AHB4ENR_GPIOBEN; - RCC->AHB4ENR |= RCC_AHB4ENR_GPIOCEN; - RCC->AHB4ENR |= RCC_AHB4ENR_GPIODEN; - RCC->AHB4ENR |= RCC_AHB4ENR_GPIOEEN; - RCC->AHB4ENR |= RCC_AHB4ENR_GPIOFEN; - RCC->AHB4ENR |= RCC_AHB4ENR_GPIOGEN; - - // Enable CPU access to SRAM1 and SRAM2 (in domain D2) for DMA - RCC->AHB2ENR |= RCC_AHB2ENR_SRAM1EN | RCC_AHB2ENR_SRAM2EN; - - // Supplemental - RCC->AHB1ENR |= RCC_AHB1ENR_DMA1EN; // DAC DMA - RCC->AHB1ENR |= RCC_AHB1ENR_DMA2EN; // SPI DMA - RCC->APB4ENR |= RCC_APB4ENR_SYSCFGEN; - - // Connectivity - RCC->APB2ENR |= RCC_APB2ENR_SPI4EN; // SPI - RCC->APB1LENR |= RCC_APB1LENR_I2C5EN; // codec I2C - RCC->AHB1ENR |= RCC_AHB1ENR_USB1OTGHSEN; // USB - RCC->AHB1LPENR |= RCC_AHB1LPENR_USB1OTGHSLPEN; // USB LP needed for CSleep state(__WFI()) - RCC->AHB1LPENR &= ~(RCC_AHB1LPENR_USB1OTGHSULPILPEN); // disable USB ULPI - RCC->APB1LENR |= RCC_APB1LENR_UART7EN; // SOM uart - RCC->APB1HENR |= RCC_APB1HENR_FDCANEN; // FDCAN core enable - - // Analog - RCC->AHB1ENR |= RCC_AHB1ENR_ADC12EN; // Enable ADC12 clocks - RCC->APB1LENR |= RCC_APB1LENR_DAC12EN; // DAC - - // Timers - RCC->APB2ENR |= RCC_APB2ENR_TIM1EN; // clock source timer - RCC->APB1LENR |= RCC_APB1LENR_TIM2EN; // main counter - RCC->APB1LENR |= RCC_APB1LENR_TIM3EN; // fan pwm - RCC->APB1LENR |= RCC_APB1LENR_TIM6EN; // interrupt timer - RCC->APB1LENR |= RCC_APB1LENR_TIM7EN; // DMA trigger timer - RCC->APB2ENR |= RCC_APB2ENR_TIM8EN; // tick timer - RCC->APB1LENR |= RCC_APB1LENR_TIM12EN; // slow loop - -#ifdef PANDA_JUNGLE - RCC->AHB3ENR |= RCC_AHB3ENR_SDMMC1EN; // SDMMC - RCC->AHB4ENR |= RCC_AHB4ENR_ADC3EN; // Enable ADC3 clocks -#endif -} - -void enable_interrupt_timer(void) { - register_set_bits(&(RCC->APB1LENR), RCC_APB1LENR_TIM6EN); // Enable interrupt timer peripheral -} diff --git a/panda/board/stm32h7/stm32h7_config.h b/panda/board/stm32h7/stm32h7_config.h deleted file mode 100644 index 6f36a5a..0000000 --- a/panda/board/stm32h7/stm32h7_config.h +++ /dev/null @@ -1,99 +0,0 @@ -#include "stm32h7/inc/stm32h7xx.h" -#include "stm32h7/inc/stm32h7xx_hal_gpio_ex.h" -#define MCU_IDCODE 0x483U - -// from the linker script -#define APP_START_ADDRESS 0x8020000U - -#define CORE_FREQ 240U // in Mhz -//APB1 - 120Mhz, APB2 - 120Mhz -#define APB1_FREQ (CORE_FREQ/4U) -#define APB1_TIMER_FREQ (APB1_FREQ*2U) // APB1 is multiplied by 2 for the timer peripherals -#define APB2_FREQ (CORE_FREQ/4U) -#define APB2_TIMER_FREQ (APB2_FREQ*2U) // APB2 is multiplied by 2 for the timer peripherals - -#define BOOTLOADER_ADDRESS 0x1FF09804U - -/* -An IRQ is received on message RX/TX (or RX errors), with -separate IRQs for RX and TX. - -0-byte CAN FD frame as the worst case: -- 17 slow bits = SOF + 11 ID + R1 + IDE + EDL + R0 + BRS -- 23 fast bits = ESI + 4 DLC + 0 DATA + 17 CRC + CRC delimeter -- 12 slow bits = ACK + DEL + 7 EOF + 3 IFS -- all currently supported cars are 0.5 Mbps / 2 Mbps - -1 / ((29 bits / 0.5Mbps) + (23 bits / 2Mbps)) = 14388Hz -*/ -#define CAN_INTERRUPT_RATE 16000U - -#define MAX_LED_FADE 10240U - -// There are 163 external interrupt sources (see stm32f735xx.h) -#define NUM_INTERRUPTS 163U - -#define TICK_TIMER_IRQ TIM8_BRK_TIM12_IRQn -#define TICK_TIMER TIM12 - -#define MICROSECOND_TIMER TIM2 - -#define INTERRUPT_TIMER_IRQ TIM6_DAC_IRQn -#define INTERRUPT_TIMER TIM6 - -#define IND_WDG IWDG1 - -#define PROVISION_CHUNK_ADDRESS 0x080FFFE0U -#define DEVICE_SERIAL_NUMBER_ADDRESS 0x080FFFC0U - -#include "can_definitions.h" -#include "comms_definitions.h" - -#ifndef BOOTSTUB - #include "main_declarations.h" -#else - #include "bootstub_declarations.h" -#endif - -#include "libc.h" -#include "critical.h" -#include "faults.h" -#include "utils.h" - -#include "drivers/registers.h" -#include "drivers/interrupts.h" -#include "drivers/gpio.h" -#include "stm32h7/peripherals.h" -#include "stm32h7/interrupt_handlers.h" -#include "drivers/timers.h" -#include "drivers/watchdog.h" - -#if !defined(BOOTSTUB) - #include "drivers/uart.h" - #include "stm32h7/lluart.h" -#endif - -#include "stm32h7/board.h" -#include "stm32h7/clock.h" - -#if !defined(BOOTSTUB) && defined(PANDA) - #include "stm32h7/llexti.h" -#endif - -#ifdef BOOTSTUB - #include "stm32h7/llflash.h" -#else - #include "stm32h7/llfdcan.h" -#endif - -#include "stm32h7/llusb.h" - -#include "drivers/spi.h" -#include "stm32h7/llspi.h" - -void early_gpio_float(void) { - RCC->AHB4ENR = RCC_AHB4ENR_GPIOAEN | RCC_AHB4ENR_GPIOBEN | RCC_AHB4ENR_GPIOCEN | RCC_AHB4ENR_GPIODEN | RCC_AHB4ENR_GPIOEEN | RCC_AHB4ENR_GPIOFEN | RCC_AHB4ENR_GPIOGEN | RCC_AHB4ENR_GPIOHEN; - GPIOA->MODER = 0xAB000000U; GPIOB->MODER = 0; GPIOC->MODER = 0; GPIOD->MODER = 0; GPIOE->MODER = 0; GPIOF->MODER = 0; GPIOG->MODER = 0; GPIOH->MODER = 0; - GPIOA->ODR = 0; GPIOB->ODR = 0; GPIOC->ODR = 0; GPIOD->ODR = 0; GPIOE->ODR = 0; GPIOF->ODR = 0; GPIOG->ODR = 0; GPIOH->ODR = 0; - GPIOA->PUPDR = 0; GPIOB->PUPDR = 0; GPIOC->PUPDR = 0; GPIOD->PUPDR = 0; GPIOE->PUPDR = 0; GPIOF->PUPDR = 0; GPIOG->PUPDR = 0; GPIOH->PUPDR = 0; -} diff --git a/panda/board/utils.h b/panda/board/utils.h deleted file mode 100644 index fd69db1..0000000 --- a/panda/board/utils.h +++ /dev/null @@ -1,43 +0,0 @@ -#define MIN(a, b) ({ \ - __typeof__ (a) _a = (a); \ - __typeof__ (b) _b = (b); \ - (_a < _b) ? _a : _b; \ -}) - -#define MAX(a, b) ({ \ - __typeof__ (a) _a = (a); \ - __typeof__ (b) _b = (b); \ - (_a > _b) ? _a : _b; \ -}) - -#define CLAMP(x, low, high) ({ \ - __typeof__(x) __x = (x); \ - __typeof__(low) __low = (low);\ - __typeof__(high) __high = (high);\ - (__x > __high) ? __high : ((__x < __low) ? __low : __x); \ -}) - -#define ABS(a) ({ \ - __typeof__ (a) _a = (a); \ - (_a > 0) ? _a : (-_a); \ -}) - -#ifndef NULL -// this just provides a standard implementation of NULL -// in lieu of including libc in the panda build -// cppcheck-suppress [misra-c2012-21.1] -#define NULL ((void*)0) -#endif - -// STM32 HAL defines this -#ifndef UNUSED -#define UNUSED(x) ((void)(x)) -#endif - -#define COMPILE_TIME_ASSERT(pred) ((void)sizeof(char[1 - (2 * (!(pred) ? 1 : 0))])) - -// compute the time elapsed (in microseconds) from 2 counter samples -// case where ts < ts_last is ok: overflow is properly re-casted into uint32_t -uint32_t get_ts_elapsed(uint32_t ts, uint32_t ts_last) { - return ts - ts_last; -} diff --git a/panda/crypto/hash-internal.h b/panda/crypto/hash-internal.h deleted file mode 100644 index 05ec3ec..0000000 --- a/panda/crypto/hash-internal.h +++ /dev/null @@ -1,63 +0,0 @@ -/* - * Copyright 2007 The Android Open Source Project - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in the - * documentation and/or other materials provided with the distribution. - * * Neither the name of Google Inc. nor the names of its contributors may - * be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY Google Inc. ``AS IS'' AND ANY EXPRESS OR - * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO - * EVENT SHALL Google Inc. BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, - * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, - * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; - * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, - * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR - * OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF - * ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - */ - -#ifndef SYSTEM_CORE_INCLUDE_MINCRYPT_HASH_INTERNAL_H_ -#define SYSTEM_CORE_INCLUDE_MINCRYPT_HASH_INTERNAL_H_ - -#include "stdint.h" - -#ifdef __cplusplus -extern "C" { -#endif // __cplusplus - -struct HASH_CTX; // forward decl - -typedef struct HASH_VTAB { - void (* const init)(struct HASH_CTX*); - void (* const update)(struct HASH_CTX*, const void*, int); - const uint8_t* (* const final)(struct HASH_CTX*); - const uint8_t* (* const hash)(const void*, int, uint8_t*); - int size; -} HASH_VTAB; - -typedef struct HASH_CTX { - const HASH_VTAB * f; - uint64_t count; - uint8_t buf[64]; - uint32_t state[8]; // upto SHA2 -} HASH_CTX; - -#define HASH_init(ctx) (ctx)->f->init(ctx) -#define HASH_update(ctx, data, len) (ctx)->f->update(ctx, data, len) -#define HASH_final(ctx) (ctx)->f->final(ctx) -#define HASH_hash(data, len, digest) (ctx)->f->hash(data, len, digest) -#define HASH_size(ctx) (ctx)->f->size - -#ifdef __cplusplus -} -#endif // __cplusplus - -#endif // SYSTEM_CORE_INCLUDE_MINCRYPT_HASH_INTERNAL_H_ diff --git a/panda/crypto/rsa.h b/panda/crypto/rsa.h deleted file mode 100644 index 4ba4e10..0000000 --- a/panda/crypto/rsa.h +++ /dev/null @@ -1,58 +0,0 @@ -/* rsa.h -** -** Copyright 2008, The Android Open Source Project -** -** Redistribution and use in source and binary forms, with or without -** modification, are permitted provided that the following conditions are met: -** * Redistributions of source code must retain the above copyright -** notice, this list of conditions and the following disclaimer. -** * Redistributions in binary form must reproduce the above copyright -** notice, this list of conditions and the following disclaimer in the -** documentation and/or other materials provided with the distribution. -** * Neither the name of Google Inc. nor the names of its contributors may -** be used to endorse or promote products derived from this software -** without specific prior written permission. -** -** THIS SOFTWARE IS PROVIDED BY Google Inc. ``AS IS'' AND ANY EXPRESS OR -** IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF -** MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO -** EVENT SHALL Google Inc. BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, -** SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, -** PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; -** OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, -** WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR -** OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF -** ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. -*/ - -#ifndef SYSTEM_CORE_INCLUDE_MINCRYPT_RSA_H_ -#define SYSTEM_CORE_INCLUDE_MINCRYPT_RSA_H_ - -#include - -#ifdef __cplusplus -extern "C" { -#endif - -#define RSANUMBYTES 128 /* 1024 bit key length */ -#define RSANUMWORDS (RSANUMBYTES / sizeof(uint32_t)) - -typedef struct RSAPublicKey { - int len; /* Length of n[] in number of uint32_t */ - uint32_t n0inv; /* -1 / n[0] mod 2^32 */ - uint32_t n[RSANUMWORDS]; /* modulus as little endian array */ - uint32_t rr[RSANUMWORDS]; /* R^2 as little endian array */ - int exponent; /* 3 or 65537 */ -} RSAPublicKey; - -int RSA_verify(const RSAPublicKey *key, - const uint8_t* signature, - const int len, - const uint8_t* hash, - const int hash_len); - -#ifdef __cplusplus -} -#endif - -#endif // SYSTEM_CORE_INCLUDE_MINCRYPT_RSA_H_ diff --git a/panda/crypto/sha.h b/panda/crypto/sha.h deleted file mode 100644 index 4b51a53..0000000 --- a/panda/crypto/sha.h +++ /dev/null @@ -1,51 +0,0 @@ -/* - * Copyright 2005 The Android Open Source Project - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in the - * documentation and/or other materials provided with the distribution. - * * Neither the name of Google Inc. nor the names of its contributors may - * be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY Google Inc. ``AS IS'' AND ANY EXPRESS OR - * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO - * EVENT SHALL Google Inc. BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, - * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, - * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; - * OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, - * WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR - * OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF - * ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - */ -#ifndef SYSTEM_CORE_INCLUDE_MINCRYPT_SHA1_H_ -#define SYSTEM_CORE_INCLUDE_MINCRYPT_SHA1_H_ - -#include "hash-internal.h" - -#ifdef __cplusplus -extern "C" { -#endif // __cplusplus - -typedef HASH_CTX SHA_CTX; - -void SHA_init(SHA_CTX* ctx); -void SHA_update(SHA_CTX* ctx, const void* data, int len); -const uint8_t* SHA_final(SHA_CTX* ctx); - -// Convenience method. Returns digest address. -// NOTE: *digest needs to hold SHA_DIGEST_SIZE bytes. -const uint8_t* SHA_hash(const void* data, int len, uint8_t* digest); - -#define SHA_DIGEST_SIZE 20 - -#ifdef __cplusplus -} -#endif // __cplusplus - -#endif // SYSTEM_CORE_INCLUDE_MINCRYPT_SHA1_H_ diff --git a/panda/drivers/linux/test/Makefile b/panda/drivers/linux/test/Makefile deleted file mode 100644 index c73945e..0000000 --- a/panda/drivers/linux/test/Makefile +++ /dev/null @@ -1,2 +0,0 @@ -all: - gcc main.c -o cantest -pthread -lpthread diff --git a/panda/drivers/linux/test/main.c b/panda/drivers/linux/test/main.c deleted file mode 100644 index 1f44efc..0000000 --- a/panda/drivers/linux/test/main.c +++ /dev/null @@ -1,120 +0,0 @@ -#include -#include -#include -#include -#include - -#include -#include -#include -#include - -#include -#include - -const char *ifname = "can0"; - -static unsigned char payload[] = {0xAA, 0xAA, 0xAA, 0xAA, 0x07, 0x00, 0x00, 0x00}; -int packet_len = 8; -int dir = 0; - -void *write_thread( void *dat ){ - int nbytes; - struct can_frame frame; - int s = *((int*) dat); - - while(1){ - for(int i = 0; i < 1; i ++){ - if(packet_len % 2){ - frame.can_id = 0x8AA | CAN_EFF_FLAG; - }else{ - frame.can_id = 0xAA; - } - - frame.can_dlc = packet_len; - memcpy(frame.data, payload, frame.can_dlc); - - nbytes = write(s, &frame, sizeof(struct can_frame)); - - printf("Wrote %d bytes; addr: %lx; datlen: %d\n", nbytes, frame.can_id, frame.can_dlc); - - if(dir){ - packet_len++; - if(packet_len >= 8) - dir = 0; - }else{ - packet_len--; - if(packet_len <= 0) - dir = 1; - } - } - sleep(2); - } -} - - -int main(void) -{ - pthread_t sndthread; - int err, s, nbytes; - struct sockaddr_can addr; - struct can_frame frame; - struct ifreq ifr; - - if((s = socket(PF_CAN, SOCK_RAW, CAN_RAW)) < 0) { - perror("Error while opening socket"); - return -1; - } - - strcpy(ifr.ifr_name, ifname); - ioctl(s, SIOCGIFINDEX, &ifr); - - addr.can_family = AF_CAN; - addr.can_ifindex = ifr.ifr_ifindex; - - printf("%s at index %d\n", ifname, ifr.ifr_ifindex); - - if(bind(s, (struct sockaddr *)&addr, sizeof(addr)) < 0) { - perror("Error in socket bind"); - return -2; - } - - /////// Create Write Thread - - err = pthread_create( &sndthread, NULL, write_thread, (void*) &s); - if(err){ - fprintf(stderr,"Error - pthread_create() return code: %d\n", err); - exit(EXIT_FAILURE); - } - - /////// Listen to socket - while (1) { - struct can_frame framein; - - // Read in a CAN frame - int numBytes = read(s, &framein, CANFD_MTU); - switch (numBytes) { - case CAN_MTU: - if(framein.can_id & 0x80000000) - printf("Received %u byte payload; canid 0x%lx (EXT)\n", - framein.can_dlc, framein.can_id & 0x7FFFFFFF); - else - printf("Received %u byte payload; canid 0x%lx\n", framein.can_dlc, framein.can_id); - break; - case CANFD_MTU: - // TODO: Should make an example for CAN FD - break; - case -1: - // Check the signal value on interrupt - //if (EINTR == errno) - // continue; - - // Delay before continuing - sleep(1); - default: - continue; - } - } - - return 0; -} diff --git a/panda/drivers/linux/test/run.sh b/panda/drivers/linux/test/run.sh deleted file mode 100644 index 5301719..0000000 --- a/panda/drivers/linux/test/run.sh +++ /dev/null @@ -1,4 +0,0 @@ -#!/usr/bin/env bash -sudo ifconfig can0 up -make -./cantest diff --git a/panda/tests/benchmark.py b/panda/tests/benchmark.py deleted file mode 100644 index c2b0c85..0000000 --- a/panda/tests/benchmark.py +++ /dev/null @@ -1,43 +0,0 @@ -#!/usr/bin/env python3 -import time -from contextlib import contextmanager - -from panda import Panda, PandaDFU -from panda.tests.hitl.helpers import get_random_can_messages - - -@contextmanager -def print_time(desc): - start = time.perf_counter() - yield - end = time.perf_counter() - print(f"{end - start:.2f}s - {desc}") - - -if __name__ == "__main__": - with print_time("Panda()"): - p = Panda() - - with print_time("PandaDFU.list()"): - PandaDFU.list() - - fxn = [ - 'reset', - 'reconnect', - 'up_to_date', - 'health', - #'flash', - ] - for f in fxn: - with print_time(f"Panda.{f}()"): - getattr(p, f)() - - p.set_can_loopback(True) - - for n in range(6): - msgs = get_random_can_messages(int(10**n)) - with print_time(f"Panda.can_send_many() - {len(msgs)} msgs"): - p.can_send_many(msgs) - - with print_time("Panda.can_recv()"): - m = p.can_recv() diff --git a/panda/tests/black_white_loopback_test.py b/panda/tests/black_white_loopback_test.py deleted file mode 100644 index 5b2312b..0000000 --- a/panda/tests/black_white_loopback_test.py +++ /dev/null @@ -1,156 +0,0 @@ -#!/usr/bin/env python3 - -# Loopback test between black panda (+ harness and power) and white/grey panda -# Tests all buses, including OBD CAN, which is on the same bus as CAN0 in this test. -# To be sure, the test should be run with both harness orientations - - -import os -import time -import random -import argparse -from panda import Panda - -def get_test_string(): - return b"test" + os.urandom(10) - -counter = 0 -nonzero_bus_errors = 0 -zero_bus_errors = 0 -content_errors = 0 - -def run_test(sleep_duration): - global counter - - pandas = Panda.list() - print(pandas) - - # make sure two pandas are connected - if len(pandas) != 2: - raise Exception("Connect white/grey and black panda to run this test!") - - # connect - pandas[0] = Panda(pandas[0]) - pandas[1] = Panda(pandas[1]) - - black_panda = None - other_panda = None - - # find out which one is black - if pandas[0].is_black() and not pandas[1].is_black(): - black_panda = pandas[0] - other_panda = pandas[1] - elif not pandas[0].is_black() and pandas[1].is_black(): - black_panda = pandas[1] - other_panda = pandas[0] - else: - raise Exception("Connect white/grey and black panda to run this test!") - - # disable safety modes - black_panda.set_safety_mode(Panda.SAFETY_ALLOUTPUT) - other_panda.set_safety_mode(Panda.SAFETY_ALLOUTPUT) - - # test health packet - print("black panda health", black_panda.health()) - print("other panda health", other_panda.health()) - - # test black -> other - while True: - test_buses(black_panda, other_panda, True, [(0, False, [0]), (1, False, [1]), (2, False, [2]), (1, True, [0])], sleep_duration) - test_buses(black_panda, other_panda, False, [(0, False, [0]), (1, False, [1]), (2, False, [2]), (0, True, [0, 1])], sleep_duration) - counter += 1 - print("Number of cycles:", counter, "Non-zero bus errors:", nonzero_bus_errors, "Zero bus errors:", zero_bus_errors, "Content errors:", content_errors) - - # Toggle relay - black_panda.set_safety_mode(Panda.SAFETY_SILENT) - time.sleep(1) - black_panda.set_safety_mode(Panda.SAFETY_ALLOUTPUT) - time.sleep(1) - - -def test_buses(black_panda, other_panda, direction, test_array, sleep_duration): - global nonzero_bus_errors, zero_bus_errors, content_errors - - if direction: - print("***************** TESTING (BLACK --> OTHER) *****************") - else: - print("***************** TESTING (OTHER --> BLACK) *****************") - - for send_bus, obd, recv_buses in test_array: - black_panda.send_heartbeat() - other_panda.send_heartbeat() - print("\ntest can: ", send_bus, " OBD: ", obd) - - # set OBD on black panda - black_panda.set_gmlan(True if obd else None) - - # clear and flush - if direction: - black_panda.can_clear(send_bus) - else: - other_panda.can_clear(send_bus) - - for recv_bus in recv_buses: - if direction: - other_panda.can_clear(recv_bus) - else: - black_panda.can_clear(recv_bus) - - black_panda.can_recv() - other_panda.can_recv() - - # send the characters - at = random.randint(1, 2000) - st = get_test_string()[0:8] - if direction: - black_panda.can_send(at, st, send_bus) - else: - other_panda.can_send(at, st, send_bus) - time.sleep(0.1) - - # check for receive - if direction: - _ = black_panda.can_recv() # can echo - cans_loop = other_panda.can_recv() - else: - _ = other_panda.can_recv() # can echo - cans_loop = black_panda.can_recv() - - loop_buses = [] - for loop in cans_loop: - if (loop[0] != at) or (loop[2] != st): - content_errors += 1 - - print(" Loop on bus", str(loop[3])) - loop_buses.append(loop[3]) - if len(cans_loop) == 0: - print(" No loop") - assert not os.getenv("NOASSERT") - - # test loop buses - recv_buses.sort() - loop_buses.sort() - if(recv_buses != loop_buses): - if len(loop_buses) == 0: - zero_bus_errors += 1 - else: - nonzero_bus_errors += 1 - assert not os.getenv("NOASSERT") - else: - print(" TEST PASSED") - - time.sleep(sleep_duration) - print("\n") - -if __name__ == "__main__": - parser = argparse.ArgumentParser() - parser.add_argument("-n", type=int, help="Number of test iterations to run") - parser.add_argument("-sleep", type=int, help="Sleep time between tests", default=0) - args = parser.parse_args() - - if args.n is None: - while True: - run_test(sleep_duration=args.sleep) - else: - for _ in range(args.n): - run_test(sleep_duration=args.sleep) diff --git a/panda/tests/black_white_relay_endurance.py b/panda/tests/black_white_relay_endurance.py deleted file mode 100644 index db19e72..0000000 --- a/panda/tests/black_white_relay_endurance.py +++ /dev/null @@ -1,164 +0,0 @@ -#!/usr/bin/env python3 - -# Loopback test between black panda (+ harness and power) and white/grey panda -# Tests all buses, including OBD CAN, which is on the same bus as CAN0 in this test. -# To be sure, the test should be run with both harness orientations - - -import os -import time -import random -import argparse - -from panda import Panda - -def get_test_string(): - return b"test" + os.urandom(10) - -counter = 0 -nonzero_bus_errors = 0 -zero_bus_errors = 0 -content_errors = 0 - -def run_test(sleep_duration): - global counter - - pandas = Panda.list() - print(pandas) - - # make sure two pandas are connected - if len(pandas) != 2: - raise Exception("Connect white/grey and black panda to run this test!") - - # connect - pandas[0] = Panda(pandas[0]) - pandas[1] = Panda(pandas[1]) - - black_panda = None - other_panda = None - - # find out which one is black - if pandas[0].is_black() and not pandas[1].is_black(): - black_panda = pandas[0] - other_panda = pandas[1] - elif not pandas[0].is_black() and pandas[1].is_black(): - black_panda = pandas[1] - other_panda = pandas[0] - else: - raise Exception("Connect white/grey and black panda to run this test!") - - # disable safety modes - black_panda.set_safety_mode(Panda.SAFETY_ALLOUTPUT) - other_panda.set_safety_mode(Panda.SAFETY_ALLOUTPUT) - - # test health packet - print("black panda health", black_panda.health()) - print("other panda health", other_panda.health()) - - # test black -> other - start_time = time.time() - temp_start_time = start_time - while True: - test_buses(black_panda, other_panda, True, [(0, False, [0]), (1, False, [1]), (2, False, [2]), (1, True, [0])], sleep_duration) - test_buses(black_panda, other_panda, False, [(0, False, [0]), (1, False, [1]), (2, False, [2]), (0, True, [0, 1])], sleep_duration) - counter += 1 - - runtime = time.time() - start_time - print("Number of cycles:", counter, "Non-zero bus errors:", nonzero_bus_errors, "Zero bus errors:", zero_bus_errors, - "Content errors:", content_errors, "Runtime: ", runtime) - - if (time.time() - temp_start_time) > 3600 * 6: - # Toggle relay - black_panda.set_safety_mode(Panda.SAFETY_SILENT) - time.sleep(1) - black_panda.set_safety_mode(Panda.SAFETY_ALLOUTPUT) - time.sleep(1) - temp_start_time = time.time() - - -def test_buses(black_panda, other_panda, direction, test_array, sleep_duration): - global nonzero_bus_errors, zero_bus_errors, content_errors - - if direction: - print("***************** TESTING (BLACK --> OTHER) *****************") - else: - print("***************** TESTING (OTHER --> BLACK) *****************") - - for send_bus, obd, recv_buses in test_array: - black_panda.send_heartbeat() - other_panda.send_heartbeat() - print("\ntest can: ", send_bus, " OBD: ", obd) - - # set OBD on black panda - black_panda.set_gmlan(True if obd else None) - - # clear and flush - if direction: - black_panda.can_clear(send_bus) - else: - other_panda.can_clear(send_bus) - - for recv_bus in recv_buses: - if direction: - other_panda.can_clear(recv_bus) - else: - black_panda.can_clear(recv_bus) - - black_panda.can_recv() - other_panda.can_recv() - - # send the characters - at = random.randint(1, 2000) - st = get_test_string()[0:8] - if direction: - black_panda.can_send(at, st, send_bus) - else: - other_panda.can_send(at, st, send_bus) - time.sleep(0.1) - - # check for receive - if direction: - _ = black_panda.can_recv() # cans echo - cans_loop = other_panda.can_recv() - else: - _ = other_panda.can_recv() # cans echo - cans_loop = black_panda.can_recv() - - loop_buses = [] - for loop in cans_loop: - if (loop[0] != at) or (loop[2] != st): - content_errors += 1 - - print(" Loop on bus", str(loop[3])) - loop_buses.append(loop[3]) - if len(cans_loop) == 0: - print(" No loop") - assert os.getenv("NOASSERT") - - # test loop buses - recv_buses.sort() - loop_buses.sort() - if(recv_buses != loop_buses): - if len(loop_buses) == 0: - zero_bus_errors += 1 - else: - nonzero_bus_errors += 1 - assert os.getenv("NOASSERT") - else: - print(" TEST PASSED") - - time.sleep(sleep_duration) - print("\n") - -if __name__ == "__main__": - parser = argparse.ArgumentParser() - parser.add_argument("-n", type=int, help="Number of test iterations to run") - parser.add_argument("-sleep", type=int, help="Sleep time between tests", default=0) - args = parser.parse_args() - - if args.n is None: - while True: - run_test(sleep_duration=args.sleep) - else: - for _ in range(args.n): - run_test(sleep_duration=args.sleep) diff --git a/panda/tests/black_white_relay_test.py b/panda/tests/black_white_relay_test.py deleted file mode 100644 index 90b33be..0000000 --- a/panda/tests/black_white_relay_test.py +++ /dev/null @@ -1,135 +0,0 @@ -#!/usr/bin/env python3 - -# Relay test with loopback between black panda (+ harness and power) and white/grey panda -# Tests the relay switching multiple times / second by looking at the buses on which loop occurs. - - -import os -import time -import random -import argparse - -from panda import Panda - -def get_test_string(): - return b"test" + os.urandom(10) - -counter = 0 -open_errors = 0 -closed_errors = 0 -content_errors = 0 - -def run_test(sleep_duration): - global counter, open_errors, closed_errors - - pandas = Panda.list() - print(pandas) - - # make sure two pandas are connected - if len(pandas) != 2: - raise Exception("Connect white/grey and black panda to run this test!") - - # connect - pandas[0] = Panda(pandas[0]) - pandas[1] = Panda(pandas[1]) - - # find out which one is black - type0 = pandas[0].get_type() - type1 = pandas[1].get_type() - - black_panda = None - other_panda = None - - if type0 == "\x03" and type1 != "\x03": - black_panda = pandas[0] - other_panda = pandas[1] - elif type0 != "\x03" and type1 == "\x03": - black_panda = pandas[1] - other_panda = pandas[0] - else: - raise Exception("Connect white/grey and black panda to run this test!") - - # disable safety modes - black_panda.set_safety_mode(Panda.SAFETY_ALLOUTPUT) - other_panda.set_safety_mode(Panda.SAFETY_ALLOUTPUT) - - # test health packet - print("black panda health", black_panda.health()) - print("other panda health", other_panda.health()) - - # test black -> other - while True: - # Switch on relay - black_panda.set_safety_mode(Panda.SAFETY_ALLOUTPUT) - time.sleep(0.05) - - if not test_buses(black_panda, other_panda, (0, False, [0])): - open_errors += 1 - raise Exception("Open error") - - # Switch off relay - black_panda.set_safety_mode(Panda.SAFETY_SILENT) - time.sleep(0.05) - - if not test_buses(black_panda, other_panda, (0, False, [0, 2])): - closed_errors += 1 - raise Exception("Close error") - - counter += 1 - print("Number of cycles:", counter, "Open errors:", open_errors, "Closed errors:", closed_errors, "Content errors:", content_errors) - -def test_buses(black_panda, other_panda, test_obj): - global content_errors - send_bus, obd, recv_buses = test_obj - - black_panda.send_heartbeat() - other_panda.send_heartbeat() - - # Set OBD on send panda - other_panda.set_gmlan(True if obd else None) - - # clear and flush - other_panda.can_clear(send_bus) - - for recv_bus in recv_buses: - black_panda.can_clear(recv_bus) - - black_panda.can_recv() - other_panda.can_recv() - - # send the characters - at = random.randint(1, 2000) - st = get_test_string()[0:8] - other_panda.can_send(at, st, send_bus) - time.sleep(0.05) - - # check for receive - _ = other_panda.can_recv() # can echo - cans_loop = black_panda.can_recv() - - loop_buses = [] - for loop in cans_loop: - if (loop[0] != at) or (loop[2] != st): - content_errors += 1 - loop_buses.append(loop[3]) - - # test loop buses - recv_buses.sort() - loop_buses.sort() - if(recv_buses != loop_buses): - return False - else: - return True - -if __name__ == "__main__": - parser = argparse.ArgumentParser() - parser.add_argument("-n", type=int, help="Number of test iterations to run") - parser.add_argument("-sleep", type=int, help="Sleep time between tests", default=0) - args = parser.parse_args() - - if args.n is None: - while True: - run_test(sleep_duration=args.sleep) - else: - for _ in range(args.n): - run_test(sleep_duration=args.sleep) diff --git a/panda/tests/bulk_write_test.py b/panda/tests/bulk_write_test.py deleted file mode 100644 index 278766a..0000000 --- a/panda/tests/bulk_write_test.py +++ /dev/null @@ -1,48 +0,0 @@ -#!/usr/bin/env python3 -import os -import time -import threading -from typing import Any - -from panda import Panda - -JUNGLE = "JUNGLE" in os.environ -if JUNGLE: - from panda import PandaJungle - -# The TX buffers on pandas is 0x100 in length. -NUM_MESSAGES_PER_BUS = 10000 - -def flood_tx(panda): - print('Sending!') - msg = b"\xaa" * 4 - packet = [[0xaa, None, msg, 0], [0xaa, None, msg, 1], [0xaa, None, msg, 2]] * NUM_MESSAGES_PER_BUS - panda.can_send_many(packet, timeout=10000) - print(f"Done sending {3*NUM_MESSAGES_PER_BUS} messages!") - -if __name__ == "__main__": - serials = Panda.list() - if JUNGLE: - sender = Panda() - receiver = PandaJungle() - else: - if len(serials) != 2: - raise Exception("Connect two pandas to perform this test!") - sender = Panda(serials[0]) - receiver = Panda(serials[1]) # type: ignore - receiver.set_safety_mode(Panda.SAFETY_ALLOUTPUT) - - sender.set_safety_mode(Panda.SAFETY_ALLOUTPUT) - - # Start transmisson - threading.Thread(target=flood_tx, args=(sender,)).start() - - # Receive as much as we can in a few second time period - rx: list[Any] = [] - old_len = 0 - start_time = time.time() - while time.time() - start_time < 3 or len(rx) > old_len: - old_len = len(rx) - print(old_len) - rx.extend(receiver.can_recv()) - print(f"Received {len(rx)} messages") diff --git a/panda/tests/can_printer.py b/panda/tests/can_printer.py deleted file mode 100644 index 15ce89f..0000000 --- a/panda/tests/can_printer.py +++ /dev/null @@ -1,36 +0,0 @@ -#!/usr/bin/env python3 -import os -import time -from collections import defaultdict -import binascii - -from panda import Panda - -# fake -def sec_since_boot(): - return time.time() - -def can_printer(): - p = Panda() - p.set_safety_mode(Panda.SAFETY_ALLOUTPUT) - - start = sec_since_boot() - lp = sec_since_boot() - msgs = defaultdict(list) - canbus = int(os.getenv("CAN", "0")) - while True: - can_recv = p.can_recv() - for address, _, dat, src in can_recv: - if src == canbus: - msgs[address].append(dat) - - if sec_since_boot() - lp > 0.1: - dd = chr(27) + "[2J" - dd += "%5.2f\n" % (sec_since_boot() - start) - for k, v in sorted(zip(list(msgs.keys()), [binascii.hexlify(x[-1]) for x in list(msgs.values())], strict=True)): - dd += "%s(%6d) %s\n" % ("%04X(%4d)" % (k, k), len(msgs[k]), v) - print(dd) - lp = sec_since_boot() - -if __name__ == "__main__": - can_printer() diff --git a/panda/tests/canfd/test_canfd.py b/panda/tests/canfd/test_canfd.py deleted file mode 100644 index 873bc79..0000000 --- a/panda/tests/canfd/test_canfd.py +++ /dev/null @@ -1,152 +0,0 @@ -#!/usr/bin/env python3 -import os -import time -import random -from collections import defaultdict -from panda import Panda, calculate_checksum, DLC_TO_LEN -from panda import PandaJungle -from panda.tests.hitl.helpers import time_many_sends - -H7_HW_TYPES = [Panda.HW_TYPE_RED_PANDA, Panda.HW_TYPE_RED_PANDA_V2] -JUNGLE_SERIAL = os.getenv("JUNGLE") -H7_PANDAS_EXCLUDE = [] # type: ignore -if os.getenv("H7_PANDAS_EXCLUDE"): - H7_PANDAS_EXCLUDE = os.getenv("H7_PANDAS_EXCLUDE").strip().split(" ") # type: ignore - -def panda_reset(): - panda_serials = [] - - panda_jungle = PandaJungle(JUNGLE_SERIAL) - panda_jungle.set_can_silent(True) - panda_jungle.set_panda_power(False) - time.sleep(1) - panda_jungle.set_panda_power(True) - time.sleep(4) - - for serial in Panda.list(): - if serial not in H7_PANDAS_EXCLUDE: - with Panda(serial=serial) as p: - if p.get_type() in H7_HW_TYPES: - p.reset() - panda_serials.append(serial) - - print("test pandas", panda_serials) - assert len(panda_serials) == 2, "Two H7 pandas required" - - return panda_serials - -def panda_init(serial, enable_canfd=False, enable_non_iso=False): - p = Panda(serial=serial) - p.set_power_save(False) - for bus in range(3): - p.set_can_speed_kbps(0, 500) - if enable_canfd: - p.set_can_data_speed_kbps(bus, 2000) - if enable_non_iso: - p.set_canfd_non_iso(bus, True) - p.set_safety_mode(Panda.SAFETY_ALLOUTPUT) - return p - -def test_canfd_throughput(p, p_recv=None): - two_pandas = p_recv is not None - p.set_safety_mode(Panda.SAFETY_ALLOUTPUT) - if two_pandas: - p_recv.set_safety_mode(Panda.SAFETY_ALLOUTPUT) - # enable output mode - else: - p.set_can_loopback(True) - - tests = [ - [500, 1000, 2000], # speeds - [93, 87, 78], # saturation thresholds - ] - - for i in range(len(tests[0])): - # set bus 0 data speed to speed - p.set_can_data_speed_kbps(0, tests[0][i]) - if p_recv is not None: - p_recv.set_can_data_speed_kbps(0, tests[0][i]) - time.sleep(0.05) - - comp_kbps = time_many_sends(p, 0, p_recv=p_recv, msg_count=400, two_pandas=two_pandas, msg_len=64) - - # bit count from https://en.wikipedia.org/wiki/CAN_bus - saturation_pct = (comp_kbps / tests[0][i]) * 100.0 - assert saturation_pct > tests[1][i] - assert saturation_pct < 100 - -def canfd_test(p_send, p_recv): - for n in range(100): - sent_msgs = defaultdict(set) - to_send = [] - for _ in range(200): - bus = random.randrange(3) - for dlc in range(len(DLC_TO_LEN)): - address = random.randrange(1, 1<<29) - data = bytearray(random.getrandbits(8) for _ in range(DLC_TO_LEN[dlc])) - if len(data) >= 2: - data[0] = calculate_checksum(data[1:] + bytes(str(address), encoding="utf-8")) - to_send.append([address, 0, data, bus]) - sent_msgs[bus].add((address, bytes(data))) - - p_send.can_send_many(to_send, timeout=0) - - start_time = time.monotonic() - while (time.monotonic() - start_time < 1) and any(len(x) > 0 for x in sent_msgs.values()): - incoming = p_recv.can_recv() - for msg in incoming: - address, _, data, bus = msg - if len(data) >= 2: - assert calculate_checksum(data[1:] + bytes(str(address), encoding="utf-8")) == data[0] - k = (address, bytes(data)) - assert k in sent_msgs[bus], f"message {k} was never sent on bus {bus}" - sent_msgs[bus].discard(k) - - for bus in range(3): - assert not len(sent_msgs[bus]), f"loop {n}: bus {bus} missing {len(sent_msgs[bus])} messages" - -def setup_test(enable_non_iso=False): - panda_serials = panda_reset() - - p_send = panda_init(panda_serials[0], enable_canfd=False, enable_non_iso=enable_non_iso) - p_recv = panda_init(panda_serials[1], enable_canfd=True, enable_non_iso=enable_non_iso) - - # Check that sending panda CAN FD and BRS are turned off - for bus in range(3): - health = p_send.can_health(bus) - assert not health["canfd_enabled"] - assert not health["brs_enabled"] - assert health["canfd_non_iso"] == enable_non_iso - - # Receiving panda sends dummy CAN FD message that should enable CAN FD on sender side - for bus in range(3): - p_recv.can_send(0x200, b"dummymessage", bus) - p_recv.can_recv() - p_send.can_recv() - - # Check if all tested buses on sending panda have swithed to CAN FD with BRS - for bus in range(3): - health = p_send.can_health(bus) - assert health["canfd_enabled"] - assert health["brs_enabled"] - assert health["canfd_non_iso"] == enable_non_iso - - return p_send, p_recv - -def main(): - print("[TEST CAN-FD]") - p_send, p_recv = setup_test() - canfd_test(p_send, p_recv) - - print("[TEST CAN-FD non-ISO]") - p_send, p_recv = setup_test(enable_non_iso=True) - canfd_test(p_send, p_recv) - - print("[TEST CAN-FD THROUGHPUT]") - panda_serials = panda_reset() - p_send = panda_init(panda_serials[0], enable_canfd=True) - p_recv = panda_init(panda_serials[1], enable_canfd=True) - test_canfd_throughput(p_send, p_recv) - -if __name__ == "__main__": - main() diff --git a/panda/tests/check_fw_size.py b/panda/tests/check_fw_size.py deleted file mode 100644 index 53681c5..0000000 --- a/panda/tests/check_fw_size.py +++ /dev/null @@ -1,97 +0,0 @@ -#!/usr/bin/env python3 -import subprocess -from collections import defaultdict - - -def check_space(file, mcu): - MCUS = { - "H7": { - ".flash": 1024*1024, # FLASH - ".dtcmram": 128*1024, # DTCMRAM - ".itcmram": 64*1024, # ITCMRAM - ".axisram": 320*1024, # AXI SRAM - ".sram12": 32*1024, # SRAM1(16kb) + SRAM2(16kb) - ".sram4": 16*1024, # SRAM4 - ".backup_sram": 4*1024, # SRAM4 - }, - "F4": { - ".flash": 1024*1024, # FLASH - ".dtcmram": 256*1024, # RAM - ".ram_d1": 64*1024, # RAM2 - }, - } - IGNORE_LIST = [ - ".ARM.attributes", - ".comment", - ".debug_line", - ".debug_info", - ".debug_abbrev", - ".debug_aranges", - ".debug_str", - ".debug_ranges", - ".debug_loc", - ".debug_frame", - ".debug_line_str", - ".debug_rnglists", - ".debug_loclists", - ] - FLASH = [ - ".isr_vector", - ".text", - ".rodata", - ".data" - ] - RAM = [ - ".data", - ".bss", - "._user_heap_stack" # _user_heap_stack considered free? - ] - - result = {} - calcs = defaultdict(int) - - output = str(subprocess.check_output(f"arm-none-eabi-size -x --format=sysv {file}", shell=True), 'utf-8') - - for row in output.split('\n'): - pop = False - line = row.split() - if len(line) == 3 and line[0].startswith('.'): - if line[0] in IGNORE_LIST: - continue - result[line[0]] = [line[1], line[2]] - if line[0] in FLASH: - calcs[".flash"] += int(line[1], 16) - pop = True - if line[0] in RAM: - calcs[".dtcmram"] += int(line[1], 16) - pop = True - if pop: - result.pop(line[0]) - - if len(result): - for line in result: - calcs[line] += int(result[line][0], 16) - - print(f"=======SUMMARY FOR {mcu} FILE {file}=======") - for line in calcs: - if line in MCUS[mcu]: - used_percent = (100 - (MCUS[mcu][line] - calcs[line]) / MCUS[mcu][line] * 100) - print(f"SECTION: {line} size: {MCUS[mcu][line]} USED: {calcs[line]}({used_percent:.2f}%) FREE: {MCUS[mcu][line] - calcs[line]}") - else: - print(line, calcs[line]) - print() - - -if __name__ == "__main__": - # red panda - check_space("../board/obj/bootstub.panda_h7.elf", "H7") - check_space("../board/obj/panda_h7.elf", "H7") - # black panda - check_space("../board/obj/bootstub.panda.elf", "F4") - check_space("../board/obj/panda.elf", "F4") - # jungle v1 - check_space("../board/jungle/obj/bootstub.panda_jungle.elf", "F4") - check_space("../board/jungle/obj/panda_jungle.elf", "F4") - # jungle v2 - check_space("../board/jungle/obj/bootstub.panda_jungle_h7.elf", "H7") - check_space("../board/jungle/obj/panda_jungle_h7.elf", "H7") diff --git a/panda/tests/ci_shell.sh b/panda/tests/ci_shell.sh deleted file mode 100644 index 92c0f96..0000000 --- a/panda/tests/ci_shell.sh +++ /dev/null @@ -1,20 +0,0 @@ -#!/bin/bash -e - -DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" -OP_ROOT="$DIR/../../" -PANDA_ROOT="$DIR/../" - -if [ -z "$BUILD" ]; then - docker pull docker.io/commaai/panda:latest -else - docker build --cache-from docker.io/commaai/panda:latest -t docker.io/commaai/panda:latest -f $PANDA_ROOT/Dockerfile $PANDA_ROOT -fi - -docker run \ - -it \ - --rm \ - --volume $OP_ROOT:$OP_ROOT \ - --workdir $PWD \ - --env PYTHONPATH=$OP_ROOT \ - docker.io/commaai/panda:latest \ - /bin/bash diff --git a/panda/tests/debug_console.py b/panda/tests/debug_console.py deleted file mode 100644 index 8755be1..0000000 --- a/panda/tests/debug_console.py +++ /dev/null @@ -1,62 +0,0 @@ -#!/usr/bin/env python3 - -import os -import sys -import time -import select -import codecs - -from panda import Panda - -setcolor = ["\033[1;32;40m", "\033[1;31;40m"] -unsetcolor = "\033[00m" - -port_number = int(os.getenv("PORT", "0")) -claim = os.getenv("CLAIM") is not None -no_color = os.getenv("NO_COLOR") is not None -no_reconnect = os.getenv("NO_RECONNECT") is not None - -if __name__ == "__main__": - while True: - try: - serials = Panda.list() - if os.getenv("SERIAL"): - serials = [x for x in serials if x == os.getenv("SERIAL")] - - pandas = [Panda(x, claim=claim) for x in serials] - decoders = [codecs.getincrementaldecoder('utf-8')() for _ in pandas] - - if not len(pandas): - print("no pandas found") - if no_reconnect: - sys.exit(0) - time.sleep(1) - continue - - if os.getenv("BAUD") is not None: - for panda in pandas: - panda.set_uart_baud(port_number, int(os.getenv("BAUD"))) # type: ignore - - while True: - for i, panda in enumerate(pandas): - while True: - ret = panda.serial_read(port_number) - if len(ret) > 0: - decoded = decoders[i].decode(ret) - if no_color: - sys.stdout.write(decoded) - else: - sys.stdout.write(setcolor[i] + decoded + unsetcolor) - sys.stdout.flush() - else: - break - if select.select([sys.stdin], [], [], 0) == ([sys.stdin], [], []): - ln = sys.stdin.readline() - if claim: - panda.serial_write(port_number, ln) - time.sleep(0.01) - except KeyboardInterrupt: - break - except Exception: - print("panda disconnected!") - time.sleep(0.5) diff --git a/panda/tests/development/register_hashmap_spread.py b/panda/tests/development/register_hashmap_spread.py deleted file mode 100644 index 3e20e58..0000000 --- a/panda/tests/development/register_hashmap_spread.py +++ /dev/null @@ -1,50 +0,0 @@ -#!/usr/bin/env python3 -import matplotlib.pyplot as plt # pylint: disable=import-error - -HASHING_PRIME = 23 -REGISTER_MAP_SIZE = 0x3FF -BYTES_PER_REG = 4 - -# From ST32F413 datasheet -REGISTER_ADDRESS_REGIONS = [ - (0x40000000, 0x40007FFF), - (0x40010000, 0x400107FF), - (0x40011000, 0x400123FF), - (0x40012C00, 0x40014BFF), - (0x40015000, 0x400153FF), - (0x40015800, 0x40015BFF), - (0x40016000, 0x400167FF), - (0x40020000, 0x40021FFF), - (0x40023000, 0x400233FF), - (0x40023800, 0x40023FFF), - (0x40026000, 0x400267FF), - (0x50000000, 0x5003FFFF), - (0x50060000, 0x500603FF), - (0x50060800, 0x50060BFF), - (0x50060800, 0x50060BFF), - (0xE0000000, 0xE00FFFFF) -] - -def _hash(reg_addr): - return (((reg_addr >> 16) ^ ((((reg_addr + 1) & 0xFFFF) * HASHING_PRIME) & 0xFFFF)) & REGISTER_MAP_SIZE) - -# Calculate hash for each address -hashes = [] -double_hashes = [] -for (start_addr, stop_addr) in REGISTER_ADDRESS_REGIONS: - for addr in range(start_addr, stop_addr + 1, BYTES_PER_REG): - h = _hash(addr) - hashes.append(h) - double_hashes.append(_hash(h)) - -# Make histograms -plt.subplot(2, 1, 1) -plt.hist(hashes, bins=REGISTER_MAP_SIZE) -plt.title("Number of collisions per _hash") -plt.xlabel("Address") - -plt.subplot(2, 1, 2) -plt.hist(double_hashes, bins=REGISTER_MAP_SIZE) -plt.title("Number of collisions per double _hash") -plt.xlabel("Address") -plt.show() diff --git a/panda/tests/echo.py b/panda/tests/echo.py deleted file mode 100644 index 90bf4a8..0000000 --- a/panda/tests/echo.py +++ /dev/null @@ -1,16 +0,0 @@ -#!/usr/bin/env python3 -from panda import Panda - -# This script is intended to be used in conjunction with the echo_loopback_test.py test script from panda jungle. -# It sends a reversed response back for every message received containing b"test". -if __name__ == "__main__": - p = Panda() - p.set_safety_mode(Panda.SAFETY_ALLOUTPUT) - p.set_power_save(False) - - while True: - incoming = p.can_recv() - for message in incoming: - address, notused, data, bus = message - if b'test' in data: - p.can_send(address, data[::-1], bus) diff --git a/panda/tests/elm_car_simulator.py b/panda/tests/elm_car_simulator.py deleted file mode 100644 index 56e825f..0000000 --- a/panda/tests/elm_car_simulator.py +++ /dev/null @@ -1,232 +0,0 @@ -#!/usr/bin/env python3 - -"""Used to Reverse/Test ELM protocol auto detect and OBD message response without a car.""" - -import os -import sys -import struct -import binascii -import time -import threading -from collections import deque - -from panda import Panda - -def lin_checksum(dat): - return sum(dat) % 0x100 - -class ELMCarSimulator(): - def __init__(self, sn, silent=False, can_kbaud=500, - can=True, can11b=True, can29b=True, - lin=True): - self.__p = Panda(sn if sn else Panda.list()[0]) - self.__on = True - self.__stop = False - self.__silent = silent - - self.__lin_timer = None - self.__lin_active = False - self.__lin_enable = lin - self.__lin_monitor_thread = threading.Thread(target=self.__lin_monitor) - - self.__can_multipart_data = None - self.__can_kbaud = can_kbaud - self.__can_extra_noise_msgs = deque() - self.__can_enable = can - self.__can11b = can11b - self.__can29b = can29b - self.__can_monitor_thread = threading.Thread(target=self.__can_monitor) - - @property - def panda(self): - return self.__p - - def stop(self): - if self.__lin_timer: - self.__lin_timer.cancel() - self.__lin_timeout_handler() - - self.__stop = True - - def join(self): - if self.__lin_monitor_thread.is_alive(): - self.__lin_monitor_thread.join() - if self.__can_monitor_thread.is_alive(): - self.__can_monitor_thread.join() - if self.__p: - print("closing handle") - self.__p.close() - - def set_enable(self, on): - self.__on = on - - def start(self): - self.panda.set_safety_mode(Panda.SAFETY_ALLOUTPUT) - if self.__lin_enable: - self.__lin_monitor_thread.start() - if self.__can_enable: - self.__can_monitor_thread.start() - - ######################### - # CAN related functions # - ######################### - - def __can_monitor(self): - print("STARTING CAN THREAD") - self.panda.set_can_speed_kbps(0, self.__can_kbaud) - self.panda.can_recv() # Toss whatever was already there - - while not self.__stop: - for address, ts, data, src in self.panda.can_recv(): - if self.__on and src == 0 and len(data) == 8 and data[0] >= 2: - if not self.__silent: - print("Processing CAN message", src, hex(address), binascii.hexlify(data)) - self.__can_process_msg(data[1], data[2], address, ts, data, src) - elif not self.__silent: - print("Rejecting CAN message", src, hex(address), binascii.hexlify(data)) - - def can_mode_11b(self): - self.__can11b = True - self.__can29b = False - - def can_mode_29b(self): - self.__can11b = False - self.__can29b = True - - def can_mode_11b_29b(self): - self.__can11b = True - self.__can29b = True - - def change_can_baud(self, kbaud): - self.__can_kbaud = kbaud - self.panda.set_can_speed_kbps(0, self.__can_kbaud) - - def can_add_extra_noise(self, noise_msg, addr=None): - self.__can_extra_noise_msgs.append((addr, noise_msg)) - - def _can_send(self, addr, msg): - if not self.__silent: - print(" CAN Reply (%x)" % addr, binascii.hexlify(msg)) - self.panda.can_send(addr, msg + b'\x00' * (8 - len(msg)), 0) - if self.__can_extra_noise_msgs: - noise = self.__can_extra_noise_msgs.popleft() - self.panda.can_send(noise[0] if noise[0] is not None else addr, - noise[1] + b'\x00' * (8 - len(noise[1])), 0) - - def _can_addr_matches(self, addr): - if self.__can11b and (addr == 0x7DF or (addr & 0x7F8) == 0x7E0): - return True - if self.__can29b and (addr == 0x18db33f1 or (addr & 0x1FFF00FF) == 0x18da00f1): - return True - return False - - def __can_process_msg(self, mode, pid, address, ts, data, src): - if not self.__silent: - print("CAN MSG", binascii.hexlify(data[1:1 + data[0]]), - "Addr:", hex(address), "Mode:", hex(mode)[2:].zfill(2), - "PID:", hex(pid)[2:].zfill(2), "canLen:", len(data), - binascii.hexlify(data)) - - if self._can_addr_matches(address) and len(data) == 8: - outmsg = None - if data[:3] == b'\x30\x00\x00' and len(self.__can_multipart_data): - if not self.__silent: - print("Request for more data") - outaddr = 0x7E8 if address == 0x7DF or address == 0x7E0 else 0x18DAF110 - msgnum = 1 - while(self.__can_multipart_data): - datalen = min(7, len(self.__can_multipart_data)) - msgpiece = struct.pack("B", 0x20 | msgnum) + self.__can_multipart_data[:datalen] - self._can_send(outaddr, msgpiece) - self.__can_multipart_data = self.__can_multipart_data[7:] - msgnum = (msgnum + 1) % 0x10 - time.sleep(0.01) - - else: - outmsg = self._process_obd(mode, pid) - - if outmsg: - outaddr = 0x7E8 if address == 0x7DF or address == 0x7E0 else 0x18DAF110 - - if len(outmsg) <= 5: - self._can_send(outaddr, - struct.pack("BBB", len(outmsg) + 2, 0x40 | data[1], pid) + outmsg) - else: - first_msg_len = min(3, len(outmsg) % 7) - payload_len = len(outmsg) + 3 - msgpiece = struct.pack("BBBBB", 0x10 | ((payload_len >> 8) & 0xF), - payload_len & 0xFF, - 0x40 | data[1], pid, 1) + outmsg[:first_msg_len] - self._can_send(outaddr, msgpiece) - self.__can_multipart_data = outmsg[first_msg_len:] - - ######################### - # General OBD functions # - ######################### - - def _process_obd(self, mode, pid): - if mode == 0x01: # Mode: Show current data - if pid == 0x00: # List supported things - return b"\xff\xff\xff\xfe" # b"\xBE\x1F\xB8\x10" #Bitfield, random features - elif pid == 0x01: # Monitor Status since DTC cleared - return b"\x00\x00\x00\x00" # Bitfield, random features - elif pid == 0x04: # Calculated engine load - return b"\x2f" - elif pid == 0x05: # Engine coolant temperature - return b"\x3c" - elif pid == 0x0B: # Intake manifold absolute pressure - return b"\x90" - elif pid == 0x0C: # Engine RPM - return b"\x1A\xF8" - elif pid == 0x0D: # Vehicle Speed - return b"\x53" - elif pid == 0x10: # MAF air flow rate - return b"\x01\xA0" - elif pid == 0x11: # Throttle Position - return b"\x90" - elif pid == 0x33: # Absolute Barometric Pressure - return b"\x90" - elif mode == 0x09: # Mode: Request vehicle information - if pid == 0x02: # Show VIN - return b"1D4GP00R55B123456" - if pid == 0xFC: # test long multi message. Ligned up for LIN responses - return b''.join(struct.pack(">BBH", 0xAA, 0xAA, num + 1) for num in range(80)) - if pid == 0xFD: # test long multi message - parts = (b'\xAA\xAA\xAA' + struct.pack(">I", num) for num in range(80)) - return b'\xAA\xAA\xAA' + b''.join(parts) - if pid == 0xFE: # test very long multi message - parts = (b'\xAA\xAA\xAA' + struct.pack(">I", num) for num in range(584)) - return b'\xAA\xAA\xAA' + b''.join(parts) + b'\xAA' - if pid == 0xFF: - return b'\xAA\x00\x00' + \ - b"".join((b'\xAA' * 5) + struct.pack(">H", num + 1) for num in range(584)) - #return b"\xAA"*100#(0xFFF-3) - - -if __name__ == "__main__": - serial = os.getenv("SERIAL") if os.getenv("SERIAL") else None - kbaud = int(os.getenv("CANKBAUD")) if os.getenv("CANKBAUD") else 500 # type: ignore - bitwidth = int(os.getenv("CANBITWIDTH")) if os.getenv("CANBITWIDTH") else 0 # type: ignore - canenable = bool(int(os.getenv("CANENABLE"))) if os.getenv("CANENABLE") else True # type: ignore - linenable = bool(int(os.getenv("LINENABLE"))) if os.getenv("LINENABLE") else True # type: ignore - sim = ELMCarSimulator(serial, can_kbaud=kbaud, can=canenable, lin=linenable) - if(bitwidth == 0): - sim.can_mode_11b_29b() - if(bitwidth == 11): - sim.can_mode_11b() - if(bitwidth == 29): - sim.can_mode_29b() - - import signal - - def signal_handler(signal, frame): - print('\nShutting down simulator') - sim.stop() - sim.join() - sys.exit(0) - - signal.signal(signal.SIGINT, signal_handler) - - sim.start() - - signal.pause() diff --git a/panda/tests/elm_throughput.py b/panda/tests/elm_throughput.py deleted file mode 100644 index 983d4a1..0000000 --- a/panda/tests/elm_throughput.py +++ /dev/null @@ -1,44 +0,0 @@ -#!/usr/bin/env python3 - -import socket -import threading -import select - -class Reader(threading.Thread): - def __init__(self, s, *args, **kwargs): - super().__init__(*args, **kwargs) - self._s = s - self.__stop = False - - def stop(self): - self.__stop = True - - def run(self): - while not self.__stop: - s.recv(1000) - -def read_or_fail(s): - ready = select.select([s], [], [], 4) - assert ready[0], "Socket did not receive data within the timeout duration." - return s.recv(1000) - -def send_msg(s, msg): - s.send(msg) - res = b'' - while not res.endswith(">"): - res += read_or_fail(s) - return res - -if __name__ == "__main__": - s = socket.create_connection(("192.168.0.10", 35000)) - send_msg(s, b"ATZ\r") - send_msg(s, b"ATL1\r") - print(send_msg(s, b"ATE0\r")) - print(send_msg(s, b"ATS0\r")) - print(send_msg(s, b"ATSP6\r")) - - print("\nLOOP\n") - - while True: - print(send_msg(s, b"0100\r")) - print(send_msg(s, b"010d\r")) diff --git a/panda/tests/fan/fan_test.py b/panda/tests/fan/fan_test.py deleted file mode 100644 index 36a1171..0000000 --- a/panda/tests/fan/fan_test.py +++ /dev/null @@ -1,14 +0,0 @@ -#!/usr/bin/env python -import time - -from panda import Panda - -if __name__ == "__main__": - p = Panda() - power = 0 - while True: - p.set_fan_power(power) - time.sleep(5) - print("Power: ", power, "RPM:", str(p.get_fan_rpm()), "Expected:", int(6500 * power / 100)) - power += 10 - power %= 110 diff --git a/panda/tests/fan/fan_tuning.py b/panda/tests/fan/fan_tuning.py deleted file mode 100644 index 2bdfab7..0000000 --- a/panda/tests/fan/fan_tuning.py +++ /dev/null @@ -1,88 +0,0 @@ -#!/usr/bin/env python3 -import json -import time -import threading - -from panda import Panda - -def drain_serial(p): - ret = [] - while True: - d = p.serial_read(0) - if len(d) == 0: - break - ret.append(d) - return ret - - -fan_cmd = 0. - -def logger(event): - # requires a build with DEBUG_FAN - with Panda(claim=False) as p, open('/tmp/fan_log', 'w') as f: - power = None - target_rpm = None - stall_count = None - rpm_fast = None - t = time.monotonic() - - drain_serial(p) - while not event.is_set(): - p.set_fan_power(fan_cmd) - - for l in drain_serial(p)[::-1]: - ns = l.decode('utf8').strip().split(' ') - if len(ns) == 4: - target_rpm, rpm_fast, power, stall_count = (int(n, 16) for n in ns) - break - - dat = { - 't': time.monotonic() - t, - 'cmd_power': fan_cmd, - 'pwm_power': power, - 'target_rpm': target_rpm, - 'rpm_fast': rpm_fast, - 'rpm': p.get_fan_rpm(), - 'stall_counter': stall_count, - 'total_stall_count': p.health()['fan_stall_count'], - } - f.write(json.dumps(dat) + '\n') - time.sleep(1/16.) - p.set_fan_power(0) - -def get_overshoot_rpm(p, power): - global fan_cmd - - # make sure the fan is stopped completely - fan_cmd = 0. - while p.get_fan_rpm() > 100: - time.sleep(0.1) - time.sleep(3) - - # set it to 30% power to mimic going onroad - fan_cmd = power - max_rpm = 0 - max_power = 0 - for _ in range(70): - max_rpm = max(max_rpm, p.get_fan_rpm()) - max_power = max(max_power, p.health()['fan_power']) - time.sleep(0.1) - - # tolerate 10% overshoot - expected_rpm = Panda.MAX_FAN_RPMs[bytes(p.get_type())] * power / 100 - overshoot = (max_rpm / expected_rpm) - 1 - - return overshoot, max_rpm, max_power - - -if __name__ == "__main__": - event = threading.Event() - threading.Thread(target=logger, args=(event, )).start() - - try: - p = Panda() - for power in range(10, 101, 10): - overshoot, max_rpm, max_power = get_overshoot_rpm(p, power) - print(f"Fan power {power}%: overshoot {overshoot:.2%}, Max RPM {max_rpm}, Max power {max_power}%") - finally: - event.set() diff --git a/panda/tests/get_version.py b/panda/tests/get_version.py deleted file mode 100644 index a013812..0000000 --- a/panda/tests/get_version.py +++ /dev/null @@ -1,7 +0,0 @@ -#!/usr/bin/env python3 -from panda import Panda - -if __name__ == "__main__": - for p in Panda.list(): - pp = Panda(p) - print(f"{pp.get_serial()[0]}: {pp.get_version()}") diff --git a/panda/tests/gmbitbang/recv.py b/panda/tests/gmbitbang/recv.py deleted file mode 100644 index 8dc594d..0000000 --- a/panda/tests/gmbitbang/recv.py +++ /dev/null @@ -1,18 +0,0 @@ -#!/usr/bin/env python3 - -from panda import Panda - -if __name__ == "__main__": - p = Panda() - p.set_safety_mode(Panda.SAFETY_ALLOUTPUT) - p.set_gmlan(bus=2) - #p.can_send(0xaaa, b"\x00\x00", bus=3) - last_add: int | None = None - while True: - ret = p.can_recv() - if len(ret) > 0: - add = ret[0][0] - if last_add is not None and add != last_add + 1: - print("MISS: ", last_add, add) - last_add = add - print(ret) diff --git a/panda/tests/gmbitbang/rigol.py b/panda/tests/gmbitbang/rigol.py deleted file mode 100644 index 818df74..0000000 --- a/panda/tests/gmbitbang/rigol.py +++ /dev/null @@ -1,36 +0,0 @@ -#!/usr/bin/env python3 -# pylint: skip-file -# type: ignore -import numpy as np -import visa -import matplotlib.pyplot as plt - -resources = visa.ResourceManager() -print(resources.list_resources()) - -scope = resources.open_resource('USB0::0x1AB1::0x04CE::DS1ZA184652242::INSTR', timeout=2000, chunk_size=1024000) -print(scope.query('*IDN?').strip()) - -#voltscale = scope.ask_for_values(':CHAN1:SCAL?')[0] -#voltoffset = scope.ask_for_values(":CHAN1:OFFS?")[0] - -#scope.write(":STOP") -scope.write(":WAV:POIN:MODE RAW") -scope.write(":WAV:DATA? CHAN1")[10:] -rawdata = scope.read_raw() -data = np.frombuffer(rawdata, 'B') -print(data.shape) - -s1 = data[0:650] -s2 = data[650:] -s1i = np.argmax(s1 > 100) -s2i = np.argmax(s2 > 100) -s1 = s1[s1i:] -s2 = s2[s2i:] - -plt.plot(s1) -plt.plot(s2) -plt.show() -#data = (data - 130.0 - voltoffset/voltscale*25) / 25 * voltscale - -print(data) diff --git a/panda/tests/gmbitbang/test.py b/panda/tests/gmbitbang/test.py deleted file mode 100644 index b804113..0000000 --- a/panda/tests/gmbitbang/test.py +++ /dev/null @@ -1,32 +0,0 @@ -#!/usr/bin/env python3 -import time -from panda import Panda - -p1 = Panda('380016000551363338383037') -p2 = Panda('430026000951363338383037') - -# this is a test, no safety -p1.set_safety_mode(Panda.SAFETY_ALLOUTPUT) -p2.set_safety_mode(Panda.SAFETY_ALLOUTPUT) - -# get versions -print(p1.get_version()) -print(p2.get_version()) - -# this sets bus 2 to actually be GMLAN -p2.set_gmlan(bus=2) - -# send w bitbang then without -#iden = 123 -iden = 18000 -#dat = "\x01\x02" -dat = "\x01\x02\x03\x04\x05\x06\x07\x08" -while 1: - iden += 1 - p1.set_gmlan(bus=None) - p1.can_send(iden, dat, bus=3) - #p1.set_gmlan(bus=2) - #p1.can_send(iden, dat, bus=3) - time.sleep(0.01) - print(p2.can_recv()) - #exit(0) diff --git a/panda/tests/gmbitbang/test_one.py b/panda/tests/gmbitbang/test_one.py deleted file mode 100644 index 981edc5..0000000 --- a/panda/tests/gmbitbang/test_one.py +++ /dev/null @@ -1,22 +0,0 @@ -#!/usr/bin/env python3 -import time -from panda import Panda - -p = Panda() -p.set_safety_mode(Panda.SAFETY_ALLOUTPUT) - -# hack anything on bus -p.set_gmlan(bus=2) -time.sleep(0.1) -while len(p.can_recv()) > 0: - print("clearing") - time.sleep(0.1) -print("cleared") -p.set_gmlan(bus=None) - -iden = 18000 -dat = "\x01\x02\x03\x04\x05\x06\x07\x08" -while 1: - iden += 1 - p.can_send(iden, dat, bus=3) - time.sleep(0.01) diff --git a/panda/tests/gmbitbang/test_packer.c b/panda/tests/gmbitbang/test_packer.c deleted file mode 100644 index 63c0131..0000000 --- a/panda/tests/gmbitbang/test_packer.c +++ /dev/null @@ -1,28 +0,0 @@ -#include -#include - -#define CANPACKET_DATA_SIZE_MAX 8 -#include "../../board/can_definitions.h" - -#include "../../board/drivers/canbitbang.h" - -int main() { - char out[300]; - CANPacket_t to_bang = {0}; - to_bang.addr = 20 << 18; - to_bang.data_len_code = 1; - to_bang.data[0] = 1; - - int len = get_bit_message(out, &to_bang); - printf("T:"); - for (int i = 0; i < len; i++) { - printf("%d", out[i]); - } - printf("\n"); - printf("R:0000010010100000100010000010011110111010100111111111111111"); - printf("\n"); - return 0; -} - - - diff --git a/panda/tests/gmlan_harness_test.py b/panda/tests/gmlan_harness_test.py deleted file mode 100644 index 950918c..0000000 --- a/panda/tests/gmlan_harness_test.py +++ /dev/null @@ -1,78 +0,0 @@ -#!/usr/bin/env python3 - -import time - -from panda import Panda - -WHITE_GMLAN_BUS = 3 -OTHER_GMLAN_BUS = 1 - -def set_gmlan(p): - if p.get_type() == Panda.HW_TYPE_WHITE_PANDA: - p.set_gmlan(2) - else: - p.set_obd(True) - -def set_speed_kbps(p, speed): - if p.get_type() == Panda.HW_TYPE_WHITE_PANDA: - p.set_can_speed_kbps(WHITE_GMLAN_BUS, speed) - else: - p.set_can_speed_kbps(OTHER_GMLAN_BUS, speed) - -def send(p, id_, msg): - if p.get_type() == Panda.HW_TYPE_WHITE_PANDA: - p.can_send(id_, msg, WHITE_GMLAN_BUS) - else: - p.can_send(id_, msg, OTHER_GMLAN_BUS) - -if __name__ == "__main__": - pl = Panda.list() - assert(len(pl) == 2) - p0 = Panda(pl[1]) - p1 = Panda(pl[0]) - - p0.set_safety_mode(Panda.SAFETY_ALLOUTPUT) - p1.set_safety_mode(Panda.SAFETY_ALLOUTPUT) - - print("0: ", p0.get_type()) - print("1: ", p1.get_type()) - - set_gmlan(p0) - set_gmlan(p1) - - p0.can_clear(0xFFFF) - p1.can_clear(0xFFFF) - - try: - loops = 0 - while True: - for speed in [33.3, 83.3]: - set_speed_kbps(p0, speed) - set_speed_kbps(p1, speed) - p0.can_clear(0xFFFF) - p1.can_clear(0xFFFF) - - print(f"Speed: {speed}") - time.sleep(0.1) - - print("Send 1 -> 0") - send(p1, 1, b"1to0:" + bytes(str(loops%100), "utf-8")) - time.sleep(0.05) - rx = list(filter(lambda x: x[3] < 128, p0.can_recv())) - print(rx) - assert(len(rx) == 1) - - print("Send 0 -> 1") - send(p0, 1, b"0to1:" + bytes(str(loops%100), "utf-8")) - time.sleep(0.05) - rx = list(filter(lambda x: x[3] < 128, p1.can_recv())) - print(rx) - assert(len(rx) == 1) - - time.sleep(0.5) - - - loops += 1 - print(f"Completed {loops} loops") - except Exception: - print("Test failed somehow. Did you power the black panda using the GMLAN harness?") diff --git a/panda/tests/health_test.py b/panda/tests/health_test.py deleted file mode 100644 index 1195c2d..0000000 --- a/panda/tests/health_test.py +++ /dev/null @@ -1,18 +0,0 @@ -#!/usr/bin/env python3 -import time -from panda import Panda - -if __name__ == "__main__": - i = 0 - pi = 0 - - panda = Panda() - while True: - st = time.monotonic() - while time.monotonic() - st < 1: - panda.health() - i += 1 - print(i, panda.health(), "\n") - print(f"Speed: {i - pi}Hz") - pi = i - diff --git a/panda/tests/hitl/1_program.py b/panda/tests/hitl/1_program.py deleted file mode 100644 index 6a5087f..0000000 --- a/panda/tests/hitl/1_program.py +++ /dev/null @@ -1,103 +0,0 @@ -import os -import time -import pytest - -from panda import Panda, PandaDFU, McuType, BASEDIR - - -def check_signature(p): - assert not p.bootstub, "Flashed firmware not booting. Stuck in bootstub." - assert p.up_to_date() - - -def test_dfu(p): - app_mcu_type = p.get_mcu_type() - dfu_serial = p.get_dfu_serial() - - p.reset(enter_bootstub=True) - p.reset(enter_bootloader=True) - assert Panda.wait_for_dfu(dfu_serial, timeout=19), "failed to enter DFU" - - dfu = PandaDFU(dfu_serial) - assert dfu.get_mcu_type() == app_mcu_type - - assert dfu_serial in PandaDFU.list() - - dfu._handle.clear_status() - dfu.reset() - p.reconnect() - -# TODO: make more comprehensive bootstub tests and run on a few production ones + current -# TODO: also test release-signed app -@pytest.mark.timeout(30) -def test_known_bootstub(p): - """ - Test that compiled app can work with known production bootstub - """ - known_bootstubs = { - # covers the two cases listed in Panda.connect - McuType.F4: [ - # case A - no bcdDevice or panda type, has to assume F4 - "bootstub_f4_first_dos_production.panda.bin", - - # case B - just bcdDevice - "bootstub_f4_only_bcd.panda.bin", - ], - McuType.H7: ["bootstub.panda_h7.bin"], - } - - for kb in known_bootstubs[p.get_mcu_type()]: - app_ids = (p.get_mcu_type(), p.get_usb_serial()) - assert None not in app_ids - - p.reset(enter_bootstub=True) - p.reset(enter_bootloader=True) - - dfu_serial = p.get_dfu_serial() - assert Panda.wait_for_dfu(dfu_serial, timeout=30) - - dfu = PandaDFU(dfu_serial) - with open(os.path.join(BASEDIR, "tests/hitl/known_bootstub", kb), "rb") as f: - code = f.read() - - dfu.program_bootstub(code) - dfu.reset() - - p.connect(claim=False, wait=True) - - # check for MCU or serial mismatch - with Panda(p._serial, claim=False) as np: - bootstub_ids = (np.get_mcu_type(), np.get_usb_serial()) - assert app_ids == bootstub_ids - - # ensure we can flash app and it jumps to app - p.flash() - check_signature(p) - assert not p.bootstub - -@pytest.mark.timeout(25) -def test_recover(p): - assert p.recover(timeout=30) - check_signature(p) - -@pytest.mark.timeout(25) -def test_flash(p): - # test flash from bootstub - serial = p._serial - assert serial is not None - p.reset(enter_bootstub=True) - p.close() - time.sleep(2) - - with Panda(serial) as np: - assert np.bootstub - assert np._serial == serial - np.flash() - - p.reconnect() - p.reset() - check_signature(p) - - # test flash from app - p.flash() - check_signature(p) diff --git a/panda/tests/hitl/2_health.py b/panda/tests/hitl/2_health.py deleted file mode 100644 index acb993f..0000000 --- a/panda/tests/hitl/2_health.py +++ /dev/null @@ -1,125 +0,0 @@ -import time -import pytest - -from panda import Panda -from panda import PandaJungle -from panda.tests.hitl.conftest import PandaGroup - - -def test_ignition(p, panda_jungle): - # Set harness orientation to #2, since the ignition line is on the wrong SBU bus :/ - panda_jungle.set_harness_orientation(PandaJungle.HARNESS_ORIENTATION_2) - p.reset() - - for ign in (True, False): - panda_jungle.set_ignition(ign) - time.sleep(0.1) - assert p.health()['ignition_line'] == ign - - -@pytest.mark.test_panda_types(PandaGroup.GEN2) -def test_harness_status(p, panda_jungle): - flipped = None - for ignition in [True, False]: - for orientation in [Panda.HARNESS_STATUS_NC, Panda.HARNESS_STATUS_NORMAL, Panda.HARNESS_STATUS_FLIPPED]: - panda_jungle.set_harness_orientation(orientation) - panda_jungle.set_ignition(ignition) - time.sleep(1) - - health = p.health() - detected_orientation = health['car_harness_status'] - print(f"set: {orientation} detected: {detected_orientation}") - - # Orientation - if orientation == Panda.HARNESS_STATUS_NC: - assert detected_orientation == Panda.HARNESS_STATUS_NC - else: - if flipped is None: - flipped = (detected_orientation != orientation) - - if orientation == Panda.HARNESS_STATUS_NORMAL: - assert detected_orientation == (Panda.HARNESS_STATUS_FLIPPED if flipped else Panda.HARNESS_STATUS_NORMAL) - else: - assert detected_orientation == (Panda.HARNESS_STATUS_NORMAL if flipped else Panda.HARNESS_STATUS_FLIPPED) - - # Line ignition - assert health['ignition_line'] == (False if orientation == Panda.HARNESS_STATUS_NC else ignition) - - # SBU voltages - supply_voltage_mV = 1800 if p.get_type() in [Panda.HW_TYPE_TRES, ] else 3300 - - if orientation == Panda.HARNESS_STATUS_NC: - assert health['sbu1_voltage_mV'] > 0.9 * supply_voltage_mV - assert health['sbu2_voltage_mV'] > 0.9 * supply_voltage_mV - else: - relay_line = 'sbu1_voltage_mV' if (detected_orientation == Panda.HARNESS_STATUS_FLIPPED) else 'sbu2_voltage_mV' - ignition_line = 'sbu2_voltage_mV' if (detected_orientation == Panda.HARNESS_STATUS_FLIPPED) else 'sbu1_voltage_mV' - - assert health[relay_line] < 0.1 * supply_voltage_mV - assert health[ignition_line] > health[relay_line] - if ignition: - assert health[ignition_line] < 0.3 * supply_voltage_mV - else: - assert health[ignition_line] > 0.9 * supply_voltage_mV - - - -@pytest.mark.skip_panda_types((Panda.HW_TYPE_DOS, )) -def test_voltage(p): - for _ in range(10): - voltage = p.health()['voltage'] - assert ((voltage > 11000) and (voltage < 13000)) - time.sleep(0.1) - -def test_hw_type(p): - """ - hw type should be same in bootstub as application - """ - - hw_type = p.get_type() - mcu_type = p.get_mcu_type() - assert mcu_type is not None - - app_uid = p.get_uid() - usb_serial = p.get_usb_serial() - assert app_uid == usb_serial - - p.reset(enter_bootstub=True, reconnect=True) - p.close() - time.sleep(3) - with Panda(p.get_usb_serial()) as pp: - assert pp.bootstub - assert pp.get_type() == hw_type, "Bootstub and app hw type mismatch" - assert pp.get_mcu_type() == mcu_type, "Bootstub and app MCU type mismatch" - assert pp.get_uid() == app_uid - -def test_heartbeat(p, panda_jungle): - panda_jungle.set_ignition(True) - # TODO: add more cases here once the tests aren't super slow - p.set_safety_mode(mode=Panda.SAFETY_HYUNDAI, param=Panda.FLAG_HYUNDAI_LONG) - p.send_heartbeat() - assert p.health()['safety_mode'] == Panda.SAFETY_HYUNDAI - assert p.health()['safety_param'] == Panda.FLAG_HYUNDAI_LONG - - # shouldn't do anything once we're in a car safety mode - p.set_heartbeat_disabled() - - time.sleep(6.) - - h = p.health() - assert h['heartbeat_lost'] - assert h['safety_mode'] == Panda.SAFETY_SILENT - assert h['safety_param'] == 0 - assert h['controls_allowed'] == 0 - -def test_microsecond_timer(p): - start_time = p.get_microsecond_timer() - time.sleep(1) - end_time = p.get_microsecond_timer() - - # account for uint32 overflow - if end_time < start_time: - end_time += 2**32 - - time_diff = (end_time - start_time) / 1e6 - assert 0.98 < time_diff < 1.02, f"Timer not running at the correct speed! (got {time_diff:.2f}s instead of 1.0s)" diff --git a/panda/tests/hitl/3_usb_to_can.py b/panda/tests/hitl/3_usb_to_can.py deleted file mode 100644 index 9321eb4..0000000 --- a/panda/tests/hitl/3_usb_to_can.py +++ /dev/null @@ -1,127 +0,0 @@ -import time -import pytest -from flaky import flaky - -from panda import Panda -from panda.tests.hitl.conftest import SPEED_NORMAL, SPEED_GMLAN, PandaGroup -from panda.tests.hitl.helpers import time_many_sends - -def test_can_loopback(p): - p.set_safety_mode(Panda.SAFETY_ALLOUTPUT) - p.set_can_loopback(True) - - for bus in (0, 1, 2): - # set bus 0 speed to 5000 - p.set_can_speed_kbps(bus, 500) - - # send a message on bus 0 - p.can_send(0x1aa, b"message", bus) - - # confirm receive both on loopback and send receipt - time.sleep(0.05) - r = p.can_recv() - sr = [x for x in r if x[3] == 0x80 | bus] - lb = [x for x in r if x[3] == bus] - assert len(sr) == 1 - assert len(lb) == 1 - - # confirm data is correct - assert 0x1aa == sr[0][0] == lb[0][0] - assert b"message" == sr[0][2] == lb[0][2] - -def test_reliability(p): - MSG_COUNT = 100 - - p.set_safety_mode(Panda.SAFETY_ALLOUTPUT) - p.set_can_loopback(True) - p.set_can_speed_kbps(0, 1000) - - addrs = list(range(100, 100 + MSG_COUNT)) - ts = [(j, 0, b"\xaa" * 8, 0) for j in addrs] - - for _ in range(100): - st = time.monotonic() - - p.can_send_many(ts) - - r = [] - while len(r) < 200 and (time.monotonic() - st) < 0.5: - r.extend(p.can_recv()) - - sent_echo = [x for x in r if x[3] == 0x80] - loopback_resp = [x for x in r if x[3] == 0] - - assert sorted([x[0] for x in loopback_resp]) == addrs - assert sorted([x[0] for x in sent_echo]) == addrs - assert len(r) == 200 - - # take sub 20ms - et = (time.monotonic() - st) * 1000.0 - assert et < 20 - -@flaky(max_runs=6, min_passes=1) -def test_throughput(p): - # enable output mode - p.set_safety_mode(Panda.SAFETY_ALLOUTPUT) - - # enable CAN loopback mode - p.set_can_loopback(True) - - for speed in [10, 20, 50, 100, 125, 250, 500, 1000]: - # set bus 0 speed to speed - p.set_can_speed_kbps(0, speed) - time.sleep(0.05) - - comp_kbps = time_many_sends(p, 0) - - # bit count from https://en.wikipedia.org/wiki/CAN_bus - saturation_pct = (comp_kbps / speed) * 100.0 - assert saturation_pct > 80 - assert saturation_pct < 100 - - print("loopback 100 messages at speed %d, comp speed is %.2f, percent %.2f" % (speed, comp_kbps, saturation_pct)) - -@pytest.mark.test_panda_types(PandaGroup.GMLAN) -def test_gmlan(p): - p.set_safety_mode(Panda.SAFETY_ALLOUTPUT) - p.set_can_loopback(True) - - # set gmlan on CAN2 - for bus in [Panda.GMLAN_CAN2, Panda.GMLAN_CAN3, Panda.GMLAN_CAN2, Panda.GMLAN_CAN3]: - p.set_gmlan(bus) - comp_kbps_gmlan = time_many_sends(p, 3) - assert comp_kbps_gmlan > (0.8 * SPEED_GMLAN) - assert comp_kbps_gmlan < (1.0 * SPEED_GMLAN) - - p.set_gmlan(None) - comp_kbps_normal = time_many_sends(p, bus) - assert comp_kbps_normal > (0.8 * SPEED_NORMAL) - assert comp_kbps_normal < (1.0 * SPEED_NORMAL) - - print("%d: %.2f kbps vs %.2f kbps" % (bus, comp_kbps_gmlan, comp_kbps_normal)) - -@pytest.mark.test_panda_types(PandaGroup.GMLAN) -def test_gmlan_bad_toggle(p): - p.set_safety_mode(Panda.SAFETY_ALLOUTPUT) - p.set_can_loopback(True) - - # GMLAN_CAN2 - for bus in [Panda.GMLAN_CAN2, Panda.GMLAN_CAN3]: - p.set_gmlan(bus) - comp_kbps_gmlan = time_many_sends(p, 3) - assert comp_kbps_gmlan > (0.6 * SPEED_GMLAN) - assert comp_kbps_gmlan < (1.0 * SPEED_GMLAN) - - # normal - for bus in [Panda.GMLAN_CAN2, Panda.GMLAN_CAN3]: - p.set_gmlan(None) - comp_kbps_normal = time_many_sends(p, bus) - assert comp_kbps_normal > (0.6 * SPEED_NORMAL) - assert comp_kbps_normal < (1.0 * SPEED_NORMAL) - - -# this will fail if you have hardware serial connected -def test_serial_debug(p): - _ = p.serial_read(Panda.SERIAL_DEBUG) # junk - p.call_control_api(0x01) - assert p.serial_read(Panda.SERIAL_DEBUG).startswith(b"NO HANDLER") diff --git a/panda/tests/hitl/4_can_loopback.py b/panda/tests/hitl/4_can_loopback.py deleted file mode 100644 index a7e1aea..0000000 --- a/panda/tests/hitl/4_can_loopback.py +++ /dev/null @@ -1,202 +0,0 @@ -import os -import time -import pytest -import random -import threading -from flaky import flaky -from collections import defaultdict - -from panda import Panda -from panda.tests.hitl.conftest import PandaGroup -from panda.tests.hitl.helpers import time_many_sends, get_random_can_messages, clear_can_buffers - -@flaky(max_runs=3, min_passes=1) -@pytest.mark.timeout(35) -def test_send_recv(p, panda_jungle): - def test(p_send, p_recv): - for bus in (0, 1, 2): - for speed in (10, 20, 50, 100, 125, 250, 500, 1000): - clear_can_buffers(p_send, speed) - clear_can_buffers(p_recv, speed) - - comp_kbps = time_many_sends(p_send, bus, p_recv, two_pandas=True) - - saturation_pct = (comp_kbps / speed) * 100.0 - assert 80 < saturation_pct < 100 - - print(f"two pandas bus {bus}, 100 messages at speed {speed:4d}, comp speed is {comp_kbps:7.2f}, {saturation_pct:6.2f}%") - - # Run tests in both directions - p.set_safety_mode(Panda.SAFETY_ALLOUTPUT) - test(p, panda_jungle) - test(panda_jungle, p) - - -@flaky(max_runs=6, min_passes=1) -@pytest.mark.timeout(30) -def test_latency(p, panda_jungle): - def test(p_send, p_recv): - for bus in (0, 1, 2): - for speed in (10, 20, 50, 100, 125, 250, 500, 1000): - clear_can_buffers(p_send, speed) - clear_can_buffers(p_recv, speed) - - latencies = [] - comp_kbps_list = [] - saturation_pcts = [] - - num_messages = 100 - - for _ in range(num_messages): - st = time.monotonic() - p_send.can_send(0x1ab, b"message", bus) - r = [] - while len(r) < 1 and (time.monotonic() - st) < 5: - r = p_recv.can_recv() - et = time.monotonic() - r_echo = [] - while len(r_echo) < 1 and (time.monotonic() - st) < 10: - r_echo = p_send.can_recv() - - if len(r) == 0 or len(r_echo) == 0: - print(f"r: {r}, r_echo: {r_echo}") - - assert len(r) == 1 - assert len(r_echo) == 1 - - et = (et - st) * 1000.0 - comp_kbps = (1 + 11 + 1 + 1 + 1 + 4 + 8 * 8 + 15 + 1 + 1 + 1 + 7) / et - latency = et - ((1 + 11 + 1 + 1 + 1 + 4 + 8 * 8 + 15 + 1 + 1 + 1 + 7) / speed) - - assert latency < 5.0 - - saturation_pct = (comp_kbps / speed) * 100.0 - latencies.append(latency) - comp_kbps_list.append(comp_kbps) - saturation_pcts.append(saturation_pct) - - average_latency = sum(latencies) / num_messages - assert average_latency < 1.0 - average_comp_kbps = sum(comp_kbps_list) / num_messages - average_saturation_pct = sum(saturation_pcts) / num_messages - - print("two pandas bus {}, {} message average at speed {:4d}, latency is {:5.3f}ms, comp speed is {:7.2f}, percent {:6.2f}" - .format(bus, num_messages, speed, average_latency, average_comp_kbps, average_saturation_pct)) - - # Run tests in both directions - p.set_safety_mode(Panda.SAFETY_ALLOUTPUT) - test(p, panda_jungle) - test(panda_jungle, p) - - -@pytest.mark.panda_expect_can_error -@pytest.mark.test_panda_types(PandaGroup.GEN2) -def test_gen2_loopback(p, panda_jungle): - def test(p_send, p_recv, address=None): - for bus in range(4): - obd = False - if bus == 3: - obd = True - bus = 1 - - # Clear buses - clear_can_buffers(p_send) - clear_can_buffers(p_recv) - - # Send a random string - addr = address if address else random.randint(1, 2000) - string = b"test" + os.urandom(4) - p_send.set_obd(obd) - p_recv.set_obd(obd) - time.sleep(0.2) - p_send.can_send(addr, string, bus) - time.sleep(0.2) - - content = p_recv.can_recv() - - # Check amount of messages - assert len(content) == 1 - - # Check content - assert content[0][0] == addr and content[0][2] == string - - # Check bus - assert content[0][3] == bus - - print("Bus:", bus, "address:", addr, "OBD:", obd, "OK") - - # Run tests in both directions - p.set_safety_mode(Panda.SAFETY_ALLOUTPUT) - test(p, panda_jungle) - test(panda_jungle, p) - - # Test extended frame address with ELM327 mode - p.set_safety_mode(Panda.SAFETY_ELM327) - test(p, panda_jungle, 0x18DB33F1) - test(panda_jungle, p, 0x18DB33F1) - - # TODO: why it's not being reset by fixtures reinit? - p.set_obd(False) - panda_jungle.set_obd(False) - -def test_bulk_write(p, panda_jungle): - # The TX buffers on pandas is 0x100 in length. - NUM_MESSAGES_PER_BUS = 10000 - - def flood_tx(panda): - print('Sending!') - msg = b"\xaa" * 8 - packet = [] - # start with many messages on a single bus (higher contention for single TX ring buffer) - packet += [[0xaa, None, msg, 0]] * NUM_MESSAGES_PER_BUS - # end with many messages on multiple buses - packet += [[0xaa, None, msg, 0], [0xaa, None, msg, 1], [0xaa, None, msg, 2]] * NUM_MESSAGES_PER_BUS - - # Disable timeout - panda.set_safety_mode(Panda.SAFETY_ALLOUTPUT) - panda.can_send_many(packet, timeout=0) - print(f"Done sending {4 * NUM_MESSAGES_PER_BUS} messages!", time.monotonic()) - print(panda.health()) - - # Start transmisson - threading.Thread(target=flood_tx, args=(p,)).start() - - # Receive as much as we can in a few second time period - rx = [] - old_len = 0 - start_time = time.monotonic() - while time.monotonic() - start_time < 5 or len(rx) > old_len: - old_len = len(rx) - rx.extend(panda_jungle.can_recv()) - print(f"Received {len(rx)} messages", time.monotonic()) - - # All messages should have been received - if len(rx) != 4 * NUM_MESSAGES_PER_BUS: - raise Exception("Did not receive all messages!") - -def test_message_integrity(p): - p.set_safety_mode(Panda.SAFETY_ALLOUTPUT) - p.set_can_loopback(True) - for i in range(250): - sent_msgs = defaultdict(set) - for _ in range(random.randrange(10)): - to_send = get_random_can_messages(random.randrange(100)) - for m in to_send: - sent_msgs[m[3]].add((m[0], m[2])) - p.can_send_many(to_send, timeout=0) - - start_time = time.monotonic() - while time.monotonic() - start_time < 2 and any(len(sent_msgs[bus]) for bus in range(3)): - recvd = p.can_recv() - for msg in recvd: - if msg[3] >= 128: - k = (msg[0], bytes(msg[2])) - bus = msg[3]-128 - assert k in sent_msgs[bus], f"message {k} was never sent on bus {bus}" - sent_msgs[msg[3]-128].discard(k) - - # if a set isn't empty, messages got dropped - for bus in range(3): - assert not len(sent_msgs[bus]), f"loop {i}: bus {bus} missing {len(sent_msgs[bus])} messages" - - print("Got all messages intact") diff --git a/panda/tests/hitl/5_spi.py b/panda/tests/hitl/5_spi.py deleted file mode 100644 index f9a4e28..0000000 --- a/panda/tests/hitl/5_spi.py +++ /dev/null @@ -1,103 +0,0 @@ -import binascii -import pytest -import random -from unittest.mock import patch - -from panda import Panda, PandaDFU -from panda.python.spi import SpiDevice, PandaProtocolMismatch, PandaSpiNackResponse - -pytestmark = [ - pytest.mark.test_panda_types((Panda.HW_TYPE_TRES, )) -] - -@pytest.mark.skip("doesn't work, bootloader seems to ignore commands once it sees junk") -def test_dfu_with_spam(p): - dfu_serial = p.get_dfu_serial() - - # enter DFU - p.reset(enter_bootstub=True) - p.reset(enter_bootloader=True) - assert Panda.wait_for_dfu(dfu_serial, timeout=19), "failed to enter DFU" - - # send junk - d = SpiDevice() - for _ in range(9): - with d.acquire() as spi: - dat = [random.randint(-1, 255) for _ in range(random.randint(1, 100))] - spi.xfer(dat) - - # should still show up - assert dfu_serial in PandaDFU.list() - -class TestSpi: - def _ping(self, mocker, panda): - # should work with no retries - spy = mocker.spy(panda._handle, '_wait_for_ack') - panda.health() - assert spy.call_count == 2 - mocker.stop(spy) - - def test_protocol_version_check(self, p): - for bootstub in (False, True): - p.reset(enter_bootstub=bootstub) - with patch('panda.python.spi.PandaSpiHandle.PROTOCOL_VERSION', return_value="abc"): - # list should still work with wrong version - assert p._serial in Panda.list() - - # connect but raise protocol error - with pytest.raises(PandaProtocolMismatch): - Panda(p._serial) - - def test_protocol_version_data(self, p): - for bootstub in (False, True): - p.reset(enter_bootstub=bootstub) - v = p._handle.get_protocol_version() - - uid = binascii.hexlify(v[:12]).decode() - assert uid == p.get_uid() - - hwtype = v[12] - assert hwtype == ord(p.get_type()) - - bstub = v[13] - assert bstub == (0xEE if bootstub else 0xCC) - - def test_all_comm_types(self, mocker, p): - spy = mocker.spy(p._handle, '_wait_for_ack') - - # controlRead + controlWrite - p.health() - p.can_clear(0) - assert spy.call_count == 2*2 - - # bulkRead + bulkWrite - p.can_recv() - p.can_send(0x123, b"somedata", 0) - assert spy.call_count == 2*4 - - def test_bad_header(self, mocker, p): - with patch('panda.python.spi.SYNC', return_value=0): - with pytest.raises(PandaSpiNackResponse): - p._handle.controlRead(Panda.REQUEST_IN, 0xd2, 0, 0, p.HEALTH_STRUCT.size, timeout=50) - self._ping(mocker, p) - - def test_bad_checksum(self, mocker, p): - cnt = p.health()['spi_checksum_error_count'] - with patch('panda.python.spi.PandaSpiHandle._calc_checksum', return_value=0): - with pytest.raises(PandaSpiNackResponse): - p._handle.controlRead(Panda.REQUEST_IN, 0xd2, 0, 0, p.HEALTH_STRUCT.size, timeout=50) - self._ping(mocker, p) - assert (p.health()['spi_checksum_error_count'] - cnt) > 0 - - def test_non_existent_endpoint(self, mocker, p): - for _ in range(10): - ep = random.randint(4, 20) - with pytest.raises(PandaSpiNackResponse): - p._handle.bulkRead(ep, random.randint(1, 1000), timeout=50) - - self._ping(mocker, p) - - with pytest.raises(PandaSpiNackResponse): - p._handle.bulkWrite(ep, b"abc", timeout=50) - - self._ping(mocker, p) diff --git a/panda/tests/hitl/6_safety.py b/panda/tests/hitl/6_safety.py deleted file mode 100644 index 2237f53..0000000 --- a/panda/tests/hitl/6_safety.py +++ /dev/null @@ -1,29 +0,0 @@ -import time - -from panda import Panda - - -def test_safety_nooutput(p): - p.set_safety_mode(Panda.SAFETY_SILENT) - p.set_can_loopback(True) - - # send a message on bus 0 - p.can_send(0x1aa, b"message", 0) - - # confirm receive nothing - time.sleep(0.05) - r = p.can_recv() - # bus 192 is messages blocked by TX safety hook on bus 0 - assert len([x for x in r if x[3] != 192]) == 0 - assert len([x for x in r if x[3] == 192]) == 1 - - -def test_canfd_safety_modes(p): - # works on all pandas - p.set_safety_mode(Panda.SAFETY_TOYOTA) - assert p.health()['safety_mode'] == Panda.SAFETY_TOYOTA - - # shouldn't be able to set a CAN-FD safety mode on non CAN-FD panda - p.set_safety_mode(Panda.SAFETY_HYUNDAI_CANFD) - expected_mode = Panda.SAFETY_HYUNDAI_CANFD if p.get_type() in Panda.H7_DEVICES else Panda.SAFETY_SILENT - assert p.health()['safety_mode'] == expected_mode diff --git a/panda/tests/hitl/7_internal.py b/panda/tests/hitl/7_internal.py deleted file mode 100644 index eb8577f..0000000 --- a/panda/tests/hitl/7_internal.py +++ /dev/null @@ -1,68 +0,0 @@ -import time -import pytest - -from panda import Panda - -pytestmark = [ - pytest.mark.skip_panda_types(Panda.HW_TYPE_UNO), - pytest.mark.test_panda_types(Panda.INTERNAL_DEVICES) -] - -@pytest.mark.timeout(2*60) -def test_fan_controller(p): - start_health = p.health() - - for power in (30, 50, 80, 100): - p.set_fan_power(0) - while p.get_fan_rpm() > 0: - time.sleep(0.1) - - # wait until fan spins up (and recovers if needed), - # then wait a bit more for the RPM to converge - p.set_fan_power(power) - for _ in range(20): - time.sleep(1) - if p.get_fan_rpm() > 1000: - break - time.sleep(5) - - expected_rpm = Panda.MAX_FAN_RPMs[bytes(p.get_type())] * power / 100 - assert 0.9 * expected_rpm <= p.get_fan_rpm() <= 1.1 * expected_rpm - - # Ensure the stall detection is tested on dos - if p.get_type() == Panda.HW_TYPE_DOS: - stalls = p.health()['fan_stall_count'] - start_health['fan_stall_count'] - assert stalls >= 2 - print("stall count", stalls) - else: - assert p.health()['fan_stall_count'] == 0 - -def test_fan_cooldown(p): - # if the fan cooldown doesn't work, we get high frequency noise on the tach line - # while the rotor spins down. this makes sure it never goes beyond the expected max RPM - p.set_fan_power(100) - time.sleep(3) - p.set_fan_power(0) - for _ in range(5): - assert p.get_fan_rpm() <= 7000 - time.sleep(0.5) - -def test_fan_overshoot(p): - if p.get_type() == Panda.HW_TYPE_DOS: - pytest.skip("panda's fan controller overshoots on the comma three fans that need stall recovery") - - # make sure it's stopped completely - p.set_fan_power(0) - while p.get_fan_rpm() > 0: - time.sleep(0.1) - - # set it to 30% power to mimic going onroad - p.set_fan_power(30) - max_rpm = 0 - for _ in range(50): - max_rpm = max(max_rpm, p.get_fan_rpm()) - time.sleep(0.1) - - # tolerate 10% overshoot - expected_rpm = Panda.MAX_FAN_RPMs[bytes(p.get_type())] * 30 / 100 - assert max_rpm <= 1.1 * expected_rpm, f"Fan overshoot: {(max_rpm / expected_rpm * 100) - 100:.1f}%" diff --git a/panda/tests/hitl/__init__.py b/panda/tests/hitl/__init__.py deleted file mode 100644 index e69de29..0000000 diff --git a/panda/tests/hitl/conftest.py b/panda/tests/hitl/conftest.py deleted file mode 100644 index b784435..0000000 --- a/panda/tests/hitl/conftest.py +++ /dev/null @@ -1,225 +0,0 @@ -import os -import pytest -import concurrent.futures - -from panda import Panda, PandaDFU, PandaJungle -from panda.tests.hitl.helpers import clear_can_buffers - -# needed to get output when using xdist -if "DEBUG" in os.environ: - import sys - sys.stdout = sys.stderr - -SPEED_NORMAL = 500 -SPEED_GMLAN = 33.3 -BUS_SPEEDS = [(0, SPEED_NORMAL), (1, SPEED_NORMAL), (2, SPEED_NORMAL), (3, SPEED_GMLAN)] - - -JUNGLE_SERIAL = os.getenv("PANDAS_JUNGLE") -NO_JUNGLE = os.environ.get("NO_JUNGLE", "0") == "1" -PANDAS_EXCLUDE = os.getenv("PANDAS_EXCLUDE", "").strip().split(" ") -HW_TYPES = os.environ.get("HW_TYPES", None) - -PARALLEL = "PARALLEL" in os.environ -NON_PARALLEL = "NON_PARALLEL" in os.environ -if PARALLEL: - NO_JUNGLE = True - -class PandaGroup: - H7 = (Panda.HW_TYPE_RED_PANDA, Panda.HW_TYPE_RED_PANDA_V2, Panda.HW_TYPE_TRES) - GEN2 = (Panda.HW_TYPE_BLACK_PANDA, Panda.HW_TYPE_UNO, Panda.HW_TYPE_DOS) + H7 - GMLAN = (Panda.HW_TYPE_WHITE_PANDA, Panda.HW_TYPE_GREY_PANDA) - - TESTED = (Panda.HW_TYPE_WHITE_PANDA, Panda.HW_TYPE_BLACK_PANDA, Panda.HW_TYPE_RED_PANDA, Panda.HW_TYPE_RED_PANDA_V2, Panda.HW_TYPE_UNO) - -if HW_TYPES is not None: - PandaGroup.TESTED = [bytes([int(x), ]) for x in HW_TYPES.strip().split(",")] # type: ignore - - -# Find all pandas connected -_all_pandas = {} -_panda_jungle = None -def init_all_pandas(): - if not NO_JUNGLE: - global _panda_jungle - _panda_jungle = PandaJungle(JUNGLE_SERIAL) - _panda_jungle.set_panda_power(True) - - for serial in Panda.list(): - if serial not in PANDAS_EXCLUDE: - with Panda(serial=serial, claim=False) as p: - ptype = bytes(p.get_type()) - if ptype in PandaGroup.TESTED: - _all_pandas[serial] = ptype - - # ensure we have all tested panda types - missing_types = set(PandaGroup.TESTED) - set(_all_pandas.values()) - assert len(missing_types) == 0, f"Missing panda types: {missing_types}" - - print(f"{len(_all_pandas)} total pandas") -init_all_pandas() -_all_panda_serials = sorted(_all_pandas.keys()) - - -def init_jungle(): - if _panda_jungle is None: - return - clear_can_buffers(_panda_jungle) - _panda_jungle.set_panda_power(True) - _panda_jungle.set_can_loopback(False) - _panda_jungle.set_obd(False) - _panda_jungle.set_harness_orientation(PandaJungle.HARNESS_ORIENTATION_1) - for bus, speed in BUS_SPEEDS: - _panda_jungle.set_can_speed_kbps(bus, speed) - - # ensure FW hasn't changed - assert _panda_jungle.up_to_date() - - -def pytest_configure(config): - config.addinivalue_line( - "markers", "test_panda_types(name): whitelist a test for specific panda types" - ) - config.addinivalue_line( - "markers", "skip_panda_types(name): blacklist panda types from a test" - ) - config.addinivalue_line( - "markers", "panda_expect_can_error: mark test to ignore CAN health errors" - ) - -@pytest.hookimpl(tryfirst=True) -def pytest_collection_modifyitems(items): - for item in items: - if item.get_closest_marker('timeout') is None: - item.add_marker(pytest.mark.timeout(60)) - - # xdist grouping by panda - serial = item.name.split("serial=")[1].split(",")[0] - assert len(serial) == 24 - item.add_marker(pytest.mark.xdist_group(serial)) - - needs_jungle = "panda_jungle" in item.fixturenames - if PARALLEL and needs_jungle: - item.add_marker(pytest.mark.skip(reason="no jungle tests in PARALLEL mode")) - elif NON_PARALLEL and not needs_jungle: - item.add_marker(pytest.mark.skip(reason="only running jungle tests")) - -def pytest_make_parametrize_id(config, val, argname): - if val in _all_pandas: - # TODO: get nice string instead of int - hw_type = _all_pandas[val][0] - return f"serial={val}, hw_type={hw_type}" - return None - - -@pytest.fixture(name='panda_jungle', scope='function') -def fixture_panda_jungle(request): - init_jungle() - return _panda_jungle - -@pytest.fixture(name='p', scope='function') -def func_fixture_panda(request, module_panda): - p = module_panda - - # Check if test is applicable to this panda - mark = request.node.get_closest_marker('test_panda_types') - if mark: - assert len(mark.args) > 0, "Missing panda types argument in mark" - test_types = mark.args[0] - if _all_pandas[p.get_usb_serial()] not in test_types: - pytest.skip(f"Not applicable, {test_types} pandas only") - - mark = request.node.get_closest_marker('skip_panda_types') - if mark: - assert len(mark.args) > 0, "Missing panda types argument in mark" - skip_types = mark.args[0] - if _all_pandas[p.get_usb_serial()] in skip_types: - pytest.skip(f"Not applicable to {skip_types}") - - # TODO: reset is slow (2+ seconds) - p.reset() - - # ensure FW hasn't changed - assert p.up_to_date() - - # Run test - yield p - - # Teardown - - # reconnect - if p.get_dfu_serial() in PandaDFU.list(): - PandaDFU(p.get_dfu_serial()).reset() - p.reconnect() - if not p.connected: - p.reconnect() - if p.bootstub: - p.reset() - - assert not p.bootstub - - # TODO: would be nice to make these common checks in the teardown - # show up as failed tests instead of "errors" - - # Check for faults - assert p.health()['faults'] == 0 - assert p.health()['fault_status'] == 0 - - # Check for SPI errors - #assert p.health()['spi_checksum_error_count'] == 0 - - # Check health of each CAN core after test, normal to fail for test_gen2_loopback on OBD bus, so skipping - mark = request.node.get_closest_marker('panda_expect_can_error') - expect_can_error = mark is not None - if not expect_can_error: - for i in range(3): - can_health = p.can_health(i) - assert can_health['bus_off_cnt'] == 0 - assert can_health['receive_error_cnt'] < 127 - assert can_health['transmit_error_cnt'] < 255 - assert can_health['error_passive'] == 0 - assert can_health['error_warning'] == 0 - assert can_health['total_rx_lost_cnt'] == 0 - assert can_health['total_tx_lost_cnt'] == 0 - assert can_health['total_error_cnt'] == 0 - assert can_health['total_tx_checksum_error_cnt'] == 0 - -@pytest.fixture(name='module_panda', params=_all_panda_serials, scope='module') -def fixture_panda_setup(request): - """ - Clean up all pandas + jungle and return the panda under test. - """ - panda_serial = request.param - - # Initialize jungle - init_jungle() - - # Connect to pandas - def cnnct(s): - if s == panda_serial: - p = Panda(serial=s) - p.reset(reconnect=True) - - p.set_can_loopback(False) - p.set_gmlan(None) - p.set_power_save(False) - for bus, speed in BUS_SPEEDS: - p.set_can_speed_kbps(bus, speed) - clear_can_buffers(p) - p.set_power_save(False) - return p - elif not PARALLEL: - with Panda(serial=s) as p: - p.reset(reconnect=False) - return None - - with concurrent.futures.ThreadPoolExecutor() as exc: - ps = list(exc.map(cnnct, _all_panda_serials, timeout=20)) - pandas = [p for p in ps if p is not None] - - # run test - yield pandas[0] - - # Teardown - for p in pandas: - p.close() diff --git a/panda/tests/hitl/helpers.py b/panda/tests/hitl/helpers.py deleted file mode 100644 index 4eee437..0000000 --- a/panda/tests/hitl/helpers.py +++ /dev/null @@ -1,71 +0,0 @@ -import time -import random - - -def get_random_can_messages(n): - m = [] - for _ in range(n): - bus = random.randrange(3) - addr = random.randrange(1 << 29) - dat = bytes([random.getrandbits(8) for _ in range(random.randrange(1, 9))]) - m.append([addr, None, dat, bus]) - return m - - -def time_many_sends(p, bus, p_recv=None, msg_count=100, two_pandas=False, msg_len=8): - if p_recv is None: - p_recv = p - if p == p_recv and two_pandas: - raise ValueError("Cannot have two pandas that are the same panda") - - msg_id = random.randint(0x100, 0x200) - to_send = [(msg_id, 0, b"\xaa" * msg_len, bus)] * msg_count - - start_time = time.monotonic() - p.can_send_many(to_send) - r = [] - r_echo = [] - r_len_expected = msg_count if two_pandas else msg_count * 2 - r_echo_len_exected = msg_count if two_pandas else 0 - - while len(r) < r_len_expected and (time.monotonic() - start_time) < 5: - r.extend(p_recv.can_recv()) - end_time = time.monotonic() - if two_pandas: - while len(r_echo) < r_echo_len_exected and (time.monotonic() - start_time) < 10: - r_echo.extend(p.can_recv()) - - sent_echo = [x for x in r if x[3] == 0x80 | bus and x[0] == msg_id] - sent_echo.extend([x for x in r_echo if x[3] == 0x80 | bus and x[0] == msg_id]) - resp = [x for x in r if x[3] == bus and x[0] == msg_id] - - leftovers = [x for x in r if (x[3] != 0x80 | bus and x[3] != bus) or x[0] != msg_id] - assert len(leftovers) == 0 - - assert len(resp) == msg_count - assert len(sent_echo) == msg_count - - end_time = (end_time - start_time) * 1000.0 - comp_kbps = (1 + 11 + 1 + 1 + 1 + 4 + (msg_len * 8) + 15 + 1 + 1 + 1 + 7) * msg_count / end_time - - return comp_kbps - - -def clear_can_buffers(panda, speed: int | None = None): - if speed is not None: - for bus in range(3): - panda.set_can_speed_kbps(bus, speed) - - # clear tx buffers - for i in range(4): - panda.can_clear(i) - - # clear rx buffers - panda.can_clear(0xFFFF) - r = [1] - st = time.monotonic() - while len(r) > 0: - r = panda.can_recv() - time.sleep(0.05) - if (time.monotonic() - st) > 10: - raise Exception("Unable to clear can buffers for panda ", panda.get_serial()) diff --git a/panda/tests/hitl/known_bootstub/bootstub.panda_h7.bin b/panda/tests/hitl/known_bootstub/bootstub.panda_h7.bin deleted file mode 100644 index a6d856b..0000000 Binary files a/panda/tests/hitl/known_bootstub/bootstub.panda_h7.bin and /dev/null differ diff --git a/panda/tests/hitl/known_bootstub/bootstub_f4_first_dos_production.panda.bin b/panda/tests/hitl/known_bootstub/bootstub_f4_first_dos_production.panda.bin deleted file mode 100644 index 786acf6..0000000 Binary files a/panda/tests/hitl/known_bootstub/bootstub_f4_first_dos_production.panda.bin and /dev/null differ diff --git a/panda/tests/hitl/known_bootstub/bootstub_f4_only_bcd.panda.bin b/panda/tests/hitl/known_bootstub/bootstub_f4_only_bcd.panda.bin deleted file mode 100644 index 000fd26..0000000 Binary files a/panda/tests/hitl/known_bootstub/bootstub_f4_only_bcd.panda.bin and /dev/null differ diff --git a/panda/tests/hitl/reset_jungles.py b/panda/tests/hitl/reset_jungles.py deleted file mode 100644 index fb94673..0000000 --- a/panda/tests/hitl/reset_jungles.py +++ /dev/null @@ -1,42 +0,0 @@ -#!/usr/bin/env python3 -import concurrent.futures - -from panda import PandaJungle, PandaJungleDFU, McuType -from panda.tests.libs.resetter import Resetter - -SERIALS = {'180019001451313236343430', '1d0017000c50435635333720'} - -def recover(s): - with PandaJungleDFU(s) as pd: - pd.recover() - -def flash(s): - with PandaJungle(s) as p: - p.flash() - return p.get_mcu_type() - -# Reset + flash all CI hardware to get it into a consistent state -# * port 1: jungles-under-test -# * port 2: USB hubs -# * port 3: HITL pandas and their jungles -if __name__ == "__main__": - with Resetter() as r: - # everything off - for i in range(1, 4): - r.enable_power(i, 0) - r.cycle_power(ports=[1, 2], dfu=True) - - dfu_serials = PandaJungleDFU.list() - print(len(dfu_serials), len(SERIALS)) - assert len(dfu_serials) == len(SERIALS) - - with concurrent.futures.ProcessPoolExecutor(max_workers=len(dfu_serials)) as exc: - list(exc.map(recover, dfu_serials, timeout=30)) - - # power cycle for H7 bootloader bug - r.cycle_power(ports=[1, 2]) - - serials = PandaJungle.list() - assert set(PandaJungle.list()) >= SERIALS - mcu_types = list(exc.map(flash, SERIALS, timeout=20)) - assert set(mcu_types) == {McuType.F4, McuType.H7} diff --git a/panda/tests/hitl/run_parallel_tests.sh b/panda/tests/hitl/run_parallel_tests.sh deleted file mode 100644 index b6b79d9..0000000 --- a/panda/tests/hitl/run_parallel_tests.sh +++ /dev/null @@ -1,8 +0,0 @@ -#!/bin/bash -set -e - -DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" -cd $DIR - -# n = number of pandas tested -PARALLEL=1 pytest --durations=0 *.py -n 5 --dist loadgroup -x diff --git a/panda/tests/hitl/run_serial_tests.sh b/panda/tests/hitl/run_serial_tests.sh deleted file mode 100644 index 31270f0..0000000 --- a/panda/tests/hitl/run_serial_tests.sh +++ /dev/null @@ -1,7 +0,0 @@ -#!/bin/bash -set -e - -DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" -cd $DIR - -NON_PARALLEL=1 pytest --durations=0 *.py -x diff --git a/panda/tests/ir_test.py b/panda/tests/ir_test.py deleted file mode 100644 index e41decf..0000000 --- a/panda/tests/ir_test.py +++ /dev/null @@ -1,14 +0,0 @@ -#!/usr/bin/env python3 -import time - -from panda import Panda - -power = 0 -if __name__ == "__main__": - p = Panda() - while True: - p.set_ir_power(power) - print("Power: ", str(power)) - time.sleep(1) - power += 10 - power %= 100 diff --git a/panda/tests/libpanda/SConscript b/panda/tests/libpanda/SConscript deleted file mode 100644 index cc08907..0000000 --- a/panda/tests/libpanda/SConscript +++ /dev/null @@ -1,42 +0,0 @@ -import platform - -CC = 'gcc' -system = platform.system() -if system == 'Darwin': - # gcc installed by homebrew has version suffix (e.g. gcc-12) in order to be - # distinguishable from system one - which acts as a symlink to clang - CC += '-13' - -env = Environment( - CC=CC, - CFLAGS=[ - '-nostdlib', - '-fno-builtin', - '-std=gnu11', - '-Wfatal-errors', - '-Wno-pointer-to-int-cast', - ], - CPPPATH=[".", "../../board/"], -) -if system == "Darwin": - env.PrependENVPath('PATH', '/opt/homebrew/bin') - -if GetOption('ubsan'): - flags = [ - "-fsanitize=undefined", - "-fno-sanitize-recover=undefined", - ] - env['CFLAGS'] += flags - env['LINKFLAGS'] += flags - -panda = env.SharedObject("panda.os", "panda.c") -libpanda = env.SharedLibrary("libpanda.so", [panda]) - -if GetOption('coverage'): - env.Append( - CFLAGS=["-fprofile-arcs", "-ftest-coverage", "-fprofile-abs-path",], - LIBS=["gcov"], - ) - # GCC note file is generated by compiler, ensure we build it, and allow scons to clean it up - AlwaysBuild(panda) - env.SideEffect("panda.gcno", panda) diff --git a/panda/tests/libpanda/libpanda_py.py b/panda/tests/libpanda/libpanda_py.py deleted file mode 100644 index 8f876c5..0000000 --- a/panda/tests/libpanda/libpanda_py.py +++ /dev/null @@ -1,98 +0,0 @@ -import os -from cffi import FFI -from typing import Any, Protocol - -from panda import LEN_TO_DLC -from panda.tests.libpanda.safety_helpers import PandaSafety, setup_safety_helpers - -libpanda_dir = os.path.dirname(os.path.abspath(__file__)) -libpanda_fn = os.path.join(libpanda_dir, "libpanda.so") - -ffi = FFI() - -ffi.cdef(""" -typedef struct { - unsigned char reserved : 1; - unsigned char bus : 3; - unsigned char data_len_code : 4; - unsigned char rejected : 1; - unsigned char returned : 1; - unsigned char extended : 1; - unsigned int addr : 29; - unsigned char checksum; - unsigned char data[64]; -} CANPacket_t; -""", packed=True) - -ffi.cdef(""" -bool safety_rx_hook(CANPacket_t *to_send); -bool safety_tx_hook(CANPacket_t *to_push); -int safety_fwd_hook(int bus_num, int addr); -int set_safety_hooks(uint16_t mode, uint16_t param); -""") - -ffi.cdef(""" -typedef struct { - volatile uint32_t w_ptr; - volatile uint32_t r_ptr; - uint32_t fifo_size; - CANPacket_t *elems; -} can_ring; - -extern can_ring *rx_q; -extern can_ring *txgmlan_q; -extern can_ring *tx1_q; -extern can_ring *tx2_q; -extern can_ring *tx3_q; - -bool can_pop(can_ring *q, CANPacket_t *elem); -bool can_push(can_ring *q, CANPacket_t *elem); -void can_set_checksum(CANPacket_t *packet); -int comms_can_read(uint8_t *data, uint32_t max_len); -void comms_can_write(uint8_t *data, uint32_t len); -void comms_can_reset(void); -uint32_t can_slots_empty(can_ring *q); -""") - -setup_safety_helpers(ffi) - -class CANPacket: - reserved: int - bus: int - data_len_code: int - rejected: int - returned: int - extended: int - addr: int - data: list[int] - -class Panda(PandaSafety, Protocol): - # CAN - tx1_q: Any - tx2_q: Any - tx3_q: Any - txgmlan_q: Any - def can_set_checksum(self, p: CANPacket) -> None: ... - - # safety - def safety_rx_hook(self, to_send: CANPacket) -> int: ... - def safety_tx_hook(self, to_push: CANPacket) -> int: ... - def safety_fwd_hook(self, bus_num: int, addr: int) -> int: ... - def set_safety_hooks(self, mode: int, param: int) -> int: ... - - -libpanda: Panda = ffi.dlopen(libpanda_fn) - - -# helpers - -def make_CANPacket(addr: int, bus: int, dat): - ret = ffi.new('CANPacket_t *') - ret[0].extended = 1 if addr >= 0x800 else 0 - ret[0].addr = addr - ret[0].data_len_code = LEN_TO_DLC[len(dat)] - ret[0].bus = bus - ret[0].data = bytes(dat) - libpanda.can_set_checksum(ret) - - return ret diff --git a/panda/tests/libpanda/panda.c b/panda/tests/libpanda/panda.c deleted file mode 100644 index 8efb6de..0000000 --- a/panda/tests/libpanda/panda.c +++ /dev/null @@ -1,33 +0,0 @@ -#include "fake_stm.h" -#include "config.h" -#include "can_definitions.h" - -bool bitbang_gmlan(CANPacket_t *to_bang) { return true; } -bool can_init(uint8_t can_number) { return true; } -void process_can(uint8_t can_number) { } -//int safety_tx_hook(CANPacket_t *to_send) { return 1; } - -typedef struct harness_configuration harness_configuration; -void refresh_can_tx_slots_available(void); -void can_tx_comms_resume_usb(void) { }; -void can_tx_comms_resume_spi(void) { }; - -#include "health.h" -#include "faults.h" -#include "libc.h" -#include "boards/board_declarations.h" -#include "safety.h" -#include "main_declarations.h" -#include "drivers/can_common.h" - -can_ring *rx_q = &can_rx_q; -can_ring *txgmlan_q = &can_txgmlan_q; -can_ring *tx1_q = &can_tx1_q; -can_ring *tx2_q = &can_tx2_q; -can_ring *tx3_q = &can_tx3_q; - -#include "comms_definitions.h" -#include "can_comms.h" - -// libpanda stuff -#include "safety_helpers.h" diff --git a/panda/tests/libpanda/safety_helpers.h b/panda/tests/libpanda/safety_helpers.h deleted file mode 100644 index 074463d..0000000 --- a/panda/tests/libpanda/safety_helpers.h +++ /dev/null @@ -1,195 +0,0 @@ -void safety_tick_current_safety_config() { - safety_tick(¤t_safety_config); -} - -bool safety_config_valid() { - if (current_safety_config.rx_checks_len <= 0) { - printf("missing RX checks\n"); - return false; - } - - for (int i = 0; i < current_safety_config.rx_checks_len; i++) { - const RxCheck addr = current_safety_config.rx_checks[i]; - bool valid = addr.status.msg_seen && !addr.status.lagging && addr.status.valid_checksum && (addr.status.wrong_counters < MAX_WRONG_COUNTERS) && addr.status.valid_quality_flag; - if (!valid) { - // printf("i %d seen %d lagging %d valid checksum %d wrong counters %d valid quality flag %d\n", i, addr.status.msg_seen, addr.status.lagging, addr.status.valid_checksum, addr.status.wrong_counters, addr.status.valid_quality_flag); - return false; - } - } - return true; -} - -void set_controls_allowed(bool c){ - controls_allowed = c; -} - -void set_alternative_experience(int mode){ - alternative_experience = mode; -} - -void set_relay_malfunction(bool c){ - relay_malfunction = c; -} - -bool get_controls_allowed(void){ - return controls_allowed; -} - -int get_alternative_experience(void){ - return alternative_experience; -} - -bool get_relay_malfunction(void){ - return relay_malfunction; -} - -int get_gas_interceptor_prev(void){ - return gas_interceptor_prev; -} - -bool get_gas_pressed_prev(void){ - return gas_pressed_prev; -} - -bool get_brake_pressed_prev(void){ - return brake_pressed_prev; -} - -bool get_regen_braking_prev(void){ - return regen_braking_prev; -} - -bool get_cruise_engaged_prev(void){ - return cruise_engaged_prev; -} - -void set_cruise_engaged_prev(bool engaged){ - cruise_engaged_prev = engaged; -} - -bool get_vehicle_moving(void){ - return vehicle_moving; -} - -bool get_acc_main_on(void){ - return acc_main_on; -} - -int get_vehicle_speed_min(void){ - return vehicle_speed.min; -} - -int get_vehicle_speed_max(void){ - return vehicle_speed.max; -} - -int get_vehicle_speed_last(void){ - return vehicle_speed.values[0]; -} - -int get_current_safety_mode(void){ - return current_safety_mode; -} - -int get_current_safety_param(void){ - return current_safety_param; -} - -int get_hw_type(void){ - return hw_type; -} - -void set_timer(uint32_t t){ - timer.CNT = t; -} - -void set_torque_meas(int min, int max){ - torque_meas.min = min; - torque_meas.max = max; -} - -int get_torque_meas_min(void){ - return torque_meas.min; -} - -int get_torque_meas_max(void){ - return torque_meas.max; -} - -void set_torque_driver(int min, int max){ - torque_driver.min = min; - torque_driver.max = max; -} - -int get_torque_driver_min(void){ - return torque_driver.min; -} - -int get_torque_driver_max(void){ - return torque_driver.max; -} - -void set_rt_torque_last(int t){ - rt_torque_last = t; -} - -void set_desired_torque_last(int t){ - desired_torque_last = t; -} - -void set_desired_angle_last(int t){ - desired_angle_last = t; -} - -int get_desired_angle_last(void){ - return desired_angle_last; -} - -void set_angle_meas(int min, int max){ - angle_meas.min = min; - angle_meas.max = max; -} - -int get_angle_meas_min(void){ - return angle_meas.min; -} - -int get_angle_meas_max(void){ - return angle_meas.max; -} - - -// ***** car specific helpers ***** - -void set_honda_alt_brake_msg(bool c){ - honda_alt_brake_msg = c; -} - -void set_honda_bosch_long(bool c){ - honda_bosch_long = c; -} - -int get_honda_hw(void) { - return honda_hw; -} - -void set_honda_fwd_brake(bool c){ - honda_fwd_brake = c; -} - -bool get_honda_fwd_brake(void){ - return honda_fwd_brake; -} - -void init_tests(void){ - // get HW_TYPE from env variable set in test.sh - if (getenv("HW_TYPE")) { - hw_type = atoi(getenv("HW_TYPE")); - } - safety_mode_cnt = 2U; // avoid ignoring relay_malfunction logic - alternative_experience = 0; - set_timer(0); - ts_steer_req_mismatch_last = 0; - valid_steer_req_count = 0; - invalid_steer_req_count = 0; -} diff --git a/panda/tests/libpanda/safety_helpers.py b/panda/tests/libpanda/safety_helpers.py deleted file mode 100644 index 28f3349..0000000 --- a/panda/tests/libpanda/safety_helpers.py +++ /dev/null @@ -1,106 +0,0 @@ -# panda safety helpers, from safety_helpers.c -from typing import Protocol - -def setup_safety_helpers(ffi): - ffi.cdef(""" - void set_controls_allowed(bool c); - bool get_controls_allowed(void); - bool get_longitudinal_allowed(void); - void set_alternative_experience(int mode); - int get_alternative_experience(void); - void set_relay_malfunction(bool c); - bool get_relay_malfunction(void); - int get_gas_interceptor_prev(void); - bool get_gas_pressed_prev(void); - bool get_brake_pressed_prev(void); - bool get_regen_braking_prev(void); - bool get_acc_main_on(void); - int get_vehicle_speed_min(void); - int get_vehicle_speed_max(void); - int get_vehicle_speed_last(void); - int get_current_safety_mode(void); - int get_current_safety_param(void); - - void set_torque_meas(int min, int max); - int get_torque_meas_min(void); - int get_torque_meas_max(void); - void set_torque_driver(int min, int max); - int get_torque_driver_min(void); - int get_torque_driver_max(void); - void set_desired_torque_last(int t); - void set_rt_torque_last(int t); - void set_desired_angle_last(int t); - int get_desired_angle_last(); - void set_angle_meas(int min, int max); - int get_angle_meas_min(void); - int get_angle_meas_max(void); - - bool get_cruise_engaged_prev(void); - void set_cruise_engaged_prev(bool engaged); - bool get_vehicle_moving(void); - int get_hw_type(void); - void set_timer(uint32_t t); - - void safety_tick_current_safety_config(); - bool safety_config_valid(); - - void init_tests(void); - - void set_honda_fwd_brake(bool c); - bool get_honda_fwd_brake(void); - void set_honda_alt_brake_msg(bool c); - void set_honda_bosch_long(bool c); - int get_honda_hw(void); - """) - -class PandaSafety(Protocol): - def set_controls_allowed(self, c: bool) -> None: ... - def get_controls_allowed(self) -> bool: ... - def get_longitudinal_allowed(self) -> bool: ... - def set_alternative_experience(self, mode: int) -> None: ... - def get_alternative_experience(self) -> int: ... - def set_relay_malfunction(self, c: bool) -> None: ... - def get_relay_malfunction(self) -> bool: ... - def get_gas_interceptor_prev(self) -> int: ... - def get_gas_pressed_prev(self) -> bool: ... - def get_brake_pressed_prev(self) -> bool: ... - def get_regen_braking_prev(self) -> bool: ... - def get_acc_main_on(self) -> bool: ... - def get_vehicle_speed_min(self) -> int: ... - def get_vehicle_speed_max(self) -> int: ... - def get_vehicle_speed_last(self) -> int: ... - def get_current_safety_mode(self) -> int: ... - def get_current_safety_param(self) -> int: ... - - def set_torque_meas(self, min: int, max: int) -> None: ... # noqa: A002 - def get_torque_meas_min(self) -> int: ... - def get_torque_meas_max(self) -> int: ... - def set_torque_driver(self, min: int, max: int) -> None: ... # noqa: A002 - def get_torque_driver_min(self) -> int: ... - def get_torque_driver_max(self) -> int: ... - def set_desired_torque_last(self, t: int) -> None: ... - def set_rt_torque_last(self, t: int) -> None: ... - def set_desired_angle_last(self, t: int) -> None: ... - def get_desired_angle_last(self) -> int: ... - def set_angle_meas(self, min: int, max: int) -> None: ... # noqa: A002 - def get_angle_meas_min(self) -> int: ... - def get_angle_meas_max(self) -> int: ... - - def get_cruise_engaged_prev(self) -> bool: ... - def set_cruise_engaged_prev(self, enabled: bool) -> None: ... - def get_vehicle_moving(self) -> bool: ... - def get_hw_type(self) -> int: ... - def set_timer(self, t: int) -> None: ... - - def safety_tick_current_safety_config(self) -> None: ... - def safety_config_valid(self) -> bool: ... - - def init_tests(self) -> None: ... - - def set_honda_fwd_brake(self, c: bool) -> None: ... - def get_honda_fwd_brake(self) -> bool: ... - def set_honda_alt_brake_msg(self, c: bool) -> None: ... - def set_honda_bosch_long(self, c: bool) -> None: ... - def get_honda_hw(self) -> int: ... - - diff --git a/panda/tests/libs/resetter.py b/panda/tests/libs/resetter.py deleted file mode 100644 index 3868bde..0000000 --- a/panda/tests/libs/resetter.py +++ /dev/null @@ -1,57 +0,0 @@ -import time -import usb1 - - -class Resetter(): - def __init__(self): - self._handle = None - self.connect() - - def __enter__(self): - return self - - def __exit__(self, *args): - self.close() - - def close(self): - self._handle.close() - self._context.close() - self._handle = None - - def connect(self): - if self._handle: - self.close() - - self._handle = None - - self._context = usb1.USBContext() - self._context.open() - for device in self._context.getDeviceList(skip_on_error=True): - if device.getVendorID() == 0xbbaa and device.getProductID() == 0xddc0: - try: - self._handle = device.open() - self._handle.claimInterface(0) - break - except Exception as e: - print(e) - assert self._handle - - def enable_power(self, port, enabled): - self._handle.controlWrite((usb1.ENDPOINT_OUT | usb1.TYPE_VENDOR | usb1.RECIPIENT_DEVICE), 0xff, port, enabled, b'') - - def enable_boot(self, enabled): - self._handle.controlWrite((usb1.ENDPOINT_OUT | usb1.TYPE_VENDOR | usb1.RECIPIENT_DEVICE), 0xff, 0, enabled, b'') - - def cycle_power(self, delay=5, dfu=False, ports=None): - if ports is None: - ports = [1, 2, 3] - - self.enable_boot(dfu) - for port in ports: - self.enable_power(port, False) - time.sleep(0.5) - - for port in ports: - self.enable_power(port, True) - time.sleep(delay) - self.enable_boot(False) diff --git a/panda/tests/loopback_test.py b/panda/tests/loopback_test.py deleted file mode 100644 index d4f8beb..0000000 --- a/panda/tests/loopback_test.py +++ /dev/null @@ -1,94 +0,0 @@ -#!/usr/bin/env python3 - -import os -import time -import random -import argparse -from itertools import permutations - -from panda import Panda - -def get_test_string(): - return b"test" + os.urandom(10) - -def run_test(sleep_duration): - pandas = Panda.list() - print(pandas) - - if len(pandas) < 2: - raise Exception("Minimum two pandas are needed for test") - - run_test_w_pandas(pandas, sleep_duration) - -def run_test_w_pandas(pandas, sleep_duration): - h = [Panda(x) for x in pandas] - print("H", h) - - for hh in h: - hh.set_safety_mode(Panda.SAFETY_ALLOUTPUT) - - # test both directions - for ho in permutations(list(range(len(h))), r=2): - print("***************** TESTING", ho) - - panda0, panda1 = h[ho[0]], h[ho[1]] - - # **** test health packet **** - print("health", ho[0], h[ho[0]].health()) - - # **** test can line loopback **** - for bus, gmlan in [(0, False), (1, False), (2, False), (1, True), (2, True)]: - print("\ntest can", bus) - # flush - cans_echo = panda0.can_recv() - cans_loop = panda1.can_recv() - - panda0.set_gmlan(None) - panda1.set_gmlan(None) - - if gmlan is True: - panda0.set_gmlan(bus) - panda1.set_gmlan(bus) - bus = 3 - - # send the characters - at = random.randint(1, 2000) - st = get_test_string()[0:8] - panda0.can_send(at, st, bus) - time.sleep(0.1) - - # check for receive - cans_echo = panda0.can_recv() - cans_loop = panda1.can_recv() - - print("Bus", bus, "echo", cans_echo, "loop", cans_loop) - - assert len(cans_echo) == 1 - assert len(cans_loop) == 1 - - assert cans_echo[0][0] == at - assert cans_loop[0][0] == at - - assert cans_echo[0][2] == st - assert cans_loop[0][2] == st - - assert cans_echo[0][3] == 0x80 | bus - if cans_loop[0][3] != bus: - print("EXPECTED %d GOT %d" % (bus, cans_loop[0][3])) - assert cans_loop[0][3] == bus - - print("CAN pass", bus, ho) - time.sleep(sleep_duration) - -if __name__ == "__main__": - parser = argparse.ArgumentParser() - parser.add_argument("-n", type=int, help="Number of test iterations to run") - parser.add_argument("-sleep", type=int, help="Sleep time between tests", default=0) - args = parser.parse_args() - - if args.n is None: - while True: - run_test(sleep_duration=args.sleep) - else: - for _ in range(args.n): - run_test(sleep_duration=args.sleep) diff --git a/panda/tests/message_drop_test.py b/panda/tests/message_drop_test.py deleted file mode 100644 index bf485e4..0000000 --- a/panda/tests/message_drop_test.py +++ /dev/null @@ -1,70 +0,0 @@ -#!/usr/bin/env python3 -import os -import usb1 -import time -import struct -import itertools -import threading -from typing import Any - -from panda import Panda - -JUNGLE = "JUNGLE" in os.environ -if JUNGLE: - from panda import PandaJungle - -# Generate unique messages -NUM_MESSAGES_PER_BUS = 10000 -messages = [bytes(struct.pack("Q", i)) for i in range(NUM_MESSAGES_PER_BUS)] -tx_messages = list(itertools.chain.from_iterable([[0xaa, None, msg, 0], [0xaa, None, msg, 1], [0xaa, None, msg, 2]] for msg in messages)) - -def flood_tx(panda): - print('Sending!') - transferred = 0 - while True: - try: - print(f"Sending block {transferred}-{len(tx_messages)}: ", end="") - panda.can_send_many(tx_messages[transferred:], timeout=10) - print("OK") - break - except usb1.USBErrorTimeout as e: - transferred += (e.transferred // 16) - print("timeout, transferred: ", transferred) - - print(f"Done sending {3*NUM_MESSAGES_PER_BUS} messages!") - -if __name__ == "__main__": - serials = Panda.list() - receiver: Panda | PandaJungle - if JUNGLE: - sender = Panda() - receiver = PandaJungle() - else: - if len(serials) != 2: - raise Exception("Connect two pandas to perform this test!") - sender = Panda(serials[0]) - receiver = Panda(serials[1]) - receiver.set_safety_mode(Panda.SAFETY_ALLOUTPUT) - - sender.set_safety_mode(Panda.SAFETY_ALLOUTPUT) - - # Start transmisson - threading.Thread(target=flood_tx, args=(sender,)).start() - - # Receive as much as we can, and stop when there hasn't been anything for a second - rx: list[Any] = [] - old_len = 0 - last_change = time.monotonic() - while time.monotonic() - last_change < 1: - if old_len < len(rx): - last_change = time.monotonic() - old_len = len(rx) - - rx.extend(receiver.can_recv()) - print(f"Received {len(rx)} messages") - - # Check if we received everything - for bus in range(3): - received_msgs = {bytes(m[2]) for m in filter(lambda m, b=bus: m[3] == b, rx)} # type: ignore - dropped_msgs = set(messages).difference(received_msgs) - print(f"Bus {bus} dropped msgs: {len(list(dropped_msgs))} / {len(messages)}") diff --git a/panda/tests/misra/.gitignore b/panda/tests/misra/.gitignore deleted file mode 100644 index fc9ac22..0000000 --- a/panda/tests/misra/.gitignore +++ /dev/null @@ -1,5 +0,0 @@ -*.pdf -*.txt -.output.log -new_table -cppcheck/ diff --git a/panda/tests/misra/coverage_table b/panda/tests/misra/coverage_table deleted file mode 100644 index 0395aba..0000000 --- a/panda/tests/misra/coverage_table +++ /dev/null @@ -1,156 +0,0 @@ -1.1 -1.2 X (Addon) -1.3 X (Cppcheck) -2.1 X (Cppcheck) -2.2 X (Addon) -2.3 X (Addon) -2.4 X (Addon) -2.5 X (Addon) -2.6 X (Cppcheck) -2.7 X (Addon) -3.1 X (Addon) -3.2 X (Addon) -4.1 X (Addon) -4.2 X (Addon) -5.1 X (Addon) -5.2 X (Addon) -5.3 X (Cppcheck) -5.4 X (Addon) -5.5 X (Addon) -5.6 X (Addon) -5.7 X (Addon) -5.8 X (Addon) -5.9 X (Addon) -6.1 X (Addon) -6.2 X (Addon) -7.1 X (Addon) -7.2 X (Addon) -7.3 X (Addon) -7.4 X (Addon) -8.1 X (Addon) -8.2 X (Addon) -8.3 X (Cppcheck) -8.4 X (Addon) -8.5 X (Addon) -8.6 X (Addon) -8.7 X (Addon) -8.8 X (Addon) -8.9 X (Addon) -8.10 X (Addon) -8.11 X (Addon) -8.12 X (Addon) -8.13 X (Cppcheck) -8.14 X (Addon) -9.1 X (Cppcheck) -9.2 X (Addon) -9.3 X (Addon) -9.4 X (Addon) -9.5 X (Addon) -10.1 X (Addon) -10.2 X (Addon) -10.3 X (Addon) -10.4 X (Addon) -10.5 X (Addon) -10.6 X (Addon) -10.7 X (Addon) -10.8 X (Addon) -11.1 X (Addon) -11.2 X (Addon) -11.3 X (Addon) -11.4 X (Addon) -11.5 X (Addon) -11.6 X (Addon) -11.7 X (Addon) -11.8 X (Addon) -11.9 X (Addon) -12.1 X (Addon) -12.2 X (Addon) -12.3 X (Addon) -12.4 X (Addon) -13.1 X (Addon) -13.2 X (Cppcheck) -13.3 X (Addon) -13.4 X (Addon) -13.5 X (Addon) -13.6 X (Addon) -14.1 X (Addon) -14.2 X (Addon) -14.3 X (Cppcheck) -14.4 X (Addon) -15.1 X (Addon) -15.2 X (Addon) -15.3 X (Addon) -15.4 X (Addon) -15.5 X (Addon) -15.6 X (Addon) -15.7 X (Addon) -16.1 X (Addon) -16.2 X (Addon) -16.3 X (Addon) -16.4 X (Addon) -16.5 X (Addon) -16.6 X (Addon) -16.7 X (Addon) -17.1 X (Addon) -17.2 X (Addon) -17.3 X (Addon) -17.4 X (Cppcheck) -17.5 X (Cppcheck) -17.6 X (Addon) -17.7 X (Addon) -17.8 X (Addon) -18.1 X (Cppcheck) -18.2 X (Cppcheck) -18.3 X (Cppcheck) -18.4 X (Addon) -18.5 X (Addon) -18.6 X (Cppcheck) -18.7 X (Addon) -18.8 X (Addon) -19.1 X (Cppcheck) -19.2 X (Addon) -20.1 X (Addon) -20.2 X (Addon) -20.3 X (Addon) -20.4 X (Addon) -20.5 X (Addon) -20.6 X (Cppcheck) -20.7 X (Addon) -20.8 X (Addon) -20.9 X (Addon) -20.10 X (Addon) -20.11 X (Addon) -20.12 X (Addon) -20.13 X (Addon) -20.14 X (Addon) -21.1 X (Addon) -21.2 X (Addon) -21.3 X (Addon) -21.4 X (Addon) -21.5 X (Addon) -21.6 X (Addon) -21.7 X (Addon) -21.8 X (Addon) -21.9 X (Addon) -21.10 X (Addon) -21.11 X (Addon) -21.12 X (Addon) -21.13 X (Cppcheck) -21.14 X (Addon) -21.15 X (Addon) -21.16 X (Addon) -21.17 X (Cppcheck) -21.18 X (Cppcheck) -21.19 X (Addon) -21.20 X (Addon) -21.21 X (Addon) -22.1 X (Cppcheck) -22.2 X (Cppcheck) -22.3 X (Cppcheck) -22.4 X (Cppcheck) -22.5 X (Addon) -22.6 X (Cppcheck) -22.7 X (Addon) -22.8 X (Addon) -22.9 X (Addon) -22.10 X (Addon) diff --git a/panda/tests/misra/install.sh b/panda/tests/misra/install.sh deleted file mode 100644 index ecc0b3f..0000000 --- a/panda/tests/misra/install.sh +++ /dev/null @@ -1,19 +0,0 @@ -#!/bin/bash -set -e - -DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null 2>&1 && pwd )" -: "${CPPCHECK_DIR:=$DIR/cppcheck/}" - -if [ ! -d "$CPPCHECK_DIR" ]; then - git clone https://github.com/danmar/cppcheck.git $CPPCHECK_DIR -fi - -cd $CPPCHECK_DIR - -VERS="2.13.0" -git fetch --all --tags -git checkout $VERS -git cherry-pick -n f6b538e855f0bacea33c4074664628024ef39dc6 b11b42087ff29569bc3740f5aa07eb6616ea4f63 - -#make clean -make MATCHCOMPILTER=yes CXXFLAGS="-O2" -j8 diff --git a/panda/tests/misra/test_misra.sh b/panda/tests/misra/test_misra.sh deleted file mode 100644 index 9fdbea1..0000000 --- a/panda/tests/misra/test_misra.sh +++ /dev/null @@ -1,61 +0,0 @@ -#!/bin/bash -set -e - -DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null 2>&1 && pwd )" -PANDA_DIR=$(realpath $DIR/../../) - -GREEN="\e[1;32m" -NC='\033[0m' - -: "${CPPCHECK_DIR:=$DIR/cppcheck/}" - -# install cppcheck if missing -if [ -z "${SKIP_BUILD}" ]; then - $DIR/install.sh -fi - -# ensure checked in coverage table is up to date -cd $DIR -python $CPPCHECK_DIR/addons/misra.py -generate-table > new_table -if ! cmp -s new_table coverage_table; then - echo "MISRA coverage table doesn't match. Update and commit:" - echo "mv new_table coverage_table && git add . && git commit -m 'update table'" - exit 1 -fi - -cd $PANDA_DIR -if [ -z "${SKIP_BUILD}" ]; then - scons -j8 -fi - -cppcheck() { - # note that cppcheck build cache results in inconsistent results as of v2.13.0 - OUTPUT=$DIR/.output.log - $CPPCHECK_DIR/cppcheck --force --inline-suppr -I $PANDA_DIR/board/ \ - -I $gcc_inc "$(arm-none-eabi-gcc -print-file-name=include)" \ - --suppressions-list=$DIR/suppressions.txt --suppress=*:*inc/* \ - --suppress=*:*include/* --error-exitcode=2 --check-level=exhaustive \ - --platform=arm32-wchar_t2 \ - "$@" |& tee $OUTPUT - - # cppcheck bug: some MISRA errors won't result in the error exit code, - # so check the output (https://trac.cppcheck.net/ticket/12440#no1) - if grep -e "misra violation" -e "error" -e "style: " $OUTPUT > /dev/null; then - exit 1 - fi -} - -PANDA_OPTS="--enable=all --disable=unusedFunction -DPANDA --addon=misra" - -printf "\n${GREEN}** PANDA F4 CODE **${NC}\n" -cppcheck $PANDA_OPTS -DSTM32F4 -DUID_BASE $PANDA_DIR/board/main.c - -printf "\n${GREEN}** PANDA H7 CODE **${NC}\n" -cppcheck $PANDA_OPTS -DSTM32H7 -DUID_BASE $PANDA_DIR/board/main.c - -# unused needs to run globally -#printf "\n${GREEN}** UNUSED ALL CODE **${NC}\n" -#cppcheck --enable=unusedFunction --quiet $PANDA_DIR/board/ - -printf "\n${GREEN}Success!${NC} took $SECONDS seconds\n" - diff --git a/panda/tests/misra/test_mutation.py b/panda/tests/misra/test_mutation.py deleted file mode 100644 index cc3666f..0000000 --- a/panda/tests/misra/test_mutation.py +++ /dev/null @@ -1,84 +0,0 @@ -#!/usr/bin/env python3 -import os -import glob -import pytest -import shutil -import subprocess -import tempfile -import random - -HERE = os.path.abspath(os.path.dirname(__file__)) -ROOT = os.path.join(HERE, "../../") - -IGNORED_PATHS = ( - 'board/obj', - 'board/jungle', - 'board/stm32h7/inc', - 'board/stm32fx/inc', - 'board/fake_stm.h', - - # bootstub only files - 'board/flasher.h', - 'board/bootstub.c', - 'board/bootstub_declarations.h', - 'board/stm32fx/llflash.h' -) - -mutations = [ - # default - (None, None, False), - # F4 only - ("board/stm32fx/llbxcan.h", "s/1U/1/g", True), - # H7 only - ("board/stm32h7/llfdcan.h", "s/return ret;/if (true) { return ret; } else { return false; }/g", True), - # general safety - ("board/safety/safety_toyota.h", "s/is_lkas_msg =.*;/is_lkas_msg = addr == 1 || addr == 2;/g", True), -] - -patterns = [ - # misra-c2012-13.3 - "$a void test(int tmp) { int tmp2 = tmp++ + 2; if (tmp2) {;}}", - # misra-c2012-13.4 - "$a int test(int x, int y) { return (x=2) && (y=2); }", - # misra-c2012-13.5 - "$a void test(int tmp) { if (true && tmp++) {;} }", - # misra-c2012-13.6 - "$a void test(int tmp) { if (sizeof(tmp++)) {;} }", - # misra-c2012-14.1 - "$a void test(float len) { for (float j = 0; j < len; j++) {;} }", - # misra-c2012-14.4 - "$a void test(int len) { if (len - 8) {;} }", - # misra-c2012-16.4 - r"$a void test(int temp) {switch (temp) { case 1: ; }}\n", - # misra-c2012-17.8 - "$a void test(int cnt) { for (cnt=0;;cnt++) {;} }", - # misra-c2012-20.4 - r"$a #define auto 1\n", - # misra-c2012-20.5 - r"$a #define TEST 1\n#undef TEST\n", -] - -all_files = glob.glob('board/**', root_dir=ROOT, recursive=True) -files = [f for f in all_files if f.endswith(('.c', '.h')) and not f.startswith(IGNORED_PATHS)] -assert len(files) > 70, all(d in files for d in ('board/main.c', 'board/stm32fx/llbxcan.h', 'board/stm32h7/llfdcan.h', 'board/safety/safety_toyota.h')) - -for p in patterns: - mutations.append((random.choice(files), p, True)) - -@pytest.mark.parametrize("fn, patch, should_fail", mutations) -def test_misra_mutation(fn, patch, should_fail): - with tempfile.TemporaryDirectory() as tmp: - shutil.copytree(ROOT, tmp, dirs_exist_ok=True) - - # apply patch - if fn is not None: - r = os.system(f"cd {tmp} && sed -i '{patch}' {fn}") - assert r == 0 - - # run test - r = subprocess.run("tests/misra/test_misra.sh", cwd=tmp, shell=True) - failed = r.returncode != 0 - assert failed == should_fail - -if __name__ == "__main__": - pytest.main([__file__, "-n 8"]) diff --git a/panda/tests/read_flash_spi.py b/panda/tests/read_flash_spi.py deleted file mode 100644 index 133062b..0000000 --- a/panda/tests/read_flash_spi.py +++ /dev/null @@ -1,32 +0,0 @@ -#!/usr/bin/env python3 -from panda import Panda, PandaDFU - -if __name__ == "__main__": - try: - from openpilot.system.hardware import HARDWARE - HARDWARE.recover_internal_panda() - Panda.wait_for_dfu(None, 5) - except Exception: - pass - - p = PandaDFU(None) - cfg = p.get_mcu_type().config - - def readmem(addr, length, fn): - print(f"reading {hex(addr)} {hex(length)} bytes to {fn}") - max_size = 255 - with open(fn, "wb") as f: - to_read = length - while to_read > 0: - l = min(to_read, max_size) - dat = p._handle.read(addr, l) - assert len(dat) == l - f.write(dat) - - to_read -= len(dat) - addr += len(dat) - - addr = cfg.bootstub_address - for i, sector_size in enumerate(cfg.sector_sizes): - readmem(addr, sector_size, f"sector_{i}.bin") - addr += sector_size diff --git a/panda/tests/read_st_flash.sh b/panda/tests/read_st_flash.sh deleted file mode 100644 index ffcfd7b..0000000 --- a/panda/tests/read_st_flash.sh +++ /dev/null @@ -1,6 +0,0 @@ -#!/bin/bash -rm -f /tmp/dump_bootstub -rm -f /tmp/dump_main -dfu-util -a 0 -s 0x08000000 -U /tmp/dump_bootstub -dfu-util -a 0 -s 0x08004000 -U /tmp/dump_main - diff --git a/panda/tests/read_winusb_descriptors.py b/panda/tests/read_winusb_descriptors.py deleted file mode 100644 index 5d311c9..0000000 --- a/panda/tests/read_winusb_descriptors.py +++ /dev/null @@ -1,34 +0,0 @@ -#!/usr/bin/env python3 -# type: ignore -from panda import Panda -from hexdump import hexdump - -DEBUG = False - -if __name__ == "__main__": - p = Panda() - - length = p._handle.controlRead(Panda.REQUEST_IN, 0x06, 3 << 8 | 238, 0, 1) - print('Microsoft OS String Descriptor') - dat = p._handle.controlRead(Panda.REQUEST_IN, 0x06, 3 << 8 | 238, 0, length[0]) - if DEBUG: - print(f'LEN: {hex(length[0])}') - hexdump("".join(map(chr, dat))) - - ms_vendor_code = dat[16] - if DEBUG: - print(f'MS_VENDOR_CODE: {hex(length[0])}') - - print('\nMicrosoft Compatible ID Feature Descriptor') - length = p._handle.controlRead(Panda.REQUEST_IN, ms_vendor_code, 0, 4, 1) - if DEBUG: - print(f'LEN: {hex(length[0])}') - dat = p._handle.controlRead(Panda.REQUEST_IN, ms_vendor_code, 0, 4, length[0]) - hexdump("".join(map(chr, dat))) - - print('\nMicrosoft Extended Properties Feature Descriptor') - length = p._handle.controlRead(Panda.REQUEST_IN, ms_vendor_code, 0, 5, 1) - if DEBUG: - print(f'LEN: {hex(length[0])}') - dat = p._handle.controlRead(Panda.REQUEST_IN, ms_vendor_code, 0, 5, length[0]) - hexdump("".join(map(chr, dat))) diff --git a/panda/tests/reflash_internal_panda.py b/panda/tests/reflash_internal_panda.py deleted file mode 100644 index c2ad9f8..0000000 --- a/panda/tests/reflash_internal_panda.py +++ /dev/null @@ -1,49 +0,0 @@ -#!/usr/bin/env python3 -import time -from panda import Panda, PandaDFU - -class GPIO: - STM_RST_N = 124 - STM_BOOT0 = 134 - HUB_RST_N = 30 - - -def gpio_init(pin, output): - with open(f"/sys/class/gpio/gpio{pin}/direction", 'wb') as f: - f.write(b"out" if output else b"in") - -def gpio_set(pin, high): - with open(f"/sys/class/gpio/gpio{pin}/value", 'wb') as f: - f.write(b"1" if high else b"0") - - -if __name__ == "__main__": - for pin in (GPIO.STM_RST_N, GPIO.STM_BOOT0, GPIO.HUB_RST_N): - gpio_init(pin, True) - - # reset USB hub - gpio_set(GPIO.HUB_RST_N, 0) - time.sleep(0.5) - gpio_set(GPIO.HUB_RST_N, 1) - - # flash bootstub - print("resetting into DFU") - gpio_set(GPIO.STM_RST_N, 1) - gpio_set(GPIO.STM_BOOT0, 1) - time.sleep(1) - gpio_set(GPIO.STM_RST_N, 0) - gpio_set(GPIO.STM_BOOT0, 0) - time.sleep(1) - - print("flashing bootstub") - PandaDFU(None).recover() - - gpio_set(GPIO.STM_RST_N, 1) - time.sleep(0.5) - gpio_set(GPIO.STM_RST_N, 0) - time.sleep(1) - - print("flashing app") - p = Panda() - assert p.bootstub - p.flash() diff --git a/panda/tests/relay_test.py b/panda/tests/relay_test.py deleted file mode 100644 index 68789b1..0000000 --- a/panda/tests/relay_test.py +++ /dev/null @@ -1,16 +0,0 @@ -#!/usr/bin/env python -import time -from panda import Panda - -p = Panda() - -while True: - p.set_safety_mode(Panda.SAFETY_TOYOTA) - p.send_heartbeat() - print("ON") - time.sleep(1) - p.set_safety_mode(Panda.SAFETY_NOOUTPUT) - p.send_heartbeat() - print("OFF") - time.sleep(1) - diff --git a/panda/tests/restore_flash_spi.py b/panda/tests/restore_flash_spi.py deleted file mode 100644 index c23b298..0000000 --- a/panda/tests/restore_flash_spi.py +++ /dev/null @@ -1,27 +0,0 @@ -#!/usr/bin/env python3 -from panda import Panda, PandaDFU, STBootloaderSPIHandle - -if __name__ == "__main__": - try: - from openpilot.system.hardware import HARDWARE - HARDWARE.recover_internal_panda() - Panda.wait_for_dfu(None, 5) - except Exception: - pass - - p = PandaDFU(None) - assert isinstance(p._handle, STBootloaderSPIHandle) - cfg = p.get_mcu_type().config - - print("restoring from backup...") - addr = cfg.bootstub_address - for i, sector_size in enumerate(cfg.sector_sizes): - print(f"- sector #{i}") - p._handle.erase_sector(i) - with open(f"sector_{i}.bin", "rb") as f: - dat = f.read() - assert len(dat) == sector_size - p._handle.program(addr, dat) - addr += len(dat) - - p.reset() diff --git a/panda/tests/rtc_test.py b/panda/tests/rtc_test.py deleted file mode 100644 index 01c9f4d..0000000 --- a/panda/tests/rtc_test.py +++ /dev/null @@ -1,10 +0,0 @@ -#!/usr/bin/env python -import datetime - -from panda import Panda - -if __name__ == "__main__": - p = Panda() - - p.set_datetime(datetime.datetime.now()) - print(p.get_datetime()) diff --git a/panda/tests/safety/__init__.py b/panda/tests/safety/__init__.py deleted file mode 100644 index e69de29..0000000 diff --git a/panda/tests/safety/common.py b/panda/tests/safety/common.py deleted file mode 100644 index a3c22df..0000000 --- a/panda/tests/safety/common.py +++ /dev/null @@ -1,1071 +0,0 @@ -import os -import abc -import unittest -import importlib -import numpy as np -from collections.abc import Callable - -from opendbc.can.packer import CANPacker # pylint: disable=import-error -from panda import ALTERNATIVE_EXPERIENCE -from panda.tests.libpanda import libpanda_py - -MAX_WRONG_COUNTERS = 5 -MAX_SAMPLE_VALS = 6 -VEHICLE_SPEED_FACTOR = 100 - -MessageFunction = Callable[[float], libpanda_py.CANPacket] - -def sign_of(a): - return 1 if a > 0 else -1 - - -def make_msg(bus, addr, length=8, dat=None): - if dat is None: - dat = b'\x00' * length - return libpanda_py.make_CANPacket(addr, bus, dat) - - -class CANPackerPanda(CANPacker): - def make_can_msg_panda(self, name_or_addr, bus, values, fix_checksum=None): - msg = self.make_can_msg(name_or_addr, bus, values) - if fix_checksum is not None: - msg = fix_checksum(msg) - addr, _, dat, bus = msg - return libpanda_py.make_CANPacket(addr, bus, dat) - - -def add_regen_tests(cls): - """Dynamically adds regen tests for all user brake tests.""" - - # only rx/user brake tests, not brake command - found_tests = [func for func in dir(cls) if func.startswith("test_") and "user_brake" in func] - assert len(found_tests) >= 3, "Failed to detect known brake tests" - - for test in found_tests: - def _make_regen_test(brake_func): - def _regen_test(self): - # only for safety modes with a regen message - if self._user_regen_msg(0) is None: - raise unittest.SkipTest("Safety mode implements no _user_regen_msg") - - getattr(self, brake_func)(self._user_regen_msg, self.safety.get_regen_braking_prev) - return _regen_test - - setattr(cls, test.replace("brake", "regen"), _make_regen_test(test)) - - return cls - - -class PandaSafetyTestBase(unittest.TestCase): - safety: libpanda_py.Panda - - @classmethod - def setUpClass(cls): - if cls.__name__ == "PandaSafetyTestBase": - cls.safety = None - raise unittest.SkipTest - - def _reset_safety_hooks(self): - self.safety.set_safety_hooks(self.safety.get_current_safety_mode(), - self.safety.get_current_safety_param()) - - def _rx(self, msg): - return self.safety.safety_rx_hook(msg) - - def _tx(self, msg): - return self.safety.safety_tx_hook(msg) - - def _generic_limit_safety_check(self, msg_function: MessageFunction, min_allowed_value: float, max_allowed_value: float, - min_possible_value: float, max_possible_value: float, test_delta: float = 1, inactive_value: float = 0, - msg_allowed = True, additional_setup: Callable[[float], None] | None = None): - """ - Enforces that a signal within a message is only allowed to be sent within a specific range, min_allowed_value -> max_allowed_value. - Tests the range of min_possible_value -> max_possible_value with a delta of test_delta. - Message is also only allowed to be sent when controls_allowed is true, unless the value is equal to inactive_value. - Message is never allowed if msg_allowed is false, for example when stock longitudinal is enabled and you are sending acceleration requests. - additional_setup is used for extra setup before each _tx, ex: for setting the previous torque for rate limits - """ - - # Ensure that we at least test the allowed_value range - self.assertGreater(max_possible_value, max_allowed_value) - self.assertLessEqual(min_possible_value, min_allowed_value) - - for controls_allowed in [False, True]: - # enforce we don't skip over 0 or inactive - for v in np.concatenate((np.arange(min_possible_value, max_possible_value, test_delta), np.array([0, inactive_value]))): - v = round(v, 2) # floats might not hit exact boundary conditions without rounding - self.safety.set_controls_allowed(controls_allowed) - if additional_setup is not None: - additional_setup(v) - should_tx = controls_allowed and min_allowed_value <= v <= max_allowed_value - should_tx = (should_tx or v == inactive_value) and msg_allowed - self.assertEqual(self._tx(msg_function(v)), should_tx, (controls_allowed, should_tx, v)) - - def _common_measurement_test(self, msg_func: Callable, min_value: float, max_value: float, factor: float, - meas_min_func: Callable[[], int], meas_max_func: Callable[[], int]): - """Tests accurate measurement parsing, and that the struct is reset on safety mode init""" - for val in np.arange(min_value, max_value, 0.5): - for i in range(MAX_SAMPLE_VALS): - self.assertTrue(self._rx(msg_func(val + i * 0.1))) - - # assert close by one decimal place - self.assertAlmostEqual(meas_min_func() / factor, val, delta=0.1) - self.assertAlmostEqual(meas_max_func() / factor - 0.5, val, delta=0.1) - - # ensure sample_t is reset on safety init - self._reset_safety_hooks() - self.assertEqual(meas_min_func(), 0) - self.assertEqual(meas_max_func(), 0) - - -class GasInterceptorSafetyTest(PandaSafetyTestBase): - - INTERCEPTOR_THRESHOLD = 0 - - cnt_gas_cmd = 0 - cnt_user_gas = 0 - - packer: CANPackerPanda - - @classmethod - def setUpClass(cls): - if cls.__name__ == "GasInterceptorSafetyTest" or cls.__name__.endswith("Base"): - cls.safety = None - raise unittest.SkipTest - - def _interceptor_gas_cmd(self, gas: int): - values: dict[str, float | int] = {"COUNTER_PEDAL": self.__class__.cnt_gas_cmd & 0xF} - if gas > 0: - values["GAS_COMMAND"] = gas * 255. - values["GAS_COMMAND2"] = gas * 255. - self.__class__.cnt_gas_cmd += 1 - return self.packer.make_can_msg_panda("GAS_COMMAND", 0, values) - - def _interceptor_user_gas(self, gas: int): - values = {"INTERCEPTOR_GAS": gas, "INTERCEPTOR_GAS2": gas, - "COUNTER_PEDAL": self.__class__.cnt_user_gas} - self.__class__.cnt_user_gas += 1 - return self.packer.make_can_msg_panda("GAS_SENSOR", 0, values) - - # Skip non-interceptor user gas tests - def test_prev_gas(self): - pass - - def test_disengage_on_gas(self): - pass - - def test_alternative_experience_no_disengage_on_gas(self): - pass - - def test_prev_gas_interceptor(self): - self._rx(self._interceptor_user_gas(0x0)) - self.assertFalse(self.safety.get_gas_interceptor_prev()) - self._rx(self._interceptor_user_gas(0x1000)) - self.assertTrue(self.safety.get_gas_interceptor_prev()) - self._rx(self._interceptor_user_gas(0x0)) - - def test_disengage_on_gas_interceptor(self): - for g in range(0x1000): - self._rx(self._interceptor_user_gas(0)) - self.safety.set_controls_allowed(True) - self._rx(self._interceptor_user_gas(g)) - remain_enabled = g <= self.INTERCEPTOR_THRESHOLD - self.assertEqual(remain_enabled, self.safety.get_controls_allowed()) - self._rx(self._interceptor_user_gas(0)) - - def test_alternative_experience_no_disengage_on_gas_interceptor(self): - self.safety.set_controls_allowed(True) - self.safety.set_alternative_experience(ALTERNATIVE_EXPERIENCE.DISABLE_DISENGAGE_ON_GAS) - for g in range(0x1000): - self._rx(self._interceptor_user_gas(g)) - # Test we allow lateral, but not longitudinal - self.assertTrue(self.safety.get_controls_allowed()) - self.assertEqual(g <= self.INTERCEPTOR_THRESHOLD, self.safety.get_longitudinal_allowed()) - # Make sure we can re-gain longitudinal actuation - self._rx(self._interceptor_user_gas(0)) - self.assertTrue(self.safety.get_longitudinal_allowed()) - - def test_allow_engage_with_gas_interceptor_pressed(self): - self._rx(self._interceptor_user_gas(0x1000)) - self.safety.set_controls_allowed(1) - self._rx(self._interceptor_user_gas(0x1000)) - self.assertTrue(self.safety.get_controls_allowed()) - self._rx(self._interceptor_user_gas(0)) - - def test_gas_interceptor_safety_check(self): - for gas in np.arange(0, 4000, 100): - for controls_allowed in [True, False]: - self.safety.set_controls_allowed(controls_allowed) - if controls_allowed: - send = True - else: - send = gas == 0 - self.assertEqual(send, self._tx(self._interceptor_gas_cmd(gas))) - - -class LongitudinalAccelSafetyTest(PandaSafetyTestBase, abc.ABC): - - MAX_ACCEL: float = 2.0 - MIN_ACCEL: float = -3.5 - INACTIVE_ACCEL: float = 0.0 - - @classmethod - def setUpClass(cls): - if cls.__name__ == "LongitudinalAccelSafetyTest": - cls.safety = None - raise unittest.SkipTest - - @abc.abstractmethod - def _accel_msg(self, accel: float): - pass - - def test_accel_limits_correct(self): - self.assertGreater(self.MAX_ACCEL, 0) - self.assertLess(self.MIN_ACCEL, 0) - - def test_accel_actuation_limits(self, stock_longitudinal=False): - limits = ((self.MIN_ACCEL, self.MAX_ACCEL, ALTERNATIVE_EXPERIENCE.DEFAULT), - (self.MIN_ACCEL, self.MAX_ACCEL, ALTERNATIVE_EXPERIENCE.RAISE_LONGITUDINAL_LIMITS_TO_ISO_MAX)) - - for min_accel, max_accel, alternative_experience in limits: - # enforce we don't skip over 0 or inactive accel - for accel in np.concatenate((np.arange(min_accel - 1, max_accel + 1, 0.05), [0, self.INACTIVE_ACCEL])): - accel = round(accel, 2) # floats might not hit exact boundary conditions without rounding - for controls_allowed in [True, False]: - self.safety.set_controls_allowed(controls_allowed) - self.safety.set_alternative_experience(alternative_experience) - if stock_longitudinal: - should_tx = False - else: - should_tx = controls_allowed and min_accel <= accel <= max_accel - should_tx = should_tx or accel == self.INACTIVE_ACCEL - self.assertEqual(should_tx, self._tx(self._accel_msg(accel))) - - -class LongitudinalGasBrakeSafetyTest(PandaSafetyTestBase, abc.ABC): - - MIN_BRAKE: int = 0 - MAX_BRAKE: int | None = None - MAX_POSSIBLE_BRAKE: int | None = None - - MIN_GAS: int = 0 - MAX_GAS: int | None = None - INACTIVE_GAS = 0 - MAX_POSSIBLE_GAS: int | None = None - - def test_gas_brake_limits_correct(self): - self.assertIsNotNone(self.MAX_POSSIBLE_BRAKE) - self.assertIsNotNone(self.MAX_POSSIBLE_GAS) - - self.assertGreater(self.MAX_BRAKE, self.MIN_BRAKE) - self.assertGreater(self.MAX_GAS, self.MIN_GAS) - - @abc.abstractmethod - def _send_gas_msg(self, gas: int): - pass - - @abc.abstractmethod - def _send_brake_msg(self, brake: int): - pass - - def test_brake_safety_check(self): - self._generic_limit_safety_check(self._send_brake_msg, self.MIN_BRAKE, self.MAX_BRAKE, 0, self.MAX_POSSIBLE_BRAKE, 1) - - def test_gas_safety_check(self): - self._generic_limit_safety_check(self._send_gas_msg, self.MIN_GAS, self.MAX_GAS, 0, self.MAX_POSSIBLE_GAS, 1, self.INACTIVE_GAS) - - -class TorqueSteeringSafetyTestBase(PandaSafetyTestBase, abc.ABC): - - MAX_RATE_UP = 0 - MAX_RATE_DOWN = 0 - MAX_TORQUE = 0 - MAX_RT_DELTA = 0 - RT_INTERVAL = 0 - - NO_STEER_REQ_BIT = False - - @classmethod - def setUpClass(cls): - if cls.__name__ == "TorqueSteeringSafetyTestBase": - cls.safety = None - raise unittest.SkipTest - - @abc.abstractmethod - def _torque_cmd_msg(self, torque, steer_req=1): - pass - - def _set_prev_torque(self, t): - self.safety.set_desired_torque_last(t) - self.safety.set_rt_torque_last(t) - - def test_steer_safety_check(self): - for enabled in [0, 1]: - for t in range(int(-self.MAX_TORQUE * 1.5), int(self.MAX_TORQUE * 1.5)): - self.safety.set_controls_allowed(enabled) - self._set_prev_torque(t) - if abs(t) > self.MAX_TORQUE or (not enabled and abs(t) > 0): - self.assertFalse(self._tx(self._torque_cmd_msg(t))) - else: - self.assertTrue(self._tx(self._torque_cmd_msg(t))) - - def test_non_realtime_limit_up(self): - self.safety.set_controls_allowed(True) - - self._set_prev_torque(0) - self.assertTrue(self._tx(self._torque_cmd_msg(self.MAX_RATE_UP))) - self._set_prev_torque(0) - self.assertTrue(self._tx(self._torque_cmd_msg(-self.MAX_RATE_UP))) - - self._set_prev_torque(0) - self.assertFalse(self._tx(self._torque_cmd_msg(self.MAX_RATE_UP + 1))) - self.safety.set_controls_allowed(True) - self._set_prev_torque(0) - self.assertFalse(self._tx(self._torque_cmd_msg(-self.MAX_RATE_UP - 1))) - - def test_steer_req_bit(self): - """Asserts all torque safety modes check the steering request bit""" - if self.NO_STEER_REQ_BIT: - raise unittest.SkipTest("No steering request bit") - - self.safety.set_controls_allowed(True) - self._set_prev_torque(self.MAX_TORQUE) - - # Send torque successfully, then only drop the request bit and ensure it stays blocked - for _ in range(10): - self.assertTrue(self._tx(self._torque_cmd_msg(self.MAX_TORQUE, 1))) - - self.assertFalse(self._tx(self._torque_cmd_msg(self.MAX_TORQUE, 0))) - for _ in range(10): - self.assertFalse(self._tx(self._torque_cmd_msg(self.MAX_TORQUE, 1))) - - -class SteerRequestCutSafetyTest(TorqueSteeringSafetyTestBase, abc.ABC): - - @classmethod - def setUpClass(cls): - if cls.__name__ == "SteerRequestCutSafetyTest": - cls.safety = None - raise unittest.SkipTest - - # Safety around steering request bit mismatch tolerance - MIN_VALID_STEERING_FRAMES: int - MAX_INVALID_STEERING_FRAMES: int - MIN_VALID_STEERING_RT_INTERVAL: int - - def test_steer_req_bit_frames(self): - """ - Certain safety modes implement some tolerance on their steer request bits matching the - requested torque to avoid a steering fault or lockout and maintain torque. This tests: - - We can't cut torque for more than one frame - - We can't cut torque until at least the minimum number of matching steer_req messages - - We can always recover from violations if steer_req=1 - """ - - for min_valid_steer_frames in range(self.MIN_VALID_STEERING_FRAMES * 2): - # Reset match count and rt timer to allow cut (valid_steer_req_count, ts_steer_req_mismatch_last) - self.safety.init_tests() - self.safety.set_timer(self.MIN_VALID_STEERING_RT_INTERVAL) - - # Allow torque cut - self.safety.set_controls_allowed(True) - self._set_prev_torque(self.MAX_TORQUE) - for _ in range(min_valid_steer_frames): - self.assertTrue(self._tx(self._torque_cmd_msg(self.MAX_TORQUE, steer_req=1))) - - # should tx if we've sent enough valid frames, and we're not cutting torque for too many frames consecutively - should_tx = min_valid_steer_frames >= self.MIN_VALID_STEERING_FRAMES - for idx in range(self.MAX_INVALID_STEERING_FRAMES * 2): - tx = self._tx(self._torque_cmd_msg(self.MAX_TORQUE, steer_req=0)) - self.assertEqual(should_tx and idx < self.MAX_INVALID_STEERING_FRAMES, tx) - - # Keep blocking after one steer_req mismatch - for _ in range(100): - self.assertFalse(self._tx(self._torque_cmd_msg(self.MAX_TORQUE, steer_req=0))) - - # Make sure we can recover - self.assertTrue(self._tx(self._torque_cmd_msg(0, steer_req=1))) - self._set_prev_torque(self.MAX_TORQUE) - self.assertTrue(self._tx(self._torque_cmd_msg(self.MAX_TORQUE, steer_req=1))) - - def test_steer_req_bit_multi_invalid(self): - """ - For safety modes allowing multiple consecutive invalid frames, this ensures that once a valid frame - is sent after an invalid frame (even without sending the max number of allowed invalid frames), - all counters are reset. - """ - for max_invalid_steer_frames in range(1, self.MAX_INVALID_STEERING_FRAMES * 2): - self.safety.init_tests() - self.safety.set_timer(self.MIN_VALID_STEERING_RT_INTERVAL) - - # Allow torque cut - self.safety.set_controls_allowed(True) - self._set_prev_torque(self.MAX_TORQUE) - for _ in range(self.MIN_VALID_STEERING_FRAMES): - self.assertTrue(self._tx(self._torque_cmd_msg(self.MAX_TORQUE, steer_req=1))) - - # Send partial amount of allowed invalid frames - for idx in range(max_invalid_steer_frames): - should_tx = idx < self.MAX_INVALID_STEERING_FRAMES - self.assertEqual(should_tx, self._tx(self._torque_cmd_msg(self.MAX_TORQUE, steer_req=0))) - - # Send one valid frame, and subsequent invalid should now be blocked - self._set_prev_torque(self.MAX_TORQUE) - self.assertTrue(self._tx(self._torque_cmd_msg(self.MAX_TORQUE, steer_req=1))) - for _ in range(self.MIN_VALID_STEERING_FRAMES + 1): - self.assertFalse(self._tx(self._torque_cmd_msg(self.MAX_TORQUE, steer_req=0))) - - def test_steer_req_bit_realtime(self): - """ - Realtime safety for cutting steer request bit. This tests: - - That we allow messages with mismatching steer request bit if time from last is >= MIN_VALID_STEERING_RT_INTERVAL - - That frame mismatch safety does not interfere with this test - """ - for rt_us in np.arange(self.MIN_VALID_STEERING_RT_INTERVAL - 50000, self.MIN_VALID_STEERING_RT_INTERVAL + 50000, 10000): - # Reset match count and rt timer (valid_steer_req_count, ts_steer_req_mismatch_last) - self.safety.init_tests() - - # Make sure valid_steer_req_count doesn't affect this test - self.safety.set_controls_allowed(True) - self._set_prev_torque(self.MAX_TORQUE) - for _ in range(self.MIN_VALID_STEERING_FRAMES): - self.assertTrue(self._tx(self._torque_cmd_msg(self.MAX_TORQUE, steer_req=1))) - - # Normally, sending MIN_VALID_STEERING_FRAMES valid frames should always allow - self.safety.set_timer(max(rt_us, 0)) - should_tx = rt_us >= self.MIN_VALID_STEERING_RT_INTERVAL - for _ in range(self.MAX_INVALID_STEERING_FRAMES): - self.assertEqual(should_tx, self._tx(self._torque_cmd_msg(self.MAX_TORQUE, steer_req=0))) - - # Keep blocking after one steer_req mismatch - for _ in range(100): - self.assertFalse(self._tx(self._torque_cmd_msg(self.MAX_TORQUE, steer_req=0))) - - # Make sure we can recover - self.assertTrue(self._tx(self._torque_cmd_msg(0, steer_req=1))) - self._set_prev_torque(self.MAX_TORQUE) - self.assertTrue(self._tx(self._torque_cmd_msg(self.MAX_TORQUE, steer_req=1))) - - -class DriverTorqueSteeringSafetyTest(TorqueSteeringSafetyTestBase, abc.ABC): - - DRIVER_TORQUE_ALLOWANCE = 0 - DRIVER_TORQUE_FACTOR = 0 - - @classmethod - def setUpClass(cls): - if cls.__name__ == "DriverTorqueSteeringSafetyTest": - cls.safety = None - raise unittest.SkipTest - - @abc.abstractmethod - def _torque_driver_msg(self, torque): - pass - - def _reset_torque_driver_measurement(self, torque): - for _ in range(MAX_SAMPLE_VALS): - self._rx(self._torque_driver_msg(torque)) - - def test_non_realtime_limit_up(self): - self._reset_torque_driver_measurement(0) - super().test_non_realtime_limit_up() - - def test_against_torque_driver(self): - # Tests down limits and driver torque blending - self.safety.set_controls_allowed(True) - - # Cannot stay at MAX_TORQUE if above DRIVER_TORQUE_ALLOWANCE - for sign in [-1, 1]: - for driver_torque in np.arange(0, self.DRIVER_TORQUE_ALLOWANCE * 2, 1): - self._reset_torque_driver_measurement(-driver_torque * sign) - self._set_prev_torque(self.MAX_TORQUE * sign) - should_tx = abs(driver_torque) <= self.DRIVER_TORQUE_ALLOWANCE - self.assertEqual(should_tx, self._tx(self._torque_cmd_msg(self.MAX_TORQUE * sign))) - - # arbitrary high driver torque to ensure max steer torque is allowed - max_driver_torque = int(self.MAX_TORQUE / self.DRIVER_TORQUE_FACTOR + self.DRIVER_TORQUE_ALLOWANCE + 1) - - # spot check some individual cases - for sign in [-1, 1]: - # Ensure we wind down factor units for every unit above allowance - driver_torque = (self.DRIVER_TORQUE_ALLOWANCE + 10) * sign - torque_desired = (self.MAX_TORQUE - 10 * self.DRIVER_TORQUE_FACTOR) * sign - delta = 1 * sign - self._set_prev_torque(torque_desired) - self._reset_torque_driver_measurement(-driver_torque) - self.assertTrue(self._tx(self._torque_cmd_msg(torque_desired))) - self._set_prev_torque(torque_desired + delta) - self._reset_torque_driver_measurement(-driver_torque) - self.assertFalse(self._tx(self._torque_cmd_msg(torque_desired + delta))) - - # If we're well past the allowance, minimum wind down is MAX_RATE_DOWN - self._set_prev_torque(self.MAX_TORQUE * sign) - self._reset_torque_driver_measurement(-max_driver_torque * sign) - self.assertTrue(self._tx(self._torque_cmd_msg((self.MAX_TORQUE - self.MAX_RATE_DOWN) * sign))) - self._set_prev_torque(self.MAX_TORQUE * sign) - self._reset_torque_driver_measurement(-max_driver_torque * sign) - self.assertTrue(self._tx(self._torque_cmd_msg(0))) - self._set_prev_torque(self.MAX_TORQUE * sign) - self._reset_torque_driver_measurement(-max_driver_torque * sign) - self.assertFalse(self._tx(self._torque_cmd_msg((self.MAX_TORQUE - self.MAX_RATE_DOWN + 1) * sign))) - - def test_realtime_limits(self): - self.safety.set_controls_allowed(True) - - for sign in [-1, 1]: - self.safety.init_tests() - self._set_prev_torque(0) - self._reset_torque_driver_measurement(0) - for t in np.arange(0, self.MAX_RT_DELTA, 1): - t *= sign - self.assertTrue(self._tx(self._torque_cmd_msg(t))) - self.assertFalse(self._tx(self._torque_cmd_msg(sign * (self.MAX_RT_DELTA + 1)))) - - self._set_prev_torque(0) - for t in np.arange(0, self.MAX_RT_DELTA, 1): - t *= sign - self.assertTrue(self._tx(self._torque_cmd_msg(t))) - - # Increase timer to update rt_torque_last - self.safety.set_timer(self.RT_INTERVAL + 1) - self.assertTrue(self._tx(self._torque_cmd_msg(sign * (self.MAX_RT_DELTA - 1)))) - self.assertTrue(self._tx(self._torque_cmd_msg(sign * (self.MAX_RT_DELTA + 1)))) - - def test_reset_driver_torque_measurements(self): - # Tests that the driver torque measurement sample_t is reset on safety mode init - for t in np.linspace(-self.MAX_TORQUE, self.MAX_TORQUE, MAX_SAMPLE_VALS): - self.assertTrue(self._rx(self._torque_driver_msg(t))) - - self.assertNotEqual(self.safety.get_torque_driver_min(), 0) - self.assertNotEqual(self.safety.get_torque_driver_max(), 0) - - self._reset_safety_hooks() - self.assertEqual(self.safety.get_torque_driver_min(), 0) - self.assertEqual(self.safety.get_torque_driver_max(), 0) - - -class MotorTorqueSteeringSafetyTest(TorqueSteeringSafetyTestBase, abc.ABC): - - MAX_TORQUE_ERROR = 0 - TORQUE_MEAS_TOLERANCE = 0 - - @classmethod - def setUpClass(cls): - if cls.__name__ == "MotorTorqueSteeringSafetyTest": - cls.safety = None - raise unittest.SkipTest - - @abc.abstractmethod - def _torque_meas_msg(self, torque): - pass - - def _set_prev_torque(self, t): - super()._set_prev_torque(t) - self.safety.set_torque_meas(t, t) - - def test_torque_absolute_limits(self): - for controls_allowed in [True, False]: - for torque in np.arange(-self.MAX_TORQUE - 1000, self.MAX_TORQUE + 1000, self.MAX_RATE_UP): - self.safety.set_controls_allowed(controls_allowed) - self.safety.set_rt_torque_last(torque) - self.safety.set_torque_meas(torque, torque) - self.safety.set_desired_torque_last(torque - self.MAX_RATE_UP) - - if controls_allowed: - send = (-self.MAX_TORQUE <= torque <= self.MAX_TORQUE) - else: - send = torque == 0 - - self.assertEqual(send, self._tx(self._torque_cmd_msg(torque))) - - def test_non_realtime_limit_down(self): - self.safety.set_controls_allowed(True) - - torque_meas = self.MAX_TORQUE - self.MAX_TORQUE_ERROR - 50 - - self.safety.set_rt_torque_last(self.MAX_TORQUE) - self.safety.set_torque_meas(torque_meas, torque_meas) - self.safety.set_desired_torque_last(self.MAX_TORQUE) - self.assertTrue(self._tx(self._torque_cmd_msg(self.MAX_TORQUE - self.MAX_RATE_DOWN))) - - self.safety.set_rt_torque_last(self.MAX_TORQUE) - self.safety.set_torque_meas(torque_meas, torque_meas) - self.safety.set_desired_torque_last(self.MAX_TORQUE) - self.assertFalse(self._tx(self._torque_cmd_msg(self.MAX_TORQUE - self.MAX_RATE_DOWN + 1))) - - def test_exceed_torque_sensor(self): - self.safety.set_controls_allowed(True) - - for sign in [-1, 1]: - self._set_prev_torque(0) - for t in np.arange(0, self.MAX_TORQUE_ERROR + 2, 2): # step needs to be smaller than MAX_TORQUE_ERROR - t *= sign - self.assertTrue(self._tx(self._torque_cmd_msg(t))) - - self.assertFalse(self._tx(self._torque_cmd_msg(sign * (self.MAX_TORQUE_ERROR + 2)))) - - def test_realtime_limit_up(self): - self.safety.set_controls_allowed(True) - - for sign in [-1, 1]: - self.safety.init_tests() - self._set_prev_torque(0) - for t in np.arange(0, self.MAX_RT_DELTA + 1, 1): - t *= sign - self.safety.set_torque_meas(t, t) - self.assertTrue(self._tx(self._torque_cmd_msg(t))) - self.assertFalse(self._tx(self._torque_cmd_msg(sign * (self.MAX_RT_DELTA + 1)))) - - self._set_prev_torque(0) - for t in np.arange(0, self.MAX_RT_DELTA + 1, 1): - t *= sign - self.safety.set_torque_meas(t, t) - self.assertTrue(self._tx(self._torque_cmd_msg(t))) - - # Increase timer to update rt_torque_last - self.safety.set_timer(self.RT_INTERVAL + 1) - self.assertTrue(self._tx(self._torque_cmd_msg(sign * self.MAX_RT_DELTA))) - self.assertTrue(self._tx(self._torque_cmd_msg(sign * (self.MAX_RT_DELTA + 1)))) - - def test_torque_measurements(self): - trq = 50 - for t in [trq, -trq, 0, 0, 0, 0]: - self._rx(self._torque_meas_msg(t)) - - max_range = range(trq, trq + self.TORQUE_MEAS_TOLERANCE + 1) - min_range = range(-(trq + self.TORQUE_MEAS_TOLERANCE), -trq + 1) - self.assertTrue(self.safety.get_torque_meas_min() in min_range) - self.assertTrue(self.safety.get_torque_meas_max() in max_range) - - max_range = range(self.TORQUE_MEAS_TOLERANCE + 1) - min_range = range(-(trq + self.TORQUE_MEAS_TOLERANCE), -trq + 1) - self._rx(self._torque_meas_msg(0)) - self.assertTrue(self.safety.get_torque_meas_min() in min_range) - self.assertTrue(self.safety.get_torque_meas_max() in max_range) - - max_range = range(self.TORQUE_MEAS_TOLERANCE + 1) - min_range = range(-self.TORQUE_MEAS_TOLERANCE, 0 + 1) - self._rx(self._torque_meas_msg(0)) - self.assertTrue(self.safety.get_torque_meas_min() in min_range) - self.assertTrue(self.safety.get_torque_meas_max() in max_range) - - def test_reset_torque_measurements(self): - # Tests that the torque measurement sample_t is reset on safety mode init - for t in np.linspace(-self.MAX_TORQUE, self.MAX_TORQUE, MAX_SAMPLE_VALS): - self.assertTrue(self._rx(self._torque_meas_msg(t))) - - self.assertNotEqual(self.safety.get_torque_meas_min(), 0) - self.assertNotEqual(self.safety.get_torque_meas_max(), 0) - - self._reset_safety_hooks() - self.assertEqual(self.safety.get_torque_meas_min(), 0) - self.assertEqual(self.safety.get_torque_meas_max(), 0) - - -class AngleSteeringSafetyTest(PandaSafetyTestBase): - - DEG_TO_CAN: float - ANGLE_RATE_BP: list[float] - ANGLE_RATE_UP: list[float] # windup limit - ANGLE_RATE_DOWN: list[float] # unwind limit - - @classmethod - def setUpClass(cls): - if cls.__name__ == "AngleSteeringSafetyTest": - cls.safety = None - raise unittest.SkipTest - - @abc.abstractmethod - def _speed_msg(self, speed): - pass - - @abc.abstractmethod - def _angle_cmd_msg(self, angle: float, enabled: bool): - pass - - @abc.abstractmethod - def _angle_meas_msg(self, angle: float): - pass - - def _set_prev_desired_angle(self, t): - t = round(t * self.DEG_TO_CAN) - self.safety.set_desired_angle_last(t) - - def _reset_angle_measurement(self, angle): - for _ in range(MAX_SAMPLE_VALS): - self._rx(self._angle_meas_msg(angle)) - - def _reset_speed_measurement(self, speed): - for _ in range(MAX_SAMPLE_VALS): - self._rx(self._speed_msg(speed)) - - def test_vehicle_speed_measurements(self): - self._common_measurement_test(self._speed_msg, 0, 80, VEHICLE_SPEED_FACTOR, self.safety.get_vehicle_speed_min, self.safety.get_vehicle_speed_max) - - def test_steering_angle_measurements(self, max_angle=300): - self._common_measurement_test(self._angle_meas_msg, -max_angle, max_angle, self.DEG_TO_CAN, self.safety.get_angle_meas_min, self.safety.get_angle_meas_max) - - def test_angle_cmd_when_enabled(self, max_angle=300): - # when controls are allowed, angle cmd rate limit is enforced - speeds = [0., 1., 5., 10., 15., 50.] - angles = np.concatenate((np.arange(-max_angle, max_angle, 5), [0])) - for a in angles: - for s in speeds: - max_delta_up = np.interp(s, self.ANGLE_RATE_BP, self.ANGLE_RATE_UP) - max_delta_down = np.interp(s, self.ANGLE_RATE_BP, self.ANGLE_RATE_DOWN) - - # first test against false positives - self._reset_angle_measurement(a) - self._reset_speed_measurement(s) - - self._set_prev_desired_angle(a) - self.safety.set_controls_allowed(1) - - # Stay within limits - # Up - self.assertTrue(self._tx(self._angle_cmd_msg(a + sign_of(a) * max_delta_up, True))) - self.assertTrue(self.safety.get_controls_allowed()) - - # Don't change - self.assertTrue(self._tx(self._angle_cmd_msg(a, True))) - self.assertTrue(self.safety.get_controls_allowed()) - - # Down - self.assertTrue(self._tx(self._angle_cmd_msg(a - sign_of(a) * max_delta_down, True))) - self.assertTrue(self.safety.get_controls_allowed()) - - # Inject too high rates - # Up - self.assertFalse(self._tx(self._angle_cmd_msg(a + sign_of(a) * (max_delta_up + 1.1), True))) - - # Don't change - self.safety.set_controls_allowed(1) - self._set_prev_desired_angle(a) - self.assertTrue(self.safety.get_controls_allowed()) - self.assertTrue(self._tx(self._angle_cmd_msg(a, True))) - self.assertTrue(self.safety.get_controls_allowed()) - - # Down - self.assertFalse(self._tx(self._angle_cmd_msg(a - sign_of(a) * (max_delta_down + 1.1), True))) - - # Check desired steer should be the same as steer angle when controls are off - self.safety.set_controls_allowed(0) - self.assertTrue(self._tx(self._angle_cmd_msg(a, False))) - - def test_angle_cmd_when_disabled(self): - # Tests that only angles close to the meas are allowed while - # steer actuation bit is 0, regardless of controls allowed. - for controls_allowed in (True, False): - self.safety.set_controls_allowed(controls_allowed) - - for steer_control_enabled in (True, False): - for angle_meas in np.arange(-90, 91, 10): - self._reset_angle_measurement(angle_meas) - - for angle_cmd in np.arange(-90, 91, 10): - self._set_prev_desired_angle(angle_cmd) - - # controls_allowed is checked if actuation bit is 1, else the angle must be close to meas (inactive) - should_tx = controls_allowed if steer_control_enabled else angle_cmd == angle_meas - self.assertEqual(should_tx, self._tx(self._angle_cmd_msg(angle_cmd, steer_control_enabled))) - - -class PandaSafetyTest(PandaSafetyTestBase): - TX_MSGS: list[list[int]] | None = None - SCANNED_ADDRS = [*range(0x800), # Entire 11-bit CAN address space - *range(0x18DA00F1, 0x18DB00F1, 0x100), # 29-bit UDS physical addressing - *range(0x18DB00F1, 0x18DC00F1, 0x100), # 29-bit UDS functional addressing - *range(0x3300, 0x3400), # Honda - 0x10400060, 0x104c006c] # GMLAN (exceptions, range/format unclear) - FWD_BLACKLISTED_ADDRS: dict[int, list[int]] = {} # {bus: [addr]} - FWD_BUS_LOOKUP: dict[int, int] = {} - - @classmethod - def setUpClass(cls): - if cls.__name__ == "PandaSafetyTest" or cls.__name__.endswith('Base'): - cls.safety = None - raise unittest.SkipTest - - # ***** standard tests for all safety modes ***** - - def test_tx_msg_in_scanned_range(self): - # the relay malfunction, fwd hook, and spam can tests don't exhaustively - # scan the entire 29-bit address space, only some known important ranges - # make sure SCANNED_ADDRS stays up to date with car port TX_MSGS; new - # model ports should expand the range if needed - for msg in self.TX_MSGS: - self.assertTrue(msg[0] in self.SCANNED_ADDRS, f"{msg[0]=:#x}") - - def test_fwd_hook(self): - # some safety modes don't forward anything, while others blacklist msgs - for bus in range(3): - for addr in self.SCANNED_ADDRS: - # assume len 8 - fwd_bus = self.FWD_BUS_LOOKUP.get(bus, -1) - if bus in self.FWD_BLACKLISTED_ADDRS and addr in self.FWD_BLACKLISTED_ADDRS[bus]: - fwd_bus = -1 - self.assertEqual(fwd_bus, self.safety.safety_fwd_hook(bus, addr), f"{addr=:#x} from {bus=} to {fwd_bus=}") - - def test_spam_can_buses(self): - for bus in range(4): - for addr in self.SCANNED_ADDRS: - if [addr, bus] not in self.TX_MSGS: - self.assertFalse(self._tx(make_msg(bus, addr, 8)), f"allowed TX {addr=} {bus=}") - - def test_default_controls_not_allowed(self): - self.assertFalse(self.safety.get_controls_allowed()) - - def test_manually_enable_controls_allowed(self): - self.safety.set_controls_allowed(1) - self.assertTrue(self.safety.get_controls_allowed()) - self.safety.set_controls_allowed(0) - self.assertFalse(self.safety.get_controls_allowed()) - - def test_tx_hook_on_wrong_safety_mode(self): - files = os.listdir(os.path.dirname(os.path.realpath(__file__))) - test_files = [f for f in files if f.startswith("test_") and f.endswith(".py")] - - current_test = self.__class__.__name__ - - all_tx = [] - for tf in test_files: - test = importlib.import_module("panda.tests.safety."+tf[:-3]) - for attr in dir(test): - if attr.startswith("Test") and attr != current_test: - tc = getattr(test, attr) - tx = tc.TX_MSGS - if tx is not None and not attr.endswith('Base'): - # No point in comparing different Tesla safety modes - if 'Tesla' in attr and 'Tesla' in current_test: - continue - # No point in comparing to ALLOUTPUT which allows all messages - if attr.startswith('TestAllOutput'): - continue - if attr.startswith('TestToyota') and current_test.startswith('TestToyota'): - continue - if attr.startswith('TestSubaruGen') and current_test.startswith('TestSubaruGen'): - continue - if attr.startswith('TestSubaruPreglobal') and current_test.startswith('TestSubaruPreglobal'): - continue - if {attr, current_test}.issubset({'TestVolkswagenPqSafety', 'TestVolkswagenPqStockSafety', 'TestVolkswagenPqLongSafety'}): - continue - if {attr, current_test}.issubset({'TestGmCameraSafety', 'TestGmCameraLongitudinalSafety'}): - continue - if attr.startswith('TestFord') and current_test.startswith('TestFord'): - continue - if attr.startswith('TestHyundaiCanfd') and current_test.startswith('TestHyundaiCanfd'): - continue - if {attr, current_test}.issubset({'TestVolkswagenMqbSafety', 'TestVolkswagenMqbStockSafety', 'TestVolkswagenMqbLongSafety'}): - continue - - # overlapping TX addrs, but they're not actuating messages for either car - if attr == 'TestHyundaiCanfdHDA2LongEV' and current_test.startswith('TestToyota'): - tx = list(filter(lambda m: m[0] not in [0x160, ], tx)) - - # Volkswagen MQB longitudinal actuating message overlaps with the Subaru lateral actuating message - if attr == 'TestVolkswagenMqbLongSafety' and current_test.startswith('TestSubaru'): - tx = list(filter(lambda m: m[0] not in [0x122, ], tx)) - - # Volkswagen MQB and Honda Nidec ACC HUD messages overlap - if attr == 'TestVolkswagenMqbLongSafety' and current_test.startswith('TestHondaNidec'): - tx = list(filter(lambda m: m[0] not in [0x30c, ], tx)) - - # Volkswagen MQB and Honda Bosch Radarless ACC HUD messages overlap - if attr == 'TestVolkswagenMqbLongSafety' and current_test.startswith('TestHondaBoschRadarless'): - tx = list(filter(lambda m: m[0] not in [0x30c, ], tx)) - - # TODO: Temporary, should be fixed in panda firmware, safety_honda.h - if attr.startswith('TestHonda'): - # exceptions for common msgs across different hondas - tx = list(filter(lambda m: m[0] not in [0x1FA, 0x30C, 0x33D, 0x33DB], tx)) - all_tx.append([[m[0], m[1], attr] for m in tx]) - - # make sure we got all the msgs - self.assertTrue(len(all_tx) >= len(test_files)-1) - - for tx_msgs in all_tx: - for addr, bus, test_name in tx_msgs: - msg = make_msg(bus, addr) - self.safety.set_controls_allowed(1) - # TODO: this should be blocked - if current_test in ["TestNissanSafety", "TestNissanSafetyAltEpsBus", "TestNissanLeafSafety"] and [addr, bus] in self.TX_MSGS: - continue - self.assertFalse(self._tx(msg), f"transmit of {addr=:#x} {bus=} from {test_name} during {current_test} was allowed") - - -@add_regen_tests -class PandaCarSafetyTest(PandaSafetyTest): - STANDSTILL_THRESHOLD: float | None = None - GAS_PRESSED_THRESHOLD = 0 - RELAY_MALFUNCTION_ADDRS: dict[int, tuple[int, ...]] | None = None - - @classmethod - def setUpClass(cls): - if cls.__name__ == "PandaCarSafetyTest" or cls.__name__.endswith('Base'): - cls.safety = None - raise unittest.SkipTest - - @abc.abstractmethod - def _user_brake_msg(self, brake): - pass - - def _user_regen_msg(self, regen): - pass - - @abc.abstractmethod - def _speed_msg(self, speed): - pass - - # Safety modes can override if vehicle_moving is driven by a different message - def _vehicle_moving_msg(self, speed: float): - return self._speed_msg(speed) - - @abc.abstractmethod - def _user_gas_msg(self, gas): - pass - - @abc.abstractmethod - def _pcm_status_msg(self, enable): - pass - - # ***** standard tests for all car-specific safety modes ***** - - def test_relay_malfunction(self): - # each car has an addr that is used to detect relay malfunction - # if that addr is seen on specified bus, triggers the relay malfunction - # protection logic: both tx_hook and fwd_hook are expected to return failure - self.assertFalse(self.safety.get_relay_malfunction()) - for bus in range(3): - for addr in self.SCANNED_ADDRS: - self.safety.set_relay_malfunction(False) - self._rx(make_msg(bus, addr, 8)) - should_relay_malfunction = addr in self.RELAY_MALFUNCTION_ADDRS.get(bus, ()) - self.assertEqual(should_relay_malfunction, self.safety.get_relay_malfunction(), (bus, addr)) - - # test relay malfunction protection logic - self.safety.set_relay_malfunction(True) - for bus in range(3): - for addr in self.SCANNED_ADDRS: - self.assertFalse(self._tx(make_msg(bus, addr, 8))) - self.assertEqual(-1, self.safety.safety_fwd_hook(bus, addr)) - - def test_prev_gas(self): - self.assertFalse(self.safety.get_gas_pressed_prev()) - for pressed in [self.GAS_PRESSED_THRESHOLD + 1, 0]: - self._rx(self._user_gas_msg(pressed)) - self.assertEqual(bool(pressed), self.safety.get_gas_pressed_prev()) - - def test_allow_engage_with_gas_pressed(self): - self._rx(self._user_gas_msg(1)) - self.safety.set_controls_allowed(True) - self._rx(self._user_gas_msg(1)) - self.assertTrue(self.safety.get_controls_allowed()) - self._rx(self._user_gas_msg(1)) - self.assertTrue(self.safety.get_controls_allowed()) - - def test_disengage_on_gas(self): - self._rx(self._user_gas_msg(0)) - self.safety.set_controls_allowed(True) - self._rx(self._user_gas_msg(self.GAS_PRESSED_THRESHOLD + 1)) - self.assertFalse(self.safety.get_controls_allowed()) - - def test_alternative_experience_no_disengage_on_gas(self): - self._rx(self._user_gas_msg(0)) - self.safety.set_controls_allowed(True) - self.safety.set_alternative_experience(ALTERNATIVE_EXPERIENCE.DISABLE_DISENGAGE_ON_GAS) - self._rx(self._user_gas_msg(self.GAS_PRESSED_THRESHOLD + 1)) - # Test we allow lateral, but not longitudinal - self.assertTrue(self.safety.get_controls_allowed()) - self.assertFalse(self.safety.get_longitudinal_allowed()) - # Make sure we can re-gain longitudinal actuation - self._rx(self._user_gas_msg(0)) - self.assertTrue(self.safety.get_longitudinal_allowed()) - - def test_prev_user_brake(self, _user_brake_msg=None, get_brake_pressed_prev=None): - if _user_brake_msg is None: - _user_brake_msg = self._user_brake_msg - get_brake_pressed_prev = self.safety.get_brake_pressed_prev - - self.assertFalse(get_brake_pressed_prev()) - for pressed in [True, False]: - self._rx(_user_brake_msg(not pressed)) - self.assertEqual(not pressed, get_brake_pressed_prev()) - self._rx(_user_brake_msg(pressed)) - self.assertEqual(pressed, get_brake_pressed_prev()) - - def test_enable_control_allowed_from_cruise(self): - self._rx(self._pcm_status_msg(False)) - self.assertFalse(self.safety.get_controls_allowed()) - self._rx(self._pcm_status_msg(True)) - self.assertTrue(self.safety.get_controls_allowed()) - - def test_disable_control_allowed_from_cruise(self): - self.safety.set_controls_allowed(1) - self._rx(self._pcm_status_msg(False)) - self.assertFalse(self.safety.get_controls_allowed()) - - def test_cruise_engaged_prev(self): - for engaged in [True, False]: - self._rx(self._pcm_status_msg(engaged)) - self.assertEqual(engaged, self.safety.get_cruise_engaged_prev()) - self._rx(self._pcm_status_msg(not engaged)) - self.assertEqual(not engaged, self.safety.get_cruise_engaged_prev()) - - def test_allow_user_brake_at_zero_speed(self, _user_brake_msg=None, get_brake_pressed_prev=None): - if _user_brake_msg is None: - _user_brake_msg = self._user_brake_msg - - # Brake was already pressed - self._rx(self._vehicle_moving_msg(0)) - self._rx(_user_brake_msg(1)) - self.safety.set_controls_allowed(1) - self._rx(_user_brake_msg(1)) - self.assertTrue(self.safety.get_controls_allowed()) - self.assertTrue(self.safety.get_longitudinal_allowed()) - self._rx(_user_brake_msg(0)) - self.assertTrue(self.safety.get_controls_allowed()) - self.assertTrue(self.safety.get_longitudinal_allowed()) - # rising edge of brake should disengage - self._rx(_user_brake_msg(1)) - self.assertFalse(self.safety.get_controls_allowed()) - self.assertFalse(self.safety.get_longitudinal_allowed()) - self._rx(_user_brake_msg(0)) # reset no brakes - - def test_not_allow_user_brake_when_moving(self, _user_brake_msg=None, get_brake_pressed_prev=None): - if _user_brake_msg is None: - _user_brake_msg = self._user_brake_msg - - # Brake was already pressed - self._rx(_user_brake_msg(1)) - self.safety.set_controls_allowed(1) - self._rx(self._vehicle_moving_msg(self.STANDSTILL_THRESHOLD)) - self._rx(_user_brake_msg(1)) - self.assertTrue(self.safety.get_controls_allowed()) - self.assertTrue(self.safety.get_longitudinal_allowed()) - self._rx(self._vehicle_moving_msg(self.STANDSTILL_THRESHOLD + 1)) - self._rx(_user_brake_msg(1)) - self.assertFalse(self.safety.get_controls_allowed()) - self.assertFalse(self.safety.get_longitudinal_allowed()) - self._rx(self._vehicle_moving_msg(0)) - - def test_vehicle_moving(self): - self.assertFalse(self.safety.get_vehicle_moving()) - - # not moving - self._rx(self._vehicle_moving_msg(0)) - self.assertFalse(self.safety.get_vehicle_moving()) - - # speed is at threshold - self._rx(self._vehicle_moving_msg(self.STANDSTILL_THRESHOLD)) - self.assertFalse(self.safety.get_vehicle_moving()) - - # past threshold - self._rx(self._vehicle_moving_msg(self.STANDSTILL_THRESHOLD + 1)) - self.assertTrue(self.safety.get_vehicle_moving()) - - def test_safety_tick(self): - self.safety.set_timer(int(2e6)) - self.safety.set_controls_allowed(True) - self.safety.safety_tick_current_safety_config() - self.assertFalse(self.safety.get_controls_allowed()) - self.assertFalse(self.safety.safety_config_valid()) diff --git a/panda/tests/safety/hyundai_common.py b/panda/tests/safety/hyundai_common.py deleted file mode 100644 index da18671..0000000 --- a/panda/tests/safety/hyundai_common.py +++ /dev/null @@ -1,157 +0,0 @@ -import unittest - -import panda.tests.safety.common as common -from panda.tests.libpanda import libpanda_py -from panda.tests.safety.common import make_msg - - -class Buttons: - NONE = 0 - RESUME = 1 - SET = 2 - CANCEL = 4 - - -PREV_BUTTON_SAMPLES = 8 -ENABLE_BUTTONS = (Buttons.RESUME, Buttons.SET, Buttons.CANCEL) - - -class HyundaiButtonBase: - # pylint: disable=no-member,abstract-method - BUTTONS_TX_BUS = 0 # tx on this bus, rx on 0 - SCC_BUS = 0 # rx on this bus - - def test_button_sends(self): - """ - Only RES and CANCEL buttons are allowed - - RES allowed while controls allowed - - CANCEL allowed while cruise is enabled - """ - self.safety.set_controls_allowed(0) - self.assertFalse(self._tx(self._button_msg(Buttons.RESUME, bus=self.BUTTONS_TX_BUS))) - self.assertFalse(self._tx(self._button_msg(Buttons.SET, bus=self.BUTTONS_TX_BUS))) - - self.safety.set_controls_allowed(1) - self.assertTrue(self._tx(self._button_msg(Buttons.RESUME, bus=self.BUTTONS_TX_BUS))) - self.assertFalse(self._tx(self._button_msg(Buttons.SET, bus=self.BUTTONS_TX_BUS))) - - for enabled in (True, False): - self._rx(self._pcm_status_msg(enabled)) - self.assertEqual(enabled, self._tx(self._button_msg(Buttons.CANCEL, bus=self.BUTTONS_TX_BUS))) - - def test_enable_control_allowed_from_cruise(self): - """ - Hyundai non-longitudinal only enables on PCM rising edge and recent button press. Tests PCM enabling with: - - disallowed: No buttons - - disallowed: Buttons that don't enable cruise - - allowed: Buttons that do enable cruise - - allowed: Main button with all above combinations - """ - for main_button in (0, 1): - for btn in range(8): - for _ in range(PREV_BUTTON_SAMPLES): # reset - self._rx(self._button_msg(Buttons.NONE)) - - self._rx(self._pcm_status_msg(False)) - self.assertFalse(self.safety.get_controls_allowed()) - self._rx(self._button_msg(btn, main_button=main_button)) - self._rx(self._pcm_status_msg(True)) - controls_allowed = btn in ENABLE_BUTTONS or main_button - self.assertEqual(controls_allowed, self.safety.get_controls_allowed()) - - def test_sampling_cruise_buttons(self): - """ - Test that we allow controls on recent button press, but not as button leaves sliding window - """ - self._rx(self._button_msg(Buttons.SET)) - for i in range(2 * PREV_BUTTON_SAMPLES): - self._rx(self._pcm_status_msg(False)) - self.assertFalse(self.safety.get_controls_allowed()) - self._rx(self._pcm_status_msg(True)) - controls_allowed = i < PREV_BUTTON_SAMPLES - self.assertEqual(controls_allowed, self.safety.get_controls_allowed()) - self._rx(self._button_msg(Buttons.NONE)) - - -class HyundaiLongitudinalBase(common.LongitudinalAccelSafetyTest): - # pylint: disable=no-member,abstract-method - - DISABLED_ECU_UDS_MSG: tuple[int, int] - DISABLED_ECU_ACTUATION_MSG: tuple[int, int] - - @classmethod - def setUpClass(cls): - if cls.__name__ == "HyundaiLongitudinalBase": - cls.safety = None - raise unittest.SkipTest - - # override these tests from PandaCarSafetyTest, hyundai longitudinal uses button enable - def test_disable_control_allowed_from_cruise(self): - pass - - def test_enable_control_allowed_from_cruise(self): - pass - - def test_sampling_cruise_buttons(self): - pass - - def test_cruise_engaged_prev(self): - pass - - def test_button_sends(self): - pass - - def _pcm_status_msg(self, enable): - raise Exception - - def _accel_msg(self, accel, aeb_req=False, aeb_decel=0): - raise NotImplementedError - - def test_set_resume_buttons(self): - """ - SET and RESUME enter controls allowed on their falling edge. - """ - for btn_prev in range(8): - for btn_cur in range(8): - self._rx(self._button_msg(Buttons.NONE)) - self.safety.set_controls_allowed(0) - for _ in range(10): - self._rx(self._button_msg(btn_prev)) - self.assertFalse(self.safety.get_controls_allowed()) - - # should enter controls allowed on falling edge and not transitioning to cancel - should_enable = btn_cur != btn_prev and \ - btn_cur != Buttons.CANCEL and \ - btn_prev in (Buttons.RESUME, Buttons.SET) - - self._rx(self._button_msg(btn_cur)) - self.assertEqual(should_enable, self.safety.get_controls_allowed()) - - def test_cancel_button(self): - self.safety.set_controls_allowed(1) - self._rx(self._button_msg(Buttons.CANCEL)) - self.assertFalse(self.safety.get_controls_allowed()) - - def test_tester_present_allowed(self): - """ - Ensure tester present diagnostic message is allowed to keep ECU knocked out - for longitudinal control. - """ - - addr, bus = self.DISABLED_ECU_UDS_MSG - tester_present = libpanda_py.make_CANPacket(addr, bus, b"\x02\x3E\x80\x00\x00\x00\x00\x00") - self.assertTrue(self._tx(tester_present)) - - not_tester_present = libpanda_py.make_CANPacket(addr, bus, b"\x03\xAA\xAA\x00\x00\x00\x00\x00") - self.assertFalse(self._tx(not_tester_present)) - - def test_disabled_ecu_alive(self): - """ - If the ECU knockout failed, make sure the relay malfunction is shown - """ - - addr, bus = self.DISABLED_ECU_ACTUATION_MSG - self.assertFalse(self.safety.get_relay_malfunction()) - self._rx(make_msg(bus, addr, 8)) - self.assertTrue(self.safety.get_relay_malfunction()) - diff --git a/panda/tests/safety/test.sh b/panda/tests/safety/test.sh deleted file mode 100644 index 13703b2..0000000 --- a/panda/tests/safety/test.sh +++ /dev/null @@ -1,34 +0,0 @@ -#!/usr/bin/env bash -set -e - -DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" -cd $DIR - -# reset coverage data and generate gcc note file -rm -f ../libpanda/*.gcda -scons -j$(nproc) -D --coverage - -# run safety tests and generate coverage data -HW_TYPES=( 6 9 ) -for hw_type in "${HW_TYPES[@]}"; do - echo "Testing HW_TYPE: $hw_type" - HW_TYPE=$hw_type pytest test_*.py -done - -# generate and open report -if [ "$1" == "--report" ]; then - geninfo ../libpanda/ -o coverage.info - genhtml coverage.info -o coverage-out - sensible-browser coverage-out/index.html -fi - -# test coverage -GCOV_OUTPUT=$(gcov -n ../libpanda/panda.c) -INCOMPLETE_COVERAGE=$(echo "$GCOV_OUTPUT" | paste -s -d' \n' | grep -E "File.*(safety\/safety_.*)|(safety)\.h" | grep -v "100.00%" || true) -if [ -n "$INCOMPLETE_COVERAGE" ]; then - echo "FAILED: Some files have less than 100% coverage:" - echo "$INCOMPLETE_COVERAGE" - exit 1 -else - echo "SUCCESS: All checked files have 100% coverage!" -fi diff --git a/panda/tests/safety/test_body.py b/panda/tests/safety/test_body.py deleted file mode 100644 index d23c09f..0000000 --- a/panda/tests/safety/test_body.py +++ /dev/null @@ -1,70 +0,0 @@ -#!/usr/bin/env python3 -import unittest - -import panda.tests.safety.common as common - -from panda import Panda -from panda.tests.libpanda import libpanda_py -from panda.tests.safety.common import CANPackerPanda - - -class TestBody(common.PandaSafetyTest): - TX_MSGS = [[0x250, 0], [0x251, 0], [0x350, 0], [0x351, 0], - [0x1, 0], [0x1, 1], [0x1, 2], [0x1, 3]] - - def setUp(self): - self.packer = CANPackerPanda("comma_body") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_BODY, 0) - self.safety.init_tests() - - def _motors_data_msg(self, speed_l, speed_r): - values = {"SPEED_L": speed_l, "SPEED_R": speed_r} - return self.packer.make_can_msg_panda("MOTORS_DATA", 0, values) - - def _torque_cmd_msg(self, torque_l, torque_r): - values = {"TORQUE_L": torque_l, "TORQUE_R": torque_r} - return self.packer.make_can_msg_panda("TORQUE_CMD", 0, values) - - def _knee_torque_cmd_msg(self, torque_l, torque_r): - values = {"TORQUE_L": torque_l, "TORQUE_R": torque_r} - return self.packer.make_can_msg_panda("KNEE_TORQUE_CMD", 0, values) - - def _max_motor_rpm_cmd_msg(self, max_rpm_l, max_rpm_r): - values = {"MAX_RPM_L": max_rpm_l, "MAX_RPM_R": max_rpm_r} - return self.packer.make_can_msg_panda("MAX_MOTOR_RPM_CMD", 0, values) - - def test_rx_hook(self): - self.assertFalse(self.safety.get_controls_allowed()) - self.assertFalse(self.safety.get_vehicle_moving()) - - # controls allowed when we get MOTORS_DATA message - self.assertTrue(self._rx(self._torque_cmd_msg(0, 0))) - self.assertTrue(self.safety.get_vehicle_moving()) # always moving - self.assertFalse(self.safety.get_controls_allowed()) - - self.assertTrue(self._rx(self._motors_data_msg(0, 0))) - self.assertTrue(self.safety.get_vehicle_moving()) # always moving - self.assertTrue(self.safety.get_controls_allowed()) - - def test_tx_hook(self): - self.assertFalse(self._tx(self._torque_cmd_msg(0, 0))) - self.assertFalse(self._tx(self._knee_torque_cmd_msg(0, 0))) - self.safety.set_controls_allowed(True) - self.assertTrue(self._tx(self._torque_cmd_msg(0, 0))) - self.assertTrue(self._tx(self._knee_torque_cmd_msg(0, 0))) - - def test_can_flasher(self): - # CAN flasher always allowed - self.safety.set_controls_allowed(False) - self.assertTrue(self._tx(common.make_msg(0, 0x1, 8))) - - # 0xdeadfaceU enters CAN flashing mode for base & knee - for addr in (0x250, 0x350): - self.assertTrue(self._tx(common.make_msg(0, addr, dat=b'\xce\xfa\xad\xde\x1e\x0b\xb0\x0a'))) - self.assertFalse(self._tx(common.make_msg(0, addr, dat=b'\xce\xfa\xad\xde\x1e\x0b\xb0'))) # not correct data/len - self.assertFalse(self._tx(common.make_msg(0, addr + 1, dat=b'\xce\xfa\xad\xde\x1e\x0b\xb0\x0a'))) # wrong address - - -if __name__ == "__main__": - unittest.main() diff --git a/panda/tests/safety/test_chrysler.py b/panda/tests/safety/test_chrysler.py deleted file mode 100644 index 5bbb6dd..0000000 --- a/panda/tests/safety/test_chrysler.py +++ /dev/null @@ -1,125 +0,0 @@ -#!/usr/bin/env python3 -import unittest -from panda import Panda -from panda.tests.libpanda import libpanda_py -import panda.tests.safety.common as common -from panda.tests.safety.common import CANPackerPanda - - -class TestChryslerSafety(common.PandaCarSafetyTest, common.MotorTorqueSteeringSafetyTest): - TX_MSGS = [[0x23B, 0], [0x292, 0], [0x2A6, 0]] - STANDSTILL_THRESHOLD = 0 - RELAY_MALFUNCTION_ADDRS = {0: (0x292,)} - FWD_BLACKLISTED_ADDRS = {2: [0x292, 0x2A6]} - FWD_BUS_LOOKUP = {0: 2, 2: 0} - - MAX_RATE_UP = 3 - MAX_RATE_DOWN = 3 - MAX_TORQUE = 261 - MAX_RT_DELTA = 112 - RT_INTERVAL = 250000 - MAX_TORQUE_ERROR = 80 - - LKAS_ACTIVE_VALUE = 1 - - DAS_BUS = 0 - - def setUp(self): - self.packer = CANPackerPanda("chrysler_pacifica_2017_hybrid_generated") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_CHRYSLER, 0) - self.safety.init_tests() - - def _button_msg(self, cancel=False, resume=False): - values = {"ACC_Cancel": cancel, "ACC_Resume": resume} - return self.packer.make_can_msg_panda("CRUISE_BUTTONS", self.DAS_BUS, values) - - def _pcm_status_msg(self, enable): - values = {"ACC_ACTIVE": enable} - return self.packer.make_can_msg_panda("DAS_3", self.DAS_BUS, values) - - def _speed_msg(self, speed): - values = {"SPEED_LEFT": speed, "SPEED_RIGHT": speed} - return self.packer.make_can_msg_panda("SPEED_1", 0, values) - - def _user_gas_msg(self, gas): - values = {"Accelerator_Position": gas} - return self.packer.make_can_msg_panda("ECM_5", 0, values) - - def _user_brake_msg(self, brake): - values = {"Brake_Pedal_State": 1 if brake else 0} - return self.packer.make_can_msg_panda("ESP_1", 0, values) - - def _torque_meas_msg(self, torque): - values = {"EPS_TORQUE_MOTOR": torque} - return self.packer.make_can_msg_panda("EPS_2", 0, values) - - def _torque_cmd_msg(self, torque, steer_req=1): - values = {"STEERING_TORQUE": torque, "LKAS_CONTROL_BIT": self.LKAS_ACTIVE_VALUE if steer_req else 0} - return self.packer.make_can_msg_panda("LKAS_COMMAND", 0, values) - - def test_buttons(self): - for controls_allowed in (True, False): - self.safety.set_controls_allowed(controls_allowed) - - # resume only while controls allowed - self.assertEqual(controls_allowed, self._tx(self._button_msg(resume=True))) - - # can always cancel - self.assertTrue(self._tx(self._button_msg(cancel=True))) - - # only one button at a time - self.assertFalse(self._tx(self._button_msg(cancel=True, resume=True))) - self.assertFalse(self._tx(self._button_msg(cancel=False, resume=False))) - - -class TestChryslerRamDTSafety(TestChryslerSafety): - TX_MSGS = [[0xB1, 2], [0xA6, 0], [0xFA, 0]] - RELAY_MALFUNCTION_ADDRS = {0: (0xA6,)} - FWD_BLACKLISTED_ADDRS = {2: [0xA6, 0xFA]} - - MAX_RATE_UP = 6 - MAX_RATE_DOWN = 6 - MAX_TORQUE = 350 - - DAS_BUS = 2 - - LKAS_ACTIVE_VALUE = 2 - - def setUp(self): - self.packer = CANPackerPanda("chrysler_ram_dt_generated") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_CHRYSLER, Panda.FLAG_CHRYSLER_RAM_DT) - self.safety.init_tests() - - def _speed_msg(self, speed): - values = {"Vehicle_Speed": speed} - return self.packer.make_can_msg_panda("ESP_8", 0, values) - -class TestChryslerRamHDSafety(TestChryslerSafety): - TX_MSGS = [[0x275, 0], [0x276, 0], [0x23A, 2]] - RELAY_MALFUNCTION_ADDRS = {0: (0x276,)} - FWD_BLACKLISTED_ADDRS = {2: [0x275, 0x276]} - - MAX_TORQUE = 361 - MAX_RATE_UP = 14 - MAX_RATE_DOWN = 14 - MAX_RT_DELTA = 182 - - DAS_BUS = 2 - - LKAS_ACTIVE_VALUE = 2 - - def setUp(self): - self.packer = CANPackerPanda("chrysler_ram_hd_generated") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_CHRYSLER, Panda.FLAG_CHRYSLER_RAM_HD) - self.safety.init_tests() - - def _speed_msg(self, speed): - values = {"Vehicle_Speed": speed} - return self.packer.make_can_msg_panda("ESP_8", 0, values) - - -if __name__ == "__main__": - unittest.main() diff --git a/panda/tests/safety/test_defaults.py b/panda/tests/safety/test_defaults.py deleted file mode 100644 index 81bafee..0000000 --- a/panda/tests/safety/test_defaults.py +++ /dev/null @@ -1,73 +0,0 @@ -#!/usr/bin/env python3 -import unittest - -import panda.tests.safety.common as common - -from panda import Panda -from panda.tests.libpanda import libpanda_py - - -class TestDefaultRxHookBase(common.PandaSafetyTest): - def test_rx_hook(self): - # default rx hook allows all msgs - for bus in range(4): - for addr in self.SCANNED_ADDRS: - self.assertTrue(self._rx(common.make_msg(bus, addr, 8)), f"failed RX {addr=}") - - -class TestNoOutput(TestDefaultRxHookBase): - TX_MSGS = [] - - def setUp(self): - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_NOOUTPUT, 0) - self.safety.init_tests() - - -class TestSilent(TestNoOutput): - """SILENT uses same hooks as NOOUTPUT""" - - def setUp(self): - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_SILENT, 0) - self.safety.init_tests() - - -class TestAllOutput(TestDefaultRxHookBase): - # Allow all messages - TX_MSGS = [[addr, bus] for addr in common.PandaSafetyTest.SCANNED_ADDRS - for bus in range(4)] - - def setUp(self): - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_ALLOUTPUT, 0) - self.safety.init_tests() - - def test_spam_can_buses(self): - # asserts tx allowed for all scanned addrs - for bus in range(4): - for addr in self.SCANNED_ADDRS: - should_tx = [addr, bus] in self.TX_MSGS - self.assertEqual(should_tx, self._tx(common.make_msg(bus, addr, 8)), f"allowed TX {addr=} {bus=}") - - def test_default_controls_not_allowed(self): - # controls always allowed - self.assertTrue(self.safety.get_controls_allowed()) - - def test_tx_hook_on_wrong_safety_mode(self): - # No point, since we allow all messages - pass - - -class TestAllOutputPassthrough(TestAllOutput): - FWD_BLACKLISTED_ADDRS = {} - FWD_BUS_LOOKUP = {0: 2, 2: 0} - - def setUp(self): - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_ALLOUTPUT, 1) - self.safety.init_tests() - - -if __name__ == "__main__": - unittest.main() diff --git a/panda/tests/safety/test_elm327.py b/panda/tests/safety/test_elm327.py deleted file mode 100644 index f133b2e..0000000 --- a/panda/tests/safety/test_elm327.py +++ /dev/null @@ -1,48 +0,0 @@ -#!/usr/bin/env python3 -import unittest - -import panda.tests.safety.common as common - -from panda import DLC_TO_LEN, Panda -from panda.tests.libpanda import libpanda_py -from panda.tests.safety.test_defaults import TestDefaultRxHookBase - -GM_CAMERA_DIAG_ADDR = 0x24B - - -class TestElm327(TestDefaultRxHookBase): - TX_MSGS = [[addr, bus] for addr in [GM_CAMERA_DIAG_ADDR, *range(0x600, 0x800), - *range(0x18DA00F1, 0x18DB00F1, 0x100), # 29-bit UDS physical addressing - *[0x18DB33F1], # 29-bit UDS functional address - ] for bus in range(4)] - - def setUp(self): - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_ELM327, 0) - self.safety.init_tests() - - def test_tx_hook(self): - # ensure we can transmit arbitrary data on allowed addresses - for bus in range(4): - for addr in self.SCANNED_ADDRS: - should_tx = [addr, bus] in self.TX_MSGS - self.assertEqual(should_tx, self._tx(common.make_msg(bus, addr, 8))) - - # ELM only allows 8 byte UDS/KWP messages under ISO 15765-4 - for msg_len in DLC_TO_LEN: - should_tx = msg_len == 8 - self.assertEqual(should_tx, self._tx(common.make_msg(0, 0x700, msg_len))) - - # TODO: perform this check for all addresses - # 4 to 15 are reserved ISO-TP frame types (https://en.wikipedia.org/wiki/ISO_15765-2) - for byte in range(0xff): - should_tx = (byte >> 4) <= 3 - self.assertEqual(should_tx, self._tx(common.make_msg(0, GM_CAMERA_DIAG_ADDR, dat=bytes([byte] * 8)))) - - def test_tx_hook_on_wrong_safety_mode(self): - # No point, since we allow many diagnostic addresses - pass - - -if __name__ == "__main__": - unittest.main() diff --git a/panda/tests/safety/test_ford.py b/panda/tests/safety/test_ford.py deleted file mode 100644 index 1be3a27..0000000 --- a/panda/tests/safety/test_ford.py +++ /dev/null @@ -1,476 +0,0 @@ -#!/usr/bin/env python3 -import numpy as np -import random -import unittest - -import panda.tests.safety.common as common - -from panda import Panda -from panda.tests.libpanda import libpanda_py -from panda.tests.safety.common import CANPackerPanda - -MSG_EngBrakeData = 0x165 # RX from PCM, for driver brake pedal and cruise state -MSG_EngVehicleSpThrottle = 0x204 # RX from PCM, for driver throttle input -MSG_BrakeSysFeatures = 0x415 # RX from ABS, for vehicle speed -MSG_EngVehicleSpThrottle2 = 0x202 # RX from PCM, for second vehicle speed -MSG_Yaw_Data_FD1 = 0x91 # RX from RCM, for yaw rate -MSG_Steering_Data_FD1 = 0x083 # TX by OP, various driver switches and LKAS/CC buttons -MSG_ACCDATA = 0x186 # TX by OP, ACC controls -MSG_ACCDATA_3 = 0x18A # TX by OP, ACC/TJA user interface -MSG_Lane_Assist_Data1 = 0x3CA # TX by OP, Lane Keep Assist -MSG_LateralMotionControl = 0x3D3 # TX by OP, Lateral Control message -MSG_LateralMotionControl2 = 0x3D6 # TX by OP, alternate Lateral Control message -MSG_IPMA_Data = 0x3D8 # TX by OP, IPMA and LKAS user interface - - -def checksum(msg): - addr, t, dat, bus = msg - ret = bytearray(dat) - - if addr == MSG_Yaw_Data_FD1: - chksum = dat[0] + dat[1] # VehRol_W_Actl - chksum += dat[2] + dat[3] # VehYaw_W_Actl - chksum += dat[5] # VehRollYaw_No_Cnt - chksum += dat[6] >> 6 # VehRolWActl_D_Qf - chksum += (dat[6] >> 4) & 0x3 # VehYawWActl_D_Qf - chksum = 0xff - (chksum & 0xff) - ret[4] = chksum - - elif addr == MSG_BrakeSysFeatures: - chksum = dat[0] + dat[1] # Veh_V_ActlBrk - chksum += (dat[2] >> 2) & 0xf # VehVActlBrk_No_Cnt - chksum += dat[2] >> 6 # VehVActlBrk_D_Qf - chksum = 0xff - (chksum & 0xff) - ret[3] = chksum - - elif addr == MSG_EngVehicleSpThrottle2: - chksum = (dat[2] >> 3) & 0xf # VehVActlEng_No_Cnt - chksum += (dat[4] >> 5) & 0x3 # VehVActlEng_D_Qf - chksum += dat[6] + dat[7] # Veh_V_ActlEng - chksum = 0xff - (chksum & 0xff) - ret[1] = chksum - - return addr, t, ret, bus - - -class Buttons: - CANCEL = 0 - RESUME = 1 - TJA_TOGGLE = 2 - - -# Ford safety has four different configurations tested here: -# * CAN with stock longitudinal -# * CAN with openpilot longitudinal -# * CAN FD with stock longitudinal -# * CAN FD with openpilot longitudinal - -class TestFordSafetyBase(common.PandaCarSafetyTest): - STANDSTILL_THRESHOLD = 1 - RELAY_MALFUNCTION_ADDRS = {0: (MSG_ACCDATA_3, MSG_Lane_Assist_Data1, MSG_LateralMotionControl, - MSG_LateralMotionControl2, MSG_IPMA_Data)} - - FWD_BLACKLISTED_ADDRS = {2: [MSG_ACCDATA_3, MSG_Lane_Assist_Data1, MSG_LateralMotionControl, - MSG_LateralMotionControl2, MSG_IPMA_Data]} - FWD_BUS_LOOKUP = {0: 2, 2: 0} - - # Max allowed delta between car speeds - MAX_SPEED_DELTA = 2.0 # m/s - - STEER_MESSAGE = 0 - - # Curvature control limits - DEG_TO_CAN = 50000 # 1 / (2e-5) rad to can - MAX_CURVATURE = 0.02 - MAX_CURVATURE_ERROR = 0.002 - CURVATURE_ERROR_MIN_SPEED = 10.0 # m/s - - ANGLE_RATE_BP = [5., 25., 25.] - ANGLE_RATE_UP = [0.0002, 0.0001, 0.0001] # windup limit - ANGLE_RATE_DOWN = [0.000225, 0.00015, 0.00015] # unwind limit - - cnt_speed = 0 - cnt_speed_2 = 0 - cnt_yaw_rate = 0 - - packer: CANPackerPanda - safety: libpanda_py.Panda - - @classmethod - def setUpClass(cls): - if cls.__name__ == "TestFordSafetyBase": - raise unittest.SkipTest - - def _set_prev_desired_angle(self, t): - t = round(t * self.DEG_TO_CAN) - self.safety.set_desired_angle_last(t) - - def _reset_curvature_measurement(self, curvature, speed): - for _ in range(6): - self._rx(self._speed_msg(speed)) - self._rx(self._yaw_rate_msg(curvature, speed)) - - # Driver brake pedal - def _user_brake_msg(self, brake: bool): - # brake pedal and cruise state share same message, so we have to send - # the other signal too - enable = self.safety.get_controls_allowed() - values = { - "BpedDrvAppl_D_Actl": 2 if brake else 1, - "CcStat_D_Actl": 5 if enable else 0, - } - return self.packer.make_can_msg_panda("EngBrakeData", 0, values) - - # ABS vehicle speed - def _speed_msg(self, speed: float, quality_flag=True): - values = {"Veh_V_ActlBrk": speed * 3.6, "VehVActlBrk_D_Qf": 3 if quality_flag else 0, "VehVActlBrk_No_Cnt": self.cnt_speed % 16} - self.__class__.cnt_speed += 1 - return self.packer.make_can_msg_panda("BrakeSysFeatures", 0, values, fix_checksum=checksum) - - # PCM vehicle speed - def _speed_msg_2(self, speed: float, quality_flag=True): - values = {"Veh_V_ActlEng": speed * 3.6, "VehVActlEng_D_Qf": 3 if quality_flag else 0, "VehVActlEng_No_Cnt": self.cnt_speed_2 % 16} - self.__class__.cnt_speed_2 += 1 - return self.packer.make_can_msg_panda("EngVehicleSpThrottle2", 0, values, fix_checksum=checksum) - - # Standstill state - def _vehicle_moving_msg(self, speed: float): - values = {"VehStop_D_Stat": 1 if speed <= self.STANDSTILL_THRESHOLD else random.choice((0, 2, 3))} - return self.packer.make_can_msg_panda("DesiredTorqBrk", 0, values) - - # Current curvature - def _yaw_rate_msg(self, curvature: float, speed: float, quality_flag=True): - values = {"VehYaw_W_Actl": curvature * speed, "VehYawWActl_D_Qf": 3 if quality_flag else 0, - "VehRollYaw_No_Cnt": self.cnt_yaw_rate % 256} - self.__class__.cnt_yaw_rate += 1 - return self.packer.make_can_msg_panda("Yaw_Data_FD1", 0, values, fix_checksum=checksum) - - # Drive throttle input - def _user_gas_msg(self, gas: float): - values = {"ApedPos_Pc_ActlArb": gas} - return self.packer.make_can_msg_panda("EngVehicleSpThrottle", 0, values) - - # Cruise status - def _pcm_status_msg(self, enable: bool): - # brake pedal and cruise state share same message, so we have to send - # the other signal too - brake = self.safety.get_brake_pressed_prev() - values = { - "BpedDrvAppl_D_Actl": 2 if brake else 1, - "CcStat_D_Actl": 5 if enable else 0, - } - return self.packer.make_can_msg_panda("EngBrakeData", 0, values) - - # LKAS command - def _lkas_command_msg(self, action: int): - values = { - "LkaActvStats_D2_Req": action, - } - return self.packer.make_can_msg_panda("Lane_Assist_Data1", 0, values) - - # LCA command - def _lat_ctl_msg(self, enabled: bool, path_offset: float, path_angle: float, curvature: float, curvature_rate: float): - if self.STEER_MESSAGE == MSG_LateralMotionControl: - values = { - "LatCtl_D_Rq": 1 if enabled else 0, - "LatCtlPathOffst_L_Actl": path_offset, # Path offset [-5.12|5.11] meter - "LatCtlPath_An_Actl": path_angle, # Path angle [-0.5|0.5235] radians - "LatCtlCurv_NoRate_Actl": curvature_rate, # Curvature rate [-0.001024|0.00102375] 1/meter^2 - "LatCtlCurv_No_Actl": curvature, # Curvature [-0.02|0.02094] 1/meter - } - return self.packer.make_can_msg_panda("LateralMotionControl", 0, values) - elif self.STEER_MESSAGE == MSG_LateralMotionControl2: - values = { - "LatCtl_D2_Rq": 1 if enabled else 0, - "LatCtlPathOffst_L_Actl": path_offset, # Path offset [-5.12|5.11] meter - "LatCtlPath_An_Actl": path_angle, # Path angle [-0.5|0.5235] radians - "LatCtlCrv_NoRate2_Actl": curvature_rate, # Curvature rate [-0.001024|0.001023] 1/meter^2 - "LatCtlCurv_No_Actl": curvature, # Curvature [-0.02|0.02094] 1/meter - } - return self.packer.make_can_msg_panda("LateralMotionControl2", 0, values) - - # Cruise control buttons - def _acc_button_msg(self, button: int, bus: int): - values = { - "CcAslButtnCnclPress": 1 if button == Buttons.CANCEL else 0, - "CcAsllButtnResPress": 1 if button == Buttons.RESUME else 0, - "TjaButtnOnOffPress": 1 if button == Buttons.TJA_TOGGLE else 0, - } - return self.packer.make_can_msg_panda("Steering_Data_FD1", bus, values) - - def test_rx_hook(self): - # checksum, counter, and quality flag checks - for quality_flag in [True, False]: - for msg in ["speed", "speed_2", "yaw"]: - self.safety.set_controls_allowed(True) - # send multiple times to verify counter checks - for _ in range(10): - if msg == "speed": - to_push = self._speed_msg(0, quality_flag=quality_flag) - elif msg == "speed_2": - to_push = self._speed_msg_2(0, quality_flag=quality_flag) - elif msg == "yaw": - to_push = self._yaw_rate_msg(0, 0, quality_flag=quality_flag) - - self.assertEqual(quality_flag, self._rx(to_push)) - self.assertEqual(quality_flag, self.safety.get_controls_allowed()) - - # Mess with checksum to make it fail, checksum is not checked for 2nd speed - to_push[0].data[3] = 0 # Speed checksum & half of yaw signal - should_rx = msg == "speed_2" and quality_flag - self.assertEqual(should_rx, self._rx(to_push)) - self.assertEqual(should_rx, self.safety.get_controls_allowed()) - - def test_rx_hook_speed_mismatch(self): - # Ford relies on speed for driver curvature limiting, so it checks two sources - for speed in np.arange(0, 40, 0.5): - for speed_delta in np.arange(-5, 5, 0.1): - speed_2 = round(max(speed + speed_delta, 0), 1) - # Set controls allowed in between rx since first message can reset it - self._rx(self._speed_msg(speed)) - self.safety.set_controls_allowed(True) - self._rx(self._speed_msg_2(speed_2)) - - within_delta = abs(speed - speed_2) <= self.MAX_SPEED_DELTA - self.assertEqual(self.safety.get_controls_allowed(), within_delta) - - def test_angle_measurements(self): - """Tests rx hook correctly parses the curvature measurement from the vehicle speed and yaw rate""" - for speed in np.arange(0.5, 40, 0.5): - for curvature in np.arange(0, self.MAX_CURVATURE * 2, 2e-3): - self._rx(self._speed_msg(speed)) - for c in (curvature, -curvature, 0, 0, 0, 0): - self._rx(self._yaw_rate_msg(c, speed)) - - self.assertEqual(self.safety.get_angle_meas_min(), round(-curvature * self.DEG_TO_CAN)) - self.assertEqual(self.safety.get_angle_meas_max(), round(curvature * self.DEG_TO_CAN)) - - self._rx(self._yaw_rate_msg(0, speed)) - self.assertEqual(self.safety.get_angle_meas_min(), round(-curvature * self.DEG_TO_CAN)) - self.assertEqual(self.safety.get_angle_meas_max(), 0) - - self._rx(self._yaw_rate_msg(0, speed)) - self.assertEqual(self.safety.get_angle_meas_min(), 0) - self.assertEqual(self.safety.get_angle_meas_max(), 0) - - def test_steer_allowed(self): - path_offsets = np.arange(-5.12, 5.11, 1).round() - path_angles = np.arange(-0.5, 0.5235, 0.1).round(1) - curvature_rates = np.arange(-0.001024, 0.00102375, 0.001).round(3) - curvatures = np.arange(-0.02, 0.02094, 0.01).round(2) - - for speed in (self.CURVATURE_ERROR_MIN_SPEED - 1, - self.CURVATURE_ERROR_MIN_SPEED + 1): - for controls_allowed in (True, False): - for steer_control_enabled in (True, False): - for path_offset in path_offsets: - for path_angle in path_angles: - for curvature_rate in curvature_rates: - for curvature in curvatures: - self.safety.set_controls_allowed(controls_allowed) - self._set_prev_desired_angle(curvature) - self._reset_curvature_measurement(curvature, speed) - - should_tx = path_offset == 0 and path_angle == 0 and curvature_rate == 0 - # when request bit is 0, only allow curvature of 0 since the signal range - # is not large enough to enforce it tracking measured - should_tx = should_tx and (controls_allowed if steer_control_enabled else curvature == 0) - with self.subTest(controls_allowed=controls_allowed, steer_control_enabled=steer_control_enabled, - path_offset=path_offset, path_angle=path_angle, curvature_rate=curvature_rate, - curvature=curvature): - self.assertEqual(should_tx, self._tx(self._lat_ctl_msg(steer_control_enabled, path_offset, path_angle, curvature, curvature_rate))) - - def test_curvature_rate_limit_up(self): - """ - When the curvature error is exceeded, commanded curvature must start moving towards meas respecting rate limits. - Since panda allows higher rate limits to avoid false positives, we need to allow a lower rate to move towards meas. - """ - self.safety.set_controls_allowed(True) - small_curvature = 2 / self.DEG_TO_CAN # significant small amount of curvature to cross boundary - - for speed in np.arange(0, 40, 0.5): - limit_command = speed > self.CURVATURE_ERROR_MIN_SPEED - max_delta_up = np.interp(speed, self.ANGLE_RATE_BP, self.ANGLE_RATE_UP) - max_delta_up_lower = np.interp(speed + 1, self.ANGLE_RATE_BP, self.ANGLE_RATE_UP) - - cases = [ - (not limit_command, 0), - (not limit_command, max_delta_up_lower - small_curvature), - (True, max_delta_up_lower), - (True, max_delta_up), - (False, max_delta_up + small_curvature), - ] - - for sign in (-1, 1): - self._reset_curvature_measurement(sign * (self.MAX_CURVATURE_ERROR + 1e-3), speed) - for should_tx, curvature in cases: - self._set_prev_desired_angle(sign * small_curvature) - self.assertEqual(should_tx, self._tx(self._lat_ctl_msg(True, 0, 0, sign * (small_curvature + curvature), 0))) - - def test_curvature_rate_limit_down(self): - self.safety.set_controls_allowed(True) - small_curvature = 2 / self.DEG_TO_CAN # significant small amount of curvature to cross boundary - - for speed in np.arange(0, 40, 0.5): - limit_command = speed > self.CURVATURE_ERROR_MIN_SPEED - max_delta_down = np.interp(speed, self.ANGLE_RATE_BP, self.ANGLE_RATE_DOWN) - max_delta_down_lower = np.interp(speed + 1, self.ANGLE_RATE_BP, self.ANGLE_RATE_DOWN) - - cases = [ - (not limit_command, self.MAX_CURVATURE), - (not limit_command, self.MAX_CURVATURE - max_delta_down_lower + small_curvature), - (True, self.MAX_CURVATURE - max_delta_down_lower), - (True, self.MAX_CURVATURE - max_delta_down), - (False, self.MAX_CURVATURE - max_delta_down - small_curvature), - ] - - for sign in (-1, 1): - self._reset_curvature_measurement(sign * (self.MAX_CURVATURE - self.MAX_CURVATURE_ERROR - 1e-3), speed) - for should_tx, curvature in cases: - self._set_prev_desired_angle(sign * self.MAX_CURVATURE) - self.assertEqual(should_tx, self._tx(self._lat_ctl_msg(True, 0, 0, sign * curvature, 0))) - - def test_prevent_lkas_action(self): - self.safety.set_controls_allowed(1) - self.assertFalse(self._tx(self._lkas_command_msg(1))) - - self.safety.set_controls_allowed(0) - self.assertFalse(self._tx(self._lkas_command_msg(1))) - - def test_acc_buttons(self): - for allowed in (0, 1): - self.safety.set_controls_allowed(allowed) - for enabled in (True, False): - self._rx(self._pcm_status_msg(enabled)) - self.assertTrue(self._tx(self._acc_button_msg(Buttons.TJA_TOGGLE, 2))) - - for allowed in (0, 1): - self.safety.set_controls_allowed(allowed) - for bus in (0, 2): - self.assertEqual(allowed, self._tx(self._acc_button_msg(Buttons.RESUME, bus))) - - for enabled in (True, False): - self._rx(self._pcm_status_msg(enabled)) - for bus in (0, 2): - self.assertEqual(enabled, self._tx(self._acc_button_msg(Buttons.CANCEL, bus))) - - -class TestFordStockSafety(TestFordSafetyBase): - STEER_MESSAGE = MSG_LateralMotionControl - - TX_MSGS = [ - [MSG_Steering_Data_FD1, 0], [MSG_Steering_Data_FD1, 2], [MSG_ACCDATA_3, 0], [MSG_Lane_Assist_Data1, 0], - [MSG_LateralMotionControl, 0], [MSG_IPMA_Data, 0], - ] - - def setUp(self): - self.packer = CANPackerPanda("ford_lincoln_base_pt") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_FORD, 0) - self.safety.init_tests() - - -class TestFordCANFDStockSafety(TestFordSafetyBase): - STEER_MESSAGE = MSG_LateralMotionControl2 - - TX_MSGS = [ - [MSG_Steering_Data_FD1, 0], [MSG_Steering_Data_FD1, 2], [MSG_ACCDATA_3, 0], [MSG_Lane_Assist_Data1, 0], - [MSG_LateralMotionControl2, 0], [MSG_IPMA_Data, 0], - ] - - def setUp(self): - self.packer = CANPackerPanda("ford_lincoln_base_pt") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_FORD, Panda.FLAG_FORD_CANFD) - self.safety.init_tests() - - -class TestFordLongitudinalSafetyBase(TestFordSafetyBase): - RELAY_MALFUNCTION_ADDRS = {0: (MSG_ACCDATA, MSG_ACCDATA_3, MSG_Lane_Assist_Data1, MSG_LateralMotionControl, - MSG_LateralMotionControl2, MSG_IPMA_Data)} - - FWD_BLACKLISTED_ADDRS = {2: [MSG_ACCDATA, MSG_ACCDATA_3, MSG_Lane_Assist_Data1, MSG_LateralMotionControl, - MSG_LateralMotionControl2, MSG_IPMA_Data]} - - MAX_ACCEL = 2.0 # accel is used for brakes, but openpilot can set positive values - MIN_ACCEL = -3.5 - INACTIVE_ACCEL = 0.0 - - MAX_GAS = 2.0 - MIN_GAS = -0.5 - INACTIVE_GAS = -5.0 - - @classmethod - def setUpClass(cls): - if cls.__name__ == "TestFordLongitudinalSafetyBase": - raise unittest.SkipTest - - # ACC command - def _acc_command_msg(self, gas: float, brake: float, cmbb_deny: bool = False): - values = { - "AccPrpl_A_Rq": gas, # [-5|5.23] m/s^2 - "AccPrpl_A_Pred": gas, # [-5|5.23] m/s^2 - "AccBrkTot_A_Rq": brake, # [-20|11.9449] m/s^2 - "CmbbDeny_B_Actl": 1 if cmbb_deny else 0, # [0|1] deny AEB actuation - } - return self.packer.make_can_msg_panda("ACCDATA", 0, values) - - def test_stock_aeb(self): - # Test that CmbbDeny_B_Actl is never 1, it prevents the ABS module from actuating AEB requests from ACCDATA_2 - for controls_allowed in (True, False): - self.safety.set_controls_allowed(controls_allowed) - for cmbb_deny in (True, False): - should_tx = not cmbb_deny - self.assertEqual(should_tx, self._tx(self._acc_command_msg(self.INACTIVE_GAS, self.INACTIVE_ACCEL, cmbb_deny))) - should_tx = controls_allowed and not cmbb_deny - self.assertEqual(should_tx, self._tx(self._acc_command_msg(self.MAX_GAS, self.MAX_ACCEL, cmbb_deny))) - - def test_gas_safety_check(self): - for controls_allowed in (True, False): - self.safety.set_controls_allowed(controls_allowed) - for gas in np.concatenate((np.arange(self.MIN_GAS - 2, self.MAX_GAS + 2, 0.05), [self.INACTIVE_GAS])): - gas = round(gas, 2) # floats might not hit exact boundary conditions without rounding - should_tx = (controls_allowed and self.MIN_GAS <= gas <= self.MAX_GAS) or gas == self.INACTIVE_GAS - self.assertEqual(should_tx, self._tx(self._acc_command_msg(gas, self.INACTIVE_ACCEL))) - - def test_brake_safety_check(self): - for controls_allowed in (True, False): - self.safety.set_controls_allowed(controls_allowed) - for brake in np.arange(self.MIN_ACCEL - 2, self.MAX_ACCEL + 2, 0.05): - brake = round(brake, 2) # floats might not hit exact boundary conditions without rounding - should_tx = (controls_allowed and self.MIN_ACCEL <= brake <= self.MAX_ACCEL) or brake == self.INACTIVE_ACCEL - self.assertEqual(should_tx, self._tx(self._acc_command_msg(self.INACTIVE_GAS, brake))) - - -class TestFordLongitudinalSafety(TestFordLongitudinalSafetyBase): - STEER_MESSAGE = MSG_LateralMotionControl - - TX_MSGS = [ - [MSG_Steering_Data_FD1, 0], [MSG_Steering_Data_FD1, 2], [MSG_ACCDATA, 0], [MSG_ACCDATA_3, 0], [MSG_Lane_Assist_Data1, 0], - [MSG_LateralMotionControl, 0], [MSG_IPMA_Data, 0], - ] - - def setUp(self): - self.packer = CANPackerPanda("ford_lincoln_base_pt") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_FORD, Panda.FLAG_FORD_LONG_CONTROL) - self.safety.init_tests() - - -class TestFordCANFDLongitudinalSafety(TestFordLongitudinalSafetyBase): - STEER_MESSAGE = MSG_LateralMotionControl2 - - TX_MSGS = [ - [MSG_Steering_Data_FD1, 0], [MSG_Steering_Data_FD1, 2], [MSG_ACCDATA, 0], [MSG_ACCDATA_3, 0], [MSG_Lane_Assist_Data1, 0], - [MSG_LateralMotionControl2, 0], [MSG_IPMA_Data, 0], - ] - - def setUp(self): - self.packer = CANPackerPanda("ford_lincoln_base_pt") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_FORD, Panda.FLAG_FORD_LONG_CONTROL | Panda.FLAG_FORD_CANFD) - self.safety.init_tests() - - -if __name__ == "__main__": - unittest.main() diff --git a/panda/tests/safety/test_gm.py b/panda/tests/safety/test_gm.py deleted file mode 100644 index 28b2ad5..0000000 --- a/panda/tests/safety/test_gm.py +++ /dev/null @@ -1,228 +0,0 @@ -#!/usr/bin/env python3 -import unittest -from panda import Panda -from panda.tests.libpanda import libpanda_py -import panda.tests.safety.common as common -from panda.tests.safety.common import CANPackerPanda - - -class Buttons: - UNPRESS = 1 - RES_ACCEL = 2 - DECEL_SET = 3 - CANCEL = 6 - - -class GmLongitudinalBase(common.PandaCarSafetyTest, common.LongitudinalGasBrakeSafetyTest): - # pylint: disable=no-member,abstract-method - - RELAY_MALFUNCTION_ADDRS = {0: (0x180, 0x2CB)} # ASCMLKASteeringCmd, ASCMGasRegenCmd - - MAX_POSSIBLE_BRAKE = 2 ** 12 - MAX_BRAKE = 400 - - MAX_POSSIBLE_GAS = 2 ** 12 - - PCM_CRUISE = False # openpilot can control the PCM state if longitudinal - - def _send_brake_msg(self, brake): - values = {"FrictionBrakeCmd": -brake} - return self.packer_chassis.make_can_msg_panda("EBCMFrictionBrakeCmd", self.BRAKE_BUS, values) - - def _send_gas_msg(self, gas): - values = {"GasRegenCmd": gas} - return self.packer.make_can_msg_panda("ASCMGasRegenCmd", 0, values) - - # override these tests from PandaCarSafetyTest, GM longitudinal uses button enable - def _pcm_status_msg(self, enable): - raise NotImplementedError - - def test_disable_control_allowed_from_cruise(self): - pass - - def test_enable_control_allowed_from_cruise(self): - pass - - def test_cruise_engaged_prev(self): - pass - - def test_set_resume_buttons(self): - """ - SET and RESUME enter controls allowed on their falling and rising edges, respectively. - """ - for btn_prev in range(8): - for btn_cur in range(8): - with self.subTest(btn_prev=btn_prev, btn_cur=btn_cur): - self._rx(self._button_msg(btn_prev)) - self.safety.set_controls_allowed(0) - for _ in range(10): - self._rx(self._button_msg(btn_cur)) - - should_enable = btn_cur != Buttons.DECEL_SET and btn_prev == Buttons.DECEL_SET - should_enable = should_enable or (btn_cur == Buttons.RES_ACCEL and btn_prev != Buttons.RES_ACCEL) - should_enable = should_enable and btn_cur != Buttons.CANCEL - self.assertEqual(should_enable, self.safety.get_controls_allowed()) - - def test_cancel_button(self): - self.safety.set_controls_allowed(1) - self._rx(self._button_msg(Buttons.CANCEL)) - self.assertFalse(self.safety.get_controls_allowed()) - - -class TestGmSafetyBase(common.PandaCarSafetyTest, common.DriverTorqueSteeringSafetyTest): - STANDSTILL_THRESHOLD = 10 * 0.0311 - # Ensures ASCM is off on ASCM cars, and relay is not malfunctioning for camera-ACC cars - RELAY_MALFUNCTION_ADDRS = {0: (0x180,)} # ASCMLKASteeringCmd - BUTTONS_BUS = 0 # rx or tx - BRAKE_BUS = 0 # tx only - - MAX_RATE_UP = 10 - MAX_RATE_DOWN = 15 - MAX_TORQUE = 300 - MAX_RT_DELTA = 128 - RT_INTERVAL = 250000 - DRIVER_TORQUE_ALLOWANCE = 65 - DRIVER_TORQUE_FACTOR = 4 - - PCM_CRUISE = True # openpilot is tied to the PCM state if not longitudinal - - @classmethod - def setUpClass(cls): - if cls.__name__ == "TestGmSafetyBase": - cls.packer = None - cls.safety = None - raise unittest.SkipTest - - def setUp(self): - self.packer = CANPackerPanda("gm_global_a_powertrain_generated") - self.packer_chassis = CANPackerPanda("gm_global_a_chassis") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_GM, 0) - self.safety.init_tests() - - def _pcm_status_msg(self, enable): - if self.PCM_CRUISE: - values = {"CruiseState": enable} - return self.packer.make_can_msg_panda("AcceleratorPedal2", 0, values) - else: - raise NotImplementedError - - def _speed_msg(self, speed): - values = {"%sWheelSpd" % s: speed for s in ["RL", "RR"]} - return self.packer.make_can_msg_panda("EBCMWheelSpdRear", 0, values) - - def _user_brake_msg(self, brake): - # GM safety has a brake threshold of 8 - values = {"BrakePedalPos": 8 if brake else 0} - return self.packer.make_can_msg_panda("ECMAcceleratorPos", 0, values) - - def _user_regen_msg(self, regen): - values = {"RegenPaddle": 2 if regen else 0} - return self.packer.make_can_msg_panda("EBCMRegenPaddle", 0, values) - - def _user_gas_msg(self, gas): - values = {"AcceleratorPedal2": 1 if gas else 0} - if self.PCM_CRUISE: - # Fill CruiseState with expected value if the safety mode reads cruise state from gas msg - values["CruiseState"] = self.safety.get_controls_allowed() - return self.packer.make_can_msg_panda("AcceleratorPedal2", 0, values) - - def _torque_driver_msg(self, torque): - # Safety tests assume driver torque is an int, use DBC factor - values = {"LKADriverAppldTrq": torque * 0.01} - return self.packer.make_can_msg_panda("PSCMStatus", 0, values) - - def _torque_cmd_msg(self, torque, steer_req=1): - values = {"LKASteeringCmd": torque, "LKASteeringCmdActive": steer_req} - return self.packer.make_can_msg_panda("ASCMLKASteeringCmd", 0, values) - - def _button_msg(self, buttons): - values = {"ACCButtons": buttons} - return self.packer.make_can_msg_panda("ASCMSteeringButton", self.BUTTONS_BUS, values) - - -class TestGmAscmSafety(GmLongitudinalBase, TestGmSafetyBase): - TX_MSGS = [[0x180, 0], [0x409, 0], [0x40A, 0], [0x2CB, 0], [0x370, 0], # pt bus - [0xA1, 1], [0x306, 1], [0x308, 1], [0x310, 1], # obs bus - [0x315, 2], # ch bus - [0x104c006c, 3], [0x10400060, 3]] # gmlan - FWD_BLACKLISTED_ADDRS: dict[int, list[int]] = {} - FWD_BUS_LOOKUP: dict[int, int] = {} - BRAKE_BUS = 2 - - MAX_GAS = 3072 - MIN_GAS = 1404 # maximum regen - INACTIVE_GAS = 1404 - - def setUp(self): - self.packer = CANPackerPanda("gm_global_a_powertrain_generated") - self.packer_chassis = CANPackerPanda("gm_global_a_chassis") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_GM, 0) - self.safety.init_tests() - - -class TestGmCameraSafetyBase(TestGmSafetyBase): - - FWD_BUS_LOOKUP = {0: 2, 2: 0} - - @classmethod - def setUpClass(cls): - if cls.__name__ == "TestGmCameraSafetyBase": - cls.packer = None - cls.safety = None - raise unittest.SkipTest - - def _user_brake_msg(self, brake): - values = {"BrakePressed": brake} - return self.packer.make_can_msg_panda("ECMEngineStatus", 0, values) - - -class TestGmCameraSafety(TestGmCameraSafetyBase): - TX_MSGS = [[0x180, 0], # pt bus - [0x184, 2]] # camera bus - FWD_BLACKLISTED_ADDRS = {2: [0x180], 0: [0x184]} # block LKAS message and PSCMStatus - BUTTONS_BUS = 2 # tx only - - def setUp(self): - self.packer = CANPackerPanda("gm_global_a_powertrain_generated") - self.packer_chassis = CANPackerPanda("gm_global_a_chassis") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_GM, Panda.FLAG_GM_HW_CAM) - self.safety.init_tests() - - def test_buttons(self): - # Only CANCEL button is allowed while cruise is enabled - self.safety.set_controls_allowed(0) - for btn in range(8): - self.assertFalse(self._tx(self._button_msg(btn))) - - self.safety.set_controls_allowed(1) - for btn in range(8): - self.assertFalse(self._tx(self._button_msg(btn))) - - for enabled in (True, False): - self._rx(self._pcm_status_msg(enabled)) - self.assertEqual(enabled, self._tx(self._button_msg(Buttons.CANCEL))) - - -class TestGmCameraLongitudinalSafety(GmLongitudinalBase, TestGmCameraSafetyBase): - TX_MSGS = [[0x180, 0], [0x315, 0], [0x2CB, 0], [0x370, 0], # pt bus - [0x184, 2]] # camera bus - FWD_BLACKLISTED_ADDRS = {2: [0x180, 0x2CB, 0x370, 0x315], 0: [0x184]} # block LKAS, ACC messages and PSCMStatus - BUTTONS_BUS = 0 # rx only - - MAX_GAS = 3400 - MIN_GAS = 1514 # maximum regen - INACTIVE_GAS = 1554 - - def setUp(self): - self.packer = CANPackerPanda("gm_global_a_powertrain_generated") - self.packer_chassis = CANPackerPanda("gm_global_a_chassis") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_GM, Panda.FLAG_GM_HW_CAM | Panda.FLAG_GM_HW_CAM_LONG) - self.safety.init_tests() - - -if __name__ == "__main__": - unittest.main() diff --git a/panda/tests/safety/test_honda.py b/panda/tests/safety/test_honda.py deleted file mode 100644 index 45f190c..0000000 --- a/panda/tests/safety/test_honda.py +++ /dev/null @@ -1,618 +0,0 @@ -#!/usr/bin/env python3 -import unittest -import numpy as np - -from panda import Panda -from panda.tests.libpanda import libpanda_py -import panda.tests.safety.common as common -from panda.tests.safety.common import CANPackerPanda, MAX_WRONG_COUNTERS - -HONDA_N_COMMON_TX_MSGS = [[0xE4, 0], [0x194, 0], [0x1FA, 0], [0x30C, 0], [0x33D, 0]] - -class Btn: - NONE = 0 - MAIN = 1 - CANCEL = 2 - SET = 3 - RESUME = 4 - -HONDA_NIDEC = 0 -HONDA_BOSCH = 1 - - -# Honda safety has several different configurations tested here: -# * Nidec -# * normal (PCM-enable) -# * alt SCM messages (PCM-enable) -# * gas interceptor (button-enable) -# * gas interceptor with alt SCM messages (button-enable) -# * Bosch -# * Bosch with Longitudinal Support -# * Bosch Radarless -# * Bosch Radarless with Longitudinal Support - - -class HondaButtonEnableBase(common.PandaCarSafetyTest): - # pylint: disable=no-member,abstract-method - - # override these inherited tests since we're using button enable - def test_disable_control_allowed_from_cruise(self): - pass - - def test_enable_control_allowed_from_cruise(self): - pass - - def test_cruise_engaged_prev(self): - pass - - def test_buttons_with_main_off(self): - for btn in (Btn.SET, Btn.RESUME, Btn.CANCEL): - self.safety.set_controls_allowed(1) - self._rx(self._acc_state_msg(False)) - self._rx(self._button_msg(btn, main_on=False)) - self.assertFalse(self.safety.get_controls_allowed()) - - def test_set_resume_buttons(self): - """ - Both SET and RES should enter controls allowed on their falling edge. - """ - for main_on in (True, False): - self._rx(self._acc_state_msg(main_on)) - for btn_prev in range(8): - for btn_cur in range(8): - self._rx(self._button_msg(Btn.NONE)) - self.safety.set_controls_allowed(0) - for _ in range(10): - self._rx(self._button_msg(btn_prev)) - self.assertFalse(self.safety.get_controls_allowed()) - - # should enter controls allowed on falling edge and not transitioning to cancel or main - should_enable = (main_on and - btn_cur != btn_prev and - btn_prev in (Btn.RESUME, Btn.SET) and - btn_cur not in (Btn.CANCEL, Btn.MAIN)) - - self._rx(self._button_msg(btn_cur, main_on=main_on)) - self.assertEqual(should_enable, self.safety.get_controls_allowed(), msg=f"{main_on=} {btn_prev=} {btn_cur=}") - - def test_main_cancel_buttons(self): - """ - Both MAIN and CANCEL should exit controls immediately. - """ - for btn in (Btn.MAIN, Btn.CANCEL): - self.safety.set_controls_allowed(1) - self._rx(self._button_msg(btn, main_on=True)) - self.assertFalse(self.safety.get_controls_allowed()) - - def test_disengage_on_main(self): - self.safety.set_controls_allowed(1) - self._rx(self._acc_state_msg(True)) - self.assertTrue(self.safety.get_controls_allowed()) - self._rx(self._acc_state_msg(False)) - self.assertFalse(self.safety.get_controls_allowed()) - - def test_rx_hook(self): - - # TODO: move this test to common - # checksum checks - for msg in ["btn", "gas", "speed"]: - self.safety.set_controls_allowed(1) - if msg == "btn": - to_push = self._button_msg(Btn.SET) - if msg == "gas": - to_push = self._user_gas_msg(0) - if msg == "speed": - to_push = self._speed_msg(0) - self.assertTrue(self._rx(to_push)) - if msg != "btn": - to_push[0].data[4] = 0 # invalidate checksum - to_push[0].data[5] = 0 - to_push[0].data[6] = 0 - to_push[0].data[7] = 0 - self.assertFalse(self._rx(to_push)) - self.assertFalse(self.safety.get_controls_allowed()) - - # counter - # reset wrong_counters to zero by sending valid messages - for i in range(MAX_WRONG_COUNTERS + 1): - self.__class__.cnt_speed += 1 - self.__class__.cnt_button += 1 - self.__class__.cnt_powertrain_data += 1 - if i < MAX_WRONG_COUNTERS: - self.safety.set_controls_allowed(1) - self._rx(self._button_msg(Btn.SET)) - self._rx(self._speed_msg(0)) - self._rx(self._user_gas_msg(0)) - else: - self.assertFalse(self._rx(self._button_msg(Btn.SET))) - self.assertFalse(self._rx(self._speed_msg(0))) - self.assertFalse(self._rx(self._user_gas_msg(0))) - self.assertFalse(self.safety.get_controls_allowed()) - - # restore counters for future tests with a couple of good messages - for _ in range(2): - self.safety.set_controls_allowed(1) - self._rx(self._button_msg(Btn.SET, main_on=True)) - self._rx(self._speed_msg(0)) - self._rx(self._user_gas_msg(0)) - self._rx(self._button_msg(Btn.SET, main_on=True)) - self.assertTrue(self.safety.get_controls_allowed()) - - -class HondaPcmEnableBase(common.PandaCarSafetyTest): - # pylint: disable=no-member,abstract-method - - def test_buttons(self): - """ - Buttons should only cancel in this configuration, - since our state is tied to the PCM's cruise state. - """ - for controls_allowed in (True, False): - for main_on in (True, False): - # not a valid state - if controls_allowed and not main_on: - continue - - for btn in (Btn.SET, Btn.RESUME, Btn.CANCEL): - self.safety.set_controls_allowed(controls_allowed) - self._rx(self._acc_state_msg(main_on)) - - # btn + none for falling edge - self._rx(self._button_msg(btn, main_on=main_on)) - self._rx(self._button_msg(Btn.NONE, main_on=main_on)) - - if btn == Btn.CANCEL: - self.assertFalse(self.safety.get_controls_allowed()) - else: - self.assertEqual(controls_allowed, self.safety.get_controls_allowed()) - - -class HondaBase(common.PandaCarSafetyTest): - MAX_BRAKE = 255 - PT_BUS: int | None = None # must be set when inherited - STEER_BUS: int | None = None # must be set when inherited - BUTTONS_BUS: int | None = None # must be set when inherited, tx on this bus, rx on PT_BUS - - STANDSTILL_THRESHOLD = 0 - RELAY_MALFUNCTION_ADDRS = {0: (0xE4, 0x194)} # STEERING_CONTROL - FWD_BUS_LOOKUP = {0: 2, 2: 0} - - cnt_speed = 0 - cnt_button = 0 - cnt_brake = 0 - cnt_powertrain_data = 0 - cnt_acc_state = 0 - - @classmethod - def setUpClass(cls): - if cls.__name__.endswith("Base"): - cls.packer = None - cls.safety = None - raise unittest.SkipTest - - def _powertrain_data_msg(self, cruise_on=None, brake_pressed=None, gas_pressed=None): - # preserve the state - if cruise_on is None: - # or'd with controls allowed since the tests use it to "enable" cruise - cruise_on = self.safety.get_cruise_engaged_prev() or self.safety.get_controls_allowed() - if brake_pressed is None: - brake_pressed = self.safety.get_brake_pressed_prev() - if gas_pressed is None: - gas_pressed = self.safety.get_gas_pressed_prev() - - values = { - "ACC_STATUS": cruise_on, - "BRAKE_PRESSED": brake_pressed, - "PEDAL_GAS": gas_pressed, - "COUNTER": self.cnt_powertrain_data % 4 - } - self.__class__.cnt_powertrain_data += 1 - return self.packer.make_can_msg_panda("POWERTRAIN_DATA", self.PT_BUS, values) - - def _pcm_status_msg(self, enable): - return self._powertrain_data_msg(cruise_on=enable) - - def _speed_msg(self, speed): - values = {"XMISSION_SPEED": speed, "COUNTER": self.cnt_speed % 4} - self.__class__.cnt_speed += 1 - return self.packer.make_can_msg_panda("ENGINE_DATA", self.PT_BUS, values) - - def _acc_state_msg(self, main_on): - values = {"MAIN_ON": main_on, "COUNTER": self.cnt_acc_state % 4} - self.__class__.cnt_acc_state += 1 - return self.packer.make_can_msg_panda("SCM_FEEDBACK", self.PT_BUS, values) - - def _button_msg(self, buttons, main_on=False, bus=None): - bus = self.PT_BUS if bus is None else bus - values = {"CRUISE_BUTTONS": buttons, "COUNTER": self.cnt_button % 4} - self.__class__.cnt_button += 1 - return self.packer.make_can_msg_panda("SCM_BUTTONS", bus, values) - - def _user_brake_msg(self, brake): - return self._powertrain_data_msg(brake_pressed=brake) - - def _user_gas_msg(self, gas): - return self._powertrain_data_msg(gas_pressed=gas) - - def _send_steer_msg(self, steer): - values = {"STEER_TORQUE": steer} - return self.packer.make_can_msg_panda("STEERING_CONTROL", self.STEER_BUS, values) - - def _send_brake_msg(self, brake): - # must be implemented when inherited - raise NotImplementedError - - def test_disengage_on_brake(self): - self.safety.set_controls_allowed(1) - self._rx(self._user_brake_msg(1)) - self.assertFalse(self.safety.get_controls_allowed()) - - def test_steer_safety_check(self): - self.safety.set_controls_allowed(0) - self.assertTrue(self._tx(self._send_steer_msg(0x0000))) - self.assertFalse(self._tx(self._send_steer_msg(0x1000))) - - -# ********************* Honda Nidec ********************** - - -class TestHondaNidecSafetyBase(HondaBase): - TX_MSGS = HONDA_N_COMMON_TX_MSGS - FWD_BLACKLISTED_ADDRS = {2: [0xE4, 0x194, 0x33D, 0x30C]} - - PT_BUS = 0 - STEER_BUS = 0 - BUTTONS_BUS = 0 - - MAX_GAS = 198 - - def setUp(self): - self.packer = CANPackerPanda("honda_civic_touring_2016_can_generated") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_HONDA_NIDEC, 0) - self.safety.init_tests() - - def _send_brake_msg(self, brake, aeb_req=0, bus=0): - values = {"COMPUTER_BRAKE": brake, "AEB_REQ_1": aeb_req} - return self.packer.make_can_msg_panda("BRAKE_COMMAND", bus, values) - - def _rx_brake_msg(self, brake, aeb_req=0): - return self._send_brake_msg(brake, aeb_req, bus=2) - - def _send_acc_hud_msg(self, pcm_gas, pcm_speed): - # Used to control ACC on Nidec without pedal - values = {"PCM_GAS": pcm_gas, "PCM_SPEED": pcm_speed} - return self.packer.make_can_msg_panda("ACC_HUD", 0, values) - - def test_acc_hud_safety_check(self): - for controls_allowed in [True, False]: - self.safety.set_controls_allowed(controls_allowed) - for pcm_gas in range(255): - for pcm_speed in range(100): - send = (controls_allowed and pcm_gas <= self.MAX_GAS) or (pcm_gas == 0 and pcm_speed == 0) - self.assertEqual(send, self._tx(self._send_acc_hud_msg(pcm_gas, pcm_speed))) - - def test_fwd_hook(self): - # normal operation, not forwarding AEB - self.FWD_BLACKLISTED_ADDRS[2].append(0x1FA) - self.safety.set_honda_fwd_brake(False) - super().test_fwd_hook() - - # forwarding AEB brake signal - self.FWD_BLACKLISTED_ADDRS = {2: [0xE4, 0x194, 0x33D, 0x30C]} - self.safety.set_honda_fwd_brake(True) - super().test_fwd_hook() - - def test_honda_fwd_brake_latching(self): - # Shouldn't fwd stock Honda requesting brake without AEB - self.assertTrue(self._rx(self._rx_brake_msg(self.MAX_BRAKE, aeb_req=0))) - self.assertFalse(self.safety.get_honda_fwd_brake()) - - # Now allow controls and request some brake - openpilot_brake = round(self.MAX_BRAKE / 2.0) - self.safety.set_controls_allowed(True) - self.assertTrue(self._tx(self._send_brake_msg(openpilot_brake))) - - # Still shouldn't fwd stock Honda brake until it's more than openpilot's - for stock_honda_brake in range(self.MAX_BRAKE + 1): - self.assertTrue(self._rx(self._rx_brake_msg(stock_honda_brake, aeb_req=1))) - should_fwd_brake = stock_honda_brake >= openpilot_brake - self.assertEqual(should_fwd_brake, self.safety.get_honda_fwd_brake()) - - # Shouldn't stop fwding until AEB event is over - for stock_honda_brake in range(self.MAX_BRAKE + 1)[::-1]: - self.assertTrue(self._rx(self._rx_brake_msg(stock_honda_brake, aeb_req=1))) - self.assertTrue(self.safety.get_honda_fwd_brake()) - - self.assertTrue(self._rx(self._rx_brake_msg(0, aeb_req=0))) - self.assertFalse(self.safety.get_honda_fwd_brake()) - - def test_brake_safety_check(self): - for fwd_brake in [False, True]: - self.safety.set_honda_fwd_brake(fwd_brake) - for brake in np.arange(0, self.MAX_BRAKE + 10, 1): - for controls_allowed in [True, False]: - self.safety.set_controls_allowed(controls_allowed) - if fwd_brake: - send = False # block openpilot brake msg when fwd'ing stock msg - elif controls_allowed: - send = self.MAX_BRAKE >= brake >= 0 - else: - send = brake == 0 - self.assertEqual(send, self._tx(self._send_brake_msg(brake))) - - -class TestHondaNidecPcmSafety(HondaPcmEnableBase, TestHondaNidecSafetyBase): - """ - Covers the Honda Nidec safety mode - """ - - # Nidec doesn't disengage on falling edge of cruise. See comment in safety_honda.h - def test_disable_control_allowed_from_cruise(self): - pass - - -class TestHondaNidecGasInterceptorSafety(common.GasInterceptorSafetyTest, HondaButtonEnableBase, TestHondaNidecSafetyBase): - """ - Covers the Honda Nidec safety mode with a gas interceptor, switches to a button-enable car - """ - - TX_MSGS = HONDA_N_COMMON_TX_MSGS + [[0x200, 0]] - INTERCEPTOR_THRESHOLD = 492 - - def setUp(self): - self.packer = CANPackerPanda("honda_civic_touring_2016_can_generated") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_HONDA_NIDEC, Panda.FLAG_HONDA_GAS_INTERCEPTOR) - self.safety.init_tests() - - -class TestHondaNidecPcmAltSafety(TestHondaNidecPcmSafety): - """ - Covers the Honda Nidec safety mode with alt SCM messages - """ - def setUp(self): - self.packer = CANPackerPanda("acura_ilx_2016_can_generated") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_HONDA_NIDEC, Panda.FLAG_HONDA_NIDEC_ALT) - self.safety.init_tests() - - def _acc_state_msg(self, main_on): - values = {"MAIN_ON": main_on, "COUNTER": self.cnt_acc_state % 4} - self.__class__.cnt_acc_state += 1 - return self.packer.make_can_msg_panda("SCM_BUTTONS", self.PT_BUS, values) - - def _button_msg(self, buttons, main_on=False, bus=None): - bus = self.PT_BUS if bus is None else bus - values = {"CRUISE_BUTTONS": buttons, "MAIN_ON": main_on, "COUNTER": self.cnt_button % 4} - self.__class__.cnt_button += 1 - return self.packer.make_can_msg_panda("SCM_BUTTONS", bus, values) - - -class TestHondaNidecAltGasInterceptorSafety(common.GasInterceptorSafetyTest, HondaButtonEnableBase, TestHondaNidecSafetyBase): - """ - Covers the Honda Nidec safety mode with alt SCM messages and gas interceptor, switches to a button-enable car - """ - - TX_MSGS = HONDA_N_COMMON_TX_MSGS + [[0x200, 0]] - INTERCEPTOR_THRESHOLD = 492 - - def setUp(self): - self.packer = CANPackerPanda("acura_ilx_2016_can_generated") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_HONDA_NIDEC, Panda.FLAG_HONDA_NIDEC_ALT | Panda.FLAG_HONDA_GAS_INTERCEPTOR) - self.safety.init_tests() - - def _acc_state_msg(self, main_on): - values = {"MAIN_ON": main_on, "COUNTER": self.cnt_acc_state % 4} - self.__class__.cnt_acc_state += 1 - return self.packer.make_can_msg_panda("SCM_BUTTONS", self.PT_BUS, values) - - def _button_msg(self, buttons, main_on=False, bus=None): - bus = self.PT_BUS if bus is None else bus - values = {"CRUISE_BUTTONS": buttons, "MAIN_ON": main_on, "COUNTER": self.cnt_button % 4} - self.__class__.cnt_button += 1 - return self.packer.make_can_msg_panda("SCM_BUTTONS", bus, values) - - - -# ********************* Honda Bosch ********************** - - -class TestHondaBoschSafetyBase(HondaBase): - PT_BUS = 1 - STEER_BUS = 0 - BUTTONS_BUS = 1 - - TX_MSGS = [[0xE4, 0], [0xE5, 0], [0x296, 1], [0x33D, 0], [0x33DA, 0], [0x33DB, 0]] - FWD_BLACKLISTED_ADDRS = {2: [0xE4, 0xE5, 0x33D, 0x33DA, 0x33DB]} - - def setUp(self): - self.packer = CANPackerPanda("honda_accord_2018_can_generated") - self.safety = libpanda_py.libpanda - - def _alt_brake_msg(self, brake): - values = {"BRAKE_PRESSED": brake, "COUNTER": self.cnt_brake % 4} - self.__class__.cnt_brake += 1 - return self.packer.make_can_msg_panda("BRAKE_MODULE", self.PT_BUS, values) - - def _send_brake_msg(self, brake): - pass - - def test_alt_disengage_on_brake(self): - self.safety.set_honda_alt_brake_msg(1) - self.safety.set_controls_allowed(1) - self._rx(self._alt_brake_msg(1)) - self.assertFalse(self.safety.get_controls_allowed()) - - self.safety.set_honda_alt_brake_msg(0) - self.safety.set_controls_allowed(1) - self._rx(self._alt_brake_msg(1)) - self.assertTrue(self.safety.get_controls_allowed()) - - def test_spam_cancel_safety_check(self): - self.safety.set_controls_allowed(0) - self.assertTrue(self._tx(self._button_msg(Btn.CANCEL, bus=self.BUTTONS_BUS))) - self.assertFalse(self._tx(self._button_msg(Btn.RESUME, bus=self.BUTTONS_BUS))) - self.assertFalse(self._tx(self._button_msg(Btn.SET, bus=self.BUTTONS_BUS))) - # do not block resume if we are engaged already - self.safety.set_controls_allowed(1) - self.assertTrue(self._tx(self._button_msg(Btn.RESUME, bus=self.BUTTONS_BUS))) - - -class TestHondaBoschAltBrakeSafetyBase(TestHondaBoschSafetyBase): - """ - Base Bosch safety test class with an alternate brake message - """ - def setUp(self): - super().setUp() - self.safety.set_safety_hooks(Panda.SAFETY_HONDA_BOSCH, Panda.FLAG_HONDA_ALT_BRAKE) - self.safety.init_tests() - - def _user_brake_msg(self, brake): - return self._alt_brake_msg(brake) - - def test_alt_brake_rx_hook(self): - self.safety.set_honda_alt_brake_msg(1) - self.safety.set_controls_allowed(1) - to_push = self._alt_brake_msg(0) - self.assertTrue(self._rx(to_push)) - to_push[0].data[2] = to_push[0].data[2] & 0xF0 # invalidate checksum - self.assertFalse(self._rx(to_push)) - self.assertFalse(self.safety.get_controls_allowed()) - - -class TestHondaBoschSafety(HondaPcmEnableBase, TestHondaBoschSafetyBase): - """ - Covers the Honda Bosch safety mode with stock longitudinal - """ - def setUp(self): - super().setUp() - self.safety.set_safety_hooks(Panda.SAFETY_HONDA_BOSCH, 0) - self.safety.init_tests() - - -class TestHondaBoschAltBrakeSafety(HondaPcmEnableBase, TestHondaBoschAltBrakeSafetyBase): - """ - Covers the Honda Bosch safety mode with stock longitudinal and an alternate brake message - """ - - -class TestHondaBoschLongSafety(HondaButtonEnableBase, TestHondaBoschSafetyBase): - """ - Covers the Honda Bosch safety mode with longitudinal control - """ - NO_GAS = -30000 - MAX_GAS = 2000 - MAX_ACCEL = 2.0 # accel is used for brakes, but openpilot can set positive values - MIN_ACCEL = -3.5 - - STEER_BUS = 1 - TX_MSGS = [[0xE4, 1], [0x1DF, 1], [0x1EF, 1], [0x1FA, 1], [0x30C, 1], [0x33D, 1], [0x33DA, 1], [0x33DB, 1], [0x39F, 1], [0x18DAB0F1, 1]] - FWD_BLACKLISTED_ADDRS = {2: [0xE4, 0xE5, 0x33D, 0x33DA, 0x33DB]} - # 0x1DF is to test that radar is disabled - RELAY_MALFUNCTION_ADDRS = {0: (0xE4, 0x194), 1: (0x1DF,)} # STEERING_CONTROL, ACC_CONTROL - - def setUp(self): - super().setUp() - self.safety.set_safety_hooks(Panda.SAFETY_HONDA_BOSCH, Panda.FLAG_HONDA_BOSCH_LONG) - self.safety.init_tests() - - def _send_gas_brake_msg(self, gas, accel): - values = { - "GAS_COMMAND": gas, - "ACCEL_COMMAND": accel, - "BRAKE_REQUEST": accel < 0, - } - return self.packer.make_can_msg_panda("ACC_CONTROL", self.PT_BUS, values) - - # Longitudinal doesn't need to send buttons - def test_spam_cancel_safety_check(self): - pass - - def test_diagnostics(self): - tester_present = libpanda_py.make_CANPacket(0x18DAB0F1, self.PT_BUS, b"\x02\x3E\x80\x00\x00\x00\x00\x00") - self.assertTrue(self._tx(tester_present)) - - not_tester_present = libpanda_py.make_CANPacket(0x18DAB0F1, self.PT_BUS, b"\x03\xAA\xAA\x00\x00\x00\x00\x00") - self.assertFalse(self._tx(not_tester_present)) - - def test_gas_safety_check(self): - for controls_allowed in [True, False]: - for gas in np.arange(self.NO_GAS, self.MAX_GAS + 2000, 100): - accel = 0 if gas < 0 else gas / 1000 - self.safety.set_controls_allowed(controls_allowed) - send = (controls_allowed and 0 <= gas <= self.MAX_GAS) or gas == self.NO_GAS - self.assertEqual(send, self._tx(self._send_gas_brake_msg(gas, accel)), (controls_allowed, gas, accel)) - - def test_brake_safety_check(self): - for controls_allowed in [True, False]: - for accel in np.arange(self.MIN_ACCEL - 1, self.MAX_ACCEL + 1, 0.01): - accel = round(accel, 2) # floats might not hit exact boundary conditions without rounding - self.safety.set_controls_allowed(controls_allowed) - send = self.MIN_ACCEL <= accel <= self.MAX_ACCEL if controls_allowed else accel == 0 - self.assertEqual(send, self._tx(self._send_gas_brake_msg(self.NO_GAS, accel)), (controls_allowed, accel)) - - -class TestHondaBoschRadarlessSafetyBase(TestHondaBoschSafetyBase): - """Base class for radarless Honda Bosch""" - PT_BUS = 0 - STEER_BUS = 0 - BUTTONS_BUS = 2 # camera controls ACC, need to send buttons on bus 2 - - TX_MSGS = [[0xE4, 0], [0x296, 2], [0x33D, 0]] - FWD_BLACKLISTED_ADDRS = {2: [0xE4, 0xE5, 0x33D, 0x33DA, 0x33DB]} - - def setUp(self): - self.packer = CANPackerPanda("honda_civic_ex_2022_can_generated") - self.safety = libpanda_py.libpanda - - -class TestHondaBoschRadarlessSafety(HondaPcmEnableBase, TestHondaBoschRadarlessSafetyBase): - """ - Covers the Honda Bosch Radarless safety mode with stock longitudinal - """ - - def setUp(self): - super().setUp() - self.safety.set_safety_hooks(Panda.SAFETY_HONDA_BOSCH, Panda.FLAG_HONDA_RADARLESS) - self.safety.init_tests() - - -class TestHondaBoschRadarlessAltBrakeSafety(HondaPcmEnableBase, TestHondaBoschRadarlessSafetyBase, TestHondaBoschAltBrakeSafetyBase): - """ - Covers the Honda Bosch Radarless safety mode with stock longitudinal and an alternate brake message - """ - - def setUp(self): - super().setUp() - self.safety.set_safety_hooks(Panda.SAFETY_HONDA_BOSCH, Panda.FLAG_HONDA_RADARLESS | Panda.FLAG_HONDA_ALT_BRAKE) - self.safety.init_tests() - - -class TestHondaBoschRadarlessLongSafety(common.LongitudinalAccelSafetyTest, HondaButtonEnableBase, - TestHondaBoschRadarlessSafetyBase): - """ - Covers the Honda Bosch Radarless safety mode with longitudinal control - """ - TX_MSGS = [[0xE4, 0], [0x33D, 0], [0x1C8, 0], [0x30C, 0]] - FWD_BLACKLISTED_ADDRS = {2: [0xE4, 0xE5, 0x33D, 0x33DA, 0x33DB, 0x1C8, 0x30C]} - - def setUp(self): - super().setUp() - self.safety.set_safety_hooks(Panda.SAFETY_HONDA_BOSCH, Panda.FLAG_HONDA_RADARLESS | Panda.FLAG_HONDA_BOSCH_LONG) - self.safety.init_tests() - - def _accel_msg(self, accel): - values = { - "ACCEL_COMMAND": accel, - } - return self.packer.make_can_msg_panda("ACC_CONTROL", self.PT_BUS, values) - - # Longitudinal doesn't need to send buttons - def test_spam_cancel_safety_check(self): - pass - - -if __name__ == "__main__": - unittest.main() diff --git a/panda/tests/safety/test_hyundai.py b/panda/tests/safety/test_hyundai.py deleted file mode 100644 index fbe7d10..0000000 --- a/panda/tests/safety/test_hyundai.py +++ /dev/null @@ -1,216 +0,0 @@ -#!/usr/bin/env python3 -import random -import unittest -from panda import Panda -from panda.tests.libpanda import libpanda_py -import panda.tests.safety.common as common -from panda.tests.safety.common import CANPackerPanda -from panda.tests.safety.hyundai_common import HyundaiButtonBase, HyundaiLongitudinalBase - - -# 4 bit checkusm used in some hyundai messages -# lives outside the can packer because we never send this msg -def checksum(msg): - addr, t, dat, bus = msg - - chksum = 0 - if addr == 0x386: - for i, b in enumerate(dat): - for j in range(8): - # exclude checksum and counter bits - if (i != 1 or j < 6) and (i != 3 or j < 6) and (i != 5 or j < 6) and (i != 7 or j < 6): - bit = (b >> j) & 1 - else: - bit = 0 - chksum += bit - chksum = (chksum ^ 9) & 0xF - ret = bytearray(dat) - ret[5] |= (chksum & 0x3) << 6 - ret[7] |= (chksum & 0xc) << 4 - else: - for i, b in enumerate(dat): - if addr in [0x260, 0x421] and i == 7: - b &= 0x0F if addr == 0x421 else 0xF0 - elif addr == 0x394 and i == 6: - b &= 0xF0 - elif addr == 0x394 and i == 7: - continue - chksum += sum(divmod(b, 16)) - chksum = (16 - chksum) % 16 - ret = bytearray(dat) - ret[6 if addr == 0x394 else 7] |= chksum << (4 if addr == 0x421 else 0) - - return addr, t, ret, bus - - -class TestHyundaiSafety(HyundaiButtonBase, common.PandaCarSafetyTest, common.DriverTorqueSteeringSafetyTest, common.SteerRequestCutSafetyTest): - TX_MSGS = [[0x340, 0], [0x4F1, 0], [0x485, 0]] - STANDSTILL_THRESHOLD = 12 # 0.375 kph - RELAY_MALFUNCTION_ADDRS = {0: (0x340,)} # LKAS11 - FWD_BLACKLISTED_ADDRS = {2: [0x340, 0x485]} - FWD_BUS_LOOKUP = {0: 2, 2: 0} - - MAX_RATE_UP = 3 - MAX_RATE_DOWN = 7 - MAX_TORQUE = 384 - MAX_RT_DELTA = 112 - RT_INTERVAL = 250000 - DRIVER_TORQUE_ALLOWANCE = 50 - DRIVER_TORQUE_FACTOR = 2 - - # Safety around steering req bit - MIN_VALID_STEERING_FRAMES = 89 - MAX_INVALID_STEERING_FRAMES = 2 - MIN_VALID_STEERING_RT_INTERVAL = 810000 # a ~10% buffer, can send steer up to 110Hz - - cnt_gas = 0 - cnt_speed = 0 - cnt_brake = 0 - cnt_cruise = 0 - cnt_button = 0 - - def setUp(self): - self.packer = CANPackerPanda("hyundai_kia_generic") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_HYUNDAI, 0) - self.safety.init_tests() - - def _button_msg(self, buttons, main_button=0, bus=0): - values = {"CF_Clu_CruiseSwState": buttons, "CF_Clu_CruiseSwMain": main_button, "CF_Clu_AliveCnt1": self.cnt_button} - self.__class__.cnt_button += 1 - return self.packer.make_can_msg_panda("CLU11", bus, values) - - def _user_gas_msg(self, gas): - values = {"CF_Ems_AclAct": gas, "AliveCounter": self.cnt_gas % 4} - self.__class__.cnt_gas += 1 - return self.packer.make_can_msg_panda("EMS16", 0, values, fix_checksum=checksum) - - def _user_brake_msg(self, brake): - values = {"DriverOverride": 2 if brake else random.choice((0, 1, 3)), - "AliveCounterTCS": self.cnt_brake % 8} - self.__class__.cnt_brake += 1 - return self.packer.make_can_msg_panda("TCS13", 0, values, fix_checksum=checksum) - - def _speed_msg(self, speed): - # panda safety doesn't scale, so undo the scaling - values = {"WHL_SPD_%s" % s: speed * 0.03125 for s in ["FL", "FR", "RL", "RR"]} - values["WHL_SPD_AliveCounter_LSB"] = (self.cnt_speed % 16) & 0x3 - values["WHL_SPD_AliveCounter_MSB"] = (self.cnt_speed % 16) >> 2 - self.__class__.cnt_speed += 1 - return self.packer.make_can_msg_panda("WHL_SPD11", 0, values, fix_checksum=checksum) - - def _pcm_status_msg(self, enable): - values = {"ACCMode": enable, "CR_VSM_Alive": self.cnt_cruise % 16} - self.__class__.cnt_cruise += 1 - return self.packer.make_can_msg_panda("SCC12", self.SCC_BUS, values, fix_checksum=checksum) - - def _torque_driver_msg(self, torque): - values = {"CR_Mdps_StrColTq": torque} - return self.packer.make_can_msg_panda("MDPS12", 0, values) - - def _torque_cmd_msg(self, torque, steer_req=1): - values = {"CR_Lkas_StrToqReq": torque, "CF_Lkas_ActToi": steer_req} - return self.packer.make_can_msg_panda("LKAS11", 0, values) - - -class TestHyundaiSafetyAltLimits(TestHyundaiSafety): - MAX_RATE_UP = 2 - MAX_RATE_DOWN = 3 - MAX_TORQUE = 270 - - def setUp(self): - self.packer = CANPackerPanda("hyundai_kia_generic") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_HYUNDAI, Panda.FLAG_HYUNDAI_ALT_LIMITS) - self.safety.init_tests() - - -class TestHyundaiSafetyCameraSCC(TestHyundaiSafety): - BUTTONS_TX_BUS = 2 # tx on 2, rx on 0 - SCC_BUS = 2 # rx on 2 - - def setUp(self): - self.packer = CANPackerPanda("hyundai_kia_generic") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_HYUNDAI, Panda.FLAG_HYUNDAI_CAMERA_SCC) - self.safety.init_tests() - - -class TestHyundaiLegacySafety(TestHyundaiSafety): - def setUp(self): - self.packer = CANPackerPanda("hyundai_kia_generic") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_HYUNDAI_LEGACY, 0) - self.safety.init_tests() - - -class TestHyundaiLegacySafetyEV(TestHyundaiSafety): - def setUp(self): - self.packer = CANPackerPanda("hyundai_kia_generic") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_HYUNDAI_LEGACY, 1) - self.safety.init_tests() - - def _user_gas_msg(self, gas): - values = {"Accel_Pedal_Pos": gas} - return self.packer.make_can_msg_panda("E_EMS11", 0, values, fix_checksum=checksum) - - -class TestHyundaiLegacySafetyHEV(TestHyundaiSafety): - def setUp(self): - self.packer = CANPackerPanda("hyundai_kia_generic") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_HYUNDAI_LEGACY, 2) - self.safety.init_tests() - - def _user_gas_msg(self, gas): - values = {"CR_Vcu_AccPedDep_Pos": gas} - return self.packer.make_can_msg_panda("E_EMS11", 0, values, fix_checksum=checksum) - -class TestHyundaiLongitudinalSafety(HyundaiLongitudinalBase, TestHyundaiSafety): - TX_MSGS = [[0x340, 0], [0x4F1, 0], [0x485, 0], [0x420, 0], [0x421, 0], [0x50A, 0], [0x389, 0], [0x4A2, 0], [0x38D, 0], [0x483, 0], [0x7D0, 0]] - - RELAY_MALFUNCTION_ADDRS = {0: (0x340, 0x421)} # LKAS11, SCC12 - - DISABLED_ECU_UDS_MSG = (0x7D0, 0) - DISABLED_ECU_ACTUATION_MSG = (0x421, 0) - - def setUp(self): - self.packer = CANPackerPanda("hyundai_kia_generic") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_HYUNDAI, Panda.FLAG_HYUNDAI_LONG) - self.safety.init_tests() - - def _accel_msg(self, accel, aeb_req=False, aeb_decel=0): - values = { - "aReqRaw": accel, - "aReqValue": accel, - "AEB_CmdAct": int(aeb_req), - "CR_VSM_DecCmd": aeb_decel, - } - return self.packer.make_can_msg_panda("SCC12", self.SCC_BUS, values) - - def _fca11_msg(self, idx=0, vsm_aeb_req=False, fca_aeb_req=False, aeb_decel=0): - values = { - "CR_FCA_Alive": idx % 0xF, - "FCA_Status": 2, - "CR_VSM_DecCmd": aeb_decel, - "CF_VSM_DecCmdAct": int(vsm_aeb_req), - "FCA_CmdAct": int(fca_aeb_req), - } - return self.packer.make_can_msg_panda("FCA11", 0, values) - - def test_no_aeb_fca11(self): - self.assertTrue(self._tx(self._fca11_msg())) - self.assertFalse(self._tx(self._fca11_msg(vsm_aeb_req=True))) - self.assertFalse(self._tx(self._fca11_msg(fca_aeb_req=True))) - self.assertFalse(self._tx(self._fca11_msg(aeb_decel=1.0))) - - def test_no_aeb_scc12(self): - self.assertTrue(self._tx(self._accel_msg(0))) - self.assertFalse(self._tx(self._accel_msg(0, aeb_req=True))) - self.assertFalse(self._tx(self._accel_msg(0, aeb_decel=1.0))) - - -if __name__ == "__main__": - unittest.main() diff --git a/panda/tests/safety/test_hyundai_canfd.py b/panda/tests/safety/test_hyundai_canfd.py deleted file mode 100644 index 7f280b6..0000000 --- a/panda/tests/safety/test_hyundai_canfd.py +++ /dev/null @@ -1,272 +0,0 @@ -#!/usr/bin/env python3 -from parameterized import parameterized_class -import unittest -from panda import Panda -from panda.tests.libpanda import libpanda_py -import panda.tests.safety.common as common -from panda.tests.safety.common import CANPackerPanda -from panda.tests.safety.hyundai_common import HyundaiButtonBase, HyundaiLongitudinalBase - - -class TestHyundaiCanfdBase(HyundaiButtonBase, common.PandaCarSafetyTest, common.DriverTorqueSteeringSafetyTest, common.SteerRequestCutSafetyTest): - - TX_MSGS = [[0x50, 0], [0x1CF, 1], [0x2A4, 0]] - STANDSTILL_THRESHOLD = 12 # 0.375 kph - FWD_BLACKLISTED_ADDRS = {2: [0x50, 0x2a4]} - FWD_BUS_LOOKUP = {0: 2, 2: 0} - - MAX_RATE_UP = 2 - MAX_RATE_DOWN = 3 - MAX_TORQUE = 270 - - MAX_RT_DELTA = 112 - RT_INTERVAL = 250000 - - DRIVER_TORQUE_ALLOWANCE = 250 - DRIVER_TORQUE_FACTOR = 2 - - # Safety around steering req bit - MIN_VALID_STEERING_FRAMES = 89 - MAX_INVALID_STEERING_FRAMES = 2 - MIN_VALID_STEERING_RT_INTERVAL = 810000 # a ~10% buffer, can send steer up to 110Hz - - PT_BUS = 0 - SCC_BUS = 2 - STEER_BUS = 0 - STEER_MSG = "" - GAS_MSG = ("", "") - BUTTONS_TX_BUS = 1 - - @classmethod - def setUpClass(cls): - super().setUpClass() - if cls.__name__ == "TestHyundaiCanfdBase": - cls.packer = None - cls.safety = None - raise unittest.SkipTest - - def _torque_driver_msg(self, torque): - values = {"STEERING_COL_TORQUE": torque} - return self.packer.make_can_msg_panda("MDPS", self.PT_BUS, values) - - def _torque_cmd_msg(self, torque, steer_req=1): - values = {"TORQUE_REQUEST": torque, "STEER_REQ": steer_req} - return self.packer.make_can_msg_panda(self.STEER_MSG, self.STEER_BUS, values) - - def _speed_msg(self, speed): - values = {f"WHEEL_SPEED_{i}": speed * 0.03125 for i in range(1, 5)} - return self.packer.make_can_msg_panda("WHEEL_SPEEDS", self.PT_BUS, values) - - def _user_brake_msg(self, brake): - values = {"DriverBraking": brake} - return self.packer.make_can_msg_panda("TCS", self.PT_BUS, values) - - def _user_gas_msg(self, gas): - values = {self.GAS_MSG[1]: gas} - return self.packer.make_can_msg_panda(self.GAS_MSG[0], self.PT_BUS, values) - - def _pcm_status_msg(self, enable): - values = {"ACCMode": 1 if enable else 0} - return self.packer.make_can_msg_panda("SCC_CONTROL", self.SCC_BUS, values) - - def _button_msg(self, buttons, main_button=0, bus=None): - if bus is None: - bus = self.PT_BUS - values = { - "CRUISE_BUTTONS": buttons, - "ADAPTIVE_CRUISE_MAIN_BTN": main_button, - } - return self.packer.make_can_msg_panda("CRUISE_BUTTONS", bus, values) - - -class TestHyundaiCanfdHDA1Base(TestHyundaiCanfdBase): - - TX_MSGS = [[0x12A, 0], [0x1A0, 1], [0x1CF, 0], [0x1E0, 0]] - RELAY_MALFUNCTION_ADDRS = {0: (0x12A,)} # LFA - FWD_BLACKLISTED_ADDRS = {2: [0x12A, 0x1E0]} - FWD_BUS_LOOKUP = {0: 2, 2: 0} - - STEER_MSG = "LFA" - BUTTONS_TX_BUS = 2 - SAFETY_PARAM: int - - @classmethod - def setUpClass(cls): - super().setUpClass() - if cls.__name__ in ("TestHyundaiCanfdHDA1", "TestHyundaiCanfdHDA1AltButtons"): - cls.packer = None - cls.safety = None - raise unittest.SkipTest - - def setUp(self): - self.packer = CANPackerPanda("hyundai_canfd") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_HYUNDAI_CANFD, self.SAFETY_PARAM) - self.safety.init_tests() - - -@parameterized_class([ - # Radar SCC, test with long flag to ensure flag is not respected until it is supported - {"GAS_MSG": ("ACCELERATOR_BRAKE_ALT", "ACCELERATOR_PEDAL_PRESSED"), "SCC_BUS": 0, "SAFETY_PARAM": Panda.FLAG_HYUNDAI_LONG}, - {"GAS_MSG": ("ACCELERATOR", "ACCELERATOR_PEDAL"), "SCC_BUS": 0, "SAFETY_PARAM": Panda.FLAG_HYUNDAI_EV_GAS | Panda.FLAG_HYUNDAI_LONG}, - {"GAS_MSG": ("ACCELERATOR_ALT", "ACCELERATOR_PEDAL"), "SCC_BUS": 0, "SAFETY_PARAM": Panda.FLAG_HYUNDAI_HYBRID_GAS | Panda.FLAG_HYUNDAI_LONG}, - # Camera SCC - {"GAS_MSG": ("ACCELERATOR_BRAKE_ALT", "ACCELERATOR_PEDAL_PRESSED"), "SCC_BUS": 2, "SAFETY_PARAM": Panda.FLAG_HYUNDAI_CAMERA_SCC}, - {"GAS_MSG": ("ACCELERATOR", "ACCELERATOR_PEDAL"), "SCC_BUS": 2, "SAFETY_PARAM": Panda.FLAG_HYUNDAI_EV_GAS | Panda.FLAG_HYUNDAI_CAMERA_SCC}, - {"GAS_MSG": ("ACCELERATOR_ALT", "ACCELERATOR_PEDAL"), "SCC_BUS": 2, "SAFETY_PARAM": Panda.FLAG_HYUNDAI_HYBRID_GAS | Panda.FLAG_HYUNDAI_CAMERA_SCC}, -]) -class TestHyundaiCanfdHDA1(TestHyundaiCanfdHDA1Base): - pass - - -@parameterized_class([ - # Radar SCC, test with long flag to ensure flag is not respected until it is supported - {"GAS_MSG": ("ACCELERATOR_BRAKE_ALT", "ACCELERATOR_PEDAL_PRESSED"), "SCC_BUS": 0, "SAFETY_PARAM": Panda.FLAG_HYUNDAI_LONG}, - {"GAS_MSG": ("ACCELERATOR", "ACCELERATOR_PEDAL"), "SCC_BUS": 0, "SAFETY_PARAM": Panda.FLAG_HYUNDAI_EV_GAS | Panda.FLAG_HYUNDAI_LONG}, - {"GAS_MSG": ("ACCELERATOR_ALT", "ACCELERATOR_PEDAL"), "SCC_BUS": 0, "SAFETY_PARAM": Panda.FLAG_HYUNDAI_HYBRID_GAS | Panda.FLAG_HYUNDAI_LONG}, - # Camera SCC - {"GAS_MSG": ("ACCELERATOR_BRAKE_ALT", "ACCELERATOR_PEDAL_PRESSED"), "SCC_BUS": 2, "SAFETY_PARAM": Panda.FLAG_HYUNDAI_CAMERA_SCC}, - {"GAS_MSG": ("ACCELERATOR", "ACCELERATOR_PEDAL"), "SCC_BUS": 2, "SAFETY_PARAM": Panda.FLAG_HYUNDAI_EV_GAS | Panda.FLAG_HYUNDAI_CAMERA_SCC}, - {"GAS_MSG": ("ACCELERATOR_ALT", "ACCELERATOR_PEDAL"), "SCC_BUS": 2, "SAFETY_PARAM": Panda.FLAG_HYUNDAI_HYBRID_GAS | Panda.FLAG_HYUNDAI_CAMERA_SCC}, -]) -class TestHyundaiCanfdHDA1AltButtons(TestHyundaiCanfdHDA1Base): - - SAFETY_PARAM: int - - def setUp(self): - self.packer = CANPackerPanda("hyundai_canfd") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_HYUNDAI_CANFD, Panda.FLAG_HYUNDAI_CANFD_ALT_BUTTONS | self.SAFETY_PARAM) - self.safety.init_tests() - - def _button_msg(self, buttons, main_button=0, bus=1): - values = { - "CRUISE_BUTTONS": buttons, - "ADAPTIVE_CRUISE_MAIN_BTN": main_button, - } - return self.packer.make_can_msg_panda("CRUISE_BUTTONS_ALT", self.PT_BUS, values) - - def test_button_sends(self): - """ - No button send allowed with alt buttons. - """ - for enabled in (True, False): - for btn in range(8): - self.safety.set_controls_allowed(enabled) - self.assertFalse(self._tx(self._button_msg(btn))) - - -class TestHyundaiCanfdHDA2EV(TestHyundaiCanfdBase): - - TX_MSGS = [[0x50, 0], [0x1CF, 1], [0x2A4, 0]] - RELAY_MALFUNCTION_ADDRS = {0: (0x50,)} # LKAS - FWD_BLACKLISTED_ADDRS = {2: [0x50, 0x2a4]} - FWD_BUS_LOOKUP = {0: 2, 2: 0} - - PT_BUS = 1 - SCC_BUS = 1 - STEER_MSG = "LKAS" - GAS_MSG = ("ACCELERATOR", "ACCELERATOR_PEDAL") - - def setUp(self): - self.packer = CANPackerPanda("hyundai_canfd") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_HYUNDAI_CANFD, Panda.FLAG_HYUNDAI_CANFD_HDA2 | Panda.FLAG_HYUNDAI_EV_GAS) - self.safety.init_tests() - - -# TODO: Handle ICE and HEV configurations once we see cars that use the new messages -class TestHyundaiCanfdHDA2EVAltSteering(TestHyundaiCanfdBase): - - TX_MSGS = [[0x110, 0], [0x1CF, 1], [0x362, 0]] - RELAY_MALFUNCTION_ADDRS = {0: (0x110,)} # LKAS_ALT - FWD_BLACKLISTED_ADDRS = {2: [0x110, 0x362]} - FWD_BUS_LOOKUP = {0: 2, 2: 0} - - PT_BUS = 1 - SCC_BUS = 1 - STEER_MSG = "LKAS_ALT" - GAS_MSG = ("ACCELERATOR", "ACCELERATOR_PEDAL") - - def setUp(self): - self.packer = CANPackerPanda("hyundai_canfd") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_HYUNDAI_CANFD, Panda.FLAG_HYUNDAI_CANFD_HDA2 | Panda.FLAG_HYUNDAI_EV_GAS | - Panda.FLAG_HYUNDAI_CANFD_HDA2_ALT_STEERING) - self.safety.init_tests() - - -class TestHyundaiCanfdHDA2LongEV(HyundaiLongitudinalBase, TestHyundaiCanfdHDA2EV): - - TX_MSGS = [[0x50, 0], [0x1CF, 1], [0x2A4, 0], [0x51, 0], [0x730, 1], [0x12a, 1], [0x160, 1], - [0x1e0, 1], [0x1a0, 1], [0x1ea, 1], [0x200, 1], [0x345, 1], [0x1da, 1]] - - RELAY_MALFUNCTION_ADDRS = {0: (0x50,), 1: (0x1a0,)} # LKAS, SCC_CONTROL - - DISABLED_ECU_UDS_MSG = (0x730, 1) - DISABLED_ECU_ACTUATION_MSG = (0x1a0, 1) - - STEER_MSG = "LFA" - GAS_MSG = ("ACCELERATOR", "ACCELERATOR_PEDAL") - STEER_BUS = 1 - - def setUp(self): - self.packer = CANPackerPanda("hyundai_canfd") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_HYUNDAI_CANFD, Panda.FLAG_HYUNDAI_CANFD_HDA2 | Panda.FLAG_HYUNDAI_LONG | Panda.FLAG_HYUNDAI_EV_GAS) - self.safety.init_tests() - - def _accel_msg(self, accel, aeb_req=False, aeb_decel=0): - values = { - "aReqRaw": accel, - "aReqValue": accel, - } - return self.packer.make_can_msg_panda("SCC_CONTROL", 1, values) - - -# Tests HDA1 longitudinal for ICE, hybrid, EV -@parameterized_class([ - # Camera SCC is the only supported configuration for HDA1 longitudinal, TODO: allow radar SCC - {"GAS_MSG": ("ACCELERATOR_BRAKE_ALT", "ACCELERATOR_PEDAL_PRESSED"), "SAFETY_PARAM": Panda.FLAG_HYUNDAI_LONG}, - {"GAS_MSG": ("ACCELERATOR", "ACCELERATOR_PEDAL"), "SAFETY_PARAM": Panda.FLAG_HYUNDAI_LONG | Panda.FLAG_HYUNDAI_EV_GAS}, - {"GAS_MSG": ("ACCELERATOR_ALT", "ACCELERATOR_PEDAL"), "SAFETY_PARAM": Panda.FLAG_HYUNDAI_LONG | Panda.FLAG_HYUNDAI_HYBRID_GAS}, -]) -class TestHyundaiCanfdHDA1Long(HyundaiLongitudinalBase, TestHyundaiCanfdHDA1Base): - - FWD_BLACKLISTED_ADDRS = {2: [0x12a, 0x1e0, 0x1a0]} - - RELAY_MALFUNCTION_ADDRS = {0: (0x12A, 0x1a0)} # LFA, SCC_CONTROL - - DISABLED_ECU_UDS_MSG = (0x730, 1) - DISABLED_ECU_ACTUATION_MSG = (0x1a0, 0) - - STEER_MSG = "LFA" - STEER_BUS = 0 - SCC_BUS = 2 - - @classmethod - def setUpClass(cls): - if cls.__name__ == "TestHyundaiCanfdHDA1Long": - cls.safety = None - raise unittest.SkipTest - - def setUp(self): - self.packer = CANPackerPanda("hyundai_canfd") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_HYUNDAI_CANFD, Panda.FLAG_HYUNDAI_CAMERA_SCC | self.SAFETY_PARAM) - self.safety.init_tests() - - def _accel_msg(self, accel, aeb_req=False, aeb_decel=0): - values = { - "aReqRaw": accel, - "aReqValue": accel, - } - return self.packer.make_can_msg_panda("SCC_CONTROL", 0, values) - - # no knockout - def test_tester_present_allowed(self): - pass - - -if __name__ == "__main__": - unittest.main() diff --git a/panda/tests/safety/test_mazda.py b/panda/tests/safety/test_mazda.py deleted file mode 100644 index 9d2fb89..0000000 --- a/panda/tests/safety/test_mazda.py +++ /dev/null @@ -1,86 +0,0 @@ -#!/usr/bin/env python3 -import unittest -from panda import Panda -from panda.tests.libpanda import libpanda_py -import panda.tests.safety.common as common -from panda.tests.safety.common import CANPackerPanda - - -class TestMazdaSafety(common.PandaCarSafetyTest, common.DriverTorqueSteeringSafetyTest): - - TX_MSGS = [[0x243, 0], [0x09d, 0], [0x440, 0]] - STANDSTILL_THRESHOLD = .1 - RELAY_MALFUNCTION_ADDRS = {0: (0x243,)} - FWD_BLACKLISTED_ADDRS = {2: [0x243, 0x440]} - FWD_BUS_LOOKUP = {0: 2, 2: 0} - - MAX_RATE_UP = 10 - MAX_RATE_DOWN = 25 - MAX_TORQUE = 800 - - MAX_RT_DELTA = 300 - RT_INTERVAL = 250000 - - DRIVER_TORQUE_ALLOWANCE = 15 - DRIVER_TORQUE_FACTOR = 1 - - # Mazda actually does not set any bit when requesting torque - NO_STEER_REQ_BIT = True - - def setUp(self): - self.packer = CANPackerPanda("mazda_2017") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_MAZDA, 0) - self.safety.init_tests() - - def _torque_meas_msg(self, torque): - values = {"STEER_TORQUE_MOTOR": torque} - return self.packer.make_can_msg_panda("STEER_TORQUE", 0, values) - - def _torque_driver_msg(self, torque): - values = {"STEER_TORQUE_SENSOR": torque} - return self.packer.make_can_msg_panda("STEER_TORQUE", 0, values) - - def _torque_cmd_msg(self, torque, steer_req=1): - values = {"LKAS_REQUEST": torque} - return self.packer.make_can_msg_panda("CAM_LKAS", 0, values) - - def _speed_msg(self, speed): - values = {"SPEED": speed} - return self.packer.make_can_msg_panda("ENGINE_DATA", 0, values) - - def _user_brake_msg(self, brake): - values = {"BRAKE_ON": brake} - return self.packer.make_can_msg_panda("PEDALS", 0, values) - - def _user_gas_msg(self, gas): - values = {"PEDAL_GAS": gas} - return self.packer.make_can_msg_panda("ENGINE_DATA", 0, values) - - def _pcm_status_msg(self, enable): - values = {"CRZ_ACTIVE": enable} - return self.packer.make_can_msg_panda("CRZ_CTRL", 0, values) - - def _button_msg(self, resume=False, cancel=False): - values = { - "CAN_OFF": cancel, - "CAN_OFF_INV": (cancel + 1) % 2, - "RES": resume, - "RES_INV": (resume + 1) % 2, - } - return self.packer.make_can_msg_panda("CRZ_BTNS", 0, values) - - def test_buttons(self): - # only cancel allows while controls not allowed - self.safety.set_controls_allowed(0) - self.assertTrue(self._tx(self._button_msg(cancel=True))) - self.assertFalse(self._tx(self._button_msg(resume=True))) - - # do not block resume if we are engaged already - self.safety.set_controls_allowed(1) - self.assertTrue(self._tx(self._button_msg(cancel=True))) - self.assertTrue(self._tx(self._button_msg(resume=True))) - - -if __name__ == "__main__": - unittest.main() diff --git a/panda/tests/safety/test_nissan.py b/panda/tests/safety/test_nissan.py deleted file mode 100644 index 4c83ca3..0000000 --- a/panda/tests/safety/test_nissan.py +++ /dev/null @@ -1,117 +0,0 @@ -#!/usr/bin/env python3 -import unittest -from panda import Panda -from panda.tests.libpanda import libpanda_py -import panda.tests.safety.common as common -from panda.tests.safety.common import CANPackerPanda - - -class TestNissanSafety(common.PandaCarSafetyTest, common.AngleSteeringSafetyTest): - - TX_MSGS = [[0x169, 0], [0x2b1, 0], [0x4cc, 0], [0x20b, 2], [0x280, 2]] - STANDSTILL_THRESHOLD = 0 - GAS_PRESSED_THRESHOLD = 3 - RELAY_MALFUNCTION_ADDRS = {0: (0x169,)} - FWD_BLACKLISTED_ADDRS = {0: [0x280], 2: [0x169, 0x2b1, 0x4cc]} - FWD_BUS_LOOKUP = {0: 2, 2: 0} - - EPS_BUS = 0 - CRUISE_BUS = 2 - - # Angle control limits - DEG_TO_CAN = 100 - - ANGLE_RATE_BP = [0., 5., 15.] - ANGLE_RATE_UP = [5., .8, .15] # windup limit - ANGLE_RATE_DOWN = [5., 3.5, .4] # unwind limit - - def setUp(self): - self.packer = CANPackerPanda("nissan_x_trail_2017_generated") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_NISSAN, 0) - self.safety.init_tests() - - def _angle_cmd_msg(self, angle: float, enabled: bool): - values = {"DESIRED_ANGLE": angle, "LKA_ACTIVE": 1 if enabled else 0} - return self.packer.make_can_msg_panda("LKAS", 0, values) - - def _angle_meas_msg(self, angle: float): - values = {"STEER_ANGLE": angle} - return self.packer.make_can_msg_panda("STEER_ANGLE_SENSOR", self.EPS_BUS, values) - - def _pcm_status_msg(self, enable): - values = {"CRUISE_ENABLED": enable} - return self.packer.make_can_msg_panda("CRUISE_STATE", self.CRUISE_BUS, values) - - def _speed_msg(self, speed): - values = {"WHEEL_SPEED_%s" % s: speed * 3.6 for s in ["RR", "RL"]} - return self.packer.make_can_msg_panda("WHEEL_SPEEDS_REAR", self.EPS_BUS, values) - - def _user_brake_msg(self, brake): - values = {"USER_BRAKE_PRESSED": brake} - return self.packer.make_can_msg_panda("DOORS_LIGHTS", self.EPS_BUS, values) - - def _user_gas_msg(self, gas): - values = {"GAS_PEDAL": gas} - return self.packer.make_can_msg_panda("GAS_PEDAL", self.EPS_BUS, values) - - def _acc_button_cmd(self, cancel=0, propilot=0, flw_dist=0, _set=0, res=0): - no_button = not any([cancel, propilot, flw_dist, _set, res]) - values = {"CANCEL_BUTTON": cancel, "PROPILOT_BUTTON": propilot, - "FOLLOW_DISTANCE_BUTTON": flw_dist, "SET_BUTTON": _set, - "RES_BUTTON": res, "NO_BUTTON_PRESSED": no_button} - return self.packer.make_can_msg_panda("CRUISE_THROTTLE", 2, values) - - def test_acc_buttons(self): - btns = [ - ("cancel", True), - ("propilot", False), - ("flw_dist", False), - ("_set", False), - ("res", False), - (None, False), - ] - for controls_allowed in (True, False): - for btn, should_tx in btns: - self.safety.set_controls_allowed(controls_allowed) - args = {} if btn is None else {btn: 1} - tx = self._tx(self._acc_button_cmd(**args)) - self.assertEqual(tx, should_tx) - - -class TestNissanSafetyAltEpsBus(TestNissanSafety): - """Altima uses different buses""" - - EPS_BUS = 1 - CRUISE_BUS = 1 - - def setUp(self): - self.packer = CANPackerPanda("nissan_x_trail_2017_generated") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_NISSAN, Panda.FLAG_NISSAN_ALT_EPS_BUS) - self.safety.init_tests() - - -class TestNissanLeafSafety(TestNissanSafety): - - def setUp(self): - self.packer = CANPackerPanda("nissan_leaf_2018_generated") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_NISSAN, 0) - self.safety.init_tests() - - def _user_brake_msg(self, brake): - values = {"USER_BRAKE_PRESSED": brake} - return self.packer.make_can_msg_panda("CRUISE_THROTTLE", 0, values) - - def _user_gas_msg(self, gas): - values = {"GAS_PEDAL": gas} - return self.packer.make_can_msg_panda("CRUISE_THROTTLE", 0, values) - - # TODO: leaf should use its own safety param - def test_acc_buttons(self): - pass - - -if __name__ == "__main__": - unittest.main() diff --git a/panda/tests/safety/test_subaru.py b/panda/tests/safety/test_subaru.py deleted file mode 100644 index 61d3d91..0000000 --- a/panda/tests/safety/test_subaru.py +++ /dev/null @@ -1,228 +0,0 @@ -#!/usr/bin/env python3 -import enum -import unittest -from panda import Panda -from panda.tests.libpanda import libpanda_py -import panda.tests.safety.common as common -from panda.tests.safety.common import CANPackerPanda -from functools import partial - -class SubaruMsg(enum.IntEnum): - Brake_Status = 0x13c - CruiseControl = 0x240 - Throttle = 0x40 - Steering_Torque = 0x119 - Wheel_Speeds = 0x13a - ES_LKAS = 0x122 - ES_LKAS_ANGLE = 0x124 - ES_Brake = 0x220 - ES_Distance = 0x221 - ES_Status = 0x222 - ES_DashStatus = 0x321 - ES_LKAS_State = 0x322 - ES_Infotainment = 0x323 - ES_UDS_Request = 0x787 - ES_HighBeamAssist = 0x121 - ES_STATIC_1 = 0x22a - ES_STATIC_2 = 0x325 - - -SUBARU_MAIN_BUS = 0 -SUBARU_ALT_BUS = 1 -SUBARU_CAM_BUS = 2 - - -def lkas_tx_msgs(alt_bus, lkas_msg=SubaruMsg.ES_LKAS): - return [[lkas_msg, SUBARU_MAIN_BUS], - [SubaruMsg.ES_Distance, alt_bus], - [SubaruMsg.ES_DashStatus, SUBARU_MAIN_BUS], - [SubaruMsg.ES_LKAS_State, SUBARU_MAIN_BUS], - [SubaruMsg.ES_Infotainment, SUBARU_MAIN_BUS]] - -def long_tx_msgs(alt_bus): - return [[SubaruMsg.ES_Brake, alt_bus], - [SubaruMsg.ES_Status, alt_bus]] - -def gen2_long_additional_tx_msgs(): - return [[SubaruMsg.ES_UDS_Request, SUBARU_CAM_BUS], - [SubaruMsg.ES_HighBeamAssist, SUBARU_MAIN_BUS], - [SubaruMsg.ES_STATIC_1, SUBARU_MAIN_BUS], - [SubaruMsg.ES_STATIC_2, SUBARU_MAIN_BUS]] - -def fwd_blacklisted_addr(lkas_msg=SubaruMsg.ES_LKAS): - return {SUBARU_CAM_BUS: [lkas_msg, SubaruMsg.ES_DashStatus, SubaruMsg.ES_LKAS_State, SubaruMsg.ES_Infotainment]} - -class TestSubaruSafetyBase(common.PandaCarSafetyTest): - FLAGS = 0 - STANDSTILL_THRESHOLD = 0 # kph - RELAY_MALFUNCTION_ADDRS = {SUBARU_MAIN_BUS: (SubaruMsg.ES_LKAS,)} - FWD_BUS_LOOKUP = {SUBARU_MAIN_BUS: SUBARU_CAM_BUS, SUBARU_CAM_BUS: SUBARU_MAIN_BUS} - FWD_BLACKLISTED_ADDRS = fwd_blacklisted_addr() - - MAX_RT_DELTA = 940 - RT_INTERVAL = 250000 - - DRIVER_TORQUE_ALLOWANCE = 60 - DRIVER_TORQUE_FACTOR = 50 - - ALT_MAIN_BUS = SUBARU_MAIN_BUS - ALT_CAM_BUS = SUBARU_CAM_BUS - - DEG_TO_CAN = 100 - - INACTIVE_GAS = 1818 - - def setUp(self): - self.packer = CANPackerPanda("subaru_global_2017_generated") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_SUBARU, self.FLAGS) - self.safety.init_tests() - - def _set_prev_torque(self, t): - self.safety.set_desired_torque_last(t) - self.safety.set_rt_torque_last(t) - - def _torque_driver_msg(self, torque): - values = {"Steer_Torque_Sensor": torque} - return self.packer.make_can_msg_panda("Steering_Torque", 0, values) - - def _speed_msg(self, speed): - values = {s: speed for s in ["FR", "FL", "RR", "RL"]} - return self.packer.make_can_msg_panda("Wheel_Speeds", self.ALT_MAIN_BUS, values) - - def _angle_meas_msg(self, angle): - values = {"Steering_Angle": angle} - return self.packer.make_can_msg_panda("Steering_Torque", 0, values) - - def _user_brake_msg(self, brake): - values = {"Brake": brake} - return self.packer.make_can_msg_panda("Brake_Status", self.ALT_MAIN_BUS, values) - - def _user_gas_msg(self, gas): - values = {"Throttle_Pedal": gas} - return self.packer.make_can_msg_panda("Throttle", 0, values) - - def _pcm_status_msg(self, enable): - values = {"Cruise_Activated": enable} - return self.packer.make_can_msg_panda("CruiseControl", self.ALT_MAIN_BUS, values) - - -class TestSubaruStockLongitudinalSafetyBase(TestSubaruSafetyBase): - def _cancel_msg(self, cancel, cruise_throttle=0): - values = {"Cruise_Cancel": cancel, "Cruise_Throttle": cruise_throttle} - return self.packer.make_can_msg_panda("ES_Distance", self.ALT_MAIN_BUS, values) - - def test_cancel_message(self): - # test that we can only send the cancel message (ES_Distance) with inactive throttle (1818) and Cruise_Cancel=1 - for cancel in [True, False]: - self._generic_limit_safety_check(partial(self._cancel_msg, cancel), self.INACTIVE_GAS, self.INACTIVE_GAS, 0, 2**12, 1, self.INACTIVE_GAS, cancel) - - -class TestSubaruLongitudinalSafetyBase(TestSubaruSafetyBase, common.LongitudinalGasBrakeSafetyTest): - MIN_GAS = 808 - MAX_GAS = 3400 - INACTIVE_GAS = 1818 - MAX_POSSIBLE_GAS = 2**13 - - MIN_BRAKE = 0 - MAX_BRAKE = 600 - MAX_POSSIBLE_BRAKE = 2**16 - - MIN_RPM = 0 - MAX_RPM = 2400 - MAX_POSSIBLE_RPM = 2**13 - - FWD_BLACKLISTED_ADDRS = {2: [SubaruMsg.ES_LKAS, SubaruMsg.ES_Brake, SubaruMsg.ES_Distance, - SubaruMsg.ES_Status, SubaruMsg.ES_DashStatus, - SubaruMsg.ES_LKAS_State, SubaruMsg.ES_Infotainment]} - - def test_rpm_safety_check(self): - self._generic_limit_safety_check(self._send_rpm_msg, self.MIN_RPM, self.MAX_RPM, 0, self.MAX_POSSIBLE_RPM, 1) - - def _send_brake_msg(self, brake): - values = {"Brake_Pressure": brake} - return self.packer.make_can_msg_panda("ES_Brake", self.ALT_MAIN_BUS, values) - - def _send_gas_msg(self, gas): - values = {"Cruise_Throttle": gas} - return self.packer.make_can_msg_panda("ES_Distance", self.ALT_MAIN_BUS, values) - - def _send_rpm_msg(self, rpm): - values = {"Cruise_RPM": rpm} - return self.packer.make_can_msg_panda("ES_Status", self.ALT_MAIN_BUS, values) - - -class TestSubaruTorqueSafetyBase(TestSubaruSafetyBase, common.DriverTorqueSteeringSafetyTest, common.SteerRequestCutSafetyTest): - MAX_RATE_UP = 50 - MAX_RATE_DOWN = 70 - MAX_TORQUE = 2047 - - # Safety around steering req bit - MIN_VALID_STEERING_FRAMES = 7 - MAX_INVALID_STEERING_FRAMES = 1 - MIN_VALID_STEERING_RT_INTERVAL = 144000 - - def _torque_cmd_msg(self, torque, steer_req=1): - values = {"LKAS_Output": torque, "LKAS_Request": steer_req} - return self.packer.make_can_msg_panda("ES_LKAS", SUBARU_MAIN_BUS, values) - - -class TestSubaruGen1TorqueStockLongitudinalSafety(TestSubaruStockLongitudinalSafetyBase, TestSubaruTorqueSafetyBase): - FLAGS = 0 - TX_MSGS = lkas_tx_msgs(SUBARU_MAIN_BUS) - - -class TestSubaruGen2TorqueSafetyBase(TestSubaruTorqueSafetyBase): - ALT_MAIN_BUS = SUBARU_ALT_BUS - ALT_CAM_BUS = SUBARU_ALT_BUS - - MAX_RATE_UP = 40 - MAX_RATE_DOWN = 40 - MAX_TORQUE = 1000 - - -class TestSubaruGen2TorqueStockLongitudinalSafety(TestSubaruStockLongitudinalSafetyBase, TestSubaruGen2TorqueSafetyBase): - FLAGS = Panda.FLAG_SUBARU_GEN2 - TX_MSGS = lkas_tx_msgs(SUBARU_ALT_BUS) - - -class TestSubaruGen1LongitudinalSafety(TestSubaruLongitudinalSafetyBase, TestSubaruTorqueSafetyBase): - FLAGS = Panda.FLAG_SUBARU_LONG - TX_MSGS = lkas_tx_msgs(SUBARU_MAIN_BUS) + long_tx_msgs(SUBARU_MAIN_BUS) - - -class TestSubaruGen2LongitudinalSafety(TestSubaruLongitudinalSafetyBase, TestSubaruGen2TorqueSafetyBase): - FLAGS = Panda.FLAG_SUBARU_LONG | Panda.FLAG_SUBARU_GEN2 - TX_MSGS = lkas_tx_msgs(SUBARU_ALT_BUS) + long_tx_msgs(SUBARU_ALT_BUS) + gen2_long_additional_tx_msgs() - - def _rdbi_msg(self, did: int): - return b'\x03\x22' + did.to_bytes(2) + b'\x00\x00\x00\x00' - - def _es_uds_msg(self, msg: bytes): - return libpanda_py.make_CANPacket(SubaruMsg.ES_UDS_Request, 2, msg) - - def test_es_uds_message(self): - tester_present = b'\x02\x3E\x80\x00\x00\x00\x00\x00' - not_tester_present = b"\x03\xAA\xAA\x00\x00\x00\x00\x00" - - button_did = 0x1130 - - # Tester present is allowed for gen2 long to keep eyesight disabled - self.assertTrue(self._tx(self._es_uds_msg(tester_present))) - - # Non-Tester present is not allowed - self.assertFalse(self._tx(self._es_uds_msg(not_tester_present))) - - # Only button_did is allowed to be read via UDS - for did in range(0xFFFF): - should_tx = (did == button_did) - self.assertEqual(self._tx(self._es_uds_msg(self._rdbi_msg(did))), should_tx) - - # any other msg is not allowed - for sid in range(0xFF): - msg = b'\x03' + sid.to_bytes(1) + b'\x00' * 6 - self.assertFalse(self._tx(self._es_uds_msg(msg))) - - -if __name__ == "__main__": - unittest.main() diff --git a/panda/tests/safety/test_subaru_preglobal.py b/panda/tests/safety/test_subaru_preglobal.py deleted file mode 100644 index 06c4cde..0000000 --- a/panda/tests/safety/test_subaru_preglobal.py +++ /dev/null @@ -1,70 +0,0 @@ -#!/usr/bin/env python3 -import unittest -from panda import Panda -from panda.tests.libpanda import libpanda_py -import panda.tests.safety.common as common -from panda.tests.safety.common import CANPackerPanda - - -class TestSubaruPreglobalSafety(common.PandaCarSafetyTest, common.DriverTorqueSteeringSafetyTest): - FLAGS = 0 - DBC = "subaru_outback_2015_generated" - TX_MSGS = [[0x161, 0], [0x164, 0]] - STANDSTILL_THRESHOLD = 0 # kph - RELAY_MALFUNCTION_ADDRS = {0: (0x164,)} - FWD_BLACKLISTED_ADDRS = {2: [0x161, 0x164]} - FWD_BUS_LOOKUP = {0: 2, 2: 0} - - MAX_RATE_UP = 50 - MAX_RATE_DOWN = 70 - MAX_TORQUE = 2047 - - MAX_RT_DELTA = 940 - RT_INTERVAL = 250000 - - DRIVER_TORQUE_ALLOWANCE = 75 - DRIVER_TORQUE_FACTOR = 10 - - def setUp(self): - self.packer = CANPackerPanda(self.DBC) - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_SUBARU_PREGLOBAL, self.FLAGS) - self.safety.init_tests() - - def _set_prev_torque(self, t): - self.safety.set_desired_torque_last(t) - self.safety.set_rt_torque_last(t) - - def _torque_driver_msg(self, torque): - values = {"Steer_Torque_Sensor": torque} - return self.packer.make_can_msg_panda("Steering_Torque", 0, values) - - def _speed_msg(self, speed): - # subaru safety doesn't use the scaled value, so undo the scaling - values = {s: speed*0.0592 for s in ["FR", "FL", "RR", "RL"]} - return self.packer.make_can_msg_panda("Wheel_Speeds", 0, values) - - def _user_brake_msg(self, brake): - values = {"Brake_Pedal": brake} - return self.packer.make_can_msg_panda("Brake_Pedal", 0, values) - - def _torque_cmd_msg(self, torque, steer_req=1): - values = {"LKAS_Command": torque, "LKAS_Active": steer_req} - return self.packer.make_can_msg_panda("ES_LKAS", 0, values) - - def _user_gas_msg(self, gas): - values = {"Throttle_Pedal": gas} - return self.packer.make_can_msg_panda("Throttle", 0, values) - - def _pcm_status_msg(self, enable): - values = {"Cruise_Activated": enable} - return self.packer.make_can_msg_panda("CruiseControl", 0, values) - - -class TestSubaruPreglobalReversedDriverTorqueSafety(TestSubaruPreglobalSafety): - FLAGS = Panda.FLAG_SUBARU_PREGLOBAL_REVERSED_DRIVER_TORQUE - DBC = "subaru_outback_2019_generated" - - -if __name__ == "__main__": - unittest.main() diff --git a/panda/tests/safety/test_tesla.py b/panda/tests/safety/test_tesla.py deleted file mode 100644 index 9461ff6..0000000 --- a/panda/tests/safety/test_tesla.py +++ /dev/null @@ -1,185 +0,0 @@ -#!/usr/bin/env python3 -import unittest -import numpy as np -from panda import Panda -import panda.tests.safety.common as common -from panda.tests.libpanda import libpanda_py -from panda.tests.safety.common import CANPackerPanda - -MAX_ACCEL = 2.0 -MIN_ACCEL = -3.5 - - -class CONTROL_LEVER_STATE: - DN_1ST = 32 - UP_1ST = 16 - DN_2ND = 8 - UP_2ND = 4 - RWD = 2 - FWD = 1 - IDLE = 0 - - -class TestTeslaSafety(common.PandaCarSafetyTest): - STANDSTILL_THRESHOLD = 0 - GAS_PRESSED_THRESHOLD = 3 - FWD_BUS_LOOKUP = {0: 2, 2: 0} - - def setUp(self): - self.packer = None - raise unittest.SkipTest - - def _speed_msg(self, speed): - values = {"DI_vehicleSpeed": speed / 0.447} - return self.packer.make_can_msg_panda("DI_torque2", 0, values) - - def _user_brake_msg(self, brake): - values = {"driverBrakeStatus": 2 if brake else 1} - return self.packer.make_can_msg_panda("BrakeMessage", 0, values) - - def _user_gas_msg(self, gas): - values = {"DI_pedalPos": gas} - return self.packer.make_can_msg_panda("DI_torque1", 0, values) - - def _control_lever_cmd(self, command): - values = {"SpdCtrlLvr_Stat": command} - return self.packer.make_can_msg_panda("STW_ACTN_RQ", 0, values) - - def _pcm_status_msg(self, enable): - values = {"DI_cruiseState": 2 if enable else 0} - return self.packer.make_can_msg_panda("DI_state", 0, values) - - def _long_control_msg(self, set_speed, acc_val=0, jerk_limits=(0, 0), accel_limits=(0, 0), aeb_event=0, bus=0): - values = { - "DAS_setSpeed": set_speed, - "DAS_accState": acc_val, - "DAS_aebEvent": aeb_event, - "DAS_jerkMin": jerk_limits[0], - "DAS_jerkMax": jerk_limits[1], - "DAS_accelMin": accel_limits[0], - "DAS_accelMax": accel_limits[1], - } - return self.packer.make_can_msg_panda("DAS_control", bus, values) - - -class TestTeslaSteeringSafety(TestTeslaSafety, common.AngleSteeringSafetyTest): - TX_MSGS = [[0x488, 0], [0x45, 0], [0x45, 2]] - RELAY_MALFUNCTION_ADDRS = {0: (0x488,)} - FWD_BLACKLISTED_ADDRS = {2: [0x488]} - - # Angle control limits - DEG_TO_CAN = 10 - - ANGLE_RATE_BP = [0., 5., 15.] - ANGLE_RATE_UP = [10., 1.6, .3] # windup limit - ANGLE_RATE_DOWN = [10., 7.0, .8] # unwind limit - - def setUp(self): - self.packer = CANPackerPanda("tesla_can") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_TESLA, 0) - self.safety.init_tests() - - def _angle_cmd_msg(self, angle: float, enabled: bool): - values = {"DAS_steeringAngleRequest": angle, "DAS_steeringControlType": 1 if enabled else 0} - return self.packer.make_can_msg_panda("DAS_steeringControl", 0, values) - - def _angle_meas_msg(self, angle: float): - values = {"EPAS_internalSAS": angle} - return self.packer.make_can_msg_panda("EPAS_sysStatus", 0, values) - - def test_acc_buttons(self): - """ - FWD (cancel) always allowed. - """ - btns = [ - (CONTROL_LEVER_STATE.FWD, True), - (CONTROL_LEVER_STATE.RWD, False), - (CONTROL_LEVER_STATE.UP_1ST, False), - (CONTROL_LEVER_STATE.UP_2ND, False), - (CONTROL_LEVER_STATE.DN_1ST, False), - (CONTROL_LEVER_STATE.DN_2ND, False), - (CONTROL_LEVER_STATE.IDLE, False), - ] - for btn, should_tx in btns: - for controls_allowed in (True, False): - self.safety.set_controls_allowed(controls_allowed) - tx = self._tx(self._control_lever_cmd(btn)) - self.assertEqual(tx, should_tx) - - -class TestTeslaRavenSteeringSafety(TestTeslaSteeringSafety): - def setUp(self): - self.packer = CANPackerPanda("tesla_can") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_TESLA, Panda.FLAG_TESLA_RAVEN) - self.safety.init_tests() - - def _angle_meas_msg(self, angle: float): - values = {"EPAS_internalSAS": angle} - return self.packer.make_can_msg_panda("EPAS3P_sysStatus", 2, values) - -class TestTeslaLongitudinalSafety(TestTeslaSafety): - def setUp(self): - raise unittest.SkipTest - - def test_no_aeb(self): - for aeb_event in range(4): - self.assertEqual(self._tx(self._long_control_msg(10, aeb_event=aeb_event)), aeb_event == 0) - - def test_stock_aeb_passthrough(self): - no_aeb_msg = self._long_control_msg(10, aeb_event=0) - no_aeb_msg_cam = self._long_control_msg(10, aeb_event=0, bus=2) - aeb_msg_cam = self._long_control_msg(10, aeb_event=1, bus=2) - - # stock system sends no AEB -> no forwarding, and OP is allowed to TX - self.assertEqual(1, self._rx(no_aeb_msg_cam)) - self.assertEqual(-1, self.safety.safety_fwd_hook(2, no_aeb_msg_cam.addr)) - self.assertEqual(True, self._tx(no_aeb_msg)) - - # stock system sends AEB -> forwarding, and OP is not allowed to TX - self.assertEqual(1, self._rx(aeb_msg_cam)) - self.assertEqual(0, self.safety.safety_fwd_hook(2, aeb_msg_cam.addr)) - self.assertEqual(False, self._tx(no_aeb_msg)) - - def test_acc_accel_limits(self): - for controls_allowed in [True, False]: - self.safety.set_controls_allowed(controls_allowed) - for min_accel in np.arange(MIN_ACCEL - 1, MAX_ACCEL + 1, 0.1): - for max_accel in np.arange(MIN_ACCEL - 1, MAX_ACCEL + 1, 0.1): - # floats might not hit exact boundary conditions without rounding - min_accel = round(min_accel, 2) - max_accel = round(max_accel, 2) - if controls_allowed: - send = (MIN_ACCEL <= min_accel <= MAX_ACCEL) and (MIN_ACCEL <= max_accel <= MAX_ACCEL) - else: - send = np.all(np.isclose([min_accel, max_accel], 0, atol=0.0001)) - self.assertEqual(send, self._tx(self._long_control_msg(10, acc_val=4, accel_limits=[min_accel, max_accel]))) - - -class TestTeslaChassisLongitudinalSafety(TestTeslaLongitudinalSafety): - TX_MSGS = [[0x488, 0], [0x45, 0], [0x45, 2], [0x2B9, 0]] - RELAY_MALFUNCTION_ADDRS = {0: (0x488,)} - FWD_BLACKLISTED_ADDRS = {2: [0x2B9, 0x488]} - - def setUp(self): - self.packer = CANPackerPanda("tesla_can") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_TESLA, Panda.FLAG_TESLA_LONG_CONTROL) - self.safety.init_tests() - - -class TestTeslaPTLongitudinalSafety(TestTeslaLongitudinalSafety): - TX_MSGS = [[0x2BF, 0]] - RELAY_MALFUNCTION_ADDRS = {0: (0x2BF,)} - FWD_BLACKLISTED_ADDRS = {2: [0x2BF]} - - def setUp(self): - self.packer = CANPackerPanda("tesla_powertrain") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_TESLA, Panda.FLAG_TESLA_LONG_CONTROL | Panda.FLAG_TESLA_POWERTRAIN) - self.safety.init_tests() - - -if __name__ == "__main__": - unittest.main() diff --git a/panda/tests/safety/test_toyota.py b/panda/tests/safety/test_toyota.py deleted file mode 100644 index 0743c67..0000000 --- a/panda/tests/safety/test_toyota.py +++ /dev/null @@ -1,367 +0,0 @@ -#!/usr/bin/env python3 -import numpy as np -import random -import unittest -import itertools - -from panda import Panda -from panda.tests.libpanda import libpanda_py -import panda.tests.safety.common as common -from panda.tests.safety.common import CANPackerPanda - -TOYOTA_COMMON_TX_MSGS = [[0x2E4, 0], [0x191, 0], [0x412, 0], [0x343, 0], [0x1D2, 0]] # LKAS + LTA + ACC & PCM cancel cmds -TOYOTA_COMMON_LONG_TX_MSGS = [[0x283, 0], [0x2E6, 0], [0x2E7, 0], [0x33E, 0], [0x344, 0], [0x365, 0], [0x366, 0], [0x4CB, 0], # DSU bus 0 - [0x128, 1], [0x141, 1], [0x160, 1], [0x161, 1], [0x470, 1], # DSU bus 1 - [0x411, 0], # PCS_HUD - [0x750, 0]] # radar diagnostic address -GAS_INTERCEPTOR_TX_MSGS = [[0x200, 0]] - - -class TestToyotaSafetyBase(common.PandaCarSafetyTest, common.LongitudinalAccelSafetyTest): - - TX_MSGS = TOYOTA_COMMON_TX_MSGS + TOYOTA_COMMON_LONG_TX_MSGS - STANDSTILL_THRESHOLD = 0 # kph - RELAY_MALFUNCTION_ADDRS = {0: (0x2E4, 0x343)} - FWD_BLACKLISTED_ADDRS = {2: [0x2E4, 0x412, 0x191, 0x343]} - FWD_BUS_LOOKUP = {0: 2, 2: 0} - EPS_SCALE = 73 - - packer: CANPackerPanda - safety: libpanda_py.Panda - - @classmethod - def setUpClass(cls): - if cls.__name__.endswith("Base"): - cls.packer = None - cls.safety = None - raise unittest.SkipTest - - def _torque_meas_msg(self, torque: int, driver_torque: int | None = None): - values = {"STEER_TORQUE_EPS": (torque / self.EPS_SCALE) * 100.} - if driver_torque is not None: - values["STEER_TORQUE_DRIVER"] = driver_torque - return self.packer.make_can_msg_panda("STEER_TORQUE_SENSOR", 0, values) - - # Both torque and angle safety modes test with each other's steering commands - def _torque_cmd_msg(self, torque, steer_req=1): - values = {"STEER_TORQUE_CMD": torque, "STEER_REQUEST": steer_req} - return self.packer.make_can_msg_panda("STEERING_LKA", 0, values) - - def _angle_meas_msg(self, angle: float, steer_angle_initializing: bool = False): - # This creates a steering torque angle message. Not set on all platforms, - # relative to init angle on some older TSS2 platforms. Only to be used with LTA - values = {"STEER_ANGLE": angle, "STEER_ANGLE_INITIALIZING": int(steer_angle_initializing)} - return self.packer.make_can_msg_panda("STEER_TORQUE_SENSOR", 0, values) - - def _angle_cmd_msg(self, angle: float, enabled: bool): - return self._lta_msg(int(enabled), int(enabled), angle, torque_wind_down=100 if enabled else 0) - - def _lta_msg(self, req, req2, angle_cmd, torque_wind_down=100): - values = {"STEER_REQUEST": req, "STEER_REQUEST_2": req2, "STEER_ANGLE_CMD": angle_cmd, "TORQUE_WIND_DOWN": torque_wind_down} - return self.packer.make_can_msg_panda("STEERING_LTA", 0, values) - - def _accel_msg(self, accel, cancel_req=0): - values = {"ACCEL_CMD": accel, "CANCEL_REQ": cancel_req} - return self.packer.make_can_msg_panda("ACC_CONTROL", 0, values) - - def _speed_msg(self, speed): - values = {("WHEEL_SPEED_%s" % n): speed * 3.6 for n in ["FR", "FL", "RR", "RL"]} - return self.packer.make_can_msg_panda("WHEEL_SPEEDS", 0, values) - - def _user_brake_msg(self, brake): - values = {"BRAKE_PRESSED": brake} - return self.packer.make_can_msg_panda("BRAKE_MODULE", 0, values) - - def _user_gas_msg(self, gas): - cruise_active = self.safety.get_controls_allowed() - values = {"GAS_RELEASED": not gas, "CRUISE_ACTIVE": cruise_active} - return self.packer.make_can_msg_panda("PCM_CRUISE", 0, values) - - def _pcm_status_msg(self, enable): - values = {"CRUISE_ACTIVE": enable} - return self.packer.make_can_msg_panda("PCM_CRUISE", 0, values) - - def test_diagnostics(self, stock_longitudinal: bool = False): - for should_tx, msg in ((False, b"\x6D\x02\x3E\x00\x00\x00\x00\x00"), # fwdCamera tester present - (False, b"\x0F\x03\xAA\xAA\x00\x00\x00\x00"), # non-tester present - (True, b"\x0F\x02\x3E\x00\x00\x00\x00\x00")): - tester_present = libpanda_py.make_CANPacket(0x750, 0, msg) - self.assertEqual(should_tx and not stock_longitudinal, self._tx(tester_present)) - - def test_block_aeb(self, stock_longitudinal: bool = False): - for controls_allowed in (True, False): - for bad in (True, False): - for _ in range(10): - self.safety.set_controls_allowed(controls_allowed) - dat = [random.randint(1, 255) for _ in range(7)] - if not bad: - dat = [0]*6 + dat[-1:] - msg = libpanda_py.make_CANPacket(0x283, 0, bytes(dat)) - self.assertEqual(not bad and not stock_longitudinal, self._tx(msg)) - - # Only allow LTA msgs with no actuation - def test_lta_steer_cmd(self): - for engaged, req, req2, torque_wind_down, angle in itertools.product([True, False], - [0, 1], [0, 1], - [0, 50, 100], - np.linspace(-20, 20, 5)): - self.safety.set_controls_allowed(engaged) - - should_tx = not req and not req2 and angle == 0 and torque_wind_down == 0 - self.assertEqual(should_tx, self._tx(self._lta_msg(req, req2, angle, torque_wind_down))) - - def test_rx_hook(self): - # checksum checks - for msg in ["trq", "pcm"]: - self.safety.set_controls_allowed(1) - if msg == "trq": - to_push = self._torque_meas_msg(0) - if msg == "pcm": - to_push = self._pcm_status_msg(True) - self.assertTrue(self._rx(to_push)) - to_push[0].data[4] = 0 - to_push[0].data[5] = 0 - to_push[0].data[6] = 0 - to_push[0].data[7] = 0 - self.assertFalse(self._rx(to_push)) - self.assertFalse(self.safety.get_controls_allowed()) - - -class TestToyotaSafetyGasInterceptorBase(common.GasInterceptorSafetyTest, TestToyotaSafetyBase): - - TX_MSGS = TOYOTA_COMMON_TX_MSGS + TOYOTA_COMMON_LONG_TX_MSGS + GAS_INTERCEPTOR_TX_MSGS - INTERCEPTOR_THRESHOLD = 805 - - def setUp(self): - super().setUp() - self.safety.set_safety_hooks(Panda.SAFETY_TOYOTA, self.safety.get_current_safety_param() | - Panda.FLAG_TOYOTA_GAS_INTERCEPTOR) - self.safety.init_tests() - - def test_stock_longitudinal(self): - # If stock longitudinal is set, the gas interceptor safety param should not be respected - self.safety.set_safety_hooks(Panda.SAFETY_TOYOTA, self.safety.get_current_safety_param() | - Panda.FLAG_TOYOTA_STOCK_LONGITUDINAL) - self.safety.init_tests() - - # Spot check a few gas interceptor tests: (1) reading interceptor, - # (2) behavior around interceptor, and (3) txing interceptor msgs - for test in (self.test_prev_gas_interceptor, self.test_disengage_on_gas_interceptor, - self.test_gas_interceptor_safety_check): - with self.subTest(test=test.__name__): - with self.assertRaises(AssertionError): - test() - - -class TestToyotaSafetyTorque(TestToyotaSafetyBase, common.MotorTorqueSteeringSafetyTest, common.SteerRequestCutSafetyTest): - - MAX_RATE_UP = 15 - MAX_RATE_DOWN = 25 - MAX_TORQUE = 1500 - MAX_RT_DELTA = 450 - RT_INTERVAL = 250000 - MAX_TORQUE_ERROR = 350 - TORQUE_MEAS_TOLERANCE = 1 # toyota safety adds one to be conservative for rounding - - # Safety around steering req bit - MIN_VALID_STEERING_FRAMES = 18 - MAX_INVALID_STEERING_FRAMES = 1 - MIN_VALID_STEERING_RT_INTERVAL = 170000 # a ~10% buffer, can send steer up to 110Hz - - def setUp(self): - self.packer = CANPackerPanda("toyota_nodsu_pt_generated") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_TOYOTA, self.EPS_SCALE) - self.safety.init_tests() - - -class TestToyotaSafetyTorqueGasInterceptor(TestToyotaSafetyGasInterceptorBase, TestToyotaSafetyTorque): - pass - - -class TestToyotaSafetyAngle(TestToyotaSafetyBase, common.AngleSteeringSafetyTest): - - # Angle control limits - DEG_TO_CAN = 17.452007 # 1 / 0.0573 deg to can - - ANGLE_RATE_BP = [5., 25., 25.] - ANGLE_RATE_UP = [0.3, 0.15, 0.15] # windup limit - ANGLE_RATE_DOWN = [0.36, 0.26, 0.26] # unwind limit - - MAX_LTA_ANGLE = 94.9461 # PCS faults if commanding above this, deg - MAX_MEAS_TORQUE = 1500 # max allowed measured EPS torque before wind down - MAX_LTA_DRIVER_TORQUE = 150 # max allowed driver torque before wind down - - def setUp(self): - self.packer = CANPackerPanda("toyota_nodsu_pt_generated") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_TOYOTA, self.EPS_SCALE | Panda.FLAG_TOYOTA_LTA) - self.safety.init_tests() - - # Only allow LKA msgs with no actuation - def test_lka_steer_cmd(self): - for engaged, steer_req, torque in itertools.product([True, False], - [0, 1], - np.linspace(-1500, 1500, 7)): - self.safety.set_controls_allowed(engaged) - torque = int(torque) - self.safety.set_rt_torque_last(torque) - self.safety.set_torque_meas(torque, torque) - self.safety.set_desired_torque_last(torque) - - should_tx = not steer_req and torque == 0 - self.assertEqual(should_tx, self._tx(self._torque_cmd_msg(torque, steer_req))) - - def test_lta_steer_cmd(self): - """ - Tests the LTA steering command message - controls_allowed: - * STEER_REQUEST and STEER_REQUEST_2 do not mismatch - * TORQUE_WIND_DOWN is only set to 0 or 100 when STEER_REQUEST and STEER_REQUEST_2 are both 1 - * Full torque messages are blocked if either EPS torque or driver torque is above the threshold - - not controls_allowed: - * STEER_REQUEST, STEER_REQUEST_2, and TORQUE_WIND_DOWN are all 0 - """ - for controls_allowed in (True, False): - for angle in np.arange(-90, 90, 1): - self.safety.set_controls_allowed(controls_allowed) - self._reset_angle_measurement(angle) - self._set_prev_desired_angle(angle) - - self.assertTrue(self._tx(self._lta_msg(0, 0, angle, 0))) - if controls_allowed: - # Test the two steer request bits and TORQUE_WIND_DOWN torque wind down signal - for req, req2, torque_wind_down in itertools.product([0, 1], [0, 1], [0, 50, 100]): - mismatch = not (req or req2) and torque_wind_down != 0 - should_tx = req == req2 and (torque_wind_down in (0, 100)) and not mismatch - self.assertEqual(should_tx, self._tx(self._lta_msg(req, req2, angle, torque_wind_down))) - - # Test max EPS torque and driver override thresholds - cases = itertools.product( - (0, self.MAX_MEAS_TORQUE - 1, self.MAX_MEAS_TORQUE, self.MAX_MEAS_TORQUE + 1, self.MAX_MEAS_TORQUE * 2), - (0, self.MAX_LTA_DRIVER_TORQUE - 1, self.MAX_LTA_DRIVER_TORQUE, self.MAX_LTA_DRIVER_TORQUE + 1, self.MAX_LTA_DRIVER_TORQUE * 2) - ) - - for eps_torque, driver_torque in cases: - for sign in (-1, 1): - for _ in range(6): - self._rx(self._torque_meas_msg(sign * eps_torque, sign * driver_torque)) - - # Toyota adds 1 to EPS torque since it is rounded after EPS factor - should_tx = (eps_torque - 1) <= self.MAX_MEAS_TORQUE and driver_torque <= self.MAX_LTA_DRIVER_TORQUE - self.assertEqual(should_tx, self._tx(self._lta_msg(1, 1, angle, 100))) - self.assertTrue(self._tx(self._lta_msg(1, 1, angle, 0))) # should tx if we wind down torque - - else: - # Controls not allowed - for req, req2, torque_wind_down in itertools.product([0, 1], [0, 1], [0, 50, 100]): - should_tx = not (req or req2) and torque_wind_down == 0 - self.assertEqual(should_tx, self._tx(self._lta_msg(req, req2, angle, torque_wind_down))) - - def test_steering_angle_measurements(self, max_angle=None): - # Measurement test tests max angle + 0.5 which will fail - super().test_steering_angle_measurements(max_angle=self.MAX_LTA_ANGLE - 0.5) - - def test_angle_cmd_when_enabled(self, max_angle=None): - super().test_angle_cmd_when_enabled(max_angle=self.MAX_LTA_ANGLE) - - def test_angle_measurements(self): - """ - * Tests angle meas quality flag dictates whether angle measurement is parsed, and if rx is valid - * Tests rx hook correctly clips the angle measurement, since it is to be compared to LTA cmd when inactive - """ - for steer_angle_initializing in (True, False): - for angle in np.arange(0, self.MAX_LTA_ANGLE * 2, 1): - # If init flag is set, do not rx or parse any angle measurements - for a in (angle, -angle, 0, 0, 0, 0): - self.assertEqual(not steer_angle_initializing, - self._rx(self._angle_meas_msg(a, steer_angle_initializing))) - - final_angle = (0 if steer_angle_initializing else - round(min(angle, self.MAX_LTA_ANGLE) * self.DEG_TO_CAN)) - self.assertEqual(self.safety.get_angle_meas_min(), -final_angle) - self.assertEqual(self.safety.get_angle_meas_max(), final_angle) - - self._rx(self._angle_meas_msg(0)) - self.assertEqual(self.safety.get_angle_meas_min(), -final_angle) - self.assertEqual(self.safety.get_angle_meas_max(), 0) - - self._rx(self._angle_meas_msg(0)) - self.assertEqual(self.safety.get_angle_meas_min(), 0) - self.assertEqual(self.safety.get_angle_meas_max(), 0) - - -class TestToyotaSafetyAngleGasInterceptor(TestToyotaSafetyGasInterceptorBase, TestToyotaSafetyAngle): - pass - - -class TestToyotaAltBrakeSafety(TestToyotaSafetyTorque): - - def setUp(self): - self.packer = CANPackerPanda("toyota_new_mc_pt_generated") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_TOYOTA, self.EPS_SCALE | Panda.FLAG_TOYOTA_ALT_BRAKE) - self.safety.init_tests() - - def _user_brake_msg(self, brake): - values = {"BRAKE_PRESSED": brake} - return self.packer.make_can_msg_panda("BRAKE_MODULE", 0, values) - - # No LTA message in the DBC - def test_lta_steer_cmd(self): - pass - - -class TestToyotaAltBrakeSafetyGasInterceptor(TestToyotaSafetyGasInterceptorBase, TestToyotaAltBrakeSafety): - pass - - -class TestToyotaStockLongitudinalBase(TestToyotaSafetyBase): - - TX_MSGS = TOYOTA_COMMON_TX_MSGS - # Base addresses minus ACC_CONTROL (0x343) - RELAY_MALFUNCTION_ADDRS = {0: (0x2E4,)} - FWD_BLACKLISTED_ADDRS = {2: [0x2E4, 0x412, 0x191]} - - def test_diagnostics(self, stock_longitudinal: bool = True): - super().test_diagnostics(stock_longitudinal=stock_longitudinal) - - def test_block_aeb(self, stock_longitudinal: bool = True): - super().test_block_aeb(stock_longitudinal=stock_longitudinal) - - def test_accel_actuation_limits(self, stock_longitudinal=True): - super().test_accel_actuation_limits(stock_longitudinal=stock_longitudinal) - - def test_acc_cancel(self): - """ - Regardless of controls allowed, never allow ACC_CONTROL if cancel bit isn't set - """ - for controls_allowed in [True, False]: - self.safety.set_controls_allowed(controls_allowed) - for accel in np.arange(self.MIN_ACCEL - 1, self.MAX_ACCEL + 1, 0.1): - self.assertFalse(self._tx(self._accel_msg(accel))) - should_tx = np.isclose(accel, 0, atol=0.0001) - self.assertEqual(should_tx, self._tx(self._accel_msg(accel, cancel_req=1))) - - -class TestToyotaStockLongitudinalTorque(TestToyotaStockLongitudinalBase, TestToyotaSafetyTorque): - - def setUp(self): - self.packer = CANPackerPanda("toyota_nodsu_pt_generated") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_TOYOTA, self.EPS_SCALE | Panda.FLAG_TOYOTA_STOCK_LONGITUDINAL) - self.safety.init_tests() - - -class TestToyotaStockLongitudinalAngle(TestToyotaStockLongitudinalBase, TestToyotaSafetyAngle): - - def setUp(self): - self.packer = CANPackerPanda("toyota_nodsu_pt_generated") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_TOYOTA, self.EPS_SCALE | Panda.FLAG_TOYOTA_STOCK_LONGITUDINAL | Panda.FLAG_TOYOTA_LTA) - self.safety.init_tests() - - -if __name__ == "__main__": - unittest.main() diff --git a/panda/tests/safety/test_volkswagen_mqb.py b/panda/tests/safety/test_volkswagen_mqb.py deleted file mode 100644 index 276ee6c..0000000 --- a/panda/tests/safety/test_volkswagen_mqb.py +++ /dev/null @@ -1,225 +0,0 @@ -#!/usr/bin/env python3 -import unittest -import numpy as np -from panda import Panda -from panda.tests.libpanda import libpanda_py -import panda.tests.safety.common as common -from panda.tests.safety.common import CANPackerPanda - -MAX_ACCEL = 2.0 -MIN_ACCEL = -3.5 - -MSG_ESP_19 = 0xB2 # RX from ABS, for wheel speeds -MSG_LH_EPS_03 = 0x9F # RX from EPS, for driver steering torque -MSG_ESP_05 = 0x106 # RX from ABS, for brake light state -MSG_TSK_06 = 0x120 # RX from ECU, for ACC status from drivetrain coordinator -MSG_MOTOR_20 = 0x121 # RX from ECU, for driver throttle input -MSG_ACC_06 = 0x122 # TX by OP, ACC control instructions to the drivetrain coordinator -MSG_HCA_01 = 0x126 # TX by OP, Heading Control Assist steering torque -MSG_GRA_ACC_01 = 0x12B # TX by OP, ACC control buttons for cancel/resume -MSG_ACC_07 = 0x12E # TX by OP, ACC control instructions to the drivetrain coordinator -MSG_ACC_02 = 0x30C # TX by OP, ACC HUD data to the instrument cluster -MSG_LDW_02 = 0x397 # TX by OP, Lane line recognition and text alerts - - -class TestVolkswagenMqbSafety(common.PandaCarSafetyTest, common.DriverTorqueSteeringSafetyTest): - STANDSTILL_THRESHOLD = 0 - RELAY_MALFUNCTION_ADDRS = {0: (MSG_HCA_01,)} - - MAX_RATE_UP = 4 - MAX_RATE_DOWN = 10 - MAX_TORQUE = 300 - MAX_RT_DELTA = 75 - RT_INTERVAL = 250000 - - DRIVER_TORQUE_ALLOWANCE = 80 - DRIVER_TORQUE_FACTOR = 3 - - @classmethod - def setUpClass(cls): - if cls.__name__ == "TestVolkswagenMqbSafety": - cls.packer = None - cls.safety = None - raise unittest.SkipTest - - # Wheel speeds _esp_19_msg - def _speed_msg(self, speed): - values = {"ESP_%s_Radgeschw_02" % s: speed for s in ["HL", "HR", "VL", "VR"]} - return self.packer.make_can_msg_panda("ESP_19", 0, values) - - # Driver brake pressure over threshold - def _esp_05_msg(self, brake): - values = {"ESP_Fahrer_bremst": brake} - return self.packer.make_can_msg_panda("ESP_05", 0, values) - - # Brake pedal switch - def _motor_14_msg(self, brake): - values = {"MO_Fahrer_bremst": brake} - return self.packer.make_can_msg_panda("Motor_14", 0, values) - - def _user_brake_msg(self, brake): - return self._motor_14_msg(brake) - - # Driver throttle input - def _user_gas_msg(self, gas): - values = {"MO_Fahrpedalrohwert_01": gas} - return self.packer.make_can_msg_panda("Motor_20", 0, values) - - # ACC engagement status - def _tsk_status_msg(self, enable, main_switch=True): - if main_switch: - tsk_status = 3 if enable else 2 - else: - tsk_status = 0 - values = {"TSK_Status": tsk_status} - return self.packer.make_can_msg_panda("TSK_06", 0, values) - - def _pcm_status_msg(self, enable): - return self._tsk_status_msg(enable) - - # Driver steering input torque - def _torque_driver_msg(self, torque): - values = {"EPS_Lenkmoment": abs(torque), "EPS_VZ_Lenkmoment": torque < 0} - return self.packer.make_can_msg_panda("LH_EPS_03", 0, values) - - # openpilot steering output torque - def _torque_cmd_msg(self, torque, steer_req=1): - values = {"HCA_01_LM_Offset": abs(torque), "HCA_01_LM_OffSign": torque < 0, "HCA_01_Sendestatus": steer_req} - return self.packer.make_can_msg_panda("HCA_01", 0, values) - - # Cruise control buttons - def _gra_acc_01_msg(self, cancel=0, resume=0, _set=0, bus=2): - values = {"GRA_Abbrechen": cancel, "GRA_Tip_Setzen": _set, "GRA_Tip_Wiederaufnahme": resume} - return self.packer.make_can_msg_panda("GRA_ACC_01", bus, values) - - # Acceleration request to drivetrain coordinator - def _acc_06_msg(self, accel): - values = {"ACC_Sollbeschleunigung_02": accel} - return self.packer.make_can_msg_panda("ACC_06", 0, values) - - # Acceleration request to drivetrain coordinator - def _acc_07_msg(self, accel, secondary_accel=3.02): - values = {"ACC_Sollbeschleunigung_02": accel, "ACC_Folgebeschl": secondary_accel} - return self.packer.make_can_msg_panda("ACC_07", 0, values) - - # Verify brake_pressed is true if either the switch or pressure threshold signals are true - def test_redundant_brake_signals(self): - test_combinations = [(True, True, True), (True, True, False), (True, False, True), (False, False, False)] - for brake_pressed, motor_14_signal, esp_05_signal in test_combinations: - self._rx(self._motor_14_msg(False)) - self._rx(self._esp_05_msg(False)) - self.assertFalse(self.safety.get_brake_pressed_prev()) - self._rx(self._motor_14_msg(motor_14_signal)) - self._rx(self._esp_05_msg(esp_05_signal)) - self.assertEqual(brake_pressed, self.safety.get_brake_pressed_prev(), - f"expected {brake_pressed=} with {motor_14_signal=} and {esp_05_signal=}") - - def test_torque_measurements(self): - # TODO: make this test work with all cars - self._rx(self._torque_driver_msg(50)) - self._rx(self._torque_driver_msg(-50)) - self._rx(self._torque_driver_msg(0)) - self._rx(self._torque_driver_msg(0)) - self._rx(self._torque_driver_msg(0)) - self._rx(self._torque_driver_msg(0)) - - self.assertEqual(-50, self.safety.get_torque_driver_min()) - self.assertEqual(50, self.safety.get_torque_driver_max()) - - self._rx(self._torque_driver_msg(0)) - self.assertEqual(0, self.safety.get_torque_driver_max()) - self.assertEqual(-50, self.safety.get_torque_driver_min()) - - self._rx(self._torque_driver_msg(0)) - self.assertEqual(0, self.safety.get_torque_driver_max()) - self.assertEqual(0, self.safety.get_torque_driver_min()) - - -class TestVolkswagenMqbStockSafety(TestVolkswagenMqbSafety): - TX_MSGS = [[MSG_HCA_01, 0], [MSG_LDW_02, 0], [MSG_LH_EPS_03, 2], [MSG_GRA_ACC_01, 0], [MSG_GRA_ACC_01, 2]] - FWD_BLACKLISTED_ADDRS = {0: [MSG_LH_EPS_03], 2: [MSG_HCA_01, MSG_LDW_02]} - FWD_BUS_LOOKUP = {0: 2, 2: 0} - - def setUp(self): - self.packer = CANPackerPanda("vw_mqb_2010") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_VOLKSWAGEN_MQB, 0) - self.safety.init_tests() - - def test_spam_cancel_safety_check(self): - self.safety.set_controls_allowed(0) - self.assertTrue(self._tx(self._gra_acc_01_msg(cancel=1))) - self.assertFalse(self._tx(self._gra_acc_01_msg(resume=1))) - self.assertFalse(self._tx(self._gra_acc_01_msg(_set=1))) - # do not block resume if we are engaged already - self.safety.set_controls_allowed(1) - self.assertTrue(self._tx(self._gra_acc_01_msg(resume=1))) - - -class TestVolkswagenMqbLongSafety(TestVolkswagenMqbSafety): - TX_MSGS = [[MSG_HCA_01, 0], [MSG_LDW_02, 0], [MSG_LH_EPS_03, 2], [MSG_ACC_02, 0], [MSG_ACC_06, 0], [MSG_ACC_07, 0]] - FWD_BLACKLISTED_ADDRS = {0: [MSG_LH_EPS_03], 2: [MSG_HCA_01, MSG_LDW_02, MSG_ACC_02, MSG_ACC_06, MSG_ACC_07]} - FWD_BUS_LOOKUP = {0: 2, 2: 0} - INACTIVE_ACCEL = 3.01 - - def setUp(self): - self.packer = CANPackerPanda("vw_mqb_2010") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_VOLKSWAGEN_MQB, Panda.FLAG_VOLKSWAGEN_LONG_CONTROL) - self.safety.init_tests() - - # stock cruise controls are entirely bypassed under openpilot longitudinal control - def test_disable_control_allowed_from_cruise(self): - pass - - def test_enable_control_allowed_from_cruise(self): - pass - - def test_cruise_engaged_prev(self): - pass - - def test_set_and_resume_buttons(self): - for button in ["set", "resume"]: - # ACC main switch must be on, engage on falling edge - self.safety.set_controls_allowed(0) - self._rx(self._tsk_status_msg(False, main_switch=False)) - self._rx(self._gra_acc_01_msg(_set=(button == "set"), resume=(button == "resume"), bus=0)) - self.assertFalse(self.safety.get_controls_allowed(), f"controls allowed on {button} with main switch off") - self._rx(self._tsk_status_msg(False, main_switch=True)) - self._rx(self._gra_acc_01_msg(_set=(button == "set"), resume=(button == "resume"), bus=0)) - self.assertFalse(self.safety.get_controls_allowed(), f"controls allowed on {button} rising edge") - self._rx(self._gra_acc_01_msg(bus=0)) - self.assertTrue(self.safety.get_controls_allowed(), f"controls not allowed on {button} falling edge") - - def test_cancel_button(self): - # Disable on rising edge of cancel button - self._rx(self._tsk_status_msg(False, main_switch=True)) - self.safety.set_controls_allowed(1) - self._rx(self._gra_acc_01_msg(cancel=True, bus=0)) - self.assertFalse(self.safety.get_controls_allowed(), "controls allowed after cancel") - - def test_main_switch(self): - # Disable as soon as main switch turns off - self._rx(self._tsk_status_msg(False, main_switch=True)) - self.safety.set_controls_allowed(1) - self._rx(self._tsk_status_msg(False, main_switch=False)) - self.assertFalse(self.safety.get_controls_allowed(), "controls allowed after ACC main switch off") - - def test_accel_safety_check(self): - for controls_allowed in [True, False]: - # enforce we don't skip over 0 or inactive accel - for accel in np.concatenate((np.arange(MIN_ACCEL - 2, MAX_ACCEL + 2, 0.03), [0, self.INACTIVE_ACCEL])): - accel = round(accel, 2) # floats might not hit exact boundary conditions without rounding - is_inactive_accel = accel == self.INACTIVE_ACCEL - send = (controls_allowed and MIN_ACCEL <= accel <= MAX_ACCEL) or is_inactive_accel - self.safety.set_controls_allowed(controls_allowed) - # primary accel request used by ECU - self.assertEqual(send, self._tx(self._acc_06_msg(accel)), (controls_allowed, accel)) - # additional accel request used by ABS/ESP - self.assertEqual(send, self._tx(self._acc_07_msg(accel)), (controls_allowed, accel)) - # ensure the optional secondary accel field remains inactive for now - self.assertEqual(is_inactive_accel, self._tx(self._acc_07_msg(accel, secondary_accel=accel)), (controls_allowed, accel)) - - -if __name__ == "__main__": - unittest.main() diff --git a/panda/tests/safety/test_volkswagen_pq.py b/panda/tests/safety/test_volkswagen_pq.py deleted file mode 100644 index f2bc317..0000000 --- a/panda/tests/safety/test_volkswagen_pq.py +++ /dev/null @@ -1,199 +0,0 @@ -#!/usr/bin/env python3 -import unittest -from panda import Panda -from panda.tests.libpanda import libpanda_py -import panda.tests.safety.common as common -from panda.tests.safety.common import CANPackerPanda - -MSG_LENKHILFE_3 = 0x0D0 # RX from EPS, for steering angle and driver steering torque -MSG_HCA_1 = 0x0D2 # TX by OP, Heading Control Assist steering torque -MSG_BREMSE_1 = 0x1A0 # RX from ABS, for ego speed -MSG_MOTOR_2 = 0x288 # RX from ECU, for CC state and brake switch state -MSG_ACC_SYSTEM = 0x368 # TX by OP, longitudinal acceleration controls -MSG_MOTOR_3 = 0x380 # RX from ECU, for driver throttle input -MSG_GRA_NEU = 0x38A # TX by OP, ACC control buttons for cancel/resume -MSG_MOTOR_5 = 0x480 # RX from ECU, for ACC main switch state -MSG_ACC_GRA_ANZEIGE = 0x56A # TX by OP, ACC HUD -MSG_LDW_1 = 0x5BE # TX by OP, Lane line recognition and text alerts - - -class TestVolkswagenPqSafety(common.PandaCarSafetyTest, common.DriverTorqueSteeringSafetyTest): - cruise_engaged = False - - STANDSTILL_THRESHOLD = 0 - RELAY_MALFUNCTION_ADDRS = {0: (MSG_HCA_1,)} - - MAX_RATE_UP = 6 - MAX_RATE_DOWN = 10 - MAX_TORQUE = 300 - MAX_RT_DELTA = 113 - RT_INTERVAL = 250000 - - DRIVER_TORQUE_ALLOWANCE = 80 - DRIVER_TORQUE_FACTOR = 3 - - @classmethod - def setUpClass(cls): - if cls.__name__ == "TestVolkswagenPqSafety": - cls.packer = None - cls.safety = None - raise unittest.SkipTest - - def _set_prev_torque(self, t): - self.safety.set_desired_torque_last(t) - self.safety.set_rt_torque_last(t) - - # Ego speed (Bremse_1) - def _speed_msg(self, speed): - values = {"Geschwindigkeit_neu__Bremse_1_": speed} - return self.packer.make_can_msg_panda("Bremse_1", 0, values) - - # Brake light switch (shared message Motor_2) - def _user_brake_msg(self, brake): - # since this signal is used for engagement status, preserve current state - return self._motor_2_msg(brake_pressed=brake, cruise_engaged=self.safety.get_controls_allowed()) - - # ACC engaged status (shared message Motor_2) - def _pcm_status_msg(self, enable): - self.__class__.cruise_engaged = enable - return self._motor_2_msg(cruise_engaged=enable) - - # Acceleration request to drivetrain coordinator - def _accel_msg(self, accel): - values = {"ACS_Sollbeschl": accel} - return self.packer.make_can_msg_panda("ACC_System", 0, values) - - # Driver steering input torque - def _torque_driver_msg(self, torque): - values = {"LH3_LM": abs(torque), "LH3_LMSign": torque < 0} - return self.packer.make_can_msg_panda("Lenkhilfe_3", 0, values) - - # openpilot steering output torque - def _torque_cmd_msg(self, torque, steer_req=1, hca_status=5): - values = {"LM_Offset": abs(torque), "LM_OffSign": torque < 0, "HCA_Status": hca_status if steer_req else 3} - return self.packer.make_can_msg_panda("HCA_1", 0, values) - - # ACC engagement and brake light switch status - # Called indirectly for compatibility with common.py tests - def _motor_2_msg(self, brake_pressed=False, cruise_engaged=False): - values = {"Bremslichtschalter": brake_pressed, - "GRA_Status": cruise_engaged} - return self.packer.make_can_msg_panda("Motor_2", 0, values) - - # ACC main switch status - def _motor_5_msg(self, main_switch=False): - values = {"GRA_Hauptschalter": main_switch} - return self.packer.make_can_msg_panda("Motor_5", 0, values) - - # Driver throttle input (Motor_3) - def _user_gas_msg(self, gas): - values = {"Fahrpedal_Rohsignal": gas} - return self.packer.make_can_msg_panda("Motor_3", 0, values) - - # Cruise control buttons (GRA_Neu) - def _button_msg(self, _set=False, resume=False, cancel=False, bus=2): - values = {"GRA_Neu_Setzen": _set, "GRA_Recall": resume, "GRA_Abbrechen": cancel} - return self.packer.make_can_msg_panda("GRA_Neu", bus, values) - - def test_torque_measurements(self): - # TODO: make this test work with all cars - self._rx(self._torque_driver_msg(50)) - self._rx(self._torque_driver_msg(-50)) - self._rx(self._torque_driver_msg(0)) - self._rx(self._torque_driver_msg(0)) - self._rx(self._torque_driver_msg(0)) - self._rx(self._torque_driver_msg(0)) - - self.assertEqual(-50, self.safety.get_torque_driver_min()) - self.assertEqual(50, self.safety.get_torque_driver_max()) - - self._rx(self._torque_driver_msg(0)) - self.assertEqual(0, self.safety.get_torque_driver_max()) - self.assertEqual(-50, self.safety.get_torque_driver_min()) - - self._rx(self._torque_driver_msg(0)) - self.assertEqual(0, self.safety.get_torque_driver_max()) - self.assertEqual(0, self.safety.get_torque_driver_min()) - - -class TestVolkswagenPqStockSafety(TestVolkswagenPqSafety): - # Transmit of GRA_Neu is allowed on bus 0 and 2 to keep compatibility with gateway and camera integration - TX_MSGS = [[MSG_HCA_1, 0], [MSG_GRA_NEU, 0], [MSG_GRA_NEU, 2], [MSG_LDW_1, 0]] - FWD_BLACKLISTED_ADDRS = {2: [MSG_HCA_1, MSG_LDW_1]} - FWD_BUS_LOOKUP = {0: 2, 2: 0} - - def setUp(self): - self.packer = CANPackerPanda("vw_golf_mk4") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_VOLKSWAGEN_PQ, 0) - self.safety.init_tests() - - def test_spam_cancel_safety_check(self): - self.safety.set_controls_allowed(0) - self.assertTrue(self._tx(self._button_msg(cancel=True))) - self.assertFalse(self._tx(self._button_msg(resume=True))) - self.assertFalse(self._tx(self._button_msg(_set=True))) - # do not block resume if we are engaged already - self.safety.set_controls_allowed(1) - self.assertTrue(self._tx(self._button_msg(resume=True))) - - -class TestVolkswagenPqLongSafety(TestVolkswagenPqSafety, common.LongitudinalAccelSafetyTest): - TX_MSGS = [[MSG_HCA_1, 0], [MSG_LDW_1, 0], [MSG_ACC_SYSTEM, 0], [MSG_ACC_GRA_ANZEIGE, 0]] - FWD_BLACKLISTED_ADDRS = {2: [MSG_HCA_1, MSG_LDW_1, MSG_ACC_SYSTEM, MSG_ACC_GRA_ANZEIGE]} - FWD_BUS_LOOKUP = {0: 2, 2: 0} - INACTIVE_ACCEL = 3.01 - - def setUp(self): - self.packer = CANPackerPanda("vw_golf_mk4") - self.safety = libpanda_py.libpanda - self.safety.set_safety_hooks(Panda.SAFETY_VOLKSWAGEN_PQ, Panda.FLAG_VOLKSWAGEN_LONG_CONTROL) - self.safety.init_tests() - - # stock cruise controls are entirely bypassed under openpilot longitudinal control - def test_disable_control_allowed_from_cruise(self): - pass - - def test_enable_control_allowed_from_cruise(self): - pass - - def test_cruise_engaged_prev(self): - pass - - def test_set_and_resume_buttons(self): - for button in ["set", "resume"]: - # ACC main switch must be on, engage on falling edge - self.safety.set_controls_allowed(0) - self._rx(self._motor_5_msg(main_switch=False)) - self._rx(self._button_msg(_set=(button == "set"), resume=(button == "resume"), bus=0)) - self._rx(self._button_msg(bus=0)) - self.assertFalse(self.safety.get_controls_allowed(), f"controls allowed on {button} with main switch off") - self._rx(self._motor_5_msg(main_switch=True)) - self._rx(self._button_msg(_set=(button == "set"), resume=(button == "resume"), bus=0)) - self.assertFalse(self.safety.get_controls_allowed(), f"controls allowed on {button} rising edge") - self._rx(self._button_msg(bus=0)) - self.assertTrue(self.safety.get_controls_allowed(), f"controls not allowed on {button} falling edge") - - def test_cancel_button(self): - # Disable on rising edge of cancel button - self._rx(self._motor_5_msg(main_switch=True)) - self.safety.set_controls_allowed(1) - self._rx(self._button_msg(cancel=True, bus=0)) - self.assertFalse(self.safety.get_controls_allowed(), "controls allowed after cancel") - - def test_main_switch(self): - # Disable as soon as main switch turns off - self._rx(self._motor_5_msg(main_switch=True)) - self.safety.set_controls_allowed(1) - self._rx(self._motor_5_msg(main_switch=False)) - self.assertFalse(self.safety.get_controls_allowed(), "controls allowed after ACC main switch off") - - def test_torque_cmd_enable_variants(self): - # The EPS rack accepts either 5 or 7 for an enabled status, with different low speed tuning behavior - self.safety.set_controls_allowed(1) - for enabled_status in (5, 7): - self.assertTrue(self._tx(self._torque_cmd_msg(self.MAX_RATE_UP, steer_req=1, hca_status=enabled_status)), - f"torque cmd rejected with {enabled_status=}") - -if __name__ == "__main__": - unittest.main() diff --git a/panda/tests/safety_replay/.gitignore b/panda/tests/safety_replay/.gitignore deleted file mode 100644 index 192fb09..0000000 --- a/panda/tests/safety_replay/.gitignore +++ /dev/null @@ -1 +0,0 @@ -*.bz2 diff --git a/panda/tests/safety_replay/__init__.py b/panda/tests/safety_replay/__init__.py deleted file mode 100644 index e69de29..0000000 diff --git a/panda/tests/safety_replay/helpers.py b/panda/tests/safety_replay/helpers.py deleted file mode 100644 index a1a6cd3..0000000 --- a/panda/tests/safety_replay/helpers.py +++ /dev/null @@ -1,80 +0,0 @@ -import panda.tests.libpanda.libpanda_py as libpanda_py -from panda import Panda - -def to_signed(d, bits): - ret = d - if d >= (1 << (bits - 1)): - ret = d - (1 << bits) - return ret - -def is_steering_msg(mode, param, addr): - ret = False - if mode in (Panda.SAFETY_HONDA_NIDEC, Panda.SAFETY_HONDA_BOSCH): - ret = (addr == 0xE4) or (addr == 0x194) or (addr == 0x33D) or (addr == 0x33DA) or (addr == 0x33DB) - elif mode == Panda.SAFETY_TOYOTA: - ret = addr == (0x191 if param & Panda.FLAG_TOYOTA_LTA else 0x2E4) - elif mode == Panda.SAFETY_GM: - ret = addr == 384 - elif mode == Panda.SAFETY_HYUNDAI: - ret = addr == 832 - elif mode == Panda.SAFETY_CHRYSLER: - ret = addr == 0x292 - elif mode == Panda.SAFETY_SUBARU: - ret = addr == 0x122 - elif mode == Panda.SAFETY_FORD: - ret = addr == 0x3d3 - elif mode == Panda.SAFETY_NISSAN: - ret = addr == 0x169 - return ret - -def get_steer_value(mode, param, to_send): - torque, angle = 0, 0 - if mode in (Panda.SAFETY_HONDA_NIDEC, Panda.SAFETY_HONDA_BOSCH): - torque = (to_send.data[0] << 8) | to_send.data[1] - torque = to_signed(torque, 16) - elif mode == Panda.SAFETY_TOYOTA: - if param & Panda.FLAG_TOYOTA_LTA: - angle = (to_send.data[1] << 8) | to_send.data[2] - angle = to_signed(angle, 16) - else: - torque = (to_send.data[1] << 8) | (to_send.data[2]) - torque = to_signed(torque, 16) - elif mode == Panda.SAFETY_GM: - torque = ((to_send.data[0] & 0x7) << 8) | to_send.data[1] - torque = to_signed(torque, 11) - elif mode == Panda.SAFETY_HYUNDAI: - torque = (((to_send.data[3] & 0x7) << 8) | to_send.data[2]) - 1024 - elif mode == Panda.SAFETY_CHRYSLER: - torque = (((to_send.data[0] & 0x7) << 8) | to_send.data[1]) - 1024 - elif mode == Panda.SAFETY_SUBARU: - torque = ((to_send.data[3] & 0x1F) << 8) | to_send.data[2] - torque = -to_signed(torque, 13) - elif mode == Panda.SAFETY_FORD: - angle = ((to_send.data[0] << 3) | (to_send.data[1] >> 5)) - 1000 - elif mode == Panda.SAFETY_NISSAN: - angle = (to_send.data[0] << 10) | (to_send.data[1] << 2) | (to_send.data[2] >> 6) - angle = -angle + (1310 * 100) - return torque, angle - -def package_can_msg(msg): - return libpanda_py.make_CANPacket(msg.address, msg.src % 4, msg.dat) - -def init_segment(safety, lr, mode, param): - sendcan = (msg for msg in lr if msg.which() == 'sendcan') - steering_msgs = (can for msg in sendcan for can in msg.sendcan if is_steering_msg(mode, param, can.address)) - - msg = next(steering_msgs, None) - if msg is None: - # no steering msgs - return - - to_send = package_can_msg(msg) - torque, angle = get_steer_value(mode, param, to_send) - if torque != 0: - safety.set_controls_allowed(1) - safety.set_desired_torque_last(torque) - elif angle != 0: - safety.set_controls_allowed(1) - safety.set_desired_angle_last(angle) - safety.set_angle_meas(angle, angle) - assert safety.safety_tx_hook(to_send), "failed to initialize panda safety for segment" diff --git a/panda/tests/safety_replay/replay_drive.py b/panda/tests/safety_replay/replay_drive.py deleted file mode 100644 index df3e055..0000000 --- a/panda/tests/safety_replay/replay_drive.py +++ /dev/null @@ -1,103 +0,0 @@ -#!/usr/bin/env python3 -import argparse -import os -from collections import Counter - -from panda.tests.libpanda import libpanda_py -from panda.tests.safety_replay.helpers import package_can_msg, init_segment - -# replay a drive to check for safety violations -def replay_drive(lr, safety_mode, param, alternative_experience, segment=False): - safety = libpanda_py.libpanda - - err = safety.set_safety_hooks(safety_mode, param) - assert err == 0, "invalid safety mode: %d" % safety_mode - safety.set_alternative_experience(alternative_experience) - - if segment: - init_segment(safety, lr, safety_mode, param) - lr.reset() - - rx_tot, rx_invalid, tx_tot, tx_blocked, tx_controls, tx_controls_blocked = 0, 0, 0, 0, 0, 0 - safety_tick_rx_invalid = False - blocked_addrs = Counter() - invalid_addrs = set() - - can_msgs = [m for m in lr if m.which() in ('can', 'sendcan')] - start_t = can_msgs[0].logMonoTime - end_t = can_msgs[-1].logMonoTime - for msg in can_msgs: - safety.set_timer((msg.logMonoTime // 1000) % 0xFFFFFFFF) - - # skip start and end of route, warm up/down period - if msg.logMonoTime - start_t > 1e9 and end_t - msg.logMonoTime > 1e9: - safety.safety_tick_current_safety_config() - safety_tick_rx_invalid |= not safety.safety_config_valid() or safety_tick_rx_invalid - - if msg.which() == 'sendcan': - for canmsg in msg.sendcan: - to_send = package_can_msg(canmsg) - sent = safety.safety_tx_hook(to_send) - if not sent: - tx_blocked += 1 - tx_controls_blocked += safety.get_controls_allowed() - blocked_addrs[canmsg.address] += 1 - - if "DEBUG" in os.environ: - print("blocked bus %d msg %d at %f" % (canmsg.src, canmsg.address, (msg.logMonoTime - start_t) / 1e9)) - tx_controls += safety.get_controls_allowed() - tx_tot += 1 - elif msg.which() == 'can': - # ignore msgs we sent - for canmsg in filter(lambda m: m.src < 128, msg.can): - to_push = package_can_msg(canmsg) - recv = safety.safety_rx_hook(to_push) - if not recv: - rx_invalid += 1 - invalid_addrs.add(canmsg.address) - rx_tot += 1 - - print("\nRX") - print("total rx msgs:", rx_tot) - print("invalid rx msgs:", rx_invalid) - print("safety tick rx invalid:", safety_tick_rx_invalid) - print("invalid addrs:", invalid_addrs) - print("\nTX") - print("total openpilot msgs:", tx_tot) - print("total msgs with controls allowed:", tx_controls) - print("blocked msgs:", tx_blocked) - print("blocked with controls allowed:", tx_controls_blocked) - print("blocked addrs:", blocked_addrs) - - return tx_controls_blocked == 0 and rx_invalid == 0 and not safety_tick_rx_invalid - -if __name__ == "__main__": - from openpilot.tools.lib.logreader import LogReader - - parser = argparse.ArgumentParser(description="Replay CAN messages from a route or segment through a safety mode", - formatter_class=argparse.ArgumentDefaultsHelpFormatter) - parser.add_argument("route_or_segment_name", nargs='+') - parser.add_argument("--mode", type=int, help="Override the safety mode from the log") - parser.add_argument("--param", type=int, help="Override the safety param from the log") - parser.add_argument("--alternative-experience", type=int, help="Override the alternative experience from the log") - args = parser.parse_args() - - lr = LogReader(args.route_or_segment_name[0]) - - if None in (args.mode, args.param, args.alternative_experience): - for msg in lr: - if msg.which() == 'carParams': - if args.mode is None: - args.mode = msg.carParams.safetyConfigs[-1].safetyModel.raw - if args.param is None: - args.param = msg.carParams.safetyConfigs[-1].safetyParam - if args.alternative_experience is None: - args.alternative_experience = msg.carParams.alternativeExperience - break - else: - raise Exception("carParams not found in log. Set safety mode and param manually.") - - lr.reset() - - print(f"replaying {args.route_or_segment_name[0]} with safety mode {args.mode}, param {args.param}, alternative experience {args.alternative_experience}") - replay_drive(lr, args.mode, args.param, args.alternative_experience, segment=len(lr.logreader_identifiers) == 1) diff --git a/panda/tests/setup_device_ci.sh b/panda/tests/setup_device_ci.sh deleted file mode 100644 index b45c6b4..0000000 --- a/panda/tests/setup_device_ci.sh +++ /dev/null @@ -1,74 +0,0 @@ -#!/usr/bin/bash - -set -e - -if [ -z "$SOURCE_DIR" ]; then - echo "SOURCE_DIR must be set" - exit 1 -fi - -if [ -z "$GIT_COMMIT" ]; then - echo "GIT_COMMIT must be set" - exit 1 -fi - -if [ -z "$TEST_DIR" ]; then - echo "TEST_DIR must be set" - exit 1 -fi - -CONTINUE_PATH="/data/continue.sh" -tee $CONTINUE_PATH << EOF -#!/usr/bin/bash - -sudo abctl --set_success - -# patch sshd config -sudo mount -o rw,remount / -sudo sed -i "s,/data/params/d/GithubSshKeys,/usr/comma/setup_keys," /etc/ssh/sshd_config -sudo systemctl daemon-reload -sudo systemctl restart ssh -sudo systemctl disable ssh-param-watcher.path -sudo systemctl disable ssh-param-watcher.service -sudo mount -o ro,remount / - -while true; do - if ! sudo systemctl is-active -q ssh; then - sudo systemctl start ssh - fi - sleep 5s -done - -sleep infinity -EOF -chmod +x $CONTINUE_PATH - - -# set up environment -if [ ! -d "$SOURCE_DIR" ]; then - git clone https://github.com/commaai/panda.git $SOURCE_DIR -fi - -# setup device/SOM state -SOM_ST_IO=49 -echo $SOM_ST_IO > /sys/class/gpio/export || true -echo out > /sys/class/gpio/gpio${SOM_ST_IO}/direction -echo 1 > /sys/class/gpio/gpio${SOM_ST_IO}/value - -# checkout panda commit -cd $SOURCE_DIR - -rm -f .git/index.lock -git reset --hard -git fetch --no-tags --no-recurse-submodules -j4 --verbose --depth 1 origin $GIT_COMMIT -find . -maxdepth 1 -not -path './.git' -not -name '.' -not -name '..' -exec rm -rf '{}' \; -git reset --hard $GIT_COMMIT -git checkout $GIT_COMMIT -git clean -xdff - -echo "git checkout done, t=$SECONDS" -du -hs $SOURCE_DIR $SOURCE_DIR/.git - -rsync -a --delete $SOURCE_DIR $TEST_DIR - -echo "$TEST_DIR synced with $GIT_COMMIT, t=$SECONDS" diff --git a/panda/tests/som/on-device.py b/panda/tests/som/on-device.py deleted file mode 100644 index f88d5a9..0000000 --- a/panda/tests/som/on-device.py +++ /dev/null @@ -1,24 +0,0 @@ -#!/usr/bin/env python3 -import os -import time - -from panda import Panda - - -if __name__ == "__main__": - flag_set = False - while True: - try: - with Panda(disable_checks=False) as p: - if not flag_set: - p.set_heartbeat_disabled() - p.set_safety_mode(Panda.SAFETY_ELM327, 30) - flag_set = True - - # shutdown when told - dt = p.get_datetime() - if dt.year == 2040 and dt.month == 8: - os.system("sudo poweroff") - except Exception as e: - print(str(e)) - time.sleep(0.5) diff --git a/panda/tests/som/test_bootkick.py b/panda/tests/som/test_bootkick.py deleted file mode 100644 index 6c08e1a..0000000 --- a/panda/tests/som/test_bootkick.py +++ /dev/null @@ -1,154 +0,0 @@ -import time -import pytest -import datetime - -from panda import Panda, PandaJungle - -PANDA_SERIAL = "28002d000451323431333839" -JUNGLE_SERIAL = "26001c001451313236343430" - -OBDC_PORT = 1 - -@pytest.fixture(autouse=True, scope="function") -def pj(): - jungle = PandaJungle(JUNGLE_SERIAL) - jungle.flash() - - jungle.reset() - jungle.set_ignition(False) - - yield jungle - - jungle.set_panda_power(False) - jungle.close() - -@pytest.fixture(scope="function") -def p(pj): - # note that the 3X's panda lib isn't updated, which - # shold be fine since it only uses stable APIs - pj.set_panda_power(True) - assert Panda.wait_for_panda(PANDA_SERIAL, 10) - p = Panda(PANDA_SERIAL) - p.flash() - p.reset() - yield p - p.close() - -def setup_state(panda, jungle, state): - jungle.set_panda_power(0) - - if state == "off": - wait_for_full_poweroff(jungle) - elif state == "normal boot": - jungle.set_panda_individual_power(OBDC_PORT, 1) - elif state == "QDL": - time.sleep(0.5) - jungle.set_panda_individual_power(OBDC_PORT, 1) - elif state == "ready to bootkick": - wait_for_full_poweroff(jungle) - jungle.set_panda_individual_power(OBDC_PORT, 1) - wait_for_boot(panda, jungle) - set_som_shutdown_flag(panda) - panda.set_safety_mode(Panda.SAFETY_SILENT) - panda.send_heartbeat() - wait_for_som_shutdown(panda, jungle) - else: - raise ValueError(f"unkown state: {state}") - - -def wait_for_som_shutdown(panda, jungle): - st = time.monotonic() - while panda.read_som_gpio(): - # can take a while for the SOM to fully shutdown - if time.monotonic() - st > 120: - raise Exception("SOM didn't shutdown in time") - if check_som_boot_flag(panda): - raise Exception(f"SOM rebooted instead of shutdown: {time.monotonic() - st}s") - time.sleep(0.5) - dt = time.monotonic() - st - print("waiting for shutdown", round(dt)) - dt = time.monotonic() - st - print(f"took {dt:.2f}s for SOM to shutdown") - -def wait_for_full_poweroff(jungle, timeout=30): - st = time.monotonic() - - time.sleep(15) - while PANDA_SERIAL in Panda.list(): - if time.monotonic() - st > timeout: - raise Exception("took too long for device to turn off") - - health = jungle.health() - assert all(health[f"ch{i}_power"] < 0.1 for i in range(1, 7)) - -def check_som_boot_flag(panda): - h = panda.health() - return h['safety_mode'] == Panda.SAFETY_ELM327 and h['safety_param'] == 30 - -def set_som_shutdown_flag(panda): - panda.set_datetime(datetime.datetime(year=2040, month=8, day=23)) - -def wait_for_boot(panda, jungle, reset_expected=False, bootkick=False, timeout=120): - st = time.monotonic() - - Panda.wait_for_panda(PANDA_SERIAL, timeout) - panda.reconnect() - if bootkick: - assert panda.health()['uptime'] > 20 - else: - assert panda.health()['uptime'] < 3 - - for i in range(3): - assert not check_som_boot_flag(panda) - time.sleep(1) - - # wait for SOM to bootup - while not check_som_boot_flag(panda): - if time.monotonic() - st > timeout: - raise Exception("SOM didn't boot in time") - time.sleep(1.0) - - assert panda.health()['som_reset_triggered'] == reset_expected - -def test_cold_boot(p, pj): - setup_state(p, pj, "off") - setup_state(p, pj, "normal boot") - wait_for_boot(p, pj) - -def test_bootkick_ignition_line(p, pj): - setup_state(p, pj, "ready to bootkick") - pj.set_ignition(True) - wait_for_boot(p, pj, bootkick=True) - -@pytest.mark.skip("test isn't reliable yet") -def test_bootkick_can_ignition(p, pj): - setup_state(p, pj, "ready to bootkick") - for _ in range(10): - # Mazda ignition signal - pj.can_send(0x9E, b'\xc0\x00\x00\x00\x00\x00\x00\x00', 0) - time.sleep(0.5) - wait_for_boot(p, pj, bootkick=True) - -def test_recovery_from_qdl(p, pj): - setup_state(p, pj, "ready to bootkick") - - # put into QDL using the FORCE_USB_BOOT pin - for i in range(10): - pj.set_header_pin(i, 1) - - # try to boot - time.sleep(1) - pj.set_ignition(True) - time.sleep(3) - - # release FORCE_USB_BOOT - for i in range(10): - pj.set_header_pin(i, 0) - - # normally, this GPIO is set immediately since it's first enabled in the ABL - for i in range(40): - assert not p.read_som_gpio() - time.sleep(1) - - # should boot after 45s - wait_for_boot(p, pj, reset_expected=True, bootkick=True, timeout=120) diff --git a/panda/tests/som_debug.sh b/panda/tests/som_debug.sh deleted file mode 100644 index 9bb4219..0000000 --- a/panda/tests/som_debug.sh +++ /dev/null @@ -1,7 +0,0 @@ -#!/usr/bin/bash -set -e - -DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" -cd $DIR - -PYTHONUNBUFFERED=1 NO_COLOR=1 CLAIM=1 PORT=4 ./debug_console.py diff --git a/panda/tests/spam_can.py b/panda/tests/spam_can.py deleted file mode 100644 index 3154cc0..0000000 --- a/panda/tests/spam_can.py +++ /dev/null @@ -1,20 +0,0 @@ -#!/usr/bin/env python3 -import os -import random - -from panda import Panda - -def get_test_string(): - return b"test" + os.urandom(10) - -if __name__ == "__main__": - p = Panda() - p.set_safety_mode(Panda.SAFETY_ALLOUTPUT) - - print("Spamming all buses...") - while True: - at = random.randint(1, 2000) - st = get_test_string()[0:8] - bus = random.randint(0, 2) - p.can_send(at, st, bus) - # print("Sent message on bus: ", bus) diff --git a/panda/tests/standalone_test.py b/panda/tests/standalone_test.py deleted file mode 100644 index 7ec5559..0000000 --- a/panda/tests/standalone_test.py +++ /dev/null @@ -1,32 +0,0 @@ -#!/usr/bin/env python3 -import struct -import time - -from panda import Panda - -if __name__ == "__main__": - p = Panda() - print(p.get_serial()) - print(p.health()) - - t1 = time.time() - for _ in range(100): - p.get_serial() - t2 = time.time() - print("100 requests took %.2f ms" % ((t2 - t1) * 1000)) - - p.set_safety_mode(Panda.SAFETY_ALLOUTPUT) - - a = 0 - while True: - # flood - msg = b"\xaa" * 4 + struct.pack("I", a) - p.can_send(0xaa, msg, 0) - p.can_send(0xaa, msg, 1) - p.can_send(0xaa, msg, 4) - time.sleep(0.01) - - dat = p.can_recv() - if len(dat) > 0: - print(dat) - a += 1 diff --git a/panda/tests/test_rsa.c b/panda/tests/test_rsa.c deleted file mode 100644 index 5c784e2..0000000 --- a/panda/tests/test_rsa.c +++ /dev/null @@ -1,34 +0,0 @@ -/* -gcc -DTEST_RSA test_rsa.c ../crypto/rsa.c ../crypto/sha.c && ./a.out -*/ - -#include -#include - -#define MAX_LEN 0x40000 -char buf[MAX_LEN]; - -#include "../crypto/sha.h" -#include "../crypto/rsa.h" -#include "../obj/cert.h" - -int main() { - FILE *f = fopen("../obj/panda.bin", "rb"); - int tlen = fread(buf, 1, MAX_LEN, f); - fclose(f); - printf("read %d\n", tlen); - uint32_t *_app_start = (uint32_t *)buf; - - int len = _app_start[0]; - char digest[SHA_DIGEST_SIZE]; - SHA_hash(&_app_start[1], len-4, digest); - printf("SHA hash done\n"); - - if (!RSA_verify(&rsa_key, ((void*)&_app_start[0]) + len, RSANUMBYTES, digest, SHA_DIGEST_SIZE)) { - printf("RSA fail\n"); - } else { - printf("RSA match!!!\n"); - } - - return 0; -} diff --git a/panda/tests/tucan_loopback.py b/panda/tests/tucan_loopback.py deleted file mode 100644 index 457facd..0000000 --- a/panda/tests/tucan_loopback.py +++ /dev/null @@ -1,92 +0,0 @@ -#!/usr/bin/env python3 - -import os -import time -import random -import argparse -from itertools import permutations - -from panda import Panda - -def get_test_string(): - return b"test" + os.urandom(10) - -def run_test(sleep_duration): - pandas = Panda.list() - print(pandas) - - if len(pandas) < 2: - raise Exception("Two pandas are needed for test") - - run_test_w_pandas(pandas, sleep_duration) - -def run_test_w_pandas(pandas, sleep_duration): - h = [Panda(x) for x in pandas] - print("H", h) - - for hh in h: - hh.set_safety_mode(Panda.SAFETY_ALLOUTPUT) - - # test both directions - for ho in permutations(list(range(len(h))), r=2): - print("***************** TESTING", ho) - - panda0, panda1 = h[ho[0]], h[ho[1]] - - # **** test health packet **** - print("health", ho[0], h[ho[0]].health()) - - # **** test can line loopback **** - # for bus, gmlan in [(0, None), (1, False), (2, False), (1, True), (2, True)]: - for bus, gmlan in [(0, None), (1, None)]: - print("\ntest can", bus) - # flush - cans_echo = panda0.can_recv() - cans_loop = panda1.can_recv() - - if gmlan is not None: - panda0.set_gmlan(gmlan, bus) - panda1.set_gmlan(gmlan, bus) - - # send the characters - # pick addresses high enough to not conflict with honda code - at = random.randint(1024, 2000) - st = get_test_string()[0:8] - panda0.can_send(at, st, bus) - time.sleep(0.1) - - # check for receive - cans_echo = panda0.can_recv() - cans_loop = panda1.can_recv() - - print("Bus", bus, "echo", cans_echo, "loop", cans_loop) - - assert len(cans_echo) == 1 - assert len(cans_loop) == 1 - - assert cans_echo[0][0] == at - assert cans_loop[0][0] == at - - assert cans_echo[0][2] == st - assert cans_loop[0][2] == st - - assert cans_echo[0][3] == 0x80 | bus - if cans_loop[0][3] != bus: - print("EXPECTED %d GOT %d" % (bus, cans_loop[0][3])) - assert cans_loop[0][3] == bus - - print("CAN pass", bus, ho) - time.sleep(sleep_duration) - -if __name__ == "__main__": - parser = argparse.ArgumentParser() - parser.add_argument("-n", type=int, help="Number of test iterations to run") - parser.add_argument("-sleep", type=int, help="Sleep time between tests", default=0) - args = parser.parse_args() - - if args.n is None: - while True: - run_test(sleep_duration=args.sleep) - else: - for _ in range(args.n): - run_test(sleep_duration=args.sleep) diff --git a/panda/tests/usbprotocol/test.sh b/panda/tests/usbprotocol/test.sh deleted file mode 100644 index 8e3886d..0000000 --- a/panda/tests/usbprotocol/test.sh +++ /dev/null @@ -1,8 +0,0 @@ -#!/usr/bin/env bash -set -e - -# Loops over all HW_TYPEs, see board/boards/board_declarations.h -for hw_type in {0..7}; do - echo "Testing HW_TYPE: $hw_type" - HW_TYPE=$hw_type python -m unittest discover . -done diff --git a/panda/tests/usbprotocol/test_comms.py b/panda/tests/usbprotocol/test_comms.py deleted file mode 100644 index c08551b..0000000 --- a/panda/tests/usbprotocol/test_comms.py +++ /dev/null @@ -1,160 +0,0 @@ -#!/usr/bin/env python3 -import random -import unittest - -from panda import Panda, DLC_TO_LEN, USBPACKET_MAX_SIZE, pack_can_buffer, unpack_can_buffer -from panda.tests.libpanda import libpanda_py - -lpp = libpanda_py.libpanda - -CHUNK_SIZE = USBPACKET_MAX_SIZE -TX_QUEUES = (lpp.tx1_q, lpp.tx2_q, lpp.tx3_q, lpp.txgmlan_q) - - -def unpackage_can_msg(pkt): - dat_len = DLC_TO_LEN[pkt[0].data_len_code] - dat = bytes(pkt[0].data[0:dat_len]) - return pkt[0].addr, 0, dat, pkt[0].bus - - -def random_can_messages(n, bus=None): - msgs = [] - for _ in range(n): - if bus is None: - bus = random.randint(0, 3) - address = random.randint(1, (1 << 29) - 1) - data = bytes([random.getrandbits(8) for _ in range(DLC_TO_LEN[random.randrange(0, len(DLC_TO_LEN))])]) - msgs.append((address, 0, data, bus)) - return msgs - - -class TestPandaComms(unittest.TestCase): - def setUp(self): - lpp.comms_can_reset() - - def test_tx_queues(self): - for bus in range(4): - message = (0x100, 0, b"test", bus) - - can_pkt_tx = libpanda_py.make_CANPacket(message[0], message[3], message[2]) - can_pkt_rx = libpanda_py.ffi.new('CANPacket_t *') - - assert lpp.can_push(TX_QUEUES[bus], can_pkt_tx), "CAN push failed" - assert lpp.can_pop(TX_QUEUES[bus], can_pkt_rx), "CAN pop failed" - - assert unpackage_can_msg(can_pkt_rx) == message - - def test_comms_reset_rx(self): - # store some test messages in the queue - test_msg = (0x100, 0, b"test", 0) - for _ in range(100): - can_pkt_tx = libpanda_py.make_CANPacket(test_msg[0], test_msg[3], test_msg[2]) - lpp.can_push(lpp.rx_q, can_pkt_tx) - - # read a small chunk such that we have some overflow - TINY_CHUNK_SIZE = 6 - dat = libpanda_py.ffi.new(f"uint8_t[{TINY_CHUNK_SIZE}]") - rx_len = lpp.comms_can_read(dat, TINY_CHUNK_SIZE) - assert rx_len == TINY_CHUNK_SIZE, "comms_can_read returned too little data" - - _, overflow = unpack_can_buffer(bytes(dat)) - assert len(overflow) > 0, "overflow buffer should not be empty" - - # reset the comms to clear the overflow buffer on the panda side - lpp.comms_can_reset() - - # read a large chunk, which should now contain valid messages - LARGE_CHUNK_SIZE = 512 - dat = libpanda_py.ffi.new(f"uint8_t[{LARGE_CHUNK_SIZE}]") - rx_len = lpp.comms_can_read(dat, LARGE_CHUNK_SIZE) - assert rx_len == LARGE_CHUNK_SIZE, "comms_can_read returned too little data" - - msgs, _ = unpack_can_buffer(bytes(dat)) - assert len(msgs) > 0, "message buffer should not be empty" - for m in msgs: - assert m == test_msg, "message buffer should contain valid test messages" - - def test_comms_reset_tx(self): - # store some test messages in the queue - test_msg = (0x100, 0, b"test", 0) - packed = pack_can_buffer([test_msg for _ in range(100)]) - - # write a small chunk such that we have some overflow - TINY_CHUNK_SIZE = 6 - lpp.comms_can_write(packed[0][:TINY_CHUNK_SIZE], TINY_CHUNK_SIZE) - - # reset the comms to clear the overflow buffer on the panda side - lpp.comms_can_reset() - - # write a full valid chunk, which should now contain valid messages - lpp.comms_can_write(packed[1], len(packed[1])) - - # read the messages from the queue and make sure they're valid - queue_msgs = [] - pkt = libpanda_py.ffi.new('CANPacket_t *') - while lpp.can_pop(TX_QUEUES[0], pkt): - queue_msgs.append(unpackage_can_msg(pkt)) - - assert len(queue_msgs) > 0, "message buffer should not be empty" - for m in queue_msgs: - assert m == test_msg, "message buffer should contain valid test messages" - - - def test_can_send_usb(self): - lpp.set_safety_hooks(Panda.SAFETY_ALLOUTPUT, 0) - - for bus in range(3): - with self.subTest(bus=bus): - for _ in range(100): - msgs = random_can_messages(200, bus=bus) - packed = pack_can_buffer(msgs) - - # Simulate USB bulk chunks - for buf in packed: - for i in range(0, len(buf), CHUNK_SIZE): - chunk_len = min(CHUNK_SIZE, len(buf) - i) - lpp.comms_can_write(buf[i:i+chunk_len], chunk_len) - - # Check that they ended up in the right buffers - queue_msgs = [] - pkt = libpanda_py.ffi.new('CANPacket_t *') - while lpp.can_pop(TX_QUEUES[bus], pkt): - queue_msgs.append(unpackage_can_msg(pkt)) - - self.assertEqual(len(queue_msgs), len(msgs)) - self.assertEqual(queue_msgs, msgs) - - def test_can_receive_usb(self): - msgs = random_can_messages(50000) - packets = [libpanda_py.make_CANPacket(m[0], m[3], m[2]) for m in msgs] - - rx_msgs = [] - overflow_buf = b"" - while len(packets) > 0: - # Push into queue - while lpp.can_slots_empty(lpp.rx_q) > 0 and len(packets) > 0: - lpp.can_push(lpp.rx_q, packets.pop(0)) - - # Simulate USB bulk IN chunks - MAX_TRANSFER_SIZE = 16384 - dat = libpanda_py.ffi.new(f"uint8_t[{CHUNK_SIZE}]") - while True: - buf = b"" - while len(buf) < MAX_TRANSFER_SIZE: - max_size = min(CHUNK_SIZE, MAX_TRANSFER_SIZE - len(buf)) - rx_len = lpp.comms_can_read(dat, max_size) - buf += bytes(dat[0:rx_len]) - if rx_len < max_size: - break - - if len(buf) == 0: - break - unpacked_msgs, overflow_buf = unpack_can_buffer(overflow_buf + buf) - rx_msgs.extend(unpacked_msgs) - - self.assertEqual(len(rx_msgs), len(msgs)) - self.assertEqual(rx_msgs, msgs) - - -if __name__ == "__main__": - unittest.main() diff --git a/panda/tests/usbprotocol/test_pandalib.py b/panda/tests/usbprotocol/test_pandalib.py deleted file mode 100644 index c03f246..0000000 --- a/panda/tests/usbprotocol/test_pandalib.py +++ /dev/null @@ -1,26 +0,0 @@ -#!/usr/bin/env python3 -import random -import unittest - -from panda import pack_can_buffer, unpack_can_buffer, DLC_TO_LEN - -class PandaTestPackUnpack(unittest.TestCase): - def test_panda_lib_pack_unpack(self): - overflow_buf = b'' - - to_pack = [] - for _ in range(10000): - address = random.randint(1, (1 << 29) - 1) - data = bytes([random.getrandbits(8) for _ in range(DLC_TO_LEN[random.randrange(0, len(DLC_TO_LEN))])]) - to_pack.append((address, 0, data, 0)) - - packed = pack_can_buffer(to_pack) - unpacked = [] - for dat in packed: - msgs, overflow_buf = unpack_can_buffer(overflow_buf + dat) - unpacked.extend(msgs) - - self.assertEqual(unpacked, to_pack) - -if __name__ == "__main__": - unittest.main() diff --git a/panda/tests/__init__.py b/prebuilt similarity index 100% rename from panda/tests/__init__.py rename to prebuilt diff --git a/rednose/SConscript b/rednose/SConscript deleted file mode 100644 index 52e36e0..0000000 --- a/rednose/SConscript +++ /dev/null @@ -1,17 +0,0 @@ -Import('env', 'envCython', 'common') - -cc_sources = [ - "helpers/ekf_load.cc", - "helpers/ekf_sym.cc", -] -libs = ["dl"] -if common != "": - # for SWAGLOG support - libs += [common, 'zmq'] - -ekf_objects = env.SharedObject(cc_sources) -rednose = env.Library("helpers/ekf_sym", ekf_objects, LIBS=libs) -rednose_python = envCython.Program("helpers/ekf_sym_pyx.so", ["helpers/ekf_sym_pyx.pyx", ekf_objects], - LIBS=libs + envCython["LIBS"]) - -Export('rednose', 'rednose_python') diff --git a/rednose/helpers/ekf.h b/rednose/helpers/ekf.h deleted file mode 100644 index 2afe6dd..0000000 --- a/rednose/helpers/ekf.h +++ /dev/null @@ -1,42 +0,0 @@ -#pragma once - -#include -#include -#include -#include -#include -#include -#include -#include - -#include - -typedef void (*extra_routine_t)(double *, double *); - -struct EKF { - std::string name; - std::vector kinds; - std::vector feature_kinds; - - void (*f_fun)(double *, double, double *); - void (*F_fun)(double *, double, double *); - void (*err_fun)(double *, double *, double *); - void (*inv_err_fun)(double *, double *, double *); - void (*H_mod_fun)(double *, double *); - void (*predict)(double *, double *, double *, double); - std::unordered_map hs = {}; - std::unordered_map Hs = {}; - std::unordered_map updates = {}; - std::unordered_map Hes = {}; - std::unordered_map sets = {}; - std::unordered_map extra_routines = {}; -}; - -#define ekf_lib_init(ekf) \ -extern "C" void* ekf_get() { \ - return (void*) &ekf; \ -} \ -extern void __attribute__((weak)) ekf_register(const EKF* ptr); \ -static void __attribute__((constructor)) do_ekf_init_ ## ekf(void) { \ - if (ekf_register) ekf_register(&ekf); \ -} diff --git a/rednose/helpers/ekf_load.cc b/rednose/helpers/ekf_load.cc deleted file mode 100644 index 882b0b4..0000000 --- a/rednose/helpers/ekf_load.cc +++ /dev/null @@ -1,39 +0,0 @@ -#include "ekf_load.h" -#include - -std::vector& ekf_get_all() { - static std::vector vec; - return vec; -} - -void ekf_register(const EKF* ekf) { - ekf_get_all().push_back(ekf); -} - -const EKF* ekf_lookup(const std::string& ekf_name) { - for (const auto& ekfi : ekf_get_all()) { - if (ekf_name == ekfi->name) { - return ekfi; - } - } - return NULL; -} - -void ekf_load_and_register(const std::string& ekf_directory, const std::string& ekf_name) { - if (ekf_lookup(ekf_name)) { - return; - } - -#ifdef __APPLE__ - std::string dylib_ext = ".dylib"; -#else - std::string dylib_ext = ".so"; -#endif - std::string ekf_path = ekf_directory + "/lib" + ekf_name + dylib_ext; - void* handle = dlopen(ekf_path.c_str(), RTLD_NOW); - assert(handle); - void* (*ekf_get)() = (void*(*)())dlsym(handle, "ekf_get"); - assert(ekf_get != NULL); - const EKF* ekf = (const EKF*)ekf_get(); - ekf_register(ekf); -} diff --git a/rednose/helpers/ekf_load.h b/rednose/helpers/ekf_load.h deleted file mode 100644 index 89180b8..0000000 --- a/rednose/helpers/ekf_load.h +++ /dev/null @@ -1,9 +0,0 @@ -#include -#include - -#include "ekf.h" - -std::vector& ekf_get_all(); -const EKF* ekf_lookup(const std::string& ekf_name); -void ekf_register(const EKF* ekf); -void ekf_load_and_register(const std::string& ekf_directory, const std::string& ekf_name); diff --git a/rednose/helpers/ekf_sym.cc b/rednose/helpers/ekf_sym.cc deleted file mode 100644 index 38d419d..0000000 --- a/rednose/helpers/ekf_sym.cc +++ /dev/null @@ -1,223 +0,0 @@ -#include "ekf_sym.h" -#include "logger/logger.h" - -using namespace EKFS; -using namespace Eigen; - -EKFSym::EKFSym(std::string name, Map Q, Map x_initial, Map P_initial, int dim_main, - int dim_main_err, int N, int dim_augment, int dim_augment_err, std::vector maha_test_kinds, - std::vector quaternion_idxs, std::vector global_vars, double max_rewind_age) -{ - // TODO: add logger - this->ekf = ekf_lookup(name); - assert(this->ekf); - - this->msckf = N > 0; - this->N = N; - this->dim_augment = dim_augment; - this->dim_augment_err = dim_augment_err; - this->dim_main = dim_main; - this->dim_main_err = dim_main_err; - - this->dim_x = x_initial.rows(); - this->dim_err = P_initial.rows(); - - assert(dim_main + dim_augment * N == dim_x); - assert(dim_main_err + dim_augment_err * N == this->dim_err); - assert(Q.rows() == P_initial.rows() && Q.cols() == P_initial.cols()); - - // kinds that should get mahalanobis distance - // tested for outlier rejection - this->maha_test_kinds = maha_test_kinds; - - // quaternions need normalization - this->quaternion_idxs = quaternion_idxs; - - this->global_vars = global_vars; - - // Process noise - this->Q = Q; - - this->max_rewind_age = max_rewind_age; - this->init_state(x_initial, P_initial, NAN); -} - -void EKFSym::init_state(Map state, Map covs, double init_filter_time) { - this->x = state; - this->P = covs; - this->filter_time = init_filter_time; - this->augment_times = VectorXd::Zero(this->N); - this->reset_rewind(); -} - -VectorXd EKFSym::state() { - return this->x; -} - -MatrixXdr EKFSym::covs() { - return this->P; -} - -void EKFSym::set_filter_time(double t) { - this->filter_time = t; -} - -double EKFSym::get_filter_time() { - return this->filter_time; -} - -void EKFSym::normalize_quaternions() { - for(std::size_t i = 0; i < this->quaternion_idxs.size(); ++i) { - this->normalize_slice(this->quaternion_idxs[i], this->quaternion_idxs[i] + 4); - } -} - -void EKFSym::normalize_slice(int slice_start, int slice_end_ex) { - this->x.block(slice_start, 0, slice_end_ex - slice_start, this->x.cols()).normalize(); -} - -void EKFSym::set_global(std::string global_var, double val) { - this->ekf->sets.at(global_var)(val); -} - -std::optional EKFSym::predict_and_update_batch(double t, int kind, std::vector> z_map, - std::vector> R_map, std::vector> extra_args, bool augment) -{ - // TODO handle rewinding at this level - - std::deque rewound; - if (!std::isnan(this->filter_time) && t < this->filter_time) { - if (this->rewind_t.empty() || t < this->rewind_t.front() || t < this->rewind_t.back() - this->max_rewind_age) { - LOGD("observation too old at %f with filter at %f, ignoring!", t, this->filter_time); - return std::nullopt; - } - rewound = this->rewind(t); - } - - Observation obs; - obs.t = t; - obs.kind = kind; - obs.extra_args = extra_args; - for (Map zi : z_map) { - obs.z.push_back(zi); - } - for (Map Ri : R_map) { - obs.R.push_back(Ri); - } - - std::optional res = std::make_optional(this->predict_and_update_batch(obs, augment)); - - // optional fast forward - while (!rewound.empty()) { - this->predict_and_update_batch(rewound.front(), false); - rewound.pop_front(); - } - - return res; -} - -void EKFSym::reset_rewind() { - this->rewind_obscache.clear(); - this->rewind_t.clear(); - this->rewind_states.clear(); -} - -std::deque EKFSym::rewind(double t) { - std::deque rewound; - - // rewind observations until t is after previous observation - while (this->rewind_t.back() > t) { - rewound.push_front(this->rewind_obscache.back()); - this->rewind_t.pop_back(); - this->rewind_states.pop_back(); - this->rewind_obscache.pop_back(); - } - - // set the state to the time right before that - this->filter_time = this->rewind_t.back(); - this->x = this->rewind_states.back().first; - this->P = this->rewind_states.back().second; - - return rewound; -} - -void EKFSym::checkpoint(Observation& obs) { - // push to rewinder - this->rewind_t.push_back(this->filter_time); - this->rewind_states.push_back(std::make_pair(this->x, this->P)); - this->rewind_obscache.push_back(obs); - - // only keep a certain number around - if (this->rewind_t.size() > REWIND_TO_KEEP) { - this->rewind_t.pop_front(); - this->rewind_states.pop_front(); - this->rewind_obscache.pop_front(); - } -} - -Estimate EKFSym::predict_and_update_batch(Observation& obs, bool augment) { - assert(obs.z.size() == obs.R.size()); - assert(obs.z.size() == obs.extra_args.size()); - - this->predict(obs.t); - - Estimate res; - res.t = obs.t; - res.kind = obs.kind; - res.z = obs.z; - res.extra_args = obs.extra_args; - res.xk1 = this->x; - res.Pk1 = this->P; - - // update batch - std::vector y; - for (int i = 0; i < obs.z.size(); i++) { - assert(obs.z[i].rows() == obs.R[i].rows()); - assert(obs.z[i].rows() == obs.R[i].cols()); - - // update state - y.push_back(this->update(obs.kind, obs.z[i], obs.R[i], obs.extra_args[i])); - } - - res.xk = this->x; - res.Pk = this->P; - res.y = y; - - assert(!augment); // TODO - // if (augment) { - // this->augment(); - // } - - this->checkpoint(obs); - - return res; -} - -void EKFSym::predict(double t) { - // initialize time - if (std::isnan(this->filter_time)) { - this->filter_time = t; - } - - // predict - double dt = t - this->filter_time; - assert(dt >= 0.0); - - this->ekf->predict(this->x.data(), this->P.data(), this->Q.data(), dt); - this->normalize_quaternions(); - this->filter_time = t; -} - -VectorXd EKFSym::update(int kind, VectorXd z, MatrixXdr R, std::vector extra_args) { - this->ekf->updates.at(kind)(this->x.data(), this->P.data(), z.data(), R.data(), extra_args.data()); - this->normalize_quaternions(); - - if (this->msckf && std::find(this->feature_track_kinds.begin(), this->feature_track_kinds.end(), kind) != this->feature_track_kinds.end()) { - return z.head(z.rows() - extra_args.size()); - } - return z; -} - -extra_routine_t EKFSym::get_extra_routine(const std::string& routine) { - return this->ekf->extra_routines.at(routine); -} diff --git a/rednose/helpers/ekf_sym.h b/rednose/helpers/ekf_sym.h deleted file mode 100644 index b83d7f3..0000000 --- a/rednose/helpers/ekf_sym.h +++ /dev/null @@ -1,113 +0,0 @@ -#pragma once - -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include - -#include "ekf.h" -#include "ekf_load.h" - -#define REWIND_TO_KEEP 512 - -namespace EKFS { - -typedef Eigen::Matrix MatrixXdr; - -typedef struct Observation { - double t; - int kind; - std::vector z; - std::vector R; - std::vector> extra_args; -} Observation; - -typedef struct Estimate { - Eigen::VectorXd xk1; - Eigen::VectorXd xk; - MatrixXdr Pk1; - MatrixXdr Pk; - double t; - int kind; - std::vector y; - std::vector z; - std::vector> extra_args; -} Estimate; - -class EKFSym { -public: - EKFSym(std::string name, Eigen::Map Q, Eigen::Map x_initial, - Eigen::Map P_initial, int dim_main, int dim_main_err, int N = 0, int dim_augment = 0, - int dim_augment_err = 0, std::vector maha_test_kinds = std::vector(), - std::vector quaternion_idxs = std::vector(), - std::vector global_vars = std::vector(), double max_rewind_age = 1.0); - void init_state(Eigen::Map state, Eigen::Map covs, double filter_time); - - Eigen::VectorXd state(); - MatrixXdr covs(); - void set_filter_time(double t); - double get_filter_time(); - void normalize_quaternions(); - void normalize_slice(int slice_start, int slice_end_ex); - void set_global(std::string global_var, double val); - void reset_rewind(); - - void predict(double t); - std::optional predict_and_update_batch(double t, int kind, std::vector> z, - std::vector> R, std::vector> extra_args = {{}}, bool augment = false); - - extra_routine_t get_extra_routine(const std::string& routine); - -private: - std::deque rewind(double t); - void checkpoint(Observation& obs); - - Estimate predict_and_update_batch(Observation& obs, bool augment); - Eigen::VectorXd update(int kind, Eigen::VectorXd z, MatrixXdr R, std::vector extra_args); - - // stuct with linked sympy generated functions - const EKF *ekf = NULL; - - Eigen::VectorXd x; // state - MatrixXdr P; // covs - - bool msckf; - int N; - int dim_augment; - int dim_augment_err; - int dim_main; - int dim_main_err; - - // state - int dim_x; - int dim_err; - - double filter_time; - - std::vector maha_test_kinds; - std::vector quaternion_idxs; - - std::vector global_vars; - - // process noise - MatrixXdr Q; - - // rewind stuff - double max_rewind_age; - std::deque rewind_t; - std::deque> rewind_states; - std::deque rewind_obscache; - - Eigen::VectorXd augment_times; - - std::vector feature_track_kinds; -}; - -} diff --git a/rednose/helpers/ekf_sym_pyx.cpp b/rednose/helpers/ekf_sym_pyx.cpp new file mode 100644 index 0000000..de77e6b --- /dev/null +++ b/rednose/helpers/ekf_sym_pyx.cpp @@ -0,0 +1,35816 @@ +/* Generated by Cython 3.0.8 */ + +/* BEGIN: Cython Metadata +{ + "distutils": { + "depends": [ + "rednose/helpers/ekf_load.h", + "rednose/helpers/ekf_sym.h" + ], + "language": "c++", + "name": "rednose.helpers.ekf_sym_pyx", + "sources": [ + "/data/openpilot/rednose/helpers/ekf_sym_pyx.pyx" + ] + }, + "module_name": "rednose.helpers.ekf_sym_pyx" +} +END: Cython Metadata */ + +#ifndef PY_SSIZE_T_CLEAN +#define PY_SSIZE_T_CLEAN +#endif /* PY_SSIZE_T_CLEAN */ +#if defined(CYTHON_LIMITED_API) && 0 + #ifndef Py_LIMITED_API + #if CYTHON_LIMITED_API+0 > 0x03030000 + #define Py_LIMITED_API CYTHON_LIMITED_API + #else + #define Py_LIMITED_API 0x03030000 + #endif + #endif +#endif + +#include "Python.h" +#ifndef Py_PYTHON_H + #error Python headers needed to compile C extensions, please install development version of Python. +#elif PY_VERSION_HEX < 0x02070000 || (0x03000000 <= PY_VERSION_HEX && PY_VERSION_HEX < 0x03030000) + #error Cython requires Python 2.7+ or Python 3.3+. +#else +#if defined(CYTHON_LIMITED_API) && CYTHON_LIMITED_API +#define __PYX_EXTRA_ABI_MODULE_NAME "limited" +#else +#define __PYX_EXTRA_ABI_MODULE_NAME "" +#endif +#define CYTHON_ABI "3_0_8" __PYX_EXTRA_ABI_MODULE_NAME +#define __PYX_ABI_MODULE_NAME "_cython_" CYTHON_ABI +#define __PYX_TYPE_MODULE_PREFIX __PYX_ABI_MODULE_NAME "." +#define CYTHON_HEX_VERSION 0x030008F0 +#define CYTHON_FUTURE_DIVISION 1 +#include +#ifndef offsetof + #define offsetof(type, member) ( (size_t) & ((type*)0) -> member ) +#endif +#if !defined(_WIN32) && !defined(WIN32) && !defined(MS_WINDOWS) + #ifndef __stdcall + #define __stdcall + #endif + #ifndef __cdecl + #define __cdecl + #endif + #ifndef __fastcall + #define __fastcall + #endif +#endif +#ifndef DL_IMPORT + #define DL_IMPORT(t) t +#endif +#ifndef DL_EXPORT + #define DL_EXPORT(t) t +#endif +#define __PYX_COMMA , +#ifndef HAVE_LONG_LONG + #define HAVE_LONG_LONG +#endif +#ifndef PY_LONG_LONG + #define PY_LONG_LONG LONG_LONG +#endif +#ifndef Py_HUGE_VAL + #define Py_HUGE_VAL HUGE_VAL +#endif +#define __PYX_LIMITED_VERSION_HEX PY_VERSION_HEX +#if defined(GRAALVM_PYTHON) + /* For very preliminary testing purposes. Most variables are set the same as PyPy. + The existence of this section does not imply that anything works or is even tested */ + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 1 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(PYPY_VERSION) + #define CYTHON_COMPILING_IN_PYPY 1 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #ifndef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #endif + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #if PY_VERSION_HEX < 0x03090000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE (PY_VERSION_HEX >= 0x030400a1 && PYPY_VERSION_NUM >= 0x07030C00) + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(CYTHON_LIMITED_API) + #ifdef Py_LIMITED_API + #undef __PYX_LIMITED_VERSION_HEX + #define __PYX_LIMITED_VERSION_HEX Py_LIMITED_API + #endif + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 1 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_CLINE_IN_TRACEBACK + #define CYTHON_CLINE_IN_TRACEBACK 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 1 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #endif + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 1 + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(Py_GIL_DISABLED) || defined(Py_NOGIL) + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 1 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #ifndef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 +#else + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 1 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #ifndef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #endif + #ifndef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 1 + #endif + #if PY_MAJOR_VERSION < 3 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #ifndef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 1 + #endif + #ifndef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 1 + #endif + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #if PY_VERSION_HEX < 0x030300F0 || PY_VERSION_HEX >= 0x030B00A2 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #elif !defined(CYTHON_USE_UNICODE_WRITER) + #define CYTHON_USE_UNICODE_WRITER 1 + #endif + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #ifndef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 1 + #endif + #ifndef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL (PY_MAJOR_VERSION < 3 || PY_VERSION_HEX >= 0x03060000 && PY_VERSION_HEX < 0x030C00A6) + #endif + #ifndef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL (PY_VERSION_HEX >= 0x030700A1) + #endif + #ifndef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 1 + #endif + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #endif + #if PY_VERSION_HEX < 0x030400a1 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #elif !defined(CYTHON_USE_TP_FINALIZE) + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #if PY_VERSION_HEX < 0x030600B1 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #elif !defined(CYTHON_USE_DICT_VERSIONS) + #define CYTHON_USE_DICT_VERSIONS (PY_VERSION_HEX < 0x030C00A5) + #endif + #if PY_VERSION_HEX < 0x030700A3 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #elif !defined(CYTHON_USE_EXC_INFO_STACK) + #define CYTHON_USE_EXC_INFO_STACK 1 + #endif + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 1 + #endif +#endif +#if !defined(CYTHON_FAST_PYCCALL) +#define CYTHON_FAST_PYCCALL (CYTHON_FAST_PYCALL && PY_VERSION_HEX >= 0x030600B1) +#endif +#if !defined(CYTHON_VECTORCALL) +#define CYTHON_VECTORCALL (CYTHON_FAST_PYCCALL && PY_VERSION_HEX >= 0x030800B1) +#endif +#define CYTHON_BACKPORT_VECTORCALL (CYTHON_METH_FASTCALL && PY_VERSION_HEX < 0x030800B1) +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_MAJOR_VERSION < 3 + #include "longintrepr.h" + #endif + #undef SHIFT + #undef BASE + #undef MASK + #ifdef SIZEOF_VOID_P + enum { __pyx_check_sizeof_voidp = 1 / (int)(SIZEOF_VOID_P == sizeof(void*)) }; + #endif +#endif +#ifndef __has_attribute + #define __has_attribute(x) 0 +#endif +#ifndef __has_cpp_attribute + #define __has_cpp_attribute(x) 0 +#endif +#ifndef CYTHON_RESTRICT + #if defined(__GNUC__) + #define CYTHON_RESTRICT __restrict__ + #elif defined(_MSC_VER) && _MSC_VER >= 1400 + #define CYTHON_RESTRICT __restrict + #elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define CYTHON_RESTRICT restrict + #else + #define CYTHON_RESTRICT + #endif +#endif +#ifndef CYTHON_UNUSED + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(maybe_unused) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(maybe_unused) + #define CYTHON_UNUSED [[maybe_unused]] + #endif + #endif + #endif +#endif +#ifndef CYTHON_UNUSED +# if defined(__GNUC__) +# if !(defined(__cplusplus)) || (__GNUC__ > 3 || (__GNUC__ == 3 && __GNUC_MINOR__ >= 4)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +# elif defined(__ICC) || (defined(__INTEL_COMPILER) && !defined(_MSC_VER)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +#endif +#ifndef CYTHON_UNUSED_VAR +# if defined(__cplusplus) + template void CYTHON_UNUSED_VAR( const T& ) { } +# else +# define CYTHON_UNUSED_VAR(x) (void)(x) +# endif +#endif +#ifndef CYTHON_MAYBE_UNUSED_VAR + #define CYTHON_MAYBE_UNUSED_VAR(x) CYTHON_UNUSED_VAR(x) +#endif +#ifndef CYTHON_NCP_UNUSED +# if CYTHON_COMPILING_IN_CPYTHON +# define CYTHON_NCP_UNUSED +# else +# define CYTHON_NCP_UNUSED CYTHON_UNUSED +# endif +#endif +#ifndef CYTHON_USE_CPP_STD_MOVE + #if defined(__cplusplus) && (\ + __cplusplus >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1600)) + #define CYTHON_USE_CPP_STD_MOVE 1 + #else + #define CYTHON_USE_CPP_STD_MOVE 0 + #endif +#endif +#define __Pyx_void_to_None(void_result) ((void)(void_result), Py_INCREF(Py_None), Py_None) +#ifdef _MSC_VER + #ifndef _MSC_STDINT_H_ + #if _MSC_VER < 1300 + typedef unsigned char uint8_t; + typedef unsigned short uint16_t; + typedef unsigned int uint32_t; + #else + typedef unsigned __int8 uint8_t; + typedef unsigned __int16 uint16_t; + typedef unsigned __int32 uint32_t; + #endif + #endif + #if _MSC_VER < 1300 + #ifdef _WIN64 + typedef unsigned long long __pyx_uintptr_t; + #else + typedef unsigned int __pyx_uintptr_t; + #endif + #else + #ifdef _WIN64 + typedef unsigned __int64 __pyx_uintptr_t; + #else + typedef unsigned __int32 __pyx_uintptr_t; + #endif + #endif +#else + #include + typedef uintptr_t __pyx_uintptr_t; +#endif +#ifndef CYTHON_FALLTHROUGH + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(fallthrough) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(fallthrough) + #define CYTHON_FALLTHROUGH [[fallthrough]] + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_cpp_attribute(clang::fallthrough) + #define CYTHON_FALLTHROUGH [[clang::fallthrough]] + #elif __has_cpp_attribute(gnu::fallthrough) + #define CYTHON_FALLTHROUGH [[gnu::fallthrough]] + #endif + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_attribute(fallthrough) + #define CYTHON_FALLTHROUGH __attribute__((fallthrough)) + #else + #define CYTHON_FALLTHROUGH + #endif + #endif + #if defined(__clang__) && defined(__apple_build_version__) + #if __apple_build_version__ < 7000000 + #undef CYTHON_FALLTHROUGH + #define CYTHON_FALLTHROUGH + #endif + #endif +#endif +#ifdef __cplusplus + template + struct __PYX_IS_UNSIGNED_IMPL {static const bool value = T(0) < T(-1);}; + #define __PYX_IS_UNSIGNED(type) (__PYX_IS_UNSIGNED_IMPL::value) +#else + #define __PYX_IS_UNSIGNED(type) (((type)-1) > 0) +#endif +#if CYTHON_COMPILING_IN_PYPY == 1 + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x030A0000) +#else + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x03090000) +#endif +#define __PYX_REINTERPRET_FUNCION(func_pointer, other_pointer) ((func_pointer)(void(*)(void))(other_pointer)) + +#ifndef __cplusplus + #error "Cython files generated with the C++ option must be compiled with a C++ compiler." +#endif +#ifndef CYTHON_INLINE + #if defined(__clang__) + #define CYTHON_INLINE __inline__ __attribute__ ((__unused__)) + #else + #define CYTHON_INLINE inline + #endif +#endif +template +void __Pyx_call_destructor(T& x) { + x.~T(); +} +template +class __Pyx_FakeReference { + public: + __Pyx_FakeReference() : ptr(NULL) { } + __Pyx_FakeReference(const T& ref) : ptr(const_cast(&ref)) { } + T *operator->() { return ptr; } + T *operator&() { return ptr; } + operator T&() { return *ptr; } + template bool operator ==(const U& other) const { return *ptr == other; } + template bool operator !=(const U& other) const { return *ptr != other; } + template bool operator==(const __Pyx_FakeReference& other) const { return *ptr == *other.ptr; } + template bool operator!=(const __Pyx_FakeReference& other) const { return *ptr != *other.ptr; } + private: + T *ptr; +}; + +#define __PYX_BUILD_PY_SSIZE_T "n" +#define CYTHON_FORMAT_SSIZE_T "z" +#if PY_MAJOR_VERSION < 3 + #define __Pyx_BUILTIN_MODULE_NAME "__builtin__" + #define __Pyx_DefaultClassType PyClass_Type + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a+k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_BUILTIN_MODULE_NAME "builtins" + #define __Pyx_DefaultClassType PyType_Type +#if CYTHON_COMPILING_IN_LIMITED_API + static CYTHON_INLINE PyObject* __Pyx_PyCode_New(int a, int p, int k, int l, int s, int f, + PyObject *code, PyObject *c, PyObject* n, PyObject *v, + PyObject *fv, PyObject *cell, PyObject* fn, + PyObject *name, int fline, PyObject *lnos) { + PyObject *exception_table = NULL; + PyObject *types_module=NULL, *code_type=NULL, *result=NULL; + #if __PYX_LIMITED_VERSION_HEX < 0x030B0000 + PyObject *version_info; + PyObject *py_minor_version = NULL; + #endif + long minor_version = 0; + PyObject *type, *value, *traceback; + PyErr_Fetch(&type, &value, &traceback); + #if __PYX_LIMITED_VERSION_HEX >= 0x030B0000 + minor_version = 11; + #else + if (!(version_info = PySys_GetObject("version_info"))) goto end; + if (!(py_minor_version = PySequence_GetItem(version_info, 1))) goto end; + minor_version = PyLong_AsLong(py_minor_version); + Py_DECREF(py_minor_version); + if (minor_version == -1 && PyErr_Occurred()) goto end; + #endif + if (!(types_module = PyImport_ImportModule("types"))) goto end; + if (!(code_type = PyObject_GetAttrString(types_module, "CodeType"))) goto end; + if (minor_version <= 7) { + (void)p; + result = PyObject_CallFunction(code_type, "iiiiiOOOOOOiOO", a, k, l, s, f, code, + c, n, v, fn, name, fline, lnos, fv, cell); + } else if (minor_version <= 10) { + result = PyObject_CallFunction(code_type, "iiiiiiOOOOOOiOO", a,p, k, l, s, f, code, + c, n, v, fn, name, fline, lnos, fv, cell); + } else { + if (!(exception_table = PyBytes_FromStringAndSize(NULL, 0))) goto end; + result = PyObject_CallFunction(code_type, "iiiiiiOOOOOOOiOO", a,p, k, l, s, f, code, + c, n, v, fn, name, name, fline, lnos, exception_table, fv, cell); + } + end: + Py_XDECREF(code_type); + Py_XDECREF(exception_table); + Py_XDECREF(types_module); + if (type) { + PyErr_Restore(type, value, traceback); + } + return result; + } + #ifndef CO_OPTIMIZED + #define CO_OPTIMIZED 0x0001 + #endif + #ifndef CO_NEWLOCALS + #define CO_NEWLOCALS 0x0002 + #endif + #ifndef CO_VARARGS + #define CO_VARARGS 0x0004 + #endif + #ifndef CO_VARKEYWORDS + #define CO_VARKEYWORDS 0x0008 + #endif + #ifndef CO_ASYNC_GENERATOR + #define CO_ASYNC_GENERATOR 0x0200 + #endif + #ifndef CO_GENERATOR + #define CO_GENERATOR 0x0020 + #endif + #ifndef CO_COROUTINE + #define CO_COROUTINE 0x0080 + #endif +#elif PY_VERSION_HEX >= 0x030B0000 + static CYTHON_INLINE PyCodeObject* __Pyx_PyCode_New(int a, int p, int k, int l, int s, int f, + PyObject *code, PyObject *c, PyObject* n, PyObject *v, + PyObject *fv, PyObject *cell, PyObject* fn, + PyObject *name, int fline, PyObject *lnos) { + PyCodeObject *result; + PyObject *empty_bytes = PyBytes_FromStringAndSize("", 0); + if (!empty_bytes) return NULL; + result = + #if PY_VERSION_HEX >= 0x030C0000 + PyUnstable_Code_NewWithPosOnlyArgs + #else + PyCode_NewWithPosOnlyArgs + #endif + (a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, name, fline, lnos, empty_bytes); + Py_DECREF(empty_bytes); + return result; + } +#elif PY_VERSION_HEX >= 0x030800B2 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_NewWithPosOnlyArgs(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#endif +#endif +#if PY_VERSION_HEX >= 0x030900A4 || defined(Py_IS_TYPE) + #define __Pyx_IS_TYPE(ob, type) Py_IS_TYPE(ob, type) +#else + #define __Pyx_IS_TYPE(ob, type) (((const PyObject*)ob)->ob_type == (type)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_Is) + #define __Pyx_Py_Is(x, y) Py_Is(x, y) +#else + #define __Pyx_Py_Is(x, y) ((x) == (y)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsNone) + #define __Pyx_Py_IsNone(ob) Py_IsNone(ob) +#else + #define __Pyx_Py_IsNone(ob) __Pyx_Py_Is((ob), Py_None) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsTrue) + #define __Pyx_Py_IsTrue(ob) Py_IsTrue(ob) +#else + #define __Pyx_Py_IsTrue(ob) __Pyx_Py_Is((ob), Py_True) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsFalse) + #define __Pyx_Py_IsFalse(ob) Py_IsFalse(ob) +#else + #define __Pyx_Py_IsFalse(ob) __Pyx_Py_Is((ob), Py_False) +#endif +#define __Pyx_NoneAsNull(obj) (__Pyx_Py_IsNone(obj) ? NULL : (obj)) +#if PY_VERSION_HEX >= 0x030900F0 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_GC_IsFinalized(o) PyObject_GC_IsFinalized(o) +#else + #define __Pyx_PyObject_GC_IsFinalized(o) _PyGC_FINALIZED(o) +#endif +#ifndef CO_COROUTINE + #define CO_COROUTINE 0x80 +#endif +#ifndef CO_ASYNC_GENERATOR + #define CO_ASYNC_GENERATOR 0x200 +#endif +#ifndef Py_TPFLAGS_CHECKTYPES + #define Py_TPFLAGS_CHECKTYPES 0 +#endif +#ifndef Py_TPFLAGS_HAVE_INDEX + #define Py_TPFLAGS_HAVE_INDEX 0 +#endif +#ifndef Py_TPFLAGS_HAVE_NEWBUFFER + #define Py_TPFLAGS_HAVE_NEWBUFFER 0 +#endif +#ifndef Py_TPFLAGS_HAVE_FINALIZE + #define Py_TPFLAGS_HAVE_FINALIZE 0 +#endif +#ifndef Py_TPFLAGS_SEQUENCE + #define Py_TPFLAGS_SEQUENCE 0 +#endif +#ifndef Py_TPFLAGS_MAPPING + #define Py_TPFLAGS_MAPPING 0 +#endif +#ifndef METH_STACKLESS + #define METH_STACKLESS 0 +#endif +#if PY_VERSION_HEX <= 0x030700A3 || !defined(METH_FASTCALL) + #ifndef METH_FASTCALL + #define METH_FASTCALL 0x80 + #endif + typedef PyObject *(*__Pyx_PyCFunctionFast) (PyObject *self, PyObject *const *args, Py_ssize_t nargs); + typedef PyObject *(*__Pyx_PyCFunctionFastWithKeywords) (PyObject *self, PyObject *const *args, + Py_ssize_t nargs, PyObject *kwnames); +#else + #define __Pyx_PyCFunctionFast _PyCFunctionFast + #define __Pyx_PyCFunctionFastWithKeywords _PyCFunctionFastWithKeywords +#endif +#if CYTHON_METH_FASTCALL + #define __Pyx_METH_FASTCALL METH_FASTCALL + #define __Pyx_PyCFunction_FastCall __Pyx_PyCFunctionFast + #define __Pyx_PyCFunction_FastCallWithKeywords __Pyx_PyCFunctionFastWithKeywords +#else + #define __Pyx_METH_FASTCALL METH_VARARGS + #define __Pyx_PyCFunction_FastCall PyCFunction + #define __Pyx_PyCFunction_FastCallWithKeywords PyCFunctionWithKeywords +#endif +#if CYTHON_VECTORCALL + #define __pyx_vectorcallfunc vectorcallfunc + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET PY_VECTORCALL_ARGUMENTS_OFFSET + #define __Pyx_PyVectorcall_NARGS(n) PyVectorcall_NARGS((size_t)(n)) +#elif CYTHON_BACKPORT_VECTORCALL + typedef PyObject *(*__pyx_vectorcallfunc)(PyObject *callable, PyObject *const *args, + size_t nargsf, PyObject *kwnames); + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET ((size_t)1 << (8 * sizeof(size_t) - 1)) + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(((size_t)(n)) & ~__Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET)) +#else + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET 0 + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(n)) +#endif +#if PY_MAJOR_VERSION >= 0x030900B1 +#define __Pyx_PyCFunction_CheckExact(func) PyCFunction_CheckExact(func) +#else +#define __Pyx_PyCFunction_CheckExact(func) PyCFunction_Check(func) +#endif +#define __Pyx_CyOrPyCFunction_Check(func) PyCFunction_Check(func) +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_CyOrPyCFunction_GET_FUNCTION(func) (((PyCFunctionObject*)(func))->m_ml->ml_meth) +#elif !CYTHON_COMPILING_IN_LIMITED_API +#define __Pyx_CyOrPyCFunction_GET_FUNCTION(func) PyCFunction_GET_FUNCTION(func) +#endif +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_CyOrPyCFunction_GET_FLAGS(func) (((PyCFunctionObject*)(func))->m_ml->ml_flags) +static CYTHON_INLINE PyObject* __Pyx_CyOrPyCFunction_GET_SELF(PyObject *func) { + return (__Pyx_CyOrPyCFunction_GET_FLAGS(func) & METH_STATIC) ? NULL : ((PyCFunctionObject*)func)->m_self; +} +#endif +static CYTHON_INLINE int __Pyx__IsSameCFunction(PyObject *func, void *cfunc) { +#if CYTHON_COMPILING_IN_LIMITED_API + return PyCFunction_Check(func) && PyCFunction_GetFunction(func) == (PyCFunction) cfunc; +#else + return PyCFunction_Check(func) && PyCFunction_GET_FUNCTION(func) == (PyCFunction) cfunc; +#endif +} +#define __Pyx_IsSameCFunction(func, cfunc) __Pyx__IsSameCFunction(func, cfunc) +#if __PYX_LIMITED_VERSION_HEX < 0x030900B1 + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) ((void)m, PyType_FromSpecWithBases(s, b)) + typedef PyObject *(*__Pyx_PyCMethod)(PyObject *, PyTypeObject *, PyObject *const *, size_t, PyObject *); +#else + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) PyType_FromModuleAndSpec(m, s, b) + #define __Pyx_PyCMethod PyCMethod +#endif +#ifndef METH_METHOD + #define METH_METHOD 0x200 +#endif +#if CYTHON_COMPILING_IN_PYPY && !defined(PyObject_Malloc) + #define PyObject_Malloc(s) PyMem_Malloc(s) + #define PyObject_Free(p) PyMem_Free(p) + #define PyObject_Realloc(p) PyMem_Realloc(p) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) +#else + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) (frame)->f_lineno = (lineno) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyThreadState_Current PyThreadState_Get() +#elif !CYTHON_FAST_THREAD_STATE + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#elif PY_VERSION_HEX >= 0x030d00A1 + #define __Pyx_PyThreadState_Current PyThreadState_GetUnchecked() +#elif PY_VERSION_HEX >= 0x03060000 + #define __Pyx_PyThreadState_Current _PyThreadState_UncheckedGet() +#elif PY_VERSION_HEX >= 0x03000000 + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#else + #define __Pyx_PyThreadState_Current _PyThreadState_Current +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE void *__Pyx_PyModule_GetState(PyObject *op) +{ + void *result; + result = PyModule_GetState(op); + if (!result) + Py_FatalError("Couldn't find the module state"); + return result; +} +#endif +#define __Pyx_PyObject_GetSlot(obj, name, func_ctype) __Pyx_PyType_GetSlot(Py_TYPE(obj), name, func_ctype) +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((func_ctype) PyType_GetSlot((type), Py_##name)) +#else + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((type)->name) +#endif +#if PY_VERSION_HEX < 0x030700A2 && !defined(PyThread_tss_create) && !defined(Py_tss_NEEDS_INIT) +#include "pythread.h" +#define Py_tss_NEEDS_INIT 0 +typedef int Py_tss_t; +static CYTHON_INLINE int PyThread_tss_create(Py_tss_t *key) { + *key = PyThread_create_key(); + return 0; +} +static CYTHON_INLINE Py_tss_t * PyThread_tss_alloc(void) { + Py_tss_t *key = (Py_tss_t *)PyObject_Malloc(sizeof(Py_tss_t)); + *key = Py_tss_NEEDS_INIT; + return key; +} +static CYTHON_INLINE void PyThread_tss_free(Py_tss_t *key) { + PyObject_Free(key); +} +static CYTHON_INLINE int PyThread_tss_is_created(Py_tss_t *key) { + return *key != Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE void PyThread_tss_delete(Py_tss_t *key) { + PyThread_delete_key(*key); + *key = Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE int PyThread_tss_set(Py_tss_t *key, void *value) { + return PyThread_set_key_value(*key, value); +} +static CYTHON_INLINE void * PyThread_tss_get(Py_tss_t *key) { + return PyThread_get_key_value(*key); +} +#endif +#if PY_MAJOR_VERSION < 3 + #if CYTHON_COMPILING_IN_PYPY + #if PYPY_VERSION_NUM < 0x07030600 + #if defined(__cplusplus) && __cplusplus >= 201402L + [[deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")]] + #elif defined(__GNUC__) || defined(__clang__) + __attribute__ ((__deprecated__("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6"))) + #elif defined(_MSC_VER) + __declspec(deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")) + #endif + static CYTHON_INLINE int PyGILState_Check(void) { + return 0; + } + #else // PYPY_VERSION_NUM < 0x07030600 + #endif // PYPY_VERSION_NUM < 0x07030600 + #else + static CYTHON_INLINE int PyGILState_Check(void) { + PyThreadState * tstate = _PyThreadState_Current; + return tstate && (tstate == PyGILState_GetThisThreadState()); + } + #endif +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030d0000 || defined(_PyDict_NewPresized) +#define __Pyx_PyDict_NewPresized(n) ((n <= 8) ? PyDict_New() : _PyDict_NewPresized(n)) +#else +#define __Pyx_PyDict_NewPresized(n) PyDict_New() +#endif +#if PY_MAJOR_VERSION >= 3 || CYTHON_FUTURE_DIVISION + #define __Pyx_PyNumber_Divide(x,y) PyNumber_TrueDivide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceTrueDivide(x,y) +#else + #define __Pyx_PyNumber_Divide(x,y) PyNumber_Divide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceDivide(x,y) +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX > 0x030600B4 && PY_VERSION_HEX < 0x030d0000 && CYTHON_USE_UNICODE_INTERNALS +#define __Pyx_PyDict_GetItemStrWithError(dict, name) _PyDict_GetItem_KnownHash(dict, name, ((PyASCIIObject *) name)->hash) +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStr(PyObject *dict, PyObject *name) { + PyObject *res = __Pyx_PyDict_GetItemStrWithError(dict, name); + if (res == NULL) PyErr_Clear(); + return res; +} +#elif PY_MAJOR_VERSION >= 3 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07020000) +#define __Pyx_PyDict_GetItemStrWithError PyDict_GetItemWithError +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#else +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStrWithError(PyObject *dict, PyObject *name) { +#if CYTHON_COMPILING_IN_PYPY + return PyDict_GetItem(dict, name); +#else + PyDictEntry *ep; + PyDictObject *mp = (PyDictObject*) dict; + long hash = ((PyStringObject *) name)->ob_shash; + assert(hash != -1); + ep = (mp->ma_lookup)(mp, name, hash); + if (ep == NULL) { + return NULL; + } + return ep->me_value; +#endif +} +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#endif +#if CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyType_GetFlags(tp) (((PyTypeObject *)tp)->tp_flags) + #define __Pyx_PyType_HasFeature(type, feature) ((__Pyx_PyType_GetFlags(type) & (feature)) != 0) + #define __Pyx_PyObject_GetIterNextFunc(obj) (Py_TYPE(obj)->tp_iternext) +#else + #define __Pyx_PyType_GetFlags(tp) (PyType_GetFlags((PyTypeObject *)tp)) + #define __Pyx_PyType_HasFeature(type, feature) PyType_HasFeature(type, feature) + #define __Pyx_PyObject_GetIterNextFunc(obj) PyIter_Next +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_SetItemOnTypeDict(tp, k, v) PyObject_GenericSetAttr((PyObject*)tp, k, v) +#else + #define __Pyx_SetItemOnTypeDict(tp, k, v) PyDict_SetItem(tp->tp_dict, k, v) +#endif +#if CYTHON_USE_TYPE_SPECS && PY_VERSION_HEX >= 0x03080000 +#define __Pyx_PyHeapTypeObject_GC_Del(obj) {\ + PyTypeObject *type = Py_TYPE((PyObject*)obj);\ + assert(__Pyx_PyType_HasFeature(type, Py_TPFLAGS_HEAPTYPE));\ + PyObject_GC_Del(obj);\ + Py_DECREF(type);\ +} +#else +#define __Pyx_PyHeapTypeObject_GC_Del(obj) PyObject_GC_Del(obj) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define CYTHON_PEP393_ENABLED 1 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GetLength(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_ReadChar(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((void)u, 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((void)u, (0)) + #define __Pyx_PyUnicode_DATA(u) ((void*)u) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)k, PyUnicode_ReadChar((PyObject*)(d), i)) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GetLength(u)) +#elif PY_VERSION_HEX > 0x03030000 && defined(PyUnicode_KIND) + #define CYTHON_PEP393_ENABLED 1 + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_READY(op) (0) + #else + #define __Pyx_PyUnicode_READY(op) (likely(PyUnicode_IS_READY(op)) ?\ + 0 : _PyUnicode_Ready((PyObject *)(op))) + #endif + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_LENGTH(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_READ_CHAR(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) PyUnicode_MAX_CHAR_VALUE(u) + #define __Pyx_PyUnicode_KIND(u) ((int)PyUnicode_KIND(u)) + #define __Pyx_PyUnicode_DATA(u) PyUnicode_DATA(u) + #define __Pyx_PyUnicode_READ(k, d, i) PyUnicode_READ(k, d, i) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) PyUnicode_WRITE(k, d, i, (Py_UCS4) ch) + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_LENGTH(u)) + #else + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x03090000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : ((PyCompactUnicodeObject *)(u))->wstr_length)) + #else + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : PyUnicode_GET_SIZE(u))) + #endif + #endif +#else + #define CYTHON_PEP393_ENABLED 0 + #define PyUnicode_1BYTE_KIND 1 + #define PyUnicode_2BYTE_KIND 2 + #define PyUnicode_4BYTE_KIND 4 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_SIZE(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) ((Py_UCS4)(PyUnicode_AS_UNICODE(u)[i])) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((sizeof(Py_UNICODE) == 2) ? 65535U : 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((int)sizeof(Py_UNICODE)) + #define __Pyx_PyUnicode_DATA(u) ((void*)PyUnicode_AS_UNICODE(u)) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)(k), (Py_UCS4)(((Py_UNICODE*)d)[i])) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) (((void)(k)), ((Py_UNICODE*)d)[i] = (Py_UNICODE) ch) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_SIZE(u)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyUnicode_Concat(a, b) PyNumber_Add(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) PyNumber_Add(a, b) +#else + #define __Pyx_PyUnicode_Concat(a, b) PyUnicode_Concat(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) ((unlikely((a) == Py_None) || unlikely((b) == Py_None)) ?\ + PyNumber_Add(a, b) : __Pyx_PyUnicode_Concat(a, b)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #if !defined(PyUnicode_DecodeUnicodeEscape) + #define PyUnicode_DecodeUnicodeEscape(s, size, errors) PyUnicode_Decode(s, size, "unicode_escape", errors) + #endif + #if !defined(PyUnicode_Contains) || (PY_MAJOR_VERSION == 2 && PYPY_VERSION_NUM < 0x07030500) + #undef PyUnicode_Contains + #define PyUnicode_Contains(u, s) PySequence_Contains(u, s) + #endif + #if !defined(PyByteArray_Check) + #define PyByteArray_Check(obj) PyObject_TypeCheck(obj, &PyByteArray_Type) + #endif + #if !defined(PyObject_Format) + #define PyObject_Format(obj, fmt) PyObject_CallMethod(obj, "__format__", "O", fmt) + #endif +#endif +#define __Pyx_PyString_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyString_Check(b) && !PyString_CheckExact(b)))) ? PyNumber_Remainder(a, b) : __Pyx_PyString_Format(a, b)) +#define __Pyx_PyUnicode_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyUnicode_Check(b) && !PyUnicode_CheckExact(b)))) ? PyNumber_Remainder(a, b) : PyUnicode_Format(a, b)) +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyString_Format(a, b) PyUnicode_Format(a, b) +#else + #define __Pyx_PyString_Format(a, b) PyString_Format(a, b) +#endif +#if PY_MAJOR_VERSION < 3 && !defined(PyObject_ASCII) + #define PyObject_ASCII(o) PyObject_Repr(o) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBaseString_Type PyUnicode_Type + #define PyStringObject PyUnicodeObject + #define PyString_Type PyUnicode_Type + #define PyString_Check PyUnicode_Check + #define PyString_CheckExact PyUnicode_CheckExact +#ifndef PyObject_Unicode + #define PyObject_Unicode PyObject_Str +#endif +#endif +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyBaseString_Check(obj) PyUnicode_Check(obj) + #define __Pyx_PyBaseString_CheckExact(obj) PyUnicode_CheckExact(obj) +#else + #define __Pyx_PyBaseString_Check(obj) (PyString_Check(obj) || PyUnicode_Check(obj)) + #define __Pyx_PyBaseString_CheckExact(obj) (PyString_CheckExact(obj) || PyUnicode_CheckExact(obj)) +#endif +#if CYTHON_COMPILING_IN_CPYTHON + #define __Pyx_PySequence_ListKeepNew(obj)\ + (likely(PyList_CheckExact(obj) && Py_REFCNT(obj) == 1) ? __Pyx_NewRef(obj) : PySequence_List(obj)) +#else + #define __Pyx_PySequence_ListKeepNew(obj) PySequence_List(obj) +#endif +#ifndef PySet_CheckExact + #define PySet_CheckExact(obj) __Pyx_IS_TYPE(obj, &PySet_Type) +#endif +#if PY_VERSION_HEX >= 0x030900A4 + #define __Pyx_SET_REFCNT(obj, refcnt) Py_SET_REFCNT(obj, refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SET_SIZE(obj, size) +#else + #define __Pyx_SET_REFCNT(obj, refcnt) Py_REFCNT(obj) = (refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SIZE(obj) = (size) +#endif +#if CYTHON_ASSUME_SAFE_MACROS + #define __Pyx_PySequence_ITEM(o, i) PySequence_ITEM(o, i) + #define __Pyx_PySequence_SIZE(seq) Py_SIZE(seq) + #define __Pyx_PyTuple_SET_ITEM(o, i, v) (PyTuple_SET_ITEM(o, i, v), (0)) + #define __Pyx_PyList_SET_ITEM(o, i, v) (PyList_SET_ITEM(o, i, v), (0)) + #define __Pyx_PyTuple_GET_SIZE(o) PyTuple_GET_SIZE(o) + #define __Pyx_PyList_GET_SIZE(o) PyList_GET_SIZE(o) + #define __Pyx_PySet_GET_SIZE(o) PySet_GET_SIZE(o) + #define __Pyx_PyBytes_GET_SIZE(o) PyBytes_GET_SIZE(o) + #define __Pyx_PyByteArray_GET_SIZE(o) PyByteArray_GET_SIZE(o) +#else + #define __Pyx_PySequence_ITEM(o, i) PySequence_GetItem(o, i) + #define __Pyx_PySequence_SIZE(seq) PySequence_Size(seq) + #define __Pyx_PyTuple_SET_ITEM(o, i, v) PyTuple_SetItem(o, i, v) + #define __Pyx_PyList_SET_ITEM(o, i, v) PyList_SetItem(o, i, v) + #define __Pyx_PyTuple_GET_SIZE(o) PyTuple_Size(o) + #define __Pyx_PyList_GET_SIZE(o) PyList_Size(o) + #define __Pyx_PySet_GET_SIZE(o) PySet_Size(o) + #define __Pyx_PyBytes_GET_SIZE(o) PyBytes_Size(o) + #define __Pyx_PyByteArray_GET_SIZE(o) PyByteArray_Size(o) +#endif +#if PY_VERSION_HEX >= 0x030d00A1 + #define __Pyx_PyImport_AddModuleRef(name) PyImport_AddModuleRef(name) +#else + static CYTHON_INLINE PyObject *__Pyx_PyImport_AddModuleRef(const char *name) { + PyObject *module = PyImport_AddModule(name); + Py_XINCREF(module); + return module; + } +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyIntObject PyLongObject + #define PyInt_Type PyLong_Type + #define PyInt_Check(op) PyLong_Check(op) + #define PyInt_CheckExact(op) PyLong_CheckExact(op) + #define __Pyx_Py3Int_Check(op) PyLong_Check(op) + #define __Pyx_Py3Int_CheckExact(op) PyLong_CheckExact(op) + #define PyInt_FromString PyLong_FromString + #define PyInt_FromUnicode PyLong_FromUnicode + #define PyInt_FromLong PyLong_FromLong + #define PyInt_FromSize_t PyLong_FromSize_t + #define PyInt_FromSsize_t PyLong_FromSsize_t + #define PyInt_AsLong PyLong_AsLong + #define PyInt_AS_LONG PyLong_AS_LONG + #define PyInt_AsSsize_t PyLong_AsSsize_t + #define PyInt_AsUnsignedLongMask PyLong_AsUnsignedLongMask + #define PyInt_AsUnsignedLongLongMask PyLong_AsUnsignedLongLongMask + #define PyNumber_Int PyNumber_Long +#else + #define __Pyx_Py3Int_Check(op) (PyLong_Check(op) || PyInt_Check(op)) + #define __Pyx_Py3Int_CheckExact(op) (PyLong_CheckExact(op) || PyInt_CheckExact(op)) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBoolObject PyLongObject +#endif +#if PY_MAJOR_VERSION >= 3 && CYTHON_COMPILING_IN_PYPY + #ifndef PyUnicode_InternFromString + #define PyUnicode_InternFromString(s) PyUnicode_FromString(s) + #endif +#endif +#if PY_VERSION_HEX < 0x030200A4 + typedef long Py_hash_t; + #define __Pyx_PyInt_FromHash_t PyInt_FromLong + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsHash_t +#else + #define __Pyx_PyInt_FromHash_t PyInt_FromSsize_t + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsSsize_t +#endif +#if CYTHON_USE_ASYNC_SLOTS + #if PY_VERSION_HEX >= 0x030500B1 + #define __Pyx_PyAsyncMethodsStruct PyAsyncMethods + #define __Pyx_PyType_AsAsync(obj) (Py_TYPE(obj)->tp_as_async) + #else + #define __Pyx_PyType_AsAsync(obj) ((__Pyx_PyAsyncMethodsStruct*) (Py_TYPE(obj)->tp_reserved)) + #endif +#else + #define __Pyx_PyType_AsAsync(obj) NULL +#endif +#ifndef __Pyx_PyAsyncMethodsStruct + typedef struct { + unaryfunc am_await; + unaryfunc am_aiter; + unaryfunc am_anext; + } __Pyx_PyAsyncMethodsStruct; +#endif + +#if defined(_WIN32) || defined(WIN32) || defined(MS_WINDOWS) + #if !defined(_USE_MATH_DEFINES) + #define _USE_MATH_DEFINES + #endif +#endif +#include +#ifdef NAN +#define __PYX_NAN() ((float) NAN) +#else +static CYTHON_INLINE float __PYX_NAN() { + float value; + memset(&value, 0xFF, sizeof(value)); + return value; +} +#endif +#if defined(__CYGWIN__) && defined(_LDBL_EQ_DBL) +#define __Pyx_truncl trunc +#else +#define __Pyx_truncl truncl +#endif + +#define __PYX_MARK_ERR_POS(f_index, lineno) \ + { __pyx_filename = __pyx_f[f_index]; (void)__pyx_filename; __pyx_lineno = lineno; (void)__pyx_lineno; __pyx_clineno = __LINE__; (void)__pyx_clineno; } +#define __PYX_ERR(f_index, lineno, Ln_error) \ + { __PYX_MARK_ERR_POS(f_index, lineno) goto Ln_error; } + +#ifdef CYTHON_EXTERN_C + #undef __PYX_EXTERN_C + #define __PYX_EXTERN_C CYTHON_EXTERN_C +#elif defined(__PYX_EXTERN_C) + #ifdef _MSC_VER + #pragma message ("Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead.") + #else + #warning Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead. + #endif +#else + #define __PYX_EXTERN_C extern "C++" +#endif + +#define __PYX_HAVE__rednose__helpers__ekf_sym_pyx +#define __PYX_HAVE_API__rednose__helpers__ekf_sym_pyx +/* Early includes */ +#include +#include +#include "ios" +#include "new" +#include "stdexcept" +#include "typeinfo" +#include +#include + + /* Using NumPy API declarations from "numpy/__init__.cython-30.pxd" */ + +#include "numpy/arrayobject.h" +#include "numpy/ndarrayobject.h" +#include "numpy/ndarraytypes.h" +#include "numpy/arrayscalars.h" +#include "numpy/ufuncobject.h" +#include +#include "rednose/helpers/ekf_load.h" +#include "rednose/helpers/ekf_sym.h" +#include "pythread.h" +#include +#ifdef _OPENMP +#include +#endif /* _OPENMP */ + +#if defined(PYREX_WITHOUT_ASSERTIONS) && !defined(CYTHON_WITHOUT_ASSERTIONS) +#define CYTHON_WITHOUT_ASSERTIONS +#endif + +typedef struct {PyObject **p; const char *s; const Py_ssize_t n; const char* encoding; + const char is_unicode; const char is_str; const char intern; } __Pyx_StringTabEntry; + +#define __PYX_DEFAULT_STRING_ENCODING_IS_ASCII 0 +#define __PYX_DEFAULT_STRING_ENCODING_IS_UTF8 0 +#define __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT (PY_MAJOR_VERSION >= 3 && __PYX_DEFAULT_STRING_ENCODING_IS_UTF8) +#define __PYX_DEFAULT_STRING_ENCODING "" +#define __Pyx_PyObject_FromString __Pyx_PyBytes_FromString +#define __Pyx_PyObject_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#define __Pyx_uchar_cast(c) ((unsigned char)c) +#define __Pyx_long_cast(x) ((long)x) +#define __Pyx_fits_Py_ssize_t(v, type, is_signed) (\ + (sizeof(type) < sizeof(Py_ssize_t)) ||\ + (sizeof(type) > sizeof(Py_ssize_t) &&\ + likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX) &&\ + (!is_signed || likely(v > (type)PY_SSIZE_T_MIN ||\ + v == (type)PY_SSIZE_T_MIN))) ||\ + (sizeof(type) == sizeof(Py_ssize_t) &&\ + (is_signed || likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX))) ) +static CYTHON_INLINE int __Pyx_is_valid_index(Py_ssize_t i, Py_ssize_t limit) { + return (size_t) i < (size_t) limit; +} +#if defined (__cplusplus) && __cplusplus >= 201103L + #include + #define __Pyx_sst_abs(value) std::abs(value) +#elif SIZEOF_INT >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) abs(value) +#elif SIZEOF_LONG >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) labs(value) +#elif defined (_MSC_VER) + #define __Pyx_sst_abs(value) ((Py_ssize_t)_abs64(value)) +#elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define __Pyx_sst_abs(value) llabs(value) +#elif defined (__GNUC__) + #define __Pyx_sst_abs(value) __builtin_llabs(value) +#else + #define __Pyx_sst_abs(value) ((value<0) ? -value : value) +#endif +static CYTHON_INLINE Py_ssize_t __Pyx_ssize_strlen(const char *s); +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject*); +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject*, Py_ssize_t* length); +static CYTHON_INLINE PyObject* __Pyx_PyByteArray_FromString(const char*); +#define __Pyx_PyByteArray_FromStringAndSize(s, l) PyByteArray_FromStringAndSize((const char*)s, l) +#define __Pyx_PyBytes_FromString PyBytes_FromString +#define __Pyx_PyBytes_FromStringAndSize PyBytes_FromStringAndSize +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char*); +#if PY_MAJOR_VERSION < 3 + #define __Pyx_PyStr_FromString __Pyx_PyBytes_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#else + #define __Pyx_PyStr_FromString __Pyx_PyUnicode_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyUnicode_FromStringAndSize +#endif +#define __Pyx_PyBytes_AsWritableString(s) ((char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableSString(s) ((signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableUString(s) ((unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsString(s) ((const char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsSString(s) ((const signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsUString(s) ((const unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyObject_AsWritableString(s) ((char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableSString(s) ((signed char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableUString(s) ((unsigned char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsSString(s) ((const signed char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsUString(s) ((const unsigned char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_FromCString(s) __Pyx_PyObject_FromString((const char*)s) +#define __Pyx_PyBytes_FromCString(s) __Pyx_PyBytes_FromString((const char*)s) +#define __Pyx_PyByteArray_FromCString(s) __Pyx_PyByteArray_FromString((const char*)s) +#define __Pyx_PyStr_FromCString(s) __Pyx_PyStr_FromString((const char*)s) +#define __Pyx_PyUnicode_FromCString(s) __Pyx_PyUnicode_FromString((const char*)s) +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const wchar_t *u) +{ + const wchar_t *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#else +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const Py_UNICODE *u) +{ + const Py_UNICODE *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#endif +#define __Pyx_PyUnicode_FromOrdinal(o) PyUnicode_FromOrdinal((int)o) +#define __Pyx_PyUnicode_FromUnicode(u) PyUnicode_FromUnicode(u, __Pyx_Py_UNICODE_strlen(u)) +#define __Pyx_PyUnicode_FromUnicodeAndLength PyUnicode_FromUnicode +#define __Pyx_PyUnicode_AsUnicode PyUnicode_AsUnicode +#define __Pyx_NewRef(obj) (Py_INCREF(obj), obj) +#define __Pyx_Owned_Py_None(b) __Pyx_NewRef(Py_None) +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b); +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject*); +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject*); +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x); +#define __Pyx_PySequence_Tuple(obj)\ + (likely(PyTuple_CheckExact(obj)) ? __Pyx_NewRef(obj) : PySequence_Tuple(obj)) +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject*); +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t); +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject*); +#if CYTHON_ASSUME_SAFE_MACROS +#define __pyx_PyFloat_AsDouble(x) (PyFloat_CheckExact(x) ? PyFloat_AS_DOUBLE(x) : PyFloat_AsDouble(x)) +#else +#define __pyx_PyFloat_AsDouble(x) PyFloat_AsDouble(x) +#endif +#define __pyx_PyFloat_AsFloat(x) ((float) __pyx_PyFloat_AsDouble(x)) +#if PY_MAJOR_VERSION >= 3 +#define __Pyx_PyNumber_Int(x) (PyLong_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Long(x)) +#else +#define __Pyx_PyNumber_Int(x) (PyInt_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Int(x)) +#endif +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_VERSION_HEX >= 0x030C00A7 + #ifndef _PyLong_SIGN_MASK + #define _PyLong_SIGN_MASK 3 + #endif + #ifndef _PyLong_NON_SIZE_BITS + #define _PyLong_NON_SIZE_BITS 3 + #endif + #define __Pyx_PyLong_Sign(x) (((PyLongObject*)x)->long_value.lv_tag & _PyLong_SIGN_MASK) + #define __Pyx_PyLong_IsNeg(x) ((__Pyx_PyLong_Sign(x) & 2) != 0) + #define __Pyx_PyLong_IsNonNeg(x) (!__Pyx_PyLong_IsNeg(x)) + #define __Pyx_PyLong_IsZero(x) (__Pyx_PyLong_Sign(x) & 1) + #define __Pyx_PyLong_IsPos(x) (__Pyx_PyLong_Sign(x) == 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) (__Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) ((Py_ssize_t) (((PyLongObject*)x)->long_value.lv_tag >> _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_SignedDigitCount(x)\ + ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * __Pyx_PyLong_DigitCount(x)) + #if defined(PyUnstable_Long_IsCompact) && defined(PyUnstable_Long_CompactValue) + #define __Pyx_PyLong_IsCompact(x) PyUnstable_Long_IsCompact((PyLongObject*) x) + #define __Pyx_PyLong_CompactValue(x) PyUnstable_Long_CompactValue((PyLongObject*) x) + #else + #define __Pyx_PyLong_IsCompact(x) (((PyLongObject*)x)->long_value.lv_tag < (2 << _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_CompactValue(x) ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * (Py_ssize_t) __Pyx_PyLong_Digits(x)[0]) + #endif + typedef Py_ssize_t __Pyx_compact_pylong; + typedef size_t __Pyx_compact_upylong; + #else + #define __Pyx_PyLong_IsNeg(x) (Py_SIZE(x) < 0) + #define __Pyx_PyLong_IsNonNeg(x) (Py_SIZE(x) >= 0) + #define __Pyx_PyLong_IsZero(x) (Py_SIZE(x) == 0) + #define __Pyx_PyLong_IsPos(x) (Py_SIZE(x) > 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) ((Py_SIZE(x) == 0) ? 0 : __Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) __Pyx_sst_abs(Py_SIZE(x)) + #define __Pyx_PyLong_SignedDigitCount(x) Py_SIZE(x) + #define __Pyx_PyLong_IsCompact(x) (Py_SIZE(x) == 0 || Py_SIZE(x) == 1 || Py_SIZE(x) == -1) + #define __Pyx_PyLong_CompactValue(x)\ + ((Py_SIZE(x) == 0) ? (sdigit) 0 : ((Py_SIZE(x) < 0) ? -(sdigit)__Pyx_PyLong_Digits(x)[0] : (sdigit)__Pyx_PyLong_Digits(x)[0])) + typedef sdigit __Pyx_compact_pylong; + typedef digit __Pyx_compact_upylong; + #endif + #if PY_VERSION_HEX >= 0x030C00A5 + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->long_value.ob_digit) + #else + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->ob_digit) + #endif +#endif +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII +#include +static int __Pyx_sys_getdefaultencoding_not_ascii; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + PyObject* ascii_chars_u = NULL; + PyObject* ascii_chars_b = NULL; + const char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + if (strcmp(default_encoding_c, "ascii") == 0) { + __Pyx_sys_getdefaultencoding_not_ascii = 0; + } else { + char ascii_chars[128]; + int c; + for (c = 0; c < 128; c++) { + ascii_chars[c] = (char) c; + } + __Pyx_sys_getdefaultencoding_not_ascii = 1; + ascii_chars_u = PyUnicode_DecodeASCII(ascii_chars, 128, NULL); + if (!ascii_chars_u) goto bad; + ascii_chars_b = PyUnicode_AsEncodedString(ascii_chars_u, default_encoding_c, NULL); + if (!ascii_chars_b || !PyBytes_Check(ascii_chars_b) || memcmp(ascii_chars, PyBytes_AS_STRING(ascii_chars_b), 128) != 0) { + PyErr_Format( + PyExc_ValueError, + "This module compiled with c_string_encoding=ascii, but default encoding '%.200s' is not a superset of ascii.", + default_encoding_c); + goto bad; + } + Py_DECREF(ascii_chars_u); + Py_DECREF(ascii_chars_b); + } + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + Py_XDECREF(ascii_chars_u); + Py_XDECREF(ascii_chars_b); + return -1; +} +#endif +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT && PY_MAJOR_VERSION >= 3 +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_DecodeUTF8(c_str, size, NULL) +#else +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_Decode(c_str, size, __PYX_DEFAULT_STRING_ENCODING, NULL) +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +#include +static char* __PYX_DEFAULT_STRING_ENCODING; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) (const char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + __PYX_DEFAULT_STRING_ENCODING = (char*) malloc(strlen(default_encoding_c) + 1); + if (!__PYX_DEFAULT_STRING_ENCODING) goto bad; + strcpy(__PYX_DEFAULT_STRING_ENCODING, default_encoding_c); + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + return -1; +} +#endif +#endif + + +/* Test for GCC > 2.95 */ +#if defined(__GNUC__) && (__GNUC__ > 2 || (__GNUC__ == 2 && (__GNUC_MINOR__ > 95))) + #define likely(x) __builtin_expect(!!(x), 1) + #define unlikely(x) __builtin_expect(!!(x), 0) +#else /* !__GNUC__ or GCC < 2.95 */ + #define likely(x) (x) + #define unlikely(x) (x) +#endif /* __GNUC__ */ +static CYTHON_INLINE void __Pyx_pretend_to_initialize(void* ptr) { (void)ptr; } + +#if !CYTHON_USE_MODULE_STATE +static PyObject *__pyx_m = NULL; +#endif +static int __pyx_lineno; +static int __pyx_clineno = 0; +static const char * __pyx_cfilenm = __FILE__; +static const char *__pyx_filename; + +/* Header.proto */ +#if !defined(CYTHON_CCOMPLEX) + #if defined(__cplusplus) + #define CYTHON_CCOMPLEX 1 + #elif (defined(_Complex_I) && !defined(_MSC_VER)) || ((defined (__STDC_VERSION__) && __STDC_VERSION__ >= 201112L) && !defined(__STDC_NO_COMPLEX__) && !defined(_MSC_VER)) + #define CYTHON_CCOMPLEX 1 + #else + #define CYTHON_CCOMPLEX 0 + #endif +#endif +#if CYTHON_CCOMPLEX + #ifdef __cplusplus + #include + #else + #include + #endif +#endif +#if CYTHON_CCOMPLEX && !defined(__cplusplus) && defined(__sun__) && defined(__GNUC__) + #undef _Complex_I + #define _Complex_I 1.0fj +#endif + +/* #### Code section: filename_table ### */ + +static const char *__pyx_f[] = { + "rednose/helpers/ekf_sym_pyx.pyx", + "", + "__init__.cython-30.pxd", + "type.pxd", +}; +/* #### Code section: utility_code_proto_before_types ### */ +/* ForceInitThreads.proto */ +#ifndef __PYX_FORCE_INIT_THREADS + #define __PYX_FORCE_INIT_THREADS 0 +#endif + +/* NoFastGil.proto */ +#define __Pyx_PyGILState_Ensure PyGILState_Ensure +#define __Pyx_PyGILState_Release PyGILState_Release +#define __Pyx_FastGIL_Remember() +#define __Pyx_FastGIL_Forget() +#define __Pyx_FastGilFuncInit() + +/* BufferFormatStructs.proto */ +struct __Pyx_StructField_; +#define __PYX_BUF_FLAGS_PACKED_STRUCT (1 << 0) +typedef struct { + const char* name; + struct __Pyx_StructField_* fields; + size_t size; + size_t arraysize[8]; + int ndim; + char typegroup; + char is_unsigned; + int flags; +} __Pyx_TypeInfo; +typedef struct __Pyx_StructField_ { + __Pyx_TypeInfo* type; + const char* name; + size_t offset; +} __Pyx_StructField; +typedef struct { + __Pyx_StructField* field; + size_t parent_offset; +} __Pyx_BufFmt_StackElem; +typedef struct { + __Pyx_StructField root; + __Pyx_BufFmt_StackElem* head; + size_t fmt_offset; + size_t new_count, enc_count; + size_t struct_alignment; + int is_complex; + char enc_type; + char new_packmode; + char enc_packmode; + char is_valid_array; +} __Pyx_BufFmt_Context; + +/* Atomics.proto */ +#include +#ifndef CYTHON_ATOMICS + #define CYTHON_ATOMICS 1 +#endif +#define __PYX_CYTHON_ATOMICS_ENABLED() CYTHON_ATOMICS +#define __pyx_atomic_int_type int +#define __pyx_nonatomic_int_type int +#if CYTHON_ATOMICS && (defined(__STDC_VERSION__) &&\ + (__STDC_VERSION__ >= 201112L) &&\ + !defined(__STDC_NO_ATOMICS__)) + #include +#elif CYTHON_ATOMICS && (defined(__cplusplus) && (\ + (__cplusplus >= 201103L) ||\ + (defined(_MSC_VER) && _MSC_VER >= 1700))) + #include +#endif +#if CYTHON_ATOMICS && (defined(__STDC_VERSION__) &&\ + (__STDC_VERSION__ >= 201112L) &&\ + !defined(__STDC_NO_ATOMICS__) &&\ + ATOMIC_INT_LOCK_FREE == 2) + #undef __pyx_atomic_int_type + #define __pyx_atomic_int_type atomic_int + #define __pyx_atomic_incr_aligned(value) atomic_fetch_add_explicit(value, 1, memory_order_relaxed) + #define __pyx_atomic_decr_aligned(value) atomic_fetch_sub_explicit(value, 1, memory_order_acq_rel) + #if defined(__PYX_DEBUG_ATOMICS) && defined(_MSC_VER) + #pragma message ("Using standard C atomics") + #elif defined(__PYX_DEBUG_ATOMICS) + #warning "Using standard C atomics" + #endif +#elif CYTHON_ATOMICS && (defined(__cplusplus) && (\ + (__cplusplus >= 201103L) ||\ +\ + (defined(_MSC_VER) && _MSC_VER >= 1700)) &&\ + ATOMIC_INT_LOCK_FREE == 2) + #undef __pyx_atomic_int_type + #define __pyx_atomic_int_type std::atomic_int + #define __pyx_atomic_incr_aligned(value) std::atomic_fetch_add_explicit(value, 1, std::memory_order_relaxed) + #define __pyx_atomic_decr_aligned(value) std::atomic_fetch_sub_explicit(value, 1, std::memory_order_acq_rel) + #if defined(__PYX_DEBUG_ATOMICS) && defined(_MSC_VER) + #pragma message ("Using standard C++ atomics") + #elif defined(__PYX_DEBUG_ATOMICS) + #warning "Using standard C++ atomics" + #endif +#elif CYTHON_ATOMICS && (__GNUC__ >= 5 || (__GNUC__ == 4 &&\ + (__GNUC_MINOR__ > 1 ||\ + (__GNUC_MINOR__ == 1 && __GNUC_PATCHLEVEL__ >= 2)))) + #define __pyx_atomic_incr_aligned(value) __sync_fetch_and_add(value, 1) + #define __pyx_atomic_decr_aligned(value) __sync_fetch_and_sub(value, 1) + #ifdef __PYX_DEBUG_ATOMICS + #warning "Using GNU atomics" + #endif +#elif CYTHON_ATOMICS && defined(_MSC_VER) + #include + #undef __pyx_atomic_int_type + #define __pyx_atomic_int_type long + #undef __pyx_nonatomic_int_type + #define __pyx_nonatomic_int_type long + #pragma intrinsic (_InterlockedExchangeAdd) + #define __pyx_atomic_incr_aligned(value) _InterlockedExchangeAdd(value, 1) + #define __pyx_atomic_decr_aligned(value) _InterlockedExchangeAdd(value, -1) + #ifdef __PYX_DEBUG_ATOMICS + #pragma message ("Using MSVC atomics") + #endif +#else + #undef CYTHON_ATOMICS + #define CYTHON_ATOMICS 0 + #ifdef __PYX_DEBUG_ATOMICS + #warning "Not using atomics" + #endif +#endif +#if CYTHON_ATOMICS + #define __pyx_add_acquisition_count(memview)\ + __pyx_atomic_incr_aligned(__pyx_get_slice_count_pointer(memview)) + #define __pyx_sub_acquisition_count(memview)\ + __pyx_atomic_decr_aligned(__pyx_get_slice_count_pointer(memview)) +#else + #define __pyx_add_acquisition_count(memview)\ + __pyx_add_acquisition_count_locked(__pyx_get_slice_count_pointer(memview), memview->lock) + #define __pyx_sub_acquisition_count(memview)\ + __pyx_sub_acquisition_count_locked(__pyx_get_slice_count_pointer(memview), memview->lock) +#endif + +/* MemviewSliceStruct.proto */ +struct __pyx_memoryview_obj; +typedef struct { + struct __pyx_memoryview_obj *memview; + char *data; + Py_ssize_t shape[8]; + Py_ssize_t strides[8]; + Py_ssize_t suboffsets[8]; +} __Pyx_memviewslice; +#define __Pyx_MemoryView_Len(m) (m.shape[0]) + +/* #### Code section: numeric_typedefs ### */ + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":730 + * # in Cython to enable them only on the right systems. + * + * ctypedef npy_int8 int8_t # <<<<<<<<<<<<<< + * ctypedef npy_int16 int16_t + * ctypedef npy_int32 int32_t + */ +typedef npy_int8 __pyx_t_5numpy_int8_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":731 + * + * ctypedef npy_int8 int8_t + * ctypedef npy_int16 int16_t # <<<<<<<<<<<<<< + * ctypedef npy_int32 int32_t + * ctypedef npy_int64 int64_t + */ +typedef npy_int16 __pyx_t_5numpy_int16_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":732 + * ctypedef npy_int8 int8_t + * ctypedef npy_int16 int16_t + * ctypedef npy_int32 int32_t # <<<<<<<<<<<<<< + * ctypedef npy_int64 int64_t + * #ctypedef npy_int96 int96_t + */ +typedef npy_int32 __pyx_t_5numpy_int32_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":733 + * ctypedef npy_int16 int16_t + * ctypedef npy_int32 int32_t + * ctypedef npy_int64 int64_t # <<<<<<<<<<<<<< + * #ctypedef npy_int96 int96_t + * #ctypedef npy_int128 int128_t + */ +typedef npy_int64 __pyx_t_5numpy_int64_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":737 + * #ctypedef npy_int128 int128_t + * + * ctypedef npy_uint8 uint8_t # <<<<<<<<<<<<<< + * ctypedef npy_uint16 uint16_t + * ctypedef npy_uint32 uint32_t + */ +typedef npy_uint8 __pyx_t_5numpy_uint8_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":738 + * + * ctypedef npy_uint8 uint8_t + * ctypedef npy_uint16 uint16_t # <<<<<<<<<<<<<< + * ctypedef npy_uint32 uint32_t + * ctypedef npy_uint64 uint64_t + */ +typedef npy_uint16 __pyx_t_5numpy_uint16_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":739 + * ctypedef npy_uint8 uint8_t + * ctypedef npy_uint16 uint16_t + * ctypedef npy_uint32 uint32_t # <<<<<<<<<<<<<< + * ctypedef npy_uint64 uint64_t + * #ctypedef npy_uint96 uint96_t + */ +typedef npy_uint32 __pyx_t_5numpy_uint32_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":740 + * ctypedef npy_uint16 uint16_t + * ctypedef npy_uint32 uint32_t + * ctypedef npy_uint64 uint64_t # <<<<<<<<<<<<<< + * #ctypedef npy_uint96 uint96_t + * #ctypedef npy_uint128 uint128_t + */ +typedef npy_uint64 __pyx_t_5numpy_uint64_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":744 + * #ctypedef npy_uint128 uint128_t + * + * ctypedef npy_float32 float32_t # <<<<<<<<<<<<<< + * ctypedef npy_float64 float64_t + * #ctypedef npy_float80 float80_t + */ +typedef npy_float32 __pyx_t_5numpy_float32_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":745 + * + * ctypedef npy_float32 float32_t + * ctypedef npy_float64 float64_t # <<<<<<<<<<<<<< + * #ctypedef npy_float80 float80_t + * #ctypedef npy_float128 float128_t + */ +typedef npy_float64 __pyx_t_5numpy_float64_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":754 + * # The int types are mapped a bit surprising -- + * # numpy.int corresponds to 'l' and numpy.long to 'q' + * ctypedef npy_long int_t # <<<<<<<<<<<<<< + * ctypedef npy_longlong longlong_t + * + */ +typedef npy_long __pyx_t_5numpy_int_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":755 + * # numpy.int corresponds to 'l' and numpy.long to 'q' + * ctypedef npy_long int_t + * ctypedef npy_longlong longlong_t # <<<<<<<<<<<<<< + * + * ctypedef npy_ulong uint_t + */ +typedef npy_longlong __pyx_t_5numpy_longlong_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":757 + * ctypedef npy_longlong longlong_t + * + * ctypedef npy_ulong uint_t # <<<<<<<<<<<<<< + * ctypedef npy_ulonglong ulonglong_t + * + */ +typedef npy_ulong __pyx_t_5numpy_uint_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":758 + * + * ctypedef npy_ulong uint_t + * ctypedef npy_ulonglong ulonglong_t # <<<<<<<<<<<<<< + * + * ctypedef npy_intp intp_t + */ +typedef npy_ulonglong __pyx_t_5numpy_ulonglong_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":760 + * ctypedef npy_ulonglong ulonglong_t + * + * ctypedef npy_intp intp_t # <<<<<<<<<<<<<< + * ctypedef npy_uintp uintp_t + * + */ +typedef npy_intp __pyx_t_5numpy_intp_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":761 + * + * ctypedef npy_intp intp_t + * ctypedef npy_uintp uintp_t # <<<<<<<<<<<<<< + * + * ctypedef npy_double float_t + */ +typedef npy_uintp __pyx_t_5numpy_uintp_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":763 + * ctypedef npy_uintp uintp_t + * + * ctypedef npy_double float_t # <<<<<<<<<<<<<< + * ctypedef npy_double double_t + * ctypedef npy_longdouble longdouble_t + */ +typedef npy_double __pyx_t_5numpy_float_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":764 + * + * ctypedef npy_double float_t + * ctypedef npy_double double_t # <<<<<<<<<<<<<< + * ctypedef npy_longdouble longdouble_t + * + */ +typedef npy_double __pyx_t_5numpy_double_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":765 + * ctypedef npy_double float_t + * ctypedef npy_double double_t + * ctypedef npy_longdouble longdouble_t # <<<<<<<<<<<<<< + * + * ctypedef npy_cfloat cfloat_t + */ +typedef npy_longdouble __pyx_t_5numpy_longdouble_t; +/* #### Code section: complex_type_declarations ### */ +/* Declarations.proto */ +#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #ifdef __cplusplus + typedef ::std::complex< float > __pyx_t_float_complex; + #else + typedef float _Complex __pyx_t_float_complex; + #endif +#else + typedef struct { float real, imag; } __pyx_t_float_complex; +#endif +static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float, float); + +/* Declarations.proto */ +#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #ifdef __cplusplus + typedef ::std::complex< double > __pyx_t_double_complex; + #else + typedef double _Complex __pyx_t_double_complex; + #endif +#else + typedef struct { double real, imag; } __pyx_t_double_complex; +#endif +static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double, double); + +/* #### Code section: type_declarations ### */ + +/*--- Type declarations ---*/ +struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx; +struct __pyx_array_obj; +struct __pyx_MemviewEnum_obj; +struct __pyx_memoryview_obj; +struct __pyx_memoryviewslice_obj; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":767 + * ctypedef npy_longdouble longdouble_t + * + * ctypedef npy_cfloat cfloat_t # <<<<<<<<<<<<<< + * ctypedef npy_cdouble cdouble_t + * ctypedef npy_clongdouble clongdouble_t + */ +typedef npy_cfloat __pyx_t_5numpy_cfloat_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":768 + * + * ctypedef npy_cfloat cfloat_t + * ctypedef npy_cdouble cdouble_t # <<<<<<<<<<<<<< + * ctypedef npy_clongdouble clongdouble_t + * + */ +typedef npy_cdouble __pyx_t_5numpy_cdouble_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":769 + * ctypedef npy_cfloat cfloat_t + * ctypedef npy_cdouble cdouble_t + * ctypedef npy_clongdouble clongdouble_t # <<<<<<<<<<<<<< + * + * ctypedef npy_cdouble complex_t + */ +typedef npy_clongdouble __pyx_t_5numpy_clongdouble_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":771 + * ctypedef npy_clongdouble clongdouble_t + * + * ctypedef npy_cdouble complex_t # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew1(a): + */ +typedef npy_cdouble __pyx_t_5numpy_complex_t; + +/* "rednose/helpers/ekf_sym_pyx.pyx":85 + * return np.copy(np.asarray(mem_view, dtype=np.double, order="C")) + * + * cdef class EKF_sym_pyx: # <<<<<<<<<<<<<< + * cdef EKFSym* ekf + * def __cinit__(self, str gen_dir, str name, np.ndarray[np.float64_t, ndim=2] Q, + */ +struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx { + PyObject_HEAD + EKFS::EKFSym *ekf; +}; + + +/* "View.MemoryView":114 + * @cython.collection_type("sequence") + * @cname("__pyx_array") + * cdef class array: # <<<<<<<<<<<<<< + * + * cdef: + */ +struct __pyx_array_obj { + PyObject_HEAD + struct __pyx_vtabstruct_array *__pyx_vtab; + char *data; + Py_ssize_t len; + char *format; + int ndim; + Py_ssize_t *_shape; + Py_ssize_t *_strides; + Py_ssize_t itemsize; + PyObject *mode; + PyObject *_format; + void (*callback_free_data)(void *); + int free_data; + int dtype_is_object; +}; + + +/* "View.MemoryView":302 + * + * @cname('__pyx_MemviewEnum') + * cdef class Enum(object): # <<<<<<<<<<<<<< + * cdef object name + * def __init__(self, name): + */ +struct __pyx_MemviewEnum_obj { + PyObject_HEAD + PyObject *name; +}; + + +/* "View.MemoryView":337 + * + * @cname('__pyx_memoryview') + * cdef class memoryview: # <<<<<<<<<<<<<< + * + * cdef object obj + */ +struct __pyx_memoryview_obj { + PyObject_HEAD + struct __pyx_vtabstruct_memoryview *__pyx_vtab; + PyObject *obj; + PyObject *_size; + PyObject *_array_interface; + PyThread_type_lock lock; + __pyx_atomic_int_type acquisition_count; + Py_buffer view; + int flags; + int dtype_is_object; + __Pyx_TypeInfo *typeinfo; +}; + + +/* "View.MemoryView":952 + * @cython.collection_type("sequence") + * @cname('__pyx_memoryviewslice') + * cdef class _memoryviewslice(memoryview): # <<<<<<<<<<<<<< + * "Internal class for passing memoryview slices to Python" + * + */ +struct __pyx_memoryviewslice_obj { + struct __pyx_memoryview_obj __pyx_base; + __Pyx_memviewslice from_slice; + PyObject *from_object; + PyObject *(*to_object_func)(char *); + int (*to_dtype_func)(char *, PyObject *); +}; + + + +/* "View.MemoryView":114 + * @cython.collection_type("sequence") + * @cname("__pyx_array") + * cdef class array: # <<<<<<<<<<<<<< + * + * cdef: + */ + +struct __pyx_vtabstruct_array { + PyObject *(*get_memview)(struct __pyx_array_obj *); +}; +static struct __pyx_vtabstruct_array *__pyx_vtabptr_array; + + +/* "View.MemoryView":337 + * + * @cname('__pyx_memoryview') + * cdef class memoryview: # <<<<<<<<<<<<<< + * + * cdef object obj + */ + +struct __pyx_vtabstruct_memoryview { + char *(*get_item_pointer)(struct __pyx_memoryview_obj *, PyObject *); + PyObject *(*is_slice)(struct __pyx_memoryview_obj *, PyObject *); + PyObject *(*setitem_slice_assignment)(struct __pyx_memoryview_obj *, PyObject *, PyObject *); + PyObject *(*setitem_slice_assign_scalar)(struct __pyx_memoryview_obj *, struct __pyx_memoryview_obj *, PyObject *); + PyObject *(*setitem_indexed)(struct __pyx_memoryview_obj *, PyObject *, PyObject *); + PyObject *(*convert_item_to_object)(struct __pyx_memoryview_obj *, char *); + PyObject *(*assign_item_from_object)(struct __pyx_memoryview_obj *, char *, PyObject *); + PyObject *(*_get_base)(struct __pyx_memoryview_obj *); +}; +static struct __pyx_vtabstruct_memoryview *__pyx_vtabptr_memoryview; + + +/* "View.MemoryView":952 + * @cython.collection_type("sequence") + * @cname('__pyx_memoryviewslice') + * cdef class _memoryviewslice(memoryview): # <<<<<<<<<<<<<< + * "Internal class for passing memoryview slices to Python" + * + */ + +struct __pyx_vtabstruct__memoryviewslice { + struct __pyx_vtabstruct_memoryview __pyx_base; +}; +static struct __pyx_vtabstruct__memoryviewslice *__pyx_vtabptr__memoryviewslice; +/* #### Code section: utility_code_proto ### */ + +/* --- Runtime support code (head) --- */ +/* Refnanny.proto */ +#ifndef CYTHON_REFNANNY + #define CYTHON_REFNANNY 0 +#endif +#if CYTHON_REFNANNY + typedef struct { + void (*INCREF)(void*, PyObject*, Py_ssize_t); + void (*DECREF)(void*, PyObject*, Py_ssize_t); + void (*GOTREF)(void*, PyObject*, Py_ssize_t); + void (*GIVEREF)(void*, PyObject*, Py_ssize_t); + void* (*SetupContext)(const char*, Py_ssize_t, const char*); + void (*FinishContext)(void**); + } __Pyx_RefNannyAPIStruct; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNanny = NULL; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname); + #define __Pyx_RefNannyDeclarations void *__pyx_refnanny = NULL; +#ifdef WITH_THREAD + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + if (acquire_gil) {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + PyGILState_Release(__pyx_gilstate_save);\ + } else {\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + } + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } +#else + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__)) + #define __Pyx_RefNannyFinishContextNogil() __Pyx_RefNannyFinishContext() +#endif + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } + #define __Pyx_RefNannyFinishContext()\ + __Pyx_RefNanny->FinishContext(&__pyx_refnanny) + #define __Pyx_INCREF(r) __Pyx_RefNanny->INCREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_DECREF(r) __Pyx_RefNanny->DECREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GOTREF(r) __Pyx_RefNanny->GOTREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GIVEREF(r) __Pyx_RefNanny->GIVEREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_XINCREF(r) do { if((r) == NULL); else {__Pyx_INCREF(r); }} while(0) + #define __Pyx_XDECREF(r) do { if((r) == NULL); else {__Pyx_DECREF(r); }} while(0) + #define __Pyx_XGOTREF(r) do { if((r) == NULL); else {__Pyx_GOTREF(r); }} while(0) + #define __Pyx_XGIVEREF(r) do { if((r) == NULL); else {__Pyx_GIVEREF(r);}} while(0) +#else + #define __Pyx_RefNannyDeclarations + #define __Pyx_RefNannySetupContext(name, acquire_gil) + #define __Pyx_RefNannyFinishContextNogil() + #define __Pyx_RefNannyFinishContext() + #define __Pyx_INCREF(r) Py_INCREF(r) + #define __Pyx_DECREF(r) Py_DECREF(r) + #define __Pyx_GOTREF(r) + #define __Pyx_GIVEREF(r) + #define __Pyx_XINCREF(r) Py_XINCREF(r) + #define __Pyx_XDECREF(r) Py_XDECREF(r) + #define __Pyx_XGOTREF(r) + #define __Pyx_XGIVEREF(r) +#endif +#define __Pyx_Py_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; Py_XDECREF(tmp);\ + } while (0) +#define __Pyx_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_XDECREF(tmp);\ + } while (0) +#define __Pyx_DECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_DECREF(tmp);\ + } while (0) +#define __Pyx_CLEAR(r) do { PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);} while(0) +#define __Pyx_XCLEAR(r) do { if((r) != NULL) {PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);}} while(0) + +/* PyErrExceptionMatches.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_ExceptionMatches(err) __Pyx_PyErr_ExceptionMatchesInState(__pyx_tstate, err) +static CYTHON_INLINE int __Pyx_PyErr_ExceptionMatchesInState(PyThreadState* tstate, PyObject* err); +#else +#define __Pyx_PyErr_ExceptionMatches(err) PyErr_ExceptionMatches(err) +#endif + +/* PyThreadStateGet.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyThreadState_declare PyThreadState *__pyx_tstate; +#define __Pyx_PyThreadState_assign __pyx_tstate = __Pyx_PyThreadState_Current; +#if PY_VERSION_HEX >= 0x030C00A6 +#define __Pyx_PyErr_Occurred() (__pyx_tstate->current_exception != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->current_exception ? (PyObject*) Py_TYPE(__pyx_tstate->current_exception) : (PyObject*) NULL) +#else +#define __Pyx_PyErr_Occurred() (__pyx_tstate->curexc_type != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->curexc_type) +#endif +#else +#define __Pyx_PyThreadState_declare +#define __Pyx_PyThreadState_assign +#define __Pyx_PyErr_Occurred() (PyErr_Occurred() != NULL) +#define __Pyx_PyErr_CurrentExceptionType() PyErr_Occurred() +#endif + +/* PyErrFetchRestore.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_Clear() __Pyx_ErrRestore(NULL, NULL, NULL) +#define __Pyx_ErrRestoreWithState(type, value, tb) __Pyx_ErrRestoreInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) __Pyx_ErrFetchInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) __Pyx_ErrRestoreInState(__pyx_tstate, type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) __Pyx_ErrFetchInState(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb); +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A6 +#define __Pyx_PyErr_SetNone(exc) (Py_INCREF(exc), __Pyx_ErrRestore((exc), NULL, NULL)) +#else +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#endif +#else +#define __Pyx_PyErr_Clear() PyErr_Clear() +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#define __Pyx_ErrRestoreWithState(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestoreInState(tstate, type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchInState(tstate, type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) PyErr_Fetch(type, value, tb) +#endif + +/* PyObjectGetAttrStr.proto */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GetAttrStr(o,n) PyObject_GetAttr(o,n) +#endif + +/* PyObjectGetAttrStrNoError.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name); + +/* GetBuiltinName.proto */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name); + +/* TupleAndListFromArray.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n); +static CYTHON_INLINE PyObject* __Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n); +#endif + +/* IncludeStringH.proto */ +#include + +/* BytesEquals.proto */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals); + +/* UnicodeEquals.proto */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals); + +/* fastcall.proto */ +#if CYTHON_AVOID_BORROWED_REFS + #define __Pyx_Arg_VARARGS(args, i) PySequence_GetItem(args, i) +#elif CYTHON_ASSUME_SAFE_MACROS + #define __Pyx_Arg_VARARGS(args, i) PyTuple_GET_ITEM(args, i) +#else + #define __Pyx_Arg_VARARGS(args, i) PyTuple_GetItem(args, i) +#endif +#if CYTHON_AVOID_BORROWED_REFS + #define __Pyx_Arg_NewRef_VARARGS(arg) __Pyx_NewRef(arg) + #define __Pyx_Arg_XDECREF_VARARGS(arg) Py_XDECREF(arg) +#else + #define __Pyx_Arg_NewRef_VARARGS(arg) arg + #define __Pyx_Arg_XDECREF_VARARGS(arg) +#endif +#define __Pyx_NumKwargs_VARARGS(kwds) PyDict_Size(kwds) +#define __Pyx_KwValues_VARARGS(args, nargs) NULL +#define __Pyx_GetKwValue_VARARGS(kw, kwvalues, s) __Pyx_PyDict_GetItemStrWithError(kw, s) +#define __Pyx_KwargsAsDict_VARARGS(kw, kwvalues) PyDict_Copy(kw) +#if CYTHON_METH_FASTCALL + #define __Pyx_Arg_FASTCALL(args, i) args[i] + #define __Pyx_NumKwargs_FASTCALL(kwds) PyTuple_GET_SIZE(kwds) + #define __Pyx_KwValues_FASTCALL(args, nargs) ((args) + (nargs)) + static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 + CYTHON_UNUSED static PyObject *__Pyx_KwargsAsDict_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues); + #else + #define __Pyx_KwargsAsDict_FASTCALL(kw, kwvalues) _PyStack_AsDict(kwvalues, kw) + #endif + #define __Pyx_Arg_NewRef_FASTCALL(arg) arg /* no-op, __Pyx_Arg_FASTCALL is direct and this needs + to have the same reference counting */ + #define __Pyx_Arg_XDECREF_FASTCALL(arg) +#else + #define __Pyx_Arg_FASTCALL __Pyx_Arg_VARARGS + #define __Pyx_NumKwargs_FASTCALL __Pyx_NumKwargs_VARARGS + #define __Pyx_KwValues_FASTCALL __Pyx_KwValues_VARARGS + #define __Pyx_GetKwValue_FASTCALL __Pyx_GetKwValue_VARARGS + #define __Pyx_KwargsAsDict_FASTCALL __Pyx_KwargsAsDict_VARARGS + #define __Pyx_Arg_NewRef_FASTCALL(arg) __Pyx_Arg_NewRef_VARARGS(arg) + #define __Pyx_Arg_XDECREF_FASTCALL(arg) __Pyx_Arg_XDECREF_VARARGS(arg) +#endif +#if CYTHON_COMPILING_IN_CPYTHON && CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_VARARGS(args, start), stop - start) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_FASTCALL(args, start), stop - start) +#else +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) PyTuple_GetSlice(args, start, stop) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) PyTuple_GetSlice(args, start, stop) +#endif + +/* RaiseArgTupleInvalid.proto */ +static void __Pyx_RaiseArgtupleInvalid(const char* func_name, int exact, + Py_ssize_t num_min, Py_ssize_t num_max, Py_ssize_t num_found); + +/* RaiseDoubleKeywords.proto */ +static void __Pyx_RaiseDoubleKeywordsError(const char* func_name, PyObject* kw_name); + +/* ParseKeywords.proto */ +static int __Pyx_ParseOptionalKeywords(PyObject *kwds, PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, PyObject *values[], Py_ssize_t num_pos_args, + const char* function_name); + +/* ArgTypeTest.proto */ +#define __Pyx_ArgTypeTest(obj, type, none_allowed, name, exact)\ + ((likely(__Pyx_IS_TYPE(obj, type) | (none_allowed && (obj == Py_None)))) ? 1 :\ + __Pyx__ArgTypeTest(obj, type, name, exact)) +static int __Pyx__ArgTypeTest(PyObject *obj, PyTypeObject *type, const char *name, int exact); + +/* RaiseException.proto */ +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause); + +/* PyFunctionFastCall.proto */ +#if CYTHON_FAST_PYCALL +#if !CYTHON_VECTORCALL +#define __Pyx_PyFunction_FastCall(func, args, nargs)\ + __Pyx_PyFunction_FastCallDict((func), (args), (nargs), NULL) +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs); +#endif +#define __Pyx_BUILD_ASSERT_EXPR(cond)\ + (sizeof(char [1 - 2*!(cond)]) - 1) +#ifndef Py_MEMBER_SIZE +#define Py_MEMBER_SIZE(type, member) sizeof(((type *)0)->member) +#endif +#if !CYTHON_VECTORCALL +#if PY_VERSION_HEX >= 0x03080000 + #include "frameobject.h" +#if PY_VERSION_HEX >= 0x030b00a6 && !CYTHON_COMPILING_IN_LIMITED_API + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif + #define __Pxy_PyFrame_Initialize_Offsets() + #define __Pyx_PyFrame_GetLocalsplus(frame) ((frame)->f_localsplus) +#else + static size_t __pyx_pyframe_localsplus_offset = 0; + #include "frameobject.h" + #define __Pxy_PyFrame_Initialize_Offsets()\ + ((void)__Pyx_BUILD_ASSERT_EXPR(sizeof(PyFrameObject) == offsetof(PyFrameObject, f_localsplus) + Py_MEMBER_SIZE(PyFrameObject, f_localsplus)),\ + (void)(__pyx_pyframe_localsplus_offset = ((size_t)PyFrame_Type.tp_basicsize) - Py_MEMBER_SIZE(PyFrameObject, f_localsplus))) + #define __Pyx_PyFrame_GetLocalsplus(frame)\ + (assert(__pyx_pyframe_localsplus_offset), (PyObject **)(((char *)(frame)) + __pyx_pyframe_localsplus_offset)) +#endif +#endif +#endif + +/* PyObjectCall.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw); +#else +#define __Pyx_PyObject_Call(func, arg, kw) PyObject_Call(func, arg, kw) +#endif + +/* PyObjectCallMethO.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg); +#endif + +/* PyObjectFastCall.proto */ +#define __Pyx_PyObject_FastCall(func, args, nargs) __Pyx_PyObject_FastCallDict(func, args, (size_t)(nargs), NULL) +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs); + +/* RaiseUnexpectedTypeError.proto */ +static int __Pyx_RaiseUnexpectedTypeError(const char *expected, PyObject *obj); + +/* GCCDiagnostics.proto */ +#if !defined(__INTEL_COMPILER) && defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 6)) +#define __Pyx_HAS_GCC_DIAGNOSTIC +#endif + +/* BuildPyUnicode.proto */ +static PyObject* __Pyx_PyUnicode_BuildFromAscii(Py_ssize_t ulength, char* chars, int clength, + int prepend_sign, char padding_char); + +/* CIntToPyUnicode.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_int(int value, Py_ssize_t width, char padding_char, char format_char); + +/* CIntToPyUnicode.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_Py_ssize_t(Py_ssize_t value, Py_ssize_t width, char padding_char, char format_char); + +/* JoinPyUnicode.proto */ +static PyObject* __Pyx_PyUnicode_Join(PyObject* value_tuple, Py_ssize_t value_count, Py_ssize_t result_ulength, + Py_UCS4 max_char); + +/* StrEquals.proto */ +#if PY_MAJOR_VERSION >= 3 +#define __Pyx_PyString_Equals __Pyx_PyUnicode_Equals +#else +#define __Pyx_PyString_Equals __Pyx_PyBytes_Equals +#endif + +/* PyObjectFormatSimple.proto */ +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + PyObject_Format(s, f)) +#elif PY_MAJOR_VERSION < 3 + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + likely(PyString_CheckExact(s)) ? PyUnicode_FromEncodedObject(s, NULL, "strict") :\ + PyObject_Format(s, f)) +#elif CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + likely(PyLong_CheckExact(s)) ? PyLong_Type.tp_repr(s) :\ + likely(PyFloat_CheckExact(s)) ? PyFloat_Type.tp_repr(s) :\ + PyObject_Format(s, f)) +#else + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + PyObject_Format(s, f)) +#endif + +CYTHON_UNUSED static int __pyx_array_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +static PyObject *__pyx_array_get_memview(struct __pyx_array_obj *); /*proto*/ +/* GetAttr.proto */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr(PyObject *, PyObject *); + +/* GetItemInt.proto */ +#define __Pyx_GetItemInt(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_Fast(o, (Py_ssize_t)i, is_list, wraparound, boundscheck) :\ + (is_list ? (PyErr_SetString(PyExc_IndexError, "list index out of range"), (PyObject*)NULL) :\ + __Pyx_GetItemInt_Generic(o, to_py_func(i)))) +#define __Pyx_GetItemInt_List(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_List_Fast(o, (Py_ssize_t)i, wraparound, boundscheck) :\ + (PyErr_SetString(PyExc_IndexError, "list index out of range"), (PyObject*)NULL)) +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_List_Fast(PyObject *o, Py_ssize_t i, + int wraparound, int boundscheck); +#define __Pyx_GetItemInt_Tuple(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_Tuple_Fast(o, (Py_ssize_t)i, wraparound, boundscheck) :\ + (PyErr_SetString(PyExc_IndexError, "tuple index out of range"), (PyObject*)NULL)) +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Tuple_Fast(PyObject *o, Py_ssize_t i, + int wraparound, int boundscheck); +static PyObject *__Pyx_GetItemInt_Generic(PyObject *o, PyObject* j); +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Fast(PyObject *o, Py_ssize_t i, + int is_list, int wraparound, int boundscheck); + +/* PyObjectCallOneArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg); + +/* ObjectGetItem.proto */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject *__Pyx_PyObject_GetItem(PyObject *obj, PyObject *key); +#else +#define __Pyx_PyObject_GetItem(obj, key) PyObject_GetItem(obj, key) +#endif + +/* KeywordStringCheck.proto */ +static int __Pyx_CheckKeywordStrings(PyObject *kw, const char* function_name, int kw_allowed); + +/* DivInt[Py_ssize_t].proto */ +static CYTHON_INLINE Py_ssize_t __Pyx_div_Py_ssize_t(Py_ssize_t, Py_ssize_t); + +/* UnaryNegOverflows.proto */ +#define __Pyx_UNARY_NEG_WOULD_OVERFLOW(x)\ + (((x) < 0) & ((unsigned long)(x) == 0-(unsigned long)(x))) + +/* GetAttr3.proto */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr3(PyObject *, PyObject *, PyObject *); + +/* PyDictVersioning.proto */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +#define __PYX_DICT_VERSION_INIT ((PY_UINT64_T) -1) +#define __PYX_GET_DICT_VERSION(dict) (((PyDictObject*)(dict))->ma_version_tag) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var)\ + (version_var) = __PYX_GET_DICT_VERSION(dict);\ + (cache_var) = (value); +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + if (likely(__PYX_GET_DICT_VERSION(DICT) == __pyx_dict_version)) {\ + (VAR) = __pyx_dict_cached_value;\ + } else {\ + (VAR) = __pyx_dict_cached_value = (LOOKUP);\ + __pyx_dict_version = __PYX_GET_DICT_VERSION(DICT);\ + }\ +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj); +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj); +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version); +#else +#define __PYX_GET_DICT_VERSION(dict) (0) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var) +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) (VAR) = (LOOKUP); +#endif + +/* GetModuleGlobalName.proto */ +#if CYTHON_USE_DICT_VERSIONS +#define __Pyx_GetModuleGlobalName(var, name) do {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + (var) = (likely(__pyx_dict_version == __PYX_GET_DICT_VERSION(__pyx_d))) ?\ + (likely(__pyx_dict_cached_value) ? __Pyx_NewRef(__pyx_dict_cached_value) : __Pyx_GetBuiltinName(name)) :\ + __Pyx__GetModuleGlobalName(name, &__pyx_dict_version, &__pyx_dict_cached_value);\ +} while(0) +#define __Pyx_GetModuleGlobalNameUncached(var, name) do {\ + PY_UINT64_T __pyx_dict_version;\ + PyObject *__pyx_dict_cached_value;\ + (var) = __Pyx__GetModuleGlobalName(name, &__pyx_dict_version, &__pyx_dict_cached_value);\ +} while(0) +static PyObject *__Pyx__GetModuleGlobalName(PyObject *name, PY_UINT64_T *dict_version, PyObject **dict_cached_value); +#else +#define __Pyx_GetModuleGlobalName(var, name) (var) = __Pyx__GetModuleGlobalName(name) +#define __Pyx_GetModuleGlobalNameUncached(var, name) (var) = __Pyx__GetModuleGlobalName(name) +static CYTHON_INLINE PyObject *__Pyx__GetModuleGlobalName(PyObject *name); +#endif + +/* AssertionsEnabled.proto */ +#if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX < 0x02070600 && !defined(Py_OptimizeFlag) + #define __Pyx_init_assertions_enabled() (0) + #define __pyx_assertions_enabled() (1) +#elif CYTHON_COMPILING_IN_LIMITED_API || (CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030C0000) + static int __pyx_assertions_enabled_flag; + #define __pyx_assertions_enabled() (__pyx_assertions_enabled_flag) + static int __Pyx_init_assertions_enabled(void) { + PyObject *builtins, *debug, *debug_str; + int flag; + builtins = PyEval_GetBuiltins(); + if (!builtins) goto bad; + debug_str = PyUnicode_FromStringAndSize("__debug__", 9); + if (!debug_str) goto bad; + debug = PyObject_GetItem(builtins, debug_str); + Py_DECREF(debug_str); + if (!debug) goto bad; + flag = PyObject_IsTrue(debug); + Py_DECREF(debug); + if (flag == -1) goto bad; + __pyx_assertions_enabled_flag = flag; + return 0; + bad: + __pyx_assertions_enabled_flag = 1; + return -1; + } +#else + #define __Pyx_init_assertions_enabled() (0) + #define __pyx_assertions_enabled() (!Py_OptimizeFlag) +#endif + +/* RaiseTooManyValuesToUnpack.proto */ +static CYTHON_INLINE void __Pyx_RaiseTooManyValuesError(Py_ssize_t expected); + +/* RaiseNeedMoreValuesToUnpack.proto */ +static CYTHON_INLINE void __Pyx_RaiseNeedMoreValuesError(Py_ssize_t index); + +/* RaiseNoneIterError.proto */ +static CYTHON_INLINE void __Pyx_RaiseNoneNotIterableError(void); + +/* ExtTypeTest.proto */ +static CYTHON_INLINE int __Pyx_TypeTest(PyObject *obj, PyTypeObject *type); + +/* GetTopmostException.proto */ +#if CYTHON_USE_EXC_INFO_STACK && CYTHON_FAST_THREAD_STATE +static _PyErr_StackItem * __Pyx_PyErr_GetTopmostException(PyThreadState *tstate); +#endif + +/* SaveResetException.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_ExceptionSave(type, value, tb) __Pyx__ExceptionSave(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx__ExceptionSave(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#define __Pyx_ExceptionReset(type, value, tb) __Pyx__ExceptionReset(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx__ExceptionReset(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb); +#else +#define __Pyx_ExceptionSave(type, value, tb) PyErr_GetExcInfo(type, value, tb) +#define __Pyx_ExceptionReset(type, value, tb) PyErr_SetExcInfo(type, value, tb) +#endif + +/* GetException.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_GetException(type, value, tb) __Pyx__GetException(__pyx_tstate, type, value, tb) +static int __Pyx__GetException(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#else +static int __Pyx_GetException(PyObject **type, PyObject **value, PyObject **tb); +#endif + +/* SwapException.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_ExceptionSwap(type, value, tb) __Pyx__ExceptionSwap(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx__ExceptionSwap(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#else +static CYTHON_INLINE void __Pyx_ExceptionSwap(PyObject **type, PyObject **value, PyObject **tb); +#endif + +/* Import.proto */ +static PyObject *__Pyx_Import(PyObject *name, PyObject *from_list, int level); + +/* ImportDottedModule.proto */ +static PyObject *__Pyx_ImportDottedModule(PyObject *name, PyObject *parts_tuple); +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_ImportDottedModule_WalkParts(PyObject *module, PyObject *name, PyObject *parts_tuple); +#endif + +/* FastTypeChecks.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_TypeCheck(obj, type) __Pyx_IsSubtype(Py_TYPE(obj), (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) __Pyx_IsAnySubtype2(Py_TYPE(obj), (PyTypeObject *)type1, (PyTypeObject *)type2) +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches(PyObject *err, PyObject *type); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches2(PyObject *err, PyObject *type1, PyObject *type2); +#else +#define __Pyx_TypeCheck(obj, type) PyObject_TypeCheck(obj, (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) (PyObject_TypeCheck(obj, (PyTypeObject *)type1) || PyObject_TypeCheck(obj, (PyTypeObject *)type2)) +#define __Pyx_PyErr_GivenExceptionMatches(err, type) PyErr_GivenExceptionMatches(err, type) +#define __Pyx_PyErr_GivenExceptionMatches2(err, type1, type2) (PyErr_GivenExceptionMatches(err, type1) || PyErr_GivenExceptionMatches(err, type2)) +#endif +#define __Pyx_PyErr_ExceptionMatches2(err1, err2) __Pyx_PyErr_GivenExceptionMatches2(__Pyx_PyErr_CurrentExceptionType(), err1, err2) +#define __Pyx_PyException_Check(obj) __Pyx_TypeCheck(obj, PyExc_Exception) + +CYTHON_UNUSED static int __pyx_memoryview_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +/* ListCompAppend.proto */ +#if CYTHON_USE_PYLIST_INTERNALS && CYTHON_ASSUME_SAFE_MACROS +static CYTHON_INLINE int __Pyx_ListComp_Append(PyObject* list, PyObject* x) { + PyListObject* L = (PyListObject*) list; + Py_ssize_t len = Py_SIZE(list); + if (likely(L->allocated > len)) { + Py_INCREF(x); + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 + L->ob_item[len] = x; + #else + PyList_SET_ITEM(list, len, x); + #endif + __Pyx_SET_SIZE(list, len + 1); + return 0; + } + return PyList_Append(list, x); +} +#else +#define __Pyx_ListComp_Append(L,x) PyList_Append(L,x) +#endif + +/* PySequenceMultiply.proto */ +#define __Pyx_PySequence_Multiply_Left(mul, seq) __Pyx_PySequence_Multiply(seq, mul) +static CYTHON_INLINE PyObject* __Pyx_PySequence_Multiply(PyObject *seq, Py_ssize_t mul); + +/* SetItemInt.proto */ +#define __Pyx_SetItemInt(o, i, v, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_SetItemInt_Fast(o, (Py_ssize_t)i, v, is_list, wraparound, boundscheck) :\ + (is_list ? (PyErr_SetString(PyExc_IndexError, "list assignment index out of range"), -1) :\ + __Pyx_SetItemInt_Generic(o, to_py_func(i), v))) +static int __Pyx_SetItemInt_Generic(PyObject *o, PyObject *j, PyObject *v); +static CYTHON_INLINE int __Pyx_SetItemInt_Fast(PyObject *o, Py_ssize_t i, PyObject *v, + int is_list, int wraparound, int boundscheck); + +/* RaiseUnboundLocalError.proto */ +static CYTHON_INLINE void __Pyx_RaiseUnboundLocalError(const char *varname); + +/* DivInt[long].proto */ +static CYTHON_INLINE long __Pyx_div_long(long, long); + +/* PySequenceContains.proto */ +static CYTHON_INLINE int __Pyx_PySequence_ContainsTF(PyObject* item, PyObject* seq, int eq) { + int result = PySequence_Contains(seq, item); + return unlikely(result < 0) ? result : (result == (eq == Py_EQ)); +} + +/* ImportFrom.proto */ +static PyObject* __Pyx_ImportFrom(PyObject* module, PyObject* name); + +/* HasAttr.proto */ +#if __PYX_LIMITED_VERSION_HEX >= 0x030d00A1 +#define __Pyx_HasAttr(o, n) PyObject_HasAttrWithError(o, n) +#else +static CYTHON_INLINE int __Pyx_HasAttr(PyObject *, PyObject *); +#endif + +/* ListAppend.proto */ +#if CYTHON_USE_PYLIST_INTERNALS && CYTHON_ASSUME_SAFE_MACROS +static CYTHON_INLINE int __Pyx_PyList_Append(PyObject* list, PyObject* x) { + PyListObject* L = (PyListObject*) list; + Py_ssize_t len = Py_SIZE(list); + if (likely(L->allocated > len) & likely(len > (L->allocated >> 1))) { + Py_INCREF(x); + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 + L->ob_item[len] = x; + #else + PyList_SET_ITEM(list, len, x); + #endif + __Pyx_SET_SIZE(list, len + 1); + return 0; + } + return PyList_Append(list, x); +} +#else +#define __Pyx_PyList_Append(L,x) PyList_Append(L,x) +#endif + +/* PyObjectCall2Args.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call2Args(PyObject* function, PyObject* arg1, PyObject* arg2); + +/* PyObjectGetMethod.proto */ +static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method); + +/* PyObjectCallMethod1.proto */ +static PyObject* __Pyx_PyObject_CallMethod1(PyObject* obj, PyObject* method_name, PyObject* arg); + +/* StringJoin.proto */ +#if PY_MAJOR_VERSION < 3 +#define __Pyx_PyString_Join __Pyx_PyBytes_Join +#define __Pyx_PyBaseString_Join(s, v) (PyUnicode_CheckExact(s) ? PyUnicode_Join(s, v) : __Pyx_PyBytes_Join(s, v)) +#else +#define __Pyx_PyString_Join PyUnicode_Join +#define __Pyx_PyBaseString_Join PyUnicode_Join +#endif +static CYTHON_INLINE PyObject* __Pyx_PyBytes_Join(PyObject* sep, PyObject* values); + +/* CIntToPyUnicode.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_size_t(size_t value, Py_ssize_t width, char padding_char, char format_char); + +/* Profile.proto */ +#ifndef CYTHON_PROFILE +#if CYTHON_COMPILING_IN_LIMITED_API || CYTHON_COMPILING_IN_PYPY + #define CYTHON_PROFILE 0 +#else + #define CYTHON_PROFILE 1 +#endif +#endif +#ifndef CYTHON_TRACE_NOGIL + #define CYTHON_TRACE_NOGIL 0 +#else + #if CYTHON_TRACE_NOGIL && !defined(CYTHON_TRACE) + #define CYTHON_TRACE 1 + #endif +#endif +#ifndef CYTHON_TRACE + #define CYTHON_TRACE 0 +#endif +#if CYTHON_TRACE + #undef CYTHON_PROFILE_REUSE_FRAME +#endif +#ifndef CYTHON_PROFILE_REUSE_FRAME + #define CYTHON_PROFILE_REUSE_FRAME 0 +#endif +#if CYTHON_PROFILE || CYTHON_TRACE + #include "compile.h" + #include "frameobject.h" + #include "traceback.h" +#if PY_VERSION_HEX >= 0x030b00a6 + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif + #if CYTHON_PROFILE_REUSE_FRAME + #define CYTHON_FRAME_MODIFIER static + #define CYTHON_FRAME_DEL(frame) + #else + #define CYTHON_FRAME_MODIFIER + #define CYTHON_FRAME_DEL(frame) Py_CLEAR(frame) + #endif + #define __Pyx_TraceDeclarations\ + static PyCodeObject *__pyx_frame_code = NULL;\ + CYTHON_FRAME_MODIFIER PyFrameObject *__pyx_frame = NULL;\ + int __Pyx_use_tracing = 0; + #define __Pyx_TraceFrameInit(codeobj)\ + if (codeobj) __pyx_frame_code = (PyCodeObject*) codeobj; +#if PY_VERSION_HEX >= 0x030b00a2 + #if PY_VERSION_HEX >= 0x030C00b1 + #define __Pyx_IsTracing(tstate, check_tracing, check_funcs)\ + ((!(check_tracing) || !(tstate)->tracing) &&\ + (!(check_funcs) || (tstate)->c_profilefunc || (CYTHON_TRACE && (tstate)->c_tracefunc))) + #else + #define __Pyx_IsTracing(tstate, check_tracing, check_funcs)\ + (unlikely((tstate)->cframe->use_tracing) &&\ + (!(check_tracing) || !(tstate)->tracing) &&\ + (!(check_funcs) || (tstate)->c_profilefunc || (CYTHON_TRACE && (tstate)->c_tracefunc))) + #endif + #define __Pyx_EnterTracing(tstate) PyThreadState_EnterTracing(tstate) + #define __Pyx_LeaveTracing(tstate) PyThreadState_LeaveTracing(tstate) +#elif PY_VERSION_HEX >= 0x030a00b1 + #define __Pyx_IsTracing(tstate, check_tracing, check_funcs)\ + (unlikely((tstate)->cframe->use_tracing) &&\ + (!(check_tracing) || !(tstate)->tracing) &&\ + (!(check_funcs) || (tstate)->c_profilefunc || (CYTHON_TRACE && (tstate)->c_tracefunc))) + #define __Pyx_EnterTracing(tstate)\ + do { tstate->tracing++; tstate->cframe->use_tracing = 0; } while (0) + #define __Pyx_LeaveTracing(tstate)\ + do {\ + tstate->tracing--;\ + tstate->cframe->use_tracing = ((CYTHON_TRACE && tstate->c_tracefunc != NULL)\ + || tstate->c_profilefunc != NULL);\ + } while (0) +#else + #define __Pyx_IsTracing(tstate, check_tracing, check_funcs)\ + (unlikely((tstate)->use_tracing) &&\ + (!(check_tracing) || !(tstate)->tracing) &&\ + (!(check_funcs) || (tstate)->c_profilefunc || (CYTHON_TRACE && (tstate)->c_tracefunc))) + #define __Pyx_EnterTracing(tstate)\ + do { tstate->tracing++; tstate->use_tracing = 0; } while (0) + #define __Pyx_LeaveTracing(tstate)\ + do {\ + tstate->tracing--;\ + tstate->use_tracing = ((CYTHON_TRACE && tstate->c_tracefunc != NULL)\ + || tstate->c_profilefunc != NULL);\ + } while (0) +#endif + #ifdef WITH_THREAD + #define __Pyx_TraceCall(funcname, srcfile, firstlineno, nogil, goto_error)\ + if (nogil) {\ + if (CYTHON_TRACE_NOGIL) {\ + PyThreadState *tstate;\ + PyGILState_STATE state = PyGILState_Ensure();\ + tstate = __Pyx_PyThreadState_Current;\ + if (__Pyx_IsTracing(tstate, 1, 1)) {\ + __Pyx_use_tracing = __Pyx_TraceSetupAndCall(&__pyx_frame_code, &__pyx_frame, tstate, funcname, srcfile, firstlineno);\ + }\ + PyGILState_Release(state);\ + if (unlikely(__Pyx_use_tracing < 0)) goto_error;\ + }\ + } else {\ + PyThreadState* tstate = PyThreadState_GET();\ + if (__Pyx_IsTracing(tstate, 1, 1)) {\ + __Pyx_use_tracing = __Pyx_TraceSetupAndCall(&__pyx_frame_code, &__pyx_frame, tstate, funcname, srcfile, firstlineno);\ + if (unlikely(__Pyx_use_tracing < 0)) goto_error;\ + }\ + } + #else + #define __Pyx_TraceCall(funcname, srcfile, firstlineno, nogil, goto_error)\ + { PyThreadState* tstate = PyThreadState_GET();\ + if (__Pyx_IsTracing(tstate, 1, 1)) {\ + __Pyx_use_tracing = __Pyx_TraceSetupAndCall(&__pyx_frame_code, &__pyx_frame, tstate, funcname, srcfile, firstlineno);\ + if (unlikely(__Pyx_use_tracing < 0)) goto_error;\ + }\ + } + #endif + #define __Pyx_TraceException()\ + if (likely(!__Pyx_use_tracing)); else {\ + PyThreadState* tstate = __Pyx_PyThreadState_Current;\ + if (__Pyx_IsTracing(tstate, 0, 1)) {\ + __Pyx_EnterTracing(tstate);\ + PyObject *exc_info = __Pyx_GetExceptionTuple(tstate);\ + if (exc_info) {\ + if (CYTHON_TRACE && tstate->c_tracefunc)\ + tstate->c_tracefunc(\ + tstate->c_traceobj, __pyx_frame, PyTrace_EXCEPTION, exc_info);\ + tstate->c_profilefunc(\ + tstate->c_profileobj, __pyx_frame, PyTrace_EXCEPTION, exc_info);\ + Py_DECREF(exc_info);\ + }\ + __Pyx_LeaveTracing(tstate);\ + }\ + } + static void __Pyx_call_return_trace_func(PyThreadState *tstate, PyFrameObject *frame, PyObject *result) { + PyObject *type, *value, *traceback; + __Pyx_ErrFetchInState(tstate, &type, &value, &traceback); + __Pyx_EnterTracing(tstate); + if (CYTHON_TRACE && tstate->c_tracefunc) + tstate->c_tracefunc(tstate->c_traceobj, frame, PyTrace_RETURN, result); + if (tstate->c_profilefunc) + tstate->c_profilefunc(tstate->c_profileobj, frame, PyTrace_RETURN, result); + CYTHON_FRAME_DEL(frame); + __Pyx_LeaveTracing(tstate); + __Pyx_ErrRestoreInState(tstate, type, value, traceback); + } + #ifdef WITH_THREAD + #define __Pyx_TraceReturn(result, nogil)\ + if (likely(!__Pyx_use_tracing)); else {\ + if (nogil) {\ + if (CYTHON_TRACE_NOGIL) {\ + PyThreadState *tstate;\ + PyGILState_STATE state = PyGILState_Ensure();\ + tstate = __Pyx_PyThreadState_Current;\ + if (__Pyx_IsTracing(tstate, 0, 0)) {\ + __Pyx_call_return_trace_func(tstate, __pyx_frame, (PyObject*)result);\ + }\ + PyGILState_Release(state);\ + }\ + } else {\ + PyThreadState* tstate = __Pyx_PyThreadState_Current;\ + if (__Pyx_IsTracing(tstate, 0, 0)) {\ + __Pyx_call_return_trace_func(tstate, __pyx_frame, (PyObject*)result);\ + }\ + }\ + } + #else + #define __Pyx_TraceReturn(result, nogil)\ + if (likely(!__Pyx_use_tracing)); else {\ + PyThreadState* tstate = __Pyx_PyThreadState_Current;\ + if (__Pyx_IsTracing(tstate, 0, 0)) {\ + __Pyx_call_return_trace_func(tstate, __pyx_frame, (PyObject*)result);\ + }\ + } + #endif + static PyCodeObject *__Pyx_createFrameCodeObject(const char *funcname, const char *srcfile, int firstlineno); + static int __Pyx_TraceSetupAndCall(PyCodeObject** code, PyFrameObject** frame, PyThreadState* tstate, const char *funcname, const char *srcfile, int firstlineno); +#else + #define __Pyx_TraceDeclarations + #define __Pyx_TraceFrameInit(codeobj) + #define __Pyx_TraceCall(funcname, srcfile, firstlineno, nogil, goto_error) if ((1)); else goto_error; + #define __Pyx_TraceException() + #define __Pyx_TraceReturn(result, nogil) +#endif +#if CYTHON_TRACE + static int __Pyx_call_line_trace_func(PyThreadState *tstate, PyFrameObject *frame, int lineno) { + int ret; + PyObject *type, *value, *traceback; + __Pyx_ErrFetchInState(tstate, &type, &value, &traceback); + __Pyx_PyFrame_SetLineNumber(frame, lineno); + __Pyx_EnterTracing(tstate); + ret = tstate->c_tracefunc(tstate->c_traceobj, frame, PyTrace_LINE, NULL); + __Pyx_LeaveTracing(tstate); + if (likely(!ret)) { + __Pyx_ErrRestoreInState(tstate, type, value, traceback); + } else { + Py_XDECREF(type); + Py_XDECREF(value); + Py_XDECREF(traceback); + } + return ret; + } + #ifdef WITH_THREAD + #define __Pyx_TraceLine(lineno, nogil, goto_error)\ + if (likely(!__Pyx_use_tracing)); else {\ + if (nogil) {\ + if (CYTHON_TRACE_NOGIL) {\ + int ret = 0;\ + PyThreadState *tstate;\ + PyGILState_STATE state = __Pyx_PyGILState_Ensure();\ + tstate = __Pyx_PyThreadState_Current;\ + if (__Pyx_IsTracing(tstate, 0, 0) && tstate->c_tracefunc && __pyx_frame->f_trace) {\ + ret = __Pyx_call_line_trace_func(tstate, __pyx_frame, lineno);\ + }\ + __Pyx_PyGILState_Release(state);\ + if (unlikely(ret)) goto_error;\ + }\ + } else {\ + PyThreadState* tstate = __Pyx_PyThreadState_Current;\ + if (__Pyx_IsTracing(tstate, 0, 0) && tstate->c_tracefunc && __pyx_frame->f_trace) {\ + int ret = __Pyx_call_line_trace_func(tstate, __pyx_frame, lineno);\ + if (unlikely(ret)) goto_error;\ + }\ + }\ + } + #else + #define __Pyx_TraceLine(lineno, nogil, goto_error)\ + if (likely(!__Pyx_use_tracing)); else {\ + PyThreadState* tstate = __Pyx_PyThreadState_Current;\ + if (__Pyx_IsTracing(tstate, 0, 0) && tstate->c_tracefunc && __pyx_frame->f_trace) {\ + int ret = __Pyx_call_line_trace_func(tstate, __pyx_frame, lineno);\ + if (unlikely(ret)) goto_error;\ + }\ + } + #endif +#else + #define __Pyx_TraceLine(lineno, nogil, goto_error) if ((1)); else goto_error; +#endif + +/* IsLittleEndian.proto */ +static CYTHON_INLINE int __Pyx_Is_Little_Endian(void); + +/* BufferFormatCheck.proto */ +static const char* __Pyx_BufFmt_CheckString(__Pyx_BufFmt_Context* ctx, const char* ts); +static void __Pyx_BufFmt_Init(__Pyx_BufFmt_Context* ctx, + __Pyx_BufFmt_StackElem* stack, + __Pyx_TypeInfo* type); + +/* BufferGetAndValidate.proto */ +#define __Pyx_GetBufferAndValidate(buf, obj, dtype, flags, nd, cast, stack)\ + ((obj == Py_None || obj == NULL) ?\ + (__Pyx_ZeroBuffer(buf), 0) :\ + __Pyx__GetBufferAndValidate(buf, obj, dtype, flags, nd, cast, stack)) +static int __Pyx__GetBufferAndValidate(Py_buffer* buf, PyObject* obj, + __Pyx_TypeInfo* dtype, int flags, int nd, int cast, __Pyx_BufFmt_StackElem* stack); +static void __Pyx_ZeroBuffer(Py_buffer* buf); +static CYTHON_INLINE void __Pyx_SafeReleaseBuffer(Py_buffer* info); +static Py_ssize_t __Pyx_minusones[] = { -1, -1, -1, -1, -1, -1, -1, -1 }; +static Py_ssize_t __Pyx_zeros[] = { 0, 0, 0, 0, 0, 0, 0, 0 }; + +/* MoveIfSupported.proto */ +#if CYTHON_USE_CPP_STD_MOVE + #include + #define __PYX_STD_MOVE_IF_SUPPORTED(x) std::move(x) +#else + #define __PYX_STD_MOVE_IF_SUPPORTED(x) x +#endif + +/* BufferFallbackError.proto */ +static void __Pyx_RaiseBufferFallbackError(void); + +/* PyObjectCallNoArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func); + +/* WriteUnraisableException.proto */ +static void __Pyx_WriteUnraisable(const char *name, int clineno, + int lineno, const char *filename, + int full_traceback, int nogil); + +/* PyObject_GenericGetAttrNoDict.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttrNoDict PyObject_GenericGetAttr +#endif + +/* PyObject_GenericGetAttr.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttr PyObject_GenericGetAttr +#endif + +/* IncludeStructmemberH.proto */ +#include + +/* FixUpExtensionType.proto */ +#if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type); +#endif + +/* PyObjectCallMethod0.proto */ +static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name); + +/* ValidateBasesTuple.proto */ +#if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases); +#endif + +/* PyType_Ready.proto */ +CYTHON_UNUSED static int __Pyx_PyType_Ready(PyTypeObject *t); + +/* SetupReduce.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce(PyObject* type_obj); +#endif + +/* SetVTable.proto */ +static int __Pyx_SetVtable(PyTypeObject* typeptr , void* vtable); + +/* GetVTable.proto */ +static void* __Pyx_GetVtable(PyTypeObject *type); + +/* MergeVTables.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_MergeVtables(PyTypeObject *type); +#endif + +/* TypeImport.proto */ +#ifndef __PYX_HAVE_RT_ImportType_proto_3_0_8 +#define __PYX_HAVE_RT_ImportType_proto_3_0_8 +#if defined (__STDC_VERSION__) && __STDC_VERSION__ >= 201112L +#include +#endif +#if (defined (__STDC_VERSION__) && __STDC_VERSION__ >= 201112L) || __cplusplus >= 201103L +#define __PYX_GET_STRUCT_ALIGNMENT_3_0_8(s) alignof(s) +#else +#define __PYX_GET_STRUCT_ALIGNMENT_3_0_8(s) sizeof(void*) +#endif +enum __Pyx_ImportType_CheckSize_3_0_8 { + __Pyx_ImportType_CheckSize_Error_3_0_8 = 0, + __Pyx_ImportType_CheckSize_Warn_3_0_8 = 1, + __Pyx_ImportType_CheckSize_Ignore_3_0_8 = 2 +}; +static PyTypeObject *__Pyx_ImportType_3_0_8(PyObject* module, const char *module_name, const char *class_name, size_t size, size_t alignment, enum __Pyx_ImportType_CheckSize_3_0_8 check_size); +#endif + +/* FetchSharedCythonModule.proto */ +static PyObject *__Pyx_FetchSharedCythonABIModule(void); + +/* FetchCommonType.proto */ +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type); +#else +static PyTypeObject* __Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases); +#endif + +/* PyMethodNew.proto */ +#if CYTHON_COMPILING_IN_LIMITED_API +static PyObject *__Pyx_PyMethod_New(PyObject *func, PyObject *self, PyObject *typ) { + PyObject *typesModule=NULL, *methodType=NULL, *result=NULL; + CYTHON_UNUSED_VAR(typ); + if (!self) + return __Pyx_NewRef(func); + typesModule = PyImport_ImportModule("types"); + if (!typesModule) return NULL; + methodType = PyObject_GetAttrString(typesModule, "MethodType"); + Py_DECREF(typesModule); + if (!methodType) return NULL; + result = PyObject_CallFunctionObjArgs(methodType, func, self, NULL); + Py_DECREF(methodType); + return result; +} +#elif PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_PyMethod_New(PyObject *func, PyObject *self, PyObject *typ) { + CYTHON_UNUSED_VAR(typ); + if (!self) + return __Pyx_NewRef(func); + return PyMethod_New(func, self); +} +#else + #define __Pyx_PyMethod_New PyMethod_New +#endif + +/* PyVectorcallFastCallDict.proto */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw); +#endif + +/* CythonFunctionShared.proto */ +#define __Pyx_CyFunction_USED +#define __Pyx_CYFUNCTION_STATICMETHOD 0x01 +#define __Pyx_CYFUNCTION_CLASSMETHOD 0x02 +#define __Pyx_CYFUNCTION_CCLASS 0x04 +#define __Pyx_CYFUNCTION_COROUTINE 0x08 +#define __Pyx_CyFunction_GetClosure(f)\ + (((__pyx_CyFunctionObject *) (f))->func_closure) +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_CyFunction_GetClassObj(f)\ + (((__pyx_CyFunctionObject *) (f))->func_classobj) +#else + #define __Pyx_CyFunction_GetClassObj(f)\ + ((PyObject*) ((PyCMethodObject *) (f))->mm_class) +#endif +#define __Pyx_CyFunction_SetClassObj(f, classobj)\ + __Pyx__CyFunction_SetClassObj((__pyx_CyFunctionObject *) (f), (classobj)) +#define __Pyx_CyFunction_Defaults(type, f)\ + ((type *)(((__pyx_CyFunctionObject *) (f))->defaults)) +#define __Pyx_CyFunction_SetDefaultsGetter(f, g)\ + ((__pyx_CyFunctionObject *) (f))->defaults_getter = (g) +typedef struct { +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject_HEAD + PyObject *func; +#elif PY_VERSION_HEX < 0x030900B1 + PyCFunctionObject func; +#else + PyCMethodObject func; +#endif +#if CYTHON_BACKPORT_VECTORCALL + __pyx_vectorcallfunc func_vectorcall; +#endif +#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API + PyObject *func_weakreflist; +#endif + PyObject *func_dict; + PyObject *func_name; + PyObject *func_qualname; + PyObject *func_doc; + PyObject *func_globals; + PyObject *func_code; + PyObject *func_closure; +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + PyObject *func_classobj; +#endif + void *defaults; + int defaults_pyobjects; + size_t defaults_size; + int flags; + PyObject *defaults_tuple; + PyObject *defaults_kwdict; + PyObject *(*defaults_getter)(PyObject *); + PyObject *func_annotations; + PyObject *func_is_coroutine; +} __pyx_CyFunctionObject; +#undef __Pyx_CyOrPyCFunction_Check +#define __Pyx_CyFunction_Check(obj) __Pyx_TypeCheck(obj, __pyx_CyFunctionType) +#define __Pyx_CyOrPyCFunction_Check(obj) __Pyx_TypeCheck2(obj, __pyx_CyFunctionType, &PyCFunction_Type) +#define __Pyx_CyFunction_CheckExact(obj) __Pyx_IS_TYPE(obj, __pyx_CyFunctionType) +static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc); +#undef __Pyx_IsSameCFunction +#define __Pyx_IsSameCFunction(func, cfunc) __Pyx__IsSameCyOrCFunction(func, cfunc) +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject* op, PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj); +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *m, + size_t size, + int pyobjects); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *m, + PyObject *tuple); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *m, + PyObject *dict); +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *m, + PyObject *dict); +static int __pyx_CyFunction_init(PyObject *module); +#if CYTHON_METH_FASTCALL +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +#if CYTHON_BACKPORT_VECTORCALL +#define __Pyx_CyFunction_func_vectorcall(f) (((__pyx_CyFunctionObject*)f)->func_vectorcall) +#else +#define __Pyx_CyFunction_func_vectorcall(f) (((PyCFunctionObject*)f)->vectorcall) +#endif +#endif + +/* CythonFunction.proto */ +static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); + +/* CLineInTraceback.proto */ +#ifdef CYTHON_CLINE_IN_TRACEBACK +#define __Pyx_CLineForTraceback(tstate, c_line) (((CYTHON_CLINE_IN_TRACEBACK)) ? c_line : 0) +#else +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line); +#endif + +/* CodeObjectCache.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +typedef struct { + PyCodeObject* code_object; + int code_line; +} __Pyx_CodeObjectCacheEntry; +struct __Pyx_CodeObjectCache { + int count; + int max_count; + __Pyx_CodeObjectCacheEntry* entries; +}; +static struct __Pyx_CodeObjectCache __pyx_code_cache = {0,0,NULL}; +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line); +static PyCodeObject *__pyx_find_code_object(int code_line); +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object); +#endif + +/* AddTraceback.proto */ +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename); + +#if PY_MAJOR_VERSION < 3 + static int __Pyx_GetBuffer(PyObject *obj, Py_buffer *view, int flags); + static void __Pyx_ReleaseBuffer(Py_buffer *view); +#else + #define __Pyx_GetBuffer PyObject_GetBuffer + #define __Pyx_ReleaseBuffer PyBuffer_Release +#endif + + +/* BufferStructDeclare.proto */ +typedef struct { + Py_ssize_t shape, strides, suboffsets; +} __Pyx_Buf_DimInfo; +typedef struct { + size_t refcount; + Py_buffer pybuffer; +} __Pyx_Buffer; +typedef struct { + __Pyx_Buffer *rcbuffer; + char *data; + __Pyx_Buf_DimInfo diminfo[8]; +} __Pyx_LocalBuf_ND; + +/* MemviewSliceIsContig.proto */ +static int __pyx_memviewslice_is_contig(const __Pyx_memviewslice mvs, char order, int ndim); + +/* OverlappingSlices.proto */ +static int __pyx_slices_overlap(__Pyx_memviewslice *slice1, + __Pyx_memviewslice *slice2, + int ndim, size_t itemsize); + +/* TypeInfoCompare.proto */ +static int __pyx_typeinfo_cmp(__Pyx_TypeInfo *a, __Pyx_TypeInfo *b); + +/* MemviewSliceValidateAndInit.proto */ +static int __Pyx_ValidateAndInit_memviewslice( + int *axes_specs, + int c_or_f_flag, + int buf_flags, + int ndim, + __Pyx_TypeInfo *dtype, + __Pyx_BufFmt_StackElem stack[], + __Pyx_memviewslice *memviewslice, + PyObject *original_obj); + +/* ObjectToMemviewSlice.proto */ +static CYTHON_INLINE __Pyx_memviewslice __Pyx_PyObject_to_MemoryviewSlice_dsds_double(PyObject *, int writable_flag); + +/* MemviewDtypeToObject.proto */ +static CYTHON_INLINE PyObject *__pyx_memview_get_double(const char *itemp); +static CYTHON_INLINE int __pyx_memview_set_double(const char *itemp, PyObject *obj); + +/* ObjectToMemviewSlice.proto */ +static CYTHON_INLINE __Pyx_memviewslice __Pyx_PyObject_to_MemoryviewSlice_ds_double(PyObject *, int writable_flag); + +/* CppExceptionConversion.proto */ +#ifndef __Pyx_CppExn2PyErr +#include +#include +#include +#include +static void __Pyx_CppExn2PyErr() { + try { + if (PyErr_Occurred()) + ; // let the latest Python exn pass through and ignore the current one + else + throw; + } catch (const std::bad_alloc& exn) { + PyErr_SetString(PyExc_MemoryError, exn.what()); + } catch (const std::bad_cast& exn) { + PyErr_SetString(PyExc_TypeError, exn.what()); + } catch (const std::bad_typeid& exn) { + PyErr_SetString(PyExc_TypeError, exn.what()); + } catch (const std::domain_error& exn) { + PyErr_SetString(PyExc_ValueError, exn.what()); + } catch (const std::invalid_argument& exn) { + PyErr_SetString(PyExc_ValueError, exn.what()); + } catch (const std::ios_base::failure& exn) { + PyErr_SetString(PyExc_IOError, exn.what()); + } catch (const std::out_of_range& exn) { + PyErr_SetString(PyExc_IndexError, exn.what()); + } catch (const std::overflow_error& exn) { + PyErr_SetString(PyExc_OverflowError, exn.what()); + } catch (const std::range_error& exn) { + PyErr_SetString(PyExc_ArithmeticError, exn.what()); + } catch (const std::underflow_error& exn) { + PyErr_SetString(PyExc_ArithmeticError, exn.what()); + } catch (const std::exception& exn) { + PyErr_SetString(PyExc_RuntimeError, exn.what()); + } + catch (...) + { + PyErr_SetString(PyExc_RuntimeError, "Unknown exception"); + } +} +#endif + +/* RealImag.proto */ +#if CYTHON_CCOMPLEX + #ifdef __cplusplus + #define __Pyx_CREAL(z) ((z).real()) + #define __Pyx_CIMAG(z) ((z).imag()) + #else + #define __Pyx_CREAL(z) (__real__(z)) + #define __Pyx_CIMAG(z) (__imag__(z)) + #endif +#else + #define __Pyx_CREAL(z) ((z).real) + #define __Pyx_CIMAG(z) ((z).imag) +#endif +#if defined(__cplusplus) && CYTHON_CCOMPLEX\ + && (defined(_WIN32) || defined(__clang__) || (defined(__GNUC__) && (__GNUC__ >= 5 || __GNUC__ == 4 && __GNUC_MINOR__ >= 4 )) || __cplusplus >= 201103) + #define __Pyx_SET_CREAL(z,x) ((z).real(x)) + #define __Pyx_SET_CIMAG(z,y) ((z).imag(y)) +#else + #define __Pyx_SET_CREAL(z,x) __Pyx_CREAL(z) = (x) + #define __Pyx_SET_CIMAG(z,y) __Pyx_CIMAG(z) = (y) +#endif + +/* Arithmetic.proto */ +#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #define __Pyx_c_eq_float(a, b) ((a)==(b)) + #define __Pyx_c_sum_float(a, b) ((a)+(b)) + #define __Pyx_c_diff_float(a, b) ((a)-(b)) + #define __Pyx_c_prod_float(a, b) ((a)*(b)) + #define __Pyx_c_quot_float(a, b) ((a)/(b)) + #define __Pyx_c_neg_float(a) (-(a)) + #ifdef __cplusplus + #define __Pyx_c_is_zero_float(z) ((z)==(float)0) + #define __Pyx_c_conj_float(z) (::std::conj(z)) + #if 1 + #define __Pyx_c_abs_float(z) (::std::abs(z)) + #define __Pyx_c_pow_float(a, b) (::std::pow(a, b)) + #endif + #else + #define __Pyx_c_is_zero_float(z) ((z)==0) + #define __Pyx_c_conj_float(z) (conjf(z)) + #if 1 + #define __Pyx_c_abs_float(z) (cabsf(z)) + #define __Pyx_c_pow_float(a, b) (cpowf(a, b)) + #endif + #endif +#else + static CYTHON_INLINE int __Pyx_c_eq_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_sum_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_diff_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_prod_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_quot_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_neg_float(__pyx_t_float_complex); + static CYTHON_INLINE int __Pyx_c_is_zero_float(__pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_conj_float(__pyx_t_float_complex); + #if 1 + static CYTHON_INLINE float __Pyx_c_abs_float(__pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_pow_float(__pyx_t_float_complex, __pyx_t_float_complex); + #endif +#endif + +/* Arithmetic.proto */ +#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #define __Pyx_c_eq_double(a, b) ((a)==(b)) + #define __Pyx_c_sum_double(a, b) ((a)+(b)) + #define __Pyx_c_diff_double(a, b) ((a)-(b)) + #define __Pyx_c_prod_double(a, b) ((a)*(b)) + #define __Pyx_c_quot_double(a, b) ((a)/(b)) + #define __Pyx_c_neg_double(a) (-(a)) + #ifdef __cplusplus + #define __Pyx_c_is_zero_double(z) ((z)==(double)0) + #define __Pyx_c_conj_double(z) (::std::conj(z)) + #if 1 + #define __Pyx_c_abs_double(z) (::std::abs(z)) + #define __Pyx_c_pow_double(a, b) (::std::pow(a, b)) + #endif + #else + #define __Pyx_c_is_zero_double(z) ((z)==0) + #define __Pyx_c_conj_double(z) (conj(z)) + #if 1 + #define __Pyx_c_abs_double(z) (cabs(z)) + #define __Pyx_c_pow_double(a, b) (cpow(a, b)) + #endif + #endif +#else + static CYTHON_INLINE int __Pyx_c_eq_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_sum_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_diff_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_prod_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_quot_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_neg_double(__pyx_t_double_complex); + static CYTHON_INLINE int __Pyx_c_is_zero_double(__pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_conj_double(__pyx_t_double_complex); + #if 1 + static CYTHON_INLINE double __Pyx_c_abs_double(__pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_pow_double(__pyx_t_double_complex, __pyx_t_double_complex); + #endif +#endif + +/* MemviewSliceCopyTemplate.proto */ +static __Pyx_memviewslice +__pyx_memoryview_copy_new_contig(const __Pyx_memviewslice *from_mvs, + const char *mode, int ndim, + size_t sizeof_dtype, int contig_flag, + int dtype_is_object); + +/* MemviewSliceInit.proto */ +#define __Pyx_BUF_MAX_NDIMS %(BUF_MAX_NDIMS)d +#define __Pyx_MEMVIEW_DIRECT 1 +#define __Pyx_MEMVIEW_PTR 2 +#define __Pyx_MEMVIEW_FULL 4 +#define __Pyx_MEMVIEW_CONTIG 8 +#define __Pyx_MEMVIEW_STRIDED 16 +#define __Pyx_MEMVIEW_FOLLOW 32 +#define __Pyx_IS_C_CONTIG 1 +#define __Pyx_IS_F_CONTIG 2 +static int __Pyx_init_memviewslice( + struct __pyx_memoryview_obj *memview, + int ndim, + __Pyx_memviewslice *memviewslice, + int memview_is_new_reference); +static CYTHON_INLINE int __pyx_add_acquisition_count_locked( + __pyx_atomic_int_type *acquisition_count, PyThread_type_lock lock); +static CYTHON_INLINE int __pyx_sub_acquisition_count_locked( + __pyx_atomic_int_type *acquisition_count, PyThread_type_lock lock); +#define __pyx_get_slice_count_pointer(memview) (&memview->acquisition_count) +#define __PYX_INC_MEMVIEW(slice, have_gil) __Pyx_INC_MEMVIEW(slice, have_gil, __LINE__) +#define __PYX_XCLEAR_MEMVIEW(slice, have_gil) __Pyx_XCLEAR_MEMVIEW(slice, have_gil, __LINE__) +static CYTHON_INLINE void __Pyx_INC_MEMVIEW(__Pyx_memviewslice *, int, int); +static CYTHON_INLINE void __Pyx_XCLEAR_MEMVIEW(__Pyx_memviewslice *, int, int); + +/* TypeInfoToFormat.proto */ +struct __pyx_typeinfo_string { + char string[3]; +}; +static struct __pyx_typeinfo_string __Pyx_TypeInfoToFormat(__Pyx_TypeInfo *type); + +/* CIntFromPy.proto */ +static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_int(int value); + +/* None.proto */ +#include + +/* CIntFromPy.proto */ +static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *); + +/* CIntFromPy.proto */ +static CYTHON_INLINE char __Pyx_PyInt_As_char(PyObject *); + +/* FormatTypeName.proto */ +#if CYTHON_COMPILING_IN_LIMITED_API +typedef PyObject *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%U" +static __Pyx_TypeName __Pyx_PyType_GetName(PyTypeObject* tp); +#define __Pyx_DECREF_TypeName(obj) Py_XDECREF(obj) +#else +typedef const char *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%.200s" +#define __Pyx_PyType_GetName(tp) ((tp)->tp_name) +#define __Pyx_DECREF_TypeName(obj) +#endif + +/* CheckBinaryVersion.proto */ +static unsigned long __Pyx_get_runtime_version(void); +static int __Pyx_check_binary_version(unsigned long ct_version, unsigned long rt_version, int allow_newer); + +/* InitStrings.proto */ +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t); + +/* #### Code section: module_declarations ### */ +static PyObject *__pyx_array_get_memview(struct __pyx_array_obj *__pyx_v_self); /* proto*/ +static char *__pyx_memoryview_get_item_pointer(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index); /* proto*/ +static PyObject *__pyx_memoryview_is_slice(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj); /* proto*/ +static PyObject *__pyx_memoryview_setitem_slice_assignment(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_dst, PyObject *__pyx_v_src); /* proto*/ +static PyObject *__pyx_memoryview_setitem_slice_assign_scalar(struct __pyx_memoryview_obj *__pyx_v_self, struct __pyx_memoryview_obj *__pyx_v_dst, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryview_setitem_indexed(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryview_convert_item_to_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp); /* proto*/ +static PyObject *__pyx_memoryview_assign_item_from_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryview__get_base(struct __pyx_memoryview_obj *__pyx_v_self); /* proto*/ +static PyObject *__pyx_memoryviewslice_convert_item_to_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp); /* proto*/ +static PyObject *__pyx_memoryviewslice_assign_item_from_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryviewslice__get_base(struct __pyx_memoryviewslice_obj *__pyx_v_self); /* proto*/ +static CYTHON_INLINE PyObject *__pyx_f_5numpy_7ndarray_4base_base(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE PyArray_Descr *__pyx_f_5numpy_7ndarray_5descr_descr(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE int __pyx_f_5numpy_7ndarray_4ndim_ndim(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_5shape_shape(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_7strides_strides(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE npy_intp __pyx_f_5numpy_7ndarray_4size_size(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE char *__pyx_f_5numpy_7ndarray_4data_data(PyArrayObject *__pyx_v_self); /* proto*/ + +/* Module declarations from "cython.view" */ +static struct __pyx_array_obj *__pyx_array_new(PyObject *, Py_ssize_t, char *, char *, char *); /*proto*/ + +/* Module declarations from "cython.dataclasses" */ + +/* Module declarations from "cython" */ + +/* Module declarations from "libc.string" */ + +/* Module declarations from "libcpp.string" */ + +/* Module declarations from "libcpp.vector" */ + +/* Module declarations from "libcpp" */ + +/* Module declarations from "libc.stdio" */ + +/* Module declarations from "__builtin__" */ + +/* Module declarations from "cpython.type" */ + +/* Module declarations from "cpython" */ + +/* Module declarations from "cpython.object" */ + +/* Module declarations from "cpython.ref" */ + +/* Module declarations from "numpy" */ + +/* Module declarations from "numpy" */ + +/* Module declarations from "rednose.helpers.ekf_sym_pyx" */ +static PyObject *__pyx_collections_abc_Sequence = 0; +static PyObject *generic = 0; +static PyObject *strided = 0; +static PyObject *indirect = 0; +static PyObject *contiguous = 0; +static PyObject *indirect_contiguous = 0; +static int __pyx_memoryview_thread_locks_used; +static PyThread_type_lock __pyx_memoryview_thread_locks[8]; +static PyArrayObject *__pyx_f_7rednose_7helpers_11ekf_sym_pyx_matrix_to_numpy(Eigen::Matrix); /*proto*/ +static PyArrayObject *__pyx_f_7rednose_7helpers_11ekf_sym_pyx_vector_to_numpy(Eigen::VectorXd); /*proto*/ +static std::string __pyx_convert_string_from_py_std__in_string(PyObject *); /*proto*/ +static std::vector __pyx_convert_vector_from_py_int(PyObject *); /*proto*/ +static std::vector __pyx_convert_vector_from_py_std_3a__3a_string(PyObject *); /*proto*/ +static int __pyx_array_allocate_buffer(struct __pyx_array_obj *); /*proto*/ +static struct __pyx_array_obj *__pyx_array_new(PyObject *, Py_ssize_t, char *, char *, char *); /*proto*/ +static PyObject *__pyx_memoryview_new(PyObject *, int, int, __Pyx_TypeInfo *); /*proto*/ +static CYTHON_INLINE int __pyx_memoryview_check(PyObject *); /*proto*/ +static PyObject *_unellipsify(PyObject *, int); /*proto*/ +static int assert_direct_dimensions(Py_ssize_t *, int); /*proto*/ +static struct __pyx_memoryview_obj *__pyx_memview_slice(struct __pyx_memoryview_obj *, PyObject *); /*proto*/ +static int __pyx_memoryview_slice_memviewslice(__Pyx_memviewslice *, Py_ssize_t, Py_ssize_t, Py_ssize_t, int, int, int *, Py_ssize_t, Py_ssize_t, Py_ssize_t, int, int, int, int); /*proto*/ +static char *__pyx_pybuffer_index(Py_buffer *, char *, Py_ssize_t, Py_ssize_t); /*proto*/ +static int __pyx_memslice_transpose(__Pyx_memviewslice *); /*proto*/ +static PyObject *__pyx_memoryview_fromslice(__Pyx_memviewslice, int, PyObject *(*)(char *), int (*)(char *, PyObject *), int); /*proto*/ +static __Pyx_memviewslice *__pyx_memoryview_get_slice_from_memoryview(struct __pyx_memoryview_obj *, __Pyx_memviewslice *); /*proto*/ +static void __pyx_memoryview_slice_copy(struct __pyx_memoryview_obj *, __Pyx_memviewslice *); /*proto*/ +static PyObject *__pyx_memoryview_copy_object(struct __pyx_memoryview_obj *); /*proto*/ +static PyObject *__pyx_memoryview_copy_object_from_slice(struct __pyx_memoryview_obj *, __Pyx_memviewslice *); /*proto*/ +static Py_ssize_t abs_py_ssize_t(Py_ssize_t); /*proto*/ +static char __pyx_get_best_slice_order(__Pyx_memviewslice *, int); /*proto*/ +static void _copy_strided_to_strided(char *, Py_ssize_t *, char *, Py_ssize_t *, Py_ssize_t *, Py_ssize_t *, int, size_t); /*proto*/ +static void copy_strided_to_strided(__Pyx_memviewslice *, __Pyx_memviewslice *, int, size_t); /*proto*/ +static Py_ssize_t __pyx_memoryview_slice_get_size(__Pyx_memviewslice *, int); /*proto*/ +static Py_ssize_t __pyx_fill_contig_strides_array(Py_ssize_t *, Py_ssize_t *, Py_ssize_t, int, char); /*proto*/ +static void *__pyx_memoryview_copy_data_to_temp(__Pyx_memviewslice *, __Pyx_memviewslice *, char, int); /*proto*/ +static int __pyx_memoryview_err_extents(int, Py_ssize_t, Py_ssize_t); /*proto*/ +static int __pyx_memoryview_err_dim(PyObject *, PyObject *, int); /*proto*/ +static int __pyx_memoryview_err(PyObject *, PyObject *); /*proto*/ +static int __pyx_memoryview_err_no_memory(void); /*proto*/ +static int __pyx_memoryview_copy_contents(__Pyx_memviewslice, __Pyx_memviewslice, int, int, int); /*proto*/ +static void __pyx_memoryview_broadcast_leading(__Pyx_memviewslice *, int, int); /*proto*/ +static void __pyx_memoryview_refcount_copying(__Pyx_memviewslice *, int, int, int); /*proto*/ +static void __pyx_memoryview_refcount_objects_in_slice_with_gil(char *, Py_ssize_t *, Py_ssize_t *, int, int); /*proto*/ +static void __pyx_memoryview_refcount_objects_in_slice(char *, Py_ssize_t *, Py_ssize_t *, int, int); /*proto*/ +static void __pyx_memoryview_slice_assign_scalar(__Pyx_memviewslice *, int, size_t, void *, int); /*proto*/ +static void __pyx_memoryview__slice_assign_scalar(char *, Py_ssize_t *, Py_ssize_t *, int, size_t, void *); /*proto*/ +static PyObject *__pyx_unpickle_Enum__set_state(struct __pyx_MemviewEnum_obj *, PyObject *); /*proto*/ +static PyObject *__pyx_format_from_typeinfo(__Pyx_TypeInfo *); /*proto*/ +/* #### Code section: typeinfo ### */ +static __Pyx_TypeInfo __Pyx_TypeInfo_double = { "double", NULL, sizeof(double), { 0 }, 0, 'R', 0, 0 }; +static __Pyx_TypeInfo __Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t = { "float64_t", NULL, sizeof(__pyx_t_5numpy_float64_t), { 0 }, 0, 'R', 0, 0 }; +/* #### Code section: before_global_var ### */ +#define __Pyx_MODULE_NAME "rednose.helpers.ekf_sym_pyx" +extern int __pyx_module_is_main_rednose__helpers__ekf_sym_pyx; +int __pyx_module_is_main_rednose__helpers__ekf_sym_pyx = 0; + +/* Implementation of "rednose.helpers.ekf_sym_pyx" */ +/* #### Code section: global_var ### */ +static PyObject *__pyx_builtin_NotImplementedError; +static PyObject *__pyx_builtin_TypeError; +static PyObject *__pyx_builtin___import__; +static PyObject *__pyx_builtin_ValueError; +static PyObject *__pyx_builtin_MemoryError; +static PyObject *__pyx_builtin_enumerate; +static PyObject *__pyx_builtin_range; +static PyObject *__pyx_builtin_AssertionError; +static PyObject *__pyx_builtin_Ellipsis; +static PyObject *__pyx_builtin_id; +static PyObject *__pyx_builtin_IndexError; +static PyObject *__pyx_builtin_ImportError; +/* #### Code section: string_decls ### */ +static const char __pyx_k_[] = ": "; +static const char __pyx_k_C[] = "C"; +static const char __pyx_k_N[] = "N"; +static const char __pyx_k_O[] = "O"; +static const char __pyx_k_P[] = "P"; +static const char __pyx_k_Q[] = "Q"; +static const char __pyx_k_R[] = "R"; +static const char __pyx_k_T[] = "T{"; + static const char __pyx_k_a[] = "a"; + static const char __pyx_k_c[] = "c"; + static const char __pyx_k_t[] = "t"; + static const char __pyx_k_x[] = "x"; + static const char __pyx_k_z[] = "z"; + static const char __pyx_k_Ri[] = "Ri"; + static const char __pyx_k__2[] = "."; + static const char __pyx_k__3[] = "*"; + static const char __pyx_k__6[] = "'"; + static const char __pyx_k__7[] = ")"; + static const char __pyx_k__9[] = "^"; + static const char __pyx_k_gc[] = "gc"; + static const char __pyx_k_id[] = "id"; + static const char __pyx_k_np[] = "np"; + static const char __pyx_k_zi[] = "zi"; + static const char __pyx_k__10[] = ""; + static const char __pyx_k__11[] = ":"; +static const char __pyx_k__12[] = "}"; +static const char __pyx_k__13[] = "("; +static const char __pyx_k__14[] = ","; +static const char __pyx_k__58[] = "?"; +static const char __pyx_k_abc[] = "abc"; +static const char __pyx_k_and[] = " and "; +static const char __pyx_k_got[] = " (got "; +static const char __pyx_k_nan[] = "nan"; +static const char __pyx_k_new[] = "__new__"; +static const char __pyx_k_obj[] = "obj"; +static const char __pyx_k_res[] = "res"; +static const char __pyx_k_sys[] = "sys"; +static const char __pyx_k_val[] = "val"; +static const char __pyx_k_Ri_b[] = "Ri_b"; +static const char __pyx_k_args[] = "args"; +static const char __pyx_k_base[] = "base"; +static const char __pyx_k_copy[] = "copy"; +static const char __pyx_k_covs[] = "covs"; +static const char __pyx_k_dict[] = "__dict__"; +static const char __pyx_k_join[] = "join"; +static const char __pyx_k_kind[] = "kind"; +static const char __pyx_k_main[] = "__main__"; +static const char __pyx_k_mode[] = "mode"; +static const char __pyx_k_name[] = "name"; +static const char __pyx_k_ndim[] = "ndim"; +static const char __pyx_k_pack[] = "pack"; +static const char __pyx_k_self[] = "self"; +static const char __pyx_k_size[] = "size"; +static const char __pyx_k_spec[] = "__spec__"; +static const char __pyx_k_step[] = "step"; +static const char __pyx_k_stop[] = "stop"; +static const char __pyx_k_test[] = "__test__"; +static const char __pyx_k_utf8[] = "utf8"; +static const char __pyx_k_zi_b[] = "zi_b"; +static const char __pyx_k_ASCII[] = "ASCII"; +static const char __pyx_k_R_map[] = "R_map"; +static const char __pyx_k_class[] = "__class__"; +static const char __pyx_k_count[] = "count"; +static const char __pyx_k_dtype[] = "dtype"; +static const char __pyx_k_error[] = "error"; +static const char __pyx_k_flags[] = "flags"; +static const char __pyx_k_index[] = "index"; +static const char __pyx_k_numpy[] = "numpy"; +static const char __pyx_k_order[] = "order"; +static const char __pyx_k_range[] = "range"; +static const char __pyx_k_shape[] = "shape"; +static const char __pyx_k_start[] = "start"; +static const char __pyx_k_state[] = "state"; +static const char __pyx_k_z_map[] = "z_map"; +static const char __pyx_k_covs_b[] = "covs_b"; +static const char __pyx_k_double[] = "double"; +static const char __pyx_k_enable[] = "enable"; +static const char __pyx_k_encode[] = "encode"; +static const char __pyx_k_format[] = "format"; +static const char __pyx_k_import[] = "__import__"; +static const char __pyx_k_logger[] = "logger"; +static const char __pyx_k_name_2[] = "__name__"; +static const char __pyx_k_pickle[] = "pickle"; +static const char __pyx_k_reduce[] = "__reduce__"; +static const char __pyx_k_struct[] = "struct"; +static const char __pyx_k_tmpvec[] = "tmpvec"; +static const char __pyx_k_unpack[] = "unpack"; +static const char __pyx_k_update[] = "update"; +static const char __pyx_k_asarray[] = "asarray"; +static const char __pyx_k_augment[] = "augment"; +static const char __pyx_k_disable[] = "disable"; +static const char __pyx_k_fortran[] = "fortran"; +static const char __pyx_k_gen_dir[] = "gen_dir"; +static const char __pyx_k_memview[] = "memview"; +static const char __pyx_k_predict[] = "predict"; +static const char __pyx_k_state_b[] = "state_b"; +static const char __pyx_k_Ellipsis[] = "Ellipsis"; +static const char __pyx_k_Sequence[] = "Sequence"; +static const char __pyx_k_args_map[] = "args_map"; +static const char __pyx_k_dim_main[] = "dim_main"; +static const char __pyx_k_getstate[] = "__getstate__"; +static const char __pyx_k_itemsize[] = "itemsize"; +static const char __pyx_k_pyx_type[] = "__pyx_type"; +static const char __pyx_k_register[] = "register"; +static const char __pyx_k_setstate[] = "__setstate__"; +static const char __pyx_k_P_initial[] = "P_initial"; +static const char __pyx_k_TypeError[] = "TypeError"; +static const char __pyx_k_enumerate[] = "enumerate"; +static const char __pyx_k_estimates[] = "estimates"; +static const char __pyx_k_isenabled[] = "isenabled"; +static const char __pyx_k_maha_test[] = "maha_test"; +static const char __pyx_k_pyx_state[] = "__pyx_state"; +static const char __pyx_k_reduce_ex[] = "__reduce_ex__"; +static const char __pyx_k_x_initial[] = "x_initial"; +static const char __pyx_k_IndexError[] = "IndexError"; +static const char __pyx_k_ValueError[] = "ValueError"; +static const char __pyx_k_extra_args[] = "extra_args"; +static const char __pyx_k_global_var[] = "global_var"; +static const char __pyx_k_init_state[] = "init_state"; +static const char __pyx_k_norm_quats[] = "norm_quats"; +static const char __pyx_k_pyx_result[] = "__pyx_result"; +static const char __pyx_k_pyx_vtable[] = "__pyx_vtable__"; +static const char __pyx_k_rts_smooth[] = "rts_smooth"; +static const char __pyx_k_set_global[] = "set_global"; +static const char __pyx_k_EKF_sym_pyx[] = "EKF_sym_pyx"; +static const char __pyx_k_ImportError[] = "ImportError"; +static const char __pyx_k_MemoryError[] = "MemoryError"; +static const char __pyx_k_PickleError[] = "PickleError"; +static const char __pyx_k_collections[] = "collections"; +static const char __pyx_k_dim_augment[] = "dim_augment"; +static const char __pyx_k_filter_time[] = "filter_time"; +static const char __pyx_k_global_vars[] = "global_vars"; +static const char __pyx_k_maha_thresh[] = "maha_thresh"; +static const char __pyx_k_dim_main_err[] = "dim_main_err"; +static const char __pyx_k_initializing[] = "_initializing"; +static const char __pyx_k_is_coroutine[] = "_is_coroutine"; +static const char __pyx_k_pyx_checksum[] = "__pyx_checksum"; +static const char __pyx_k_reset_rewind[] = "reset_rewind"; +static const char __pyx_k_stringsource[] = ""; +static const char __pyx_k_version_info[] = "version_info"; +static const char __pyx_k_class_getitem[] = "__class_getitem__"; +static const char __pyx_k_reduce_cython[] = "__reduce_cython__"; +static const char __pyx_k_AssertionError[] = "AssertionError"; +static const char __pyx_k_extra_args_map[] = "extra_args_map"; +static const char __pyx_k_max_rewind_age[] = "max_rewind_age"; +static const char __pyx_k_View_MemoryView[] = "View.MemoryView"; +static const char __pyx_k_allocate_buffer[] = "allocate_buffer"; +static const char __pyx_k_collections_abc[] = "collections.abc"; +static const char __pyx_k_dim_augment_err[] = "dim_augment_err"; +static const char __pyx_k_dtype_is_object[] = "dtype_is_object"; +static const char __pyx_k_get_filter_time[] = "get_filter_time"; +static const char __pyx_k_maha_test_kinds[] = "maha_test_kinds"; +static const char __pyx_k_pyx_PickleError[] = "__pyx_PickleError"; +static const char __pyx_k_quaternion_idxs[] = "quaternion_idxs"; +static const char __pyx_k_set_filter_time[] = "set_filter_time"; +static const char __pyx_k_setstate_cython[] = "__setstate_cython__"; +static const char __pyx_k_EKF_sym_pyx_covs[] = "EKF_sym_pyx.covs"; +static const char __pyx_k_EKF_sym_pyx_state[] = "EKF_sym_pyx.state"; +static const char __pyx_k_ascontiguousarray[] = "ascontiguousarray"; +static const char __pyx_k_get_augment_times[] = "get_augment_times"; +static const char __pyx_k_pyx_unpickle_Enum[] = "__pyx_unpickle_Enum"; +static const char __pyx_k_asyncio_coroutines[] = "asyncio.coroutines"; +static const char __pyx_k_cline_in_traceback[] = "cline_in_traceback"; +static const char __pyx_k_strided_and_direct[] = ""; +static const char __pyx_k_EKF_sym_pyx_augment[] = "EKF_sym_pyx.augment"; +static const char __pyx_k_EKF_sym_pyx_predict[] = "EKF_sym_pyx.predict"; +static const char __pyx_k_NotImplementedError[] = "NotImplementedError"; +static const char __pyx_k_strided_and_indirect[] = ""; +static const char __pyx_k_EKF_sym_pyx_maha_test[] = "EKF_sym_pyx.maha_test"; +static const char __pyx_k_Invalid_shape_in_axis[] = "Invalid shape in axis "; +static const char __pyx_k_contiguous_and_direct[] = ""; +static const char __pyx_k_Cannot_index_with_type[] = "Cannot index with type '"; +static const char __pyx_k_EKF_sym_pyx_init_state[] = "EKF_sym_pyx.init_state"; +static const char __pyx_k_EKF_sym_pyx_rts_smooth[] = "EKF_sym_pyx.rts_smooth"; +static const char __pyx_k_EKF_sym_pyx_set_global[] = "EKF_sym_pyx.set_global"; +static const char __pyx_k_MemoryView_of_r_object[] = ""; +static const char __pyx_k_MemoryView_of_r_at_0x_x[] = ""; +static const char __pyx_k_contiguous_and_indirect[] = ""; +static const char __pyx_k_EKF_sym_pyx_reset_rewind[] = "EKF_sym_pyx.reset_rewind"; +static const char __pyx_k_predict_and_update_batch[] = "predict_and_update_batch"; +static const char __pyx_k_Dimension_d_is_not_direct[] = "Dimension %d is not direct"; +static const char __pyx_k_Index_out_of_bounds_axis_d[] = "Index out of bounds (axis %d)"; +static const char __pyx_k_EKF_sym_pyx___reduce_cython[] = "EKF_sym_pyx.__reduce_cython__"; +static const char __pyx_k_EKF_sym_pyx_get_filter_time[] = "EKF_sym_pyx.get_filter_time"; +static const char __pyx_k_EKF_sym_pyx_set_filter_time[] = "EKF_sym_pyx.set_filter_time"; +static const char __pyx_k_Step_may_not_be_zero_axis_d[] = "Step may not be zero (axis %d)"; +static const char __pyx_k_itemsize_0_for_cython_array[] = "itemsize <= 0 for cython.array"; +static const char __pyx_k_rednose_helpers_ekf_sym_pyx[] = "rednose.helpers.ekf_sym_pyx"; +static const char __pyx_k_EKF_sym_pyx___setstate_cython[] = "EKF_sym_pyx.__setstate_cython__"; +static const char __pyx_k_EKF_sym_pyx_get_augment_times[] = "EKF_sym_pyx.get_augment_times"; +static const char __pyx_k_unable_to_allocate_array_data[] = "unable to allocate array data."; +static const char __pyx_k_strided_and_direct_or_indirect[] = ""; +static const char __pyx_k_numpy_core_multiarray_failed_to[] = "numpy.core.multiarray failed to import"; +static const char __pyx_k_rednose_helpers_ekf_sym_pyx_pyx[] = "rednose/helpers/ekf_sym_pyx.pyx"; +static const char __pyx_k_All_dimensions_preceding_dimensi[] = "All dimensions preceding dimension %d must be indexed and not sliced"; +static const char __pyx_k_Buffer_view_does_not_expose_stri[] = "Buffer view does not expose strides"; +static const char __pyx_k_Can_only_create_a_buffer_that_is[] = "Can only create a buffer that is contiguous in memory."; +static const char __pyx_k_Cannot_assign_to_read_only_memor[] = "Cannot assign to read-only memoryview"; +static const char __pyx_k_Cannot_create_writable_memory_vi[] = "Cannot create writable memory view from read-only memoryview"; +static const char __pyx_k_Cannot_transpose_memoryview_with[] = "Cannot transpose memoryview with indirect dimensions"; +static const char __pyx_k_EKF_sym_pyx_predict_and_update_b[] = "EKF_sym_pyx.predict_and_update_batch"; +static const char __pyx_k_Empty_shape_tuple_for_cython_arr[] = "Empty shape tuple for cython.array"; +static const char __pyx_k_Incompatible_checksums_0x_x_vs_0[] = "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))"; +static const char __pyx_k_Indirect_dimensions_not_supporte[] = "Indirect dimensions not supported"; +static const char __pyx_k_Invalid_mode_expected_c_or_fortr[] = "Invalid mode, expected 'c' or 'fortran', got "; +static const char __pyx_k_Out_of_bounds_on_buffer_access_a[] = "Out of bounds on buffer access (axis "; +static const char __pyx_k_Unable_to_convert_item_to_object[] = "Unable to convert item to object"; +static const char __pyx_k_got_differing_extents_in_dimensi[] = "got differing extents in dimension "; +static const char __pyx_k_no_default___reduce___due_to_non[] = "no default __reduce__ due to non-trivial __cinit__"; +static const char __pyx_k_numpy_core_umath_failed_to_impor[] = "numpy.core.umath failed to import"; +static const char __pyx_k_unable_to_allocate_shape_and_str[] = "unable to allocate shape and strides."; +/* #### Code section: decls ### */ +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array___cinit__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_shape, Py_ssize_t __pyx_v_itemsize, PyObject *__pyx_v_format, PyObject *__pyx_v_mode, int __pyx_v_allocate_buffer); /* proto */ +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_2__getbuffer__(struct __pyx_array_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /* proto */ +static void __pyx_array___pyx_pf_15View_dot_MemoryView_5array_4__dealloc__(struct __pyx_array_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_5array_7memview___get__(struct __pyx_array_obj *__pyx_v_self); /* proto */ +static Py_ssize_t __pyx_array___pyx_pf_15View_dot_MemoryView_5array_6__len__(struct __pyx_array_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_8__getattr__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_attr); /* proto */ +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_10__getitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item); /* proto */ +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_12__setitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value); /* proto */ +static PyObject *__pyx_pf___pyx_array___reduce_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_array_2__setstate_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum___init__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v_name); /* proto */ +static PyObject *__pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum_2__repr__(struct __pyx_MemviewEnum_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_MemviewEnum___reduce_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_MemviewEnum_2__setstate_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview___cinit__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj, int __pyx_v_flags, int __pyx_v_dtype_is_object); /* proto */ +static void __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_2__dealloc__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_4__getitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index); /* proto */ +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_6__setitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value); /* proto */ +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_8__getbuffer__(struct __pyx_memoryview_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_1T___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4base___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_5shape___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_7strides___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_10suboffsets___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4ndim___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_8itemsize___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_6nbytes___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4size___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static Py_ssize_t __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_10__len__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_12__repr__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_14__str__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_16is_c_contig(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_18is_f_contig(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_20copy(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_22copy_fortran(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryview___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryview_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static void __pyx_memoryviewslice___pyx_pf_15View_dot_MemoryView_16_memoryviewslice___dealloc__(struct __pyx_memoryviewslice_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryviewslice___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryviewslice_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView___pyx_unpickle_Enum(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v___pyx_type, long __pyx_v___pyx_checksum, PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx___cinit__(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, PyObject *__pyx_v_gen_dir, PyObject *__pyx_v_name, PyArrayObject *__pyx_v_Q, PyArrayObject *__pyx_v_x_initial, PyArrayObject *__pyx_v_P_initial, int __pyx_v_dim_main, int __pyx_v_dim_main_err, int __pyx_v_N, int __pyx_v_dim_augment, int __pyx_v_dim_augment_err, PyObject *__pyx_v_maha_test_kinds, PyObject *__pyx_v_quaternion_idxs, PyObject *__pyx_v_global_vars, double __pyx_v_max_rewind_age, CYTHON_UNUSED PyObject *__pyx_v_logger); /* proto */ +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_2init_state(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, PyArrayObject *__pyx_v_state, PyArrayObject *__pyx_v_covs, PyObject *__pyx_v_filter_time); /* proto */ +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_4state(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_6covs(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_8set_filter_time(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, double __pyx_v_t); /* proto */ +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_10get_filter_time(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_12set_global(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, PyObject *__pyx_v_global_var, double __pyx_v_val); /* proto */ +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_14reset_rewind(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_16predict(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, double __pyx_v_t); /* proto */ +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_18predict_and_update_batch(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, double __pyx_v_t, int __pyx_v_kind, PyObject *__pyx_v_z, PyObject *__pyx_v_R, PyObject *__pyx_v_extra_args, bool __pyx_v_augment); /* proto */ +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_20augment(CYTHON_UNUSED struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_22get_augment_times(CYTHON_UNUSED struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_24rts_smooth(CYTHON_UNUSED struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_estimates, CYTHON_UNUSED PyObject *__pyx_v_norm_quats); /* proto */ +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_26maha_test(CYTHON_UNUSED struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_x, CYTHON_UNUSED PyObject *__pyx_v_P, CYTHON_UNUSED PyObject *__pyx_v_kind, CYTHON_UNUSED PyObject *__pyx_v_z, CYTHON_UNUSED PyObject *__pyx_v_R, CYTHON_UNUSED PyObject *__pyx_v_extra_args, CYTHON_UNUSED PyObject *__pyx_v_maha_thresh); /* proto */ +static void __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_28__dealloc__(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_30__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_32__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_tp_new_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_array(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_Enum(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_memoryview(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new__memoryviewslice(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +/* #### Code section: late_includes ### */ +/* #### Code section: module_state ### */ +typedef struct { + PyObject *__pyx_d; + PyObject *__pyx_b; + PyObject *__pyx_cython_runtime; + PyObject *__pyx_empty_tuple; + PyObject *__pyx_empty_bytes; + PyObject *__pyx_empty_unicode; + #ifdef __Pyx_CyFunction_USED + PyTypeObject *__pyx_CyFunctionType; + #endif + #ifdef __Pyx_FusedFunction_USED + PyTypeObject *__pyx_FusedFunctionType; + #endif + #ifdef __Pyx_Generator_USED + PyTypeObject *__pyx_GeneratorType; + #endif + #ifdef __Pyx_IterableCoroutine_USED + PyTypeObject *__pyx_IterableCoroutineType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineAwaitType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineType; + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + PyTypeObject *__pyx_ptype_7cpython_4type_type; + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + PyTypeObject *__pyx_ptype_5numpy_dtype; + PyTypeObject *__pyx_ptype_5numpy_flatiter; + PyTypeObject *__pyx_ptype_5numpy_broadcast; + PyTypeObject *__pyx_ptype_5numpy_ndarray; + PyTypeObject *__pyx_ptype_5numpy_generic; + PyTypeObject *__pyx_ptype_5numpy_number; + PyTypeObject *__pyx_ptype_5numpy_integer; + PyTypeObject *__pyx_ptype_5numpy_signedinteger; + PyTypeObject *__pyx_ptype_5numpy_unsignedinteger; + PyTypeObject *__pyx_ptype_5numpy_inexact; + PyTypeObject *__pyx_ptype_5numpy_floating; + PyTypeObject *__pyx_ptype_5numpy_complexfloating; + PyTypeObject *__pyx_ptype_5numpy_flexible; + PyTypeObject *__pyx_ptype_5numpy_character; + PyTypeObject *__pyx_ptype_5numpy_ufunc; + #if CYTHON_USE_MODULE_STATE + PyObject *__pyx_type_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx; + PyObject *__pyx_type___pyx_array; + PyObject *__pyx_type___pyx_MemviewEnum; + PyObject *__pyx_type___pyx_memoryview; + PyObject *__pyx_type___pyx_memoryviewslice; + #endif + PyTypeObject *__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx; + PyTypeObject *__pyx_array_type; + PyTypeObject *__pyx_MemviewEnum_type; + PyTypeObject *__pyx_memoryview_type; + PyTypeObject *__pyx_memoryviewslice_type; + PyObject *__pyx_kp_u_; + PyObject *__pyx_n_s_ASCII; + PyObject *__pyx_kp_s_All_dimensions_preceding_dimensi; + PyObject *__pyx_n_s_AssertionError; + PyObject *__pyx_kp_s_Buffer_view_does_not_expose_stri; + PyObject *__pyx_n_u_C; + PyObject *__pyx_kp_s_Can_only_create_a_buffer_that_is; + PyObject *__pyx_kp_s_Cannot_assign_to_read_only_memor; + PyObject *__pyx_kp_s_Cannot_create_writable_memory_vi; + PyObject *__pyx_kp_u_Cannot_index_with_type; + PyObject *__pyx_kp_s_Cannot_transpose_memoryview_with; + PyObject *__pyx_kp_s_Dimension_d_is_not_direct; + PyObject *__pyx_n_s_EKF_sym_pyx; + PyObject *__pyx_n_s_EKF_sym_pyx___reduce_cython; + PyObject *__pyx_n_s_EKF_sym_pyx___setstate_cython; + PyObject *__pyx_n_s_EKF_sym_pyx_augment; + PyObject *__pyx_n_s_EKF_sym_pyx_covs; + PyObject *__pyx_n_s_EKF_sym_pyx_get_augment_times; + PyObject *__pyx_n_s_EKF_sym_pyx_get_filter_time; + PyObject *__pyx_n_s_EKF_sym_pyx_init_state; + PyObject *__pyx_n_s_EKF_sym_pyx_maha_test; + PyObject *__pyx_n_s_EKF_sym_pyx_predict; + PyObject *__pyx_n_s_EKF_sym_pyx_predict_and_update_b; + PyObject *__pyx_n_s_EKF_sym_pyx_reset_rewind; + PyObject *__pyx_n_s_EKF_sym_pyx_rts_smooth; + PyObject *__pyx_n_s_EKF_sym_pyx_set_filter_time; + PyObject *__pyx_n_s_EKF_sym_pyx_set_global; + PyObject *__pyx_n_s_EKF_sym_pyx_state; + PyObject *__pyx_n_s_Ellipsis; + PyObject *__pyx_kp_s_Empty_shape_tuple_for_cython_arr; + PyObject *__pyx_n_s_ImportError; + PyObject *__pyx_kp_s_Incompatible_checksums_0x_x_vs_0; + PyObject *__pyx_n_s_IndexError; + PyObject *__pyx_kp_s_Index_out_of_bounds_axis_d; + PyObject *__pyx_kp_s_Indirect_dimensions_not_supporte; + PyObject *__pyx_kp_u_Invalid_mode_expected_c_or_fortr; + PyObject *__pyx_kp_u_Invalid_shape_in_axis; + PyObject *__pyx_n_s_MemoryError; + PyObject *__pyx_kp_s_MemoryView_of_r_at_0x_x; + PyObject *__pyx_kp_s_MemoryView_of_r_object; + PyObject *__pyx_n_s_N; + PyObject *__pyx_n_s_NotImplementedError; + PyObject *__pyx_n_b_O; + PyObject *__pyx_kp_u_Out_of_bounds_on_buffer_access_a; + PyObject *__pyx_n_s_P; + PyObject *__pyx_n_s_P_initial; + PyObject *__pyx_n_s_PickleError; + PyObject *__pyx_n_s_Q; + PyObject *__pyx_n_s_R; + PyObject *__pyx_n_s_R_map; + PyObject *__pyx_n_s_Ri; + PyObject *__pyx_n_s_Ri_b; + PyObject *__pyx_n_s_Sequence; + PyObject *__pyx_kp_s_Step_may_not_be_zero_axis_d; + PyObject *__pyx_kp_b_T; + PyObject *__pyx_n_s_TypeError; + PyObject *__pyx_kp_s_Unable_to_convert_item_to_object; + PyObject *__pyx_n_s_ValueError; + PyObject *__pyx_n_s_View_MemoryView; + PyObject *__pyx_kp_b__10; + PyObject *__pyx_kp_b__11; + PyObject *__pyx_kp_b__12; + PyObject *__pyx_kp_u__13; + PyObject *__pyx_kp_u__14; + PyObject *__pyx_kp_u__2; + PyObject *__pyx_n_s__3; + PyObject *__pyx_n_s__58; + PyObject *__pyx_kp_u__6; + PyObject *__pyx_kp_u__7; + PyObject *__pyx_kp_b__9; + PyObject *__pyx_n_s_a; + PyObject *__pyx_n_s_abc; + PyObject *__pyx_n_s_allocate_buffer; + PyObject *__pyx_kp_u_and; + PyObject *__pyx_n_s_args; + PyObject *__pyx_n_s_args_map; + PyObject *__pyx_n_s_asarray; + PyObject *__pyx_n_s_ascontiguousarray; + PyObject *__pyx_n_s_asyncio_coroutines; + PyObject *__pyx_n_s_augment; + PyObject *__pyx_n_s_base; + PyObject *__pyx_n_s_c; + PyObject *__pyx_n_u_c; + PyObject *__pyx_n_s_class; + PyObject *__pyx_n_s_class_getitem; + PyObject *__pyx_n_s_cline_in_traceback; + PyObject *__pyx_n_s_collections; + PyObject *__pyx_kp_s_collections_abc; + PyObject *__pyx_kp_s_contiguous_and_direct; + PyObject *__pyx_kp_s_contiguous_and_indirect; + PyObject *__pyx_n_s_copy; + PyObject *__pyx_n_s_count; + PyObject *__pyx_n_s_covs; + PyObject *__pyx_n_s_covs_b; + PyObject *__pyx_n_s_dict; + PyObject *__pyx_n_s_dim_augment; + PyObject *__pyx_n_s_dim_augment_err; + PyObject *__pyx_n_s_dim_main; + PyObject *__pyx_n_s_dim_main_err; + PyObject *__pyx_kp_u_disable; + PyObject *__pyx_n_s_double; + PyObject *__pyx_n_s_dtype; + PyObject *__pyx_n_s_dtype_is_object; + PyObject *__pyx_kp_u_enable; + PyObject *__pyx_n_s_encode; + PyObject *__pyx_n_s_enumerate; + PyObject *__pyx_n_s_error; + PyObject *__pyx_n_s_estimates; + PyObject *__pyx_n_s_extra_args; + PyObject *__pyx_n_s_extra_args_map; + PyObject *__pyx_n_s_filter_time; + PyObject *__pyx_n_s_flags; + PyObject *__pyx_n_s_format; + PyObject *__pyx_n_s_fortran; + PyObject *__pyx_n_u_fortran; + PyObject *__pyx_kp_u_gc; + PyObject *__pyx_n_s_gen_dir; + PyObject *__pyx_n_s_get_augment_times; + PyObject *__pyx_n_s_get_filter_time; + PyObject *__pyx_n_s_getstate; + PyObject *__pyx_n_s_global_var; + PyObject *__pyx_n_s_global_vars; + PyObject *__pyx_kp_u_got; + PyObject *__pyx_kp_u_got_differing_extents_in_dimensi; + PyObject *__pyx_n_s_id; + PyObject *__pyx_n_s_import; + PyObject *__pyx_n_s_index; + PyObject *__pyx_n_s_init_state; + PyObject *__pyx_n_s_initializing; + PyObject *__pyx_n_s_is_coroutine; + PyObject *__pyx_kp_u_isenabled; + PyObject *__pyx_n_s_itemsize; + PyObject *__pyx_kp_s_itemsize_0_for_cython_array; + PyObject *__pyx_n_s_join; + PyObject *__pyx_n_s_kind; + PyObject *__pyx_n_s_logger; + PyObject *__pyx_n_s_maha_test; + PyObject *__pyx_n_s_maha_test_kinds; + PyObject *__pyx_n_s_maha_thresh; + PyObject *__pyx_n_s_main; + PyObject *__pyx_n_s_max_rewind_age; + PyObject *__pyx_n_s_memview; + PyObject *__pyx_n_s_mode; + PyObject *__pyx_n_s_name; + PyObject *__pyx_n_s_name_2; + PyObject *__pyx_n_s_nan; + PyObject *__pyx_n_s_ndim; + PyObject *__pyx_n_s_new; + PyObject *__pyx_kp_s_no_default___reduce___due_to_non; + PyObject *__pyx_n_s_norm_quats; + PyObject *__pyx_n_s_np; + PyObject *__pyx_n_s_numpy; + PyObject *__pyx_kp_u_numpy_core_multiarray_failed_to; + PyObject *__pyx_kp_u_numpy_core_umath_failed_to_impor; + PyObject *__pyx_n_s_obj; + PyObject *__pyx_n_s_order; + PyObject *__pyx_n_s_pack; + PyObject *__pyx_n_s_pickle; + PyObject *__pyx_n_s_predict; + PyObject *__pyx_n_s_predict_and_update_batch; + PyObject *__pyx_n_s_pyx_PickleError; + PyObject *__pyx_n_s_pyx_checksum; + PyObject *__pyx_n_s_pyx_result; + PyObject *__pyx_n_s_pyx_state; + PyObject *__pyx_n_s_pyx_type; + PyObject *__pyx_n_s_pyx_unpickle_Enum; + PyObject *__pyx_n_s_pyx_vtable; + PyObject *__pyx_n_s_quaternion_idxs; + PyObject *__pyx_n_s_range; + PyObject *__pyx_n_s_rednose_helpers_ekf_sym_pyx; + PyObject *__pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx; + PyObject *__pyx_n_s_reduce; + PyObject *__pyx_n_s_reduce_cython; + PyObject *__pyx_n_s_reduce_ex; + PyObject *__pyx_n_s_register; + PyObject *__pyx_n_s_res; + PyObject *__pyx_n_s_reset_rewind; + PyObject *__pyx_n_s_rts_smooth; + PyObject *__pyx_n_s_self; + PyObject *__pyx_n_s_set_filter_time; + PyObject *__pyx_n_s_set_global; + PyObject *__pyx_n_s_setstate; + PyObject *__pyx_n_s_setstate_cython; + PyObject *__pyx_n_s_shape; + PyObject *__pyx_n_s_size; + PyObject *__pyx_n_s_spec; + PyObject *__pyx_n_s_start; + PyObject *__pyx_n_s_state; + PyObject *__pyx_n_s_state_b; + PyObject *__pyx_n_s_step; + PyObject *__pyx_n_s_stop; + PyObject *__pyx_kp_s_strided_and_direct; + PyObject *__pyx_kp_s_strided_and_direct_or_indirect; + PyObject *__pyx_kp_s_strided_and_indirect; + PyObject *__pyx_kp_s_stringsource; + PyObject *__pyx_n_s_struct; + PyObject *__pyx_n_s_sys; + PyObject *__pyx_n_s_t; + PyObject *__pyx_n_s_test; + PyObject *__pyx_n_s_tmpvec; + PyObject *__pyx_kp_s_unable_to_allocate_array_data; + PyObject *__pyx_kp_s_unable_to_allocate_shape_and_str; + PyObject *__pyx_n_s_unpack; + PyObject *__pyx_n_s_update; + PyObject *__pyx_n_u_utf8; + PyObject *__pyx_n_s_val; + PyObject *__pyx_n_s_version_info; + PyObject *__pyx_n_s_x; + PyObject *__pyx_n_s_x_initial; + PyObject *__pyx_n_s_z; + PyObject *__pyx_n_s_z_map; + PyObject *__pyx_n_s_zi; + PyObject *__pyx_n_s_zi_b; + PyObject *__pyx_float_0_95; + PyObject *__pyx_int_0; + PyObject *__pyx_int_1; + PyObject *__pyx_int_3; + PyObject *__pyx_int_112105877; + PyObject *__pyx_int_136983863; + PyObject *__pyx_int_184977713; + PyObject *__pyx_int_neg_1; + PyObject *__pyx_k__17; + PyObject *__pyx_k__18; + PyObject *__pyx_k__19; + PyObject *__pyx_k__28; + PyObject *__pyx_k__33; + PyObject *__pyx_slice__5; + PyObject *__pyx_tuple__4; + PyObject *__pyx_tuple__8; + PyObject *__pyx_tuple__15; + PyObject *__pyx_tuple__16; + PyObject *__pyx_tuple__37; + PyObject *__pyx_tuple__38; + PyObject *__pyx_tuple__39; + PyObject *__pyx_tuple__40; + PyObject *__pyx_tuple__41; + PyObject *__pyx_tuple__42; + PyObject *__pyx_tuple__43; + PyObject *__pyx_tuple__44; + PyObject *__pyx_tuple__45; + PyObject *__pyx_tuple__46; + PyObject *__pyx_tuple__48; + PyObject *__pyx_tuple__49; + PyObject *__pyx_tuple__50; + PyObject *__pyx_tuple__51; + PyObject *__pyx_tuple__52; + PyObject *__pyx_tuple__53; + PyObject *__pyx_tuple__54; + PyObject *__pyx_tuple__55; + PyObject *__pyx_tuple__56; + PyObject *__pyx_tuple__57; + PyObject *__pyx_codeobj__20; + PyObject *__pyx_codeobj__21; + PyObject *__pyx_codeobj__22; + PyObject *__pyx_codeobj__23; + PyObject *__pyx_codeobj__24; + PyObject *__pyx_codeobj__25; + PyObject *__pyx_codeobj__26; + PyObject *__pyx_codeobj__27; + PyObject *__pyx_codeobj__29; + PyObject *__pyx_codeobj__30; + PyObject *__pyx_codeobj__31; + PyObject *__pyx_codeobj__32; + PyObject *__pyx_codeobj__34; + PyObject *__pyx_codeobj__35; + PyObject *__pyx_codeobj__36; + PyObject *__pyx_codeobj__47; +} __pyx_mstate; + +#if CYTHON_USE_MODULE_STATE +#ifdef __cplusplus +namespace { + extern struct PyModuleDef __pyx_moduledef; +} /* anonymous namespace */ +#else +static struct PyModuleDef __pyx_moduledef; +#endif + +#define __pyx_mstate(o) ((__pyx_mstate *)__Pyx_PyModule_GetState(o)) + +#define __pyx_mstate_global (__pyx_mstate(PyState_FindModule(&__pyx_moduledef))) + +#define __pyx_m (PyState_FindModule(&__pyx_moduledef)) +#else +static __pyx_mstate __pyx_mstate_global_static = +#ifdef __cplusplus + {}; +#else + {0}; +#endif +static __pyx_mstate *__pyx_mstate_global = &__pyx_mstate_global_static; +#endif +/* #### Code section: module_state_clear ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_clear(PyObject *m) { + __pyx_mstate *clear_module_state = __pyx_mstate(m); + if (!clear_module_state) return 0; + Py_CLEAR(clear_module_state->__pyx_d); + Py_CLEAR(clear_module_state->__pyx_b); + Py_CLEAR(clear_module_state->__pyx_cython_runtime); + Py_CLEAR(clear_module_state->__pyx_empty_tuple); + Py_CLEAR(clear_module_state->__pyx_empty_bytes); + Py_CLEAR(clear_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_CLEAR(clear_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_CLEAR(clear_module_state->__pyx_FusedFunctionType); + #endif + Py_CLEAR(clear_module_state->__pyx_ptype_7cpython_4type_type); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_dtype); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_flatiter); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_broadcast); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_ndarray); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_generic); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_number); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_integer); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_signedinteger); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_unsignedinteger); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_inexact); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_floating); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_complexfloating); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_flexible); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_character); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_ufunc); + Py_CLEAR(clear_module_state->__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); + Py_CLEAR(clear_module_state->__pyx_type_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); + Py_CLEAR(clear_module_state->__pyx_array_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_array); + Py_CLEAR(clear_module_state->__pyx_MemviewEnum_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_MemviewEnum); + Py_CLEAR(clear_module_state->__pyx_memoryview_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_memoryview); + Py_CLEAR(clear_module_state->__pyx_memoryviewslice_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_memoryviewslice); + Py_CLEAR(clear_module_state->__pyx_kp_u_); + Py_CLEAR(clear_module_state->__pyx_n_s_ASCII); + Py_CLEAR(clear_module_state->__pyx_kp_s_All_dimensions_preceding_dimensi); + Py_CLEAR(clear_module_state->__pyx_n_s_AssertionError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Buffer_view_does_not_expose_stri); + Py_CLEAR(clear_module_state->__pyx_n_u_C); + Py_CLEAR(clear_module_state->__pyx_kp_s_Can_only_create_a_buffer_that_is); + Py_CLEAR(clear_module_state->__pyx_kp_s_Cannot_assign_to_read_only_memor); + Py_CLEAR(clear_module_state->__pyx_kp_s_Cannot_create_writable_memory_vi); + Py_CLEAR(clear_module_state->__pyx_kp_u_Cannot_index_with_type); + Py_CLEAR(clear_module_state->__pyx_kp_s_Cannot_transpose_memoryview_with); + Py_CLEAR(clear_module_state->__pyx_kp_s_Dimension_d_is_not_direct); + Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx); + Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx___reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx___setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx_augment); + Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx_covs); + Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx_get_augment_times); + Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx_get_filter_time); + Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx_init_state); + Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx_maha_test); + Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx_predict); + Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx_predict_and_update_b); + Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx_reset_rewind); + Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx_rts_smooth); + Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx_set_filter_time); + Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx_set_global); + Py_CLEAR(clear_module_state->__pyx_n_s_EKF_sym_pyx_state); + Py_CLEAR(clear_module_state->__pyx_n_s_Ellipsis); + Py_CLEAR(clear_module_state->__pyx_kp_s_Empty_shape_tuple_for_cython_arr); + Py_CLEAR(clear_module_state->__pyx_n_s_ImportError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0); + Py_CLEAR(clear_module_state->__pyx_n_s_IndexError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Index_out_of_bounds_axis_d); + Py_CLEAR(clear_module_state->__pyx_kp_s_Indirect_dimensions_not_supporte); + Py_CLEAR(clear_module_state->__pyx_kp_u_Invalid_mode_expected_c_or_fortr); + Py_CLEAR(clear_module_state->__pyx_kp_u_Invalid_shape_in_axis); + Py_CLEAR(clear_module_state->__pyx_n_s_MemoryError); + Py_CLEAR(clear_module_state->__pyx_kp_s_MemoryView_of_r_at_0x_x); + Py_CLEAR(clear_module_state->__pyx_kp_s_MemoryView_of_r_object); + Py_CLEAR(clear_module_state->__pyx_n_s_N); + Py_CLEAR(clear_module_state->__pyx_n_s_NotImplementedError); + Py_CLEAR(clear_module_state->__pyx_n_b_O); + Py_CLEAR(clear_module_state->__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + Py_CLEAR(clear_module_state->__pyx_n_s_P); + Py_CLEAR(clear_module_state->__pyx_n_s_P_initial); + Py_CLEAR(clear_module_state->__pyx_n_s_PickleError); + Py_CLEAR(clear_module_state->__pyx_n_s_Q); + Py_CLEAR(clear_module_state->__pyx_n_s_R); + Py_CLEAR(clear_module_state->__pyx_n_s_R_map); + Py_CLEAR(clear_module_state->__pyx_n_s_Ri); + Py_CLEAR(clear_module_state->__pyx_n_s_Ri_b); + Py_CLEAR(clear_module_state->__pyx_n_s_Sequence); + Py_CLEAR(clear_module_state->__pyx_kp_s_Step_may_not_be_zero_axis_d); + Py_CLEAR(clear_module_state->__pyx_kp_b_T); + Py_CLEAR(clear_module_state->__pyx_n_s_TypeError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Unable_to_convert_item_to_object); + Py_CLEAR(clear_module_state->__pyx_n_s_ValueError); + Py_CLEAR(clear_module_state->__pyx_n_s_View_MemoryView); + Py_CLEAR(clear_module_state->__pyx_kp_b__10); + Py_CLEAR(clear_module_state->__pyx_kp_b__11); + Py_CLEAR(clear_module_state->__pyx_kp_b__12); + Py_CLEAR(clear_module_state->__pyx_kp_u__13); + Py_CLEAR(clear_module_state->__pyx_kp_u__14); + Py_CLEAR(clear_module_state->__pyx_kp_u__2); + Py_CLEAR(clear_module_state->__pyx_n_s__3); + Py_CLEAR(clear_module_state->__pyx_n_s__58); + Py_CLEAR(clear_module_state->__pyx_kp_u__6); + Py_CLEAR(clear_module_state->__pyx_kp_u__7); + Py_CLEAR(clear_module_state->__pyx_kp_b__9); + Py_CLEAR(clear_module_state->__pyx_n_s_a); + Py_CLEAR(clear_module_state->__pyx_n_s_abc); + Py_CLEAR(clear_module_state->__pyx_n_s_allocate_buffer); + Py_CLEAR(clear_module_state->__pyx_kp_u_and); + Py_CLEAR(clear_module_state->__pyx_n_s_args); + Py_CLEAR(clear_module_state->__pyx_n_s_args_map); + Py_CLEAR(clear_module_state->__pyx_n_s_asarray); + Py_CLEAR(clear_module_state->__pyx_n_s_ascontiguousarray); + Py_CLEAR(clear_module_state->__pyx_n_s_asyncio_coroutines); + Py_CLEAR(clear_module_state->__pyx_n_s_augment); + Py_CLEAR(clear_module_state->__pyx_n_s_base); + Py_CLEAR(clear_module_state->__pyx_n_s_c); + Py_CLEAR(clear_module_state->__pyx_n_u_c); + Py_CLEAR(clear_module_state->__pyx_n_s_class); + Py_CLEAR(clear_module_state->__pyx_n_s_class_getitem); + Py_CLEAR(clear_module_state->__pyx_n_s_cline_in_traceback); + Py_CLEAR(clear_module_state->__pyx_n_s_collections); + Py_CLEAR(clear_module_state->__pyx_kp_s_collections_abc); + Py_CLEAR(clear_module_state->__pyx_kp_s_contiguous_and_direct); + Py_CLEAR(clear_module_state->__pyx_kp_s_contiguous_and_indirect); + Py_CLEAR(clear_module_state->__pyx_n_s_copy); + Py_CLEAR(clear_module_state->__pyx_n_s_count); + Py_CLEAR(clear_module_state->__pyx_n_s_covs); + Py_CLEAR(clear_module_state->__pyx_n_s_covs_b); + Py_CLEAR(clear_module_state->__pyx_n_s_dict); + Py_CLEAR(clear_module_state->__pyx_n_s_dim_augment); + Py_CLEAR(clear_module_state->__pyx_n_s_dim_augment_err); + Py_CLEAR(clear_module_state->__pyx_n_s_dim_main); + Py_CLEAR(clear_module_state->__pyx_n_s_dim_main_err); + Py_CLEAR(clear_module_state->__pyx_kp_u_disable); + Py_CLEAR(clear_module_state->__pyx_n_s_double); + Py_CLEAR(clear_module_state->__pyx_n_s_dtype); + Py_CLEAR(clear_module_state->__pyx_n_s_dtype_is_object); + Py_CLEAR(clear_module_state->__pyx_kp_u_enable); + Py_CLEAR(clear_module_state->__pyx_n_s_encode); + Py_CLEAR(clear_module_state->__pyx_n_s_enumerate); + Py_CLEAR(clear_module_state->__pyx_n_s_error); + Py_CLEAR(clear_module_state->__pyx_n_s_estimates); + Py_CLEAR(clear_module_state->__pyx_n_s_extra_args); + Py_CLEAR(clear_module_state->__pyx_n_s_extra_args_map); + Py_CLEAR(clear_module_state->__pyx_n_s_filter_time); + Py_CLEAR(clear_module_state->__pyx_n_s_flags); + Py_CLEAR(clear_module_state->__pyx_n_s_format); + Py_CLEAR(clear_module_state->__pyx_n_s_fortran); + Py_CLEAR(clear_module_state->__pyx_n_u_fortran); + Py_CLEAR(clear_module_state->__pyx_kp_u_gc); + Py_CLEAR(clear_module_state->__pyx_n_s_gen_dir); + Py_CLEAR(clear_module_state->__pyx_n_s_get_augment_times); + Py_CLEAR(clear_module_state->__pyx_n_s_get_filter_time); + Py_CLEAR(clear_module_state->__pyx_n_s_getstate); + Py_CLEAR(clear_module_state->__pyx_n_s_global_var); + Py_CLEAR(clear_module_state->__pyx_n_s_global_vars); + Py_CLEAR(clear_module_state->__pyx_kp_u_got); + Py_CLEAR(clear_module_state->__pyx_kp_u_got_differing_extents_in_dimensi); + Py_CLEAR(clear_module_state->__pyx_n_s_id); + Py_CLEAR(clear_module_state->__pyx_n_s_import); + Py_CLEAR(clear_module_state->__pyx_n_s_index); + Py_CLEAR(clear_module_state->__pyx_n_s_init_state); + Py_CLEAR(clear_module_state->__pyx_n_s_initializing); + Py_CLEAR(clear_module_state->__pyx_n_s_is_coroutine); + Py_CLEAR(clear_module_state->__pyx_kp_u_isenabled); + Py_CLEAR(clear_module_state->__pyx_n_s_itemsize); + Py_CLEAR(clear_module_state->__pyx_kp_s_itemsize_0_for_cython_array); + Py_CLEAR(clear_module_state->__pyx_n_s_join); + Py_CLEAR(clear_module_state->__pyx_n_s_kind); + Py_CLEAR(clear_module_state->__pyx_n_s_logger); + Py_CLEAR(clear_module_state->__pyx_n_s_maha_test); + Py_CLEAR(clear_module_state->__pyx_n_s_maha_test_kinds); + Py_CLEAR(clear_module_state->__pyx_n_s_maha_thresh); + Py_CLEAR(clear_module_state->__pyx_n_s_main); + Py_CLEAR(clear_module_state->__pyx_n_s_max_rewind_age); + Py_CLEAR(clear_module_state->__pyx_n_s_memview); + Py_CLEAR(clear_module_state->__pyx_n_s_mode); + Py_CLEAR(clear_module_state->__pyx_n_s_name); + Py_CLEAR(clear_module_state->__pyx_n_s_name_2); + Py_CLEAR(clear_module_state->__pyx_n_s_nan); + Py_CLEAR(clear_module_state->__pyx_n_s_ndim); + Py_CLEAR(clear_module_state->__pyx_n_s_new); + Py_CLEAR(clear_module_state->__pyx_kp_s_no_default___reduce___due_to_non); + Py_CLEAR(clear_module_state->__pyx_n_s_norm_quats); + Py_CLEAR(clear_module_state->__pyx_n_s_np); + Py_CLEAR(clear_module_state->__pyx_n_s_numpy); + Py_CLEAR(clear_module_state->__pyx_kp_u_numpy_core_multiarray_failed_to); + Py_CLEAR(clear_module_state->__pyx_kp_u_numpy_core_umath_failed_to_impor); + Py_CLEAR(clear_module_state->__pyx_n_s_obj); + Py_CLEAR(clear_module_state->__pyx_n_s_order); + Py_CLEAR(clear_module_state->__pyx_n_s_pack); + Py_CLEAR(clear_module_state->__pyx_n_s_pickle); + Py_CLEAR(clear_module_state->__pyx_n_s_predict); + Py_CLEAR(clear_module_state->__pyx_n_s_predict_and_update_batch); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_PickleError); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_checksum); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_result); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_state); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_type); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_unpickle_Enum); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_vtable); + Py_CLEAR(clear_module_state->__pyx_n_s_quaternion_idxs); + Py_CLEAR(clear_module_state->__pyx_n_s_range); + Py_CLEAR(clear_module_state->__pyx_n_s_rednose_helpers_ekf_sym_pyx); + Py_CLEAR(clear_module_state->__pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_ex); + Py_CLEAR(clear_module_state->__pyx_n_s_register); + Py_CLEAR(clear_module_state->__pyx_n_s_res); + Py_CLEAR(clear_module_state->__pyx_n_s_reset_rewind); + Py_CLEAR(clear_module_state->__pyx_n_s_rts_smooth); + Py_CLEAR(clear_module_state->__pyx_n_s_self); + Py_CLEAR(clear_module_state->__pyx_n_s_set_filter_time); + Py_CLEAR(clear_module_state->__pyx_n_s_set_global); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_shape); + Py_CLEAR(clear_module_state->__pyx_n_s_size); + Py_CLEAR(clear_module_state->__pyx_n_s_spec); + Py_CLEAR(clear_module_state->__pyx_n_s_start); + Py_CLEAR(clear_module_state->__pyx_n_s_state); + Py_CLEAR(clear_module_state->__pyx_n_s_state_b); + Py_CLEAR(clear_module_state->__pyx_n_s_step); + Py_CLEAR(clear_module_state->__pyx_n_s_stop); + Py_CLEAR(clear_module_state->__pyx_kp_s_strided_and_direct); + Py_CLEAR(clear_module_state->__pyx_kp_s_strided_and_direct_or_indirect); + Py_CLEAR(clear_module_state->__pyx_kp_s_strided_and_indirect); + Py_CLEAR(clear_module_state->__pyx_kp_s_stringsource); + Py_CLEAR(clear_module_state->__pyx_n_s_struct); + Py_CLEAR(clear_module_state->__pyx_n_s_sys); + Py_CLEAR(clear_module_state->__pyx_n_s_t); + Py_CLEAR(clear_module_state->__pyx_n_s_test); + Py_CLEAR(clear_module_state->__pyx_n_s_tmpvec); + Py_CLEAR(clear_module_state->__pyx_kp_s_unable_to_allocate_array_data); + Py_CLEAR(clear_module_state->__pyx_kp_s_unable_to_allocate_shape_and_str); + Py_CLEAR(clear_module_state->__pyx_n_s_unpack); + Py_CLEAR(clear_module_state->__pyx_n_s_update); + Py_CLEAR(clear_module_state->__pyx_n_u_utf8); + Py_CLEAR(clear_module_state->__pyx_n_s_val); + Py_CLEAR(clear_module_state->__pyx_n_s_version_info); + Py_CLEAR(clear_module_state->__pyx_n_s_x); + Py_CLEAR(clear_module_state->__pyx_n_s_x_initial); + Py_CLEAR(clear_module_state->__pyx_n_s_z); + Py_CLEAR(clear_module_state->__pyx_n_s_z_map); + Py_CLEAR(clear_module_state->__pyx_n_s_zi); + Py_CLEAR(clear_module_state->__pyx_n_s_zi_b); + Py_CLEAR(clear_module_state->__pyx_float_0_95); + Py_CLEAR(clear_module_state->__pyx_int_0); + Py_CLEAR(clear_module_state->__pyx_int_1); + Py_CLEAR(clear_module_state->__pyx_int_3); + Py_CLEAR(clear_module_state->__pyx_int_112105877); + Py_CLEAR(clear_module_state->__pyx_int_136983863); + Py_CLEAR(clear_module_state->__pyx_int_184977713); + Py_CLEAR(clear_module_state->__pyx_int_neg_1); + Py_CLEAR(clear_module_state->__pyx_k__17); + Py_CLEAR(clear_module_state->__pyx_k__18); + Py_CLEAR(clear_module_state->__pyx_k__19); + Py_CLEAR(clear_module_state->__pyx_k__28); + Py_CLEAR(clear_module_state->__pyx_k__33); + Py_CLEAR(clear_module_state->__pyx_slice__5); + Py_CLEAR(clear_module_state->__pyx_tuple__4); + Py_CLEAR(clear_module_state->__pyx_tuple__8); + Py_CLEAR(clear_module_state->__pyx_tuple__15); + Py_CLEAR(clear_module_state->__pyx_tuple__16); + Py_CLEAR(clear_module_state->__pyx_tuple__37); + Py_CLEAR(clear_module_state->__pyx_tuple__38); + Py_CLEAR(clear_module_state->__pyx_tuple__39); + Py_CLEAR(clear_module_state->__pyx_tuple__40); + Py_CLEAR(clear_module_state->__pyx_tuple__41); + Py_CLEAR(clear_module_state->__pyx_tuple__42); + Py_CLEAR(clear_module_state->__pyx_tuple__43); + Py_CLEAR(clear_module_state->__pyx_tuple__44); + Py_CLEAR(clear_module_state->__pyx_tuple__45); + Py_CLEAR(clear_module_state->__pyx_tuple__46); + Py_CLEAR(clear_module_state->__pyx_tuple__48); + Py_CLEAR(clear_module_state->__pyx_tuple__49); + Py_CLEAR(clear_module_state->__pyx_tuple__50); + Py_CLEAR(clear_module_state->__pyx_tuple__51); + Py_CLEAR(clear_module_state->__pyx_tuple__52); + Py_CLEAR(clear_module_state->__pyx_tuple__53); + Py_CLEAR(clear_module_state->__pyx_tuple__54); + Py_CLEAR(clear_module_state->__pyx_tuple__55); + Py_CLEAR(clear_module_state->__pyx_tuple__56); + Py_CLEAR(clear_module_state->__pyx_tuple__57); + Py_CLEAR(clear_module_state->__pyx_codeobj__20); + Py_CLEAR(clear_module_state->__pyx_codeobj__21); + Py_CLEAR(clear_module_state->__pyx_codeobj__22); + Py_CLEAR(clear_module_state->__pyx_codeobj__23); + Py_CLEAR(clear_module_state->__pyx_codeobj__24); + Py_CLEAR(clear_module_state->__pyx_codeobj__25); + Py_CLEAR(clear_module_state->__pyx_codeobj__26); + Py_CLEAR(clear_module_state->__pyx_codeobj__27); + Py_CLEAR(clear_module_state->__pyx_codeobj__29); + Py_CLEAR(clear_module_state->__pyx_codeobj__30); + Py_CLEAR(clear_module_state->__pyx_codeobj__31); + Py_CLEAR(clear_module_state->__pyx_codeobj__32); + Py_CLEAR(clear_module_state->__pyx_codeobj__34); + Py_CLEAR(clear_module_state->__pyx_codeobj__35); + Py_CLEAR(clear_module_state->__pyx_codeobj__36); + Py_CLEAR(clear_module_state->__pyx_codeobj__47); + return 0; +} +#endif +/* #### Code section: module_state_traverse ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { + __pyx_mstate *traverse_module_state = __pyx_mstate(m); + if (!traverse_module_state) return 0; + Py_VISIT(traverse_module_state->__pyx_d); + Py_VISIT(traverse_module_state->__pyx_b); + Py_VISIT(traverse_module_state->__pyx_cython_runtime); + Py_VISIT(traverse_module_state->__pyx_empty_tuple); + Py_VISIT(traverse_module_state->__pyx_empty_bytes); + Py_VISIT(traverse_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_VISIT(traverse_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_VISIT(traverse_module_state->__pyx_FusedFunctionType); + #endif + Py_VISIT(traverse_module_state->__pyx_ptype_7cpython_4type_type); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_dtype); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_flatiter); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_broadcast); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_ndarray); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_generic); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_number); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_integer); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_signedinteger); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_unsignedinteger); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_inexact); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_floating); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_complexfloating); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_flexible); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_character); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_ufunc); + Py_VISIT(traverse_module_state->__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); + Py_VISIT(traverse_module_state->__pyx_type_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); + Py_VISIT(traverse_module_state->__pyx_array_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_array); + Py_VISIT(traverse_module_state->__pyx_MemviewEnum_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_MemviewEnum); + Py_VISIT(traverse_module_state->__pyx_memoryview_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_memoryview); + Py_VISIT(traverse_module_state->__pyx_memoryviewslice_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_memoryviewslice); + Py_VISIT(traverse_module_state->__pyx_kp_u_); + Py_VISIT(traverse_module_state->__pyx_n_s_ASCII); + Py_VISIT(traverse_module_state->__pyx_kp_s_All_dimensions_preceding_dimensi); + Py_VISIT(traverse_module_state->__pyx_n_s_AssertionError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Buffer_view_does_not_expose_stri); + Py_VISIT(traverse_module_state->__pyx_n_u_C); + Py_VISIT(traverse_module_state->__pyx_kp_s_Can_only_create_a_buffer_that_is); + Py_VISIT(traverse_module_state->__pyx_kp_s_Cannot_assign_to_read_only_memor); + Py_VISIT(traverse_module_state->__pyx_kp_s_Cannot_create_writable_memory_vi); + Py_VISIT(traverse_module_state->__pyx_kp_u_Cannot_index_with_type); + Py_VISIT(traverse_module_state->__pyx_kp_s_Cannot_transpose_memoryview_with); + Py_VISIT(traverse_module_state->__pyx_kp_s_Dimension_d_is_not_direct); + Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx); + Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx___reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx___setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx_augment); + Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx_covs); + Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx_get_augment_times); + Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx_get_filter_time); + Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx_init_state); + Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx_maha_test); + Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx_predict); + Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx_predict_and_update_b); + Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx_reset_rewind); + Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx_rts_smooth); + Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx_set_filter_time); + Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx_set_global); + Py_VISIT(traverse_module_state->__pyx_n_s_EKF_sym_pyx_state); + Py_VISIT(traverse_module_state->__pyx_n_s_Ellipsis); + Py_VISIT(traverse_module_state->__pyx_kp_s_Empty_shape_tuple_for_cython_arr); + Py_VISIT(traverse_module_state->__pyx_n_s_ImportError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0); + Py_VISIT(traverse_module_state->__pyx_n_s_IndexError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Index_out_of_bounds_axis_d); + Py_VISIT(traverse_module_state->__pyx_kp_s_Indirect_dimensions_not_supporte); + Py_VISIT(traverse_module_state->__pyx_kp_u_Invalid_mode_expected_c_or_fortr); + Py_VISIT(traverse_module_state->__pyx_kp_u_Invalid_shape_in_axis); + Py_VISIT(traverse_module_state->__pyx_n_s_MemoryError); + Py_VISIT(traverse_module_state->__pyx_kp_s_MemoryView_of_r_at_0x_x); + Py_VISIT(traverse_module_state->__pyx_kp_s_MemoryView_of_r_object); + Py_VISIT(traverse_module_state->__pyx_n_s_N); + Py_VISIT(traverse_module_state->__pyx_n_s_NotImplementedError); + Py_VISIT(traverse_module_state->__pyx_n_b_O); + Py_VISIT(traverse_module_state->__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + Py_VISIT(traverse_module_state->__pyx_n_s_P); + Py_VISIT(traverse_module_state->__pyx_n_s_P_initial); + Py_VISIT(traverse_module_state->__pyx_n_s_PickleError); + Py_VISIT(traverse_module_state->__pyx_n_s_Q); + Py_VISIT(traverse_module_state->__pyx_n_s_R); + Py_VISIT(traverse_module_state->__pyx_n_s_R_map); + Py_VISIT(traverse_module_state->__pyx_n_s_Ri); + Py_VISIT(traverse_module_state->__pyx_n_s_Ri_b); + Py_VISIT(traverse_module_state->__pyx_n_s_Sequence); + Py_VISIT(traverse_module_state->__pyx_kp_s_Step_may_not_be_zero_axis_d); + Py_VISIT(traverse_module_state->__pyx_kp_b_T); + Py_VISIT(traverse_module_state->__pyx_n_s_TypeError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Unable_to_convert_item_to_object); + Py_VISIT(traverse_module_state->__pyx_n_s_ValueError); + Py_VISIT(traverse_module_state->__pyx_n_s_View_MemoryView); + Py_VISIT(traverse_module_state->__pyx_kp_b__10); + Py_VISIT(traverse_module_state->__pyx_kp_b__11); + Py_VISIT(traverse_module_state->__pyx_kp_b__12); + Py_VISIT(traverse_module_state->__pyx_kp_u__13); + Py_VISIT(traverse_module_state->__pyx_kp_u__14); + Py_VISIT(traverse_module_state->__pyx_kp_u__2); + Py_VISIT(traverse_module_state->__pyx_n_s__3); + Py_VISIT(traverse_module_state->__pyx_n_s__58); + Py_VISIT(traverse_module_state->__pyx_kp_u__6); + Py_VISIT(traverse_module_state->__pyx_kp_u__7); + Py_VISIT(traverse_module_state->__pyx_kp_b__9); + Py_VISIT(traverse_module_state->__pyx_n_s_a); + Py_VISIT(traverse_module_state->__pyx_n_s_abc); + Py_VISIT(traverse_module_state->__pyx_n_s_allocate_buffer); + Py_VISIT(traverse_module_state->__pyx_kp_u_and); + Py_VISIT(traverse_module_state->__pyx_n_s_args); + Py_VISIT(traverse_module_state->__pyx_n_s_args_map); + Py_VISIT(traverse_module_state->__pyx_n_s_asarray); + Py_VISIT(traverse_module_state->__pyx_n_s_ascontiguousarray); + Py_VISIT(traverse_module_state->__pyx_n_s_asyncio_coroutines); + Py_VISIT(traverse_module_state->__pyx_n_s_augment); + Py_VISIT(traverse_module_state->__pyx_n_s_base); + Py_VISIT(traverse_module_state->__pyx_n_s_c); + Py_VISIT(traverse_module_state->__pyx_n_u_c); + Py_VISIT(traverse_module_state->__pyx_n_s_class); + Py_VISIT(traverse_module_state->__pyx_n_s_class_getitem); + Py_VISIT(traverse_module_state->__pyx_n_s_cline_in_traceback); + Py_VISIT(traverse_module_state->__pyx_n_s_collections); + Py_VISIT(traverse_module_state->__pyx_kp_s_collections_abc); + Py_VISIT(traverse_module_state->__pyx_kp_s_contiguous_and_direct); + Py_VISIT(traverse_module_state->__pyx_kp_s_contiguous_and_indirect); + Py_VISIT(traverse_module_state->__pyx_n_s_copy); + Py_VISIT(traverse_module_state->__pyx_n_s_count); + Py_VISIT(traverse_module_state->__pyx_n_s_covs); + Py_VISIT(traverse_module_state->__pyx_n_s_covs_b); + Py_VISIT(traverse_module_state->__pyx_n_s_dict); + Py_VISIT(traverse_module_state->__pyx_n_s_dim_augment); + Py_VISIT(traverse_module_state->__pyx_n_s_dim_augment_err); + Py_VISIT(traverse_module_state->__pyx_n_s_dim_main); + Py_VISIT(traverse_module_state->__pyx_n_s_dim_main_err); + Py_VISIT(traverse_module_state->__pyx_kp_u_disable); + Py_VISIT(traverse_module_state->__pyx_n_s_double); + Py_VISIT(traverse_module_state->__pyx_n_s_dtype); + Py_VISIT(traverse_module_state->__pyx_n_s_dtype_is_object); + Py_VISIT(traverse_module_state->__pyx_kp_u_enable); + Py_VISIT(traverse_module_state->__pyx_n_s_encode); + Py_VISIT(traverse_module_state->__pyx_n_s_enumerate); + Py_VISIT(traverse_module_state->__pyx_n_s_error); + Py_VISIT(traverse_module_state->__pyx_n_s_estimates); + Py_VISIT(traverse_module_state->__pyx_n_s_extra_args); + Py_VISIT(traverse_module_state->__pyx_n_s_extra_args_map); + Py_VISIT(traverse_module_state->__pyx_n_s_filter_time); + Py_VISIT(traverse_module_state->__pyx_n_s_flags); + Py_VISIT(traverse_module_state->__pyx_n_s_format); + Py_VISIT(traverse_module_state->__pyx_n_s_fortran); + Py_VISIT(traverse_module_state->__pyx_n_u_fortran); + Py_VISIT(traverse_module_state->__pyx_kp_u_gc); + Py_VISIT(traverse_module_state->__pyx_n_s_gen_dir); + Py_VISIT(traverse_module_state->__pyx_n_s_get_augment_times); + Py_VISIT(traverse_module_state->__pyx_n_s_get_filter_time); + Py_VISIT(traverse_module_state->__pyx_n_s_getstate); + Py_VISIT(traverse_module_state->__pyx_n_s_global_var); + Py_VISIT(traverse_module_state->__pyx_n_s_global_vars); + Py_VISIT(traverse_module_state->__pyx_kp_u_got); + Py_VISIT(traverse_module_state->__pyx_kp_u_got_differing_extents_in_dimensi); + Py_VISIT(traverse_module_state->__pyx_n_s_id); + Py_VISIT(traverse_module_state->__pyx_n_s_import); + Py_VISIT(traverse_module_state->__pyx_n_s_index); + Py_VISIT(traverse_module_state->__pyx_n_s_init_state); + Py_VISIT(traverse_module_state->__pyx_n_s_initializing); + Py_VISIT(traverse_module_state->__pyx_n_s_is_coroutine); + Py_VISIT(traverse_module_state->__pyx_kp_u_isenabled); + Py_VISIT(traverse_module_state->__pyx_n_s_itemsize); + Py_VISIT(traverse_module_state->__pyx_kp_s_itemsize_0_for_cython_array); + Py_VISIT(traverse_module_state->__pyx_n_s_join); + Py_VISIT(traverse_module_state->__pyx_n_s_kind); + Py_VISIT(traverse_module_state->__pyx_n_s_logger); + Py_VISIT(traverse_module_state->__pyx_n_s_maha_test); + Py_VISIT(traverse_module_state->__pyx_n_s_maha_test_kinds); + Py_VISIT(traverse_module_state->__pyx_n_s_maha_thresh); + Py_VISIT(traverse_module_state->__pyx_n_s_main); + Py_VISIT(traverse_module_state->__pyx_n_s_max_rewind_age); + Py_VISIT(traverse_module_state->__pyx_n_s_memview); + Py_VISIT(traverse_module_state->__pyx_n_s_mode); + Py_VISIT(traverse_module_state->__pyx_n_s_name); + Py_VISIT(traverse_module_state->__pyx_n_s_name_2); + Py_VISIT(traverse_module_state->__pyx_n_s_nan); + Py_VISIT(traverse_module_state->__pyx_n_s_ndim); + Py_VISIT(traverse_module_state->__pyx_n_s_new); + Py_VISIT(traverse_module_state->__pyx_kp_s_no_default___reduce___due_to_non); + Py_VISIT(traverse_module_state->__pyx_n_s_norm_quats); + Py_VISIT(traverse_module_state->__pyx_n_s_np); + Py_VISIT(traverse_module_state->__pyx_n_s_numpy); + Py_VISIT(traverse_module_state->__pyx_kp_u_numpy_core_multiarray_failed_to); + Py_VISIT(traverse_module_state->__pyx_kp_u_numpy_core_umath_failed_to_impor); + Py_VISIT(traverse_module_state->__pyx_n_s_obj); + Py_VISIT(traverse_module_state->__pyx_n_s_order); + Py_VISIT(traverse_module_state->__pyx_n_s_pack); + Py_VISIT(traverse_module_state->__pyx_n_s_pickle); + Py_VISIT(traverse_module_state->__pyx_n_s_predict); + Py_VISIT(traverse_module_state->__pyx_n_s_predict_and_update_batch); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_PickleError); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_checksum); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_result); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_state); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_type); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_unpickle_Enum); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_vtable); + Py_VISIT(traverse_module_state->__pyx_n_s_quaternion_idxs); + Py_VISIT(traverse_module_state->__pyx_n_s_range); + Py_VISIT(traverse_module_state->__pyx_n_s_rednose_helpers_ekf_sym_pyx); + Py_VISIT(traverse_module_state->__pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_ex); + Py_VISIT(traverse_module_state->__pyx_n_s_register); + Py_VISIT(traverse_module_state->__pyx_n_s_res); + Py_VISIT(traverse_module_state->__pyx_n_s_reset_rewind); + Py_VISIT(traverse_module_state->__pyx_n_s_rts_smooth); + Py_VISIT(traverse_module_state->__pyx_n_s_self); + Py_VISIT(traverse_module_state->__pyx_n_s_set_filter_time); + Py_VISIT(traverse_module_state->__pyx_n_s_set_global); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_shape); + Py_VISIT(traverse_module_state->__pyx_n_s_size); + Py_VISIT(traverse_module_state->__pyx_n_s_spec); + Py_VISIT(traverse_module_state->__pyx_n_s_start); + Py_VISIT(traverse_module_state->__pyx_n_s_state); + Py_VISIT(traverse_module_state->__pyx_n_s_state_b); + Py_VISIT(traverse_module_state->__pyx_n_s_step); + Py_VISIT(traverse_module_state->__pyx_n_s_stop); + Py_VISIT(traverse_module_state->__pyx_kp_s_strided_and_direct); + Py_VISIT(traverse_module_state->__pyx_kp_s_strided_and_direct_or_indirect); + Py_VISIT(traverse_module_state->__pyx_kp_s_strided_and_indirect); + Py_VISIT(traverse_module_state->__pyx_kp_s_stringsource); + Py_VISIT(traverse_module_state->__pyx_n_s_struct); + Py_VISIT(traverse_module_state->__pyx_n_s_sys); + Py_VISIT(traverse_module_state->__pyx_n_s_t); + Py_VISIT(traverse_module_state->__pyx_n_s_test); + Py_VISIT(traverse_module_state->__pyx_n_s_tmpvec); + Py_VISIT(traverse_module_state->__pyx_kp_s_unable_to_allocate_array_data); + Py_VISIT(traverse_module_state->__pyx_kp_s_unable_to_allocate_shape_and_str); + Py_VISIT(traverse_module_state->__pyx_n_s_unpack); + Py_VISIT(traverse_module_state->__pyx_n_s_update); + Py_VISIT(traverse_module_state->__pyx_n_u_utf8); + Py_VISIT(traverse_module_state->__pyx_n_s_val); + Py_VISIT(traverse_module_state->__pyx_n_s_version_info); + Py_VISIT(traverse_module_state->__pyx_n_s_x); + Py_VISIT(traverse_module_state->__pyx_n_s_x_initial); + Py_VISIT(traverse_module_state->__pyx_n_s_z); + Py_VISIT(traverse_module_state->__pyx_n_s_z_map); + Py_VISIT(traverse_module_state->__pyx_n_s_zi); + Py_VISIT(traverse_module_state->__pyx_n_s_zi_b); + Py_VISIT(traverse_module_state->__pyx_float_0_95); + Py_VISIT(traverse_module_state->__pyx_int_0); + Py_VISIT(traverse_module_state->__pyx_int_1); + Py_VISIT(traverse_module_state->__pyx_int_3); + Py_VISIT(traverse_module_state->__pyx_int_112105877); + Py_VISIT(traverse_module_state->__pyx_int_136983863); + Py_VISIT(traverse_module_state->__pyx_int_184977713); + Py_VISIT(traverse_module_state->__pyx_int_neg_1); + Py_VISIT(traverse_module_state->__pyx_k__17); + Py_VISIT(traverse_module_state->__pyx_k__18); + Py_VISIT(traverse_module_state->__pyx_k__19); + Py_VISIT(traverse_module_state->__pyx_k__28); + Py_VISIT(traverse_module_state->__pyx_k__33); + Py_VISIT(traverse_module_state->__pyx_slice__5); + Py_VISIT(traverse_module_state->__pyx_tuple__4); + Py_VISIT(traverse_module_state->__pyx_tuple__8); + Py_VISIT(traverse_module_state->__pyx_tuple__15); + Py_VISIT(traverse_module_state->__pyx_tuple__16); + Py_VISIT(traverse_module_state->__pyx_tuple__37); + Py_VISIT(traverse_module_state->__pyx_tuple__38); + Py_VISIT(traverse_module_state->__pyx_tuple__39); + Py_VISIT(traverse_module_state->__pyx_tuple__40); + Py_VISIT(traverse_module_state->__pyx_tuple__41); + Py_VISIT(traverse_module_state->__pyx_tuple__42); + Py_VISIT(traverse_module_state->__pyx_tuple__43); + Py_VISIT(traverse_module_state->__pyx_tuple__44); + Py_VISIT(traverse_module_state->__pyx_tuple__45); + Py_VISIT(traverse_module_state->__pyx_tuple__46); + Py_VISIT(traverse_module_state->__pyx_tuple__48); + Py_VISIT(traverse_module_state->__pyx_tuple__49); + Py_VISIT(traverse_module_state->__pyx_tuple__50); + Py_VISIT(traverse_module_state->__pyx_tuple__51); + Py_VISIT(traverse_module_state->__pyx_tuple__52); + Py_VISIT(traverse_module_state->__pyx_tuple__53); + Py_VISIT(traverse_module_state->__pyx_tuple__54); + Py_VISIT(traverse_module_state->__pyx_tuple__55); + Py_VISIT(traverse_module_state->__pyx_tuple__56); + Py_VISIT(traverse_module_state->__pyx_tuple__57); + Py_VISIT(traverse_module_state->__pyx_codeobj__20); + Py_VISIT(traverse_module_state->__pyx_codeobj__21); + Py_VISIT(traverse_module_state->__pyx_codeobj__22); + Py_VISIT(traverse_module_state->__pyx_codeobj__23); + Py_VISIT(traverse_module_state->__pyx_codeobj__24); + Py_VISIT(traverse_module_state->__pyx_codeobj__25); + Py_VISIT(traverse_module_state->__pyx_codeobj__26); + Py_VISIT(traverse_module_state->__pyx_codeobj__27); + Py_VISIT(traverse_module_state->__pyx_codeobj__29); + Py_VISIT(traverse_module_state->__pyx_codeobj__30); + Py_VISIT(traverse_module_state->__pyx_codeobj__31); + Py_VISIT(traverse_module_state->__pyx_codeobj__32); + Py_VISIT(traverse_module_state->__pyx_codeobj__34); + Py_VISIT(traverse_module_state->__pyx_codeobj__35); + Py_VISIT(traverse_module_state->__pyx_codeobj__36); + Py_VISIT(traverse_module_state->__pyx_codeobj__47); + return 0; +} +#endif +/* #### Code section: module_state_defines ### */ +#define __pyx_d __pyx_mstate_global->__pyx_d +#define __pyx_b __pyx_mstate_global->__pyx_b +#define __pyx_cython_runtime __pyx_mstate_global->__pyx_cython_runtime +#define __pyx_empty_tuple __pyx_mstate_global->__pyx_empty_tuple +#define __pyx_empty_bytes __pyx_mstate_global->__pyx_empty_bytes +#define __pyx_empty_unicode __pyx_mstate_global->__pyx_empty_unicode +#ifdef __Pyx_CyFunction_USED +#define __pyx_CyFunctionType __pyx_mstate_global->__pyx_CyFunctionType +#endif +#ifdef __Pyx_FusedFunction_USED +#define __pyx_FusedFunctionType __pyx_mstate_global->__pyx_FusedFunctionType +#endif +#ifdef __Pyx_Generator_USED +#define __pyx_GeneratorType __pyx_mstate_global->__pyx_GeneratorType +#endif +#ifdef __Pyx_IterableCoroutine_USED +#define __pyx_IterableCoroutineType __pyx_mstate_global->__pyx_IterableCoroutineType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineAwaitType __pyx_mstate_global->__pyx_CoroutineAwaitType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineType __pyx_mstate_global->__pyx_CoroutineType +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#define __pyx_ptype_7cpython_4type_type __pyx_mstate_global->__pyx_ptype_7cpython_4type_type +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#define __pyx_ptype_5numpy_dtype __pyx_mstate_global->__pyx_ptype_5numpy_dtype +#define __pyx_ptype_5numpy_flatiter __pyx_mstate_global->__pyx_ptype_5numpy_flatiter +#define __pyx_ptype_5numpy_broadcast __pyx_mstate_global->__pyx_ptype_5numpy_broadcast +#define __pyx_ptype_5numpy_ndarray __pyx_mstate_global->__pyx_ptype_5numpy_ndarray +#define __pyx_ptype_5numpy_generic __pyx_mstate_global->__pyx_ptype_5numpy_generic +#define __pyx_ptype_5numpy_number __pyx_mstate_global->__pyx_ptype_5numpy_number +#define __pyx_ptype_5numpy_integer __pyx_mstate_global->__pyx_ptype_5numpy_integer +#define __pyx_ptype_5numpy_signedinteger __pyx_mstate_global->__pyx_ptype_5numpy_signedinteger +#define __pyx_ptype_5numpy_unsignedinteger __pyx_mstate_global->__pyx_ptype_5numpy_unsignedinteger +#define __pyx_ptype_5numpy_inexact __pyx_mstate_global->__pyx_ptype_5numpy_inexact +#define __pyx_ptype_5numpy_floating __pyx_mstate_global->__pyx_ptype_5numpy_floating +#define __pyx_ptype_5numpy_complexfloating __pyx_mstate_global->__pyx_ptype_5numpy_complexfloating +#define __pyx_ptype_5numpy_flexible __pyx_mstate_global->__pyx_ptype_5numpy_flexible +#define __pyx_ptype_5numpy_character __pyx_mstate_global->__pyx_ptype_5numpy_character +#define __pyx_ptype_5numpy_ufunc __pyx_mstate_global->__pyx_ptype_5numpy_ufunc +#if CYTHON_USE_MODULE_STATE +#define __pyx_type_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx __pyx_mstate_global->__pyx_type_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx +#define __pyx_type___pyx_array __pyx_mstate_global->__pyx_type___pyx_array +#define __pyx_type___pyx_MemviewEnum __pyx_mstate_global->__pyx_type___pyx_MemviewEnum +#define __pyx_type___pyx_memoryview __pyx_mstate_global->__pyx_type___pyx_memoryview +#define __pyx_type___pyx_memoryviewslice __pyx_mstate_global->__pyx_type___pyx_memoryviewslice +#endif +#define __pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx __pyx_mstate_global->__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx +#define __pyx_array_type __pyx_mstate_global->__pyx_array_type +#define __pyx_MemviewEnum_type __pyx_mstate_global->__pyx_MemviewEnum_type +#define __pyx_memoryview_type __pyx_mstate_global->__pyx_memoryview_type +#define __pyx_memoryviewslice_type __pyx_mstate_global->__pyx_memoryviewslice_type +#define __pyx_kp_u_ __pyx_mstate_global->__pyx_kp_u_ +#define __pyx_n_s_ASCII __pyx_mstate_global->__pyx_n_s_ASCII +#define __pyx_kp_s_All_dimensions_preceding_dimensi __pyx_mstate_global->__pyx_kp_s_All_dimensions_preceding_dimensi +#define __pyx_n_s_AssertionError __pyx_mstate_global->__pyx_n_s_AssertionError +#define __pyx_kp_s_Buffer_view_does_not_expose_stri __pyx_mstate_global->__pyx_kp_s_Buffer_view_does_not_expose_stri +#define __pyx_n_u_C __pyx_mstate_global->__pyx_n_u_C +#define __pyx_kp_s_Can_only_create_a_buffer_that_is __pyx_mstate_global->__pyx_kp_s_Can_only_create_a_buffer_that_is +#define __pyx_kp_s_Cannot_assign_to_read_only_memor __pyx_mstate_global->__pyx_kp_s_Cannot_assign_to_read_only_memor +#define __pyx_kp_s_Cannot_create_writable_memory_vi __pyx_mstate_global->__pyx_kp_s_Cannot_create_writable_memory_vi +#define __pyx_kp_u_Cannot_index_with_type __pyx_mstate_global->__pyx_kp_u_Cannot_index_with_type +#define __pyx_kp_s_Cannot_transpose_memoryview_with __pyx_mstate_global->__pyx_kp_s_Cannot_transpose_memoryview_with +#define __pyx_kp_s_Dimension_d_is_not_direct __pyx_mstate_global->__pyx_kp_s_Dimension_d_is_not_direct +#define __pyx_n_s_EKF_sym_pyx __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx +#define __pyx_n_s_EKF_sym_pyx___reduce_cython __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx___reduce_cython +#define __pyx_n_s_EKF_sym_pyx___setstate_cython __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx___setstate_cython +#define __pyx_n_s_EKF_sym_pyx_augment __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx_augment +#define __pyx_n_s_EKF_sym_pyx_covs __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx_covs +#define __pyx_n_s_EKF_sym_pyx_get_augment_times __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx_get_augment_times +#define __pyx_n_s_EKF_sym_pyx_get_filter_time __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx_get_filter_time +#define __pyx_n_s_EKF_sym_pyx_init_state __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx_init_state +#define __pyx_n_s_EKF_sym_pyx_maha_test __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx_maha_test +#define __pyx_n_s_EKF_sym_pyx_predict __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx_predict +#define __pyx_n_s_EKF_sym_pyx_predict_and_update_b __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx_predict_and_update_b +#define __pyx_n_s_EKF_sym_pyx_reset_rewind __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx_reset_rewind +#define __pyx_n_s_EKF_sym_pyx_rts_smooth __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx_rts_smooth +#define __pyx_n_s_EKF_sym_pyx_set_filter_time __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx_set_filter_time +#define __pyx_n_s_EKF_sym_pyx_set_global __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx_set_global +#define __pyx_n_s_EKF_sym_pyx_state __pyx_mstate_global->__pyx_n_s_EKF_sym_pyx_state +#define __pyx_n_s_Ellipsis __pyx_mstate_global->__pyx_n_s_Ellipsis +#define __pyx_kp_s_Empty_shape_tuple_for_cython_arr __pyx_mstate_global->__pyx_kp_s_Empty_shape_tuple_for_cython_arr +#define __pyx_n_s_ImportError __pyx_mstate_global->__pyx_n_s_ImportError +#define __pyx_kp_s_Incompatible_checksums_0x_x_vs_0 __pyx_mstate_global->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0 +#define __pyx_n_s_IndexError __pyx_mstate_global->__pyx_n_s_IndexError +#define __pyx_kp_s_Index_out_of_bounds_axis_d __pyx_mstate_global->__pyx_kp_s_Index_out_of_bounds_axis_d +#define __pyx_kp_s_Indirect_dimensions_not_supporte __pyx_mstate_global->__pyx_kp_s_Indirect_dimensions_not_supporte +#define __pyx_kp_u_Invalid_mode_expected_c_or_fortr __pyx_mstate_global->__pyx_kp_u_Invalid_mode_expected_c_or_fortr +#define __pyx_kp_u_Invalid_shape_in_axis __pyx_mstate_global->__pyx_kp_u_Invalid_shape_in_axis +#define __pyx_n_s_MemoryError __pyx_mstate_global->__pyx_n_s_MemoryError +#define __pyx_kp_s_MemoryView_of_r_at_0x_x __pyx_mstate_global->__pyx_kp_s_MemoryView_of_r_at_0x_x +#define __pyx_kp_s_MemoryView_of_r_object __pyx_mstate_global->__pyx_kp_s_MemoryView_of_r_object +#define __pyx_n_s_N __pyx_mstate_global->__pyx_n_s_N +#define __pyx_n_s_NotImplementedError __pyx_mstate_global->__pyx_n_s_NotImplementedError +#define __pyx_n_b_O __pyx_mstate_global->__pyx_n_b_O +#define __pyx_kp_u_Out_of_bounds_on_buffer_access_a __pyx_mstate_global->__pyx_kp_u_Out_of_bounds_on_buffer_access_a +#define __pyx_n_s_P __pyx_mstate_global->__pyx_n_s_P +#define __pyx_n_s_P_initial __pyx_mstate_global->__pyx_n_s_P_initial +#define __pyx_n_s_PickleError __pyx_mstate_global->__pyx_n_s_PickleError +#define __pyx_n_s_Q __pyx_mstate_global->__pyx_n_s_Q +#define __pyx_n_s_R __pyx_mstate_global->__pyx_n_s_R +#define __pyx_n_s_R_map __pyx_mstate_global->__pyx_n_s_R_map +#define __pyx_n_s_Ri __pyx_mstate_global->__pyx_n_s_Ri +#define __pyx_n_s_Ri_b __pyx_mstate_global->__pyx_n_s_Ri_b +#define __pyx_n_s_Sequence __pyx_mstate_global->__pyx_n_s_Sequence +#define __pyx_kp_s_Step_may_not_be_zero_axis_d __pyx_mstate_global->__pyx_kp_s_Step_may_not_be_zero_axis_d +#define __pyx_kp_b_T __pyx_mstate_global->__pyx_kp_b_T +#define __pyx_n_s_TypeError __pyx_mstate_global->__pyx_n_s_TypeError +#define __pyx_kp_s_Unable_to_convert_item_to_object __pyx_mstate_global->__pyx_kp_s_Unable_to_convert_item_to_object +#define __pyx_n_s_ValueError __pyx_mstate_global->__pyx_n_s_ValueError +#define __pyx_n_s_View_MemoryView __pyx_mstate_global->__pyx_n_s_View_MemoryView +#define __pyx_kp_b__10 __pyx_mstate_global->__pyx_kp_b__10 +#define __pyx_kp_b__11 __pyx_mstate_global->__pyx_kp_b__11 +#define __pyx_kp_b__12 __pyx_mstate_global->__pyx_kp_b__12 +#define __pyx_kp_u__13 __pyx_mstate_global->__pyx_kp_u__13 +#define __pyx_kp_u__14 __pyx_mstate_global->__pyx_kp_u__14 +#define __pyx_kp_u__2 __pyx_mstate_global->__pyx_kp_u__2 +#define __pyx_n_s__3 __pyx_mstate_global->__pyx_n_s__3 +#define __pyx_n_s__58 __pyx_mstate_global->__pyx_n_s__58 +#define __pyx_kp_u__6 __pyx_mstate_global->__pyx_kp_u__6 +#define __pyx_kp_u__7 __pyx_mstate_global->__pyx_kp_u__7 +#define __pyx_kp_b__9 __pyx_mstate_global->__pyx_kp_b__9 +#define __pyx_n_s_a __pyx_mstate_global->__pyx_n_s_a +#define __pyx_n_s_abc __pyx_mstate_global->__pyx_n_s_abc +#define __pyx_n_s_allocate_buffer __pyx_mstate_global->__pyx_n_s_allocate_buffer +#define __pyx_kp_u_and __pyx_mstate_global->__pyx_kp_u_and +#define __pyx_n_s_args __pyx_mstate_global->__pyx_n_s_args +#define __pyx_n_s_args_map __pyx_mstate_global->__pyx_n_s_args_map +#define __pyx_n_s_asarray __pyx_mstate_global->__pyx_n_s_asarray +#define __pyx_n_s_ascontiguousarray __pyx_mstate_global->__pyx_n_s_ascontiguousarray +#define __pyx_n_s_asyncio_coroutines __pyx_mstate_global->__pyx_n_s_asyncio_coroutines +#define __pyx_n_s_augment __pyx_mstate_global->__pyx_n_s_augment +#define __pyx_n_s_base __pyx_mstate_global->__pyx_n_s_base +#define __pyx_n_s_c __pyx_mstate_global->__pyx_n_s_c +#define __pyx_n_u_c __pyx_mstate_global->__pyx_n_u_c +#define __pyx_n_s_class __pyx_mstate_global->__pyx_n_s_class +#define __pyx_n_s_class_getitem __pyx_mstate_global->__pyx_n_s_class_getitem +#define __pyx_n_s_cline_in_traceback __pyx_mstate_global->__pyx_n_s_cline_in_traceback +#define __pyx_n_s_collections __pyx_mstate_global->__pyx_n_s_collections +#define __pyx_kp_s_collections_abc __pyx_mstate_global->__pyx_kp_s_collections_abc +#define __pyx_kp_s_contiguous_and_direct __pyx_mstate_global->__pyx_kp_s_contiguous_and_direct +#define __pyx_kp_s_contiguous_and_indirect __pyx_mstate_global->__pyx_kp_s_contiguous_and_indirect +#define __pyx_n_s_copy __pyx_mstate_global->__pyx_n_s_copy +#define __pyx_n_s_count __pyx_mstate_global->__pyx_n_s_count +#define __pyx_n_s_covs __pyx_mstate_global->__pyx_n_s_covs +#define __pyx_n_s_covs_b __pyx_mstate_global->__pyx_n_s_covs_b +#define __pyx_n_s_dict __pyx_mstate_global->__pyx_n_s_dict +#define __pyx_n_s_dim_augment __pyx_mstate_global->__pyx_n_s_dim_augment +#define __pyx_n_s_dim_augment_err __pyx_mstate_global->__pyx_n_s_dim_augment_err +#define __pyx_n_s_dim_main __pyx_mstate_global->__pyx_n_s_dim_main +#define __pyx_n_s_dim_main_err __pyx_mstate_global->__pyx_n_s_dim_main_err +#define __pyx_kp_u_disable __pyx_mstate_global->__pyx_kp_u_disable +#define __pyx_n_s_double __pyx_mstate_global->__pyx_n_s_double +#define __pyx_n_s_dtype __pyx_mstate_global->__pyx_n_s_dtype +#define __pyx_n_s_dtype_is_object __pyx_mstate_global->__pyx_n_s_dtype_is_object +#define __pyx_kp_u_enable __pyx_mstate_global->__pyx_kp_u_enable +#define __pyx_n_s_encode __pyx_mstate_global->__pyx_n_s_encode +#define __pyx_n_s_enumerate __pyx_mstate_global->__pyx_n_s_enumerate +#define __pyx_n_s_error __pyx_mstate_global->__pyx_n_s_error +#define __pyx_n_s_estimates __pyx_mstate_global->__pyx_n_s_estimates +#define __pyx_n_s_extra_args __pyx_mstate_global->__pyx_n_s_extra_args +#define __pyx_n_s_extra_args_map __pyx_mstate_global->__pyx_n_s_extra_args_map +#define __pyx_n_s_filter_time __pyx_mstate_global->__pyx_n_s_filter_time +#define __pyx_n_s_flags __pyx_mstate_global->__pyx_n_s_flags +#define __pyx_n_s_format __pyx_mstate_global->__pyx_n_s_format +#define __pyx_n_s_fortran __pyx_mstate_global->__pyx_n_s_fortran +#define __pyx_n_u_fortran __pyx_mstate_global->__pyx_n_u_fortran +#define __pyx_kp_u_gc __pyx_mstate_global->__pyx_kp_u_gc +#define __pyx_n_s_gen_dir __pyx_mstate_global->__pyx_n_s_gen_dir +#define __pyx_n_s_get_augment_times __pyx_mstate_global->__pyx_n_s_get_augment_times +#define __pyx_n_s_get_filter_time __pyx_mstate_global->__pyx_n_s_get_filter_time +#define __pyx_n_s_getstate __pyx_mstate_global->__pyx_n_s_getstate +#define __pyx_n_s_global_var __pyx_mstate_global->__pyx_n_s_global_var +#define __pyx_n_s_global_vars __pyx_mstate_global->__pyx_n_s_global_vars +#define __pyx_kp_u_got __pyx_mstate_global->__pyx_kp_u_got +#define __pyx_kp_u_got_differing_extents_in_dimensi __pyx_mstate_global->__pyx_kp_u_got_differing_extents_in_dimensi +#define __pyx_n_s_id __pyx_mstate_global->__pyx_n_s_id +#define __pyx_n_s_import __pyx_mstate_global->__pyx_n_s_import +#define __pyx_n_s_index __pyx_mstate_global->__pyx_n_s_index +#define __pyx_n_s_init_state __pyx_mstate_global->__pyx_n_s_init_state +#define __pyx_n_s_initializing __pyx_mstate_global->__pyx_n_s_initializing +#define __pyx_n_s_is_coroutine __pyx_mstate_global->__pyx_n_s_is_coroutine +#define __pyx_kp_u_isenabled __pyx_mstate_global->__pyx_kp_u_isenabled +#define __pyx_n_s_itemsize __pyx_mstate_global->__pyx_n_s_itemsize +#define __pyx_kp_s_itemsize_0_for_cython_array __pyx_mstate_global->__pyx_kp_s_itemsize_0_for_cython_array +#define __pyx_n_s_join __pyx_mstate_global->__pyx_n_s_join +#define __pyx_n_s_kind __pyx_mstate_global->__pyx_n_s_kind +#define __pyx_n_s_logger __pyx_mstate_global->__pyx_n_s_logger +#define __pyx_n_s_maha_test __pyx_mstate_global->__pyx_n_s_maha_test +#define __pyx_n_s_maha_test_kinds __pyx_mstate_global->__pyx_n_s_maha_test_kinds +#define __pyx_n_s_maha_thresh __pyx_mstate_global->__pyx_n_s_maha_thresh +#define __pyx_n_s_main __pyx_mstate_global->__pyx_n_s_main +#define __pyx_n_s_max_rewind_age __pyx_mstate_global->__pyx_n_s_max_rewind_age +#define __pyx_n_s_memview __pyx_mstate_global->__pyx_n_s_memview +#define __pyx_n_s_mode __pyx_mstate_global->__pyx_n_s_mode +#define __pyx_n_s_name __pyx_mstate_global->__pyx_n_s_name +#define __pyx_n_s_name_2 __pyx_mstate_global->__pyx_n_s_name_2 +#define __pyx_n_s_nan __pyx_mstate_global->__pyx_n_s_nan +#define __pyx_n_s_ndim __pyx_mstate_global->__pyx_n_s_ndim +#define __pyx_n_s_new __pyx_mstate_global->__pyx_n_s_new +#define __pyx_kp_s_no_default___reduce___due_to_non __pyx_mstate_global->__pyx_kp_s_no_default___reduce___due_to_non +#define __pyx_n_s_norm_quats __pyx_mstate_global->__pyx_n_s_norm_quats +#define __pyx_n_s_np __pyx_mstate_global->__pyx_n_s_np +#define __pyx_n_s_numpy __pyx_mstate_global->__pyx_n_s_numpy +#define __pyx_kp_u_numpy_core_multiarray_failed_to __pyx_mstate_global->__pyx_kp_u_numpy_core_multiarray_failed_to +#define __pyx_kp_u_numpy_core_umath_failed_to_impor __pyx_mstate_global->__pyx_kp_u_numpy_core_umath_failed_to_impor +#define __pyx_n_s_obj __pyx_mstate_global->__pyx_n_s_obj +#define __pyx_n_s_order __pyx_mstate_global->__pyx_n_s_order +#define __pyx_n_s_pack __pyx_mstate_global->__pyx_n_s_pack +#define __pyx_n_s_pickle __pyx_mstate_global->__pyx_n_s_pickle +#define __pyx_n_s_predict __pyx_mstate_global->__pyx_n_s_predict +#define __pyx_n_s_predict_and_update_batch __pyx_mstate_global->__pyx_n_s_predict_and_update_batch +#define __pyx_n_s_pyx_PickleError __pyx_mstate_global->__pyx_n_s_pyx_PickleError +#define __pyx_n_s_pyx_checksum __pyx_mstate_global->__pyx_n_s_pyx_checksum +#define __pyx_n_s_pyx_result __pyx_mstate_global->__pyx_n_s_pyx_result +#define __pyx_n_s_pyx_state __pyx_mstate_global->__pyx_n_s_pyx_state +#define __pyx_n_s_pyx_type __pyx_mstate_global->__pyx_n_s_pyx_type +#define __pyx_n_s_pyx_unpickle_Enum __pyx_mstate_global->__pyx_n_s_pyx_unpickle_Enum +#define __pyx_n_s_pyx_vtable __pyx_mstate_global->__pyx_n_s_pyx_vtable +#define __pyx_n_s_quaternion_idxs __pyx_mstate_global->__pyx_n_s_quaternion_idxs +#define __pyx_n_s_range __pyx_mstate_global->__pyx_n_s_range +#define __pyx_n_s_rednose_helpers_ekf_sym_pyx __pyx_mstate_global->__pyx_n_s_rednose_helpers_ekf_sym_pyx +#define __pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx __pyx_mstate_global->__pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx +#define __pyx_n_s_reduce __pyx_mstate_global->__pyx_n_s_reduce +#define __pyx_n_s_reduce_cython __pyx_mstate_global->__pyx_n_s_reduce_cython +#define __pyx_n_s_reduce_ex __pyx_mstate_global->__pyx_n_s_reduce_ex +#define __pyx_n_s_register __pyx_mstate_global->__pyx_n_s_register +#define __pyx_n_s_res __pyx_mstate_global->__pyx_n_s_res +#define __pyx_n_s_reset_rewind __pyx_mstate_global->__pyx_n_s_reset_rewind +#define __pyx_n_s_rts_smooth __pyx_mstate_global->__pyx_n_s_rts_smooth +#define __pyx_n_s_self __pyx_mstate_global->__pyx_n_s_self +#define __pyx_n_s_set_filter_time __pyx_mstate_global->__pyx_n_s_set_filter_time +#define __pyx_n_s_set_global __pyx_mstate_global->__pyx_n_s_set_global +#define __pyx_n_s_setstate __pyx_mstate_global->__pyx_n_s_setstate +#define __pyx_n_s_setstate_cython __pyx_mstate_global->__pyx_n_s_setstate_cython +#define __pyx_n_s_shape __pyx_mstate_global->__pyx_n_s_shape +#define __pyx_n_s_size __pyx_mstate_global->__pyx_n_s_size +#define __pyx_n_s_spec __pyx_mstate_global->__pyx_n_s_spec +#define __pyx_n_s_start __pyx_mstate_global->__pyx_n_s_start +#define __pyx_n_s_state __pyx_mstate_global->__pyx_n_s_state +#define __pyx_n_s_state_b __pyx_mstate_global->__pyx_n_s_state_b +#define __pyx_n_s_step __pyx_mstate_global->__pyx_n_s_step +#define __pyx_n_s_stop __pyx_mstate_global->__pyx_n_s_stop +#define __pyx_kp_s_strided_and_direct __pyx_mstate_global->__pyx_kp_s_strided_and_direct +#define __pyx_kp_s_strided_and_direct_or_indirect __pyx_mstate_global->__pyx_kp_s_strided_and_direct_or_indirect +#define __pyx_kp_s_strided_and_indirect __pyx_mstate_global->__pyx_kp_s_strided_and_indirect +#define __pyx_kp_s_stringsource __pyx_mstate_global->__pyx_kp_s_stringsource +#define __pyx_n_s_struct __pyx_mstate_global->__pyx_n_s_struct +#define __pyx_n_s_sys __pyx_mstate_global->__pyx_n_s_sys +#define __pyx_n_s_t __pyx_mstate_global->__pyx_n_s_t +#define __pyx_n_s_test __pyx_mstate_global->__pyx_n_s_test +#define __pyx_n_s_tmpvec __pyx_mstate_global->__pyx_n_s_tmpvec +#define __pyx_kp_s_unable_to_allocate_array_data __pyx_mstate_global->__pyx_kp_s_unable_to_allocate_array_data +#define __pyx_kp_s_unable_to_allocate_shape_and_str __pyx_mstate_global->__pyx_kp_s_unable_to_allocate_shape_and_str +#define __pyx_n_s_unpack __pyx_mstate_global->__pyx_n_s_unpack +#define __pyx_n_s_update __pyx_mstate_global->__pyx_n_s_update +#define __pyx_n_u_utf8 __pyx_mstate_global->__pyx_n_u_utf8 +#define __pyx_n_s_val __pyx_mstate_global->__pyx_n_s_val +#define __pyx_n_s_version_info __pyx_mstate_global->__pyx_n_s_version_info +#define __pyx_n_s_x __pyx_mstate_global->__pyx_n_s_x +#define __pyx_n_s_x_initial __pyx_mstate_global->__pyx_n_s_x_initial +#define __pyx_n_s_z __pyx_mstate_global->__pyx_n_s_z +#define __pyx_n_s_z_map __pyx_mstate_global->__pyx_n_s_z_map +#define __pyx_n_s_zi __pyx_mstate_global->__pyx_n_s_zi +#define __pyx_n_s_zi_b __pyx_mstate_global->__pyx_n_s_zi_b +#define __pyx_float_0_95 __pyx_mstate_global->__pyx_float_0_95 +#define __pyx_int_0 __pyx_mstate_global->__pyx_int_0 +#define __pyx_int_1 __pyx_mstate_global->__pyx_int_1 +#define __pyx_int_3 __pyx_mstate_global->__pyx_int_3 +#define __pyx_int_112105877 __pyx_mstate_global->__pyx_int_112105877 +#define __pyx_int_136983863 __pyx_mstate_global->__pyx_int_136983863 +#define __pyx_int_184977713 __pyx_mstate_global->__pyx_int_184977713 +#define __pyx_int_neg_1 __pyx_mstate_global->__pyx_int_neg_1 +#define __pyx_k__17 __pyx_mstate_global->__pyx_k__17 +#define __pyx_k__18 __pyx_mstate_global->__pyx_k__18 +#define __pyx_k__19 __pyx_mstate_global->__pyx_k__19 +#define __pyx_k__28 __pyx_mstate_global->__pyx_k__28 +#define __pyx_k__33 __pyx_mstate_global->__pyx_k__33 +#define __pyx_slice__5 __pyx_mstate_global->__pyx_slice__5 +#define __pyx_tuple__4 __pyx_mstate_global->__pyx_tuple__4 +#define __pyx_tuple__8 __pyx_mstate_global->__pyx_tuple__8 +#define __pyx_tuple__15 __pyx_mstate_global->__pyx_tuple__15 +#define __pyx_tuple__16 __pyx_mstate_global->__pyx_tuple__16 +#define __pyx_tuple__37 __pyx_mstate_global->__pyx_tuple__37 +#define __pyx_tuple__38 __pyx_mstate_global->__pyx_tuple__38 +#define __pyx_tuple__39 __pyx_mstate_global->__pyx_tuple__39 +#define __pyx_tuple__40 __pyx_mstate_global->__pyx_tuple__40 +#define __pyx_tuple__41 __pyx_mstate_global->__pyx_tuple__41 +#define __pyx_tuple__42 __pyx_mstate_global->__pyx_tuple__42 +#define __pyx_tuple__43 __pyx_mstate_global->__pyx_tuple__43 +#define __pyx_tuple__44 __pyx_mstate_global->__pyx_tuple__44 +#define __pyx_tuple__45 __pyx_mstate_global->__pyx_tuple__45 +#define __pyx_tuple__46 __pyx_mstate_global->__pyx_tuple__46 +#define __pyx_tuple__48 __pyx_mstate_global->__pyx_tuple__48 +#define __pyx_tuple__49 __pyx_mstate_global->__pyx_tuple__49 +#define __pyx_tuple__50 __pyx_mstate_global->__pyx_tuple__50 +#define __pyx_tuple__51 __pyx_mstate_global->__pyx_tuple__51 +#define __pyx_tuple__52 __pyx_mstate_global->__pyx_tuple__52 +#define __pyx_tuple__53 __pyx_mstate_global->__pyx_tuple__53 +#define __pyx_tuple__54 __pyx_mstate_global->__pyx_tuple__54 +#define __pyx_tuple__55 __pyx_mstate_global->__pyx_tuple__55 +#define __pyx_tuple__56 __pyx_mstate_global->__pyx_tuple__56 +#define __pyx_tuple__57 __pyx_mstate_global->__pyx_tuple__57 +#define __pyx_codeobj__20 __pyx_mstate_global->__pyx_codeobj__20 +#define __pyx_codeobj__21 __pyx_mstate_global->__pyx_codeobj__21 +#define __pyx_codeobj__22 __pyx_mstate_global->__pyx_codeobj__22 +#define __pyx_codeobj__23 __pyx_mstate_global->__pyx_codeobj__23 +#define __pyx_codeobj__24 __pyx_mstate_global->__pyx_codeobj__24 +#define __pyx_codeobj__25 __pyx_mstate_global->__pyx_codeobj__25 +#define __pyx_codeobj__26 __pyx_mstate_global->__pyx_codeobj__26 +#define __pyx_codeobj__27 __pyx_mstate_global->__pyx_codeobj__27 +#define __pyx_codeobj__29 __pyx_mstate_global->__pyx_codeobj__29 +#define __pyx_codeobj__30 __pyx_mstate_global->__pyx_codeobj__30 +#define __pyx_codeobj__31 __pyx_mstate_global->__pyx_codeobj__31 +#define __pyx_codeobj__32 __pyx_mstate_global->__pyx_codeobj__32 +#define __pyx_codeobj__34 __pyx_mstate_global->__pyx_codeobj__34 +#define __pyx_codeobj__35 __pyx_mstate_global->__pyx_codeobj__35 +#define __pyx_codeobj__36 __pyx_mstate_global->__pyx_codeobj__36 +#define __pyx_codeobj__47 __pyx_mstate_global->__pyx_codeobj__47 +/* #### Code section: module_code ### */ + +/* "string.from_py":13 + * + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: # <<<<<<<<<<<<<< + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + */ + +static std::string __pyx_convert_string_from_py_std__in_string(PyObject *__pyx_v_o) { + Py_ssize_t __pyx_v_length; + char const *__pyx_v_data; + std::string __pyx_r; + char const *__pyx_t_1; + std::string __pyx_t_2; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + + /* "string.from_py":14 + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: + * cdef Py_ssize_t length = 0 # <<<<<<<<<<<<<< + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + * return string(data, length) + */ + __pyx_v_length = 0; + + /* "string.from_py":15 + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) # <<<<<<<<<<<<<< + * return string(data, length) + * + */ + __pyx_t_1 = __Pyx_PyObject_AsStringAndSize(__pyx_v_o, (&__pyx_v_length)); if (unlikely(__pyx_t_1 == ((char const *)NULL))) __PYX_ERR(1, 15, __pyx_L1_error) + __pyx_v_data = __pyx_t_1; + + /* "string.from_py":16 + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + * return string(data, length) # <<<<<<<<<<<<<< + * + * + */ + try { + __pyx_t_2 = std::string(__pyx_v_data, __pyx_v_length); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(1, 16, __pyx_L1_error) + } + __pyx_r = __pyx_t_2; + goto __pyx_L0; + + /* "string.from_py":13 + * + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: # <<<<<<<<<<<<<< + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("string.from_py.__pyx_convert_string_from_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_pretend_to_initialize(&__pyx_r); + __pyx_L0:; + return __pyx_r; +} + +/* "vector.from_py":45 + * + * @cname("__pyx_convert_vector_from_py_int") + * cdef vector[X] __pyx_convert_vector_from_py_int(object o) except *: # <<<<<<<<<<<<<< + * cdef vector[X] v + * for item in o: + */ + +static std::vector __pyx_convert_vector_from_py_int(PyObject *__pyx_v_o) { + std::vector __pyx_v_v; + PyObject *__pyx_v_item = NULL; + std::vector __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + Py_ssize_t __pyx_t_2; + PyObject *(*__pyx_t_3)(PyObject *); + PyObject *__pyx_t_4 = NULL; + int __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_vector_from_py_int", 1); + + /* "vector.from_py":47 + * cdef vector[X] __pyx_convert_vector_from_py_int(object o) except *: + * cdef vector[X] v + * for item in o: # <<<<<<<<<<<<<< + * v.push_back(item) + * return v + */ + if (likely(PyList_CheckExact(__pyx_v_o)) || PyTuple_CheckExact(__pyx_v_o)) { + __pyx_t_1 = __pyx_v_o; __Pyx_INCREF(__pyx_t_1); + __pyx_t_2 = 0; + __pyx_t_3 = NULL; + } else { + __pyx_t_2 = -1; __pyx_t_1 = PyObject_GetIter(__pyx_v_o); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 47, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 47, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_3)) { + if (likely(PyList_CheckExact(__pyx_t_1))) { + { + Py_ssize_t __pyx_temp = __Pyx_PyList_GET_SIZE(__pyx_t_1); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 47, __pyx_L1_error) + #endif + if (__pyx_t_2 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyList_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(1, 47, __pyx_L1_error) + #else + __pyx_t_4 = __Pyx_PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 47, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } else { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_1); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 47, __pyx_L1_error) + #endif + if (__pyx_t_2 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyTuple_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(1, 47, __pyx_L1_error) + #else + __pyx_t_4 = __Pyx_PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 47, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } + } else { + __pyx_t_4 = __pyx_t_3(__pyx_t_1); + if (unlikely(!__pyx_t_4)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(1, 47, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_4); + } + __Pyx_XDECREF_SET(__pyx_v_item, __pyx_t_4); + __pyx_t_4 = 0; + + /* "vector.from_py":48 + * cdef vector[X] v + * for item in o: + * v.push_back(item) # <<<<<<<<<<<<<< + * return v + * + */ + __pyx_t_5 = __Pyx_PyInt_As_int(__pyx_v_item); if (unlikely((__pyx_t_5 == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 48, __pyx_L1_error) + try { + __pyx_v_v.push_back(((int)__pyx_t_5)); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(1, 48, __pyx_L1_error) + } + + /* "vector.from_py":47 + * cdef vector[X] __pyx_convert_vector_from_py_int(object o) except *: + * cdef vector[X] v + * for item in o: # <<<<<<<<<<<<<< + * v.push_back(item) + * return v + */ + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "vector.from_py":49 + * for item in o: + * v.push_back(item) + * return v # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = __pyx_v_v; + goto __pyx_L0; + + /* "vector.from_py":45 + * + * @cname("__pyx_convert_vector_from_py_int") + * cdef vector[X] __pyx_convert_vector_from_py_int(object o) except *: # <<<<<<<<<<<<<< + * cdef vector[X] v + * for item in o: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("vector.from_py.__pyx_convert_vector_from_py_int", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_pretend_to_initialize(&__pyx_r); + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_item); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static std::vector __pyx_convert_vector_from_py_std_3a__3a_string(PyObject *__pyx_v_o) { + std::vector __pyx_v_v; + PyObject *__pyx_v_item = NULL; + std::vector __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + Py_ssize_t __pyx_t_2; + PyObject *(*__pyx_t_3)(PyObject *); + PyObject *__pyx_t_4 = NULL; + std::string __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_vector_from_py_std_3a__3a_string", 1); + + /* "vector.from_py":47 + * cdef vector[X] __pyx_convert_vector_from_py_std_3a__3a_string(object o) except *: + * cdef vector[X] v + * for item in o: # <<<<<<<<<<<<<< + * v.push_back(item) + * return v + */ + if (likely(PyList_CheckExact(__pyx_v_o)) || PyTuple_CheckExact(__pyx_v_o)) { + __pyx_t_1 = __pyx_v_o; __Pyx_INCREF(__pyx_t_1); + __pyx_t_2 = 0; + __pyx_t_3 = NULL; + } else { + __pyx_t_2 = -1; __pyx_t_1 = PyObject_GetIter(__pyx_v_o); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 47, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 47, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_3)) { + if (likely(PyList_CheckExact(__pyx_t_1))) { + { + Py_ssize_t __pyx_temp = __Pyx_PyList_GET_SIZE(__pyx_t_1); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 47, __pyx_L1_error) + #endif + if (__pyx_t_2 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyList_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(1, 47, __pyx_L1_error) + #else + __pyx_t_4 = __Pyx_PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 47, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } else { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_1); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 47, __pyx_L1_error) + #endif + if (__pyx_t_2 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyTuple_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(1, 47, __pyx_L1_error) + #else + __pyx_t_4 = __Pyx_PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 47, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } + } else { + __pyx_t_4 = __pyx_t_3(__pyx_t_1); + if (unlikely(!__pyx_t_4)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(1, 47, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_4); + } + __Pyx_XDECREF_SET(__pyx_v_item, __pyx_t_4); + __pyx_t_4 = 0; + + /* "vector.from_py":48 + * cdef vector[X] v + * for item in o: + * v.push_back(item) # <<<<<<<<<<<<<< + * return v + * + */ + __pyx_t_5 = __pyx_convert_string_from_py_std__in_string(__pyx_v_item); if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 48, __pyx_L1_error) + try { + __pyx_v_v.push_back(((std::string)__pyx_t_5)); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(1, 48, __pyx_L1_error) + } + + /* "vector.from_py":47 + * cdef vector[X] __pyx_convert_vector_from_py_std_3a__3a_string(object o) except *: + * cdef vector[X] v + * for item in o: # <<<<<<<<<<<<<< + * v.push_back(item) + * return v + */ + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "vector.from_py":49 + * for item in o: + * v.push_back(item) + * return v # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = __pyx_v_v; + goto __pyx_L0; + + /* "vector.from_py":45 + * + * @cname("__pyx_convert_vector_from_py_std_3a__3a_string") + * cdef vector[X] __pyx_convert_vector_from_py_std_3a__3a_string(object o) except *: # <<<<<<<<<<<<<< + * cdef vector[X] v + * for item in o: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("vector.from_py.__pyx_convert_vector_from_py_std_3a__3a_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_pretend_to_initialize(&__pyx_r); + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_item); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":131 + * cdef bint dtype_is_object + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, # <<<<<<<<<<<<<< + * mode="c", bint allocate_buffer=True): + * + */ + +/* Python wrapper */ +static int __pyx_array___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_array___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_shape = 0; + Py_ssize_t __pyx_v_itemsize; + PyObject *__pyx_v_format = 0; + PyObject *__pyx_v_mode = 0; + int __pyx_v_allocate_buffer; + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[5] = {0,0,0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_shape,&__pyx_n_s_itemsize,&__pyx_n_s_format,&__pyx_n_s_mode,&__pyx_n_s_allocate_buffer,0}; + values[3] = __Pyx_Arg_NewRef_VARARGS(((PyObject *)__pyx_n_s_c)); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 5: values[4] = __Pyx_Arg_VARARGS(__pyx_args, 4); + CYTHON_FALLTHROUGH; + case 4: values[3] = __Pyx_Arg_VARARGS(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_shape)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_itemsize)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 3, 5, 1); __PYX_ERR(1, 131, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_format)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 3, 5, 2); __PYX_ERR(1, 131, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 3: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_mode); + if (value) { values[3] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 4: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_allocate_buffer); + if (value) { values[4] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(1, 131, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 5: values[4] = __Pyx_Arg_VARARGS(__pyx_args, 4); + CYTHON_FALLTHROUGH; + case 4: values[3] = __Pyx_Arg_VARARGS(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_shape = ((PyObject*)values[0]); + __pyx_v_itemsize = __Pyx_PyIndex_AsSsize_t(values[1]); if (unlikely((__pyx_v_itemsize == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + __pyx_v_format = values[2]; + __pyx_v_mode = values[3]; + if (values[4]) { + __pyx_v_allocate_buffer = __Pyx_PyObject_IsTrue(values[4]); if (unlikely((__pyx_v_allocate_buffer == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 132, __pyx_L3_error) + } else { + + /* "View.MemoryView":132 + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, + * mode="c", bint allocate_buffer=True): # <<<<<<<<<<<<<< + * + * cdef int idx + */ + __pyx_v_allocate_buffer = ((int)1); + } + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 3, 5, __pyx_nargs); __PYX_ERR(1, 131, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.array.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_shape), (&PyTuple_Type), 1, "shape", 1))) __PYX_ERR(1, 131, __pyx_L1_error) + if (unlikely(((PyObject *)__pyx_v_format) == Py_None)) { + PyErr_Format(PyExc_TypeError, "Argument '%.200s' must not be None", "format"); __PYX_ERR(1, 131, __pyx_L1_error) + } + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array___cinit__(((struct __pyx_array_obj *)__pyx_v_self), __pyx_v_shape, __pyx_v_itemsize, __pyx_v_format, __pyx_v_mode, __pyx_v_allocate_buffer); + + /* "View.MemoryView":131 + * cdef bint dtype_is_object + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, # <<<<<<<<<<<<<< + * mode="c", bint allocate_buffer=True): + * + */ + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = -1; + __pyx_L0:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array___cinit__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_shape, Py_ssize_t __pyx_v_itemsize, PyObject *__pyx_v_format, PyObject *__pyx_v_mode, int __pyx_v_allocate_buffer) { + int __pyx_v_idx; + Py_ssize_t __pyx_v_dim; + char __pyx_v_order; + int __pyx_r; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + int __pyx_t_7; + char *__pyx_t_8; + Py_ssize_t __pyx_t_9; + Py_UCS4 __pyx_t_10; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__cinit__", 0); + __Pyx_INCREF(__pyx_v_format); + + /* "View.MemoryView":137 + * cdef Py_ssize_t dim + * + * self.ndim = len(shape) # <<<<<<<<<<<<<< + * self.itemsize = itemsize + * + */ + if (unlikely(__pyx_v_shape == Py_None)) { + PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); + __PYX_ERR(1, 137, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_PyTuple_GET_SIZE(__pyx_v_shape); if (unlikely(__pyx_t_1 == ((Py_ssize_t)-1))) __PYX_ERR(1, 137, __pyx_L1_error) + __pyx_v_self->ndim = ((int)__pyx_t_1); + + /* "View.MemoryView":138 + * + * self.ndim = len(shape) + * self.itemsize = itemsize # <<<<<<<<<<<<<< + * + * if not self.ndim: + */ + __pyx_v_self->itemsize = __pyx_v_itemsize; + + /* "View.MemoryView":140 + * self.itemsize = itemsize + * + * if not self.ndim: # <<<<<<<<<<<<<< + * raise ValueError, "Empty shape tuple for cython.array" + * + */ + __pyx_t_2 = (!(__pyx_v_self->ndim != 0)); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":141 + * + * if not self.ndim: + * raise ValueError, "Empty shape tuple for cython.array" # <<<<<<<<<<<<<< + * + * if itemsize <= 0: + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Empty_shape_tuple_for_cython_arr, 0, 0); + __PYX_ERR(1, 141, __pyx_L1_error) + + /* "View.MemoryView":140 + * self.itemsize = itemsize + * + * if not self.ndim: # <<<<<<<<<<<<<< + * raise ValueError, "Empty shape tuple for cython.array" + * + */ + } + + /* "View.MemoryView":143 + * raise ValueError, "Empty shape tuple for cython.array" + * + * if itemsize <= 0: # <<<<<<<<<<<<<< + * raise ValueError, "itemsize <= 0 for cython.array" + * + */ + __pyx_t_2 = (__pyx_v_itemsize <= 0); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":144 + * + * if itemsize <= 0: + * raise ValueError, "itemsize <= 0 for cython.array" # <<<<<<<<<<<<<< + * + * if not isinstance(format, bytes): + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_itemsize_0_for_cython_array, 0, 0); + __PYX_ERR(1, 144, __pyx_L1_error) + + /* "View.MemoryView":143 + * raise ValueError, "Empty shape tuple for cython.array" + * + * if itemsize <= 0: # <<<<<<<<<<<<<< + * raise ValueError, "itemsize <= 0 for cython.array" + * + */ + } + + /* "View.MemoryView":146 + * raise ValueError, "itemsize <= 0 for cython.array" + * + * if not isinstance(format, bytes): # <<<<<<<<<<<<<< + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string + */ + __pyx_t_2 = PyBytes_Check(__pyx_v_format); + __pyx_t_3 = (!__pyx_t_2); + if (__pyx_t_3) { + + /* "View.MemoryView":147 + * + * if not isinstance(format, bytes): + * format = format.encode('ASCII') # <<<<<<<<<<<<<< + * self._format = format # keep a reference to the byte string + * self.format = self._format + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_format, __pyx_n_s_encode); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 147, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = NULL; + __pyx_t_7 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_6 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_6)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_6); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_7 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_6, __pyx_n_s_ASCII}; + __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_7, 1+__pyx_t_7); + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 147, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + __Pyx_DECREF_SET(__pyx_v_format, __pyx_t_4); + __pyx_t_4 = 0; + + /* "View.MemoryView":146 + * raise ValueError, "itemsize <= 0 for cython.array" + * + * if not isinstance(format, bytes): # <<<<<<<<<<<<<< + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string + */ + } + + /* "View.MemoryView":148 + * if not isinstance(format, bytes): + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string # <<<<<<<<<<<<<< + * self.format = self._format + * + */ + if (!(likely(PyBytes_CheckExact(__pyx_v_format))||((__pyx_v_format) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_v_format))) __PYX_ERR(1, 148, __pyx_L1_error) + __pyx_t_4 = __pyx_v_format; + __Pyx_INCREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + __Pyx_GOTREF(__pyx_v_self->_format); + __Pyx_DECREF(__pyx_v_self->_format); + __pyx_v_self->_format = ((PyObject*)__pyx_t_4); + __pyx_t_4 = 0; + + /* "View.MemoryView":149 + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string + * self.format = self._format # <<<<<<<<<<<<<< + * + * + */ + if (unlikely(__pyx_v_self->_format == Py_None)) { + PyErr_SetString(PyExc_TypeError, "expected bytes, NoneType found"); + __PYX_ERR(1, 149, __pyx_L1_error) + } + __pyx_t_8 = __Pyx_PyBytes_AsWritableString(__pyx_v_self->_format); if (unlikely((!__pyx_t_8) && PyErr_Occurred())) __PYX_ERR(1, 149, __pyx_L1_error) + __pyx_v_self->format = __pyx_t_8; + + /* "View.MemoryView":152 + * + * + * self._shape = PyObject_Malloc(sizeof(Py_ssize_t)*self.ndim*2) # <<<<<<<<<<<<<< + * self._strides = self._shape + self.ndim + * + */ + __pyx_v_self->_shape = ((Py_ssize_t *)PyObject_Malloc((((sizeof(Py_ssize_t)) * __pyx_v_self->ndim) * 2))); + + /* "View.MemoryView":153 + * + * self._shape = PyObject_Malloc(sizeof(Py_ssize_t)*self.ndim*2) + * self._strides = self._shape + self.ndim # <<<<<<<<<<<<<< + * + * if not self._shape: + */ + __pyx_v_self->_strides = (__pyx_v_self->_shape + __pyx_v_self->ndim); + + /* "View.MemoryView":155 + * self._strides = self._shape + self.ndim + * + * if not self._shape: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate shape and strides." + * + */ + __pyx_t_3 = (!(__pyx_v_self->_shape != 0)); + if (unlikely(__pyx_t_3)) { + + /* "View.MemoryView":156 + * + * if not self._shape: + * raise MemoryError, "unable to allocate shape and strides." # <<<<<<<<<<<<<< + * + * + */ + __Pyx_Raise(__pyx_builtin_MemoryError, __pyx_kp_s_unable_to_allocate_shape_and_str, 0, 0); + __PYX_ERR(1, 156, __pyx_L1_error) + + /* "View.MemoryView":155 + * self._strides = self._shape + self.ndim + * + * if not self._shape: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate shape and strides." + * + */ + } + + /* "View.MemoryView":159 + * + * + * for idx, dim in enumerate(shape): # <<<<<<<<<<<<<< + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + */ + __pyx_t_7 = 0; + __pyx_t_4 = __pyx_v_shape; __Pyx_INCREF(__pyx_t_4); + __pyx_t_1 = 0; + for (;;) { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_4); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 159, __pyx_L1_error) + #endif + if (__pyx_t_1 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_5 = PyTuple_GET_ITEM(__pyx_t_4, __pyx_t_1); __Pyx_INCREF(__pyx_t_5); __pyx_t_1++; if (unlikely((0 < 0))) __PYX_ERR(1, 159, __pyx_L1_error) + #else + __pyx_t_5 = __Pyx_PySequence_ITEM(__pyx_t_4, __pyx_t_1); __pyx_t_1++; if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 159, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + #endif + __pyx_t_9 = __Pyx_PyIndex_AsSsize_t(__pyx_t_5); if (unlikely((__pyx_t_9 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 159, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_v_dim = __pyx_t_9; + __pyx_v_idx = __pyx_t_7; + __pyx_t_7 = (__pyx_t_7 + 1); + + /* "View.MemoryView":160 + * + * for idx, dim in enumerate(shape): + * if dim <= 0: # <<<<<<<<<<<<<< + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + * self._shape[idx] = dim + */ + __pyx_t_3 = (__pyx_v_dim <= 0); + if (unlikely(__pyx_t_3)) { + + /* "View.MemoryView":161 + * for idx, dim in enumerate(shape): + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." # <<<<<<<<<<<<<< + * self._shape[idx] = dim + * + */ + __pyx_t_5 = PyTuple_New(5); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_9 = 0; + __pyx_t_10 = 127; + __Pyx_INCREF(__pyx_kp_u_Invalid_shape_in_axis); + __pyx_t_9 += 22; + __Pyx_GIVEREF(__pyx_kp_u_Invalid_shape_in_axis); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_kp_u_Invalid_shape_in_axis); + __pyx_t_6 = __Pyx_PyUnicode_From_int(__pyx_v_idx, 0, ' ', 'd'); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_9 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_6); + __Pyx_GIVEREF(__pyx_t_6); + PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_6); + __pyx_t_6 = 0; + __Pyx_INCREF(__pyx_kp_u_); + __pyx_t_9 += 2; + __Pyx_GIVEREF(__pyx_kp_u_); + PyTuple_SET_ITEM(__pyx_t_5, 2, __pyx_kp_u_); + __pyx_t_6 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_dim, 0, ' ', 'd'); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_9 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_6); + __Pyx_GIVEREF(__pyx_t_6); + PyTuple_SET_ITEM(__pyx_t_5, 3, __pyx_t_6); + __pyx_t_6 = 0; + __Pyx_INCREF(__pyx_kp_u__2); + __pyx_t_9 += 1; + __Pyx_GIVEREF(__pyx_kp_u__2); + PyTuple_SET_ITEM(__pyx_t_5, 4, __pyx_kp_u__2); + __pyx_t_6 = __Pyx_PyUnicode_Join(__pyx_t_5, 5, __pyx_t_9, __pyx_t_10); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_t_6, 0, 0); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __PYX_ERR(1, 161, __pyx_L1_error) + + /* "View.MemoryView":160 + * + * for idx, dim in enumerate(shape): + * if dim <= 0: # <<<<<<<<<<<<<< + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + * self._shape[idx] = dim + */ + } + + /* "View.MemoryView":162 + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + * self._shape[idx] = dim # <<<<<<<<<<<<<< + * + * cdef char order + */ + (__pyx_v_self->_shape[__pyx_v_idx]) = __pyx_v_dim; + + /* "View.MemoryView":159 + * + * + * for idx, dim in enumerate(shape): # <<<<<<<<<<<<<< + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + */ + } + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "View.MemoryView":165 + * + * cdef char order + * if mode == 'c': # <<<<<<<<<<<<<< + * order = b'C' + * self.mode = u'c' + */ + __pyx_t_3 = (__Pyx_PyString_Equals(__pyx_v_mode, __pyx_n_s_c, Py_EQ)); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(1, 165, __pyx_L1_error) + if (__pyx_t_3) { + + /* "View.MemoryView":166 + * cdef char order + * if mode == 'c': + * order = b'C' # <<<<<<<<<<<<<< + * self.mode = u'c' + * elif mode == 'fortran': + */ + __pyx_v_order = 'C'; + + /* "View.MemoryView":167 + * if mode == 'c': + * order = b'C' + * self.mode = u'c' # <<<<<<<<<<<<<< + * elif mode == 'fortran': + * order = b'F' + */ + __Pyx_INCREF(__pyx_n_u_c); + __Pyx_GIVEREF(__pyx_n_u_c); + __Pyx_GOTREF(__pyx_v_self->mode); + __Pyx_DECREF(__pyx_v_self->mode); + __pyx_v_self->mode = __pyx_n_u_c; + + /* "View.MemoryView":165 + * + * cdef char order + * if mode == 'c': # <<<<<<<<<<<<<< + * order = b'C' + * self.mode = u'c' + */ + goto __pyx_L11; + } + + /* "View.MemoryView":168 + * order = b'C' + * self.mode = u'c' + * elif mode == 'fortran': # <<<<<<<<<<<<<< + * order = b'F' + * self.mode = u'fortran' + */ + __pyx_t_3 = (__Pyx_PyString_Equals(__pyx_v_mode, __pyx_n_s_fortran, Py_EQ)); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(1, 168, __pyx_L1_error) + if (likely(__pyx_t_3)) { + + /* "View.MemoryView":169 + * self.mode = u'c' + * elif mode == 'fortran': + * order = b'F' # <<<<<<<<<<<<<< + * self.mode = u'fortran' + * else: + */ + __pyx_v_order = 'F'; + + /* "View.MemoryView":170 + * elif mode == 'fortran': + * order = b'F' + * self.mode = u'fortran' # <<<<<<<<<<<<<< + * else: + * raise ValueError, f"Invalid mode, expected 'c' or 'fortran', got {mode}" + */ + __Pyx_INCREF(__pyx_n_u_fortran); + __Pyx_GIVEREF(__pyx_n_u_fortran); + __Pyx_GOTREF(__pyx_v_self->mode); + __Pyx_DECREF(__pyx_v_self->mode); + __pyx_v_self->mode = __pyx_n_u_fortran; + + /* "View.MemoryView":168 + * order = b'C' + * self.mode = u'c' + * elif mode == 'fortran': # <<<<<<<<<<<<<< + * order = b'F' + * self.mode = u'fortran' + */ + goto __pyx_L11; + } + + /* "View.MemoryView":172 + * self.mode = u'fortran' + * else: + * raise ValueError, f"Invalid mode, expected 'c' or 'fortran', got {mode}" # <<<<<<<<<<<<<< + * + * self.len = fill_contig_strides_array(self._shape, self._strides, itemsize, self.ndim, order) + */ + /*else*/ { + __pyx_t_4 = __Pyx_PyObject_FormatSimple(__pyx_v_mode, __pyx_empty_unicode); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 172, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_6 = __Pyx_PyUnicode_Concat(__pyx_kp_u_Invalid_mode_expected_c_or_fortr, __pyx_t_4); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 172, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_t_6, 0, 0); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __PYX_ERR(1, 172, __pyx_L1_error) + } + __pyx_L11:; + + /* "View.MemoryView":174 + * raise ValueError, f"Invalid mode, expected 'c' or 'fortran', got {mode}" + * + * self.len = fill_contig_strides_array(self._shape, self._strides, itemsize, self.ndim, order) # <<<<<<<<<<<<<< + * + * self.free_data = allocate_buffer + */ + __pyx_v_self->len = __pyx_fill_contig_strides_array(__pyx_v_self->_shape, __pyx_v_self->_strides, __pyx_v_itemsize, __pyx_v_self->ndim, __pyx_v_order); + + /* "View.MemoryView":176 + * self.len = fill_contig_strides_array(self._shape, self._strides, itemsize, self.ndim, order) + * + * self.free_data = allocate_buffer # <<<<<<<<<<<<<< + * self.dtype_is_object = format == b'O' + * + */ + __pyx_v_self->free_data = __pyx_v_allocate_buffer; + + /* "View.MemoryView":177 + * + * self.free_data = allocate_buffer + * self.dtype_is_object = format == b'O' # <<<<<<<<<<<<<< + * + * if allocate_buffer: + */ + __pyx_t_6 = PyObject_RichCompare(__pyx_v_format, __pyx_n_b_O, Py_EQ); __Pyx_XGOTREF(__pyx_t_6); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 177, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_IsTrue(__pyx_t_6); if (unlikely((__pyx_t_3 == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 177, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __pyx_v_self->dtype_is_object = __pyx_t_3; + + /* "View.MemoryView":179 + * self.dtype_is_object = format == b'O' + * + * if allocate_buffer: # <<<<<<<<<<<<<< + * _allocate_buffer(self) + * + */ + if (__pyx_v_allocate_buffer) { + + /* "View.MemoryView":180 + * + * if allocate_buffer: + * _allocate_buffer(self) # <<<<<<<<<<<<<< + * + * @cname('getbuffer') + */ + __pyx_t_7 = __pyx_array_allocate_buffer(__pyx_v_self); if (unlikely(__pyx_t_7 == ((int)-1))) __PYX_ERR(1, 180, __pyx_L1_error) + + /* "View.MemoryView":179 + * self.dtype_is_object = format == b'O' + * + * if allocate_buffer: # <<<<<<<<<<<<<< + * _allocate_buffer(self) + * + */ + } + + /* "View.MemoryView":131 + * cdef bint dtype_is_object + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, # <<<<<<<<<<<<<< + * mode="c", bint allocate_buffer=True): + * + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("View.MemoryView.array.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_format); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":182 + * _allocate_buffer(self) + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + */ + +/* Python wrapper */ +CYTHON_UNUSED static int __pyx_array_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +CYTHON_UNUSED static int __pyx_array_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getbuffer__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_2__getbuffer__(((struct __pyx_array_obj *)__pyx_v_self), ((Py_buffer *)__pyx_v_info), ((int)__pyx_v_flags)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_2__getbuffer__(struct __pyx_array_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + int __pyx_v_bufmode; + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + char *__pyx_t_2; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + Py_ssize_t *__pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + if (unlikely(__pyx_v_info == NULL)) { + PyErr_SetString(PyExc_BufferError, "PyObject_GetBuffer: view==NULL argument is obsolete"); + return -1; + } + __Pyx_RefNannySetupContext("__getbuffer__", 0); + __pyx_v_info->obj = Py_None; __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(__pyx_v_info->obj); + + /* "View.MemoryView":184 + * @cname('getbuffer') + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 # <<<<<<<<<<<<<< + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": + */ + __pyx_v_bufmode = -1; + + /* "View.MemoryView":185 + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): # <<<<<<<<<<<<<< + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + */ + __pyx_t_1 = ((__pyx_v_flags & ((PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS) | PyBUF_ANY_CONTIGUOUS)) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":186 + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": # <<<<<<<<<<<<<< + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": + */ + __pyx_t_1 = (__Pyx_PyUnicode_Equals(__pyx_v_self->mode, __pyx_n_u_c, Py_EQ)); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 186, __pyx_L1_error) + if (__pyx_t_1) { + + /* "View.MemoryView":187 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS # <<<<<<<<<<<<<< + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + */ + __pyx_v_bufmode = (PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS); + + /* "View.MemoryView":186 + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": # <<<<<<<<<<<<<< + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": + */ + goto __pyx_L4; + } + + /* "View.MemoryView":188 + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": # <<<<<<<<<<<<<< + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): + */ + __pyx_t_1 = (__Pyx_PyUnicode_Equals(__pyx_v_self->mode, __pyx_n_u_fortran, Py_EQ)); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 188, __pyx_L1_error) + if (__pyx_t_1) { + + /* "View.MemoryView":189 + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS # <<<<<<<<<<<<<< + * if not (flags & bufmode): + * raise ValueError, "Can only create a buffer that is contiguous in memory." + */ + __pyx_v_bufmode = (PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS); + + /* "View.MemoryView":188 + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": # <<<<<<<<<<<<<< + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): + */ + } + __pyx_L4:; + + /* "View.MemoryView":190 + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): # <<<<<<<<<<<<<< + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data + */ + __pyx_t_1 = (!((__pyx_v_flags & __pyx_v_bufmode) != 0)); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":191 + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): + * raise ValueError, "Can only create a buffer that is contiguous in memory." # <<<<<<<<<<<<<< + * info.buf = self.data + * info.len = self.len + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Can_only_create_a_buffer_that_is, 0, 0); + __PYX_ERR(1, 191, __pyx_L1_error) + + /* "View.MemoryView":190 + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): # <<<<<<<<<<<<<< + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data + */ + } + + /* "View.MemoryView":185 + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): # <<<<<<<<<<<<<< + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + */ + } + + /* "View.MemoryView":192 + * if not (flags & bufmode): + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data # <<<<<<<<<<<<<< + * info.len = self.len + * + */ + __pyx_t_2 = __pyx_v_self->data; + __pyx_v_info->buf = __pyx_t_2; + + /* "View.MemoryView":193 + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data + * info.len = self.len # <<<<<<<<<<<<<< + * + * if flags & PyBUF_STRIDES: + */ + __pyx_t_3 = __pyx_v_self->len; + __pyx_v_info->len = __pyx_t_3; + + /* "View.MemoryView":195 + * info.len = self.len + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.ndim = self.ndim + * info.shape = self._shape + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_STRIDES) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":196 + * + * if flags & PyBUF_STRIDES: + * info.ndim = self.ndim # <<<<<<<<<<<<<< + * info.shape = self._shape + * info.strides = self._strides + */ + __pyx_t_4 = __pyx_v_self->ndim; + __pyx_v_info->ndim = __pyx_t_4; + + /* "View.MemoryView":197 + * if flags & PyBUF_STRIDES: + * info.ndim = self.ndim + * info.shape = self._shape # <<<<<<<<<<<<<< + * info.strides = self._strides + * else: + */ + __pyx_t_5 = __pyx_v_self->_shape; + __pyx_v_info->shape = __pyx_t_5; + + /* "View.MemoryView":198 + * info.ndim = self.ndim + * info.shape = self._shape + * info.strides = self._strides # <<<<<<<<<<<<<< + * else: + * info.ndim = 1 + */ + __pyx_t_5 = __pyx_v_self->_strides; + __pyx_v_info->strides = __pyx_t_5; + + /* "View.MemoryView":195 + * info.len = self.len + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.ndim = self.ndim + * info.shape = self._shape + */ + goto __pyx_L6; + } + + /* "View.MemoryView":200 + * info.strides = self._strides + * else: + * info.ndim = 1 # <<<<<<<<<<<<<< + * info.shape = &self.len if flags & PyBUF_ND else NULL + * info.strides = NULL + */ + /*else*/ { + __pyx_v_info->ndim = 1; + + /* "View.MemoryView":201 + * else: + * info.ndim = 1 + * info.shape = &self.len if flags & PyBUF_ND else NULL # <<<<<<<<<<<<<< + * info.strides = NULL + * + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_ND) != 0); + if (__pyx_t_1) { + __pyx_t_5 = (&__pyx_v_self->len); + } else { + __pyx_t_5 = NULL; + } + __pyx_v_info->shape = __pyx_t_5; + + /* "View.MemoryView":202 + * info.ndim = 1 + * info.shape = &self.len if flags & PyBUF_ND else NULL + * info.strides = NULL # <<<<<<<<<<<<<< + * + * info.suboffsets = NULL + */ + __pyx_v_info->strides = NULL; + } + __pyx_L6:; + + /* "View.MemoryView":204 + * info.strides = NULL + * + * info.suboffsets = NULL # <<<<<<<<<<<<<< + * info.itemsize = self.itemsize + * info.readonly = 0 + */ + __pyx_v_info->suboffsets = NULL; + + /* "View.MemoryView":205 + * + * info.suboffsets = NULL + * info.itemsize = self.itemsize # <<<<<<<<<<<<<< + * info.readonly = 0 + * info.format = self.format if flags & PyBUF_FORMAT else NULL + */ + __pyx_t_3 = __pyx_v_self->itemsize; + __pyx_v_info->itemsize = __pyx_t_3; + + /* "View.MemoryView":206 + * info.suboffsets = NULL + * info.itemsize = self.itemsize + * info.readonly = 0 # <<<<<<<<<<<<<< + * info.format = self.format if flags & PyBUF_FORMAT else NULL + * info.obj = self + */ + __pyx_v_info->readonly = 0; + + /* "View.MemoryView":207 + * info.itemsize = self.itemsize + * info.readonly = 0 + * info.format = self.format if flags & PyBUF_FORMAT else NULL # <<<<<<<<<<<<<< + * info.obj = self + * + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_FORMAT) != 0); + if (__pyx_t_1) { + __pyx_t_2 = __pyx_v_self->format; + } else { + __pyx_t_2 = NULL; + } + __pyx_v_info->format = __pyx_t_2; + + /* "View.MemoryView":208 + * info.readonly = 0 + * info.format = self.format if flags & PyBUF_FORMAT else NULL + * info.obj = self # <<<<<<<<<<<<<< + * + * def __dealloc__(array self): + */ + __Pyx_INCREF((PyObject *)__pyx_v_self); + __Pyx_GIVEREF((PyObject *)__pyx_v_self); + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); + __pyx_v_info->obj = ((PyObject *)__pyx_v_self); + + /* "View.MemoryView":182 + * _allocate_buffer(self) + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.array.__getbuffer__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + if (__pyx_v_info->obj != NULL) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + goto __pyx_L2; + __pyx_L0:; + if (__pyx_v_info->obj == Py_None) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + __pyx_L2:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":210 + * info.obj = self + * + * def __dealloc__(array self): # <<<<<<<<<<<<<< + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + */ + +/* Python wrapper */ +static void __pyx_array___dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_array___dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_array___pyx_pf_15View_dot_MemoryView_5array_4__dealloc__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_array___pyx_pf_15View_dot_MemoryView_5array_4__dealloc__(struct __pyx_array_obj *__pyx_v_self) { + int __pyx_t_1; + int __pyx_t_2; + + /* "View.MemoryView":211 + * + * def __dealloc__(array self): + * if self.callback_free_data != NULL: # <<<<<<<<<<<<<< + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + */ + __pyx_t_1 = (__pyx_v_self->callback_free_data != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":212 + * def __dealloc__(array self): + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) # <<<<<<<<<<<<<< + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: + */ + __pyx_v_self->callback_free_data(__pyx_v_self->data); + + /* "View.MemoryView":211 + * + * def __dealloc__(array self): + * if self.callback_free_data != NULL: # <<<<<<<<<<<<<< + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":213 + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: # <<<<<<<<<<<<<< + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + */ + if (__pyx_v_self->free_data) { + } else { + __pyx_t_1 = __pyx_v_self->free_data; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_2 = (__pyx_v_self->data != NULL); + __pyx_t_1 = __pyx_t_2; + __pyx_L4_bool_binop_done:; + if (__pyx_t_1) { + + /* "View.MemoryView":214 + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) + */ + if (__pyx_v_self->dtype_is_object) { + + /* "View.MemoryView":215 + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) # <<<<<<<<<<<<<< + * free(self.data) + * PyObject_Free(self._shape) + */ + __pyx_memoryview_refcount_objects_in_slice(__pyx_v_self->data, __pyx_v_self->_shape, __pyx_v_self->_strides, __pyx_v_self->ndim, 0); + + /* "View.MemoryView":214 + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) + */ + } + + /* "View.MemoryView":216 + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) # <<<<<<<<<<<<<< + * PyObject_Free(self._shape) + * + */ + free(__pyx_v_self->data); + + /* "View.MemoryView":213 + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: # <<<<<<<<<<<<<< + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + */ + } + __pyx_L3:; + + /* "View.MemoryView":217 + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) + * PyObject_Free(self._shape) # <<<<<<<<<<<<<< + * + * @property + */ + PyObject_Free(__pyx_v_self->_shape); + + /* "View.MemoryView":210 + * info.obj = self + * + * def __dealloc__(array self): # <<<<<<<<<<<<<< + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + */ + + /* function exit code */ +} + +/* "View.MemoryView":219 + * PyObject_Free(self._shape) + * + * @property # <<<<<<<<<<<<<< + * def memview(self): + * return self.get_memview() + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_5array_7memview_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_5array_7memview_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_5array_7memview___get__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_5array_7memview___get__(struct __pyx_array_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":221 + * @property + * def memview(self): + * return self.get_memview() # <<<<<<<<<<<<<< + * + * @cname('get_memview') + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = ((struct __pyx_vtabstruct_array *)__pyx_v_self->__pyx_vtab)->get_memview(__pyx_v_self); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 221, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":219 + * PyObject_Free(self._shape) + * + * @property # <<<<<<<<<<<<<< + * def memview(self): + * return self.get_memview() + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.array.memview.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":224 + * + * @cname('get_memview') + * cdef get_memview(self): # <<<<<<<<<<<<<< + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE + * return memoryview(self, flags, self.dtype_is_object) + */ + +static PyObject *__pyx_array_get_memview(struct __pyx_array_obj *__pyx_v_self) { + int __pyx_v_flags; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_memview", 1); + + /* "View.MemoryView":225 + * @cname('get_memview') + * cdef get_memview(self): + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE # <<<<<<<<<<<<<< + * return memoryview(self, flags, self.dtype_is_object) + * + */ + __pyx_v_flags = ((PyBUF_ANY_CONTIGUOUS | PyBUF_FORMAT) | PyBUF_WRITABLE); + + /* "View.MemoryView":226 + * cdef get_memview(self): + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE + * return memoryview(self, flags, self.dtype_is_object) # <<<<<<<<<<<<<< + * + * def __len__(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_flags); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_v_self->dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF((PyObject *)__pyx_v_self); + __Pyx_GIVEREF((PyObject *)__pyx_v_self); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, ((PyObject *)__pyx_v_self))) __PYX_ERR(1, 226, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1)) __PYX_ERR(1, 226, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_t_2)) __PYX_ERR(1, 226, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_Call(((PyObject *)__pyx_memoryview_type), __pyx_t_3, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":224 + * + * @cname('get_memview') + * cdef get_memview(self): # <<<<<<<<<<<<<< + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE + * return memoryview(self, flags, self.dtype_is_object) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.array.get_memview", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":228 + * return memoryview(self, flags, self.dtype_is_object) + * + * def __len__(self): # <<<<<<<<<<<<<< + * return self._shape[0] + * + */ + +/* Python wrapper */ +static Py_ssize_t __pyx_array___len__(PyObject *__pyx_v_self); /*proto*/ +static Py_ssize_t __pyx_array___len__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + Py_ssize_t __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__len__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_6__len__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static Py_ssize_t __pyx_array___pyx_pf_15View_dot_MemoryView_5array_6__len__(struct __pyx_array_obj *__pyx_v_self) { + Py_ssize_t __pyx_r; + + /* "View.MemoryView":229 + * + * def __len__(self): + * return self._shape[0] # <<<<<<<<<<<<<< + * + * def __getattr__(self, attr): + */ + __pyx_r = (__pyx_v_self->_shape[0]); + goto __pyx_L0; + + /* "View.MemoryView":228 + * return memoryview(self, flags, self.dtype_is_object) + * + * def __len__(self): # <<<<<<<<<<<<<< + * return self._shape[0] + * + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":231 + * return self._shape[0] + * + * def __getattr__(self, attr): # <<<<<<<<<<<<<< + * return getattr(self.memview, attr) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_array___getattr__(PyObject *__pyx_v_self, PyObject *__pyx_v_attr); /*proto*/ +static PyObject *__pyx_array___getattr__(PyObject *__pyx_v_self, PyObject *__pyx_v_attr) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getattr__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_8__getattr__(((struct __pyx_array_obj *)__pyx_v_self), ((PyObject *)__pyx_v_attr)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_8__getattr__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_attr) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__getattr__", 1); + + /* "View.MemoryView":232 + * + * def __getattr__(self, attr): + * return getattr(self.memview, attr) # <<<<<<<<<<<<<< + * + * def __getitem__(self, item): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_memview); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 232, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_GetAttr(__pyx_t_1, __pyx_v_attr); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 232, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":231 + * return self._shape[0] + * + * def __getattr__(self, attr): # <<<<<<<<<<<<<< + * return getattr(self.memview, attr) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.array.__getattr__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":234 + * return getattr(self.memview, attr) + * + * def __getitem__(self, item): # <<<<<<<<<<<<<< + * return self.memview[item] + * + */ + +/* Python wrapper */ +static PyObject *__pyx_array___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item); /*proto*/ +static PyObject *__pyx_array___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getitem__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_10__getitem__(((struct __pyx_array_obj *)__pyx_v_self), ((PyObject *)__pyx_v_item)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_10__getitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__getitem__", 1); + + /* "View.MemoryView":235 + * + * def __getitem__(self, item): + * return self.memview[item] # <<<<<<<<<<<<<< + * + * def __setitem__(self, item, value): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_memview); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 235, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_t_1, __pyx_v_item); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 235, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":234 + * return getattr(self.memview, attr) + * + * def __getitem__(self, item): # <<<<<<<<<<<<<< + * return self.memview[item] + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.array.__getitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":237 + * return self.memview[item] + * + * def __setitem__(self, item, value): # <<<<<<<<<<<<<< + * self.memview[item] = value + * + */ + +/* Python wrapper */ +static int __pyx_array___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value); /*proto*/ +static int __pyx_array___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setitem__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_12__setitem__(((struct __pyx_array_obj *)__pyx_v_self), ((PyObject *)__pyx_v_item), ((PyObject *)__pyx_v_value)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_12__setitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setitem__", 1); + + /* "View.MemoryView":238 + * + * def __setitem__(self, item, value): + * self.memview[item] = value # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_memview); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 238, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyObject_SetItem(__pyx_t_1, __pyx_v_item, __pyx_v_value) < 0))) __PYX_ERR(1, 238, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "View.MemoryView":237 + * return self.memview[item] + * + * def __setitem__(self, item, value): # <<<<<<<<<<<<<< + * self.memview[item] = value + * + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.array.__setitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_array_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_array_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_array___reduce_cython__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_array___reduce_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.array.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_array_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_array_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.array.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_array_2__setstate_cython__(((struct __pyx_array_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_array_2__setstate_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.array.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":248 + * + * @cname("__pyx_array_allocate_buffer") + * cdef int _allocate_buffer(array self) except -1: # <<<<<<<<<<<<<< + * + * + */ + +static int __pyx_array_allocate_buffer(struct __pyx_array_obj *__pyx_v_self) { + Py_ssize_t __pyx_v_i; + PyObject **__pyx_v_p; + int __pyx_r; + int __pyx_t_1; + Py_ssize_t __pyx_t_2; + Py_ssize_t __pyx_t_3; + Py_ssize_t __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + + /* "View.MemoryView":254 + * cdef PyObject **p + * + * self.free_data = True # <<<<<<<<<<<<<< + * self.data = malloc(self.len) + * if not self.data: + */ + __pyx_v_self->free_data = 1; + + /* "View.MemoryView":255 + * + * self.free_data = True + * self.data = malloc(self.len) # <<<<<<<<<<<<<< + * if not self.data: + * raise MemoryError, "unable to allocate array data." + */ + __pyx_v_self->data = ((char *)malloc(__pyx_v_self->len)); + + /* "View.MemoryView":256 + * self.free_data = True + * self.data = malloc(self.len) + * if not self.data: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate array data." + * + */ + __pyx_t_1 = (!(__pyx_v_self->data != 0)); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":257 + * self.data = malloc(self.len) + * if not self.data: + * raise MemoryError, "unable to allocate array data." # <<<<<<<<<<<<<< + * + * if self.dtype_is_object: + */ + __Pyx_Raise(__pyx_builtin_MemoryError, __pyx_kp_s_unable_to_allocate_array_data, 0, 0); + __PYX_ERR(1, 257, __pyx_L1_error) + + /* "View.MemoryView":256 + * self.free_data = True + * self.data = malloc(self.len) + * if not self.data: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate array data." + * + */ + } + + /* "View.MemoryView":259 + * raise MemoryError, "unable to allocate array data." + * + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * p = self.data + * for i in range(self.len // self.itemsize): + */ + if (__pyx_v_self->dtype_is_object) { + + /* "View.MemoryView":260 + * + * if self.dtype_is_object: + * p = self.data # <<<<<<<<<<<<<< + * for i in range(self.len // self.itemsize): + * p[i] = Py_None + */ + __pyx_v_p = ((PyObject **)__pyx_v_self->data); + + /* "View.MemoryView":261 + * if self.dtype_is_object: + * p = self.data + * for i in range(self.len // self.itemsize): # <<<<<<<<<<<<<< + * p[i] = Py_None + * Py_INCREF(Py_None) + */ + if (unlikely(__pyx_v_self->itemsize == 0)) { + PyErr_SetString(PyExc_ZeroDivisionError, "integer division or modulo by zero"); + __PYX_ERR(1, 261, __pyx_L1_error) + } + else if (sizeof(Py_ssize_t) == sizeof(long) && (!(((Py_ssize_t)-1) > 0)) && unlikely(__pyx_v_self->itemsize == (Py_ssize_t)-1) && unlikely(__Pyx_UNARY_NEG_WOULD_OVERFLOW(__pyx_v_self->len))) { + PyErr_SetString(PyExc_OverflowError, "value too large to perform division"); + __PYX_ERR(1, 261, __pyx_L1_error) + } + __pyx_t_2 = __Pyx_div_Py_ssize_t(__pyx_v_self->len, __pyx_v_self->itemsize); + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":262 + * p = self.data + * for i in range(self.len // self.itemsize): + * p[i] = Py_None # <<<<<<<<<<<<<< + * Py_INCREF(Py_None) + * return 0 + */ + (__pyx_v_p[__pyx_v_i]) = Py_None; + + /* "View.MemoryView":263 + * for i in range(self.len // self.itemsize): + * p[i] = Py_None + * Py_INCREF(Py_None) # <<<<<<<<<<<<<< + * return 0 + * + */ + Py_INCREF(Py_None); + } + + /* "View.MemoryView":259 + * raise MemoryError, "unable to allocate array data." + * + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * p = self.data + * for i in range(self.len // self.itemsize): + */ + } + + /* "View.MemoryView":264 + * p[i] = Py_None + * Py_INCREF(Py_None) + * return 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":248 + * + * @cname("__pyx_array_allocate_buffer") + * cdef int _allocate_buffer(array self) except -1: # <<<<<<<<<<<<<< + * + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._allocate_buffer", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":268 + * + * @cname("__pyx_array_new") + * cdef array array_cwrapper(tuple shape, Py_ssize_t itemsize, char *format, char *c_mode, char *buf): # <<<<<<<<<<<<<< + * cdef array result + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + */ + +static struct __pyx_array_obj *__pyx_array_new(PyObject *__pyx_v_shape, Py_ssize_t __pyx_v_itemsize, char *__pyx_v_format, char *__pyx_v_c_mode, char *__pyx_v_buf) { + struct __pyx_array_obj *__pyx_v_result = 0; + PyObject *__pyx_v_mode = 0; + struct __pyx_array_obj *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("array_cwrapper", 1); + + /* "View.MemoryView":270 + * cdef array array_cwrapper(tuple shape, Py_ssize_t itemsize, char *format, char *c_mode, char *buf): + * cdef array result + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. # <<<<<<<<<<<<<< + * + * if buf is NULL: + */ + __pyx_t_2 = ((__pyx_v_c_mode[0]) == 'f'); + if (__pyx_t_2) { + __Pyx_INCREF(__pyx_n_s_fortran); + __pyx_t_1 = __pyx_n_s_fortran; + } else { + __Pyx_INCREF(__pyx_n_s_c); + __pyx_t_1 = __pyx_n_s_c; + } + __pyx_v_mode = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":272 + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + * + * if buf is NULL: # <<<<<<<<<<<<<< + * result = array.__new__(array, shape, itemsize, format, mode) + * else: + */ + __pyx_t_2 = (__pyx_v_buf == NULL); + if (__pyx_t_2) { + + /* "View.MemoryView":273 + * + * if buf is NULL: + * result = array.__new__(array, shape, itemsize, format, mode) # <<<<<<<<<<<<<< + * else: + * result = array.__new__(array, shape, itemsize, format, mode, allocate_buffer=False) + */ + __pyx_t_1 = PyInt_FromSsize_t(__pyx_v_itemsize); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 273, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyBytes_FromString(__pyx_v_format); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 273, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PyTuple_New(4); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 273, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_INCREF(__pyx_v_shape); + __Pyx_GIVEREF(__pyx_v_shape); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_v_shape)) __PYX_ERR(1, 273, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_t_1)) __PYX_ERR(1, 273, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 2, __pyx_t_3)) __PYX_ERR(1, 273, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_mode); + __Pyx_GIVEREF(__pyx_v_mode); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 3, __pyx_v_mode)) __PYX_ERR(1, 273, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_3 = 0; + __pyx_t_3 = ((PyObject *)__pyx_tp_new_array(((PyTypeObject *)__pyx_array_type), __pyx_t_4, NULL)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 273, __pyx_L1_error) + __Pyx_GOTREF((PyObject *)__pyx_t_3); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_v_result = ((struct __pyx_array_obj *)__pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":272 + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + * + * if buf is NULL: # <<<<<<<<<<<<<< + * result = array.__new__(array, shape, itemsize, format, mode) + * else: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":275 + * result = array.__new__(array, shape, itemsize, format, mode) + * else: + * result = array.__new__(array, shape, itemsize, format, mode, allocate_buffer=False) # <<<<<<<<<<<<<< + * result.data = buf + * + */ + /*else*/ { + __pyx_t_3 = PyInt_FromSsize_t(__pyx_v_itemsize); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = __Pyx_PyBytes_FromString(__pyx_v_format); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_1 = PyTuple_New(4); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v_shape); + __Pyx_GIVEREF(__pyx_v_shape); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v_shape)) __PYX_ERR(1, 275, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_t_3)) __PYX_ERR(1, 275, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_4); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_t_4)) __PYX_ERR(1, 275, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_mode); + __Pyx_GIVEREF(__pyx_v_mode); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 3, __pyx_v_mode)) __PYX_ERR(1, 275, __pyx_L1_error); + __pyx_t_3 = 0; + __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem(__pyx_t_4, __pyx_n_s_allocate_buffer, Py_False) < 0) __PYX_ERR(1, 275, __pyx_L1_error) + __pyx_t_3 = ((PyObject *)__pyx_tp_new_array(((PyTypeObject *)__pyx_array_type), __pyx_t_1, __pyx_t_4)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 275, __pyx_L1_error) + __Pyx_GOTREF((PyObject *)__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_v_result = ((struct __pyx_array_obj *)__pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":276 + * else: + * result = array.__new__(array, shape, itemsize, format, mode, allocate_buffer=False) + * result.data = buf # <<<<<<<<<<<<<< + * + * return result + */ + __pyx_v_result->data = __pyx_v_buf; + } + __pyx_L3:; + + /* "View.MemoryView":278 + * result.data = buf + * + * return result # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF((PyObject *)__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = __pyx_v_result; + goto __pyx_L0; + + /* "View.MemoryView":268 + * + * @cname("__pyx_array_new") + * cdef array array_cwrapper(tuple shape, Py_ssize_t itemsize, char *format, char *c_mode, char *buf): # <<<<<<<<<<<<<< + * cdef array result + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.array_cwrapper", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XDECREF(__pyx_v_mode); + __Pyx_XGIVEREF((PyObject *)__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":304 + * cdef class Enum(object): + * cdef object name + * def __init__(self, name): # <<<<<<<<<<<<<< + * self.name = name + * def __repr__(self): + */ + +/* Python wrapper */ +static int __pyx_MemviewEnum___init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_MemviewEnum___init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_name = 0; + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__init__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_name,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_name)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 304, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__init__") < 0)) __PYX_ERR(1, 304, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + } + __pyx_v_name = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__init__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 304, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.Enum.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum___init__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self), __pyx_v_name); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum___init__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v_name) { + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__init__", 1); + + /* "View.MemoryView":305 + * cdef object name + * def __init__(self, name): + * self.name = name # <<<<<<<<<<<<<< + * def __repr__(self): + * return self.name + */ + __Pyx_INCREF(__pyx_v_name); + __Pyx_GIVEREF(__pyx_v_name); + __Pyx_GOTREF(__pyx_v_self->name); + __Pyx_DECREF(__pyx_v_self->name); + __pyx_v_self->name = __pyx_v_name; + + /* "View.MemoryView":304 + * cdef class Enum(object): + * cdef object name + * def __init__(self, name): # <<<<<<<<<<<<<< + * self.name = name + * def __repr__(self): + */ + + /* function exit code */ + __pyx_r = 0; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":306 + * def __init__(self, name): + * self.name = name + * def __repr__(self): # <<<<<<<<<<<<<< + * return self.name + * + */ + +/* Python wrapper */ +static PyObject *__pyx_MemviewEnum___repr__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_MemviewEnum___repr__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__repr__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum_2__repr__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum_2__repr__(struct __pyx_MemviewEnum_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__repr__", 1); + + /* "View.MemoryView":307 + * self.name = name + * def __repr__(self): + * return self.name # <<<<<<<<<<<<<< + * + * cdef generic = Enum("") + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->name); + __pyx_r = __pyx_v_self->name; + goto __pyx_L0; + + /* "View.MemoryView":306 + * def __init__(self, name): + * self.name = name + * def __repr__(self): # <<<<<<<<<<<<<< + * return self.name + * + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * cdef tuple state + * cdef object _dict + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_MemviewEnum_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_MemviewEnum_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_MemviewEnum___reduce_cython__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_MemviewEnum___reduce_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self) { + PyObject *__pyx_v_state = 0; + PyObject *__pyx_v__dict = 0; + int __pyx_v_use_setstate; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":5 + * cdef object _dict + * cdef bint use_setstate + * state = (self.name,) # <<<<<<<<<<<<<< + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: + */ + __pyx_t_1 = PyTuple_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v_self->name); + __Pyx_GIVEREF(__pyx_v_self->name); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v_self->name)) __PYX_ERR(1, 5, __pyx_L1_error); + __pyx_v_state = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "(tree fragment)":6 + * cdef bint use_setstate + * state = (self.name,) + * _dict = getattr(self, '__dict__', None) # <<<<<<<<<<<<<< + * if _dict is not None: + * state += (_dict,) + */ + __pyx_t_1 = __Pyx_GetAttr3(((PyObject *)__pyx_v_self), __pyx_n_s_dict, Py_None); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v__dict = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":7 + * state = (self.name,) + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: # <<<<<<<<<<<<<< + * state += (_dict,) + * use_setstate = True + */ + __pyx_t_2 = (__pyx_v__dict != Py_None); + if (__pyx_t_2) { + + /* "(tree fragment)":8 + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: + * state += (_dict,) # <<<<<<<<<<<<<< + * use_setstate = True + * else: + */ + __pyx_t_1 = PyTuple_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 8, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v__dict); + __Pyx_GIVEREF(__pyx_v__dict); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v__dict)) __PYX_ERR(1, 8, __pyx_L1_error); + __pyx_t_3 = PyNumber_InPlaceAdd(__pyx_v_state, __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 8, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF_SET(__pyx_v_state, ((PyObject*)__pyx_t_3)); + __pyx_t_3 = 0; + + /* "(tree fragment)":9 + * if _dict is not None: + * state += (_dict,) + * use_setstate = True # <<<<<<<<<<<<<< + * else: + * use_setstate = self.name is not None + */ + __pyx_v_use_setstate = 1; + + /* "(tree fragment)":7 + * state = (self.name,) + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: # <<<<<<<<<<<<<< + * state += (_dict,) + * use_setstate = True + */ + goto __pyx_L3; + } + + /* "(tree fragment)":11 + * use_setstate = True + * else: + * use_setstate = self.name is not None # <<<<<<<<<<<<<< + * if use_setstate: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + */ + /*else*/ { + __pyx_t_2 = (__pyx_v_self->name != Py_None); + __pyx_v_use_setstate = __pyx_t_2; + } + __pyx_L3:; + + /* "(tree fragment)":12 + * else: + * use_setstate = self.name is not None + * if use_setstate: # <<<<<<<<<<<<<< + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + * else: + */ + if (__pyx_v_use_setstate) { + + /* "(tree fragment)":13 + * use_setstate = self.name is not None + * if use_setstate: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state # <<<<<<<<<<<<<< + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_pyx_unpickle_Enum); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = PyTuple_New(3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_GIVEREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, ((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self))))) __PYX_ERR(1, 13, __pyx_L1_error); + __Pyx_INCREF(__pyx_int_136983863); + __Pyx_GIVEREF(__pyx_int_136983863); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_int_136983863)) __PYX_ERR(1, 13, __pyx_L1_error); + __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(Py_None); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 2, Py_None)) __PYX_ERR(1, 13, __pyx_L1_error); + __pyx_t_4 = PyTuple_New(3); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_3)) __PYX_ERR(1, 13, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_t_1)) __PYX_ERR(1, 13, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_state); + __Pyx_GIVEREF(__pyx_v_state); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 2, __pyx_v_state)) __PYX_ERR(1, 13, __pyx_L1_error); + __pyx_t_3 = 0; + __pyx_t_1 = 0; + __pyx_r = __pyx_t_4; + __pyx_t_4 = 0; + goto __pyx_L0; + + /* "(tree fragment)":12 + * else: + * use_setstate = self.name is not None + * if use_setstate: # <<<<<<<<<<<<<< + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + * else: + */ + } + + /* "(tree fragment)":15 + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * __pyx_unpickle_Enum__set_state(self, __pyx_state) + */ + /*else*/ { + __Pyx_XDECREF(__pyx_r); + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_pyx_unpickle_Enum); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_1 = PyTuple_New(3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_GIVEREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, ((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self))))) __PYX_ERR(1, 15, __pyx_L1_error); + __Pyx_INCREF(__pyx_int_136983863); + __Pyx_GIVEREF(__pyx_int_136983863); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_int_136983863)) __PYX_ERR(1, 15, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_state); + __Pyx_GIVEREF(__pyx_v_state); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_v_state)) __PYX_ERR(1, 15, __pyx_L1_error); + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_4); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_4)) __PYX_ERR(1, 15, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1)) __PYX_ERR(1, 15, __pyx_L1_error); + __pyx_t_4 = 0; + __pyx_t_1 = 0; + __pyx_r = __pyx_t_3; + __pyx_t_3 = 0; + goto __pyx_L0; + } + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * cdef tuple state + * cdef object _dict + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.Enum.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_state); + __Pyx_XDECREF(__pyx_v__dict); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":16 + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state(self, __pyx_state) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_MemviewEnum_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_MemviewEnum_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 16, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 16, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 16, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.Enum.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_MemviewEnum_2__setstate_cython__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_MemviewEnum_2__setstate_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":17 + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + * def __setstate_cython__(self, __pyx_state): + * __pyx_unpickle_Enum__set_state(self, __pyx_state) # <<<<<<<<<<<<<< + */ + if (!(likely(PyTuple_CheckExact(__pyx_v___pyx_state))||((__pyx_v___pyx_state) == Py_None) || __Pyx_RaiseUnexpectedTypeError("tuple", __pyx_v___pyx_state))) __PYX_ERR(1, 17, __pyx_L1_error) + __pyx_t_1 = __pyx_unpickle_Enum__set_state(__pyx_v_self, ((PyObject*)__pyx_v___pyx_state)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 17, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":16 + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state(self, __pyx_state) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.Enum.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":349 + * cdef __Pyx_TypeInfo *typeinfo + * + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): # <<<<<<<<<<<<<< + * self.obj = obj + * self.flags = flags + */ + +/* Python wrapper */ +static int __pyx_memoryview___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_memoryview___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_obj = 0; + int __pyx_v_flags; + int __pyx_v_dtype_is_object; + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_obj,&__pyx_n_s_flags,&__pyx_n_s_dtype_is_object,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_obj)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_flags)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 2, 3, 1); __PYX_ERR(1, 349, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_dtype_is_object); + if (value) { values[2] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(1, 349, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_obj = values[0]; + __pyx_v_flags = __Pyx_PyInt_As_int(values[1]); if (unlikely((__pyx_v_flags == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) + if (values[2]) { + __pyx_v_dtype_is_object = __Pyx_PyObject_IsTrue(values[2]); if (unlikely((__pyx_v_dtype_is_object == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) + } else { + __pyx_v_dtype_is_object = ((int)0); + } + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 2, 3, __pyx_nargs); __PYX_ERR(1, 349, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.memoryview.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview___cinit__(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v_obj, __pyx_v_flags, __pyx_v_dtype_is_object); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview___cinit__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj, int __pyx_v_flags, int __pyx_v_dtype_is_object) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + Py_intptr_t __pyx_t_4; + size_t __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__cinit__", 1); + + /* "View.MemoryView":350 + * + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): + * self.obj = obj # <<<<<<<<<<<<<< + * self.flags = flags + * if type(self) is memoryview or obj is not None: + */ + __Pyx_INCREF(__pyx_v_obj); + __Pyx_GIVEREF(__pyx_v_obj); + __Pyx_GOTREF(__pyx_v_self->obj); + __Pyx_DECREF(__pyx_v_self->obj); + __pyx_v_self->obj = __pyx_v_obj; + + /* "View.MemoryView":351 + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): + * self.obj = obj + * self.flags = flags # <<<<<<<<<<<<<< + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) + */ + __pyx_v_self->flags = __pyx_v_flags; + + /* "View.MemoryView":352 + * self.obj = obj + * self.flags = flags + * if type(self) is memoryview or obj is not None: # <<<<<<<<<<<<<< + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: + */ + __pyx_t_2 = (((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self))) == ((PyObject *)__pyx_memoryview_type)); + if (!__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_2 = (__pyx_v_obj != Py_None); + __pyx_t_1 = __pyx_t_2; + __pyx_L4_bool_binop_done:; + if (__pyx_t_1) { + + /* "View.MemoryView":353 + * self.flags = flags + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) # <<<<<<<<<<<<<< + * if self.view.obj == NULL: + * (<__pyx_buffer *> &self.view).obj = Py_None + */ + __pyx_t_3 = __Pyx_GetBuffer(__pyx_v_obj, (&__pyx_v_self->view), __pyx_v_flags); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 353, __pyx_L1_error) + + /* "View.MemoryView":354 + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: # <<<<<<<<<<<<<< + * (<__pyx_buffer *> &self.view).obj = Py_None + * Py_INCREF(Py_None) + */ + __pyx_t_1 = (((PyObject *)__pyx_v_self->view.obj) == NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":355 + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: + * (<__pyx_buffer *> &self.view).obj = Py_None # <<<<<<<<<<<<<< + * Py_INCREF(Py_None) + * + */ + ((Py_buffer *)(&__pyx_v_self->view))->obj = Py_None; + + /* "View.MemoryView":356 + * if self.view.obj == NULL: + * (<__pyx_buffer *> &self.view).obj = Py_None + * Py_INCREF(Py_None) # <<<<<<<<<<<<<< + * + * if not __PYX_CYTHON_ATOMICS_ENABLED(): + */ + Py_INCREF(Py_None); + + /* "View.MemoryView":354 + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: # <<<<<<<<<<<<<< + * (<__pyx_buffer *> &self.view).obj = Py_None + * Py_INCREF(Py_None) + */ + } + + /* "View.MemoryView":352 + * self.obj = obj + * self.flags = flags + * if type(self) is memoryview or obj is not None: # <<<<<<<<<<<<<< + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: + */ + } + + /* "View.MemoryView":358 + * Py_INCREF(Py_None) + * + * if not __PYX_CYTHON_ATOMICS_ENABLED(): # <<<<<<<<<<<<<< + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: + */ + __pyx_t_1 = (!__PYX_CYTHON_ATOMICS_ENABLED()); + if (__pyx_t_1) { + + /* "View.MemoryView":360 + * if not __PYX_CYTHON_ATOMICS_ENABLED(): + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: # <<<<<<<<<<<<<< + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + */ + __pyx_t_1 = (__pyx_memoryview_thread_locks_used < 8); + if (__pyx_t_1) { + + /* "View.MemoryView":361 + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: + */ + __pyx_v_self->lock = (__pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used]); + + /* "View.MemoryView":362 + * if __pyx_memoryview_thread_locks_used < 8: + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 # <<<<<<<<<<<<<< + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() + */ + __pyx_memoryview_thread_locks_used = (__pyx_memoryview_thread_locks_used + 1); + + /* "View.MemoryView":360 + * if not __PYX_CYTHON_ATOMICS_ENABLED(): + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: # <<<<<<<<<<<<<< + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + */ + } + + /* "View.MemoryView":363 + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: # <<<<<<<<<<<<<< + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: + */ + __pyx_t_1 = (__pyx_v_self->lock == NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":364 + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() # <<<<<<<<<<<<<< + * if self.lock is NULL: + * raise MemoryError + */ + __pyx_v_self->lock = PyThread_allocate_lock(); + + /* "View.MemoryView":365 + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + __pyx_t_1 = (__pyx_v_self->lock == NULL); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":366 + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: + * raise MemoryError # <<<<<<<<<<<<<< + * + * if flags & PyBUF_FORMAT: + */ + PyErr_NoMemory(); __PYX_ERR(1, 366, __pyx_L1_error) + + /* "View.MemoryView":365 + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + } + + /* "View.MemoryView":363 + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: # <<<<<<<<<<<<<< + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: + */ + } + + /* "View.MemoryView":358 + * Py_INCREF(Py_None) + * + * if not __PYX_CYTHON_ATOMICS_ENABLED(): # <<<<<<<<<<<<<< + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: + */ + } + + /* "View.MemoryView":368 + * raise MemoryError + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_FORMAT) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":369 + * + * if flags & PyBUF_FORMAT: + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') # <<<<<<<<<<<<<< + * else: + * self.dtype_is_object = dtype_is_object + */ + __pyx_t_2 = ((__pyx_v_self->view.format[0]) == 'O'); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L12_bool_binop_done; + } + __pyx_t_2 = ((__pyx_v_self->view.format[1]) == '\x00'); + __pyx_t_1 = __pyx_t_2; + __pyx_L12_bool_binop_done:; + __pyx_v_self->dtype_is_object = __pyx_t_1; + + /* "View.MemoryView":368 + * raise MemoryError + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') + * else: + */ + goto __pyx_L11; + } + + /* "View.MemoryView":371 + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') + * else: + * self.dtype_is_object = dtype_is_object # <<<<<<<<<<<<<< + * + * assert (&self.acquisition_count) % sizeof(__pyx_atomic_int_type) == 0 + */ + /*else*/ { + __pyx_v_self->dtype_is_object = __pyx_v_dtype_is_object; + } + __pyx_L11:; + + /* "View.MemoryView":373 + * self.dtype_is_object = dtype_is_object + * + * assert (&self.acquisition_count) % sizeof(__pyx_atomic_int_type) == 0 # <<<<<<<<<<<<<< + * self.typeinfo = NULL + * + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_4 = ((Py_intptr_t)((void *)(&__pyx_v_self->acquisition_count))); + __pyx_t_5 = (sizeof(__pyx_atomic_int_type)); + if (unlikely(__pyx_t_5 == 0)) { + PyErr_SetString(PyExc_ZeroDivisionError, "integer division or modulo by zero"); + __PYX_ERR(1, 373, __pyx_L1_error) + } + __pyx_t_1 = ((__pyx_t_4 % __pyx_t_5) == 0); + if (unlikely(!__pyx_t_1)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(1, 373, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(1, 373, __pyx_L1_error) + #endif + + /* "View.MemoryView":374 + * + * assert (&self.acquisition_count) % sizeof(__pyx_atomic_int_type) == 0 + * self.typeinfo = NULL # <<<<<<<<<<<<<< + * + * def __dealloc__(memoryview self): + */ + __pyx_v_self->typeinfo = NULL; + + /* "View.MemoryView":349 + * cdef __Pyx_TypeInfo *typeinfo + * + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): # <<<<<<<<<<<<<< + * self.obj = obj + * self.flags = flags + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":376 + * self.typeinfo = NULL + * + * def __dealloc__(memoryview self): # <<<<<<<<<<<<<< + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + */ + +/* Python wrapper */ +static void __pyx_memoryview___dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_memoryview___dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_2__dealloc__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_2__dealloc__(struct __pyx_memoryview_obj *__pyx_v_self) { + int __pyx_v_i; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + PyThread_type_lock __pyx_t_5; + PyThread_type_lock __pyx_t_6; + + /* "View.MemoryView":377 + * + * def __dealloc__(memoryview self): + * if self.obj is not None: # <<<<<<<<<<<<<< + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + */ + __pyx_t_1 = (__pyx_v_self->obj != Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":378 + * def __dealloc__(memoryview self): + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) # <<<<<<<<<<<<<< + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + * + */ + __Pyx_ReleaseBuffer((&__pyx_v_self->view)); + + /* "View.MemoryView":377 + * + * def __dealloc__(memoryview self): + * if self.obj is not None: # <<<<<<<<<<<<<< + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":379 + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: # <<<<<<<<<<<<<< + * + * (<__pyx_buffer *> &self.view).obj = NULL + */ + __pyx_t_1 = (((Py_buffer *)(&__pyx_v_self->view))->obj == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":381 + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + * + * (<__pyx_buffer *> &self.view).obj = NULL # <<<<<<<<<<<<<< + * Py_DECREF(Py_None) + * + */ + ((Py_buffer *)(&__pyx_v_self->view))->obj = NULL; + + /* "View.MemoryView":382 + * + * (<__pyx_buffer *> &self.view).obj = NULL + * Py_DECREF(Py_None) # <<<<<<<<<<<<<< + * + * cdef int i + */ + Py_DECREF(Py_None); + + /* "View.MemoryView":379 + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: # <<<<<<<<<<<<<< + * + * (<__pyx_buffer *> &self.view).obj = NULL + */ + } + __pyx_L3:; + + /* "View.MemoryView":386 + * cdef int i + * global __pyx_memoryview_thread_locks_used + * if self.lock != NULL: # <<<<<<<<<<<<<< + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: + */ + __pyx_t_1 = (__pyx_v_self->lock != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":387 + * global __pyx_memoryview_thread_locks_used + * if self.lock != NULL: + * for i in range(__pyx_memoryview_thread_locks_used): # <<<<<<<<<<<<<< + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 + */ + __pyx_t_2 = __pyx_memoryview_thread_locks_used; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":388 + * if self.lock != NULL: + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: + */ + __pyx_t_1 = ((__pyx_memoryview_thread_locks[__pyx_v_i]) == __pyx_v_self->lock); + if (__pyx_t_1) { + + /* "View.MemoryView":389 + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 # <<<<<<<<<<<<<< + * if i != __pyx_memoryview_thread_locks_used: + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + */ + __pyx_memoryview_thread_locks_used = (__pyx_memoryview_thread_locks_used - 1); + + /* "View.MemoryView":390 + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + */ + __pyx_t_1 = (__pyx_v_i != __pyx_memoryview_thread_locks_used); + if (__pyx_t_1) { + + /* "View.MemoryView":392 + * if i != __pyx_memoryview_thread_locks_used: + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) # <<<<<<<<<<<<<< + * break + * else: + */ + __pyx_t_5 = (__pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used]); + __pyx_t_6 = (__pyx_memoryview_thread_locks[__pyx_v_i]); + + /* "View.MemoryView":391 + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + * break + */ + (__pyx_memoryview_thread_locks[__pyx_v_i]) = __pyx_t_5; + (__pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used]) = __pyx_t_6; + + /* "View.MemoryView":390 + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + */ + } + + /* "View.MemoryView":393 + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + * break # <<<<<<<<<<<<<< + * else: + * PyThread_free_lock(self.lock) + */ + goto __pyx_L6_break; + + /* "View.MemoryView":388 + * if self.lock != NULL: + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: + */ + } + } + /*else*/ { + + /* "View.MemoryView":395 + * break + * else: + * PyThread_free_lock(self.lock) # <<<<<<<<<<<<<< + * + * cdef char *get_item_pointer(memoryview self, object index) except NULL: + */ + PyThread_free_lock(__pyx_v_self->lock); + } + __pyx_L6_break:; + + /* "View.MemoryView":386 + * cdef int i + * global __pyx_memoryview_thread_locks_used + * if self.lock != NULL: # <<<<<<<<<<<<<< + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: + */ + } + + /* "View.MemoryView":376 + * self.typeinfo = NULL + * + * def __dealloc__(memoryview self): # <<<<<<<<<<<<<< + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + */ + + /* function exit code */ +} + +/* "View.MemoryView":397 + * PyThread_free_lock(self.lock) + * + * cdef char *get_item_pointer(memoryview self, object index) except NULL: # <<<<<<<<<<<<<< + * cdef Py_ssize_t dim + * cdef char *itemp = self.view.buf + */ + +static char *__pyx_memoryview_get_item_pointer(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index) { + Py_ssize_t __pyx_v_dim; + char *__pyx_v_itemp; + PyObject *__pyx_v_idx = NULL; + char *__pyx_r; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + Py_ssize_t __pyx_t_3; + PyObject *(*__pyx_t_4)(PyObject *); + PyObject *__pyx_t_5 = NULL; + Py_ssize_t __pyx_t_6; + char *__pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_item_pointer", 1); + + /* "View.MemoryView":399 + * cdef char *get_item_pointer(memoryview self, object index) except NULL: + * cdef Py_ssize_t dim + * cdef char *itemp = self.view.buf # <<<<<<<<<<<<<< + * + * for dim, idx in enumerate(index): + */ + __pyx_v_itemp = ((char *)__pyx_v_self->view.buf); + + /* "View.MemoryView":401 + * cdef char *itemp = self.view.buf + * + * for dim, idx in enumerate(index): # <<<<<<<<<<<<<< + * itemp = pybuffer_index(&self.view, itemp, idx, dim) + * + */ + __pyx_t_1 = 0; + if (likely(PyList_CheckExact(__pyx_v_index)) || PyTuple_CheckExact(__pyx_v_index)) { + __pyx_t_2 = __pyx_v_index; __Pyx_INCREF(__pyx_t_2); + __pyx_t_3 = 0; + __pyx_t_4 = NULL; + } else { + __pyx_t_3 = -1; __pyx_t_2 = PyObject_GetIter(__pyx_v_index); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 401, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_2); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 401, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_4)) { + if (likely(PyList_CheckExact(__pyx_t_2))) { + { + Py_ssize_t __pyx_temp = __Pyx_PyList_GET_SIZE(__pyx_t_2); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 401, __pyx_L1_error) + #endif + if (__pyx_t_3 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_5 = PyList_GET_ITEM(__pyx_t_2, __pyx_t_3); __Pyx_INCREF(__pyx_t_5); __pyx_t_3++; if (unlikely((0 < 0))) __PYX_ERR(1, 401, __pyx_L1_error) + #else + __pyx_t_5 = __Pyx_PySequence_ITEM(__pyx_t_2, __pyx_t_3); __pyx_t_3++; if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 401, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + #endif + } else { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_2); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 401, __pyx_L1_error) + #endif + if (__pyx_t_3 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_5 = PyTuple_GET_ITEM(__pyx_t_2, __pyx_t_3); __Pyx_INCREF(__pyx_t_5); __pyx_t_3++; if (unlikely((0 < 0))) __PYX_ERR(1, 401, __pyx_L1_error) + #else + __pyx_t_5 = __Pyx_PySequence_ITEM(__pyx_t_2, __pyx_t_3); __pyx_t_3++; if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 401, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + #endif + } + } else { + __pyx_t_5 = __pyx_t_4(__pyx_t_2); + if (unlikely(!__pyx_t_5)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(1, 401, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_5); + } + __Pyx_XDECREF_SET(__pyx_v_idx, __pyx_t_5); + __pyx_t_5 = 0; + __pyx_v_dim = __pyx_t_1; + __pyx_t_1 = (__pyx_t_1 + 1); + + /* "View.MemoryView":402 + * + * for dim, idx in enumerate(index): + * itemp = pybuffer_index(&self.view, itemp, idx, dim) # <<<<<<<<<<<<<< + * + * return itemp + */ + __pyx_t_6 = __Pyx_PyIndex_AsSsize_t(__pyx_v_idx); if (unlikely((__pyx_t_6 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 402, __pyx_L1_error) + __pyx_t_7 = __pyx_pybuffer_index((&__pyx_v_self->view), __pyx_v_itemp, __pyx_t_6, __pyx_v_dim); if (unlikely(__pyx_t_7 == ((char *)NULL))) __PYX_ERR(1, 402, __pyx_L1_error) + __pyx_v_itemp = __pyx_t_7; + + /* "View.MemoryView":401 + * cdef char *itemp = self.view.buf + * + * for dim, idx in enumerate(index): # <<<<<<<<<<<<<< + * itemp = pybuffer_index(&self.view, itemp, idx, dim) + * + */ + } + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":404 + * itemp = pybuffer_index(&self.view, itemp, idx, dim) + * + * return itemp # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = __pyx_v_itemp; + goto __pyx_L0; + + /* "View.MemoryView":397 + * PyThread_free_lock(self.lock) + * + * cdef char *get_item_pointer(memoryview self, object index) except NULL: # <<<<<<<<<<<<<< + * cdef Py_ssize_t dim + * cdef char *itemp = self.view.buf + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.memoryview.get_item_pointer", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_idx); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":407 + * + * + * def __getitem__(memoryview self, object index): # <<<<<<<<<<<<<< + * if index is Ellipsis: + * return self + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index); /*proto*/ +static PyObject *__pyx_memoryview___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getitem__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_4__getitem__(((struct __pyx_memoryview_obj *)__pyx_v_self), ((PyObject *)__pyx_v_index)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_4__getitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index) { + PyObject *__pyx_v_have_slices = NULL; + PyObject *__pyx_v_indices = NULL; + char *__pyx_v_itemp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + char *__pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__getitem__", 1); + + /* "View.MemoryView":408 + * + * def __getitem__(memoryview self, object index): + * if index is Ellipsis: # <<<<<<<<<<<<<< + * return self + * + */ + __pyx_t_1 = (__pyx_v_index == __pyx_builtin_Ellipsis); + if (__pyx_t_1) { + + /* "View.MemoryView":409 + * def __getitem__(memoryview self, object index): + * if index is Ellipsis: + * return self # <<<<<<<<<<<<<< + * + * have_slices, indices = _unellipsify(index, self.view.ndim) + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_self); + __pyx_r = ((PyObject *)__pyx_v_self); + goto __pyx_L0; + + /* "View.MemoryView":408 + * + * def __getitem__(memoryview self, object index): + * if index is Ellipsis: # <<<<<<<<<<<<<< + * return self + * + */ + } + + /* "View.MemoryView":411 + * return self + * + * have_slices, indices = _unellipsify(index, self.view.ndim) # <<<<<<<<<<<<<< + * + * cdef char *itemp + */ + __pyx_t_2 = _unellipsify(__pyx_v_index, __pyx_v_self->view.ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 411, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (likely(__pyx_t_2 != Py_None)) { + PyObject* sequence = __pyx_t_2; + Py_ssize_t size = __Pyx_PySequence_SIZE(sequence); + if (unlikely(size != 2)) { + if (size > 2) __Pyx_RaiseTooManyValuesError(2); + else if (size >= 0) __Pyx_RaiseNeedMoreValuesError(size); + __PYX_ERR(1, 411, __pyx_L1_error) + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_3 = PyTuple_GET_ITEM(sequence, 0); + __pyx_t_4 = PyTuple_GET_ITEM(sequence, 1); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(__pyx_t_4); + #else + __pyx_t_3 = PySequence_ITEM(sequence, 0); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 411, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PySequence_ITEM(sequence, 1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 411, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } else { + __Pyx_RaiseNoneNotIterableError(); __PYX_ERR(1, 411, __pyx_L1_error) + } + __pyx_v_have_slices = __pyx_t_3; + __pyx_t_3 = 0; + __pyx_v_indices = __pyx_t_4; + __pyx_t_4 = 0; + + /* "View.MemoryView":414 + * + * cdef char *itemp + * if have_slices: # <<<<<<<<<<<<<< + * return memview_slice(self, indices) + * else: + */ + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_v_have_slices); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 414, __pyx_L1_error) + if (__pyx_t_1) { + + /* "View.MemoryView":415 + * cdef char *itemp + * if have_slices: + * return memview_slice(self, indices) # <<<<<<<<<<<<<< + * else: + * itemp = self.get_item_pointer(indices) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = ((PyObject *)__pyx_memview_slice(__pyx_v_self, __pyx_v_indices)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 415, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":414 + * + * cdef char *itemp + * if have_slices: # <<<<<<<<<<<<<< + * return memview_slice(self, indices) + * else: + */ + } + + /* "View.MemoryView":417 + * return memview_slice(self, indices) + * else: + * itemp = self.get_item_pointer(indices) # <<<<<<<<<<<<<< + * return self.convert_item_to_object(itemp) + * + */ + /*else*/ { + __pyx_t_5 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->get_item_pointer(__pyx_v_self, __pyx_v_indices); if (unlikely(__pyx_t_5 == ((char *)NULL))) __PYX_ERR(1, 417, __pyx_L1_error) + __pyx_v_itemp = __pyx_t_5; + + /* "View.MemoryView":418 + * else: + * itemp = self.get_item_pointer(indices) + * return self.convert_item_to_object(itemp) # <<<<<<<<<<<<<< + * + * def __setitem__(memoryview self, object index, object value): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->convert_item_to_object(__pyx_v_self, __pyx_v_itemp); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 418, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + } + + /* "View.MemoryView":407 + * + * + * def __getitem__(memoryview self, object index): # <<<<<<<<<<<<<< + * if index is Ellipsis: + * return self + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.memoryview.__getitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_have_slices); + __Pyx_XDECREF(__pyx_v_indices); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":420 + * return self.convert_item_to_object(itemp) + * + * def __setitem__(memoryview self, object index, object value): # <<<<<<<<<<<<<< + * if self.view.readonly: + * raise TypeError, "Cannot assign to read-only memoryview" + */ + +/* Python wrapper */ +static int __pyx_memoryview___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value); /*proto*/ +static int __pyx_memoryview___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setitem__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_6__setitem__(((struct __pyx_memoryview_obj *)__pyx_v_self), ((PyObject *)__pyx_v_index), ((PyObject *)__pyx_v_value)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_6__setitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value) { + PyObject *__pyx_v_have_slices = NULL; + PyObject *__pyx_v_obj = NULL; + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setitem__", 0); + __Pyx_INCREF(__pyx_v_index); + + /* "View.MemoryView":421 + * + * def __setitem__(memoryview self, object index, object value): + * if self.view.readonly: # <<<<<<<<<<<<<< + * raise TypeError, "Cannot assign to read-only memoryview" + * + */ + if (unlikely(__pyx_v_self->view.readonly)) { + + /* "View.MemoryView":422 + * def __setitem__(memoryview self, object index, object value): + * if self.view.readonly: + * raise TypeError, "Cannot assign to read-only memoryview" # <<<<<<<<<<<<<< + * + * have_slices, index = _unellipsify(index, self.view.ndim) + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_Cannot_assign_to_read_only_memor, 0, 0); + __PYX_ERR(1, 422, __pyx_L1_error) + + /* "View.MemoryView":421 + * + * def __setitem__(memoryview self, object index, object value): + * if self.view.readonly: # <<<<<<<<<<<<<< + * raise TypeError, "Cannot assign to read-only memoryview" + * + */ + } + + /* "View.MemoryView":424 + * raise TypeError, "Cannot assign to read-only memoryview" + * + * have_slices, index = _unellipsify(index, self.view.ndim) # <<<<<<<<<<<<<< + * + * if have_slices: + */ + __pyx_t_1 = _unellipsify(__pyx_v_index, __pyx_v_self->view.ndim); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 424, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (likely(__pyx_t_1 != Py_None)) { + PyObject* sequence = __pyx_t_1; + Py_ssize_t size = __Pyx_PySequence_SIZE(sequence); + if (unlikely(size != 2)) { + if (size > 2) __Pyx_RaiseTooManyValuesError(2); + else if (size >= 0) __Pyx_RaiseNeedMoreValuesError(size); + __PYX_ERR(1, 424, __pyx_L1_error) + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_2 = PyTuple_GET_ITEM(sequence, 0); + __pyx_t_3 = PyTuple_GET_ITEM(sequence, 1); + __Pyx_INCREF(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + #else + __pyx_t_2 = PySequence_ITEM(sequence, 0); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 424, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PySequence_ITEM(sequence, 1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 424, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + #endif + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } else { + __Pyx_RaiseNoneNotIterableError(); __PYX_ERR(1, 424, __pyx_L1_error) + } + __pyx_v_have_slices = __pyx_t_2; + __pyx_t_2 = 0; + __Pyx_DECREF_SET(__pyx_v_index, __pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":426 + * have_slices, index = _unellipsify(index, self.view.ndim) + * + * if have_slices: # <<<<<<<<<<<<<< + * obj = self.is_slice(value) + * if obj: + */ + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_v_have_slices); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(1, 426, __pyx_L1_error) + if (__pyx_t_4) { + + /* "View.MemoryView":427 + * + * if have_slices: + * obj = self.is_slice(value) # <<<<<<<<<<<<<< + * if obj: + * self.setitem_slice_assignment(self[index], obj) + */ + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->is_slice(__pyx_v_self, __pyx_v_value); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 427, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_obj = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":428 + * if have_slices: + * obj = self.is_slice(value) + * if obj: # <<<<<<<<<<<<<< + * self.setitem_slice_assignment(self[index], obj) + * else: + */ + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_v_obj); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(1, 428, __pyx_L1_error) + if (__pyx_t_4) { + + /* "View.MemoryView":429 + * obj = self.is_slice(value) + * if obj: + * self.setitem_slice_assignment(self[index], obj) # <<<<<<<<<<<<<< + * else: + * self.setitem_slice_assign_scalar(self[index], value) + */ + __pyx_t_1 = __Pyx_PyObject_GetItem(((PyObject *)__pyx_v_self), __pyx_v_index); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 429, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->setitem_slice_assignment(__pyx_v_self, __pyx_t_1, __pyx_v_obj); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 429, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "View.MemoryView":428 + * if have_slices: + * obj = self.is_slice(value) + * if obj: # <<<<<<<<<<<<<< + * self.setitem_slice_assignment(self[index], obj) + * else: + */ + goto __pyx_L5; + } + + /* "View.MemoryView":431 + * self.setitem_slice_assignment(self[index], obj) + * else: + * self.setitem_slice_assign_scalar(self[index], value) # <<<<<<<<<<<<<< + * else: + * self.setitem_indexed(index, value) + */ + /*else*/ { + __pyx_t_3 = __Pyx_PyObject_GetItem(((PyObject *)__pyx_v_self), __pyx_v_index); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 431, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (!(likely(((__pyx_t_3) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_3, __pyx_memoryview_type))))) __PYX_ERR(1, 431, __pyx_L1_error) + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->setitem_slice_assign_scalar(__pyx_v_self, ((struct __pyx_memoryview_obj *)__pyx_t_3), __pyx_v_value); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 431, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_L5:; + + /* "View.MemoryView":426 + * have_slices, index = _unellipsify(index, self.view.ndim) + * + * if have_slices: # <<<<<<<<<<<<<< + * obj = self.is_slice(value) + * if obj: + */ + goto __pyx_L4; + } + + /* "View.MemoryView":433 + * self.setitem_slice_assign_scalar(self[index], value) + * else: + * self.setitem_indexed(index, value) # <<<<<<<<<<<<<< + * + * cdef is_slice(self, obj): + */ + /*else*/ { + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->setitem_indexed(__pyx_v_self, __pyx_v_index, __pyx_v_value); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 433, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_L4:; + + /* "View.MemoryView":420 + * return self.convert_item_to_object(itemp) + * + * def __setitem__(memoryview self, object index, object value): # <<<<<<<<<<<<<< + * if self.view.readonly: + * raise TypeError, "Cannot assign to read-only memoryview" + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.__setitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_have_slices); + __Pyx_XDECREF(__pyx_v_obj); + __Pyx_XDECREF(__pyx_v_index); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":435 + * self.setitem_indexed(index, value) + * + * cdef is_slice(self, obj): # <<<<<<<<<<<<<< + * if not isinstance(obj, memoryview): + * try: + */ + +static PyObject *__pyx_memoryview_is_slice(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("is_slice", 0); + __Pyx_INCREF(__pyx_v_obj); + + /* "View.MemoryView":436 + * + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): # <<<<<<<<<<<<<< + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + */ + __pyx_t_1 = __Pyx_TypeCheck(__pyx_v_obj, __pyx_memoryview_type); + __pyx_t_2 = (!__pyx_t_1); + if (__pyx_t_2) { + + /* "View.MemoryView":437 + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): + * try: # <<<<<<<<<<<<<< + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_3, &__pyx_t_4, &__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_4); + __Pyx_XGOTREF(__pyx_t_5); + /*try:*/ { + + /* "View.MemoryView":438 + * if not isinstance(obj, memoryview): + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, # <<<<<<<<<<<<<< + * self.dtype_is_object) + * except TypeError: + */ + __pyx_t_6 = __Pyx_PyInt_From_int(((__pyx_v_self->flags & (~PyBUF_WRITABLE)) | PyBUF_ANY_CONTIGUOUS)); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 438, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_6); + + /* "View.MemoryView":439 + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) # <<<<<<<<<<<<<< + * except TypeError: + * return None + */ + __pyx_t_7 = __Pyx_PyBool_FromLong(__pyx_v_self->dtype_is_object); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 439, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_7); + + /* "View.MemoryView":438 + * if not isinstance(obj, memoryview): + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, # <<<<<<<<<<<<<< + * self.dtype_is_object) + * except TypeError: + */ + __pyx_t_8 = PyTuple_New(3); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 438, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_INCREF(__pyx_v_obj); + __Pyx_GIVEREF(__pyx_v_obj); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_8, 0, __pyx_v_obj)) __PYX_ERR(1, 438, __pyx_L4_error); + __Pyx_GIVEREF(__pyx_t_6); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_8, 1, __pyx_t_6)) __PYX_ERR(1, 438, __pyx_L4_error); + __Pyx_GIVEREF(__pyx_t_7); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_8, 2, __pyx_t_7)) __PYX_ERR(1, 438, __pyx_L4_error); + __pyx_t_6 = 0; + __pyx_t_7 = 0; + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_memoryview_type), __pyx_t_8, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 438, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_DECREF_SET(__pyx_v_obj, __pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":437 + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): + * try: # <<<<<<<<<<<<<< + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + */ + } + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + goto __pyx_L9_try_end; + __pyx_L4_error:; + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + + /* "View.MemoryView":440 + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + * except TypeError: # <<<<<<<<<<<<<< + * return None + * + */ + __pyx_t_9 = __Pyx_PyErr_ExceptionMatches(__pyx_builtin_TypeError); + if (__pyx_t_9) { + __Pyx_AddTraceback("View.MemoryView.memoryview.is_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_7, &__pyx_t_8, &__pyx_t_6) < 0) __PYX_ERR(1, 440, __pyx_L6_except_error) + __Pyx_XGOTREF(__pyx_t_7); + __Pyx_XGOTREF(__pyx_t_8); + __Pyx_XGOTREF(__pyx_t_6); + + /* "View.MemoryView":441 + * self.dtype_is_object) + * except TypeError: + * return None # <<<<<<<<<<<<<< + * + * return obj + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L7_except_return; + } + goto __pyx_L6_except_error; + + /* "View.MemoryView":437 + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): + * try: # <<<<<<<<<<<<<< + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + */ + __pyx_L6_except_error:; + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_XGIVEREF(__pyx_t_5); + __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_4, __pyx_t_5); + goto __pyx_L1_error; + __pyx_L7_except_return:; + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_XGIVEREF(__pyx_t_5); + __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_4, __pyx_t_5); + goto __pyx_L0; + __pyx_L9_try_end:; + } + + /* "View.MemoryView":436 + * + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): # <<<<<<<<<<<<<< + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + */ + } + + /* "View.MemoryView":443 + * return None + * + * return obj # <<<<<<<<<<<<<< + * + * cdef setitem_slice_assignment(self, dst, src): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_obj); + __pyx_r = __pyx_v_obj; + goto __pyx_L0; + + /* "View.MemoryView":435 + * self.setitem_indexed(index, value) + * + * cdef is_slice(self, obj): # <<<<<<<<<<<<<< + * if not isinstance(obj, memoryview): + * try: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("View.MemoryView.memoryview.is_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_obj); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":445 + * return obj + * + * cdef setitem_slice_assignment(self, dst, src): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice dst_slice + * cdef __Pyx_memviewslice src_slice + */ + +static PyObject *__pyx_memoryview_setitem_slice_assignment(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_dst, PyObject *__pyx_v_src) { + __Pyx_memviewslice __pyx_v_dst_slice; + __Pyx_memviewslice __pyx_v_src_slice; + __Pyx_memviewslice __pyx_v_msrc; + __Pyx_memviewslice __pyx_v_mdst; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_t_3; + int __pyx_t_4; + int __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("setitem_slice_assignment", 1); + + /* "View.MemoryView":448 + * cdef __Pyx_memviewslice dst_slice + * cdef __Pyx_memviewslice src_slice + * cdef __Pyx_memviewslice msrc = get_slice_from_memview(src, &src_slice)[0] # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice mdst = get_slice_from_memview(dst, &dst_slice)[0] + * + */ + if (!(likely(((__pyx_v_src) == Py_None) || likely(__Pyx_TypeTest(__pyx_v_src, __pyx_memoryview_type))))) __PYX_ERR(1, 448, __pyx_L1_error) + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(((struct __pyx_memoryview_obj *)__pyx_v_src), (&__pyx_v_src_slice)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 448, __pyx_L1_error) + __pyx_v_msrc = (__pyx_t_1[0]); + + /* "View.MemoryView":449 + * cdef __Pyx_memviewslice src_slice + * cdef __Pyx_memviewslice msrc = get_slice_from_memview(src, &src_slice)[0] + * cdef __Pyx_memviewslice mdst = get_slice_from_memview(dst, &dst_slice)[0] # <<<<<<<<<<<<<< + * + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) + */ + if (!(likely(((__pyx_v_dst) == Py_None) || likely(__Pyx_TypeTest(__pyx_v_dst, __pyx_memoryview_type))))) __PYX_ERR(1, 449, __pyx_L1_error) + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(((struct __pyx_memoryview_obj *)__pyx_v_dst), (&__pyx_v_dst_slice)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 449, __pyx_L1_error) + __pyx_v_mdst = (__pyx_t_1[0]); + + /* "View.MemoryView":451 + * cdef __Pyx_memviewslice mdst = get_slice_from_memview(dst, &dst_slice)[0] + * + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) # <<<<<<<<<<<<<< + * + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_src, __pyx_n_s_ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 451, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_PyInt_As_int(__pyx_t_2); if (unlikely((__pyx_t_3 == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 451, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_dst, __pyx_n_s_ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 451, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __Pyx_PyInt_As_int(__pyx_t_2); if (unlikely((__pyx_t_4 == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 451, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_5 = __pyx_memoryview_copy_contents(__pyx_v_msrc, __pyx_v_mdst, __pyx_t_3, __pyx_t_4, __pyx_v_self->dtype_is_object); if (unlikely(__pyx_t_5 == ((int)-1))) __PYX_ERR(1, 451, __pyx_L1_error) + + /* "View.MemoryView":445 + * return obj + * + * cdef setitem_slice_assignment(self, dst, src): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice dst_slice + * cdef __Pyx_memviewslice src_slice + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.setitem_slice_assignment", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":453 + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) + * + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): # <<<<<<<<<<<<<< + * cdef int array[128] + * cdef void *tmp = NULL + */ + +static PyObject *__pyx_memoryview_setitem_slice_assign_scalar(struct __pyx_memoryview_obj *__pyx_v_self, struct __pyx_memoryview_obj *__pyx_v_dst, PyObject *__pyx_v_value) { + int __pyx_v_array[0x80]; + void *__pyx_v_tmp; + void *__pyx_v_item; + __Pyx_memviewslice *__pyx_v_dst_slice; + __Pyx_memviewslice __pyx_v_tmp_slice; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_t_5; + char const *__pyx_t_6; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + PyObject *__pyx_t_9 = NULL; + PyObject *__pyx_t_10 = NULL; + PyObject *__pyx_t_11 = NULL; + PyObject *__pyx_t_12 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("setitem_slice_assign_scalar", 1); + + /* "View.MemoryView":455 + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): + * cdef int array[128] + * cdef void *tmp = NULL # <<<<<<<<<<<<<< + * cdef void *item + * + */ + __pyx_v_tmp = NULL; + + /* "View.MemoryView":460 + * cdef __Pyx_memviewslice *dst_slice + * cdef __Pyx_memviewslice tmp_slice + * dst_slice = get_slice_from_memview(dst, &tmp_slice) # <<<<<<<<<<<<<< + * + * if self.view.itemsize > sizeof(array): + */ + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(__pyx_v_dst, (&__pyx_v_tmp_slice)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 460, __pyx_L1_error) + __pyx_v_dst_slice = __pyx_t_1; + + /* "View.MemoryView":462 + * dst_slice = get_slice_from_memview(dst, &tmp_slice) + * + * if self.view.itemsize > sizeof(array): # <<<<<<<<<<<<<< + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: + */ + __pyx_t_2 = (((size_t)__pyx_v_self->view.itemsize) > (sizeof(__pyx_v_array))); + if (__pyx_t_2) { + + /* "View.MemoryView":463 + * + * if self.view.itemsize > sizeof(array): + * tmp = PyMem_Malloc(self.view.itemsize) # <<<<<<<<<<<<<< + * if tmp == NULL: + * raise MemoryError + */ + __pyx_v_tmp = PyMem_Malloc(__pyx_v_self->view.itemsize); + + /* "View.MemoryView":464 + * if self.view.itemsize > sizeof(array): + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * item = tmp + */ + __pyx_t_2 = (__pyx_v_tmp == NULL); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":465 + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: + * raise MemoryError # <<<<<<<<<<<<<< + * item = tmp + * else: + */ + PyErr_NoMemory(); __PYX_ERR(1, 465, __pyx_L1_error) + + /* "View.MemoryView":464 + * if self.view.itemsize > sizeof(array): + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * item = tmp + */ + } + + /* "View.MemoryView":466 + * if tmp == NULL: + * raise MemoryError + * item = tmp # <<<<<<<<<<<<<< + * else: + * item = array + */ + __pyx_v_item = __pyx_v_tmp; + + /* "View.MemoryView":462 + * dst_slice = get_slice_from_memview(dst, &tmp_slice) + * + * if self.view.itemsize > sizeof(array): # <<<<<<<<<<<<<< + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":468 + * item = tmp + * else: + * item = array # <<<<<<<<<<<<<< + * + * try: + */ + /*else*/ { + __pyx_v_item = ((void *)__pyx_v_array); + } + __pyx_L3:; + + /* "View.MemoryView":470 + * item = array + * + * try: # <<<<<<<<<<<<<< + * if self.dtype_is_object: + * ( item)[0] = value + */ + /*try:*/ { + + /* "View.MemoryView":471 + * + * try: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * ( item)[0] = value + * else: + */ + if (__pyx_v_self->dtype_is_object) { + + /* "View.MemoryView":472 + * try: + * if self.dtype_is_object: + * ( item)[0] = value # <<<<<<<<<<<<<< + * else: + * self.assign_item_from_object( item, value) + */ + (((PyObject **)__pyx_v_item)[0]) = ((PyObject *)__pyx_v_value); + + /* "View.MemoryView":471 + * + * try: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * ( item)[0] = value + * else: + */ + goto __pyx_L8; + } + + /* "View.MemoryView":474 + * ( item)[0] = value + * else: + * self.assign_item_from_object( item, value) # <<<<<<<<<<<<<< + * + * + */ + /*else*/ { + __pyx_t_3 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->assign_item_from_object(__pyx_v_self, ((char *)__pyx_v_item), __pyx_v_value); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 474, __pyx_L6_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_L8:; + + /* "View.MemoryView":478 + * + * + * if self.view.suboffsets != NULL: # <<<<<<<<<<<<<< + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, + */ + __pyx_t_2 = (__pyx_v_self->view.suboffsets != NULL); + if (__pyx_t_2) { + + /* "View.MemoryView":479 + * + * if self.view.suboffsets != NULL: + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) # <<<<<<<<<<<<<< + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, + * item, self.dtype_is_object) + */ + __pyx_t_4 = assert_direct_dimensions(__pyx_v_self->view.suboffsets, __pyx_v_self->view.ndim); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(1, 479, __pyx_L6_error) + + /* "View.MemoryView":478 + * + * + * if self.view.suboffsets != NULL: # <<<<<<<<<<<<<< + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, + */ + } + + /* "View.MemoryView":480 + * if self.view.suboffsets != NULL: + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, # <<<<<<<<<<<<<< + * item, self.dtype_is_object) + * finally: + */ + __pyx_memoryview_slice_assign_scalar(__pyx_v_dst_slice, __pyx_v_dst->view.ndim, __pyx_v_self->view.itemsize, __pyx_v_item, __pyx_v_self->dtype_is_object); + } + + /* "View.MemoryView":483 + * item, self.dtype_is_object) + * finally: + * PyMem_Free(tmp) # <<<<<<<<<<<<<< + * + * cdef setitem_indexed(self, index, value): + */ + /*finally:*/ { + /*normal exit:*/{ + PyMem_Free(__pyx_v_tmp); + goto __pyx_L7; + } + __pyx_L6_error:; + /*exception exit:*/{ + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __pyx_t_7 = 0; __pyx_t_8 = 0; __pyx_t_9 = 0; __pyx_t_10 = 0; __pyx_t_11 = 0; __pyx_t_12 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (PY_MAJOR_VERSION >= 3) __Pyx_ExceptionSwap(&__pyx_t_10, &__pyx_t_11, &__pyx_t_12); + if ((PY_MAJOR_VERSION < 3) || unlikely(__Pyx_GetException(&__pyx_t_7, &__pyx_t_8, &__pyx_t_9) < 0)) __Pyx_ErrFetch(&__pyx_t_7, &__pyx_t_8, &__pyx_t_9); + __Pyx_XGOTREF(__pyx_t_7); + __Pyx_XGOTREF(__pyx_t_8); + __Pyx_XGOTREF(__pyx_t_9); + __Pyx_XGOTREF(__pyx_t_10); + __Pyx_XGOTREF(__pyx_t_11); + __Pyx_XGOTREF(__pyx_t_12); + __pyx_t_4 = __pyx_lineno; __pyx_t_5 = __pyx_clineno; __pyx_t_6 = __pyx_filename; + { + PyMem_Free(__pyx_v_tmp); + } + if (PY_MAJOR_VERSION >= 3) { + __Pyx_XGIVEREF(__pyx_t_10); + __Pyx_XGIVEREF(__pyx_t_11); + __Pyx_XGIVEREF(__pyx_t_12); + __Pyx_ExceptionReset(__pyx_t_10, __pyx_t_11, __pyx_t_12); + } + __Pyx_XGIVEREF(__pyx_t_7); + __Pyx_XGIVEREF(__pyx_t_8); + __Pyx_XGIVEREF(__pyx_t_9); + __Pyx_ErrRestore(__pyx_t_7, __pyx_t_8, __pyx_t_9); + __pyx_t_7 = 0; __pyx_t_8 = 0; __pyx_t_9 = 0; __pyx_t_10 = 0; __pyx_t_11 = 0; __pyx_t_12 = 0; + __pyx_lineno = __pyx_t_4; __pyx_clineno = __pyx_t_5; __pyx_filename = __pyx_t_6; + goto __pyx_L1_error; + } + __pyx_L7:; + } + + /* "View.MemoryView":453 + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) + * + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): # <<<<<<<<<<<<<< + * cdef int array[128] + * cdef void *tmp = NULL + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.setitem_slice_assign_scalar", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":485 + * PyMem_Free(tmp) + * + * cdef setitem_indexed(self, index, value): # <<<<<<<<<<<<<< + * cdef char *itemp = self.get_item_pointer(index) + * self.assign_item_from_object(itemp, value) + */ + +static PyObject *__pyx_memoryview_setitem_indexed(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value) { + char *__pyx_v_itemp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + char *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("setitem_indexed", 1); + + /* "View.MemoryView":486 + * + * cdef setitem_indexed(self, index, value): + * cdef char *itemp = self.get_item_pointer(index) # <<<<<<<<<<<<<< + * self.assign_item_from_object(itemp, value) + * + */ + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->get_item_pointer(__pyx_v_self, __pyx_v_index); if (unlikely(__pyx_t_1 == ((char *)NULL))) __PYX_ERR(1, 486, __pyx_L1_error) + __pyx_v_itemp = __pyx_t_1; + + /* "View.MemoryView":487 + * cdef setitem_indexed(self, index, value): + * cdef char *itemp = self.get_item_pointer(index) + * self.assign_item_from_object(itemp, value) # <<<<<<<<<<<<<< + * + * cdef convert_item_to_object(self, char *itemp): + */ + __pyx_t_2 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->assign_item_from_object(__pyx_v_self, __pyx_v_itemp, __pyx_v_value); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 487, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":485 + * PyMem_Free(tmp) + * + * cdef setitem_indexed(self, index, value): # <<<<<<<<<<<<<< + * cdef char *itemp = self.get_item_pointer(index) + * self.assign_item_from_object(itemp, value) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.setitem_indexed", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":489 + * self.assign_item_from_object(itemp, value) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + +static PyObject *__pyx_memoryview_convert_item_to_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp) { + PyObject *__pyx_v_struct = NULL; + PyObject *__pyx_v_bytesitem = 0; + PyObject *__pyx_v_result = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + int __pyx_t_8; + Py_ssize_t __pyx_t_9; + int __pyx_t_10; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("convert_item_to_object", 1); + + /* "View.MemoryView":492 + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + * import struct # <<<<<<<<<<<<<< + * cdef bytes bytesitem + * + */ + __pyx_t_1 = __Pyx_ImportDottedModule(__pyx_n_s_struct, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 492, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_struct = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":495 + * cdef bytes bytesitem + * + * bytesitem = itemp[:self.view.itemsize] # <<<<<<<<<<<<<< + * try: + * result = struct.unpack(self.view.format, bytesitem) + */ + __pyx_t_1 = __Pyx_PyBytes_FromStringAndSize(__pyx_v_itemp + 0, __pyx_v_self->view.itemsize - 0); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 495, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_bytesitem = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":496 + * + * bytesitem = itemp[:self.view.itemsize] + * try: # <<<<<<<<<<<<<< + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_2, &__pyx_t_3, &__pyx_t_4); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_4); + /*try:*/ { + + /* "View.MemoryView":497 + * bytesitem = itemp[:self.view.itemsize] + * try: + * result = struct.unpack(self.view.format, bytesitem) # <<<<<<<<<<<<<< + * except struct.error: + * raise ValueError, "Unable to convert item to object" + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_unpack); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 497, __pyx_L3_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = __Pyx_PyBytes_FromString(__pyx_v_self->view.format); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 497, __pyx_L3_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_7 = NULL; + __pyx_t_8 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_8 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_7, __pyx_t_6, __pyx_v_bytesitem}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_8, 2+__pyx_t_8); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 497, __pyx_L3_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + __pyx_v_result = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":496 + * + * bytesitem = itemp[:self.view.itemsize] + * try: # <<<<<<<<<<<<<< + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + */ + } + + /* "View.MemoryView":501 + * raise ValueError, "Unable to convert item to object" + * else: + * if len(self.view.format) == 1: # <<<<<<<<<<<<<< + * return result[0] + * return result + */ + /*else:*/ { + __pyx_t_9 = __Pyx_ssize_strlen(__pyx_v_self->view.format); if (unlikely(__pyx_t_9 == ((Py_ssize_t)-1))) __PYX_ERR(1, 501, __pyx_L5_except_error) + __pyx_t_10 = (__pyx_t_9 == 1); + if (__pyx_t_10) { + + /* "View.MemoryView":502 + * else: + * if len(self.view.format) == 1: + * return result[0] # <<<<<<<<<<<<<< + * return result + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_result, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 502, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L6_except_return; + + /* "View.MemoryView":501 + * raise ValueError, "Unable to convert item to object" + * else: + * if len(self.view.format) == 1: # <<<<<<<<<<<<<< + * return result[0] + * return result + */ + } + + /* "View.MemoryView":503 + * if len(self.view.format) == 1: + * return result[0] + * return result # <<<<<<<<<<<<<< + * + * cdef assign_item_from_object(self, char *itemp, object value): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_result); + __pyx_r = __pyx_v_result; + goto __pyx_L6_except_return; + } + __pyx_L3_error:; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":498 + * try: + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: # <<<<<<<<<<<<<< + * raise ValueError, "Unable to convert item to object" + * else: + */ + __Pyx_ErrFetch(&__pyx_t_1, &__pyx_t_5, &__pyx_t_6); + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_error); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 498, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_8 = __Pyx_PyErr_GivenExceptionMatches(__pyx_t_1, __pyx_t_7); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_ErrRestore(__pyx_t_1, __pyx_t_5, __pyx_t_6); + __pyx_t_1 = 0; __pyx_t_5 = 0; __pyx_t_6 = 0; + if (__pyx_t_8) { + __Pyx_AddTraceback("View.MemoryView.memoryview.convert_item_to_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_6, &__pyx_t_5, &__pyx_t_1) < 0) __PYX_ERR(1, 498, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_1); + + /* "View.MemoryView":499 + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + * raise ValueError, "Unable to convert item to object" # <<<<<<<<<<<<<< + * else: + * if len(self.view.format) == 1: + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Unable_to_convert_item_to_object, 0, 0); + __PYX_ERR(1, 499, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "View.MemoryView":496 + * + * bytesitem = itemp[:self.view.itemsize] + * try: # <<<<<<<<<<<<<< + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_ExceptionReset(__pyx_t_2, __pyx_t_3, __pyx_t_4); + goto __pyx_L1_error; + __pyx_L6_except_return:; + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_ExceptionReset(__pyx_t_2, __pyx_t_3, __pyx_t_4); + goto __pyx_L0; + } + + /* "View.MemoryView":489 + * self.assign_item_from_object(itemp, value) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("View.MemoryView.memoryview.convert_item_to_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_struct); + __Pyx_XDECREF(__pyx_v_bytesitem); + __Pyx_XDECREF(__pyx_v_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":505 + * return result + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + +static PyObject *__pyx_memoryview_assign_item_from_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value) { + PyObject *__pyx_v_struct = NULL; + char __pyx_v_c; + PyObject *__pyx_v_bytesvalue = 0; + Py_ssize_t __pyx_v_i; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + Py_ssize_t __pyx_t_7; + PyObject *__pyx_t_8 = NULL; + char *__pyx_t_9; + char *__pyx_t_10; + char *__pyx_t_11; + char *__pyx_t_12; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("assign_item_from_object", 1); + + /* "View.MemoryView":508 + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + * import struct # <<<<<<<<<<<<<< + * cdef char c + * cdef bytes bytesvalue + */ + __pyx_t_1 = __Pyx_ImportDottedModule(__pyx_n_s_struct, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 508, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_struct = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":513 + * cdef Py_ssize_t i + * + * if isinstance(value, tuple): # <<<<<<<<<<<<<< + * bytesvalue = struct.pack(self.view.format, *value) + * else: + */ + __pyx_t_2 = PyTuple_Check(__pyx_v_value); + if (__pyx_t_2) { + + /* "View.MemoryView":514 + * + * if isinstance(value, tuple): + * bytesvalue = struct.pack(self.view.format, *value) # <<<<<<<<<<<<<< + * else: + * bytesvalue = struct.pack(self.view.format, value) + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_pack); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyBytes_FromString(__pyx_v_self->view.format); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PyTuple_New(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_3)) __PYX_ERR(1, 514, __pyx_L1_error); + __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PySequence_Tuple(__pyx_v_value); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = PyNumber_Add(__pyx_t_4, __pyx_t_3); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PyObject_Call(__pyx_t_1, __pyx_t_5, NULL); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (!(likely(PyBytes_CheckExact(__pyx_t_3))||((__pyx_t_3) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_t_3))) __PYX_ERR(1, 514, __pyx_L1_error) + __pyx_v_bytesvalue = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":513 + * cdef Py_ssize_t i + * + * if isinstance(value, tuple): # <<<<<<<<<<<<<< + * bytesvalue = struct.pack(self.view.format, *value) + * else: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":516 + * bytesvalue = struct.pack(self.view.format, *value) + * else: + * bytesvalue = struct.pack(self.view.format, value) # <<<<<<<<<<<<<< + * + * for i, c in enumerate(bytesvalue): + */ + /*else*/ { + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_pack); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 516, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 = __Pyx_PyBytes_FromString(__pyx_v_self->view.format); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 516, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_4 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_4, __pyx_t_1, __pyx_v_value}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 516, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + if (!(likely(PyBytes_CheckExact(__pyx_t_3))||((__pyx_t_3) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_t_3))) __PYX_ERR(1, 516, __pyx_L1_error) + __pyx_v_bytesvalue = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; + } + __pyx_L3:; + + /* "View.MemoryView":518 + * bytesvalue = struct.pack(self.view.format, value) + * + * for i, c in enumerate(bytesvalue): # <<<<<<<<<<<<<< + * itemp[i] = c + * + */ + __pyx_t_7 = 0; + if (unlikely(__pyx_v_bytesvalue == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' is not iterable"); + __PYX_ERR(1, 518, __pyx_L1_error) + } + __Pyx_INCREF(__pyx_v_bytesvalue); + __pyx_t_8 = __pyx_v_bytesvalue; + __pyx_t_10 = PyBytes_AS_STRING(__pyx_t_8); + __pyx_t_11 = (__pyx_t_10 + PyBytes_GET_SIZE(__pyx_t_8)); + for (__pyx_t_12 = __pyx_t_10; __pyx_t_12 < __pyx_t_11; __pyx_t_12++) { + __pyx_t_9 = __pyx_t_12; + __pyx_v_c = (__pyx_t_9[0]); + + /* "View.MemoryView":519 + * + * for i, c in enumerate(bytesvalue): + * itemp[i] = c # <<<<<<<<<<<<<< + * + * @cname('getbuffer') + */ + __pyx_v_i = __pyx_t_7; + + /* "View.MemoryView":518 + * bytesvalue = struct.pack(self.view.format, value) + * + * for i, c in enumerate(bytesvalue): # <<<<<<<<<<<<<< + * itemp[i] = c + * + */ + __pyx_t_7 = (__pyx_t_7 + 1); + + /* "View.MemoryView":519 + * + * for i, c in enumerate(bytesvalue): + * itemp[i] = c # <<<<<<<<<<<<<< + * + * @cname('getbuffer') + */ + (__pyx_v_itemp[__pyx_v_i]) = __pyx_v_c; + } + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + + /* "View.MemoryView":505 + * return result + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("View.MemoryView.memoryview.assign_item_from_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_struct); + __Pyx_XDECREF(__pyx_v_bytesvalue); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":521 + * itemp[i] = c + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: + */ + +/* Python wrapper */ +CYTHON_UNUSED static int __pyx_memoryview_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +CYTHON_UNUSED static int __pyx_memoryview_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getbuffer__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_8__getbuffer__(((struct __pyx_memoryview_obj *)__pyx_v_self), ((Py_buffer *)__pyx_v_info), ((int)__pyx_v_flags)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_8__getbuffer__(struct __pyx_memoryview_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + Py_ssize_t *__pyx_t_3; + char *__pyx_t_4; + void *__pyx_t_5; + int __pyx_t_6; + Py_ssize_t __pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + if (unlikely(__pyx_v_info == NULL)) { + PyErr_SetString(PyExc_BufferError, "PyObject_GetBuffer: view==NULL argument is obsolete"); + return -1; + } + __Pyx_RefNannySetupContext("__getbuffer__", 0); + __pyx_v_info->obj = Py_None; __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(__pyx_v_info->obj); + + /* "View.MemoryView":523 + * @cname('getbuffer') + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: # <<<<<<<<<<<<<< + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + */ + __pyx_t_2 = ((__pyx_v_flags & PyBUF_WRITABLE) != 0); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_1 = __pyx_v_self->view.readonly; + __pyx_L4_bool_binop_done:; + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":524 + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: + * raise ValueError, "Cannot create writable memory view from read-only memoryview" # <<<<<<<<<<<<<< + * + * if flags & PyBUF_ND: + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Cannot_create_writable_memory_vi, 0, 0); + __PYX_ERR(1, 524, __pyx_L1_error) + + /* "View.MemoryView":523 + * @cname('getbuffer') + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: # <<<<<<<<<<<<<< + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + */ + } + + /* "View.MemoryView":526 + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + * if flags & PyBUF_ND: # <<<<<<<<<<<<<< + * info.shape = self.view.shape + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_ND) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":527 + * + * if flags & PyBUF_ND: + * info.shape = self.view.shape # <<<<<<<<<<<<<< + * else: + * info.shape = NULL + */ + __pyx_t_3 = __pyx_v_self->view.shape; + __pyx_v_info->shape = __pyx_t_3; + + /* "View.MemoryView":526 + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + * if flags & PyBUF_ND: # <<<<<<<<<<<<<< + * info.shape = self.view.shape + * else: + */ + goto __pyx_L6; + } + + /* "View.MemoryView":529 + * info.shape = self.view.shape + * else: + * info.shape = NULL # <<<<<<<<<<<<<< + * + * if flags & PyBUF_STRIDES: + */ + /*else*/ { + __pyx_v_info->shape = NULL; + } + __pyx_L6:; + + /* "View.MemoryView":531 + * info.shape = NULL + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.strides = self.view.strides + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_STRIDES) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":532 + * + * if flags & PyBUF_STRIDES: + * info.strides = self.view.strides # <<<<<<<<<<<<<< + * else: + * info.strides = NULL + */ + __pyx_t_3 = __pyx_v_self->view.strides; + __pyx_v_info->strides = __pyx_t_3; + + /* "View.MemoryView":531 + * info.shape = NULL + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.strides = self.view.strides + * else: + */ + goto __pyx_L7; + } + + /* "View.MemoryView":534 + * info.strides = self.view.strides + * else: + * info.strides = NULL # <<<<<<<<<<<<<< + * + * if flags & PyBUF_INDIRECT: + */ + /*else*/ { + __pyx_v_info->strides = NULL; + } + __pyx_L7:; + + /* "View.MemoryView":536 + * info.strides = NULL + * + * if flags & PyBUF_INDIRECT: # <<<<<<<<<<<<<< + * info.suboffsets = self.view.suboffsets + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_INDIRECT) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":537 + * + * if flags & PyBUF_INDIRECT: + * info.suboffsets = self.view.suboffsets # <<<<<<<<<<<<<< + * else: + * info.suboffsets = NULL + */ + __pyx_t_3 = __pyx_v_self->view.suboffsets; + __pyx_v_info->suboffsets = __pyx_t_3; + + /* "View.MemoryView":536 + * info.strides = NULL + * + * if flags & PyBUF_INDIRECT: # <<<<<<<<<<<<<< + * info.suboffsets = self.view.suboffsets + * else: + */ + goto __pyx_L8; + } + + /* "View.MemoryView":539 + * info.suboffsets = self.view.suboffsets + * else: + * info.suboffsets = NULL # <<<<<<<<<<<<<< + * + * if flags & PyBUF_FORMAT: + */ + /*else*/ { + __pyx_v_info->suboffsets = NULL; + } + __pyx_L8:; + + /* "View.MemoryView":541 + * info.suboffsets = NULL + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * info.format = self.view.format + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_FORMAT) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":542 + * + * if flags & PyBUF_FORMAT: + * info.format = self.view.format # <<<<<<<<<<<<<< + * else: + * info.format = NULL + */ + __pyx_t_4 = __pyx_v_self->view.format; + __pyx_v_info->format = __pyx_t_4; + + /* "View.MemoryView":541 + * info.suboffsets = NULL + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * info.format = self.view.format + * else: + */ + goto __pyx_L9; + } + + /* "View.MemoryView":544 + * info.format = self.view.format + * else: + * info.format = NULL # <<<<<<<<<<<<<< + * + * info.buf = self.view.buf + */ + /*else*/ { + __pyx_v_info->format = NULL; + } + __pyx_L9:; + + /* "View.MemoryView":546 + * info.format = NULL + * + * info.buf = self.view.buf # <<<<<<<<<<<<<< + * info.ndim = self.view.ndim + * info.itemsize = self.view.itemsize + */ + __pyx_t_5 = __pyx_v_self->view.buf; + __pyx_v_info->buf = __pyx_t_5; + + /* "View.MemoryView":547 + * + * info.buf = self.view.buf + * info.ndim = self.view.ndim # <<<<<<<<<<<<<< + * info.itemsize = self.view.itemsize + * info.len = self.view.len + */ + __pyx_t_6 = __pyx_v_self->view.ndim; + __pyx_v_info->ndim = __pyx_t_6; + + /* "View.MemoryView":548 + * info.buf = self.view.buf + * info.ndim = self.view.ndim + * info.itemsize = self.view.itemsize # <<<<<<<<<<<<<< + * info.len = self.view.len + * info.readonly = self.view.readonly + */ + __pyx_t_7 = __pyx_v_self->view.itemsize; + __pyx_v_info->itemsize = __pyx_t_7; + + /* "View.MemoryView":549 + * info.ndim = self.view.ndim + * info.itemsize = self.view.itemsize + * info.len = self.view.len # <<<<<<<<<<<<<< + * info.readonly = self.view.readonly + * info.obj = self + */ + __pyx_t_7 = __pyx_v_self->view.len; + __pyx_v_info->len = __pyx_t_7; + + /* "View.MemoryView":550 + * info.itemsize = self.view.itemsize + * info.len = self.view.len + * info.readonly = self.view.readonly # <<<<<<<<<<<<<< + * info.obj = self + * + */ + __pyx_t_1 = __pyx_v_self->view.readonly; + __pyx_v_info->readonly = __pyx_t_1; + + /* "View.MemoryView":551 + * info.len = self.view.len + * info.readonly = self.view.readonly + * info.obj = self # <<<<<<<<<<<<<< + * + * + */ + __Pyx_INCREF((PyObject *)__pyx_v_self); + __Pyx_GIVEREF((PyObject *)__pyx_v_self); + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); + __pyx_v_info->obj = ((PyObject *)__pyx_v_self); + + /* "View.MemoryView":521 + * itemp[i] = c + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__getbuffer__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + if (__pyx_v_info->obj != NULL) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + goto __pyx_L2; + __pyx_L0:; + if (__pyx_v_info->obj == Py_None) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + __pyx_L2:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":554 + * + * + * @property # <<<<<<<<<<<<<< + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_1T_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_1T_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_1T___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_1T___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + struct __pyx_memoryviewslice_obj *__pyx_v_result = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":556 + * @property + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) # <<<<<<<<<<<<<< + * transpose_memslice(&result.from_slice) + * return result + */ + __pyx_t_1 = __pyx_memoryview_copy_object(__pyx_v_self); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 556, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (!(likely(((__pyx_t_1) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_1, __pyx_memoryviewslice_type))))) __PYX_ERR(1, 556, __pyx_L1_error) + __pyx_v_result = ((struct __pyx_memoryviewslice_obj *)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":557 + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) + * transpose_memslice(&result.from_slice) # <<<<<<<<<<<<<< + * return result + * + */ + __pyx_t_2 = __pyx_memslice_transpose((&__pyx_v_result->from_slice)); if (unlikely(__pyx_t_2 == ((int)-1))) __PYX_ERR(1, 557, __pyx_L1_error) + + /* "View.MemoryView":558 + * cdef _memoryviewslice result = memoryview_copy(self) + * transpose_memslice(&result.from_slice) + * return result # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = ((PyObject *)__pyx_v_result); + goto __pyx_L0; + + /* "View.MemoryView":554 + * + * + * @property # <<<<<<<<<<<<<< + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.T.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":560 + * return result + * + * @property # <<<<<<<<<<<<<< + * def base(self): + * return self._get_base() + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4base_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4base_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_4base___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4base___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":562 + * @property + * def base(self): + * return self._get_base() # <<<<<<<<<<<<<< + * + * cdef _get_base(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->_get_base(__pyx_v_self); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 562, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":560 + * return result + * + * @property # <<<<<<<<<<<<<< + * def base(self): + * return self._get_base() + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.base.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":564 + * return self._get_base() + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.obj + * + */ + +static PyObject *__pyx_memoryview__get_base(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("_get_base", 1); + + /* "View.MemoryView":565 + * + * cdef _get_base(self): + * return self.obj # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->obj); + __pyx_r = __pyx_v_self->obj; + goto __pyx_L0; + + /* "View.MemoryView":564 + * return self._get_base() + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.obj + * + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":567 + * return self.obj + * + * @property # <<<<<<<<<<<<<< + * def shape(self): + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_5shape_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_5shape_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_5shape___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_5shape___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_7genexpr__pyx_v_length; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + PyObject *__pyx_t_5 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":569 + * @property + * def shape(self): + * return tuple([length for length in self.view.shape[:self.view.ndim]]) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + { /* enter inner scope */ + __pyx_t_1 = PyList_New(0); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 569, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = (__pyx_v_self->view.shape + __pyx_v_self->view.ndim); + for (__pyx_t_4 = __pyx_v_self->view.shape; __pyx_t_4 < __pyx_t_3; __pyx_t_4++) { + __pyx_t_2 = __pyx_t_4; + __pyx_7genexpr__pyx_v_length = (__pyx_t_2[0]); + __pyx_t_5 = PyInt_FromSsize_t(__pyx_7genexpr__pyx_v_length); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 569, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_1, (PyObject*)__pyx_t_5))) __PYX_ERR(1, 569, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + } /* exit inner scope */ + __pyx_t_5 = PyList_AsTuple(((PyObject*)__pyx_t_1)); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 569, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_5; + __pyx_t_5 = 0; + goto __pyx_L0; + + /* "View.MemoryView":567 + * return self.obj + * + * @property # <<<<<<<<<<<<<< + * def shape(self): + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.memoryview.shape.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":571 + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def strides(self): + * if self.view.strides == NULL: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_7strides_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_7strides_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_7strides___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_7strides___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_8genexpr1__pyx_v_stride; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + Py_ssize_t *__pyx_t_5; + PyObject *__pyx_t_6 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":573 + * @property + * def strides(self): + * if self.view.strides == NULL: # <<<<<<<<<<<<<< + * + * raise ValueError, "Buffer view does not expose strides" + */ + __pyx_t_1 = (__pyx_v_self->view.strides == NULL); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":575 + * if self.view.strides == NULL: + * + * raise ValueError, "Buffer view does not expose strides" # <<<<<<<<<<<<<< + * + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Buffer_view_does_not_expose_stri, 0, 0); + __PYX_ERR(1, 575, __pyx_L1_error) + + /* "View.MemoryView":573 + * @property + * def strides(self): + * if self.view.strides == NULL: # <<<<<<<<<<<<<< + * + * raise ValueError, "Buffer view does not expose strides" + */ + } + + /* "View.MemoryView":577 + * raise ValueError, "Buffer view does not expose strides" + * + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + { /* enter inner scope */ + __pyx_t_2 = PyList_New(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 577, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = (__pyx_v_self->view.strides + __pyx_v_self->view.ndim); + for (__pyx_t_5 = __pyx_v_self->view.strides; __pyx_t_5 < __pyx_t_4; __pyx_t_5++) { + __pyx_t_3 = __pyx_t_5; + __pyx_8genexpr1__pyx_v_stride = (__pyx_t_3[0]); + __pyx_t_6 = PyInt_FromSsize_t(__pyx_8genexpr1__pyx_v_stride); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 577, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_2, (PyObject*)__pyx_t_6))) __PYX_ERR(1, 577, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + } /* exit inner scope */ + __pyx_t_6 = PyList_AsTuple(((PyObject*)__pyx_t_2)); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 577, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_6; + __pyx_t_6 = 0; + goto __pyx_L0; + + /* "View.MemoryView":571 + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def strides(self): + * if self.view.strides == NULL: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("View.MemoryView.memoryview.strides.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":579 + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def suboffsets(self): + * if self.view.suboffsets == NULL: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_10suboffsets_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_10suboffsets_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_10suboffsets___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_10suboffsets___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_8genexpr2__pyx_v_suboffset; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + Py_ssize_t *__pyx_t_5; + PyObject *__pyx_t_6 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":581 + * @property + * def suboffsets(self): + * if self.view.suboffsets == NULL: # <<<<<<<<<<<<<< + * return (-1,) * self.view.ndim + * + */ + __pyx_t_1 = (__pyx_v_self->view.suboffsets == NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":582 + * def suboffsets(self): + * if self.view.suboffsets == NULL: + * return (-1,) * self.view.ndim # <<<<<<<<<<<<<< + * + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PySequence_Multiply(__pyx_tuple__4, __pyx_v_self->view.ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 582, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":581 + * @property + * def suboffsets(self): + * if self.view.suboffsets == NULL: # <<<<<<<<<<<<<< + * return (-1,) * self.view.ndim + * + */ + } + + /* "View.MemoryView":584 + * return (-1,) * self.view.ndim + * + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + { /* enter inner scope */ + __pyx_t_2 = PyList_New(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 584, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = (__pyx_v_self->view.suboffsets + __pyx_v_self->view.ndim); + for (__pyx_t_5 = __pyx_v_self->view.suboffsets; __pyx_t_5 < __pyx_t_4; __pyx_t_5++) { + __pyx_t_3 = __pyx_t_5; + __pyx_8genexpr2__pyx_v_suboffset = (__pyx_t_3[0]); + __pyx_t_6 = PyInt_FromSsize_t(__pyx_8genexpr2__pyx_v_suboffset); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 584, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_2, (PyObject*)__pyx_t_6))) __PYX_ERR(1, 584, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + } /* exit inner scope */ + __pyx_t_6 = PyList_AsTuple(((PyObject*)__pyx_t_2)); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 584, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_6; + __pyx_t_6 = 0; + goto __pyx_L0; + + /* "View.MemoryView":579 + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def suboffsets(self): + * if self.view.suboffsets == NULL: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("View.MemoryView.memoryview.suboffsets.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":586 + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def ndim(self): + * return self.view.ndim + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4ndim_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4ndim_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_4ndim___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4ndim___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":588 + * @property + * def ndim(self): + * return self.view.ndim # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_self->view.ndim); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 588, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":586 + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def ndim(self): + * return self.view.ndim + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.ndim.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":590 + * return self.view.ndim + * + * @property # <<<<<<<<<<<<<< + * def itemsize(self): + * return self.view.itemsize + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_8itemsize_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_8itemsize_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_8itemsize___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_8itemsize___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":592 + * @property + * def itemsize(self): + * return self.view.itemsize # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyInt_FromSsize_t(__pyx_v_self->view.itemsize); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 592, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":590 + * return self.view.ndim + * + * @property # <<<<<<<<<<<<<< + * def itemsize(self): + * return self.view.itemsize + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.itemsize.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":594 + * return self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def nbytes(self): + * return self.size * self.view.itemsize + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_6nbytes_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_6nbytes_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_6nbytes___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_6nbytes___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":596 + * @property + * def nbytes(self): + * return self.size * self.view.itemsize # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_size); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 596, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = PyInt_FromSsize_t(__pyx_v_self->view.itemsize); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 596, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyNumber_Multiply(__pyx_t_1, __pyx_t_2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 596, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_3; + __pyx_t_3 = 0; + goto __pyx_L0; + + /* "View.MemoryView":594 + * return self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def nbytes(self): + * return self.size * self.view.itemsize + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.nbytes.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":598 + * return self.size * self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def size(self): + * if self._size is None: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4size_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4size_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_4size___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4size___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_v_result = NULL; + PyObject *__pyx_v_length = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + PyObject *__pyx_t_5 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":600 + * @property + * def size(self): + * if self._size is None: # <<<<<<<<<<<<<< + * result = 1 + * + */ + __pyx_t_1 = (__pyx_v_self->_size == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":601 + * def size(self): + * if self._size is None: + * result = 1 # <<<<<<<<<<<<<< + * + * for length in self.view.shape[:self.view.ndim]: + */ + __Pyx_INCREF(__pyx_int_1); + __pyx_v_result = __pyx_int_1; + + /* "View.MemoryView":603 + * result = 1 + * + * for length in self.view.shape[:self.view.ndim]: # <<<<<<<<<<<<<< + * result *= length + * + */ + __pyx_t_3 = (__pyx_v_self->view.shape + __pyx_v_self->view.ndim); + for (__pyx_t_4 = __pyx_v_self->view.shape; __pyx_t_4 < __pyx_t_3; __pyx_t_4++) { + __pyx_t_2 = __pyx_t_4; + __pyx_t_5 = PyInt_FromSsize_t((__pyx_t_2[0])); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 603, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_XDECREF_SET(__pyx_v_length, __pyx_t_5); + __pyx_t_5 = 0; + + /* "View.MemoryView":604 + * + * for length in self.view.shape[:self.view.ndim]: + * result *= length # <<<<<<<<<<<<<< + * + * self._size = result + */ + __pyx_t_5 = PyNumber_InPlaceMultiply(__pyx_v_result, __pyx_v_length); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 604, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF_SET(__pyx_v_result, __pyx_t_5); + __pyx_t_5 = 0; + } + + /* "View.MemoryView":606 + * result *= length + * + * self._size = result # <<<<<<<<<<<<<< + * + * return self._size + */ + __Pyx_INCREF(__pyx_v_result); + __Pyx_GIVEREF(__pyx_v_result); + __Pyx_GOTREF(__pyx_v_self->_size); + __Pyx_DECREF(__pyx_v_self->_size); + __pyx_v_self->_size = __pyx_v_result; + + /* "View.MemoryView":600 + * @property + * def size(self): + * if self._size is None: # <<<<<<<<<<<<<< + * result = 1 + * + */ + } + + /* "View.MemoryView":608 + * self._size = result + * + * return self._size # <<<<<<<<<<<<<< + * + * def __len__(self): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->_size); + __pyx_r = __pyx_v_self->_size; + goto __pyx_L0; + + /* "View.MemoryView":598 + * return self.size * self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def size(self): + * if self._size is None: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.memoryview.size.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_result); + __Pyx_XDECREF(__pyx_v_length); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":610 + * return self._size + * + * def __len__(self): # <<<<<<<<<<<<<< + * if self.view.ndim >= 1: + * return self.view.shape[0] + */ + +/* Python wrapper */ +static Py_ssize_t __pyx_memoryview___len__(PyObject *__pyx_v_self); /*proto*/ +static Py_ssize_t __pyx_memoryview___len__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + Py_ssize_t __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__len__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_10__len__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static Py_ssize_t __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_10__len__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_r; + int __pyx_t_1; + + /* "View.MemoryView":611 + * + * def __len__(self): + * if self.view.ndim >= 1: # <<<<<<<<<<<<<< + * return self.view.shape[0] + * + */ + __pyx_t_1 = (__pyx_v_self->view.ndim >= 1); + if (__pyx_t_1) { + + /* "View.MemoryView":612 + * def __len__(self): + * if self.view.ndim >= 1: + * return self.view.shape[0] # <<<<<<<<<<<<<< + * + * return 0 + */ + __pyx_r = (__pyx_v_self->view.shape[0]); + goto __pyx_L0; + + /* "View.MemoryView":611 + * + * def __len__(self): + * if self.view.ndim >= 1: # <<<<<<<<<<<<<< + * return self.view.shape[0] + * + */ + } + + /* "View.MemoryView":614 + * return self.view.shape[0] + * + * return 0 # <<<<<<<<<<<<<< + * + * def __repr__(self): + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":610 + * return self._size + * + * def __len__(self): # <<<<<<<<<<<<<< + * if self.view.ndim >= 1: + * return self.view.shape[0] + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":616 + * return 0 + * + * def __repr__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__, + * id(self)) + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview___repr__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_memoryview___repr__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__repr__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_12__repr__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_12__repr__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__repr__", 1); + + /* "View.MemoryView":617 + * + * def __repr__(self): + * return "" % (self.base.__class__.__name__, # <<<<<<<<<<<<<< + * id(self)) + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_base); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_class); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_name_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":618 + * def __repr__(self): + * return "" % (self.base.__class__.__name__, + * id(self)) # <<<<<<<<<<<<<< + * + * def __str__(self): + */ + __pyx_t_2 = __Pyx_PyObject_CallOneArg(__pyx_builtin_id, ((PyObject *)__pyx_v_self)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 618, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + + /* "View.MemoryView":617 + * + * def __repr__(self): + * return "" % (self.base.__class__.__name__, # <<<<<<<<<<<<<< + * id(self)) + * + */ + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_1)) __PYX_ERR(1, 617, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_2)) __PYX_ERR(1, 617, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyString_Format(__pyx_kp_s_MemoryView_of_r_at_0x_x, __pyx_t_3); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":616 + * return 0 + * + * def __repr__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__, + * id(self)) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.__repr__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":620 + * id(self)) + * + * def __str__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__,) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview___str__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_memoryview___str__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__str__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_14__str__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_14__str__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__str__", 1); + + /* "View.MemoryView":621 + * + * def __str__(self): + * return "" % (self.base.__class__.__name__,) # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_base); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_class); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_name_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = PyTuple_New(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_t_1)) __PYX_ERR(1, 621, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_MemoryView_of_r_object, __pyx_t_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":620 + * id(self)) + * + * def __str__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__,) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.__str__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":624 + * + * + * def is_c_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_is_c_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_is_c_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("is_c_contig (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("is_c_contig", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "is_c_contig", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_16is_c_contig(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_16is_c_contig(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice *__pyx_v_mslice; + __Pyx_memviewslice __pyx_v_tmp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("is_c_contig", 1); + + /* "View.MemoryView":627 + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) # <<<<<<<<<<<<<< + * return slice_is_contig(mslice[0], 'C', self.view.ndim) + * + */ + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(__pyx_v_self, (&__pyx_v_tmp)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 627, __pyx_L1_error) + __pyx_v_mslice = __pyx_t_1; + + /* "View.MemoryView":628 + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) + * return slice_is_contig(mslice[0], 'C', self.view.ndim) # <<<<<<<<<<<<<< + * + * def is_f_contig(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_memviewslice_is_contig((__pyx_v_mslice[0]), 'C', __pyx_v_self->view.ndim)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 628, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":624 + * + * + * def is_c_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.is_c_contig", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":630 + * return slice_is_contig(mslice[0], 'C', self.view.ndim) + * + * def is_f_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_is_f_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_is_f_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("is_f_contig (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("is_f_contig", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "is_f_contig", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_18is_f_contig(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_18is_f_contig(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice *__pyx_v_mslice; + __Pyx_memviewslice __pyx_v_tmp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("is_f_contig", 1); + + /* "View.MemoryView":633 + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) # <<<<<<<<<<<<<< + * return slice_is_contig(mslice[0], 'F', self.view.ndim) + * + */ + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(__pyx_v_self, (&__pyx_v_tmp)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 633, __pyx_L1_error) + __pyx_v_mslice = __pyx_t_1; + + /* "View.MemoryView":634 + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) + * return slice_is_contig(mslice[0], 'F', self.view.ndim) # <<<<<<<<<<<<<< + * + * def copy(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_memviewslice_is_contig((__pyx_v_mslice[0]), 'F', __pyx_v_self->view.ndim)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 634, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":630 + * return slice_is_contig(mslice[0], 'C', self.view.ndim) + * + * def is_f_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.is_f_contig", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":636 + * return slice_is_contig(mslice[0], 'F', self.view.ndim) + * + * def copy(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice mslice + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_copy(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_copy(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("copy (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("copy", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "copy", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_20copy(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_20copy(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice __pyx_v_mslice; + int __pyx_v_flags; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("copy", 1); + + /* "View.MemoryView":638 + * def copy(self): + * cdef __Pyx_memviewslice mslice + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS # <<<<<<<<<<<<<< + * + * slice_copy(self, &mslice) + */ + __pyx_v_flags = (__pyx_v_self->flags & (~PyBUF_F_CONTIGUOUS)); + + /* "View.MemoryView":640 + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS + * + * slice_copy(self, &mslice) # <<<<<<<<<<<<<< + * mslice = slice_copy_contig(&mslice, "c", self.view.ndim, + * self.view.itemsize, + */ + __pyx_memoryview_slice_copy(__pyx_v_self, (&__pyx_v_mslice)); + + /* "View.MemoryView":641 + * + * slice_copy(self, &mslice) + * mslice = slice_copy_contig(&mslice, "c", self.view.ndim, # <<<<<<<<<<<<<< + * self.view.itemsize, + * flags|PyBUF_C_CONTIGUOUS, + */ + __pyx_t_1 = __pyx_memoryview_copy_new_contig((&__pyx_v_mslice), ((char *)"c"), __pyx_v_self->view.ndim, __pyx_v_self->view.itemsize, (__pyx_v_flags | PyBUF_C_CONTIGUOUS), __pyx_v_self->dtype_is_object); if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 641, __pyx_L1_error) + __pyx_v_mslice = __pyx_t_1; + + /* "View.MemoryView":646 + * self.dtype_is_object) + * + * return memoryview_copy_from_slice(self, &mslice) # <<<<<<<<<<<<<< + * + * def copy_fortran(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_memoryview_copy_object_from_slice(__pyx_v_self, (&__pyx_v_mslice)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 646, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":636 + * return slice_is_contig(mslice[0], 'F', self.view.ndim) + * + * def copy(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice mslice + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.copy", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":648 + * return memoryview_copy_from_slice(self, &mslice) + * + * def copy_fortran(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice src, dst + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_copy_fortran(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_copy_fortran(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("copy_fortran (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("copy_fortran", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "copy_fortran", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_22copy_fortran(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_22copy_fortran(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice __pyx_v_src; + __Pyx_memviewslice __pyx_v_dst; + int __pyx_v_flags; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("copy_fortran", 1); + + /* "View.MemoryView":650 + * def copy_fortran(self): + * cdef __Pyx_memviewslice src, dst + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS # <<<<<<<<<<<<<< + * + * slice_copy(self, &src) + */ + __pyx_v_flags = (__pyx_v_self->flags & (~PyBUF_C_CONTIGUOUS)); + + /* "View.MemoryView":652 + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS + * + * slice_copy(self, &src) # <<<<<<<<<<<<<< + * dst = slice_copy_contig(&src, "fortran", self.view.ndim, + * self.view.itemsize, + */ + __pyx_memoryview_slice_copy(__pyx_v_self, (&__pyx_v_src)); + + /* "View.MemoryView":653 + * + * slice_copy(self, &src) + * dst = slice_copy_contig(&src, "fortran", self.view.ndim, # <<<<<<<<<<<<<< + * self.view.itemsize, + * flags|PyBUF_F_CONTIGUOUS, + */ + __pyx_t_1 = __pyx_memoryview_copy_new_contig((&__pyx_v_src), ((char *)"fortran"), __pyx_v_self->view.ndim, __pyx_v_self->view.itemsize, (__pyx_v_flags | PyBUF_F_CONTIGUOUS), __pyx_v_self->dtype_is_object); if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 653, __pyx_L1_error) + __pyx_v_dst = __pyx_t_1; + + /* "View.MemoryView":658 + * self.dtype_is_object) + * + * return memoryview_copy_from_slice(self, &dst) # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_memoryview_copy_object_from_slice(__pyx_v_self, (&__pyx_v_dst)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 658, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":648 + * return memoryview_copy_from_slice(self, &mslice) + * + * def copy_fortran(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice src, dst + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.copy_fortran", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryview_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryview_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_memoryview___reduce_cython__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryview___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryview_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryview_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.memoryview.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_memoryview_2__setstate_cython__(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryview_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":662 + * + * @cname('__pyx_memoryview_new') + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): # <<<<<<<<<<<<<< + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo + */ + +static PyObject *__pyx_memoryview_new(PyObject *__pyx_v_o, int __pyx_v_flags, int __pyx_v_dtype_is_object, __Pyx_TypeInfo *__pyx_v_typeinfo) { + struct __pyx_memoryview_obj *__pyx_v_result = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_cwrapper", 1); + + /* "View.MemoryView":663 + * @cname('__pyx_memoryview_new') + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): + * cdef memoryview result = memoryview(o, flags, dtype_is_object) # <<<<<<<<<<<<<< + * result.typeinfo = typeinfo + * return result + */ + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_flags); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_v_dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_v_o); + __Pyx_GIVEREF(__pyx_v_o); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_v_o)) __PYX_ERR(1, 663, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1)) __PYX_ERR(1, 663, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_t_2)) __PYX_ERR(1, 663, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_Call(((PyObject *)__pyx_memoryview_type), __pyx_t_3, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_v_result = ((struct __pyx_memoryview_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":664 + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo # <<<<<<<<<<<<<< + * return result + * + */ + __pyx_v_result->typeinfo = __pyx_v_typeinfo; + + /* "View.MemoryView":665 + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo + * return result # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_check') + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = ((PyObject *)__pyx_v_result); + goto __pyx_L0; + + /* "View.MemoryView":662 + * + * @cname('__pyx_memoryview_new') + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): # <<<<<<<<<<<<<< + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview_cwrapper", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":668 + * + * @cname('__pyx_memoryview_check') + * cdef inline bint memoryview_check(object o) noexcept: # <<<<<<<<<<<<<< + * return isinstance(o, memoryview) + * + */ + +static CYTHON_INLINE int __pyx_memoryview_check(PyObject *__pyx_v_o) { + int __pyx_r; + int __pyx_t_1; + + /* "View.MemoryView":669 + * @cname('__pyx_memoryview_check') + * cdef inline bint memoryview_check(object o) noexcept: + * return isinstance(o, memoryview) # <<<<<<<<<<<<<< + * + * cdef tuple _unellipsify(object index, int ndim): + */ + __pyx_t_1 = __Pyx_TypeCheck(__pyx_v_o, __pyx_memoryview_type); + __pyx_r = __pyx_t_1; + goto __pyx_L0; + + /* "View.MemoryView":668 + * + * @cname('__pyx_memoryview_check') + * cdef inline bint memoryview_check(object o) noexcept: # <<<<<<<<<<<<<< + * return isinstance(o, memoryview) + * + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":671 + * return isinstance(o, memoryview) + * + * cdef tuple _unellipsify(object index, int ndim): # <<<<<<<<<<<<<< + * """ + * Replace all ellipses with full slices and fill incomplete indices with + */ + +static PyObject *_unellipsify(PyObject *__pyx_v_index, int __pyx_v_ndim) { + Py_ssize_t __pyx_v_idx; + PyObject *__pyx_v_tup = NULL; + PyObject *__pyx_v_result = NULL; + int __pyx_v_have_slices; + int __pyx_v_seen_ellipsis; + PyObject *__pyx_v_item = NULL; + Py_ssize_t __pyx_v_nslices; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + Py_ssize_t __pyx_t_4; + Py_ssize_t __pyx_t_5; + Py_UCS4 __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("_unellipsify", 1); + + /* "View.MemoryView":677 + * """ + * cdef Py_ssize_t idx + * tup = index if isinstance(index, tuple) else (index,) # <<<<<<<<<<<<<< + * + * result = [slice(None)] * ndim + */ + __pyx_t_2 = PyTuple_Check(__pyx_v_index); + if (__pyx_t_2) { + __Pyx_INCREF(((PyObject*)__pyx_v_index)); + __pyx_t_1 = __pyx_v_index; + } else { + __pyx_t_3 = PyTuple_New(1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 677, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_v_index); + __Pyx_GIVEREF(__pyx_v_index); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_v_index)) __PYX_ERR(1, 677, __pyx_L1_error); + __pyx_t_1 = __pyx_t_3; + __pyx_t_3 = 0; + } + __pyx_v_tup = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":679 + * tup = index if isinstance(index, tuple) else (index,) + * + * result = [slice(None)] * ndim # <<<<<<<<<<<<<< + * have_slices = False + * seen_ellipsis = False + */ + __pyx_t_1 = PyList_New(1 * ((__pyx_v_ndim<0) ? 0:__pyx_v_ndim)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 679, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + { Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < __pyx_v_ndim; __pyx_temp++) { + __Pyx_INCREF(__pyx_slice__5); + __Pyx_GIVEREF(__pyx_slice__5); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, __pyx_temp, __pyx_slice__5)) __PYX_ERR(1, 679, __pyx_L1_error); + } + } + __pyx_v_result = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":680 + * + * result = [slice(None)] * ndim + * have_slices = False # <<<<<<<<<<<<<< + * seen_ellipsis = False + * idx = 0 + */ + __pyx_v_have_slices = 0; + + /* "View.MemoryView":681 + * result = [slice(None)] * ndim + * have_slices = False + * seen_ellipsis = False # <<<<<<<<<<<<<< + * idx = 0 + * for item in tup: + */ + __pyx_v_seen_ellipsis = 0; + + /* "View.MemoryView":682 + * have_slices = False + * seen_ellipsis = False + * idx = 0 # <<<<<<<<<<<<<< + * for item in tup: + * if item is Ellipsis: + */ + __pyx_v_idx = 0; + + /* "View.MemoryView":683 + * seen_ellipsis = False + * idx = 0 + * for item in tup: # <<<<<<<<<<<<<< + * if item is Ellipsis: + * if not seen_ellipsis: + */ + if (unlikely(__pyx_v_tup == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not iterable"); + __PYX_ERR(1, 683, __pyx_L1_error) + } + __pyx_t_1 = __pyx_v_tup; __Pyx_INCREF(__pyx_t_1); + __pyx_t_4 = 0; + for (;;) { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_1); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 683, __pyx_L1_error) + #endif + if (__pyx_t_4 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_3 = PyTuple_GET_ITEM(__pyx_t_1, __pyx_t_4); __Pyx_INCREF(__pyx_t_3); __pyx_t_4++; if (unlikely((0 < 0))) __PYX_ERR(1, 683, __pyx_L1_error) + #else + __pyx_t_3 = __Pyx_PySequence_ITEM(__pyx_t_1, __pyx_t_4); __pyx_t_4++; if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 683, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + #endif + __Pyx_XDECREF_SET(__pyx_v_item, __pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":684 + * idx = 0 + * for item in tup: + * if item is Ellipsis: # <<<<<<<<<<<<<< + * if not seen_ellipsis: + * idx += ndim - len(tup) + */ + __pyx_t_2 = (__pyx_v_item == __pyx_builtin_Ellipsis); + if (__pyx_t_2) { + + /* "View.MemoryView":685 + * for item in tup: + * if item is Ellipsis: + * if not seen_ellipsis: # <<<<<<<<<<<<<< + * idx += ndim - len(tup) + * seen_ellipsis = True + */ + __pyx_t_2 = (!__pyx_v_seen_ellipsis); + if (__pyx_t_2) { + + /* "View.MemoryView":686 + * if item is Ellipsis: + * if not seen_ellipsis: + * idx += ndim - len(tup) # <<<<<<<<<<<<<< + * seen_ellipsis = True + * have_slices = True + */ + if (unlikely(__pyx_v_tup == Py_None)) { + PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); + __PYX_ERR(1, 686, __pyx_L1_error) + } + __pyx_t_5 = __Pyx_PyTuple_GET_SIZE(__pyx_v_tup); if (unlikely(__pyx_t_5 == ((Py_ssize_t)-1))) __PYX_ERR(1, 686, __pyx_L1_error) + __pyx_v_idx = (__pyx_v_idx + (__pyx_v_ndim - __pyx_t_5)); + + /* "View.MemoryView":687 + * if not seen_ellipsis: + * idx += ndim - len(tup) + * seen_ellipsis = True # <<<<<<<<<<<<<< + * have_slices = True + * else: + */ + __pyx_v_seen_ellipsis = 1; + + /* "View.MemoryView":685 + * for item in tup: + * if item is Ellipsis: + * if not seen_ellipsis: # <<<<<<<<<<<<<< + * idx += ndim - len(tup) + * seen_ellipsis = True + */ + } + + /* "View.MemoryView":688 + * idx += ndim - len(tup) + * seen_ellipsis = True + * have_slices = True # <<<<<<<<<<<<<< + * else: + * if isinstance(item, slice): + */ + __pyx_v_have_slices = 1; + + /* "View.MemoryView":684 + * idx = 0 + * for item in tup: + * if item is Ellipsis: # <<<<<<<<<<<<<< + * if not seen_ellipsis: + * idx += ndim - len(tup) + */ + goto __pyx_L5; + } + + /* "View.MemoryView":690 + * have_slices = True + * else: + * if isinstance(item, slice): # <<<<<<<<<<<<<< + * have_slices = True + * elif not PyIndex_Check(item): + */ + /*else*/ { + __pyx_t_2 = PySlice_Check(__pyx_v_item); + if (__pyx_t_2) { + + /* "View.MemoryView":691 + * else: + * if isinstance(item, slice): + * have_slices = True # <<<<<<<<<<<<<< + * elif not PyIndex_Check(item): + * raise TypeError, f"Cannot index with type '{type(item)}'" + */ + __pyx_v_have_slices = 1; + + /* "View.MemoryView":690 + * have_slices = True + * else: + * if isinstance(item, slice): # <<<<<<<<<<<<<< + * have_slices = True + * elif not PyIndex_Check(item): + */ + goto __pyx_L7; + } + + /* "View.MemoryView":692 + * if isinstance(item, slice): + * have_slices = True + * elif not PyIndex_Check(item): # <<<<<<<<<<<<<< + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item + */ + __pyx_t_2 = (!(PyIndex_Check(__pyx_v_item) != 0)); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":693 + * have_slices = True + * elif not PyIndex_Check(item): + * raise TypeError, f"Cannot index with type '{type(item)}'" # <<<<<<<<<<<<<< + * result[idx] = item + * idx += 1 + */ + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 693, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = 0; + __pyx_t_6 = 127; + __Pyx_INCREF(__pyx_kp_u_Cannot_index_with_type); + __pyx_t_5 += 24; + __Pyx_GIVEREF(__pyx_kp_u_Cannot_index_with_type); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_kp_u_Cannot_index_with_type); + __pyx_t_7 = __Pyx_PyObject_FormatSimple(((PyObject *)Py_TYPE(__pyx_v_item)), __pyx_empty_unicode); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 693, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_7) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_7) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_7); + __pyx_t_7 = 0; + __Pyx_INCREF(__pyx_kp_u__6); + __pyx_t_5 += 1; + __Pyx_GIVEREF(__pyx_kp_u__6); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_kp_u__6); + __pyx_t_7 = __Pyx_PyUnicode_Join(__pyx_t_3, 3, __pyx_t_5, __pyx_t_6); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 693, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_t_7, 0, 0); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __PYX_ERR(1, 693, __pyx_L1_error) + + /* "View.MemoryView":692 + * if isinstance(item, slice): + * have_slices = True + * elif not PyIndex_Check(item): # <<<<<<<<<<<<<< + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item + */ + } + __pyx_L7:; + + /* "View.MemoryView":694 + * elif not PyIndex_Check(item): + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item # <<<<<<<<<<<<<< + * idx += 1 + * + */ + if (unlikely((__Pyx_SetItemInt(__pyx_v_result, __pyx_v_idx, __pyx_v_item, Py_ssize_t, 1, PyInt_FromSsize_t, 1, 1, 1) < 0))) __PYX_ERR(1, 694, __pyx_L1_error) + } + __pyx_L5:; + + /* "View.MemoryView":695 + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item + * idx += 1 # <<<<<<<<<<<<<< + * + * nslices = ndim - idx + */ + __pyx_v_idx = (__pyx_v_idx + 1); + + /* "View.MemoryView":683 + * seen_ellipsis = False + * idx = 0 + * for item in tup: # <<<<<<<<<<<<<< + * if item is Ellipsis: + * if not seen_ellipsis: + */ + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "View.MemoryView":697 + * idx += 1 + * + * nslices = ndim - idx # <<<<<<<<<<<<<< + * return have_slices or nslices, tuple(result) + * + */ + __pyx_v_nslices = (__pyx_v_ndim - __pyx_v_idx); + + /* "View.MemoryView":698 + * + * nslices = ndim - idx + * return have_slices or nslices, tuple(result) # <<<<<<<<<<<<<< + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + */ + __Pyx_XDECREF(__pyx_r); + if (!__pyx_v_have_slices) { + } else { + __pyx_t_7 = __Pyx_PyBool_FromLong(__pyx_v_have_slices); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_1 = __pyx_t_7; + __pyx_t_7 = 0; + goto __pyx_L9_bool_binop_done; + } + __pyx_t_7 = PyInt_FromSsize_t(__pyx_v_nslices); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_1 = __pyx_t_7; + __pyx_t_7 = 0; + __pyx_L9_bool_binop_done:; + __pyx_t_7 = PyList_AsTuple(__pyx_v_result); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_1)) __PYX_ERR(1, 698, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_7); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_7)) __PYX_ERR(1, 698, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_7 = 0; + __pyx_r = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; + goto __pyx_L0; + + /* "View.MemoryView":671 + * return isinstance(o, memoryview) + * + * cdef tuple _unellipsify(object index, int ndim): # <<<<<<<<<<<<<< + * """ + * Replace all ellipses with full slices and fill incomplete indices with + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("View.MemoryView._unellipsify", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_tup); + __Pyx_XDECREF(__pyx_v_result); + __Pyx_XDECREF(__pyx_v_item); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":700 + * return have_slices or nslices, tuple(result) + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: # <<<<<<<<<<<<<< + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: + */ + +static int assert_direct_dimensions(Py_ssize_t *__pyx_v_suboffsets, int __pyx_v_ndim) { + Py_ssize_t __pyx_v_suboffset; + int __pyx_r; + Py_ssize_t *__pyx_t_1; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + int __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + + /* "View.MemoryView":701 + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + * for suboffset in suboffsets[:ndim]: # <<<<<<<<<<<<<< + * if suboffset >= 0: + * raise ValueError, "Indirect dimensions not supported" + */ + __pyx_t_2 = (__pyx_v_suboffsets + __pyx_v_ndim); + for (__pyx_t_3 = __pyx_v_suboffsets; __pyx_t_3 < __pyx_t_2; __pyx_t_3++) { + __pyx_t_1 = __pyx_t_3; + __pyx_v_suboffset = (__pyx_t_1[0]); + + /* "View.MemoryView":702 + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * raise ValueError, "Indirect dimensions not supported" + * return 0 # return type just used as an error flag + */ + __pyx_t_4 = (__pyx_v_suboffset >= 0); + if (unlikely(__pyx_t_4)) { + + /* "View.MemoryView":703 + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: + * raise ValueError, "Indirect dimensions not supported" # <<<<<<<<<<<<<< + * return 0 # return type just used as an error flag + * + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Indirect_dimensions_not_supporte, 0, 0); + __PYX_ERR(1, 703, __pyx_L1_error) + + /* "View.MemoryView":702 + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * raise ValueError, "Indirect dimensions not supported" + * return 0 # return type just used as an error flag + */ + } + } + + /* "View.MemoryView":704 + * if suboffset >= 0: + * raise ValueError, "Indirect dimensions not supported" + * return 0 # return type just used as an error flag # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":700 + * return have_slices or nslices, tuple(result) + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: # <<<<<<<<<<<<<< + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.assert_direct_dimensions", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":711 + * + * @cname('__pyx_memview_slice') + * cdef memoryview memview_slice(memoryview memview, object indices): # <<<<<<<<<<<<<< + * cdef int new_ndim = 0, suboffset_dim = -1, dim + * cdef bint negative_step + */ + +static struct __pyx_memoryview_obj *__pyx_memview_slice(struct __pyx_memoryview_obj *__pyx_v_memview, PyObject *__pyx_v_indices) { + int __pyx_v_new_ndim; + int __pyx_v_suboffset_dim; + int __pyx_v_dim; + __Pyx_memviewslice __pyx_v_src; + __Pyx_memviewslice __pyx_v_dst; + __Pyx_memviewslice *__pyx_v_p_src; + struct __pyx_memoryviewslice_obj *__pyx_v_memviewsliceobj = 0; + __Pyx_memviewslice *__pyx_v_p_dst; + int *__pyx_v_p_suboffset_dim; + Py_ssize_t __pyx_v_start; + Py_ssize_t __pyx_v_stop; + Py_ssize_t __pyx_v_step; + Py_ssize_t __pyx_v_cindex; + int __pyx_v_have_start; + int __pyx_v_have_stop; + int __pyx_v_have_step; + PyObject *__pyx_v_index = NULL; + struct __pyx_memoryview_obj *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + struct __pyx_memoryview_obj *__pyx_t_3; + char *__pyx_t_4; + int __pyx_t_5; + Py_ssize_t __pyx_t_6; + PyObject *(*__pyx_t_7)(PyObject *); + PyObject *__pyx_t_8 = NULL; + Py_ssize_t __pyx_t_9; + int __pyx_t_10; + Py_ssize_t __pyx_t_11; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memview_slice", 1); + + /* "View.MemoryView":712 + * @cname('__pyx_memview_slice') + * cdef memoryview memview_slice(memoryview memview, object indices): + * cdef int new_ndim = 0, suboffset_dim = -1, dim # <<<<<<<<<<<<<< + * cdef bint negative_step + * cdef __Pyx_memviewslice src, dst + */ + __pyx_v_new_ndim = 0; + __pyx_v_suboffset_dim = -1; + + /* "View.MemoryView":719 + * + * + * memset(&dst, 0, sizeof(dst)) # <<<<<<<<<<<<<< + * + * cdef _memoryviewslice memviewsliceobj + */ + (void)(memset((&__pyx_v_dst), 0, (sizeof(__pyx_v_dst)))); + + /* "View.MemoryView":723 + * cdef _memoryviewslice memviewsliceobj + * + * assert memview.view.ndim > 0 # <<<<<<<<<<<<<< + * + * if isinstance(memview, _memoryviewslice): + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_1 = (__pyx_v_memview->view.ndim > 0); + if (unlikely(!__pyx_t_1)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(1, 723, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(1, 723, __pyx_L1_error) + #endif + + /* "View.MemoryView":725 + * assert memview.view.ndim > 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * memviewsliceobj = memview + * p_src = &memviewsliceobj.from_slice + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":726 + * + * if isinstance(memview, _memoryviewslice): + * memviewsliceobj = memview # <<<<<<<<<<<<<< + * p_src = &memviewsliceobj.from_slice + * else: + */ + if (!(likely(((((PyObject *)__pyx_v_memview)) == Py_None) || likely(__Pyx_TypeTest(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type))))) __PYX_ERR(1, 726, __pyx_L1_error) + __pyx_t_2 = ((PyObject *)__pyx_v_memview); + __Pyx_INCREF(__pyx_t_2); + __pyx_v_memviewsliceobj = ((struct __pyx_memoryviewslice_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":727 + * if isinstance(memview, _memoryviewslice): + * memviewsliceobj = memview + * p_src = &memviewsliceobj.from_slice # <<<<<<<<<<<<<< + * else: + * slice_copy(memview, &src) + */ + __pyx_v_p_src = (&__pyx_v_memviewsliceobj->from_slice); + + /* "View.MemoryView":725 + * assert memview.view.ndim > 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * memviewsliceobj = memview + * p_src = &memviewsliceobj.from_slice + */ + goto __pyx_L3; + } + + /* "View.MemoryView":729 + * p_src = &memviewsliceobj.from_slice + * else: + * slice_copy(memview, &src) # <<<<<<<<<<<<<< + * p_src = &src + * + */ + /*else*/ { + __pyx_memoryview_slice_copy(__pyx_v_memview, (&__pyx_v_src)); + + /* "View.MemoryView":730 + * else: + * slice_copy(memview, &src) + * p_src = &src # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_p_src = (&__pyx_v_src); + } + __pyx_L3:; + + /* "View.MemoryView":736 + * + * + * dst.memview = p_src.memview # <<<<<<<<<<<<<< + * dst.data = p_src.data + * + */ + __pyx_t_3 = __pyx_v_p_src->memview; + __pyx_v_dst.memview = __pyx_t_3; + + /* "View.MemoryView":737 + * + * dst.memview = p_src.memview + * dst.data = p_src.data # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_4 = __pyx_v_p_src->data; + __pyx_v_dst.data = __pyx_t_4; + + /* "View.MemoryView":742 + * + * + * cdef __Pyx_memviewslice *p_dst = &dst # <<<<<<<<<<<<<< + * cdef int *p_suboffset_dim = &suboffset_dim + * cdef Py_ssize_t start, stop, step, cindex + */ + __pyx_v_p_dst = (&__pyx_v_dst); + + /* "View.MemoryView":743 + * + * cdef __Pyx_memviewslice *p_dst = &dst + * cdef int *p_suboffset_dim = &suboffset_dim # <<<<<<<<<<<<<< + * cdef Py_ssize_t start, stop, step, cindex + * cdef bint have_start, have_stop, have_step + */ + __pyx_v_p_suboffset_dim = (&__pyx_v_suboffset_dim); + + /* "View.MemoryView":747 + * cdef bint have_start, have_stop, have_step + * + * for dim, index in enumerate(indices): # <<<<<<<<<<<<<< + * if PyIndex_Check(index): + * cindex = index + */ + __pyx_t_5 = 0; + if (likely(PyList_CheckExact(__pyx_v_indices)) || PyTuple_CheckExact(__pyx_v_indices)) { + __pyx_t_2 = __pyx_v_indices; __Pyx_INCREF(__pyx_t_2); + __pyx_t_6 = 0; + __pyx_t_7 = NULL; + } else { + __pyx_t_6 = -1; __pyx_t_2 = PyObject_GetIter(__pyx_v_indices); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 747, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_7 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_2); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 747, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_7)) { + if (likely(PyList_CheckExact(__pyx_t_2))) { + { + Py_ssize_t __pyx_temp = __Pyx_PyList_GET_SIZE(__pyx_t_2); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 747, __pyx_L1_error) + #endif + if (__pyx_t_6 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_8 = PyList_GET_ITEM(__pyx_t_2, __pyx_t_6); __Pyx_INCREF(__pyx_t_8); __pyx_t_6++; if (unlikely((0 < 0))) __PYX_ERR(1, 747, __pyx_L1_error) + #else + __pyx_t_8 = __Pyx_PySequence_ITEM(__pyx_t_2, __pyx_t_6); __pyx_t_6++; if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 747, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + #endif + } else { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_2); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 747, __pyx_L1_error) + #endif + if (__pyx_t_6 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_8 = PyTuple_GET_ITEM(__pyx_t_2, __pyx_t_6); __Pyx_INCREF(__pyx_t_8); __pyx_t_6++; if (unlikely((0 < 0))) __PYX_ERR(1, 747, __pyx_L1_error) + #else + __pyx_t_8 = __Pyx_PySequence_ITEM(__pyx_t_2, __pyx_t_6); __pyx_t_6++; if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 747, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + #endif + } + } else { + __pyx_t_8 = __pyx_t_7(__pyx_t_2); + if (unlikely(!__pyx_t_8)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(1, 747, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_8); + } + __Pyx_XDECREF_SET(__pyx_v_index, __pyx_t_8); + __pyx_t_8 = 0; + __pyx_v_dim = __pyx_t_5; + __pyx_t_5 = (__pyx_t_5 + 1); + + /* "View.MemoryView":748 + * + * for dim, index in enumerate(indices): + * if PyIndex_Check(index): # <<<<<<<<<<<<<< + * cindex = index + * slice_memviewslice( + */ + __pyx_t_1 = (PyIndex_Check(__pyx_v_index) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":749 + * for dim, index in enumerate(indices): + * if PyIndex_Check(index): + * cindex = index # <<<<<<<<<<<<<< + * slice_memviewslice( + * p_dst, p_src.shape[dim], p_src.strides[dim], p_src.suboffsets[dim], + */ + __pyx_t_9 = __Pyx_PyIndex_AsSsize_t(__pyx_v_index); if (unlikely((__pyx_t_9 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 749, __pyx_L1_error) + __pyx_v_cindex = __pyx_t_9; + + /* "View.MemoryView":750 + * if PyIndex_Check(index): + * cindex = index + * slice_memviewslice( # <<<<<<<<<<<<<< + * p_dst, p_src.shape[dim], p_src.strides[dim], p_src.suboffsets[dim], + * dim, new_ndim, p_suboffset_dim, + */ + __pyx_t_10 = __pyx_memoryview_slice_memviewslice(__pyx_v_p_dst, (__pyx_v_p_src->shape[__pyx_v_dim]), (__pyx_v_p_src->strides[__pyx_v_dim]), (__pyx_v_p_src->suboffsets[__pyx_v_dim]), __pyx_v_dim, __pyx_v_new_ndim, __pyx_v_p_suboffset_dim, __pyx_v_cindex, 0, 0, 0, 0, 0, 0); if (unlikely(__pyx_t_10 == ((int)-1))) __PYX_ERR(1, 750, __pyx_L1_error) + + /* "View.MemoryView":748 + * + * for dim, index in enumerate(indices): + * if PyIndex_Check(index): # <<<<<<<<<<<<<< + * cindex = index + * slice_memviewslice( + */ + goto __pyx_L6; + } + + /* "View.MemoryView":756 + * 0, 0, 0, # have_{start,stop,step} + * False) + * elif index is None: # <<<<<<<<<<<<<< + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 + */ + __pyx_t_1 = (__pyx_v_index == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":757 + * False) + * elif index is None: + * p_dst.shape[new_ndim] = 1 # <<<<<<<<<<<<<< + * p_dst.strides[new_ndim] = 0 + * p_dst.suboffsets[new_ndim] = -1 + */ + (__pyx_v_p_dst->shape[__pyx_v_new_ndim]) = 1; + + /* "View.MemoryView":758 + * elif index is None: + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 # <<<<<<<<<<<<<< + * p_dst.suboffsets[new_ndim] = -1 + * new_ndim += 1 + */ + (__pyx_v_p_dst->strides[__pyx_v_new_ndim]) = 0; + + /* "View.MemoryView":759 + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 + * p_dst.suboffsets[new_ndim] = -1 # <<<<<<<<<<<<<< + * new_ndim += 1 + * else: + */ + (__pyx_v_p_dst->suboffsets[__pyx_v_new_ndim]) = -1L; + + /* "View.MemoryView":760 + * p_dst.strides[new_ndim] = 0 + * p_dst.suboffsets[new_ndim] = -1 + * new_ndim += 1 # <<<<<<<<<<<<<< + * else: + * start = index.start or 0 + */ + __pyx_v_new_ndim = (__pyx_v_new_ndim + 1); + + /* "View.MemoryView":756 + * 0, 0, 0, # have_{start,stop,step} + * False) + * elif index is None: # <<<<<<<<<<<<<< + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 + */ + goto __pyx_L6; + } + + /* "View.MemoryView":762 + * new_ndim += 1 + * else: + * start = index.start or 0 # <<<<<<<<<<<<<< + * stop = index.stop or 0 + * step = index.step or 0 + */ + /*else*/ { + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_start); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 762, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_t_8); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 762, __pyx_L1_error) + if (!__pyx_t_1) { + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } else { + __pyx_t_11 = __Pyx_PyIndex_AsSsize_t(__pyx_t_8); if (unlikely((__pyx_t_11 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 762, __pyx_L1_error) + __pyx_t_9 = __pyx_t_11; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L7_bool_binop_done; + } + __pyx_t_9 = 0; + __pyx_L7_bool_binop_done:; + __pyx_v_start = __pyx_t_9; + + /* "View.MemoryView":763 + * else: + * start = index.start or 0 + * stop = index.stop or 0 # <<<<<<<<<<<<<< + * step = index.step or 0 + * + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_stop); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 763, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_t_8); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 763, __pyx_L1_error) + if (!__pyx_t_1) { + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } else { + __pyx_t_11 = __Pyx_PyIndex_AsSsize_t(__pyx_t_8); if (unlikely((__pyx_t_11 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 763, __pyx_L1_error) + __pyx_t_9 = __pyx_t_11; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L9_bool_binop_done; + } + __pyx_t_9 = 0; + __pyx_L9_bool_binop_done:; + __pyx_v_stop = __pyx_t_9; + + /* "View.MemoryView":764 + * start = index.start or 0 + * stop = index.stop or 0 + * step = index.step or 0 # <<<<<<<<<<<<<< + * + * have_start = index.start is not None + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_step); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 764, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_t_8); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 764, __pyx_L1_error) + if (!__pyx_t_1) { + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } else { + __pyx_t_11 = __Pyx_PyIndex_AsSsize_t(__pyx_t_8); if (unlikely((__pyx_t_11 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 764, __pyx_L1_error) + __pyx_t_9 = __pyx_t_11; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L11_bool_binop_done; + } + __pyx_t_9 = 0; + __pyx_L11_bool_binop_done:; + __pyx_v_step = __pyx_t_9; + + /* "View.MemoryView":766 + * step = index.step or 0 + * + * have_start = index.start is not None # <<<<<<<<<<<<<< + * have_stop = index.stop is not None + * have_step = index.step is not None + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_start); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 766, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = (__pyx_t_8 != Py_None); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_v_have_start = __pyx_t_1; + + /* "View.MemoryView":767 + * + * have_start = index.start is not None + * have_stop = index.stop is not None # <<<<<<<<<<<<<< + * have_step = index.step is not None + * + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_stop); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 767, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = (__pyx_t_8 != Py_None); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_v_have_stop = __pyx_t_1; + + /* "View.MemoryView":768 + * have_start = index.start is not None + * have_stop = index.stop is not None + * have_step = index.step is not None # <<<<<<<<<<<<<< + * + * slice_memviewslice( + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_step); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 768, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = (__pyx_t_8 != Py_None); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_v_have_step = __pyx_t_1; + + /* "View.MemoryView":770 + * have_step = index.step is not None + * + * slice_memviewslice( # <<<<<<<<<<<<<< + * p_dst, p_src.shape[dim], p_src.strides[dim], p_src.suboffsets[dim], + * dim, new_ndim, p_suboffset_dim, + */ + __pyx_t_10 = __pyx_memoryview_slice_memviewslice(__pyx_v_p_dst, (__pyx_v_p_src->shape[__pyx_v_dim]), (__pyx_v_p_src->strides[__pyx_v_dim]), (__pyx_v_p_src->suboffsets[__pyx_v_dim]), __pyx_v_dim, __pyx_v_new_ndim, __pyx_v_p_suboffset_dim, __pyx_v_start, __pyx_v_stop, __pyx_v_step, __pyx_v_have_start, __pyx_v_have_stop, __pyx_v_have_step, 1); if (unlikely(__pyx_t_10 == ((int)-1))) __PYX_ERR(1, 770, __pyx_L1_error) + + /* "View.MemoryView":776 + * have_start, have_stop, have_step, + * True) + * new_ndim += 1 # <<<<<<<<<<<<<< + * + * if isinstance(memview, _memoryviewslice): + */ + __pyx_v_new_ndim = (__pyx_v_new_ndim + 1); + } + __pyx_L6:; + + /* "View.MemoryView":747 + * cdef bint have_start, have_stop, have_step + * + * for dim, index in enumerate(indices): # <<<<<<<<<<<<<< + * if PyIndex_Check(index): + * cindex = index + */ + } + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":778 + * new_ndim += 1 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":779 + * + * if isinstance(memview, _memoryviewslice): + * return memoryview_fromslice(dst, new_ndim, # <<<<<<<<<<<<<< + * memviewsliceobj.to_object_func, + * memviewsliceobj.to_dtype_func, + */ + __Pyx_XDECREF((PyObject *)__pyx_r); + + /* "View.MemoryView":780 + * if isinstance(memview, _memoryviewslice): + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, # <<<<<<<<<<<<<< + * memviewsliceobj.to_dtype_func, + * memview.dtype_is_object) + */ + if (unlikely(!__pyx_v_memviewsliceobj)) { __Pyx_RaiseUnboundLocalError("memviewsliceobj"); __PYX_ERR(1, 780, __pyx_L1_error) } + + /* "View.MemoryView":781 + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, + * memviewsliceobj.to_dtype_func, # <<<<<<<<<<<<<< + * memview.dtype_is_object) + * else: + */ + if (unlikely(!__pyx_v_memviewsliceobj)) { __Pyx_RaiseUnboundLocalError("memviewsliceobj"); __PYX_ERR(1, 781, __pyx_L1_error) } + + /* "View.MemoryView":779 + * + * if isinstance(memview, _memoryviewslice): + * return memoryview_fromslice(dst, new_ndim, # <<<<<<<<<<<<<< + * memviewsliceobj.to_object_func, + * memviewsliceobj.to_dtype_func, + */ + __pyx_t_2 = __pyx_memoryview_fromslice(__pyx_v_dst, __pyx_v_new_ndim, __pyx_v_memviewsliceobj->to_object_func, __pyx_v_memviewsliceobj->to_dtype_func, __pyx_v_memview->dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 779, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (!(likely(((__pyx_t_2) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_2, __pyx_memoryview_type))))) __PYX_ERR(1, 779, __pyx_L1_error) + __pyx_r = ((struct __pyx_memoryview_obj *)__pyx_t_2); + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":778 + * new_ndim += 1 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, + */ + } + + /* "View.MemoryView":784 + * memview.dtype_is_object) + * else: + * return memoryview_fromslice(dst, new_ndim, NULL, NULL, # <<<<<<<<<<<<<< + * memview.dtype_is_object) + * + */ + /*else*/ { + __Pyx_XDECREF((PyObject *)__pyx_r); + + /* "View.MemoryView":785 + * else: + * return memoryview_fromslice(dst, new_ndim, NULL, NULL, + * memview.dtype_is_object) # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = __pyx_memoryview_fromslice(__pyx_v_dst, __pyx_v_new_ndim, NULL, NULL, __pyx_v_memview->dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 784, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + + /* "View.MemoryView":784 + * memview.dtype_is_object) + * else: + * return memoryview_fromslice(dst, new_ndim, NULL, NULL, # <<<<<<<<<<<<<< + * memview.dtype_is_object) + * + */ + if (!(likely(((__pyx_t_2) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_2, __pyx_memoryview_type))))) __PYX_ERR(1, 784, __pyx_L1_error) + __pyx_r = ((struct __pyx_memoryview_obj *)__pyx_t_2); + __pyx_t_2 = 0; + goto __pyx_L0; + } + + /* "View.MemoryView":711 + * + * @cname('__pyx_memview_slice') + * cdef memoryview memview_slice(memoryview memview, object indices): # <<<<<<<<<<<<<< + * cdef int new_ndim = 0, suboffset_dim = -1, dim + * cdef bint negative_step + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("View.MemoryView.memview_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_memviewsliceobj); + __Pyx_XDECREF(__pyx_v_index); + __Pyx_XGIVEREF((PyObject *)__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":793 + * + * @cname('__pyx_memoryview_slice_memviewslice') + * cdef int slice_memviewslice( # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * Py_ssize_t shape, Py_ssize_t stride, Py_ssize_t suboffset, + */ + +static int __pyx_memoryview_slice_memviewslice(__Pyx_memviewslice *__pyx_v_dst, Py_ssize_t __pyx_v_shape, Py_ssize_t __pyx_v_stride, Py_ssize_t __pyx_v_suboffset, int __pyx_v_dim, int __pyx_v_new_ndim, int *__pyx_v_suboffset_dim, Py_ssize_t __pyx_v_start, Py_ssize_t __pyx_v_stop, Py_ssize_t __pyx_v_step, int __pyx_v_have_start, int __pyx_v_have_stop, int __pyx_v_have_step, int __pyx_v_is_slice) { + Py_ssize_t __pyx_v_new_shape; + int __pyx_v_negative_step; + int __pyx_r; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":813 + * cdef bint negative_step + * + * if not is_slice: # <<<<<<<<<<<<<< + * + * if start < 0: + */ + __pyx_t_1 = (!__pyx_v_is_slice); + if (__pyx_t_1) { + + /* "View.MemoryView":815 + * if not is_slice: + * + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if not 0 <= start < shape: + */ + __pyx_t_1 = (__pyx_v_start < 0); + if (__pyx_t_1) { + + /* "View.MemoryView":816 + * + * if start < 0: + * start += shape # <<<<<<<<<<<<<< + * if not 0 <= start < shape: + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) + */ + __pyx_v_start = (__pyx_v_start + __pyx_v_shape); + + /* "View.MemoryView":815 + * if not is_slice: + * + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if not 0 <= start < shape: + */ + } + + /* "View.MemoryView":817 + * if start < 0: + * start += shape + * if not 0 <= start < shape: # <<<<<<<<<<<<<< + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) + * else: + */ + __pyx_t_1 = (0 <= __pyx_v_start); + if (__pyx_t_1) { + __pyx_t_1 = (__pyx_v_start < __pyx_v_shape); + } + __pyx_t_2 = (!__pyx_t_1); + if (__pyx_t_2) { + + /* "View.MemoryView":818 + * start += shape + * if not 0 <= start < shape: + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) # <<<<<<<<<<<<<< + * else: + * + */ + __pyx_t_3 = __pyx_memoryview_err_dim(PyExc_IndexError, __pyx_kp_s_Index_out_of_bounds_axis_d, __pyx_v_dim); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 818, __pyx_L1_error) + + /* "View.MemoryView":817 + * if start < 0: + * start += shape + * if not 0 <= start < shape: # <<<<<<<<<<<<<< + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) + * else: + */ + } + + /* "View.MemoryView":813 + * cdef bint negative_step + * + * if not is_slice: # <<<<<<<<<<<<<< + * + * if start < 0: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":821 + * else: + * + * if have_step: # <<<<<<<<<<<<<< + * negative_step = step < 0 + * if step == 0: + */ + /*else*/ { + __pyx_t_2 = (__pyx_v_have_step != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":822 + * + * if have_step: + * negative_step = step < 0 # <<<<<<<<<<<<<< + * if step == 0: + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + */ + __pyx_v_negative_step = (__pyx_v_step < 0); + + /* "View.MemoryView":823 + * if have_step: + * negative_step = step < 0 + * if step == 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + * else: + */ + __pyx_t_2 = (__pyx_v_step == 0); + if (__pyx_t_2) { + + /* "View.MemoryView":824 + * negative_step = step < 0 + * if step == 0: + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) # <<<<<<<<<<<<<< + * else: + * negative_step = False + */ + __pyx_t_3 = __pyx_memoryview_err_dim(PyExc_ValueError, __pyx_kp_s_Step_may_not_be_zero_axis_d, __pyx_v_dim); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 824, __pyx_L1_error) + + /* "View.MemoryView":823 + * if have_step: + * negative_step = step < 0 + * if step == 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + * else: + */ + } + + /* "View.MemoryView":821 + * else: + * + * if have_step: # <<<<<<<<<<<<<< + * negative_step = step < 0 + * if step == 0: + */ + goto __pyx_L6; + } + + /* "View.MemoryView":826 + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + * else: + * negative_step = False # <<<<<<<<<<<<<< + * step = 1 + * + */ + /*else*/ { + __pyx_v_negative_step = 0; + + /* "View.MemoryView":827 + * else: + * negative_step = False + * step = 1 # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_step = 1; + } + __pyx_L6:; + + /* "View.MemoryView":830 + * + * + * if have_start: # <<<<<<<<<<<<<< + * if start < 0: + * start += shape + */ + __pyx_t_2 = (__pyx_v_have_start != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":831 + * + * if have_start: + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if start < 0: + */ + __pyx_t_2 = (__pyx_v_start < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":832 + * if have_start: + * if start < 0: + * start += shape # <<<<<<<<<<<<<< + * if start < 0: + * start = 0 + */ + __pyx_v_start = (__pyx_v_start + __pyx_v_shape); + + /* "View.MemoryView":833 + * if start < 0: + * start += shape + * if start < 0: # <<<<<<<<<<<<<< + * start = 0 + * elif start >= shape: + */ + __pyx_t_2 = (__pyx_v_start < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":834 + * start += shape + * if start < 0: + * start = 0 # <<<<<<<<<<<<<< + * elif start >= shape: + * if negative_step: + */ + __pyx_v_start = 0; + + /* "View.MemoryView":833 + * if start < 0: + * start += shape + * if start < 0: # <<<<<<<<<<<<<< + * start = 0 + * elif start >= shape: + */ + } + + /* "View.MemoryView":831 + * + * if have_start: + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if start < 0: + */ + goto __pyx_L9; + } + + /* "View.MemoryView":835 + * if start < 0: + * start = 0 + * elif start >= shape: # <<<<<<<<<<<<<< + * if negative_step: + * start = shape - 1 + */ + __pyx_t_2 = (__pyx_v_start >= __pyx_v_shape); + if (__pyx_t_2) { + + /* "View.MemoryView":836 + * start = 0 + * elif start >= shape: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + if (__pyx_v_negative_step) { + + /* "View.MemoryView":837 + * elif start >= shape: + * if negative_step: + * start = shape - 1 # <<<<<<<<<<<<<< + * else: + * start = shape + */ + __pyx_v_start = (__pyx_v_shape - 1); + + /* "View.MemoryView":836 + * start = 0 + * elif start >= shape: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + goto __pyx_L11; + } + + /* "View.MemoryView":839 + * start = shape - 1 + * else: + * start = shape # <<<<<<<<<<<<<< + * else: + * if negative_step: + */ + /*else*/ { + __pyx_v_start = __pyx_v_shape; + } + __pyx_L11:; + + /* "View.MemoryView":835 + * if start < 0: + * start = 0 + * elif start >= shape: # <<<<<<<<<<<<<< + * if negative_step: + * start = shape - 1 + */ + } + __pyx_L9:; + + /* "View.MemoryView":830 + * + * + * if have_start: # <<<<<<<<<<<<<< + * if start < 0: + * start += shape + */ + goto __pyx_L8; + } + + /* "View.MemoryView":841 + * start = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + /*else*/ { + if (__pyx_v_negative_step) { + + /* "View.MemoryView":842 + * else: + * if negative_step: + * start = shape - 1 # <<<<<<<<<<<<<< + * else: + * start = 0 + */ + __pyx_v_start = (__pyx_v_shape - 1); + + /* "View.MemoryView":841 + * start = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + goto __pyx_L12; + } + + /* "View.MemoryView":844 + * start = shape - 1 + * else: + * start = 0 # <<<<<<<<<<<<<< + * + * if have_stop: + */ + /*else*/ { + __pyx_v_start = 0; + } + __pyx_L12:; + } + __pyx_L8:; + + /* "View.MemoryView":846 + * start = 0 + * + * if have_stop: # <<<<<<<<<<<<<< + * if stop < 0: + * stop += shape + */ + __pyx_t_2 = (__pyx_v_have_stop != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":847 + * + * if have_stop: + * if stop < 0: # <<<<<<<<<<<<<< + * stop += shape + * if stop < 0: + */ + __pyx_t_2 = (__pyx_v_stop < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":848 + * if have_stop: + * if stop < 0: + * stop += shape # <<<<<<<<<<<<<< + * if stop < 0: + * stop = 0 + */ + __pyx_v_stop = (__pyx_v_stop + __pyx_v_shape); + + /* "View.MemoryView":849 + * if stop < 0: + * stop += shape + * if stop < 0: # <<<<<<<<<<<<<< + * stop = 0 + * elif stop > shape: + */ + __pyx_t_2 = (__pyx_v_stop < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":850 + * stop += shape + * if stop < 0: + * stop = 0 # <<<<<<<<<<<<<< + * elif stop > shape: + * stop = shape + */ + __pyx_v_stop = 0; + + /* "View.MemoryView":849 + * if stop < 0: + * stop += shape + * if stop < 0: # <<<<<<<<<<<<<< + * stop = 0 + * elif stop > shape: + */ + } + + /* "View.MemoryView":847 + * + * if have_stop: + * if stop < 0: # <<<<<<<<<<<<<< + * stop += shape + * if stop < 0: + */ + goto __pyx_L14; + } + + /* "View.MemoryView":851 + * if stop < 0: + * stop = 0 + * elif stop > shape: # <<<<<<<<<<<<<< + * stop = shape + * else: + */ + __pyx_t_2 = (__pyx_v_stop > __pyx_v_shape); + if (__pyx_t_2) { + + /* "View.MemoryView":852 + * stop = 0 + * elif stop > shape: + * stop = shape # <<<<<<<<<<<<<< + * else: + * if negative_step: + */ + __pyx_v_stop = __pyx_v_shape; + + /* "View.MemoryView":851 + * if stop < 0: + * stop = 0 + * elif stop > shape: # <<<<<<<<<<<<<< + * stop = shape + * else: + */ + } + __pyx_L14:; + + /* "View.MemoryView":846 + * start = 0 + * + * if have_stop: # <<<<<<<<<<<<<< + * if stop < 0: + * stop += shape + */ + goto __pyx_L13; + } + + /* "View.MemoryView":854 + * stop = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * stop = -1 + * else: + */ + /*else*/ { + if (__pyx_v_negative_step) { + + /* "View.MemoryView":855 + * else: + * if negative_step: + * stop = -1 # <<<<<<<<<<<<<< + * else: + * stop = shape + */ + __pyx_v_stop = -1L; + + /* "View.MemoryView":854 + * stop = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * stop = -1 + * else: + */ + goto __pyx_L16; + } + + /* "View.MemoryView":857 + * stop = -1 + * else: + * stop = shape # <<<<<<<<<<<<<< + * + * + */ + /*else*/ { + __pyx_v_stop = __pyx_v_shape; + } + __pyx_L16:; + } + __pyx_L13:; + + /* "View.MemoryView":861 + * + * with cython.cdivision(True): + * new_shape = (stop - start) // step # <<<<<<<<<<<<<< + * + * if (stop - start) - step * new_shape: + */ + __pyx_v_new_shape = ((__pyx_v_stop - __pyx_v_start) / __pyx_v_step); + + /* "View.MemoryView":863 + * new_shape = (stop - start) // step + * + * if (stop - start) - step * new_shape: # <<<<<<<<<<<<<< + * new_shape += 1 + * + */ + __pyx_t_2 = (((__pyx_v_stop - __pyx_v_start) - (__pyx_v_step * __pyx_v_new_shape)) != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":864 + * + * if (stop - start) - step * new_shape: + * new_shape += 1 # <<<<<<<<<<<<<< + * + * if new_shape < 0: + */ + __pyx_v_new_shape = (__pyx_v_new_shape + 1); + + /* "View.MemoryView":863 + * new_shape = (stop - start) // step + * + * if (stop - start) - step * new_shape: # <<<<<<<<<<<<<< + * new_shape += 1 + * + */ + } + + /* "View.MemoryView":866 + * new_shape += 1 + * + * if new_shape < 0: # <<<<<<<<<<<<<< + * new_shape = 0 + * + */ + __pyx_t_2 = (__pyx_v_new_shape < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":867 + * + * if new_shape < 0: + * new_shape = 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_new_shape = 0; + + /* "View.MemoryView":866 + * new_shape += 1 + * + * if new_shape < 0: # <<<<<<<<<<<<<< + * new_shape = 0 + * + */ + } + + /* "View.MemoryView":870 + * + * + * dst.strides[new_ndim] = stride * step # <<<<<<<<<<<<<< + * dst.shape[new_ndim] = new_shape + * dst.suboffsets[new_ndim] = suboffset + */ + (__pyx_v_dst->strides[__pyx_v_new_ndim]) = (__pyx_v_stride * __pyx_v_step); + + /* "View.MemoryView":871 + * + * dst.strides[new_ndim] = stride * step + * dst.shape[new_ndim] = new_shape # <<<<<<<<<<<<<< + * dst.suboffsets[new_ndim] = suboffset + * + */ + (__pyx_v_dst->shape[__pyx_v_new_ndim]) = __pyx_v_new_shape; + + /* "View.MemoryView":872 + * dst.strides[new_ndim] = stride * step + * dst.shape[new_ndim] = new_shape + * dst.suboffsets[new_ndim] = suboffset # <<<<<<<<<<<<<< + * + * + */ + (__pyx_v_dst->suboffsets[__pyx_v_new_ndim]) = __pyx_v_suboffset; + } + __pyx_L3:; + + /* "View.MemoryView":875 + * + * + * if suboffset_dim[0] < 0: # <<<<<<<<<<<<<< + * dst.data += start * stride + * else: + */ + __pyx_t_2 = ((__pyx_v_suboffset_dim[0]) < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":876 + * + * if suboffset_dim[0] < 0: + * dst.data += start * stride # <<<<<<<<<<<<<< + * else: + * dst.suboffsets[suboffset_dim[0]] += start * stride + */ + __pyx_v_dst->data = (__pyx_v_dst->data + (__pyx_v_start * __pyx_v_stride)); + + /* "View.MemoryView":875 + * + * + * if suboffset_dim[0] < 0: # <<<<<<<<<<<<<< + * dst.data += start * stride + * else: + */ + goto __pyx_L19; + } + + /* "View.MemoryView":878 + * dst.data += start * stride + * else: + * dst.suboffsets[suboffset_dim[0]] += start * stride # <<<<<<<<<<<<<< + * + * if suboffset >= 0: + */ + /*else*/ { + __pyx_t_3 = (__pyx_v_suboffset_dim[0]); + (__pyx_v_dst->suboffsets[__pyx_t_3]) = ((__pyx_v_dst->suboffsets[__pyx_t_3]) + (__pyx_v_start * __pyx_v_stride)); + } + __pyx_L19:; + + /* "View.MemoryView":880 + * dst.suboffsets[suboffset_dim[0]] += start * stride + * + * if suboffset >= 0: # <<<<<<<<<<<<<< + * if not is_slice: + * if new_ndim == 0: + */ + __pyx_t_2 = (__pyx_v_suboffset >= 0); + if (__pyx_t_2) { + + /* "View.MemoryView":881 + * + * if suboffset >= 0: + * if not is_slice: # <<<<<<<<<<<<<< + * if new_ndim == 0: + * dst.data = ( dst.data)[0] + suboffset + */ + __pyx_t_2 = (!__pyx_v_is_slice); + if (__pyx_t_2) { + + /* "View.MemoryView":882 + * if suboffset >= 0: + * if not is_slice: + * if new_ndim == 0: # <<<<<<<<<<<<<< + * dst.data = ( dst.data)[0] + suboffset + * else: + */ + __pyx_t_2 = (__pyx_v_new_ndim == 0); + if (__pyx_t_2) { + + /* "View.MemoryView":883 + * if not is_slice: + * if new_ndim == 0: + * dst.data = ( dst.data)[0] + suboffset # <<<<<<<<<<<<<< + * else: + * _err_dim(PyExc_IndexError, "All dimensions preceding dimension %d " + */ + __pyx_v_dst->data = ((((char **)__pyx_v_dst->data)[0]) + __pyx_v_suboffset); + + /* "View.MemoryView":882 + * if suboffset >= 0: + * if not is_slice: + * if new_ndim == 0: # <<<<<<<<<<<<<< + * dst.data = ( dst.data)[0] + suboffset + * else: + */ + goto __pyx_L22; + } + + /* "View.MemoryView":885 + * dst.data = ( dst.data)[0] + suboffset + * else: + * _err_dim(PyExc_IndexError, "All dimensions preceding dimension %d " # <<<<<<<<<<<<<< + * "must be indexed and not sliced", dim) + * else: + */ + /*else*/ { + + /* "View.MemoryView":886 + * else: + * _err_dim(PyExc_IndexError, "All dimensions preceding dimension %d " + * "must be indexed and not sliced", dim) # <<<<<<<<<<<<<< + * else: + * suboffset_dim[0] = new_ndim + */ + __pyx_t_3 = __pyx_memoryview_err_dim(PyExc_IndexError, __pyx_kp_s_All_dimensions_preceding_dimensi, __pyx_v_dim); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 885, __pyx_L1_error) + } + __pyx_L22:; + + /* "View.MemoryView":881 + * + * if suboffset >= 0: + * if not is_slice: # <<<<<<<<<<<<<< + * if new_ndim == 0: + * dst.data = ( dst.data)[0] + suboffset + */ + goto __pyx_L21; + } + + /* "View.MemoryView":888 + * "must be indexed and not sliced", dim) + * else: + * suboffset_dim[0] = new_ndim # <<<<<<<<<<<<<< + * + * return 0 + */ + /*else*/ { + (__pyx_v_suboffset_dim[0]) = __pyx_v_new_ndim; + } + __pyx_L21:; + + /* "View.MemoryView":880 + * dst.suboffsets[suboffset_dim[0]] += start * stride + * + * if suboffset >= 0: # <<<<<<<<<<<<<< + * if not is_slice: + * if new_ndim == 0: + */ + } + + /* "View.MemoryView":890 + * suboffset_dim[0] = new_ndim + * + * return 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":793 + * + * @cname('__pyx_memoryview_slice_memviewslice') + * cdef int slice_memviewslice( # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * Py_ssize_t shape, Py_ssize_t stride, Py_ssize_t suboffset, + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.slice_memviewslice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":896 + * + * @cname('__pyx_pybuffer_index') + * cdef char *pybuffer_index(Py_buffer *view, char *bufp, Py_ssize_t index, # <<<<<<<<<<<<<< + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 + */ + +static char *__pyx_pybuffer_index(Py_buffer *__pyx_v_view, char *__pyx_v_bufp, Py_ssize_t __pyx_v_index, Py_ssize_t __pyx_v_dim) { + Py_ssize_t __pyx_v_shape; + Py_ssize_t __pyx_v_stride; + Py_ssize_t __pyx_v_suboffset; + Py_ssize_t __pyx_v_itemsize; + char *__pyx_v_resultp; + char *__pyx_r; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + Py_UCS4 __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("pybuffer_index", 1); + + /* "View.MemoryView":898 + * cdef char *pybuffer_index(Py_buffer *view, char *bufp, Py_ssize_t index, + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 # <<<<<<<<<<<<<< + * cdef Py_ssize_t itemsize = view.itemsize + * cdef char *resultp + */ + __pyx_v_suboffset = -1L; + + /* "View.MemoryView":899 + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 + * cdef Py_ssize_t itemsize = view.itemsize # <<<<<<<<<<<<<< + * cdef char *resultp + * + */ + __pyx_t_1 = __pyx_v_view->itemsize; + __pyx_v_itemsize = __pyx_t_1; + + /* "View.MemoryView":902 + * cdef char *resultp + * + * if view.ndim == 0: # <<<<<<<<<<<<<< + * shape = view.len // itemsize + * stride = itemsize + */ + __pyx_t_2 = (__pyx_v_view->ndim == 0); + if (__pyx_t_2) { + + /* "View.MemoryView":903 + * + * if view.ndim == 0: + * shape = view.len // itemsize # <<<<<<<<<<<<<< + * stride = itemsize + * else: + */ + if (unlikely(__pyx_v_itemsize == 0)) { + PyErr_SetString(PyExc_ZeroDivisionError, "integer division or modulo by zero"); + __PYX_ERR(1, 903, __pyx_L1_error) + } + else if (sizeof(Py_ssize_t) == sizeof(long) && (!(((Py_ssize_t)-1) > 0)) && unlikely(__pyx_v_itemsize == (Py_ssize_t)-1) && unlikely(__Pyx_UNARY_NEG_WOULD_OVERFLOW(__pyx_v_view->len))) { + PyErr_SetString(PyExc_OverflowError, "value too large to perform division"); + __PYX_ERR(1, 903, __pyx_L1_error) + } + __pyx_v_shape = __Pyx_div_Py_ssize_t(__pyx_v_view->len, __pyx_v_itemsize); + + /* "View.MemoryView":904 + * if view.ndim == 0: + * shape = view.len // itemsize + * stride = itemsize # <<<<<<<<<<<<<< + * else: + * shape = view.shape[dim] + */ + __pyx_v_stride = __pyx_v_itemsize; + + /* "View.MemoryView":902 + * cdef char *resultp + * + * if view.ndim == 0: # <<<<<<<<<<<<<< + * shape = view.len // itemsize + * stride = itemsize + */ + goto __pyx_L3; + } + + /* "View.MemoryView":906 + * stride = itemsize + * else: + * shape = view.shape[dim] # <<<<<<<<<<<<<< + * stride = view.strides[dim] + * if view.suboffsets != NULL: + */ + /*else*/ { + __pyx_v_shape = (__pyx_v_view->shape[__pyx_v_dim]); + + /* "View.MemoryView":907 + * else: + * shape = view.shape[dim] + * stride = view.strides[dim] # <<<<<<<<<<<<<< + * if view.suboffsets != NULL: + * suboffset = view.suboffsets[dim] + */ + __pyx_v_stride = (__pyx_v_view->strides[__pyx_v_dim]); + + /* "View.MemoryView":908 + * shape = view.shape[dim] + * stride = view.strides[dim] + * if view.suboffsets != NULL: # <<<<<<<<<<<<<< + * suboffset = view.suboffsets[dim] + * + */ + __pyx_t_2 = (__pyx_v_view->suboffsets != NULL); + if (__pyx_t_2) { + + /* "View.MemoryView":909 + * stride = view.strides[dim] + * if view.suboffsets != NULL: + * suboffset = view.suboffsets[dim] # <<<<<<<<<<<<<< + * + * if index < 0: + */ + __pyx_v_suboffset = (__pyx_v_view->suboffsets[__pyx_v_dim]); + + /* "View.MemoryView":908 + * shape = view.shape[dim] + * stride = view.strides[dim] + * if view.suboffsets != NULL: # <<<<<<<<<<<<<< + * suboffset = view.suboffsets[dim] + * + */ + } + } + __pyx_L3:; + + /* "View.MemoryView":911 + * suboffset = view.suboffsets[dim] + * + * if index < 0: # <<<<<<<<<<<<<< + * index += view.shape[dim] + * if index < 0: + */ + __pyx_t_2 = (__pyx_v_index < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":912 + * + * if index < 0: + * index += view.shape[dim] # <<<<<<<<<<<<<< + * if index < 0: + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + */ + __pyx_v_index = (__pyx_v_index + (__pyx_v_view->shape[__pyx_v_dim])); + + /* "View.MemoryView":913 + * if index < 0: + * index += view.shape[dim] + * if index < 0: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + __pyx_t_2 = (__pyx_v_index < 0); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":914 + * index += view.shape[dim] + * if index < 0: + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" # <<<<<<<<<<<<<< + * + * if index >= shape: + */ + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 914, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = 0; + __pyx_t_4 = 127; + __Pyx_INCREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_1 += 37; + __Pyx_GIVEREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_5 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_dim, 0, ' ', 'd'); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 914, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_5); + __Pyx_GIVEREF(__pyx_t_5); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_5); + __pyx_t_5 = 0; + __Pyx_INCREF(__pyx_kp_u__7); + __pyx_t_1 += 1; + __Pyx_GIVEREF(__pyx_kp_u__7); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_kp_u__7); + __pyx_t_5 = __Pyx_PyUnicode_Join(__pyx_t_3, 3, __pyx_t_1, __pyx_t_4); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 914, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_builtin_IndexError, __pyx_t_5, 0, 0); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __PYX_ERR(1, 914, __pyx_L1_error) + + /* "View.MemoryView":913 + * if index < 0: + * index += view.shape[dim] + * if index < 0: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + } + + /* "View.MemoryView":911 + * suboffset = view.suboffsets[dim] + * + * if index < 0: # <<<<<<<<<<<<<< + * index += view.shape[dim] + * if index < 0: + */ + } + + /* "View.MemoryView":916 + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + * if index >= shape: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + __pyx_t_2 = (__pyx_v_index >= __pyx_v_shape); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":917 + * + * if index >= shape: + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" # <<<<<<<<<<<<<< + * + * resultp = bufp + index * stride + */ + __pyx_t_5 = PyTuple_New(3); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 917, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 = 0; + __pyx_t_4 = 127; + __Pyx_INCREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_1 += 37; + __Pyx_GIVEREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_3 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_dim, 0, ' ', 'd'); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 917, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_3); + PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_3); + __pyx_t_3 = 0; + __Pyx_INCREF(__pyx_kp_u__7); + __pyx_t_1 += 1; + __Pyx_GIVEREF(__pyx_kp_u__7); + PyTuple_SET_ITEM(__pyx_t_5, 2, __pyx_kp_u__7); + __pyx_t_3 = __Pyx_PyUnicode_Join(__pyx_t_5, 3, __pyx_t_1, __pyx_t_4); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 917, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_Raise(__pyx_builtin_IndexError, __pyx_t_3, 0, 0); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __PYX_ERR(1, 917, __pyx_L1_error) + + /* "View.MemoryView":916 + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + * if index >= shape: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + } + + /* "View.MemoryView":919 + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + * resultp = bufp + index * stride # <<<<<<<<<<<<<< + * if suboffset >= 0: + * resultp = ( resultp)[0] + suboffset + */ + __pyx_v_resultp = (__pyx_v_bufp + (__pyx_v_index * __pyx_v_stride)); + + /* "View.MemoryView":920 + * + * resultp = bufp + index * stride + * if suboffset >= 0: # <<<<<<<<<<<<<< + * resultp = ( resultp)[0] + suboffset + * + */ + __pyx_t_2 = (__pyx_v_suboffset >= 0); + if (__pyx_t_2) { + + /* "View.MemoryView":921 + * resultp = bufp + index * stride + * if suboffset >= 0: + * resultp = ( resultp)[0] + suboffset # <<<<<<<<<<<<<< + * + * return resultp + */ + __pyx_v_resultp = ((((char **)__pyx_v_resultp)[0]) + __pyx_v_suboffset); + + /* "View.MemoryView":920 + * + * resultp = bufp + index * stride + * if suboffset >= 0: # <<<<<<<<<<<<<< + * resultp = ( resultp)[0] + suboffset + * + */ + } + + /* "View.MemoryView":923 + * resultp = ( resultp)[0] + suboffset + * + * return resultp # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = __pyx_v_resultp; + goto __pyx_L0; + + /* "View.MemoryView":896 + * + * @cname('__pyx_pybuffer_index') + * cdef char *pybuffer_index(Py_buffer *view, char *bufp, Py_ssize_t index, # <<<<<<<<<<<<<< + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.pybuffer_index", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":929 + * + * @cname('__pyx_memslice_transpose') + * cdef int transpose_memslice(__Pyx_memviewslice *memslice) except -1 nogil: # <<<<<<<<<<<<<< + * cdef int ndim = memslice.memview.view.ndim + * + */ + +static int __pyx_memslice_transpose(__Pyx_memviewslice *__pyx_v_memslice) { + int __pyx_v_ndim; + Py_ssize_t *__pyx_v_shape; + Py_ssize_t *__pyx_v_strides; + int __pyx_v_i; + int __pyx_v_j; + int __pyx_r; + int __pyx_t_1; + Py_ssize_t *__pyx_t_2; + long __pyx_t_3; + long __pyx_t_4; + Py_ssize_t __pyx_t_5; + Py_ssize_t __pyx_t_6; + int __pyx_t_7; + int __pyx_t_8; + int __pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":930 + * @cname('__pyx_memslice_transpose') + * cdef int transpose_memslice(__Pyx_memviewslice *memslice) except -1 nogil: + * cdef int ndim = memslice.memview.view.ndim # <<<<<<<<<<<<<< + * + * cdef Py_ssize_t *shape = memslice.shape + */ + __pyx_t_1 = __pyx_v_memslice->memview->view.ndim; + __pyx_v_ndim = __pyx_t_1; + + /* "View.MemoryView":932 + * cdef int ndim = memslice.memview.view.ndim + * + * cdef Py_ssize_t *shape = memslice.shape # <<<<<<<<<<<<<< + * cdef Py_ssize_t *strides = memslice.strides + * + */ + __pyx_t_2 = __pyx_v_memslice->shape; + __pyx_v_shape = __pyx_t_2; + + /* "View.MemoryView":933 + * + * cdef Py_ssize_t *shape = memslice.shape + * cdef Py_ssize_t *strides = memslice.strides # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = __pyx_v_memslice->strides; + __pyx_v_strides = __pyx_t_2; + + /* "View.MemoryView":937 + * + * cdef int i, j + * for i in range(ndim // 2): # <<<<<<<<<<<<<< + * j = ndim - 1 - i + * strides[i], strides[j] = strides[j], strides[i] + */ + __pyx_t_3 = __Pyx_div_long(__pyx_v_ndim, 2); + __pyx_t_4 = __pyx_t_3; + for (__pyx_t_1 = 0; __pyx_t_1 < __pyx_t_4; __pyx_t_1+=1) { + __pyx_v_i = __pyx_t_1; + + /* "View.MemoryView":938 + * cdef int i, j + * for i in range(ndim // 2): + * j = ndim - 1 - i # <<<<<<<<<<<<<< + * strides[i], strides[j] = strides[j], strides[i] + * shape[i], shape[j] = shape[j], shape[i] + */ + __pyx_v_j = ((__pyx_v_ndim - 1) - __pyx_v_i); + + /* "View.MemoryView":939 + * for i in range(ndim // 2): + * j = ndim - 1 - i + * strides[i], strides[j] = strides[j], strides[i] # <<<<<<<<<<<<<< + * shape[i], shape[j] = shape[j], shape[i] + * + */ + __pyx_t_5 = (__pyx_v_strides[__pyx_v_j]); + __pyx_t_6 = (__pyx_v_strides[__pyx_v_i]); + (__pyx_v_strides[__pyx_v_i]) = __pyx_t_5; + (__pyx_v_strides[__pyx_v_j]) = __pyx_t_6; + + /* "View.MemoryView":940 + * j = ndim - 1 - i + * strides[i], strides[j] = strides[j], strides[i] + * shape[i], shape[j] = shape[j], shape[i] # <<<<<<<<<<<<<< + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: + */ + __pyx_t_6 = (__pyx_v_shape[__pyx_v_j]); + __pyx_t_5 = (__pyx_v_shape[__pyx_v_i]); + (__pyx_v_shape[__pyx_v_i]) = __pyx_t_6; + (__pyx_v_shape[__pyx_v_j]) = __pyx_t_5; + + /* "View.MemoryView":942 + * shape[i], shape[j] = shape[j], shape[i] + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: # <<<<<<<<<<<<<< + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") + * + */ + __pyx_t_8 = ((__pyx_v_memslice->suboffsets[__pyx_v_i]) >= 0); + if (!__pyx_t_8) { + } else { + __pyx_t_7 = __pyx_t_8; + goto __pyx_L6_bool_binop_done; + } + __pyx_t_8 = ((__pyx_v_memslice->suboffsets[__pyx_v_j]) >= 0); + __pyx_t_7 = __pyx_t_8; + __pyx_L6_bool_binop_done:; + if (__pyx_t_7) { + + /* "View.MemoryView":943 + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") # <<<<<<<<<<<<<< + * + * return 0 + */ + __pyx_t_9 = __pyx_memoryview_err(PyExc_ValueError, __pyx_kp_s_Cannot_transpose_memoryview_with); if (unlikely(__pyx_t_9 == ((int)-1))) __PYX_ERR(1, 943, __pyx_L1_error) + + /* "View.MemoryView":942 + * shape[i], shape[j] = shape[j], shape[i] + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: # <<<<<<<<<<<<<< + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") + * + */ + } + } + + /* "View.MemoryView":945 + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") + * + * return 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":929 + * + * @cname('__pyx_memslice_transpose') + * cdef int transpose_memslice(__Pyx_memviewslice *memslice) except -1 nogil: # <<<<<<<<<<<<<< + * cdef int ndim = memslice.memview.view.ndim + * + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.transpose_memslice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":963 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + */ + +/* Python wrapper */ +static void __pyx_memoryviewslice___dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_memoryviewslice___dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_memoryviewslice___pyx_pf_15View_dot_MemoryView_16_memoryviewslice___dealloc__(((struct __pyx_memoryviewslice_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_memoryviewslice___pyx_pf_15View_dot_MemoryView_16_memoryviewslice___dealloc__(struct __pyx_memoryviewslice_obj *__pyx_v_self) { + + /* "View.MemoryView":964 + * + * def __dealloc__(self): + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) # <<<<<<<<<<<<<< + * + * cdef convert_item_to_object(self, char *itemp): + */ + __PYX_XCLEAR_MEMVIEW((&__pyx_v_self->from_slice), 1); + + /* "View.MemoryView":963 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + */ + + /* function exit code */ +} + +/* "View.MemoryView":966 + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * if self.to_object_func != NULL: + * return self.to_object_func(itemp) + */ + +static PyObject *__pyx_memoryviewslice_convert_item_to_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("convert_item_to_object", 1); + + /* "View.MemoryView":967 + * + * cdef convert_item_to_object(self, char *itemp): + * if self.to_object_func != NULL: # <<<<<<<<<<<<<< + * return self.to_object_func(itemp) + * else: + */ + __pyx_t_1 = (__pyx_v_self->to_object_func != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":968 + * cdef convert_item_to_object(self, char *itemp): + * if self.to_object_func != NULL: + * return self.to_object_func(itemp) # <<<<<<<<<<<<<< + * else: + * return memoryview.convert_item_to_object(self, itemp) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_v_self->to_object_func(__pyx_v_itemp); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 968, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":967 + * + * cdef convert_item_to_object(self, char *itemp): + * if self.to_object_func != NULL: # <<<<<<<<<<<<<< + * return self.to_object_func(itemp) + * else: + */ + } + + /* "View.MemoryView":970 + * return self.to_object_func(itemp) + * else: + * return memoryview.convert_item_to_object(self, itemp) # <<<<<<<<<<<<<< + * + * cdef assign_item_from_object(self, char *itemp, object value): + */ + /*else*/ { + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_memoryview_convert_item_to_object(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v_itemp); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 970, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + } + + /* "View.MemoryView":966 + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * if self.to_object_func != NULL: + * return self.to_object_func(itemp) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.convert_item_to_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":972 + * return memoryview.convert_item_to_object(self, itemp) + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * if self.to_dtype_func != NULL: + * self.to_dtype_func(itemp, value) + */ + +static PyObject *__pyx_memoryviewslice_assign_item_from_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("assign_item_from_object", 1); + + /* "View.MemoryView":973 + * + * cdef assign_item_from_object(self, char *itemp, object value): + * if self.to_dtype_func != NULL: # <<<<<<<<<<<<<< + * self.to_dtype_func(itemp, value) + * else: + */ + __pyx_t_1 = (__pyx_v_self->to_dtype_func != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":974 + * cdef assign_item_from_object(self, char *itemp, object value): + * if self.to_dtype_func != NULL: + * self.to_dtype_func(itemp, value) # <<<<<<<<<<<<<< + * else: + * memoryview.assign_item_from_object(self, itemp, value) + */ + __pyx_t_2 = __pyx_v_self->to_dtype_func(__pyx_v_itemp, __pyx_v_value); if (unlikely(__pyx_t_2 == ((int)0))) __PYX_ERR(1, 974, __pyx_L1_error) + + /* "View.MemoryView":973 + * + * cdef assign_item_from_object(self, char *itemp, object value): + * if self.to_dtype_func != NULL: # <<<<<<<<<<<<<< + * self.to_dtype_func(itemp, value) + * else: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":976 + * self.to_dtype_func(itemp, value) + * else: + * memoryview.assign_item_from_object(self, itemp, value) # <<<<<<<<<<<<<< + * + * cdef _get_base(self): + */ + /*else*/ { + __pyx_t_3 = __pyx_memoryview_assign_item_from_object(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v_itemp, __pyx_v_value); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 976, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_L3:; + + /* "View.MemoryView":972 + * return memoryview.convert_item_to_object(self, itemp) + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * if self.to_dtype_func != NULL: + * self.to_dtype_func(itemp, value) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.assign_item_from_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":978 + * memoryview.assign_item_from_object(self, itemp, value) + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.from_object + * + */ + +static PyObject *__pyx_memoryviewslice__get_base(struct __pyx_memoryviewslice_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("_get_base", 1); + + /* "View.MemoryView":979 + * + * cdef _get_base(self): + * return self.from_object # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->from_object); + __pyx_r = __pyx_v_self->from_object; + goto __pyx_L0; + + /* "View.MemoryView":978 + * memoryview.assign_item_from_object(self, itemp, value) + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.from_object + * + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryviewslice_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryviewslice_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_memoryviewslice___reduce_cython__(((struct __pyx_memoryviewslice_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryviewslice___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryviewslice_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryviewslice_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_memoryviewslice_2__setstate_cython__(((struct __pyx_memoryviewslice_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryviewslice_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":999 + * + * @cname('__pyx_memoryview_fromslice') + * cdef memoryview_fromslice(__Pyx_memviewslice memviewslice, # <<<<<<<<<<<<<< + * int ndim, + * object (*to_object_func)(char *), + */ + +static PyObject *__pyx_memoryview_fromslice(__Pyx_memviewslice __pyx_v_memviewslice, int __pyx_v_ndim, PyObject *(*__pyx_v_to_object_func)(char *), int (*__pyx_v_to_dtype_func)(char *, PyObject *), int __pyx_v_dtype_is_object) { + struct __pyx_memoryviewslice_obj *__pyx_v_result = 0; + Py_ssize_t __pyx_v_suboffset; + PyObject *__pyx_v_length = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + __Pyx_TypeInfo *__pyx_t_4; + Py_buffer __pyx_t_5; + Py_ssize_t *__pyx_t_6; + Py_ssize_t *__pyx_t_7; + Py_ssize_t *__pyx_t_8; + Py_ssize_t __pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_fromslice", 1); + + /* "View.MemoryView":1007 + * cdef _memoryviewslice result + * + * if memviewslice.memview == Py_None: # <<<<<<<<<<<<<< + * return None + * + */ + __pyx_t_1 = (((PyObject *)__pyx_v_memviewslice.memview) == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":1008 + * + * if memviewslice.memview == Py_None: + * return None # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "View.MemoryView":1007 + * cdef _memoryviewslice result + * + * if memviewslice.memview == Py_None: # <<<<<<<<<<<<<< + * return None + * + */ + } + + /* "View.MemoryView":1013 + * + * + * result = _memoryviewslice.__new__(_memoryviewslice, None, 0, dtype_is_object) # <<<<<<<<<<<<<< + * + * result.from_slice = memviewslice + */ + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_v_dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1013, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 1013, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(Py_None); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, Py_None)) __PYX_ERR(1, 1013, __pyx_L1_error); + __Pyx_INCREF(__pyx_int_0); + __Pyx_GIVEREF(__pyx_int_0); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_int_0)) __PYX_ERR(1, 1013, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_t_2)) __PYX_ERR(1, 1013, __pyx_L1_error); + __pyx_t_2 = 0; + __pyx_t_2 = ((PyObject *)__pyx_tp_new__memoryviewslice(((PyTypeObject *)__pyx_memoryviewslice_type), __pyx_t_3, NULL)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1013, __pyx_L1_error) + __Pyx_GOTREF((PyObject *)__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_v_result = ((struct __pyx_memoryviewslice_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":1015 + * result = _memoryviewslice.__new__(_memoryviewslice, None, 0, dtype_is_object) + * + * result.from_slice = memviewslice # <<<<<<<<<<<<<< + * __PYX_INC_MEMVIEW(&memviewslice, 1) + * + */ + __pyx_v_result->from_slice = __pyx_v_memviewslice; + + /* "View.MemoryView":1016 + * + * result.from_slice = memviewslice + * __PYX_INC_MEMVIEW(&memviewslice, 1) # <<<<<<<<<<<<<< + * + * result.from_object = ( memviewslice.memview)._get_base() + */ + __PYX_INC_MEMVIEW((&__pyx_v_memviewslice), 1); + + /* "View.MemoryView":1018 + * __PYX_INC_MEMVIEW(&memviewslice, 1) + * + * result.from_object = ( memviewslice.memview)._get_base() # <<<<<<<<<<<<<< + * result.typeinfo = memviewslice.memview.typeinfo + * + */ + __pyx_t_2 = ((struct __pyx_vtabstruct_memoryview *)((struct __pyx_memoryview_obj *)__pyx_v_memviewslice.memview)->__pyx_vtab)->_get_base(((struct __pyx_memoryview_obj *)__pyx_v_memviewslice.memview)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1018, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + __Pyx_GOTREF(__pyx_v_result->from_object); + __Pyx_DECREF(__pyx_v_result->from_object); + __pyx_v_result->from_object = __pyx_t_2; + __pyx_t_2 = 0; + + /* "View.MemoryView":1019 + * + * result.from_object = ( memviewslice.memview)._get_base() + * result.typeinfo = memviewslice.memview.typeinfo # <<<<<<<<<<<<<< + * + * result.view = memviewslice.memview.view + */ + __pyx_t_4 = __pyx_v_memviewslice.memview->typeinfo; + __pyx_v_result->__pyx_base.typeinfo = __pyx_t_4; + + /* "View.MemoryView":1021 + * result.typeinfo = memviewslice.memview.typeinfo + * + * result.view = memviewslice.memview.view # <<<<<<<<<<<<<< + * result.view.buf = memviewslice.data + * result.view.ndim = ndim + */ + __pyx_t_5 = __pyx_v_memviewslice.memview->view; + __pyx_v_result->__pyx_base.view = __pyx_t_5; + + /* "View.MemoryView":1022 + * + * result.view = memviewslice.memview.view + * result.view.buf = memviewslice.data # <<<<<<<<<<<<<< + * result.view.ndim = ndim + * (<__pyx_buffer *> &result.view).obj = Py_None + */ + __pyx_v_result->__pyx_base.view.buf = ((void *)__pyx_v_memviewslice.data); + + /* "View.MemoryView":1023 + * result.view = memviewslice.memview.view + * result.view.buf = memviewslice.data + * result.view.ndim = ndim # <<<<<<<<<<<<<< + * (<__pyx_buffer *> &result.view).obj = Py_None + * Py_INCREF(Py_None) + */ + __pyx_v_result->__pyx_base.view.ndim = __pyx_v_ndim; + + /* "View.MemoryView":1024 + * result.view.buf = memviewslice.data + * result.view.ndim = ndim + * (<__pyx_buffer *> &result.view).obj = Py_None # <<<<<<<<<<<<<< + * Py_INCREF(Py_None) + * + */ + ((Py_buffer *)(&__pyx_v_result->__pyx_base.view))->obj = Py_None; + + /* "View.MemoryView":1025 + * result.view.ndim = ndim + * (<__pyx_buffer *> &result.view).obj = Py_None + * Py_INCREF(Py_None) # <<<<<<<<<<<<<< + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: + */ + Py_INCREF(Py_None); + + /* "View.MemoryView":1027 + * Py_INCREF(Py_None) + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: # <<<<<<<<<<<<<< + * result.flags = PyBUF_RECORDS + * else: + */ + __pyx_t_1 = ((((struct __pyx_memoryview_obj *)__pyx_v_memviewslice.memview)->flags & PyBUF_WRITABLE) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":1028 + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: + * result.flags = PyBUF_RECORDS # <<<<<<<<<<<<<< + * else: + * result.flags = PyBUF_RECORDS_RO + */ + __pyx_v_result->__pyx_base.flags = PyBUF_RECORDS; + + /* "View.MemoryView":1027 + * Py_INCREF(Py_None) + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: # <<<<<<<<<<<<<< + * result.flags = PyBUF_RECORDS + * else: + */ + goto __pyx_L4; + } + + /* "View.MemoryView":1030 + * result.flags = PyBUF_RECORDS + * else: + * result.flags = PyBUF_RECORDS_RO # <<<<<<<<<<<<<< + * + * result.view.shape = result.from_slice.shape + */ + /*else*/ { + __pyx_v_result->__pyx_base.flags = PyBUF_RECORDS_RO; + } + __pyx_L4:; + + /* "View.MemoryView":1032 + * result.flags = PyBUF_RECORDS_RO + * + * result.view.shape = result.from_slice.shape # <<<<<<<<<<<<<< + * result.view.strides = result.from_slice.strides + * + */ + __pyx_v_result->__pyx_base.view.shape = ((Py_ssize_t *)__pyx_v_result->from_slice.shape); + + /* "View.MemoryView":1033 + * + * result.view.shape = result.from_slice.shape + * result.view.strides = result.from_slice.strides # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_result->__pyx_base.view.strides = ((Py_ssize_t *)__pyx_v_result->from_slice.strides); + + /* "View.MemoryView":1036 + * + * + * result.view.suboffsets = NULL # <<<<<<<<<<<<<< + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: + */ + __pyx_v_result->__pyx_base.view.suboffsets = NULL; + + /* "View.MemoryView":1037 + * + * result.view.suboffsets = NULL + * for suboffset in result.from_slice.suboffsets[:ndim]: # <<<<<<<<<<<<<< + * if suboffset >= 0: + * result.view.suboffsets = result.from_slice.suboffsets + */ + __pyx_t_7 = (__pyx_v_result->from_slice.suboffsets + __pyx_v_ndim); + for (__pyx_t_8 = __pyx_v_result->from_slice.suboffsets; __pyx_t_8 < __pyx_t_7; __pyx_t_8++) { + __pyx_t_6 = __pyx_t_8; + __pyx_v_suboffset = (__pyx_t_6[0]); + + /* "View.MemoryView":1038 + * result.view.suboffsets = NULL + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * result.view.suboffsets = result.from_slice.suboffsets + * break + */ + __pyx_t_1 = (__pyx_v_suboffset >= 0); + if (__pyx_t_1) { + + /* "View.MemoryView":1039 + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: + * result.view.suboffsets = result.from_slice.suboffsets # <<<<<<<<<<<<<< + * break + * + */ + __pyx_v_result->__pyx_base.view.suboffsets = ((Py_ssize_t *)__pyx_v_result->from_slice.suboffsets); + + /* "View.MemoryView":1040 + * if suboffset >= 0: + * result.view.suboffsets = result.from_slice.suboffsets + * break # <<<<<<<<<<<<<< + * + * result.view.len = result.view.itemsize + */ + goto __pyx_L6_break; + + /* "View.MemoryView":1038 + * result.view.suboffsets = NULL + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * result.view.suboffsets = result.from_slice.suboffsets + * break + */ + } + } + __pyx_L6_break:; + + /* "View.MemoryView":1042 + * break + * + * result.view.len = result.view.itemsize # <<<<<<<<<<<<<< + * for length in result.view.shape[:ndim]: + * result.view.len *= length + */ + __pyx_t_9 = __pyx_v_result->__pyx_base.view.itemsize; + __pyx_v_result->__pyx_base.view.len = __pyx_t_9; + + /* "View.MemoryView":1043 + * + * result.view.len = result.view.itemsize + * for length in result.view.shape[:ndim]: # <<<<<<<<<<<<<< + * result.view.len *= length + * + */ + __pyx_t_7 = (__pyx_v_result->__pyx_base.view.shape + __pyx_v_ndim); + for (__pyx_t_8 = __pyx_v_result->__pyx_base.view.shape; __pyx_t_8 < __pyx_t_7; __pyx_t_8++) { + __pyx_t_6 = __pyx_t_8; + __pyx_t_2 = PyInt_FromSsize_t((__pyx_t_6[0])); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1043, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_XDECREF_SET(__pyx_v_length, __pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":1044 + * result.view.len = result.view.itemsize + * for length in result.view.shape[:ndim]: + * result.view.len *= length # <<<<<<<<<<<<<< + * + * result.to_object_func = to_object_func + */ + __pyx_t_2 = PyInt_FromSsize_t(__pyx_v_result->__pyx_base.view.len); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1044, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyNumber_InPlaceMultiply(__pyx_t_2, __pyx_v_length); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 1044, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_9 = __Pyx_PyIndex_AsSsize_t(__pyx_t_3); if (unlikely((__pyx_t_9 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 1044, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_v_result->__pyx_base.view.len = __pyx_t_9; + } + + /* "View.MemoryView":1046 + * result.view.len *= length + * + * result.to_object_func = to_object_func # <<<<<<<<<<<<<< + * result.to_dtype_func = to_dtype_func + * + */ + __pyx_v_result->to_object_func = __pyx_v_to_object_func; + + /* "View.MemoryView":1047 + * + * result.to_object_func = to_object_func + * result.to_dtype_func = to_dtype_func # <<<<<<<<<<<<<< + * + * return result + */ + __pyx_v_result->to_dtype_func = __pyx_v_to_dtype_func; + + /* "View.MemoryView":1049 + * result.to_dtype_func = to_dtype_func + * + * return result # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_get_slice_from_memoryview') + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = ((PyObject *)__pyx_v_result); + goto __pyx_L0; + + /* "View.MemoryView":999 + * + * @cname('__pyx_memoryview_fromslice') + * cdef memoryview_fromslice(__Pyx_memviewslice memviewslice, # <<<<<<<<<<<<<< + * int ndim, + * object (*to_object_func)(char *), + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview_fromslice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XDECREF(__pyx_v_length); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1052 + * + * @cname('__pyx_memoryview_get_slice_from_memoryview') + * cdef __Pyx_memviewslice *get_slice_from_memview(memoryview memview, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + */ + +static __Pyx_memviewslice *__pyx_memoryview_get_slice_from_memoryview(struct __pyx_memoryview_obj *__pyx_v_memview, __Pyx_memviewslice *__pyx_v_mslice) { + struct __pyx_memoryviewslice_obj *__pyx_v_obj = 0; + __Pyx_memviewslice *__pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_slice_from_memview", 1); + + /* "View.MemoryView":1055 + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * obj = memview + * return &obj.from_slice + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":1056 + * cdef _memoryviewslice obj + * if isinstance(memview, _memoryviewslice): + * obj = memview # <<<<<<<<<<<<<< + * return &obj.from_slice + * else: + */ + if (!(likely(((((PyObject *)__pyx_v_memview)) == Py_None) || likely(__Pyx_TypeTest(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type))))) __PYX_ERR(1, 1056, __pyx_L1_error) + __pyx_t_2 = ((PyObject *)__pyx_v_memview); + __Pyx_INCREF(__pyx_t_2); + __pyx_v_obj = ((struct __pyx_memoryviewslice_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":1057 + * if isinstance(memview, _memoryviewslice): + * obj = memview + * return &obj.from_slice # <<<<<<<<<<<<<< + * else: + * slice_copy(memview, mslice) + */ + __pyx_r = (&__pyx_v_obj->from_slice); + goto __pyx_L0; + + /* "View.MemoryView":1055 + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * obj = memview + * return &obj.from_slice + */ + } + + /* "View.MemoryView":1059 + * return &obj.from_slice + * else: + * slice_copy(memview, mslice) # <<<<<<<<<<<<<< + * return mslice + * + */ + /*else*/ { + __pyx_memoryview_slice_copy(__pyx_v_memview, __pyx_v_mslice); + + /* "View.MemoryView":1060 + * else: + * slice_copy(memview, mslice) + * return mslice # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_slice_copy') + */ + __pyx_r = __pyx_v_mslice; + goto __pyx_L0; + } + + /* "View.MemoryView":1052 + * + * @cname('__pyx_memoryview_get_slice_from_memoryview') + * cdef __Pyx_memviewslice *get_slice_from_memview(memoryview memview, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.get_slice_from_memview", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_obj); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1063 + * + * @cname('__pyx_memoryview_slice_copy') + * cdef void slice_copy(memoryview memview, __Pyx_memviewslice *dst) noexcept: # <<<<<<<<<<<<<< + * cdef int dim + * cdef (Py_ssize_t*) shape, strides, suboffsets + */ + +static void __pyx_memoryview_slice_copy(struct __pyx_memoryview_obj *__pyx_v_memview, __Pyx_memviewslice *__pyx_v_dst) { + int __pyx_v_dim; + Py_ssize_t *__pyx_v_shape; + Py_ssize_t *__pyx_v_strides; + Py_ssize_t *__pyx_v_suboffsets; + Py_ssize_t *__pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + Py_ssize_t __pyx_t_5; + int __pyx_t_6; + + /* "View.MemoryView":1067 + * cdef (Py_ssize_t*) shape, strides, suboffsets + * + * shape = memview.view.shape # <<<<<<<<<<<<<< + * strides = memview.view.strides + * suboffsets = memview.view.suboffsets + */ + __pyx_t_1 = __pyx_v_memview->view.shape; + __pyx_v_shape = __pyx_t_1; + + /* "View.MemoryView":1068 + * + * shape = memview.view.shape + * strides = memview.view.strides # <<<<<<<<<<<<<< + * suboffsets = memview.view.suboffsets + * + */ + __pyx_t_1 = __pyx_v_memview->view.strides; + __pyx_v_strides = __pyx_t_1; + + /* "View.MemoryView":1069 + * shape = memview.view.shape + * strides = memview.view.strides + * suboffsets = memview.view.suboffsets # <<<<<<<<<<<<<< + * + * dst.memview = <__pyx_memoryview *> memview + */ + __pyx_t_1 = __pyx_v_memview->view.suboffsets; + __pyx_v_suboffsets = __pyx_t_1; + + /* "View.MemoryView":1071 + * suboffsets = memview.view.suboffsets + * + * dst.memview = <__pyx_memoryview *> memview # <<<<<<<<<<<<<< + * dst.data = memview.view.buf + * + */ + __pyx_v_dst->memview = ((struct __pyx_memoryview_obj *)__pyx_v_memview); + + /* "View.MemoryView":1072 + * + * dst.memview = <__pyx_memoryview *> memview + * dst.data = memview.view.buf # <<<<<<<<<<<<<< + * + * for dim in range(memview.view.ndim): + */ + __pyx_v_dst->data = ((char *)__pyx_v_memview->view.buf); + + /* "View.MemoryView":1074 + * dst.data = memview.view.buf + * + * for dim in range(memview.view.ndim): # <<<<<<<<<<<<<< + * dst.shape[dim] = shape[dim] + * dst.strides[dim] = strides[dim] + */ + __pyx_t_2 = __pyx_v_memview->view.ndim; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_dim = __pyx_t_4; + + /* "View.MemoryView":1075 + * + * for dim in range(memview.view.ndim): + * dst.shape[dim] = shape[dim] # <<<<<<<<<<<<<< + * dst.strides[dim] = strides[dim] + * dst.suboffsets[dim] = suboffsets[dim] if suboffsets else -1 + */ + (__pyx_v_dst->shape[__pyx_v_dim]) = (__pyx_v_shape[__pyx_v_dim]); + + /* "View.MemoryView":1076 + * for dim in range(memview.view.ndim): + * dst.shape[dim] = shape[dim] + * dst.strides[dim] = strides[dim] # <<<<<<<<<<<<<< + * dst.suboffsets[dim] = suboffsets[dim] if suboffsets else -1 + * + */ + (__pyx_v_dst->strides[__pyx_v_dim]) = (__pyx_v_strides[__pyx_v_dim]); + + /* "View.MemoryView":1077 + * dst.shape[dim] = shape[dim] + * dst.strides[dim] = strides[dim] + * dst.suboffsets[dim] = suboffsets[dim] if suboffsets else -1 # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_copy_object') + */ + __pyx_t_6 = (__pyx_v_suboffsets != 0); + if (__pyx_t_6) { + __pyx_t_5 = (__pyx_v_suboffsets[__pyx_v_dim]); + } else { + __pyx_t_5 = -1L; + } + (__pyx_v_dst->suboffsets[__pyx_v_dim]) = __pyx_t_5; + } + + /* "View.MemoryView":1063 + * + * @cname('__pyx_memoryview_slice_copy') + * cdef void slice_copy(memoryview memview, __Pyx_memviewslice *dst) noexcept: # <<<<<<<<<<<<<< + * cdef int dim + * cdef (Py_ssize_t*) shape, strides, suboffsets + */ + + /* function exit code */ +} + +/* "View.MemoryView":1080 + * + * @cname('__pyx_memoryview_copy_object') + * cdef memoryview_copy(memoryview memview): # <<<<<<<<<<<<<< + * "Create a new memoryview object" + * cdef __Pyx_memviewslice memviewslice + */ + +static PyObject *__pyx_memoryview_copy_object(struct __pyx_memoryview_obj *__pyx_v_memview) { + __Pyx_memviewslice __pyx_v_memviewslice; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_copy", 1); + + /* "View.MemoryView":1083 + * "Create a new memoryview object" + * cdef __Pyx_memviewslice memviewslice + * slice_copy(memview, &memviewslice) # <<<<<<<<<<<<<< + * return memoryview_copy_from_slice(memview, &memviewslice) + * + */ + __pyx_memoryview_slice_copy(__pyx_v_memview, (&__pyx_v_memviewslice)); + + /* "View.MemoryView":1084 + * cdef __Pyx_memviewslice memviewslice + * slice_copy(memview, &memviewslice) + * return memoryview_copy_from_slice(memview, &memviewslice) # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_copy_object_from_slice') + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __pyx_memoryview_copy_object_from_slice(__pyx_v_memview, (&__pyx_v_memviewslice)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 1084, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":1080 + * + * @cname('__pyx_memoryview_copy_object') + * cdef memoryview_copy(memoryview memview): # <<<<<<<<<<<<<< + * "Create a new memoryview object" + * cdef __Pyx_memviewslice memviewslice + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview_copy", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1087 + * + * @cname('__pyx_memoryview_copy_object_from_slice') + * cdef memoryview_copy_from_slice(memoryview memview, __Pyx_memviewslice *memviewslice): # <<<<<<<<<<<<<< + * """ + * Create a new memoryview object from a given memoryview object and slice. + */ + +static PyObject *__pyx_memoryview_copy_object_from_slice(struct __pyx_memoryview_obj *__pyx_v_memview, __Pyx_memviewslice *__pyx_v_memviewslice) { + PyObject *(*__pyx_v_to_object_func)(char *); + int (*__pyx_v_to_dtype_func)(char *, PyObject *); + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *(*__pyx_t_2)(char *); + int (*__pyx_t_3)(char *, PyObject *); + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_copy_from_slice", 1); + + /* "View.MemoryView":1094 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * to_object_func = (<_memoryviewslice> memview).to_object_func + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":1095 + * + * if isinstance(memview, _memoryviewslice): + * to_object_func = (<_memoryviewslice> memview).to_object_func # <<<<<<<<<<<<<< + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + * else: + */ + __pyx_t_2 = ((struct __pyx_memoryviewslice_obj *)__pyx_v_memview)->to_object_func; + __pyx_v_to_object_func = __pyx_t_2; + + /* "View.MemoryView":1096 + * if isinstance(memview, _memoryviewslice): + * to_object_func = (<_memoryviewslice> memview).to_object_func + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func # <<<<<<<<<<<<<< + * else: + * to_object_func = NULL + */ + __pyx_t_3 = ((struct __pyx_memoryviewslice_obj *)__pyx_v_memview)->to_dtype_func; + __pyx_v_to_dtype_func = __pyx_t_3; + + /* "View.MemoryView":1094 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * to_object_func = (<_memoryviewslice> memview).to_object_func + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1098 + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + * else: + * to_object_func = NULL # <<<<<<<<<<<<<< + * to_dtype_func = NULL + * + */ + /*else*/ { + __pyx_v_to_object_func = NULL; + + /* "View.MemoryView":1099 + * else: + * to_object_func = NULL + * to_dtype_func = NULL # <<<<<<<<<<<<<< + * + * return memoryview_fromslice(memviewslice[0], memview.view.ndim, + */ + __pyx_v_to_dtype_func = NULL; + } + __pyx_L3:; + + /* "View.MemoryView":1101 + * to_dtype_func = NULL + * + * return memoryview_fromslice(memviewslice[0], memview.view.ndim, # <<<<<<<<<<<<<< + * to_object_func, to_dtype_func, + * memview.dtype_is_object) + */ + __Pyx_XDECREF(__pyx_r); + + /* "View.MemoryView":1103 + * return memoryview_fromslice(memviewslice[0], memview.view.ndim, + * to_object_func, to_dtype_func, + * memview.dtype_is_object) # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_4 = __pyx_memoryview_fromslice((__pyx_v_memviewslice[0]), __pyx_v_memview->view.ndim, __pyx_v_to_object_func, __pyx_v_to_dtype_func, __pyx_v_memview->dtype_is_object); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1101, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_r = __pyx_t_4; + __pyx_t_4 = 0; + goto __pyx_L0; + + /* "View.MemoryView":1087 + * + * @cname('__pyx_memoryview_copy_object_from_slice') + * cdef memoryview_copy_from_slice(memoryview memview, __Pyx_memviewslice *memviewslice): # <<<<<<<<<<<<<< + * """ + * Create a new memoryview object from a given memoryview object and slice. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.memoryview_copy_from_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1109 + * + * + * cdef Py_ssize_t abs_py_ssize_t(Py_ssize_t arg) noexcept nogil: # <<<<<<<<<<<<<< + * return -arg if arg < 0 else arg + * + */ + +static Py_ssize_t abs_py_ssize_t(Py_ssize_t __pyx_v_arg) { + Py_ssize_t __pyx_r; + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + + /* "View.MemoryView":1110 + * + * cdef Py_ssize_t abs_py_ssize_t(Py_ssize_t arg) noexcept nogil: + * return -arg if arg < 0 else arg # <<<<<<<<<<<<<< + * + * @cname('__pyx_get_best_slice_order') + */ + __pyx_t_2 = (__pyx_v_arg < 0); + if (__pyx_t_2) { + __pyx_t_1 = (-__pyx_v_arg); + } else { + __pyx_t_1 = __pyx_v_arg; + } + __pyx_r = __pyx_t_1; + goto __pyx_L0; + + /* "View.MemoryView":1109 + * + * + * cdef Py_ssize_t abs_py_ssize_t(Py_ssize_t arg) noexcept nogil: # <<<<<<<<<<<<<< + * return -arg if arg < 0 else arg + * + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1113 + * + * @cname('__pyx_get_best_slice_order') + * cdef char get_best_order(__Pyx_memviewslice *mslice, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * """ + * Figure out the best memory access order for a given slice. + */ + +static char __pyx_get_best_slice_order(__Pyx_memviewslice *__pyx_v_mslice, int __pyx_v_ndim) { + int __pyx_v_i; + Py_ssize_t __pyx_v_c_stride; + Py_ssize_t __pyx_v_f_stride; + char __pyx_r; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + + /* "View.MemoryView":1118 + * """ + * cdef int i + * cdef Py_ssize_t c_stride = 0 # <<<<<<<<<<<<<< + * cdef Py_ssize_t f_stride = 0 + * + */ + __pyx_v_c_stride = 0; + + /* "View.MemoryView":1119 + * cdef int i + * cdef Py_ssize_t c_stride = 0 + * cdef Py_ssize_t f_stride = 0 # <<<<<<<<<<<<<< + * + * for i in range(ndim - 1, -1, -1): + */ + __pyx_v_f_stride = 0; + + /* "View.MemoryView":1121 + * cdef Py_ssize_t f_stride = 0 + * + * for i in range(ndim - 1, -1, -1): # <<<<<<<<<<<<<< + * if mslice.shape[i] > 1: + * c_stride = mslice.strides[i] + */ + for (__pyx_t_1 = (__pyx_v_ndim - 1); __pyx_t_1 > -1; __pyx_t_1-=1) { + __pyx_v_i = __pyx_t_1; + + /* "View.MemoryView":1122 + * + * for i in range(ndim - 1, -1, -1): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * c_stride = mslice.strides[i] + * break + */ + __pyx_t_2 = ((__pyx_v_mslice->shape[__pyx_v_i]) > 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1123 + * for i in range(ndim - 1, -1, -1): + * if mslice.shape[i] > 1: + * c_stride = mslice.strides[i] # <<<<<<<<<<<<<< + * break + * + */ + __pyx_v_c_stride = (__pyx_v_mslice->strides[__pyx_v_i]); + + /* "View.MemoryView":1124 + * if mslice.shape[i] > 1: + * c_stride = mslice.strides[i] + * break # <<<<<<<<<<<<<< + * + * for i in range(ndim): + */ + goto __pyx_L4_break; + + /* "View.MemoryView":1122 + * + * for i in range(ndim - 1, -1, -1): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * c_stride = mslice.strides[i] + * break + */ + } + } + __pyx_L4_break:; + + /* "View.MemoryView":1126 + * break + * + * for i in range(ndim): # <<<<<<<<<<<<<< + * if mslice.shape[i] > 1: + * f_stride = mslice.strides[i] + */ + __pyx_t_1 = __pyx_v_ndim; + __pyx_t_3 = __pyx_t_1; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1127 + * + * for i in range(ndim): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * f_stride = mslice.strides[i] + * break + */ + __pyx_t_2 = ((__pyx_v_mslice->shape[__pyx_v_i]) > 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1128 + * for i in range(ndim): + * if mslice.shape[i] > 1: + * f_stride = mslice.strides[i] # <<<<<<<<<<<<<< + * break + * + */ + __pyx_v_f_stride = (__pyx_v_mslice->strides[__pyx_v_i]); + + /* "View.MemoryView":1129 + * if mslice.shape[i] > 1: + * f_stride = mslice.strides[i] + * break # <<<<<<<<<<<<<< + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): + */ + goto __pyx_L7_break; + + /* "View.MemoryView":1127 + * + * for i in range(ndim): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * f_stride = mslice.strides[i] + * break + */ + } + } + __pyx_L7_break:; + + /* "View.MemoryView":1131 + * break + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): # <<<<<<<<<<<<<< + * return 'C' + * else: + */ + __pyx_t_2 = (abs_py_ssize_t(__pyx_v_c_stride) <= abs_py_ssize_t(__pyx_v_f_stride)); + if (__pyx_t_2) { + + /* "View.MemoryView":1132 + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): + * return 'C' # <<<<<<<<<<<<<< + * else: + * return 'F' + */ + __pyx_r = 'C'; + goto __pyx_L0; + + /* "View.MemoryView":1131 + * break + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): # <<<<<<<<<<<<<< + * return 'C' + * else: + */ + } + + /* "View.MemoryView":1134 + * return 'C' + * else: + * return 'F' # <<<<<<<<<<<<<< + * + * @cython.cdivision(True) + */ + /*else*/ { + __pyx_r = 'F'; + goto __pyx_L0; + } + + /* "View.MemoryView":1113 + * + * @cname('__pyx_get_best_slice_order') + * cdef char get_best_order(__Pyx_memviewslice *mslice, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * """ + * Figure out the best memory access order for a given slice. + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1137 + * + * @cython.cdivision(True) + * cdef void _copy_strided_to_strided(char *src_data, Py_ssize_t *src_strides, # <<<<<<<<<<<<<< + * char *dst_data, Py_ssize_t *dst_strides, + * Py_ssize_t *src_shape, Py_ssize_t *dst_shape, + */ + +static void _copy_strided_to_strided(char *__pyx_v_src_data, Py_ssize_t *__pyx_v_src_strides, char *__pyx_v_dst_data, Py_ssize_t *__pyx_v_dst_strides, Py_ssize_t *__pyx_v_src_shape, Py_ssize_t *__pyx_v_dst_shape, int __pyx_v_ndim, size_t __pyx_v_itemsize) { + CYTHON_UNUSED Py_ssize_t __pyx_v_i; + CYTHON_UNUSED Py_ssize_t __pyx_v_src_extent; + Py_ssize_t __pyx_v_dst_extent; + Py_ssize_t __pyx_v_src_stride; + Py_ssize_t __pyx_v_dst_stride; + int __pyx_t_1; + int __pyx_t_2; + Py_ssize_t __pyx_t_3; + Py_ssize_t __pyx_t_4; + Py_ssize_t __pyx_t_5; + + /* "View.MemoryView":1144 + * + * cdef Py_ssize_t i + * cdef Py_ssize_t src_extent = src_shape[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t dst_extent = dst_shape[0] + * cdef Py_ssize_t src_stride = src_strides[0] + */ + __pyx_v_src_extent = (__pyx_v_src_shape[0]); + + /* "View.MemoryView":1145 + * cdef Py_ssize_t i + * cdef Py_ssize_t src_extent = src_shape[0] + * cdef Py_ssize_t dst_extent = dst_shape[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t src_stride = src_strides[0] + * cdef Py_ssize_t dst_stride = dst_strides[0] + */ + __pyx_v_dst_extent = (__pyx_v_dst_shape[0]); + + /* "View.MemoryView":1146 + * cdef Py_ssize_t src_extent = src_shape[0] + * cdef Py_ssize_t dst_extent = dst_shape[0] + * cdef Py_ssize_t src_stride = src_strides[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t dst_stride = dst_strides[0] + * + */ + __pyx_v_src_stride = (__pyx_v_src_strides[0]); + + /* "View.MemoryView":1147 + * cdef Py_ssize_t dst_extent = dst_shape[0] + * cdef Py_ssize_t src_stride = src_strides[0] + * cdef Py_ssize_t dst_stride = dst_strides[0] # <<<<<<<<<<<<<< + * + * if ndim == 1: + */ + __pyx_v_dst_stride = (__pyx_v_dst_strides[0]); + + /* "View.MemoryView":1149 + * cdef Py_ssize_t dst_stride = dst_strides[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): + */ + __pyx_t_1 = (__pyx_v_ndim == 1); + if (__pyx_t_1) { + + /* "View.MemoryView":1150 + * + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and # <<<<<<<<<<<<<< + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) + */ + __pyx_t_2 = (__pyx_v_src_stride > 0); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L5_bool_binop_done; + } + __pyx_t_2 = (__pyx_v_dst_stride > 0); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L5_bool_binop_done; + } + + /* "View.MemoryView":1151 + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): # <<<<<<<<<<<<<< + * memcpy(dst_data, src_data, itemsize * dst_extent) + * else: + */ + __pyx_t_2 = (((size_t)__pyx_v_src_stride) == __pyx_v_itemsize); + if (__pyx_t_2) { + __pyx_t_2 = (__pyx_v_itemsize == ((size_t)__pyx_v_dst_stride)); + } + __pyx_t_1 = __pyx_t_2; + __pyx_L5_bool_binop_done:; + + /* "View.MemoryView":1150 + * + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and # <<<<<<<<<<<<<< + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) + */ + if (__pyx_t_1) { + + /* "View.MemoryView":1152 + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) # <<<<<<<<<<<<<< + * else: + * for i in range(dst_extent): + */ + (void)(memcpy(__pyx_v_dst_data, __pyx_v_src_data, (__pyx_v_itemsize * __pyx_v_dst_extent))); + + /* "View.MemoryView":1150 + * + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and # <<<<<<<<<<<<<< + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) + */ + goto __pyx_L4; + } + + /* "View.MemoryView":1154 + * memcpy(dst_data, src_data, itemsize * dst_extent) + * else: + * for i in range(dst_extent): # <<<<<<<<<<<<<< + * memcpy(dst_data, src_data, itemsize) + * src_data += src_stride + */ + /*else*/ { + __pyx_t_3 = __pyx_v_dst_extent; + __pyx_t_4 = __pyx_t_3; + for (__pyx_t_5 = 0; __pyx_t_5 < __pyx_t_4; __pyx_t_5+=1) { + __pyx_v_i = __pyx_t_5; + + /* "View.MemoryView":1155 + * else: + * for i in range(dst_extent): + * memcpy(dst_data, src_data, itemsize) # <<<<<<<<<<<<<< + * src_data += src_stride + * dst_data += dst_stride + */ + (void)(memcpy(__pyx_v_dst_data, __pyx_v_src_data, __pyx_v_itemsize)); + + /* "View.MemoryView":1156 + * for i in range(dst_extent): + * memcpy(dst_data, src_data, itemsize) + * src_data += src_stride # <<<<<<<<<<<<<< + * dst_data += dst_stride + * else: + */ + __pyx_v_src_data = (__pyx_v_src_data + __pyx_v_src_stride); + + /* "View.MemoryView":1157 + * memcpy(dst_data, src_data, itemsize) + * src_data += src_stride + * dst_data += dst_stride # <<<<<<<<<<<<<< + * else: + * for i in range(dst_extent): + */ + __pyx_v_dst_data = (__pyx_v_dst_data + __pyx_v_dst_stride); + } + } + __pyx_L4:; + + /* "View.MemoryView":1149 + * cdef Py_ssize_t dst_stride = dst_strides[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1159 + * dst_data += dst_stride + * else: + * for i in range(dst_extent): # <<<<<<<<<<<<<< + * _copy_strided_to_strided(src_data, src_strides + 1, + * dst_data, dst_strides + 1, + */ + /*else*/ { + __pyx_t_3 = __pyx_v_dst_extent; + __pyx_t_4 = __pyx_t_3; + for (__pyx_t_5 = 0; __pyx_t_5 < __pyx_t_4; __pyx_t_5+=1) { + __pyx_v_i = __pyx_t_5; + + /* "View.MemoryView":1160 + * else: + * for i in range(dst_extent): + * _copy_strided_to_strided(src_data, src_strides + 1, # <<<<<<<<<<<<<< + * dst_data, dst_strides + 1, + * src_shape + 1, dst_shape + 1, + */ + _copy_strided_to_strided(__pyx_v_src_data, (__pyx_v_src_strides + 1), __pyx_v_dst_data, (__pyx_v_dst_strides + 1), (__pyx_v_src_shape + 1), (__pyx_v_dst_shape + 1), (__pyx_v_ndim - 1), __pyx_v_itemsize); + + /* "View.MemoryView":1164 + * src_shape + 1, dst_shape + 1, + * ndim - 1, itemsize) + * src_data += src_stride # <<<<<<<<<<<<<< + * dst_data += dst_stride + * + */ + __pyx_v_src_data = (__pyx_v_src_data + __pyx_v_src_stride); + + /* "View.MemoryView":1165 + * ndim - 1, itemsize) + * src_data += src_stride + * dst_data += dst_stride # <<<<<<<<<<<<<< + * + * cdef void copy_strided_to_strided(__Pyx_memviewslice *src, + */ + __pyx_v_dst_data = (__pyx_v_dst_data + __pyx_v_dst_stride); + } + } + __pyx_L3:; + + /* "View.MemoryView":1137 + * + * @cython.cdivision(True) + * cdef void _copy_strided_to_strided(char *src_data, Py_ssize_t *src_strides, # <<<<<<<<<<<<<< + * char *dst_data, Py_ssize_t *dst_strides, + * Py_ssize_t *src_shape, Py_ssize_t *dst_shape, + */ + + /* function exit code */ +} + +/* "View.MemoryView":1167 + * dst_data += dst_stride + * + * cdef void copy_strided_to_strided(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * int ndim, size_t itemsize) noexcept nogil: + */ + +static void copy_strided_to_strided(__Pyx_memviewslice *__pyx_v_src, __Pyx_memviewslice *__pyx_v_dst, int __pyx_v_ndim, size_t __pyx_v_itemsize) { + + /* "View.MemoryView":1170 + * __Pyx_memviewslice *dst, + * int ndim, size_t itemsize) noexcept nogil: + * _copy_strided_to_strided(src.data, src.strides, dst.data, dst.strides, # <<<<<<<<<<<<<< + * src.shape, dst.shape, ndim, itemsize) + * + */ + _copy_strided_to_strided(__pyx_v_src->data, __pyx_v_src->strides, __pyx_v_dst->data, __pyx_v_dst->strides, __pyx_v_src->shape, __pyx_v_dst->shape, __pyx_v_ndim, __pyx_v_itemsize); + + /* "View.MemoryView":1167 + * dst_data += dst_stride + * + * cdef void copy_strided_to_strided(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * int ndim, size_t itemsize) noexcept nogil: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1174 + * + * @cname('__pyx_memoryview_slice_get_size') + * cdef Py_ssize_t slice_get_size(__Pyx_memviewslice *src, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * "Return the size of the memory occupied by the slice in number of bytes" + * cdef Py_ssize_t shape, size = src.memview.view.itemsize + */ + +static Py_ssize_t __pyx_memoryview_slice_get_size(__Pyx_memviewslice *__pyx_v_src, int __pyx_v_ndim) { + Py_ssize_t __pyx_v_shape; + Py_ssize_t __pyx_v_size; + Py_ssize_t __pyx_r; + Py_ssize_t __pyx_t_1; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + + /* "View.MemoryView":1176 + * cdef Py_ssize_t slice_get_size(__Pyx_memviewslice *src, int ndim) noexcept nogil: + * "Return the size of the memory occupied by the slice in number of bytes" + * cdef Py_ssize_t shape, size = src.memview.view.itemsize # <<<<<<<<<<<<<< + * + * for shape in src.shape[:ndim]: + */ + __pyx_t_1 = __pyx_v_src->memview->view.itemsize; + __pyx_v_size = __pyx_t_1; + + /* "View.MemoryView":1178 + * cdef Py_ssize_t shape, size = src.memview.view.itemsize + * + * for shape in src.shape[:ndim]: # <<<<<<<<<<<<<< + * size *= shape + * + */ + __pyx_t_3 = (__pyx_v_src->shape + __pyx_v_ndim); + for (__pyx_t_4 = __pyx_v_src->shape; __pyx_t_4 < __pyx_t_3; __pyx_t_4++) { + __pyx_t_2 = __pyx_t_4; + __pyx_v_shape = (__pyx_t_2[0]); + + /* "View.MemoryView":1179 + * + * for shape in src.shape[:ndim]: + * size *= shape # <<<<<<<<<<<<<< + * + * return size + */ + __pyx_v_size = (__pyx_v_size * __pyx_v_shape); + } + + /* "View.MemoryView":1181 + * size *= shape + * + * return size # <<<<<<<<<<<<<< + * + * @cname('__pyx_fill_contig_strides_array') + */ + __pyx_r = __pyx_v_size; + goto __pyx_L0; + + /* "View.MemoryView":1174 + * + * @cname('__pyx_memoryview_slice_get_size') + * cdef Py_ssize_t slice_get_size(__Pyx_memviewslice *src, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * "Return the size of the memory occupied by the slice in number of bytes" + * cdef Py_ssize_t shape, size = src.memview.view.itemsize + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1184 + * + * @cname('__pyx_fill_contig_strides_array') + * cdef Py_ssize_t fill_contig_strides_array( # <<<<<<<<<<<<<< + * Py_ssize_t *shape, Py_ssize_t *strides, Py_ssize_t stride, + * int ndim, char order) noexcept nogil: + */ + +static Py_ssize_t __pyx_fill_contig_strides_array(Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, Py_ssize_t __pyx_v_stride, int __pyx_v_ndim, char __pyx_v_order) { + int __pyx_v_idx; + Py_ssize_t __pyx_r; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + + /* "View.MemoryView":1193 + * cdef int idx + * + * if order == 'F': # <<<<<<<<<<<<<< + * for idx in range(ndim): + * strides[idx] = stride + */ + __pyx_t_1 = (__pyx_v_order == 'F'); + if (__pyx_t_1) { + + /* "View.MemoryView":1194 + * + * if order == 'F': + * for idx in range(ndim): # <<<<<<<<<<<<<< + * strides[idx] = stride + * stride *= shape[idx] + */ + __pyx_t_2 = __pyx_v_ndim; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_idx = __pyx_t_4; + + /* "View.MemoryView":1195 + * if order == 'F': + * for idx in range(ndim): + * strides[idx] = stride # <<<<<<<<<<<<<< + * stride *= shape[idx] + * else: + */ + (__pyx_v_strides[__pyx_v_idx]) = __pyx_v_stride; + + /* "View.MemoryView":1196 + * for idx in range(ndim): + * strides[idx] = stride + * stride *= shape[idx] # <<<<<<<<<<<<<< + * else: + * for idx in range(ndim - 1, -1, -1): + */ + __pyx_v_stride = (__pyx_v_stride * (__pyx_v_shape[__pyx_v_idx])); + } + + /* "View.MemoryView":1193 + * cdef int idx + * + * if order == 'F': # <<<<<<<<<<<<<< + * for idx in range(ndim): + * strides[idx] = stride + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1198 + * stride *= shape[idx] + * else: + * for idx in range(ndim - 1, -1, -1): # <<<<<<<<<<<<<< + * strides[idx] = stride + * stride *= shape[idx] + */ + /*else*/ { + for (__pyx_t_2 = (__pyx_v_ndim - 1); __pyx_t_2 > -1; __pyx_t_2-=1) { + __pyx_v_idx = __pyx_t_2; + + /* "View.MemoryView":1199 + * else: + * for idx in range(ndim - 1, -1, -1): + * strides[idx] = stride # <<<<<<<<<<<<<< + * stride *= shape[idx] + * + */ + (__pyx_v_strides[__pyx_v_idx]) = __pyx_v_stride; + + /* "View.MemoryView":1200 + * for idx in range(ndim - 1, -1, -1): + * strides[idx] = stride + * stride *= shape[idx] # <<<<<<<<<<<<<< + * + * return stride + */ + __pyx_v_stride = (__pyx_v_stride * (__pyx_v_shape[__pyx_v_idx])); + } + } + __pyx_L3:; + + /* "View.MemoryView":1202 + * stride *= shape[idx] + * + * return stride # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_copy_data_to_temp') + */ + __pyx_r = __pyx_v_stride; + goto __pyx_L0; + + /* "View.MemoryView":1184 + * + * @cname('__pyx_fill_contig_strides_array') + * cdef Py_ssize_t fill_contig_strides_array( # <<<<<<<<<<<<<< + * Py_ssize_t *shape, Py_ssize_t *strides, Py_ssize_t stride, + * int ndim, char order) noexcept nogil: + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1205 + * + * @cname('__pyx_memoryview_copy_data_to_temp') + * cdef void *copy_data_to_temp(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *tmpslice, + * char order, + */ + +static void *__pyx_memoryview_copy_data_to_temp(__Pyx_memviewslice *__pyx_v_src, __Pyx_memviewslice *__pyx_v_tmpslice, char __pyx_v_order, int __pyx_v_ndim) { + int __pyx_v_i; + void *__pyx_v_result; + size_t __pyx_v_itemsize; + size_t __pyx_v_size; + void *__pyx_r; + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + struct __pyx_memoryview_obj *__pyx_t_4; + int __pyx_t_5; + int __pyx_t_6; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":1216 + * cdef void *result + * + * cdef size_t itemsize = src.memview.view.itemsize # <<<<<<<<<<<<<< + * cdef size_t size = slice_get_size(src, ndim) + * + */ + __pyx_t_1 = __pyx_v_src->memview->view.itemsize; + __pyx_v_itemsize = __pyx_t_1; + + /* "View.MemoryView":1217 + * + * cdef size_t itemsize = src.memview.view.itemsize + * cdef size_t size = slice_get_size(src, ndim) # <<<<<<<<<<<<<< + * + * result = malloc(size) + */ + __pyx_v_size = __pyx_memoryview_slice_get_size(__pyx_v_src, __pyx_v_ndim); + + /* "View.MemoryView":1219 + * cdef size_t size = slice_get_size(src, ndim) + * + * result = malloc(size) # <<<<<<<<<<<<<< + * if not result: + * _err_no_memory() + */ + __pyx_v_result = malloc(__pyx_v_size); + + /* "View.MemoryView":1220 + * + * result = malloc(size) + * if not result: # <<<<<<<<<<<<<< + * _err_no_memory() + * + */ + __pyx_t_2 = (!(__pyx_v_result != 0)); + if (__pyx_t_2) { + + /* "View.MemoryView":1221 + * result = malloc(size) + * if not result: + * _err_no_memory() # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_3 = __pyx_memoryview_err_no_memory(); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 1221, __pyx_L1_error) + + /* "View.MemoryView":1220 + * + * result = malloc(size) + * if not result: # <<<<<<<<<<<<<< + * _err_no_memory() + * + */ + } + + /* "View.MemoryView":1224 + * + * + * tmpslice.data = result # <<<<<<<<<<<<<< + * tmpslice.memview = src.memview + * for i in range(ndim): + */ + __pyx_v_tmpslice->data = ((char *)__pyx_v_result); + + /* "View.MemoryView":1225 + * + * tmpslice.data = result + * tmpslice.memview = src.memview # <<<<<<<<<<<<<< + * for i in range(ndim): + * tmpslice.shape[i] = src.shape[i] + */ + __pyx_t_4 = __pyx_v_src->memview; + __pyx_v_tmpslice->memview = __pyx_t_4; + + /* "View.MemoryView":1226 + * tmpslice.data = result + * tmpslice.memview = src.memview + * for i in range(ndim): # <<<<<<<<<<<<<< + * tmpslice.shape[i] = src.shape[i] + * tmpslice.suboffsets[i] = -1 + */ + __pyx_t_3 = __pyx_v_ndim; + __pyx_t_5 = __pyx_t_3; + for (__pyx_t_6 = 0; __pyx_t_6 < __pyx_t_5; __pyx_t_6+=1) { + __pyx_v_i = __pyx_t_6; + + /* "View.MemoryView":1227 + * tmpslice.memview = src.memview + * for i in range(ndim): + * tmpslice.shape[i] = src.shape[i] # <<<<<<<<<<<<<< + * tmpslice.suboffsets[i] = -1 + * + */ + (__pyx_v_tmpslice->shape[__pyx_v_i]) = (__pyx_v_src->shape[__pyx_v_i]); + + /* "View.MemoryView":1228 + * for i in range(ndim): + * tmpslice.shape[i] = src.shape[i] + * tmpslice.suboffsets[i] = -1 # <<<<<<<<<<<<<< + * + * fill_contig_strides_array(&tmpslice.shape[0], &tmpslice.strides[0], itemsize, ndim, order) + */ + (__pyx_v_tmpslice->suboffsets[__pyx_v_i]) = -1L; + } + + /* "View.MemoryView":1230 + * tmpslice.suboffsets[i] = -1 + * + * fill_contig_strides_array(&tmpslice.shape[0], &tmpslice.strides[0], itemsize, ndim, order) # <<<<<<<<<<<<<< + * + * + */ + (void)(__pyx_fill_contig_strides_array((&(__pyx_v_tmpslice->shape[0])), (&(__pyx_v_tmpslice->strides[0])), __pyx_v_itemsize, __pyx_v_ndim, __pyx_v_order)); + + /* "View.MemoryView":1233 + * + * + * for i in range(ndim): # <<<<<<<<<<<<<< + * if tmpslice.shape[i] == 1: + * tmpslice.strides[i] = 0 + */ + __pyx_t_3 = __pyx_v_ndim; + __pyx_t_5 = __pyx_t_3; + for (__pyx_t_6 = 0; __pyx_t_6 < __pyx_t_5; __pyx_t_6+=1) { + __pyx_v_i = __pyx_t_6; + + /* "View.MemoryView":1234 + * + * for i in range(ndim): + * if tmpslice.shape[i] == 1: # <<<<<<<<<<<<<< + * tmpslice.strides[i] = 0 + * + */ + __pyx_t_2 = ((__pyx_v_tmpslice->shape[__pyx_v_i]) == 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1235 + * for i in range(ndim): + * if tmpslice.shape[i] == 1: + * tmpslice.strides[i] = 0 # <<<<<<<<<<<<<< + * + * if slice_is_contig(src[0], order, ndim): + */ + (__pyx_v_tmpslice->strides[__pyx_v_i]) = 0; + + /* "View.MemoryView":1234 + * + * for i in range(ndim): + * if tmpslice.shape[i] == 1: # <<<<<<<<<<<<<< + * tmpslice.strides[i] = 0 + * + */ + } + } + + /* "View.MemoryView":1237 + * tmpslice.strides[i] = 0 + * + * if slice_is_contig(src[0], order, ndim): # <<<<<<<<<<<<<< + * memcpy(result, src.data, size) + * else: + */ + __pyx_t_2 = __pyx_memviewslice_is_contig((__pyx_v_src[0]), __pyx_v_order, __pyx_v_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1238 + * + * if slice_is_contig(src[0], order, ndim): + * memcpy(result, src.data, size) # <<<<<<<<<<<<<< + * else: + * copy_strided_to_strided(src, tmpslice, ndim, itemsize) + */ + (void)(memcpy(__pyx_v_result, __pyx_v_src->data, __pyx_v_size)); + + /* "View.MemoryView":1237 + * tmpslice.strides[i] = 0 + * + * if slice_is_contig(src[0], order, ndim): # <<<<<<<<<<<<<< + * memcpy(result, src.data, size) + * else: + */ + goto __pyx_L9; + } + + /* "View.MemoryView":1240 + * memcpy(result, src.data, size) + * else: + * copy_strided_to_strided(src, tmpslice, ndim, itemsize) # <<<<<<<<<<<<<< + * + * return result + */ + /*else*/ { + copy_strided_to_strided(__pyx_v_src, __pyx_v_tmpslice, __pyx_v_ndim, __pyx_v_itemsize); + } + __pyx_L9:; + + /* "View.MemoryView":1242 + * copy_strided_to_strided(src, tmpslice, ndim, itemsize) + * + * return result # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = __pyx_v_result; + goto __pyx_L0; + + /* "View.MemoryView":1205 + * + * @cname('__pyx_memoryview_copy_data_to_temp') + * cdef void *copy_data_to_temp(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *tmpslice, + * char order, + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.copy_data_to_temp", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1247 + * + * @cname('__pyx_memoryview_err_extents') + * cdef int _err_extents(int i, Py_ssize_t extent1, # <<<<<<<<<<<<<< + * Py_ssize_t extent2) except -1 with gil: + * raise ValueError, f"got differing extents in dimension {i} (got {extent1} and {extent2})" + */ + +static int __pyx_memoryview_err_extents(int __pyx_v_i, Py_ssize_t __pyx_v_extent1, Py_ssize_t __pyx_v_extent2) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + Py_ssize_t __pyx_t_2; + Py_UCS4 __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_RefNannySetupContext("_err_extents", 0); + + /* "View.MemoryView":1249 + * cdef int _err_extents(int i, Py_ssize_t extent1, + * Py_ssize_t extent2) except -1 with gil: + * raise ValueError, f"got differing extents in dimension {i} (got {extent1} and {extent2})" # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_err_dim') + */ + __pyx_t_1 = PyTuple_New(7); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = 0; + __pyx_t_3 = 127; + __Pyx_INCREF(__pyx_kp_u_got_differing_extents_in_dimensi); + __pyx_t_2 += 35; + __Pyx_GIVEREF(__pyx_kp_u_got_differing_extents_in_dimensi); + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_kp_u_got_differing_extents_in_dimensi); + __pyx_t_4 = __Pyx_PyUnicode_From_int(__pyx_v_i, 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_2 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_t_4); + __pyx_t_4 = 0; + __Pyx_INCREF(__pyx_kp_u_got); + __pyx_t_2 += 6; + __Pyx_GIVEREF(__pyx_kp_u_got); + PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_kp_u_got); + __pyx_t_4 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_extent1, 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_2 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_1, 3, __pyx_t_4); + __pyx_t_4 = 0; + __Pyx_INCREF(__pyx_kp_u_and); + __pyx_t_2 += 5; + __Pyx_GIVEREF(__pyx_kp_u_and); + PyTuple_SET_ITEM(__pyx_t_1, 4, __pyx_kp_u_and); + __pyx_t_4 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_extent2, 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_2 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_1, 5, __pyx_t_4); + __pyx_t_4 = 0; + __Pyx_INCREF(__pyx_kp_u__7); + __pyx_t_2 += 1; + __Pyx_GIVEREF(__pyx_kp_u__7); + PyTuple_SET_ITEM(__pyx_t_1, 6, __pyx_kp_u__7); + __pyx_t_4 = __Pyx_PyUnicode_Join(__pyx_t_1, 7, __pyx_t_2, __pyx_t_3); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_t_4, 0, 0); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __PYX_ERR(1, 1249, __pyx_L1_error) + + /* "View.MemoryView":1247 + * + * @cname('__pyx_memoryview_err_extents') + * cdef int _err_extents(int i, Py_ssize_t extent1, # <<<<<<<<<<<<<< + * Py_ssize_t extent2) except -1 with gil: + * raise ValueError, f"got differing extents in dimension {i} (got {extent1} and {extent2})" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView._err_extents", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __Pyx_RefNannyFinishContext(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1252 + * + * @cname('__pyx_memoryview_err_dim') + * cdef int _err_dim(PyObject *error, str msg, int dim) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg % dim + * + */ + +static int __pyx_memoryview_err_dim(PyObject *__pyx_v_error, PyObject *__pyx_v_msg, int __pyx_v_dim) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_RefNannySetupContext("_err_dim", 0); + __Pyx_INCREF(__pyx_v_msg); + + /* "View.MemoryView":1253 + * @cname('__pyx_memoryview_err_dim') + * cdef int _err_dim(PyObject *error, str msg, int dim) except -1 with gil: + * raise error, msg % dim # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_err') + */ + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_dim); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 1253, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyString_FormatSafe(__pyx_v_msg, __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1253, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(((PyObject *)__pyx_v_error), __pyx_t_2, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(1, 1253, __pyx_L1_error) + + /* "View.MemoryView":1252 + * + * @cname('__pyx_memoryview_err_dim') + * cdef int _err_dim(PyObject *error, str msg, int dim) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg % dim + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView._err_dim", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __Pyx_XDECREF(__pyx_v_msg); + __Pyx_RefNannyFinishContext(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1256 + * + * @cname('__pyx_memoryview_err') + * cdef int _err(PyObject *error, str msg) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg + * + */ + +static int __pyx_memoryview_err(PyObject *__pyx_v_error, PyObject *__pyx_v_msg) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_RefNannySetupContext("_err", 0); + __Pyx_INCREF(__pyx_v_msg); + + /* "View.MemoryView":1257 + * @cname('__pyx_memoryview_err') + * cdef int _err(PyObject *error, str msg) except -1 with gil: + * raise error, msg # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_err_no_memory') + */ + __Pyx_Raise(((PyObject *)__pyx_v_error), __pyx_v_msg, 0, 0); + __PYX_ERR(1, 1257, __pyx_L1_error) + + /* "View.MemoryView":1256 + * + * @cname('__pyx_memoryview_err') + * cdef int _err(PyObject *error, str msg) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._err", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __Pyx_XDECREF(__pyx_v_msg); + __Pyx_RefNannyFinishContext(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1260 + * + * @cname('__pyx_memoryview_err_no_memory') + * cdef int _err_no_memory() except -1 with gil: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + +static int __pyx_memoryview_err_no_memory(void) { + int __pyx_r; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + + /* "View.MemoryView":1261 + * @cname('__pyx_memoryview_err_no_memory') + * cdef int _err_no_memory() except -1 with gil: + * raise MemoryError # <<<<<<<<<<<<<< + * + * + */ + PyErr_NoMemory(); __PYX_ERR(1, 1261, __pyx_L1_error) + + /* "View.MemoryView":1260 + * + * @cname('__pyx_memoryview_err_no_memory') + * cdef int _err_no_memory() except -1 with gil: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._err_no_memory", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1265 + * + * @cname('__pyx_memoryview_copy_contents') + * cdef int memoryview_copy_contents(__Pyx_memviewslice src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice dst, + * int src_ndim, int dst_ndim, + */ + +static int __pyx_memoryview_copy_contents(__Pyx_memviewslice __pyx_v_src, __Pyx_memviewslice __pyx_v_dst, int __pyx_v_src_ndim, int __pyx_v_dst_ndim, int __pyx_v_dtype_is_object) { + void *__pyx_v_tmpdata; + size_t __pyx_v_itemsize; + int __pyx_v_i; + char __pyx_v_order; + int __pyx_v_broadcasting; + int __pyx_v_direct_copy; + __Pyx_memviewslice __pyx_v_tmp; + int __pyx_v_ndim; + int __pyx_r; + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + int __pyx_t_5; + int __pyx_t_6; + void *__pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":1273 + * Check for overlapping memory and verify the shapes. + * """ + * cdef void *tmpdata = NULL # <<<<<<<<<<<<<< + * cdef size_t itemsize = src.memview.view.itemsize + * cdef int i + */ + __pyx_v_tmpdata = NULL; + + /* "View.MemoryView":1274 + * """ + * cdef void *tmpdata = NULL + * cdef size_t itemsize = src.memview.view.itemsize # <<<<<<<<<<<<<< + * cdef int i + * cdef char order = get_best_order(&src, src_ndim) + */ + __pyx_t_1 = __pyx_v_src.memview->view.itemsize; + __pyx_v_itemsize = __pyx_t_1; + + /* "View.MemoryView":1276 + * cdef size_t itemsize = src.memview.view.itemsize + * cdef int i + * cdef char order = get_best_order(&src, src_ndim) # <<<<<<<<<<<<<< + * cdef bint broadcasting = False + * cdef bint direct_copy = False + */ + __pyx_v_order = __pyx_get_best_slice_order((&__pyx_v_src), __pyx_v_src_ndim); + + /* "View.MemoryView":1277 + * cdef int i + * cdef char order = get_best_order(&src, src_ndim) + * cdef bint broadcasting = False # <<<<<<<<<<<<<< + * cdef bint direct_copy = False + * cdef __Pyx_memviewslice tmp + */ + __pyx_v_broadcasting = 0; + + /* "View.MemoryView":1278 + * cdef char order = get_best_order(&src, src_ndim) + * cdef bint broadcasting = False + * cdef bint direct_copy = False # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice tmp + * + */ + __pyx_v_direct_copy = 0; + + /* "View.MemoryView":1281 + * cdef __Pyx_memviewslice tmp + * + * if src_ndim < dst_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: + */ + __pyx_t_2 = (__pyx_v_src_ndim < __pyx_v_dst_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1282 + * + * if src_ndim < dst_ndim: + * broadcast_leading(&src, src_ndim, dst_ndim) # <<<<<<<<<<<<<< + * elif dst_ndim < src_ndim: + * broadcast_leading(&dst, dst_ndim, src_ndim) + */ + __pyx_memoryview_broadcast_leading((&__pyx_v_src), __pyx_v_src_ndim, __pyx_v_dst_ndim); + + /* "View.MemoryView":1281 + * cdef __Pyx_memviewslice tmp + * + * if src_ndim < dst_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1283 + * if src_ndim < dst_ndim: + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&dst, dst_ndim, src_ndim) + * + */ + __pyx_t_2 = (__pyx_v_dst_ndim < __pyx_v_src_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1284 + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: + * broadcast_leading(&dst, dst_ndim, src_ndim) # <<<<<<<<<<<<<< + * + * cdef int ndim = max(src_ndim, dst_ndim) + */ + __pyx_memoryview_broadcast_leading((&__pyx_v_dst), __pyx_v_dst_ndim, __pyx_v_src_ndim); + + /* "View.MemoryView":1283 + * if src_ndim < dst_ndim: + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&dst, dst_ndim, src_ndim) + * + */ + } + __pyx_L3:; + + /* "View.MemoryView":1286 + * broadcast_leading(&dst, dst_ndim, src_ndim) + * + * cdef int ndim = max(src_ndim, dst_ndim) # <<<<<<<<<<<<<< + * + * for i in range(ndim): + */ + __pyx_t_3 = __pyx_v_dst_ndim; + __pyx_t_4 = __pyx_v_src_ndim; + __pyx_t_2 = (__pyx_t_3 > __pyx_t_4); + if (__pyx_t_2) { + __pyx_t_5 = __pyx_t_3; + } else { + __pyx_t_5 = __pyx_t_4; + } + __pyx_v_ndim = __pyx_t_5; + + /* "View.MemoryView":1288 + * cdef int ndim = max(src_ndim, dst_ndim) + * + * for i in range(ndim): # <<<<<<<<<<<<<< + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: + */ + __pyx_t_5 = __pyx_v_ndim; + __pyx_t_3 = __pyx_t_5; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1289 + * + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: # <<<<<<<<<<<<<< + * if src.shape[i] == 1: + * broadcasting = True + */ + __pyx_t_2 = ((__pyx_v_src.shape[__pyx_v_i]) != (__pyx_v_dst.shape[__pyx_v_i])); + if (__pyx_t_2) { + + /* "View.MemoryView":1290 + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: # <<<<<<<<<<<<<< + * broadcasting = True + * src.strides[i] = 0 + */ + __pyx_t_2 = ((__pyx_v_src.shape[__pyx_v_i]) == 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1291 + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: + * broadcasting = True # <<<<<<<<<<<<<< + * src.strides[i] = 0 + * else: + */ + __pyx_v_broadcasting = 1; + + /* "View.MemoryView":1292 + * if src.shape[i] == 1: + * broadcasting = True + * src.strides[i] = 0 # <<<<<<<<<<<<<< + * else: + * _err_extents(i, dst.shape[i], src.shape[i]) + */ + (__pyx_v_src.strides[__pyx_v_i]) = 0; + + /* "View.MemoryView":1290 + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: # <<<<<<<<<<<<<< + * broadcasting = True + * src.strides[i] = 0 + */ + goto __pyx_L7; + } + + /* "View.MemoryView":1294 + * src.strides[i] = 0 + * else: + * _err_extents(i, dst.shape[i], src.shape[i]) # <<<<<<<<<<<<<< + * + * if src.suboffsets[i] >= 0: + */ + /*else*/ { + __pyx_t_6 = __pyx_memoryview_err_extents(__pyx_v_i, (__pyx_v_dst.shape[__pyx_v_i]), (__pyx_v_src.shape[__pyx_v_i])); if (unlikely(__pyx_t_6 == ((int)-1))) __PYX_ERR(1, 1294, __pyx_L1_error) + } + __pyx_L7:; + + /* "View.MemoryView":1289 + * + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: # <<<<<<<<<<<<<< + * if src.shape[i] == 1: + * broadcasting = True + */ + } + + /* "View.MemoryView":1296 + * _err_extents(i, dst.shape[i], src.shape[i]) + * + * if src.suboffsets[i] >= 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + */ + __pyx_t_2 = ((__pyx_v_src.suboffsets[__pyx_v_i]) >= 0); + if (__pyx_t_2) { + + /* "View.MemoryView":1297 + * + * if src.suboffsets[i] >= 0: + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) # <<<<<<<<<<<<<< + * + * if slices_overlap(&src, &dst, ndim, itemsize): + */ + __pyx_t_6 = __pyx_memoryview_err_dim(PyExc_ValueError, __pyx_kp_s_Dimension_d_is_not_direct, __pyx_v_i); if (unlikely(__pyx_t_6 == ((int)-1))) __PYX_ERR(1, 1297, __pyx_L1_error) + + /* "View.MemoryView":1296 + * _err_extents(i, dst.shape[i], src.shape[i]) + * + * if src.suboffsets[i] >= 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + */ + } + } + + /* "View.MemoryView":1299 + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + * if slices_overlap(&src, &dst, ndim, itemsize): # <<<<<<<<<<<<<< + * + * if not slice_is_contig(src, order, ndim): + */ + __pyx_t_2 = __pyx_slices_overlap((&__pyx_v_src), (&__pyx_v_dst), __pyx_v_ndim, __pyx_v_itemsize); + if (__pyx_t_2) { + + /* "View.MemoryView":1301 + * if slices_overlap(&src, &dst, ndim, itemsize): + * + * if not slice_is_contig(src, order, ndim): # <<<<<<<<<<<<<< + * order = get_best_order(&dst, ndim) + * + */ + __pyx_t_2 = (!__pyx_memviewslice_is_contig(__pyx_v_src, __pyx_v_order, __pyx_v_ndim)); + if (__pyx_t_2) { + + /* "View.MemoryView":1302 + * + * if not slice_is_contig(src, order, ndim): + * order = get_best_order(&dst, ndim) # <<<<<<<<<<<<<< + * + * tmpdata = copy_data_to_temp(&src, &tmp, order, ndim) + */ + __pyx_v_order = __pyx_get_best_slice_order((&__pyx_v_dst), __pyx_v_ndim); + + /* "View.MemoryView":1301 + * if slices_overlap(&src, &dst, ndim, itemsize): + * + * if not slice_is_contig(src, order, ndim): # <<<<<<<<<<<<<< + * order = get_best_order(&dst, ndim) + * + */ + } + + /* "View.MemoryView":1304 + * order = get_best_order(&dst, ndim) + * + * tmpdata = copy_data_to_temp(&src, &tmp, order, ndim) # <<<<<<<<<<<<<< + * src = tmp + * + */ + __pyx_t_7 = __pyx_memoryview_copy_data_to_temp((&__pyx_v_src), (&__pyx_v_tmp), __pyx_v_order, __pyx_v_ndim); if (unlikely(__pyx_t_7 == ((void *)NULL))) __PYX_ERR(1, 1304, __pyx_L1_error) + __pyx_v_tmpdata = __pyx_t_7; + + /* "View.MemoryView":1305 + * + * tmpdata = copy_data_to_temp(&src, &tmp, order, ndim) + * src = tmp # <<<<<<<<<<<<<< + * + * if not broadcasting: + */ + __pyx_v_src = __pyx_v_tmp; + + /* "View.MemoryView":1299 + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + * if slices_overlap(&src, &dst, ndim, itemsize): # <<<<<<<<<<<<<< + * + * if not slice_is_contig(src, order, ndim): + */ + } + + /* "View.MemoryView":1307 + * src = tmp + * + * if not broadcasting: # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = (!__pyx_v_broadcasting); + if (__pyx_t_2) { + + /* "View.MemoryView":1310 + * + * + * if slice_is_contig(src, 'C', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): + */ + __pyx_t_2 = __pyx_memviewslice_is_contig(__pyx_v_src, 'C', __pyx_v_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1311 + * + * if slice_is_contig(src, 'C', ndim): + * direct_copy = slice_is_contig(dst, 'C', ndim) # <<<<<<<<<<<<<< + * elif slice_is_contig(src, 'F', ndim): + * direct_copy = slice_is_contig(dst, 'F', ndim) + */ + __pyx_v_direct_copy = __pyx_memviewslice_is_contig(__pyx_v_dst, 'C', __pyx_v_ndim); + + /* "View.MemoryView":1310 + * + * + * if slice_is_contig(src, 'C', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): + */ + goto __pyx_L12; + } + + /* "View.MemoryView":1312 + * if slice_is_contig(src, 'C', ndim): + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + */ + __pyx_t_2 = __pyx_memviewslice_is_contig(__pyx_v_src, 'F', __pyx_v_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1313 + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): + * direct_copy = slice_is_contig(dst, 'F', ndim) # <<<<<<<<<<<<<< + * + * if direct_copy: + */ + __pyx_v_direct_copy = __pyx_memviewslice_is_contig(__pyx_v_dst, 'F', __pyx_v_ndim); + + /* "View.MemoryView":1312 + * if slice_is_contig(src, 'C', ndim): + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + */ + } + __pyx_L12:; + + /* "View.MemoryView":1315 + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + * if direct_copy: # <<<<<<<<<<<<<< + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + */ + if (__pyx_v_direct_copy) { + + /* "View.MemoryView":1317 + * if direct_copy: + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) # <<<<<<<<<<<<<< + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 0); + + /* "View.MemoryView":1318 + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) # <<<<<<<<<<<<<< + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * free(tmpdata) + */ + (void)(memcpy(__pyx_v_dst.data, __pyx_v_src.data, __pyx_memoryview_slice_get_size((&__pyx_v_src), __pyx_v_ndim))); + + /* "View.MemoryView":1319 + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) # <<<<<<<<<<<<<< + * free(tmpdata) + * return 0 + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 1); + + /* "View.MemoryView":1320 + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * free(tmpdata) # <<<<<<<<<<<<<< + * return 0 + * + */ + free(__pyx_v_tmpdata); + + /* "View.MemoryView":1321 + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * free(tmpdata) + * return 0 # <<<<<<<<<<<<<< + * + * if order == 'F' == get_best_order(&dst, ndim): + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":1315 + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + * if direct_copy: # <<<<<<<<<<<<<< + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + */ + } + + /* "View.MemoryView":1307 + * src = tmp + * + * if not broadcasting: # <<<<<<<<<<<<<< + * + * + */ + } + + /* "View.MemoryView":1323 + * return 0 + * + * if order == 'F' == get_best_order(&dst, ndim): # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = (__pyx_v_order == 'F'); + if (__pyx_t_2) { + __pyx_t_2 = ('F' == __pyx_get_best_slice_order((&__pyx_v_dst), __pyx_v_ndim)); + } + if (__pyx_t_2) { + + /* "View.MemoryView":1326 + * + * + * transpose_memslice(&src) # <<<<<<<<<<<<<< + * transpose_memslice(&dst) + * + */ + __pyx_t_5 = __pyx_memslice_transpose((&__pyx_v_src)); if (unlikely(__pyx_t_5 == ((int)-1))) __PYX_ERR(1, 1326, __pyx_L1_error) + + /* "View.MemoryView":1327 + * + * transpose_memslice(&src) + * transpose_memslice(&dst) # <<<<<<<<<<<<<< + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + */ + __pyx_t_5 = __pyx_memslice_transpose((&__pyx_v_dst)); if (unlikely(__pyx_t_5 == ((int)-1))) __PYX_ERR(1, 1327, __pyx_L1_error) + + /* "View.MemoryView":1323 + * return 0 + * + * if order == 'F' == get_best_order(&dst, ndim): # <<<<<<<<<<<<<< + * + * + */ + } + + /* "View.MemoryView":1329 + * transpose_memslice(&dst) + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) # <<<<<<<<<<<<<< + * copy_strided_to_strided(&src, &dst, ndim, itemsize) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 0); + + /* "View.MemoryView":1330 + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * copy_strided_to_strided(&src, &dst, ndim, itemsize) # <<<<<<<<<<<<<< + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * + */ + copy_strided_to_strided((&__pyx_v_src), (&__pyx_v_dst), __pyx_v_ndim, __pyx_v_itemsize); + + /* "View.MemoryView":1331 + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * copy_strided_to_strided(&src, &dst, ndim, itemsize) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) # <<<<<<<<<<<<<< + * + * free(tmpdata) + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 1); + + /* "View.MemoryView":1333 + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * + * free(tmpdata) # <<<<<<<<<<<<<< + * return 0 + * + */ + free(__pyx_v_tmpdata); + + /* "View.MemoryView":1334 + * + * free(tmpdata) + * return 0 # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_broadcast_leading') + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":1265 + * + * @cname('__pyx_memoryview_copy_contents') + * cdef int memoryview_copy_contents(__Pyx_memviewslice src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice dst, + * int src_ndim, int dst_ndim, + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.memoryview_copy_contents", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1337 + * + * @cname('__pyx_memoryview_broadcast_leading') + * cdef void broadcast_leading(__Pyx_memviewslice *mslice, # <<<<<<<<<<<<<< + * int ndim, + * int ndim_other) noexcept nogil: + */ + +static void __pyx_memoryview_broadcast_leading(__Pyx_memviewslice *__pyx_v_mslice, int __pyx_v_ndim, int __pyx_v_ndim_other) { + int __pyx_v_i; + int __pyx_v_offset; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + + /* "View.MemoryView":1341 + * int ndim_other) noexcept nogil: + * cdef int i + * cdef int offset = ndim_other - ndim # <<<<<<<<<<<<<< + * + * for i in range(ndim - 1, -1, -1): + */ + __pyx_v_offset = (__pyx_v_ndim_other - __pyx_v_ndim); + + /* "View.MemoryView":1343 + * cdef int offset = ndim_other - ndim + * + * for i in range(ndim - 1, -1, -1): # <<<<<<<<<<<<<< + * mslice.shape[i + offset] = mslice.shape[i] + * mslice.strides[i + offset] = mslice.strides[i] + */ + for (__pyx_t_1 = (__pyx_v_ndim - 1); __pyx_t_1 > -1; __pyx_t_1-=1) { + __pyx_v_i = __pyx_t_1; + + /* "View.MemoryView":1344 + * + * for i in range(ndim - 1, -1, -1): + * mslice.shape[i + offset] = mslice.shape[i] # <<<<<<<<<<<<<< + * mslice.strides[i + offset] = mslice.strides[i] + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] + */ + (__pyx_v_mslice->shape[(__pyx_v_i + __pyx_v_offset)]) = (__pyx_v_mslice->shape[__pyx_v_i]); + + /* "View.MemoryView":1345 + * for i in range(ndim - 1, -1, -1): + * mslice.shape[i + offset] = mslice.shape[i] + * mslice.strides[i + offset] = mslice.strides[i] # <<<<<<<<<<<<<< + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] + * + */ + (__pyx_v_mslice->strides[(__pyx_v_i + __pyx_v_offset)]) = (__pyx_v_mslice->strides[__pyx_v_i]); + + /* "View.MemoryView":1346 + * mslice.shape[i + offset] = mslice.shape[i] + * mslice.strides[i + offset] = mslice.strides[i] + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] # <<<<<<<<<<<<<< + * + * for i in range(offset): + */ + (__pyx_v_mslice->suboffsets[(__pyx_v_i + __pyx_v_offset)]) = (__pyx_v_mslice->suboffsets[__pyx_v_i]); + } + + /* "View.MemoryView":1348 + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] + * + * for i in range(offset): # <<<<<<<<<<<<<< + * mslice.shape[i] = 1 + * mslice.strides[i] = mslice.strides[0] + */ + __pyx_t_1 = __pyx_v_offset; + __pyx_t_2 = __pyx_t_1; + for (__pyx_t_3 = 0; __pyx_t_3 < __pyx_t_2; __pyx_t_3+=1) { + __pyx_v_i = __pyx_t_3; + + /* "View.MemoryView":1349 + * + * for i in range(offset): + * mslice.shape[i] = 1 # <<<<<<<<<<<<<< + * mslice.strides[i] = mslice.strides[0] + * mslice.suboffsets[i] = -1 + */ + (__pyx_v_mslice->shape[__pyx_v_i]) = 1; + + /* "View.MemoryView":1350 + * for i in range(offset): + * mslice.shape[i] = 1 + * mslice.strides[i] = mslice.strides[0] # <<<<<<<<<<<<<< + * mslice.suboffsets[i] = -1 + * + */ + (__pyx_v_mslice->strides[__pyx_v_i]) = (__pyx_v_mslice->strides[0]); + + /* "View.MemoryView":1351 + * mslice.shape[i] = 1 + * mslice.strides[i] = mslice.strides[0] + * mslice.suboffsets[i] = -1 # <<<<<<<<<<<<<< + * + * + */ + (__pyx_v_mslice->suboffsets[__pyx_v_i]) = -1L; + } + + /* "View.MemoryView":1337 + * + * @cname('__pyx_memoryview_broadcast_leading') + * cdef void broadcast_leading(__Pyx_memviewslice *mslice, # <<<<<<<<<<<<<< + * int ndim, + * int ndim_other) noexcept nogil: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1359 + * + * @cname('__pyx_memoryview_refcount_copying') + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: # <<<<<<<<<<<<<< + * + * if dtype_is_object: + */ + +static void __pyx_memoryview_refcount_copying(__Pyx_memviewslice *__pyx_v_dst, int __pyx_v_dtype_is_object, int __pyx_v_ndim, int __pyx_v_inc) { + + /* "View.MemoryView":1361 + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: + * + * if dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice_with_gil(dst.data, dst.shape, dst.strides, ndim, inc) + * + */ + if (__pyx_v_dtype_is_object) { + + /* "View.MemoryView":1362 + * + * if dtype_is_object: + * refcount_objects_in_slice_with_gil(dst.data, dst.shape, dst.strides, ndim, inc) # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_refcount_objects_in_slice_with_gil') + */ + __pyx_memoryview_refcount_objects_in_slice_with_gil(__pyx_v_dst->data, __pyx_v_dst->shape, __pyx_v_dst->strides, __pyx_v_ndim, __pyx_v_inc); + + /* "View.MemoryView":1361 + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: + * + * if dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice_with_gil(dst.data, dst.shape, dst.strides, ndim, inc) + * + */ + } + + /* "View.MemoryView":1359 + * + * @cname('__pyx_memoryview_refcount_copying') + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: # <<<<<<<<<<<<<< + * + * if dtype_is_object: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1365 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice_with_gil') + * cdef void refcount_objects_in_slice_with_gil(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * bint inc) noexcept with gil: + */ + +static void __pyx_memoryview_refcount_objects_in_slice_with_gil(char *__pyx_v_data, Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, int __pyx_v_ndim, int __pyx_v_inc) { + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + + /* "View.MemoryView":1368 + * Py_ssize_t *strides, int ndim, + * bint inc) noexcept with gil: + * refcount_objects_in_slice(data, shape, strides, ndim, inc) # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_refcount_objects_in_slice') + */ + __pyx_memoryview_refcount_objects_in_slice(__pyx_v_data, __pyx_v_shape, __pyx_v_strides, __pyx_v_ndim, __pyx_v_inc); + + /* "View.MemoryView":1365 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice_with_gil') + * cdef void refcount_objects_in_slice_with_gil(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * bint inc) noexcept with gil: + */ + + /* function exit code */ + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif +} + +/* "View.MemoryView":1371 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice') + * cdef void refcount_objects_in_slice(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, bint inc) noexcept: + * cdef Py_ssize_t i + */ + +static void __pyx_memoryview_refcount_objects_in_slice(char *__pyx_v_data, Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, int __pyx_v_ndim, int __pyx_v_inc) { + CYTHON_UNUSED Py_ssize_t __pyx_v_i; + Py_ssize_t __pyx_v_stride; + Py_ssize_t __pyx_t_1; + Py_ssize_t __pyx_t_2; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + + /* "View.MemoryView":1374 + * Py_ssize_t *strides, int ndim, bint inc) noexcept: + * cdef Py_ssize_t i + * cdef Py_ssize_t stride = strides[0] # <<<<<<<<<<<<<< + * + * for i in range(shape[0]): + */ + __pyx_v_stride = (__pyx_v_strides[0]); + + /* "View.MemoryView":1376 + * cdef Py_ssize_t stride = strides[0] + * + * for i in range(shape[0]): # <<<<<<<<<<<<<< + * if ndim == 1: + * if inc: + */ + __pyx_t_1 = (__pyx_v_shape[0]); + __pyx_t_2 = __pyx_t_1; + for (__pyx_t_3 = 0; __pyx_t_3 < __pyx_t_2; __pyx_t_3+=1) { + __pyx_v_i = __pyx_t_3; + + /* "View.MemoryView":1377 + * + * for i in range(shape[0]): + * if ndim == 1: # <<<<<<<<<<<<<< + * if inc: + * Py_INCREF(( data)[0]) + */ + __pyx_t_4 = (__pyx_v_ndim == 1); + if (__pyx_t_4) { + + /* "View.MemoryView":1378 + * for i in range(shape[0]): + * if ndim == 1: + * if inc: # <<<<<<<<<<<<<< + * Py_INCREF(( data)[0]) + * else: + */ + if (__pyx_v_inc) { + + /* "View.MemoryView":1379 + * if ndim == 1: + * if inc: + * Py_INCREF(( data)[0]) # <<<<<<<<<<<<<< + * else: + * Py_DECREF(( data)[0]) + */ + Py_INCREF((((PyObject **)__pyx_v_data)[0])); + + /* "View.MemoryView":1378 + * for i in range(shape[0]): + * if ndim == 1: + * if inc: # <<<<<<<<<<<<<< + * Py_INCREF(( data)[0]) + * else: + */ + goto __pyx_L6; + } + + /* "View.MemoryView":1381 + * Py_INCREF(( data)[0]) + * else: + * Py_DECREF(( data)[0]) # <<<<<<<<<<<<<< + * else: + * refcount_objects_in_slice(data, shape + 1, strides + 1, ndim - 1, inc) + */ + /*else*/ { + Py_DECREF((((PyObject **)__pyx_v_data)[0])); + } + __pyx_L6:; + + /* "View.MemoryView":1377 + * + * for i in range(shape[0]): + * if ndim == 1: # <<<<<<<<<<<<<< + * if inc: + * Py_INCREF(( data)[0]) + */ + goto __pyx_L5; + } + + /* "View.MemoryView":1383 + * Py_DECREF(( data)[0]) + * else: + * refcount_objects_in_slice(data, shape + 1, strides + 1, ndim - 1, inc) # <<<<<<<<<<<<<< + * + * data += stride + */ + /*else*/ { + __pyx_memoryview_refcount_objects_in_slice(__pyx_v_data, (__pyx_v_shape + 1), (__pyx_v_strides + 1), (__pyx_v_ndim - 1), __pyx_v_inc); + } + __pyx_L5:; + + /* "View.MemoryView":1385 + * refcount_objects_in_slice(data, shape + 1, strides + 1, ndim - 1, inc) + * + * data += stride # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_data = (__pyx_v_data + __pyx_v_stride); + } + + /* "View.MemoryView":1371 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice') + * cdef void refcount_objects_in_slice(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, bint inc) noexcept: + * cdef Py_ssize_t i + */ + + /* function exit code */ +} + +/* "View.MemoryView":1391 + * + * @cname('__pyx_memoryview_slice_assign_scalar') + * cdef void slice_assign_scalar(__Pyx_memviewslice *dst, int ndim, # <<<<<<<<<<<<<< + * size_t itemsize, void *item, + * bint dtype_is_object) noexcept nogil: + */ + +static void __pyx_memoryview_slice_assign_scalar(__Pyx_memviewslice *__pyx_v_dst, int __pyx_v_ndim, size_t __pyx_v_itemsize, void *__pyx_v_item, int __pyx_v_dtype_is_object) { + + /* "View.MemoryView":1394 + * size_t itemsize, void *item, + * bint dtype_is_object) noexcept nogil: + * refcount_copying(dst, dtype_is_object, ndim, inc=False) # <<<<<<<<<<<<<< + * _slice_assign_scalar(dst.data, dst.shape, dst.strides, ndim, itemsize, item) + * refcount_copying(dst, dtype_is_object, ndim, inc=True) + */ + __pyx_memoryview_refcount_copying(__pyx_v_dst, __pyx_v_dtype_is_object, __pyx_v_ndim, 0); + + /* "View.MemoryView":1395 + * bint dtype_is_object) noexcept nogil: + * refcount_copying(dst, dtype_is_object, ndim, inc=False) + * _slice_assign_scalar(dst.data, dst.shape, dst.strides, ndim, itemsize, item) # <<<<<<<<<<<<<< + * refcount_copying(dst, dtype_is_object, ndim, inc=True) + * + */ + __pyx_memoryview__slice_assign_scalar(__pyx_v_dst->data, __pyx_v_dst->shape, __pyx_v_dst->strides, __pyx_v_ndim, __pyx_v_itemsize, __pyx_v_item); + + /* "View.MemoryView":1396 + * refcount_copying(dst, dtype_is_object, ndim, inc=False) + * _slice_assign_scalar(dst.data, dst.shape, dst.strides, ndim, itemsize, item) + * refcount_copying(dst, dtype_is_object, ndim, inc=True) # <<<<<<<<<<<<<< + * + * + */ + __pyx_memoryview_refcount_copying(__pyx_v_dst, __pyx_v_dtype_is_object, __pyx_v_ndim, 1); + + /* "View.MemoryView":1391 + * + * @cname('__pyx_memoryview_slice_assign_scalar') + * cdef void slice_assign_scalar(__Pyx_memviewslice *dst, int ndim, # <<<<<<<<<<<<<< + * size_t itemsize, void *item, + * bint dtype_is_object) noexcept nogil: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1400 + * + * @cname('__pyx_memoryview__slice_assign_scalar') + * cdef void _slice_assign_scalar(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * size_t itemsize, void *item) noexcept nogil: + */ + +static void __pyx_memoryview__slice_assign_scalar(char *__pyx_v_data, Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, int __pyx_v_ndim, size_t __pyx_v_itemsize, void *__pyx_v_item) { + CYTHON_UNUSED Py_ssize_t __pyx_v_i; + Py_ssize_t __pyx_v_stride; + Py_ssize_t __pyx_v_extent; + int __pyx_t_1; + Py_ssize_t __pyx_t_2; + Py_ssize_t __pyx_t_3; + Py_ssize_t __pyx_t_4; + + /* "View.MemoryView":1404 + * size_t itemsize, void *item) noexcept nogil: + * cdef Py_ssize_t i + * cdef Py_ssize_t stride = strides[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t extent = shape[0] + * + */ + __pyx_v_stride = (__pyx_v_strides[0]); + + /* "View.MemoryView":1405 + * cdef Py_ssize_t i + * cdef Py_ssize_t stride = strides[0] + * cdef Py_ssize_t extent = shape[0] # <<<<<<<<<<<<<< + * + * if ndim == 1: + */ + __pyx_v_extent = (__pyx_v_shape[0]); + + /* "View.MemoryView":1407 + * cdef Py_ssize_t extent = shape[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * for i in range(extent): + * memcpy(data, item, itemsize) + */ + __pyx_t_1 = (__pyx_v_ndim == 1); + if (__pyx_t_1) { + + /* "View.MemoryView":1408 + * + * if ndim == 1: + * for i in range(extent): # <<<<<<<<<<<<<< + * memcpy(data, item, itemsize) + * data += stride + */ + __pyx_t_2 = __pyx_v_extent; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1409 + * if ndim == 1: + * for i in range(extent): + * memcpy(data, item, itemsize) # <<<<<<<<<<<<<< + * data += stride + * else: + */ + (void)(memcpy(__pyx_v_data, __pyx_v_item, __pyx_v_itemsize)); + + /* "View.MemoryView":1410 + * for i in range(extent): + * memcpy(data, item, itemsize) + * data += stride # <<<<<<<<<<<<<< + * else: + * for i in range(extent): + */ + __pyx_v_data = (__pyx_v_data + __pyx_v_stride); + } + + /* "View.MemoryView":1407 + * cdef Py_ssize_t extent = shape[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * for i in range(extent): + * memcpy(data, item, itemsize) + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1412 + * data += stride + * else: + * for i in range(extent): # <<<<<<<<<<<<<< + * _slice_assign_scalar(data, shape + 1, strides + 1, ndim - 1, itemsize, item) + * data += stride + */ + /*else*/ { + __pyx_t_2 = __pyx_v_extent; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1413 + * else: + * for i in range(extent): + * _slice_assign_scalar(data, shape + 1, strides + 1, ndim - 1, itemsize, item) # <<<<<<<<<<<<<< + * data += stride + * + */ + __pyx_memoryview__slice_assign_scalar(__pyx_v_data, (__pyx_v_shape + 1), (__pyx_v_strides + 1), (__pyx_v_ndim - 1), __pyx_v_itemsize, __pyx_v_item); + + /* "View.MemoryView":1414 + * for i in range(extent): + * _slice_assign_scalar(data, shape + 1, strides + 1, ndim - 1, itemsize, item) + * data += stride # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_data = (__pyx_v_data + __pyx_v_stride); + } + } + __pyx_L3:; + + /* "View.MemoryView":1400 + * + * @cname('__pyx_memoryview__slice_assign_scalar') + * cdef void _slice_assign_scalar(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * size_t itemsize, void *item) noexcept nogil: + */ + + /* function exit code */ +} + +/* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_1__pyx_unpickle_Enum(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_15View_dot_MemoryView_1__pyx_unpickle_Enum = {"__pyx_unpickle_Enum", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15View_dot_MemoryView_1__pyx_unpickle_Enum, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15View_dot_MemoryView_1__pyx_unpickle_Enum(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v___pyx_type = 0; + long __pyx_v___pyx_checksum; + PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__pyx_unpickle_Enum (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_type,&__pyx_n_s_pyx_checksum,&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_type)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_checksum)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle_Enum", 1, 3, 3, 1); __PYX_ERR(1, 1, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle_Enum", 1, 3, 3, 2); __PYX_ERR(1, 1, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__pyx_unpickle_Enum") < 0)) __PYX_ERR(1, 1, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + } + __pyx_v___pyx_type = values[0]; + __pyx_v___pyx_checksum = __Pyx_PyInt_As_long(values[1]); if (unlikely((__pyx_v___pyx_checksum == (long)-1) && PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + __pyx_v___pyx_state = values[2]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle_Enum", 1, 3, 3, __pyx_nargs); __PYX_ERR(1, 1, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.__pyx_unpickle_Enum", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15View_dot_MemoryView___pyx_unpickle_Enum(__pyx_self, __pyx_v___pyx_type, __pyx_v___pyx_checksum, __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView___pyx_unpickle_Enum(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v___pyx_type, long __pyx_v___pyx_checksum, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_v___pyx_PickleError = 0; + PyObject *__pyx_v___pyx_result = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_unpickle_Enum", 1); + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + */ + __pyx_t_1 = __Pyx_PyInt_From_long(__pyx_v___pyx_checksum); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 4, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = (__Pyx_PySequence_ContainsTF(__pyx_t_1, __pyx_tuple__8, Py_NE)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(1, 4, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (__pyx_t_2) { + + /* "(tree fragment)":5 + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): + * from pickle import PickleError as __pyx_PickleError # <<<<<<<<<<<<<< + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) + */ + __pyx_t_1 = PyList_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_s_PickleError); + __Pyx_GIVEREF(__pyx_n_s_PickleError); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_s_PickleError)) __PYX_ERR(1, 5, __pyx_L1_error); + __pyx_t_3 = __Pyx_Import(__pyx_n_s_pickle, __pyx_t_1, 0); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_ImportFrom(__pyx_t_3, __pyx_n_s_PickleError); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_t_1); + __pyx_v___pyx_PickleError = __pyx_t_1; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "(tree fragment)":6 + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum # <<<<<<<<<<<<<< + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: + */ + __pyx_t_3 = __Pyx_PyInt_From_long(__pyx_v___pyx_checksum); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_Incompatible_checksums_0x_x_vs_0, __pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_v___pyx_PickleError, __pyx_t_1, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(1, 6, __pyx_L1_error) + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + */ + } + + /* "(tree fragment)":7 + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) # <<<<<<<<<<<<<< + * if __pyx_state is not None: + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_MemviewEnum_type), __pyx_n_s_new); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 7, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = NULL; + __pyx_t_5 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_5 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_4, __pyx_v___pyx_type}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_5, 1+__pyx_t_5); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 7, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_v___pyx_result = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":8 + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + */ + __pyx_t_2 = (__pyx_v___pyx_state != Py_None); + if (__pyx_t_2) { + + /* "(tree fragment)":9 + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) # <<<<<<<<<<<<<< + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + */ + if (!(likely(PyTuple_CheckExact(__pyx_v___pyx_state))||((__pyx_v___pyx_state) == Py_None) || __Pyx_RaiseUnexpectedTypeError("tuple", __pyx_v___pyx_state))) __PYX_ERR(1, 9, __pyx_L1_error) + __pyx_t_1 = __pyx_unpickle_Enum__set_state(((struct __pyx_MemviewEnum_obj *)__pyx_v___pyx_result), ((PyObject*)__pyx_v___pyx_state)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 9, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":8 + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + */ + } + + /* "(tree fragment)":10 + * if __pyx_state is not None: + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result # <<<<<<<<<<<<<< + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v___pyx_result); + __pyx_r = __pyx_v___pyx_result; + goto __pyx_L0; + + /* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.__pyx_unpickle_Enum", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v___pyx_PickleError); + __Pyx_XDECREF(__pyx_v___pyx_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":11 + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): # <<<<<<<<<<<<<< + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + */ + +static PyObject *__pyx_unpickle_Enum__set_state(struct __pyx_MemviewEnum_obj *__pyx_v___pyx_result, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + int __pyx_t_8; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_unpickle_Enum__set_state", 1); + + /* "(tree fragment)":12 + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] # <<<<<<<<<<<<<< + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + * __pyx_result.__dict__.update(__pyx_state[1]) + */ + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 12, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 12, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + __Pyx_GOTREF(__pyx_v___pyx_result->name); + __Pyx_DECREF(__pyx_v___pyx_result->name); + __pyx_v___pyx_result->name = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":13 + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): # <<<<<<<<<<<<<< + * __pyx_result.__dict__.update(__pyx_state[1]) + */ + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); + __PYX_ERR(1, 13, __pyx_L1_error) + } + __pyx_t_3 = __Pyx_PyTuple_GET_SIZE(__pyx_v___pyx_state); if (unlikely(__pyx_t_3 == ((Py_ssize_t)-1))) __PYX_ERR(1, 13, __pyx_L1_error) + __pyx_t_4 = (__pyx_t_3 > 1); + if (__pyx_t_4) { + } else { + __pyx_t_2 = __pyx_t_4; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_4 = __Pyx_HasAttr(((PyObject *)__pyx_v___pyx_result), __pyx_n_s_dict); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(1, 13, __pyx_L1_error) + __pyx_t_2 = __pyx_t_4; + __pyx_L4_bool_binop_done:; + if (__pyx_t_2) { + + /* "(tree fragment)":14 + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + * __pyx_result.__dict__.update(__pyx_state[1]) # <<<<<<<<<<<<<< + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v___pyx_result), __pyx_n_s_dict); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_update); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 14, __pyx_L1_error) + } + __pyx_t_5 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_7 = NULL; + __pyx_t_8 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_6))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_6); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_6); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_6, function); + __pyx_t_8 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_7, __pyx_t_5}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_6, __pyx_callargs+1-__pyx_t_8, 1+__pyx_t_8); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":13 + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): # <<<<<<<<<<<<<< + * __pyx_result.__dict__.update(__pyx_state[1]) + */ + } + + /* "(tree fragment)":11 + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): # <<<<<<<<<<<<<< + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("View.MemoryView.__pyx_unpickle_Enum__set_state", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "BufferFormatFromTypeInfo":1450 + * + * @cname('__pyx_format_from_typeinfo') + * cdef bytes format_from_typeinfo(__Pyx_TypeInfo *type): # <<<<<<<<<<<<<< + * cdef __Pyx_StructField *field + * cdef __pyx_typeinfo_string fmt + */ + +static PyObject *__pyx_format_from_typeinfo(__Pyx_TypeInfo *__pyx_v_type) { + __Pyx_StructField *__pyx_v_field; + struct __pyx_typeinfo_string __pyx_v_fmt; + PyObject *__pyx_v_part = 0; + PyObject *__pyx_v_result = 0; + PyObject *__pyx_v_alignment = NULL; + PyObject *__pyx_v_parts = NULL; + PyObject *__pyx_v_extents = NULL; + Py_ssize_t __pyx_7genexpr__pyx_v_i; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + __Pyx_StructField *__pyx_t_3; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + int __pyx_t_7; + int __pyx_t_8; + Py_ssize_t __pyx_t_9; + Py_UCS4 __pyx_t_10; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("format_from_typeinfo", 1); + + /* "BufferFormatFromTypeInfo":1456 + * cdef Py_ssize_t i + * + * if type.typegroup == 'S': # <<<<<<<<<<<<<< + * assert type.fields != NULL + * assert type.fields.type != NULL + */ + __pyx_t_1 = (__pyx_v_type->typegroup == 'S'); + if (__pyx_t_1) { + + /* "BufferFormatFromTypeInfo":1457 + * + * if type.typegroup == 'S': + * assert type.fields != NULL # <<<<<<<<<<<<<< + * assert type.fields.type != NULL + * + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_1 = (__pyx_v_type->fields != NULL); + if (unlikely(!__pyx_t_1)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(1, 1457, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(1, 1457, __pyx_L1_error) + #endif + + /* "BufferFormatFromTypeInfo":1458 + * if type.typegroup == 'S': + * assert type.fields != NULL + * assert type.fields.type != NULL # <<<<<<<<<<<<<< + * + * if type.flags & __PYX_BUF_FLAGS_PACKED_STRUCT: + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_1 = (__pyx_v_type->fields->type != NULL); + if (unlikely(!__pyx_t_1)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(1, 1458, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(1, 1458, __pyx_L1_error) + #endif + + /* "BufferFormatFromTypeInfo":1460 + * assert type.fields.type != NULL + * + * if type.flags & __PYX_BUF_FLAGS_PACKED_STRUCT: # <<<<<<<<<<<<<< + * alignment = b'^' + * else: + */ + __pyx_t_1 = ((__pyx_v_type->flags & __PYX_BUF_FLAGS_PACKED_STRUCT) != 0); + if (__pyx_t_1) { + + /* "BufferFormatFromTypeInfo":1461 + * + * if type.flags & __PYX_BUF_FLAGS_PACKED_STRUCT: + * alignment = b'^' # <<<<<<<<<<<<<< + * else: + * alignment = b'' + */ + __Pyx_INCREF(__pyx_kp_b__9); + __pyx_v_alignment = __pyx_kp_b__9; + + /* "BufferFormatFromTypeInfo":1460 + * assert type.fields.type != NULL + * + * if type.flags & __PYX_BUF_FLAGS_PACKED_STRUCT: # <<<<<<<<<<<<<< + * alignment = b'^' + * else: + */ + goto __pyx_L4; + } + + /* "BufferFormatFromTypeInfo":1463 + * alignment = b'^' + * else: + * alignment = b'' # <<<<<<<<<<<<<< + * + * parts = [b"T{"] + */ + /*else*/ { + __Pyx_INCREF(__pyx_kp_b__10); + __pyx_v_alignment = __pyx_kp_b__10; + } + __pyx_L4:; + + /* "BufferFormatFromTypeInfo":1465 + * alignment = b'' + * + * parts = [b"T{"] # <<<<<<<<<<<<<< + * field = type.fields + * + */ + __pyx_t_2 = PyList_New(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1465, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_INCREF(__pyx_kp_b_T); + __Pyx_GIVEREF(__pyx_kp_b_T); + if (__Pyx_PyList_SET_ITEM(__pyx_t_2, 0, __pyx_kp_b_T)) __PYX_ERR(1, 1465, __pyx_L1_error); + __pyx_v_parts = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; + + /* "BufferFormatFromTypeInfo":1466 + * + * parts = [b"T{"] + * field = type.fields # <<<<<<<<<<<<<< + * + * while field.type: + */ + __pyx_t_3 = __pyx_v_type->fields; + __pyx_v_field = __pyx_t_3; + + /* "BufferFormatFromTypeInfo":1468 + * field = type.fields + * + * while field.type: # <<<<<<<<<<<<<< + * part = format_from_typeinfo(field.type) + * parts.append(part + b':' + field.name + b':') + */ + while (1) { + __pyx_t_1 = (__pyx_v_field->type != 0); + if (!__pyx_t_1) break; + + /* "BufferFormatFromTypeInfo":1469 + * + * while field.type: + * part = format_from_typeinfo(field.type) # <<<<<<<<<<<<<< + * parts.append(part + b':' + field.name + b':') + * field += 1 + */ + __pyx_t_2 = __pyx_format_from_typeinfo(__pyx_v_field->type); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1469, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_XDECREF_SET(__pyx_v_part, ((PyObject*)__pyx_t_2)); + __pyx_t_2 = 0; + + /* "BufferFormatFromTypeInfo":1470 + * while field.type: + * part = format_from_typeinfo(field.type) + * parts.append(part + b':' + field.name + b':') # <<<<<<<<<<<<<< + * field += 1 + * + */ + __pyx_t_2 = PyNumber_Add(__pyx_v_part, __pyx_kp_b__11); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1470, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __Pyx_PyBytes_FromString(__pyx_v_field->name); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1470, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = PyNumber_Add(__pyx_t_2, __pyx_t_4); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 1470, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = PyNumber_Add(__pyx_t_5, __pyx_kp_b__11); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1470, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_6 = __Pyx_PyList_Append(__pyx_v_parts, __pyx_t_4); if (unlikely(__pyx_t_6 == ((int)-1))) __PYX_ERR(1, 1470, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "BufferFormatFromTypeInfo":1471 + * part = format_from_typeinfo(field.type) + * parts.append(part + b':' + field.name + b':') + * field += 1 # <<<<<<<<<<<<<< + * + * result = alignment.join(parts) + b'}' + */ + __pyx_v_field = (__pyx_v_field + 1); + } + + /* "BufferFormatFromTypeInfo":1473 + * field += 1 + * + * result = alignment.join(parts) + b'}' # <<<<<<<<<<<<<< + * else: + * fmt = __Pyx_TypeInfoToFormat(type) + */ + __pyx_t_4 = __Pyx_PyBytes_Join(__pyx_v_alignment, __pyx_v_parts); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1473, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = PyNumber_Add(__pyx_t_4, __pyx_kp_b__12); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 1473, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (!(likely(PyBytes_CheckExact(__pyx_t_5))||((__pyx_t_5) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_t_5))) __PYX_ERR(1, 1473, __pyx_L1_error) + __pyx_v_result = ((PyObject*)__pyx_t_5); + __pyx_t_5 = 0; + + /* "BufferFormatFromTypeInfo":1456 + * cdef Py_ssize_t i + * + * if type.typegroup == 'S': # <<<<<<<<<<<<<< + * assert type.fields != NULL + * assert type.fields.type != NULL + */ + goto __pyx_L3; + } + + /* "BufferFormatFromTypeInfo":1475 + * result = alignment.join(parts) + b'}' + * else: + * fmt = __Pyx_TypeInfoToFormat(type) # <<<<<<<<<<<<<< + * result = fmt.string + * if type.arraysize[0]: + */ + /*else*/ { + __pyx_v_fmt = __Pyx_TypeInfoToFormat(__pyx_v_type); + + /* "BufferFormatFromTypeInfo":1476 + * else: + * fmt = __Pyx_TypeInfoToFormat(type) + * result = fmt.string # <<<<<<<<<<<<<< + * if type.arraysize[0]: + * extents = [f"{type.arraysize[i]}" for i in range(type.ndim)] + */ + __pyx_t_5 = __Pyx_PyObject_FromString(__pyx_v_fmt.string); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 1476, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_v_result = ((PyObject*)__pyx_t_5); + __pyx_t_5 = 0; + + /* "BufferFormatFromTypeInfo":1477 + * fmt = __Pyx_TypeInfoToFormat(type) + * result = fmt.string + * if type.arraysize[0]: # <<<<<<<<<<<<<< + * extents = [f"{type.arraysize[i]}" for i in range(type.ndim)] + * result = f"({u','.join(extents)})".encode('ascii') + result + */ + __pyx_t_1 = ((__pyx_v_type->arraysize[0]) != 0); + if (__pyx_t_1) { + + /* "BufferFormatFromTypeInfo":1478 + * result = fmt.string + * if type.arraysize[0]: + * extents = [f"{type.arraysize[i]}" for i in range(type.ndim)] # <<<<<<<<<<<<<< + * result = f"({u','.join(extents)})".encode('ascii') + result + * + */ + { /* enter inner scope */ + __pyx_t_5 = PyList_New(0); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 1478, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_7 = __pyx_v_type->ndim; + __pyx_t_8 = __pyx_t_7; + for (__pyx_t_9 = 0; __pyx_t_9 < __pyx_t_8; __pyx_t_9+=1) { + __pyx_7genexpr__pyx_v_i = __pyx_t_9; + __pyx_t_4 = __Pyx_PyUnicode_From_size_t((__pyx_v_type->arraysize[__pyx_7genexpr__pyx_v_i]), 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1478, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_5, (PyObject*)__pyx_t_4))) __PYX_ERR(1, 1478, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + } /* exit inner scope */ + __pyx_v_extents = ((PyObject*)__pyx_t_5); + __pyx_t_5 = 0; + + /* "BufferFormatFromTypeInfo":1479 + * if type.arraysize[0]: + * extents = [f"{type.arraysize[i]}" for i in range(type.ndim)] + * result = f"({u','.join(extents)})".encode('ascii') + result # <<<<<<<<<<<<<< + * + * return result + */ + __pyx_t_5 = PyTuple_New(3); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 1479, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_9 = 0; + __pyx_t_10 = 127; + __Pyx_INCREF(__pyx_kp_u__13); + __pyx_t_9 += 1; + __Pyx_GIVEREF(__pyx_kp_u__13); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_kp_u__13); + __pyx_t_4 = PyUnicode_Join(__pyx_kp_u__14, __pyx_v_extents); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1479, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_10 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_4) > __pyx_t_10) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_4) : __pyx_t_10; + __pyx_t_9 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_4); + __pyx_t_4 = 0; + __Pyx_INCREF(__pyx_kp_u__7); + __pyx_t_9 += 1; + __Pyx_GIVEREF(__pyx_kp_u__7); + PyTuple_SET_ITEM(__pyx_t_5, 2, __pyx_kp_u__7); + __pyx_t_4 = __Pyx_PyUnicode_Join(__pyx_t_5, 3, __pyx_t_9, __pyx_t_10); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1479, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_5 = PyUnicode_AsASCIIString(((PyObject*)__pyx_t_4)); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 1479, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = PyNumber_Add(__pyx_t_5, __pyx_v_result); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1479, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (!(likely(PyBytes_CheckExact(__pyx_t_4)) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_t_4))) __PYX_ERR(1, 1479, __pyx_L1_error) + __Pyx_DECREF_SET(__pyx_v_result, ((PyObject*)__pyx_t_4)); + __pyx_t_4 = 0; + + /* "BufferFormatFromTypeInfo":1477 + * fmt = __Pyx_TypeInfoToFormat(type) + * result = fmt.string + * if type.arraysize[0]: # <<<<<<<<<<<<<< + * extents = [f"{type.arraysize[i]}" for i in range(type.ndim)] + * result = f"({u','.join(extents)})".encode('ascii') + result + */ + } + } + __pyx_L3:; + + /* "BufferFormatFromTypeInfo":1481 + * result = f"({u','.join(extents)})".encode('ascii') + result + * + * return result # <<<<<<<<<<<<<< + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_result); + __pyx_r = __pyx_v_result; + goto __pyx_L0; + + /* "BufferFormatFromTypeInfo":1450 + * + * @cname('__pyx_format_from_typeinfo') + * cdef bytes format_from_typeinfo(__Pyx_TypeInfo *type): # <<<<<<<<<<<<<< + * cdef __Pyx_StructField *field + * cdef __pyx_typeinfo_string fmt + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("BufferFormatFromTypeInfo.format_from_typeinfo", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_part); + __Pyx_XDECREF(__pyx_v_result); + __Pyx_XDECREF(__pyx_v_alignment); + __Pyx_XDECREF(__pyx_v_parts); + __Pyx_XDECREF(__pyx_v_extents); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":245 + * + * @property + * cdef inline PyObject* base(self) nogil: # <<<<<<<<<<<<<< + * """Returns a borrowed reference to the object owning the data/memory. + * """ + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_7ndarray_4base_base(PyArrayObject *__pyx_v_self) { + PyObject *__pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":248 + * """Returns a borrowed reference to the object owning the data/memory. + * """ + * return PyArray_BASE(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_BASE(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":245 + * + * @property + * cdef inline PyObject* base(self) nogil: # <<<<<<<<<<<<<< + * """Returns a borrowed reference to the object owning the data/memory. + * """ + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":251 + * + * @property + * cdef inline dtype descr(self): # <<<<<<<<<<<<<< + * """Returns an owned reference to the dtype of the array. + * """ + */ + +static CYTHON_INLINE PyArray_Descr *__pyx_f_5numpy_7ndarray_5descr_descr(PyArrayObject *__pyx_v_self) { + PyArray_Descr *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyArray_Descr *__pyx_t_1; + __Pyx_RefNannySetupContext("descr", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":254 + * """Returns an owned reference to the dtype of the array. + * """ + * return PyArray_DESCR(self) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF((PyObject *)__pyx_r); + __pyx_t_1 = PyArray_DESCR(__pyx_v_self); + __Pyx_INCREF((PyObject *)((PyArray_Descr *)__pyx_t_1)); + __pyx_r = ((PyArray_Descr *)__pyx_t_1); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":251 + * + * @property + * cdef inline dtype descr(self): # <<<<<<<<<<<<<< + * """Returns an owned reference to the dtype of the array. + * """ + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF((PyObject *)__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":257 + * + * @property + * cdef inline int ndim(self) nogil: # <<<<<<<<<<<<<< + * """Returns the number of dimensions in the array. + * """ + */ + +static CYTHON_INLINE int __pyx_f_5numpy_7ndarray_4ndim_ndim(PyArrayObject *__pyx_v_self) { + int __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":260 + * """Returns the number of dimensions in the array. + * """ + * return PyArray_NDIM(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_NDIM(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":257 + * + * @property + * cdef inline int ndim(self) nogil: # <<<<<<<<<<<<<< + * """Returns the number of dimensions in the array. + * """ + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":263 + * + * @property + * cdef inline npy_intp *shape(self) nogil: # <<<<<<<<<<<<<< + * """Returns a pointer to the dimensions/shape of the array. + * The number of elements matches the number of dimensions of the array (ndim). + */ + +static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_5shape_shape(PyArrayObject *__pyx_v_self) { + npy_intp *__pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":268 + * Can return NULL for 0-dimensional arrays. + * """ + * return PyArray_DIMS(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_DIMS(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":263 + * + * @property + * cdef inline npy_intp *shape(self) nogil: # <<<<<<<<<<<<<< + * """Returns a pointer to the dimensions/shape of the array. + * The number of elements matches the number of dimensions of the array (ndim). + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":271 + * + * @property + * cdef inline npy_intp *strides(self) nogil: # <<<<<<<<<<<<<< + * """Returns a pointer to the strides of the array. + * The number of elements matches the number of dimensions of the array (ndim). + */ + +static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_7strides_strides(PyArrayObject *__pyx_v_self) { + npy_intp *__pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":275 + * The number of elements matches the number of dimensions of the array (ndim). + * """ + * return PyArray_STRIDES(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_STRIDES(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":271 + * + * @property + * cdef inline npy_intp *strides(self) nogil: # <<<<<<<<<<<<<< + * """Returns a pointer to the strides of the array. + * The number of elements matches the number of dimensions of the array (ndim). + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":278 + * + * @property + * cdef inline npy_intp size(self) nogil: # <<<<<<<<<<<<<< + * """Returns the total size (in number of elements) of the array. + * """ + */ + +static CYTHON_INLINE npy_intp __pyx_f_5numpy_7ndarray_4size_size(PyArrayObject *__pyx_v_self) { + npy_intp __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":281 + * """Returns the total size (in number of elements) of the array. + * """ + * return PyArray_SIZE(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_SIZE(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":278 + * + * @property + * cdef inline npy_intp size(self) nogil: # <<<<<<<<<<<<<< + * """Returns the total size (in number of elements) of the array. + * """ + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":284 + * + * @property + * cdef inline char* data(self) nogil: # <<<<<<<<<<<<<< + * """The pointer to the data buffer as a char*. + * This is provided for legacy reasons to avoid direct struct field access. + */ + +static CYTHON_INLINE char *__pyx_f_5numpy_7ndarray_4data_data(PyArrayObject *__pyx_v_self) { + char *__pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":290 + * of `PyArray_DATA()` instead, which returns a 'void*'. + * """ + * return PyArray_BYTES(self) # <<<<<<<<<<<<<< + * + * ctypedef unsigned char npy_bool + */ + __pyx_r = PyArray_BYTES(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":284 + * + * @property + * cdef inline char* data(self) nogil: # <<<<<<<<<<<<<< + * """The pointer to the data buffer as a char*. + * This is provided for legacy reasons to avoid direct struct field access. + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":773 + * ctypedef npy_cdouble complex_t + * + * cdef inline object PyArray_MultiIterNew1(a): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(1, a) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew1(PyObject *__pyx_v_a) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew1", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":774 + * + * cdef inline object PyArray_MultiIterNew1(a): + * return PyArray_MultiIterNew(1, a) # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew2(a, b): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(1, ((void *)__pyx_v_a)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 774, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":773 + * ctypedef npy_cdouble complex_t + * + * cdef inline object PyArray_MultiIterNew1(a): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(1, a) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew1", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":776 + * return PyArray_MultiIterNew(1, a) + * + * cdef inline object PyArray_MultiIterNew2(a, b): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(2, a, b) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew2(PyObject *__pyx_v_a, PyObject *__pyx_v_b) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew2", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":777 + * + * cdef inline object PyArray_MultiIterNew2(a, b): + * return PyArray_MultiIterNew(2, a, b) # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew3(a, b, c): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(2, ((void *)__pyx_v_a), ((void *)__pyx_v_b)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 777, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":776 + * return PyArray_MultiIterNew(1, a) + * + * cdef inline object PyArray_MultiIterNew2(a, b): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(2, a, b) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew2", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":779 + * return PyArray_MultiIterNew(2, a, b) + * + * cdef inline object PyArray_MultiIterNew3(a, b, c): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(3, a, b, c) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew3(PyObject *__pyx_v_a, PyObject *__pyx_v_b, PyObject *__pyx_v_c) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew3", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":780 + * + * cdef inline object PyArray_MultiIterNew3(a, b, c): + * return PyArray_MultiIterNew(3, a, b, c) # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew4(a, b, c, d): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(3, ((void *)__pyx_v_a), ((void *)__pyx_v_b), ((void *)__pyx_v_c)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 780, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":779 + * return PyArray_MultiIterNew(2, a, b) + * + * cdef inline object PyArray_MultiIterNew3(a, b, c): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(3, a, b, c) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew3", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":782 + * return PyArray_MultiIterNew(3, a, b, c) + * + * cdef inline object PyArray_MultiIterNew4(a, b, c, d): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(4, a, b, c, d) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew4(PyObject *__pyx_v_a, PyObject *__pyx_v_b, PyObject *__pyx_v_c, PyObject *__pyx_v_d) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew4", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":783 + * + * cdef inline object PyArray_MultiIterNew4(a, b, c, d): + * return PyArray_MultiIterNew(4, a, b, c, d) # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(4, ((void *)__pyx_v_a), ((void *)__pyx_v_b), ((void *)__pyx_v_c), ((void *)__pyx_v_d)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 783, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":782 + * return PyArray_MultiIterNew(3, a, b, c) + * + * cdef inline object PyArray_MultiIterNew4(a, b, c, d): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(4, a, b, c, d) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew4", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":785 + * return PyArray_MultiIterNew(4, a, b, c, d) + * + * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(5, a, b, c, d, e) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew5(PyObject *__pyx_v_a, PyObject *__pyx_v_b, PyObject *__pyx_v_c, PyObject *__pyx_v_d, PyObject *__pyx_v_e) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew5", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":786 + * + * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): + * return PyArray_MultiIterNew(5, a, b, c, d, e) # <<<<<<<<<<<<<< + * + * cdef inline tuple PyDataType_SHAPE(dtype d): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(5, ((void *)__pyx_v_a), ((void *)__pyx_v_b), ((void *)__pyx_v_c), ((void *)__pyx_v_d), ((void *)__pyx_v_e)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 786, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":785 + * return PyArray_MultiIterNew(4, a, b, c, d) + * + * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(5, a, b, c, d, e) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew5", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":788 + * return PyArray_MultiIterNew(5, a, b, c, d, e) + * + * cdef inline tuple PyDataType_SHAPE(dtype d): # <<<<<<<<<<<<<< + * if PyDataType_HASSUBARRAY(d): + * return d.subarray.shape + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyDataType_SHAPE(PyArray_Descr *__pyx_v_d) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + __Pyx_RefNannySetupContext("PyDataType_SHAPE", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":789 + * + * cdef inline tuple PyDataType_SHAPE(dtype d): + * if PyDataType_HASSUBARRAY(d): # <<<<<<<<<<<<<< + * return d.subarray.shape + * else: + */ + __pyx_t_1 = PyDataType_HASSUBARRAY(__pyx_v_d); + if (__pyx_t_1) { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":790 + * cdef inline tuple PyDataType_SHAPE(dtype d): + * if PyDataType_HASSUBARRAY(d): + * return d.subarray.shape # <<<<<<<<<<<<<< + * else: + * return () + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(((PyObject*)__pyx_v_d->subarray->shape)); + __pyx_r = ((PyObject*)__pyx_v_d->subarray->shape); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":789 + * + * cdef inline tuple PyDataType_SHAPE(dtype d): + * if PyDataType_HASSUBARRAY(d): # <<<<<<<<<<<<<< + * return d.subarray.shape + * else: + */ + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":792 + * return d.subarray.shape + * else: + * return () # <<<<<<<<<<<<<< + * + * + */ + /*else*/ { + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_empty_tuple); + __pyx_r = __pyx_empty_tuple; + goto __pyx_L0; + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":788 + * return PyArray_MultiIterNew(5, a, b, c, d, e) + * + * cdef inline tuple PyDataType_SHAPE(dtype d): # <<<<<<<<<<<<<< + * if PyDataType_HASSUBARRAY(d): + * return d.subarray.shape + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":968 + * int _import_umath() except -1 + * + * cdef inline void set_array_base(ndarray arr, object base): # <<<<<<<<<<<<<< + * Py_INCREF(base) # important to do this before stealing the reference below! + * PyArray_SetBaseObject(arr, base) + */ + +static CYTHON_INLINE void __pyx_f_5numpy_set_array_base(PyArrayObject *__pyx_v_arr, PyObject *__pyx_v_base) { + int __pyx_t_1; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":969 + * + * cdef inline void set_array_base(ndarray arr, object base): + * Py_INCREF(base) # important to do this before stealing the reference below! # <<<<<<<<<<<<<< + * PyArray_SetBaseObject(arr, base) + * + */ + Py_INCREF(__pyx_v_base); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":970 + * cdef inline void set_array_base(ndarray arr, object base): + * Py_INCREF(base) # important to do this before stealing the reference below! + * PyArray_SetBaseObject(arr, base) # <<<<<<<<<<<<<< + * + * cdef inline object get_array_base(ndarray arr): + */ + __pyx_t_1 = PyArray_SetBaseObject(__pyx_v_arr, __pyx_v_base); if (unlikely(__pyx_t_1 == ((int)-1))) __PYX_ERR(2, 970, __pyx_L1_error) + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":968 + * int _import_umath() except -1 + * + * cdef inline void set_array_base(ndarray arr, object base): # <<<<<<<<<<<<<< + * Py_INCREF(base) # important to do this before stealing the reference below! + * PyArray_SetBaseObject(arr, base) + */ + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("numpy.set_array_base", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_L0:; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":972 + * PyArray_SetBaseObject(arr, base) + * + * cdef inline object get_array_base(ndarray arr): # <<<<<<<<<<<<<< + * base = PyArray_BASE(arr) + * if base is NULL: + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_get_array_base(PyArrayObject *__pyx_v_arr) { + PyObject *__pyx_v_base; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + __Pyx_RefNannySetupContext("get_array_base", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":973 + * + * cdef inline object get_array_base(ndarray arr): + * base = PyArray_BASE(arr) # <<<<<<<<<<<<<< + * if base is NULL: + * return None + */ + __pyx_v_base = PyArray_BASE(__pyx_v_arr); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":974 + * cdef inline object get_array_base(ndarray arr): + * base = PyArray_BASE(arr) + * if base is NULL: # <<<<<<<<<<<<<< + * return None + * return base + */ + __pyx_t_1 = (__pyx_v_base == NULL); + if (__pyx_t_1) { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":975 + * base = PyArray_BASE(arr) + * if base is NULL: + * return None # <<<<<<<<<<<<<< + * return base + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":974 + * cdef inline object get_array_base(ndarray arr): + * base = PyArray_BASE(arr) + * if base is NULL: # <<<<<<<<<<<<<< + * return None + * return base + */ + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":976 + * if base is NULL: + * return None + * return base # <<<<<<<<<<<<<< + * + * # Versions of the import_* functions which are more suitable for + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(((PyObject *)__pyx_v_base)); + __pyx_r = ((PyObject *)__pyx_v_base); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":972 + * PyArray_SetBaseObject(arr, base) + * + * cdef inline object get_array_base(ndarray arr): # <<<<<<<<<<<<<< + * base = PyArray_BASE(arr) + * if base is NULL: + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":980 + * # Versions of the import_* functions which are more suitable for + * # Cython code. + * cdef inline int import_array() except -1: # <<<<<<<<<<<<<< + * try: + * __pyx_import_array() + */ + +static CYTHON_INLINE int __pyx_f_5numpy_import_array(void) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("import_array", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":981 + * # Cython code. + * cdef inline int import_array() except -1: + * try: # <<<<<<<<<<<<<< + * __pyx_import_array() + * except Exception: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":982 + * cdef inline int import_array() except -1: + * try: + * __pyx_import_array() # <<<<<<<<<<<<<< + * except Exception: + * raise ImportError("numpy.core.multiarray failed to import") + */ + __pyx_t_4 = _import_array(); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(2, 982, __pyx_L3_error) + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":981 + * # Cython code. + * cdef inline int import_array() except -1: + * try: # <<<<<<<<<<<<<< + * __pyx_import_array() + * except Exception: + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L8_try_end; + __pyx_L3_error:; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":983 + * try: + * __pyx_import_array() + * except Exception: # <<<<<<<<<<<<<< + * raise ImportError("numpy.core.multiarray failed to import") + * + */ + __pyx_t_4 = __Pyx_PyErr_ExceptionMatches(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0]))); + if (__pyx_t_4) { + __Pyx_AddTraceback("numpy.import_array", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_6, &__pyx_t_7) < 0) __PYX_ERR(2, 983, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_7); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":984 + * __pyx_import_array() + * except Exception: + * raise ImportError("numpy.core.multiarray failed to import") # <<<<<<<<<<<<<< + * + * cdef inline int import_umath() except -1: + */ + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_builtin_ImportError, __pyx_tuple__15, NULL); if (unlikely(!__pyx_t_8)) __PYX_ERR(2, 984, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_Raise(__pyx_t_8, 0, 0, 0); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __PYX_ERR(2, 984, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":981 + * # Cython code. + * cdef inline int import_array() except -1: + * try: # <<<<<<<<<<<<<< + * __pyx_import_array() + * except Exception: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + goto __pyx_L1_error; + __pyx_L8_try_end:; + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":980 + * # Versions of the import_* functions which are more suitable for + * # Cython code. + * cdef inline int import_array() except -1: # <<<<<<<<<<<<<< + * try: + * __pyx_import_array() + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("numpy.import_array", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":986 + * raise ImportError("numpy.core.multiarray failed to import") + * + * cdef inline int import_umath() except -1: # <<<<<<<<<<<<<< + * try: + * _import_umath() + */ + +static CYTHON_INLINE int __pyx_f_5numpy_import_umath(void) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("import_umath", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":987 + * + * cdef inline int import_umath() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":988 + * cdef inline int import_umath() except -1: + * try: + * _import_umath() # <<<<<<<<<<<<<< + * except Exception: + * raise ImportError("numpy.core.umath failed to import") + */ + __pyx_t_4 = _import_umath(); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(2, 988, __pyx_L3_error) + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":987 + * + * cdef inline int import_umath() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L8_try_end; + __pyx_L3_error:; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":989 + * try: + * _import_umath() + * except Exception: # <<<<<<<<<<<<<< + * raise ImportError("numpy.core.umath failed to import") + * + */ + __pyx_t_4 = __Pyx_PyErr_ExceptionMatches(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0]))); + if (__pyx_t_4) { + __Pyx_AddTraceback("numpy.import_umath", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_6, &__pyx_t_7) < 0) __PYX_ERR(2, 989, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_7); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":990 + * _import_umath() + * except Exception: + * raise ImportError("numpy.core.umath failed to import") # <<<<<<<<<<<<<< + * + * cdef inline int import_ufunc() except -1: + */ + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_builtin_ImportError, __pyx_tuple__16, NULL); if (unlikely(!__pyx_t_8)) __PYX_ERR(2, 990, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_Raise(__pyx_t_8, 0, 0, 0); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __PYX_ERR(2, 990, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":987 + * + * cdef inline int import_umath() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + goto __pyx_L1_error; + __pyx_L8_try_end:; + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":986 + * raise ImportError("numpy.core.multiarray failed to import") + * + * cdef inline int import_umath() except -1: # <<<<<<<<<<<<<< + * try: + * _import_umath() + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("numpy.import_umath", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":992 + * raise ImportError("numpy.core.umath failed to import") + * + * cdef inline int import_ufunc() except -1: # <<<<<<<<<<<<<< + * try: + * _import_umath() + */ + +static CYTHON_INLINE int __pyx_f_5numpy_import_ufunc(void) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("import_ufunc", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":993 + * + * cdef inline int import_ufunc() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":994 + * cdef inline int import_ufunc() except -1: + * try: + * _import_umath() # <<<<<<<<<<<<<< + * except Exception: + * raise ImportError("numpy.core.umath failed to import") + */ + __pyx_t_4 = _import_umath(); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(2, 994, __pyx_L3_error) + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":993 + * + * cdef inline int import_ufunc() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L8_try_end; + __pyx_L3_error:; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":995 + * try: + * _import_umath() + * except Exception: # <<<<<<<<<<<<<< + * raise ImportError("numpy.core.umath failed to import") + * + */ + __pyx_t_4 = __Pyx_PyErr_ExceptionMatches(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0]))); + if (__pyx_t_4) { + __Pyx_AddTraceback("numpy.import_ufunc", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_6, &__pyx_t_7) < 0) __PYX_ERR(2, 995, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_7); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":996 + * _import_umath() + * except Exception: + * raise ImportError("numpy.core.umath failed to import") # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_builtin_ImportError, __pyx_tuple__16, NULL); if (unlikely(!__pyx_t_8)) __PYX_ERR(2, 996, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_Raise(__pyx_t_8, 0, 0, 0); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __PYX_ERR(2, 996, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":993 + * + * cdef inline int import_ufunc() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + goto __pyx_L1_error; + __pyx_L8_try_end:; + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":992 + * raise ImportError("numpy.core.umath failed to import") + * + * cdef inline int import_ufunc() except -1: # <<<<<<<<<<<<<< + * try: + * _import_umath() + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("numpy.import_ufunc", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":999 + * + * + * cdef inline bint is_timedelta64_object(object obj): # <<<<<<<<<<<<<< + * """ + * Cython equivalent of `isinstance(obj, np.timedelta64)` + */ + +static CYTHON_INLINE int __pyx_f_5numpy_is_timedelta64_object(PyObject *__pyx_v_obj) { + int __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1011 + * bool + * """ + * return PyObject_TypeCheck(obj, &PyTimedeltaArrType_Type) # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = PyObject_TypeCheck(__pyx_v_obj, (&PyTimedeltaArrType_Type)); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":999 + * + * + * cdef inline bint is_timedelta64_object(object obj): # <<<<<<<<<<<<<< + * """ + * Cython equivalent of `isinstance(obj, np.timedelta64)` + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1014 + * + * + * cdef inline bint is_datetime64_object(object obj): # <<<<<<<<<<<<<< + * """ + * Cython equivalent of `isinstance(obj, np.datetime64)` + */ + +static CYTHON_INLINE int __pyx_f_5numpy_is_datetime64_object(PyObject *__pyx_v_obj) { + int __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1026 + * bool + * """ + * return PyObject_TypeCheck(obj, &PyDatetimeArrType_Type) # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = PyObject_TypeCheck(__pyx_v_obj, (&PyDatetimeArrType_Type)); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1014 + * + * + * cdef inline bint is_datetime64_object(object obj): # <<<<<<<<<<<<<< + * """ + * Cython equivalent of `isinstance(obj, np.datetime64)` + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1029 + * + * + * cdef inline npy_datetime get_datetime64_value(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the int64 value underlying scalar numpy datetime64 object + */ + +static CYTHON_INLINE npy_datetime __pyx_f_5numpy_get_datetime64_value(PyObject *__pyx_v_obj) { + npy_datetime __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1036 + * also needed. That can be found using `get_datetime64_unit`. + * """ + * return (obj).obval # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = ((PyDatetimeScalarObject *)__pyx_v_obj)->obval; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1029 + * + * + * cdef inline npy_datetime get_datetime64_value(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the int64 value underlying scalar numpy datetime64 object + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1039 + * + * + * cdef inline npy_timedelta get_timedelta64_value(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the int64 value underlying scalar numpy timedelta64 object + */ + +static CYTHON_INLINE npy_timedelta __pyx_f_5numpy_get_timedelta64_value(PyObject *__pyx_v_obj) { + npy_timedelta __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1043 + * returns the int64 value underlying scalar numpy timedelta64 object + * """ + * return (obj).obval # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = ((PyTimedeltaScalarObject *)__pyx_v_obj)->obval; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1039 + * + * + * cdef inline npy_timedelta get_timedelta64_value(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the int64 value underlying scalar numpy timedelta64 object + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1046 + * + * + * cdef inline NPY_DATETIMEUNIT get_datetime64_unit(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the unit part of the dtype for a numpy datetime64 object. + */ + +static CYTHON_INLINE NPY_DATETIMEUNIT __pyx_f_5numpy_get_datetime64_unit(PyObject *__pyx_v_obj) { + NPY_DATETIMEUNIT __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1050 + * returns the unit part of the dtype for a numpy datetime64 object. + * """ + * return (obj).obmeta.base # <<<<<<<<<<<<<< + */ + __pyx_r = ((NPY_DATETIMEUNIT)((PyDatetimeScalarObject *)__pyx_v_obj)->obmeta.base); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1046 + * + * + * cdef inline NPY_DATETIMEUNIT get_datetime64_unit(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the unit part of the dtype for a numpy datetime64 object. + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "rednose/helpers/ekf_sym_pyx.pyx":75 + * @cython.wraparound(False) + * @cython.boundscheck(False) + * cdef np.ndarray[np.float64_t, ndim=2, mode="c"] matrix_to_numpy(MatrixXdr arr): # <<<<<<<<<<<<<< + * cdef double[:,:] mem_view = arr.data() + * return np.copy(np.asarray(mem_view, dtype=np.double, order="C")) + */ + +static PyArrayObject *__pyx_f_7rednose_7helpers_11ekf_sym_pyx_matrix_to_numpy(Eigen::Matrix __pyx_v_arr) { + __Pyx_memviewslice __pyx_v_mem_view = { 0, 0, { 0 }, { 0 }, { 0 } }; + PyArrayObject *__pyx_r = NULL; + __Pyx_TraceDeclarations + __Pyx_RefNannyDeclarations + double *__pyx_t_1; + struct __pyx_array_obj *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + __Pyx_memviewslice __pyx_t_5 = { 0, 0, { 0 }, { 0 }, { 0 } }; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + PyObject *__pyx_t_9 = NULL; + PyObject *__pyx_t_10 = NULL; + int __pyx_t_11; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("matrix_to_numpy", 1); + __Pyx_TraceCall("matrix_to_numpy", __pyx_f[0], 75, 0, __PYX_ERR(0, 75, __pyx_L1_error)); + + /* "rednose/helpers/ekf_sym_pyx.pyx":76 + * @cython.boundscheck(False) + * cdef np.ndarray[np.float64_t, ndim=2, mode="c"] matrix_to_numpy(MatrixXdr arr): + * cdef double[:,:] mem_view = arr.data() # <<<<<<<<<<<<<< + * return np.copy(np.asarray(mem_view, dtype=np.double, order="C")) + * + */ + __pyx_t_1 = __pyx_v_arr.data(); + if (!__pyx_t_1) { + PyErr_SetString(PyExc_ValueError,"Cannot create cython.array from NULL pointer"); + __PYX_ERR(0, 76, __pyx_L1_error) + } + __pyx_t_4 = __pyx_format_from_typeinfo(&__Pyx_TypeInfo_double); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 76, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_3 = Py_BuildValue((char*) "(" __PYX_BUILD_PY_SSIZE_T __PYX_BUILD_PY_SSIZE_T ")", ((Py_ssize_t)__pyx_v_arr.rows()), ((Py_ssize_t)__pyx_v_arr.cols())); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 76, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_2 = __pyx_array_new(__pyx_t_3, sizeof(double), PyBytes_AS_STRING(__pyx_t_4), (char *) "c", (char *) __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 76, __pyx_L1_error) + __Pyx_GOTREF((PyObject *)__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_5 = __Pyx_PyObject_to_MemoryviewSlice_dsds_double(((PyObject *)__pyx_t_2), PyBUF_WRITABLE); if (unlikely(!__pyx_t_5.memview)) __PYX_ERR(0, 76, __pyx_L1_error) + __Pyx_DECREF((PyObject *)__pyx_t_2); __pyx_t_2 = 0; + __pyx_v_mem_view = __pyx_t_5; + __pyx_t_5.memview = NULL; + __pyx_t_5.data = NULL; + + /* "rednose/helpers/ekf_sym_pyx.pyx":77 + * cdef np.ndarray[np.float64_t, ndim=2, mode="c"] matrix_to_numpy(MatrixXdr arr): + * cdef double[:,:] mem_view = arr.data() + * return np.copy(np.asarray(mem_view, dtype=np.double, order="C")) # <<<<<<<<<<<<<< + * + * @cython.wraparound(False) + */ + __Pyx_XDECREF((PyObject *)__pyx_r); + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_np); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 77, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_copy); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 77, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_np); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 77, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_asarray); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 77, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __pyx_memoryview_fromslice(__pyx_v_mem_view, 2, (PyObject *(*)(char *)) __pyx_memview_get_double, (int (*)(char *, PyObject *)) __pyx_memview_set_double, 0);; if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 77, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_8 = PyTuple_New(1); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 77, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_8, 0, __pyx_t_3)) __PYX_ERR(0, 77, __pyx_L1_error); + __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PyDict_NewPresized(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 77, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GetModuleGlobalName(__pyx_t_9, __pyx_n_s_np); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 77, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __pyx_t_10 = __Pyx_PyObject_GetAttrStr(__pyx_t_9, __pyx_n_s_double); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 77, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_dtype, __pyx_t_10) < 0) __PYX_ERR(0, 77, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_order, __pyx_n_u_C) < 0) __PYX_ERR(0, 77, __pyx_L1_error) + __pyx_t_10 = __Pyx_PyObject_Call(__pyx_t_7, __pyx_t_8, __pyx_t_3); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 77, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = NULL; + __pyx_t_11 = 0; + #if CYTHON_UNPACK_METHODS + if (unlikely(PyMethod_Check(__pyx_t_6))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_6); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_6); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_6, function); + __pyx_t_11 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_t_10}; + __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_6, __pyx_callargs+1-__pyx_t_11, 1+__pyx_t_11); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 77, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + if (!(likely(((__pyx_t_4) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_4, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 77, __pyx_L1_error) + __pyx_r = ((PyArrayObject *)__pyx_t_4); + __pyx_t_4 = 0; + goto __pyx_L0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":75 + * @cython.wraparound(False) + * @cython.boundscheck(False) + * cdef np.ndarray[np.float64_t, ndim=2, mode="c"] matrix_to_numpy(MatrixXdr arr): # <<<<<<<<<<<<<< + * cdef double[:,:] mem_view = arr.data() + * return np.copy(np.asarray(mem_view, dtype=np.double, order="C")) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF((PyObject *)__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __PYX_XCLEAR_MEMVIEW(&__pyx_t_5, 1); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_XDECREF(__pyx_t_9); + __Pyx_XDECREF(__pyx_t_10); + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.matrix_to_numpy", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __PYX_XCLEAR_MEMVIEW(&__pyx_v_mem_view, 1); + __Pyx_XGIVEREF((PyObject *)__pyx_r); + __Pyx_TraceReturn(__pyx_r, 0); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "rednose/helpers/ekf_sym_pyx.pyx":81 + * @cython.wraparound(False) + * @cython.boundscheck(False) + * cdef np.ndarray[np.float64_t, ndim=1, mode="c"] vector_to_numpy(VectorXd arr): # <<<<<<<<<<<<<< + * cdef double[:] mem_view = arr.data() + * return np.copy(np.asarray(mem_view, dtype=np.double, order="C")) + */ + +static PyArrayObject *__pyx_f_7rednose_7helpers_11ekf_sym_pyx_vector_to_numpy(Eigen::VectorXd __pyx_v_arr) { + __Pyx_memviewslice __pyx_v_mem_view = { 0, 0, { 0 }, { 0 }, { 0 } }; + PyArrayObject *__pyx_r = NULL; + __Pyx_TraceDeclarations + __Pyx_RefNannyDeclarations + double *__pyx_t_1; + struct __pyx_array_obj *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + __Pyx_memviewslice __pyx_t_5 = { 0, 0, { 0 }, { 0 }, { 0 } }; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + PyObject *__pyx_t_9 = NULL; + PyObject *__pyx_t_10 = NULL; + int __pyx_t_11; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("vector_to_numpy", 1); + __Pyx_TraceCall("vector_to_numpy", __pyx_f[0], 81, 0, __PYX_ERR(0, 81, __pyx_L1_error)); + + /* "rednose/helpers/ekf_sym_pyx.pyx":82 + * @cython.boundscheck(False) + * cdef np.ndarray[np.float64_t, ndim=1, mode="c"] vector_to_numpy(VectorXd arr): + * cdef double[:] mem_view = arr.data() # <<<<<<<<<<<<<< + * return np.copy(np.asarray(mem_view, dtype=np.double, order="C")) + * + */ + __pyx_t_1 = __pyx_v_arr.data(); + if (!__pyx_t_1) { + PyErr_SetString(PyExc_ValueError,"Cannot create cython.array from NULL pointer"); + __PYX_ERR(0, 82, __pyx_L1_error) + } + __pyx_t_4 = __pyx_format_from_typeinfo(&__Pyx_TypeInfo_double); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 82, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_3 = Py_BuildValue((char*) "(" __PYX_BUILD_PY_SSIZE_T ")", ((Py_ssize_t)__pyx_v_arr.rows())); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 82, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_2 = __pyx_array_new(__pyx_t_3, sizeof(double), PyBytes_AS_STRING(__pyx_t_4), (char *) "c", (char *) __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 82, __pyx_L1_error) + __Pyx_GOTREF((PyObject *)__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_5 = __Pyx_PyObject_to_MemoryviewSlice_ds_double(((PyObject *)__pyx_t_2), PyBUF_WRITABLE); if (unlikely(!__pyx_t_5.memview)) __PYX_ERR(0, 82, __pyx_L1_error) + __Pyx_DECREF((PyObject *)__pyx_t_2); __pyx_t_2 = 0; + __pyx_v_mem_view = __pyx_t_5; + __pyx_t_5.memview = NULL; + __pyx_t_5.data = NULL; + + /* "rednose/helpers/ekf_sym_pyx.pyx":83 + * cdef np.ndarray[np.float64_t, ndim=1, mode="c"] vector_to_numpy(VectorXd arr): + * cdef double[:] mem_view = arr.data() + * return np.copy(np.asarray(mem_view, dtype=np.double, order="C")) # <<<<<<<<<<<<<< + * + * cdef class EKF_sym_pyx: + */ + __Pyx_XDECREF((PyObject *)__pyx_r); + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_np); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 83, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_copy); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 83, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_np); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 83, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_asarray); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 83, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __pyx_memoryview_fromslice(__pyx_v_mem_view, 1, (PyObject *(*)(char *)) __pyx_memview_get_double, (int (*)(char *, PyObject *)) __pyx_memview_set_double, 0);; if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 83, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_8 = PyTuple_New(1); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 83, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_8, 0, __pyx_t_3)) __PYX_ERR(0, 83, __pyx_L1_error); + __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PyDict_NewPresized(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 83, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GetModuleGlobalName(__pyx_t_9, __pyx_n_s_np); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 83, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __pyx_t_10 = __Pyx_PyObject_GetAttrStr(__pyx_t_9, __pyx_n_s_double); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 83, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_dtype, __pyx_t_10) < 0) __PYX_ERR(0, 83, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_order, __pyx_n_u_C) < 0) __PYX_ERR(0, 83, __pyx_L1_error) + __pyx_t_10 = __Pyx_PyObject_Call(__pyx_t_7, __pyx_t_8, __pyx_t_3); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 83, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = NULL; + __pyx_t_11 = 0; + #if CYTHON_UNPACK_METHODS + if (unlikely(PyMethod_Check(__pyx_t_6))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_6); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_6); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_6, function); + __pyx_t_11 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_t_10}; + __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_6, __pyx_callargs+1-__pyx_t_11, 1+__pyx_t_11); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 83, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + if (!(likely(((__pyx_t_4) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_4, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 83, __pyx_L1_error) + __pyx_r = ((PyArrayObject *)__pyx_t_4); + __pyx_t_4 = 0; + goto __pyx_L0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":81 + * @cython.wraparound(False) + * @cython.boundscheck(False) + * cdef np.ndarray[np.float64_t, ndim=1, mode="c"] vector_to_numpy(VectorXd arr): # <<<<<<<<<<<<<< + * cdef double[:] mem_view = arr.data() + * return np.copy(np.asarray(mem_view, dtype=np.double, order="C")) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF((PyObject *)__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __PYX_XCLEAR_MEMVIEW(&__pyx_t_5, 1); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_XDECREF(__pyx_t_9); + __Pyx_XDECREF(__pyx_t_10); + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.vector_to_numpy", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __PYX_XCLEAR_MEMVIEW(&__pyx_v_mem_view, 1); + __Pyx_XGIVEREF((PyObject *)__pyx_r); + __Pyx_TraceReturn(__pyx_r, 0); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "rednose/helpers/ekf_sym_pyx.pyx":87 + * cdef class EKF_sym_pyx: + * cdef EKFSym* ekf + * def __cinit__(self, str gen_dir, str name, np.ndarray[np.float64_t, ndim=2] Q, # <<<<<<<<<<<<<< + * np.ndarray[np.float64_t, ndim=1] x_initial, np.ndarray[np.float64_t, ndim=2] P_initial, int dim_main, + * int dim_main_err, int N=0, int dim_augment=0, int dim_augment_err=0, list maha_test_kinds=[], + */ + +/* Python wrapper */ +static int __pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_gen_dir = 0; + PyObject *__pyx_v_name = 0; + PyArrayObject *__pyx_v_Q = 0; + PyArrayObject *__pyx_v_x_initial = 0; + PyArrayObject *__pyx_v_P_initial = 0; + int __pyx_v_dim_main; + int __pyx_v_dim_main_err; + int __pyx_v_N; + int __pyx_v_dim_augment; + int __pyx_v_dim_augment_err; + PyObject *__pyx_v_maha_test_kinds = 0; + PyObject *__pyx_v_quaternion_idxs = 0; + PyObject *__pyx_v_global_vars = 0; + double __pyx_v_max_rewind_age; + CYTHON_UNUSED PyObject *__pyx_v_logger = 0; + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[15] = {0,0,0,0,0,0,0,0,0,0,0,0,0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_gen_dir,&__pyx_n_s_name,&__pyx_n_s_Q,&__pyx_n_s_x_initial,&__pyx_n_s_P_initial,&__pyx_n_s_dim_main,&__pyx_n_s_dim_main_err,&__pyx_n_s_N,&__pyx_n_s_dim_augment,&__pyx_n_s_dim_augment_err,&__pyx_n_s_maha_test_kinds,&__pyx_n_s_quaternion_idxs,&__pyx_n_s_global_vars,&__pyx_n_s_max_rewind_age,&__pyx_n_s_logger,0}; + values[10] = __Pyx_Arg_NewRef_VARARGS(__pyx_k__17); + values[11] = __Pyx_Arg_NewRef_VARARGS(__pyx_k__18); + values[12] = __Pyx_Arg_NewRef_VARARGS(__pyx_k__19); + + /* "rednose/helpers/ekf_sym_pyx.pyx":90 + * np.ndarray[np.float64_t, ndim=1] x_initial, np.ndarray[np.float64_t, ndim=2] P_initial, int dim_main, + * int dim_main_err, int N=0, int dim_augment=0, int dim_augment_err=0, list maha_test_kinds=[], + * list quaternion_idxs=[], list global_vars=[], double max_rewind_age=1.0, logger=None): # <<<<<<<<<<<<<< + * # TODO logger + * ekf_load_and_register(gen_dir.encode('utf8'), name.encode('utf8')) + */ + values[14] = __Pyx_Arg_NewRef_VARARGS(((PyObject *)Py_None)); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 15: values[14] = __Pyx_Arg_VARARGS(__pyx_args, 14); + CYTHON_FALLTHROUGH; + case 14: values[13] = __Pyx_Arg_VARARGS(__pyx_args, 13); + CYTHON_FALLTHROUGH; + case 13: values[12] = __Pyx_Arg_VARARGS(__pyx_args, 12); + CYTHON_FALLTHROUGH; + case 12: values[11] = __Pyx_Arg_VARARGS(__pyx_args, 11); + CYTHON_FALLTHROUGH; + case 11: values[10] = __Pyx_Arg_VARARGS(__pyx_args, 10); + CYTHON_FALLTHROUGH; + case 10: values[9] = __Pyx_Arg_VARARGS(__pyx_args, 9); + CYTHON_FALLTHROUGH; + case 9: values[8] = __Pyx_Arg_VARARGS(__pyx_args, 8); + CYTHON_FALLTHROUGH; + case 8: values[7] = __Pyx_Arg_VARARGS(__pyx_args, 7); + CYTHON_FALLTHROUGH; + case 7: values[6] = __Pyx_Arg_VARARGS(__pyx_args, 6); + CYTHON_FALLTHROUGH; + case 6: values[5] = __Pyx_Arg_VARARGS(__pyx_args, 5); + CYTHON_FALLTHROUGH; + case 5: values[4] = __Pyx_Arg_VARARGS(__pyx_args, 4); + CYTHON_FALLTHROUGH; + case 4: values[3] = __Pyx_Arg_VARARGS(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_gen_dir)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 87, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_name)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 87, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 7, 15, 1); __PYX_ERR(0, 87, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_Q)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 87, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 7, 15, 2); __PYX_ERR(0, 87, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 3: + if (likely((values[3] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_x_initial)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[3]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 87, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 7, 15, 3); __PYX_ERR(0, 87, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 4: + if (likely((values[4] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_P_initial)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[4]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 87, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 7, 15, 4); __PYX_ERR(0, 87, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 5: + if (likely((values[5] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_dim_main)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[5]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 87, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 7, 15, 5); __PYX_ERR(0, 87, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 6: + if (likely((values[6] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_dim_main_err)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[6]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 87, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 7, 15, 6); __PYX_ERR(0, 87, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 7: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_N); + if (value) { values[7] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 87, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 8: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_dim_augment); + if (value) { values[8] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 87, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 9: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_dim_augment_err); + if (value) { values[9] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 87, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 10: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_maha_test_kinds); + if (value) { values[10] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 87, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 11: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_quaternion_idxs); + if (value) { values[11] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 87, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 12: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_global_vars); + if (value) { values[12] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 87, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 13: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_max_rewind_age); + if (value) { values[13] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 87, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 14: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_logger); + if (value) { values[14] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 87, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(0, 87, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 15: values[14] = __Pyx_Arg_VARARGS(__pyx_args, 14); + CYTHON_FALLTHROUGH; + case 14: values[13] = __Pyx_Arg_VARARGS(__pyx_args, 13); + CYTHON_FALLTHROUGH; + case 13: values[12] = __Pyx_Arg_VARARGS(__pyx_args, 12); + CYTHON_FALLTHROUGH; + case 12: values[11] = __Pyx_Arg_VARARGS(__pyx_args, 11); + CYTHON_FALLTHROUGH; + case 11: values[10] = __Pyx_Arg_VARARGS(__pyx_args, 10); + CYTHON_FALLTHROUGH; + case 10: values[9] = __Pyx_Arg_VARARGS(__pyx_args, 9); + CYTHON_FALLTHROUGH; + case 9: values[8] = __Pyx_Arg_VARARGS(__pyx_args, 8); + CYTHON_FALLTHROUGH; + case 8: values[7] = __Pyx_Arg_VARARGS(__pyx_args, 7); + CYTHON_FALLTHROUGH; + case 7: values[6] = __Pyx_Arg_VARARGS(__pyx_args, 6); + values[5] = __Pyx_Arg_VARARGS(__pyx_args, 5); + values[4] = __Pyx_Arg_VARARGS(__pyx_args, 4); + values[3] = __Pyx_Arg_VARARGS(__pyx_args, 3); + values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_gen_dir = ((PyObject*)values[0]); + __pyx_v_name = ((PyObject*)values[1]); + __pyx_v_Q = ((PyArrayObject *)values[2]); + __pyx_v_x_initial = ((PyArrayObject *)values[3]); + __pyx_v_P_initial = ((PyArrayObject *)values[4]); + __pyx_v_dim_main = __Pyx_PyInt_As_int(values[5]); if (unlikely((__pyx_v_dim_main == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 88, __pyx_L3_error) + __pyx_v_dim_main_err = __Pyx_PyInt_As_int(values[6]); if (unlikely((__pyx_v_dim_main_err == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 89, __pyx_L3_error) + if (values[7]) { + __pyx_v_N = __Pyx_PyInt_As_int(values[7]); if (unlikely((__pyx_v_N == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 89, __pyx_L3_error) + } else { + __pyx_v_N = ((int)0); + } + if (values[8]) { + __pyx_v_dim_augment = __Pyx_PyInt_As_int(values[8]); if (unlikely((__pyx_v_dim_augment == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 89, __pyx_L3_error) + } else { + __pyx_v_dim_augment = ((int)0); + } + if (values[9]) { + __pyx_v_dim_augment_err = __Pyx_PyInt_As_int(values[9]); if (unlikely((__pyx_v_dim_augment_err == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 89, __pyx_L3_error) + } else { + __pyx_v_dim_augment_err = ((int)0); + } + __pyx_v_maha_test_kinds = ((PyObject*)values[10]); + __pyx_v_quaternion_idxs = ((PyObject*)values[11]); + __pyx_v_global_vars = ((PyObject*)values[12]); + if (values[13]) { + __pyx_v_max_rewind_age = __pyx_PyFloat_AsDouble(values[13]); if (unlikely((__pyx_v_max_rewind_age == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 90, __pyx_L3_error) + } else { + __pyx_v_max_rewind_age = ((double)1.0); + } + __pyx_v_logger = values[14]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 7, 15, __pyx_nargs); __PYX_ERR(0, 87, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_gen_dir), (&PyUnicode_Type), 1, "gen_dir", 1))) __PYX_ERR(0, 87, __pyx_L1_error) + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_name), (&PyUnicode_Type), 1, "name", 1))) __PYX_ERR(0, 87, __pyx_L1_error) + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_Q), __pyx_ptype_5numpy_ndarray, 1, "Q", 0))) __PYX_ERR(0, 87, __pyx_L1_error) + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_x_initial), __pyx_ptype_5numpy_ndarray, 1, "x_initial", 0))) __PYX_ERR(0, 88, __pyx_L1_error) + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_P_initial), __pyx_ptype_5numpy_ndarray, 1, "P_initial", 0))) __PYX_ERR(0, 88, __pyx_L1_error) + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_maha_test_kinds), (&PyList_Type), 1, "maha_test_kinds", 1))) __PYX_ERR(0, 89, __pyx_L1_error) + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_quaternion_idxs), (&PyList_Type), 1, "quaternion_idxs", 1))) __PYX_ERR(0, 90, __pyx_L1_error) + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_global_vars), (&PyList_Type), 1, "global_vars", 1))) __PYX_ERR(0, 90, __pyx_L1_error) + __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx___cinit__(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self), __pyx_v_gen_dir, __pyx_v_name, __pyx_v_Q, __pyx_v_x_initial, __pyx_v_P_initial, __pyx_v_dim_main, __pyx_v_dim_main_err, __pyx_v_N, __pyx_v_dim_augment, __pyx_v_dim_augment_err, __pyx_v_maha_test_kinds, __pyx_v_quaternion_idxs, __pyx_v_global_vars, __pyx_v_max_rewind_age, __pyx_v_logger); + + /* "rednose/helpers/ekf_sym_pyx.pyx":87 + * cdef class EKF_sym_pyx: + * cdef EKFSym* ekf + * def __cinit__(self, str gen_dir, str name, np.ndarray[np.float64_t, ndim=2] Q, # <<<<<<<<<<<<<< + * np.ndarray[np.float64_t, ndim=1] x_initial, np.ndarray[np.float64_t, ndim=2] P_initial, int dim_main, + * int dim_main_err, int N=0, int dim_augment=0, int dim_augment_err=0, list maha_test_kinds=[], + */ + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = -1; + __pyx_L0:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx___cinit__(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, PyObject *__pyx_v_gen_dir, PyObject *__pyx_v_name, PyArrayObject *__pyx_v_Q, PyArrayObject *__pyx_v_x_initial, PyArrayObject *__pyx_v_P_initial, int __pyx_v_dim_main, int __pyx_v_dim_main_err, int __pyx_v_N, int __pyx_v_dim_augment, int __pyx_v_dim_augment_err, PyObject *__pyx_v_maha_test_kinds, PyObject *__pyx_v_quaternion_idxs, PyObject *__pyx_v_global_vars, double __pyx_v_max_rewind_age, CYTHON_UNUSED PyObject *__pyx_v_logger) { + PyArrayObject *__pyx_v_Q_b = 0; + PyArrayObject *__pyx_v_x_initial_b = 0; + PyArrayObject *__pyx_v_P_initial_b = 0; + PyObject *__pyx_7genexpr__pyx_v_x = NULL; + __Pyx_LocalBuf_ND __pyx_pybuffernd_P_initial; + __Pyx_Buffer __pyx_pybuffer_P_initial; + __Pyx_LocalBuf_ND __pyx_pybuffernd_P_initial_b; + __Pyx_Buffer __pyx_pybuffer_P_initial_b; + __Pyx_LocalBuf_ND __pyx_pybuffernd_Q; + __Pyx_Buffer __pyx_pybuffer_Q; + __Pyx_LocalBuf_ND __pyx_pybuffernd_Q_b; + __Pyx_Buffer __pyx_pybuffer_Q_b; + __Pyx_LocalBuf_ND __pyx_pybuffernd_x_initial; + __Pyx_Buffer __pyx_pybuffer_x_initial; + __Pyx_LocalBuf_ND __pyx_pybuffernd_x_initial_b; + __Pyx_Buffer __pyx_pybuffer_x_initial_b; + int __pyx_r; + __Pyx_TraceDeclarations + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + std::string __pyx_t_2; + std::string __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyArrayObject *__pyx_t_8 = NULL; + PyArrayObject *__pyx_t_9 = NULL; + PyArrayObject *__pyx_t_10 = NULL; + char *__pyx_t_11; + npy_intp *__pyx_t_12; + npy_intp *__pyx_t_13; + char *__pyx_t_14; + npy_intp *__pyx_t_15; + char *__pyx_t_16; + npy_intp *__pyx_t_17; + npy_intp *__pyx_t_18; + std::vector __pyx_t_19; + std::vector __pyx_t_20; + Py_ssize_t __pyx_t_21; + int __pyx_t_22; + std::vector __pyx_t_23; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__cinit__", 1); + __Pyx_TraceCall("__cinit__", __pyx_f[0], 87, 0, __PYX_ERR(0, 87, __pyx_L1_error)); + __pyx_pybuffer_Q_b.pybuffer.buf = NULL; + __pyx_pybuffer_Q_b.refcount = 0; + __pyx_pybuffernd_Q_b.data = NULL; + __pyx_pybuffernd_Q_b.rcbuffer = &__pyx_pybuffer_Q_b; + __pyx_pybuffer_x_initial_b.pybuffer.buf = NULL; + __pyx_pybuffer_x_initial_b.refcount = 0; + __pyx_pybuffernd_x_initial_b.data = NULL; + __pyx_pybuffernd_x_initial_b.rcbuffer = &__pyx_pybuffer_x_initial_b; + __pyx_pybuffer_P_initial_b.pybuffer.buf = NULL; + __pyx_pybuffer_P_initial_b.refcount = 0; + __pyx_pybuffernd_P_initial_b.data = NULL; + __pyx_pybuffernd_P_initial_b.rcbuffer = &__pyx_pybuffer_P_initial_b; + __pyx_pybuffer_Q.pybuffer.buf = NULL; + __pyx_pybuffer_Q.refcount = 0; + __pyx_pybuffernd_Q.data = NULL; + __pyx_pybuffernd_Q.rcbuffer = &__pyx_pybuffer_Q; + __pyx_pybuffer_x_initial.pybuffer.buf = NULL; + __pyx_pybuffer_x_initial.refcount = 0; + __pyx_pybuffernd_x_initial.data = NULL; + __pyx_pybuffernd_x_initial.rcbuffer = &__pyx_pybuffer_x_initial; + __pyx_pybuffer_P_initial.pybuffer.buf = NULL; + __pyx_pybuffer_P_initial.refcount = 0; + __pyx_pybuffernd_P_initial.data = NULL; + __pyx_pybuffernd_P_initial.rcbuffer = &__pyx_pybuffer_P_initial; + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_Q.rcbuffer->pybuffer, (PyObject*)__pyx_v_Q, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 2, 0, __pyx_stack) == -1)) __PYX_ERR(0, 87, __pyx_L1_error) + } + __pyx_pybuffernd_Q.diminfo[0].strides = __pyx_pybuffernd_Q.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_Q.diminfo[0].shape = __pyx_pybuffernd_Q.rcbuffer->pybuffer.shape[0]; __pyx_pybuffernd_Q.diminfo[1].strides = __pyx_pybuffernd_Q.rcbuffer->pybuffer.strides[1]; __pyx_pybuffernd_Q.diminfo[1].shape = __pyx_pybuffernd_Q.rcbuffer->pybuffer.shape[1]; + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_x_initial.rcbuffer->pybuffer, (PyObject*)__pyx_v_x_initial, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 1, 0, __pyx_stack) == -1)) __PYX_ERR(0, 87, __pyx_L1_error) + } + __pyx_pybuffernd_x_initial.diminfo[0].strides = __pyx_pybuffernd_x_initial.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_x_initial.diminfo[0].shape = __pyx_pybuffernd_x_initial.rcbuffer->pybuffer.shape[0]; + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_P_initial.rcbuffer->pybuffer, (PyObject*)__pyx_v_P_initial, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 2, 0, __pyx_stack) == -1)) __PYX_ERR(0, 87, __pyx_L1_error) + } + __pyx_pybuffernd_P_initial.diminfo[0].strides = __pyx_pybuffernd_P_initial.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_P_initial.diminfo[0].shape = __pyx_pybuffernd_P_initial.rcbuffer->pybuffer.shape[0]; __pyx_pybuffernd_P_initial.diminfo[1].strides = __pyx_pybuffernd_P_initial.rcbuffer->pybuffer.strides[1]; __pyx_pybuffernd_P_initial.diminfo[1].shape = __pyx_pybuffernd_P_initial.rcbuffer->pybuffer.shape[1]; + + /* "rednose/helpers/ekf_sym_pyx.pyx":92 + * list quaternion_idxs=[], list global_vars=[], double max_rewind_age=1.0, logger=None): + * # TODO logger + * ekf_load_and_register(gen_dir.encode('utf8'), name.encode('utf8')) # <<<<<<<<<<<<<< + * + * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] Q_b = np.ascontiguousarray(Q, dtype=np.double) + */ + if (unlikely(__pyx_v_gen_dir == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); + __PYX_ERR(0, 92, __pyx_L1_error) + } + __pyx_t_1 = PyUnicode_AsUTF8String(__pyx_v_gen_dir); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 92, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_convert_string_from_py_std__in_string(__pyx_t_1); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 92, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(__pyx_v_name == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); + __PYX_ERR(0, 92, __pyx_L1_error) + } + __pyx_t_1 = PyUnicode_AsUTF8String(__pyx_v_name); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 92, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __pyx_convert_string_from_py_std__in_string(__pyx_t_1); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 92, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + ekf_load_and_register(__PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_2), __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_3)); + + /* "rednose/helpers/ekf_sym_pyx.pyx":94 + * ekf_load_and_register(gen_dir.encode('utf8'), name.encode('utf8')) + * + * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] Q_b = np.ascontiguousarray(Q, dtype=np.double) # <<<<<<<<<<<<<< + * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] x_initial_b = np.ascontiguousarray(x_initial, dtype=np.double) + * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] P_initial_b = np.ascontiguousarray(P_initial, dtype=np.double) + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 94, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 94, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = PyTuple_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 94, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF((PyObject *)__pyx_v_Q); + __Pyx_GIVEREF((PyObject *)__pyx_v_Q); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, ((PyObject *)__pyx_v_Q))) __PYX_ERR(0, 94, __pyx_L1_error); + __pyx_t_5 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 94, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_GetModuleGlobalName(__pyx_t_6, __pyx_n_s_np); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 94, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_t_6, __pyx_n_s_double); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 94, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + if (PyDict_SetItem(__pyx_t_5, __pyx_n_s_dtype, __pyx_t_7) < 0) __PYX_ERR(0, 94, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __pyx_t_7 = __Pyx_PyObject_Call(__pyx_t_4, __pyx_t_1, __pyx_t_5); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 94, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (!(likely(((__pyx_t_7) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_7, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 94, __pyx_L1_error) + __pyx_t_8 = ((PyArrayObject *)__pyx_t_7); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_Q_b.rcbuffer->pybuffer, (PyObject*)__pyx_t_8, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_C_CONTIGUOUS, 2, 0, __pyx_stack) == -1)) { + __pyx_v_Q_b = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_Q_b.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 94, __pyx_L1_error) + } else {__pyx_pybuffernd_Q_b.diminfo[0].strides = __pyx_pybuffernd_Q_b.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_Q_b.diminfo[0].shape = __pyx_pybuffernd_Q_b.rcbuffer->pybuffer.shape[0]; __pyx_pybuffernd_Q_b.diminfo[1].strides = __pyx_pybuffernd_Q_b.rcbuffer->pybuffer.strides[1]; __pyx_pybuffernd_Q_b.diminfo[1].shape = __pyx_pybuffernd_Q_b.rcbuffer->pybuffer.shape[1]; + } + } + __pyx_t_8 = 0; + __pyx_v_Q_b = ((PyArrayObject *)__pyx_t_7); + __pyx_t_7 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":95 + * + * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] Q_b = np.ascontiguousarray(Q, dtype=np.double) + * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] x_initial_b = np.ascontiguousarray(x_initial, dtype=np.double) # <<<<<<<<<<<<<< + * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] P_initial_b = np.ascontiguousarray(P_initial, dtype=np.double) + * self.ekf = new EKFSym( + */ + __Pyx_GetModuleGlobalName(__pyx_t_7, __pyx_n_s_np); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 95, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_7, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 95, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __pyx_t_7 = PyTuple_New(1); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 95, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_INCREF((PyObject *)__pyx_v_x_initial); + __Pyx_GIVEREF((PyObject *)__pyx_v_x_initial); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_7, 0, ((PyObject *)__pyx_v_x_initial))) __PYX_ERR(0, 95, __pyx_L1_error); + __pyx_t_1 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 95, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_np); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 95, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_double); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 95, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (PyDict_SetItem(__pyx_t_1, __pyx_n_s_dtype, __pyx_t_6) < 0) __PYX_ERR(0, 95, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __pyx_t_6 = __Pyx_PyObject_Call(__pyx_t_5, __pyx_t_7, __pyx_t_1); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 95, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (!(likely(((__pyx_t_6) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_6, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 95, __pyx_L1_error) + __pyx_t_9 = ((PyArrayObject *)__pyx_t_6); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_x_initial_b.rcbuffer->pybuffer, (PyObject*)__pyx_t_9, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_C_CONTIGUOUS, 1, 0, __pyx_stack) == -1)) { + __pyx_v_x_initial_b = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_x_initial_b.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 95, __pyx_L1_error) + } else {__pyx_pybuffernd_x_initial_b.diminfo[0].strides = __pyx_pybuffernd_x_initial_b.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_x_initial_b.diminfo[0].shape = __pyx_pybuffernd_x_initial_b.rcbuffer->pybuffer.shape[0]; + } + } + __pyx_t_9 = 0; + __pyx_v_x_initial_b = ((PyArrayObject *)__pyx_t_6); + __pyx_t_6 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":96 + * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] Q_b = np.ascontiguousarray(Q, dtype=np.double) + * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] x_initial_b = np.ascontiguousarray(x_initial, dtype=np.double) + * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] P_initial_b = np.ascontiguousarray(P_initial, dtype=np.double) # <<<<<<<<<<<<<< + * self.ekf = new EKFSym( + * name.encode('utf8'), + */ + __Pyx_GetModuleGlobalName(__pyx_t_6, __pyx_n_s_np); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 96, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_6, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 96, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __pyx_t_6 = PyTuple_New(1); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 96, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_INCREF((PyObject *)__pyx_v_P_initial); + __Pyx_GIVEREF((PyObject *)__pyx_v_P_initial); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_6, 0, ((PyObject *)__pyx_v_P_initial))) __PYX_ERR(0, 96, __pyx_L1_error); + __pyx_t_7 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 96, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_GetModuleGlobalName(__pyx_t_5, __pyx_n_s_np); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 96, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_double); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 96, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (PyDict_SetItem(__pyx_t_7, __pyx_n_s_dtype, __pyx_t_4) < 0) __PYX_ERR(0, 96, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyObject_Call(__pyx_t_1, __pyx_t_6, __pyx_t_7); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 96, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (!(likely(((__pyx_t_4) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_4, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 96, __pyx_L1_error) + __pyx_t_10 = ((PyArrayObject *)__pyx_t_4); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_P_initial_b.rcbuffer->pybuffer, (PyObject*)__pyx_t_10, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_C_CONTIGUOUS, 2, 0, __pyx_stack) == -1)) { + __pyx_v_P_initial_b = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_P_initial_b.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 96, __pyx_L1_error) + } else {__pyx_pybuffernd_P_initial_b.diminfo[0].strides = __pyx_pybuffernd_P_initial_b.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_P_initial_b.diminfo[0].shape = __pyx_pybuffernd_P_initial_b.rcbuffer->pybuffer.shape[0]; __pyx_pybuffernd_P_initial_b.diminfo[1].strides = __pyx_pybuffernd_P_initial_b.rcbuffer->pybuffer.strides[1]; __pyx_pybuffernd_P_initial_b.diminfo[1].shape = __pyx_pybuffernd_P_initial_b.rcbuffer->pybuffer.shape[1]; + } + } + __pyx_t_10 = 0; + __pyx_v_P_initial_b = ((PyArrayObject *)__pyx_t_4); + __pyx_t_4 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":98 + * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] P_initial_b = np.ascontiguousarray(P_initial, dtype=np.double) + * self.ekf = new EKFSym( + * name.encode('utf8'), # <<<<<<<<<<<<<< + * MapMatrixXdr( Q_b.data, Q.shape[0], Q.shape[1]), + * MapVectorXd( x_initial_b.data, x_initial.shape[0]), + */ + if (unlikely(__pyx_v_name == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); + __PYX_ERR(0, 98, __pyx_L1_error) + } + __pyx_t_4 = PyUnicode_AsUTF8String(__pyx_v_name); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 98, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_3 = __pyx_convert_string_from_py_std__in_string(__pyx_t_4); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 98, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":99 + * self.ekf = new EKFSym( + * name.encode('utf8'), + * MapMatrixXdr( Q_b.data, Q.shape[0], Q.shape[1]), # <<<<<<<<<<<<<< + * MapVectorXd( x_initial_b.data, x_initial.shape[0]), + * MapMatrixXdr( P_initial_b.data, P_initial.shape[0], P_initial.shape[1]), + */ + __pyx_t_11 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_Q_b)); if (unlikely(__pyx_t_11 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 99, __pyx_L1_error) + __pyx_t_12 = __pyx_f_5numpy_7ndarray_5shape_shape(((PyArrayObject *)__pyx_v_Q)); if (unlikely(__pyx_t_12 == ((npy_intp *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 99, __pyx_L1_error) + __pyx_t_13 = __pyx_f_5numpy_7ndarray_5shape_shape(((PyArrayObject *)__pyx_v_Q)); if (unlikely(__pyx_t_13 == ((npy_intp *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 99, __pyx_L1_error) + + /* "rednose/helpers/ekf_sym_pyx.pyx":100 + * name.encode('utf8'), + * MapMatrixXdr( Q_b.data, Q.shape[0], Q.shape[1]), + * MapVectorXd( x_initial_b.data, x_initial.shape[0]), # <<<<<<<<<<<<<< + * MapMatrixXdr( P_initial_b.data, P_initial.shape[0], P_initial.shape[1]), + * dim_main, + */ + __pyx_t_14 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_x_initial_b)); if (unlikely(__pyx_t_14 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 100, __pyx_L1_error) + __pyx_t_15 = __pyx_f_5numpy_7ndarray_5shape_shape(((PyArrayObject *)__pyx_v_x_initial)); if (unlikely(__pyx_t_15 == ((npy_intp *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 100, __pyx_L1_error) + + /* "rednose/helpers/ekf_sym_pyx.pyx":101 + * MapMatrixXdr( Q_b.data, Q.shape[0], Q.shape[1]), + * MapVectorXd( x_initial_b.data, x_initial.shape[0]), + * MapMatrixXdr( P_initial_b.data, P_initial.shape[0], P_initial.shape[1]), # <<<<<<<<<<<<<< + * dim_main, + * dim_main_err, + */ + __pyx_t_16 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_P_initial_b)); if (unlikely(__pyx_t_16 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 101, __pyx_L1_error) + __pyx_t_17 = __pyx_f_5numpy_7ndarray_5shape_shape(((PyArrayObject *)__pyx_v_P_initial)); if (unlikely(__pyx_t_17 == ((npy_intp *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 101, __pyx_L1_error) + __pyx_t_18 = __pyx_f_5numpy_7ndarray_5shape_shape(((PyArrayObject *)__pyx_v_P_initial)); if (unlikely(__pyx_t_18 == ((npy_intp *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 101, __pyx_L1_error) + + /* "rednose/helpers/ekf_sym_pyx.pyx":107 + * dim_augment, + * dim_augment_err, + * maha_test_kinds, # <<<<<<<<<<<<<< + * quaternion_idxs, + * [x.encode('utf8') for x in global_vars], + */ + __pyx_t_19 = __pyx_convert_vector_from_py_int(__pyx_v_maha_test_kinds); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 107, __pyx_L1_error) + + /* "rednose/helpers/ekf_sym_pyx.pyx":108 + * dim_augment_err, + * maha_test_kinds, + * quaternion_idxs, # <<<<<<<<<<<<<< + * [x.encode('utf8') for x in global_vars], + * max_rewind_age + */ + __pyx_t_20 = __pyx_convert_vector_from_py_int(__pyx_v_quaternion_idxs); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 108, __pyx_L1_error) + { /* enter inner scope */ + + /* "rednose/helpers/ekf_sym_pyx.pyx":109 + * maha_test_kinds, + * quaternion_idxs, + * [x.encode('utf8') for x in global_vars], # <<<<<<<<<<<<<< + * max_rewind_age + * ) + */ + __pyx_t_4 = PyList_New(0); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 109, __pyx_L5_error) + __Pyx_GOTREF(__pyx_t_4); + if (unlikely(__pyx_v_global_vars == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not iterable"); + __PYX_ERR(0, 109, __pyx_L5_error) + } + __pyx_t_7 = __pyx_v_global_vars; __Pyx_INCREF(__pyx_t_7); + __pyx_t_21 = 0; + for (;;) { + { + Py_ssize_t __pyx_temp = __Pyx_PyList_GET_SIZE(__pyx_t_7); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 109, __pyx_L5_error) + #endif + if (__pyx_t_21 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_6 = PyList_GET_ITEM(__pyx_t_7, __pyx_t_21); __Pyx_INCREF(__pyx_t_6); __pyx_t_21++; if (unlikely((0 < 0))) __PYX_ERR(0, 109, __pyx_L5_error) + #else + __pyx_t_6 = __Pyx_PySequence_ITEM(__pyx_t_7, __pyx_t_21); __pyx_t_21++; if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 109, __pyx_L5_error) + __Pyx_GOTREF(__pyx_t_6); + #endif + __Pyx_XDECREF_SET(__pyx_7genexpr__pyx_v_x, __pyx_t_6); + __pyx_t_6 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_7genexpr__pyx_v_x, __pyx_n_s_encode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 109, __pyx_L5_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = NULL; + __pyx_t_22 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_22 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_5, __pyx_n_u_utf8}; + __pyx_t_6 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_22, 1+__pyx_t_22); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 109, __pyx_L5_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + if (unlikely(__Pyx_ListComp_Append(__pyx_t_4, (PyObject*)__pyx_t_6))) __PYX_ERR(0, 109, __pyx_L5_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_XDECREF(__pyx_7genexpr__pyx_v_x); __pyx_7genexpr__pyx_v_x = 0; + goto __pyx_L9_exit_scope; + __pyx_L5_error:; + __Pyx_XDECREF(__pyx_7genexpr__pyx_v_x); __pyx_7genexpr__pyx_v_x = 0; + goto __pyx_L1_error; + __pyx_L9_exit_scope:; + } /* exit inner scope */ + __pyx_t_23 = __pyx_convert_vector_from_py_std_3a__3a_string(__pyx_t_4); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 109, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":97 + * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] x_initial_b = np.ascontiguousarray(x_initial, dtype=np.double) + * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] P_initial_b = np.ascontiguousarray(P_initial, dtype=np.double) + * self.ekf = new EKFSym( # <<<<<<<<<<<<<< + * name.encode('utf8'), + * MapMatrixXdr( Q_b.data, Q.shape[0], Q.shape[1]), + */ + __pyx_v_self->ekf = new EKFS::EKFSym(__pyx_t_3, Eigen::Map >(((double *)__pyx_t_11), (__pyx_t_12[0]), (__pyx_t_13[1])), Eigen::Map(((double *)__pyx_t_14), (__pyx_t_15[0])), Eigen::Map >(((double *)__pyx_t_16), (__pyx_t_17[0]), (__pyx_t_18[1])), __pyx_v_dim_main, __pyx_v_dim_main_err, __pyx_v_N, __pyx_v_dim_augment, __pyx_v_dim_augment_err, __pyx_t_19, __pyx_t_20, __pyx_t_23, __pyx_v_max_rewind_age); + + /* "rednose/helpers/ekf_sym_pyx.pyx":87 + * cdef class EKF_sym_pyx: + * cdef EKFSym* ekf + * def __cinit__(self, str gen_dir, str name, np.ndarray[np.float64_t, ndim=2] Q, # <<<<<<<<<<<<<< + * np.ndarray[np.float64_t, ndim=1] x_initial, np.ndarray[np.float64_t, ndim=2] P_initial, int dim_main, + * int dim_main_err, int N=0, int dim_augment=0, int dim_augment_err=0, list maha_test_kinds=[], + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_P_initial.rcbuffer->pybuffer); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_P_initial_b.rcbuffer->pybuffer); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_Q.rcbuffer->pybuffer); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_Q_b.rcbuffer->pybuffer); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_x_initial.rcbuffer->pybuffer); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_x_initial_b.rcbuffer->pybuffer); + __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + goto __pyx_L2; + __pyx_L0:; + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_P_initial.rcbuffer->pybuffer); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_P_initial_b.rcbuffer->pybuffer); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_Q.rcbuffer->pybuffer); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_Q_b.rcbuffer->pybuffer); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_x_initial.rcbuffer->pybuffer); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_x_initial_b.rcbuffer->pybuffer); + __pyx_L2:; + __Pyx_XDECREF((PyObject *)__pyx_v_Q_b); + __Pyx_XDECREF((PyObject *)__pyx_v_x_initial_b); + __Pyx_XDECREF((PyObject *)__pyx_v_P_initial_b); + __Pyx_XDECREF(__pyx_7genexpr__pyx_v_x); + __Pyx_TraceReturn(Py_None, 0); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "rednose/helpers/ekf_sym_pyx.pyx":113 + * ) + * + * def init_state(self, np.ndarray[np.float64_t, ndim=1] state, np.ndarray[np.float64_t, ndim=2] covs, filter_time): # <<<<<<<<<<<<<< + * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] state_b = np.ascontiguousarray(state, dtype=np.double) + * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] covs_b = np.ascontiguousarray(covs, dtype=np.double) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_3init_state(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_3init_state = {"init_state", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_3init_state, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_3init_state(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyArrayObject *__pyx_v_state = 0; + PyArrayObject *__pyx_v_covs = 0; + PyObject *__pyx_v_filter_time = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("init_state (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_state,&__pyx_n_s_covs,&__pyx_n_s_filter_time,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 113, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_covs)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 113, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("init_state", 1, 3, 3, 1); __PYX_ERR(0, 113, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_filter_time)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 113, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("init_state", 1, 3, 3, 2); __PYX_ERR(0, 113, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "init_state") < 0)) __PYX_ERR(0, 113, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + } + __pyx_v_state = ((PyArrayObject *)values[0]); + __pyx_v_covs = ((PyArrayObject *)values[1]); + __pyx_v_filter_time = values[2]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("init_state", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 113, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.init_state", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_state), __pyx_ptype_5numpy_ndarray, 1, "state", 0))) __PYX_ERR(0, 113, __pyx_L1_error) + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_covs), __pyx_ptype_5numpy_ndarray, 1, "covs", 0))) __PYX_ERR(0, 113, __pyx_L1_error) + __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_2init_state(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self), __pyx_v_state, __pyx_v_covs, __pyx_v_filter_time); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = NULL; + __pyx_L0:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_2init_state(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, PyArrayObject *__pyx_v_state, PyArrayObject *__pyx_v_covs, PyObject *__pyx_v_filter_time) { + PyArrayObject *__pyx_v_state_b = 0; + PyArrayObject *__pyx_v_covs_b = 0; + __Pyx_LocalBuf_ND __pyx_pybuffernd_covs; + __Pyx_Buffer __pyx_pybuffer_covs; + __Pyx_LocalBuf_ND __pyx_pybuffernd_covs_b; + __Pyx_Buffer __pyx_pybuffer_covs_b; + __Pyx_LocalBuf_ND __pyx_pybuffernd_state; + __Pyx_Buffer __pyx_pybuffer_state; + __Pyx_LocalBuf_ND __pyx_pybuffernd_state_b; + __Pyx_Buffer __pyx_pybuffer_state_b; + PyObject *__pyx_r = NULL; + __Pyx_TraceDeclarations + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyArrayObject *__pyx_t_6 = NULL; + PyArrayObject *__pyx_t_7 = NULL; + char *__pyx_t_8; + npy_intp *__pyx_t_9; + char *__pyx_t_10; + npy_intp *__pyx_t_11; + npy_intp *__pyx_t_12; + double __pyx_t_13; + int __pyx_t_14; + double __pyx_t_15; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_TraceFrameInit(__pyx_codeobj__20) + __Pyx_RefNannySetupContext("init_state", 1); + __Pyx_TraceCall("init_state", __pyx_f[0], 113, 0, __PYX_ERR(0, 113, __pyx_L1_error)); + __pyx_pybuffer_state_b.pybuffer.buf = NULL; + __pyx_pybuffer_state_b.refcount = 0; + __pyx_pybuffernd_state_b.data = NULL; + __pyx_pybuffernd_state_b.rcbuffer = &__pyx_pybuffer_state_b; + __pyx_pybuffer_covs_b.pybuffer.buf = NULL; + __pyx_pybuffer_covs_b.refcount = 0; + __pyx_pybuffernd_covs_b.data = NULL; + __pyx_pybuffernd_covs_b.rcbuffer = &__pyx_pybuffer_covs_b; + __pyx_pybuffer_state.pybuffer.buf = NULL; + __pyx_pybuffer_state.refcount = 0; + __pyx_pybuffernd_state.data = NULL; + __pyx_pybuffernd_state.rcbuffer = &__pyx_pybuffer_state; + __pyx_pybuffer_covs.pybuffer.buf = NULL; + __pyx_pybuffer_covs.refcount = 0; + __pyx_pybuffernd_covs.data = NULL; + __pyx_pybuffernd_covs.rcbuffer = &__pyx_pybuffer_covs; + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_state.rcbuffer->pybuffer, (PyObject*)__pyx_v_state, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 1, 0, __pyx_stack) == -1)) __PYX_ERR(0, 113, __pyx_L1_error) + } + __pyx_pybuffernd_state.diminfo[0].strides = __pyx_pybuffernd_state.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_state.diminfo[0].shape = __pyx_pybuffernd_state.rcbuffer->pybuffer.shape[0]; + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_covs.rcbuffer->pybuffer, (PyObject*)__pyx_v_covs, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 2, 0, __pyx_stack) == -1)) __PYX_ERR(0, 113, __pyx_L1_error) + } + __pyx_pybuffernd_covs.diminfo[0].strides = __pyx_pybuffernd_covs.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_covs.diminfo[0].shape = __pyx_pybuffernd_covs.rcbuffer->pybuffer.shape[0]; __pyx_pybuffernd_covs.diminfo[1].strides = __pyx_pybuffernd_covs.rcbuffer->pybuffer.strides[1]; __pyx_pybuffernd_covs.diminfo[1].shape = __pyx_pybuffernd_covs.rcbuffer->pybuffer.shape[1]; + + /* "rednose/helpers/ekf_sym_pyx.pyx":114 + * + * def init_state(self, np.ndarray[np.float64_t, ndim=1] state, np.ndarray[np.float64_t, ndim=2] covs, filter_time): + * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] state_b = np.ascontiguousarray(state, dtype=np.double) # <<<<<<<<<<<<<< + * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] covs_b = np.ascontiguousarray(covs, dtype=np.double) + * self.ekf.init_state( + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 114, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 114, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = PyTuple_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 114, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF((PyObject *)__pyx_v_state); + __Pyx_GIVEREF((PyObject *)__pyx_v_state); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, ((PyObject *)__pyx_v_state))) __PYX_ERR(0, 114, __pyx_L1_error); + __pyx_t_3 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 114, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_np); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 114, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_double); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 114, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_dtype, __pyx_t_5) < 0) __PYX_ERR(0, 114, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_5 = __Pyx_PyObject_Call(__pyx_t_2, __pyx_t_1, __pyx_t_3); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 114, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + if (!(likely(((__pyx_t_5) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_5, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 114, __pyx_L1_error) + __pyx_t_6 = ((PyArrayObject *)__pyx_t_5); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_state_b.rcbuffer->pybuffer, (PyObject*)__pyx_t_6, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_C_CONTIGUOUS, 1, 0, __pyx_stack) == -1)) { + __pyx_v_state_b = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_state_b.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 114, __pyx_L1_error) + } else {__pyx_pybuffernd_state_b.diminfo[0].strides = __pyx_pybuffernd_state_b.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_state_b.diminfo[0].shape = __pyx_pybuffernd_state_b.rcbuffer->pybuffer.shape[0]; + } + } + __pyx_t_6 = 0; + __pyx_v_state_b = ((PyArrayObject *)__pyx_t_5); + __pyx_t_5 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":115 + * def init_state(self, np.ndarray[np.float64_t, ndim=1] state, np.ndarray[np.float64_t, ndim=2] covs, filter_time): + * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] state_b = np.ascontiguousarray(state, dtype=np.double) + * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] covs_b = np.ascontiguousarray(covs, dtype=np.double) # <<<<<<<<<<<<<< + * self.ekf.init_state( + * MapVectorXd( state_b.data, state.shape[0]), + */ + __Pyx_GetModuleGlobalName(__pyx_t_5, __pyx_n_s_np); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 115, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 115, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_5 = PyTuple_New(1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 115, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_INCREF((PyObject *)__pyx_v_covs); + __Pyx_GIVEREF((PyObject *)__pyx_v_covs); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_5, 0, ((PyObject *)__pyx_v_covs))) __PYX_ERR(0, 115, __pyx_L1_error); + __pyx_t_1 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 115, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_np); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 115, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_double); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 115, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + if (PyDict_SetItem(__pyx_t_1, __pyx_n_s_dtype, __pyx_t_4) < 0) __PYX_ERR(0, 115, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyObject_Call(__pyx_t_3, __pyx_t_5, __pyx_t_1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 115, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (!(likely(((__pyx_t_4) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_4, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 115, __pyx_L1_error) + __pyx_t_7 = ((PyArrayObject *)__pyx_t_4); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_covs_b.rcbuffer->pybuffer, (PyObject*)__pyx_t_7, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_C_CONTIGUOUS, 2, 0, __pyx_stack) == -1)) { + __pyx_v_covs_b = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_covs_b.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 115, __pyx_L1_error) + } else {__pyx_pybuffernd_covs_b.diminfo[0].strides = __pyx_pybuffernd_covs_b.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_covs_b.diminfo[0].shape = __pyx_pybuffernd_covs_b.rcbuffer->pybuffer.shape[0]; __pyx_pybuffernd_covs_b.diminfo[1].strides = __pyx_pybuffernd_covs_b.rcbuffer->pybuffer.strides[1]; __pyx_pybuffernd_covs_b.diminfo[1].shape = __pyx_pybuffernd_covs_b.rcbuffer->pybuffer.shape[1]; + } + } + __pyx_t_7 = 0; + __pyx_v_covs_b = ((PyArrayObject *)__pyx_t_4); + __pyx_t_4 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":117 + * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] covs_b = np.ascontiguousarray(covs, dtype=np.double) + * self.ekf.init_state( + * MapVectorXd( state_b.data, state.shape[0]), # <<<<<<<<<<<<<< + * MapMatrixXdr( covs_b.data, covs.shape[0], covs.shape[1]), + * np.nan if filter_time is None else filter_time + */ + __pyx_t_8 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_state_b)); if (unlikely(__pyx_t_8 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 117, __pyx_L1_error) + __pyx_t_9 = __pyx_f_5numpy_7ndarray_5shape_shape(((PyArrayObject *)__pyx_v_state)); if (unlikely(__pyx_t_9 == ((npy_intp *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 117, __pyx_L1_error) + + /* "rednose/helpers/ekf_sym_pyx.pyx":118 + * self.ekf.init_state( + * MapVectorXd( state_b.data, state.shape[0]), + * MapMatrixXdr( covs_b.data, covs.shape[0], covs.shape[1]), # <<<<<<<<<<<<<< + * np.nan if filter_time is None else filter_time + * ) + */ + __pyx_t_10 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_covs_b)); if (unlikely(__pyx_t_10 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 118, __pyx_L1_error) + __pyx_t_11 = __pyx_f_5numpy_7ndarray_5shape_shape(((PyArrayObject *)__pyx_v_covs)); if (unlikely(__pyx_t_11 == ((npy_intp *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 118, __pyx_L1_error) + __pyx_t_12 = __pyx_f_5numpy_7ndarray_5shape_shape(((PyArrayObject *)__pyx_v_covs)); if (unlikely(__pyx_t_12 == ((npy_intp *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 118, __pyx_L1_error) + + /* "rednose/helpers/ekf_sym_pyx.pyx":119 + * MapVectorXd( state_b.data, state.shape[0]), + * MapMatrixXdr( covs_b.data, covs.shape[0], covs.shape[1]), + * np.nan if filter_time is None else filter_time # <<<<<<<<<<<<<< + * ) + * + */ + __pyx_t_14 = (__pyx_v_filter_time == Py_None); + if (__pyx_t_14) { + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_np); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 119, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_nan); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 119, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_15 = __pyx_PyFloat_AsDouble(__pyx_t_1); if (unlikely((__pyx_t_15 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 119, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_13 = __pyx_t_15; + } else { + __pyx_t_15 = __pyx_PyFloat_AsDouble(__pyx_v_filter_time); if (unlikely((__pyx_t_15 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 119, __pyx_L1_error) + __pyx_t_13 = __pyx_t_15; + } + + /* "rednose/helpers/ekf_sym_pyx.pyx":116 + * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] state_b = np.ascontiguousarray(state, dtype=np.double) + * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] covs_b = np.ascontiguousarray(covs, dtype=np.double) + * self.ekf.init_state( # <<<<<<<<<<<<<< + * MapVectorXd( state_b.data, state.shape[0]), + * MapMatrixXdr( covs_b.data, covs.shape[0], covs.shape[1]), + */ + __pyx_v_self->ekf->init_state(Eigen::Map(((double *)__pyx_t_8), (__pyx_t_9[0])), Eigen::Map >(((double *)__pyx_t_10), (__pyx_t_11[0]), (__pyx_t_12[1])), __pyx_t_13); + + /* "rednose/helpers/ekf_sym_pyx.pyx":113 + * ) + * + * def init_state(self, np.ndarray[np.float64_t, ndim=1] state, np.ndarray[np.float64_t, ndim=2] covs, filter_time): # <<<<<<<<<<<<<< + * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] state_b = np.ascontiguousarray(state, dtype=np.double) + * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] covs_b = np.ascontiguousarray(covs, dtype=np.double) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_covs.rcbuffer->pybuffer); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_covs_b.rcbuffer->pybuffer); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_state.rcbuffer->pybuffer); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_state_b.rcbuffer->pybuffer); + __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.init_state", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + goto __pyx_L2; + __pyx_L0:; + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_covs.rcbuffer->pybuffer); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_covs_b.rcbuffer->pybuffer); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_state.rcbuffer->pybuffer); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_state_b.rcbuffer->pybuffer); + __pyx_L2:; + __Pyx_XDECREF((PyObject *)__pyx_v_state_b); + __Pyx_XDECREF((PyObject *)__pyx_v_covs_b); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_TraceReturn(__pyx_r, 0); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "rednose/helpers/ekf_sym_pyx.pyx":122 + * ) + * + * def state(self): # <<<<<<<<<<<<<< + * cdef np.ndarray res = vector_to_numpy(self.ekf.state()) + * return res + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_5state(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_5state = {"state", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_5state, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_5state(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("state (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("state", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "state", 0))) return NULL; + __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_4state(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_4state(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self) { + PyArrayObject *__pyx_v_res = 0; + PyObject *__pyx_r = NULL; + __Pyx_TraceDeclarations + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_TraceFrameInit(__pyx_codeobj__21) + __Pyx_RefNannySetupContext("state", 1); + __Pyx_TraceCall("state", __pyx_f[0], 122, 0, __PYX_ERR(0, 122, __pyx_L1_error)); + + /* "rednose/helpers/ekf_sym_pyx.pyx":123 + * + * def state(self): + * cdef np.ndarray res = vector_to_numpy(self.ekf.state()) # <<<<<<<<<<<<<< + * return res + * + */ + __pyx_t_1 = ((PyObject *)__pyx_f_7rednose_7helpers_11ekf_sym_pyx_vector_to_numpy(__pyx_v_self->ekf->state())); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 123, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_res = ((PyArrayObject *)__pyx_t_1); + __pyx_t_1 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":124 + * def state(self): + * cdef np.ndarray res = vector_to_numpy(self.ekf.state()) + * return res # <<<<<<<<<<<<<< + * + * def covs(self): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_res); + __pyx_r = ((PyObject *)__pyx_v_res); + goto __pyx_L0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":122 + * ) + * + * def state(self): # <<<<<<<<<<<<<< + * cdef np.ndarray res = vector_to_numpy(self.ekf.state()) + * return res + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.state", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_res); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_TraceReturn(__pyx_r, 0); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "rednose/helpers/ekf_sym_pyx.pyx":126 + * return res + * + * def covs(self): # <<<<<<<<<<<<<< + * return matrix_to_numpy(self.ekf.covs()) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_7covs(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_7covs = {"covs", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_7covs, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_7covs(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("covs (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("covs", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "covs", 0))) return NULL; + __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_6covs(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_6covs(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_TraceDeclarations + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_TraceFrameInit(__pyx_codeobj__22) + __Pyx_RefNannySetupContext("covs", 1); + __Pyx_TraceCall("covs", __pyx_f[0], 126, 0, __PYX_ERR(0, 126, __pyx_L1_error)); + + /* "rednose/helpers/ekf_sym_pyx.pyx":127 + * + * def covs(self): + * return matrix_to_numpy(self.ekf.covs()) # <<<<<<<<<<<<<< + * + * def set_filter_time(self, double t): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = ((PyObject *)__pyx_f_7rednose_7helpers_11ekf_sym_pyx_matrix_to_numpy(__pyx_v_self->ekf->covs())); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 127, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":126 + * return res + * + * def covs(self): # <<<<<<<<<<<<<< + * return matrix_to_numpy(self.ekf.covs()) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.covs", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_TraceReturn(__pyx_r, 0); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "rednose/helpers/ekf_sym_pyx.pyx":129 + * return matrix_to_numpy(self.ekf.covs()) + * + * def set_filter_time(self, double t): # <<<<<<<<<<<<<< + * self.ekf.set_filter_time(t) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_9set_filter_time(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_9set_filter_time = {"set_filter_time", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_9set_filter_time, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_9set_filter_time(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + double __pyx_v_t; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("set_filter_time (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_t,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_t)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 129, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "set_filter_time") < 0)) __PYX_ERR(0, 129, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_t = __pyx_PyFloat_AsDouble(values[0]); if (unlikely((__pyx_v_t == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 129, __pyx_L3_error) + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("set_filter_time", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 129, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.set_filter_time", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_8set_filter_time(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self), __pyx_v_t); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_8set_filter_time(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, double __pyx_v_t) { + PyObject *__pyx_r = NULL; + __Pyx_TraceDeclarations + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_TraceFrameInit(__pyx_codeobj__23) + __Pyx_RefNannySetupContext("set_filter_time", 1); + __Pyx_TraceCall("set_filter_time", __pyx_f[0], 129, 0, __PYX_ERR(0, 129, __pyx_L1_error)); + + /* "rednose/helpers/ekf_sym_pyx.pyx":130 + * + * def set_filter_time(self, double t): + * self.ekf.set_filter_time(t) # <<<<<<<<<<<<<< + * + * def get_filter_time(self): + */ + __pyx_v_self->ekf->set_filter_time(__pyx_v_t); + + /* "rednose/helpers/ekf_sym_pyx.pyx":129 + * return matrix_to_numpy(self.ekf.covs()) + * + * def set_filter_time(self, double t): # <<<<<<<<<<<<<< + * self.ekf.set_filter_time(t) + * + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.set_filter_time", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_TraceReturn(__pyx_r, 0); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "rednose/helpers/ekf_sym_pyx.pyx":132 + * self.ekf.set_filter_time(t) + * + * def get_filter_time(self): # <<<<<<<<<<<<<< + * return self.ekf.get_filter_time() + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_11get_filter_time(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_11get_filter_time = {"get_filter_time", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_11get_filter_time, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_11get_filter_time(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("get_filter_time (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("get_filter_time", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "get_filter_time", 0))) return NULL; + __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_10get_filter_time(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_10get_filter_time(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_TraceDeclarations + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_TraceFrameInit(__pyx_codeobj__24) + __Pyx_RefNannySetupContext("get_filter_time", 1); + __Pyx_TraceCall("get_filter_time", __pyx_f[0], 132, 0, __PYX_ERR(0, 132, __pyx_L1_error)); + + /* "rednose/helpers/ekf_sym_pyx.pyx":133 + * + * def get_filter_time(self): + * return self.ekf.get_filter_time() # <<<<<<<<<<<<<< + * + * def set_global(self, str global_var, double val): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyFloat_FromDouble(__pyx_v_self->ekf->get_filter_time()); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 133, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":132 + * self.ekf.set_filter_time(t) + * + * def get_filter_time(self): # <<<<<<<<<<<<<< + * return self.ekf.get_filter_time() + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.get_filter_time", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_TraceReturn(__pyx_r, 0); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "rednose/helpers/ekf_sym_pyx.pyx":135 + * return self.ekf.get_filter_time() + * + * def set_global(self, str global_var, double val): # <<<<<<<<<<<<<< + * self.ekf.set_global(global_var.encode('utf8'), val) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_13set_global(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_13set_global = {"set_global", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_13set_global, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_13set_global(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_global_var = 0; + double __pyx_v_val; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[2] = {0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("set_global (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_global_var,&__pyx_n_s_val,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_global_var)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 135, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_val)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 135, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("set_global", 1, 2, 2, 1); __PYX_ERR(0, 135, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "set_global") < 0)) __PYX_ERR(0, 135, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 2)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + } + __pyx_v_global_var = ((PyObject*)values[0]); + __pyx_v_val = __pyx_PyFloat_AsDouble(values[1]); if (unlikely((__pyx_v_val == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 135, __pyx_L3_error) + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("set_global", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 135, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.set_global", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_global_var), (&PyUnicode_Type), 1, "global_var", 1))) __PYX_ERR(0, 135, __pyx_L1_error) + __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_12set_global(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self), __pyx_v_global_var, __pyx_v_val); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = NULL; + __pyx_L0:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_12set_global(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, PyObject *__pyx_v_global_var, double __pyx_v_val) { + PyObject *__pyx_r = NULL; + __Pyx_TraceDeclarations + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + std::string __pyx_t_2; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_TraceFrameInit(__pyx_codeobj__25) + __Pyx_RefNannySetupContext("set_global", 1); + __Pyx_TraceCall("set_global", __pyx_f[0], 135, 0, __PYX_ERR(0, 135, __pyx_L1_error)); + + /* "rednose/helpers/ekf_sym_pyx.pyx":136 + * + * def set_global(self, str global_var, double val): + * self.ekf.set_global(global_var.encode('utf8'), val) # <<<<<<<<<<<<<< + * + * def reset_rewind(self): + */ + if (unlikely(__pyx_v_global_var == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); + __PYX_ERR(0, 136, __pyx_L1_error) + } + __pyx_t_1 = PyUnicode_AsUTF8String(__pyx_v_global_var); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 136, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __pyx_convert_string_from_py_std__in_string(__pyx_t_1); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 136, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_self->ekf->set_global(__PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_2), __pyx_v_val); + + /* "rednose/helpers/ekf_sym_pyx.pyx":135 + * return self.ekf.get_filter_time() + * + * def set_global(self, str global_var, double val): # <<<<<<<<<<<<<< + * self.ekf.set_global(global_var.encode('utf8'), val) + * + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.set_global", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_TraceReturn(__pyx_r, 0); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "rednose/helpers/ekf_sym_pyx.pyx":138 + * self.ekf.set_global(global_var.encode('utf8'), val) + * + * def reset_rewind(self): # <<<<<<<<<<<<<< + * self.ekf.reset_rewind() + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_15reset_rewind(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_15reset_rewind = {"reset_rewind", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_15reset_rewind, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_15reset_rewind(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("reset_rewind (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("reset_rewind", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "reset_rewind", 0))) return NULL; + __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_14reset_rewind(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_14reset_rewind(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_TraceDeclarations + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_TraceFrameInit(__pyx_codeobj__26) + __Pyx_RefNannySetupContext("reset_rewind", 1); + __Pyx_TraceCall("reset_rewind", __pyx_f[0], 138, 0, __PYX_ERR(0, 138, __pyx_L1_error)); + + /* "rednose/helpers/ekf_sym_pyx.pyx":139 + * + * def reset_rewind(self): + * self.ekf.reset_rewind() # <<<<<<<<<<<<<< + * + * def predict(self, double t): + */ + __pyx_v_self->ekf->reset_rewind(); + + /* "rednose/helpers/ekf_sym_pyx.pyx":138 + * self.ekf.set_global(global_var.encode('utf8'), val) + * + * def reset_rewind(self): # <<<<<<<<<<<<<< + * self.ekf.reset_rewind() + * + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.reset_rewind", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_TraceReturn(__pyx_r, 0); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "rednose/helpers/ekf_sym_pyx.pyx":141 + * self.ekf.reset_rewind() + * + * def predict(self, double t): # <<<<<<<<<<<<<< + * self.ekf.predict(t) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_17predict(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_17predict = {"predict", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_17predict, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_17predict(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + double __pyx_v_t; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("predict (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_t,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_t)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 141, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "predict") < 0)) __PYX_ERR(0, 141, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_t = __pyx_PyFloat_AsDouble(values[0]); if (unlikely((__pyx_v_t == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 141, __pyx_L3_error) + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("predict", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 141, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.predict", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_16predict(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self), __pyx_v_t); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_16predict(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, double __pyx_v_t) { + PyObject *__pyx_r = NULL; + __Pyx_TraceDeclarations + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_TraceFrameInit(__pyx_codeobj__27) + __Pyx_RefNannySetupContext("predict", 1); + __Pyx_TraceCall("predict", __pyx_f[0], 141, 0, __PYX_ERR(0, 141, __pyx_L1_error)); + + /* "rednose/helpers/ekf_sym_pyx.pyx":142 + * + * def predict(self, double t): + * self.ekf.predict(t) # <<<<<<<<<<<<<< + * + * def predict_and_update_batch(self, double t, int kind, z, R, extra_args=[[]], bool augment=False): + */ + __pyx_v_self->ekf->predict(__pyx_v_t); + + /* "rednose/helpers/ekf_sym_pyx.pyx":141 + * self.ekf.reset_rewind() + * + * def predict(self, double t): # <<<<<<<<<<<<<< + * self.ekf.predict(t) + * + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.predict", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_TraceReturn(__pyx_r, 0); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "rednose/helpers/ekf_sym_pyx.pyx":144 + * self.ekf.predict(t) + * + * def predict_and_update_batch(self, double t, int kind, z, R, extra_args=[[]], bool augment=False): # <<<<<<<<<<<<<< + * cdef vector[MapVectorXd] z_map + * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] zi_b + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_19predict_and_update_batch(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_19predict_and_update_batch = {"predict_and_update_batch", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_19predict_and_update_batch, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_19predict_and_update_batch(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + double __pyx_v_t; + int __pyx_v_kind; + PyObject *__pyx_v_z = 0; + PyObject *__pyx_v_R = 0; + PyObject *__pyx_v_extra_args = 0; + bool __pyx_v_augment; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[6] = {0,0,0,0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("predict_and_update_batch (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_t,&__pyx_n_s_kind,&__pyx_n_s_z,&__pyx_n_s_R,&__pyx_n_s_extra_args,&__pyx_n_s_augment,0}; + values[4] = __Pyx_Arg_NewRef_FASTCALL(__pyx_k__28); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 6: values[5] = __Pyx_Arg_FASTCALL(__pyx_args, 5); + CYTHON_FALLTHROUGH; + case 5: values[4] = __Pyx_Arg_FASTCALL(__pyx_args, 4); + CYTHON_FALLTHROUGH; + case 4: values[3] = __Pyx_Arg_FASTCALL(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_t)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 144, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_kind)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 144, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("predict_and_update_batch", 0, 4, 6, 1); __PYX_ERR(0, 144, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_z)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 144, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("predict_and_update_batch", 0, 4, 6, 2); __PYX_ERR(0, 144, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 3: + if (likely((values[3] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_R)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[3]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 144, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("predict_and_update_batch", 0, 4, 6, 3); __PYX_ERR(0, 144, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 4: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_extra_args); + if (value) { values[4] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 144, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 5: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_augment); + if (value) { values[5] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 144, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "predict_and_update_batch") < 0)) __PYX_ERR(0, 144, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 6: values[5] = __Pyx_Arg_FASTCALL(__pyx_args, 5); + CYTHON_FALLTHROUGH; + case 5: values[4] = __Pyx_Arg_FASTCALL(__pyx_args, 4); + CYTHON_FALLTHROUGH; + case 4: values[3] = __Pyx_Arg_FASTCALL(__pyx_args, 3); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_t = __pyx_PyFloat_AsDouble(values[0]); if (unlikely((__pyx_v_t == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 144, __pyx_L3_error) + __pyx_v_kind = __Pyx_PyInt_As_int(values[1]); if (unlikely((__pyx_v_kind == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 144, __pyx_L3_error) + __pyx_v_z = values[2]; + __pyx_v_R = values[3]; + __pyx_v_extra_args = values[4]; + if (values[5]) { + __pyx_v_augment = __Pyx_PyObject_IsTrue(values[5]); if (unlikely((__pyx_v_augment == ((bool)-1)) && PyErr_Occurred())) __PYX_ERR(0, 144, __pyx_L3_error) + } else { + __pyx_v_augment = ((bool)0); + } + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("predict_and_update_batch", 0, 4, 6, __pyx_nargs); __PYX_ERR(0, 144, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.predict_and_update_batch", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_18predict_and_update_batch(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self), __pyx_v_t, __pyx_v_kind, __pyx_v_z, __pyx_v_R, __pyx_v_extra_args, __pyx_v_augment); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_18predict_and_update_batch(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, double __pyx_v_t, int __pyx_v_kind, PyObject *__pyx_v_z, PyObject *__pyx_v_R, PyObject *__pyx_v_extra_args, bool __pyx_v_augment) { + std::vector> __pyx_v_z_map; + PyArrayObject *__pyx_v_zi_b = 0; + PyObject *__pyx_v_zi = NULL; + std::vector >> __pyx_v_R_map; + PyArrayObject *__pyx_v_Ri_b = 0; + PyObject *__pyx_v_Ri = NULL; + std::vector > __pyx_v_extra_args_map; + std::vector __pyx_v_args_map; + PyObject *__pyx_v_args = NULL; + PyObject *__pyx_v_a = NULL; + std::optional __pyx_v_res; + Eigen::VectorXd __pyx_8genexpr1__pyx_v_tmpvec; + __Pyx_LocalBuf_ND __pyx_pybuffernd_Ri_b; + __Pyx_Buffer __pyx_pybuffer_Ri_b; + __Pyx_LocalBuf_ND __pyx_pybuffernd_zi_b; + __Pyx_Buffer __pyx_pybuffer_zi_b; + PyObject *__pyx_r = NULL; + __Pyx_TraceDeclarations + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + Py_ssize_t __pyx_t_2; + PyObject *(*__pyx_t_3)(PyObject *); + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + PyArrayObject *__pyx_t_9 = NULL; + int __pyx_t_10; + PyObject *__pyx_t_11 = NULL; + PyObject *__pyx_t_12 = NULL; + PyObject *__pyx_t_13 = NULL; + char *__pyx_t_14; + PyArrayObject *__pyx_t_15 = NULL; + int __pyx_t_16; + Py_ssize_t __pyx_t_17; + PyObject *(*__pyx_t_18)(PyObject *); + double __pyx_t_19; + int __pyx_t_20; + PyObject *__pyx_t_21 = NULL; + std::vector ::iterator __pyx_t_22; + std::vector __pyx_t_23; + Eigen::VectorXd __pyx_t_24; + PyObject *__pyx_t_25 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_TraceFrameInit(__pyx_codeobj__29) + __Pyx_RefNannySetupContext("predict_and_update_batch", 1); + __Pyx_TraceCall("predict_and_update_batch", __pyx_f[0], 144, 0, __PYX_ERR(0, 144, __pyx_L1_error)); + __pyx_pybuffer_zi_b.pybuffer.buf = NULL; + __pyx_pybuffer_zi_b.refcount = 0; + __pyx_pybuffernd_zi_b.data = NULL; + __pyx_pybuffernd_zi_b.rcbuffer = &__pyx_pybuffer_zi_b; + __pyx_pybuffer_Ri_b.pybuffer.buf = NULL; + __pyx_pybuffer_Ri_b.refcount = 0; + __pyx_pybuffernd_Ri_b.data = NULL; + __pyx_pybuffernd_Ri_b.rcbuffer = &__pyx_pybuffer_Ri_b; + + /* "rednose/helpers/ekf_sym_pyx.pyx":147 + * cdef vector[MapVectorXd] z_map + * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] zi_b + * for zi in z: # <<<<<<<<<<<<<< + * zi_b = np.ascontiguousarray(zi, dtype=np.double) + * z_map.push_back(MapVectorXd( zi_b.data, zi.shape[0])) + */ + if (likely(PyList_CheckExact(__pyx_v_z)) || PyTuple_CheckExact(__pyx_v_z)) { + __pyx_t_1 = __pyx_v_z; __Pyx_INCREF(__pyx_t_1); + __pyx_t_2 = 0; + __pyx_t_3 = NULL; + } else { + __pyx_t_2 = -1; __pyx_t_1 = PyObject_GetIter(__pyx_v_z); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 147, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 147, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_3)) { + if (likely(PyList_CheckExact(__pyx_t_1))) { + { + Py_ssize_t __pyx_temp = __Pyx_PyList_GET_SIZE(__pyx_t_1); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 147, __pyx_L1_error) + #endif + if (__pyx_t_2 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyList_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(0, 147, __pyx_L1_error) + #else + __pyx_t_4 = __Pyx_PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 147, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } else { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_1); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 147, __pyx_L1_error) + #endif + if (__pyx_t_2 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyTuple_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_4); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(0, 147, __pyx_L1_error) + #else + __pyx_t_4 = __Pyx_PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 147, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } + } else { + __pyx_t_4 = __pyx_t_3(__pyx_t_1); + if (unlikely(!__pyx_t_4)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(0, 147, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_4); + } + __Pyx_XDECREF_SET(__pyx_v_zi, __pyx_t_4); + __pyx_t_4 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":148 + * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] zi_b + * for zi in z: + * zi_b = np.ascontiguousarray(zi, dtype=np.double) # <<<<<<<<<<<<<< + * z_map.push_back(MapVectorXd( zi_b.data, zi.shape[0])) + * + */ + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_np); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 148, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 148, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = PyTuple_New(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 148, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_INCREF(__pyx_v_zi); + __Pyx_GIVEREF(__pyx_v_zi); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_v_zi)) __PYX_ERR(0, 148, __pyx_L1_error); + __pyx_t_6 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 148, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_GetModuleGlobalName(__pyx_t_7, __pyx_n_s_np); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 148, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_t_7, __pyx_n_s_double); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 148, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (PyDict_SetItem(__pyx_t_6, __pyx_n_s_dtype, __pyx_t_8) < 0) __PYX_ERR(0, 148, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_t_5, __pyx_t_4, __pyx_t_6); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 148, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + if (!(likely(((__pyx_t_8) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_8, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 148, __pyx_L1_error) + __pyx_t_9 = ((PyArrayObject *)__pyx_t_8); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_zi_b.rcbuffer->pybuffer); + __pyx_t_10 = __Pyx_GetBufferAndValidate(&__pyx_pybuffernd_zi_b.rcbuffer->pybuffer, (PyObject*)__pyx_t_9, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_C_CONTIGUOUS, 1, 0, __pyx_stack); + if (unlikely(__pyx_t_10 < 0)) { + PyErr_Fetch(&__pyx_t_11, &__pyx_t_12, &__pyx_t_13); + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_zi_b.rcbuffer->pybuffer, (PyObject*)__pyx_v_zi_b, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_C_CONTIGUOUS, 1, 0, __pyx_stack) == -1)) { + Py_XDECREF(__pyx_t_11); Py_XDECREF(__pyx_t_12); Py_XDECREF(__pyx_t_13); + __Pyx_RaiseBufferFallbackError(); + } else { + PyErr_Restore(__pyx_t_11, __pyx_t_12, __pyx_t_13); + } + __pyx_t_11 = __pyx_t_12 = __pyx_t_13 = 0; + } + __pyx_pybuffernd_zi_b.diminfo[0].strides = __pyx_pybuffernd_zi_b.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_zi_b.diminfo[0].shape = __pyx_pybuffernd_zi_b.rcbuffer->pybuffer.shape[0]; + if (unlikely((__pyx_t_10 < 0))) __PYX_ERR(0, 148, __pyx_L1_error) + } + __pyx_t_9 = 0; + __Pyx_XDECREF_SET(__pyx_v_zi_b, ((PyArrayObject *)__pyx_t_8)); + __pyx_t_8 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":149 + * for zi in z: + * zi_b = np.ascontiguousarray(zi, dtype=np.double) + * z_map.push_back(MapVectorXd( zi_b.data, zi.shape[0])) # <<<<<<<<<<<<<< + * + * cdef vector[MapMatrixXdr] R_map + */ + __pyx_t_14 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_zi_b)); if (unlikely(__pyx_t_14 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 149, __pyx_L1_error) + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_zi, __pyx_n_s_shape); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 149, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_6 = __Pyx_GetItemInt(__pyx_t_8, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 149, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_t_10 = __Pyx_PyInt_As_int(__pyx_t_6); if (unlikely((__pyx_t_10 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 149, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + try { + __pyx_v_z_map.push_back(Eigen::Map(((double *)__pyx_t_14), __pyx_t_10)); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(0, 149, __pyx_L1_error) + } + + /* "rednose/helpers/ekf_sym_pyx.pyx":147 + * cdef vector[MapVectorXd] z_map + * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] zi_b + * for zi in z: # <<<<<<<<<<<<<< + * zi_b = np.ascontiguousarray(zi, dtype=np.double) + * z_map.push_back(MapVectorXd( zi_b.data, zi.shape[0])) + */ + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":153 + * cdef vector[MapMatrixXdr] R_map + * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] Ri_b + * for Ri in R: # <<<<<<<<<<<<<< + * Ri_b = np.ascontiguousarray(Ri, dtype=np.double) + * R_map.push_back(MapMatrixXdr( Ri_b.data, Ri.shape[0], Ri.shape[1])) + */ + if (likely(PyList_CheckExact(__pyx_v_R)) || PyTuple_CheckExact(__pyx_v_R)) { + __pyx_t_1 = __pyx_v_R; __Pyx_INCREF(__pyx_t_1); + __pyx_t_2 = 0; + __pyx_t_3 = NULL; + } else { + __pyx_t_2 = -1; __pyx_t_1 = PyObject_GetIter(__pyx_v_R); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 153, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 153, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_3)) { + if (likely(PyList_CheckExact(__pyx_t_1))) { + { + Py_ssize_t __pyx_temp = __Pyx_PyList_GET_SIZE(__pyx_t_1); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 153, __pyx_L1_error) + #endif + if (__pyx_t_2 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_6 = PyList_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_6); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(0, 153, __pyx_L1_error) + #else + __pyx_t_6 = __Pyx_PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 153, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + #endif + } else { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_1); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 153, __pyx_L1_error) + #endif + if (__pyx_t_2 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_6 = PyTuple_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_6); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(0, 153, __pyx_L1_error) + #else + __pyx_t_6 = __Pyx_PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 153, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + #endif + } + } else { + __pyx_t_6 = __pyx_t_3(__pyx_t_1); + if (unlikely(!__pyx_t_6)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(0, 153, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_6); + } + __Pyx_XDECREF_SET(__pyx_v_Ri, __pyx_t_6); + __pyx_t_6 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":154 + * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] Ri_b + * for Ri in R: + * Ri_b = np.ascontiguousarray(Ri, dtype=np.double) # <<<<<<<<<<<<<< + * R_map.push_back(MapMatrixXdr( Ri_b.data, Ri.shape[0], Ri.shape[1])) + * + */ + __Pyx_GetModuleGlobalName(__pyx_t_6, __pyx_n_s_np); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 154, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_t_6, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 154, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __pyx_t_6 = PyTuple_New(1); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 154, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_INCREF(__pyx_v_Ri); + __Pyx_GIVEREF(__pyx_v_Ri); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_6, 0, __pyx_v_Ri)) __PYX_ERR(0, 154, __pyx_L1_error); + __pyx_t_4 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 154, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GetModuleGlobalName(__pyx_t_5, __pyx_n_s_np); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 154, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_double); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 154, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (PyDict_SetItem(__pyx_t_4, __pyx_n_s_dtype, __pyx_t_7) < 0) __PYX_ERR(0, 154, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __pyx_t_7 = __Pyx_PyObject_Call(__pyx_t_8, __pyx_t_6, __pyx_t_4); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 154, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (!(likely(((__pyx_t_7) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_7, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 154, __pyx_L1_error) + __pyx_t_15 = ((PyArrayObject *)__pyx_t_7); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_Ri_b.rcbuffer->pybuffer); + __pyx_t_10 = __Pyx_GetBufferAndValidate(&__pyx_pybuffernd_Ri_b.rcbuffer->pybuffer, (PyObject*)__pyx_t_15, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_C_CONTIGUOUS, 2, 0, __pyx_stack); + if (unlikely(__pyx_t_10 < 0)) { + PyErr_Fetch(&__pyx_t_13, &__pyx_t_12, &__pyx_t_11); + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_Ri_b.rcbuffer->pybuffer, (PyObject*)__pyx_v_Ri_b, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_C_CONTIGUOUS, 2, 0, __pyx_stack) == -1)) { + Py_XDECREF(__pyx_t_13); Py_XDECREF(__pyx_t_12); Py_XDECREF(__pyx_t_11); + __Pyx_RaiseBufferFallbackError(); + } else { + PyErr_Restore(__pyx_t_13, __pyx_t_12, __pyx_t_11); + } + __pyx_t_13 = __pyx_t_12 = __pyx_t_11 = 0; + } + __pyx_pybuffernd_Ri_b.diminfo[0].strides = __pyx_pybuffernd_Ri_b.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_Ri_b.diminfo[0].shape = __pyx_pybuffernd_Ri_b.rcbuffer->pybuffer.shape[0]; __pyx_pybuffernd_Ri_b.diminfo[1].strides = __pyx_pybuffernd_Ri_b.rcbuffer->pybuffer.strides[1]; __pyx_pybuffernd_Ri_b.diminfo[1].shape = __pyx_pybuffernd_Ri_b.rcbuffer->pybuffer.shape[1]; + if (unlikely((__pyx_t_10 < 0))) __PYX_ERR(0, 154, __pyx_L1_error) + } + __pyx_t_15 = 0; + __Pyx_XDECREF_SET(__pyx_v_Ri_b, ((PyArrayObject *)__pyx_t_7)); + __pyx_t_7 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":155 + * for Ri in R: + * Ri_b = np.ascontiguousarray(Ri, dtype=np.double) + * R_map.push_back(MapMatrixXdr( Ri_b.data, Ri.shape[0], Ri.shape[1])) # <<<<<<<<<<<<<< + * + * cdef vector[vector[double]] extra_args_map + */ + __pyx_t_14 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_Ri_b)); if (unlikely(__pyx_t_14 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 155, __pyx_L1_error) + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_v_Ri, __pyx_n_s_shape); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 155, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_4 = __Pyx_GetItemInt(__pyx_t_7, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 155, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __pyx_t_10 = __Pyx_PyInt_As_int(__pyx_t_4); if (unlikely((__pyx_t_10 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 155, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_v_Ri, __pyx_n_s_shape); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 155, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_7 = __Pyx_GetItemInt(__pyx_t_4, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 155, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_16 = __Pyx_PyInt_As_int(__pyx_t_7); if (unlikely((__pyx_t_16 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 155, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + try { + __pyx_v_R_map.push_back(Eigen::Map >(((double *)__pyx_t_14), __pyx_t_10, __pyx_t_16)); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(0, 155, __pyx_L1_error) + } + + /* "rednose/helpers/ekf_sym_pyx.pyx":153 + * cdef vector[MapMatrixXdr] R_map + * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] Ri_b + * for Ri in R: # <<<<<<<<<<<<<< + * Ri_b = np.ascontiguousarray(Ri, dtype=np.double) + * R_map.push_back(MapMatrixXdr( Ri_b.data, Ri.shape[0], Ri.shape[1])) + */ + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":159 + * cdef vector[vector[double]] extra_args_map + * cdef vector[double] args_map + * for args in extra_args: # <<<<<<<<<<<<<< + * args_map.clear() + * for a in args: + */ + if (likely(PyList_CheckExact(__pyx_v_extra_args)) || PyTuple_CheckExact(__pyx_v_extra_args)) { + __pyx_t_1 = __pyx_v_extra_args; __Pyx_INCREF(__pyx_t_1); + __pyx_t_2 = 0; + __pyx_t_3 = NULL; + } else { + __pyx_t_2 = -1; __pyx_t_1 = PyObject_GetIter(__pyx_v_extra_args); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 159, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 159, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_3)) { + if (likely(PyList_CheckExact(__pyx_t_1))) { + { + Py_ssize_t __pyx_temp = __Pyx_PyList_GET_SIZE(__pyx_t_1); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 159, __pyx_L1_error) + #endif + if (__pyx_t_2 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_7 = PyList_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_7); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(0, 159, __pyx_L1_error) + #else + __pyx_t_7 = __Pyx_PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 159, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + #endif + } else { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_1); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 159, __pyx_L1_error) + #endif + if (__pyx_t_2 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_7 = PyTuple_GET_ITEM(__pyx_t_1, __pyx_t_2); __Pyx_INCREF(__pyx_t_7); __pyx_t_2++; if (unlikely((0 < 0))) __PYX_ERR(0, 159, __pyx_L1_error) + #else + __pyx_t_7 = __Pyx_PySequence_ITEM(__pyx_t_1, __pyx_t_2); __pyx_t_2++; if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 159, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + #endif + } + } else { + __pyx_t_7 = __pyx_t_3(__pyx_t_1); + if (unlikely(!__pyx_t_7)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(0, 159, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_7); + } + __Pyx_XDECREF_SET(__pyx_v_args, __pyx_t_7); + __pyx_t_7 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":160 + * cdef vector[double] args_map + * for args in extra_args: + * args_map.clear() # <<<<<<<<<<<<<< + * for a in args: + * args_map.push_back(a) + */ + __pyx_v_args_map.clear(); + + /* "rednose/helpers/ekf_sym_pyx.pyx":161 + * for args in extra_args: + * args_map.clear() + * for a in args: # <<<<<<<<<<<<<< + * args_map.push_back(a) + * extra_args_map.push_back(args_map) + */ + if (likely(PyList_CheckExact(__pyx_v_args)) || PyTuple_CheckExact(__pyx_v_args)) { + __pyx_t_7 = __pyx_v_args; __Pyx_INCREF(__pyx_t_7); + __pyx_t_17 = 0; + __pyx_t_18 = NULL; + } else { + __pyx_t_17 = -1; __pyx_t_7 = PyObject_GetIter(__pyx_v_args); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_18 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_7); if (unlikely(!__pyx_t_18)) __PYX_ERR(0, 161, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_18)) { + if (likely(PyList_CheckExact(__pyx_t_7))) { + { + Py_ssize_t __pyx_temp = __Pyx_PyList_GET_SIZE(__pyx_t_7); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 161, __pyx_L1_error) + #endif + if (__pyx_t_17 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyList_GET_ITEM(__pyx_t_7, __pyx_t_17); __Pyx_INCREF(__pyx_t_4); __pyx_t_17++; if (unlikely((0 < 0))) __PYX_ERR(0, 161, __pyx_L1_error) + #else + __pyx_t_4 = __Pyx_PySequence_ITEM(__pyx_t_7, __pyx_t_17); __pyx_t_17++; if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } else { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_7); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 161, __pyx_L1_error) + #endif + if (__pyx_t_17 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyTuple_GET_ITEM(__pyx_t_7, __pyx_t_17); __Pyx_INCREF(__pyx_t_4); __pyx_t_17++; if (unlikely((0 < 0))) __PYX_ERR(0, 161, __pyx_L1_error) + #else + __pyx_t_4 = __Pyx_PySequence_ITEM(__pyx_t_7, __pyx_t_17); __pyx_t_17++; if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } + } else { + __pyx_t_4 = __pyx_t_18(__pyx_t_7); + if (unlikely(!__pyx_t_4)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(0, 161, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_4); + } + __Pyx_XDECREF_SET(__pyx_v_a, __pyx_t_4); + __pyx_t_4 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":162 + * args_map.clear() + * for a in args: + * args_map.push_back(a) # <<<<<<<<<<<<<< + * extra_args_map.push_back(args_map) + * + */ + __pyx_t_19 = __pyx_PyFloat_AsDouble(__pyx_v_a); if (unlikely((__pyx_t_19 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 162, __pyx_L1_error) + try { + __pyx_v_args_map.push_back(__pyx_t_19); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(0, 162, __pyx_L1_error) + } + + /* "rednose/helpers/ekf_sym_pyx.pyx":161 + * for args in extra_args: + * args_map.clear() + * for a in args: # <<<<<<<<<<<<<< + * args_map.push_back(a) + * extra_args_map.push_back(args_map) + */ + } + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":163 + * for a in args: + * args_map.push_back(a) + * extra_args_map.push_back(args_map) # <<<<<<<<<<<<<< + * + * cdef optional[Estimate] res = self.ekf.predict_and_update_batch(t, kind, z_map, R_map, extra_args_map, augment) + */ + try { + __pyx_v_extra_args_map.push_back(__pyx_v_args_map); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(0, 163, __pyx_L1_error) + } + + /* "rednose/helpers/ekf_sym_pyx.pyx":159 + * cdef vector[vector[double]] extra_args_map + * cdef vector[double] args_map + * for args in extra_args: # <<<<<<<<<<<<<< + * args_map.clear() + * for a in args: + */ + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":165 + * extra_args_map.push_back(args_map) + * + * cdef optional[Estimate] res = self.ekf.predict_and_update_batch(t, kind, z_map, R_map, extra_args_map, augment) # <<<<<<<<<<<<<< + * if not res.has_value(): + * return None + */ + __pyx_v_res = __pyx_v_self->ekf->predict_and_update_batch(__pyx_v_t, __pyx_v_kind, __pyx_v_z_map, __pyx_v_R_map, __pyx_v_extra_args_map, __pyx_v_augment); + + /* "rednose/helpers/ekf_sym_pyx.pyx":166 + * + * cdef optional[Estimate] res = self.ekf.predict_and_update_batch(t, kind, z_map, R_map, extra_args_map, augment) + * if not res.has_value(): # <<<<<<<<<<<<<< + * return None + * + */ + __pyx_t_20 = (!(__pyx_v_res.has_value() != 0)); + if (__pyx_t_20) { + + /* "rednose/helpers/ekf_sym_pyx.pyx":167 + * cdef optional[Estimate] res = self.ekf.predict_and_update_batch(t, kind, z_map, R_map, extra_args_map, augment) + * if not res.has_value(): + * return None # <<<<<<<<<<<<<< + * + * cdef VectorXd tmpvec + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":166 + * + * cdef optional[Estimate] res = self.ekf.predict_and_update_batch(t, kind, z_map, R_map, extra_args_map, augment) + * if not res.has_value(): # <<<<<<<<<<<<<< + * return None + * + */ + } + + /* "rednose/helpers/ekf_sym_pyx.pyx":170 + * + * cdef VectorXd tmpvec + * return ( # <<<<<<<<<<<<<< + * vector_to_numpy(res.value().xk1), + * vector_to_numpy(res.value().xk), + */ + __Pyx_XDECREF(__pyx_r); + + /* "rednose/helpers/ekf_sym_pyx.pyx":171 + * cdef VectorXd tmpvec + * return ( + * vector_to_numpy(res.value().xk1), # <<<<<<<<<<<<<< + * vector_to_numpy(res.value().xk), + * matrix_to_numpy(res.value().Pk1), + */ + __pyx_t_1 = ((PyObject *)__pyx_f_7rednose_7helpers_11ekf_sym_pyx_vector_to_numpy(__pyx_v_res.value().xk1)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 171, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + + /* "rednose/helpers/ekf_sym_pyx.pyx":172 + * return ( + * vector_to_numpy(res.value().xk1), + * vector_to_numpy(res.value().xk), # <<<<<<<<<<<<<< + * matrix_to_numpy(res.value().Pk1), + * matrix_to_numpy(res.value().Pk), + */ + __pyx_t_7 = ((PyObject *)__pyx_f_7rednose_7helpers_11ekf_sym_pyx_vector_to_numpy(__pyx_v_res.value().xk)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 172, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + + /* "rednose/helpers/ekf_sym_pyx.pyx":173 + * vector_to_numpy(res.value().xk1), + * vector_to_numpy(res.value().xk), + * matrix_to_numpy(res.value().Pk1), # <<<<<<<<<<<<<< + * matrix_to_numpy(res.value().Pk), + * res.value().t, + */ + __pyx_t_4 = ((PyObject *)__pyx_f_7rednose_7helpers_11ekf_sym_pyx_matrix_to_numpy(__pyx_v_res.value().Pk1)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 173, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + + /* "rednose/helpers/ekf_sym_pyx.pyx":174 + * vector_to_numpy(res.value().xk), + * matrix_to_numpy(res.value().Pk1), + * matrix_to_numpy(res.value().Pk), # <<<<<<<<<<<<<< + * res.value().t, + * res.value().kind, + */ + __pyx_t_6 = ((PyObject *)__pyx_f_7rednose_7helpers_11ekf_sym_pyx_matrix_to_numpy(__pyx_v_res.value().Pk)); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 174, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + + /* "rednose/helpers/ekf_sym_pyx.pyx":175 + * matrix_to_numpy(res.value().Pk1), + * matrix_to_numpy(res.value().Pk), + * res.value().t, # <<<<<<<<<<<<<< + * res.value().kind, + * [vector_to_numpy(tmpvec) for tmpvec in res.value().y], + */ + __pyx_t_8 = PyFloat_FromDouble(__pyx_v_res.value().t); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 175, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + + /* "rednose/helpers/ekf_sym_pyx.pyx":176 + * matrix_to_numpy(res.value().Pk), + * res.value().t, + * res.value().kind, # <<<<<<<<<<<<<< + * [vector_to_numpy(tmpvec) for tmpvec in res.value().y], + * z, # TODO: take return values? + */ + __pyx_t_5 = __Pyx_PyInt_From_int(__pyx_v_res.value().kind); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 176, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + { /* enter inner scope */ + + /* "rednose/helpers/ekf_sym_pyx.pyx":177 + * res.value().t, + * res.value().kind, + * [vector_to_numpy(tmpvec) for tmpvec in res.value().y], # <<<<<<<<<<<<<< + * z, # TODO: take return values? + * extra_args, + */ + __pyx_t_21 = PyList_New(0); if (unlikely(!__pyx_t_21)) __PYX_ERR(0, 177, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_21); + __pyx_t_23 = __pyx_v_res.value().y; + __pyx_t_22 = __pyx_t_23.begin(); + for (;;) { + if (!(__pyx_t_22 != __pyx_t_23.end())) break; + __pyx_t_24 = *__pyx_t_22; + ++__pyx_t_22; + __pyx_8genexpr1__pyx_v_tmpvec = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_24); + __pyx_t_25 = ((PyObject *)__pyx_f_7rednose_7helpers_11ekf_sym_pyx_vector_to_numpy(__pyx_8genexpr1__pyx_v_tmpvec)); if (unlikely(!__pyx_t_25)) __PYX_ERR(0, 177, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_25); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_21, (PyObject*)__pyx_t_25))) __PYX_ERR(0, 177, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_25); __pyx_t_25 = 0; + } + } /* exit inner scope */ + + /* "rednose/helpers/ekf_sym_pyx.pyx":171 + * cdef VectorXd tmpvec + * return ( + * vector_to_numpy(res.value().xk1), # <<<<<<<<<<<<<< + * vector_to_numpy(res.value().xk), + * matrix_to_numpy(res.value().Pk1), + */ + __pyx_t_25 = PyTuple_New(9); if (unlikely(!__pyx_t_25)) __PYX_ERR(0, 171, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_25); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_25, 0, __pyx_t_1)) __PYX_ERR(0, 171, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_7); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_25, 1, __pyx_t_7)) __PYX_ERR(0, 171, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_4); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_25, 2, __pyx_t_4)) __PYX_ERR(0, 171, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_6); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_25, 3, __pyx_t_6)) __PYX_ERR(0, 171, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_8); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_25, 4, __pyx_t_8)) __PYX_ERR(0, 171, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_5); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_25, 5, __pyx_t_5)) __PYX_ERR(0, 171, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_21); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_25, 6, __pyx_t_21)) __PYX_ERR(0, 171, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_z); + __Pyx_GIVEREF(__pyx_v_z); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_25, 7, __pyx_v_z)) __PYX_ERR(0, 171, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_extra_args); + __Pyx_GIVEREF(__pyx_v_extra_args); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_25, 8, __pyx_v_extra_args)) __PYX_ERR(0, 171, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_7 = 0; + __pyx_t_4 = 0; + __pyx_t_6 = 0; + __pyx_t_8 = 0; + __pyx_t_5 = 0; + __pyx_t_21 = 0; + __pyx_r = __pyx_t_25; + __pyx_t_25 = 0; + goto __pyx_L0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":144 + * self.ekf.predict(t) + * + * def predict_and_update_batch(self, double t, int kind, z, R, extra_args=[[]], bool augment=False): # <<<<<<<<<<<<<< + * cdef vector[MapVectorXd] z_map + * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] zi_b + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_XDECREF(__pyx_t_21); + __Pyx_XDECREF(__pyx_t_25); + { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_Ri_b.rcbuffer->pybuffer); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_zi_b.rcbuffer->pybuffer); + __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.predict_and_update_batch", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + goto __pyx_L2; + __pyx_L0:; + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_Ri_b.rcbuffer->pybuffer); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_zi_b.rcbuffer->pybuffer); + __pyx_L2:; + __Pyx_XDECREF((PyObject *)__pyx_v_zi_b); + __Pyx_XDECREF(__pyx_v_zi); + __Pyx_XDECREF((PyObject *)__pyx_v_Ri_b); + __Pyx_XDECREF(__pyx_v_Ri); + __Pyx_XDECREF(__pyx_v_args); + __Pyx_XDECREF(__pyx_v_a); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_TraceReturn(__pyx_r, 0); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "rednose/helpers/ekf_sym_pyx.pyx":182 + * ) + * + * def augment(self): # <<<<<<<<<<<<<< + * raise NotImplementedError() # TODO + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_21augment(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_21augment = {"augment", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_21augment, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_21augment(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("augment (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("augment", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "augment", 0))) return NULL; + __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_20augment(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_20augment(CYTHON_UNUSED struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_TraceDeclarations + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_TraceFrameInit(__pyx_codeobj__30) + __Pyx_RefNannySetupContext("augment", 1); + __Pyx_TraceCall("augment", __pyx_f[0], 182, 0, __PYX_ERR(0, 182, __pyx_L1_error)); + + /* "rednose/helpers/ekf_sym_pyx.pyx":183 + * + * def augment(self): + * raise NotImplementedError() # TODO # <<<<<<<<<<<<<< + * + * def get_augment_times(self): + */ + __pyx_t_1 = __Pyx_PyObject_CallNoArg(__pyx_builtin_NotImplementedError); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 183, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 183, __pyx_L1_error) + + /* "rednose/helpers/ekf_sym_pyx.pyx":182 + * ) + * + * def augment(self): # <<<<<<<<<<<<<< + * raise NotImplementedError() # TODO + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.augment", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_TraceReturn(__pyx_r, 0); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "rednose/helpers/ekf_sym_pyx.pyx":185 + * raise NotImplementedError() # TODO + * + * def get_augment_times(self): # <<<<<<<<<<<<<< + * raise NotImplementedError() # TODO + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_23get_augment_times(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_23get_augment_times = {"get_augment_times", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_23get_augment_times, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_23get_augment_times(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("get_augment_times (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("get_augment_times", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "get_augment_times", 0))) return NULL; + __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_22get_augment_times(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_22get_augment_times(CYTHON_UNUSED struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_TraceDeclarations + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_TraceFrameInit(__pyx_codeobj__31) + __Pyx_RefNannySetupContext("get_augment_times", 1); + __Pyx_TraceCall("get_augment_times", __pyx_f[0], 185, 0, __PYX_ERR(0, 185, __pyx_L1_error)); + + /* "rednose/helpers/ekf_sym_pyx.pyx":186 + * + * def get_augment_times(self): + * raise NotImplementedError() # TODO # <<<<<<<<<<<<<< + * + * def rts_smooth(self, estimates, norm_quats=False): + */ + __pyx_t_1 = __Pyx_PyObject_CallNoArg(__pyx_builtin_NotImplementedError); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 186, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 186, __pyx_L1_error) + + /* "rednose/helpers/ekf_sym_pyx.pyx":185 + * raise NotImplementedError() # TODO + * + * def get_augment_times(self): # <<<<<<<<<<<<<< + * raise NotImplementedError() # TODO + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.get_augment_times", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_TraceReturn(__pyx_r, 0); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "rednose/helpers/ekf_sym_pyx.pyx":188 + * raise NotImplementedError() # TODO + * + * def rts_smooth(self, estimates, norm_quats=False): # <<<<<<<<<<<<<< + * raise NotImplementedError() # TODO + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_25rts_smooth(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_25rts_smooth = {"rts_smooth", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_25rts_smooth, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_25rts_smooth(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v_estimates = 0; + CYTHON_UNUSED PyObject *__pyx_v_norm_quats = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[2] = {0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("rts_smooth (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_estimates,&__pyx_n_s_norm_quats,0}; + values[1] = __Pyx_Arg_NewRef_FASTCALL(((PyObject *)Py_False)); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_estimates)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 188, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_norm_quats); + if (value) { values[1] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 188, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "rts_smooth") < 0)) __PYX_ERR(0, 188, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_estimates = values[0]; + __pyx_v_norm_quats = values[1]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("rts_smooth", 0, 1, 2, __pyx_nargs); __PYX_ERR(0, 188, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.rts_smooth", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_24rts_smooth(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self), __pyx_v_estimates, __pyx_v_norm_quats); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_24rts_smooth(CYTHON_UNUSED struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_estimates, CYTHON_UNUSED PyObject *__pyx_v_norm_quats) { + PyObject *__pyx_r = NULL; + __Pyx_TraceDeclarations + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_TraceFrameInit(__pyx_codeobj__32) + __Pyx_RefNannySetupContext("rts_smooth", 1); + __Pyx_TraceCall("rts_smooth", __pyx_f[0], 188, 0, __PYX_ERR(0, 188, __pyx_L1_error)); + + /* "rednose/helpers/ekf_sym_pyx.pyx":189 + * + * def rts_smooth(self, estimates, norm_quats=False): + * raise NotImplementedError() # TODO # <<<<<<<<<<<<<< + * + * def maha_test(self, x, P, kind, z, R, extra_args=[], maha_thresh=0.95): + */ + __pyx_t_1 = __Pyx_PyObject_CallNoArg(__pyx_builtin_NotImplementedError); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 189, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 189, __pyx_L1_error) + + /* "rednose/helpers/ekf_sym_pyx.pyx":188 + * raise NotImplementedError() # TODO + * + * def rts_smooth(self, estimates, norm_quats=False): # <<<<<<<<<<<<<< + * raise NotImplementedError() # TODO + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.rts_smooth", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_TraceReturn(__pyx_r, 0); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "rednose/helpers/ekf_sym_pyx.pyx":191 + * raise NotImplementedError() # TODO + * + * def maha_test(self, x, P, kind, z, R, extra_args=[], maha_thresh=0.95): # <<<<<<<<<<<<<< + * raise NotImplementedError() # TODO + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_27maha_test(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_27maha_test = {"maha_test", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_27maha_test, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_27maha_test(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v_x = 0; + CYTHON_UNUSED PyObject *__pyx_v_P = 0; + CYTHON_UNUSED PyObject *__pyx_v_kind = 0; + CYTHON_UNUSED PyObject *__pyx_v_z = 0; + CYTHON_UNUSED PyObject *__pyx_v_R = 0; + CYTHON_UNUSED PyObject *__pyx_v_extra_args = 0; + CYTHON_UNUSED PyObject *__pyx_v_maha_thresh = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[7] = {0,0,0,0,0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("maha_test (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_x,&__pyx_n_s_P,&__pyx_n_s_kind,&__pyx_n_s_z,&__pyx_n_s_R,&__pyx_n_s_extra_args,&__pyx_n_s_maha_thresh,0}; + values[5] = __Pyx_Arg_NewRef_FASTCALL(__pyx_k__33); + values[6] = __Pyx_Arg_NewRef_FASTCALL(((PyObject *)__pyx_float_0_95)); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 7: values[6] = __Pyx_Arg_FASTCALL(__pyx_args, 6); + CYTHON_FALLTHROUGH; + case 6: values[5] = __Pyx_Arg_FASTCALL(__pyx_args, 5); + CYTHON_FALLTHROUGH; + case 5: values[4] = __Pyx_Arg_FASTCALL(__pyx_args, 4); + CYTHON_FALLTHROUGH; + case 4: values[3] = __Pyx_Arg_FASTCALL(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_x)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 191, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_P)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 191, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("maha_test", 0, 5, 7, 1); __PYX_ERR(0, 191, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_kind)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 191, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("maha_test", 0, 5, 7, 2); __PYX_ERR(0, 191, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 3: + if (likely((values[3] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_z)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[3]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 191, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("maha_test", 0, 5, 7, 3); __PYX_ERR(0, 191, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 4: + if (likely((values[4] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_R)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[4]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 191, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("maha_test", 0, 5, 7, 4); __PYX_ERR(0, 191, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 5: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_extra_args); + if (value) { values[5] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 191, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 6: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_maha_thresh); + if (value) { values[6] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 191, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "maha_test") < 0)) __PYX_ERR(0, 191, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 7: values[6] = __Pyx_Arg_FASTCALL(__pyx_args, 6); + CYTHON_FALLTHROUGH; + case 6: values[5] = __Pyx_Arg_FASTCALL(__pyx_args, 5); + CYTHON_FALLTHROUGH; + case 5: values[4] = __Pyx_Arg_FASTCALL(__pyx_args, 4); + values[3] = __Pyx_Arg_FASTCALL(__pyx_args, 3); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_x = values[0]; + __pyx_v_P = values[1]; + __pyx_v_kind = values[2]; + __pyx_v_z = values[3]; + __pyx_v_R = values[4]; + __pyx_v_extra_args = values[5]; + __pyx_v_maha_thresh = values[6]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("maha_test", 0, 5, 7, __pyx_nargs); __PYX_ERR(0, 191, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.maha_test", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_26maha_test(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self), __pyx_v_x, __pyx_v_P, __pyx_v_kind, __pyx_v_z, __pyx_v_R, __pyx_v_extra_args, __pyx_v_maha_thresh); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_26maha_test(CYTHON_UNUSED struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_x, CYTHON_UNUSED PyObject *__pyx_v_P, CYTHON_UNUSED PyObject *__pyx_v_kind, CYTHON_UNUSED PyObject *__pyx_v_z, CYTHON_UNUSED PyObject *__pyx_v_R, CYTHON_UNUSED PyObject *__pyx_v_extra_args, CYTHON_UNUSED PyObject *__pyx_v_maha_thresh) { + PyObject *__pyx_r = NULL; + __Pyx_TraceDeclarations + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_TraceFrameInit(__pyx_codeobj__34) + __Pyx_RefNannySetupContext("maha_test", 1); + __Pyx_TraceCall("maha_test", __pyx_f[0], 191, 0, __PYX_ERR(0, 191, __pyx_L1_error)); + + /* "rednose/helpers/ekf_sym_pyx.pyx":192 + * + * def maha_test(self, x, P, kind, z, R, extra_args=[], maha_thresh=0.95): + * raise NotImplementedError() # TODO # <<<<<<<<<<<<<< + * + * def __dealloc__(self): + */ + __pyx_t_1 = __Pyx_PyObject_CallNoArg(__pyx_builtin_NotImplementedError); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 192, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 192, __pyx_L1_error) + + /* "rednose/helpers/ekf_sym_pyx.pyx":191 + * raise NotImplementedError() # TODO + * + * def maha_test(self, x, P, kind, z, R, extra_args=[], maha_thresh=0.95): # <<<<<<<<<<<<<< + * raise NotImplementedError() # TODO + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.maha_test", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_TraceReturn(__pyx_r, 0); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "rednose/helpers/ekf_sym_pyx.pyx":194 + * raise NotImplementedError() # TODO + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * del self.ekf + */ + +/* Python wrapper */ +static void __pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_29__dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_29__dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_28__dealloc__(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_28__dealloc__(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self) { + __Pyx_TraceDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_TraceCall("__dealloc__", __pyx_f[0], 194, 0, __PYX_ERR(0, 194, __pyx_L1_error)); + + /* "rednose/helpers/ekf_sym_pyx.pyx":195 + * + * def __dealloc__(self): + * del self.ekf # <<<<<<<<<<<<<< + */ + delete __pyx_v_self->ekf; + + /* "rednose/helpers/ekf_sym_pyx.pyx":194 + * raise NotImplementedError() # TODO + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * del self.ekf + */ + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_WriteUnraisable("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.__dealloc__", __pyx_clineno, __pyx_lineno, __pyx_filename, 1, 0); + __pyx_L0:; + __Pyx_TraceReturn(Py_None, 0); +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_31__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_31__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_31__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_31__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_30__reduce_cython__(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_30__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_TraceDeclarations + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_TraceFrameInit(__pyx_codeobj__35) + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + __Pyx_TraceCall("__reduce_cython__", __pyx_f[1], 1, 0, __PYX_ERR(1, 1, __pyx_L1_error)); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_TraceReturn(__pyx_r, 0); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_33__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_33__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_33__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_33__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_32__setstate_cython__(((struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_32__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_TraceDeclarations + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_TraceFrameInit(__pyx_codeobj__36) + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + __Pyx_TraceCall("__setstate_cython__", __pyx_f[1], 3, 0, __PYX_ERR(1, 3, __pyx_L1_error)); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("rednose.helpers.ekf_sym_pyx.EKF_sym_pyx.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_TraceReturn(__pyx_r, 0); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_tp_new_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx(PyTypeObject *t, PyObject *a, PyObject *k) { + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + if (unlikely(__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_1__cinit__(o, a, k) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static void __pyx_tp_dealloc_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx(PyObject *o) { + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_29__dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} + +static PyMethodDef __pyx_methods_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx[] = { + {"init_state", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_3init_state, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"state", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_5state, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"covs", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_7covs, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"set_filter_time", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_9set_filter_time, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"get_filter_time", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_11get_filter_time, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"set_global", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_13set_global, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"reset_rewind", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_15reset_rewind, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"predict", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_17predict, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"predict_and_update_batch", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_19predict_and_update_batch, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"augment", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_21augment, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"get_augment_times", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_23get_augment_times, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"rts_smooth", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_25rts_smooth, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"maha_test", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_27maha_test, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_31__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_33__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx}, + {Py_tp_methods, (void *)__pyx_methods_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx}, + {Py_tp_new, (void *)__pyx_tp_new_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx}, + {0, 0}, +}; +static PyType_Spec __pyx_type_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx_spec = { + "rednose.helpers.ekf_sym_pyx.EKF_sym_pyx", + sizeof(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, + __pyx_type_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx_slots, +}; +#else + +static PyTypeObject __pyx_type_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx = { + PyVarObject_HEAD_INIT(0, 0) + "rednose.helpers.ekf_sym_pyx.""EKF_sym_pyx", /*tp_name*/ + sizeof(struct __pyx_obj_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, /*tp_flags*/ + 0, /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif +static struct __pyx_vtabstruct_array __pyx_vtable_array; + +static PyObject *__pyx_tp_new_array(PyTypeObject *t, PyObject *a, PyObject *k) { + struct __pyx_array_obj *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_array_obj *)o); + p->__pyx_vtab = __pyx_vtabptr_array; + p->mode = ((PyObject*)Py_None); Py_INCREF(Py_None); + p->_format = ((PyObject*)Py_None); Py_INCREF(Py_None); + if (unlikely(__pyx_array___cinit__(o, a, k) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static void __pyx_tp_dealloc_array(PyObject *o) { + struct __pyx_array_obj *p = (struct __pyx_array_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_array) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_array___dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + Py_CLEAR(p->mode); + Py_CLEAR(p->_format); + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} +static PyObject *__pyx_sq_item_array(PyObject *o, Py_ssize_t i) { + PyObject *r; + PyObject *x = PyInt_FromSsize_t(i); if(!x) return 0; + r = Py_TYPE(o)->tp_as_mapping->mp_subscript(o, x); + Py_DECREF(x); + return r; +} + +static int __pyx_mp_ass_subscript_array(PyObject *o, PyObject *i, PyObject *v) { + if (v) { + return __pyx_array___setitem__(o, i, v); + } + else { + __Pyx_TypeName o_type_name; + o_type_name = __Pyx_PyType_GetName(Py_TYPE(o)); + PyErr_Format(PyExc_NotImplementedError, + "Subscript deletion not supported by " __Pyx_FMT_TYPENAME, o_type_name); + __Pyx_DECREF_TypeName(o_type_name); + return -1; + } +} + +static PyObject *__pyx_tp_getattro_array(PyObject *o, PyObject *n) { + PyObject *v = __Pyx_PyObject_GenericGetAttr(o, n); + if (!v && PyErr_ExceptionMatches(PyExc_AttributeError)) { + PyErr_Clear(); + v = __pyx_array___getattr__(o, n); + } + return v; +} + +static PyObject *__pyx_getprop___pyx_array_memview(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_5array_7memview_1__get__(o); +} + +static PyMethodDef __pyx_methods_array[] = { + {"__getattr__", (PyCFunction)__pyx_array___getattr__, METH_O|METH_COEXIST, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_array_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_array_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; + +static struct PyGetSetDef __pyx_getsets_array[] = { + {(char *)"memview", __pyx_getprop___pyx_array_memview, 0, (char *)0, 0}, + {0, 0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +#if !CYTHON_COMPILING_IN_LIMITED_API + +static PyBufferProcs __pyx_tp_as_buffer_array = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_array_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; +#endif +static PyType_Slot __pyx_type___pyx_array_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_array}, + {Py_sq_length, (void *)__pyx_array___len__}, + {Py_sq_item, (void *)__pyx_sq_item_array}, + {Py_mp_length, (void *)__pyx_array___len__}, + {Py_mp_subscript, (void *)__pyx_array___getitem__}, + {Py_mp_ass_subscript, (void *)__pyx_mp_ass_subscript_array}, + {Py_tp_getattro, (void *)__pyx_tp_getattro_array}, + #if defined(Py_bf_getbuffer) + {Py_bf_getbuffer, (void *)__pyx_array_getbuffer}, + #endif + {Py_tp_methods, (void *)__pyx_methods_array}, + {Py_tp_getset, (void *)__pyx_getsets_array}, + {Py_tp_new, (void *)__pyx_tp_new_array}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_array_spec = { + "rednose.helpers.ekf_sym_pyx.array", + sizeof(struct __pyx_array_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_SEQUENCE, + __pyx_type___pyx_array_slots, +}; +#else + +static PySequenceMethods __pyx_tp_as_sequence_array = { + __pyx_array___len__, /*sq_length*/ + 0, /*sq_concat*/ + 0, /*sq_repeat*/ + __pyx_sq_item_array, /*sq_item*/ + 0, /*sq_slice*/ + 0, /*sq_ass_item*/ + 0, /*sq_ass_slice*/ + 0, /*sq_contains*/ + 0, /*sq_inplace_concat*/ + 0, /*sq_inplace_repeat*/ +}; + +static PyMappingMethods __pyx_tp_as_mapping_array = { + __pyx_array___len__, /*mp_length*/ + __pyx_array___getitem__, /*mp_subscript*/ + __pyx_mp_ass_subscript_array, /*mp_ass_subscript*/ +}; + +static PyBufferProcs __pyx_tp_as_buffer_array = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_array_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; + +static PyTypeObject __pyx_type___pyx_array = { + PyVarObject_HEAD_INIT(0, 0) + "rednose.helpers.ekf_sym_pyx.""array", /*tp_name*/ + sizeof(struct __pyx_array_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_array, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + &__pyx_tp_as_sequence_array, /*tp_as_sequence*/ + &__pyx_tp_as_mapping_array, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + __pyx_tp_getattro_array, /*tp_getattro*/ + 0, /*tp_setattro*/ + &__pyx_tp_as_buffer_array, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_SEQUENCE, /*tp_flags*/ + 0, /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_array, /*tp_methods*/ + 0, /*tp_members*/ + __pyx_getsets_array, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_array, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyObject *__pyx_tp_new_Enum(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { + struct __pyx_MemviewEnum_obj *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_MemviewEnum_obj *)o); + p->name = Py_None; Py_INCREF(Py_None); + return o; +} + +static void __pyx_tp_dealloc_Enum(PyObject *o) { + struct __pyx_MemviewEnum_obj *p = (struct __pyx_MemviewEnum_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_Enum) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + Py_CLEAR(p->name); + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} + +static int __pyx_tp_traverse_Enum(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_MemviewEnum_obj *p = (struct __pyx_MemviewEnum_obj *)o; + if (p->name) { + e = (*v)(p->name, a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear_Enum(PyObject *o) { + PyObject* tmp; + struct __pyx_MemviewEnum_obj *p = (struct __pyx_MemviewEnum_obj *)o; + tmp = ((PyObject*)p->name); + p->name = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + return 0; +} + +static PyObject *__pyx_specialmethod___pyx_MemviewEnum___repr__(PyObject *self, CYTHON_UNUSED PyObject *arg) { + return __pyx_MemviewEnum___repr__(self); +} + +static PyMethodDef __pyx_methods_Enum[] = { + {"__repr__", (PyCFunction)__pyx_specialmethod___pyx_MemviewEnum___repr__, METH_NOARGS|METH_COEXIST, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_MemviewEnum_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_MemviewEnum_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type___pyx_MemviewEnum_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_Enum}, + {Py_tp_repr, (void *)__pyx_MemviewEnum___repr__}, + {Py_tp_traverse, (void *)__pyx_tp_traverse_Enum}, + {Py_tp_clear, (void *)__pyx_tp_clear_Enum}, + {Py_tp_methods, (void *)__pyx_methods_Enum}, + {Py_tp_init, (void *)__pyx_MemviewEnum___init__}, + {Py_tp_new, (void *)__pyx_tp_new_Enum}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_MemviewEnum_spec = { + "rednose.helpers.ekf_sym_pyx.Enum", + sizeof(struct __pyx_MemviewEnum_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, + __pyx_type___pyx_MemviewEnum_slots, +}; +#else + +static PyTypeObject __pyx_type___pyx_MemviewEnum = { + PyVarObject_HEAD_INIT(0, 0) + "rednose.helpers.ekf_sym_pyx.""Enum", /*tp_name*/ + sizeof(struct __pyx_MemviewEnum_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_Enum, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + __pyx_MemviewEnum___repr__, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, /*tp_flags*/ + 0, /*tp_doc*/ + __pyx_tp_traverse_Enum, /*tp_traverse*/ + __pyx_tp_clear_Enum, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_Enum, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + __pyx_MemviewEnum___init__, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_Enum, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif +static struct __pyx_vtabstruct_memoryview __pyx_vtable_memoryview; + +static PyObject *__pyx_tp_new_memoryview(PyTypeObject *t, PyObject *a, PyObject *k) { + struct __pyx_memoryview_obj *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_memoryview_obj *)o); + p->__pyx_vtab = __pyx_vtabptr_memoryview; + p->obj = Py_None; Py_INCREF(Py_None); + p->_size = Py_None; Py_INCREF(Py_None); + p->_array_interface = Py_None; Py_INCREF(Py_None); + p->view.obj = NULL; + if (unlikely(__pyx_memoryview___cinit__(o, a, k) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static void __pyx_tp_dealloc_memoryview(PyObject *o) { + struct __pyx_memoryview_obj *p = (struct __pyx_memoryview_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_memoryview) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_memoryview___dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + Py_CLEAR(p->obj); + Py_CLEAR(p->_size); + Py_CLEAR(p->_array_interface); + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} + +static int __pyx_tp_traverse_memoryview(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_memoryview_obj *p = (struct __pyx_memoryview_obj *)o; + if (p->obj) { + e = (*v)(p->obj, a); if (e) return e; + } + if (p->_size) { + e = (*v)(p->_size, a); if (e) return e; + } + if (p->_array_interface) { + e = (*v)(p->_array_interface, a); if (e) return e; + } + if (p->view.obj) { + e = (*v)(p->view.obj, a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear_memoryview(PyObject *o) { + PyObject* tmp; + struct __pyx_memoryview_obj *p = (struct __pyx_memoryview_obj *)o; + tmp = ((PyObject*)p->obj); + p->obj = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + tmp = ((PyObject*)p->_size); + p->_size = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + tmp = ((PyObject*)p->_array_interface); + p->_array_interface = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + Py_CLEAR(p->view.obj); + return 0; +} +static PyObject *__pyx_sq_item_memoryview(PyObject *o, Py_ssize_t i) { + PyObject *r; + PyObject *x = PyInt_FromSsize_t(i); if(!x) return 0; + r = Py_TYPE(o)->tp_as_mapping->mp_subscript(o, x); + Py_DECREF(x); + return r; +} + +static int __pyx_mp_ass_subscript_memoryview(PyObject *o, PyObject *i, PyObject *v) { + if (v) { + return __pyx_memoryview___setitem__(o, i, v); + } + else { + __Pyx_TypeName o_type_name; + o_type_name = __Pyx_PyType_GetName(Py_TYPE(o)); + PyErr_Format(PyExc_NotImplementedError, + "Subscript deletion not supported by " __Pyx_FMT_TYPENAME, o_type_name); + __Pyx_DECREF_TypeName(o_type_name); + return -1; + } +} + +static PyObject *__pyx_getprop___pyx_memoryview_T(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_1T_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_base(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_4base_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_shape(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_5shape_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_strides(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_7strides_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_suboffsets(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_10suboffsets_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_ndim(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_4ndim_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_itemsize(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_8itemsize_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_nbytes(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_6nbytes_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_size(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_4size_1__get__(o); +} + +static PyObject *__pyx_specialmethod___pyx_memoryview___repr__(PyObject *self, CYTHON_UNUSED PyObject *arg) { + return __pyx_memoryview___repr__(self); +} + +static PyMethodDef __pyx_methods_memoryview[] = { + {"__repr__", (PyCFunction)__pyx_specialmethod___pyx_memoryview___repr__, METH_NOARGS|METH_COEXIST, 0}, + {"is_c_contig", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_is_c_contig, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"is_f_contig", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_is_f_contig, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"copy", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_copy, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"copy_fortran", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_copy_fortran, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryview_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryview_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; + +static struct PyGetSetDef __pyx_getsets_memoryview[] = { + {(char *)"T", __pyx_getprop___pyx_memoryview_T, 0, (char *)0, 0}, + {(char *)"base", __pyx_getprop___pyx_memoryview_base, 0, (char *)0, 0}, + {(char *)"shape", __pyx_getprop___pyx_memoryview_shape, 0, (char *)0, 0}, + {(char *)"strides", __pyx_getprop___pyx_memoryview_strides, 0, (char *)0, 0}, + {(char *)"suboffsets", __pyx_getprop___pyx_memoryview_suboffsets, 0, (char *)0, 0}, + {(char *)"ndim", __pyx_getprop___pyx_memoryview_ndim, 0, (char *)0, 0}, + {(char *)"itemsize", __pyx_getprop___pyx_memoryview_itemsize, 0, (char *)0, 0}, + {(char *)"nbytes", __pyx_getprop___pyx_memoryview_nbytes, 0, (char *)0, 0}, + {(char *)"size", __pyx_getprop___pyx_memoryview_size, 0, (char *)0, 0}, + {0, 0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +#if !CYTHON_COMPILING_IN_LIMITED_API + +static PyBufferProcs __pyx_tp_as_buffer_memoryview = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_memoryview_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; +#endif +static PyType_Slot __pyx_type___pyx_memoryview_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_memoryview}, + {Py_tp_repr, (void *)__pyx_memoryview___repr__}, + {Py_sq_length, (void *)__pyx_memoryview___len__}, + {Py_sq_item, (void *)__pyx_sq_item_memoryview}, + {Py_mp_length, (void *)__pyx_memoryview___len__}, + {Py_mp_subscript, (void *)__pyx_memoryview___getitem__}, + {Py_mp_ass_subscript, (void *)__pyx_mp_ass_subscript_memoryview}, + {Py_tp_str, (void *)__pyx_memoryview___str__}, + #if defined(Py_bf_getbuffer) + {Py_bf_getbuffer, (void *)__pyx_memoryview_getbuffer}, + #endif + {Py_tp_traverse, (void *)__pyx_tp_traverse_memoryview}, + {Py_tp_clear, (void *)__pyx_tp_clear_memoryview}, + {Py_tp_methods, (void *)__pyx_methods_memoryview}, + {Py_tp_getset, (void *)__pyx_getsets_memoryview}, + {Py_tp_new, (void *)__pyx_tp_new_memoryview}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_memoryview_spec = { + "rednose.helpers.ekf_sym_pyx.memoryview", + sizeof(struct __pyx_memoryview_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, + __pyx_type___pyx_memoryview_slots, +}; +#else + +static PySequenceMethods __pyx_tp_as_sequence_memoryview = { + __pyx_memoryview___len__, /*sq_length*/ + 0, /*sq_concat*/ + 0, /*sq_repeat*/ + __pyx_sq_item_memoryview, /*sq_item*/ + 0, /*sq_slice*/ + 0, /*sq_ass_item*/ + 0, /*sq_ass_slice*/ + 0, /*sq_contains*/ + 0, /*sq_inplace_concat*/ + 0, /*sq_inplace_repeat*/ +}; + +static PyMappingMethods __pyx_tp_as_mapping_memoryview = { + __pyx_memoryview___len__, /*mp_length*/ + __pyx_memoryview___getitem__, /*mp_subscript*/ + __pyx_mp_ass_subscript_memoryview, /*mp_ass_subscript*/ +}; + +static PyBufferProcs __pyx_tp_as_buffer_memoryview = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_memoryview_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; + +static PyTypeObject __pyx_type___pyx_memoryview = { + PyVarObject_HEAD_INIT(0, 0) + "rednose.helpers.ekf_sym_pyx.""memoryview", /*tp_name*/ + sizeof(struct __pyx_memoryview_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_memoryview, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + __pyx_memoryview___repr__, /*tp_repr*/ + 0, /*tp_as_number*/ + &__pyx_tp_as_sequence_memoryview, /*tp_as_sequence*/ + &__pyx_tp_as_mapping_memoryview, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + __pyx_memoryview___str__, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + &__pyx_tp_as_buffer_memoryview, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, /*tp_flags*/ + 0, /*tp_doc*/ + __pyx_tp_traverse_memoryview, /*tp_traverse*/ + __pyx_tp_clear_memoryview, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_memoryview, /*tp_methods*/ + 0, /*tp_members*/ + __pyx_getsets_memoryview, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_memoryview, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif +static struct __pyx_vtabstruct__memoryviewslice __pyx_vtable__memoryviewslice; + +static PyObject *__pyx_tp_new__memoryviewslice(PyTypeObject *t, PyObject *a, PyObject *k) { + struct __pyx_memoryviewslice_obj *p; + PyObject *o = __pyx_tp_new_memoryview(t, a, k); + if (unlikely(!o)) return 0; + p = ((struct __pyx_memoryviewslice_obj *)o); + p->__pyx_base.__pyx_vtab = (struct __pyx_vtabstruct_memoryview*)__pyx_vtabptr__memoryviewslice; + new((void*)&(p->from_slice)) __Pyx_memviewslice(); + p->from_object = Py_None; Py_INCREF(Py_None); + p->from_slice.memview = NULL; + return o; +} + +static void __pyx_tp_dealloc__memoryviewslice(PyObject *o) { + struct __pyx_memoryviewslice_obj *p = (struct __pyx_memoryviewslice_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc__memoryviewslice) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_memoryviewslice___dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + __Pyx_call_destructor(p->from_slice); + Py_CLEAR(p->from_object); + PyObject_GC_Track(o); + __pyx_tp_dealloc_memoryview(o); +} + +static int __pyx_tp_traverse__memoryviewslice(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_memoryviewslice_obj *p = (struct __pyx_memoryviewslice_obj *)o; + e = __pyx_tp_traverse_memoryview(o, v, a); if (e) return e; + if (p->from_object) { + e = (*v)(p->from_object, a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear__memoryviewslice(PyObject *o) { + PyObject* tmp; + struct __pyx_memoryviewslice_obj *p = (struct __pyx_memoryviewslice_obj *)o; + __pyx_tp_clear_memoryview(o); + tmp = ((PyObject*)p->from_object); + p->from_object = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + __PYX_XCLEAR_MEMVIEW(&p->from_slice, 1); + return 0; +} + +static PyMethodDef __pyx_methods__memoryviewslice[] = { + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryviewslice_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryviewslice_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type___pyx_memoryviewslice_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc__memoryviewslice}, + {Py_tp_doc, (void *)PyDoc_STR("Internal class for passing memoryview slices to Python")}, + {Py_tp_traverse, (void *)__pyx_tp_traverse__memoryviewslice}, + {Py_tp_clear, (void *)__pyx_tp_clear__memoryviewslice}, + {Py_tp_methods, (void *)__pyx_methods__memoryviewslice}, + {Py_tp_new, (void *)__pyx_tp_new__memoryviewslice}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_memoryviewslice_spec = { + "rednose.helpers.ekf_sym_pyx._memoryviewslice", + sizeof(struct __pyx_memoryviewslice_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_SEQUENCE, + __pyx_type___pyx_memoryviewslice_slots, +}; +#else + +static PyTypeObject __pyx_type___pyx_memoryviewslice = { + PyVarObject_HEAD_INIT(0, 0) + "rednose.helpers.ekf_sym_pyx.""_memoryviewslice", /*tp_name*/ + sizeof(struct __pyx_memoryviewslice_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc__memoryviewslice, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + #if CYTHON_COMPILING_IN_PYPY || 0 + __pyx_memoryview___repr__, /*tp_repr*/ + #else + 0, /*tp_repr*/ + #endif + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + #if CYTHON_COMPILING_IN_PYPY || 0 + __pyx_memoryview___str__, /*tp_str*/ + #else + 0, /*tp_str*/ + #endif + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_SEQUENCE, /*tp_flags*/ + PyDoc_STR("Internal class for passing memoryview slices to Python"), /*tp_doc*/ + __pyx_tp_traverse__memoryviewslice, /*tp_traverse*/ + __pyx_tp_clear__memoryviewslice, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods__memoryviewslice, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new__memoryviewslice, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyMethodDef __pyx_methods[] = { + {0, 0, 0, 0} +}; +#ifndef CYTHON_SMALL_CODE +#if defined(__clang__) + #define CYTHON_SMALL_CODE +#elif defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 3)) + #define CYTHON_SMALL_CODE __attribute__((cold)) +#else + #define CYTHON_SMALL_CODE +#endif +#endif +/* #### Code section: pystring_table ### */ + +static int __Pyx_CreateStringTabAndInitStrings(void) { + __Pyx_StringTabEntry __pyx_string_tab[] = { + {&__pyx_kp_u_, __pyx_k_, sizeof(__pyx_k_), 0, 1, 0, 0}, + {&__pyx_n_s_ASCII, __pyx_k_ASCII, sizeof(__pyx_k_ASCII), 0, 0, 1, 1}, + {&__pyx_kp_s_All_dimensions_preceding_dimensi, __pyx_k_All_dimensions_preceding_dimensi, sizeof(__pyx_k_All_dimensions_preceding_dimensi), 0, 0, 1, 0}, + {&__pyx_n_s_AssertionError, __pyx_k_AssertionError, sizeof(__pyx_k_AssertionError), 0, 0, 1, 1}, + {&__pyx_kp_s_Buffer_view_does_not_expose_stri, __pyx_k_Buffer_view_does_not_expose_stri, sizeof(__pyx_k_Buffer_view_does_not_expose_stri), 0, 0, 1, 0}, + {&__pyx_n_u_C, __pyx_k_C, sizeof(__pyx_k_C), 0, 1, 0, 1}, + {&__pyx_kp_s_Can_only_create_a_buffer_that_is, __pyx_k_Can_only_create_a_buffer_that_is, sizeof(__pyx_k_Can_only_create_a_buffer_that_is), 0, 0, 1, 0}, + {&__pyx_kp_s_Cannot_assign_to_read_only_memor, __pyx_k_Cannot_assign_to_read_only_memor, sizeof(__pyx_k_Cannot_assign_to_read_only_memor), 0, 0, 1, 0}, + {&__pyx_kp_s_Cannot_create_writable_memory_vi, __pyx_k_Cannot_create_writable_memory_vi, sizeof(__pyx_k_Cannot_create_writable_memory_vi), 0, 0, 1, 0}, + {&__pyx_kp_u_Cannot_index_with_type, __pyx_k_Cannot_index_with_type, sizeof(__pyx_k_Cannot_index_with_type), 0, 1, 0, 0}, + {&__pyx_kp_s_Cannot_transpose_memoryview_with, __pyx_k_Cannot_transpose_memoryview_with, sizeof(__pyx_k_Cannot_transpose_memoryview_with), 0, 0, 1, 0}, + {&__pyx_kp_s_Dimension_d_is_not_direct, __pyx_k_Dimension_d_is_not_direct, sizeof(__pyx_k_Dimension_d_is_not_direct), 0, 0, 1, 0}, + {&__pyx_n_s_EKF_sym_pyx, __pyx_k_EKF_sym_pyx, sizeof(__pyx_k_EKF_sym_pyx), 0, 0, 1, 1}, + {&__pyx_n_s_EKF_sym_pyx___reduce_cython, __pyx_k_EKF_sym_pyx___reduce_cython, sizeof(__pyx_k_EKF_sym_pyx___reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_EKF_sym_pyx___setstate_cython, __pyx_k_EKF_sym_pyx___setstate_cython, sizeof(__pyx_k_EKF_sym_pyx___setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_EKF_sym_pyx_augment, __pyx_k_EKF_sym_pyx_augment, sizeof(__pyx_k_EKF_sym_pyx_augment), 0, 0, 1, 1}, + {&__pyx_n_s_EKF_sym_pyx_covs, __pyx_k_EKF_sym_pyx_covs, sizeof(__pyx_k_EKF_sym_pyx_covs), 0, 0, 1, 1}, + {&__pyx_n_s_EKF_sym_pyx_get_augment_times, __pyx_k_EKF_sym_pyx_get_augment_times, sizeof(__pyx_k_EKF_sym_pyx_get_augment_times), 0, 0, 1, 1}, + {&__pyx_n_s_EKF_sym_pyx_get_filter_time, __pyx_k_EKF_sym_pyx_get_filter_time, sizeof(__pyx_k_EKF_sym_pyx_get_filter_time), 0, 0, 1, 1}, + {&__pyx_n_s_EKF_sym_pyx_init_state, __pyx_k_EKF_sym_pyx_init_state, sizeof(__pyx_k_EKF_sym_pyx_init_state), 0, 0, 1, 1}, + {&__pyx_n_s_EKF_sym_pyx_maha_test, __pyx_k_EKF_sym_pyx_maha_test, sizeof(__pyx_k_EKF_sym_pyx_maha_test), 0, 0, 1, 1}, + {&__pyx_n_s_EKF_sym_pyx_predict, __pyx_k_EKF_sym_pyx_predict, sizeof(__pyx_k_EKF_sym_pyx_predict), 0, 0, 1, 1}, + {&__pyx_n_s_EKF_sym_pyx_predict_and_update_b, __pyx_k_EKF_sym_pyx_predict_and_update_b, sizeof(__pyx_k_EKF_sym_pyx_predict_and_update_b), 0, 0, 1, 1}, + {&__pyx_n_s_EKF_sym_pyx_reset_rewind, __pyx_k_EKF_sym_pyx_reset_rewind, sizeof(__pyx_k_EKF_sym_pyx_reset_rewind), 0, 0, 1, 1}, + {&__pyx_n_s_EKF_sym_pyx_rts_smooth, __pyx_k_EKF_sym_pyx_rts_smooth, sizeof(__pyx_k_EKF_sym_pyx_rts_smooth), 0, 0, 1, 1}, + {&__pyx_n_s_EKF_sym_pyx_set_filter_time, __pyx_k_EKF_sym_pyx_set_filter_time, sizeof(__pyx_k_EKF_sym_pyx_set_filter_time), 0, 0, 1, 1}, + {&__pyx_n_s_EKF_sym_pyx_set_global, __pyx_k_EKF_sym_pyx_set_global, sizeof(__pyx_k_EKF_sym_pyx_set_global), 0, 0, 1, 1}, + {&__pyx_n_s_EKF_sym_pyx_state, __pyx_k_EKF_sym_pyx_state, sizeof(__pyx_k_EKF_sym_pyx_state), 0, 0, 1, 1}, + {&__pyx_n_s_Ellipsis, __pyx_k_Ellipsis, sizeof(__pyx_k_Ellipsis), 0, 0, 1, 1}, + {&__pyx_kp_s_Empty_shape_tuple_for_cython_arr, __pyx_k_Empty_shape_tuple_for_cython_arr, sizeof(__pyx_k_Empty_shape_tuple_for_cython_arr), 0, 0, 1, 0}, + {&__pyx_n_s_ImportError, __pyx_k_ImportError, sizeof(__pyx_k_ImportError), 0, 0, 1, 1}, + {&__pyx_kp_s_Incompatible_checksums_0x_x_vs_0, __pyx_k_Incompatible_checksums_0x_x_vs_0, sizeof(__pyx_k_Incompatible_checksums_0x_x_vs_0), 0, 0, 1, 0}, + {&__pyx_n_s_IndexError, __pyx_k_IndexError, sizeof(__pyx_k_IndexError), 0, 0, 1, 1}, + {&__pyx_kp_s_Index_out_of_bounds_axis_d, __pyx_k_Index_out_of_bounds_axis_d, sizeof(__pyx_k_Index_out_of_bounds_axis_d), 0, 0, 1, 0}, + {&__pyx_kp_s_Indirect_dimensions_not_supporte, __pyx_k_Indirect_dimensions_not_supporte, sizeof(__pyx_k_Indirect_dimensions_not_supporte), 0, 0, 1, 0}, + {&__pyx_kp_u_Invalid_mode_expected_c_or_fortr, __pyx_k_Invalid_mode_expected_c_or_fortr, sizeof(__pyx_k_Invalid_mode_expected_c_or_fortr), 0, 1, 0, 0}, + {&__pyx_kp_u_Invalid_shape_in_axis, __pyx_k_Invalid_shape_in_axis, sizeof(__pyx_k_Invalid_shape_in_axis), 0, 1, 0, 0}, + {&__pyx_n_s_MemoryError, __pyx_k_MemoryError, sizeof(__pyx_k_MemoryError), 0, 0, 1, 1}, + {&__pyx_kp_s_MemoryView_of_r_at_0x_x, __pyx_k_MemoryView_of_r_at_0x_x, sizeof(__pyx_k_MemoryView_of_r_at_0x_x), 0, 0, 1, 0}, + {&__pyx_kp_s_MemoryView_of_r_object, __pyx_k_MemoryView_of_r_object, sizeof(__pyx_k_MemoryView_of_r_object), 0, 0, 1, 0}, + {&__pyx_n_s_N, __pyx_k_N, sizeof(__pyx_k_N), 0, 0, 1, 1}, + {&__pyx_n_s_NotImplementedError, __pyx_k_NotImplementedError, sizeof(__pyx_k_NotImplementedError), 0, 0, 1, 1}, + {&__pyx_n_b_O, __pyx_k_O, sizeof(__pyx_k_O), 0, 0, 0, 1}, + {&__pyx_kp_u_Out_of_bounds_on_buffer_access_a, __pyx_k_Out_of_bounds_on_buffer_access_a, sizeof(__pyx_k_Out_of_bounds_on_buffer_access_a), 0, 1, 0, 0}, + {&__pyx_n_s_P, __pyx_k_P, sizeof(__pyx_k_P), 0, 0, 1, 1}, + {&__pyx_n_s_P_initial, __pyx_k_P_initial, sizeof(__pyx_k_P_initial), 0, 0, 1, 1}, + {&__pyx_n_s_PickleError, __pyx_k_PickleError, sizeof(__pyx_k_PickleError), 0, 0, 1, 1}, + {&__pyx_n_s_Q, __pyx_k_Q, sizeof(__pyx_k_Q), 0, 0, 1, 1}, + {&__pyx_n_s_R, __pyx_k_R, sizeof(__pyx_k_R), 0, 0, 1, 1}, + {&__pyx_n_s_R_map, __pyx_k_R_map, sizeof(__pyx_k_R_map), 0, 0, 1, 1}, + {&__pyx_n_s_Ri, __pyx_k_Ri, sizeof(__pyx_k_Ri), 0, 0, 1, 1}, + {&__pyx_n_s_Ri_b, __pyx_k_Ri_b, sizeof(__pyx_k_Ri_b), 0, 0, 1, 1}, + {&__pyx_n_s_Sequence, __pyx_k_Sequence, sizeof(__pyx_k_Sequence), 0, 0, 1, 1}, + {&__pyx_kp_s_Step_may_not_be_zero_axis_d, __pyx_k_Step_may_not_be_zero_axis_d, sizeof(__pyx_k_Step_may_not_be_zero_axis_d), 0, 0, 1, 0}, + {&__pyx_kp_b_T, __pyx_k_T, sizeof(__pyx_k_T), 0, 0, 0, 0}, + {&__pyx_n_s_TypeError, __pyx_k_TypeError, sizeof(__pyx_k_TypeError), 0, 0, 1, 1}, + {&__pyx_kp_s_Unable_to_convert_item_to_object, __pyx_k_Unable_to_convert_item_to_object, sizeof(__pyx_k_Unable_to_convert_item_to_object), 0, 0, 1, 0}, + {&__pyx_n_s_ValueError, __pyx_k_ValueError, sizeof(__pyx_k_ValueError), 0, 0, 1, 1}, + {&__pyx_n_s_View_MemoryView, __pyx_k_View_MemoryView, sizeof(__pyx_k_View_MemoryView), 0, 0, 1, 1}, + {&__pyx_kp_b__10, __pyx_k__10, sizeof(__pyx_k__10), 0, 0, 0, 0}, + {&__pyx_kp_b__11, __pyx_k__11, sizeof(__pyx_k__11), 0, 0, 0, 0}, + {&__pyx_kp_b__12, __pyx_k__12, sizeof(__pyx_k__12), 0, 0, 0, 0}, + {&__pyx_kp_u__13, __pyx_k__13, sizeof(__pyx_k__13), 0, 1, 0, 0}, + {&__pyx_kp_u__14, __pyx_k__14, sizeof(__pyx_k__14), 0, 1, 0, 0}, + {&__pyx_kp_u__2, __pyx_k__2, sizeof(__pyx_k__2), 0, 1, 0, 0}, + {&__pyx_n_s__3, __pyx_k__3, sizeof(__pyx_k__3), 0, 0, 1, 1}, + {&__pyx_n_s__58, __pyx_k__58, sizeof(__pyx_k__58), 0, 0, 1, 1}, + {&__pyx_kp_u__6, __pyx_k__6, sizeof(__pyx_k__6), 0, 1, 0, 0}, + {&__pyx_kp_u__7, __pyx_k__7, sizeof(__pyx_k__7), 0, 1, 0, 0}, + {&__pyx_kp_b__9, __pyx_k__9, sizeof(__pyx_k__9), 0, 0, 0, 0}, + {&__pyx_n_s_a, __pyx_k_a, sizeof(__pyx_k_a), 0, 0, 1, 1}, + {&__pyx_n_s_abc, __pyx_k_abc, sizeof(__pyx_k_abc), 0, 0, 1, 1}, + {&__pyx_n_s_allocate_buffer, __pyx_k_allocate_buffer, sizeof(__pyx_k_allocate_buffer), 0, 0, 1, 1}, + {&__pyx_kp_u_and, __pyx_k_and, sizeof(__pyx_k_and), 0, 1, 0, 0}, + {&__pyx_n_s_args, __pyx_k_args, sizeof(__pyx_k_args), 0, 0, 1, 1}, + {&__pyx_n_s_args_map, __pyx_k_args_map, sizeof(__pyx_k_args_map), 0, 0, 1, 1}, + {&__pyx_n_s_asarray, __pyx_k_asarray, sizeof(__pyx_k_asarray), 0, 0, 1, 1}, + {&__pyx_n_s_ascontiguousarray, __pyx_k_ascontiguousarray, sizeof(__pyx_k_ascontiguousarray), 0, 0, 1, 1}, + {&__pyx_n_s_asyncio_coroutines, __pyx_k_asyncio_coroutines, sizeof(__pyx_k_asyncio_coroutines), 0, 0, 1, 1}, + {&__pyx_n_s_augment, __pyx_k_augment, sizeof(__pyx_k_augment), 0, 0, 1, 1}, + {&__pyx_n_s_base, __pyx_k_base, sizeof(__pyx_k_base), 0, 0, 1, 1}, + {&__pyx_n_s_c, __pyx_k_c, sizeof(__pyx_k_c), 0, 0, 1, 1}, + {&__pyx_n_u_c, __pyx_k_c, sizeof(__pyx_k_c), 0, 1, 0, 1}, + {&__pyx_n_s_class, __pyx_k_class, sizeof(__pyx_k_class), 0, 0, 1, 1}, + {&__pyx_n_s_class_getitem, __pyx_k_class_getitem, sizeof(__pyx_k_class_getitem), 0, 0, 1, 1}, + {&__pyx_n_s_cline_in_traceback, __pyx_k_cline_in_traceback, sizeof(__pyx_k_cline_in_traceback), 0, 0, 1, 1}, + {&__pyx_n_s_collections, __pyx_k_collections, sizeof(__pyx_k_collections), 0, 0, 1, 1}, + {&__pyx_kp_s_collections_abc, __pyx_k_collections_abc, sizeof(__pyx_k_collections_abc), 0, 0, 1, 0}, + {&__pyx_kp_s_contiguous_and_direct, __pyx_k_contiguous_and_direct, sizeof(__pyx_k_contiguous_and_direct), 0, 0, 1, 0}, + {&__pyx_kp_s_contiguous_and_indirect, __pyx_k_contiguous_and_indirect, sizeof(__pyx_k_contiguous_and_indirect), 0, 0, 1, 0}, + {&__pyx_n_s_copy, __pyx_k_copy, sizeof(__pyx_k_copy), 0, 0, 1, 1}, + {&__pyx_n_s_count, __pyx_k_count, sizeof(__pyx_k_count), 0, 0, 1, 1}, + {&__pyx_n_s_covs, __pyx_k_covs, sizeof(__pyx_k_covs), 0, 0, 1, 1}, + {&__pyx_n_s_covs_b, __pyx_k_covs_b, sizeof(__pyx_k_covs_b), 0, 0, 1, 1}, + {&__pyx_n_s_dict, __pyx_k_dict, sizeof(__pyx_k_dict), 0, 0, 1, 1}, + {&__pyx_n_s_dim_augment, __pyx_k_dim_augment, sizeof(__pyx_k_dim_augment), 0, 0, 1, 1}, + {&__pyx_n_s_dim_augment_err, __pyx_k_dim_augment_err, sizeof(__pyx_k_dim_augment_err), 0, 0, 1, 1}, + {&__pyx_n_s_dim_main, __pyx_k_dim_main, sizeof(__pyx_k_dim_main), 0, 0, 1, 1}, + {&__pyx_n_s_dim_main_err, __pyx_k_dim_main_err, sizeof(__pyx_k_dim_main_err), 0, 0, 1, 1}, + {&__pyx_kp_u_disable, __pyx_k_disable, sizeof(__pyx_k_disable), 0, 1, 0, 0}, + {&__pyx_n_s_double, __pyx_k_double, sizeof(__pyx_k_double), 0, 0, 1, 1}, + {&__pyx_n_s_dtype, __pyx_k_dtype, sizeof(__pyx_k_dtype), 0, 0, 1, 1}, + {&__pyx_n_s_dtype_is_object, __pyx_k_dtype_is_object, sizeof(__pyx_k_dtype_is_object), 0, 0, 1, 1}, + {&__pyx_kp_u_enable, __pyx_k_enable, sizeof(__pyx_k_enable), 0, 1, 0, 0}, + {&__pyx_n_s_encode, __pyx_k_encode, sizeof(__pyx_k_encode), 0, 0, 1, 1}, + {&__pyx_n_s_enumerate, __pyx_k_enumerate, sizeof(__pyx_k_enumerate), 0, 0, 1, 1}, + {&__pyx_n_s_error, __pyx_k_error, sizeof(__pyx_k_error), 0, 0, 1, 1}, + {&__pyx_n_s_estimates, __pyx_k_estimates, sizeof(__pyx_k_estimates), 0, 0, 1, 1}, + {&__pyx_n_s_extra_args, __pyx_k_extra_args, sizeof(__pyx_k_extra_args), 0, 0, 1, 1}, + {&__pyx_n_s_extra_args_map, __pyx_k_extra_args_map, sizeof(__pyx_k_extra_args_map), 0, 0, 1, 1}, + {&__pyx_n_s_filter_time, __pyx_k_filter_time, sizeof(__pyx_k_filter_time), 0, 0, 1, 1}, + {&__pyx_n_s_flags, __pyx_k_flags, sizeof(__pyx_k_flags), 0, 0, 1, 1}, + {&__pyx_n_s_format, __pyx_k_format, sizeof(__pyx_k_format), 0, 0, 1, 1}, + {&__pyx_n_s_fortran, __pyx_k_fortran, sizeof(__pyx_k_fortran), 0, 0, 1, 1}, + {&__pyx_n_u_fortran, __pyx_k_fortran, sizeof(__pyx_k_fortran), 0, 1, 0, 1}, + {&__pyx_kp_u_gc, __pyx_k_gc, sizeof(__pyx_k_gc), 0, 1, 0, 0}, + {&__pyx_n_s_gen_dir, __pyx_k_gen_dir, sizeof(__pyx_k_gen_dir), 0, 0, 1, 1}, + {&__pyx_n_s_get_augment_times, __pyx_k_get_augment_times, sizeof(__pyx_k_get_augment_times), 0, 0, 1, 1}, + {&__pyx_n_s_get_filter_time, __pyx_k_get_filter_time, sizeof(__pyx_k_get_filter_time), 0, 0, 1, 1}, + {&__pyx_n_s_getstate, __pyx_k_getstate, sizeof(__pyx_k_getstate), 0, 0, 1, 1}, + {&__pyx_n_s_global_var, __pyx_k_global_var, sizeof(__pyx_k_global_var), 0, 0, 1, 1}, + {&__pyx_n_s_global_vars, __pyx_k_global_vars, sizeof(__pyx_k_global_vars), 0, 0, 1, 1}, + {&__pyx_kp_u_got, __pyx_k_got, sizeof(__pyx_k_got), 0, 1, 0, 0}, + {&__pyx_kp_u_got_differing_extents_in_dimensi, __pyx_k_got_differing_extents_in_dimensi, sizeof(__pyx_k_got_differing_extents_in_dimensi), 0, 1, 0, 0}, + {&__pyx_n_s_id, __pyx_k_id, sizeof(__pyx_k_id), 0, 0, 1, 1}, + {&__pyx_n_s_import, __pyx_k_import, sizeof(__pyx_k_import), 0, 0, 1, 1}, + {&__pyx_n_s_index, __pyx_k_index, sizeof(__pyx_k_index), 0, 0, 1, 1}, + {&__pyx_n_s_init_state, __pyx_k_init_state, sizeof(__pyx_k_init_state), 0, 0, 1, 1}, + {&__pyx_n_s_initializing, __pyx_k_initializing, sizeof(__pyx_k_initializing), 0, 0, 1, 1}, + {&__pyx_n_s_is_coroutine, __pyx_k_is_coroutine, sizeof(__pyx_k_is_coroutine), 0, 0, 1, 1}, + {&__pyx_kp_u_isenabled, __pyx_k_isenabled, sizeof(__pyx_k_isenabled), 0, 1, 0, 0}, + {&__pyx_n_s_itemsize, __pyx_k_itemsize, sizeof(__pyx_k_itemsize), 0, 0, 1, 1}, + {&__pyx_kp_s_itemsize_0_for_cython_array, __pyx_k_itemsize_0_for_cython_array, sizeof(__pyx_k_itemsize_0_for_cython_array), 0, 0, 1, 0}, + {&__pyx_n_s_join, __pyx_k_join, sizeof(__pyx_k_join), 0, 0, 1, 1}, + {&__pyx_n_s_kind, __pyx_k_kind, sizeof(__pyx_k_kind), 0, 0, 1, 1}, + {&__pyx_n_s_logger, __pyx_k_logger, sizeof(__pyx_k_logger), 0, 0, 1, 1}, + {&__pyx_n_s_maha_test, __pyx_k_maha_test, sizeof(__pyx_k_maha_test), 0, 0, 1, 1}, + {&__pyx_n_s_maha_test_kinds, __pyx_k_maha_test_kinds, sizeof(__pyx_k_maha_test_kinds), 0, 0, 1, 1}, + {&__pyx_n_s_maha_thresh, __pyx_k_maha_thresh, sizeof(__pyx_k_maha_thresh), 0, 0, 1, 1}, + {&__pyx_n_s_main, __pyx_k_main, sizeof(__pyx_k_main), 0, 0, 1, 1}, + {&__pyx_n_s_max_rewind_age, __pyx_k_max_rewind_age, sizeof(__pyx_k_max_rewind_age), 0, 0, 1, 1}, + {&__pyx_n_s_memview, __pyx_k_memview, sizeof(__pyx_k_memview), 0, 0, 1, 1}, + {&__pyx_n_s_mode, __pyx_k_mode, sizeof(__pyx_k_mode), 0, 0, 1, 1}, + {&__pyx_n_s_name, __pyx_k_name, sizeof(__pyx_k_name), 0, 0, 1, 1}, + {&__pyx_n_s_name_2, __pyx_k_name_2, sizeof(__pyx_k_name_2), 0, 0, 1, 1}, + {&__pyx_n_s_nan, __pyx_k_nan, sizeof(__pyx_k_nan), 0, 0, 1, 1}, + {&__pyx_n_s_ndim, __pyx_k_ndim, sizeof(__pyx_k_ndim), 0, 0, 1, 1}, + {&__pyx_n_s_new, __pyx_k_new, sizeof(__pyx_k_new), 0, 0, 1, 1}, + {&__pyx_kp_s_no_default___reduce___due_to_non, __pyx_k_no_default___reduce___due_to_non, sizeof(__pyx_k_no_default___reduce___due_to_non), 0, 0, 1, 0}, + {&__pyx_n_s_norm_quats, __pyx_k_norm_quats, sizeof(__pyx_k_norm_quats), 0, 0, 1, 1}, + {&__pyx_n_s_np, __pyx_k_np, sizeof(__pyx_k_np), 0, 0, 1, 1}, + {&__pyx_n_s_numpy, __pyx_k_numpy, sizeof(__pyx_k_numpy), 0, 0, 1, 1}, + {&__pyx_kp_u_numpy_core_multiarray_failed_to, __pyx_k_numpy_core_multiarray_failed_to, sizeof(__pyx_k_numpy_core_multiarray_failed_to), 0, 1, 0, 0}, + {&__pyx_kp_u_numpy_core_umath_failed_to_impor, __pyx_k_numpy_core_umath_failed_to_impor, sizeof(__pyx_k_numpy_core_umath_failed_to_impor), 0, 1, 0, 0}, + {&__pyx_n_s_obj, __pyx_k_obj, sizeof(__pyx_k_obj), 0, 0, 1, 1}, + {&__pyx_n_s_order, __pyx_k_order, sizeof(__pyx_k_order), 0, 0, 1, 1}, + {&__pyx_n_s_pack, __pyx_k_pack, sizeof(__pyx_k_pack), 0, 0, 1, 1}, + {&__pyx_n_s_pickle, __pyx_k_pickle, sizeof(__pyx_k_pickle), 0, 0, 1, 1}, + {&__pyx_n_s_predict, __pyx_k_predict, sizeof(__pyx_k_predict), 0, 0, 1, 1}, + {&__pyx_n_s_predict_and_update_batch, __pyx_k_predict_and_update_batch, sizeof(__pyx_k_predict_and_update_batch), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_PickleError, __pyx_k_pyx_PickleError, sizeof(__pyx_k_pyx_PickleError), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_checksum, __pyx_k_pyx_checksum, sizeof(__pyx_k_pyx_checksum), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_result, __pyx_k_pyx_result, sizeof(__pyx_k_pyx_result), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_state, __pyx_k_pyx_state, sizeof(__pyx_k_pyx_state), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_type, __pyx_k_pyx_type, sizeof(__pyx_k_pyx_type), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_unpickle_Enum, __pyx_k_pyx_unpickle_Enum, sizeof(__pyx_k_pyx_unpickle_Enum), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_vtable, __pyx_k_pyx_vtable, sizeof(__pyx_k_pyx_vtable), 0, 0, 1, 1}, + {&__pyx_n_s_quaternion_idxs, __pyx_k_quaternion_idxs, sizeof(__pyx_k_quaternion_idxs), 0, 0, 1, 1}, + {&__pyx_n_s_range, __pyx_k_range, sizeof(__pyx_k_range), 0, 0, 1, 1}, + {&__pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_k_rednose_helpers_ekf_sym_pyx, sizeof(__pyx_k_rednose_helpers_ekf_sym_pyx), 0, 0, 1, 1}, + {&__pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx, __pyx_k_rednose_helpers_ekf_sym_pyx_pyx, sizeof(__pyx_k_rednose_helpers_ekf_sym_pyx_pyx), 0, 0, 1, 0}, + {&__pyx_n_s_reduce, __pyx_k_reduce, sizeof(__pyx_k_reduce), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_cython, __pyx_k_reduce_cython, sizeof(__pyx_k_reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_ex, __pyx_k_reduce_ex, sizeof(__pyx_k_reduce_ex), 0, 0, 1, 1}, + {&__pyx_n_s_register, __pyx_k_register, sizeof(__pyx_k_register), 0, 0, 1, 1}, + {&__pyx_n_s_res, __pyx_k_res, sizeof(__pyx_k_res), 0, 0, 1, 1}, + {&__pyx_n_s_reset_rewind, __pyx_k_reset_rewind, sizeof(__pyx_k_reset_rewind), 0, 0, 1, 1}, + {&__pyx_n_s_rts_smooth, __pyx_k_rts_smooth, sizeof(__pyx_k_rts_smooth), 0, 0, 1, 1}, + {&__pyx_n_s_self, __pyx_k_self, sizeof(__pyx_k_self), 0, 0, 1, 1}, + {&__pyx_n_s_set_filter_time, __pyx_k_set_filter_time, sizeof(__pyx_k_set_filter_time), 0, 0, 1, 1}, + {&__pyx_n_s_set_global, __pyx_k_set_global, sizeof(__pyx_k_set_global), 0, 0, 1, 1}, + {&__pyx_n_s_setstate, __pyx_k_setstate, sizeof(__pyx_k_setstate), 0, 0, 1, 1}, + {&__pyx_n_s_setstate_cython, __pyx_k_setstate_cython, sizeof(__pyx_k_setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_shape, __pyx_k_shape, sizeof(__pyx_k_shape), 0, 0, 1, 1}, + {&__pyx_n_s_size, __pyx_k_size, sizeof(__pyx_k_size), 0, 0, 1, 1}, + {&__pyx_n_s_spec, __pyx_k_spec, sizeof(__pyx_k_spec), 0, 0, 1, 1}, + {&__pyx_n_s_start, __pyx_k_start, sizeof(__pyx_k_start), 0, 0, 1, 1}, + {&__pyx_n_s_state, __pyx_k_state, sizeof(__pyx_k_state), 0, 0, 1, 1}, + {&__pyx_n_s_state_b, __pyx_k_state_b, sizeof(__pyx_k_state_b), 0, 0, 1, 1}, + {&__pyx_n_s_step, __pyx_k_step, sizeof(__pyx_k_step), 0, 0, 1, 1}, + {&__pyx_n_s_stop, __pyx_k_stop, sizeof(__pyx_k_stop), 0, 0, 1, 1}, + {&__pyx_kp_s_strided_and_direct, __pyx_k_strided_and_direct, sizeof(__pyx_k_strided_and_direct), 0, 0, 1, 0}, + {&__pyx_kp_s_strided_and_direct_or_indirect, __pyx_k_strided_and_direct_or_indirect, sizeof(__pyx_k_strided_and_direct_or_indirect), 0, 0, 1, 0}, + {&__pyx_kp_s_strided_and_indirect, __pyx_k_strided_and_indirect, sizeof(__pyx_k_strided_and_indirect), 0, 0, 1, 0}, + {&__pyx_kp_s_stringsource, __pyx_k_stringsource, sizeof(__pyx_k_stringsource), 0, 0, 1, 0}, + {&__pyx_n_s_struct, __pyx_k_struct, sizeof(__pyx_k_struct), 0, 0, 1, 1}, + {&__pyx_n_s_sys, __pyx_k_sys, sizeof(__pyx_k_sys), 0, 0, 1, 1}, + {&__pyx_n_s_t, __pyx_k_t, sizeof(__pyx_k_t), 0, 0, 1, 1}, + {&__pyx_n_s_test, __pyx_k_test, sizeof(__pyx_k_test), 0, 0, 1, 1}, + {&__pyx_n_s_tmpvec, __pyx_k_tmpvec, sizeof(__pyx_k_tmpvec), 0, 0, 1, 1}, + {&__pyx_kp_s_unable_to_allocate_array_data, __pyx_k_unable_to_allocate_array_data, sizeof(__pyx_k_unable_to_allocate_array_data), 0, 0, 1, 0}, + {&__pyx_kp_s_unable_to_allocate_shape_and_str, __pyx_k_unable_to_allocate_shape_and_str, sizeof(__pyx_k_unable_to_allocate_shape_and_str), 0, 0, 1, 0}, + {&__pyx_n_s_unpack, __pyx_k_unpack, sizeof(__pyx_k_unpack), 0, 0, 1, 1}, + {&__pyx_n_s_update, __pyx_k_update, sizeof(__pyx_k_update), 0, 0, 1, 1}, + {&__pyx_n_u_utf8, __pyx_k_utf8, sizeof(__pyx_k_utf8), 0, 1, 0, 1}, + {&__pyx_n_s_val, __pyx_k_val, sizeof(__pyx_k_val), 0, 0, 1, 1}, + {&__pyx_n_s_version_info, __pyx_k_version_info, sizeof(__pyx_k_version_info), 0, 0, 1, 1}, + {&__pyx_n_s_x, __pyx_k_x, sizeof(__pyx_k_x), 0, 0, 1, 1}, + {&__pyx_n_s_x_initial, __pyx_k_x_initial, sizeof(__pyx_k_x_initial), 0, 0, 1, 1}, + {&__pyx_n_s_z, __pyx_k_z, sizeof(__pyx_k_z), 0, 0, 1, 1}, + {&__pyx_n_s_z_map, __pyx_k_z_map, sizeof(__pyx_k_z_map), 0, 0, 1, 1}, + {&__pyx_n_s_zi, __pyx_k_zi, sizeof(__pyx_k_zi), 0, 0, 1, 1}, + {&__pyx_n_s_zi_b, __pyx_k_zi_b, sizeof(__pyx_k_zi_b), 0, 0, 1, 1}, + {0, 0, 0, 0, 0, 0, 0} + }; + return __Pyx_InitStrings(__pyx_string_tab); +} +/* #### Code section: cached_builtins ### */ +static CYTHON_SMALL_CODE int __Pyx_InitCachedBuiltins(void) { + __pyx_builtin_NotImplementedError = __Pyx_GetBuiltinName(__pyx_n_s_NotImplementedError); if (!__pyx_builtin_NotImplementedError) __PYX_ERR(0, 183, __pyx_L1_error) + __pyx_builtin_TypeError = __Pyx_GetBuiltinName(__pyx_n_s_TypeError); if (!__pyx_builtin_TypeError) __PYX_ERR(1, 2, __pyx_L1_error) + __pyx_builtin___import__ = __Pyx_GetBuiltinName(__pyx_n_s_import); if (!__pyx_builtin___import__) __PYX_ERR(1, 100, __pyx_L1_error) + __pyx_builtin_ValueError = __Pyx_GetBuiltinName(__pyx_n_s_ValueError); if (!__pyx_builtin_ValueError) __PYX_ERR(1, 141, __pyx_L1_error) + __pyx_builtin_MemoryError = __Pyx_GetBuiltinName(__pyx_n_s_MemoryError); if (!__pyx_builtin_MemoryError) __PYX_ERR(1, 156, __pyx_L1_error) + __pyx_builtin_enumerate = __Pyx_GetBuiltinName(__pyx_n_s_enumerate); if (!__pyx_builtin_enumerate) __PYX_ERR(1, 159, __pyx_L1_error) + __pyx_builtin_range = __Pyx_GetBuiltinName(__pyx_n_s_range); if (!__pyx_builtin_range) __PYX_ERR(1, 261, __pyx_L1_error) + __pyx_builtin_AssertionError = __Pyx_GetBuiltinName(__pyx_n_s_AssertionError); if (!__pyx_builtin_AssertionError) __PYX_ERR(1, 373, __pyx_L1_error) + __pyx_builtin_Ellipsis = __Pyx_GetBuiltinName(__pyx_n_s_Ellipsis); if (!__pyx_builtin_Ellipsis) __PYX_ERR(1, 408, __pyx_L1_error) + __pyx_builtin_id = __Pyx_GetBuiltinName(__pyx_n_s_id); if (!__pyx_builtin_id) __PYX_ERR(1, 618, __pyx_L1_error) + __pyx_builtin_IndexError = __Pyx_GetBuiltinName(__pyx_n_s_IndexError); if (!__pyx_builtin_IndexError) __PYX_ERR(1, 914, __pyx_L1_error) + __pyx_builtin_ImportError = __Pyx_GetBuiltinName(__pyx_n_s_ImportError); if (!__pyx_builtin_ImportError) __PYX_ERR(2, 984, __pyx_L1_error) + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: cached_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_InitCachedConstants", 0); + + /* "View.MemoryView":582 + * def suboffsets(self): + * if self.view.suboffsets == NULL: + * return (-1,) * self.view.ndim # <<<<<<<<<<<<<< + * + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + */ + __pyx_tuple__4 = PyTuple_New(1); if (unlikely(!__pyx_tuple__4)) __PYX_ERR(1, 582, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__4); + __Pyx_INCREF(__pyx_int_neg_1); + __Pyx_GIVEREF(__pyx_int_neg_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_tuple__4, 0, __pyx_int_neg_1)) __PYX_ERR(1, 582, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_tuple__4); + + /* "View.MemoryView":679 + * tup = index if isinstance(index, tuple) else (index,) + * + * result = [slice(None)] * ndim # <<<<<<<<<<<<<< + * have_slices = False + * seen_ellipsis = False + */ + __pyx_slice__5 = PySlice_New(Py_None, Py_None, Py_None); if (unlikely(!__pyx_slice__5)) __PYX_ERR(1, 679, __pyx_L1_error) + __Pyx_GOTREF(__pyx_slice__5); + __Pyx_GIVEREF(__pyx_slice__5); + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + */ + __pyx_tuple__8 = PyTuple_Pack(3, __pyx_int_136983863, __pyx_int_112105877, __pyx_int_184977713); if (unlikely(!__pyx_tuple__8)) __PYX_ERR(1, 4, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__8); + __Pyx_GIVEREF(__pyx_tuple__8); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":984 + * __pyx_import_array() + * except Exception: + * raise ImportError("numpy.core.multiarray failed to import") # <<<<<<<<<<<<<< + * + * cdef inline int import_umath() except -1: + */ + __pyx_tuple__15 = PyTuple_Pack(1, __pyx_kp_u_numpy_core_multiarray_failed_to); if (unlikely(!__pyx_tuple__15)) __PYX_ERR(2, 984, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__15); + __Pyx_GIVEREF(__pyx_tuple__15); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":990 + * _import_umath() + * except Exception: + * raise ImportError("numpy.core.umath failed to import") # <<<<<<<<<<<<<< + * + * cdef inline int import_ufunc() except -1: + */ + __pyx_tuple__16 = PyTuple_Pack(1, __pyx_kp_u_numpy_core_umath_failed_to_impor); if (unlikely(!__pyx_tuple__16)) __PYX_ERR(2, 990, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__16); + __Pyx_GIVEREF(__pyx_tuple__16); + + /* "View.MemoryView":100 + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: + * if __import__("sys").version_info >= (3, 3): # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + */ + __pyx_tuple__37 = PyTuple_Pack(1, __pyx_n_s_sys); if (unlikely(!__pyx_tuple__37)) __PYX_ERR(1, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__37); + __Pyx_GIVEREF(__pyx_tuple__37); + __pyx_tuple__38 = PyTuple_Pack(2, __pyx_int_3, __pyx_int_3); if (unlikely(!__pyx_tuple__38)) __PYX_ERR(1, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__38); + __Pyx_GIVEREF(__pyx_tuple__38); + + /* "View.MemoryView":101 + * try: + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence # <<<<<<<<<<<<<< + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence + */ + __pyx_tuple__39 = PyTuple_Pack(1, __pyx_kp_s_collections_abc); if (unlikely(!__pyx_tuple__39)) __PYX_ERR(1, 101, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__39); + __Pyx_GIVEREF(__pyx_tuple__39); + + /* "View.MemoryView":103 + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence # <<<<<<<<<<<<<< + * except: + * + */ + __pyx_tuple__40 = PyTuple_Pack(1, __pyx_n_s_collections); if (unlikely(!__pyx_tuple__40)) __PYX_ERR(1, 103, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__40); + __Pyx_GIVEREF(__pyx_tuple__40); + + /* "View.MemoryView":309 + * return self.name + * + * cdef generic = Enum("") # <<<<<<<<<<<<<< + * cdef strided = Enum("") # default + * cdef indirect = Enum("") + */ + __pyx_tuple__41 = PyTuple_Pack(1, __pyx_kp_s_strided_and_direct_or_indirect); if (unlikely(!__pyx_tuple__41)) __PYX_ERR(1, 309, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__41); + __Pyx_GIVEREF(__pyx_tuple__41); + + /* "View.MemoryView":310 + * + * cdef generic = Enum("") + * cdef strided = Enum("") # default # <<<<<<<<<<<<<< + * cdef indirect = Enum("") + * + */ + __pyx_tuple__42 = PyTuple_Pack(1, __pyx_kp_s_strided_and_direct); if (unlikely(!__pyx_tuple__42)) __PYX_ERR(1, 310, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__42); + __Pyx_GIVEREF(__pyx_tuple__42); + + /* "View.MemoryView":311 + * cdef generic = Enum("") + * cdef strided = Enum("") # default + * cdef indirect = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_tuple__43 = PyTuple_Pack(1, __pyx_kp_s_strided_and_indirect); if (unlikely(!__pyx_tuple__43)) __PYX_ERR(1, 311, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__43); + __Pyx_GIVEREF(__pyx_tuple__43); + + /* "View.MemoryView":314 + * + * + * cdef contiguous = Enum("") # <<<<<<<<<<<<<< + * cdef indirect_contiguous = Enum("") + * + */ + __pyx_tuple__44 = PyTuple_Pack(1, __pyx_kp_s_contiguous_and_direct); if (unlikely(!__pyx_tuple__44)) __PYX_ERR(1, 314, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__44); + __Pyx_GIVEREF(__pyx_tuple__44); + + /* "View.MemoryView":315 + * + * cdef contiguous = Enum("") + * cdef indirect_contiguous = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_tuple__45 = PyTuple_Pack(1, __pyx_kp_s_contiguous_and_indirect); if (unlikely(!__pyx_tuple__45)) __PYX_ERR(1, 315, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__45); + __Pyx_GIVEREF(__pyx_tuple__45); + + /* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + __pyx_tuple__46 = PyTuple_Pack(5, __pyx_n_s_pyx_type, __pyx_n_s_pyx_checksum, __pyx_n_s_pyx_state, __pyx_n_s_pyx_PickleError, __pyx_n_s_pyx_result); if (unlikely(!__pyx_tuple__46)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__46); + __Pyx_GIVEREF(__pyx_tuple__46); + __pyx_codeobj__47 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__46, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_pyx_unpickle_Enum, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__47)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "rednose/helpers/ekf_sym_pyx.pyx":113 + * ) + * + * def init_state(self, np.ndarray[np.float64_t, ndim=1] state, np.ndarray[np.float64_t, ndim=2] covs, filter_time): # <<<<<<<<<<<<<< + * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] state_b = np.ascontiguousarray(state, dtype=np.double) + * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] covs_b = np.ascontiguousarray(covs, dtype=np.double) + */ + __pyx_tuple__48 = PyTuple_Pack(6, __pyx_n_s_self, __pyx_n_s_state, __pyx_n_s_covs, __pyx_n_s_filter_time, __pyx_n_s_state_b, __pyx_n_s_covs_b); if (unlikely(!__pyx_tuple__48)) __PYX_ERR(0, 113, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__48); + __Pyx_GIVEREF(__pyx_tuple__48); + __pyx_codeobj__20 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 6, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__48, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx, __pyx_n_s_init_state, 113, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__20)) __PYX_ERR(0, 113, __pyx_L1_error) + + /* "rednose/helpers/ekf_sym_pyx.pyx":122 + * ) + * + * def state(self): # <<<<<<<<<<<<<< + * cdef np.ndarray res = vector_to_numpy(self.ekf.state()) + * return res + */ + __pyx_tuple__49 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_res); if (unlikely(!__pyx_tuple__49)) __PYX_ERR(0, 122, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__49); + __Pyx_GIVEREF(__pyx_tuple__49); + __pyx_codeobj__21 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__49, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx, __pyx_n_s_state, 122, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__21)) __PYX_ERR(0, 122, __pyx_L1_error) + + /* "rednose/helpers/ekf_sym_pyx.pyx":126 + * return res + * + * def covs(self): # <<<<<<<<<<<<<< + * return matrix_to_numpy(self.ekf.covs()) + * + */ + __pyx_tuple__50 = PyTuple_Pack(1, __pyx_n_s_self); if (unlikely(!__pyx_tuple__50)) __PYX_ERR(0, 126, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__50); + __Pyx_GIVEREF(__pyx_tuple__50); + __pyx_codeobj__22 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__50, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx, __pyx_n_s_covs, 126, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__22)) __PYX_ERR(0, 126, __pyx_L1_error) + + /* "rednose/helpers/ekf_sym_pyx.pyx":129 + * return matrix_to_numpy(self.ekf.covs()) + * + * def set_filter_time(self, double t): # <<<<<<<<<<<<<< + * self.ekf.set_filter_time(t) + * + */ + __pyx_tuple__51 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_t); if (unlikely(!__pyx_tuple__51)) __PYX_ERR(0, 129, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__51); + __Pyx_GIVEREF(__pyx_tuple__51); + __pyx_codeobj__23 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__51, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx, __pyx_n_s_set_filter_time, 129, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__23)) __PYX_ERR(0, 129, __pyx_L1_error) + + /* "rednose/helpers/ekf_sym_pyx.pyx":132 + * self.ekf.set_filter_time(t) + * + * def get_filter_time(self): # <<<<<<<<<<<<<< + * return self.ekf.get_filter_time() + * + */ + __pyx_codeobj__24 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__50, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx, __pyx_n_s_get_filter_time, 132, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__24)) __PYX_ERR(0, 132, __pyx_L1_error) + + /* "rednose/helpers/ekf_sym_pyx.pyx":135 + * return self.ekf.get_filter_time() + * + * def set_global(self, str global_var, double val): # <<<<<<<<<<<<<< + * self.ekf.set_global(global_var.encode('utf8'), val) + * + */ + __pyx_tuple__52 = PyTuple_Pack(3, __pyx_n_s_self, __pyx_n_s_global_var, __pyx_n_s_val); if (unlikely(!__pyx_tuple__52)) __PYX_ERR(0, 135, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__52); + __Pyx_GIVEREF(__pyx_tuple__52); + __pyx_codeobj__25 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__52, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx, __pyx_n_s_set_global, 135, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__25)) __PYX_ERR(0, 135, __pyx_L1_error) + + /* "rednose/helpers/ekf_sym_pyx.pyx":138 + * self.ekf.set_global(global_var.encode('utf8'), val) + * + * def reset_rewind(self): # <<<<<<<<<<<<<< + * self.ekf.reset_rewind() + * + */ + __pyx_codeobj__26 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__50, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx, __pyx_n_s_reset_rewind, 138, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__26)) __PYX_ERR(0, 138, __pyx_L1_error) + + /* "rednose/helpers/ekf_sym_pyx.pyx":141 + * self.ekf.reset_rewind() + * + * def predict(self, double t): # <<<<<<<<<<<<<< + * self.ekf.predict(t) + * + */ + __pyx_codeobj__27 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__51, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx, __pyx_n_s_predict, 141, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__27)) __PYX_ERR(0, 141, __pyx_L1_error) + + /* "rednose/helpers/ekf_sym_pyx.pyx":144 + * self.ekf.predict(t) + * + * def predict_and_update_batch(self, double t, int kind, z, R, extra_args=[[]], bool augment=False): # <<<<<<<<<<<<<< + * cdef vector[MapVectorXd] z_map + * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] zi_b + */ + __pyx_tuple__53 = PyTuple_Pack(20, __pyx_n_s_self, __pyx_n_s_t, __pyx_n_s_kind, __pyx_n_s_z, __pyx_n_s_R, __pyx_n_s_extra_args, __pyx_n_s_augment, __pyx_n_s_z_map, __pyx_n_s_zi_b, __pyx_n_s_zi, __pyx_n_s_R_map, __pyx_n_s_Ri_b, __pyx_n_s_Ri, __pyx_n_s_extra_args_map, __pyx_n_s_args_map, __pyx_n_s_args, __pyx_n_s_a, __pyx_n_s_res, __pyx_n_s_tmpvec, __pyx_n_s_tmpvec); if (unlikely(!__pyx_tuple__53)) __PYX_ERR(0, 144, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__53); + __Pyx_GIVEREF(__pyx_tuple__53); + __pyx_codeobj__29 = (PyObject*)__Pyx_PyCode_New(7, 0, 0, 20, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__53, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx, __pyx_n_s_predict_and_update_batch, 144, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__29)) __PYX_ERR(0, 144, __pyx_L1_error) + + /* "rednose/helpers/ekf_sym_pyx.pyx":182 + * ) + * + * def augment(self): # <<<<<<<<<<<<<< + * raise NotImplementedError() # TODO + * + */ + __pyx_codeobj__30 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__50, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx, __pyx_n_s_augment, 182, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__30)) __PYX_ERR(0, 182, __pyx_L1_error) + + /* "rednose/helpers/ekf_sym_pyx.pyx":185 + * raise NotImplementedError() # TODO + * + * def get_augment_times(self): # <<<<<<<<<<<<<< + * raise NotImplementedError() # TODO + * + */ + __pyx_codeobj__31 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__50, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx, __pyx_n_s_get_augment_times, 185, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__31)) __PYX_ERR(0, 185, __pyx_L1_error) + + /* "rednose/helpers/ekf_sym_pyx.pyx":188 + * raise NotImplementedError() # TODO + * + * def rts_smooth(self, estimates, norm_quats=False): # <<<<<<<<<<<<<< + * raise NotImplementedError() # TODO + * + */ + __pyx_tuple__54 = PyTuple_Pack(3, __pyx_n_s_self, __pyx_n_s_estimates, __pyx_n_s_norm_quats); if (unlikely(!__pyx_tuple__54)) __PYX_ERR(0, 188, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__54); + __Pyx_GIVEREF(__pyx_tuple__54); + __pyx_codeobj__32 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__54, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx, __pyx_n_s_rts_smooth, 188, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__32)) __PYX_ERR(0, 188, __pyx_L1_error) + __pyx_tuple__55 = PyTuple_Pack(1, Py_False); if (unlikely(!__pyx_tuple__55)) __PYX_ERR(0, 188, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__55); + __Pyx_GIVEREF(__pyx_tuple__55); + + /* "rednose/helpers/ekf_sym_pyx.pyx":191 + * raise NotImplementedError() # TODO + * + * def maha_test(self, x, P, kind, z, R, extra_args=[], maha_thresh=0.95): # <<<<<<<<<<<<<< + * raise NotImplementedError() # TODO + * + */ + __pyx_tuple__56 = PyTuple_Pack(8, __pyx_n_s_self, __pyx_n_s_x, __pyx_n_s_P, __pyx_n_s_kind, __pyx_n_s_z, __pyx_n_s_R, __pyx_n_s_extra_args, __pyx_n_s_maha_thresh); if (unlikely(!__pyx_tuple__56)) __PYX_ERR(0, 191, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__56); + __Pyx_GIVEREF(__pyx_tuple__56); + __pyx_codeobj__34 = (PyObject*)__Pyx_PyCode_New(8, 0, 0, 8, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__56, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_rednose_helpers_ekf_sym_pyx_pyx, __pyx_n_s_maha_test, 191, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__34)) __PYX_ERR(0, 191, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_codeobj__35 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__50, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__35)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_tuple__57 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_pyx_state); if (unlikely(!__pyx_tuple__57)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__57); + __Pyx_GIVEREF(__pyx_tuple__57); + __pyx_codeobj__36 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__57, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__36)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_RefNannyFinishContext(); + return -1; +} +/* #### Code section: init_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitConstants(void) { + if (__Pyx_CreateStringTabAndInitStrings() < 0) __PYX_ERR(0, 1, __pyx_L1_error); + __pyx_float_0_95 = PyFloat_FromDouble(0.95); if (unlikely(!__pyx_float_0_95)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_0 = PyInt_FromLong(0); if (unlikely(!__pyx_int_0)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_1 = PyInt_FromLong(1); if (unlikely(!__pyx_int_1)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_3 = PyInt_FromLong(3); if (unlikely(!__pyx_int_3)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_112105877 = PyInt_FromLong(112105877L); if (unlikely(!__pyx_int_112105877)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_136983863 = PyInt_FromLong(136983863L); if (unlikely(!__pyx_int_136983863)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_184977713 = PyInt_FromLong(184977713L); if (unlikely(!__pyx_int_184977713)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_neg_1 = PyInt_FromLong(-1); if (unlikely(!__pyx_int_neg_1)) __PYX_ERR(0, 1, __pyx_L1_error) + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: init_globals ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitGlobals(void) { + /* AssertionsEnabled.init */ + if (likely(__Pyx_init_assertions_enabled() == 0)); else + +if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 1, __pyx_L1_error) + + /* NumpyImportArray.init */ + /* + * Cython has automatically inserted a call to _import_array since + * you didn't include one when you cimported numpy. To disable this + * add the line + * numpy._import_array + */ +#ifdef NPY_FEATURE_VERSION +#ifndef NO_IMPORT_ARRAY +if (unlikely(_import_array() == -1)) { + PyErr_SetString(PyExc_ImportError, "numpy.core.multiarray failed to import " + "(auto-generated because you didn't call 'numpy.import_array()' after cimporting numpy; " + "use 'numpy._import_array' to disable if you are certain you don't need it)."); +} +#endif +#endif + +if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 1, __pyx_L1_error) + + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: init_module ### */ + +static CYTHON_SMALL_CODE int __Pyx_modinit_global_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_import_code(void); /*proto*/ + +static int __Pyx_modinit_global_init_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_global_init_code", 0); + /*--- Global init code ---*/ + __pyx_collections_abc_Sequence = Py_None; Py_INCREF(Py_None); + generic = Py_None; Py_INCREF(Py_None); + strided = Py_None; Py_INCREF(Py_None); + indirect = Py_None; Py_INCREF(Py_None); + contiguous = Py_None; Py_INCREF(Py_None); + indirect_contiguous = Py_None; Py_INCREF(Py_None); + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_variable_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_export_code", 0); + /*--- Variable export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_export_code", 0); + /*--- Function export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_type_init_code(void) { + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_modinit_type_init_code", 0); + /*--- Type init code ---*/ + #if CYTHON_USE_TYPE_SPECS + __pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx_spec, NULL); if (unlikely(!__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx)) __PYX_ERR(0, 85, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx_spec, __pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx) < 0) __PYX_ERR(0, 85, __pyx_L1_error) + #else + __pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx = &__pyx_type_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx) < 0) __PYX_ERR(0, 85, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx->tp_dictoffset && __pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_EKF_sym_pyx, (PyObject *) __pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx) < 0) __PYX_ERR(0, 85, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx) < 0) __PYX_ERR(0, 85, __pyx_L1_error) + #endif + __pyx_vtabptr_array = &__pyx_vtable_array; + __pyx_vtable_array.get_memview = (PyObject *(*)(struct __pyx_array_obj *))__pyx_array_get_memview; + #if CYTHON_USE_TYPE_SPECS + __pyx_array_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_array_spec, NULL); if (unlikely(!__pyx_array_type)) __PYX_ERR(1, 114, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + __pyx_array_type->tp_as_buffer = &__pyx_tp_as_buffer_array; + if (!__pyx_array_type->tp_as_buffer->bf_releasebuffer && __pyx_array_type->tp_base->tp_as_buffer && __pyx_array_type->tp_base->tp_as_buffer->bf_releasebuffer) { + __pyx_array_type->tp_as_buffer->bf_releasebuffer = __pyx_array_type->tp_base->tp_as_buffer->bf_releasebuffer; + } + #elif defined(Py_bf_getbuffer) && defined(Py_bf_releasebuffer) + /* PY_VERSION_HEX >= 0x03090000 || Py_LIMITED_API >= 0x030B0000 */ + #elif defined(_MSC_VER) + #pragma message ("The buffer protocol is not supported in the Limited C-API < 3.11.") + #else + #warning "The buffer protocol is not supported in the Limited C-API < 3.11." + #endif + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_array_spec, __pyx_array_type) < 0) __PYX_ERR(1, 114, __pyx_L1_error) + #else + __pyx_array_type = &__pyx_type___pyx_array; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_array_type) < 0) __PYX_ERR(1, 114, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_array_type->tp_print = 0; + #endif + if (__Pyx_SetVtable(__pyx_array_type, __pyx_vtabptr_array) < 0) __PYX_ERR(1, 114, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_array_type) < 0) __PYX_ERR(1, 114, __pyx_L1_error) + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_array_type) < 0) __PYX_ERR(1, 114, __pyx_L1_error) + #endif + #if CYTHON_USE_TYPE_SPECS + __pyx_MemviewEnum_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_MemviewEnum_spec, NULL); if (unlikely(!__pyx_MemviewEnum_type)) __PYX_ERR(1, 302, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_MemviewEnum_spec, __pyx_MemviewEnum_type) < 0) __PYX_ERR(1, 302, __pyx_L1_error) + #else + __pyx_MemviewEnum_type = &__pyx_type___pyx_MemviewEnum; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_MemviewEnum_type) < 0) __PYX_ERR(1, 302, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_MemviewEnum_type->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_MemviewEnum_type->tp_dictoffset && __pyx_MemviewEnum_type->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_MemviewEnum_type->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_MemviewEnum_type) < 0) __PYX_ERR(1, 302, __pyx_L1_error) + #endif + __pyx_vtabptr_memoryview = &__pyx_vtable_memoryview; + __pyx_vtable_memoryview.get_item_pointer = (char *(*)(struct __pyx_memoryview_obj *, PyObject *))__pyx_memoryview_get_item_pointer; + __pyx_vtable_memoryview.is_slice = (PyObject *(*)(struct __pyx_memoryview_obj *, PyObject *))__pyx_memoryview_is_slice; + __pyx_vtable_memoryview.setitem_slice_assignment = (PyObject *(*)(struct __pyx_memoryview_obj *, PyObject *, PyObject *))__pyx_memoryview_setitem_slice_assignment; + __pyx_vtable_memoryview.setitem_slice_assign_scalar = (PyObject *(*)(struct __pyx_memoryview_obj *, struct __pyx_memoryview_obj *, PyObject *))__pyx_memoryview_setitem_slice_assign_scalar; + __pyx_vtable_memoryview.setitem_indexed = (PyObject *(*)(struct __pyx_memoryview_obj *, PyObject *, PyObject *))__pyx_memoryview_setitem_indexed; + __pyx_vtable_memoryview.convert_item_to_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *))__pyx_memoryview_convert_item_to_object; + __pyx_vtable_memoryview.assign_item_from_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *, PyObject *))__pyx_memoryview_assign_item_from_object; + __pyx_vtable_memoryview._get_base = (PyObject *(*)(struct __pyx_memoryview_obj *))__pyx_memoryview__get_base; + #if CYTHON_USE_TYPE_SPECS + __pyx_memoryview_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_memoryview_spec, NULL); if (unlikely(!__pyx_memoryview_type)) __PYX_ERR(1, 337, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + __pyx_memoryview_type->tp_as_buffer = &__pyx_tp_as_buffer_memoryview; + if (!__pyx_memoryview_type->tp_as_buffer->bf_releasebuffer && __pyx_memoryview_type->tp_base->tp_as_buffer && __pyx_memoryview_type->tp_base->tp_as_buffer->bf_releasebuffer) { + __pyx_memoryview_type->tp_as_buffer->bf_releasebuffer = __pyx_memoryview_type->tp_base->tp_as_buffer->bf_releasebuffer; + } + #elif defined(Py_bf_getbuffer) && defined(Py_bf_releasebuffer) + /* PY_VERSION_HEX >= 0x03090000 || Py_LIMITED_API >= 0x030B0000 */ + #elif defined(_MSC_VER) + #pragma message ("The buffer protocol is not supported in the Limited C-API < 3.11.") + #else + #warning "The buffer protocol is not supported in the Limited C-API < 3.11." + #endif + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_memoryview_spec, __pyx_memoryview_type) < 0) __PYX_ERR(1, 337, __pyx_L1_error) + #else + __pyx_memoryview_type = &__pyx_type___pyx_memoryview; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_memoryview_type) < 0) __PYX_ERR(1, 337, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_memoryview_type->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_memoryview_type->tp_dictoffset && __pyx_memoryview_type->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_memoryview_type->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (__Pyx_SetVtable(__pyx_memoryview_type, __pyx_vtabptr_memoryview) < 0) __PYX_ERR(1, 337, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_memoryview_type) < 0) __PYX_ERR(1, 337, __pyx_L1_error) + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_memoryview_type) < 0) __PYX_ERR(1, 337, __pyx_L1_error) + #endif + __pyx_vtabptr__memoryviewslice = &__pyx_vtable__memoryviewslice; + __pyx_vtable__memoryviewslice.__pyx_base = *__pyx_vtabptr_memoryview; + __pyx_vtable__memoryviewslice.__pyx_base.convert_item_to_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *))__pyx_memoryviewslice_convert_item_to_object; + __pyx_vtable__memoryviewslice.__pyx_base.assign_item_from_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *, PyObject *))__pyx_memoryviewslice_assign_item_from_object; + __pyx_vtable__memoryviewslice.__pyx_base._get_base = (PyObject *(*)(struct __pyx_memoryview_obj *))__pyx_memoryviewslice__get_base; + #if CYTHON_USE_TYPE_SPECS + __pyx_t_1 = PyTuple_Pack(1, (PyObject *)__pyx_memoryview_type); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 952, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_memoryviewslice_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_memoryviewslice_spec, __pyx_t_1); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_memoryviewslice_type)) __PYX_ERR(1, 952, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_memoryviewslice_spec, __pyx_memoryviewslice_type) < 0) __PYX_ERR(1, 952, __pyx_L1_error) + #else + __pyx_memoryviewslice_type = &__pyx_type___pyx_memoryviewslice; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + __pyx_memoryviewslice_type->tp_base = __pyx_memoryview_type; + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_memoryviewslice_type) < 0) __PYX_ERR(1, 952, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_memoryviewslice_type->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_memoryviewslice_type->tp_dictoffset && __pyx_memoryviewslice_type->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_memoryviewslice_type->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (__Pyx_SetVtable(__pyx_memoryviewslice_type, __pyx_vtabptr__memoryviewslice) < 0) __PYX_ERR(1, 952, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_memoryviewslice_type) < 0) __PYX_ERR(1, 952, __pyx_L1_error) + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_memoryviewslice_type) < 0) __PYX_ERR(1, 952, __pyx_L1_error) + #endif + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_RefNannyFinishContext(); + return -1; +} + +static int __Pyx_modinit_type_import_code(void) { + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_modinit_type_import_code", 0); + /*--- Type import code ---*/ + __pyx_t_1 = PyImport_ImportModule(__Pyx_BUILTIN_MODULE_NAME); if (unlikely(!__pyx_t_1)) __PYX_ERR(3, 9, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_ptype_7cpython_4type_type = __Pyx_ImportType_3_0_8(__pyx_t_1, __Pyx_BUILTIN_MODULE_NAME, "type", + #if defined(PYPY_VERSION_NUM) && PYPY_VERSION_NUM < 0x050B0000 + sizeof(PyTypeObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyTypeObject), + #elif CYTHON_COMPILING_IN_LIMITED_API + sizeof(PyTypeObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyTypeObject), + #else + sizeof(PyHeapTypeObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyHeapTypeObject), + #endif + __Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_7cpython_4type_type) __PYX_ERR(3, 9, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = PyImport_ImportModule("numpy"); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 202, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_ptype_5numpy_dtype = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "dtype", sizeof(PyArray_Descr), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyArray_Descr),__Pyx_ImportType_CheckSize_Ignore_3_0_8); if (!__pyx_ptype_5numpy_dtype) __PYX_ERR(2, 202, __pyx_L1_error) + __pyx_ptype_5numpy_flatiter = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "flatiter", sizeof(PyArrayIterObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyArrayIterObject),__Pyx_ImportType_CheckSize_Ignore_3_0_8); if (!__pyx_ptype_5numpy_flatiter) __PYX_ERR(2, 225, __pyx_L1_error) + __pyx_ptype_5numpy_broadcast = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "broadcast", sizeof(PyArrayMultiIterObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyArrayMultiIterObject),__Pyx_ImportType_CheckSize_Ignore_3_0_8); if (!__pyx_ptype_5numpy_broadcast) __PYX_ERR(2, 229, __pyx_L1_error) + __pyx_ptype_5numpy_ndarray = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "ndarray", sizeof(PyArrayObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyArrayObject),__Pyx_ImportType_CheckSize_Ignore_3_0_8); if (!__pyx_ptype_5numpy_ndarray) __PYX_ERR(2, 238, __pyx_L1_error) + __pyx_ptype_5numpy_generic = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "generic", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_generic) __PYX_ERR(2, 809, __pyx_L1_error) + __pyx_ptype_5numpy_number = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "number", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_number) __PYX_ERR(2, 811, __pyx_L1_error) + __pyx_ptype_5numpy_integer = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "integer", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_integer) __PYX_ERR(2, 813, __pyx_L1_error) + __pyx_ptype_5numpy_signedinteger = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "signedinteger", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_signedinteger) __PYX_ERR(2, 815, __pyx_L1_error) + __pyx_ptype_5numpy_unsignedinteger = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "unsignedinteger", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_unsignedinteger) __PYX_ERR(2, 817, __pyx_L1_error) + __pyx_ptype_5numpy_inexact = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "inexact", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_inexact) __PYX_ERR(2, 819, __pyx_L1_error) + __pyx_ptype_5numpy_floating = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "floating", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_floating) __PYX_ERR(2, 821, __pyx_L1_error) + __pyx_ptype_5numpy_complexfloating = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "complexfloating", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_complexfloating) __PYX_ERR(2, 823, __pyx_L1_error) + __pyx_ptype_5numpy_flexible = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "flexible", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_flexible) __PYX_ERR(2, 825, __pyx_L1_error) + __pyx_ptype_5numpy_character = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "character", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_character) __PYX_ERR(2, 827, __pyx_L1_error) + __pyx_ptype_5numpy_ufunc = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "ufunc", sizeof(PyUFuncObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyUFuncObject),__Pyx_ImportType_CheckSize_Ignore_3_0_8); if (!__pyx_ptype_5numpy_ufunc) __PYX_ERR(2, 866, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_RefNannyFinishContext(); + return -1; +} + +static int __Pyx_modinit_variable_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_import_code", 0); + /*--- Variable import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_import_code", 0); + /*--- Function import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + + +#if PY_MAJOR_VERSION >= 3 +#if CYTHON_PEP489_MULTI_PHASE_INIT +static PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def); /*proto*/ +static int __pyx_pymod_exec_ekf_sym_pyx(PyObject* module); /*proto*/ +static PyModuleDef_Slot __pyx_moduledef_slots[] = { + {Py_mod_create, (void*)__pyx_pymod_create}, + {Py_mod_exec, (void*)__pyx_pymod_exec_ekf_sym_pyx}, + {0, NULL} +}; +#endif + +#ifdef __cplusplus +namespace { + struct PyModuleDef __pyx_moduledef = + #else + static struct PyModuleDef __pyx_moduledef = + #endif + { + PyModuleDef_HEAD_INIT, + "ekf_sym_pyx", + 0, /* m_doc */ + #if CYTHON_PEP489_MULTI_PHASE_INIT + 0, /* m_size */ + #elif CYTHON_USE_MODULE_STATE + sizeof(__pyx_mstate), /* m_size */ + #else + -1, /* m_size */ + #endif + __pyx_methods /* m_methods */, + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_moduledef_slots, /* m_slots */ + #else + NULL, /* m_reload */ + #endif + #if CYTHON_USE_MODULE_STATE + __pyx_m_traverse, /* m_traverse */ + __pyx_m_clear, /* m_clear */ + NULL /* m_free */ + #else + NULL, /* m_traverse */ + NULL, /* m_clear */ + NULL /* m_free */ + #endif + }; + #ifdef __cplusplus +} /* anonymous namespace */ +#endif +#endif + +#ifndef CYTHON_NO_PYINIT_EXPORT +#define __Pyx_PyMODINIT_FUNC PyMODINIT_FUNC +#elif PY_MAJOR_VERSION < 3 +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" void +#else +#define __Pyx_PyMODINIT_FUNC void +#endif +#else +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" PyObject * +#else +#define __Pyx_PyMODINIT_FUNC PyObject * +#endif +#endif + + +#if PY_MAJOR_VERSION < 3 +__Pyx_PyMODINIT_FUNC initekf_sym_pyx(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC initekf_sym_pyx(void) +#else +__Pyx_PyMODINIT_FUNC PyInit_ekf_sym_pyx(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC PyInit_ekf_sym_pyx(void) +#if CYTHON_PEP489_MULTI_PHASE_INIT +{ + return PyModuleDef_Init(&__pyx_moduledef); +} +static CYTHON_SMALL_CODE int __Pyx_check_single_interpreter(void) { + #if PY_VERSION_HEX >= 0x030700A1 + static PY_INT64_T main_interpreter_id = -1; + PY_INT64_T current_id = PyInterpreterState_GetID(PyThreadState_Get()->interp); + if (main_interpreter_id == -1) { + main_interpreter_id = current_id; + return (unlikely(current_id == -1)) ? -1 : 0; + } else if (unlikely(main_interpreter_id != current_id)) + #else + static PyInterpreterState *main_interpreter = NULL; + PyInterpreterState *current_interpreter = PyThreadState_Get()->interp; + if (!main_interpreter) { + main_interpreter = current_interpreter; + } else if (unlikely(main_interpreter != current_interpreter)) + #endif + { + PyErr_SetString( + PyExc_ImportError, + "Interpreter change detected - this module can only be loaded into one interpreter per process."); + return -1; + } + return 0; +} +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *module, const char* from_name, const char* to_name, int allow_none) +#else +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *moddict, const char* from_name, const char* to_name, int allow_none) +#endif +{ + PyObject *value = PyObject_GetAttrString(spec, from_name); + int result = 0; + if (likely(value)) { + if (allow_none || value != Py_None) { +#if CYTHON_COMPILING_IN_LIMITED_API + result = PyModule_AddObject(module, to_name, value); +#else + result = PyDict_SetItemString(moddict, to_name, value); +#endif + } + Py_DECREF(value); + } else if (PyErr_ExceptionMatches(PyExc_AttributeError)) { + PyErr_Clear(); + } else { + result = -1; + } + return result; +} +static CYTHON_SMALL_CODE PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def) { + PyObject *module = NULL, *moddict, *modname; + CYTHON_UNUSED_VAR(def); + if (__Pyx_check_single_interpreter()) + return NULL; + if (__pyx_m) + return __Pyx_NewRef(__pyx_m); + modname = PyObject_GetAttrString(spec, "name"); + if (unlikely(!modname)) goto bad; + module = PyModule_NewObject(modname); + Py_DECREF(modname); + if (unlikely(!module)) goto bad; +#if CYTHON_COMPILING_IN_LIMITED_API + moddict = module; +#else + moddict = PyModule_GetDict(module); + if (unlikely(!moddict)) goto bad; +#endif + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "loader", "__loader__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "origin", "__file__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "parent", "__package__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "submodule_search_locations", "__path__", 0) < 0)) goto bad; + return module; +bad: + Py_XDECREF(module); + return NULL; +} + + +static CYTHON_SMALL_CODE int __pyx_pymod_exec_ekf_sym_pyx(PyObject *__pyx_pyinit_module) +#endif +#endif +{ + int stringtab_initialized = 0; + #if CYTHON_USE_MODULE_STATE + int pystate_addmodule_run = 0; + #endif + __Pyx_TraceDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + static PyThread_type_lock __pyx_t_8[8]; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannyDeclarations + #if CYTHON_PEP489_MULTI_PHASE_INIT + if (__pyx_m) { + if (__pyx_m == __pyx_pyinit_module) return 0; + PyErr_SetString(PyExc_RuntimeError, "Module 'ekf_sym_pyx' has already been imported. Re-initialisation is not supported."); + return -1; + } + #elif PY_MAJOR_VERSION >= 3 + if (__pyx_m) return __Pyx_NewRef(__pyx_m); + #endif + /*--- Module creation code ---*/ + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_m = __pyx_pyinit_module; + Py_INCREF(__pyx_m); + #else + #if PY_MAJOR_VERSION < 3 + __pyx_m = Py_InitModule4("ekf_sym_pyx", __pyx_methods, 0, 0, PYTHON_API_VERSION); Py_XINCREF(__pyx_m); + if (unlikely(!__pyx_m)) __PYX_ERR(0, 1, __pyx_L1_error) + #elif CYTHON_USE_MODULE_STATE + __pyx_t_1 = PyModule_Create(&__pyx_moduledef); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 1, __pyx_L1_error) + { + int add_module_result = PyState_AddModule(__pyx_t_1, &__pyx_moduledef); + __pyx_t_1 = 0; /* transfer ownership from __pyx_t_1 to "ekf_sym_pyx" pseudovariable */ + if (unlikely((add_module_result < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + pystate_addmodule_run = 1; + } + #else + __pyx_m = PyModule_Create(&__pyx_moduledef); + if (unlikely(!__pyx_m)) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #endif + CYTHON_UNUSED_VAR(__pyx_t_1); + __pyx_d = PyModule_GetDict(__pyx_m); if (unlikely(!__pyx_d)) __PYX_ERR(0, 1, __pyx_L1_error) + Py_INCREF(__pyx_d); + __pyx_b = __Pyx_PyImport_AddModuleRef(__Pyx_BUILTIN_MODULE_NAME); if (unlikely(!__pyx_b)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_cython_runtime = __Pyx_PyImport_AddModuleRef((const char *) "cython_runtime"); if (unlikely(!__pyx_cython_runtime)) __PYX_ERR(0, 1, __pyx_L1_error) + if (PyObject_SetAttrString(__pyx_m, "__builtins__", __pyx_b) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #if CYTHON_REFNANNY +__Pyx_RefNanny = __Pyx_RefNannyImportAPI("refnanny"); +if (!__Pyx_RefNanny) { + PyErr_Clear(); + __Pyx_RefNanny = __Pyx_RefNannyImportAPI("Cython.Runtime.refnanny"); + if (!__Pyx_RefNanny) + Py_FatalError("failed to import 'refnanny' module"); +} +#endif + __Pyx_RefNannySetupContext("__Pyx_PyMODINIT_FUNC PyInit_ekf_sym_pyx(void)", 0); + if (__Pyx_check_binary_version(__PYX_LIMITED_VERSION_HEX, __Pyx_get_runtime_version(), CYTHON_COMPILING_IN_LIMITED_API) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #ifdef __Pxy_PyFrame_Initialize_Offsets + __Pxy_PyFrame_Initialize_Offsets(); + #endif + __pyx_empty_tuple = PyTuple_New(0); if (unlikely(!__pyx_empty_tuple)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_empty_bytes = PyBytes_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_bytes)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_empty_unicode = PyUnicode_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_unicode)) __PYX_ERR(0, 1, __pyx_L1_error) + #ifdef __Pyx_CyFunction_USED + if (__pyx_CyFunction_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_FusedFunction_USED + if (__pyx_FusedFunction_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Coroutine_USED + if (__pyx_Coroutine_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Generator_USED + if (__pyx_Generator_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_AsyncGen_USED + if (__pyx_AsyncGen_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_StopAsyncIteration_USED + if (__pyx_StopAsyncIteration_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + /*--- Library function declarations ---*/ + /*--- Threads initialization code ---*/ + #if defined(WITH_THREAD) && PY_VERSION_HEX < 0x030700F0 && defined(__PYX_FORCE_INIT_THREADS) && __PYX_FORCE_INIT_THREADS + PyEval_InitThreads(); + #endif + /*--- Initialize various global constants etc. ---*/ + if (__Pyx_InitConstants() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + stringtab_initialized = 1; + if (__Pyx_InitGlobals() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #if PY_MAJOR_VERSION < 3 && (__PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT) + if (__Pyx_init_sys_getdefaultencoding_params() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + if (__pyx_module_is_main_rednose__helpers__ekf_sym_pyx) { + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_name_2, __pyx_n_s_main) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + } + #if PY_MAJOR_VERSION >= 3 + { + PyObject *modules = PyImport_GetModuleDict(); if (unlikely(!modules)) __PYX_ERR(0, 1, __pyx_L1_error) + if (!PyDict_GetItemString(modules, "rednose.helpers.ekf_sym_pyx")) { + if (unlikely((PyDict_SetItemString(modules, "rednose.helpers.ekf_sym_pyx", __pyx_m) < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + } + } + #endif + /*--- Builtin init code ---*/ + if (__Pyx_InitCachedBuiltins() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + /*--- Constants init code ---*/ + if (__Pyx_InitCachedConstants() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + /*--- Global type/function init code ---*/ + (void)__Pyx_modinit_global_init_code(); + (void)__Pyx_modinit_variable_export_code(); + (void)__Pyx_modinit_function_export_code(); + if (unlikely((__Pyx_modinit_type_init_code() < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + if (unlikely((__Pyx_modinit_type_import_code() < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + (void)__Pyx_modinit_variable_import_code(); + (void)__Pyx_modinit_function_import_code(); + /*--- Execution code ---*/ + #if defined(__Pyx_Generator_USED) || defined(__Pyx_Coroutine_USED) + if (__Pyx_patch_abc() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + __Pyx_TraceCall("__Pyx_PyMODINIT_FUNC PyInit_ekf_sym_pyx(void)", __pyx_f[0], 1, 0, __PYX_ERR(0, 1, __pyx_L1_error)); + + /* "View.MemoryView":99 + * + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: # <<<<<<<<<<<<<< + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "View.MemoryView":100 + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: + * if __import__("sys").version_info >= (3, 3): # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + */ + __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__37, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 100, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_version_info); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 100, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = PyObject_RichCompare(__pyx_t_5, __pyx_tuple__38, Py_GE); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 100, __pyx_L2_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_6 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(1, 100, __pyx_L2_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (__pyx_t_6) { + + /* "View.MemoryView":101 + * try: + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence # <<<<<<<<<<<<<< + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence + */ + __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__39, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 101, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_abc); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 101, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_Sequence); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 101, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XGOTREF(__pyx_collections_abc_Sequence); + __Pyx_DECREF_SET(__pyx_collections_abc_Sequence, __pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + __pyx_t_4 = 0; + + /* "View.MemoryView":100 + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: + * if __import__("sys").version_info >= (3, 3): # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + */ + goto __pyx_L8; + } + + /* "View.MemoryView":103 + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence # <<<<<<<<<<<<<< + * except: + * + */ + /*else*/ { + __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__40, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 103, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_Sequence); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 103, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XGOTREF(__pyx_collections_abc_Sequence); + __Pyx_DECREF_SET(__pyx_collections_abc_Sequence, __pyx_t_5); + __Pyx_GIVEREF(__pyx_t_5); + __pyx_t_5 = 0; + } + __pyx_L8:; + + /* "View.MemoryView":99 + * + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: # <<<<<<<<<<<<<< + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L7_try_end; + __pyx_L2_error:; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "View.MemoryView":104 + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence + * except: # <<<<<<<<<<<<<< + * + * __pyx_collections_abc_Sequence = None + */ + /*except:*/ { + __Pyx_AddTraceback("View.MemoryView", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_4, &__pyx_t_7) < 0) __PYX_ERR(1, 104, __pyx_L4_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_4); + __Pyx_XGOTREF(__pyx_t_7); + + /* "View.MemoryView":106 + * except: + * + * __pyx_collections_abc_Sequence = None # <<<<<<<<<<<<<< + * + * + */ + __Pyx_INCREF(Py_None); + __Pyx_XGOTREF(__pyx_collections_abc_Sequence); + __Pyx_DECREF_SET(__pyx_collections_abc_Sequence, Py_None); + __Pyx_GIVEREF(Py_None); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + goto __pyx_L3_exception_handled; + } + + /* "View.MemoryView":99 + * + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: # <<<<<<<<<<<<<< + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + */ + __pyx_L4_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + goto __pyx_L1_error; + __pyx_L3_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + __pyx_L7_try_end:; + } + + /* "View.MemoryView":241 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_3, &__pyx_t_2, &__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_1); + /*try:*/ { + + /* "View.MemoryView":242 + * + * try: + * count = __pyx_collections_abc_Sequence.count # <<<<<<<<<<<<<< + * index = __pyx_collections_abc_Sequence.index + * except: + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_count); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 242, __pyx_L11_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict(__pyx_array_type, __pyx_n_s_count, __pyx_t_7) < 0) __PYX_ERR(1, 242, __pyx_L11_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_array_type); + + /* "View.MemoryView":243 + * try: + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index # <<<<<<<<<<<<<< + * except: + * pass + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_index); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 243, __pyx_L11_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict(__pyx_array_type, __pyx_n_s_index, __pyx_t_7) < 0) __PYX_ERR(1, 243, __pyx_L11_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_array_type); + + /* "View.MemoryView":241 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + } + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + goto __pyx_L16_try_end; + __pyx_L11_error:; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":244 + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + * except: # <<<<<<<<<<<<<< + * pass + * + */ + /*except:*/ { + __Pyx_ErrRestore(0,0,0); + goto __pyx_L12_exception_handled; + } + __pyx_L12_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_2, __pyx_t_1); + __pyx_L16_try_end:; + } + + /* "View.MemoryView":309 + * return self.name + * + * cdef generic = Enum("") # <<<<<<<<<<<<<< + * cdef strided = Enum("") # default + * cdef indirect = Enum("") + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__41, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 309, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(generic); + __Pyx_DECREF_SET(generic, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":310 + * + * cdef generic = Enum("") + * cdef strided = Enum("") # default # <<<<<<<<<<<<<< + * cdef indirect = Enum("") + * + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__42, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 310, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(strided); + __Pyx_DECREF_SET(strided, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":311 + * cdef generic = Enum("") + * cdef strided = Enum("") # default + * cdef indirect = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__43, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 311, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(indirect); + __Pyx_DECREF_SET(indirect, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":314 + * + * + * cdef contiguous = Enum("") # <<<<<<<<<<<<<< + * cdef indirect_contiguous = Enum("") + * + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__44, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 314, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(contiguous); + __Pyx_DECREF_SET(contiguous, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":315 + * + * cdef contiguous = Enum("") + * cdef indirect_contiguous = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__45, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 315, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(indirect_contiguous); + __Pyx_DECREF_SET(indirect_contiguous, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":323 + * + * + * cdef int __pyx_memoryview_thread_locks_used = 0 # <<<<<<<<<<<<<< + * cdef PyThread_type_lock[8] __pyx_memoryview_thread_locks = [ + * PyThread_allocate_lock(), + */ + __pyx_memoryview_thread_locks_used = 0; + + /* "View.MemoryView":324 + * + * cdef int __pyx_memoryview_thread_locks_used = 0 + * cdef PyThread_type_lock[8] __pyx_memoryview_thread_locks = [ # <<<<<<<<<<<<<< + * PyThread_allocate_lock(), + * PyThread_allocate_lock(), + */ + __pyx_t_8[0] = PyThread_allocate_lock(); + __pyx_t_8[1] = PyThread_allocate_lock(); + __pyx_t_8[2] = PyThread_allocate_lock(); + __pyx_t_8[3] = PyThread_allocate_lock(); + __pyx_t_8[4] = PyThread_allocate_lock(); + __pyx_t_8[5] = PyThread_allocate_lock(); + __pyx_t_8[6] = PyThread_allocate_lock(); + __pyx_t_8[7] = PyThread_allocate_lock(); + memcpy(&(__pyx_memoryview_thread_locks[0]), __pyx_t_8, sizeof(__pyx_memoryview_thread_locks[0]) * (8)); + + /* "View.MemoryView":982 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "View.MemoryView":983 + * + * try: + * count = __pyx_collections_abc_Sequence.count # <<<<<<<<<<<<<< + * index = __pyx_collections_abc_Sequence.index + * except: + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_count); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 983, __pyx_L17_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict(__pyx_memoryviewslice_type, __pyx_n_s_count, __pyx_t_7) < 0) __PYX_ERR(1, 983, __pyx_L17_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_memoryviewslice_type); + + /* "View.MemoryView":984 + * try: + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index # <<<<<<<<<<<<<< + * except: + * pass + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_index); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 984, __pyx_L17_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict(__pyx_memoryviewslice_type, __pyx_n_s_index, __pyx_t_7) < 0) __PYX_ERR(1, 984, __pyx_L17_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_memoryviewslice_type); + + /* "View.MemoryView":982 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L22_try_end; + __pyx_L17_error:; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":985 + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + * except: # <<<<<<<<<<<<<< + * pass + * + */ + /*except:*/ { + __Pyx_ErrRestore(0,0,0); + goto __pyx_L18_exception_handled; + } + __pyx_L18_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + __pyx_L22_try_end:; + } + + /* "View.MemoryView":988 + * pass + * + * try: # <<<<<<<<<<<<<< + * if __pyx_collections_abc_Sequence: + * + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_3, &__pyx_t_2, &__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_1); + /*try:*/ { + + /* "View.MemoryView":989 + * + * try: + * if __pyx_collections_abc_Sequence: # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_6 = __Pyx_PyObject_IsTrue(__pyx_collections_abc_Sequence); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(1, 989, __pyx_L23_error) + if (__pyx_t_6) { + + /* "View.MemoryView":993 + * + * + * __pyx_collections_abc_Sequence.register(_memoryviewslice) # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence.register(array) + * except: + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_register); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 993, __pyx_L23_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_4 = __Pyx_PyObject_CallOneArg(__pyx_t_7, ((PyObject *)__pyx_memoryviewslice_type)); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 993, __pyx_L23_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "View.MemoryView":994 + * + * __pyx_collections_abc_Sequence.register(_memoryviewslice) + * __pyx_collections_abc_Sequence.register(array) # <<<<<<<<<<<<<< + * except: + * pass # ignore failure, it's a minor issue + */ + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_register); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 994, __pyx_L23_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_7 = __Pyx_PyObject_CallOneArg(__pyx_t_4, ((PyObject *)__pyx_array_type)); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 994, __pyx_L23_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":989 + * + * try: + * if __pyx_collections_abc_Sequence: # <<<<<<<<<<<<<< + * + * + */ + } + + /* "View.MemoryView":988 + * pass + * + * try: # <<<<<<<<<<<<<< + * if __pyx_collections_abc_Sequence: + * + */ + } + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + goto __pyx_L28_try_end; + __pyx_L23_error:; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":995 + * __pyx_collections_abc_Sequence.register(_memoryviewslice) + * __pyx_collections_abc_Sequence.register(array) + * except: # <<<<<<<<<<<<<< + * pass # ignore failure, it's a minor issue + * + */ + /*except:*/ { + __Pyx_ErrRestore(0,0,0); + goto __pyx_L24_exception_handled; + } + __pyx_L24_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_2, __pyx_t_1); + __pyx_L28_try_end:; + } + + /* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + __pyx_t_7 = PyCFunction_NewEx(&__pyx_mdef_15View_dot_MemoryView_1__pyx_unpickle_Enum, NULL, __pyx_n_s_View_MemoryView); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_pyx_unpickle_Enum, __pyx_t_7) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":12 + * cimport numpy as np + * + * import numpy as np # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_7 = __Pyx_ImportDottedModule(__pyx_n_s_numpy, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 12, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_np, __pyx_t_7) < 0) __PYX_ERR(0, 12, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":89 + * def __cinit__(self, str gen_dir, str name, np.ndarray[np.float64_t, ndim=2] Q, + * np.ndarray[np.float64_t, ndim=1] x_initial, np.ndarray[np.float64_t, ndim=2] P_initial, int dim_main, + * int dim_main_err, int N=0, int dim_augment=0, int dim_augment_err=0, list maha_test_kinds=[], # <<<<<<<<<<<<<< + * list quaternion_idxs=[], list global_vars=[], double max_rewind_age=1.0, logger=None): + * # TODO logger + */ + __pyx_t_7 = PyList_New(0); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 89, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_k__17 = ((PyObject*)__pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":90 + * np.ndarray[np.float64_t, ndim=1] x_initial, np.ndarray[np.float64_t, ndim=2] P_initial, int dim_main, + * int dim_main_err, int N=0, int dim_augment=0, int dim_augment_err=0, list maha_test_kinds=[], + * list quaternion_idxs=[], list global_vars=[], double max_rewind_age=1.0, logger=None): # <<<<<<<<<<<<<< + * # TODO logger + * ekf_load_and_register(gen_dir.encode('utf8'), name.encode('utf8')) + */ + __pyx_t_7 = PyList_New(0); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 90, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_k__18 = ((PyObject*)__pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + __pyx_t_7 = PyList_New(0); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 90, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_k__19 = ((PyObject*)__pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":113 + * ) + * + * def init_state(self, np.ndarray[np.float64_t, ndim=1] state, np.ndarray[np.float64_t, ndim=2] covs, filter_time): # <<<<<<<<<<<<<< + * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] state_b = np.ascontiguousarray(state, dtype=np.double) + * cdef np.ndarray[np.float64_t, ndim=2, mode='c'] covs_b = np.ascontiguousarray(covs, dtype=np.double) + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_3init_state, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx_init_state, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__20)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 113, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx, __pyx_n_s_init_state, __pyx_t_7) < 0) __PYX_ERR(0, 113, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); + + /* "rednose/helpers/ekf_sym_pyx.pyx":122 + * ) + * + * def state(self): # <<<<<<<<<<<<<< + * cdef np.ndarray res = vector_to_numpy(self.ekf.state()) + * return res + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_5state, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx_state, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__21)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 122, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx, __pyx_n_s_state, __pyx_t_7) < 0) __PYX_ERR(0, 122, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); + + /* "rednose/helpers/ekf_sym_pyx.pyx":126 + * return res + * + * def covs(self): # <<<<<<<<<<<<<< + * return matrix_to_numpy(self.ekf.covs()) + * + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_7covs, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx_covs, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__22)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 126, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx, __pyx_n_s_covs, __pyx_t_7) < 0) __PYX_ERR(0, 126, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); + + /* "rednose/helpers/ekf_sym_pyx.pyx":129 + * return matrix_to_numpy(self.ekf.covs()) + * + * def set_filter_time(self, double t): # <<<<<<<<<<<<<< + * self.ekf.set_filter_time(t) + * + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_9set_filter_time, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx_set_filter_time, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__23)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 129, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx, __pyx_n_s_set_filter_time, __pyx_t_7) < 0) __PYX_ERR(0, 129, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); + + /* "rednose/helpers/ekf_sym_pyx.pyx":132 + * self.ekf.set_filter_time(t) + * + * def get_filter_time(self): # <<<<<<<<<<<<<< + * return self.ekf.get_filter_time() + * + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_11get_filter_time, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx_get_filter_time, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__24)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 132, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx, __pyx_n_s_get_filter_time, __pyx_t_7) < 0) __PYX_ERR(0, 132, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); + + /* "rednose/helpers/ekf_sym_pyx.pyx":135 + * return self.ekf.get_filter_time() + * + * def set_global(self, str global_var, double val): # <<<<<<<<<<<<<< + * self.ekf.set_global(global_var.encode('utf8'), val) + * + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_13set_global, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx_set_global, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__25)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 135, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx, __pyx_n_s_set_global, __pyx_t_7) < 0) __PYX_ERR(0, 135, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); + + /* "rednose/helpers/ekf_sym_pyx.pyx":138 + * self.ekf.set_global(global_var.encode('utf8'), val) + * + * def reset_rewind(self): # <<<<<<<<<<<<<< + * self.ekf.reset_rewind() + * + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_15reset_rewind, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx_reset_rewind, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__26)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 138, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx, __pyx_n_s_reset_rewind, __pyx_t_7) < 0) __PYX_ERR(0, 138, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); + + /* "rednose/helpers/ekf_sym_pyx.pyx":141 + * self.ekf.reset_rewind() + * + * def predict(self, double t): # <<<<<<<<<<<<<< + * self.ekf.predict(t) + * + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_17predict, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx_predict, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__27)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 141, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx, __pyx_n_s_predict, __pyx_t_7) < 0) __PYX_ERR(0, 141, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); + + /* "rednose/helpers/ekf_sym_pyx.pyx":144 + * self.ekf.predict(t) + * + * def predict_and_update_batch(self, double t, int kind, z, R, extra_args=[[]], bool augment=False): # <<<<<<<<<<<<<< + * cdef vector[MapVectorXd] z_map + * cdef np.ndarray[np.float64_t, ndim=1, mode='c'] zi_b + */ + __pyx_t_7 = PyList_New(0); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 144, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_4 = PyList_New(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 144, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_7); + if (__Pyx_PyList_SET_ITEM(__pyx_t_4, 0, __pyx_t_7)) __PYX_ERR(0, 144, __pyx_L1_error); + __pyx_t_7 = 0; + __pyx_k__28 = __pyx_t_4; + __Pyx_GIVEREF(__pyx_t_4); + __pyx_t_4 = 0; + __pyx_t_4 = PyList_New(0); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 144, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_7 = PyList_New(1); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 144, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_GIVEREF(__pyx_t_4); + if (__Pyx_PyList_SET_ITEM(__pyx_t_7, 0, __pyx_t_4)) __PYX_ERR(0, 144, __pyx_L1_error); + __pyx_t_4 = 0; + __pyx_t_4 = PyTuple_New(2); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 144, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_7); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_7)) __PYX_ERR(0, 144, __pyx_L1_error); + __Pyx_INCREF(Py_False); + __Pyx_GIVEREF(Py_False); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 1, Py_False)) __PYX_ERR(0, 144, __pyx_L1_error); + __pyx_t_7 = 0; + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_19predict_and_update_batch, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx_predict_and_update_b, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__29)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 144, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_7, __pyx_t_4); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx, __pyx_n_s_predict_and_update_batch, __pyx_t_7) < 0) __PYX_ERR(0, 144, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); + + /* "rednose/helpers/ekf_sym_pyx.pyx":182 + * ) + * + * def augment(self): # <<<<<<<<<<<<<< + * raise NotImplementedError() # TODO + * + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_21augment, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx_augment, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__30)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 182, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx, __pyx_n_s_augment, __pyx_t_7) < 0) __PYX_ERR(0, 182, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); + + /* "rednose/helpers/ekf_sym_pyx.pyx":185 + * raise NotImplementedError() # TODO + * + * def get_augment_times(self): # <<<<<<<<<<<<<< + * raise NotImplementedError() # TODO + * + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_23get_augment_times, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx_get_augment_times, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__31)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 185, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx, __pyx_n_s_get_augment_times, __pyx_t_7) < 0) __PYX_ERR(0, 185, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); + + /* "rednose/helpers/ekf_sym_pyx.pyx":188 + * raise NotImplementedError() # TODO + * + * def rts_smooth(self, estimates, norm_quats=False): # <<<<<<<<<<<<<< + * raise NotImplementedError() # TODO + * + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_25rts_smooth, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx_rts_smooth, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__32)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 188, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_7, __pyx_tuple__55); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx, __pyx_n_s_rts_smooth, __pyx_t_7) < 0) __PYX_ERR(0, 188, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); + + /* "rednose/helpers/ekf_sym_pyx.pyx":191 + * raise NotImplementedError() # TODO + * + * def maha_test(self, x, P, kind, z, R, extra_args=[], maha_thresh=0.95): # <<<<<<<<<<<<<< + * raise NotImplementedError() # TODO + * + */ + __pyx_t_7 = PyList_New(0); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 191, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_k__33 = __pyx_t_7; + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + __pyx_t_7 = PyList_New(0); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 191, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_4 = PyTuple_New(2); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 191, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_7); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_7)) __PYX_ERR(0, 191, __pyx_L1_error); + __Pyx_INCREF(__pyx_float_0_95); + __Pyx_GIVEREF(__pyx_float_0_95); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_float_0_95)) __PYX_ERR(0, 191, __pyx_L1_error); + __pyx_t_7 = 0; + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_27maha_test, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx_maha_test, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__34)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 191, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_7, __pyx_t_4); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx, __pyx_n_s_maha_test, __pyx_t_7) < 0) __PYX_ERR(0, 191, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_7rednose_7helpers_11ekf_sym_pyx_EKF_sym_pyx); + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_31__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx___reduce_cython, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__35)); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_7) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_7rednose_7helpers_11ekf_sym_pyx_11EKF_sym_pyx_33__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_EKF_sym_pyx___setstate_cython, NULL, __pyx_n_s_rednose_helpers_ekf_sym_pyx, __pyx_d, ((PyObject *)__pyx_codeobj__36)); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_7) < 0) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "rednose/helpers/ekf_sym_pyx.pyx":1 + * # cython: language_level=3 # <<<<<<<<<<<<<< + * # cython: profile=True + * # distutils: language = c++ + */ + __pyx_t_7 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_test, __pyx_t_7) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_TraceReturn(Py_None, 0); + + /*--- Wrapped vars code ---*/ + + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_7); + if (__pyx_m) { + if (__pyx_d && stringtab_initialized) { + __Pyx_AddTraceback("init rednose.helpers.ekf_sym_pyx", __pyx_clineno, __pyx_lineno, __pyx_filename); + } + #if !CYTHON_USE_MODULE_STATE + Py_CLEAR(__pyx_m); + #else + Py_DECREF(__pyx_m); + if (pystate_addmodule_run) { + PyObject *tp, *value, *tb; + PyErr_Fetch(&tp, &value, &tb); + PyState_RemoveModule(&__pyx_moduledef); + PyErr_Restore(tp, value, tb); + } + #endif + } else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_ImportError, "init rednose.helpers.ekf_sym_pyx"); + } + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + #if CYTHON_PEP489_MULTI_PHASE_INIT + return (__pyx_m != NULL) ? 0 : -1; + #elif PY_MAJOR_VERSION >= 3 + return __pyx_m; + #else + return; + #endif +} +/* #### Code section: cleanup_globals ### */ +/* #### Code section: cleanup_module ### */ +/* #### Code section: main_method ### */ +/* #### Code section: utility_code_pragmas ### */ +#ifdef _MSC_VER +#pragma warning( push ) +/* Warning 4127: conditional expression is constant + * Cython uses constant conditional expressions to allow in inline functions to be optimized at + * compile-time, so this warning is not useful + */ +#pragma warning( disable : 4127 ) +#endif + + + +/* #### Code section: utility_code_def ### */ + +/* --- Runtime support code --- */ +/* Refnanny */ +#if CYTHON_REFNANNY +static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname) { + PyObject *m = NULL, *p = NULL; + void *r = NULL; + m = PyImport_ImportModule(modname); + if (!m) goto end; + p = PyObject_GetAttrString(m, "RefNannyAPI"); + if (!p) goto end; + r = PyLong_AsVoidPtr(p); +end: + Py_XDECREF(p); + Py_XDECREF(m); + return (__Pyx_RefNannyAPIStruct *)r; +} +#endif + +/* PyErrExceptionMatches */ +#if CYTHON_FAST_THREAD_STATE +static int __Pyx_PyErr_ExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; i= 0x030C00A6 + PyObject *current_exception = tstate->current_exception; + if (unlikely(!current_exception)) return 0; + exc_type = (PyObject*) Py_TYPE(current_exception); + if (exc_type == err) return 1; +#else + exc_type = tstate->curexc_type; + if (exc_type == err) return 1; + if (unlikely(!exc_type)) return 0; +#endif + #if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(exc_type); + #endif + if (unlikely(PyTuple_Check(err))) { + result = __Pyx_PyErr_ExceptionMatchesTuple(exc_type, err); + } else { + result = __Pyx_PyErr_GivenExceptionMatches(exc_type, err); + } + #if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(exc_type); + #endif + return result; +} +#endif + +/* PyErrFetchRestore */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject *tmp_value; + assert(type == NULL || (value != NULL && type == (PyObject*) Py_TYPE(value))); + if (value) { + #if CYTHON_COMPILING_IN_CPYTHON + if (unlikely(((PyBaseExceptionObject*) value)->traceback != tb)) + #endif + PyException_SetTraceback(value, tb); + } + tmp_value = tstate->current_exception; + tstate->current_exception = value; + Py_XDECREF(tmp_value); + Py_XDECREF(type); + Py_XDECREF(tb); +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + tmp_type = tstate->curexc_type; + tmp_value = tstate->curexc_value; + tmp_tb = tstate->curexc_traceback; + tstate->curexc_type = type; + tstate->curexc_value = value; + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); +#endif +} +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject* exc_value; + exc_value = tstate->current_exception; + tstate->current_exception = 0; + *value = exc_value; + *type = NULL; + *tb = NULL; + if (exc_value) { + *type = (PyObject*) Py_TYPE(exc_value); + Py_INCREF(*type); + #if CYTHON_COMPILING_IN_CPYTHON + *tb = ((PyBaseExceptionObject*) exc_value)->traceback; + Py_XINCREF(*tb); + #else + *tb = PyException_GetTraceback(exc_value); + #endif + } +#else + *type = tstate->curexc_type; + *value = tstate->curexc_value; + *tb = tstate->curexc_traceback; + tstate->curexc_type = 0; + tstate->curexc_value = 0; + tstate->curexc_traceback = 0; +#endif +} +#endif + +/* PyObjectGetAttrStr */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name) { + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro)) + return tp->tp_getattro(obj, attr_name); +#if PY_MAJOR_VERSION < 3 + if (likely(tp->tp_getattr)) + return tp->tp_getattr(obj, PyString_AS_STRING(attr_name)); +#endif + return PyObject_GetAttr(obj, attr_name); +} +#endif + +/* PyObjectGetAttrStrNoError */ +#if __PYX_LIMITED_VERSION_HEX < 0x030d00A1 +static void __Pyx_PyObject_GetAttrStr_ClearAttributeError(void) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + if (likely(__Pyx_PyErr_ExceptionMatches(PyExc_AttributeError))) + __Pyx_PyErr_Clear(); +} +#endif +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name) { + PyObject *result; +#if __PYX_LIMITED_VERSION_HEX >= 0x030d00A1 + (void) PyObject_GetOptionalAttr(obj, attr_name, &result); + return result; +#else +#if CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_TYPE_SLOTS && PY_VERSION_HEX >= 0x030700B1 + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro == PyObject_GenericGetAttr)) { + return _PyObject_GenericGetAttrWithDict(obj, attr_name, NULL, 1); + } +#endif + result = __Pyx_PyObject_GetAttrStr(obj, attr_name); + if (unlikely(!result)) { + __Pyx_PyObject_GetAttrStr_ClearAttributeError(); + } + return result; +#endif +} + +/* GetBuiltinName */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name) { + PyObject* result = __Pyx_PyObject_GetAttrStrNoError(__pyx_b, name); + if (unlikely(!result) && !PyErr_Occurred()) { + PyErr_Format(PyExc_NameError, +#if PY_MAJOR_VERSION >= 3 + "name '%U' is not defined", name); +#else + "name '%.200s' is not defined", PyString_AS_STRING(name)); +#endif + } + return result; +} + +/* TupleAndListFromArray */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE void __Pyx_copy_object_array(PyObject *const *CYTHON_RESTRICT src, PyObject** CYTHON_RESTRICT dest, Py_ssize_t length) { + PyObject *v; + Py_ssize_t i; + for (i = 0; i < length; i++) { + v = dest[i] = src[i]; + Py_INCREF(v); + } +} +static CYTHON_INLINE PyObject * +__Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + Py_INCREF(__pyx_empty_tuple); + return __pyx_empty_tuple; + } + res = PyTuple_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyTupleObject*)res)->ob_item, n); + return res; +} +static CYTHON_INLINE PyObject * +__Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + return PyList_New(0); + } + res = PyList_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyListObject*)res)->ob_item, n); + return res; +} +#endif + +/* BytesEquals */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else + if (s1 == s2) { + return (equals == Py_EQ); + } else if (PyBytes_CheckExact(s1) & PyBytes_CheckExact(s2)) { + const char *ps1, *ps2; + Py_ssize_t length = PyBytes_GET_SIZE(s1); + if (length != PyBytes_GET_SIZE(s2)) + return (equals == Py_NE); + ps1 = PyBytes_AS_STRING(s1); + ps2 = PyBytes_AS_STRING(s2); + if (ps1[0] != ps2[0]) { + return (equals == Py_NE); + } else if (length == 1) { + return (equals == Py_EQ); + } else { + int result; +#if CYTHON_USE_UNICODE_INTERNALS && (PY_VERSION_HEX < 0x030B0000) + Py_hash_t hash1, hash2; + hash1 = ((PyBytesObject*)s1)->ob_shash; + hash2 = ((PyBytesObject*)s2)->ob_shash; + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + return (equals == Py_NE); + } +#endif + result = memcmp(ps1, ps2, (size_t)length); + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & PyBytes_CheckExact(s2)) { + return (equals == Py_NE); + } else if ((s2 == Py_None) & PyBytes_CheckExact(s1)) { + return (equals == Py_NE); + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +#endif +} + +/* UnicodeEquals */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else +#if PY_MAJOR_VERSION < 3 + PyObject* owned_ref = NULL; +#endif + int s1_is_unicode, s2_is_unicode; + if (s1 == s2) { + goto return_eq; + } + s1_is_unicode = PyUnicode_CheckExact(s1); + s2_is_unicode = PyUnicode_CheckExact(s2); +#if PY_MAJOR_VERSION < 3 + if ((s1_is_unicode & (!s2_is_unicode)) && PyString_CheckExact(s2)) { + owned_ref = PyUnicode_FromObject(s2); + if (unlikely(!owned_ref)) + return -1; + s2 = owned_ref; + s2_is_unicode = 1; + } else if ((s2_is_unicode & (!s1_is_unicode)) && PyString_CheckExact(s1)) { + owned_ref = PyUnicode_FromObject(s1); + if (unlikely(!owned_ref)) + return -1; + s1 = owned_ref; + s1_is_unicode = 1; + } else if (((!s2_is_unicode) & (!s1_is_unicode))) { + return __Pyx_PyBytes_Equals(s1, s2, equals); + } +#endif + if (s1_is_unicode & s2_is_unicode) { + Py_ssize_t length; + int kind; + void *data1, *data2; + if (unlikely(__Pyx_PyUnicode_READY(s1) < 0) || unlikely(__Pyx_PyUnicode_READY(s2) < 0)) + return -1; + length = __Pyx_PyUnicode_GET_LENGTH(s1); + if (length != __Pyx_PyUnicode_GET_LENGTH(s2)) { + goto return_ne; + } +#if CYTHON_USE_UNICODE_INTERNALS + { + Py_hash_t hash1, hash2; + #if CYTHON_PEP393_ENABLED + hash1 = ((PyASCIIObject*)s1)->hash; + hash2 = ((PyASCIIObject*)s2)->hash; + #else + hash1 = ((PyUnicodeObject*)s1)->hash; + hash2 = ((PyUnicodeObject*)s2)->hash; + #endif + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + goto return_ne; + } + } +#endif + kind = __Pyx_PyUnicode_KIND(s1); + if (kind != __Pyx_PyUnicode_KIND(s2)) { + goto return_ne; + } + data1 = __Pyx_PyUnicode_DATA(s1); + data2 = __Pyx_PyUnicode_DATA(s2); + if (__Pyx_PyUnicode_READ(kind, data1, 0) != __Pyx_PyUnicode_READ(kind, data2, 0)) { + goto return_ne; + } else if (length == 1) { + goto return_eq; + } else { + int result = memcmp(data1, data2, (size_t)(length * kind)); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & s2_is_unicode) { + goto return_ne; + } else if ((s2 == Py_None) & s1_is_unicode) { + goto return_ne; + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +return_eq: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ); +return_ne: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_NE); +#endif +} + +/* fastcall */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s) +{ + Py_ssize_t i, n = PyTuple_GET_SIZE(kwnames); + for (i = 0; i < n; i++) + { + if (s == PyTuple_GET_ITEM(kwnames, i)) return kwvalues[i]; + } + for (i = 0; i < n; i++) + { + int eq = __Pyx_PyUnicode_Equals(s, PyTuple_GET_ITEM(kwnames, i), Py_EQ); + if (unlikely(eq != 0)) { + if (unlikely(eq < 0)) return NULL; + return kwvalues[i]; + } + } + return NULL; +} +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 +CYTHON_UNUSED static PyObject *__Pyx_KwargsAsDict_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues) { + Py_ssize_t i, nkwargs = PyTuple_GET_SIZE(kwnames); + PyObject *dict; + dict = PyDict_New(); + if (unlikely(!dict)) + return NULL; + for (i=0; i= 3 + "%s() got multiple values for keyword argument '%U'", func_name, kw_name); + #else + "%s() got multiple values for keyword argument '%s'", func_name, + PyString_AsString(kw_name)); + #endif +} + +/* ParseKeywords */ +static int __Pyx_ParseOptionalKeywords( + PyObject *kwds, + PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, + PyObject *values[], + Py_ssize_t num_pos_args, + const char* function_name) +{ + PyObject *key = 0, *value = 0; + Py_ssize_t pos = 0; + PyObject*** name; + PyObject*** first_kw_arg = argnames + num_pos_args; + int kwds_is_tuple = CYTHON_METH_FASTCALL && likely(PyTuple_Check(kwds)); + while (1) { + Py_XDECREF(key); key = NULL; + Py_XDECREF(value); value = NULL; + if (kwds_is_tuple) { + Py_ssize_t size; +#if CYTHON_ASSUME_SAFE_MACROS + size = PyTuple_GET_SIZE(kwds); +#else + size = PyTuple_Size(kwds); + if (size < 0) goto bad; +#endif + if (pos >= size) break; +#if CYTHON_AVOID_BORROWED_REFS + key = __Pyx_PySequence_ITEM(kwds, pos); + if (!key) goto bad; +#elif CYTHON_ASSUME_SAFE_MACROS + key = PyTuple_GET_ITEM(kwds, pos); +#else + key = PyTuple_GetItem(kwds, pos); + if (!key) goto bad; +#endif + value = kwvalues[pos]; + pos++; + } + else + { + if (!PyDict_Next(kwds, &pos, &key, &value)) break; +#if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(key); +#endif + } + name = first_kw_arg; + while (*name && (**name != key)) name++; + if (*name) { + values[name-argnames] = value; +#if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(value); + Py_DECREF(key); +#endif + key = NULL; + value = NULL; + continue; + } +#if !CYTHON_AVOID_BORROWED_REFS + Py_INCREF(key); +#endif + Py_INCREF(value); + name = first_kw_arg; + #if PY_MAJOR_VERSION < 3 + if (likely(PyString_Check(key))) { + while (*name) { + if ((CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**name) == PyString_GET_SIZE(key)) + && _PyString_Eq(**name, key)) { + values[name-argnames] = value; +#if CYTHON_AVOID_BORROWED_REFS + value = NULL; +#endif + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + if ((**argname == key) || ( + (CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**argname) == PyString_GET_SIZE(key)) + && _PyString_Eq(**argname, key))) { + goto arg_passed_twice; + } + argname++; + } + } + } else + #endif + if (likely(PyUnicode_Check(key))) { + while (*name) { + int cmp = ( + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**name) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**name, key) + ); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) { + values[name-argnames] = value; +#if CYTHON_AVOID_BORROWED_REFS + value = NULL; +#endif + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + int cmp = (**argname == key) ? 0 : + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**argname) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**argname, key); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) goto arg_passed_twice; + argname++; + } + } + } else + goto invalid_keyword_type; + if (kwds2) { + if (unlikely(PyDict_SetItem(kwds2, key, value))) goto bad; + } else { + goto invalid_keyword; + } + } + Py_XDECREF(key); + Py_XDECREF(value); + return 0; +arg_passed_twice: + __Pyx_RaiseDoubleKeywordsError(function_name, key); + goto bad; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + goto bad; +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif +bad: + Py_XDECREF(key); + Py_XDECREF(value); + return -1; +} + +/* ArgTypeTest */ +static int __Pyx__ArgTypeTest(PyObject *obj, PyTypeObject *type, const char *name, int exact) +{ + __Pyx_TypeName type_name; + __Pyx_TypeName obj_type_name; + if (unlikely(!type)) { + PyErr_SetString(PyExc_SystemError, "Missing type object"); + return 0; + } + else if (exact) { + #if PY_MAJOR_VERSION == 2 + if ((type == &PyBaseString_Type) && likely(__Pyx_PyBaseString_CheckExact(obj))) return 1; + #endif + } + else { + if (likely(__Pyx_TypeCheck(obj, type))) return 1; + } + type_name = __Pyx_PyType_GetName(type); + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "Argument '%.200s' has incorrect type (expected " __Pyx_FMT_TYPENAME + ", got " __Pyx_FMT_TYPENAME ")", name, type_name, obj_type_name); + __Pyx_DECREF_TypeName(type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return 0; +} + +/* RaiseException */ +#if PY_MAJOR_VERSION < 3 +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + __Pyx_PyThreadState_declare + CYTHON_UNUSED_VAR(cause); + Py_XINCREF(type); + if (!value || value == Py_None) + value = NULL; + else + Py_INCREF(value); + if (!tb || tb == Py_None) + tb = NULL; + else { + Py_INCREF(tb); + if (!PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto raise_error; + } + } + if (PyType_Check(type)) { +#if CYTHON_COMPILING_IN_PYPY + if (!value) { + Py_INCREF(Py_None); + value = Py_None; + } +#endif + PyErr_NormalizeException(&type, &value, &tb); + } else { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto raise_error; + } + value = type; + type = (PyObject*) Py_TYPE(type); + Py_INCREF(type); + if (!PyType_IsSubtype((PyTypeObject *)type, (PyTypeObject *)PyExc_BaseException)) { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto raise_error; + } + } + __Pyx_PyThreadState_assign + __Pyx_ErrRestore(type, value, tb); + return; +raise_error: + Py_XDECREF(value); + Py_XDECREF(type); + Py_XDECREF(tb); + return; +} +#else +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + PyObject* owned_instance = NULL; + if (tb == Py_None) { + tb = 0; + } else if (tb && !PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto bad; + } + if (value == Py_None) + value = 0; + if (PyExceptionInstance_Check(type)) { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto bad; + } + value = type; + type = (PyObject*) Py_TYPE(value); + } else if (PyExceptionClass_Check(type)) { + PyObject *instance_class = NULL; + if (value && PyExceptionInstance_Check(value)) { + instance_class = (PyObject*) Py_TYPE(value); + if (instance_class != type) { + int is_subclass = PyObject_IsSubclass(instance_class, type); + if (!is_subclass) { + instance_class = NULL; + } else if (unlikely(is_subclass == -1)) { + goto bad; + } else { + type = instance_class; + } + } + } + if (!instance_class) { + PyObject *args; + if (!value) + args = PyTuple_New(0); + else if (PyTuple_Check(value)) { + Py_INCREF(value); + args = value; + } else + args = PyTuple_Pack(1, value); + if (!args) + goto bad; + owned_instance = PyObject_Call(type, args, NULL); + Py_DECREF(args); + if (!owned_instance) + goto bad; + value = owned_instance; + if (!PyExceptionInstance_Check(value)) { + PyErr_Format(PyExc_TypeError, + "calling %R should have returned an instance of " + "BaseException, not %R", + type, Py_TYPE(value)); + goto bad; + } + } + } else { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto bad; + } + if (cause) { + PyObject *fixed_cause; + if (cause == Py_None) { + fixed_cause = NULL; + } else if (PyExceptionClass_Check(cause)) { + fixed_cause = PyObject_CallObject(cause, NULL); + if (fixed_cause == NULL) + goto bad; + } else if (PyExceptionInstance_Check(cause)) { + fixed_cause = cause; + Py_INCREF(fixed_cause); + } else { + PyErr_SetString(PyExc_TypeError, + "exception causes must derive from " + "BaseException"); + goto bad; + } + PyException_SetCause(value, fixed_cause); + } + PyErr_SetObject(type, value); + if (tb) { + #if PY_VERSION_HEX >= 0x030C00A6 + PyException_SetTraceback(value, tb); + #elif CYTHON_FAST_THREAD_STATE + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject* tmp_tb = tstate->curexc_traceback; + if (tb != tmp_tb) { + Py_INCREF(tb); + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_tb); + } +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + PyErr_Fetch(&tmp_type, &tmp_value, &tmp_tb); + Py_INCREF(tb); + PyErr_Restore(tmp_type, tmp_value, tb); + Py_XDECREF(tmp_tb); +#endif + } +bad: + Py_XDECREF(owned_instance); + return; +} +#endif + +/* PyFunctionFastCall */ +#if CYTHON_FAST_PYCALL && !CYTHON_VECTORCALL +static PyObject* __Pyx_PyFunction_FastCallNoKw(PyCodeObject *co, PyObject **args, Py_ssize_t na, + PyObject *globals) { + PyFrameObject *f; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject **fastlocals; + Py_ssize_t i; + PyObject *result; + assert(globals != NULL); + /* XXX Perhaps we should create a specialized + PyFrame_New() that doesn't take locals, but does + take builtins without sanity checking them. + */ + assert(tstate != NULL); + f = PyFrame_New(tstate, co, globals, NULL); + if (f == NULL) { + return NULL; + } + fastlocals = __Pyx_PyFrame_GetLocalsplus(f); + for (i = 0; i < na; i++) { + Py_INCREF(*args); + fastlocals[i] = *args++; + } + result = PyEval_EvalFrameEx(f,0); + ++tstate->recursion_depth; + Py_DECREF(f); + --tstate->recursion_depth; + return result; +} +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs) { + PyCodeObject *co = (PyCodeObject *)PyFunction_GET_CODE(func); + PyObject *globals = PyFunction_GET_GLOBALS(func); + PyObject *argdefs = PyFunction_GET_DEFAULTS(func); + PyObject *closure; +#if PY_MAJOR_VERSION >= 3 + PyObject *kwdefs; +#endif + PyObject *kwtuple, **k; + PyObject **d; + Py_ssize_t nd; + Py_ssize_t nk; + PyObject *result; + assert(kwargs == NULL || PyDict_Check(kwargs)); + nk = kwargs ? PyDict_Size(kwargs) : 0; + #if PY_MAJOR_VERSION < 3 + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) { + return NULL; + } + #else + if (unlikely(Py_EnterRecursiveCall(" while calling a Python object"))) { + return NULL; + } + #endif + if ( +#if PY_MAJOR_VERSION >= 3 + co->co_kwonlyargcount == 0 && +#endif + likely(kwargs == NULL || nk == 0) && + co->co_flags == (CO_OPTIMIZED | CO_NEWLOCALS | CO_NOFREE)) { + if (argdefs == NULL && co->co_argcount == nargs) { + result = __Pyx_PyFunction_FastCallNoKw(co, args, nargs, globals); + goto done; + } + else if (nargs == 0 && argdefs != NULL + && co->co_argcount == Py_SIZE(argdefs)) { + /* function called with no arguments, but all parameters have + a default value: use default values as arguments .*/ + args = &PyTuple_GET_ITEM(argdefs, 0); + result =__Pyx_PyFunction_FastCallNoKw(co, args, Py_SIZE(argdefs), globals); + goto done; + } + } + if (kwargs != NULL) { + Py_ssize_t pos, i; + kwtuple = PyTuple_New(2 * nk); + if (kwtuple == NULL) { + result = NULL; + goto done; + } + k = &PyTuple_GET_ITEM(kwtuple, 0); + pos = i = 0; + while (PyDict_Next(kwargs, &pos, &k[i], &k[i+1])) { + Py_INCREF(k[i]); + Py_INCREF(k[i+1]); + i += 2; + } + nk = i / 2; + } + else { + kwtuple = NULL; + k = NULL; + } + closure = PyFunction_GET_CLOSURE(func); +#if PY_MAJOR_VERSION >= 3 + kwdefs = PyFunction_GET_KW_DEFAULTS(func); +#endif + if (argdefs != NULL) { + d = &PyTuple_GET_ITEM(argdefs, 0); + nd = Py_SIZE(argdefs); + } + else { + d = NULL; + nd = 0; + } +#if PY_MAJOR_VERSION >= 3 + result = PyEval_EvalCodeEx((PyObject*)co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, kwdefs, closure); +#else + result = PyEval_EvalCodeEx(co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, closure); +#endif + Py_XDECREF(kwtuple); +done: + Py_LeaveRecursiveCall(); + return result; +} +#endif + +/* PyObjectCall */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw) { + PyObject *result; + ternaryfunc call = Py_TYPE(func)->tp_call; + if (unlikely(!call)) + return PyObject_Call(func, arg, kw); + #if PY_MAJOR_VERSION < 3 + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + #else + if (unlikely(Py_EnterRecursiveCall(" while calling a Python object"))) + return NULL; + #endif + result = (*call)(func, arg, kw); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* PyObjectCallMethO */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg) { + PyObject *self, *result; + PyCFunction cfunc; + cfunc = __Pyx_CyOrPyCFunction_GET_FUNCTION(func); + self = __Pyx_CyOrPyCFunction_GET_SELF(func); + #if PY_MAJOR_VERSION < 3 + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + #else + if (unlikely(Py_EnterRecursiveCall(" while calling a Python object"))) + return NULL; + #endif + result = cfunc(self, arg); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* PyObjectFastCall */ +#if PY_VERSION_HEX < 0x03090000 || CYTHON_COMPILING_IN_LIMITED_API +static PyObject* __Pyx_PyObject_FastCall_fallback(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs) { + PyObject *argstuple; + PyObject *result = 0; + size_t i; + argstuple = PyTuple_New((Py_ssize_t)nargs); + if (unlikely(!argstuple)) return NULL; + for (i = 0; i < nargs; i++) { + Py_INCREF(args[i]); + if (__Pyx_PyTuple_SET_ITEM(argstuple, (Py_ssize_t)i, args[i]) < 0) goto bad; + } + result = __Pyx_PyObject_Call(func, argstuple, kwargs); + bad: + Py_DECREF(argstuple); + return result; +} +#endif +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t _nargs, PyObject *kwargs) { + Py_ssize_t nargs = __Pyx_PyVectorcall_NARGS(_nargs); +#if CYTHON_COMPILING_IN_CPYTHON + if (nargs == 0 && kwargs == NULL) { + if (__Pyx_CyOrPyCFunction_Check(func) && likely( __Pyx_CyOrPyCFunction_GET_FLAGS(func) & METH_NOARGS)) + return __Pyx_PyObject_CallMethO(func, NULL); + } + else if (nargs == 1 && kwargs == NULL) { + if (__Pyx_CyOrPyCFunction_Check(func) && likely( __Pyx_CyOrPyCFunction_GET_FLAGS(func) & METH_O)) + return __Pyx_PyObject_CallMethO(func, args[0]); + } +#endif + #if PY_VERSION_HEX < 0x030800B1 + #if CYTHON_FAST_PYCCALL + if (PyCFunction_Check(func)) { + if (kwargs) { + return _PyCFunction_FastCallDict(func, args, nargs, kwargs); + } else { + return _PyCFunction_FastCallKeywords(func, args, nargs, NULL); + } + } + #if PY_VERSION_HEX >= 0x030700A1 + if (!kwargs && __Pyx_IS_TYPE(func, &PyMethodDescr_Type)) { + return _PyMethodDescr_FastCallKeywords(func, args, nargs, NULL); + } + #endif + #endif + #if CYTHON_FAST_PYCALL + if (PyFunction_Check(func)) { + return __Pyx_PyFunction_FastCallDict(func, args, nargs, kwargs); + } + #endif + #endif + if (kwargs == NULL) { + #if CYTHON_VECTORCALL + #if PY_VERSION_HEX < 0x03090000 + vectorcallfunc f = _PyVectorcall_Function(func); + #else + vectorcallfunc f = PyVectorcall_Function(func); + #endif + if (f) { + return f(func, args, (size_t)nargs, NULL); + } + #elif defined(__Pyx_CyFunction_USED) && CYTHON_BACKPORT_VECTORCALL + if (__Pyx_CyFunction_CheckExact(func)) { + __pyx_vectorcallfunc f = __Pyx_CyFunction_func_vectorcall(func); + if (f) return f(func, args, (size_t)nargs, NULL); + } + #endif + } + if (nargs == 0) { + return __Pyx_PyObject_Call(func, __pyx_empty_tuple, kwargs); + } + #if PY_VERSION_HEX >= 0x03090000 && !CYTHON_COMPILING_IN_LIMITED_API + return PyObject_VectorcallDict(func, args, (size_t)nargs, kwargs); + #else + return __Pyx_PyObject_FastCall_fallback(func, args, (size_t)nargs, kwargs); + #endif +} + +/* RaiseUnexpectedTypeError */ +static int +__Pyx_RaiseUnexpectedTypeError(const char *expected, PyObject *obj) +{ + __Pyx_TypeName obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, "Expected %s, got " __Pyx_FMT_TYPENAME, + expected, obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return 0; +} + +/* CIntToDigits */ +static const char DIGIT_PAIRS_10[2*10*10+1] = { + "00010203040506070809" + "10111213141516171819" + "20212223242526272829" + "30313233343536373839" + "40414243444546474849" + "50515253545556575859" + "60616263646566676869" + "70717273747576777879" + "80818283848586878889" + "90919293949596979899" +}; +static const char DIGIT_PAIRS_8[2*8*8+1] = { + "0001020304050607" + "1011121314151617" + "2021222324252627" + "3031323334353637" + "4041424344454647" + "5051525354555657" + "6061626364656667" + "7071727374757677" +}; +static const char DIGITS_HEX[2*16+1] = { + "0123456789abcdef" + "0123456789ABCDEF" +}; + +/* BuildPyUnicode */ +static PyObject* __Pyx_PyUnicode_BuildFromAscii(Py_ssize_t ulength, char* chars, int clength, + int prepend_sign, char padding_char) { + PyObject *uval; + Py_ssize_t uoffset = ulength - clength; +#if CYTHON_USE_UNICODE_INTERNALS + Py_ssize_t i; +#if CYTHON_PEP393_ENABLED + void *udata; + uval = PyUnicode_New(ulength, 127); + if (unlikely(!uval)) return NULL; + udata = PyUnicode_DATA(uval); +#else + Py_UNICODE *udata; + uval = PyUnicode_FromUnicode(NULL, ulength); + if (unlikely(!uval)) return NULL; + udata = PyUnicode_AS_UNICODE(uval); +#endif + if (uoffset > 0) { + i = 0; + if (prepend_sign) { + __Pyx_PyUnicode_WRITE(PyUnicode_1BYTE_KIND, udata, 0, '-'); + i++; + } + for (; i < uoffset; i++) { + __Pyx_PyUnicode_WRITE(PyUnicode_1BYTE_KIND, udata, i, padding_char); + } + } + for (i=0; i < clength; i++) { + __Pyx_PyUnicode_WRITE(PyUnicode_1BYTE_KIND, udata, uoffset+i, chars[i]); + } +#else + { + PyObject *sign = NULL, *padding = NULL; + uval = NULL; + if (uoffset > 0) { + prepend_sign = !!prepend_sign; + if (uoffset > prepend_sign) { + padding = PyUnicode_FromOrdinal(padding_char); + if (likely(padding) && uoffset > prepend_sign + 1) { + PyObject *tmp; + PyObject *repeat = PyInt_FromSsize_t(uoffset - prepend_sign); + if (unlikely(!repeat)) goto done_or_error; + tmp = PyNumber_Multiply(padding, repeat); + Py_DECREF(repeat); + Py_DECREF(padding); + padding = tmp; + } + if (unlikely(!padding)) goto done_or_error; + } + if (prepend_sign) { + sign = PyUnicode_FromOrdinal('-'); + if (unlikely(!sign)) goto done_or_error; + } + } + uval = PyUnicode_DecodeASCII(chars, clength, NULL); + if (likely(uval) && padding) { + PyObject *tmp = PyNumber_Add(padding, uval); + Py_DECREF(uval); + uval = tmp; + } + if (likely(uval) && sign) { + PyObject *tmp = PyNumber_Add(sign, uval); + Py_DECREF(uval); + uval = tmp; + } +done_or_error: + Py_XDECREF(padding); + Py_XDECREF(sign); + } +#endif + return uval; +} + +/* CIntToPyUnicode */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_int(int value, Py_ssize_t width, char padding_char, char format_char) { + char digits[sizeof(int)*3+2]; + char *dpos, *end = digits + sizeof(int)*3+2; + const char *hex_digits = DIGITS_HEX; + Py_ssize_t length, ulength; + int prepend_sign, last_one_off; + int remaining; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (format_char == 'X') { + hex_digits += 16; + format_char = 'x'; + } + remaining = value; + last_one_off = 0; + dpos = end; + do { + int digit_pos; + switch (format_char) { + case 'o': + digit_pos = abs((int)(remaining % (8*8))); + remaining = (int) (remaining / (8*8)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_8 + digit_pos * 2, 2); + last_one_off = (digit_pos < 8); + break; + case 'd': + digit_pos = abs((int)(remaining % (10*10))); + remaining = (int) (remaining / (10*10)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_10 + digit_pos * 2, 2); + last_one_off = (digit_pos < 10); + break; + case 'x': + *(--dpos) = hex_digits[abs((int)(remaining % 16))]; + remaining = (int) (remaining / 16); + break; + default: + assert(0); + break; + } + } while (unlikely(remaining != 0)); + assert(!last_one_off || *dpos == '0'); + dpos += last_one_off; + length = end - dpos; + ulength = length; + prepend_sign = 0; + if (!is_unsigned && value <= neg_one) { + if (padding_char == ' ' || width <= length + 1) { + *(--dpos) = '-'; + ++length; + } else { + prepend_sign = 1; + } + ++ulength; + } + if (width > ulength) { + ulength = width; + } + if (ulength == 1) { + return PyUnicode_FromOrdinal(*dpos); + } + return __Pyx_PyUnicode_BuildFromAscii(ulength, dpos, (int) length, prepend_sign, padding_char); +} + +/* CIntToPyUnicode */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_Py_ssize_t(Py_ssize_t value, Py_ssize_t width, char padding_char, char format_char) { + char digits[sizeof(Py_ssize_t)*3+2]; + char *dpos, *end = digits + sizeof(Py_ssize_t)*3+2; + const char *hex_digits = DIGITS_HEX; + Py_ssize_t length, ulength; + int prepend_sign, last_one_off; + Py_ssize_t remaining; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const Py_ssize_t neg_one = (Py_ssize_t) -1, const_zero = (Py_ssize_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (format_char == 'X') { + hex_digits += 16; + format_char = 'x'; + } + remaining = value; + last_one_off = 0; + dpos = end; + do { + int digit_pos; + switch (format_char) { + case 'o': + digit_pos = abs((int)(remaining % (8*8))); + remaining = (Py_ssize_t) (remaining / (8*8)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_8 + digit_pos * 2, 2); + last_one_off = (digit_pos < 8); + break; + case 'd': + digit_pos = abs((int)(remaining % (10*10))); + remaining = (Py_ssize_t) (remaining / (10*10)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_10 + digit_pos * 2, 2); + last_one_off = (digit_pos < 10); + break; + case 'x': + *(--dpos) = hex_digits[abs((int)(remaining % 16))]; + remaining = (Py_ssize_t) (remaining / 16); + break; + default: + assert(0); + break; + } + } while (unlikely(remaining != 0)); + assert(!last_one_off || *dpos == '0'); + dpos += last_one_off; + length = end - dpos; + ulength = length; + prepend_sign = 0; + if (!is_unsigned && value <= neg_one) { + if (padding_char == ' ' || width <= length + 1) { + *(--dpos) = '-'; + ++length; + } else { + prepend_sign = 1; + } + ++ulength; + } + if (width > ulength) { + ulength = width; + } + if (ulength == 1) { + return PyUnicode_FromOrdinal(*dpos); + } + return __Pyx_PyUnicode_BuildFromAscii(ulength, dpos, (int) length, prepend_sign, padding_char); +} + +/* JoinPyUnicode */ +static PyObject* __Pyx_PyUnicode_Join(PyObject* value_tuple, Py_ssize_t value_count, Py_ssize_t result_ulength, + Py_UCS4 max_char) { +#if CYTHON_USE_UNICODE_INTERNALS && CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + PyObject *result_uval; + int result_ukind, kind_shift; + Py_ssize_t i, char_pos; + void *result_udata; + CYTHON_MAYBE_UNUSED_VAR(max_char); +#if CYTHON_PEP393_ENABLED + result_uval = PyUnicode_New(result_ulength, max_char); + if (unlikely(!result_uval)) return NULL; + result_ukind = (max_char <= 255) ? PyUnicode_1BYTE_KIND : (max_char <= 65535) ? PyUnicode_2BYTE_KIND : PyUnicode_4BYTE_KIND; + kind_shift = (result_ukind == PyUnicode_4BYTE_KIND) ? 2 : result_ukind - 1; + result_udata = PyUnicode_DATA(result_uval); +#else + result_uval = PyUnicode_FromUnicode(NULL, result_ulength); + if (unlikely(!result_uval)) return NULL; + result_ukind = sizeof(Py_UNICODE); + kind_shift = (result_ukind == 4) ? 2 : result_ukind - 1; + result_udata = PyUnicode_AS_UNICODE(result_uval); +#endif + assert(kind_shift == 2 || kind_shift == 1 || kind_shift == 0); + char_pos = 0; + for (i=0; i < value_count; i++) { + int ukind; + Py_ssize_t ulength; + void *udata; + PyObject *uval = PyTuple_GET_ITEM(value_tuple, i); + if (unlikely(__Pyx_PyUnicode_READY(uval))) + goto bad; + ulength = __Pyx_PyUnicode_GET_LENGTH(uval); + if (unlikely(!ulength)) + continue; + if (unlikely((PY_SSIZE_T_MAX >> kind_shift) - ulength < char_pos)) + goto overflow; + ukind = __Pyx_PyUnicode_KIND(uval); + udata = __Pyx_PyUnicode_DATA(uval); + if (!CYTHON_PEP393_ENABLED || ukind == result_ukind) { + memcpy((char *)result_udata + (char_pos << kind_shift), udata, (size_t) (ulength << kind_shift)); + } else { + #if PY_VERSION_HEX >= 0x030d0000 + if (unlikely(PyUnicode_CopyCharacters(result_uval, char_pos, uval, 0, ulength) < 0)) goto bad; + #elif CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030300F0 || defined(_PyUnicode_FastCopyCharacters) + _PyUnicode_FastCopyCharacters(result_uval, char_pos, uval, 0, ulength); + #else + Py_ssize_t j; + for (j=0; j < ulength; j++) { + Py_UCS4 uchar = __Pyx_PyUnicode_READ(ukind, udata, j); + __Pyx_PyUnicode_WRITE(result_ukind, result_udata, char_pos+j, uchar); + } + #endif + } + char_pos += ulength; + } + return result_uval; +overflow: + PyErr_SetString(PyExc_OverflowError, "join() result is too long for a Python string"); +bad: + Py_DECREF(result_uval); + return NULL; +#else + CYTHON_UNUSED_VAR(max_char); + CYTHON_UNUSED_VAR(result_ulength); + CYTHON_UNUSED_VAR(value_count); + return PyUnicode_Join(__pyx_empty_unicode, value_tuple); +#endif +} + +/* GetAttr */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr(PyObject *o, PyObject *n) { +#if CYTHON_USE_TYPE_SLOTS +#if PY_MAJOR_VERSION >= 3 + if (likely(PyUnicode_Check(n))) +#else + if (likely(PyString_Check(n))) +#endif + return __Pyx_PyObject_GetAttrStr(o, n); +#endif + return PyObject_GetAttr(o, n); +} + +/* GetItemInt */ +static PyObject *__Pyx_GetItemInt_Generic(PyObject *o, PyObject* j) { + PyObject *r; + if (unlikely(!j)) return NULL; + r = PyObject_GetItem(o, j); + Py_DECREF(j); + return r; +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_List_Fast(PyObject *o, Py_ssize_t i, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + Py_ssize_t wrapped_i = i; + if (wraparound & unlikely(i < 0)) { + wrapped_i += PyList_GET_SIZE(o); + } + if ((!boundscheck) || likely(__Pyx_is_valid_index(wrapped_i, PyList_GET_SIZE(o)))) { + PyObject *r = PyList_GET_ITEM(o, wrapped_i); + Py_INCREF(r); + return r; + } + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +#else + return PySequence_GetItem(o, i); +#endif +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Tuple_Fast(PyObject *o, Py_ssize_t i, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + Py_ssize_t wrapped_i = i; + if (wraparound & unlikely(i < 0)) { + wrapped_i += PyTuple_GET_SIZE(o); + } + if ((!boundscheck) || likely(__Pyx_is_valid_index(wrapped_i, PyTuple_GET_SIZE(o)))) { + PyObject *r = PyTuple_GET_ITEM(o, wrapped_i); + Py_INCREF(r); + return r; + } + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +#else + return PySequence_GetItem(o, i); +#endif +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Fast(PyObject *o, Py_ssize_t i, int is_list, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS && CYTHON_USE_TYPE_SLOTS + if (is_list || PyList_CheckExact(o)) { + Py_ssize_t n = ((!wraparound) | likely(i >= 0)) ? i : i + PyList_GET_SIZE(o); + if ((!boundscheck) || (likely(__Pyx_is_valid_index(n, PyList_GET_SIZE(o))))) { + PyObject *r = PyList_GET_ITEM(o, n); + Py_INCREF(r); + return r; + } + } + else if (PyTuple_CheckExact(o)) { + Py_ssize_t n = ((!wraparound) | likely(i >= 0)) ? i : i + PyTuple_GET_SIZE(o); + if ((!boundscheck) || likely(__Pyx_is_valid_index(n, PyTuple_GET_SIZE(o)))) { + PyObject *r = PyTuple_GET_ITEM(o, n); + Py_INCREF(r); + return r; + } + } else { + PyMappingMethods *mm = Py_TYPE(o)->tp_as_mapping; + PySequenceMethods *sm = Py_TYPE(o)->tp_as_sequence; + if (mm && mm->mp_subscript) { + PyObject *r, *key = PyInt_FromSsize_t(i); + if (unlikely(!key)) return NULL; + r = mm->mp_subscript(o, key); + Py_DECREF(key); + return r; + } + if (likely(sm && sm->sq_item)) { + if (wraparound && unlikely(i < 0) && likely(sm->sq_length)) { + Py_ssize_t l = sm->sq_length(o); + if (likely(l >= 0)) { + i += l; + } else { + if (!PyErr_ExceptionMatches(PyExc_OverflowError)) + return NULL; + PyErr_Clear(); + } + } + return sm->sq_item(o, i); + } + } +#else + if (is_list || !PyMapping_Check(o)) { + return PySequence_GetItem(o, i); + } +#endif + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +} + +/* PyObjectCallOneArg */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg) { + PyObject *args[2] = {NULL, arg}; + return __Pyx_PyObject_FastCall(func, args+1, 1 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* ObjectGetItem */ +#if CYTHON_USE_TYPE_SLOTS +static PyObject *__Pyx_PyObject_GetIndex(PyObject *obj, PyObject *index) { + PyObject *runerr = NULL; + Py_ssize_t key_value; + key_value = __Pyx_PyIndex_AsSsize_t(index); + if (likely(key_value != -1 || !(runerr = PyErr_Occurred()))) { + return __Pyx_GetItemInt_Fast(obj, key_value, 0, 1, 1); + } + if (PyErr_GivenExceptionMatches(runerr, PyExc_OverflowError)) { + __Pyx_TypeName index_type_name = __Pyx_PyType_GetName(Py_TYPE(index)); + PyErr_Clear(); + PyErr_Format(PyExc_IndexError, + "cannot fit '" __Pyx_FMT_TYPENAME "' into an index-sized integer", index_type_name); + __Pyx_DECREF_TypeName(index_type_name); + } + return NULL; +} +static PyObject *__Pyx_PyObject_GetItem_Slow(PyObject *obj, PyObject *key) { + __Pyx_TypeName obj_type_name; + if (likely(PyType_Check(obj))) { + PyObject *meth = __Pyx_PyObject_GetAttrStrNoError(obj, __pyx_n_s_class_getitem); + if (!meth) { + PyErr_Clear(); + } else { + PyObject *result = __Pyx_PyObject_CallOneArg(meth, key); + Py_DECREF(meth); + return result; + } + } + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "'" __Pyx_FMT_TYPENAME "' object is not subscriptable", obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return NULL; +} +static PyObject *__Pyx_PyObject_GetItem(PyObject *obj, PyObject *key) { + PyTypeObject *tp = Py_TYPE(obj); + PyMappingMethods *mm = tp->tp_as_mapping; + PySequenceMethods *sm = tp->tp_as_sequence; + if (likely(mm && mm->mp_subscript)) { + return mm->mp_subscript(obj, key); + } + if (likely(sm && sm->sq_item)) { + return __Pyx_PyObject_GetIndex(obj, key); + } + return __Pyx_PyObject_GetItem_Slow(obj, key); +} +#endif + +/* KeywordStringCheck */ +static int __Pyx_CheckKeywordStrings( + PyObject *kw, + const char* function_name, + int kw_allowed) +{ + PyObject* key = 0; + Py_ssize_t pos = 0; +#if CYTHON_COMPILING_IN_PYPY + if (!kw_allowed && PyDict_Next(kw, &pos, &key, 0)) + goto invalid_keyword; + return 1; +#else + if (CYTHON_METH_FASTCALL && likely(PyTuple_Check(kw))) { + Py_ssize_t kwsize; +#if CYTHON_ASSUME_SAFE_MACROS + kwsize = PyTuple_GET_SIZE(kw); +#else + kwsize = PyTuple_Size(kw); + if (kwsize < 0) return 0; +#endif + if (unlikely(kwsize == 0)) + return 1; + if (!kw_allowed) { +#if CYTHON_ASSUME_SAFE_MACROS + key = PyTuple_GET_ITEM(kw, 0); +#else + key = PyTuple_GetItem(kw, pos); + if (!key) return 0; +#endif + goto invalid_keyword; + } +#if PY_VERSION_HEX < 0x03090000 + for (pos = 0; pos < kwsize; pos++) { +#if CYTHON_ASSUME_SAFE_MACROS + key = PyTuple_GET_ITEM(kw, pos); +#else + key = PyTuple_GetItem(kw, pos); + if (!key) return 0; +#endif + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } +#endif + return 1; + } + while (PyDict_Next(kw, &pos, &key, 0)) { + #if PY_MAJOR_VERSION < 3 + if (unlikely(!PyString_Check(key))) + #endif + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } + if (!kw_allowed && unlikely(key)) + goto invalid_keyword; + return 1; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + return 0; +#endif +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif + return 0; +} + +/* DivInt[Py_ssize_t] */ +static CYTHON_INLINE Py_ssize_t __Pyx_div_Py_ssize_t(Py_ssize_t a, Py_ssize_t b) { + Py_ssize_t q = a / b; + Py_ssize_t r = a - q*b; + q -= ((r != 0) & ((r ^ b) < 0)); + return q; +} + +/* GetAttr3 */ +#if __PYX_LIMITED_VERSION_HEX < 0x030d00A1 +static PyObject *__Pyx_GetAttr3Default(PyObject *d) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + if (unlikely(!__Pyx_PyErr_ExceptionMatches(PyExc_AttributeError))) + return NULL; + __Pyx_PyErr_Clear(); + Py_INCREF(d); + return d; +} +#endif +static CYTHON_INLINE PyObject *__Pyx_GetAttr3(PyObject *o, PyObject *n, PyObject *d) { + PyObject *r; +#if __PYX_LIMITED_VERSION_HEX >= 0x030d00A1 + int res = PyObject_GetOptionalAttr(o, n, &r); + return (res != 0) ? r : __Pyx_NewRef(d); +#else + #if CYTHON_USE_TYPE_SLOTS + if (likely(PyString_Check(n))) { + r = __Pyx_PyObject_GetAttrStrNoError(o, n); + if (unlikely(!r) && likely(!PyErr_Occurred())) { + r = __Pyx_NewRef(d); + } + return r; + } + #endif + r = PyObject_GetAttr(o, n); + return (likely(r)) ? r : __Pyx_GetAttr3Default(d); +#endif +} + +/* PyDictVersioning */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + return likely(dict) ? __PYX_GET_DICT_VERSION(dict) : 0; +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj) { + PyObject **dictptr = NULL; + Py_ssize_t offset = Py_TYPE(obj)->tp_dictoffset; + if (offset) { +#if CYTHON_COMPILING_IN_CPYTHON + dictptr = (likely(offset > 0)) ? (PyObject **) ((char *)obj + offset) : _PyObject_GetDictPtr(obj); +#else + dictptr = _PyObject_GetDictPtr(obj); +#endif + } + return (dictptr && *dictptr) ? __PYX_GET_DICT_VERSION(*dictptr) : 0; +} +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + if (unlikely(!dict) || unlikely(tp_dict_version != __PYX_GET_DICT_VERSION(dict))) + return 0; + return obj_dict_version == __Pyx_get_object_dict_version(obj); +} +#endif + +/* GetModuleGlobalName */ +#if CYTHON_USE_DICT_VERSIONS +static PyObject *__Pyx__GetModuleGlobalName(PyObject *name, PY_UINT64_T *dict_version, PyObject **dict_cached_value) +#else +static CYTHON_INLINE PyObject *__Pyx__GetModuleGlobalName(PyObject *name) +#endif +{ + PyObject *result; +#if !CYTHON_AVOID_BORROWED_REFS +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030500A1 && PY_VERSION_HEX < 0x030d0000 + result = _PyDict_GetItem_KnownHash(__pyx_d, name, ((PyASCIIObject *) name)->hash); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } else if (unlikely(PyErr_Occurred())) { + return NULL; + } +#elif CYTHON_COMPILING_IN_LIMITED_API + if (unlikely(!__pyx_m)) { + return NULL; + } + result = PyObject_GetAttr(__pyx_m, name); + if (likely(result)) { + return result; + } +#else + result = PyDict_GetItem(__pyx_d, name); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } +#endif +#else + result = PyObject_GetItem(__pyx_d, name); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } + PyErr_Clear(); +#endif + return __Pyx_GetBuiltinName(name); +} + +/* RaiseTooManyValuesToUnpack */ +static CYTHON_INLINE void __Pyx_RaiseTooManyValuesError(Py_ssize_t expected) { + PyErr_Format(PyExc_ValueError, + "too many values to unpack (expected %" CYTHON_FORMAT_SSIZE_T "d)", expected); +} + +/* RaiseNeedMoreValuesToUnpack */ +static CYTHON_INLINE void __Pyx_RaiseNeedMoreValuesError(Py_ssize_t index) { + PyErr_Format(PyExc_ValueError, + "need more than %" CYTHON_FORMAT_SSIZE_T "d value%.1s to unpack", + index, (index == 1) ? "" : "s"); +} + +/* RaiseNoneIterError */ +static CYTHON_INLINE void __Pyx_RaiseNoneNotIterableError(void) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not iterable"); +} + +/* ExtTypeTest */ +static CYTHON_INLINE int __Pyx_TypeTest(PyObject *obj, PyTypeObject *type) { + __Pyx_TypeName obj_type_name; + __Pyx_TypeName type_name; + if (unlikely(!type)) { + PyErr_SetString(PyExc_SystemError, "Missing type object"); + return 0; + } + if (likely(__Pyx_TypeCheck(obj, type))) + return 1; + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + type_name = __Pyx_PyType_GetName(type); + PyErr_Format(PyExc_TypeError, + "Cannot convert " __Pyx_FMT_TYPENAME " to " __Pyx_FMT_TYPENAME, + obj_type_name, type_name); + __Pyx_DECREF_TypeName(obj_type_name); + __Pyx_DECREF_TypeName(type_name); + return 0; +} + +/* GetTopmostException */ +#if CYTHON_USE_EXC_INFO_STACK && CYTHON_FAST_THREAD_STATE +static _PyErr_StackItem * +__Pyx_PyErr_GetTopmostException(PyThreadState *tstate) +{ + _PyErr_StackItem *exc_info = tstate->exc_info; + while ((exc_info->exc_value == NULL || exc_info->exc_value == Py_None) && + exc_info->previous_item != NULL) + { + exc_info = exc_info->previous_item; + } + return exc_info; +} +#endif + +/* SaveResetException */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx__ExceptionSave(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { + #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 + _PyErr_StackItem *exc_info = __Pyx_PyErr_GetTopmostException(tstate); + PyObject *exc_value = exc_info->exc_value; + if (exc_value == NULL || exc_value == Py_None) { + *value = NULL; + *type = NULL; + *tb = NULL; + } else { + *value = exc_value; + Py_INCREF(*value); + *type = (PyObject*) Py_TYPE(exc_value); + Py_INCREF(*type); + *tb = PyException_GetTraceback(exc_value); + } + #elif CYTHON_USE_EXC_INFO_STACK + _PyErr_StackItem *exc_info = __Pyx_PyErr_GetTopmostException(tstate); + *type = exc_info->exc_type; + *value = exc_info->exc_value; + *tb = exc_info->exc_traceback; + Py_XINCREF(*type); + Py_XINCREF(*value); + Py_XINCREF(*tb); + #else + *type = tstate->exc_type; + *value = tstate->exc_value; + *tb = tstate->exc_traceback; + Py_XINCREF(*type); + Py_XINCREF(*value); + Py_XINCREF(*tb); + #endif +} +static CYTHON_INLINE void __Pyx__ExceptionReset(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb) { + #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 + _PyErr_StackItem *exc_info = tstate->exc_info; + PyObject *tmp_value = exc_info->exc_value; + exc_info->exc_value = value; + Py_XDECREF(tmp_value); + Py_XDECREF(type); + Py_XDECREF(tb); + #else + PyObject *tmp_type, *tmp_value, *tmp_tb; + #if CYTHON_USE_EXC_INFO_STACK + _PyErr_StackItem *exc_info = tstate->exc_info; + tmp_type = exc_info->exc_type; + tmp_value = exc_info->exc_value; + tmp_tb = exc_info->exc_traceback; + exc_info->exc_type = type; + exc_info->exc_value = value; + exc_info->exc_traceback = tb; + #else + tmp_type = tstate->exc_type; + tmp_value = tstate->exc_value; + tmp_tb = tstate->exc_traceback; + tstate->exc_type = type; + tstate->exc_value = value; + tstate->exc_traceback = tb; + #endif + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); + #endif +} +#endif + +/* GetException */ +#if CYTHON_FAST_THREAD_STATE +static int __Pyx__GetException(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) +#else +static int __Pyx_GetException(PyObject **type, PyObject **value, PyObject **tb) +#endif +{ + PyObject *local_type = NULL, *local_value, *local_tb = NULL; +#if CYTHON_FAST_THREAD_STATE + PyObject *tmp_type, *tmp_value, *tmp_tb; + #if PY_VERSION_HEX >= 0x030C00A6 + local_value = tstate->current_exception; + tstate->current_exception = 0; + if (likely(local_value)) { + local_type = (PyObject*) Py_TYPE(local_value); + Py_INCREF(local_type); + local_tb = PyException_GetTraceback(local_value); + } + #else + local_type = tstate->curexc_type; + local_value = tstate->curexc_value; + local_tb = tstate->curexc_traceback; + tstate->curexc_type = 0; + tstate->curexc_value = 0; + tstate->curexc_traceback = 0; + #endif +#else + PyErr_Fetch(&local_type, &local_value, &local_tb); +#endif + PyErr_NormalizeException(&local_type, &local_value, &local_tb); +#if CYTHON_FAST_THREAD_STATE && PY_VERSION_HEX >= 0x030C00A6 + if (unlikely(tstate->current_exception)) +#elif CYTHON_FAST_THREAD_STATE + if (unlikely(tstate->curexc_type)) +#else + if (unlikely(PyErr_Occurred())) +#endif + goto bad; + #if PY_MAJOR_VERSION >= 3 + if (local_tb) { + if (unlikely(PyException_SetTraceback(local_value, local_tb) < 0)) + goto bad; + } + #endif + Py_XINCREF(local_tb); + Py_XINCREF(local_type); + Py_XINCREF(local_value); + *type = local_type; + *value = local_value; + *tb = local_tb; +#if CYTHON_FAST_THREAD_STATE + #if CYTHON_USE_EXC_INFO_STACK + { + _PyErr_StackItem *exc_info = tstate->exc_info; + #if PY_VERSION_HEX >= 0x030B00a4 + tmp_value = exc_info->exc_value; + exc_info->exc_value = local_value; + tmp_type = NULL; + tmp_tb = NULL; + Py_XDECREF(local_type); + Py_XDECREF(local_tb); + #else + tmp_type = exc_info->exc_type; + tmp_value = exc_info->exc_value; + tmp_tb = exc_info->exc_traceback; + exc_info->exc_type = local_type; + exc_info->exc_value = local_value; + exc_info->exc_traceback = local_tb; + #endif + } + #else + tmp_type = tstate->exc_type; + tmp_value = tstate->exc_value; + tmp_tb = tstate->exc_traceback; + tstate->exc_type = local_type; + tstate->exc_value = local_value; + tstate->exc_traceback = local_tb; + #endif + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); +#else + PyErr_SetExcInfo(local_type, local_value, local_tb); +#endif + return 0; +bad: + *type = 0; + *value = 0; + *tb = 0; + Py_XDECREF(local_type); + Py_XDECREF(local_value); + Py_XDECREF(local_tb); + return -1; +} + +/* SwapException */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx__ExceptionSwap(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { + PyObject *tmp_type, *tmp_value, *tmp_tb; + #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 + _PyErr_StackItem *exc_info = tstate->exc_info; + tmp_value = exc_info->exc_value; + exc_info->exc_value = *value; + if (tmp_value == NULL || tmp_value == Py_None) { + Py_XDECREF(tmp_value); + tmp_value = NULL; + tmp_type = NULL; + tmp_tb = NULL; + } else { + tmp_type = (PyObject*) Py_TYPE(tmp_value); + Py_INCREF(tmp_type); + #if CYTHON_COMPILING_IN_CPYTHON + tmp_tb = ((PyBaseExceptionObject*) tmp_value)->traceback; + Py_XINCREF(tmp_tb); + #else + tmp_tb = PyException_GetTraceback(tmp_value); + #endif + } + #elif CYTHON_USE_EXC_INFO_STACK + _PyErr_StackItem *exc_info = tstate->exc_info; + tmp_type = exc_info->exc_type; + tmp_value = exc_info->exc_value; + tmp_tb = exc_info->exc_traceback; + exc_info->exc_type = *type; + exc_info->exc_value = *value; + exc_info->exc_traceback = *tb; + #else + tmp_type = tstate->exc_type; + tmp_value = tstate->exc_value; + tmp_tb = tstate->exc_traceback; + tstate->exc_type = *type; + tstate->exc_value = *value; + tstate->exc_traceback = *tb; + #endif + *type = tmp_type; + *value = tmp_value; + *tb = tmp_tb; +} +#else +static CYTHON_INLINE void __Pyx_ExceptionSwap(PyObject **type, PyObject **value, PyObject **tb) { + PyObject *tmp_type, *tmp_value, *tmp_tb; + PyErr_GetExcInfo(&tmp_type, &tmp_value, &tmp_tb); + PyErr_SetExcInfo(*type, *value, *tb); + *type = tmp_type; + *value = tmp_value; + *tb = tmp_tb; +} +#endif + +/* Import */ +static PyObject *__Pyx_Import(PyObject *name, PyObject *from_list, int level) { + PyObject *module = 0; + PyObject *empty_dict = 0; + PyObject *empty_list = 0; + #if PY_MAJOR_VERSION < 3 + PyObject *py_import; + py_import = __Pyx_PyObject_GetAttrStr(__pyx_b, __pyx_n_s_import); + if (unlikely(!py_import)) + goto bad; + if (!from_list) { + empty_list = PyList_New(0); + if (unlikely(!empty_list)) + goto bad; + from_list = empty_list; + } + #endif + empty_dict = PyDict_New(); + if (unlikely(!empty_dict)) + goto bad; + { + #if PY_MAJOR_VERSION >= 3 + if (level == -1) { + if (strchr(__Pyx_MODULE_NAME, '.') != NULL) { + module = PyImport_ImportModuleLevelObject( + name, __pyx_d, empty_dict, from_list, 1); + if (unlikely(!module)) { + if (unlikely(!PyErr_ExceptionMatches(PyExc_ImportError))) + goto bad; + PyErr_Clear(); + } + } + level = 0; + } + #endif + if (!module) { + #if PY_MAJOR_VERSION < 3 + PyObject *py_level = PyInt_FromLong(level); + if (unlikely(!py_level)) + goto bad; + module = PyObject_CallFunctionObjArgs(py_import, + name, __pyx_d, empty_dict, from_list, py_level, (PyObject *)NULL); + Py_DECREF(py_level); + #else + module = PyImport_ImportModuleLevelObject( + name, __pyx_d, empty_dict, from_list, level); + #endif + } + } +bad: + Py_XDECREF(empty_dict); + Py_XDECREF(empty_list); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_import); + #endif + return module; +} + +/* ImportDottedModule */ +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx__ImportDottedModule_Error(PyObject *name, PyObject *parts_tuple, Py_ssize_t count) { + PyObject *partial_name = NULL, *slice = NULL, *sep = NULL; + if (unlikely(PyErr_Occurred())) { + PyErr_Clear(); + } + if (likely(PyTuple_GET_SIZE(parts_tuple) == count)) { + partial_name = name; + } else { + slice = PySequence_GetSlice(parts_tuple, 0, count); + if (unlikely(!slice)) + goto bad; + sep = PyUnicode_FromStringAndSize(".", 1); + if (unlikely(!sep)) + goto bad; + partial_name = PyUnicode_Join(sep, slice); + } + PyErr_Format( +#if PY_MAJOR_VERSION < 3 + PyExc_ImportError, + "No module named '%s'", PyString_AS_STRING(partial_name)); +#else +#if PY_VERSION_HEX >= 0x030600B1 + PyExc_ModuleNotFoundError, +#else + PyExc_ImportError, +#endif + "No module named '%U'", partial_name); +#endif +bad: + Py_XDECREF(sep); + Py_XDECREF(slice); + Py_XDECREF(partial_name); + return NULL; +} +#endif +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx__ImportDottedModule_Lookup(PyObject *name) { + PyObject *imported_module; +#if PY_VERSION_HEX < 0x030700A1 || (CYTHON_COMPILING_IN_PYPY && PYPY_VERSION_NUM < 0x07030400) + PyObject *modules = PyImport_GetModuleDict(); + if (unlikely(!modules)) + return NULL; + imported_module = __Pyx_PyDict_GetItemStr(modules, name); + Py_XINCREF(imported_module); +#else + imported_module = PyImport_GetModule(name); +#endif + return imported_module; +} +#endif +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_ImportDottedModule_WalkParts(PyObject *module, PyObject *name, PyObject *parts_tuple) { + Py_ssize_t i, nparts; + nparts = PyTuple_GET_SIZE(parts_tuple); + for (i=1; i < nparts && module; i++) { + PyObject *part, *submodule; +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + part = PyTuple_GET_ITEM(parts_tuple, i); +#else + part = PySequence_ITEM(parts_tuple, i); +#endif + submodule = __Pyx_PyObject_GetAttrStrNoError(module, part); +#if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(part); +#endif + Py_DECREF(module); + module = submodule; + } + if (unlikely(!module)) { + return __Pyx__ImportDottedModule_Error(name, parts_tuple, i); + } + return module; +} +#endif +static PyObject *__Pyx__ImportDottedModule(PyObject *name, PyObject *parts_tuple) { +#if PY_MAJOR_VERSION < 3 + PyObject *module, *from_list, *star = __pyx_n_s__3; + CYTHON_UNUSED_VAR(parts_tuple); + from_list = PyList_New(1); + if (unlikely(!from_list)) + return NULL; + Py_INCREF(star); + PyList_SET_ITEM(from_list, 0, star); + module = __Pyx_Import(name, from_list, 0); + Py_DECREF(from_list); + return module; +#else + PyObject *imported_module; + PyObject *module = __Pyx_Import(name, NULL, 0); + if (!parts_tuple || unlikely(!module)) + return module; + imported_module = __Pyx__ImportDottedModule_Lookup(name); + if (likely(imported_module)) { + Py_DECREF(module); + return imported_module; + } + PyErr_Clear(); + return __Pyx_ImportDottedModule_WalkParts(module, name, parts_tuple); +#endif +} +static PyObject *__Pyx_ImportDottedModule(PyObject *name, PyObject *parts_tuple) { +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030400B1 + PyObject *module = __Pyx__ImportDottedModule_Lookup(name); + if (likely(module)) { + PyObject *spec = __Pyx_PyObject_GetAttrStrNoError(module, __pyx_n_s_spec); + if (likely(spec)) { + PyObject *unsafe = __Pyx_PyObject_GetAttrStrNoError(spec, __pyx_n_s_initializing); + if (likely(!unsafe || !__Pyx_PyObject_IsTrue(unsafe))) { + Py_DECREF(spec); + spec = NULL; + } + Py_XDECREF(unsafe); + } + if (likely(!spec)) { + PyErr_Clear(); + return module; + } + Py_DECREF(spec); + Py_DECREF(module); + } else if (PyErr_Occurred()) { + PyErr_Clear(); + } +#endif + return __Pyx__ImportDottedModule(name, parts_tuple); +} + +/* FastTypeChecks */ +#if CYTHON_COMPILING_IN_CPYTHON +static int __Pyx_InBases(PyTypeObject *a, PyTypeObject *b) { + while (a) { + a = __Pyx_PyType_GetSlot(a, tp_base, PyTypeObject*); + if (a == b) + return 1; + } + return b == &PyBaseObject_Type; +} +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (a == b) return 1; + mro = a->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + if (PyTuple_GET_ITEM(mro, i) == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(a, b); +} +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (cls == a || cls == b) return 1; + mro = cls->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + PyObject *base = PyTuple_GET_ITEM(mro, i); + if (base == (PyObject *)a || base == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(cls, a) || __Pyx_InBases(cls, b); +} +#if PY_MAJOR_VERSION == 2 +static int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject* exc_type2) { + PyObject *exception, *value, *tb; + int res; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&exception, &value, &tb); + res = exc_type1 ? PyObject_IsSubclass(err, exc_type1) : 0; + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + if (!res) { + res = PyObject_IsSubclass(err, exc_type2); + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + } + __Pyx_ErrRestore(exception, value, tb); + return res; +} +#else +static CYTHON_INLINE int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject *exc_type2) { + if (exc_type1) { + return __Pyx_IsAnySubtype2((PyTypeObject*)err, (PyTypeObject*)exc_type1, (PyTypeObject*)exc_type2); + } else { + return __Pyx_IsSubtype((PyTypeObject*)err, (PyTypeObject*)exc_type2); + } +} +#endif +static int __Pyx_PyErr_GivenExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + assert(PyExceptionClass_Check(exc_type)); + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; itp_as_sequence && type->tp_as_sequence->sq_repeat)) { + return type->tp_as_sequence->sq_repeat(seq, mul); + } else +#endif + { + return __Pyx_PySequence_Multiply_Generic(seq, mul); + } +} + +/* SetItemInt */ +static int __Pyx_SetItemInt_Generic(PyObject *o, PyObject *j, PyObject *v) { + int r; + if (unlikely(!j)) return -1; + r = PyObject_SetItem(o, j, v); + Py_DECREF(j); + return r; +} +static CYTHON_INLINE int __Pyx_SetItemInt_Fast(PyObject *o, Py_ssize_t i, PyObject *v, int is_list, + CYTHON_NCP_UNUSED int wraparound, CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS && CYTHON_USE_TYPE_SLOTS + if (is_list || PyList_CheckExact(o)) { + Py_ssize_t n = (!wraparound) ? i : ((likely(i >= 0)) ? i : i + PyList_GET_SIZE(o)); + if ((!boundscheck) || likely(__Pyx_is_valid_index(n, PyList_GET_SIZE(o)))) { + PyObject* old = PyList_GET_ITEM(o, n); + Py_INCREF(v); + PyList_SET_ITEM(o, n, v); + Py_DECREF(old); + return 1; + } + } else { + PyMappingMethods *mm = Py_TYPE(o)->tp_as_mapping; + PySequenceMethods *sm = Py_TYPE(o)->tp_as_sequence; + if (mm && mm->mp_ass_subscript) { + int r; + PyObject *key = PyInt_FromSsize_t(i); + if (unlikely(!key)) return -1; + r = mm->mp_ass_subscript(o, key, v); + Py_DECREF(key); + return r; + } + if (likely(sm && sm->sq_ass_item)) { + if (wraparound && unlikely(i < 0) && likely(sm->sq_length)) { + Py_ssize_t l = sm->sq_length(o); + if (likely(l >= 0)) { + i += l; + } else { + if (!PyErr_ExceptionMatches(PyExc_OverflowError)) + return -1; + PyErr_Clear(); + } + } + return sm->sq_ass_item(o, i, v); + } + } +#else + if (is_list || !PyMapping_Check(o)) + { + return PySequence_SetItem(o, i, v); + } +#endif + return __Pyx_SetItemInt_Generic(o, PyInt_FromSsize_t(i), v); +} + +/* RaiseUnboundLocalError */ +static CYTHON_INLINE void __Pyx_RaiseUnboundLocalError(const char *varname) { + PyErr_Format(PyExc_UnboundLocalError, "local variable '%s' referenced before assignment", varname); +} + +/* DivInt[long] */ +static CYTHON_INLINE long __Pyx_div_long(long a, long b) { + long q = a / b; + long r = a - q*b; + q -= ((r != 0) & ((r ^ b) < 0)); + return q; +} + +/* ImportFrom */ +static PyObject* __Pyx_ImportFrom(PyObject* module, PyObject* name) { + PyObject* value = __Pyx_PyObject_GetAttrStr(module, name); + if (unlikely(!value) && PyErr_ExceptionMatches(PyExc_AttributeError)) { + const char* module_name_str = 0; + PyObject* module_name = 0; + PyObject* module_dot = 0; + PyObject* full_name = 0; + PyErr_Clear(); + module_name_str = PyModule_GetName(module); + if (unlikely(!module_name_str)) { goto modbad; } + module_name = PyUnicode_FromString(module_name_str); + if (unlikely(!module_name)) { goto modbad; } + module_dot = PyUnicode_Concat(module_name, __pyx_kp_u__2); + if (unlikely(!module_dot)) { goto modbad; } + full_name = PyUnicode_Concat(module_dot, name); + if (unlikely(!full_name)) { goto modbad; } + #if PY_VERSION_HEX < 0x030700A1 || (CYTHON_COMPILING_IN_PYPY && PYPY_VERSION_NUM < 0x07030400) + { + PyObject *modules = PyImport_GetModuleDict(); + if (unlikely(!modules)) + goto modbad; + value = PyObject_GetItem(modules, full_name); + } + #else + value = PyImport_GetModule(full_name); + #endif + modbad: + Py_XDECREF(full_name); + Py_XDECREF(module_dot); + Py_XDECREF(module_name); + } + if (unlikely(!value)) { + PyErr_Format(PyExc_ImportError, + #if PY_MAJOR_VERSION < 3 + "cannot import name %.230s", PyString_AS_STRING(name)); + #else + "cannot import name %S", name); + #endif + } + return value; +} + +/* HasAttr */ +#if __PYX_LIMITED_VERSION_HEX < 0x030d00A1 +static CYTHON_INLINE int __Pyx_HasAttr(PyObject *o, PyObject *n) { + PyObject *r; + if (unlikely(!__Pyx_PyBaseString_Check(n))) { + PyErr_SetString(PyExc_TypeError, + "hasattr(): attribute name must be string"); + return -1; + } + r = __Pyx_GetAttr(o, n); + if (!r) { + PyErr_Clear(); + return 0; + } else { + Py_DECREF(r); + return 1; + } +} +#endif + +/* PyObjectCall2Args */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call2Args(PyObject* function, PyObject* arg1, PyObject* arg2) { + PyObject *args[3] = {NULL, arg1, arg2}; + return __Pyx_PyObject_FastCall(function, args+1, 2 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* PyObjectGetMethod */ +static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method) { + PyObject *attr; +#if CYTHON_UNPACK_METHODS && CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_PYTYPE_LOOKUP + __Pyx_TypeName type_name; + PyTypeObject *tp = Py_TYPE(obj); + PyObject *descr; + descrgetfunc f = NULL; + PyObject **dictptr, *dict; + int meth_found = 0; + assert (*method == NULL); + if (unlikely(tp->tp_getattro != PyObject_GenericGetAttr)) { + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; + } + if (unlikely(tp->tp_dict == NULL) && unlikely(PyType_Ready(tp) < 0)) { + return 0; + } + descr = _PyType_Lookup(tp, name); + if (likely(descr != NULL)) { + Py_INCREF(descr); +#if defined(Py_TPFLAGS_METHOD_DESCRIPTOR) && Py_TPFLAGS_METHOD_DESCRIPTOR + if (__Pyx_PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_METHOD_DESCRIPTOR)) +#elif PY_MAJOR_VERSION >= 3 + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type))) + #endif +#else + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr))) + #endif +#endif + { + meth_found = 1; + } else { + f = Py_TYPE(descr)->tp_descr_get; + if (f != NULL && PyDescr_IsData(descr)) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + } + } + dictptr = _PyObject_GetDictPtr(obj); + if (dictptr != NULL && (dict = *dictptr) != NULL) { + Py_INCREF(dict); + attr = __Pyx_PyDict_GetItemStr(dict, name); + if (attr != NULL) { + Py_INCREF(attr); + Py_DECREF(dict); + Py_XDECREF(descr); + goto try_unpack; + } + Py_DECREF(dict); + } + if (meth_found) { + *method = descr; + return 1; + } + if (f != NULL) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + if (likely(descr != NULL)) { + *method = descr; + return 0; + } + type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return 0; +#else + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; +#endif +try_unpack: +#if CYTHON_UNPACK_METHODS + if (likely(attr) && PyMethod_Check(attr) && likely(PyMethod_GET_SELF(attr) == obj)) { + PyObject *function = PyMethod_GET_FUNCTION(attr); + Py_INCREF(function); + Py_DECREF(attr); + *method = function; + return 1; + } +#endif + *method = attr; + return 0; +} + +/* PyObjectCallMethod1 */ +#if !(CYTHON_VECTORCALL && __PYX_LIMITED_VERSION_HEX >= 0x030C00A2) +static PyObject* __Pyx__PyObject_CallMethod1(PyObject* method, PyObject* arg) { + PyObject *result = __Pyx_PyObject_CallOneArg(method, arg); + Py_DECREF(method); + return result; +} +#endif +static PyObject* __Pyx_PyObject_CallMethod1(PyObject* obj, PyObject* method_name, PyObject* arg) { +#if CYTHON_VECTORCALL && __PYX_LIMITED_VERSION_HEX >= 0x030C00A2 + PyObject *args[2] = {obj, arg}; + (void) __Pyx_PyObject_GetMethod; + (void) __Pyx_PyObject_CallOneArg; + (void) __Pyx_PyObject_Call2Args; + return PyObject_VectorcallMethod(method_name, args, 2 | PY_VECTORCALL_ARGUMENTS_OFFSET, NULL); +#else + PyObject *method = NULL, *result; + int is_method = __Pyx_PyObject_GetMethod(obj, method_name, &method); + if (likely(is_method)) { + result = __Pyx_PyObject_Call2Args(method, obj, arg); + Py_DECREF(method); + return result; + } + if (unlikely(!method)) return NULL; + return __Pyx__PyObject_CallMethod1(method, arg); +#endif +} + +/* StringJoin */ +static CYTHON_INLINE PyObject* __Pyx_PyBytes_Join(PyObject* sep, PyObject* values) { + (void) __Pyx_PyObject_CallMethod1; +#if CYTHON_COMPILING_IN_CPYTHON && PY_MAJOR_VERSION < 3 + return _PyString_Join(sep, values); +#elif CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030d0000 + return _PyBytes_Join(sep, values); +#else + return __Pyx_PyObject_CallMethod1(sep, __pyx_n_s_join, values); +#endif +} + +/* CIntToPyUnicode */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_size_t(size_t value, Py_ssize_t width, char padding_char, char format_char) { + char digits[sizeof(size_t)*3+2]; + char *dpos, *end = digits + sizeof(size_t)*3+2; + const char *hex_digits = DIGITS_HEX; + Py_ssize_t length, ulength; + int prepend_sign, last_one_off; + size_t remaining; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const size_t neg_one = (size_t) -1, const_zero = (size_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (format_char == 'X') { + hex_digits += 16; + format_char = 'x'; + } + remaining = value; + last_one_off = 0; + dpos = end; + do { + int digit_pos; + switch (format_char) { + case 'o': + digit_pos = abs((int)(remaining % (8*8))); + remaining = (size_t) (remaining / (8*8)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_8 + digit_pos * 2, 2); + last_one_off = (digit_pos < 8); + break; + case 'd': + digit_pos = abs((int)(remaining % (10*10))); + remaining = (size_t) (remaining / (10*10)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_10 + digit_pos * 2, 2); + last_one_off = (digit_pos < 10); + break; + case 'x': + *(--dpos) = hex_digits[abs((int)(remaining % 16))]; + remaining = (size_t) (remaining / 16); + break; + default: + assert(0); + break; + } + } while (unlikely(remaining != 0)); + assert(!last_one_off || *dpos == '0'); + dpos += last_one_off; + length = end - dpos; + ulength = length; + prepend_sign = 0; + if (!is_unsigned && value <= neg_one) { + if (padding_char == ' ' || width <= length + 1) { + *(--dpos) = '-'; + ++length; + } else { + prepend_sign = 1; + } + ++ulength; + } + if (width > ulength) { + ulength = width; + } + if (ulength == 1) { + return PyUnicode_FromOrdinal(*dpos); + } + return __Pyx_PyUnicode_BuildFromAscii(ulength, dpos, (int) length, prepend_sign, padding_char); +} + +/* Profile */ +#if CYTHON_PROFILE +static int __Pyx_TraceSetupAndCall(PyCodeObject** code, + PyFrameObject** frame, + PyThreadState* tstate, + const char *funcname, + const char *srcfile, + int firstlineno) { + PyObject *type, *value, *traceback; + int retval; + if (*frame == NULL || !CYTHON_PROFILE_REUSE_FRAME) { + if (*code == NULL) { + *code = __Pyx_createFrameCodeObject(funcname, srcfile, firstlineno); + if (*code == NULL) return 0; + } + *frame = PyFrame_New( + tstate, /*PyThreadState *tstate*/ + *code, /*PyCodeObject *code*/ + __pyx_d, /*PyObject *globals*/ + 0 /*PyObject *locals*/ + ); + if (*frame == NULL) return 0; + if (CYTHON_TRACE && (*frame)->f_trace == NULL) { + Py_INCREF(Py_None); + (*frame)->f_trace = Py_None; + } +#if PY_VERSION_HEX < 0x030400B1 + } else { + (*frame)->f_tstate = tstate; +#endif + } + __Pyx_PyFrame_SetLineNumber(*frame, firstlineno); + retval = 1; + __Pyx_EnterTracing(tstate); + __Pyx_ErrFetchInState(tstate, &type, &value, &traceback); + #if CYTHON_TRACE + if (tstate->c_tracefunc) + retval = tstate->c_tracefunc(tstate->c_traceobj, *frame, PyTrace_CALL, NULL) == 0; + if (retval && tstate->c_profilefunc) + #endif + retval = tstate->c_profilefunc(tstate->c_profileobj, *frame, PyTrace_CALL, NULL) == 0; + __Pyx_LeaveTracing(tstate); + if (retval) { + __Pyx_ErrRestoreInState(tstate, type, value, traceback); + return __Pyx_IsTracing(tstate, 0, 0) && retval; + } else { + Py_XDECREF(type); + Py_XDECREF(value); + Py_XDECREF(traceback); + return -1; + } +} +static PyCodeObject *__Pyx_createFrameCodeObject(const char *funcname, const char *srcfile, int firstlineno) { + PyCodeObject *py_code = 0; +#if PY_MAJOR_VERSION >= 3 + py_code = PyCode_NewEmpty(srcfile, funcname, firstlineno); + if (likely(py_code)) { + py_code->co_flags |= CO_OPTIMIZED | CO_NEWLOCALS; + } +#else + PyObject *py_srcfile = 0; + PyObject *py_funcname = 0; + py_funcname = PyString_FromString(funcname); + if (unlikely(!py_funcname)) goto bad; + py_srcfile = PyString_FromString(srcfile); + if (unlikely(!py_srcfile)) goto bad; + py_code = PyCode_New( + 0, + 0, + 0, + CO_OPTIMIZED | CO_NEWLOCALS, + __pyx_empty_bytes, /*PyObject *code,*/ + __pyx_empty_tuple, /*PyObject *consts,*/ + __pyx_empty_tuple, /*PyObject *names,*/ + __pyx_empty_tuple, /*PyObject *varnames,*/ + __pyx_empty_tuple, /*PyObject *freevars,*/ + __pyx_empty_tuple, /*PyObject *cellvars,*/ + py_srcfile, /*PyObject *filename,*/ + py_funcname, /*PyObject *name,*/ + firstlineno, + __pyx_empty_bytes /*PyObject *lnotab*/ + ); +bad: + Py_XDECREF(py_srcfile); + Py_XDECREF(py_funcname); +#endif + return py_code; +} +#endif + +/* IsLittleEndian */ +static CYTHON_INLINE int __Pyx_Is_Little_Endian(void) +{ + union { + uint32_t u32; + uint8_t u8[4]; + } S; + S.u32 = 0x01020304; + return S.u8[0] == 4; +} + +/* BufferFormatCheck */ +static void __Pyx_BufFmt_Init(__Pyx_BufFmt_Context* ctx, + __Pyx_BufFmt_StackElem* stack, + __Pyx_TypeInfo* type) { + stack[0].field = &ctx->root; + stack[0].parent_offset = 0; + ctx->root.type = type; + ctx->root.name = "buffer dtype"; + ctx->root.offset = 0; + ctx->head = stack; + ctx->head->field = &ctx->root; + ctx->fmt_offset = 0; + ctx->head->parent_offset = 0; + ctx->new_packmode = '@'; + ctx->enc_packmode = '@'; + ctx->new_count = 1; + ctx->enc_count = 0; + ctx->enc_type = 0; + ctx->is_complex = 0; + ctx->is_valid_array = 0; + ctx->struct_alignment = 0; + while (type->typegroup == 'S') { + ++ctx->head; + ctx->head->field = type->fields; + ctx->head->parent_offset = 0; + type = type->fields->type; + } +} +static int __Pyx_BufFmt_ParseNumber(const char** ts) { + int count; + const char* t = *ts; + if (*t < '0' || *t > '9') { + return -1; + } else { + count = *t++ - '0'; + while (*t >= '0' && *t <= '9') { + count *= 10; + count += *t++ - '0'; + } + } + *ts = t; + return count; +} +static int __Pyx_BufFmt_ExpectNumber(const char **ts) { + int number = __Pyx_BufFmt_ParseNumber(ts); + if (number == -1) + PyErr_Format(PyExc_ValueError,\ + "Does not understand character buffer dtype format string ('%c')", **ts); + return number; +} +static void __Pyx_BufFmt_RaiseUnexpectedChar(char ch) { + PyErr_Format(PyExc_ValueError, + "Unexpected format string character: '%c'", ch); +} +static const char* __Pyx_BufFmt_DescribeTypeChar(char ch, int is_complex) { + switch (ch) { + case '?': return "'bool'"; + case 'c': return "'char'"; + case 'b': return "'signed char'"; + case 'B': return "'unsigned char'"; + case 'h': return "'short'"; + case 'H': return "'unsigned short'"; + case 'i': return "'int'"; + case 'I': return "'unsigned int'"; + case 'l': return "'long'"; + case 'L': return "'unsigned long'"; + case 'q': return "'long long'"; + case 'Q': return "'unsigned long long'"; + case 'f': return (is_complex ? "'complex float'" : "'float'"); + case 'd': return (is_complex ? "'complex double'" : "'double'"); + case 'g': return (is_complex ? "'complex long double'" : "'long double'"); + case 'T': return "a struct"; + case 'O': return "Python object"; + case 'P': return "a pointer"; + case 's': case 'p': return "a string"; + case 0: return "end"; + default: return "unparsable format string"; + } +} +static size_t __Pyx_BufFmt_TypeCharToStandardSize(char ch, int is_complex) { + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return 2; + case 'i': case 'I': case 'l': case 'L': return 4; + case 'q': case 'Q': return 8; + case 'f': return (is_complex ? 8 : 4); + case 'd': return (is_complex ? 16 : 8); + case 'g': { + PyErr_SetString(PyExc_ValueError, "Python does not define a standard format string size for long double ('g').."); + return 0; + } + case 'O': case 'P': return sizeof(void*); + default: + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } +} +static size_t __Pyx_BufFmt_TypeCharToNativeSize(char ch, int is_complex) { + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return sizeof(short); + case 'i': case 'I': return sizeof(int); + case 'l': case 'L': return sizeof(long); + #ifdef HAVE_LONG_LONG + case 'q': case 'Q': return sizeof(PY_LONG_LONG); + #endif + case 'f': return sizeof(float) * (is_complex ? 2 : 1); + case 'd': return sizeof(double) * (is_complex ? 2 : 1); + case 'g': return sizeof(long double) * (is_complex ? 2 : 1); + case 'O': case 'P': return sizeof(void*); + default: { + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } + } +} +typedef struct { char c; short x; } __Pyx_st_short; +typedef struct { char c; int x; } __Pyx_st_int; +typedef struct { char c; long x; } __Pyx_st_long; +typedef struct { char c; float x; } __Pyx_st_float; +typedef struct { char c; double x; } __Pyx_st_double; +typedef struct { char c; long double x; } __Pyx_st_longdouble; +typedef struct { char c; void *x; } __Pyx_st_void_p; +#ifdef HAVE_LONG_LONG +typedef struct { char c; PY_LONG_LONG x; } __Pyx_st_longlong; +#endif +static size_t __Pyx_BufFmt_TypeCharToAlignment(char ch, int is_complex) { + CYTHON_UNUSED_VAR(is_complex); + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return sizeof(__Pyx_st_short) - sizeof(short); + case 'i': case 'I': return sizeof(__Pyx_st_int) - sizeof(int); + case 'l': case 'L': return sizeof(__Pyx_st_long) - sizeof(long); +#ifdef HAVE_LONG_LONG + case 'q': case 'Q': return sizeof(__Pyx_st_longlong) - sizeof(PY_LONG_LONG); +#endif + case 'f': return sizeof(__Pyx_st_float) - sizeof(float); + case 'd': return sizeof(__Pyx_st_double) - sizeof(double); + case 'g': return sizeof(__Pyx_st_longdouble) - sizeof(long double); + case 'P': case 'O': return sizeof(__Pyx_st_void_p) - sizeof(void*); + default: + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } +} +/* These are for computing the padding at the end of the struct to align + on the first member of the struct. This will probably the same as above, + but we don't have any guarantees. + */ +typedef struct { short x; char c; } __Pyx_pad_short; +typedef struct { int x; char c; } __Pyx_pad_int; +typedef struct { long x; char c; } __Pyx_pad_long; +typedef struct { float x; char c; } __Pyx_pad_float; +typedef struct { double x; char c; } __Pyx_pad_double; +typedef struct { long double x; char c; } __Pyx_pad_longdouble; +typedef struct { void *x; char c; } __Pyx_pad_void_p; +#ifdef HAVE_LONG_LONG +typedef struct { PY_LONG_LONG x; char c; } __Pyx_pad_longlong; +#endif +static size_t __Pyx_BufFmt_TypeCharToPadding(char ch, int is_complex) { + CYTHON_UNUSED_VAR(is_complex); + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return sizeof(__Pyx_pad_short) - sizeof(short); + case 'i': case 'I': return sizeof(__Pyx_pad_int) - sizeof(int); + case 'l': case 'L': return sizeof(__Pyx_pad_long) - sizeof(long); +#ifdef HAVE_LONG_LONG + case 'q': case 'Q': return sizeof(__Pyx_pad_longlong) - sizeof(PY_LONG_LONG); +#endif + case 'f': return sizeof(__Pyx_pad_float) - sizeof(float); + case 'd': return sizeof(__Pyx_pad_double) - sizeof(double); + case 'g': return sizeof(__Pyx_pad_longdouble) - sizeof(long double); + case 'P': case 'O': return sizeof(__Pyx_pad_void_p) - sizeof(void*); + default: + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } +} +static char __Pyx_BufFmt_TypeCharToGroup(char ch, int is_complex) { + switch (ch) { + case 'c': + return 'H'; + case 'b': case 'h': case 'i': + case 'l': case 'q': case 's': case 'p': + return 'I'; + case '?': case 'B': case 'H': case 'I': case 'L': case 'Q': + return 'U'; + case 'f': case 'd': case 'g': + return (is_complex ? 'C' : 'R'); + case 'O': + return 'O'; + case 'P': + return 'P'; + default: { + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } + } +} +static void __Pyx_BufFmt_RaiseExpected(__Pyx_BufFmt_Context* ctx) { + if (ctx->head == NULL || ctx->head->field == &ctx->root) { + const char* expected; + const char* quote; + if (ctx->head == NULL) { + expected = "end"; + quote = ""; + } else { + expected = ctx->head->field->type->name; + quote = "'"; + } + PyErr_Format(PyExc_ValueError, + "Buffer dtype mismatch, expected %s%s%s but got %s", + quote, expected, quote, + __Pyx_BufFmt_DescribeTypeChar(ctx->enc_type, ctx->is_complex)); + } else { + __Pyx_StructField* field = ctx->head->field; + __Pyx_StructField* parent = (ctx->head - 1)->field; + PyErr_Format(PyExc_ValueError, + "Buffer dtype mismatch, expected '%s' but got %s in '%s.%s'", + field->type->name, __Pyx_BufFmt_DescribeTypeChar(ctx->enc_type, ctx->is_complex), + parent->type->name, field->name); + } +} +static int __Pyx_BufFmt_ProcessTypeChunk(__Pyx_BufFmt_Context* ctx) { + char group; + size_t size, offset, arraysize = 1; + if (ctx->enc_type == 0) return 0; + if (ctx->head->field->type->arraysize[0]) { + int i, ndim = 0; + if (ctx->enc_type == 's' || ctx->enc_type == 'p') { + ctx->is_valid_array = ctx->head->field->type->ndim == 1; + ndim = 1; + if (ctx->enc_count != ctx->head->field->type->arraysize[0]) { + PyErr_Format(PyExc_ValueError, + "Expected a dimension of size %zu, got %zu", + ctx->head->field->type->arraysize[0], ctx->enc_count); + return -1; + } + } + if (!ctx->is_valid_array) { + PyErr_Format(PyExc_ValueError, "Expected %d dimensions, got %d", + ctx->head->field->type->ndim, ndim); + return -1; + } + for (i = 0; i < ctx->head->field->type->ndim; i++) { + arraysize *= ctx->head->field->type->arraysize[i]; + } + ctx->is_valid_array = 0; + ctx->enc_count = 1; + } + group = __Pyx_BufFmt_TypeCharToGroup(ctx->enc_type, ctx->is_complex); + do { + __Pyx_StructField* field = ctx->head->field; + __Pyx_TypeInfo* type = field->type; + if (ctx->enc_packmode == '@' || ctx->enc_packmode == '^') { + size = __Pyx_BufFmt_TypeCharToNativeSize(ctx->enc_type, ctx->is_complex); + } else { + size = __Pyx_BufFmt_TypeCharToStandardSize(ctx->enc_type, ctx->is_complex); + } + if (ctx->enc_packmode == '@') { + size_t align_at = __Pyx_BufFmt_TypeCharToAlignment(ctx->enc_type, ctx->is_complex); + size_t align_mod_offset; + if (align_at == 0) return -1; + align_mod_offset = ctx->fmt_offset % align_at; + if (align_mod_offset > 0) ctx->fmt_offset += align_at - align_mod_offset; + if (ctx->struct_alignment == 0) + ctx->struct_alignment = __Pyx_BufFmt_TypeCharToPadding(ctx->enc_type, + ctx->is_complex); + } + if (type->size != size || type->typegroup != group) { + if (type->typegroup == 'C' && type->fields != NULL) { + size_t parent_offset = ctx->head->parent_offset + field->offset; + ++ctx->head; + ctx->head->field = type->fields; + ctx->head->parent_offset = parent_offset; + continue; + } + if ((type->typegroup == 'H' || group == 'H') && type->size == size) { + } else { + __Pyx_BufFmt_RaiseExpected(ctx); + return -1; + } + } + offset = ctx->head->parent_offset + field->offset; + if (ctx->fmt_offset != offset) { + PyErr_Format(PyExc_ValueError, + "Buffer dtype mismatch; next field is at offset %" CYTHON_FORMAT_SSIZE_T "d but %" CYTHON_FORMAT_SSIZE_T "d expected", + (Py_ssize_t)ctx->fmt_offset, (Py_ssize_t)offset); + return -1; + } + ctx->fmt_offset += size; + if (arraysize) + ctx->fmt_offset += (arraysize - 1) * size; + --ctx->enc_count; + while (1) { + if (field == &ctx->root) { + ctx->head = NULL; + if (ctx->enc_count != 0) { + __Pyx_BufFmt_RaiseExpected(ctx); + return -1; + } + break; + } + ctx->head->field = ++field; + if (field->type == NULL) { + --ctx->head; + field = ctx->head->field; + continue; + } else if (field->type->typegroup == 'S') { + size_t parent_offset = ctx->head->parent_offset + field->offset; + if (field->type->fields->type == NULL) continue; + field = field->type->fields; + ++ctx->head; + ctx->head->field = field; + ctx->head->parent_offset = parent_offset; + break; + } else { + break; + } + } + } while (ctx->enc_count); + ctx->enc_type = 0; + ctx->is_complex = 0; + return 0; +} +static int +__pyx_buffmt_parse_array(__Pyx_BufFmt_Context* ctx, const char** tsp) +{ + const char *ts = *tsp; + int i = 0, number, ndim; + ++ts; + if (ctx->new_count != 1) { + PyErr_SetString(PyExc_ValueError, + "Cannot handle repeated arrays in format string"); + return -1; + } + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return -1; + ndim = ctx->head->field->type->ndim; + while (*ts && *ts != ')') { + switch (*ts) { + case ' ': case '\f': case '\r': case '\n': case '\t': case '\v': continue; + default: break; + } + number = __Pyx_BufFmt_ExpectNumber(&ts); + if (number == -1) return -1; + if (i < ndim && (size_t) number != ctx->head->field->type->arraysize[i]) { + PyErr_Format(PyExc_ValueError, + "Expected a dimension of size %zu, got %d", + ctx->head->field->type->arraysize[i], number); + return -1; + } + if (*ts != ',' && *ts != ')') { + PyErr_Format(PyExc_ValueError, + "Expected a comma in format string, got '%c'", *ts); + return -1; + } + if (*ts == ',') ts++; + i++; + } + if (i != ndim) { + PyErr_Format(PyExc_ValueError, "Expected %d dimension(s), got %d", + ctx->head->field->type->ndim, i); + return -1; + } + if (!*ts) { + PyErr_SetString(PyExc_ValueError, + "Unexpected end of format string, expected ')'"); + return -1; + } + ctx->is_valid_array = 1; + ctx->new_count = 1; + *tsp = ++ts; + return 0; +} +static const char* __Pyx_BufFmt_CheckString(__Pyx_BufFmt_Context* ctx, const char* ts) { + int got_Z = 0; + while (1) { + switch(*ts) { + case 0: + if (ctx->enc_type != 0 && ctx->head == NULL) { + __Pyx_BufFmt_RaiseExpected(ctx); + return NULL; + } + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + if (ctx->head != NULL) { + __Pyx_BufFmt_RaiseExpected(ctx); + return NULL; + } + return ts; + case ' ': + case '\r': + case '\n': + ++ts; + break; + case '<': + if (!__Pyx_Is_Little_Endian()) { + PyErr_SetString(PyExc_ValueError, "Little-endian buffer not supported on big-endian compiler"); + return NULL; + } + ctx->new_packmode = '='; + ++ts; + break; + case '>': + case '!': + if (__Pyx_Is_Little_Endian()) { + PyErr_SetString(PyExc_ValueError, "Big-endian buffer not supported on little-endian compiler"); + return NULL; + } + ctx->new_packmode = '='; + ++ts; + break; + case '=': + case '@': + case '^': + ctx->new_packmode = *ts++; + break; + case 'T': + { + const char* ts_after_sub; + size_t i, struct_count = ctx->new_count; + size_t struct_alignment = ctx->struct_alignment; + ctx->new_count = 1; + ++ts; + if (*ts != '{') { + PyErr_SetString(PyExc_ValueError, "Buffer acquisition: Expected '{' after 'T'"); + return NULL; + } + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->enc_type = 0; + ctx->enc_count = 0; + ctx->struct_alignment = 0; + ++ts; + ts_after_sub = ts; + for (i = 0; i != struct_count; ++i) { + ts_after_sub = __Pyx_BufFmt_CheckString(ctx, ts); + if (!ts_after_sub) return NULL; + } + ts = ts_after_sub; + if (struct_alignment) ctx->struct_alignment = struct_alignment; + } + break; + case '}': + { + size_t alignment = ctx->struct_alignment; + ++ts; + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->enc_type = 0; + if (alignment && ctx->fmt_offset % alignment) { + ctx->fmt_offset += alignment - (ctx->fmt_offset % alignment); + } + } + return ts; + case 'x': + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->fmt_offset += ctx->new_count; + ctx->new_count = 1; + ctx->enc_count = 0; + ctx->enc_type = 0; + ctx->enc_packmode = ctx->new_packmode; + ++ts; + break; + case 'Z': + got_Z = 1; + ++ts; + if (*ts != 'f' && *ts != 'd' && *ts != 'g') { + __Pyx_BufFmt_RaiseUnexpectedChar('Z'); + return NULL; + } + CYTHON_FALLTHROUGH; + case '?': case 'c': case 'b': case 'B': case 'h': case 'H': case 'i': case 'I': + case 'l': case 'L': case 'q': case 'Q': + case 'f': case 'd': case 'g': + case 'O': case 'p': + if ((ctx->enc_type == *ts) && (got_Z == ctx->is_complex) && + (ctx->enc_packmode == ctx->new_packmode) && (!ctx->is_valid_array)) { + ctx->enc_count += ctx->new_count; + ctx->new_count = 1; + got_Z = 0; + ++ts; + break; + } + CYTHON_FALLTHROUGH; + case 's': + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->enc_count = ctx->new_count; + ctx->enc_packmode = ctx->new_packmode; + ctx->enc_type = *ts; + ctx->is_complex = got_Z; + ++ts; + ctx->new_count = 1; + got_Z = 0; + break; + case ':': + ++ts; + while(*ts != ':') ++ts; + ++ts; + break; + case '(': + if (__pyx_buffmt_parse_array(ctx, &ts) < 0) return NULL; + break; + default: + { + int number = __Pyx_BufFmt_ExpectNumber(&ts); + if (number == -1) return NULL; + ctx->new_count = (size_t)number; + } + } + } +} + +/* BufferGetAndValidate */ + static CYTHON_INLINE void __Pyx_SafeReleaseBuffer(Py_buffer* info) { + if (unlikely(info->buf == NULL)) return; + if (info->suboffsets == __Pyx_minusones) info->suboffsets = NULL; + __Pyx_ReleaseBuffer(info); +} +static void __Pyx_ZeroBuffer(Py_buffer* buf) { + buf->buf = NULL; + buf->obj = NULL; + buf->strides = __Pyx_zeros; + buf->shape = __Pyx_zeros; + buf->suboffsets = __Pyx_minusones; +} +static int __Pyx__GetBufferAndValidate( + Py_buffer* buf, PyObject* obj, __Pyx_TypeInfo* dtype, int flags, + int nd, int cast, __Pyx_BufFmt_StackElem* stack) +{ + buf->buf = NULL; + if (unlikely(__Pyx_GetBuffer(obj, buf, flags) == -1)) { + __Pyx_ZeroBuffer(buf); + return -1; + } + if (unlikely(buf->ndim != nd)) { + PyErr_Format(PyExc_ValueError, + "Buffer has wrong number of dimensions (expected %d, got %d)", + nd, buf->ndim); + goto fail; + } + if (!cast) { + __Pyx_BufFmt_Context ctx; + __Pyx_BufFmt_Init(&ctx, stack, dtype); + if (!__Pyx_BufFmt_CheckString(&ctx, buf->format)) goto fail; + } + if (unlikely((size_t)buf->itemsize != dtype->size)) { + PyErr_Format(PyExc_ValueError, + "Item size of buffer (%" CYTHON_FORMAT_SSIZE_T "d byte%s) does not match size of '%s' (%" CYTHON_FORMAT_SSIZE_T "d byte%s)", + buf->itemsize, (buf->itemsize > 1) ? "s" : "", + dtype->name, (Py_ssize_t)dtype->size, (dtype->size > 1) ? "s" : ""); + goto fail; + } + if (buf->suboffsets == NULL) buf->suboffsets = __Pyx_minusones; + return 0; +fail:; + __Pyx_SafeReleaseBuffer(buf); + return -1; +} + +/* BufferFallbackError */ + static void __Pyx_RaiseBufferFallbackError(void) { + PyErr_SetString(PyExc_ValueError, + "Buffer acquisition failed on assignment; and then reacquiring the old buffer failed too!"); +} + +/* PyObjectCallNoArg */ + static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func) { + PyObject *arg[2] = {NULL, NULL}; + return __Pyx_PyObject_FastCall(func, arg + 1, 0 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* WriteUnraisableException */ + static void __Pyx_WriteUnraisable(const char *name, int clineno, + int lineno, const char *filename, + int full_traceback, int nogil) { + PyObject *old_exc, *old_val, *old_tb; + PyObject *ctx; + __Pyx_PyThreadState_declare +#ifdef WITH_THREAD + PyGILState_STATE state; + if (nogil) + state = PyGILState_Ensure(); + else state = (PyGILState_STATE)0; +#endif + CYTHON_UNUSED_VAR(clineno); + CYTHON_UNUSED_VAR(lineno); + CYTHON_UNUSED_VAR(filename); + CYTHON_MAYBE_UNUSED_VAR(nogil); + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&old_exc, &old_val, &old_tb); + if (full_traceback) { + Py_XINCREF(old_exc); + Py_XINCREF(old_val); + Py_XINCREF(old_tb); + __Pyx_ErrRestore(old_exc, old_val, old_tb); + PyErr_PrintEx(1); + } + #if PY_MAJOR_VERSION < 3 + ctx = PyString_FromString(name); + #else + ctx = PyUnicode_FromString(name); + #endif + __Pyx_ErrRestore(old_exc, old_val, old_tb); + if (!ctx) { + PyErr_WriteUnraisable(Py_None); + } else { + PyErr_WriteUnraisable(ctx); + Py_DECREF(ctx); + } +#ifdef WITH_THREAD + if (nogil) + PyGILState_Release(state); +#endif +} + +/* PyObject_GenericGetAttrNoDict */ + #if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject *__Pyx_RaiseGenericGetAttributeError(PyTypeObject *tp, PyObject *attr_name) { + __Pyx_TypeName type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, attr_name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(attr_name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name) { + PyObject *descr; + PyTypeObject *tp = Py_TYPE(obj); + if (unlikely(!PyString_Check(attr_name))) { + return PyObject_GenericGetAttr(obj, attr_name); + } + assert(!tp->tp_dictoffset); + descr = _PyType_Lookup(tp, attr_name); + if (unlikely(!descr)) { + return __Pyx_RaiseGenericGetAttributeError(tp, attr_name); + } + Py_INCREF(descr); + #if PY_MAJOR_VERSION < 3 + if (likely(PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_HAVE_CLASS))) + #endif + { + descrgetfunc f = Py_TYPE(descr)->tp_descr_get; + if (unlikely(f)) { + PyObject *res = f(descr, obj, (PyObject *)tp); + Py_DECREF(descr); + return res; + } + } + return descr; +} +#endif + +/* PyObject_GenericGetAttr */ + #if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name) { + if (unlikely(Py_TYPE(obj)->tp_dictoffset)) { + return PyObject_GenericGetAttr(obj, attr_name); + } + return __Pyx_PyObject_GenericGetAttrNoDict(obj, attr_name); +} +#endif + +/* FixUpExtensionType */ + #if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type) { +#if PY_VERSION_HEX > 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + CYTHON_UNUSED_VAR(spec); + CYTHON_UNUSED_VAR(type); +#else + const PyType_Slot *slot = spec->slots; + while (slot && slot->slot && slot->slot != Py_tp_members) + slot++; + if (slot && slot->slot == Py_tp_members) { + int changed = 0; +#if !(PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON) + const +#endif + PyMemberDef *memb = (PyMemberDef*) slot->pfunc; + while (memb && memb->name) { + if (memb->name[0] == '_' && memb->name[1] == '_') { +#if PY_VERSION_HEX < 0x030900b1 + if (strcmp(memb->name, "__weaklistoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_weaklistoffset = memb->offset; + changed = 1; + } + else if (strcmp(memb->name, "__dictoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_dictoffset = memb->offset; + changed = 1; + } +#if CYTHON_METH_FASTCALL + else if (strcmp(memb->name, "__vectorcalloffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); +#if PY_VERSION_HEX >= 0x030800b4 + type->tp_vectorcall_offset = memb->offset; +#else + type->tp_print = (printfunc) memb->offset; +#endif + changed = 1; + } +#endif +#else + if ((0)); +#endif +#if PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON + else if (strcmp(memb->name, "__module__") == 0) { + PyObject *descr; + assert(memb->type == T_OBJECT); + assert(memb->flags == 0 || memb->flags == READONLY); + descr = PyDescr_NewMember(type, memb); + if (unlikely(!descr)) + return -1; + if (unlikely(PyDict_SetItem(type->tp_dict, PyDescr_NAME(descr), descr) < 0)) { + Py_DECREF(descr); + return -1; + } + Py_DECREF(descr); + changed = 1; + } +#endif + } + memb++; + } + if (changed) + PyType_Modified(type); + } +#endif + return 0; +} +#endif + +/* PyObjectCallMethod0 */ + static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name) { + PyObject *method = NULL, *result = NULL; + int is_method = __Pyx_PyObject_GetMethod(obj, method_name, &method); + if (likely(is_method)) { + result = __Pyx_PyObject_CallOneArg(method, obj); + Py_DECREF(method); + return result; + } + if (unlikely(!method)) goto bad; + result = __Pyx_PyObject_CallNoArg(method); + Py_DECREF(method); +bad: + return result; +} + +/* ValidateBasesTuple */ + #if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases) { + Py_ssize_t i, n; +#if CYTHON_ASSUME_SAFE_MACROS + n = PyTuple_GET_SIZE(bases); +#else + n = PyTuple_Size(bases); + if (n < 0) return -1; +#endif + for (i = 1; i < n; i++) + { +#if CYTHON_AVOID_BORROWED_REFS + PyObject *b0 = PySequence_GetItem(bases, i); + if (!b0) return -1; +#elif CYTHON_ASSUME_SAFE_MACROS + PyObject *b0 = PyTuple_GET_ITEM(bases, i); +#else + PyObject *b0 = PyTuple_GetItem(bases, i); + if (!b0) return -1; +#endif + PyTypeObject *b; +#if PY_MAJOR_VERSION < 3 + if (PyClass_Check(b0)) + { + PyErr_Format(PyExc_TypeError, "base class '%.200s' is an old-style class", + PyString_AS_STRING(((PyClassObject*)b0)->cl_name)); +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + return -1; + } +#endif + b = (PyTypeObject*) b0; + if (!__Pyx_PyType_HasFeature(b, Py_TPFLAGS_HEAPTYPE)) + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "base class '" __Pyx_FMT_TYPENAME "' is not a heap type", b_name); + __Pyx_DECREF_TypeName(b_name); +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + return -1; + } + if (dictoffset == 0) + { + Py_ssize_t b_dictoffset = 0; +#if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + b_dictoffset = b->tp_dictoffset; +#else + PyObject *py_b_dictoffset = PyObject_GetAttrString((PyObject*)b, "__dictoffset__"); + if (!py_b_dictoffset) goto dictoffset_return; + b_dictoffset = PyLong_AsSsize_t(py_b_dictoffset); + Py_DECREF(py_b_dictoffset); + if (b_dictoffset == -1 && PyErr_Occurred()) goto dictoffset_return; +#endif + if (b_dictoffset) { + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "extension type '%.200s' has no __dict__ slot, " + "but base type '" __Pyx_FMT_TYPENAME "' has: " + "either add 'cdef dict __dict__' to the extension type " + "or add '__slots__ = [...]' to the base type", + type_name, b_name); + __Pyx_DECREF_TypeName(b_name); + } +#if !(CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY) + dictoffset_return: +#endif +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + return -1; + } + } +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + } + return 0; +} +#endif + +/* PyType_Ready */ + static int __Pyx_PyType_Ready(PyTypeObject *t) { +#if CYTHON_USE_TYPE_SPECS || !(CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API) || defined(PYSTON_MAJOR_VERSION) + (void)__Pyx_PyObject_CallMethod0; +#if CYTHON_USE_TYPE_SPECS + (void)__Pyx_validate_bases_tuple; +#endif + return PyType_Ready(t); +#else + int r; + PyObject *bases = __Pyx_PyType_GetSlot(t, tp_bases, PyObject*); + if (bases && unlikely(__Pyx_validate_bases_tuple(t->tp_name, t->tp_dictoffset, bases) == -1)) + return -1; +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + { + int gc_was_enabled; + #if PY_VERSION_HEX >= 0x030A00b1 + gc_was_enabled = PyGC_Disable(); + (void)__Pyx_PyObject_CallMethod0; + #else + PyObject *ret, *py_status; + PyObject *gc = NULL; + #if PY_VERSION_HEX >= 0x030700a1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM+0 >= 0x07030400) + gc = PyImport_GetModule(__pyx_kp_u_gc); + #endif + if (unlikely(!gc)) gc = PyImport_Import(__pyx_kp_u_gc); + if (unlikely(!gc)) return -1; + py_status = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_isenabled); + if (unlikely(!py_status)) { + Py_DECREF(gc); + return -1; + } + gc_was_enabled = __Pyx_PyObject_IsTrue(py_status); + Py_DECREF(py_status); + if (gc_was_enabled > 0) { + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_disable); + if (unlikely(!ret)) { + Py_DECREF(gc); + return -1; + } + Py_DECREF(ret); + } else if (unlikely(gc_was_enabled == -1)) { + Py_DECREF(gc); + return -1; + } + #endif + t->tp_flags |= Py_TPFLAGS_HEAPTYPE; +#if PY_VERSION_HEX >= 0x030A0000 + t->tp_flags |= Py_TPFLAGS_IMMUTABLETYPE; +#endif +#else + (void)__Pyx_PyObject_CallMethod0; +#endif + r = PyType_Ready(t); +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + t->tp_flags &= ~Py_TPFLAGS_HEAPTYPE; + #if PY_VERSION_HEX >= 0x030A00b1 + if (gc_was_enabled) + PyGC_Enable(); + #else + if (gc_was_enabled) { + PyObject *tp, *v, *tb; + PyErr_Fetch(&tp, &v, &tb); + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_enable); + if (likely(ret || r == -1)) { + Py_XDECREF(ret); + PyErr_Restore(tp, v, tb); + } else { + Py_XDECREF(tp); + Py_XDECREF(v); + Py_XDECREF(tb); + r = -1; + } + } + Py_DECREF(gc); + #endif + } +#endif + return r; +#endif +} + +/* SetupReduce */ + #if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce_is_named(PyObject* meth, PyObject* name) { + int ret; + PyObject *name_attr; + name_attr = __Pyx_PyObject_GetAttrStrNoError(meth, __pyx_n_s_name_2); + if (likely(name_attr)) { + ret = PyObject_RichCompareBool(name_attr, name, Py_EQ); + } else { + ret = -1; + } + if (unlikely(ret < 0)) { + PyErr_Clear(); + ret = 0; + } + Py_XDECREF(name_attr); + return ret; +} +static int __Pyx_setup_reduce(PyObject* type_obj) { + int ret = 0; + PyObject *object_reduce = NULL; + PyObject *object_getstate = NULL; + PyObject *object_reduce_ex = NULL; + PyObject *reduce = NULL; + PyObject *reduce_ex = NULL; + PyObject *reduce_cython = NULL; + PyObject *setstate = NULL; + PyObject *setstate_cython = NULL; + PyObject *getstate = NULL; +#if CYTHON_USE_PYTYPE_LOOKUP + getstate = _PyType_Lookup((PyTypeObject*)type_obj, __pyx_n_s_getstate); +#else + getstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_getstate); + if (!getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (getstate) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_getstate = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_getstate); +#else + object_getstate = __Pyx_PyObject_GetAttrStrNoError((PyObject*)&PyBaseObject_Type, __pyx_n_s_getstate); + if (!object_getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (object_getstate != getstate) { + goto __PYX_GOOD; + } + } +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce_ex = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#else + object_reduce_ex = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#endif + reduce_ex = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce_ex); if (unlikely(!reduce_ex)) goto __PYX_BAD; + if (reduce_ex == object_reduce_ex) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#else + object_reduce = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#endif + reduce = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce); if (unlikely(!reduce)) goto __PYX_BAD; + if (reduce == object_reduce || __Pyx_setup_reduce_is_named(reduce, __pyx_n_s_reduce_cython)) { + reduce_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_reduce_cython); + if (likely(reduce_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce, reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (reduce == object_reduce || PyErr_Occurred()) { + goto __PYX_BAD; + } + setstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate); + if (!setstate) PyErr_Clear(); + if (!setstate || __Pyx_setup_reduce_is_named(setstate, __pyx_n_s_setstate_cython)) { + setstate_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate_cython); + if (likely(setstate_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate, setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (!setstate || PyErr_Occurred()) { + goto __PYX_BAD; + } + } + PyType_Modified((PyTypeObject*)type_obj); + } + } + goto __PYX_GOOD; +__PYX_BAD: + if (!PyErr_Occurred()) { + __Pyx_TypeName type_obj_name = + __Pyx_PyType_GetName((PyTypeObject*)type_obj); + PyErr_Format(PyExc_RuntimeError, + "Unable to initialize pickling for " __Pyx_FMT_TYPENAME, type_obj_name); + __Pyx_DECREF_TypeName(type_obj_name); + } + ret = -1; +__PYX_GOOD: +#if !CYTHON_USE_PYTYPE_LOOKUP + Py_XDECREF(object_reduce); + Py_XDECREF(object_reduce_ex); + Py_XDECREF(object_getstate); + Py_XDECREF(getstate); +#endif + Py_XDECREF(reduce); + Py_XDECREF(reduce_ex); + Py_XDECREF(reduce_cython); + Py_XDECREF(setstate); + Py_XDECREF(setstate_cython); + return ret; +} +#endif + +/* SetVTable */ + static int __Pyx_SetVtable(PyTypeObject *type, void *vtable) { + PyObject *ob = PyCapsule_New(vtable, 0, 0); + if (unlikely(!ob)) + goto bad; +#if CYTHON_COMPILING_IN_LIMITED_API + if (unlikely(PyObject_SetAttr((PyObject *) type, __pyx_n_s_pyx_vtable, ob) < 0)) +#else + if (unlikely(PyDict_SetItem(type->tp_dict, __pyx_n_s_pyx_vtable, ob) < 0)) +#endif + goto bad; + Py_DECREF(ob); + return 0; +bad: + Py_XDECREF(ob); + return -1; +} + +/* GetVTable */ + static void* __Pyx_GetVtable(PyTypeObject *type) { + void* ptr; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *ob = PyObject_GetAttr((PyObject *)type, __pyx_n_s_pyx_vtable); +#else + PyObject *ob = PyObject_GetItem(type->tp_dict, __pyx_n_s_pyx_vtable); +#endif + if (!ob) + goto bad; + ptr = PyCapsule_GetPointer(ob, 0); + if (!ptr && !PyErr_Occurred()) + PyErr_SetString(PyExc_RuntimeError, "invalid vtable found for imported type"); + Py_DECREF(ob); + return ptr; +bad: + Py_XDECREF(ob); + return NULL; +} + +/* MergeVTables */ + #if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_MergeVtables(PyTypeObject *type) { + int i; + void** base_vtables; + __Pyx_TypeName tp_base_name; + __Pyx_TypeName base_name; + void* unknown = (void*)-1; + PyObject* bases = type->tp_bases; + int base_depth = 0; + { + PyTypeObject* base = type->tp_base; + while (base) { + base_depth += 1; + base = base->tp_base; + } + } + base_vtables = (void**) malloc(sizeof(void*) * (size_t)(base_depth + 1)); + base_vtables[0] = unknown; + for (i = 1; i < PyTuple_GET_SIZE(bases); i++) { + void* base_vtable = __Pyx_GetVtable(((PyTypeObject*)PyTuple_GET_ITEM(bases, i))); + if (base_vtable != NULL) { + int j; + PyTypeObject* base = type->tp_base; + for (j = 0; j < base_depth; j++) { + if (base_vtables[j] == unknown) { + base_vtables[j] = __Pyx_GetVtable(base); + base_vtables[j + 1] = unknown; + } + if (base_vtables[j] == base_vtable) { + break; + } else if (base_vtables[j] == NULL) { + goto bad; + } + base = base->tp_base; + } + } + } + PyErr_Clear(); + free(base_vtables); + return 0; +bad: + tp_base_name = __Pyx_PyType_GetName(type->tp_base); + base_name = __Pyx_PyType_GetName((PyTypeObject*)PyTuple_GET_ITEM(bases, i)); + PyErr_Format(PyExc_TypeError, + "multiple bases have vtable conflict: '" __Pyx_FMT_TYPENAME "' and '" __Pyx_FMT_TYPENAME "'", tp_base_name, base_name); + __Pyx_DECREF_TypeName(tp_base_name); + __Pyx_DECREF_TypeName(base_name); + free(base_vtables); + return -1; +} +#endif + +/* TypeImport */ + #ifndef __PYX_HAVE_RT_ImportType_3_0_8 +#define __PYX_HAVE_RT_ImportType_3_0_8 +static PyTypeObject *__Pyx_ImportType_3_0_8(PyObject *module, const char *module_name, const char *class_name, + size_t size, size_t alignment, enum __Pyx_ImportType_CheckSize_3_0_8 check_size) +{ + PyObject *result = 0; + char warning[200]; + Py_ssize_t basicsize; + Py_ssize_t itemsize; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *py_basicsize; + PyObject *py_itemsize; +#endif + result = PyObject_GetAttrString(module, class_name); + if (!result) + goto bad; + if (!PyType_Check(result)) { + PyErr_Format(PyExc_TypeError, + "%.200s.%.200s is not a type object", + module_name, class_name); + goto bad; + } +#if !CYTHON_COMPILING_IN_LIMITED_API + basicsize = ((PyTypeObject *)result)->tp_basicsize; + itemsize = ((PyTypeObject *)result)->tp_itemsize; +#else + py_basicsize = PyObject_GetAttrString(result, "__basicsize__"); + if (!py_basicsize) + goto bad; + basicsize = PyLong_AsSsize_t(py_basicsize); + Py_DECREF(py_basicsize); + py_basicsize = 0; + if (basicsize == (Py_ssize_t)-1 && PyErr_Occurred()) + goto bad; + py_itemsize = PyObject_GetAttrString(result, "__itemsize__"); + if (!py_itemsize) + goto bad; + itemsize = PyLong_AsSsize_t(py_itemsize); + Py_DECREF(py_itemsize); + py_itemsize = 0; + if (itemsize == (Py_ssize_t)-1 && PyErr_Occurred()) + goto bad; +#endif + if (itemsize) { + if (size % alignment) { + alignment = size % alignment; + } + if (itemsize < (Py_ssize_t)alignment) + itemsize = (Py_ssize_t)alignment; + } + if ((size_t)(basicsize + itemsize) < size) { + PyErr_Format(PyExc_ValueError, + "%.200s.%.200s size changed, may indicate binary incompatibility. " + "Expected %zd from C header, got %zd from PyObject", + module_name, class_name, size, basicsize+itemsize); + goto bad; + } + if (check_size == __Pyx_ImportType_CheckSize_Error_3_0_8 && + ((size_t)basicsize > size || (size_t)(basicsize + itemsize) < size)) { + PyErr_Format(PyExc_ValueError, + "%.200s.%.200s size changed, may indicate binary incompatibility. " + "Expected %zd from C header, got %zd-%zd from PyObject", + module_name, class_name, size, basicsize, basicsize+itemsize); + goto bad; + } + else if (check_size == __Pyx_ImportType_CheckSize_Warn_3_0_8 && (size_t)basicsize > size) { + PyOS_snprintf(warning, sizeof(warning), + "%s.%s size changed, may indicate binary incompatibility. " + "Expected %zd from C header, got %zd from PyObject", + module_name, class_name, size, basicsize); + if (PyErr_WarnEx(NULL, warning, 0) < 0) goto bad; + } + return (PyTypeObject *)result; +bad: + Py_XDECREF(result); + return NULL; +} +#endif + +/* FetchSharedCythonModule */ + static PyObject *__Pyx_FetchSharedCythonABIModule(void) { + return __Pyx_PyImport_AddModuleRef((char*) __PYX_ABI_MODULE_NAME); +} + +/* FetchCommonType */ + static int __Pyx_VerifyCachedType(PyObject *cached_type, + const char *name, + Py_ssize_t basicsize, + Py_ssize_t expected_basicsize) { + if (!PyType_Check(cached_type)) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s is not a type object", name); + return -1; + } + if (basicsize != expected_basicsize) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s has the wrong size, try recompiling", + name); + return -1; + } + return 0; +} +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type) { + PyObject* abi_module; + const char* object_name; + PyTypeObject *cached_type = NULL; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + object_name = strrchr(type->tp_name, '.'); + object_name = object_name ? object_name+1 : type->tp_name; + cached_type = (PyTypeObject*) PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + if (__Pyx_VerifyCachedType( + (PyObject *)cached_type, + object_name, + cached_type->tp_basicsize, + type->tp_basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + if (PyType_Ready(type) < 0) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, (PyObject *)type) < 0) + goto bad; + Py_INCREF(type); + cached_type = type; +done: + Py_DECREF(abi_module); + return cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#else +static PyTypeObject *__Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases) { + PyObject *abi_module, *cached_type = NULL; + const char* object_name = strrchr(spec->name, '.'); + object_name = object_name ? object_name+1 : spec->name; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + cached_type = PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + Py_ssize_t basicsize; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *py_basicsize; + py_basicsize = PyObject_GetAttrString(cached_type, "__basicsize__"); + if (unlikely(!py_basicsize)) goto bad; + basicsize = PyLong_AsSsize_t(py_basicsize); + Py_DECREF(py_basicsize); + py_basicsize = 0; + if (unlikely(basicsize == (Py_ssize_t)-1) && PyErr_Occurred()) goto bad; +#else + basicsize = likely(PyType_Check(cached_type)) ? ((PyTypeObject*) cached_type)->tp_basicsize : -1; +#endif + if (__Pyx_VerifyCachedType( + cached_type, + object_name, + basicsize, + spec->basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + CYTHON_UNUSED_VAR(module); + cached_type = __Pyx_PyType_FromModuleAndSpec(abi_module, spec, bases); + if (unlikely(!cached_type)) goto bad; + if (unlikely(__Pyx_fix_up_extension_type_from_spec(spec, (PyTypeObject *) cached_type) < 0)) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, cached_type) < 0) goto bad; +done: + Py_DECREF(abi_module); + assert(cached_type == NULL || PyType_Check(cached_type)); + return (PyTypeObject *) cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#endif + +/* PyVectorcallFastCallDict */ + #if CYTHON_METH_FASTCALL +static PyObject *__Pyx_PyVectorcall_FastCallDict_kw(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + PyObject *res = NULL; + PyObject *kwnames; + PyObject **newargs; + PyObject **kwvalues; + Py_ssize_t i, pos; + size_t j; + PyObject *key, *value; + unsigned long keys_are_strings; + Py_ssize_t nkw = PyDict_GET_SIZE(kw); + newargs = (PyObject **)PyMem_Malloc((nargs + (size_t)nkw) * sizeof(args[0])); + if (unlikely(newargs == NULL)) { + PyErr_NoMemory(); + return NULL; + } + for (j = 0; j < nargs; j++) newargs[j] = args[j]; + kwnames = PyTuple_New(nkw); + if (unlikely(kwnames == NULL)) { + PyMem_Free(newargs); + return NULL; + } + kwvalues = newargs + nargs; + pos = i = 0; + keys_are_strings = Py_TPFLAGS_UNICODE_SUBCLASS; + while (PyDict_Next(kw, &pos, &key, &value)) { + keys_are_strings &= Py_TYPE(key)->tp_flags; + Py_INCREF(key); + Py_INCREF(value); + PyTuple_SET_ITEM(kwnames, i, key); + kwvalues[i] = value; + i++; + } + if (unlikely(!keys_are_strings)) { + PyErr_SetString(PyExc_TypeError, "keywords must be strings"); + goto cleanup; + } + res = vc(func, newargs, nargs, kwnames); +cleanup: + Py_DECREF(kwnames); + for (i = 0; i < nkw; i++) + Py_DECREF(kwvalues[i]); + PyMem_Free(newargs); + return res; +} +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + if (likely(kw == NULL) || PyDict_GET_SIZE(kw) == 0) { + return vc(func, args, nargs, NULL); + } + return __Pyx_PyVectorcall_FastCallDict_kw(func, vc, args, nargs, kw); +} +#endif + +/* CythonFunctionShared */ + #if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc) { + if (__Pyx_CyFunction_Check(func)) { + return PyCFunction_GetFunction(((__pyx_CyFunctionObject*)func)->func) == (PyCFunction) cfunc; + } else if (PyCFunction_Check(func)) { + return PyCFunction_GetFunction(func) == (PyCFunction) cfunc; + } + return 0; +} +#else +static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc) { + return __Pyx_CyOrPyCFunction_Check(func) && __Pyx_CyOrPyCFunction_GET_FUNCTION(func) == (PyCFunction) cfunc; +} +#endif +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj) { +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + __Pyx_Py_XDECREF_SET( + __Pyx_CyFunction_GetClassObj(f), + ((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#else + __Pyx_Py_XDECREF_SET( + ((PyCMethodObject *) (f))->mm_class, + (PyTypeObject*)((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#endif +} +static PyObject * +__Pyx_CyFunction_get_doc(__pyx_CyFunctionObject *op, void *closure) +{ + CYTHON_UNUSED_VAR(closure); + if (unlikely(op->func_doc == NULL)) { +#if CYTHON_COMPILING_IN_LIMITED_API + op->func_doc = PyObject_GetAttrString(op->func, "__doc__"); + if (unlikely(!op->func_doc)) return NULL; +#else + if (((PyCFunctionObject*)op)->m_ml->ml_doc) { +#if PY_MAJOR_VERSION >= 3 + op->func_doc = PyUnicode_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#else + op->func_doc = PyString_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#endif + if (unlikely(op->func_doc == NULL)) + return NULL; + } else { + Py_INCREF(Py_None); + return Py_None; + } +#endif + } + Py_INCREF(op->func_doc); + return op->func_doc; +} +static int +__Pyx_CyFunction_set_doc(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (value == NULL) { + value = Py_None; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_doc, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_name(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_name == NULL)) { +#if CYTHON_COMPILING_IN_LIMITED_API + op->func_name = PyObject_GetAttrString(op->func, "__name__"); +#elif PY_MAJOR_VERSION >= 3 + op->func_name = PyUnicode_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#else + op->func_name = PyString_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#endif + if (unlikely(op->func_name == NULL)) + return NULL; + } + Py_INCREF(op->func_name); + return op->func_name; +} +static int +__Pyx_CyFunction_set_name(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__name__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_name, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_qualname(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_qualname); + return op->func_qualname; +} +static int +__Pyx_CyFunction_set_qualname(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__qualname__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_qualname, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_dict(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_dict == NULL)) { + op->func_dict = PyDict_New(); + if (unlikely(op->func_dict == NULL)) + return NULL; + } + Py_INCREF(op->func_dict); + return op->func_dict; +} +static int +__Pyx_CyFunction_set_dict(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(value == NULL)) { + PyErr_SetString(PyExc_TypeError, + "function's dictionary may not be deleted"); + return -1; + } + if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "setting function's dictionary to a non-dict"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_dict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_globals(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_globals); + return op->func_globals; +} +static PyObject * +__Pyx_CyFunction_get_closure(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(op); + CYTHON_UNUSED_VAR(context); + Py_INCREF(Py_None); + return Py_None; +} +static PyObject * +__Pyx_CyFunction_get_code(__pyx_CyFunctionObject *op, void *context) +{ + PyObject* result = (op->func_code) ? op->func_code : Py_None; + CYTHON_UNUSED_VAR(context); + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_init_defaults(__pyx_CyFunctionObject *op) { + int result = 0; + PyObject *res = op->defaults_getter((PyObject *) op); + if (unlikely(!res)) + return -1; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + op->defaults_tuple = PyTuple_GET_ITEM(res, 0); + Py_INCREF(op->defaults_tuple); + op->defaults_kwdict = PyTuple_GET_ITEM(res, 1); + Py_INCREF(op->defaults_kwdict); + #else + op->defaults_tuple = __Pyx_PySequence_ITEM(res, 0); + if (unlikely(!op->defaults_tuple)) result = -1; + else { + op->defaults_kwdict = __Pyx_PySequence_ITEM(res, 1); + if (unlikely(!op->defaults_kwdict)) result = -1; + } + #endif + Py_DECREF(res); + return result; +} +static int +__Pyx_CyFunction_set_defaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyTuple_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__defaults__ must be set to a tuple object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__defaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_tuple, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_defaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_tuple; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_tuple; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_kwdefaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__kwdefaults__ must be set to a dict object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__kwdefaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_kwdict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_kwdefaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_kwdict; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_kwdict; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_annotations(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value || value == Py_None) { + value = NULL; + } else if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__annotations__ must be set to a dict object"); + return -1; + } + Py_XINCREF(value); + __Pyx_Py_XDECREF_SET(op->func_annotations, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_annotations(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->func_annotations; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + result = PyDict_New(); + if (unlikely(!result)) return NULL; + op->func_annotations = result; + } + Py_INCREF(result); + return result; +} +static PyObject * +__Pyx_CyFunction_get_is_coroutine(__pyx_CyFunctionObject *op, void *context) { + int is_coroutine; + CYTHON_UNUSED_VAR(context); + if (op->func_is_coroutine) { + return __Pyx_NewRef(op->func_is_coroutine); + } + is_coroutine = op->flags & __Pyx_CYFUNCTION_COROUTINE; +#if PY_VERSION_HEX >= 0x03050000 + if (is_coroutine) { + PyObject *module, *fromlist, *marker = __pyx_n_s_is_coroutine; + fromlist = PyList_New(1); + if (unlikely(!fromlist)) return NULL; + Py_INCREF(marker); +#if CYTHON_ASSUME_SAFE_MACROS + PyList_SET_ITEM(fromlist, 0, marker); +#else + if (unlikely(PyList_SetItem(fromlist, 0, marker) < 0)) { + Py_DECREF(marker); + Py_DECREF(fromlist); + return NULL; + } +#endif + module = PyImport_ImportModuleLevelObject(__pyx_n_s_asyncio_coroutines, NULL, NULL, fromlist, 0); + Py_DECREF(fromlist); + if (unlikely(!module)) goto ignore; + op->func_is_coroutine = __Pyx_PyObject_GetAttrStr(module, marker); + Py_DECREF(module); + if (likely(op->func_is_coroutine)) { + return __Pyx_NewRef(op->func_is_coroutine); + } +ignore: + PyErr_Clear(); + } +#endif + op->func_is_coroutine = __Pyx_PyBool_FromLong(is_coroutine); + return __Pyx_NewRef(op->func_is_coroutine); +} +#if CYTHON_COMPILING_IN_LIMITED_API +static PyObject * +__Pyx_CyFunction_get_module(__pyx_CyFunctionObject *op, void *context) { + CYTHON_UNUSED_VAR(context); + return PyObject_GetAttrString(op->func, "__module__"); +} +static int +__Pyx_CyFunction_set_module(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + return PyObject_SetAttrString(op->func, "__module__", value); +} +#endif +static PyGetSetDef __pyx_CyFunction_getsets[] = { + {(char *) "func_doc", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "__doc__", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "func_name", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__name__", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__qualname__", (getter)__Pyx_CyFunction_get_qualname, (setter)__Pyx_CyFunction_set_qualname, 0, 0}, + {(char *) "func_dict", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "__dict__", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "func_globals", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "__globals__", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "func_closure", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "__closure__", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "func_code", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "__code__", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "func_defaults", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__defaults__", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__kwdefaults__", (getter)__Pyx_CyFunction_get_kwdefaults, (setter)__Pyx_CyFunction_set_kwdefaults, 0, 0}, + {(char *) "__annotations__", (getter)__Pyx_CyFunction_get_annotations, (setter)__Pyx_CyFunction_set_annotations, 0, 0}, + {(char *) "_is_coroutine", (getter)__Pyx_CyFunction_get_is_coroutine, 0, 0, 0}, +#if CYTHON_COMPILING_IN_LIMITED_API + {"__module__", (getter)__Pyx_CyFunction_get_module, (setter)__Pyx_CyFunction_set_module, 0, 0}, +#endif + {0, 0, 0, 0, 0} +}; +static PyMemberDef __pyx_CyFunction_members[] = { +#if !CYTHON_COMPILING_IN_LIMITED_API + {(char *) "__module__", T_OBJECT, offsetof(PyCFunctionObject, m_module), 0, 0}, +#endif +#if CYTHON_USE_TYPE_SPECS + {(char *) "__dictoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_dict), READONLY, 0}, +#if CYTHON_METH_FASTCALL +#if CYTHON_BACKPORT_VECTORCALL + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_vectorcall), READONLY, 0}, +#else +#if !CYTHON_COMPILING_IN_LIMITED_API + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(PyCFunctionObject, vectorcall), READONLY, 0}, +#endif +#endif +#endif +#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_weakreflist), READONLY, 0}, +#else + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(PyCFunctionObject, m_weakreflist), READONLY, 0}, +#endif +#endif + {0, 0, 0, 0, 0} +}; +static PyObject * +__Pyx_CyFunction_reduce(__pyx_CyFunctionObject *m, PyObject *args) +{ + CYTHON_UNUSED_VAR(args); +#if PY_MAJOR_VERSION >= 3 + Py_INCREF(m->func_qualname); + return m->func_qualname; +#else + return PyString_FromString(((PyCFunctionObject*)m)->m_ml->ml_name); +#endif +} +static PyMethodDef __pyx_CyFunction_methods[] = { + {"__reduce__", (PyCFunction)__Pyx_CyFunction_reduce, METH_VARARGS, 0}, + {0, 0, 0, 0} +}; +#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API +#define __Pyx_CyFunction_weakreflist(cyfunc) ((cyfunc)->func_weakreflist) +#else +#define __Pyx_CyFunction_weakreflist(cyfunc) (((PyCFunctionObject*)cyfunc)->m_weakreflist) +#endif +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject *op, PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { +#if !CYTHON_COMPILING_IN_LIMITED_API + PyCFunctionObject *cf = (PyCFunctionObject*) op; +#endif + if (unlikely(op == NULL)) + return NULL; +#if CYTHON_COMPILING_IN_LIMITED_API + op->func = PyCFunction_NewEx(ml, (PyObject*)op, module); + if (unlikely(!op->func)) return NULL; +#endif + op->flags = flags; + __Pyx_CyFunction_weakreflist(op) = NULL; +#if !CYTHON_COMPILING_IN_LIMITED_API + cf->m_ml = ml; + cf->m_self = (PyObject *) op; +#endif + Py_XINCREF(closure); + op->func_closure = closure; +#if !CYTHON_COMPILING_IN_LIMITED_API + Py_XINCREF(module); + cf->m_module = module; +#endif + op->func_dict = NULL; + op->func_name = NULL; + Py_INCREF(qualname); + op->func_qualname = qualname; + op->func_doc = NULL; +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + op->func_classobj = NULL; +#else + ((PyCMethodObject*)op)->mm_class = NULL; +#endif + op->func_globals = globals; + Py_INCREF(op->func_globals); + Py_XINCREF(code); + op->func_code = code; + op->defaults_pyobjects = 0; + op->defaults_size = 0; + op->defaults = NULL; + op->defaults_tuple = NULL; + op->defaults_kwdict = NULL; + op->defaults_getter = NULL; + op->func_annotations = NULL; + op->func_is_coroutine = NULL; +#if CYTHON_METH_FASTCALL + switch (ml->ml_flags & (METH_VARARGS | METH_FASTCALL | METH_NOARGS | METH_O | METH_KEYWORDS | METH_METHOD)) { + case METH_NOARGS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_NOARGS; + break; + case METH_O: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_O; + break; + case METH_METHOD | METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD; + break; + case METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS; + break; + case METH_VARARGS | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = NULL; + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + Py_DECREF(op); + return NULL; + } +#endif + return (PyObject *) op; +} +static int +__Pyx_CyFunction_clear(__pyx_CyFunctionObject *m) +{ + Py_CLEAR(m->func_closure); +#if CYTHON_COMPILING_IN_LIMITED_API + Py_CLEAR(m->func); +#else + Py_CLEAR(((PyCFunctionObject*)m)->m_module); +#endif + Py_CLEAR(m->func_dict); + Py_CLEAR(m->func_name); + Py_CLEAR(m->func_qualname); + Py_CLEAR(m->func_doc); + Py_CLEAR(m->func_globals); + Py_CLEAR(m->func_code); +#if !CYTHON_COMPILING_IN_LIMITED_API +#if PY_VERSION_HEX < 0x030900B1 + Py_CLEAR(__Pyx_CyFunction_GetClassObj(m)); +#else + { + PyObject *cls = (PyObject*) ((PyCMethodObject *) (m))->mm_class; + ((PyCMethodObject *) (m))->mm_class = NULL; + Py_XDECREF(cls); + } +#endif +#endif + Py_CLEAR(m->defaults_tuple); + Py_CLEAR(m->defaults_kwdict); + Py_CLEAR(m->func_annotations); + Py_CLEAR(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_XDECREF(pydefaults[i]); + PyObject_Free(m->defaults); + m->defaults = NULL; + } + return 0; +} +static void __Pyx__CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + if (__Pyx_CyFunction_weakreflist(m) != NULL) + PyObject_ClearWeakRefs((PyObject *) m); + __Pyx_CyFunction_clear(m); + __Pyx_PyHeapTypeObject_GC_Del(m); +} +static void __Pyx_CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + PyObject_GC_UnTrack(m); + __Pyx__CyFunction_dealloc(m); +} +static int __Pyx_CyFunction_traverse(__pyx_CyFunctionObject *m, visitproc visit, void *arg) +{ + Py_VISIT(m->func_closure); +#if CYTHON_COMPILING_IN_LIMITED_API + Py_VISIT(m->func); +#else + Py_VISIT(((PyCFunctionObject*)m)->m_module); +#endif + Py_VISIT(m->func_dict); + Py_VISIT(m->func_name); + Py_VISIT(m->func_qualname); + Py_VISIT(m->func_doc); + Py_VISIT(m->func_globals); + Py_VISIT(m->func_code); +#if !CYTHON_COMPILING_IN_LIMITED_API + Py_VISIT(__Pyx_CyFunction_GetClassObj(m)); +#endif + Py_VISIT(m->defaults_tuple); + Py_VISIT(m->defaults_kwdict); + Py_VISIT(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_VISIT(pydefaults[i]); + } + return 0; +} +static PyObject* +__Pyx_CyFunction_repr(__pyx_CyFunctionObject *op) +{ +#if PY_MAJOR_VERSION >= 3 + return PyUnicode_FromFormat("", + op->func_qualname, (void *)op); +#else + return PyString_FromFormat("", + PyString_AsString(op->func_qualname), (void *)op); +#endif +} +static PyObject * __Pyx_CyFunction_CallMethod(PyObject *func, PyObject *self, PyObject *arg, PyObject *kw) { +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *f = ((__pyx_CyFunctionObject*)func)->func; + PyObject *py_name = NULL; + PyCFunction meth; + int flags; + meth = PyCFunction_GetFunction(f); + if (unlikely(!meth)) return NULL; + flags = PyCFunction_GetFlags(f); + if (unlikely(flags < 0)) return NULL; +#else + PyCFunctionObject* f = (PyCFunctionObject*)func; + PyCFunction meth = f->m_ml->ml_meth; + int flags = f->m_ml->ml_flags; +#endif + Py_ssize_t size; + switch (flags & (METH_VARARGS | METH_KEYWORDS | METH_NOARGS | METH_O)) { + case METH_VARARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) + return (*meth)(self, arg); + break; + case METH_VARARGS | METH_KEYWORDS: + return (*(PyCFunctionWithKeywords)(void*)meth)(self, arg, kw); + case METH_NOARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { +#if CYTHON_ASSUME_SAFE_MACROS + size = PyTuple_GET_SIZE(arg); +#else + size = PyTuple_Size(arg); + if (unlikely(size < 0)) return NULL; +#endif + if (likely(size == 0)) + return (*meth)(self, NULL); +#if CYTHON_COMPILING_IN_LIMITED_API + py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); + if (!py_name) return NULL; + PyErr_Format(PyExc_TypeError, + "%.200S() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + py_name, size); + Py_DECREF(py_name); +#else + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); +#endif + return NULL; + } + break; + case METH_O: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { +#if CYTHON_ASSUME_SAFE_MACROS + size = PyTuple_GET_SIZE(arg); +#else + size = PyTuple_Size(arg); + if (unlikely(size < 0)) return NULL; +#endif + if (likely(size == 1)) { + PyObject *result, *arg0; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + arg0 = PyTuple_GET_ITEM(arg, 0); + #else + arg0 = __Pyx_PySequence_ITEM(arg, 0); if (unlikely(!arg0)) return NULL; + #endif + result = (*meth)(self, arg0); + #if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(arg0); + #endif + return result; + } +#if CYTHON_COMPILING_IN_LIMITED_API + py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); + if (!py_name) return NULL; + PyErr_Format(PyExc_TypeError, + "%.200S() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + py_name, size); + Py_DECREF(py_name); +#else + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); +#endif + return NULL; + } + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + return NULL; + } +#if CYTHON_COMPILING_IN_LIMITED_API + py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); + if (!py_name) return NULL; + PyErr_Format(PyExc_TypeError, "%.200S() takes no keyword arguments", + py_name); + Py_DECREF(py_name); +#else + PyErr_Format(PyExc_TypeError, "%.200s() takes no keyword arguments", + f->m_ml->ml_name); +#endif + return NULL; +} +static CYTHON_INLINE PyObject *__Pyx_CyFunction_Call(PyObject *func, PyObject *arg, PyObject *kw) { + PyObject *self, *result; +#if CYTHON_COMPILING_IN_LIMITED_API + self = PyCFunction_GetSelf(((__pyx_CyFunctionObject*)func)->func); + if (unlikely(!self) && PyErr_Occurred()) return NULL; +#else + self = ((PyCFunctionObject*)func)->m_self; +#endif + result = __Pyx_CyFunction_CallMethod(func, self, arg, kw); + return result; +} +static PyObject *__Pyx_CyFunction_CallAsMethod(PyObject *func, PyObject *args, PyObject *kw) { + PyObject *result; + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *) func; +#if CYTHON_METH_FASTCALL + __pyx_vectorcallfunc vc = __Pyx_CyFunction_func_vectorcall(cyfunc); + if (vc) { +#if CYTHON_ASSUME_SAFE_MACROS + return __Pyx_PyVectorcall_FastCallDict(func, vc, &PyTuple_GET_ITEM(args, 0), (size_t)PyTuple_GET_SIZE(args), kw); +#else + (void) &__Pyx_PyVectorcall_FastCallDict; + return PyVectorcall_Call(func, args, kw); +#endif + } +#endif + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + Py_ssize_t argc; + PyObject *new_args; + PyObject *self; +#if CYTHON_ASSUME_SAFE_MACROS + argc = PyTuple_GET_SIZE(args); +#else + argc = PyTuple_Size(args); + if (unlikely(!argc) < 0) return NULL; +#endif + new_args = PyTuple_GetSlice(args, 1, argc); + if (unlikely(!new_args)) + return NULL; + self = PyTuple_GetItem(args, 0); + if (unlikely(!self)) { + Py_DECREF(new_args); +#if PY_MAJOR_VERSION > 2 + PyErr_Format(PyExc_TypeError, + "unbound method %.200S() needs an argument", + cyfunc->func_qualname); +#else + PyErr_SetString(PyExc_TypeError, + "unbound method needs an argument"); +#endif + return NULL; + } + result = __Pyx_CyFunction_CallMethod(func, self, new_args, kw); + Py_DECREF(new_args); + } else { + result = __Pyx_CyFunction_Call(func, args, kw); + } + return result; +} +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE int __Pyx_CyFunction_Vectorcall_CheckArgs(__pyx_CyFunctionObject *cyfunc, Py_ssize_t nargs, PyObject *kwnames) +{ + int ret = 0; + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + if (unlikely(nargs < 1)) { + PyErr_Format(PyExc_TypeError, "%.200s() needs an argument", + ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + ret = 1; + } + if (unlikely(kwnames) && unlikely(PyTuple_GET_SIZE(kwnames))) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no keyword arguments", ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + return ret; +} +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 0)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, NULL); +} +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 1)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, args[0]); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((_PyCFunctionFastWithKeywords)(void(*)(void))def->ml_meth)(self, args, nargs, kwnames); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; + PyTypeObject *cls = (PyTypeObject *) __Pyx_CyFunction_GetClassObj(cyfunc); +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((__Pyx_PyCMethod)(void(*)(void))def->ml_meth)(self, cls, args, (size_t)nargs, kwnames); +} +#endif +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_CyFunctionType_slots[] = { + {Py_tp_dealloc, (void *)__Pyx_CyFunction_dealloc}, + {Py_tp_repr, (void *)__Pyx_CyFunction_repr}, + {Py_tp_call, (void *)__Pyx_CyFunction_CallAsMethod}, + {Py_tp_traverse, (void *)__Pyx_CyFunction_traverse}, + {Py_tp_clear, (void *)__Pyx_CyFunction_clear}, + {Py_tp_methods, (void *)__pyx_CyFunction_methods}, + {Py_tp_members, (void *)__pyx_CyFunction_members}, + {Py_tp_getset, (void *)__pyx_CyFunction_getsets}, + {Py_tp_descr_get, (void *)__Pyx_PyMethod_New}, + {0, 0}, +}; +static PyType_Spec __pyx_CyFunctionType_spec = { + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#if (defined(_Py_TPFLAGS_HAVE_VECTORCALL) && CYTHON_METH_FASTCALL) + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + __pyx_CyFunctionType_slots +}; +#else +static PyTypeObject __pyx_CyFunctionType_type = { + PyVarObject_HEAD_INIT(0, 0) + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, + (destructor) __Pyx_CyFunction_dealloc, +#if !CYTHON_METH_FASTCALL + 0, +#elif CYTHON_BACKPORT_VECTORCALL + (printfunc)offsetof(__pyx_CyFunctionObject, func_vectorcall), +#else + offsetof(PyCFunctionObject, vectorcall), +#endif + 0, + 0, +#if PY_MAJOR_VERSION < 3 + 0, +#else + 0, +#endif + (reprfunc) __Pyx_CyFunction_repr, + 0, + 0, + 0, + 0, + __Pyx_CyFunction_CallAsMethod, + 0, + 0, + 0, + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#if defined(_Py_TPFLAGS_HAVE_VECTORCALL) && CYTHON_METH_FASTCALL + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + 0, + (traverseproc) __Pyx_CyFunction_traverse, + (inquiry) __Pyx_CyFunction_clear, + 0, +#if PY_VERSION_HEX < 0x030500A0 + offsetof(__pyx_CyFunctionObject, func_weakreflist), +#else + offsetof(PyCFunctionObject, m_weakreflist), +#endif + 0, + 0, + __pyx_CyFunction_methods, + __pyx_CyFunction_members, + __pyx_CyFunction_getsets, + 0, + 0, + __Pyx_PyMethod_New, + 0, + offsetof(__pyx_CyFunctionObject, func_dict), + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, +#if PY_VERSION_HEX >= 0x030400a1 + 0, +#endif +#if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, +#endif +#if __PYX_NEED_TP_PRINT_SLOT + 0, +#endif +#if PY_VERSION_HEX >= 0x030C0000 + 0, +#endif +#if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, +#endif +}; +#endif +static int __pyx_CyFunction_init(PyObject *module) { +#if CYTHON_USE_TYPE_SPECS + __pyx_CyFunctionType = __Pyx_FetchCommonTypeFromSpec(module, &__pyx_CyFunctionType_spec, NULL); +#else + CYTHON_UNUSED_VAR(module); + __pyx_CyFunctionType = __Pyx_FetchCommonType(&__pyx_CyFunctionType_type); +#endif + if (unlikely(__pyx_CyFunctionType == NULL)) { + return -1; + } + return 0; +} +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *func, size_t size, int pyobjects) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults = PyObject_Malloc(size); + if (unlikely(!m->defaults)) + return PyErr_NoMemory(); + memset(m->defaults, 0, size); + m->defaults_pyobjects = pyobjects; + m->defaults_size = size; + return m->defaults; +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *func, PyObject *tuple) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_tuple = tuple; + Py_INCREF(tuple); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_kwdict = dict; + Py_INCREF(dict); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->func_annotations = dict; + Py_INCREF(dict); +} + +/* CythonFunction */ + static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { + PyObject *op = __Pyx_CyFunction_Init( + PyObject_GC_New(__pyx_CyFunctionObject, __pyx_CyFunctionType), + ml, flags, qualname, closure, module, globals, code + ); + if (likely(op)) { + PyObject_GC_Track(op); + } + return op; +} + +/* CLineInTraceback */ + #ifndef CYTHON_CLINE_IN_TRACEBACK +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line) { + PyObject *use_cline; + PyObject *ptype, *pvalue, *ptraceback; +#if CYTHON_COMPILING_IN_CPYTHON + PyObject **cython_runtime_dict; +#endif + CYTHON_MAYBE_UNUSED_VAR(tstate); + if (unlikely(!__pyx_cython_runtime)) { + return c_line; + } + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); +#if CYTHON_COMPILING_IN_CPYTHON + cython_runtime_dict = _PyObject_GetDictPtr(__pyx_cython_runtime); + if (likely(cython_runtime_dict)) { + __PYX_PY_DICT_LOOKUP_IF_MODIFIED( + use_cline, *cython_runtime_dict, + __Pyx_PyDict_GetItemStr(*cython_runtime_dict, __pyx_n_s_cline_in_traceback)) + } else +#endif + { + PyObject *use_cline_obj = __Pyx_PyObject_GetAttrStrNoError(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback); + if (use_cline_obj) { + use_cline = PyObject_Not(use_cline_obj) ? Py_False : Py_True; + Py_DECREF(use_cline_obj); + } else { + PyErr_Clear(); + use_cline = NULL; + } + } + if (!use_cline) { + c_line = 0; + (void) PyObject_SetAttr(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback, Py_False); + } + else if (use_cline == Py_False || (use_cline != Py_True && PyObject_Not(use_cline) != 0)) { + c_line = 0; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + return c_line; +} +#endif + +/* CodeObjectCache */ + #if !CYTHON_COMPILING_IN_LIMITED_API +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line) { + int start = 0, mid = 0, end = count - 1; + if (end >= 0 && code_line > entries[end].code_line) { + return count; + } + while (start < end) { + mid = start + (end - start) / 2; + if (code_line < entries[mid].code_line) { + end = mid; + } else if (code_line > entries[mid].code_line) { + start = mid + 1; + } else { + return mid; + } + } + if (code_line <= entries[mid].code_line) { + return mid; + } else { + return mid + 1; + } +} +static PyCodeObject *__pyx_find_code_object(int code_line) { + PyCodeObject* code_object; + int pos; + if (unlikely(!code_line) || unlikely(!__pyx_code_cache.entries)) { + return NULL; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if (unlikely(pos >= __pyx_code_cache.count) || unlikely(__pyx_code_cache.entries[pos].code_line != code_line)) { + return NULL; + } + code_object = __pyx_code_cache.entries[pos].code_object; + Py_INCREF(code_object); + return code_object; +} +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object) { + int pos, i; + __Pyx_CodeObjectCacheEntry* entries = __pyx_code_cache.entries; + if (unlikely(!code_line)) { + return; + } + if (unlikely(!entries)) { + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Malloc(64*sizeof(__Pyx_CodeObjectCacheEntry)); + if (likely(entries)) { + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = 64; + __pyx_code_cache.count = 1; + entries[0].code_line = code_line; + entries[0].code_object = code_object; + Py_INCREF(code_object); + } + return; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if ((pos < __pyx_code_cache.count) && unlikely(__pyx_code_cache.entries[pos].code_line == code_line)) { + PyCodeObject* tmp = entries[pos].code_object; + entries[pos].code_object = code_object; + Py_DECREF(tmp); + return; + } + if (__pyx_code_cache.count == __pyx_code_cache.max_count) { + int new_max = __pyx_code_cache.max_count + 64; + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Realloc( + __pyx_code_cache.entries, ((size_t)new_max) * sizeof(__Pyx_CodeObjectCacheEntry)); + if (unlikely(!entries)) { + return; + } + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = new_max; + } + for (i=__pyx_code_cache.count; i>pos; i--) { + entries[i] = entries[i-1]; + } + entries[pos].code_line = code_line; + entries[pos].code_object = code_object; + __pyx_code_cache.count++; + Py_INCREF(code_object); +} +#endif + +/* AddTraceback */ + #include "compile.h" +#include "frameobject.h" +#include "traceback.h" +#if PY_VERSION_HEX >= 0x030b00a6 && !CYTHON_COMPILING_IN_LIMITED_API + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static PyObject *__Pyx_PyCode_Replace_For_AddTraceback(PyObject *code, PyObject *scratch_dict, + PyObject *firstlineno, PyObject *name) { + PyObject *replace = NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "co_firstlineno", firstlineno))) return NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "co_name", name))) return NULL; + replace = PyObject_GetAttrString(code, "replace"); + if (likely(replace)) { + PyObject *result; + result = PyObject_Call(replace, __pyx_empty_tuple, scratch_dict); + Py_DECREF(replace); + return result; + } + PyErr_Clear(); + #if __PYX_LIMITED_VERSION_HEX < 0x030780000 + { + PyObject *compiled = NULL, *result = NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "code", code))) return NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "type", (PyObject*)(&PyType_Type)))) return NULL; + compiled = Py_CompileString( + "out = type(code)(\n" + " code.co_argcount, code.co_kwonlyargcount, code.co_nlocals, code.co_stacksize,\n" + " code.co_flags, code.co_code, code.co_consts, code.co_names,\n" + " code.co_varnames, code.co_filename, co_name, co_firstlineno,\n" + " code.co_lnotab)\n", "", Py_file_input); + if (!compiled) return NULL; + result = PyEval_EvalCode(compiled, scratch_dict, scratch_dict); + Py_DECREF(compiled); + if (!result) PyErr_Print(); + Py_DECREF(result); + result = PyDict_GetItemString(scratch_dict, "out"); + if (result) Py_INCREF(result); + return result; + } + #else + return NULL; + #endif +} +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + PyObject *code_object = NULL, *py_py_line = NULL, *py_funcname = NULL, *dict = NULL; + PyObject *replace = NULL, *getframe = NULL, *frame = NULL; + PyObject *exc_type, *exc_value, *exc_traceback; + int success = 0; + if (c_line) { + (void) __pyx_cfilenm; + (void) __Pyx_CLineForTraceback(__Pyx_PyThreadState_Current, c_line); + } + PyErr_Fetch(&exc_type, &exc_value, &exc_traceback); + code_object = Py_CompileString("_getframe()", filename, Py_eval_input); + if (unlikely(!code_object)) goto bad; + py_py_line = PyLong_FromLong(py_line); + if (unlikely(!py_py_line)) goto bad; + py_funcname = PyUnicode_FromString(funcname); + if (unlikely(!py_funcname)) goto bad; + dict = PyDict_New(); + if (unlikely(!dict)) goto bad; + { + PyObject *old_code_object = code_object; + code_object = __Pyx_PyCode_Replace_For_AddTraceback(code_object, dict, py_py_line, py_funcname); + Py_DECREF(old_code_object); + } + if (unlikely(!code_object)) goto bad; + getframe = PySys_GetObject("_getframe"); + if (unlikely(!getframe)) goto bad; + if (unlikely(PyDict_SetItemString(dict, "_getframe", getframe))) goto bad; + frame = PyEval_EvalCode(code_object, dict, dict); + if (unlikely(!frame) || frame == Py_None) goto bad; + success = 1; + bad: + PyErr_Restore(exc_type, exc_value, exc_traceback); + Py_XDECREF(code_object); + Py_XDECREF(py_py_line); + Py_XDECREF(py_funcname); + Py_XDECREF(dict); + Py_XDECREF(replace); + if (success) { + PyTraceBack_Here( + (struct _frame*)frame); + } + Py_XDECREF(frame); +} +#else +static PyCodeObject* __Pyx_CreateCodeObjectForTraceback( + const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = NULL; + PyObject *py_funcname = NULL; + #if PY_MAJOR_VERSION < 3 + PyObject *py_srcfile = NULL; + py_srcfile = PyString_FromString(filename); + if (!py_srcfile) goto bad; + #endif + if (c_line) { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + #else + py_funcname = PyUnicode_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + funcname = PyUnicode_AsUTF8(py_funcname); + if (!funcname) goto bad; + #endif + } + else { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromString(funcname); + if (!py_funcname) goto bad; + #endif + } + #if PY_MAJOR_VERSION < 3 + py_code = __Pyx_PyCode_New( + 0, + 0, + 0, + 0, + 0, + 0, + __pyx_empty_bytes, /*PyObject *code,*/ + __pyx_empty_tuple, /*PyObject *consts,*/ + __pyx_empty_tuple, /*PyObject *names,*/ + __pyx_empty_tuple, /*PyObject *varnames,*/ + __pyx_empty_tuple, /*PyObject *freevars,*/ + __pyx_empty_tuple, /*PyObject *cellvars,*/ + py_srcfile, /*PyObject *filename,*/ + py_funcname, /*PyObject *name,*/ + py_line, + __pyx_empty_bytes /*PyObject *lnotab*/ + ); + Py_DECREF(py_srcfile); + #else + py_code = PyCode_NewEmpty(filename, funcname, py_line); + #endif + Py_XDECREF(py_funcname); + return py_code; +bad: + Py_XDECREF(py_funcname); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_srcfile); + #endif + return NULL; +} +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = 0; + PyFrameObject *py_frame = 0; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject *ptype, *pvalue, *ptraceback; + if (c_line) { + c_line = __Pyx_CLineForTraceback(tstate, c_line); + } + py_code = __pyx_find_code_object(c_line ? -c_line : py_line); + if (!py_code) { + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); + py_code = __Pyx_CreateCodeObjectForTraceback( + funcname, c_line, py_line, filename); + if (!py_code) { + /* If the code object creation fails, then we should clear the + fetched exception references and propagate the new exception */ + Py_XDECREF(ptype); + Py_XDECREF(pvalue); + Py_XDECREF(ptraceback); + goto bad; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + __pyx_insert_code_object(c_line ? -c_line : py_line, py_code); + } + py_frame = PyFrame_New( + tstate, /*PyThreadState *tstate,*/ + py_code, /*PyCodeObject *code,*/ + __pyx_d, /*PyObject *globals,*/ + 0 /*PyObject *locals*/ + ); + if (!py_frame) goto bad; + __Pyx_PyFrame_SetLineNumber(py_frame, py_line); + PyTraceBack_Here(py_frame); +bad: + Py_XDECREF(py_code); + Py_XDECREF(py_frame); +} +#endif + +#if PY_MAJOR_VERSION < 3 +static int __Pyx_GetBuffer(PyObject *obj, Py_buffer *view, int flags) { + __Pyx_TypeName obj_type_name; + if (PyObject_CheckBuffer(obj)) return PyObject_GetBuffer(obj, view, flags); + if (__Pyx_TypeCheck(obj, __pyx_array_type)) return __pyx_array_getbuffer(obj, view, flags); + if (__Pyx_TypeCheck(obj, __pyx_memoryview_type)) return __pyx_memoryview_getbuffer(obj, view, flags); + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "'" __Pyx_FMT_TYPENAME "' does not have the buffer interface", + obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return -1; +} +static void __Pyx_ReleaseBuffer(Py_buffer *view) { + PyObject *obj = view->obj; + if (!obj) return; + if (PyObject_CheckBuffer(obj)) { + PyBuffer_Release(view); + return; + } + if ((0)) {} + view->obj = NULL; + Py_DECREF(obj); +} +#endif + + + /* MemviewSliceIsContig */ + static int +__pyx_memviewslice_is_contig(const __Pyx_memviewslice mvs, char order, int ndim) +{ + int i, index, step, start; + Py_ssize_t itemsize = mvs.memview->view.itemsize; + if (order == 'F') { + step = 1; + start = 0; + } else { + step = -1; + start = ndim - 1; + } + for (i = 0; i < ndim; i++) { + index = start + step * i; + if (mvs.suboffsets[index] >= 0 || mvs.strides[index] != itemsize) + return 0; + itemsize *= mvs.shape[index]; + } + return 1; +} + +/* OverlappingSlices */ + static void +__pyx_get_array_memory_extents(__Pyx_memviewslice *slice, + void **out_start, void **out_end, + int ndim, size_t itemsize) +{ + char *start, *end; + int i; + start = end = slice->data; + for (i = 0; i < ndim; i++) { + Py_ssize_t stride = slice->strides[i]; + Py_ssize_t extent = slice->shape[i]; + if (extent == 0) { + *out_start = *out_end = start; + return; + } else { + if (stride > 0) + end += stride * (extent - 1); + else + start += stride * (extent - 1); + } + } + *out_start = start; + *out_end = end + itemsize; +} +static int +__pyx_slices_overlap(__Pyx_memviewslice *slice1, + __Pyx_memviewslice *slice2, + int ndim, size_t itemsize) +{ + void *start1, *end1, *start2, *end2; + __pyx_get_array_memory_extents(slice1, &start1, &end1, ndim, itemsize); + __pyx_get_array_memory_extents(slice2, &start2, &end2, ndim, itemsize); + return (start1 < end2) && (start2 < end1); +} + +/* CIntFromPyVerify */ + #define __PYX_VERIFY_RETURN_INT(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 0) +#define __PYX_VERIFY_RETURN_INT_EXC(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 1) +#define __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, exc)\ + {\ + func_type value = func_value;\ + if (sizeof(target_type) < sizeof(func_type)) {\ + if (unlikely(value != (func_type) (target_type) value)) {\ + func_type zero = 0;\ + if (exc && unlikely(value == (func_type)-1 && PyErr_Occurred()))\ + return (target_type) -1;\ + if (is_unsigned && unlikely(value < zero))\ + goto raise_neg_overflow;\ + else\ + goto raise_overflow;\ + }\ + }\ + return (target_type) value;\ + } + +/* TypeInfoCompare */ + static int +__pyx_typeinfo_cmp(__Pyx_TypeInfo *a, __Pyx_TypeInfo *b) +{ + int i; + if (!a || !b) + return 0; + if (a == b) + return 1; + if (a->size != b->size || a->typegroup != b->typegroup || + a->is_unsigned != b->is_unsigned || a->ndim != b->ndim) { + if (a->typegroup == 'H' || b->typegroup == 'H') { + return a->size == b->size; + } else { + return 0; + } + } + if (a->ndim) { + for (i = 0; i < a->ndim; i++) + if (a->arraysize[i] != b->arraysize[i]) + return 0; + } + if (a->typegroup == 'S') { + if (a->flags != b->flags) + return 0; + if (a->fields || b->fields) { + if (!(a->fields && b->fields)) + return 0; + for (i = 0; a->fields[i].type && b->fields[i].type; i++) { + __Pyx_StructField *field_a = a->fields + i; + __Pyx_StructField *field_b = b->fields + i; + if (field_a->offset != field_b->offset || + !__pyx_typeinfo_cmp(field_a->type, field_b->type)) + return 0; + } + return !a->fields[i].type && !b->fields[i].type; + } + } + return 1; +} + +/* MemviewSliceValidateAndInit */ + static int +__pyx_check_strides(Py_buffer *buf, int dim, int ndim, int spec) +{ + if (buf->shape[dim] <= 1) + return 1; + if (buf->strides) { + if (spec & __Pyx_MEMVIEW_CONTIG) { + if (spec & (__Pyx_MEMVIEW_PTR|__Pyx_MEMVIEW_FULL)) { + if (unlikely(buf->strides[dim] != sizeof(void *))) { + PyErr_Format(PyExc_ValueError, + "Buffer is not indirectly contiguous " + "in dimension %d.", dim); + goto fail; + } + } else if (unlikely(buf->strides[dim] != buf->itemsize)) { + PyErr_SetString(PyExc_ValueError, + "Buffer and memoryview are not contiguous " + "in the same dimension."); + goto fail; + } + } + if (spec & __Pyx_MEMVIEW_FOLLOW) { + Py_ssize_t stride = buf->strides[dim]; + if (stride < 0) + stride = -stride; + if (unlikely(stride < buf->itemsize)) { + PyErr_SetString(PyExc_ValueError, + "Buffer and memoryview are not contiguous " + "in the same dimension."); + goto fail; + } + } + } else { + if (unlikely(spec & __Pyx_MEMVIEW_CONTIG && dim != ndim - 1)) { + PyErr_Format(PyExc_ValueError, + "C-contiguous buffer is not contiguous in " + "dimension %d", dim); + goto fail; + } else if (unlikely(spec & (__Pyx_MEMVIEW_PTR))) { + PyErr_Format(PyExc_ValueError, + "C-contiguous buffer is not indirect in " + "dimension %d", dim); + goto fail; + } else if (unlikely(buf->suboffsets)) { + PyErr_SetString(PyExc_ValueError, + "Buffer exposes suboffsets but no strides"); + goto fail; + } + } + return 1; +fail: + return 0; +} +static int +__pyx_check_suboffsets(Py_buffer *buf, int dim, int ndim, int spec) +{ + CYTHON_UNUSED_VAR(ndim); + if (spec & __Pyx_MEMVIEW_DIRECT) { + if (unlikely(buf->suboffsets && buf->suboffsets[dim] >= 0)) { + PyErr_Format(PyExc_ValueError, + "Buffer not compatible with direct access " + "in dimension %d.", dim); + goto fail; + } + } + if (spec & __Pyx_MEMVIEW_PTR) { + if (unlikely(!buf->suboffsets || (buf->suboffsets[dim] < 0))) { + PyErr_Format(PyExc_ValueError, + "Buffer is not indirectly accessible " + "in dimension %d.", dim); + goto fail; + } + } + return 1; +fail: + return 0; +} +static int +__pyx_verify_contig(Py_buffer *buf, int ndim, int c_or_f_flag) +{ + int i; + if (c_or_f_flag & __Pyx_IS_F_CONTIG) { + Py_ssize_t stride = 1; + for (i = 0; i < ndim; i++) { + if (unlikely(stride * buf->itemsize != buf->strides[i] && buf->shape[i] > 1)) { + PyErr_SetString(PyExc_ValueError, + "Buffer not fortran contiguous."); + goto fail; + } + stride = stride * buf->shape[i]; + } + } else if (c_or_f_flag & __Pyx_IS_C_CONTIG) { + Py_ssize_t stride = 1; + for (i = ndim - 1; i >- 1; i--) { + if (unlikely(stride * buf->itemsize != buf->strides[i] && buf->shape[i] > 1)) { + PyErr_SetString(PyExc_ValueError, + "Buffer not C contiguous."); + goto fail; + } + stride = stride * buf->shape[i]; + } + } + return 1; +fail: + return 0; +} +static int __Pyx_ValidateAndInit_memviewslice( + int *axes_specs, + int c_or_f_flag, + int buf_flags, + int ndim, + __Pyx_TypeInfo *dtype, + __Pyx_BufFmt_StackElem stack[], + __Pyx_memviewslice *memviewslice, + PyObject *original_obj) +{ + struct __pyx_memoryview_obj *memview, *new_memview; + __Pyx_RefNannyDeclarations + Py_buffer *buf; + int i, spec = 0, retval = -1; + __Pyx_BufFmt_Context ctx; + int from_memoryview = __pyx_memoryview_check(original_obj); + __Pyx_RefNannySetupContext("ValidateAndInit_memviewslice", 0); + if (from_memoryview && __pyx_typeinfo_cmp(dtype, ((struct __pyx_memoryview_obj *) + original_obj)->typeinfo)) { + memview = (struct __pyx_memoryview_obj *) original_obj; + new_memview = NULL; + } else { + memview = (struct __pyx_memoryview_obj *) __pyx_memoryview_new( + original_obj, buf_flags, 0, dtype); + new_memview = memview; + if (unlikely(!memview)) + goto fail; + } + buf = &memview->view; + if (unlikely(buf->ndim != ndim)) { + PyErr_Format(PyExc_ValueError, + "Buffer has wrong number of dimensions (expected %d, got %d)", + ndim, buf->ndim); + goto fail; + } + if (new_memview) { + __Pyx_BufFmt_Init(&ctx, stack, dtype); + if (unlikely(!__Pyx_BufFmt_CheckString(&ctx, buf->format))) goto fail; + } + if (unlikely((unsigned) buf->itemsize != dtype->size)) { + PyErr_Format(PyExc_ValueError, + "Item size of buffer (%" CYTHON_FORMAT_SSIZE_T "u byte%s) " + "does not match size of '%s' (%" CYTHON_FORMAT_SSIZE_T "u byte%s)", + buf->itemsize, + (buf->itemsize > 1) ? "s" : "", + dtype->name, + dtype->size, + (dtype->size > 1) ? "s" : ""); + goto fail; + } + if (buf->len > 0) { + for (i = 0; i < ndim; i++) { + spec = axes_specs[i]; + if (unlikely(!__pyx_check_strides(buf, i, ndim, spec))) + goto fail; + if (unlikely(!__pyx_check_suboffsets(buf, i, ndim, spec))) + goto fail; + } + if (unlikely(buf->strides && !__pyx_verify_contig(buf, ndim, c_or_f_flag))) + goto fail; + } + if (unlikely(__Pyx_init_memviewslice(memview, ndim, memviewslice, + new_memview != NULL) == -1)) { + goto fail; + } + retval = 0; + goto no_fail; +fail: + Py_XDECREF(new_memview); + retval = -1; +no_fail: + __Pyx_RefNannyFinishContext(); + return retval; +} + +/* ObjectToMemviewSlice */ + static CYTHON_INLINE __Pyx_memviewslice __Pyx_PyObject_to_MemoryviewSlice_dsds_double(PyObject *obj, int writable_flag) { + __Pyx_memviewslice result = { 0, 0, { 0 }, { 0 }, { 0 } }; + __Pyx_BufFmt_StackElem stack[1]; + int axes_specs[] = { (__Pyx_MEMVIEW_DIRECT | __Pyx_MEMVIEW_STRIDED), (__Pyx_MEMVIEW_DIRECT | __Pyx_MEMVIEW_STRIDED) }; + int retcode; + if (obj == Py_None) { + result.memview = (struct __pyx_memoryview_obj *) Py_None; + return result; + } + retcode = __Pyx_ValidateAndInit_memviewslice(axes_specs, 0, + PyBUF_RECORDS_RO | writable_flag, 2, + &__Pyx_TypeInfo_double, stack, + &result, obj); + if (unlikely(retcode == -1)) + goto __pyx_fail; + return result; +__pyx_fail: + result.memview = NULL; + result.data = NULL; + return result; +} + +/* MemviewDtypeToObject */ + static CYTHON_INLINE PyObject *__pyx_memview_get_double(const char *itemp) { + return (PyObject *) PyFloat_FromDouble(*(double *) itemp); +} +static CYTHON_INLINE int __pyx_memview_set_double(const char *itemp, PyObject *obj) { + double value = __pyx_PyFloat_AsDouble(obj); + if (unlikely((value == (double)-1) && PyErr_Occurred())) + return 0; + *(double *) itemp = value; + return 1; +} + +/* ObjectToMemviewSlice */ + static CYTHON_INLINE __Pyx_memviewslice __Pyx_PyObject_to_MemoryviewSlice_ds_double(PyObject *obj, int writable_flag) { + __Pyx_memviewslice result = { 0, 0, { 0 }, { 0 }, { 0 } }; + __Pyx_BufFmt_StackElem stack[1]; + int axes_specs[] = { (__Pyx_MEMVIEW_DIRECT | __Pyx_MEMVIEW_STRIDED) }; + int retcode; + if (obj == Py_None) { + result.memview = (struct __pyx_memoryview_obj *) Py_None; + return result; + } + retcode = __Pyx_ValidateAndInit_memviewslice(axes_specs, 0, + PyBUF_RECORDS_RO | writable_flag, 1, + &__Pyx_TypeInfo_double, stack, + &result, obj); + if (unlikely(retcode == -1)) + goto __pyx_fail; + return result; +__pyx_fail: + result.memview = NULL; + result.data = NULL; + return result; +} + +/* Declarations */ + #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #ifdef __cplusplus + static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float x, float y) { + return ::std::complex< float >(x, y); + } + #else + static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float x, float y) { + return x + y*(__pyx_t_float_complex)_Complex_I; + } + #endif +#else + static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float x, float y) { + __pyx_t_float_complex z; + z.real = x; + z.imag = y; + return z; + } +#endif + +/* Arithmetic */ + #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) +#else + static CYTHON_INLINE int __Pyx_c_eq_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + return (a.real == b.real) && (a.imag == b.imag); + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_sum_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + __pyx_t_float_complex z; + z.real = a.real + b.real; + z.imag = a.imag + b.imag; + return z; + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_diff_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + __pyx_t_float_complex z; + z.real = a.real - b.real; + z.imag = a.imag - b.imag; + return z; + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_prod_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + __pyx_t_float_complex z; + z.real = a.real * b.real - a.imag * b.imag; + z.imag = a.real * b.imag + a.imag * b.real; + return z; + } + #if 1 + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_quot_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + if (b.imag == 0) { + return __pyx_t_float_complex_from_parts(a.real / b.real, a.imag / b.real); + } else if (fabsf(b.real) >= fabsf(b.imag)) { + if (b.real == 0 && b.imag == 0) { + return __pyx_t_float_complex_from_parts(a.real / b.real, a.imag / b.imag); + } else { + float r = b.imag / b.real; + float s = (float)(1.0) / (b.real + b.imag * r); + return __pyx_t_float_complex_from_parts( + (a.real + a.imag * r) * s, (a.imag - a.real * r) * s); + } + } else { + float r = b.real / b.imag; + float s = (float)(1.0) / (b.imag + b.real * r); + return __pyx_t_float_complex_from_parts( + (a.real * r + a.imag) * s, (a.imag * r - a.real) * s); + } + } + #else + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_quot_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + if (b.imag == 0) { + return __pyx_t_float_complex_from_parts(a.real / b.real, a.imag / b.real); + } else { + float denom = b.real * b.real + b.imag * b.imag; + return __pyx_t_float_complex_from_parts( + (a.real * b.real + a.imag * b.imag) / denom, + (a.imag * b.real - a.real * b.imag) / denom); + } + } + #endif + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_neg_float(__pyx_t_float_complex a) { + __pyx_t_float_complex z; + z.real = -a.real; + z.imag = -a.imag; + return z; + } + static CYTHON_INLINE int __Pyx_c_is_zero_float(__pyx_t_float_complex a) { + return (a.real == 0) && (a.imag == 0); + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_conj_float(__pyx_t_float_complex a) { + __pyx_t_float_complex z; + z.real = a.real; + z.imag = -a.imag; + return z; + } + #if 1 + static CYTHON_INLINE float __Pyx_c_abs_float(__pyx_t_float_complex z) { + #if !defined(HAVE_HYPOT) || defined(_MSC_VER) + return sqrtf(z.real*z.real + z.imag*z.imag); + #else + return hypotf(z.real, z.imag); + #endif + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_pow_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + __pyx_t_float_complex z; + float r, lnr, theta, z_r, z_theta; + if (b.imag == 0 && b.real == (int)b.real) { + if (b.real < 0) { + float denom = a.real * a.real + a.imag * a.imag; + a.real = a.real / denom; + a.imag = -a.imag / denom; + b.real = -b.real; + } + switch ((int)b.real) { + case 0: + z.real = 1; + z.imag = 0; + return z; + case 1: + return a; + case 2: + return __Pyx_c_prod_float(a, a); + case 3: + z = __Pyx_c_prod_float(a, a); + return __Pyx_c_prod_float(z, a); + case 4: + z = __Pyx_c_prod_float(a, a); + return __Pyx_c_prod_float(z, z); + } + } + if (a.imag == 0) { + if (a.real == 0) { + return a; + } else if ((b.imag == 0) && (a.real >= 0)) { + z.real = powf(a.real, b.real); + z.imag = 0; + return z; + } else if (a.real > 0) { + r = a.real; + theta = 0; + } else { + r = -a.real; + theta = atan2f(0.0, -1.0); + } + } else { + r = __Pyx_c_abs_float(a); + theta = atan2f(a.imag, a.real); + } + lnr = logf(r); + z_r = expf(lnr * b.real - theta * b.imag); + z_theta = theta * b.real + lnr * b.imag; + z.real = z_r * cosf(z_theta); + z.imag = z_r * sinf(z_theta); + return z; + } + #endif +#endif + +/* Declarations */ + #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #ifdef __cplusplus + static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double x, double y) { + return ::std::complex< double >(x, y); + } + #else + static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double x, double y) { + return x + y*(__pyx_t_double_complex)_Complex_I; + } + #endif +#else + static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double x, double y) { + __pyx_t_double_complex z; + z.real = x; + z.imag = y; + return z; + } +#endif + +/* Arithmetic */ + #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) +#else + static CYTHON_INLINE int __Pyx_c_eq_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + return (a.real == b.real) && (a.imag == b.imag); + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_sum_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + __pyx_t_double_complex z; + z.real = a.real + b.real; + z.imag = a.imag + b.imag; + return z; + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_diff_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + __pyx_t_double_complex z; + z.real = a.real - b.real; + z.imag = a.imag - b.imag; + return z; + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_prod_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + __pyx_t_double_complex z; + z.real = a.real * b.real - a.imag * b.imag; + z.imag = a.real * b.imag + a.imag * b.real; + return z; + } + #if 1 + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_quot_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + if (b.imag == 0) { + return __pyx_t_double_complex_from_parts(a.real / b.real, a.imag / b.real); + } else if (fabs(b.real) >= fabs(b.imag)) { + if (b.real == 0 && b.imag == 0) { + return __pyx_t_double_complex_from_parts(a.real / b.real, a.imag / b.imag); + } else { + double r = b.imag / b.real; + double s = (double)(1.0) / (b.real + b.imag * r); + return __pyx_t_double_complex_from_parts( + (a.real + a.imag * r) * s, (a.imag - a.real * r) * s); + } + } else { + double r = b.real / b.imag; + double s = (double)(1.0) / (b.imag + b.real * r); + return __pyx_t_double_complex_from_parts( + (a.real * r + a.imag) * s, (a.imag * r - a.real) * s); + } + } + #else + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_quot_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + if (b.imag == 0) { + return __pyx_t_double_complex_from_parts(a.real / b.real, a.imag / b.real); + } else { + double denom = b.real * b.real + b.imag * b.imag; + return __pyx_t_double_complex_from_parts( + (a.real * b.real + a.imag * b.imag) / denom, + (a.imag * b.real - a.real * b.imag) / denom); + } + } + #endif + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_neg_double(__pyx_t_double_complex a) { + __pyx_t_double_complex z; + z.real = -a.real; + z.imag = -a.imag; + return z; + } + static CYTHON_INLINE int __Pyx_c_is_zero_double(__pyx_t_double_complex a) { + return (a.real == 0) && (a.imag == 0); + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_conj_double(__pyx_t_double_complex a) { + __pyx_t_double_complex z; + z.real = a.real; + z.imag = -a.imag; + return z; + } + #if 1 + static CYTHON_INLINE double __Pyx_c_abs_double(__pyx_t_double_complex z) { + #if !defined(HAVE_HYPOT) || defined(_MSC_VER) + return sqrt(z.real*z.real + z.imag*z.imag); + #else + return hypot(z.real, z.imag); + #endif + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_pow_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + __pyx_t_double_complex z; + double r, lnr, theta, z_r, z_theta; + if (b.imag == 0 && b.real == (int)b.real) { + if (b.real < 0) { + double denom = a.real * a.real + a.imag * a.imag; + a.real = a.real / denom; + a.imag = -a.imag / denom; + b.real = -b.real; + } + switch ((int)b.real) { + case 0: + z.real = 1; + z.imag = 0; + return z; + case 1: + return a; + case 2: + return __Pyx_c_prod_double(a, a); + case 3: + z = __Pyx_c_prod_double(a, a); + return __Pyx_c_prod_double(z, a); + case 4: + z = __Pyx_c_prod_double(a, a); + return __Pyx_c_prod_double(z, z); + } + } + if (a.imag == 0) { + if (a.real == 0) { + return a; + } else if ((b.imag == 0) && (a.real >= 0)) { + z.real = pow(a.real, b.real); + z.imag = 0; + return z; + } else if (a.real > 0) { + r = a.real; + theta = 0; + } else { + r = -a.real; + theta = atan2(0.0, -1.0); + } + } else { + r = __Pyx_c_abs_double(a); + theta = atan2(a.imag, a.real); + } + lnr = log(r); + z_r = exp(lnr * b.real - theta * b.imag); + z_theta = theta * b.real + lnr * b.imag; + z.real = z_r * cos(z_theta); + z.imag = z_r * sin(z_theta); + return z; + } + #endif +#endif + +/* MemviewSliceCopyTemplate */ + static __Pyx_memviewslice +__pyx_memoryview_copy_new_contig(const __Pyx_memviewslice *from_mvs, + const char *mode, int ndim, + size_t sizeof_dtype, int contig_flag, + int dtype_is_object) +{ + __Pyx_RefNannyDeclarations + int i; + __Pyx_memviewslice new_mvs = { 0, 0, { 0 }, { 0 }, { 0 } }; + struct __pyx_memoryview_obj *from_memview = from_mvs->memview; + Py_buffer *buf = &from_memview->view; + PyObject *shape_tuple = NULL; + PyObject *temp_int = NULL; + struct __pyx_array_obj *array_obj = NULL; + struct __pyx_memoryview_obj *memview_obj = NULL; + __Pyx_RefNannySetupContext("__pyx_memoryview_copy_new_contig", 0); + for (i = 0; i < ndim; i++) { + if (unlikely(from_mvs->suboffsets[i] >= 0)) { + PyErr_Format(PyExc_ValueError, "Cannot copy memoryview slice with " + "indirect dimensions (axis %d)", i); + goto fail; + } + } + shape_tuple = PyTuple_New(ndim); + if (unlikely(!shape_tuple)) { + goto fail; + } + __Pyx_GOTREF(shape_tuple); + for(i = 0; i < ndim; i++) { + temp_int = PyInt_FromSsize_t(from_mvs->shape[i]); + if(unlikely(!temp_int)) { + goto fail; + } else { + PyTuple_SET_ITEM(shape_tuple, i, temp_int); + temp_int = NULL; + } + } + array_obj = __pyx_array_new(shape_tuple, sizeof_dtype, buf->format, (char *) mode, NULL); + if (unlikely(!array_obj)) { + goto fail; + } + __Pyx_GOTREF(array_obj); + memview_obj = (struct __pyx_memoryview_obj *) __pyx_memoryview_new( + (PyObject *) array_obj, contig_flag, + dtype_is_object, + from_mvs->memview->typeinfo); + if (unlikely(!memview_obj)) + goto fail; + if (unlikely(__Pyx_init_memviewslice(memview_obj, ndim, &new_mvs, 1) < 0)) + goto fail; + if (unlikely(__pyx_memoryview_copy_contents(*from_mvs, new_mvs, ndim, ndim, + dtype_is_object) < 0)) + goto fail; + goto no_fail; +fail: + __Pyx_XDECREF(new_mvs.memview); + new_mvs.memview = NULL; + new_mvs.data = NULL; +no_fail: + __Pyx_XDECREF(shape_tuple); + __Pyx_XDECREF(temp_int); + __Pyx_XDECREF(array_obj); + __Pyx_RefNannyFinishContext(); + return new_mvs; +} + +/* MemviewSliceInit */ + static int +__Pyx_init_memviewslice(struct __pyx_memoryview_obj *memview, + int ndim, + __Pyx_memviewslice *memviewslice, + int memview_is_new_reference) +{ + __Pyx_RefNannyDeclarations + int i, retval=-1; + Py_buffer *buf = &memview->view; + __Pyx_RefNannySetupContext("init_memviewslice", 0); + if (unlikely(memviewslice->memview || memviewslice->data)) { + PyErr_SetString(PyExc_ValueError, + "memviewslice is already initialized!"); + goto fail; + } + if (buf->strides) { + for (i = 0; i < ndim; i++) { + memviewslice->strides[i] = buf->strides[i]; + } + } else { + Py_ssize_t stride = buf->itemsize; + for (i = ndim - 1; i >= 0; i--) { + memviewslice->strides[i] = stride; + stride *= buf->shape[i]; + } + } + for (i = 0; i < ndim; i++) { + memviewslice->shape[i] = buf->shape[i]; + if (buf->suboffsets) { + memviewslice->suboffsets[i] = buf->suboffsets[i]; + } else { + memviewslice->suboffsets[i] = -1; + } + } + memviewslice->memview = memview; + memviewslice->data = (char *)buf->buf; + if (__pyx_add_acquisition_count(memview) == 0 && !memview_is_new_reference) { + Py_INCREF(memview); + } + retval = 0; + goto no_fail; +fail: + memviewslice->memview = 0; + memviewslice->data = 0; + retval = -1; +no_fail: + __Pyx_RefNannyFinishContext(); + return retval; +} +#ifndef Py_NO_RETURN +#define Py_NO_RETURN +#endif +static void __pyx_fatalerror(const char *fmt, ...) Py_NO_RETURN { + va_list vargs; + char msg[200]; +#if PY_VERSION_HEX >= 0x030A0000 || defined(HAVE_STDARG_PROTOTYPES) + va_start(vargs, fmt); +#else + va_start(vargs); +#endif + vsnprintf(msg, 200, fmt, vargs); + va_end(vargs); + Py_FatalError(msg); +} +static CYTHON_INLINE int +__pyx_add_acquisition_count_locked(__pyx_atomic_int_type *acquisition_count, + PyThread_type_lock lock) +{ + int result; + PyThread_acquire_lock(lock, 1); + result = (*acquisition_count)++; + PyThread_release_lock(lock); + return result; +} +static CYTHON_INLINE int +__pyx_sub_acquisition_count_locked(__pyx_atomic_int_type *acquisition_count, + PyThread_type_lock lock) +{ + int result; + PyThread_acquire_lock(lock, 1); + result = (*acquisition_count)--; + PyThread_release_lock(lock); + return result; +} +static CYTHON_INLINE void +__Pyx_INC_MEMVIEW(__Pyx_memviewslice *memslice, int have_gil, int lineno) +{ + __pyx_nonatomic_int_type old_acquisition_count; + struct __pyx_memoryview_obj *memview = memslice->memview; + if (unlikely(!memview || (PyObject *) memview == Py_None)) { + return; + } + old_acquisition_count = __pyx_add_acquisition_count(memview); + if (unlikely(old_acquisition_count <= 0)) { + if (likely(old_acquisition_count == 0)) { + if (have_gil) { + Py_INCREF((PyObject *) memview); + } else { + PyGILState_STATE _gilstate = PyGILState_Ensure(); + Py_INCREF((PyObject *) memview); + PyGILState_Release(_gilstate); + } + } else { + __pyx_fatalerror("Acquisition count is %d (line %d)", + old_acquisition_count+1, lineno); + } + } +} +static CYTHON_INLINE void __Pyx_XCLEAR_MEMVIEW(__Pyx_memviewslice *memslice, + int have_gil, int lineno) { + __pyx_nonatomic_int_type old_acquisition_count; + struct __pyx_memoryview_obj *memview = memslice->memview; + if (unlikely(!memview || (PyObject *) memview == Py_None)) { + memslice->memview = NULL; + return; + } + old_acquisition_count = __pyx_sub_acquisition_count(memview); + memslice->data = NULL; + if (likely(old_acquisition_count > 1)) { + memslice->memview = NULL; + } else if (likely(old_acquisition_count == 1)) { + if (have_gil) { + Py_CLEAR(memslice->memview); + } else { + PyGILState_STATE _gilstate = PyGILState_Ensure(); + Py_CLEAR(memslice->memview); + PyGILState_Release(_gilstate); + } + } else { + __pyx_fatalerror("Acquisition count is %d (line %d)", + old_acquisition_count-1, lineno); + } +} + +/* TypeInfoToFormat */ + static struct __pyx_typeinfo_string __Pyx_TypeInfoToFormat(__Pyx_TypeInfo *type) { + struct __pyx_typeinfo_string result = { {0} }; + char *buf = (char *) result.string; + size_t size = type->size; + switch (type->typegroup) { + case 'H': + *buf = 'c'; + break; + case 'I': + case 'U': + if (size == 1) + *buf = (type->is_unsigned) ? 'B' : 'b'; + else if (size == 2) + *buf = (type->is_unsigned) ? 'H' : 'h'; + else if (size == 4) + *buf = (type->is_unsigned) ? 'I' : 'i'; + else if (size == 8) + *buf = (type->is_unsigned) ? 'Q' : 'q'; + break; + case 'P': + *buf = 'P'; + break; + case 'C': + { + __Pyx_TypeInfo complex_type = *type; + complex_type.typegroup = 'R'; + complex_type.size /= 2; + *buf++ = 'Z'; + *buf = __Pyx_TypeInfoToFormat(&complex_type).string[0]; + break; + } + case 'R': + if (size == 4) + *buf = 'f'; + else if (size == 8) + *buf = 'd'; + else + *buf = 'g'; + break; + } + return result; +} + +/* CIntFromPy */ + static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(int) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(int, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (int) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 2 * PyLong_SHIFT)) { + return (int) (((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 3 * PyLong_SHIFT)) { + return (int) (((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 4 * PyLong_SHIFT)) { + return (int) (((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(int) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(int) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) ((((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) ((((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) ((((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(int) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + int val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (int) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (int) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (int) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (int) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(int) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(int) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((int) 1) << (sizeof(int) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (int) -1; + } + } else { + int val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (int) -1; + val = __Pyx_PyInt_As_int(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to int"); + return (int) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to int"); + return (int) -1; +} + +/* CIntToPy */ + static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(long) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(long) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(long) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; +#if !CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030d0000 + return _PyLong_FromByteArray(bytes, sizeof(long), + little, !is_unsigned); +#else + PyObject *from_bytes, *result = NULL; + PyObject *py_bytes = NULL, *arg_tuple = NULL, *kwds = NULL, *order_str = NULL; + from_bytes = PyObject_GetAttrString((PyObject*)&PyLong_Type, "from_bytes"); + if (!from_bytes) return NULL; + py_bytes = PyBytes_FromStringAndSize((char*)bytes, sizeof(long)); + if (!py_bytes) goto limited_bad; + order_str = PyUnicode_FromString(little ? "little" : "big"); + if (!order_str) goto limited_bad; + arg_tuple = PyTuple_Pack(2, py_bytes, order_str); + if (!arg_tuple) goto limited_bad; + if (!is_unsigned) { + kwds = PyDict_New(); + if (!kwds) goto limited_bad; + if (PyDict_SetItemString(kwds, "signed", __Pyx_NewRef(Py_True))) goto limited_bad; + } + result = PyObject_Call(from_bytes, arg_tuple, kwds); + limited_bad: + Py_XDECREF(kwds); + Py_XDECREF(arg_tuple); + Py_XDECREF(order_str); + Py_XDECREF(py_bytes); + Py_XDECREF(from_bytes); + return result; +#endif + } +} + +/* CIntToPy */ + static CYTHON_INLINE PyObject* __Pyx_PyInt_From_int(int value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(int) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(int) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(int) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(int) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(int) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; +#if !CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030d0000 + return _PyLong_FromByteArray(bytes, sizeof(int), + little, !is_unsigned); +#else + PyObject *from_bytes, *result = NULL; + PyObject *py_bytes = NULL, *arg_tuple = NULL, *kwds = NULL, *order_str = NULL; + from_bytes = PyObject_GetAttrString((PyObject*)&PyLong_Type, "from_bytes"); + if (!from_bytes) return NULL; + py_bytes = PyBytes_FromStringAndSize((char*)bytes, sizeof(int)); + if (!py_bytes) goto limited_bad; + order_str = PyUnicode_FromString(little ? "little" : "big"); + if (!order_str) goto limited_bad; + arg_tuple = PyTuple_Pack(2, py_bytes, order_str); + if (!arg_tuple) goto limited_bad; + if (!is_unsigned) { + kwds = PyDict_New(); + if (!kwds) goto limited_bad; + if (PyDict_SetItemString(kwds, "signed", __Pyx_NewRef(Py_True))) goto limited_bad; + } + result = PyObject_Call(from_bytes, arg_tuple, kwds); + limited_bad: + Py_XDECREF(kwds); + Py_XDECREF(arg_tuple); + Py_XDECREF(order_str); + Py_XDECREF(py_bytes); + Py_XDECREF(from_bytes); + return result; +#endif + } +} + +/* CIntFromPy */ + static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(long) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(long, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (long) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 2 * PyLong_SHIFT)) { + return (long) (((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 3 * PyLong_SHIFT)) { + return (long) (((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 4 * PyLong_SHIFT)) { + return (long) (((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(long) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(long) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) ((((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) ((((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) ((((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(long) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + long val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (long) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (long) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (long) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (long) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(long) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(long) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((long) 1) << (sizeof(long) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (long) -1; + } + } else { + long val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (long) -1; + val = __Pyx_PyInt_As_long(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to long"); + return (long) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to long"); + return (long) -1; +} + +/* CIntFromPy */ + static CYTHON_INLINE char __Pyx_PyInt_As_char(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const char neg_one = (char) -1, const_zero = (char) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(char) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(char, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (char) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(char, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(char) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) >= 2 * PyLong_SHIFT)) { + return (char) (((((char)digits[1]) << PyLong_SHIFT) | (char)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(char) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) >= 3 * PyLong_SHIFT)) { + return (char) (((((((char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(char) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) >= 4 * PyLong_SHIFT)) { + return (char) (((((((((char)digits[3]) << PyLong_SHIFT) | (char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (char) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(char) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(char, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(char) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(char, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(char, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(char) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 2 * PyLong_SHIFT)) { + return (char) (((char)-1)*(((((char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(char) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 2 * PyLong_SHIFT)) { + return (char) ((((((char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(char) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 3 * PyLong_SHIFT)) { + return (char) (((char)-1)*(((((((char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(char) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 3 * PyLong_SHIFT)) { + return (char) ((((((((char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(char) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 4 * PyLong_SHIFT)) { + return (char) (((char)-1)*(((((((((char)digits[3]) << PyLong_SHIFT) | (char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(char) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 4 * PyLong_SHIFT)) { + return (char) ((((((((((char)digits[3]) << PyLong_SHIFT) | (char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(char) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(char, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(char) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(char, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + char val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (char) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (char) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (char) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (char) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (char) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(char) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((char) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(char) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((char) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((char) 1) << (sizeof(char) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (char) -1; + } + } else { + char val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (char) -1; + val = __Pyx_PyInt_As_char(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to char"); + return (char) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to char"); + return (char) -1; +} + +/* FormatTypeName */ + #if CYTHON_COMPILING_IN_LIMITED_API +static __Pyx_TypeName +__Pyx_PyType_GetName(PyTypeObject* tp) +{ + PyObject *name = __Pyx_PyObject_GetAttrStr((PyObject *)tp, + __pyx_n_s_name_2); + if (unlikely(name == NULL) || unlikely(!PyUnicode_Check(name))) { + PyErr_Clear(); + Py_XDECREF(name); + name = __Pyx_NewRef(__pyx_n_s__58); + } + return name; +} +#endif + +/* CheckBinaryVersion */ + static unsigned long __Pyx_get_runtime_version(void) { +#if __PYX_LIMITED_VERSION_HEX >= 0x030B00A4 + return Py_Version & ~0xFFUL; +#else + const char* rt_version = Py_GetVersion(); + unsigned long version = 0; + unsigned long factor = 0x01000000UL; + unsigned int digit = 0; + int i = 0; + while (factor) { + while ('0' <= rt_version[i] && rt_version[i] <= '9') { + digit = digit * 10 + (unsigned int) (rt_version[i] - '0'); + ++i; + } + version += factor * digit; + if (rt_version[i] != '.') + break; + digit = 0; + factor >>= 8; + ++i; + } + return version; +#endif +} +static int __Pyx_check_binary_version(unsigned long ct_version, unsigned long rt_version, int allow_newer) { + const unsigned long MAJOR_MINOR = 0xFFFF0000UL; + if ((rt_version & MAJOR_MINOR) == (ct_version & MAJOR_MINOR)) + return 0; + if (likely(allow_newer && (rt_version & MAJOR_MINOR) > (ct_version & MAJOR_MINOR))) + return 1; + { + char message[200]; + PyOS_snprintf(message, sizeof(message), + "compile time Python version %d.%d " + "of module '%.100s' " + "%s " + "runtime version %d.%d", + (int) (ct_version >> 24), (int) ((ct_version >> 16) & 0xFF), + __Pyx_MODULE_NAME, + (allow_newer) ? "was newer than" : "does not match", + (int) (rt_version >> 24), (int) ((rt_version >> 16) & 0xFF) + ); + return PyErr_WarnEx(NULL, message, 1); + } +} + +/* InitStrings */ + #if PY_MAJOR_VERSION >= 3 +static int __Pyx_InitString(__Pyx_StringTabEntry t, PyObject **str) { + if (t.is_unicode | t.is_str) { + if (t.intern) { + *str = PyUnicode_InternFromString(t.s); + } else if (t.encoding) { + *str = PyUnicode_Decode(t.s, t.n - 1, t.encoding, NULL); + } else { + *str = PyUnicode_FromStringAndSize(t.s, t.n - 1); + } + } else { + *str = PyBytes_FromStringAndSize(t.s, t.n - 1); + } + if (!*str) + return -1; + if (PyObject_Hash(*str) == -1) + return -1; + return 0; +} +#endif +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t) { + while (t->p) { + #if PY_MAJOR_VERSION >= 3 + __Pyx_InitString(*t, t->p); + #else + if (t->is_unicode) { + *t->p = PyUnicode_DecodeUTF8(t->s, t->n - 1, NULL); + } else if (t->intern) { + *t->p = PyString_InternFromString(t->s); + } else { + *t->p = PyString_FromStringAndSize(t->s, t->n - 1); + } + if (!*t->p) + return -1; + if (PyObject_Hash(*t->p) == -1) + return -1; + #endif + ++t; + } + return 0; +} + +#include +static CYTHON_INLINE Py_ssize_t __Pyx_ssize_strlen(const char *s) { + size_t len = strlen(s); + if (unlikely(len > (size_t) PY_SSIZE_T_MAX)) { + PyErr_SetString(PyExc_OverflowError, "byte string is too long"); + return -1; + } + return (Py_ssize_t) len; +} +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char* c_str) { + Py_ssize_t len = __Pyx_ssize_strlen(c_str); + if (unlikely(len < 0)) return NULL; + return __Pyx_PyUnicode_FromStringAndSize(c_str, len); +} +static CYTHON_INLINE PyObject* __Pyx_PyByteArray_FromString(const char* c_str) { + Py_ssize_t len = __Pyx_ssize_strlen(c_str); + if (unlikely(len < 0)) return NULL; + return PyByteArray_FromStringAndSize(c_str, len); +} +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject* o) { + Py_ssize_t ignore; + return __Pyx_PyObject_AsStringAndSize(o, &ignore); +} +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +#if !CYTHON_PEP393_ENABLED +static const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + char* defenc_c; + PyObject* defenc = _PyUnicode_AsDefaultEncodedString(o, NULL); + if (!defenc) return NULL; + defenc_c = PyBytes_AS_STRING(defenc); +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + { + char* end = defenc_c + PyBytes_GET_SIZE(defenc); + char* c; + for (c = defenc_c; c < end; c++) { + if ((unsigned char) (*c) >= 128) { + PyUnicode_AsASCIIString(o); + return NULL; + } + } + } +#endif + *length = PyBytes_GET_SIZE(defenc); + return defenc_c; +} +#else +static CYTHON_INLINE const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + if (unlikely(__Pyx_PyUnicode_READY(o) == -1)) return NULL; +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + if (likely(PyUnicode_IS_ASCII(o))) { + *length = PyUnicode_GET_LENGTH(o); + return PyUnicode_AsUTF8(o); + } else { + PyUnicode_AsASCIIString(o); + return NULL; + } +#else + return PyUnicode_AsUTF8AndSize(o, length); +#endif +} +#endif +#endif +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject* o, Py_ssize_t *length) { +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT + if ( +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + __Pyx_sys_getdefaultencoding_not_ascii && +#endif + PyUnicode_Check(o)) { + return __Pyx_PyUnicode_AsStringAndSize(o, length); + } else +#endif +#if (!CYTHON_COMPILING_IN_PYPY && !CYTHON_COMPILING_IN_LIMITED_API) || (defined(PyByteArray_AS_STRING) && defined(PyByteArray_GET_SIZE)) + if (PyByteArray_Check(o)) { + *length = PyByteArray_GET_SIZE(o); + return PyByteArray_AS_STRING(o); + } else +#endif + { + char* result; + int r = PyBytes_AsStringAndSize(o, &result, length); + if (unlikely(r < 0)) { + return NULL; + } else { + return result; + } + } +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject* x) { + int is_true = x == Py_True; + if (is_true | (x == Py_False) | (x == Py_None)) return is_true; + else return PyObject_IsTrue(x); +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject* x) { + int retval; + if (unlikely(!x)) return -1; + retval = __Pyx_PyObject_IsTrue(x); + Py_DECREF(x); + return retval; +} +static PyObject* __Pyx_PyNumber_IntOrLongWrongResultType(PyObject* result, const char* type_name) { + __Pyx_TypeName result_type_name = __Pyx_PyType_GetName(Py_TYPE(result)); +#if PY_MAJOR_VERSION >= 3 + if (PyLong_Check(result)) { + if (PyErr_WarnFormat(PyExc_DeprecationWarning, 1, + "__int__ returned non-int (type " __Pyx_FMT_TYPENAME "). " + "The ability to return an instance of a strict subclass of int is deprecated, " + "and may be removed in a future version of Python.", + result_type_name)) { + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; + } + __Pyx_DECREF_TypeName(result_type_name); + return result; + } +#endif + PyErr_Format(PyExc_TypeError, + "__%.4s__ returned non-%.4s (type " __Pyx_FMT_TYPENAME ")", + type_name, type_name, result_type_name); + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x) { +#if CYTHON_USE_TYPE_SLOTS + PyNumberMethods *m; +#endif + const char *name = NULL; + PyObject *res = NULL; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x) || PyLong_Check(x))) +#else + if (likely(PyLong_Check(x))) +#endif + return __Pyx_NewRef(x); +#if CYTHON_USE_TYPE_SLOTS + m = Py_TYPE(x)->tp_as_number; + #if PY_MAJOR_VERSION < 3 + if (m && m->nb_int) { + name = "int"; + res = m->nb_int(x); + } + else if (m && m->nb_long) { + name = "long"; + res = m->nb_long(x); + } + #else + if (likely(m && m->nb_int)) { + name = "int"; + res = m->nb_int(x); + } + #endif +#else + if (!PyBytes_CheckExact(x) && !PyUnicode_CheckExact(x)) { + res = PyNumber_Int(x); + } +#endif + if (likely(res)) { +#if PY_MAJOR_VERSION < 3 + if (unlikely(!PyInt_Check(res) && !PyLong_Check(res))) { +#else + if (unlikely(!PyLong_CheckExact(res))) { +#endif + return __Pyx_PyNumber_IntOrLongWrongResultType(res, name); + } + } + else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_TypeError, + "an integer is required"); + } + return res; +} +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject* b) { + Py_ssize_t ival; + PyObject *x; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_CheckExact(b))) { + if (sizeof(Py_ssize_t) >= sizeof(long)) + return PyInt_AS_LONG(b); + else + return PyInt_AsSsize_t(b); + } +#endif + if (likely(PyLong_CheckExact(b))) { + #if CYTHON_USE_PYLONG_INTERNALS + if (likely(__Pyx_PyLong_IsCompact(b))) { + return __Pyx_PyLong_CompactValue(b); + } else { + const digit* digits = __Pyx_PyLong_Digits(b); + const Py_ssize_t size = __Pyx_PyLong_SignedDigitCount(b); + switch (size) { + case 2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return (Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + } + } + #endif + return PyLong_AsSsize_t(b); + } + x = PyNumber_Index(b); + if (!x) return -1; + ival = PyInt_AsSsize_t(x); + Py_DECREF(x); + return ival; +} +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject* o) { + if (sizeof(Py_hash_t) == sizeof(Py_ssize_t)) { + return (Py_hash_t) __Pyx_PyIndex_AsSsize_t(o); +#if PY_MAJOR_VERSION < 3 + } else if (likely(PyInt_CheckExact(o))) { + return PyInt_AS_LONG(o); +#endif + } else { + Py_ssize_t ival; + PyObject *x; + x = PyNumber_Index(o); + if (!x) return -1; + ival = PyInt_AsLong(x); + Py_DECREF(x); + return ival; + } +} +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b) { + return b ? __Pyx_NewRef(Py_True) : __Pyx_NewRef(Py_False); +} +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t ival) { + return PyInt_FromSize_t(ival); +} + + +/* #### Code section: utility_code_pragmas_end ### */ +#ifdef _MSC_VER +#pragma warning( pop ) +#endif + + + +/* #### Code section: end ### */ +#endif /* Py_PYTHON_H */ diff --git a/rednose/helpers/ekf_sym_pyx.so b/rednose/helpers/ekf_sym_pyx.so new file mode 100755 index 0000000..63737dc Binary files /dev/null and b/rednose/helpers/ekf_sym_pyx.so differ diff --git a/rednose/logger/logger.h b/rednose/logger/logger.h deleted file mode 100644 index 8f541a2..0000000 --- a/rednose/logger/logger.h +++ /dev/null @@ -1,20 +0,0 @@ -#pragma once - -#ifdef SWAGLOG -#include SWAGLOG -#else - -#define CLOUDLOG_DEBUG 10 -#define CLOUDLOG_INFO 20 -#define CLOUDLOG_WARNING 30 -#define CLOUDLOG_ERROR 40 -#define CLOUDLOG_CRITICAL 50 - -#define cloudlog(lvl, fmt, ...) printf(fmt "\n", ## __VA_ARGS__) - -#define LOGD(fmt, ...) cloudlog(CLOUDLOG_DEBUG, fmt, ## __VA_ARGS__) -#define LOG(fmt, ...) cloudlog(CLOUDLOG_INFO, fmt, ## __VA_ARGS__) -#define LOGW(fmt, ...) cloudlog(CLOUDLOG_WARNING, fmt, ## __VA_ARGS__) -#define LOGE(fmt, ...) cloudlog(CLOUDLOG_ERROR, fmt, ## __VA_ARGS__) - -#endif diff --git a/release/build_devel.sh b/release/build_devel.sh deleted file mode 100755 index 8b6816e..0000000 --- a/release/build_devel.sh +++ /dev/null @@ -1,81 +0,0 @@ -#!/usr/bin/bash - -set -ex - -DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" - -SOURCE_DIR="$(git -C $DIR rev-parse --show-toplevel)" -if [ -z "$TARGET_DIR" ]; then - TARGET_DIR="$(mktemp -d)" -fi - -# set git identity -source $DIR/identity.sh - -echo "[-] Setting up target repo T=$SECONDS" - -rm -rf $TARGET_DIR -mkdir -p $TARGET_DIR -cd $TARGET_DIR -cp -r $SOURCE_DIR/.git $TARGET_DIR -pre-commit uninstall || true - -echo "[-] bringing master-ci and devel in sync T=$SECONDS" -cd $TARGET_DIR - -git fetch --depth 1 origin master-ci -git fetch --depth 1 origin devel - -git checkout -f --track origin/master-ci -git reset --hard master-ci -git checkout master-ci -git reset --hard origin/devel -git clean -xdff -git lfs uninstall - -# remove everything except .git -echo "[-] erasing old openpilot T=$SECONDS" -find . -maxdepth 1 -not -path './.git' -not -name '.' -not -name '..' -exec rm -rf '{}' \; - -# reset source tree -cd $SOURCE_DIR -git clean -xdff - -# do the files copy -echo "[-] copying files T=$SECONDS" -cd $SOURCE_DIR -cp -pR --parents $(cat release/files_*) $TARGET_DIR/ - -# in the directory -cd $TARGET_DIR -rm -f panda/board/obj/panda.bin.signed - -# include source commit hash and build date in commit -GIT_HASH=$(git --git-dir=$SOURCE_DIR/.git rev-parse HEAD) -DATETIME=$(date '+%Y-%m-%dT%H:%M:%S') -VERSION=$(cat $SOURCE_DIR/common/version.h | awk -F\" '{print $2}') - -echo "[-] committing version $VERSION T=$SECONDS" -git add -f . -git status -git commit -a -m "openpilot v$VERSION release - -date: $DATETIME -master commit: $GIT_HASH -" - -# ensure files are within GitHub's limit -BIG_FILES="$(find . -type f -not -path './.git/*' -size +95M)" -if [ ! -z "$BIG_FILES" ]; then - printf '\n\n\n' - echo "Found files exceeding GitHub's 100MB limit:" - echo "$BIG_FILES" - exit 1 -fi - -if [ ! -z "$BRANCH" ]; then - echo "[-] Pushing to $BRANCH T=$SECONDS" - git push -f origin master-ci:$BRANCH -fi - -echo "[-] done T=$SECONDS, ready at $TARGET_DIR" diff --git a/release/build_release.sh b/release/build_release.sh deleted file mode 100755 index fc15cf6..0000000 --- a/release/build_release.sh +++ /dev/null @@ -1,105 +0,0 @@ -#!/usr/bin/bash -e - -# git diff --name-status origin/release3-staging | grep "^A" | less - -DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" - -cd $DIR - -BUILD_DIR=/data/openpilot -SOURCE_DIR="$(git rev-parse --show-toplevel)" - -if [ -f /TICI ]; then - FILES_SRC="release/files_tici" -else - echo "no release files set" - exit 1 -fi - -if [ -z "$RELEASE_BRANCH" ]; then - echo "RELEASE_BRANCH is not set" - exit 1 -fi - - -# set git identity -source $DIR/identity.sh - -echo "[-] Setting up repo T=$SECONDS" -rm -rf $BUILD_DIR -mkdir -p $BUILD_DIR -cd $BUILD_DIR -git init -git remote add origin git@github.com:commaai/openpilot.git -git checkout --orphan $RELEASE_BRANCH - -# do the files copy -echo "[-] copying files T=$SECONDS" -cd $SOURCE_DIR -cp -pR --parents $(cat release/files_common) $BUILD_DIR/ -cp -pR --parents $(cat $FILES_SRC) $BUILD_DIR/ - -# in the directory -cd $BUILD_DIR - -rm -f panda/board/obj/panda.bin.signed -rm -f panda/board/obj/panda_h7.bin.signed - -VERSION=$(cat common/version.h | awk -F[\"-] '{print $2}') -echo "#define COMMA_VERSION \"$VERSION-release\"" > common/version.h - -echo "[-] committing version $VERSION T=$SECONDS" -git add -f . -git commit -a -m "openpilot v$VERSION release" - -# Build -export PYTHONPATH="$BUILD_DIR" -scons -j$(nproc) - -# release panda fw -CERT=/data/pandaextra/certs/release RELEASE=1 scons -j$(nproc) panda/ - -# Ensure no submodules in release -if test "$(git submodule--helper list | wc -l)" -gt "0"; then - echo "submodules found:" - git submodule--helper list - exit 1 -fi -git submodule status - -# Cleanup -find . -name '*.a' -delete -find . -name '*.o' -delete -find . -name '*.os' -delete -find . -name '*.pyc' -delete -find . -name 'moc_*' -delete -find . -name '__pycache__' -delete -rm -rf .sconsign.dblite Jenkinsfile release/ -rm selfdrive/modeld/models/supercombo.onnx - -# Restore third_party -git checkout third_party/ - -# Mark as prebuilt release -touch prebuilt - -# Add built files to git -git add -f . -git commit --amend -m "openpilot v$VERSION" - -# Run tests -TEST_FILES="tools/" -cd $SOURCE_DIR -cp -pR -n --parents $TEST_FILES $BUILD_DIR/ -cd $BUILD_DIR -RELEASE=1 selfdrive/test/test_onroad.py -#selfdrive/manager/test/test_manager.py -selfdrive/car/tests/test_car_interfaces.py -rm -rf $TEST_FILES - -if [ ! -z "$RELEASE_BRANCH" ]; then - echo "[-] pushing release T=$SECONDS" - git push -f origin $RELEASE_BRANCH:$RELEASE_BRANCH -fi - -echo "[-] done T=$SECONDS" diff --git a/release/check-dirty.sh b/release/check-dirty.sh deleted file mode 100755 index 9c6389f..0000000 --- a/release/check-dirty.sh +++ /dev/null @@ -1,11 +0,0 @@ -#!/usr/bin/bash -set -e - -DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" -cd $DIR - -if [ ! -z "$(git status --porcelain)" ]; then - echo "Dirty working tree after build:" - git status --porcelain - exit 1 -fi diff --git a/release/check-submodules.sh b/release/check-submodules.sh deleted file mode 100755 index 5f4e307..0000000 --- a/release/check-submodules.sh +++ /dev/null @@ -1,12 +0,0 @@ -#!/bin/bash - -while read hash submodule ref; do - git -C $submodule fetch --depth 1000 origin master - git -C $submodule branch -r --contains $hash | grep "origin/master" - if [ "$?" -eq 0 ]; then - echo "$submodule ok" - else - echo "$submodule: $hash is not on master" - exit 1 - fi -done <<< $(git submodule status --recursive) diff --git a/release/files_common b/release/files_common deleted file mode 100644 index 40daff2..0000000 --- a/release/files_common +++ /dev/null @@ -1,565 +0,0 @@ -.gitignore -LICENSE -launch_env.sh -launch_chffrplus.sh -launch_openpilot.sh - -Jenkinsfile -SConstruct -pyproject.toml - -README.md -RELEASES.md -docs/CARS.md -docs/CONTRIBUTING.md -docs/INTEGRATION.md -docs/LIMITATIONS.md -site_scons/site_tools/cython.py - -openpilot/__init__.py -openpilot/** - -common/.gitignore -common/__init__.py -common/*.py -common/*.pyx - -common/transformations/__init__.py -common/transformations/camera.py -common/transformations/model.py - -common/transformations/SConscript -common/transformations/coordinates.py -common/transformations/coordinates.cc -common/transformations/coordinates.hpp -common/transformations/orientation.py -common/transformations/orientation.cc -common/transformations/orientation.hpp -common/transformations/transformations.pxd -common/transformations/transformations.pyx - -common/api/__init__.py - -release/* - -tools/__init__.py -tools/lib/* -tools/bodyteleop/* -tools/joystick/* -tools/replay/*.cc -tools/replay/*.h - -selfdrive/__init__.py -selfdrive/sentry.py -selfdrive/tombstoned.py -selfdrive/updated.py -selfdrive/statsd.py - -system/logmessaged.py -system/micd.py -system/version.py - -selfdrive/athena/__init__.py -selfdrive/athena/athenad.py -selfdrive/athena/manage_athenad.py -selfdrive/athena/registration.py - -selfdrive/boardd/.gitignore -selfdrive/boardd/SConscript -selfdrive/boardd/__init__.py -selfdrive/boardd/boardd.cc -selfdrive/boardd/boardd.h -selfdrive/boardd/main.cc -selfdrive/boardd/boardd.py -selfdrive/boardd/boardd_api_impl.pyx -selfdrive/boardd/can_list_to_can_capnp.cc -selfdrive/boardd/panda.cc -selfdrive/boardd/panda.h -selfdrive/boardd/spi.cc -selfdrive/boardd/panda_comms.h -selfdrive/boardd/panda_comms.cc -selfdrive/boardd/set_time.py -selfdrive/boardd/pandad.py -selfdrive/boardd/tests/test_boardd_loopback.py - -selfdrive/car/__init__.py -selfdrive/car/docs_definitions.py -selfdrive/car/car_helpers.py -selfdrive/car/fingerprints.py -selfdrive/car/interfaces.py -selfdrive/car/vin.py -selfdrive/car/disable_ecu.py -selfdrive/car/fw_versions.py -selfdrive/car/fw_query_definitions.py -selfdrive/car/ecu_addrs.py -selfdrive/car/isotp_parallel_query.py -selfdrive/car/tests/__init__.py -selfdrive/car/tests/test_car_interfaces.py -selfdrive/car/torque_data/* - -selfdrive/car/body/*.py -selfdrive/car/chrysler/*.py -selfdrive/car/ford/*.py -selfdrive/car/gm/*.py -selfdrive/car/honda/*.py -selfdrive/car/hyundai/*.py -selfdrive/car/mazda/*.py -selfdrive/car/mock/*.py -selfdrive/car/nissan/*.py -selfdrive/car/subaru/*.py -selfdrive/car/tesla/*.py -selfdrive/car/toyota/*.py -selfdrive/car/volkswagen/*.py - -selfdrive/debug/can_printer.py -selfdrive/debug/check_freq.py -selfdrive/debug/dump.py -selfdrive/debug/filter_log_message.py -selfdrive/debug/format_fingerprints.py -selfdrive/debug/get_fingerprint.py -selfdrive/debug/uiview.py - -selfdrive/debug/hyundai_enable_radar_points.py -selfdrive/debug/vw_mqb_config.py - -common/SConscript -common/version.h - -common/*.h -common/*.cc - -selfdrive/controls/__init__.py -selfdrive/controls/controlsd.py -selfdrive/controls/plannerd.py -selfdrive/controls/radard.py -selfdrive/controls/lib/__init__.py -selfdrive/controls/lib/alertmanager.py -selfdrive/controls/lib/alerts_offroad.json -selfdrive/controls/lib/desire_helper.py -selfdrive/controls/lib/drive_helpers.py -selfdrive/controls/lib/events.py -selfdrive/controls/lib/latcontrol_angle.py -selfdrive/controls/lib/latcontrol_torque.py -selfdrive/controls/lib/latcontrol_pid.py -selfdrive/controls/lib/latcontrol.py -selfdrive/controls/lib/longcontrol.py -selfdrive/controls/lib/longitudinal_planner.py -selfdrive/controls/lib/pid.py -selfdrive/controls/lib/vehicle_model.py - -selfdrive/controls/lib/lateral_mpc_lib/.gitignore -selfdrive/controls/lib/longitudinal_mpc_lib/.gitignore -selfdrive/controls/lib/lateral_mpc_lib/* -selfdrive/controls/lib/longitudinal_mpc_lib/* - -system/__init__.py -system/*.py - -system/hardware/__init__.py -system/hardware/base.h -system/hardware/base.py -system/hardware/hw.h -system/hardware/hw.py -system/hardware/tici/__init__.py -system/hardware/tici/hardware.h -system/hardware/tici/hardware.py -system/hardware/tici/pins.py -system/hardware/tici/agnos.py -system/hardware/tici/casync.py -system/hardware/tici/agnos.json -system/hardware/tici/amplifier.py -system/hardware/tici/updater -system/hardware/tici/iwlist.py -system/hardware/tici/esim.nmconnection -system/hardware/pc/__init__.py -system/hardware/pc/hardware.h -system/hardware/pc/hardware.py - -system/ubloxd/.gitignore -system/ubloxd/SConscript -system/ubloxd/generated/* -system/ubloxd/*.h -system/ubloxd/*.cc - -selfdrive/locationd/__init__.py -selfdrive/locationd/SConscript -selfdrive/locationd/.gitignore -selfdrive/locationd/locationd.h -selfdrive/locationd/locationd.cc -selfdrive/locationd/paramsd.py -selfdrive/locationd/models/__init__.py -selfdrive/locationd/models/.gitignore -selfdrive/locationd/models/car_kf.py -selfdrive/locationd/models/live_kf.py -selfdrive/locationd/models/live_kf.h -selfdrive/locationd/models/live_kf.cc -selfdrive/locationd/models/constants.py - -selfdrive/locationd/torqued.py -selfdrive/locationd/calibrationd.py -selfdrive/locationd/helpers.py - -system/logcatd/.gitignore -system/logcatd/SConscript -system/logcatd/logcatd_systemd.cc - -system/proclogd/SConscript -system/proclogd/main.cc -system/proclogd/proclog.cc -system/proclogd/proclog.h - -system/loggerd/.gitignore -system/loggerd/SConscript -system/loggerd/encoder/encoder.cc -system/loggerd/encoder/encoder.h -system/loggerd/encoder/v4l_encoder.cc -system/loggerd/encoder/v4l_encoder.h -system/loggerd/video_writer.cc -system/loggerd/video_writer.h -system/loggerd/logger.cc -system/loggerd/logger.h -system/loggerd/loggerd.cc -system/loggerd/loggerd.h -system/loggerd/encoderd.cc -system/loggerd/bootlog.cc -system/loggerd/encoder/ffmpeg_encoder.cc -system/loggerd/encoder/ffmpeg_encoder.h - -system/loggerd/__init__.py -system/loggerd/config.py -system/loggerd/uploader.py -system/loggerd/deleter.py -system/loggerd/xattr_cache.py - -system/sensord/.gitignore -system/sensord/SConscript -system/sensord/sensors_qcom2.cc -system/sensord/sensors/*.cc -system/sensord/sensors/*.h -system/sensord/pigeond.py - -system/webrtc/__init__.py -system/webrtc/webrtcd.py -system/webrtc/schema.py -system/webrtc/device/audio.py -system/webrtc/device/video.py - -selfdrive/thermald/thermald.py -selfdrive/thermald/power_monitoring.py -selfdrive/thermald/fan_controller.py - -selfdrive/test/__init__.py -selfdrive/test/fuzzy_generation.py -selfdrive/test/helpers.py -selfdrive/test/setup_device_ci.sh -selfdrive/test/test_onroad.py -selfdrive/test/test_time_to_onroad.py - -selfdrive/ui/.gitignore -selfdrive/ui/SConscript -selfdrive/ui/*.cc -selfdrive/ui/*.h -selfdrive/ui/text -selfdrive/ui/spinner -selfdrive/ui/soundd.py -selfdrive/ui/translations/*.ts -selfdrive/ui/translations/languages.json -selfdrive/ui/update_translations.py -selfdrive/ui/tests/test_translations.py - -selfdrive/ui/qt/*.cc -selfdrive/ui/qt/*.h -selfdrive/ui/qt/network/*.cc -selfdrive/ui/qt/network/*.h -selfdrive/ui/qt/offroad/*.cc -selfdrive/ui/qt/offroad/*.h -selfdrive/ui/qt/offroad/*.qml -selfdrive/ui/qt/widgets/*.cc -selfdrive/ui/qt/widgets/*.h -selfdrive/ui/qt/maps/*.cc -selfdrive/ui/qt/maps/*.h -selfdrive/ui/qt/setup/*.cc -selfdrive/ui/qt/setup/*.h - -selfdrive/ui/installer/*.cc -selfdrive/ui/installer/*.h -selfdrive/ui/installer/*.cc - -system/camerad/SConscript -system/camerad/main.cc - -system/camerad/snapshot/* -system/camerad/cameras/camera_common.h -system/camerad/cameras/camera_common.cc -system/camerad/sensors/*.h -system/camerad/sensors/*.cc - -selfdrive/manager/__init__.py -selfdrive/manager/build.py -selfdrive/manager/helpers.py -selfdrive/manager/manager.py -selfdrive/manager/process_config.py -selfdrive/manager/process.py -selfdrive/manager/test/__init__.py -selfdrive/manager/test/test_manager.py - -selfdrive/modeld/.gitignore -selfdrive/modeld/__init__.py -selfdrive/modeld/SConscript -selfdrive/modeld/modeld.py -selfdrive/modeld/parse_model_outputs.py -selfdrive/modeld/fill_model_msg.py -selfdrive/modeld/get_model_metadata.py -selfdrive/modeld/navmodeld.py -selfdrive/modeld/dmonitoringmodeld.py -selfdrive/modeld/constants.py -selfdrive/modeld/modeld - -selfdrive/modeld/models/__init__.py -selfdrive/modeld/models/*.pxd -selfdrive/modeld/models/*.pyx - -selfdrive/modeld/models/commonmodel.cc -selfdrive/modeld/models/commonmodel.h - -selfdrive/modeld/models/supercombo.onnx - -selfdrive/modeld/models/dmonitoring_model_q.dlc - -selfdrive/modeld/models/navmodel_q.dlc - -selfdrive/modeld/transforms/loadyuv.cc -selfdrive/modeld/transforms/loadyuv.h -selfdrive/modeld/transforms/loadyuv.cl -selfdrive/modeld/transforms/transform.cc -selfdrive/modeld/transforms/transform.h -selfdrive/modeld/transforms/transform.cl - -selfdrive/modeld/thneed/*.py -selfdrive/modeld/thneed/thneed.h -selfdrive/modeld/thneed/thneed_common.cc -selfdrive/modeld/thneed/thneed_qcom2.cc -selfdrive/modeld/thneed/serialize.cc - -selfdrive/modeld/runners/__init__.py -selfdrive/modeld/runners/*.pxd -selfdrive/modeld/runners/*.pyx -selfdrive/modeld/runners/*.cc -selfdrive/modeld/runners/*.h -selfdrive/modeld/runners/*.py - -selfdrive/monitoring/dmonitoringd.py -selfdrive/monitoring/driver_monitor.py - -selfdrive/navd/.gitignore -selfdrive/navd/__init__.py -selfdrive/navd/** - -selfdrive/assets/.gitignore -selfdrive/assets/assets.qrc -selfdrive/assets/*.png -selfdrive/assets/*.svg -selfdrive/assets/body/* -selfdrive/assets/fonts/*.ttf -selfdrive/assets/icons/* -selfdrive/assets/images/* -selfdrive/assets/offroad/* -selfdrive/assets/sounds/* -selfdrive/assets/training/* -selfdrive/assets/navigation/* - -third_party/.gitignore -third_party/SConscript - -third_party/linux/** -third_party/opencl/** - -third_party/json11/json11.cpp -third_party/json11/json11.hpp - -third_party/qrcode/*.cc -third_party/qrcode/*.hpp - -third_party/kaitai/*.h -third_party/kaitai/*.cpp - -third_party/libyuv/include/** - -third_party/snpe/include/** -third_party/snpe/dsp** - -third_party/acados/.gitignore -third_party/acados/include/** -third_party/acados/acados_template/** - -third_party/bootstrap/** -third_party/qt5/larch64/bin/** -third_party/maplibre-native-qt/** - -scripts/update_now.sh -scripts/stop_updater.sh - -teleoprtc/** - -rednose_repo/site_scons/site_tools/rednose_filter.py -rednose/.gitignore -rednose/** - -body/.gitignore -body/board/SConscript -body/board/*.h -body/board/*.c -body/board/*.s -body/board/*.ld -body/board/inc/** -body/board/obj/ -body/board/bldc/** -body/board/drivers/** -body/certs/** -body/crypto/** - -cereal/.gitignore -cereal/__init__.py -cereal/car.capnp -cereal/custom.capnp -cereal/legacy.capnp -cereal/log.capnp -cereal/services.py -cereal/SConscript -cereal/include/** -cereal/logger/logger.h -cereal/messaging/.gitignore -cereal/messaging/__init__.py -cereal/messaging/bridge.cc -cereal/messaging/event.cc -cereal/messaging/event.h -cereal/messaging/impl_fake.cc -cereal/messaging/impl_fake.h -cereal/messaging/impl_msgq.cc -cereal/messaging/impl_msgq.h -cereal/messaging/impl_zmq.cc -cereal/messaging/impl_zmq.h -cereal/messaging/messaging.cc -cereal/messaging/messaging.h -cereal/messaging/messaging.pxd -cereal/messaging/messaging_pyx.pyx -cereal/messaging/msgq.cc -cereal/messaging/msgq.h -cereal/messaging/socketmaster.cc -cereal/visionipc/.gitignore -cereal/visionipc/__init__.py -cereal/visionipc/*.cc -cereal/visionipc/*.h -cereal/visionipc/*.pyx -cereal/visionipc/*.pxd - -panda/.gitignore -panda/__init__.py -panda/SConscript -panda/board/** -panda/certs/** -panda/crypto/** -panda/examples/query_fw_versions.py -panda/python/** - -opendbc/.gitignore -opendbc/__init__.py -opendbc/can/__init__.py -opendbc/can/SConscript -opendbc/can/can_define.py -opendbc/can/common.cc -opendbc/can/common.h -opendbc/can/common.pxd -opendbc/can/common_dbc.h -opendbc/can/dbc.cc -opendbc/can/packer.cc -opendbc/can/packer.py -opendbc/can/packer_pyx.pyx -opendbc/can/parser.cc -opendbc/can/parser.py -opendbc/can/parser_pyx.pyx - -opendbc/comma_body.dbc - -opendbc/chrysler_ram_hd_generated.dbc -opendbc/chrysler_ram_dt_generated.dbc -opendbc/chrysler_pacifica_2017_hybrid_generated.dbc -opendbc/chrysler_pacifica_2017_hybrid_private_fusion.dbc - -opendbc/gm_global_a_powertrain_generated.dbc -opendbc/gm_global_a_object.dbc -opendbc/gm_global_a_chassis.dbc - -opendbc/FORD_CADS.dbc -opendbc/ford_fusion_2018_adas.dbc -opendbc/ford_lincoln_base_pt.dbc - -opendbc/honda_accord_2018_can_generated.dbc -opendbc/acura_ilx_2016_can_generated.dbc -opendbc/acura_rdx_2018_can_generated.dbc -opendbc/acura_rdx_2020_can_generated.dbc -opendbc/honda_civic_touring_2016_can_generated.dbc -opendbc/honda_civic_hatchback_ex_2017_can_generated.dbc -opendbc/honda_crv_touring_2016_can_generated.dbc -opendbc/honda_crv_ex_2017_can_generated.dbc -opendbc/honda_crv_ex_2017_body_generated.dbc -opendbc/honda_crv_executive_2016_can_generated.dbc -opendbc/honda_fit_ex_2018_can_generated.dbc -opendbc/honda_odyssey_exl_2018_generated.dbc -opendbc/honda_odyssey_extreme_edition_2018_china_can_generated.dbc -opendbc/honda_insight_ex_2019_can_generated.dbc -opendbc/acura_ilx_2016_nidec.dbc -opendbc/honda_civic_ex_2022_can_generated.dbc - -opendbc/hyundai_canfd.dbc -opendbc/hyundai_kia_generic.dbc -opendbc/hyundai_kia_mando_front_radar_generated.dbc - -opendbc/mazda_2017.dbc - -opendbc/nissan_x_trail_2017_generated.dbc -opendbc/nissan_leaf_2018_generated.dbc - -opendbc/subaru_global_2017_generated.dbc -opendbc/subaru_global_2020_hybrid_generated.dbc -opendbc/subaru_outback_2015_generated.dbc -opendbc/subaru_outback_2019_generated.dbc -opendbc/subaru_forester_2017_generated.dbc - -opendbc/toyota_tnga_k_pt_generated.dbc -opendbc/toyota_new_mc_pt_generated.dbc -opendbc/toyota_nodsu_pt_generated.dbc -opendbc/toyota_adas.dbc -opendbc/toyota_tss2_adas.dbc - -opendbc/vw_golf_mk4.dbc -opendbc/vw_mqb_2010.dbc - -opendbc/tesla_can.dbc -opendbc/tesla_radar.dbc -opendbc/tesla_powertrain.dbc - -tinygrad_repo/openpilot/compile2.py -tinygrad_repo/extra/onnx.py -tinygrad_repo/extra/onnx_ops.py -tinygrad_repo/extra/thneed.py -tinygrad_repo/extra/utils.py -tinygrad_repo/tinygrad/codegen/kernel.py -tinygrad_repo/tinygrad/codegen/linearizer.py -tinygrad_repo/tinygrad/features/image.py -tinygrad_repo/tinygrad/features/search.py -tinygrad_repo/tinygrad/nn/* -tinygrad_repo/tinygrad/renderer/cstyle.py -tinygrad_repo/tinygrad/renderer/opencl.py -tinygrad_repo/tinygrad/runtime/lib.py -tinygrad_repo/tinygrad/runtime/ops_cpu.py -tinygrad_repo/tinygrad/runtime/ops_disk.py -tinygrad_repo/tinygrad/runtime/ops_gpu.py -tinygrad_repo/tinygrad/shape/* -tinygrad_repo/tinygrad/*.py - -selfdrive/frogpilot/functions/conditional_experimental_mode.py -selfdrive/frogpilot/functions/frogpilot_functions.py -selfdrive/frogpilot/functions/frogpilot_planner.py -selfdrive/frogpilot/functions/map_turn_speed_controller.py -selfdrive/frogpilot/functions/speed_limit_controller.py diff --git a/release/files_pc b/release/files_pc deleted file mode 100644 index f2bf090..0000000 --- a/release/files_pc +++ /dev/null @@ -1,4 +0,0 @@ -third_party/libyuv/x86_64/** -third_party/snpe/x86_64/** -third_party/snpe/x86_64-linux-clang/** -third_party/acados/x86_64/** diff --git a/release/files_tici b/release/files_tici deleted file mode 100644 index 1771c45..0000000 --- a/release/files_tici +++ /dev/null @@ -1,15 +0,0 @@ -third_party/libyuv/larch64/** -third_party/snpe/larch64** -third_party/snpe/aarch64-ubuntu-gcc7.5/* -third_party/acados/larch64/** - -system/camerad/cameras/camera_qcom2.cc -system/camerad/cameras/camera_qcom2.h -system/camerad/cameras/camera_util.cc -system/camerad/cameras/camera_util.h -system/camerad/cameras/real_debayer.cl - -system/qcomgpsd/* - -selfdrive/ui/qt/spinner_larch64 -selfdrive/ui/qt/text_larch64 diff --git a/release/identity.sh b/release/identity.sh deleted file mode 100644 index c699c94..0000000 --- a/release/identity.sh +++ /dev/null @@ -1,4 +0,0 @@ -export GIT_COMMITTER_NAME="Vehicle Researcher" -export GIT_COMMITTER_EMAIL="user@comma.ai" -export GIT_AUTHOR_NAME="Vehicle Researcher" -export GIT_AUTHOR_EMAIL="user@comma.ai" diff --git a/release/verify.sh b/release/verify.sh deleted file mode 100755 index ec5266b..0000000 --- a/release/verify.sh +++ /dev/null @@ -1,16 +0,0 @@ -#!/bin/bash - -set -e - -RED="\033[0;31m" -GREEN="\033[0;32m" -CLEAR="\033[0m" - -BRANCHES="devel release3" -for b in $BRANCHES; do - if git diff --quiet origin/$b origin/$b-staging && [ "$(git rev-parse origin/$b)" = "$(git rev-parse origin/$b-staging)" ]; then - printf "%-10s $GREEN ok $CLEAR\n" "$b" - else - printf "%-10s $RED mismatch $CLEAR\n" "$b" - fi -done diff --git a/selfdrive/assets/translations_assets.qrc b/selfdrive/assets/translations_assets.qrc new file mode 100644 index 0000000..b70d213 --- /dev/null +++ b/selfdrive/assets/translations_assets.qrc @@ -0,0 +1,15 @@ + + +../ui/translations/main_en.qm +../ui/translations/main_de.qm +../ui/translations/main_fr.qm +../ui/translations/main_pt-BR.qm +../ui/translations/main_tr.qm +../ui/translations/main_ar.qm +../ui/translations/main_th.qm +../ui/translations/main_zh-CHT.qm +../ui/translations/main_zh-CHS.qm +../ui/translations/main_ko.qm +../ui/translations/main_ja.qm + + \ No newline at end of file diff --git a/selfdrive/boardd/SConscript b/selfdrive/boardd/SConscript deleted file mode 100644 index 666763d..0000000 --- a/selfdrive/boardd/SConscript +++ /dev/null @@ -1,11 +0,0 @@ -Import('env', 'envCython', 'common', 'cereal', 'messaging') - -libs = ['usb-1.0', common, cereal, messaging, 'pthread', 'zmq', 'capnp', 'kj'] -panda = env.Library('panda', ['panda.cc', 'panda_comms.cc', 'spi.cc']) - -env.Program('boardd', ['main.cc', 'boardd.cc'], LIBS=[panda] + libs) -env.Library('libcan_list_to_can_capnp', ['can_list_to_can_capnp.cc']) - -envCython.Program('boardd_api_impl.so', 'boardd_api_impl.pyx', LIBS=["can_list_to_can_capnp", 'capnp', 'kj'] + envCython["LIBS"]) -if GetOption('extras'): - env.Program('tests/test_boardd_usbprotocol', ['tests/test_boardd_usbprotocol.cc'], LIBS=[panda] + libs) diff --git a/selfdrive/boardd/boardd b/selfdrive/boardd/boardd new file mode 100755 index 0000000..0b23fed Binary files /dev/null and b/selfdrive/boardd/boardd differ diff --git a/selfdrive/boardd/boardd.cc b/selfdrive/boardd/boardd.cc deleted file mode 100644 index b2b59d3..0000000 --- a/selfdrive/boardd/boardd.cc +++ /dev/null @@ -1,641 +0,0 @@ -#include "selfdrive/boardd/boardd.h" - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include "cereal/gen/cpp/car.capnp.h" -#include "cereal/messaging/messaging.h" -#include "common/params.h" -#include "common/ratekeeper.h" -#include "common/swaglog.h" -#include "common/timing.h" -#include "common/util.h" -#include "system/hardware/hw.h" - -// -- Multi-panda conventions -- -// Ordering: -// - The internal panda will always be the first panda -// - Consecutive pandas will be sorted based on panda type, and then serial number -// Connecting: -// - If a panda connection is dropped, boardd will reconnect to all pandas -// - If a panda is added, we will only reconnect when we are offroad -// CAN buses: -// - Each panda will have it's block of 4 buses. E.g.: the second panda will use -// bus numbers 4, 5, 6 and 7 -// - The internal panda will always be used for accessing the OBD2 port, -// and thus firmware queries -// Safety: -// - SafetyConfig is a list, which is mapped to the connected pandas -// - If there are more pandas connected than there are SafetyConfigs, -// the excess pandas will remain in "silent" or "noOutput" mode -// Ignition: -// - If any of the ignition sources in any panda is high, ignition is high - -#define MAX_IR_POWER 0.5f -#define MIN_IR_POWER 0.0f -#define CUTOFF_IL 400 -#define SATURATE_IL 1000 -using namespace std::chrono_literals; - -std::atomic ignition(false); - -ExitHandler do_exit; - -static std::string get_time_str(const struct tm &time) { - char s[30] = {'\0'}; - std::strftime(s, std::size(s), "%Y-%m-%d %H:%M:%S", &time); - return s; -} - -bool check_all_connected(const std::vector &pandas) { - for (const auto& panda : pandas) { - if (!panda->connected()) { - do_exit = true; - return false; - } - } - return true; -} - -enum class SyncTimeDir { TO_PANDA, FROM_PANDA }; - -void sync_time(Panda *panda, SyncTimeDir dir) { - if (!panda->has_rtc) return; - - setenv("TZ", "UTC", 1); - struct tm sys_time = util::get_time(); - struct tm rtc_time = panda->get_rtc(); - - if (dir == SyncTimeDir::TO_PANDA) { - if (util::time_valid(sys_time)) { - // Write time to RTC if it looks reasonable - double seconds = difftime(mktime(&rtc_time), mktime(&sys_time)); - if (std::abs(seconds) > 1.1) { - panda->set_rtc(sys_time); - LOGW("Updating panda RTC. dt = %.2f System: %s RTC: %s", - seconds, get_time_str(sys_time).c_str(), get_time_str(rtc_time).c_str()); - } - } - } else if (dir == SyncTimeDir::FROM_PANDA) { - LOGW("System time: %s, RTC time: %s", get_time_str(sys_time).c_str(), get_time_str(rtc_time).c_str()); - - if (!util::time_valid(sys_time) && util::time_valid(rtc_time)) { - const struct timeval tv = {mktime(&rtc_time), 0}; - settimeofday(&tv, 0); - LOGE("System time wrong, setting from RTC."); - } - } -} - -bool safety_setter_thread(std::vector pandas) { - LOGD("Starting safety setter thread"); - - Params p; - - // there should be at least one panda connected - if (pandas.size() == 0) { - return false; - } - - // initialize to ELM327 without OBD multiplexing for fingerprinting - bool obd_multiplexing_enabled = false; - for (int i = 0; i < pandas.size(); i++) { - pandas[i]->set_safety_model(cereal::CarParams::SafetyModel::ELM327, 1U); - } - - // openpilot can switch between multiplexing modes for different FW queries - while (true) { - if (do_exit || !check_all_connected(pandas) || !ignition) { - return false; - } - - bool obd_multiplexing_requested = p.getBool("ObdMultiplexingEnabled"); - if (obd_multiplexing_requested != obd_multiplexing_enabled) { - for (int i = 0; i < pandas.size(); i++) { - const uint16_t safety_param = (i > 0 || !obd_multiplexing_requested) ? 1U : 0U; - pandas[i]->set_safety_model(cereal::CarParams::SafetyModel::ELM327, safety_param); - } - obd_multiplexing_enabled = obd_multiplexing_requested; - p.putBool("ObdMultiplexingChanged", true); - } - - if (p.getBool("FirmwareQueryDone")) { - LOGW("finished FW query"); - break; - } - util::sleep_for(20); - } - - std::string params; - LOGW("waiting for params to set safety model"); - while (true) { - if (do_exit || !check_all_connected(pandas) || !ignition) { - return false; - } - - if (p.getBool("ControlsReady")) { - params = p.get("CarParams"); - if (params.size() > 0) break; - } - util::sleep_for(100); - } - LOGW("got %lu bytes CarParams", params.size()); - - AlignedBuffer aligned_buf; - capnp::FlatArrayMessageReader cmsg(aligned_buf.align(params.data(), params.size())); - cereal::CarParams::Reader car_params = cmsg.getRoot(); - cereal::CarParams::SafetyModel safety_model; - uint16_t safety_param; - - auto safety_configs = car_params.getSafetyConfigs(); - uint16_t alternative_experience = car_params.getAlternativeExperience(); - for (uint32_t i = 0; i < pandas.size(); i++) { - auto panda = pandas[i]; - - if (safety_configs.size() > i) { - safety_model = safety_configs[i].getSafetyModel(); - safety_param = safety_configs[i].getSafetyParam(); - } else { - // If no safety mode is specified, default to silent - safety_model = cereal::CarParams::SafetyModel::SILENT; - safety_param = 0U; - } - - LOGW("panda %d: setting safety model: %d, param: %d, alternative experience: %d", i, (int)safety_model, safety_param, alternative_experience); - panda->set_alternative_experience(alternative_experience); - panda->set_safety_model(safety_model, safety_param); - } - - return true; -} - -Panda *connect(std::string serial="", uint32_t index=0) { - std::unique_ptr panda; - try { - panda = std::make_unique(serial, (index * PANDA_BUS_CNT)); - } catch (std::exception &e) { - return nullptr; - } - - // common panda config - if (getenv("BOARDD_LOOPBACK")) { - panda->set_loopback(true); - } - //panda->enable_deepsleep(); - - if (!panda->up_to_date() && !getenv("BOARDD_SKIP_FW_CHECK")) { - throw std::runtime_error("Panda firmware out of date. Run pandad.py to update."); - } - - sync_time(panda.get(), SyncTimeDir::FROM_PANDA); - return panda.release(); -} - -void can_send_thread(std::vector pandas, bool fake_send) { - util::set_thread_name("boardd_can_send"); - - AlignedBuffer aligned_buf; - std::unique_ptr context(Context::create()); - std::unique_ptr subscriber(SubSocket::create(context.get(), "sendcan")); - assert(subscriber != NULL); - subscriber->setTimeout(100); - - // run as fast as messages come in - while (!do_exit && check_all_connected(pandas)) { - std::unique_ptr msg(subscriber->receive()); - if (!msg) { - if (errno == EINTR) { - do_exit = true; - } - continue; - } - - capnp::FlatArrayMessageReader cmsg(aligned_buf.align(msg.get())); - cereal::Event::Reader event = cmsg.getRoot(); - - // Don't send if older than 1 second - if ((nanos_since_boot() - event.getLogMonoTime() < 1e9) && !fake_send) { - for (const auto& panda : pandas) { - LOGT("sending sendcan to panda: %s", (panda->hw_serial()).c_str()); - panda->can_send(event.getSendcan()); - LOGT("sendcan sent to panda: %s", (panda->hw_serial()).c_str()); - } - } else { - LOGE("sendcan too old to send: %" PRIu64 ", %" PRIu64, nanos_since_boot(), event.getLogMonoTime()); - } - } -} - -void can_recv_thread(std::vector pandas) { - util::set_thread_name("boardd_can_recv"); - - PubMaster pm({"can"}); - - // run at 100Hz - RateKeeper rk("boardd_can_recv", 100); - std::vector raw_can_data; - - while (!do_exit && check_all_connected(pandas)) { - bool comms_healthy = true; - raw_can_data.clear(); - for (const auto& panda : pandas) { - comms_healthy &= panda->can_receive(raw_can_data); - } - - MessageBuilder msg; - auto evt = msg.initEvent(); - evt.setValid(comms_healthy); - auto canData = evt.initCan(raw_can_data.size()); - for (uint i = 0; i send_panda_states(PubMaster *pm, const std::vector &pandas, bool spoofing_started) { - bool ignition_local = false; - const uint32_t pandas_cnt = pandas.size(); - - // build msg - MessageBuilder msg; - auto evt = msg.initEvent(); - auto pss = evt.initPandaStates(pandas_cnt); - - std::vector pandaStates; - pandaStates.reserve(pandas_cnt); - - std::vector> pandaCanStates; - pandaCanStates.reserve(pandas_cnt); - - const bool red_panda_comma_three = (pandas.size() == 2) && - (pandas[0]->hw_type == cereal::PandaState::PandaType::DOS) && - (pandas[1]->hw_type == cereal::PandaState::PandaType::RED_PANDA); - - for (const auto& panda : pandas){ - auto health_opt = panda->get_state(); - if (!health_opt) { - return std::nullopt; - } - - health_t health = *health_opt; - - std::array can_health{}; - for (uint32_t i = 0; i < PANDA_CAN_CNT; i++) { - auto can_health_opt = panda->get_can_state(i); - if (!can_health_opt) { - return std::nullopt; - } - can_health[i] = *can_health_opt; - } - pandaCanStates.push_back(can_health); - - if (spoofing_started) { - health.ignition_line_pkt = 1; - } - - // on comma three setups with a red panda, the dos can - // get false positive ignitions due to the harness box - // without a harness connector, so ignore it - if (red_panda_comma_three && (panda->hw_type == cereal::PandaState::PandaType::DOS)) { - health.ignition_line_pkt = 0; - } - - ignition_local |= ((health.ignition_line_pkt != 0) || (health.ignition_can_pkt != 0)); - - pandaStates.push_back(health); - } - - for (uint32_t i = 0; i < pandas_cnt; i++) { - auto panda = pandas[i]; - const auto &health = pandaStates[i]; - - // Make sure CAN buses are live: safety_setter_thread does not work if Panda CAN are silent and there is only one other CAN node - if (health.safety_mode_pkt == (uint8_t)(cereal::CarParams::SafetyModel::SILENT)) { - panda->set_safety_model(cereal::CarParams::SafetyModel::NO_OUTPUT); - } - - bool power_save_desired = !ignition_local; - if (health.power_save_enabled_pkt != power_save_desired) { - panda->set_power_saving(power_save_desired); - } - - // set safety mode to NO_OUTPUT when car is off. ELM327 is an alternative if we want to leverage athenad/connect - if (!ignition_local && (health.safety_mode_pkt != (uint8_t)(cereal::CarParams::SafetyModel::NO_OUTPUT))) { - panda->set_safety_model(cereal::CarParams::SafetyModel::NO_OUTPUT); - } - - if (!panda->comms_healthy()) { - evt.setValid(false); - } - - auto ps = pss[i]; - ps.setVoltage(health.voltage_pkt); - ps.setCurrent(health.current_pkt); - ps.setUptime(health.uptime_pkt); - ps.setSafetyTxBlocked(health.safety_tx_blocked_pkt); - ps.setSafetyRxInvalid(health.safety_rx_invalid_pkt); - ps.setIgnitionLine(health.ignition_line_pkt); - ps.setIgnitionCan(health.ignition_can_pkt); - ps.setControlsAllowed(health.controls_allowed_pkt); - ps.setTxBufferOverflow(health.tx_buffer_overflow_pkt); - ps.setRxBufferOverflow(health.rx_buffer_overflow_pkt); - ps.setGmlanSendErrs(health.gmlan_send_errs_pkt); - ps.setPandaType(panda->hw_type); - ps.setSafetyModel(cereal::CarParams::SafetyModel(health.safety_mode_pkt)); - ps.setSafetyParam(health.safety_param_pkt); - ps.setFaultStatus(cereal::PandaState::FaultStatus(health.fault_status_pkt)); - ps.setPowerSaveEnabled((bool)(health.power_save_enabled_pkt)); - ps.setHeartbeatLost((bool)(health.heartbeat_lost_pkt)); - ps.setAlternativeExperience(health.alternative_experience_pkt); - ps.setHarnessStatus(cereal::PandaState::HarnessStatus(health.car_harness_status_pkt)); - ps.setInterruptLoad(health.interrupt_load_pkt); - ps.setFanPower(health.fan_power); - ps.setFanStallCount(health.fan_stall_count); - ps.setSafetyRxChecksInvalid((bool)(health.safety_rx_checks_invalid_pkt)); - ps.setSpiChecksumErrorCount(health.spi_checksum_error_count_pkt); - ps.setSbu1Voltage(health.sbu1_voltage_mV / 1000.0f); - ps.setSbu2Voltage(health.sbu2_voltage_mV / 1000.0f); - - std::array cs = {ps.initCanState0(), ps.initCanState1(), ps.initCanState2()}; - - for (uint32_t j = 0; j < PANDA_CAN_CNT; j++) { - const auto &can_health = pandaCanStates[i][j]; - cs[j].setBusOff((bool)can_health.bus_off); - cs[j].setBusOffCnt(can_health.bus_off_cnt); - cs[j].setErrorWarning((bool)can_health.error_warning); - cs[j].setErrorPassive((bool)can_health.error_passive); - cs[j].setLastError(cereal::PandaState::PandaCanState::LecErrorCode(can_health.last_error)); - cs[j].setLastStoredError(cereal::PandaState::PandaCanState::LecErrorCode(can_health.last_stored_error)); - cs[j].setLastDataError(cereal::PandaState::PandaCanState::LecErrorCode(can_health.last_data_error)); - cs[j].setLastDataStoredError(cereal::PandaState::PandaCanState::LecErrorCode(can_health.last_data_stored_error)); - cs[j].setReceiveErrorCnt(can_health.receive_error_cnt); - cs[j].setTransmitErrorCnt(can_health.transmit_error_cnt); - cs[j].setTotalErrorCnt(can_health.total_error_cnt); - cs[j].setTotalTxLostCnt(can_health.total_tx_lost_cnt); - cs[j].setTotalRxLostCnt(can_health.total_rx_lost_cnt); - cs[j].setTotalTxCnt(can_health.total_tx_cnt); - cs[j].setTotalRxCnt(can_health.total_rx_cnt); - cs[j].setTotalFwdCnt(can_health.total_fwd_cnt); - cs[j].setCanSpeed(can_health.can_speed); - cs[j].setCanDataSpeed(can_health.can_data_speed); - cs[j].setCanfdEnabled(can_health.canfd_enabled); - cs[j].setBrsEnabled(can_health.brs_enabled); - cs[j].setCanfdNonIso(can_health.canfd_non_iso); - cs[j].setIrq0CallRate(can_health.irq0_call_rate); - cs[j].setIrq1CallRate(can_health.irq1_call_rate); - cs[j].setIrq2CallRate(can_health.irq2_call_rate); - cs[j].setCanCoreResetCnt(can_health.can_core_reset_cnt); - } - - // Convert faults bitset to capnp list - std::bitset fault_bits(health.faults_pkt); - auto faults = ps.initFaults(fault_bits.count()); - - size_t j = 0; - for (size_t f = size_t(cereal::PandaState::FaultType::RELAY_MALFUNCTION); - f <= size_t(cereal::PandaState::FaultType::HEARTBEAT_LOOP_WATCHDOG); f++) { - if (fault_bits.test(f)) { - faults.set(j, cereal::PandaState::FaultType(f)); - j++; - } - } - } - - pm->send("pandaStates", msg); - return ignition_local; -} - -void send_peripheral_state(PubMaster *pm, Panda *panda) { - // build msg - MessageBuilder msg; - auto evt = msg.initEvent(); - evt.setValid(panda->comms_healthy()); - - auto ps = evt.initPeripheralState(); - ps.setPandaType(panda->hw_type); - - double read_time = millis_since_boot(); - ps.setVoltage(Hardware::get_voltage()); - ps.setCurrent(Hardware::get_current()); - read_time = millis_since_boot() - read_time; - if (read_time > 50) { - LOGW("reading hwmon took %lfms", read_time); - } - - uint16_t fan_speed_rpm = panda->get_fan_speed(); - ps.setFanSpeedRpm(fan_speed_rpm); - - pm->send("peripheralState", msg); -} - -void panda_state_thread(std::vector pandas, bool spoofing_started) { - util::set_thread_name("boardd_panda_state"); - - Params params; - SubMaster sm({"controlsState"}); - PubMaster pm({"pandaStates", "peripheralState"}); - - Panda *peripheral_panda = pandas[0]; - bool is_onroad = false; - bool is_onroad_last = false; - std::future safety_future; - - std::vector connected_serials; - for (Panda *p : pandas) { - connected_serials.push_back(p->hw_serial()); - } - - LOGD("start panda state thread"); - - // run at 10hz - RateKeeper rk("panda_state_thread", 10); - - while (!do_exit && check_all_connected(pandas)) { - // send out peripheralState at 2Hz - if (sm.frame % 5 == 0) { - send_peripheral_state(&pm, peripheral_panda); - } - - auto ignition_opt = send_panda_states(&pm, pandas, spoofing_started); - - if (!ignition_opt) { - LOGE("Failed to get ignition_opt"); - rk.keepTime(); - continue; - } - - ignition = *ignition_opt; - - // check if we should have pandad reconnect - if (!ignition) { - bool comms_healthy = true; - for (const auto &panda : pandas) { - comms_healthy &= panda->comms_healthy(); - } - - if (!comms_healthy) { - LOGE("Reconnecting, communication to pandas not healthy"); - do_exit = true; - - } else { - // check for new pandas - for (std::string &s : Panda::list(true)) { - if (!std::count(connected_serials.begin(), connected_serials.end(), s)) { - LOGW("Reconnecting to new panda: %s", s.c_str()); - do_exit = true; - break; - } - } - } - - if (do_exit) { - break; - } - } - - is_onroad = params.getBool("IsOnroad"); - - // set new safety on onroad transition, after params are cleared - if (is_onroad && !is_onroad_last) { - if (!safety_future.valid() || safety_future.wait_for(0ms) == std::future_status::ready) { - safety_future = std::async(std::launch::async, safety_setter_thread, pandas); - } else { - LOGW("Safety setter thread already running"); - } - } - - is_onroad_last = is_onroad; - - sm.update(0); - const bool engaged = sm.allAliveAndValid({"controlsState"}) && sm["controlsState"].getControlsState().getEnabled(); - - for (const auto &panda : pandas) { - panda->send_heartbeat(engaged); - } - - rk.keepTime(); - } -} - - -void peripheral_control_thread(Panda *panda, bool no_fan_control) { - util::set_thread_name("boardd_peripheral_control"); - - SubMaster sm({"deviceState", "driverCameraState"}); - - uint64_t last_driver_camera_t = 0; - uint16_t prev_fan_speed = 999; - uint16_t ir_pwr = 0; - uint16_t prev_ir_pwr = 999; - - FirstOrderFilter integ_lines_filter(0, 30.0, 0.05); - - while (!do_exit && panda->connected()) { - sm.update(1000); - - if (sm.updated("deviceState") && !no_fan_control) { - // Fan speed - uint16_t fan_speed = sm["deviceState"].getDeviceState().getFanSpeedPercentDesired(); - if (fan_speed != prev_fan_speed || sm.frame % 100 == 0) { - panda->set_fan_speed(fan_speed); - prev_fan_speed = fan_speed; - } - } - - if (sm.updated("driverCameraState")) { - auto event = sm["driverCameraState"]; - int cur_integ_lines = event.getDriverCameraState().getIntegLines(); - - cur_integ_lines = integ_lines_filter.update(cur_integ_lines); - last_driver_camera_t = event.getLogMonoTime(); - - if (cur_integ_lines <= CUTOFF_IL) { - ir_pwr = 100.0 * MIN_IR_POWER; - } else if (cur_integ_lines > SATURATE_IL) { - ir_pwr = 100.0 * MAX_IR_POWER; - } else { - ir_pwr = 100.0 * (MIN_IR_POWER + ((cur_integ_lines - CUTOFF_IL) * (MAX_IR_POWER - MIN_IR_POWER) / (SATURATE_IL - CUTOFF_IL))); - } - } - - // Disable IR on input timeout - if (nanos_since_boot() - last_driver_camera_t > 1e9) { - ir_pwr = 0; - } - - if (ir_pwr != prev_ir_pwr || sm.frame % 100 == 0 || ir_pwr >= 50.0) { - panda->set_ir_pwr(ir_pwr); - prev_ir_pwr = ir_pwr; - } - - // Write to rtc once per minute when no ignition present - if (!ignition && (sm.frame % 120 == 1)) { - sync_time(panda, SyncTimeDir::TO_PANDA); - } - } -} - -void boardd_main_thread(std::vector serials) { - LOGW("launching boardd"); - - if (serials.size() == 0) { - serials = Panda::list(); - - if (serials.size() == 0) { - LOGW("no pandas found, exiting"); - return; - } - } - - std::string serials_str; - for (int i = 0; i < serials.size(); i++) { - serials_str += serials[i]; - if (i < serials.size() - 1) serials_str += ", "; - } - LOGW("connecting to pandas: %s", serials_str.c_str()); - - // connect to all provided serials - std::vector pandas; - for (int i = 0; i < serials.size() && !do_exit; /**/) { - Panda *p = connect(serials[i], i); - if (!p) { - util::sleep_for(100); - continue; - } - - pandas.push_back(p); - ++i; - } - - if (!do_exit) { - LOGW("connected to all pandas"); - - std::vector threads; - - threads.emplace_back(panda_state_thread, pandas, getenv("STARTED") != nullptr); - threads.emplace_back(peripheral_control_thread, pandas[0], getenv("NO_FAN_CONTROL") != nullptr); - - threads.emplace_back(can_send_thread, pandas, getenv("FAKESEND") != nullptr); - threads.emplace_back(can_recv_thread, pandas); - - for (auto &t : threads) t.join(); - } - - for (Panda *panda : pandas) { - delete panda; - } -} diff --git a/selfdrive/boardd/boardd.h b/selfdrive/boardd/boardd.h deleted file mode 100644 index 0646fc6..0000000 --- a/selfdrive/boardd/boardd.h +++ /dev/null @@ -1,9 +0,0 @@ -#pragma once - -#include -#include - -#include "selfdrive/boardd/panda.h" - -bool safety_setter_thread(std::vector pandas); -void boardd_main_thread(std::vector serials); diff --git a/selfdrive/boardd/boardd_api_impl.cpp b/selfdrive/boardd/boardd_api_impl.cpp new file mode 100644 index 0000000..5ed5e00 --- /dev/null +++ b/selfdrive/boardd/boardd_api_impl.cpp @@ -0,0 +1,6887 @@ +/* Generated by Cython 3.0.8 */ + +/* BEGIN: Cython Metadata +{ + "distutils": { + "depends": [ + "selfdrive/boardd/can_list_to_can_capnp.cc", + "selfdrive/boardd/panda.h" + ], + "include_dirs": [ + "selfdrive/boardd" + ], + "language": "c++", + "name": "selfdrive.boardd.boardd_api_impl", + "sources": [ + "/data/openpilot/selfdrive/boardd/boardd_api_impl.pyx" + ] + }, + "module_name": "selfdrive.boardd.boardd_api_impl" +} +END: Cython Metadata */ + +#ifndef PY_SSIZE_T_CLEAN +#define PY_SSIZE_T_CLEAN +#endif /* PY_SSIZE_T_CLEAN */ +#if defined(CYTHON_LIMITED_API) && 0 + #ifndef Py_LIMITED_API + #if CYTHON_LIMITED_API+0 > 0x03030000 + #define Py_LIMITED_API CYTHON_LIMITED_API + #else + #define Py_LIMITED_API 0x03030000 + #endif + #endif +#endif + +#include "Python.h" +#ifndef Py_PYTHON_H + #error Python headers needed to compile C extensions, please install development version of Python. +#elif PY_VERSION_HEX < 0x02070000 || (0x03000000 <= PY_VERSION_HEX && PY_VERSION_HEX < 0x03030000) + #error Cython requires Python 2.7+ or Python 3.3+. +#else +#if defined(CYTHON_LIMITED_API) && CYTHON_LIMITED_API +#define __PYX_EXTRA_ABI_MODULE_NAME "limited" +#else +#define __PYX_EXTRA_ABI_MODULE_NAME "" +#endif +#define CYTHON_ABI "3_0_8" __PYX_EXTRA_ABI_MODULE_NAME +#define __PYX_ABI_MODULE_NAME "_cython_" CYTHON_ABI +#define __PYX_TYPE_MODULE_PREFIX __PYX_ABI_MODULE_NAME "." +#define CYTHON_HEX_VERSION 0x030008F0 +#define CYTHON_FUTURE_DIVISION 1 +#include +#ifndef offsetof + #define offsetof(type, member) ( (size_t) & ((type*)0) -> member ) +#endif +#if !defined(_WIN32) && !defined(WIN32) && !defined(MS_WINDOWS) + #ifndef __stdcall + #define __stdcall + #endif + #ifndef __cdecl + #define __cdecl + #endif + #ifndef __fastcall + #define __fastcall + #endif +#endif +#ifndef DL_IMPORT + #define DL_IMPORT(t) t +#endif +#ifndef DL_EXPORT + #define DL_EXPORT(t) t +#endif +#define __PYX_COMMA , +#ifndef HAVE_LONG_LONG + #define HAVE_LONG_LONG +#endif +#ifndef PY_LONG_LONG + #define PY_LONG_LONG LONG_LONG +#endif +#ifndef Py_HUGE_VAL + #define Py_HUGE_VAL HUGE_VAL +#endif +#define __PYX_LIMITED_VERSION_HEX PY_VERSION_HEX +#if defined(GRAALVM_PYTHON) + /* For very preliminary testing purposes. Most variables are set the same as PyPy. + The existence of this section does not imply that anything works or is even tested */ + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 1 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(PYPY_VERSION) + #define CYTHON_COMPILING_IN_PYPY 1 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #ifndef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #endif + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #if PY_VERSION_HEX < 0x03090000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE (PY_VERSION_HEX >= 0x030400a1 && PYPY_VERSION_NUM >= 0x07030C00) + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(CYTHON_LIMITED_API) + #ifdef Py_LIMITED_API + #undef __PYX_LIMITED_VERSION_HEX + #define __PYX_LIMITED_VERSION_HEX Py_LIMITED_API + #endif + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 1 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_CLINE_IN_TRACEBACK + #define CYTHON_CLINE_IN_TRACEBACK 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 1 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #endif + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 1 + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(Py_GIL_DISABLED) || defined(Py_NOGIL) + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 1 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #ifndef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 +#else + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 1 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #ifndef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #endif + #ifndef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 1 + #endif + #if PY_MAJOR_VERSION < 3 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #ifndef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 1 + #endif + #ifndef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 1 + #endif + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #if PY_VERSION_HEX < 0x030300F0 || PY_VERSION_HEX >= 0x030B00A2 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #elif !defined(CYTHON_USE_UNICODE_WRITER) + #define CYTHON_USE_UNICODE_WRITER 1 + #endif + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #ifndef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 1 + #endif + #ifndef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL (PY_MAJOR_VERSION < 3 || PY_VERSION_HEX >= 0x03060000 && PY_VERSION_HEX < 0x030C00A6) + #endif + #ifndef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL (PY_VERSION_HEX >= 0x030700A1) + #endif + #ifndef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 1 + #endif + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #endif + #if PY_VERSION_HEX < 0x030400a1 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #elif !defined(CYTHON_USE_TP_FINALIZE) + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #if PY_VERSION_HEX < 0x030600B1 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #elif !defined(CYTHON_USE_DICT_VERSIONS) + #define CYTHON_USE_DICT_VERSIONS (PY_VERSION_HEX < 0x030C00A5) + #endif + #if PY_VERSION_HEX < 0x030700A3 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #elif !defined(CYTHON_USE_EXC_INFO_STACK) + #define CYTHON_USE_EXC_INFO_STACK 1 + #endif + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 1 + #endif +#endif +#if !defined(CYTHON_FAST_PYCCALL) +#define CYTHON_FAST_PYCCALL (CYTHON_FAST_PYCALL && PY_VERSION_HEX >= 0x030600B1) +#endif +#if !defined(CYTHON_VECTORCALL) +#define CYTHON_VECTORCALL (CYTHON_FAST_PYCCALL && PY_VERSION_HEX >= 0x030800B1) +#endif +#define CYTHON_BACKPORT_VECTORCALL (CYTHON_METH_FASTCALL && PY_VERSION_HEX < 0x030800B1) +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_MAJOR_VERSION < 3 + #include "longintrepr.h" + #endif + #undef SHIFT + #undef BASE + #undef MASK + #ifdef SIZEOF_VOID_P + enum { __pyx_check_sizeof_voidp = 1 / (int)(SIZEOF_VOID_P == sizeof(void*)) }; + #endif +#endif +#ifndef __has_attribute + #define __has_attribute(x) 0 +#endif +#ifndef __has_cpp_attribute + #define __has_cpp_attribute(x) 0 +#endif +#ifndef CYTHON_RESTRICT + #if defined(__GNUC__) + #define CYTHON_RESTRICT __restrict__ + #elif defined(_MSC_VER) && _MSC_VER >= 1400 + #define CYTHON_RESTRICT __restrict + #elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define CYTHON_RESTRICT restrict + #else + #define CYTHON_RESTRICT + #endif +#endif +#ifndef CYTHON_UNUSED + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(maybe_unused) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(maybe_unused) + #define CYTHON_UNUSED [[maybe_unused]] + #endif + #endif + #endif +#endif +#ifndef CYTHON_UNUSED +# if defined(__GNUC__) +# if !(defined(__cplusplus)) || (__GNUC__ > 3 || (__GNUC__ == 3 && __GNUC_MINOR__ >= 4)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +# elif defined(__ICC) || (defined(__INTEL_COMPILER) && !defined(_MSC_VER)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +#endif +#ifndef CYTHON_UNUSED_VAR +# if defined(__cplusplus) + template void CYTHON_UNUSED_VAR( const T& ) { } +# else +# define CYTHON_UNUSED_VAR(x) (void)(x) +# endif +#endif +#ifndef CYTHON_MAYBE_UNUSED_VAR + #define CYTHON_MAYBE_UNUSED_VAR(x) CYTHON_UNUSED_VAR(x) +#endif +#ifndef CYTHON_NCP_UNUSED +# if CYTHON_COMPILING_IN_CPYTHON +# define CYTHON_NCP_UNUSED +# else +# define CYTHON_NCP_UNUSED CYTHON_UNUSED +# endif +#endif +#ifndef CYTHON_USE_CPP_STD_MOVE + #if defined(__cplusplus) && (\ + __cplusplus >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1600)) + #define CYTHON_USE_CPP_STD_MOVE 1 + #else + #define CYTHON_USE_CPP_STD_MOVE 0 + #endif +#endif +#define __Pyx_void_to_None(void_result) ((void)(void_result), Py_INCREF(Py_None), Py_None) +#ifdef _MSC_VER + #ifndef _MSC_STDINT_H_ + #if _MSC_VER < 1300 + typedef unsigned char uint8_t; + typedef unsigned short uint16_t; + typedef unsigned int uint32_t; + #else + typedef unsigned __int8 uint8_t; + typedef unsigned __int16 uint16_t; + typedef unsigned __int32 uint32_t; + #endif + #endif + #if _MSC_VER < 1300 + #ifdef _WIN64 + typedef unsigned long long __pyx_uintptr_t; + #else + typedef unsigned int __pyx_uintptr_t; + #endif + #else + #ifdef _WIN64 + typedef unsigned __int64 __pyx_uintptr_t; + #else + typedef unsigned __int32 __pyx_uintptr_t; + #endif + #endif +#else + #include + typedef uintptr_t __pyx_uintptr_t; +#endif +#ifndef CYTHON_FALLTHROUGH + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(fallthrough) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(fallthrough) + #define CYTHON_FALLTHROUGH [[fallthrough]] + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_cpp_attribute(clang::fallthrough) + #define CYTHON_FALLTHROUGH [[clang::fallthrough]] + #elif __has_cpp_attribute(gnu::fallthrough) + #define CYTHON_FALLTHROUGH [[gnu::fallthrough]] + #endif + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_attribute(fallthrough) + #define CYTHON_FALLTHROUGH __attribute__((fallthrough)) + #else + #define CYTHON_FALLTHROUGH + #endif + #endif + #if defined(__clang__) && defined(__apple_build_version__) + #if __apple_build_version__ < 7000000 + #undef CYTHON_FALLTHROUGH + #define CYTHON_FALLTHROUGH + #endif + #endif +#endif +#ifdef __cplusplus + template + struct __PYX_IS_UNSIGNED_IMPL {static const bool value = T(0) < T(-1);}; + #define __PYX_IS_UNSIGNED(type) (__PYX_IS_UNSIGNED_IMPL::value) +#else + #define __PYX_IS_UNSIGNED(type) (((type)-1) > 0) +#endif +#if CYTHON_COMPILING_IN_PYPY == 1 + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x030A0000) +#else + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x03090000) +#endif +#define __PYX_REINTERPRET_FUNCION(func_pointer, other_pointer) ((func_pointer)(void(*)(void))(other_pointer)) + +#ifndef __cplusplus + #error "Cython files generated with the C++ option must be compiled with a C++ compiler." +#endif +#ifndef CYTHON_INLINE + #if defined(__clang__) + #define CYTHON_INLINE __inline__ __attribute__ ((__unused__)) + #else + #define CYTHON_INLINE inline + #endif +#endif +template +void __Pyx_call_destructor(T& x) { + x.~T(); +} +template +class __Pyx_FakeReference { + public: + __Pyx_FakeReference() : ptr(NULL) { } + __Pyx_FakeReference(const T& ref) : ptr(const_cast(&ref)) { } + T *operator->() { return ptr; } + T *operator&() { return ptr; } + operator T&() { return *ptr; } + template bool operator ==(const U& other) const { return *ptr == other; } + template bool operator !=(const U& other) const { return *ptr != other; } + template bool operator==(const __Pyx_FakeReference& other) const { return *ptr == *other.ptr; } + template bool operator!=(const __Pyx_FakeReference& other) const { return *ptr != *other.ptr; } + private: + T *ptr; +}; + +#define __PYX_BUILD_PY_SSIZE_T "n" +#define CYTHON_FORMAT_SSIZE_T "z" +#if PY_MAJOR_VERSION < 3 + #define __Pyx_BUILTIN_MODULE_NAME "__builtin__" + #define __Pyx_DefaultClassType PyClass_Type + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a+k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_BUILTIN_MODULE_NAME "builtins" + #define __Pyx_DefaultClassType PyType_Type +#if CYTHON_COMPILING_IN_LIMITED_API + static CYTHON_INLINE PyObject* __Pyx_PyCode_New(int a, int p, int k, int l, int s, int f, + PyObject *code, PyObject *c, PyObject* n, PyObject *v, + PyObject *fv, PyObject *cell, PyObject* fn, + PyObject *name, int fline, PyObject *lnos) { + PyObject *exception_table = NULL; + PyObject *types_module=NULL, *code_type=NULL, *result=NULL; + #if __PYX_LIMITED_VERSION_HEX < 0x030B0000 + PyObject *version_info; + PyObject *py_minor_version = NULL; + #endif + long minor_version = 0; + PyObject *type, *value, *traceback; + PyErr_Fetch(&type, &value, &traceback); + #if __PYX_LIMITED_VERSION_HEX >= 0x030B0000 + minor_version = 11; + #else + if (!(version_info = PySys_GetObject("version_info"))) goto end; + if (!(py_minor_version = PySequence_GetItem(version_info, 1))) goto end; + minor_version = PyLong_AsLong(py_minor_version); + Py_DECREF(py_minor_version); + if (minor_version == -1 && PyErr_Occurred()) goto end; + #endif + if (!(types_module = PyImport_ImportModule("types"))) goto end; + if (!(code_type = PyObject_GetAttrString(types_module, "CodeType"))) goto end; + if (minor_version <= 7) { + (void)p; + result = PyObject_CallFunction(code_type, "iiiiiOOOOOOiOO", a, k, l, s, f, code, + c, n, v, fn, name, fline, lnos, fv, cell); + } else if (minor_version <= 10) { + result = PyObject_CallFunction(code_type, "iiiiiiOOOOOOiOO", a,p, k, l, s, f, code, + c, n, v, fn, name, fline, lnos, fv, cell); + } else { + if (!(exception_table = PyBytes_FromStringAndSize(NULL, 0))) goto end; + result = PyObject_CallFunction(code_type, "iiiiiiOOOOOOOiOO", a,p, k, l, s, f, code, + c, n, v, fn, name, name, fline, lnos, exception_table, fv, cell); + } + end: + Py_XDECREF(code_type); + Py_XDECREF(exception_table); + Py_XDECREF(types_module); + if (type) { + PyErr_Restore(type, value, traceback); + } + return result; + } + #ifndef CO_OPTIMIZED + #define CO_OPTIMIZED 0x0001 + #endif + #ifndef CO_NEWLOCALS + #define CO_NEWLOCALS 0x0002 + #endif + #ifndef CO_VARARGS + #define CO_VARARGS 0x0004 + #endif + #ifndef CO_VARKEYWORDS + #define CO_VARKEYWORDS 0x0008 + #endif + #ifndef CO_ASYNC_GENERATOR + #define CO_ASYNC_GENERATOR 0x0200 + #endif + #ifndef CO_GENERATOR + #define CO_GENERATOR 0x0020 + #endif + #ifndef CO_COROUTINE + #define CO_COROUTINE 0x0080 + #endif +#elif PY_VERSION_HEX >= 0x030B0000 + static CYTHON_INLINE PyCodeObject* __Pyx_PyCode_New(int a, int p, int k, int l, int s, int f, + PyObject *code, PyObject *c, PyObject* n, PyObject *v, + PyObject *fv, PyObject *cell, PyObject* fn, + PyObject *name, int fline, PyObject *lnos) { + PyCodeObject *result; + PyObject *empty_bytes = PyBytes_FromStringAndSize("", 0); + if (!empty_bytes) return NULL; + result = + #if PY_VERSION_HEX >= 0x030C0000 + PyUnstable_Code_NewWithPosOnlyArgs + #else + PyCode_NewWithPosOnlyArgs + #endif + (a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, name, fline, lnos, empty_bytes); + Py_DECREF(empty_bytes); + return result; + } +#elif PY_VERSION_HEX >= 0x030800B2 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_NewWithPosOnlyArgs(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#endif +#endif +#if PY_VERSION_HEX >= 0x030900A4 || defined(Py_IS_TYPE) + #define __Pyx_IS_TYPE(ob, type) Py_IS_TYPE(ob, type) +#else + #define __Pyx_IS_TYPE(ob, type) (((const PyObject*)ob)->ob_type == (type)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_Is) + #define __Pyx_Py_Is(x, y) Py_Is(x, y) +#else + #define __Pyx_Py_Is(x, y) ((x) == (y)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsNone) + #define __Pyx_Py_IsNone(ob) Py_IsNone(ob) +#else + #define __Pyx_Py_IsNone(ob) __Pyx_Py_Is((ob), Py_None) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsTrue) + #define __Pyx_Py_IsTrue(ob) Py_IsTrue(ob) +#else + #define __Pyx_Py_IsTrue(ob) __Pyx_Py_Is((ob), Py_True) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsFalse) + #define __Pyx_Py_IsFalse(ob) Py_IsFalse(ob) +#else + #define __Pyx_Py_IsFalse(ob) __Pyx_Py_Is((ob), Py_False) +#endif +#define __Pyx_NoneAsNull(obj) (__Pyx_Py_IsNone(obj) ? NULL : (obj)) +#if PY_VERSION_HEX >= 0x030900F0 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_GC_IsFinalized(o) PyObject_GC_IsFinalized(o) +#else + #define __Pyx_PyObject_GC_IsFinalized(o) _PyGC_FINALIZED(o) +#endif +#ifndef CO_COROUTINE + #define CO_COROUTINE 0x80 +#endif +#ifndef CO_ASYNC_GENERATOR + #define CO_ASYNC_GENERATOR 0x200 +#endif +#ifndef Py_TPFLAGS_CHECKTYPES + #define Py_TPFLAGS_CHECKTYPES 0 +#endif +#ifndef Py_TPFLAGS_HAVE_INDEX + #define Py_TPFLAGS_HAVE_INDEX 0 +#endif +#ifndef Py_TPFLAGS_HAVE_NEWBUFFER + #define Py_TPFLAGS_HAVE_NEWBUFFER 0 +#endif +#ifndef Py_TPFLAGS_HAVE_FINALIZE + #define Py_TPFLAGS_HAVE_FINALIZE 0 +#endif +#ifndef Py_TPFLAGS_SEQUENCE + #define Py_TPFLAGS_SEQUENCE 0 +#endif +#ifndef Py_TPFLAGS_MAPPING + #define Py_TPFLAGS_MAPPING 0 +#endif +#ifndef METH_STACKLESS + #define METH_STACKLESS 0 +#endif +#if PY_VERSION_HEX <= 0x030700A3 || !defined(METH_FASTCALL) + #ifndef METH_FASTCALL + #define METH_FASTCALL 0x80 + #endif + typedef PyObject *(*__Pyx_PyCFunctionFast) (PyObject *self, PyObject *const *args, Py_ssize_t nargs); + typedef PyObject *(*__Pyx_PyCFunctionFastWithKeywords) (PyObject *self, PyObject *const *args, + Py_ssize_t nargs, PyObject *kwnames); +#else + #define __Pyx_PyCFunctionFast _PyCFunctionFast + #define __Pyx_PyCFunctionFastWithKeywords _PyCFunctionFastWithKeywords +#endif +#if CYTHON_METH_FASTCALL + #define __Pyx_METH_FASTCALL METH_FASTCALL + #define __Pyx_PyCFunction_FastCall __Pyx_PyCFunctionFast + #define __Pyx_PyCFunction_FastCallWithKeywords __Pyx_PyCFunctionFastWithKeywords +#else + #define __Pyx_METH_FASTCALL METH_VARARGS + #define __Pyx_PyCFunction_FastCall PyCFunction + #define __Pyx_PyCFunction_FastCallWithKeywords PyCFunctionWithKeywords +#endif +#if CYTHON_VECTORCALL + #define __pyx_vectorcallfunc vectorcallfunc + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET PY_VECTORCALL_ARGUMENTS_OFFSET + #define __Pyx_PyVectorcall_NARGS(n) PyVectorcall_NARGS((size_t)(n)) +#elif CYTHON_BACKPORT_VECTORCALL + typedef PyObject *(*__pyx_vectorcallfunc)(PyObject *callable, PyObject *const *args, + size_t nargsf, PyObject *kwnames); + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET ((size_t)1 << (8 * sizeof(size_t) - 1)) + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(((size_t)(n)) & ~__Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET)) +#else + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET 0 + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(n)) +#endif +#if PY_MAJOR_VERSION >= 0x030900B1 +#define __Pyx_PyCFunction_CheckExact(func) PyCFunction_CheckExact(func) +#else +#define __Pyx_PyCFunction_CheckExact(func) PyCFunction_Check(func) +#endif +#define __Pyx_CyOrPyCFunction_Check(func) PyCFunction_Check(func) +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_CyOrPyCFunction_GET_FUNCTION(func) (((PyCFunctionObject*)(func))->m_ml->ml_meth) +#elif !CYTHON_COMPILING_IN_LIMITED_API +#define __Pyx_CyOrPyCFunction_GET_FUNCTION(func) PyCFunction_GET_FUNCTION(func) +#endif +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_CyOrPyCFunction_GET_FLAGS(func) (((PyCFunctionObject*)(func))->m_ml->ml_flags) +static CYTHON_INLINE PyObject* __Pyx_CyOrPyCFunction_GET_SELF(PyObject *func) { + return (__Pyx_CyOrPyCFunction_GET_FLAGS(func) & METH_STATIC) ? NULL : ((PyCFunctionObject*)func)->m_self; +} +#endif +static CYTHON_INLINE int __Pyx__IsSameCFunction(PyObject *func, void *cfunc) { +#if CYTHON_COMPILING_IN_LIMITED_API + return PyCFunction_Check(func) && PyCFunction_GetFunction(func) == (PyCFunction) cfunc; +#else + return PyCFunction_Check(func) && PyCFunction_GET_FUNCTION(func) == (PyCFunction) cfunc; +#endif +} +#define __Pyx_IsSameCFunction(func, cfunc) __Pyx__IsSameCFunction(func, cfunc) +#if __PYX_LIMITED_VERSION_HEX < 0x030900B1 + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) ((void)m, PyType_FromSpecWithBases(s, b)) + typedef PyObject *(*__Pyx_PyCMethod)(PyObject *, PyTypeObject *, PyObject *const *, size_t, PyObject *); +#else + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) PyType_FromModuleAndSpec(m, s, b) + #define __Pyx_PyCMethod PyCMethod +#endif +#ifndef METH_METHOD + #define METH_METHOD 0x200 +#endif +#if CYTHON_COMPILING_IN_PYPY && !defined(PyObject_Malloc) + #define PyObject_Malloc(s) PyMem_Malloc(s) + #define PyObject_Free(p) PyMem_Free(p) + #define PyObject_Realloc(p) PyMem_Realloc(p) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) +#else + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) (frame)->f_lineno = (lineno) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyThreadState_Current PyThreadState_Get() +#elif !CYTHON_FAST_THREAD_STATE + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#elif PY_VERSION_HEX >= 0x030d00A1 + #define __Pyx_PyThreadState_Current PyThreadState_GetUnchecked() +#elif PY_VERSION_HEX >= 0x03060000 + #define __Pyx_PyThreadState_Current _PyThreadState_UncheckedGet() +#elif PY_VERSION_HEX >= 0x03000000 + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#else + #define __Pyx_PyThreadState_Current _PyThreadState_Current +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE void *__Pyx_PyModule_GetState(PyObject *op) +{ + void *result; + result = PyModule_GetState(op); + if (!result) + Py_FatalError("Couldn't find the module state"); + return result; +} +#endif +#define __Pyx_PyObject_GetSlot(obj, name, func_ctype) __Pyx_PyType_GetSlot(Py_TYPE(obj), name, func_ctype) +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((func_ctype) PyType_GetSlot((type), Py_##name)) +#else + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((type)->name) +#endif +#if PY_VERSION_HEX < 0x030700A2 && !defined(PyThread_tss_create) && !defined(Py_tss_NEEDS_INIT) +#include "pythread.h" +#define Py_tss_NEEDS_INIT 0 +typedef int Py_tss_t; +static CYTHON_INLINE int PyThread_tss_create(Py_tss_t *key) { + *key = PyThread_create_key(); + return 0; +} +static CYTHON_INLINE Py_tss_t * PyThread_tss_alloc(void) { + Py_tss_t *key = (Py_tss_t *)PyObject_Malloc(sizeof(Py_tss_t)); + *key = Py_tss_NEEDS_INIT; + return key; +} +static CYTHON_INLINE void PyThread_tss_free(Py_tss_t *key) { + PyObject_Free(key); +} +static CYTHON_INLINE int PyThread_tss_is_created(Py_tss_t *key) { + return *key != Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE void PyThread_tss_delete(Py_tss_t *key) { + PyThread_delete_key(*key); + *key = Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE int PyThread_tss_set(Py_tss_t *key, void *value) { + return PyThread_set_key_value(*key, value); +} +static CYTHON_INLINE void * PyThread_tss_get(Py_tss_t *key) { + return PyThread_get_key_value(*key); +} +#endif +#if PY_MAJOR_VERSION < 3 + #if CYTHON_COMPILING_IN_PYPY + #if PYPY_VERSION_NUM < 0x07030600 + #if defined(__cplusplus) && __cplusplus >= 201402L + [[deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")]] + #elif defined(__GNUC__) || defined(__clang__) + __attribute__ ((__deprecated__("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6"))) + #elif defined(_MSC_VER) + __declspec(deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")) + #endif + static CYTHON_INLINE int PyGILState_Check(void) { + return 0; + } + #else // PYPY_VERSION_NUM < 0x07030600 + #endif // PYPY_VERSION_NUM < 0x07030600 + #else + static CYTHON_INLINE int PyGILState_Check(void) { + PyThreadState * tstate = _PyThreadState_Current; + return tstate && (tstate == PyGILState_GetThisThreadState()); + } + #endif +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030d0000 || defined(_PyDict_NewPresized) +#define __Pyx_PyDict_NewPresized(n) ((n <= 8) ? PyDict_New() : _PyDict_NewPresized(n)) +#else +#define __Pyx_PyDict_NewPresized(n) PyDict_New() +#endif +#if PY_MAJOR_VERSION >= 3 || CYTHON_FUTURE_DIVISION + #define __Pyx_PyNumber_Divide(x,y) PyNumber_TrueDivide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceTrueDivide(x,y) +#else + #define __Pyx_PyNumber_Divide(x,y) PyNumber_Divide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceDivide(x,y) +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX > 0x030600B4 && PY_VERSION_HEX < 0x030d0000 && CYTHON_USE_UNICODE_INTERNALS +#define __Pyx_PyDict_GetItemStrWithError(dict, name) _PyDict_GetItem_KnownHash(dict, name, ((PyASCIIObject *) name)->hash) +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStr(PyObject *dict, PyObject *name) { + PyObject *res = __Pyx_PyDict_GetItemStrWithError(dict, name); + if (res == NULL) PyErr_Clear(); + return res; +} +#elif PY_MAJOR_VERSION >= 3 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07020000) +#define __Pyx_PyDict_GetItemStrWithError PyDict_GetItemWithError +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#else +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStrWithError(PyObject *dict, PyObject *name) { +#if CYTHON_COMPILING_IN_PYPY + return PyDict_GetItem(dict, name); +#else + PyDictEntry *ep; + PyDictObject *mp = (PyDictObject*) dict; + long hash = ((PyStringObject *) name)->ob_shash; + assert(hash != -1); + ep = (mp->ma_lookup)(mp, name, hash); + if (ep == NULL) { + return NULL; + } + return ep->me_value; +#endif +} +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#endif +#if CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyType_GetFlags(tp) (((PyTypeObject *)tp)->tp_flags) + #define __Pyx_PyType_HasFeature(type, feature) ((__Pyx_PyType_GetFlags(type) & (feature)) != 0) + #define __Pyx_PyObject_GetIterNextFunc(obj) (Py_TYPE(obj)->tp_iternext) +#else + #define __Pyx_PyType_GetFlags(tp) (PyType_GetFlags((PyTypeObject *)tp)) + #define __Pyx_PyType_HasFeature(type, feature) PyType_HasFeature(type, feature) + #define __Pyx_PyObject_GetIterNextFunc(obj) PyIter_Next +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_SetItemOnTypeDict(tp, k, v) PyObject_GenericSetAttr((PyObject*)tp, k, v) +#else + #define __Pyx_SetItemOnTypeDict(tp, k, v) PyDict_SetItem(tp->tp_dict, k, v) +#endif +#if CYTHON_USE_TYPE_SPECS && PY_VERSION_HEX >= 0x03080000 +#define __Pyx_PyHeapTypeObject_GC_Del(obj) {\ + PyTypeObject *type = Py_TYPE((PyObject*)obj);\ + assert(__Pyx_PyType_HasFeature(type, Py_TPFLAGS_HEAPTYPE));\ + PyObject_GC_Del(obj);\ + Py_DECREF(type);\ +} +#else +#define __Pyx_PyHeapTypeObject_GC_Del(obj) PyObject_GC_Del(obj) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define CYTHON_PEP393_ENABLED 1 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GetLength(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_ReadChar(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((void)u, 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((void)u, (0)) + #define __Pyx_PyUnicode_DATA(u) ((void*)u) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)k, PyUnicode_ReadChar((PyObject*)(d), i)) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GetLength(u)) +#elif PY_VERSION_HEX > 0x03030000 && defined(PyUnicode_KIND) + #define CYTHON_PEP393_ENABLED 1 + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_READY(op) (0) + #else + #define __Pyx_PyUnicode_READY(op) (likely(PyUnicode_IS_READY(op)) ?\ + 0 : _PyUnicode_Ready((PyObject *)(op))) + #endif + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_LENGTH(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_READ_CHAR(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) PyUnicode_MAX_CHAR_VALUE(u) + #define __Pyx_PyUnicode_KIND(u) ((int)PyUnicode_KIND(u)) + #define __Pyx_PyUnicode_DATA(u) PyUnicode_DATA(u) + #define __Pyx_PyUnicode_READ(k, d, i) PyUnicode_READ(k, d, i) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) PyUnicode_WRITE(k, d, i, (Py_UCS4) ch) + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_LENGTH(u)) + #else + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x03090000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : ((PyCompactUnicodeObject *)(u))->wstr_length)) + #else + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : PyUnicode_GET_SIZE(u))) + #endif + #endif +#else + #define CYTHON_PEP393_ENABLED 0 + #define PyUnicode_1BYTE_KIND 1 + #define PyUnicode_2BYTE_KIND 2 + #define PyUnicode_4BYTE_KIND 4 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_SIZE(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) ((Py_UCS4)(PyUnicode_AS_UNICODE(u)[i])) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((sizeof(Py_UNICODE) == 2) ? 65535U : 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((int)sizeof(Py_UNICODE)) + #define __Pyx_PyUnicode_DATA(u) ((void*)PyUnicode_AS_UNICODE(u)) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)(k), (Py_UCS4)(((Py_UNICODE*)d)[i])) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) (((void)(k)), ((Py_UNICODE*)d)[i] = (Py_UNICODE) ch) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_SIZE(u)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyUnicode_Concat(a, b) PyNumber_Add(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) PyNumber_Add(a, b) +#else + #define __Pyx_PyUnicode_Concat(a, b) PyUnicode_Concat(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) ((unlikely((a) == Py_None) || unlikely((b) == Py_None)) ?\ + PyNumber_Add(a, b) : __Pyx_PyUnicode_Concat(a, b)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #if !defined(PyUnicode_DecodeUnicodeEscape) + #define PyUnicode_DecodeUnicodeEscape(s, size, errors) PyUnicode_Decode(s, size, "unicode_escape", errors) + #endif + #if !defined(PyUnicode_Contains) || (PY_MAJOR_VERSION == 2 && PYPY_VERSION_NUM < 0x07030500) + #undef PyUnicode_Contains + #define PyUnicode_Contains(u, s) PySequence_Contains(u, s) + #endif + #if !defined(PyByteArray_Check) + #define PyByteArray_Check(obj) PyObject_TypeCheck(obj, &PyByteArray_Type) + #endif + #if !defined(PyObject_Format) + #define PyObject_Format(obj, fmt) PyObject_CallMethod(obj, "__format__", "O", fmt) + #endif +#endif +#define __Pyx_PyString_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyString_Check(b) && !PyString_CheckExact(b)))) ? PyNumber_Remainder(a, b) : __Pyx_PyString_Format(a, b)) +#define __Pyx_PyUnicode_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyUnicode_Check(b) && !PyUnicode_CheckExact(b)))) ? PyNumber_Remainder(a, b) : PyUnicode_Format(a, b)) +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyString_Format(a, b) PyUnicode_Format(a, b) +#else + #define __Pyx_PyString_Format(a, b) PyString_Format(a, b) +#endif +#if PY_MAJOR_VERSION < 3 && !defined(PyObject_ASCII) + #define PyObject_ASCII(o) PyObject_Repr(o) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBaseString_Type PyUnicode_Type + #define PyStringObject PyUnicodeObject + #define PyString_Type PyUnicode_Type + #define PyString_Check PyUnicode_Check + #define PyString_CheckExact PyUnicode_CheckExact +#ifndef PyObject_Unicode + #define PyObject_Unicode PyObject_Str +#endif +#endif +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyBaseString_Check(obj) PyUnicode_Check(obj) + #define __Pyx_PyBaseString_CheckExact(obj) PyUnicode_CheckExact(obj) +#else + #define __Pyx_PyBaseString_Check(obj) (PyString_Check(obj) || PyUnicode_Check(obj)) + #define __Pyx_PyBaseString_CheckExact(obj) (PyString_CheckExact(obj) || PyUnicode_CheckExact(obj)) +#endif +#if CYTHON_COMPILING_IN_CPYTHON + #define __Pyx_PySequence_ListKeepNew(obj)\ + (likely(PyList_CheckExact(obj) && Py_REFCNT(obj) == 1) ? __Pyx_NewRef(obj) : PySequence_List(obj)) +#else + #define __Pyx_PySequence_ListKeepNew(obj) PySequence_List(obj) +#endif +#ifndef PySet_CheckExact + #define PySet_CheckExact(obj) __Pyx_IS_TYPE(obj, &PySet_Type) +#endif +#if PY_VERSION_HEX >= 0x030900A4 + #define __Pyx_SET_REFCNT(obj, refcnt) Py_SET_REFCNT(obj, refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SET_SIZE(obj, size) +#else + #define __Pyx_SET_REFCNT(obj, refcnt) Py_REFCNT(obj) = (refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SIZE(obj) = (size) +#endif +#if CYTHON_ASSUME_SAFE_MACROS + #define __Pyx_PySequence_ITEM(o, i) PySequence_ITEM(o, i) + #define __Pyx_PySequence_SIZE(seq) Py_SIZE(seq) + #define __Pyx_PyTuple_SET_ITEM(o, i, v) (PyTuple_SET_ITEM(o, i, v), (0)) + #define __Pyx_PyList_SET_ITEM(o, i, v) (PyList_SET_ITEM(o, i, v), (0)) + #define __Pyx_PyTuple_GET_SIZE(o) PyTuple_GET_SIZE(o) + #define __Pyx_PyList_GET_SIZE(o) PyList_GET_SIZE(o) + #define __Pyx_PySet_GET_SIZE(o) PySet_GET_SIZE(o) + #define __Pyx_PyBytes_GET_SIZE(o) PyBytes_GET_SIZE(o) + #define __Pyx_PyByteArray_GET_SIZE(o) PyByteArray_GET_SIZE(o) +#else + #define __Pyx_PySequence_ITEM(o, i) PySequence_GetItem(o, i) + #define __Pyx_PySequence_SIZE(seq) PySequence_Size(seq) + #define __Pyx_PyTuple_SET_ITEM(o, i, v) PyTuple_SetItem(o, i, v) + #define __Pyx_PyList_SET_ITEM(o, i, v) PyList_SetItem(o, i, v) + #define __Pyx_PyTuple_GET_SIZE(o) PyTuple_Size(o) + #define __Pyx_PyList_GET_SIZE(o) PyList_Size(o) + #define __Pyx_PySet_GET_SIZE(o) PySet_Size(o) + #define __Pyx_PyBytes_GET_SIZE(o) PyBytes_Size(o) + #define __Pyx_PyByteArray_GET_SIZE(o) PyByteArray_Size(o) +#endif +#if PY_VERSION_HEX >= 0x030d00A1 + #define __Pyx_PyImport_AddModuleRef(name) PyImport_AddModuleRef(name) +#else + static CYTHON_INLINE PyObject *__Pyx_PyImport_AddModuleRef(const char *name) { + PyObject *module = PyImport_AddModule(name); + Py_XINCREF(module); + return module; + } +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyIntObject PyLongObject + #define PyInt_Type PyLong_Type + #define PyInt_Check(op) PyLong_Check(op) + #define PyInt_CheckExact(op) PyLong_CheckExact(op) + #define __Pyx_Py3Int_Check(op) PyLong_Check(op) + #define __Pyx_Py3Int_CheckExact(op) PyLong_CheckExact(op) + #define PyInt_FromString PyLong_FromString + #define PyInt_FromUnicode PyLong_FromUnicode + #define PyInt_FromLong PyLong_FromLong + #define PyInt_FromSize_t PyLong_FromSize_t + #define PyInt_FromSsize_t PyLong_FromSsize_t + #define PyInt_AsLong PyLong_AsLong + #define PyInt_AS_LONG PyLong_AS_LONG + #define PyInt_AsSsize_t PyLong_AsSsize_t + #define PyInt_AsUnsignedLongMask PyLong_AsUnsignedLongMask + #define PyInt_AsUnsignedLongLongMask PyLong_AsUnsignedLongLongMask + #define PyNumber_Int PyNumber_Long +#else + #define __Pyx_Py3Int_Check(op) (PyLong_Check(op) || PyInt_Check(op)) + #define __Pyx_Py3Int_CheckExact(op) (PyLong_CheckExact(op) || PyInt_CheckExact(op)) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBoolObject PyLongObject +#endif +#if PY_MAJOR_VERSION >= 3 && CYTHON_COMPILING_IN_PYPY + #ifndef PyUnicode_InternFromString + #define PyUnicode_InternFromString(s) PyUnicode_FromString(s) + #endif +#endif +#if PY_VERSION_HEX < 0x030200A4 + typedef long Py_hash_t; + #define __Pyx_PyInt_FromHash_t PyInt_FromLong + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsHash_t +#else + #define __Pyx_PyInt_FromHash_t PyInt_FromSsize_t + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsSsize_t +#endif +#if CYTHON_USE_ASYNC_SLOTS + #if PY_VERSION_HEX >= 0x030500B1 + #define __Pyx_PyAsyncMethodsStruct PyAsyncMethods + #define __Pyx_PyType_AsAsync(obj) (Py_TYPE(obj)->tp_as_async) + #else + #define __Pyx_PyType_AsAsync(obj) ((__Pyx_PyAsyncMethodsStruct*) (Py_TYPE(obj)->tp_reserved)) + #endif +#else + #define __Pyx_PyType_AsAsync(obj) NULL +#endif +#ifndef __Pyx_PyAsyncMethodsStruct + typedef struct { + unaryfunc am_await; + unaryfunc am_aiter; + unaryfunc am_anext; + } __Pyx_PyAsyncMethodsStruct; +#endif + +#if defined(_WIN32) || defined(WIN32) || defined(MS_WINDOWS) + #if !defined(_USE_MATH_DEFINES) + #define _USE_MATH_DEFINES + #endif +#endif +#include +#ifdef NAN +#define __PYX_NAN() ((float) NAN) +#else +static CYTHON_INLINE float __PYX_NAN() { + float value; + memset(&value, 0xFF, sizeof(value)); + return value; +} +#endif +#if defined(__CYGWIN__) && defined(_LDBL_EQ_DBL) +#define __Pyx_truncl trunc +#else +#define __Pyx_truncl truncl +#endif + +#define __PYX_MARK_ERR_POS(f_index, lineno) \ + { __pyx_filename = __pyx_f[f_index]; (void)__pyx_filename; __pyx_lineno = lineno; (void)__pyx_lineno; __pyx_clineno = __LINE__; (void)__pyx_clineno; } +#define __PYX_ERR(f_index, lineno, Ln_error) \ + { __PYX_MARK_ERR_POS(f_index, lineno) goto Ln_error; } + +#ifdef CYTHON_EXTERN_C + #undef __PYX_EXTERN_C + #define __PYX_EXTERN_C CYTHON_EXTERN_C +#elif defined(__PYX_EXTERN_C) + #ifdef _MSC_VER + #pragma message ("Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead.") + #else + #warning Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead. + #endif +#else + #define __PYX_EXTERN_C extern "C++" +#endif + +#define __PYX_HAVE__selfdrive__boardd__boardd_api_impl +#define __PYX_HAVE_API__selfdrive__boardd__boardd_api_impl +/* Early includes */ +#include "ios" +#include "new" +#include "stdexcept" +#include "typeinfo" +#include +#include +#include +#include "panda.h" +#include "can_list_to_can_capnp.cc" +#ifdef _OPENMP +#include +#endif /* _OPENMP */ + +#if defined(PYREX_WITHOUT_ASSERTIONS) && !defined(CYTHON_WITHOUT_ASSERTIONS) +#define CYTHON_WITHOUT_ASSERTIONS +#endif + +typedef struct {PyObject **p; const char *s; const Py_ssize_t n; const char* encoding; + const char is_unicode; const char is_str; const char intern; } __Pyx_StringTabEntry; + +#define __PYX_DEFAULT_STRING_ENCODING_IS_ASCII 0 +#define __PYX_DEFAULT_STRING_ENCODING_IS_UTF8 0 +#define __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT (PY_MAJOR_VERSION >= 3 && __PYX_DEFAULT_STRING_ENCODING_IS_UTF8) +#define __PYX_DEFAULT_STRING_ENCODING "" +#define __Pyx_PyObject_FromString __Pyx_PyBytes_FromString +#define __Pyx_PyObject_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#define __Pyx_uchar_cast(c) ((unsigned char)c) +#define __Pyx_long_cast(x) ((long)x) +#define __Pyx_fits_Py_ssize_t(v, type, is_signed) (\ + (sizeof(type) < sizeof(Py_ssize_t)) ||\ + (sizeof(type) > sizeof(Py_ssize_t) &&\ + likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX) &&\ + (!is_signed || likely(v > (type)PY_SSIZE_T_MIN ||\ + v == (type)PY_SSIZE_T_MIN))) ||\ + (sizeof(type) == sizeof(Py_ssize_t) &&\ + (is_signed || likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX))) ) +static CYTHON_INLINE int __Pyx_is_valid_index(Py_ssize_t i, Py_ssize_t limit) { + return (size_t) i < (size_t) limit; +} +#if defined (__cplusplus) && __cplusplus >= 201103L + #include + #define __Pyx_sst_abs(value) std::abs(value) +#elif SIZEOF_INT >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) abs(value) +#elif SIZEOF_LONG >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) labs(value) +#elif defined (_MSC_VER) + #define __Pyx_sst_abs(value) ((Py_ssize_t)_abs64(value)) +#elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define __Pyx_sst_abs(value) llabs(value) +#elif defined (__GNUC__) + #define __Pyx_sst_abs(value) __builtin_llabs(value) +#else + #define __Pyx_sst_abs(value) ((value<0) ? -value : value) +#endif +static CYTHON_INLINE Py_ssize_t __Pyx_ssize_strlen(const char *s); +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject*); +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject*, Py_ssize_t* length); +static CYTHON_INLINE PyObject* __Pyx_PyByteArray_FromString(const char*); +#define __Pyx_PyByteArray_FromStringAndSize(s, l) PyByteArray_FromStringAndSize((const char*)s, l) +#define __Pyx_PyBytes_FromString PyBytes_FromString +#define __Pyx_PyBytes_FromStringAndSize PyBytes_FromStringAndSize +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char*); +#if PY_MAJOR_VERSION < 3 + #define __Pyx_PyStr_FromString __Pyx_PyBytes_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#else + #define __Pyx_PyStr_FromString __Pyx_PyUnicode_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyUnicode_FromStringAndSize +#endif +#define __Pyx_PyBytes_AsWritableString(s) ((char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableSString(s) ((signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableUString(s) ((unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsString(s) ((const char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsSString(s) ((const signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsUString(s) ((const unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyObject_AsWritableString(s) ((char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableSString(s) ((signed char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableUString(s) ((unsigned char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsSString(s) ((const signed char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsUString(s) ((const unsigned char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_FromCString(s) __Pyx_PyObject_FromString((const char*)s) +#define __Pyx_PyBytes_FromCString(s) __Pyx_PyBytes_FromString((const char*)s) +#define __Pyx_PyByteArray_FromCString(s) __Pyx_PyByteArray_FromString((const char*)s) +#define __Pyx_PyStr_FromCString(s) __Pyx_PyStr_FromString((const char*)s) +#define __Pyx_PyUnicode_FromCString(s) __Pyx_PyUnicode_FromString((const char*)s) +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const wchar_t *u) +{ + const wchar_t *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#else +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const Py_UNICODE *u) +{ + const Py_UNICODE *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#endif +#define __Pyx_PyUnicode_FromOrdinal(o) PyUnicode_FromOrdinal((int)o) +#define __Pyx_PyUnicode_FromUnicode(u) PyUnicode_FromUnicode(u, __Pyx_Py_UNICODE_strlen(u)) +#define __Pyx_PyUnicode_FromUnicodeAndLength PyUnicode_FromUnicode +#define __Pyx_PyUnicode_AsUnicode PyUnicode_AsUnicode +#define __Pyx_NewRef(obj) (Py_INCREF(obj), obj) +#define __Pyx_Owned_Py_None(b) __Pyx_NewRef(Py_None) +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b); +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject*); +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject*); +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x); +#define __Pyx_PySequence_Tuple(obj)\ + (likely(PyTuple_CheckExact(obj)) ? __Pyx_NewRef(obj) : PySequence_Tuple(obj)) +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject*); +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t); +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject*); +#if CYTHON_ASSUME_SAFE_MACROS +#define __pyx_PyFloat_AsDouble(x) (PyFloat_CheckExact(x) ? PyFloat_AS_DOUBLE(x) : PyFloat_AsDouble(x)) +#else +#define __pyx_PyFloat_AsDouble(x) PyFloat_AsDouble(x) +#endif +#define __pyx_PyFloat_AsFloat(x) ((float) __pyx_PyFloat_AsDouble(x)) +#if PY_MAJOR_VERSION >= 3 +#define __Pyx_PyNumber_Int(x) (PyLong_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Long(x)) +#else +#define __Pyx_PyNumber_Int(x) (PyInt_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Int(x)) +#endif +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_VERSION_HEX >= 0x030C00A7 + #ifndef _PyLong_SIGN_MASK + #define _PyLong_SIGN_MASK 3 + #endif + #ifndef _PyLong_NON_SIZE_BITS + #define _PyLong_NON_SIZE_BITS 3 + #endif + #define __Pyx_PyLong_Sign(x) (((PyLongObject*)x)->long_value.lv_tag & _PyLong_SIGN_MASK) + #define __Pyx_PyLong_IsNeg(x) ((__Pyx_PyLong_Sign(x) & 2) != 0) + #define __Pyx_PyLong_IsNonNeg(x) (!__Pyx_PyLong_IsNeg(x)) + #define __Pyx_PyLong_IsZero(x) (__Pyx_PyLong_Sign(x) & 1) + #define __Pyx_PyLong_IsPos(x) (__Pyx_PyLong_Sign(x) == 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) (__Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) ((Py_ssize_t) (((PyLongObject*)x)->long_value.lv_tag >> _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_SignedDigitCount(x)\ + ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * __Pyx_PyLong_DigitCount(x)) + #if defined(PyUnstable_Long_IsCompact) && defined(PyUnstable_Long_CompactValue) + #define __Pyx_PyLong_IsCompact(x) PyUnstable_Long_IsCompact((PyLongObject*) x) + #define __Pyx_PyLong_CompactValue(x) PyUnstable_Long_CompactValue((PyLongObject*) x) + #else + #define __Pyx_PyLong_IsCompact(x) (((PyLongObject*)x)->long_value.lv_tag < (2 << _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_CompactValue(x) ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * (Py_ssize_t) __Pyx_PyLong_Digits(x)[0]) + #endif + typedef Py_ssize_t __Pyx_compact_pylong; + typedef size_t __Pyx_compact_upylong; + #else + #define __Pyx_PyLong_IsNeg(x) (Py_SIZE(x) < 0) + #define __Pyx_PyLong_IsNonNeg(x) (Py_SIZE(x) >= 0) + #define __Pyx_PyLong_IsZero(x) (Py_SIZE(x) == 0) + #define __Pyx_PyLong_IsPos(x) (Py_SIZE(x) > 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) ((Py_SIZE(x) == 0) ? 0 : __Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) __Pyx_sst_abs(Py_SIZE(x)) + #define __Pyx_PyLong_SignedDigitCount(x) Py_SIZE(x) + #define __Pyx_PyLong_IsCompact(x) (Py_SIZE(x) == 0 || Py_SIZE(x) == 1 || Py_SIZE(x) == -1) + #define __Pyx_PyLong_CompactValue(x)\ + ((Py_SIZE(x) == 0) ? (sdigit) 0 : ((Py_SIZE(x) < 0) ? -(sdigit)__Pyx_PyLong_Digits(x)[0] : (sdigit)__Pyx_PyLong_Digits(x)[0])) + typedef sdigit __Pyx_compact_pylong; + typedef digit __Pyx_compact_upylong; + #endif + #if PY_VERSION_HEX >= 0x030C00A5 + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->long_value.ob_digit) + #else + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->ob_digit) + #endif +#endif +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII +#include +static int __Pyx_sys_getdefaultencoding_not_ascii; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + PyObject* ascii_chars_u = NULL; + PyObject* ascii_chars_b = NULL; + const char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + if (strcmp(default_encoding_c, "ascii") == 0) { + __Pyx_sys_getdefaultencoding_not_ascii = 0; + } else { + char ascii_chars[128]; + int c; + for (c = 0; c < 128; c++) { + ascii_chars[c] = (char) c; + } + __Pyx_sys_getdefaultencoding_not_ascii = 1; + ascii_chars_u = PyUnicode_DecodeASCII(ascii_chars, 128, NULL); + if (!ascii_chars_u) goto bad; + ascii_chars_b = PyUnicode_AsEncodedString(ascii_chars_u, default_encoding_c, NULL); + if (!ascii_chars_b || !PyBytes_Check(ascii_chars_b) || memcmp(ascii_chars, PyBytes_AS_STRING(ascii_chars_b), 128) != 0) { + PyErr_Format( + PyExc_ValueError, + "This module compiled with c_string_encoding=ascii, but default encoding '%.200s' is not a superset of ascii.", + default_encoding_c); + goto bad; + } + Py_DECREF(ascii_chars_u); + Py_DECREF(ascii_chars_b); + } + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + Py_XDECREF(ascii_chars_u); + Py_XDECREF(ascii_chars_b); + return -1; +} +#endif +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT && PY_MAJOR_VERSION >= 3 +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_DecodeUTF8(c_str, size, NULL) +#else +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_Decode(c_str, size, __PYX_DEFAULT_STRING_ENCODING, NULL) +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +#include +static char* __PYX_DEFAULT_STRING_ENCODING; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) (const char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + __PYX_DEFAULT_STRING_ENCODING = (char*) malloc(strlen(default_encoding_c) + 1); + if (!__PYX_DEFAULT_STRING_ENCODING) goto bad; + strcpy(__PYX_DEFAULT_STRING_ENCODING, default_encoding_c); + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + return -1; +} +#endif +#endif + + +/* Test for GCC > 2.95 */ +#if defined(__GNUC__) && (__GNUC__ > 2 || (__GNUC__ == 2 && (__GNUC_MINOR__ > 95))) + #define likely(x) __builtin_expect(!!(x), 1) + #define unlikely(x) __builtin_expect(!!(x), 0) +#else /* !__GNUC__ or GCC < 2.95 */ + #define likely(x) (x) + #define unlikely(x) (x) +#endif /* __GNUC__ */ +static CYTHON_INLINE void __Pyx_pretend_to_initialize(void* ptr) { (void)ptr; } + +#if !CYTHON_USE_MODULE_STATE +static PyObject *__pyx_m = NULL; +#endif +static int __pyx_lineno; +static int __pyx_clineno = 0; +static const char * __pyx_cfilenm = __FILE__; +static const char *__pyx_filename; + +/* #### Code section: filename_table ### */ + +static const char *__pyx_f[] = { + "", + "selfdrive/boardd/boardd_api_impl.pyx", +}; +/* #### Code section: utility_code_proto_before_types ### */ +/* ForceInitThreads.proto */ +#ifndef __PYX_FORCE_INIT_THREADS + #define __PYX_FORCE_INIT_THREADS 0 +#endif + +/* #### Code section: numeric_typedefs ### */ +/* #### Code section: complex_type_declarations ### */ +/* #### Code section: type_declarations ### */ + +/*--- Type declarations ---*/ +/* #### Code section: utility_code_proto ### */ + +/* --- Runtime support code (head) --- */ +/* Refnanny.proto */ +#ifndef CYTHON_REFNANNY + #define CYTHON_REFNANNY 0 +#endif +#if CYTHON_REFNANNY + typedef struct { + void (*INCREF)(void*, PyObject*, Py_ssize_t); + void (*DECREF)(void*, PyObject*, Py_ssize_t); + void (*GOTREF)(void*, PyObject*, Py_ssize_t); + void (*GIVEREF)(void*, PyObject*, Py_ssize_t); + void* (*SetupContext)(const char*, Py_ssize_t, const char*); + void (*FinishContext)(void**); + } __Pyx_RefNannyAPIStruct; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNanny = NULL; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname); + #define __Pyx_RefNannyDeclarations void *__pyx_refnanny = NULL; +#ifdef WITH_THREAD + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + if (acquire_gil) {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + PyGILState_Release(__pyx_gilstate_save);\ + } else {\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + } + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } +#else + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__)) + #define __Pyx_RefNannyFinishContextNogil() __Pyx_RefNannyFinishContext() +#endif + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } + #define __Pyx_RefNannyFinishContext()\ + __Pyx_RefNanny->FinishContext(&__pyx_refnanny) + #define __Pyx_INCREF(r) __Pyx_RefNanny->INCREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_DECREF(r) __Pyx_RefNanny->DECREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GOTREF(r) __Pyx_RefNanny->GOTREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GIVEREF(r) __Pyx_RefNanny->GIVEREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_XINCREF(r) do { if((r) == NULL); else {__Pyx_INCREF(r); }} while(0) + #define __Pyx_XDECREF(r) do { if((r) == NULL); else {__Pyx_DECREF(r); }} while(0) + #define __Pyx_XGOTREF(r) do { if((r) == NULL); else {__Pyx_GOTREF(r); }} while(0) + #define __Pyx_XGIVEREF(r) do { if((r) == NULL); else {__Pyx_GIVEREF(r);}} while(0) +#else + #define __Pyx_RefNannyDeclarations + #define __Pyx_RefNannySetupContext(name, acquire_gil) + #define __Pyx_RefNannyFinishContextNogil() + #define __Pyx_RefNannyFinishContext() + #define __Pyx_INCREF(r) Py_INCREF(r) + #define __Pyx_DECREF(r) Py_DECREF(r) + #define __Pyx_GOTREF(r) + #define __Pyx_GIVEREF(r) + #define __Pyx_XINCREF(r) Py_XINCREF(r) + #define __Pyx_XDECREF(r) Py_XDECREF(r) + #define __Pyx_XGOTREF(r) + #define __Pyx_XGIVEREF(r) +#endif +#define __Pyx_Py_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; Py_XDECREF(tmp);\ + } while (0) +#define __Pyx_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_XDECREF(tmp);\ + } while (0) +#define __Pyx_DECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_DECREF(tmp);\ + } while (0) +#define __Pyx_CLEAR(r) do { PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);} while(0) +#define __Pyx_XCLEAR(r) do { if((r) != NULL) {PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);}} while(0) + +/* TupleAndListFromArray.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n); +static CYTHON_INLINE PyObject* __Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n); +#endif + +/* IncludeStringH.proto */ +#include + +/* BytesEquals.proto */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals); + +/* UnicodeEquals.proto */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals); + +/* fastcall.proto */ +#if CYTHON_AVOID_BORROWED_REFS + #define __Pyx_Arg_VARARGS(args, i) PySequence_GetItem(args, i) +#elif CYTHON_ASSUME_SAFE_MACROS + #define __Pyx_Arg_VARARGS(args, i) PyTuple_GET_ITEM(args, i) +#else + #define __Pyx_Arg_VARARGS(args, i) PyTuple_GetItem(args, i) +#endif +#if CYTHON_AVOID_BORROWED_REFS + #define __Pyx_Arg_NewRef_VARARGS(arg) __Pyx_NewRef(arg) + #define __Pyx_Arg_XDECREF_VARARGS(arg) Py_XDECREF(arg) +#else + #define __Pyx_Arg_NewRef_VARARGS(arg) arg + #define __Pyx_Arg_XDECREF_VARARGS(arg) +#endif +#define __Pyx_NumKwargs_VARARGS(kwds) PyDict_Size(kwds) +#define __Pyx_KwValues_VARARGS(args, nargs) NULL +#define __Pyx_GetKwValue_VARARGS(kw, kwvalues, s) __Pyx_PyDict_GetItemStrWithError(kw, s) +#define __Pyx_KwargsAsDict_VARARGS(kw, kwvalues) PyDict_Copy(kw) +#if CYTHON_METH_FASTCALL + #define __Pyx_Arg_FASTCALL(args, i) args[i] + #define __Pyx_NumKwargs_FASTCALL(kwds) PyTuple_GET_SIZE(kwds) + #define __Pyx_KwValues_FASTCALL(args, nargs) ((args) + (nargs)) + static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 + CYTHON_UNUSED static PyObject *__Pyx_KwargsAsDict_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues); + #else + #define __Pyx_KwargsAsDict_FASTCALL(kw, kwvalues) _PyStack_AsDict(kwvalues, kw) + #endif + #define __Pyx_Arg_NewRef_FASTCALL(arg) arg /* no-op, __Pyx_Arg_FASTCALL is direct and this needs + to have the same reference counting */ + #define __Pyx_Arg_XDECREF_FASTCALL(arg) +#else + #define __Pyx_Arg_FASTCALL __Pyx_Arg_VARARGS + #define __Pyx_NumKwargs_FASTCALL __Pyx_NumKwargs_VARARGS + #define __Pyx_KwValues_FASTCALL __Pyx_KwValues_VARARGS + #define __Pyx_GetKwValue_FASTCALL __Pyx_GetKwValue_VARARGS + #define __Pyx_KwargsAsDict_FASTCALL __Pyx_KwargsAsDict_VARARGS + #define __Pyx_Arg_NewRef_FASTCALL(arg) __Pyx_Arg_NewRef_VARARGS(arg) + #define __Pyx_Arg_XDECREF_FASTCALL(arg) __Pyx_Arg_XDECREF_VARARGS(arg) +#endif +#if CYTHON_COMPILING_IN_CPYTHON && CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_VARARGS(args, start), stop - start) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_FASTCALL(args, start), stop - start) +#else +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) PyTuple_GetSlice(args, start, stop) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) PyTuple_GetSlice(args, start, stop) +#endif + +/* RaiseDoubleKeywords.proto */ +static void __Pyx_RaiseDoubleKeywordsError(const char* func_name, PyObject* kw_name); + +/* ParseKeywords.proto */ +static int __Pyx_ParseOptionalKeywords(PyObject *kwds, PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, PyObject *values[], Py_ssize_t num_pos_args, + const char* function_name); + +/* RaiseArgTupleInvalid.proto */ +static void __Pyx_RaiseArgtupleInvalid(const char* func_name, int exact, + Py_ssize_t num_min, Py_ssize_t num_max, Py_ssize_t num_found); + +/* GetItemInt.proto */ +#define __Pyx_GetItemInt(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_Fast(o, (Py_ssize_t)i, is_list, wraparound, boundscheck) :\ + (is_list ? (PyErr_SetString(PyExc_IndexError, "list index out of range"), (PyObject*)NULL) :\ + __Pyx_GetItemInt_Generic(o, to_py_func(i)))) +#define __Pyx_GetItemInt_List(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_List_Fast(o, (Py_ssize_t)i, wraparound, boundscheck) :\ + (PyErr_SetString(PyExc_IndexError, "list index out of range"), (PyObject*)NULL)) +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_List_Fast(PyObject *o, Py_ssize_t i, + int wraparound, int boundscheck); +#define __Pyx_GetItemInt_Tuple(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_Tuple_Fast(o, (Py_ssize_t)i, wraparound, boundscheck) :\ + (PyErr_SetString(PyExc_IndexError, "tuple index out of range"), (PyObject*)NULL)) +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Tuple_Fast(PyObject *o, Py_ssize_t i, + int wraparound, int boundscheck); +static PyObject *__Pyx_GetItemInt_Generic(PyObject *o, PyObject* j); +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Fast(PyObject *o, Py_ssize_t i, + int is_list, int wraparound, int boundscheck); + +/* MoveIfSupported.proto */ +#if CYTHON_USE_CPP_STD_MOVE + #include + #define __PYX_STD_MOVE_IF_SUPPORTED(x) std::move(x) +#else + #define __PYX_STD_MOVE_IF_SUPPORTED(x) x +#endif + +/* IncludeStructmemberH.proto */ +#include + +/* FixUpExtensionType.proto */ +#if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type); +#endif + +/* FetchSharedCythonModule.proto */ +static PyObject *__Pyx_FetchSharedCythonABIModule(void); + +/* FetchCommonType.proto */ +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type); +#else +static PyTypeObject* __Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases); +#endif + +/* PyMethodNew.proto */ +#if CYTHON_COMPILING_IN_LIMITED_API +static PyObject *__Pyx_PyMethod_New(PyObject *func, PyObject *self, PyObject *typ) { + PyObject *typesModule=NULL, *methodType=NULL, *result=NULL; + CYTHON_UNUSED_VAR(typ); + if (!self) + return __Pyx_NewRef(func); + typesModule = PyImport_ImportModule("types"); + if (!typesModule) return NULL; + methodType = PyObject_GetAttrString(typesModule, "MethodType"); + Py_DECREF(typesModule); + if (!methodType) return NULL; + result = PyObject_CallFunctionObjArgs(methodType, func, self, NULL); + Py_DECREF(methodType); + return result; +} +#elif PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_PyMethod_New(PyObject *func, PyObject *self, PyObject *typ) { + CYTHON_UNUSED_VAR(typ); + if (!self) + return __Pyx_NewRef(func); + return PyMethod_New(func, self); +} +#else + #define __Pyx_PyMethod_New PyMethod_New +#endif + +/* PyObjectGetAttrStr.proto */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GetAttrStr(o,n) PyObject_GetAttr(o,n) +#endif + +/* PyVectorcallFastCallDict.proto */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw); +#endif + +/* CythonFunctionShared.proto */ +#define __Pyx_CyFunction_USED +#define __Pyx_CYFUNCTION_STATICMETHOD 0x01 +#define __Pyx_CYFUNCTION_CLASSMETHOD 0x02 +#define __Pyx_CYFUNCTION_CCLASS 0x04 +#define __Pyx_CYFUNCTION_COROUTINE 0x08 +#define __Pyx_CyFunction_GetClosure(f)\ + (((__pyx_CyFunctionObject *) (f))->func_closure) +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_CyFunction_GetClassObj(f)\ + (((__pyx_CyFunctionObject *) (f))->func_classobj) +#else + #define __Pyx_CyFunction_GetClassObj(f)\ + ((PyObject*) ((PyCMethodObject *) (f))->mm_class) +#endif +#define __Pyx_CyFunction_SetClassObj(f, classobj)\ + __Pyx__CyFunction_SetClassObj((__pyx_CyFunctionObject *) (f), (classobj)) +#define __Pyx_CyFunction_Defaults(type, f)\ + ((type *)(((__pyx_CyFunctionObject *) (f))->defaults)) +#define __Pyx_CyFunction_SetDefaultsGetter(f, g)\ + ((__pyx_CyFunctionObject *) (f))->defaults_getter = (g) +typedef struct { +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject_HEAD + PyObject *func; +#elif PY_VERSION_HEX < 0x030900B1 + PyCFunctionObject func; +#else + PyCMethodObject func; +#endif +#if CYTHON_BACKPORT_VECTORCALL + __pyx_vectorcallfunc func_vectorcall; +#endif +#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API + PyObject *func_weakreflist; +#endif + PyObject *func_dict; + PyObject *func_name; + PyObject *func_qualname; + PyObject *func_doc; + PyObject *func_globals; + PyObject *func_code; + PyObject *func_closure; +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + PyObject *func_classobj; +#endif + void *defaults; + int defaults_pyobjects; + size_t defaults_size; + int flags; + PyObject *defaults_tuple; + PyObject *defaults_kwdict; + PyObject *(*defaults_getter)(PyObject *); + PyObject *func_annotations; + PyObject *func_is_coroutine; +} __pyx_CyFunctionObject; +#undef __Pyx_CyOrPyCFunction_Check +#define __Pyx_CyFunction_Check(obj) __Pyx_TypeCheck(obj, __pyx_CyFunctionType) +#define __Pyx_CyOrPyCFunction_Check(obj) __Pyx_TypeCheck2(obj, __pyx_CyFunctionType, &PyCFunction_Type) +#define __Pyx_CyFunction_CheckExact(obj) __Pyx_IS_TYPE(obj, __pyx_CyFunctionType) +static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc); +#undef __Pyx_IsSameCFunction +#define __Pyx_IsSameCFunction(func, cfunc) __Pyx__IsSameCyOrCFunction(func, cfunc) +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject* op, PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj); +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *m, + size_t size, + int pyobjects); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *m, + PyObject *tuple); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *m, + PyObject *dict); +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *m, + PyObject *dict); +static int __pyx_CyFunction_init(PyObject *module); +#if CYTHON_METH_FASTCALL +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +#if CYTHON_BACKPORT_VECTORCALL +#define __Pyx_CyFunction_func_vectorcall(f) (((__pyx_CyFunctionObject*)f)->func_vectorcall) +#else +#define __Pyx_CyFunction_func_vectorcall(f) (((PyCFunctionObject*)f)->vectorcall) +#endif +#endif + +/* CythonFunction.proto */ +static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); + +/* PyDictVersioning.proto */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +#define __PYX_DICT_VERSION_INIT ((PY_UINT64_T) -1) +#define __PYX_GET_DICT_VERSION(dict) (((PyDictObject*)(dict))->ma_version_tag) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var)\ + (version_var) = __PYX_GET_DICT_VERSION(dict);\ + (cache_var) = (value); +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + if (likely(__PYX_GET_DICT_VERSION(DICT) == __pyx_dict_version)) {\ + (VAR) = __pyx_dict_cached_value;\ + } else {\ + (VAR) = __pyx_dict_cached_value = (LOOKUP);\ + __pyx_dict_version = __PYX_GET_DICT_VERSION(DICT);\ + }\ +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj); +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj); +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version); +#else +#define __PYX_GET_DICT_VERSION(dict) (0) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var) +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) (VAR) = (LOOKUP); +#endif + +/* PyErrExceptionMatches.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_ExceptionMatches(err) __Pyx_PyErr_ExceptionMatchesInState(__pyx_tstate, err) +static CYTHON_INLINE int __Pyx_PyErr_ExceptionMatchesInState(PyThreadState* tstate, PyObject* err); +#else +#define __Pyx_PyErr_ExceptionMatches(err) PyErr_ExceptionMatches(err) +#endif + +/* PyThreadStateGet.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyThreadState_declare PyThreadState *__pyx_tstate; +#define __Pyx_PyThreadState_assign __pyx_tstate = __Pyx_PyThreadState_Current; +#if PY_VERSION_HEX >= 0x030C00A6 +#define __Pyx_PyErr_Occurred() (__pyx_tstate->current_exception != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->current_exception ? (PyObject*) Py_TYPE(__pyx_tstate->current_exception) : (PyObject*) NULL) +#else +#define __Pyx_PyErr_Occurred() (__pyx_tstate->curexc_type != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->curexc_type) +#endif +#else +#define __Pyx_PyThreadState_declare +#define __Pyx_PyThreadState_assign +#define __Pyx_PyErr_Occurred() (PyErr_Occurred() != NULL) +#define __Pyx_PyErr_CurrentExceptionType() PyErr_Occurred() +#endif + +/* PyErrFetchRestore.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_Clear() __Pyx_ErrRestore(NULL, NULL, NULL) +#define __Pyx_ErrRestoreWithState(type, value, tb) __Pyx_ErrRestoreInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) __Pyx_ErrFetchInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) __Pyx_ErrRestoreInState(__pyx_tstate, type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) __Pyx_ErrFetchInState(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb); +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A6 +#define __Pyx_PyErr_SetNone(exc) (Py_INCREF(exc), __Pyx_ErrRestore((exc), NULL, NULL)) +#else +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#endif +#else +#define __Pyx_PyErr_Clear() PyErr_Clear() +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#define __Pyx_ErrRestoreWithState(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestoreInState(tstate, type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchInState(tstate, type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) PyErr_Fetch(type, value, tb) +#endif + +/* PyObjectGetAttrStrNoError.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name); + +/* CLineInTraceback.proto */ +#ifdef CYTHON_CLINE_IN_TRACEBACK +#define __Pyx_CLineForTraceback(tstate, c_line) (((CYTHON_CLINE_IN_TRACEBACK)) ? c_line : 0) +#else +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line); +#endif + +/* CodeObjectCache.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +typedef struct { + PyCodeObject* code_object; + int code_line; +} __Pyx_CodeObjectCacheEntry; +struct __Pyx_CodeObjectCache { + int count; + int max_count; + __Pyx_CodeObjectCacheEntry* entries; +}; +static struct __Pyx_CodeObjectCache __pyx_code_cache = {0,0,NULL}; +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line); +static PyCodeObject *__pyx_find_code_object(int code_line); +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object); +#endif + +/* AddTraceback.proto */ +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename); + +/* CppExceptionConversion.proto */ +#ifndef __Pyx_CppExn2PyErr +#include +#include +#include +#include +static void __Pyx_CppExn2PyErr() { + try { + if (PyErr_Occurred()) + ; // let the latest Python exn pass through and ignore the current one + else + throw; + } catch (const std::bad_alloc& exn) { + PyErr_SetString(PyExc_MemoryError, exn.what()); + } catch (const std::bad_cast& exn) { + PyErr_SetString(PyExc_TypeError, exn.what()); + } catch (const std::bad_typeid& exn) { + PyErr_SetString(PyExc_TypeError, exn.what()); + } catch (const std::domain_error& exn) { + PyErr_SetString(PyExc_ValueError, exn.what()); + } catch (const std::invalid_argument& exn) { + PyErr_SetString(PyExc_ValueError, exn.what()); + } catch (const std::ios_base::failure& exn) { + PyErr_SetString(PyExc_IOError, exn.what()); + } catch (const std::out_of_range& exn) { + PyErr_SetString(PyExc_IndexError, exn.what()); + } catch (const std::overflow_error& exn) { + PyErr_SetString(PyExc_OverflowError, exn.what()); + } catch (const std::range_error& exn) { + PyErr_SetString(PyExc_ArithmeticError, exn.what()); + } catch (const std::underflow_error& exn) { + PyErr_SetString(PyExc_ArithmeticError, exn.what()); + } catch (const std::exception& exn) { + PyErr_SetString(PyExc_RuntimeError, exn.what()); + } + catch (...) + { + PyErr_SetString(PyExc_RuntimeError, "Unknown exception"); + } +} +#endif + +/* GCCDiagnostics.proto */ +#if !defined(__INTEL_COMPILER) && defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 6)) +#define __Pyx_HAS_GCC_DIAGNOSTIC +#endif + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value); + +/* CIntFromPy.proto */ +static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *); + +/* FormatTypeName.proto */ +#if CYTHON_COMPILING_IN_LIMITED_API +typedef PyObject *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%U" +static __Pyx_TypeName __Pyx_PyType_GetName(PyTypeObject* tp); +#define __Pyx_DECREF_TypeName(obj) Py_XDECREF(obj) +#else +typedef const char *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%.200s" +#define __Pyx_PyType_GetName(tp) ((tp)->tp_name) +#define __Pyx_DECREF_TypeName(obj) +#endif + +/* CIntFromPy.proto */ +static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *); + +/* FastTypeChecks.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_TypeCheck(obj, type) __Pyx_IsSubtype(Py_TYPE(obj), (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) __Pyx_IsAnySubtype2(Py_TYPE(obj), (PyTypeObject *)type1, (PyTypeObject *)type2) +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches(PyObject *err, PyObject *type); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches2(PyObject *err, PyObject *type1, PyObject *type2); +#else +#define __Pyx_TypeCheck(obj, type) PyObject_TypeCheck(obj, (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) (PyObject_TypeCheck(obj, (PyTypeObject *)type1) || PyObject_TypeCheck(obj, (PyTypeObject *)type2)) +#define __Pyx_PyErr_GivenExceptionMatches(err, type) PyErr_GivenExceptionMatches(err, type) +#define __Pyx_PyErr_GivenExceptionMatches2(err, type1, type2) (PyErr_GivenExceptionMatches(err, type1) || PyErr_GivenExceptionMatches(err, type2)) +#endif +#define __Pyx_PyErr_ExceptionMatches2(err1, err2) __Pyx_PyErr_GivenExceptionMatches2(__Pyx_PyErr_CurrentExceptionType(), err1, err2) +#define __Pyx_PyException_Check(obj) __Pyx_TypeCheck(obj, PyExc_Exception) + +/* CheckBinaryVersion.proto */ +static unsigned long __Pyx_get_runtime_version(void); +static int __Pyx_check_binary_version(unsigned long ct_version, unsigned long rt_version, int allow_newer); + +/* InitStrings.proto */ +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t); + +/* #### Code section: module_declarations ### */ + +/* Module declarations from "libcpp.vector" */ + +/* Module declarations from "libc.string" */ + +/* Module declarations from "libcpp.string" */ + +/* Module declarations from "libcpp" */ + +/* Module declarations from "selfdrive.boardd.boardd_api_impl" */ +static std::string __pyx_convert_string_from_py_std__in_string(PyObject *); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyObject_string_to_py_std__in_string(std::string const &); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyUnicode_string_to_py_std__in_string(std::string const &); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyStr_string_to_py_std__in_string(std::string const &); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyBytes_string_to_py_std__in_string(std::string const &); /*proto*/ +static CYTHON_INLINE PyObject *__pyx_convert_PyByteArray_string_to_py_std__in_string(std::string const &); /*proto*/ +/* #### Code section: typeinfo ### */ +/* #### Code section: before_global_var ### */ +#define __Pyx_MODULE_NAME "selfdrive.boardd.boardd_api_impl" +extern int __pyx_module_is_main_selfdrive__boardd__boardd_api_impl; +int __pyx_module_is_main_selfdrive__boardd__boardd_api_impl = 0; + +/* Implementation of "selfdrive.boardd.boardd_api_impl" */ +/* #### Code section: global_var ### */ +/* #### Code section: string_decls ### */ +static const char __pyx_k_f[] = "f"; +static const char __pyx_k__4[] = "?"; +static const char __pyx_k_can[] = "can"; +static const char __pyx_k_out[] = "out"; +static const char __pyx_k_main[] = "__main__"; +static const char __pyx_k_name[] = "__name__"; +static const char __pyx_k_test[] = "__test__"; +static const char __pyx_k_valid[] = "valid"; +static const char __pyx_k_can_msg[] = "can_msg"; +static const char __pyx_k_msgtype[] = "msgtype"; +static const char __pyx_k_sendcan[] = "sendcan"; +static const char __pyx_k_can_list[] = "can_list"; +static const char __pyx_k_can_msgs[] = "can_msgs"; +static const char __pyx_k_is_coroutine[] = "_is_coroutine"; +static const char __pyx_k_asyncio_coroutines[] = "asyncio.coroutines"; +static const char __pyx_k_cline_in_traceback[] = "cline_in_traceback"; +static const char __pyx_k_can_list_to_can_capnp[] = "can_list_to_can_capnp"; +static const char __pyx_k_selfdrive_boardd_boardd_api_impl[] = "selfdrive/boardd/boardd_api_impl.pyx"; +static const char __pyx_k_selfdrive_boardd_boardd_api_impl_2[] = "selfdrive.boardd.boardd_api_impl"; +/* #### Code section: decls ### */ +static PyObject *__pyx_pf_9selfdrive_6boardd_15boardd_api_impl_can_list_to_can_capnp(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_can_msgs, PyObject *__pyx_v_msgtype, PyObject *__pyx_v_valid); /* proto */ +/* #### Code section: late_includes ### */ +/* #### Code section: module_state ### */ +typedef struct { + PyObject *__pyx_d; + PyObject *__pyx_b; + PyObject *__pyx_cython_runtime; + PyObject *__pyx_empty_tuple; + PyObject *__pyx_empty_bytes; + PyObject *__pyx_empty_unicode; + #ifdef __Pyx_CyFunction_USED + PyTypeObject *__pyx_CyFunctionType; + #endif + #ifdef __Pyx_FusedFunction_USED + PyTypeObject *__pyx_FusedFunctionType; + #endif + #ifdef __Pyx_Generator_USED + PyTypeObject *__pyx_GeneratorType; + #endif + #ifdef __Pyx_IterableCoroutine_USED + PyTypeObject *__pyx_IterableCoroutineType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineAwaitType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineType; + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + PyObject *__pyx_n_s__4; + PyObject *__pyx_n_s_asyncio_coroutines; + PyObject *__pyx_n_u_can; + PyObject *__pyx_n_s_can_list; + PyObject *__pyx_n_s_can_list_to_can_capnp; + PyObject *__pyx_n_s_can_msg; + PyObject *__pyx_n_s_can_msgs; + PyObject *__pyx_n_s_cline_in_traceback; + PyObject *__pyx_n_s_f; + PyObject *__pyx_n_s_is_coroutine; + PyObject *__pyx_n_s_main; + PyObject *__pyx_n_s_msgtype; + PyObject *__pyx_n_s_name; + PyObject *__pyx_n_s_out; + PyObject *__pyx_kp_s_selfdrive_boardd_boardd_api_impl; + PyObject *__pyx_n_s_selfdrive_boardd_boardd_api_impl_2; + PyObject *__pyx_n_u_sendcan; + PyObject *__pyx_n_s_test; + PyObject *__pyx_n_s_valid; + PyObject *__pyx_tuple_; + PyObject *__pyx_tuple__3; + PyObject *__pyx_codeobj__2; +} __pyx_mstate; + +#if CYTHON_USE_MODULE_STATE +#ifdef __cplusplus +namespace { + extern struct PyModuleDef __pyx_moduledef; +} /* anonymous namespace */ +#else +static struct PyModuleDef __pyx_moduledef; +#endif + +#define __pyx_mstate(o) ((__pyx_mstate *)__Pyx_PyModule_GetState(o)) + +#define __pyx_mstate_global (__pyx_mstate(PyState_FindModule(&__pyx_moduledef))) + +#define __pyx_m (PyState_FindModule(&__pyx_moduledef)) +#else +static __pyx_mstate __pyx_mstate_global_static = +#ifdef __cplusplus + {}; +#else + {0}; +#endif +static __pyx_mstate *__pyx_mstate_global = &__pyx_mstate_global_static; +#endif +/* #### Code section: module_state_clear ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_clear(PyObject *m) { + __pyx_mstate *clear_module_state = __pyx_mstate(m); + if (!clear_module_state) return 0; + Py_CLEAR(clear_module_state->__pyx_d); + Py_CLEAR(clear_module_state->__pyx_b); + Py_CLEAR(clear_module_state->__pyx_cython_runtime); + Py_CLEAR(clear_module_state->__pyx_empty_tuple); + Py_CLEAR(clear_module_state->__pyx_empty_bytes); + Py_CLEAR(clear_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_CLEAR(clear_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_CLEAR(clear_module_state->__pyx_FusedFunctionType); + #endif + Py_CLEAR(clear_module_state->__pyx_n_s__4); + Py_CLEAR(clear_module_state->__pyx_n_s_asyncio_coroutines); + Py_CLEAR(clear_module_state->__pyx_n_u_can); + Py_CLEAR(clear_module_state->__pyx_n_s_can_list); + Py_CLEAR(clear_module_state->__pyx_n_s_can_list_to_can_capnp); + Py_CLEAR(clear_module_state->__pyx_n_s_can_msg); + Py_CLEAR(clear_module_state->__pyx_n_s_can_msgs); + Py_CLEAR(clear_module_state->__pyx_n_s_cline_in_traceback); + Py_CLEAR(clear_module_state->__pyx_n_s_f); + Py_CLEAR(clear_module_state->__pyx_n_s_is_coroutine); + Py_CLEAR(clear_module_state->__pyx_n_s_main); + Py_CLEAR(clear_module_state->__pyx_n_s_msgtype); + Py_CLEAR(clear_module_state->__pyx_n_s_name); + Py_CLEAR(clear_module_state->__pyx_n_s_out); + Py_CLEAR(clear_module_state->__pyx_kp_s_selfdrive_boardd_boardd_api_impl); + Py_CLEAR(clear_module_state->__pyx_n_s_selfdrive_boardd_boardd_api_impl_2); + Py_CLEAR(clear_module_state->__pyx_n_u_sendcan); + Py_CLEAR(clear_module_state->__pyx_n_s_test); + Py_CLEAR(clear_module_state->__pyx_n_s_valid); + Py_CLEAR(clear_module_state->__pyx_tuple_); + Py_CLEAR(clear_module_state->__pyx_tuple__3); + Py_CLEAR(clear_module_state->__pyx_codeobj__2); + return 0; +} +#endif +/* #### Code section: module_state_traverse ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { + __pyx_mstate *traverse_module_state = __pyx_mstate(m); + if (!traverse_module_state) return 0; + Py_VISIT(traverse_module_state->__pyx_d); + Py_VISIT(traverse_module_state->__pyx_b); + Py_VISIT(traverse_module_state->__pyx_cython_runtime); + Py_VISIT(traverse_module_state->__pyx_empty_tuple); + Py_VISIT(traverse_module_state->__pyx_empty_bytes); + Py_VISIT(traverse_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_VISIT(traverse_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_VISIT(traverse_module_state->__pyx_FusedFunctionType); + #endif + Py_VISIT(traverse_module_state->__pyx_n_s__4); + Py_VISIT(traverse_module_state->__pyx_n_s_asyncio_coroutines); + Py_VISIT(traverse_module_state->__pyx_n_u_can); + Py_VISIT(traverse_module_state->__pyx_n_s_can_list); + Py_VISIT(traverse_module_state->__pyx_n_s_can_list_to_can_capnp); + Py_VISIT(traverse_module_state->__pyx_n_s_can_msg); + Py_VISIT(traverse_module_state->__pyx_n_s_can_msgs); + Py_VISIT(traverse_module_state->__pyx_n_s_cline_in_traceback); + Py_VISIT(traverse_module_state->__pyx_n_s_f); + Py_VISIT(traverse_module_state->__pyx_n_s_is_coroutine); + Py_VISIT(traverse_module_state->__pyx_n_s_main); + Py_VISIT(traverse_module_state->__pyx_n_s_msgtype); + Py_VISIT(traverse_module_state->__pyx_n_s_name); + Py_VISIT(traverse_module_state->__pyx_n_s_out); + Py_VISIT(traverse_module_state->__pyx_kp_s_selfdrive_boardd_boardd_api_impl); + Py_VISIT(traverse_module_state->__pyx_n_s_selfdrive_boardd_boardd_api_impl_2); + Py_VISIT(traverse_module_state->__pyx_n_u_sendcan); + Py_VISIT(traverse_module_state->__pyx_n_s_test); + Py_VISIT(traverse_module_state->__pyx_n_s_valid); + Py_VISIT(traverse_module_state->__pyx_tuple_); + Py_VISIT(traverse_module_state->__pyx_tuple__3); + Py_VISIT(traverse_module_state->__pyx_codeobj__2); + return 0; +} +#endif +/* #### Code section: module_state_defines ### */ +#define __pyx_d __pyx_mstate_global->__pyx_d +#define __pyx_b __pyx_mstate_global->__pyx_b +#define __pyx_cython_runtime __pyx_mstate_global->__pyx_cython_runtime +#define __pyx_empty_tuple __pyx_mstate_global->__pyx_empty_tuple +#define __pyx_empty_bytes __pyx_mstate_global->__pyx_empty_bytes +#define __pyx_empty_unicode __pyx_mstate_global->__pyx_empty_unicode +#ifdef __Pyx_CyFunction_USED +#define __pyx_CyFunctionType __pyx_mstate_global->__pyx_CyFunctionType +#endif +#ifdef __Pyx_FusedFunction_USED +#define __pyx_FusedFunctionType __pyx_mstate_global->__pyx_FusedFunctionType +#endif +#ifdef __Pyx_Generator_USED +#define __pyx_GeneratorType __pyx_mstate_global->__pyx_GeneratorType +#endif +#ifdef __Pyx_IterableCoroutine_USED +#define __pyx_IterableCoroutineType __pyx_mstate_global->__pyx_IterableCoroutineType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineAwaitType __pyx_mstate_global->__pyx_CoroutineAwaitType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineType __pyx_mstate_global->__pyx_CoroutineType +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#define __pyx_n_s__4 __pyx_mstate_global->__pyx_n_s__4 +#define __pyx_n_s_asyncio_coroutines __pyx_mstate_global->__pyx_n_s_asyncio_coroutines +#define __pyx_n_u_can __pyx_mstate_global->__pyx_n_u_can +#define __pyx_n_s_can_list __pyx_mstate_global->__pyx_n_s_can_list +#define __pyx_n_s_can_list_to_can_capnp __pyx_mstate_global->__pyx_n_s_can_list_to_can_capnp +#define __pyx_n_s_can_msg __pyx_mstate_global->__pyx_n_s_can_msg +#define __pyx_n_s_can_msgs __pyx_mstate_global->__pyx_n_s_can_msgs +#define __pyx_n_s_cline_in_traceback __pyx_mstate_global->__pyx_n_s_cline_in_traceback +#define __pyx_n_s_f __pyx_mstate_global->__pyx_n_s_f +#define __pyx_n_s_is_coroutine __pyx_mstate_global->__pyx_n_s_is_coroutine +#define __pyx_n_s_main __pyx_mstate_global->__pyx_n_s_main +#define __pyx_n_s_msgtype __pyx_mstate_global->__pyx_n_s_msgtype +#define __pyx_n_s_name __pyx_mstate_global->__pyx_n_s_name +#define __pyx_n_s_out __pyx_mstate_global->__pyx_n_s_out +#define __pyx_kp_s_selfdrive_boardd_boardd_api_impl __pyx_mstate_global->__pyx_kp_s_selfdrive_boardd_boardd_api_impl +#define __pyx_n_s_selfdrive_boardd_boardd_api_impl_2 __pyx_mstate_global->__pyx_n_s_selfdrive_boardd_boardd_api_impl_2 +#define __pyx_n_u_sendcan __pyx_mstate_global->__pyx_n_u_sendcan +#define __pyx_n_s_test __pyx_mstate_global->__pyx_n_s_test +#define __pyx_n_s_valid __pyx_mstate_global->__pyx_n_s_valid +#define __pyx_tuple_ __pyx_mstate_global->__pyx_tuple_ +#define __pyx_tuple__3 __pyx_mstate_global->__pyx_tuple__3 +#define __pyx_codeobj__2 __pyx_mstate_global->__pyx_codeobj__2 +/* #### Code section: module_code ### */ + +/* "string.from_py":13 + * + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: # <<<<<<<<<<<<<< + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + */ + +static std::string __pyx_convert_string_from_py_std__in_string(PyObject *__pyx_v_o) { + Py_ssize_t __pyx_v_length; + char const *__pyx_v_data; + std::string __pyx_r; + char const *__pyx_t_1; + std::string __pyx_t_2; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + + /* "string.from_py":14 + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: + * cdef Py_ssize_t length = 0 # <<<<<<<<<<<<<< + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + * return string(data, length) + */ + __pyx_v_length = 0; + + /* "string.from_py":15 + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) # <<<<<<<<<<<<<< + * return string(data, length) + * + */ + __pyx_t_1 = __Pyx_PyObject_AsStringAndSize(__pyx_v_o, (&__pyx_v_length)); if (unlikely(__pyx_t_1 == ((char const *)NULL))) __PYX_ERR(0, 15, __pyx_L1_error) + __pyx_v_data = __pyx_t_1; + + /* "string.from_py":16 + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + * return string(data, length) # <<<<<<<<<<<<<< + * + * + */ + try { + __pyx_t_2 = std::string(__pyx_v_data, __pyx_v_length); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(0, 16, __pyx_L1_error) + } + __pyx_r = __pyx_t_2; + goto __pyx_L0; + + /* "string.from_py":13 + * + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: # <<<<<<<<<<<<<< + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("string.from_py.__pyx_convert_string_from_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_pretend_to_initialize(&__pyx_r); + __pyx_L0:; + return __pyx_r; +} + +/* "string.to_py":31 + * + * @cname("__pyx_convert_PyObject_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyObject_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyObject_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyObject_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyObject_string_to_py_std__in_string", 1); + + /* "string.to_py":32 + * @cname("__pyx_convert_PyObject_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyObject_string_to_py_std__in_string(const string& s): + * return __Pyx_PyObject_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * cdef extern from *: + * cdef object __Pyx_PyUnicode_FromStringAndSize(const char*, size_t) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 32, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":31 + * + * @cname("__pyx_convert_PyObject_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyObject_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyObject_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyObject_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":37 + * + * @cname("__pyx_convert_PyUnicode_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyUnicode_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyUnicode_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyUnicode_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyUnicode_string_to_py_std__in_string", 1); + + /* "string.to_py":38 + * @cname("__pyx_convert_PyUnicode_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyUnicode_string_to_py_std__in_string(const string& s): + * return __Pyx_PyUnicode_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * cdef extern from *: + * cdef object __Pyx_PyStr_FromStringAndSize(const char*, size_t) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyUnicode_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 38, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":37 + * + * @cname("__pyx_convert_PyUnicode_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyUnicode_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyUnicode_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyUnicode_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":43 + * + * @cname("__pyx_convert_PyStr_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyStr_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyStr_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyStr_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyStr_string_to_py_std__in_string", 1); + + /* "string.to_py":44 + * @cname("__pyx_convert_PyStr_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyStr_string_to_py_std__in_string(const string& s): + * return __Pyx_PyStr_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * cdef extern from *: + * cdef object __Pyx_PyBytes_FromStringAndSize(const char*, size_t) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyStr_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 44, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":43 + * + * @cname("__pyx_convert_PyStr_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyStr_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyStr_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyStr_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":49 + * + * @cname("__pyx_convert_PyBytes_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyBytes_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyBytes_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyBytes_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyBytes_string_to_py_std__in_string", 1); + + /* "string.to_py":50 + * @cname("__pyx_convert_PyBytes_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyBytes_string_to_py_std__in_string(const string& s): + * return __Pyx_PyBytes_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * cdef extern from *: + * cdef object __Pyx_PyByteArray_FromStringAndSize(const char*, size_t) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyBytes_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 50, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":49 + * + * @cname("__pyx_convert_PyBytes_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyBytes_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyBytes_FromStringAndSize(s.data(), s.size()) + * cdef extern from *: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyBytes_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "string.to_py":55 + * + * @cname("__pyx_convert_PyByteArray_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyByteArray_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyByteArray_FromStringAndSize(s.data(), s.size()) + * + */ + +static CYTHON_INLINE PyObject *__pyx_convert_PyByteArray_string_to_py_std__in_string(std::string const &__pyx_v_s) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_convert_PyByteArray_string_to_py_std__in_string", 1); + + /* "string.to_py":56 + * @cname("__pyx_convert_PyByteArray_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyByteArray_string_to_py_std__in_string(const string& s): + * return __Pyx_PyByteArray_FromStringAndSize(s.data(), s.size()) # <<<<<<<<<<<<<< + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyByteArray_FromStringAndSize(__pyx_v_s.data(), __pyx_v_s.size()); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 56, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "string.to_py":55 + * + * @cname("__pyx_convert_PyByteArray_string_to_py_std__in_string") + * cdef inline object __pyx_convert_PyByteArray_string_to_py_std__in_string(const string& s): # <<<<<<<<<<<<<< + * return __Pyx_PyByteArray_FromStringAndSize(s.data(), s.size()) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("string.to_py.__pyx_convert_PyByteArray_string_to_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "selfdrive/boardd/boardd_api_impl.pyx":17 + * void can_list_to_can_capnp_cpp(const vector[can_frame] &can_list, string &out, bool sendCan, bool valid) + * + * def can_list_to_can_capnp(can_msgs, msgtype='can', valid=True): # <<<<<<<<<<<<<< + * cdef vector[can_frame] can_list + * can_list.reserve(len(can_msgs)) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_9selfdrive_6boardd_15boardd_api_impl_1can_list_to_can_capnp(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_9selfdrive_6boardd_15boardd_api_impl_1can_list_to_can_capnp = {"can_list_to_can_capnp", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_9selfdrive_6boardd_15boardd_api_impl_1can_list_to_can_capnp, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_9selfdrive_6boardd_15boardd_api_impl_1can_list_to_can_capnp(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_can_msgs = 0; + PyObject *__pyx_v_msgtype = 0; + PyObject *__pyx_v_valid = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("can_list_to_can_capnp (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_can_msgs,&__pyx_n_s_msgtype,&__pyx_n_s_valid,0}; + values[1] = __Pyx_Arg_NewRef_FASTCALL(((PyObject *)((PyObject*)__pyx_n_u_can))); + values[2] = __Pyx_Arg_NewRef_FASTCALL(((PyObject *)((PyObject *)Py_True))); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_can_msgs)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 17, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_msgtype); + if (value) { values[1] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 17, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_valid); + if (value) { values[2] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 17, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "can_list_to_can_capnp") < 0)) __PYX_ERR(1, 17, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_can_msgs = values[0]; + __pyx_v_msgtype = values[1]; + __pyx_v_valid = values[2]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("can_list_to_can_capnp", 0, 1, 3, __pyx_nargs); __PYX_ERR(1, 17, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("selfdrive.boardd.boardd_api_impl.can_list_to_can_capnp", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_9selfdrive_6boardd_15boardd_api_impl_can_list_to_can_capnp(__pyx_self, __pyx_v_can_msgs, __pyx_v_msgtype, __pyx_v_valid); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_9selfdrive_6boardd_15boardd_api_impl_can_list_to_can_capnp(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_can_msgs, PyObject *__pyx_v_msgtype, PyObject *__pyx_v_valid) { + std::vector __pyx_v_can_list; + struct can_frame __pyx_v_f; + PyObject *__pyx_v_can_msg = NULL; + std::string __pyx_v_out; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + PyObject *(*__pyx_t_3)(PyObject *); + PyObject *__pyx_t_4 = NULL; + long __pyx_t_5; + std::string __pyx_t_6; + bool __pyx_t_7; + bool __pyx_t_8; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("can_list_to_can_capnp", 1); + + /* "selfdrive/boardd/boardd_api_impl.pyx":19 + * def can_list_to_can_capnp(can_msgs, msgtype='can', valid=True): + * cdef vector[can_frame] can_list + * can_list.reserve(len(can_msgs)) # <<<<<<<<<<<<<< + * + * cdef can_frame f + */ + __pyx_t_1 = PyObject_Length(__pyx_v_can_msgs); if (unlikely(__pyx_t_1 == ((Py_ssize_t)-1))) __PYX_ERR(1, 19, __pyx_L1_error) + try { + __pyx_v_can_list.reserve(__pyx_t_1); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(1, 19, __pyx_L1_error) + } + + /* "selfdrive/boardd/boardd_api_impl.pyx":22 + * + * cdef can_frame f + * for can_msg in can_msgs: # <<<<<<<<<<<<<< + * f.address = can_msg[0] + * f.busTime = can_msg[1] + */ + if (likely(PyList_CheckExact(__pyx_v_can_msgs)) || PyTuple_CheckExact(__pyx_v_can_msgs)) { + __pyx_t_2 = __pyx_v_can_msgs; __Pyx_INCREF(__pyx_t_2); + __pyx_t_1 = 0; + __pyx_t_3 = NULL; + } else { + __pyx_t_1 = -1; __pyx_t_2 = PyObject_GetIter(__pyx_v_can_msgs); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 22, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 22, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_3)) { + if (likely(PyList_CheckExact(__pyx_t_2))) { + { + Py_ssize_t __pyx_temp = __Pyx_PyList_GET_SIZE(__pyx_t_2); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 22, __pyx_L1_error) + #endif + if (__pyx_t_1 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyList_GET_ITEM(__pyx_t_2, __pyx_t_1); __Pyx_INCREF(__pyx_t_4); __pyx_t_1++; if (unlikely((0 < 0))) __PYX_ERR(1, 22, __pyx_L1_error) + #else + __pyx_t_4 = __Pyx_PySequence_ITEM(__pyx_t_2, __pyx_t_1); __pyx_t_1++; if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 22, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } else { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_2); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 22, __pyx_L1_error) + #endif + if (__pyx_t_1 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_4 = PyTuple_GET_ITEM(__pyx_t_2, __pyx_t_1); __Pyx_INCREF(__pyx_t_4); __pyx_t_1++; if (unlikely((0 < 0))) __PYX_ERR(1, 22, __pyx_L1_error) + #else + __pyx_t_4 = __Pyx_PySequence_ITEM(__pyx_t_2, __pyx_t_1); __pyx_t_1++; if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 22, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + } + } else { + __pyx_t_4 = __pyx_t_3(__pyx_t_2); + if (unlikely(!__pyx_t_4)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(1, 22, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_4); + } + __Pyx_XDECREF_SET(__pyx_v_can_msg, __pyx_t_4); + __pyx_t_4 = 0; + + /* "selfdrive/boardd/boardd_api_impl.pyx":23 + * cdef can_frame f + * for can_msg in can_msgs: + * f.address = can_msg[0] # <<<<<<<<<<<<<< + * f.busTime = can_msg[1] + * f.dat = can_msg[2] + */ + __pyx_t_4 = __Pyx_GetItemInt(__pyx_v_can_msg, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 23, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyInt_As_long(__pyx_t_4); if (unlikely((__pyx_t_5 == (long)-1) && PyErr_Occurred())) __PYX_ERR(1, 23, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_v_f.address = __pyx_t_5; + + /* "selfdrive/boardd/boardd_api_impl.pyx":24 + * for can_msg in can_msgs: + * f.address = can_msg[0] + * f.busTime = can_msg[1] # <<<<<<<<<<<<<< + * f.dat = can_msg[2] + * f.src = can_msg[3] + */ + __pyx_t_4 = __Pyx_GetItemInt(__pyx_v_can_msg, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 24, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyInt_As_long(__pyx_t_4); if (unlikely((__pyx_t_5 == (long)-1) && PyErr_Occurred())) __PYX_ERR(1, 24, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_v_f.busTime = __pyx_t_5; + + /* "selfdrive/boardd/boardd_api_impl.pyx":25 + * f.address = can_msg[0] + * f.busTime = can_msg[1] + * f.dat = can_msg[2] # <<<<<<<<<<<<<< + * f.src = can_msg[3] + * can_list.push_back(f) + */ + __pyx_t_4 = __Pyx_GetItemInt(__pyx_v_can_msg, 2, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 25, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_6 = __pyx_convert_string_from_py_std__in_string(__pyx_t_4); if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 25, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_v_f.dat = __PYX_STD_MOVE_IF_SUPPORTED(__pyx_t_6); + + /* "selfdrive/boardd/boardd_api_impl.pyx":26 + * f.busTime = can_msg[1] + * f.dat = can_msg[2] + * f.src = can_msg[3] # <<<<<<<<<<<<<< + * can_list.push_back(f) + * cdef string out + */ + __pyx_t_4 = __Pyx_GetItemInt(__pyx_v_can_msg, 3, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 26, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyInt_As_long(__pyx_t_4); if (unlikely((__pyx_t_5 == (long)-1) && PyErr_Occurred())) __PYX_ERR(1, 26, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_v_f.src = __pyx_t_5; + + /* "selfdrive/boardd/boardd_api_impl.pyx":27 + * f.dat = can_msg[2] + * f.src = can_msg[3] + * can_list.push_back(f) # <<<<<<<<<<<<<< + * cdef string out + * can_list_to_can_capnp_cpp(can_list, out, msgtype == 'sendcan', valid) + */ + try { + __pyx_v_can_list.push_back(__pyx_v_f); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(1, 27, __pyx_L1_error) + } + + /* "selfdrive/boardd/boardd_api_impl.pyx":22 + * + * cdef can_frame f + * for can_msg in can_msgs: # <<<<<<<<<<<<<< + * f.address = can_msg[0] + * f.busTime = can_msg[1] + */ + } + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "selfdrive/boardd/boardd_api_impl.pyx":29 + * can_list.push_back(f) + * cdef string out + * can_list_to_can_capnp_cpp(can_list, out, msgtype == 'sendcan', valid) # <<<<<<<<<<<<<< + * return out + */ + __pyx_t_2 = PyObject_RichCompare(__pyx_v_msgtype, __pyx_n_u_sendcan, Py_EQ); __Pyx_XGOTREF(__pyx_t_2); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 29, __pyx_L1_error) + __pyx_t_7 = __Pyx_PyObject_IsTrue(__pyx_t_2); if (unlikely((__pyx_t_7 == ((bool)-1)) && PyErr_Occurred())) __PYX_ERR(1, 29, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_8 = __Pyx_PyObject_IsTrue(__pyx_v_valid); if (unlikely((__pyx_t_8 == ((bool)-1)) && PyErr_Occurred())) __PYX_ERR(1, 29, __pyx_L1_error) + can_list_to_can_capnp_cpp(__pyx_v_can_list, __pyx_v_out, __pyx_t_7, __pyx_t_8); + + /* "selfdrive/boardd/boardd_api_impl.pyx":30 + * cdef string out + * can_list_to_can_capnp_cpp(can_list, out, msgtype == 'sendcan', valid) + * return out # <<<<<<<<<<<<<< + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_convert_PyBytes_string_to_py_std__in_string(__pyx_v_out); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 30, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "selfdrive/boardd/boardd_api_impl.pyx":17 + * void can_list_to_can_capnp_cpp(const vector[can_frame] &can_list, string &out, bool sendCan, bool valid) + * + * def can_list_to_can_capnp(can_msgs, msgtype='can', valid=True): # <<<<<<<<<<<<<< + * cdef vector[can_frame] can_list + * can_list.reserve(len(can_msgs)) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("selfdrive.boardd.boardd_api_impl.can_list_to_can_capnp", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_can_msg); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyMethodDef __pyx_methods[] = { + {0, 0, 0, 0} +}; +#ifndef CYTHON_SMALL_CODE +#if defined(__clang__) + #define CYTHON_SMALL_CODE +#elif defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 3)) + #define CYTHON_SMALL_CODE __attribute__((cold)) +#else + #define CYTHON_SMALL_CODE +#endif +#endif +/* #### Code section: pystring_table ### */ + +static int __Pyx_CreateStringTabAndInitStrings(void) { + __Pyx_StringTabEntry __pyx_string_tab[] = { + {&__pyx_n_s__4, __pyx_k__4, sizeof(__pyx_k__4), 0, 0, 1, 1}, + {&__pyx_n_s_asyncio_coroutines, __pyx_k_asyncio_coroutines, sizeof(__pyx_k_asyncio_coroutines), 0, 0, 1, 1}, + {&__pyx_n_u_can, __pyx_k_can, sizeof(__pyx_k_can), 0, 1, 0, 1}, + {&__pyx_n_s_can_list, __pyx_k_can_list, sizeof(__pyx_k_can_list), 0, 0, 1, 1}, + {&__pyx_n_s_can_list_to_can_capnp, __pyx_k_can_list_to_can_capnp, sizeof(__pyx_k_can_list_to_can_capnp), 0, 0, 1, 1}, + {&__pyx_n_s_can_msg, __pyx_k_can_msg, sizeof(__pyx_k_can_msg), 0, 0, 1, 1}, + {&__pyx_n_s_can_msgs, __pyx_k_can_msgs, sizeof(__pyx_k_can_msgs), 0, 0, 1, 1}, + {&__pyx_n_s_cline_in_traceback, __pyx_k_cline_in_traceback, sizeof(__pyx_k_cline_in_traceback), 0, 0, 1, 1}, + {&__pyx_n_s_f, __pyx_k_f, sizeof(__pyx_k_f), 0, 0, 1, 1}, + {&__pyx_n_s_is_coroutine, __pyx_k_is_coroutine, sizeof(__pyx_k_is_coroutine), 0, 0, 1, 1}, + {&__pyx_n_s_main, __pyx_k_main, sizeof(__pyx_k_main), 0, 0, 1, 1}, + {&__pyx_n_s_msgtype, __pyx_k_msgtype, sizeof(__pyx_k_msgtype), 0, 0, 1, 1}, + {&__pyx_n_s_name, __pyx_k_name, sizeof(__pyx_k_name), 0, 0, 1, 1}, + {&__pyx_n_s_out, __pyx_k_out, sizeof(__pyx_k_out), 0, 0, 1, 1}, + {&__pyx_kp_s_selfdrive_boardd_boardd_api_impl, __pyx_k_selfdrive_boardd_boardd_api_impl, sizeof(__pyx_k_selfdrive_boardd_boardd_api_impl), 0, 0, 1, 0}, + {&__pyx_n_s_selfdrive_boardd_boardd_api_impl_2, __pyx_k_selfdrive_boardd_boardd_api_impl_2, sizeof(__pyx_k_selfdrive_boardd_boardd_api_impl_2), 0, 0, 1, 1}, + {&__pyx_n_u_sendcan, __pyx_k_sendcan, sizeof(__pyx_k_sendcan), 0, 1, 0, 1}, + {&__pyx_n_s_test, __pyx_k_test, sizeof(__pyx_k_test), 0, 0, 1, 1}, + {&__pyx_n_s_valid, __pyx_k_valid, sizeof(__pyx_k_valid), 0, 0, 1, 1}, + {0, 0, 0, 0, 0, 0, 0} + }; + return __Pyx_InitStrings(__pyx_string_tab); +} +/* #### Code section: cached_builtins ### */ +static CYTHON_SMALL_CODE int __Pyx_InitCachedBuiltins(void) { + return 0; +} +/* #### Code section: cached_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_InitCachedConstants", 0); + + /* "selfdrive/boardd/boardd_api_impl.pyx":17 + * void can_list_to_can_capnp_cpp(const vector[can_frame] &can_list, string &out, bool sendCan, bool valid) + * + * def can_list_to_can_capnp(can_msgs, msgtype='can', valid=True): # <<<<<<<<<<<<<< + * cdef vector[can_frame] can_list + * can_list.reserve(len(can_msgs)) + */ + __pyx_tuple_ = PyTuple_Pack(7, __pyx_n_s_can_msgs, __pyx_n_s_msgtype, __pyx_n_s_valid, __pyx_n_s_can_list, __pyx_n_s_f, __pyx_n_s_can_msg, __pyx_n_s_out); if (unlikely(!__pyx_tuple_)) __PYX_ERR(1, 17, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple_); + __Pyx_GIVEREF(__pyx_tuple_); + __pyx_codeobj__2 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 7, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple_, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_selfdrive_boardd_boardd_api_impl, __pyx_n_s_can_list_to_can_capnp, 17, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__2)) __PYX_ERR(1, 17, __pyx_L1_error) + __pyx_tuple__3 = PyTuple_Pack(2, ((PyObject*)__pyx_n_u_can), ((PyObject *)Py_True)); if (unlikely(!__pyx_tuple__3)) __PYX_ERR(1, 17, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__3); + __Pyx_GIVEREF(__pyx_tuple__3); + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_RefNannyFinishContext(); + return -1; +} +/* #### Code section: init_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitConstants(void) { + if (__Pyx_CreateStringTabAndInitStrings() < 0) __PYX_ERR(1, 1, __pyx_L1_error); + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: init_globals ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitGlobals(void) { + return 0; +} +/* #### Code section: init_module ### */ + +static CYTHON_SMALL_CODE int __Pyx_modinit_global_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_import_code(void); /*proto*/ + +static int __Pyx_modinit_global_init_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_global_init_code", 0); + /*--- Global init code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_variable_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_export_code", 0); + /*--- Variable export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_export_code", 0); + /*--- Function export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_type_init_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_type_init_code", 0); + /*--- Type init code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_type_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_type_import_code", 0); + /*--- Type import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_variable_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_import_code", 0); + /*--- Variable import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_import_code", 0); + /*--- Function import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + + +#if PY_MAJOR_VERSION >= 3 +#if CYTHON_PEP489_MULTI_PHASE_INIT +static PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def); /*proto*/ +static int __pyx_pymod_exec_boardd_api_impl(PyObject* module); /*proto*/ +static PyModuleDef_Slot __pyx_moduledef_slots[] = { + {Py_mod_create, (void*)__pyx_pymod_create}, + {Py_mod_exec, (void*)__pyx_pymod_exec_boardd_api_impl}, + {0, NULL} +}; +#endif + +#ifdef __cplusplus +namespace { + struct PyModuleDef __pyx_moduledef = + #else + static struct PyModuleDef __pyx_moduledef = + #endif + { + PyModuleDef_HEAD_INIT, + "boardd_api_impl", + 0, /* m_doc */ + #if CYTHON_PEP489_MULTI_PHASE_INIT + 0, /* m_size */ + #elif CYTHON_USE_MODULE_STATE + sizeof(__pyx_mstate), /* m_size */ + #else + -1, /* m_size */ + #endif + __pyx_methods /* m_methods */, + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_moduledef_slots, /* m_slots */ + #else + NULL, /* m_reload */ + #endif + #if CYTHON_USE_MODULE_STATE + __pyx_m_traverse, /* m_traverse */ + __pyx_m_clear, /* m_clear */ + NULL /* m_free */ + #else + NULL, /* m_traverse */ + NULL, /* m_clear */ + NULL /* m_free */ + #endif + }; + #ifdef __cplusplus +} /* anonymous namespace */ +#endif +#endif + +#ifndef CYTHON_NO_PYINIT_EXPORT +#define __Pyx_PyMODINIT_FUNC PyMODINIT_FUNC +#elif PY_MAJOR_VERSION < 3 +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" void +#else +#define __Pyx_PyMODINIT_FUNC void +#endif +#else +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" PyObject * +#else +#define __Pyx_PyMODINIT_FUNC PyObject * +#endif +#endif + + +#if PY_MAJOR_VERSION < 3 +__Pyx_PyMODINIT_FUNC initboardd_api_impl(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC initboardd_api_impl(void) +#else +__Pyx_PyMODINIT_FUNC PyInit_boardd_api_impl(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC PyInit_boardd_api_impl(void) +#if CYTHON_PEP489_MULTI_PHASE_INIT +{ + return PyModuleDef_Init(&__pyx_moduledef); +} +static CYTHON_SMALL_CODE int __Pyx_check_single_interpreter(void) { + #if PY_VERSION_HEX >= 0x030700A1 + static PY_INT64_T main_interpreter_id = -1; + PY_INT64_T current_id = PyInterpreterState_GetID(PyThreadState_Get()->interp); + if (main_interpreter_id == -1) { + main_interpreter_id = current_id; + return (unlikely(current_id == -1)) ? -1 : 0; + } else if (unlikely(main_interpreter_id != current_id)) + #else + static PyInterpreterState *main_interpreter = NULL; + PyInterpreterState *current_interpreter = PyThreadState_Get()->interp; + if (!main_interpreter) { + main_interpreter = current_interpreter; + } else if (unlikely(main_interpreter != current_interpreter)) + #endif + { + PyErr_SetString( + PyExc_ImportError, + "Interpreter change detected - this module can only be loaded into one interpreter per process."); + return -1; + } + return 0; +} +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *module, const char* from_name, const char* to_name, int allow_none) +#else +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *moddict, const char* from_name, const char* to_name, int allow_none) +#endif +{ + PyObject *value = PyObject_GetAttrString(spec, from_name); + int result = 0; + if (likely(value)) { + if (allow_none || value != Py_None) { +#if CYTHON_COMPILING_IN_LIMITED_API + result = PyModule_AddObject(module, to_name, value); +#else + result = PyDict_SetItemString(moddict, to_name, value); +#endif + } + Py_DECREF(value); + } else if (PyErr_ExceptionMatches(PyExc_AttributeError)) { + PyErr_Clear(); + } else { + result = -1; + } + return result; +} +static CYTHON_SMALL_CODE PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def) { + PyObject *module = NULL, *moddict, *modname; + CYTHON_UNUSED_VAR(def); + if (__Pyx_check_single_interpreter()) + return NULL; + if (__pyx_m) + return __Pyx_NewRef(__pyx_m); + modname = PyObject_GetAttrString(spec, "name"); + if (unlikely(!modname)) goto bad; + module = PyModule_NewObject(modname); + Py_DECREF(modname); + if (unlikely(!module)) goto bad; +#if CYTHON_COMPILING_IN_LIMITED_API + moddict = module; +#else + moddict = PyModule_GetDict(module); + if (unlikely(!moddict)) goto bad; +#endif + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "loader", "__loader__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "origin", "__file__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "parent", "__package__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "submodule_search_locations", "__path__", 0) < 0)) goto bad; + return module; +bad: + Py_XDECREF(module); + return NULL; +} + + +static CYTHON_SMALL_CODE int __pyx_pymod_exec_boardd_api_impl(PyObject *__pyx_pyinit_module) +#endif +#endif +{ + int stringtab_initialized = 0; + #if CYTHON_USE_MODULE_STATE + int pystate_addmodule_run = 0; + #endif + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannyDeclarations + #if CYTHON_PEP489_MULTI_PHASE_INIT + if (__pyx_m) { + if (__pyx_m == __pyx_pyinit_module) return 0; + PyErr_SetString(PyExc_RuntimeError, "Module 'boardd_api_impl' has already been imported. Re-initialisation is not supported."); + return -1; + } + #elif PY_MAJOR_VERSION >= 3 + if (__pyx_m) return __Pyx_NewRef(__pyx_m); + #endif + /*--- Module creation code ---*/ + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_m = __pyx_pyinit_module; + Py_INCREF(__pyx_m); + #else + #if PY_MAJOR_VERSION < 3 + __pyx_m = Py_InitModule4("boardd_api_impl", __pyx_methods, 0, 0, PYTHON_API_VERSION); Py_XINCREF(__pyx_m); + if (unlikely(!__pyx_m)) __PYX_ERR(1, 1, __pyx_L1_error) + #elif CYTHON_USE_MODULE_STATE + __pyx_t_1 = PyModule_Create(&__pyx_moduledef); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 1, __pyx_L1_error) + { + int add_module_result = PyState_AddModule(__pyx_t_1, &__pyx_moduledef); + __pyx_t_1 = 0; /* transfer ownership from __pyx_t_1 to "boardd_api_impl" pseudovariable */ + if (unlikely((add_module_result < 0))) __PYX_ERR(1, 1, __pyx_L1_error) + pystate_addmodule_run = 1; + } + #else + __pyx_m = PyModule_Create(&__pyx_moduledef); + if (unlikely(!__pyx_m)) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + #endif + CYTHON_UNUSED_VAR(__pyx_t_1); + __pyx_d = PyModule_GetDict(__pyx_m); if (unlikely(!__pyx_d)) __PYX_ERR(1, 1, __pyx_L1_error) + Py_INCREF(__pyx_d); + __pyx_b = __Pyx_PyImport_AddModuleRef(__Pyx_BUILTIN_MODULE_NAME); if (unlikely(!__pyx_b)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_cython_runtime = __Pyx_PyImport_AddModuleRef((const char *) "cython_runtime"); if (unlikely(!__pyx_cython_runtime)) __PYX_ERR(1, 1, __pyx_L1_error) + if (PyObject_SetAttrString(__pyx_m, "__builtins__", __pyx_b) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #if CYTHON_REFNANNY +__Pyx_RefNanny = __Pyx_RefNannyImportAPI("refnanny"); +if (!__Pyx_RefNanny) { + PyErr_Clear(); + __Pyx_RefNanny = __Pyx_RefNannyImportAPI("Cython.Runtime.refnanny"); + if (!__Pyx_RefNanny) + Py_FatalError("failed to import 'refnanny' module"); +} +#endif + __Pyx_RefNannySetupContext("__Pyx_PyMODINIT_FUNC PyInit_boardd_api_impl(void)", 0); + if (__Pyx_check_binary_version(__PYX_LIMITED_VERSION_HEX, __Pyx_get_runtime_version(), CYTHON_COMPILING_IN_LIMITED_API) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #ifdef __Pxy_PyFrame_Initialize_Offsets + __Pxy_PyFrame_Initialize_Offsets(); + #endif + __pyx_empty_tuple = PyTuple_New(0); if (unlikely(!__pyx_empty_tuple)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_empty_bytes = PyBytes_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_bytes)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_empty_unicode = PyUnicode_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_unicode)) __PYX_ERR(1, 1, __pyx_L1_error) + #ifdef __Pyx_CyFunction_USED + if (__pyx_CyFunction_init(__pyx_m) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_FusedFunction_USED + if (__pyx_FusedFunction_init(__pyx_m) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Coroutine_USED + if (__pyx_Coroutine_init(__pyx_m) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Generator_USED + if (__pyx_Generator_init(__pyx_m) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_AsyncGen_USED + if (__pyx_AsyncGen_init(__pyx_m) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_StopAsyncIteration_USED + if (__pyx_StopAsyncIteration_init(__pyx_m) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + /*--- Library function declarations ---*/ + /*--- Threads initialization code ---*/ + #if defined(WITH_THREAD) && PY_VERSION_HEX < 0x030700F0 && defined(__PYX_FORCE_INIT_THREADS) && __PYX_FORCE_INIT_THREADS + PyEval_InitThreads(); + #endif + /*--- Initialize various global constants etc. ---*/ + if (__Pyx_InitConstants() < 0) __PYX_ERR(1, 1, __pyx_L1_error) + stringtab_initialized = 1; + if (__Pyx_InitGlobals() < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #if PY_MAJOR_VERSION < 3 && (__PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT) + if (__Pyx_init_sys_getdefaultencoding_params() < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + if (__pyx_module_is_main_selfdrive__boardd__boardd_api_impl) { + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_name, __pyx_n_s_main) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + } + #if PY_MAJOR_VERSION >= 3 + { + PyObject *modules = PyImport_GetModuleDict(); if (unlikely(!modules)) __PYX_ERR(1, 1, __pyx_L1_error) + if (!PyDict_GetItemString(modules, "selfdrive.boardd.boardd_api_impl")) { + if (unlikely((PyDict_SetItemString(modules, "selfdrive.boardd.boardd_api_impl", __pyx_m) < 0))) __PYX_ERR(1, 1, __pyx_L1_error) + } + } + #endif + /*--- Builtin init code ---*/ + if (__Pyx_InitCachedBuiltins() < 0) __PYX_ERR(1, 1, __pyx_L1_error) + /*--- Constants init code ---*/ + if (__Pyx_InitCachedConstants() < 0) __PYX_ERR(1, 1, __pyx_L1_error) + /*--- Global type/function init code ---*/ + (void)__Pyx_modinit_global_init_code(); + (void)__Pyx_modinit_variable_export_code(); + (void)__Pyx_modinit_function_export_code(); + (void)__Pyx_modinit_type_init_code(); + (void)__Pyx_modinit_type_import_code(); + (void)__Pyx_modinit_variable_import_code(); + (void)__Pyx_modinit_function_import_code(); + /*--- Execution code ---*/ + #if defined(__Pyx_Generator_USED) || defined(__Pyx_Coroutine_USED) + if (__Pyx_patch_abc() < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + + /* "selfdrive/boardd/boardd_api_impl.pyx":17 + * void can_list_to_can_capnp_cpp(const vector[can_frame] &can_list, string &out, bool sendCan, bool valid) + * + * def can_list_to_can_capnp(can_msgs, msgtype='can', valid=True): # <<<<<<<<<<<<<< + * cdef vector[can_frame] can_list + * can_list.reserve(len(can_msgs)) + */ + __pyx_t_2 = __Pyx_CyFunction_New(&__pyx_mdef_9selfdrive_6boardd_15boardd_api_impl_1can_list_to_can_capnp, 0, __pyx_n_s_can_list_to_can_capnp, NULL, __pyx_n_s_selfdrive_boardd_boardd_api_impl_2, __pyx_d, ((PyObject *)__pyx_codeobj__2)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 17, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_2, __pyx_tuple__3); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_can_list_to_can_capnp, __pyx_t_2) < 0) __PYX_ERR(1, 17, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "selfdrive/boardd/boardd_api_impl.pyx":1 + * # distutils: language = c++ # <<<<<<<<<<<<<< + * # cython: language_level=3 + * from libcpp.vector cimport vector + */ + __pyx_t_2 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_test, __pyx_t_2) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /*--- Wrapped vars code ---*/ + + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + if (__pyx_m) { + if (__pyx_d && stringtab_initialized) { + __Pyx_AddTraceback("init selfdrive.boardd.boardd_api_impl", __pyx_clineno, __pyx_lineno, __pyx_filename); + } + #if !CYTHON_USE_MODULE_STATE + Py_CLEAR(__pyx_m); + #else + Py_DECREF(__pyx_m); + if (pystate_addmodule_run) { + PyObject *tp, *value, *tb; + PyErr_Fetch(&tp, &value, &tb); + PyState_RemoveModule(&__pyx_moduledef); + PyErr_Restore(tp, value, tb); + } + #endif + } else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_ImportError, "init selfdrive.boardd.boardd_api_impl"); + } + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + #if CYTHON_PEP489_MULTI_PHASE_INIT + return (__pyx_m != NULL) ? 0 : -1; + #elif PY_MAJOR_VERSION >= 3 + return __pyx_m; + #else + return; + #endif +} +/* #### Code section: cleanup_globals ### */ +/* #### Code section: cleanup_module ### */ +/* #### Code section: main_method ### */ +/* #### Code section: utility_code_pragmas ### */ +#ifdef _MSC_VER +#pragma warning( push ) +/* Warning 4127: conditional expression is constant + * Cython uses constant conditional expressions to allow in inline functions to be optimized at + * compile-time, so this warning is not useful + */ +#pragma warning( disable : 4127 ) +#endif + + + +/* #### Code section: utility_code_def ### */ + +/* --- Runtime support code --- */ +/* Refnanny */ +#if CYTHON_REFNANNY +static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname) { + PyObject *m = NULL, *p = NULL; + void *r = NULL; + m = PyImport_ImportModule(modname); + if (!m) goto end; + p = PyObject_GetAttrString(m, "RefNannyAPI"); + if (!p) goto end; + r = PyLong_AsVoidPtr(p); +end: + Py_XDECREF(p); + Py_XDECREF(m); + return (__Pyx_RefNannyAPIStruct *)r; +} +#endif + +/* TupleAndListFromArray */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE void __Pyx_copy_object_array(PyObject *const *CYTHON_RESTRICT src, PyObject** CYTHON_RESTRICT dest, Py_ssize_t length) { + PyObject *v; + Py_ssize_t i; + for (i = 0; i < length; i++) { + v = dest[i] = src[i]; + Py_INCREF(v); + } +} +static CYTHON_INLINE PyObject * +__Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + Py_INCREF(__pyx_empty_tuple); + return __pyx_empty_tuple; + } + res = PyTuple_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyTupleObject*)res)->ob_item, n); + return res; +} +static CYTHON_INLINE PyObject * +__Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + return PyList_New(0); + } + res = PyList_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyListObject*)res)->ob_item, n); + return res; +} +#endif + +/* BytesEquals */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else + if (s1 == s2) { + return (equals == Py_EQ); + } else if (PyBytes_CheckExact(s1) & PyBytes_CheckExact(s2)) { + const char *ps1, *ps2; + Py_ssize_t length = PyBytes_GET_SIZE(s1); + if (length != PyBytes_GET_SIZE(s2)) + return (equals == Py_NE); + ps1 = PyBytes_AS_STRING(s1); + ps2 = PyBytes_AS_STRING(s2); + if (ps1[0] != ps2[0]) { + return (equals == Py_NE); + } else if (length == 1) { + return (equals == Py_EQ); + } else { + int result; +#if CYTHON_USE_UNICODE_INTERNALS && (PY_VERSION_HEX < 0x030B0000) + Py_hash_t hash1, hash2; + hash1 = ((PyBytesObject*)s1)->ob_shash; + hash2 = ((PyBytesObject*)s2)->ob_shash; + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + return (equals == Py_NE); + } +#endif + result = memcmp(ps1, ps2, (size_t)length); + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & PyBytes_CheckExact(s2)) { + return (equals == Py_NE); + } else if ((s2 == Py_None) & PyBytes_CheckExact(s1)) { + return (equals == Py_NE); + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +#endif +} + +/* UnicodeEquals */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else +#if PY_MAJOR_VERSION < 3 + PyObject* owned_ref = NULL; +#endif + int s1_is_unicode, s2_is_unicode; + if (s1 == s2) { + goto return_eq; + } + s1_is_unicode = PyUnicode_CheckExact(s1); + s2_is_unicode = PyUnicode_CheckExact(s2); +#if PY_MAJOR_VERSION < 3 + if ((s1_is_unicode & (!s2_is_unicode)) && PyString_CheckExact(s2)) { + owned_ref = PyUnicode_FromObject(s2); + if (unlikely(!owned_ref)) + return -1; + s2 = owned_ref; + s2_is_unicode = 1; + } else if ((s2_is_unicode & (!s1_is_unicode)) && PyString_CheckExact(s1)) { + owned_ref = PyUnicode_FromObject(s1); + if (unlikely(!owned_ref)) + return -1; + s1 = owned_ref; + s1_is_unicode = 1; + } else if (((!s2_is_unicode) & (!s1_is_unicode))) { + return __Pyx_PyBytes_Equals(s1, s2, equals); + } +#endif + if (s1_is_unicode & s2_is_unicode) { + Py_ssize_t length; + int kind; + void *data1, *data2; + if (unlikely(__Pyx_PyUnicode_READY(s1) < 0) || unlikely(__Pyx_PyUnicode_READY(s2) < 0)) + return -1; + length = __Pyx_PyUnicode_GET_LENGTH(s1); + if (length != __Pyx_PyUnicode_GET_LENGTH(s2)) { + goto return_ne; + } +#if CYTHON_USE_UNICODE_INTERNALS + { + Py_hash_t hash1, hash2; + #if CYTHON_PEP393_ENABLED + hash1 = ((PyASCIIObject*)s1)->hash; + hash2 = ((PyASCIIObject*)s2)->hash; + #else + hash1 = ((PyUnicodeObject*)s1)->hash; + hash2 = ((PyUnicodeObject*)s2)->hash; + #endif + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + goto return_ne; + } + } +#endif + kind = __Pyx_PyUnicode_KIND(s1); + if (kind != __Pyx_PyUnicode_KIND(s2)) { + goto return_ne; + } + data1 = __Pyx_PyUnicode_DATA(s1); + data2 = __Pyx_PyUnicode_DATA(s2); + if (__Pyx_PyUnicode_READ(kind, data1, 0) != __Pyx_PyUnicode_READ(kind, data2, 0)) { + goto return_ne; + } else if (length == 1) { + goto return_eq; + } else { + int result = memcmp(data1, data2, (size_t)(length * kind)); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & s2_is_unicode) { + goto return_ne; + } else if ((s2 == Py_None) & s1_is_unicode) { + goto return_ne; + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +return_eq: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ); +return_ne: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_NE); +#endif +} + +/* fastcall */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s) +{ + Py_ssize_t i, n = PyTuple_GET_SIZE(kwnames); + for (i = 0; i < n; i++) + { + if (s == PyTuple_GET_ITEM(kwnames, i)) return kwvalues[i]; + } + for (i = 0; i < n; i++) + { + int eq = __Pyx_PyUnicode_Equals(s, PyTuple_GET_ITEM(kwnames, i), Py_EQ); + if (unlikely(eq != 0)) { + if (unlikely(eq < 0)) return NULL; + return kwvalues[i]; + } + } + return NULL; +} +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 +CYTHON_UNUSED static PyObject *__Pyx_KwargsAsDict_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues) { + Py_ssize_t i, nkwargs = PyTuple_GET_SIZE(kwnames); + PyObject *dict; + dict = PyDict_New(); + if (unlikely(!dict)) + return NULL; + for (i=0; i= 3 + "%s() got multiple values for keyword argument '%U'", func_name, kw_name); + #else + "%s() got multiple values for keyword argument '%s'", func_name, + PyString_AsString(kw_name)); + #endif +} + +/* ParseKeywords */ +static int __Pyx_ParseOptionalKeywords( + PyObject *kwds, + PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, + PyObject *values[], + Py_ssize_t num_pos_args, + const char* function_name) +{ + PyObject *key = 0, *value = 0; + Py_ssize_t pos = 0; + PyObject*** name; + PyObject*** first_kw_arg = argnames + num_pos_args; + int kwds_is_tuple = CYTHON_METH_FASTCALL && likely(PyTuple_Check(kwds)); + while (1) { + Py_XDECREF(key); key = NULL; + Py_XDECREF(value); value = NULL; + if (kwds_is_tuple) { + Py_ssize_t size; +#if CYTHON_ASSUME_SAFE_MACROS + size = PyTuple_GET_SIZE(kwds); +#else + size = PyTuple_Size(kwds); + if (size < 0) goto bad; +#endif + if (pos >= size) break; +#if CYTHON_AVOID_BORROWED_REFS + key = __Pyx_PySequence_ITEM(kwds, pos); + if (!key) goto bad; +#elif CYTHON_ASSUME_SAFE_MACROS + key = PyTuple_GET_ITEM(kwds, pos); +#else + key = PyTuple_GetItem(kwds, pos); + if (!key) goto bad; +#endif + value = kwvalues[pos]; + pos++; + } + else + { + if (!PyDict_Next(kwds, &pos, &key, &value)) break; +#if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(key); +#endif + } + name = first_kw_arg; + while (*name && (**name != key)) name++; + if (*name) { + values[name-argnames] = value; +#if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(value); + Py_DECREF(key); +#endif + key = NULL; + value = NULL; + continue; + } +#if !CYTHON_AVOID_BORROWED_REFS + Py_INCREF(key); +#endif + Py_INCREF(value); + name = first_kw_arg; + #if PY_MAJOR_VERSION < 3 + if (likely(PyString_Check(key))) { + while (*name) { + if ((CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**name) == PyString_GET_SIZE(key)) + && _PyString_Eq(**name, key)) { + values[name-argnames] = value; +#if CYTHON_AVOID_BORROWED_REFS + value = NULL; +#endif + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + if ((**argname == key) || ( + (CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**argname) == PyString_GET_SIZE(key)) + && _PyString_Eq(**argname, key))) { + goto arg_passed_twice; + } + argname++; + } + } + } else + #endif + if (likely(PyUnicode_Check(key))) { + while (*name) { + int cmp = ( + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**name) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**name, key) + ); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) { + values[name-argnames] = value; +#if CYTHON_AVOID_BORROWED_REFS + value = NULL; +#endif + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + int cmp = (**argname == key) ? 0 : + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**argname) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**argname, key); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) goto arg_passed_twice; + argname++; + } + } + } else + goto invalid_keyword_type; + if (kwds2) { + if (unlikely(PyDict_SetItem(kwds2, key, value))) goto bad; + } else { + goto invalid_keyword; + } + } + Py_XDECREF(key); + Py_XDECREF(value); + return 0; +arg_passed_twice: + __Pyx_RaiseDoubleKeywordsError(function_name, key); + goto bad; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + goto bad; +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif +bad: + Py_XDECREF(key); + Py_XDECREF(value); + return -1; +} + +/* RaiseArgTupleInvalid */ +static void __Pyx_RaiseArgtupleInvalid( + const char* func_name, + int exact, + Py_ssize_t num_min, + Py_ssize_t num_max, + Py_ssize_t num_found) +{ + Py_ssize_t num_expected; + const char *more_or_less; + if (num_found < num_min) { + num_expected = num_min; + more_or_less = "at least"; + } else { + num_expected = num_max; + more_or_less = "at most"; + } + if (exact) { + more_or_less = "exactly"; + } + PyErr_Format(PyExc_TypeError, + "%.200s() takes %.8s %" CYTHON_FORMAT_SSIZE_T "d positional argument%.1s (%" CYTHON_FORMAT_SSIZE_T "d given)", + func_name, more_or_less, num_expected, + (num_expected == 1) ? "" : "s", num_found); +} + +/* GetItemInt */ +static PyObject *__Pyx_GetItemInt_Generic(PyObject *o, PyObject* j) { + PyObject *r; + if (unlikely(!j)) return NULL; + r = PyObject_GetItem(o, j); + Py_DECREF(j); + return r; +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_List_Fast(PyObject *o, Py_ssize_t i, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + Py_ssize_t wrapped_i = i; + if (wraparound & unlikely(i < 0)) { + wrapped_i += PyList_GET_SIZE(o); + } + if ((!boundscheck) || likely(__Pyx_is_valid_index(wrapped_i, PyList_GET_SIZE(o)))) { + PyObject *r = PyList_GET_ITEM(o, wrapped_i); + Py_INCREF(r); + return r; + } + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +#else + return PySequence_GetItem(o, i); +#endif +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Tuple_Fast(PyObject *o, Py_ssize_t i, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + Py_ssize_t wrapped_i = i; + if (wraparound & unlikely(i < 0)) { + wrapped_i += PyTuple_GET_SIZE(o); + } + if ((!boundscheck) || likely(__Pyx_is_valid_index(wrapped_i, PyTuple_GET_SIZE(o)))) { + PyObject *r = PyTuple_GET_ITEM(o, wrapped_i); + Py_INCREF(r); + return r; + } + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +#else + return PySequence_GetItem(o, i); +#endif +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Fast(PyObject *o, Py_ssize_t i, int is_list, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS && CYTHON_USE_TYPE_SLOTS + if (is_list || PyList_CheckExact(o)) { + Py_ssize_t n = ((!wraparound) | likely(i >= 0)) ? i : i + PyList_GET_SIZE(o); + if ((!boundscheck) || (likely(__Pyx_is_valid_index(n, PyList_GET_SIZE(o))))) { + PyObject *r = PyList_GET_ITEM(o, n); + Py_INCREF(r); + return r; + } + } + else if (PyTuple_CheckExact(o)) { + Py_ssize_t n = ((!wraparound) | likely(i >= 0)) ? i : i + PyTuple_GET_SIZE(o); + if ((!boundscheck) || likely(__Pyx_is_valid_index(n, PyTuple_GET_SIZE(o)))) { + PyObject *r = PyTuple_GET_ITEM(o, n); + Py_INCREF(r); + return r; + } + } else { + PyMappingMethods *mm = Py_TYPE(o)->tp_as_mapping; + PySequenceMethods *sm = Py_TYPE(o)->tp_as_sequence; + if (mm && mm->mp_subscript) { + PyObject *r, *key = PyInt_FromSsize_t(i); + if (unlikely(!key)) return NULL; + r = mm->mp_subscript(o, key); + Py_DECREF(key); + return r; + } + if (likely(sm && sm->sq_item)) { + if (wraparound && unlikely(i < 0) && likely(sm->sq_length)) { + Py_ssize_t l = sm->sq_length(o); + if (likely(l >= 0)) { + i += l; + } else { + if (!PyErr_ExceptionMatches(PyExc_OverflowError)) + return NULL; + PyErr_Clear(); + } + } + return sm->sq_item(o, i); + } + } +#else + if (is_list || !PyMapping_Check(o)) { + return PySequence_GetItem(o, i); + } +#endif + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +} + +/* FixUpExtensionType */ +#if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type) { +#if PY_VERSION_HEX > 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + CYTHON_UNUSED_VAR(spec); + CYTHON_UNUSED_VAR(type); +#else + const PyType_Slot *slot = spec->slots; + while (slot && slot->slot && slot->slot != Py_tp_members) + slot++; + if (slot && slot->slot == Py_tp_members) { + int changed = 0; +#if !(PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON) + const +#endif + PyMemberDef *memb = (PyMemberDef*) slot->pfunc; + while (memb && memb->name) { + if (memb->name[0] == '_' && memb->name[1] == '_') { +#if PY_VERSION_HEX < 0x030900b1 + if (strcmp(memb->name, "__weaklistoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_weaklistoffset = memb->offset; + changed = 1; + } + else if (strcmp(memb->name, "__dictoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_dictoffset = memb->offset; + changed = 1; + } +#if CYTHON_METH_FASTCALL + else if (strcmp(memb->name, "__vectorcalloffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); +#if PY_VERSION_HEX >= 0x030800b4 + type->tp_vectorcall_offset = memb->offset; +#else + type->tp_print = (printfunc) memb->offset; +#endif + changed = 1; + } +#endif +#else + if ((0)); +#endif +#if PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON + else if (strcmp(memb->name, "__module__") == 0) { + PyObject *descr; + assert(memb->type == T_OBJECT); + assert(memb->flags == 0 || memb->flags == READONLY); + descr = PyDescr_NewMember(type, memb); + if (unlikely(!descr)) + return -1; + if (unlikely(PyDict_SetItem(type->tp_dict, PyDescr_NAME(descr), descr) < 0)) { + Py_DECREF(descr); + return -1; + } + Py_DECREF(descr); + changed = 1; + } +#endif + } + memb++; + } + if (changed) + PyType_Modified(type); + } +#endif + return 0; +} +#endif + +/* FetchSharedCythonModule */ +static PyObject *__Pyx_FetchSharedCythonABIModule(void) { + return __Pyx_PyImport_AddModuleRef((char*) __PYX_ABI_MODULE_NAME); +} + +/* FetchCommonType */ +static int __Pyx_VerifyCachedType(PyObject *cached_type, + const char *name, + Py_ssize_t basicsize, + Py_ssize_t expected_basicsize) { + if (!PyType_Check(cached_type)) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s is not a type object", name); + return -1; + } + if (basicsize != expected_basicsize) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s has the wrong size, try recompiling", + name); + return -1; + } + return 0; +} +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type) { + PyObject* abi_module; + const char* object_name; + PyTypeObject *cached_type = NULL; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + object_name = strrchr(type->tp_name, '.'); + object_name = object_name ? object_name+1 : type->tp_name; + cached_type = (PyTypeObject*) PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + if (__Pyx_VerifyCachedType( + (PyObject *)cached_type, + object_name, + cached_type->tp_basicsize, + type->tp_basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + if (PyType_Ready(type) < 0) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, (PyObject *)type) < 0) + goto bad; + Py_INCREF(type); + cached_type = type; +done: + Py_DECREF(abi_module); + return cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#else +static PyTypeObject *__Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases) { + PyObject *abi_module, *cached_type = NULL; + const char* object_name = strrchr(spec->name, '.'); + object_name = object_name ? object_name+1 : spec->name; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + cached_type = PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + Py_ssize_t basicsize; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *py_basicsize; + py_basicsize = PyObject_GetAttrString(cached_type, "__basicsize__"); + if (unlikely(!py_basicsize)) goto bad; + basicsize = PyLong_AsSsize_t(py_basicsize); + Py_DECREF(py_basicsize); + py_basicsize = 0; + if (unlikely(basicsize == (Py_ssize_t)-1) && PyErr_Occurred()) goto bad; +#else + basicsize = likely(PyType_Check(cached_type)) ? ((PyTypeObject*) cached_type)->tp_basicsize : -1; +#endif + if (__Pyx_VerifyCachedType( + cached_type, + object_name, + basicsize, + spec->basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + CYTHON_UNUSED_VAR(module); + cached_type = __Pyx_PyType_FromModuleAndSpec(abi_module, spec, bases); + if (unlikely(!cached_type)) goto bad; + if (unlikely(__Pyx_fix_up_extension_type_from_spec(spec, (PyTypeObject *) cached_type) < 0)) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, cached_type) < 0) goto bad; +done: + Py_DECREF(abi_module); + assert(cached_type == NULL || PyType_Check(cached_type)); + return (PyTypeObject *) cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#endif + +/* PyObjectGetAttrStr */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name) { + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro)) + return tp->tp_getattro(obj, attr_name); +#if PY_MAJOR_VERSION < 3 + if (likely(tp->tp_getattr)) + return tp->tp_getattr(obj, PyString_AS_STRING(attr_name)); +#endif + return PyObject_GetAttr(obj, attr_name); +} +#endif + +/* PyVectorcallFastCallDict */ +#if CYTHON_METH_FASTCALL +static PyObject *__Pyx_PyVectorcall_FastCallDict_kw(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + PyObject *res = NULL; + PyObject *kwnames; + PyObject **newargs; + PyObject **kwvalues; + Py_ssize_t i, pos; + size_t j; + PyObject *key, *value; + unsigned long keys_are_strings; + Py_ssize_t nkw = PyDict_GET_SIZE(kw); + newargs = (PyObject **)PyMem_Malloc((nargs + (size_t)nkw) * sizeof(args[0])); + if (unlikely(newargs == NULL)) { + PyErr_NoMemory(); + return NULL; + } + for (j = 0; j < nargs; j++) newargs[j] = args[j]; + kwnames = PyTuple_New(nkw); + if (unlikely(kwnames == NULL)) { + PyMem_Free(newargs); + return NULL; + } + kwvalues = newargs + nargs; + pos = i = 0; + keys_are_strings = Py_TPFLAGS_UNICODE_SUBCLASS; + while (PyDict_Next(kw, &pos, &key, &value)) { + keys_are_strings &= Py_TYPE(key)->tp_flags; + Py_INCREF(key); + Py_INCREF(value); + PyTuple_SET_ITEM(kwnames, i, key); + kwvalues[i] = value; + i++; + } + if (unlikely(!keys_are_strings)) { + PyErr_SetString(PyExc_TypeError, "keywords must be strings"); + goto cleanup; + } + res = vc(func, newargs, nargs, kwnames); +cleanup: + Py_DECREF(kwnames); + for (i = 0; i < nkw; i++) + Py_DECREF(kwvalues[i]); + PyMem_Free(newargs); + return res; +} +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + if (likely(kw == NULL) || PyDict_GET_SIZE(kw) == 0) { + return vc(func, args, nargs, NULL); + } + return __Pyx_PyVectorcall_FastCallDict_kw(func, vc, args, nargs, kw); +} +#endif + +/* CythonFunctionShared */ +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc) { + if (__Pyx_CyFunction_Check(func)) { + return PyCFunction_GetFunction(((__pyx_CyFunctionObject*)func)->func) == (PyCFunction) cfunc; + } else if (PyCFunction_Check(func)) { + return PyCFunction_GetFunction(func) == (PyCFunction) cfunc; + } + return 0; +} +#else +static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc) { + return __Pyx_CyOrPyCFunction_Check(func) && __Pyx_CyOrPyCFunction_GET_FUNCTION(func) == (PyCFunction) cfunc; +} +#endif +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj) { +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + __Pyx_Py_XDECREF_SET( + __Pyx_CyFunction_GetClassObj(f), + ((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#else + __Pyx_Py_XDECREF_SET( + ((PyCMethodObject *) (f))->mm_class, + (PyTypeObject*)((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#endif +} +static PyObject * +__Pyx_CyFunction_get_doc(__pyx_CyFunctionObject *op, void *closure) +{ + CYTHON_UNUSED_VAR(closure); + if (unlikely(op->func_doc == NULL)) { +#if CYTHON_COMPILING_IN_LIMITED_API + op->func_doc = PyObject_GetAttrString(op->func, "__doc__"); + if (unlikely(!op->func_doc)) return NULL; +#else + if (((PyCFunctionObject*)op)->m_ml->ml_doc) { +#if PY_MAJOR_VERSION >= 3 + op->func_doc = PyUnicode_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#else + op->func_doc = PyString_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#endif + if (unlikely(op->func_doc == NULL)) + return NULL; + } else { + Py_INCREF(Py_None); + return Py_None; + } +#endif + } + Py_INCREF(op->func_doc); + return op->func_doc; +} +static int +__Pyx_CyFunction_set_doc(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (value == NULL) { + value = Py_None; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_doc, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_name(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_name == NULL)) { +#if CYTHON_COMPILING_IN_LIMITED_API + op->func_name = PyObject_GetAttrString(op->func, "__name__"); +#elif PY_MAJOR_VERSION >= 3 + op->func_name = PyUnicode_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#else + op->func_name = PyString_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#endif + if (unlikely(op->func_name == NULL)) + return NULL; + } + Py_INCREF(op->func_name); + return op->func_name; +} +static int +__Pyx_CyFunction_set_name(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__name__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_name, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_qualname(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_qualname); + return op->func_qualname; +} +static int +__Pyx_CyFunction_set_qualname(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__qualname__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_qualname, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_dict(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_dict == NULL)) { + op->func_dict = PyDict_New(); + if (unlikely(op->func_dict == NULL)) + return NULL; + } + Py_INCREF(op->func_dict); + return op->func_dict; +} +static int +__Pyx_CyFunction_set_dict(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(value == NULL)) { + PyErr_SetString(PyExc_TypeError, + "function's dictionary may not be deleted"); + return -1; + } + if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "setting function's dictionary to a non-dict"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_dict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_globals(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_globals); + return op->func_globals; +} +static PyObject * +__Pyx_CyFunction_get_closure(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(op); + CYTHON_UNUSED_VAR(context); + Py_INCREF(Py_None); + return Py_None; +} +static PyObject * +__Pyx_CyFunction_get_code(__pyx_CyFunctionObject *op, void *context) +{ + PyObject* result = (op->func_code) ? op->func_code : Py_None; + CYTHON_UNUSED_VAR(context); + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_init_defaults(__pyx_CyFunctionObject *op) { + int result = 0; + PyObject *res = op->defaults_getter((PyObject *) op); + if (unlikely(!res)) + return -1; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + op->defaults_tuple = PyTuple_GET_ITEM(res, 0); + Py_INCREF(op->defaults_tuple); + op->defaults_kwdict = PyTuple_GET_ITEM(res, 1); + Py_INCREF(op->defaults_kwdict); + #else + op->defaults_tuple = __Pyx_PySequence_ITEM(res, 0); + if (unlikely(!op->defaults_tuple)) result = -1; + else { + op->defaults_kwdict = __Pyx_PySequence_ITEM(res, 1); + if (unlikely(!op->defaults_kwdict)) result = -1; + } + #endif + Py_DECREF(res); + return result; +} +static int +__Pyx_CyFunction_set_defaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyTuple_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__defaults__ must be set to a tuple object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__defaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_tuple, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_defaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_tuple; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_tuple; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_kwdefaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__kwdefaults__ must be set to a dict object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__kwdefaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_kwdict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_kwdefaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_kwdict; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_kwdict; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_annotations(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value || value == Py_None) { + value = NULL; + } else if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__annotations__ must be set to a dict object"); + return -1; + } + Py_XINCREF(value); + __Pyx_Py_XDECREF_SET(op->func_annotations, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_annotations(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->func_annotations; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + result = PyDict_New(); + if (unlikely(!result)) return NULL; + op->func_annotations = result; + } + Py_INCREF(result); + return result; +} +static PyObject * +__Pyx_CyFunction_get_is_coroutine(__pyx_CyFunctionObject *op, void *context) { + int is_coroutine; + CYTHON_UNUSED_VAR(context); + if (op->func_is_coroutine) { + return __Pyx_NewRef(op->func_is_coroutine); + } + is_coroutine = op->flags & __Pyx_CYFUNCTION_COROUTINE; +#if PY_VERSION_HEX >= 0x03050000 + if (is_coroutine) { + PyObject *module, *fromlist, *marker = __pyx_n_s_is_coroutine; + fromlist = PyList_New(1); + if (unlikely(!fromlist)) return NULL; + Py_INCREF(marker); +#if CYTHON_ASSUME_SAFE_MACROS + PyList_SET_ITEM(fromlist, 0, marker); +#else + if (unlikely(PyList_SetItem(fromlist, 0, marker) < 0)) { + Py_DECREF(marker); + Py_DECREF(fromlist); + return NULL; + } +#endif + module = PyImport_ImportModuleLevelObject(__pyx_n_s_asyncio_coroutines, NULL, NULL, fromlist, 0); + Py_DECREF(fromlist); + if (unlikely(!module)) goto ignore; + op->func_is_coroutine = __Pyx_PyObject_GetAttrStr(module, marker); + Py_DECREF(module); + if (likely(op->func_is_coroutine)) { + return __Pyx_NewRef(op->func_is_coroutine); + } +ignore: + PyErr_Clear(); + } +#endif + op->func_is_coroutine = __Pyx_PyBool_FromLong(is_coroutine); + return __Pyx_NewRef(op->func_is_coroutine); +} +#if CYTHON_COMPILING_IN_LIMITED_API +static PyObject * +__Pyx_CyFunction_get_module(__pyx_CyFunctionObject *op, void *context) { + CYTHON_UNUSED_VAR(context); + return PyObject_GetAttrString(op->func, "__module__"); +} +static int +__Pyx_CyFunction_set_module(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + return PyObject_SetAttrString(op->func, "__module__", value); +} +#endif +static PyGetSetDef __pyx_CyFunction_getsets[] = { + {(char *) "func_doc", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "__doc__", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "func_name", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__name__", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__qualname__", (getter)__Pyx_CyFunction_get_qualname, (setter)__Pyx_CyFunction_set_qualname, 0, 0}, + {(char *) "func_dict", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "__dict__", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "func_globals", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "__globals__", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "func_closure", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "__closure__", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "func_code", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "__code__", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "func_defaults", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__defaults__", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__kwdefaults__", (getter)__Pyx_CyFunction_get_kwdefaults, (setter)__Pyx_CyFunction_set_kwdefaults, 0, 0}, + {(char *) "__annotations__", (getter)__Pyx_CyFunction_get_annotations, (setter)__Pyx_CyFunction_set_annotations, 0, 0}, + {(char *) "_is_coroutine", (getter)__Pyx_CyFunction_get_is_coroutine, 0, 0, 0}, +#if CYTHON_COMPILING_IN_LIMITED_API + {"__module__", (getter)__Pyx_CyFunction_get_module, (setter)__Pyx_CyFunction_set_module, 0, 0}, +#endif + {0, 0, 0, 0, 0} +}; +static PyMemberDef __pyx_CyFunction_members[] = { +#if !CYTHON_COMPILING_IN_LIMITED_API + {(char *) "__module__", T_OBJECT, offsetof(PyCFunctionObject, m_module), 0, 0}, +#endif +#if CYTHON_USE_TYPE_SPECS + {(char *) "__dictoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_dict), READONLY, 0}, +#if CYTHON_METH_FASTCALL +#if CYTHON_BACKPORT_VECTORCALL + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_vectorcall), READONLY, 0}, +#else +#if !CYTHON_COMPILING_IN_LIMITED_API + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(PyCFunctionObject, vectorcall), READONLY, 0}, +#endif +#endif +#endif +#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_weakreflist), READONLY, 0}, +#else + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(PyCFunctionObject, m_weakreflist), READONLY, 0}, +#endif +#endif + {0, 0, 0, 0, 0} +}; +static PyObject * +__Pyx_CyFunction_reduce(__pyx_CyFunctionObject *m, PyObject *args) +{ + CYTHON_UNUSED_VAR(args); +#if PY_MAJOR_VERSION >= 3 + Py_INCREF(m->func_qualname); + return m->func_qualname; +#else + return PyString_FromString(((PyCFunctionObject*)m)->m_ml->ml_name); +#endif +} +static PyMethodDef __pyx_CyFunction_methods[] = { + {"__reduce__", (PyCFunction)__Pyx_CyFunction_reduce, METH_VARARGS, 0}, + {0, 0, 0, 0} +}; +#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API +#define __Pyx_CyFunction_weakreflist(cyfunc) ((cyfunc)->func_weakreflist) +#else +#define __Pyx_CyFunction_weakreflist(cyfunc) (((PyCFunctionObject*)cyfunc)->m_weakreflist) +#endif +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject *op, PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { +#if !CYTHON_COMPILING_IN_LIMITED_API + PyCFunctionObject *cf = (PyCFunctionObject*) op; +#endif + if (unlikely(op == NULL)) + return NULL; +#if CYTHON_COMPILING_IN_LIMITED_API + op->func = PyCFunction_NewEx(ml, (PyObject*)op, module); + if (unlikely(!op->func)) return NULL; +#endif + op->flags = flags; + __Pyx_CyFunction_weakreflist(op) = NULL; +#if !CYTHON_COMPILING_IN_LIMITED_API + cf->m_ml = ml; + cf->m_self = (PyObject *) op; +#endif + Py_XINCREF(closure); + op->func_closure = closure; +#if !CYTHON_COMPILING_IN_LIMITED_API + Py_XINCREF(module); + cf->m_module = module; +#endif + op->func_dict = NULL; + op->func_name = NULL; + Py_INCREF(qualname); + op->func_qualname = qualname; + op->func_doc = NULL; +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + op->func_classobj = NULL; +#else + ((PyCMethodObject*)op)->mm_class = NULL; +#endif + op->func_globals = globals; + Py_INCREF(op->func_globals); + Py_XINCREF(code); + op->func_code = code; + op->defaults_pyobjects = 0; + op->defaults_size = 0; + op->defaults = NULL; + op->defaults_tuple = NULL; + op->defaults_kwdict = NULL; + op->defaults_getter = NULL; + op->func_annotations = NULL; + op->func_is_coroutine = NULL; +#if CYTHON_METH_FASTCALL + switch (ml->ml_flags & (METH_VARARGS | METH_FASTCALL | METH_NOARGS | METH_O | METH_KEYWORDS | METH_METHOD)) { + case METH_NOARGS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_NOARGS; + break; + case METH_O: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_O; + break; + case METH_METHOD | METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD; + break; + case METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS; + break; + case METH_VARARGS | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = NULL; + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + Py_DECREF(op); + return NULL; + } +#endif + return (PyObject *) op; +} +static int +__Pyx_CyFunction_clear(__pyx_CyFunctionObject *m) +{ + Py_CLEAR(m->func_closure); +#if CYTHON_COMPILING_IN_LIMITED_API + Py_CLEAR(m->func); +#else + Py_CLEAR(((PyCFunctionObject*)m)->m_module); +#endif + Py_CLEAR(m->func_dict); + Py_CLEAR(m->func_name); + Py_CLEAR(m->func_qualname); + Py_CLEAR(m->func_doc); + Py_CLEAR(m->func_globals); + Py_CLEAR(m->func_code); +#if !CYTHON_COMPILING_IN_LIMITED_API +#if PY_VERSION_HEX < 0x030900B1 + Py_CLEAR(__Pyx_CyFunction_GetClassObj(m)); +#else + { + PyObject *cls = (PyObject*) ((PyCMethodObject *) (m))->mm_class; + ((PyCMethodObject *) (m))->mm_class = NULL; + Py_XDECREF(cls); + } +#endif +#endif + Py_CLEAR(m->defaults_tuple); + Py_CLEAR(m->defaults_kwdict); + Py_CLEAR(m->func_annotations); + Py_CLEAR(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_XDECREF(pydefaults[i]); + PyObject_Free(m->defaults); + m->defaults = NULL; + } + return 0; +} +static void __Pyx__CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + if (__Pyx_CyFunction_weakreflist(m) != NULL) + PyObject_ClearWeakRefs((PyObject *) m); + __Pyx_CyFunction_clear(m); + __Pyx_PyHeapTypeObject_GC_Del(m); +} +static void __Pyx_CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + PyObject_GC_UnTrack(m); + __Pyx__CyFunction_dealloc(m); +} +static int __Pyx_CyFunction_traverse(__pyx_CyFunctionObject *m, visitproc visit, void *arg) +{ + Py_VISIT(m->func_closure); +#if CYTHON_COMPILING_IN_LIMITED_API + Py_VISIT(m->func); +#else + Py_VISIT(((PyCFunctionObject*)m)->m_module); +#endif + Py_VISIT(m->func_dict); + Py_VISIT(m->func_name); + Py_VISIT(m->func_qualname); + Py_VISIT(m->func_doc); + Py_VISIT(m->func_globals); + Py_VISIT(m->func_code); +#if !CYTHON_COMPILING_IN_LIMITED_API + Py_VISIT(__Pyx_CyFunction_GetClassObj(m)); +#endif + Py_VISIT(m->defaults_tuple); + Py_VISIT(m->defaults_kwdict); + Py_VISIT(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_VISIT(pydefaults[i]); + } + return 0; +} +static PyObject* +__Pyx_CyFunction_repr(__pyx_CyFunctionObject *op) +{ +#if PY_MAJOR_VERSION >= 3 + return PyUnicode_FromFormat("", + op->func_qualname, (void *)op); +#else + return PyString_FromFormat("", + PyString_AsString(op->func_qualname), (void *)op); +#endif +} +static PyObject * __Pyx_CyFunction_CallMethod(PyObject *func, PyObject *self, PyObject *arg, PyObject *kw) { +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *f = ((__pyx_CyFunctionObject*)func)->func; + PyObject *py_name = NULL; + PyCFunction meth; + int flags; + meth = PyCFunction_GetFunction(f); + if (unlikely(!meth)) return NULL; + flags = PyCFunction_GetFlags(f); + if (unlikely(flags < 0)) return NULL; +#else + PyCFunctionObject* f = (PyCFunctionObject*)func; + PyCFunction meth = f->m_ml->ml_meth; + int flags = f->m_ml->ml_flags; +#endif + Py_ssize_t size; + switch (flags & (METH_VARARGS | METH_KEYWORDS | METH_NOARGS | METH_O)) { + case METH_VARARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) + return (*meth)(self, arg); + break; + case METH_VARARGS | METH_KEYWORDS: + return (*(PyCFunctionWithKeywords)(void*)meth)(self, arg, kw); + case METH_NOARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { +#if CYTHON_ASSUME_SAFE_MACROS + size = PyTuple_GET_SIZE(arg); +#else + size = PyTuple_Size(arg); + if (unlikely(size < 0)) return NULL; +#endif + if (likely(size == 0)) + return (*meth)(self, NULL); +#if CYTHON_COMPILING_IN_LIMITED_API + py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); + if (!py_name) return NULL; + PyErr_Format(PyExc_TypeError, + "%.200S() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + py_name, size); + Py_DECREF(py_name); +#else + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); +#endif + return NULL; + } + break; + case METH_O: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { +#if CYTHON_ASSUME_SAFE_MACROS + size = PyTuple_GET_SIZE(arg); +#else + size = PyTuple_Size(arg); + if (unlikely(size < 0)) return NULL; +#endif + if (likely(size == 1)) { + PyObject *result, *arg0; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + arg0 = PyTuple_GET_ITEM(arg, 0); + #else + arg0 = __Pyx_PySequence_ITEM(arg, 0); if (unlikely(!arg0)) return NULL; + #endif + result = (*meth)(self, arg0); + #if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(arg0); + #endif + return result; + } +#if CYTHON_COMPILING_IN_LIMITED_API + py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); + if (!py_name) return NULL; + PyErr_Format(PyExc_TypeError, + "%.200S() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + py_name, size); + Py_DECREF(py_name); +#else + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); +#endif + return NULL; + } + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + return NULL; + } +#if CYTHON_COMPILING_IN_LIMITED_API + py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); + if (!py_name) return NULL; + PyErr_Format(PyExc_TypeError, "%.200S() takes no keyword arguments", + py_name); + Py_DECREF(py_name); +#else + PyErr_Format(PyExc_TypeError, "%.200s() takes no keyword arguments", + f->m_ml->ml_name); +#endif + return NULL; +} +static CYTHON_INLINE PyObject *__Pyx_CyFunction_Call(PyObject *func, PyObject *arg, PyObject *kw) { + PyObject *self, *result; +#if CYTHON_COMPILING_IN_LIMITED_API + self = PyCFunction_GetSelf(((__pyx_CyFunctionObject*)func)->func); + if (unlikely(!self) && PyErr_Occurred()) return NULL; +#else + self = ((PyCFunctionObject*)func)->m_self; +#endif + result = __Pyx_CyFunction_CallMethod(func, self, arg, kw); + return result; +} +static PyObject *__Pyx_CyFunction_CallAsMethod(PyObject *func, PyObject *args, PyObject *kw) { + PyObject *result; + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *) func; +#if CYTHON_METH_FASTCALL + __pyx_vectorcallfunc vc = __Pyx_CyFunction_func_vectorcall(cyfunc); + if (vc) { +#if CYTHON_ASSUME_SAFE_MACROS + return __Pyx_PyVectorcall_FastCallDict(func, vc, &PyTuple_GET_ITEM(args, 0), (size_t)PyTuple_GET_SIZE(args), kw); +#else + (void) &__Pyx_PyVectorcall_FastCallDict; + return PyVectorcall_Call(func, args, kw); +#endif + } +#endif + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + Py_ssize_t argc; + PyObject *new_args; + PyObject *self; +#if CYTHON_ASSUME_SAFE_MACROS + argc = PyTuple_GET_SIZE(args); +#else + argc = PyTuple_Size(args); + if (unlikely(!argc) < 0) return NULL; +#endif + new_args = PyTuple_GetSlice(args, 1, argc); + if (unlikely(!new_args)) + return NULL; + self = PyTuple_GetItem(args, 0); + if (unlikely(!self)) { + Py_DECREF(new_args); +#if PY_MAJOR_VERSION > 2 + PyErr_Format(PyExc_TypeError, + "unbound method %.200S() needs an argument", + cyfunc->func_qualname); +#else + PyErr_SetString(PyExc_TypeError, + "unbound method needs an argument"); +#endif + return NULL; + } + result = __Pyx_CyFunction_CallMethod(func, self, new_args, kw); + Py_DECREF(new_args); + } else { + result = __Pyx_CyFunction_Call(func, args, kw); + } + return result; +} +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE int __Pyx_CyFunction_Vectorcall_CheckArgs(__pyx_CyFunctionObject *cyfunc, Py_ssize_t nargs, PyObject *kwnames) +{ + int ret = 0; + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + if (unlikely(nargs < 1)) { + PyErr_Format(PyExc_TypeError, "%.200s() needs an argument", + ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + ret = 1; + } + if (unlikely(kwnames) && unlikely(PyTuple_GET_SIZE(kwnames))) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no keyword arguments", ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + return ret; +} +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 0)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, NULL); +} +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 1)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, args[0]); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((_PyCFunctionFastWithKeywords)(void(*)(void))def->ml_meth)(self, args, nargs, kwnames); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; + PyTypeObject *cls = (PyTypeObject *) __Pyx_CyFunction_GetClassObj(cyfunc); +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((__Pyx_PyCMethod)(void(*)(void))def->ml_meth)(self, cls, args, (size_t)nargs, kwnames); +} +#endif +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_CyFunctionType_slots[] = { + {Py_tp_dealloc, (void *)__Pyx_CyFunction_dealloc}, + {Py_tp_repr, (void *)__Pyx_CyFunction_repr}, + {Py_tp_call, (void *)__Pyx_CyFunction_CallAsMethod}, + {Py_tp_traverse, (void *)__Pyx_CyFunction_traverse}, + {Py_tp_clear, (void *)__Pyx_CyFunction_clear}, + {Py_tp_methods, (void *)__pyx_CyFunction_methods}, + {Py_tp_members, (void *)__pyx_CyFunction_members}, + {Py_tp_getset, (void *)__pyx_CyFunction_getsets}, + {Py_tp_descr_get, (void *)__Pyx_PyMethod_New}, + {0, 0}, +}; +static PyType_Spec __pyx_CyFunctionType_spec = { + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#if (defined(_Py_TPFLAGS_HAVE_VECTORCALL) && CYTHON_METH_FASTCALL) + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + __pyx_CyFunctionType_slots +}; +#else +static PyTypeObject __pyx_CyFunctionType_type = { + PyVarObject_HEAD_INIT(0, 0) + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, + (destructor) __Pyx_CyFunction_dealloc, +#if !CYTHON_METH_FASTCALL + 0, +#elif CYTHON_BACKPORT_VECTORCALL + (printfunc)offsetof(__pyx_CyFunctionObject, func_vectorcall), +#else + offsetof(PyCFunctionObject, vectorcall), +#endif + 0, + 0, +#if PY_MAJOR_VERSION < 3 + 0, +#else + 0, +#endif + (reprfunc) __Pyx_CyFunction_repr, + 0, + 0, + 0, + 0, + __Pyx_CyFunction_CallAsMethod, + 0, + 0, + 0, + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#if defined(_Py_TPFLAGS_HAVE_VECTORCALL) && CYTHON_METH_FASTCALL + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + 0, + (traverseproc) __Pyx_CyFunction_traverse, + (inquiry) __Pyx_CyFunction_clear, + 0, +#if PY_VERSION_HEX < 0x030500A0 + offsetof(__pyx_CyFunctionObject, func_weakreflist), +#else + offsetof(PyCFunctionObject, m_weakreflist), +#endif + 0, + 0, + __pyx_CyFunction_methods, + __pyx_CyFunction_members, + __pyx_CyFunction_getsets, + 0, + 0, + __Pyx_PyMethod_New, + 0, + offsetof(__pyx_CyFunctionObject, func_dict), + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, +#if PY_VERSION_HEX >= 0x030400a1 + 0, +#endif +#if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, +#endif +#if __PYX_NEED_TP_PRINT_SLOT + 0, +#endif +#if PY_VERSION_HEX >= 0x030C0000 + 0, +#endif +#if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, +#endif +}; +#endif +static int __pyx_CyFunction_init(PyObject *module) { +#if CYTHON_USE_TYPE_SPECS + __pyx_CyFunctionType = __Pyx_FetchCommonTypeFromSpec(module, &__pyx_CyFunctionType_spec, NULL); +#else + CYTHON_UNUSED_VAR(module); + __pyx_CyFunctionType = __Pyx_FetchCommonType(&__pyx_CyFunctionType_type); +#endif + if (unlikely(__pyx_CyFunctionType == NULL)) { + return -1; + } + return 0; +} +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *func, size_t size, int pyobjects) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults = PyObject_Malloc(size); + if (unlikely(!m->defaults)) + return PyErr_NoMemory(); + memset(m->defaults, 0, size); + m->defaults_pyobjects = pyobjects; + m->defaults_size = size; + return m->defaults; +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *func, PyObject *tuple) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_tuple = tuple; + Py_INCREF(tuple); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_kwdict = dict; + Py_INCREF(dict); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->func_annotations = dict; + Py_INCREF(dict); +} + +/* CythonFunction */ +static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { + PyObject *op = __Pyx_CyFunction_Init( + PyObject_GC_New(__pyx_CyFunctionObject, __pyx_CyFunctionType), + ml, flags, qualname, closure, module, globals, code + ); + if (likely(op)) { + PyObject_GC_Track(op); + } + return op; +} + +/* PyDictVersioning */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + return likely(dict) ? __PYX_GET_DICT_VERSION(dict) : 0; +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj) { + PyObject **dictptr = NULL; + Py_ssize_t offset = Py_TYPE(obj)->tp_dictoffset; + if (offset) { +#if CYTHON_COMPILING_IN_CPYTHON + dictptr = (likely(offset > 0)) ? (PyObject **) ((char *)obj + offset) : _PyObject_GetDictPtr(obj); +#else + dictptr = _PyObject_GetDictPtr(obj); +#endif + } + return (dictptr && *dictptr) ? __PYX_GET_DICT_VERSION(*dictptr) : 0; +} +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + if (unlikely(!dict) || unlikely(tp_dict_version != __PYX_GET_DICT_VERSION(dict))) + return 0; + return obj_dict_version == __Pyx_get_object_dict_version(obj); +} +#endif + +/* PyErrExceptionMatches */ +#if CYTHON_FAST_THREAD_STATE +static int __Pyx_PyErr_ExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; i= 0x030C00A6 + PyObject *current_exception = tstate->current_exception; + if (unlikely(!current_exception)) return 0; + exc_type = (PyObject*) Py_TYPE(current_exception); + if (exc_type == err) return 1; +#else + exc_type = tstate->curexc_type; + if (exc_type == err) return 1; + if (unlikely(!exc_type)) return 0; +#endif + #if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(exc_type); + #endif + if (unlikely(PyTuple_Check(err))) { + result = __Pyx_PyErr_ExceptionMatchesTuple(exc_type, err); + } else { + result = __Pyx_PyErr_GivenExceptionMatches(exc_type, err); + } + #if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(exc_type); + #endif + return result; +} +#endif + +/* PyErrFetchRestore */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject *tmp_value; + assert(type == NULL || (value != NULL && type == (PyObject*) Py_TYPE(value))); + if (value) { + #if CYTHON_COMPILING_IN_CPYTHON + if (unlikely(((PyBaseExceptionObject*) value)->traceback != tb)) + #endif + PyException_SetTraceback(value, tb); + } + tmp_value = tstate->current_exception; + tstate->current_exception = value; + Py_XDECREF(tmp_value); + Py_XDECREF(type); + Py_XDECREF(tb); +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + tmp_type = tstate->curexc_type; + tmp_value = tstate->curexc_value; + tmp_tb = tstate->curexc_traceback; + tstate->curexc_type = type; + tstate->curexc_value = value; + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); +#endif +} +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject* exc_value; + exc_value = tstate->current_exception; + tstate->current_exception = 0; + *value = exc_value; + *type = NULL; + *tb = NULL; + if (exc_value) { + *type = (PyObject*) Py_TYPE(exc_value); + Py_INCREF(*type); + #if CYTHON_COMPILING_IN_CPYTHON + *tb = ((PyBaseExceptionObject*) exc_value)->traceback; + Py_XINCREF(*tb); + #else + *tb = PyException_GetTraceback(exc_value); + #endif + } +#else + *type = tstate->curexc_type; + *value = tstate->curexc_value; + *tb = tstate->curexc_traceback; + tstate->curexc_type = 0; + tstate->curexc_value = 0; + tstate->curexc_traceback = 0; +#endif +} +#endif + +/* PyObjectGetAttrStrNoError */ +#if __PYX_LIMITED_VERSION_HEX < 0x030d00A1 +static void __Pyx_PyObject_GetAttrStr_ClearAttributeError(void) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + if (likely(__Pyx_PyErr_ExceptionMatches(PyExc_AttributeError))) + __Pyx_PyErr_Clear(); +} +#endif +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name) { + PyObject *result; +#if __PYX_LIMITED_VERSION_HEX >= 0x030d00A1 + (void) PyObject_GetOptionalAttr(obj, attr_name, &result); + return result; +#else +#if CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_TYPE_SLOTS && PY_VERSION_HEX >= 0x030700B1 + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro == PyObject_GenericGetAttr)) { + return _PyObject_GenericGetAttrWithDict(obj, attr_name, NULL, 1); + } +#endif + result = __Pyx_PyObject_GetAttrStr(obj, attr_name); + if (unlikely(!result)) { + __Pyx_PyObject_GetAttrStr_ClearAttributeError(); + } + return result; +#endif +} + +/* CLineInTraceback */ +#ifndef CYTHON_CLINE_IN_TRACEBACK +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line) { + PyObject *use_cline; + PyObject *ptype, *pvalue, *ptraceback; +#if CYTHON_COMPILING_IN_CPYTHON + PyObject **cython_runtime_dict; +#endif + CYTHON_MAYBE_UNUSED_VAR(tstate); + if (unlikely(!__pyx_cython_runtime)) { + return c_line; + } + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); +#if CYTHON_COMPILING_IN_CPYTHON + cython_runtime_dict = _PyObject_GetDictPtr(__pyx_cython_runtime); + if (likely(cython_runtime_dict)) { + __PYX_PY_DICT_LOOKUP_IF_MODIFIED( + use_cline, *cython_runtime_dict, + __Pyx_PyDict_GetItemStr(*cython_runtime_dict, __pyx_n_s_cline_in_traceback)) + } else +#endif + { + PyObject *use_cline_obj = __Pyx_PyObject_GetAttrStrNoError(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback); + if (use_cline_obj) { + use_cline = PyObject_Not(use_cline_obj) ? Py_False : Py_True; + Py_DECREF(use_cline_obj); + } else { + PyErr_Clear(); + use_cline = NULL; + } + } + if (!use_cline) { + c_line = 0; + (void) PyObject_SetAttr(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback, Py_False); + } + else if (use_cline == Py_False || (use_cline != Py_True && PyObject_Not(use_cline) != 0)) { + c_line = 0; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + return c_line; +} +#endif + +/* CodeObjectCache */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line) { + int start = 0, mid = 0, end = count - 1; + if (end >= 0 && code_line > entries[end].code_line) { + return count; + } + while (start < end) { + mid = start + (end - start) / 2; + if (code_line < entries[mid].code_line) { + end = mid; + } else if (code_line > entries[mid].code_line) { + start = mid + 1; + } else { + return mid; + } + } + if (code_line <= entries[mid].code_line) { + return mid; + } else { + return mid + 1; + } +} +static PyCodeObject *__pyx_find_code_object(int code_line) { + PyCodeObject* code_object; + int pos; + if (unlikely(!code_line) || unlikely(!__pyx_code_cache.entries)) { + return NULL; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if (unlikely(pos >= __pyx_code_cache.count) || unlikely(__pyx_code_cache.entries[pos].code_line != code_line)) { + return NULL; + } + code_object = __pyx_code_cache.entries[pos].code_object; + Py_INCREF(code_object); + return code_object; +} +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object) { + int pos, i; + __Pyx_CodeObjectCacheEntry* entries = __pyx_code_cache.entries; + if (unlikely(!code_line)) { + return; + } + if (unlikely(!entries)) { + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Malloc(64*sizeof(__Pyx_CodeObjectCacheEntry)); + if (likely(entries)) { + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = 64; + __pyx_code_cache.count = 1; + entries[0].code_line = code_line; + entries[0].code_object = code_object; + Py_INCREF(code_object); + } + return; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if ((pos < __pyx_code_cache.count) && unlikely(__pyx_code_cache.entries[pos].code_line == code_line)) { + PyCodeObject* tmp = entries[pos].code_object; + entries[pos].code_object = code_object; + Py_DECREF(tmp); + return; + } + if (__pyx_code_cache.count == __pyx_code_cache.max_count) { + int new_max = __pyx_code_cache.max_count + 64; + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Realloc( + __pyx_code_cache.entries, ((size_t)new_max) * sizeof(__Pyx_CodeObjectCacheEntry)); + if (unlikely(!entries)) { + return; + } + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = new_max; + } + for (i=__pyx_code_cache.count; i>pos; i--) { + entries[i] = entries[i-1]; + } + entries[pos].code_line = code_line; + entries[pos].code_object = code_object; + __pyx_code_cache.count++; + Py_INCREF(code_object); +} +#endif + +/* AddTraceback */ +#include "compile.h" +#include "frameobject.h" +#include "traceback.h" +#if PY_VERSION_HEX >= 0x030b00a6 && !CYTHON_COMPILING_IN_LIMITED_API + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static PyObject *__Pyx_PyCode_Replace_For_AddTraceback(PyObject *code, PyObject *scratch_dict, + PyObject *firstlineno, PyObject *name) { + PyObject *replace = NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "co_firstlineno", firstlineno))) return NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "co_name", name))) return NULL; + replace = PyObject_GetAttrString(code, "replace"); + if (likely(replace)) { + PyObject *result; + result = PyObject_Call(replace, __pyx_empty_tuple, scratch_dict); + Py_DECREF(replace); + return result; + } + PyErr_Clear(); + #if __PYX_LIMITED_VERSION_HEX < 0x030780000 + { + PyObject *compiled = NULL, *result = NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "code", code))) return NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "type", (PyObject*)(&PyType_Type)))) return NULL; + compiled = Py_CompileString( + "out = type(code)(\n" + " code.co_argcount, code.co_kwonlyargcount, code.co_nlocals, code.co_stacksize,\n" + " code.co_flags, code.co_code, code.co_consts, code.co_names,\n" + " code.co_varnames, code.co_filename, co_name, co_firstlineno,\n" + " code.co_lnotab)\n", "", Py_file_input); + if (!compiled) return NULL; + result = PyEval_EvalCode(compiled, scratch_dict, scratch_dict); + Py_DECREF(compiled); + if (!result) PyErr_Print(); + Py_DECREF(result); + result = PyDict_GetItemString(scratch_dict, "out"); + if (result) Py_INCREF(result); + return result; + } + #else + return NULL; + #endif +} +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + PyObject *code_object = NULL, *py_py_line = NULL, *py_funcname = NULL, *dict = NULL; + PyObject *replace = NULL, *getframe = NULL, *frame = NULL; + PyObject *exc_type, *exc_value, *exc_traceback; + int success = 0; + if (c_line) { + (void) __pyx_cfilenm; + (void) __Pyx_CLineForTraceback(__Pyx_PyThreadState_Current, c_line); + } + PyErr_Fetch(&exc_type, &exc_value, &exc_traceback); + code_object = Py_CompileString("_getframe()", filename, Py_eval_input); + if (unlikely(!code_object)) goto bad; + py_py_line = PyLong_FromLong(py_line); + if (unlikely(!py_py_line)) goto bad; + py_funcname = PyUnicode_FromString(funcname); + if (unlikely(!py_funcname)) goto bad; + dict = PyDict_New(); + if (unlikely(!dict)) goto bad; + { + PyObject *old_code_object = code_object; + code_object = __Pyx_PyCode_Replace_For_AddTraceback(code_object, dict, py_py_line, py_funcname); + Py_DECREF(old_code_object); + } + if (unlikely(!code_object)) goto bad; + getframe = PySys_GetObject("_getframe"); + if (unlikely(!getframe)) goto bad; + if (unlikely(PyDict_SetItemString(dict, "_getframe", getframe))) goto bad; + frame = PyEval_EvalCode(code_object, dict, dict); + if (unlikely(!frame) || frame == Py_None) goto bad; + success = 1; + bad: + PyErr_Restore(exc_type, exc_value, exc_traceback); + Py_XDECREF(code_object); + Py_XDECREF(py_py_line); + Py_XDECREF(py_funcname); + Py_XDECREF(dict); + Py_XDECREF(replace); + if (success) { + PyTraceBack_Here( + (struct _frame*)frame); + } + Py_XDECREF(frame); +} +#else +static PyCodeObject* __Pyx_CreateCodeObjectForTraceback( + const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = NULL; + PyObject *py_funcname = NULL; + #if PY_MAJOR_VERSION < 3 + PyObject *py_srcfile = NULL; + py_srcfile = PyString_FromString(filename); + if (!py_srcfile) goto bad; + #endif + if (c_line) { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + #else + py_funcname = PyUnicode_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + funcname = PyUnicode_AsUTF8(py_funcname); + if (!funcname) goto bad; + #endif + } + else { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromString(funcname); + if (!py_funcname) goto bad; + #endif + } + #if PY_MAJOR_VERSION < 3 + py_code = __Pyx_PyCode_New( + 0, + 0, + 0, + 0, + 0, + 0, + __pyx_empty_bytes, /*PyObject *code,*/ + __pyx_empty_tuple, /*PyObject *consts,*/ + __pyx_empty_tuple, /*PyObject *names,*/ + __pyx_empty_tuple, /*PyObject *varnames,*/ + __pyx_empty_tuple, /*PyObject *freevars,*/ + __pyx_empty_tuple, /*PyObject *cellvars,*/ + py_srcfile, /*PyObject *filename,*/ + py_funcname, /*PyObject *name,*/ + py_line, + __pyx_empty_bytes /*PyObject *lnotab*/ + ); + Py_DECREF(py_srcfile); + #else + py_code = PyCode_NewEmpty(filename, funcname, py_line); + #endif + Py_XDECREF(py_funcname); + return py_code; +bad: + Py_XDECREF(py_funcname); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_srcfile); + #endif + return NULL; +} +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = 0; + PyFrameObject *py_frame = 0; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject *ptype, *pvalue, *ptraceback; + if (c_line) { + c_line = __Pyx_CLineForTraceback(tstate, c_line); + } + py_code = __pyx_find_code_object(c_line ? -c_line : py_line); + if (!py_code) { + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); + py_code = __Pyx_CreateCodeObjectForTraceback( + funcname, c_line, py_line, filename); + if (!py_code) { + /* If the code object creation fails, then we should clear the + fetched exception references and propagate the new exception */ + Py_XDECREF(ptype); + Py_XDECREF(pvalue); + Py_XDECREF(ptraceback); + goto bad; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + __pyx_insert_code_object(c_line ? -c_line : py_line, py_code); + } + py_frame = PyFrame_New( + tstate, /*PyThreadState *tstate,*/ + py_code, /*PyCodeObject *code,*/ + __pyx_d, /*PyObject *globals,*/ + 0 /*PyObject *locals*/ + ); + if (!py_frame) goto bad; + __Pyx_PyFrame_SetLineNumber(py_frame, py_line); + PyTraceBack_Here(py_frame); +bad: + Py_XDECREF(py_code); + Py_XDECREF(py_frame); +} +#endif + +/* CIntFromPyVerify */ +#define __PYX_VERIFY_RETURN_INT(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 0) +#define __PYX_VERIFY_RETURN_INT_EXC(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 1) +#define __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, exc)\ + {\ + func_type value = func_value;\ + if (sizeof(target_type) < sizeof(func_type)) {\ + if (unlikely(value != (func_type) (target_type) value)) {\ + func_type zero = 0;\ + if (exc && unlikely(value == (func_type)-1 && PyErr_Occurred()))\ + return (target_type) -1;\ + if (is_unsigned && unlikely(value < zero))\ + goto raise_neg_overflow;\ + else\ + goto raise_overflow;\ + }\ + }\ + return (target_type) value;\ + } + +/* CIntToPy */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(long) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(long) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(long) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; +#if !CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030d0000 + return _PyLong_FromByteArray(bytes, sizeof(long), + little, !is_unsigned); +#else + PyObject *from_bytes, *result = NULL; + PyObject *py_bytes = NULL, *arg_tuple = NULL, *kwds = NULL, *order_str = NULL; + from_bytes = PyObject_GetAttrString((PyObject*)&PyLong_Type, "from_bytes"); + if (!from_bytes) return NULL; + py_bytes = PyBytes_FromStringAndSize((char*)bytes, sizeof(long)); + if (!py_bytes) goto limited_bad; + order_str = PyUnicode_FromString(little ? "little" : "big"); + if (!order_str) goto limited_bad; + arg_tuple = PyTuple_Pack(2, py_bytes, order_str); + if (!arg_tuple) goto limited_bad; + if (!is_unsigned) { + kwds = PyDict_New(); + if (!kwds) goto limited_bad; + if (PyDict_SetItemString(kwds, "signed", __Pyx_NewRef(Py_True))) goto limited_bad; + } + result = PyObject_Call(from_bytes, arg_tuple, kwds); + limited_bad: + Py_XDECREF(kwds); + Py_XDECREF(arg_tuple); + Py_XDECREF(order_str); + Py_XDECREF(py_bytes); + Py_XDECREF(from_bytes); + return result; +#endif + } +} + +/* CIntFromPy */ +static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(long) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(long, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (long) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 2 * PyLong_SHIFT)) { + return (long) (((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 3 * PyLong_SHIFT)) { + return (long) (((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 4 * PyLong_SHIFT)) { + return (long) (((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(long) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(long) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) ((((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) ((((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) ((((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(long) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + long val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (long) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (long) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (long) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (long) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(long) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(long) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((long) 1) << (sizeof(long) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (long) -1; + } + } else { + long val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (long) -1; + val = __Pyx_PyInt_As_long(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to long"); + return (long) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to long"); + return (long) -1; +} + +/* FormatTypeName */ +#if CYTHON_COMPILING_IN_LIMITED_API +static __Pyx_TypeName +__Pyx_PyType_GetName(PyTypeObject* tp) +{ + PyObject *name = __Pyx_PyObject_GetAttrStr((PyObject *)tp, + __pyx_n_s_name); + if (unlikely(name == NULL) || unlikely(!PyUnicode_Check(name))) { + PyErr_Clear(); + Py_XDECREF(name); + name = __Pyx_NewRef(__pyx_n_s__4); + } + return name; +} +#endif + +/* CIntFromPy */ +static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(int) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(int, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (int) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 2 * PyLong_SHIFT)) { + return (int) (((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 3 * PyLong_SHIFT)) { + return (int) (((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 4 * PyLong_SHIFT)) { + return (int) (((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(int) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(int) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) ((((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) ((((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) ((((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(int) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + int val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (int) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (int) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (int) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (int) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(int) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(int) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((int) 1) << (sizeof(int) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (int) -1; + } + } else { + int val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (int) -1; + val = __Pyx_PyInt_As_int(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to int"); + return (int) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to int"); + return (int) -1; +} + +/* FastTypeChecks */ +#if CYTHON_COMPILING_IN_CPYTHON +static int __Pyx_InBases(PyTypeObject *a, PyTypeObject *b) { + while (a) { + a = __Pyx_PyType_GetSlot(a, tp_base, PyTypeObject*); + if (a == b) + return 1; + } + return b == &PyBaseObject_Type; +} +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (a == b) return 1; + mro = a->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + if (PyTuple_GET_ITEM(mro, i) == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(a, b); +} +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (cls == a || cls == b) return 1; + mro = cls->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + PyObject *base = PyTuple_GET_ITEM(mro, i); + if (base == (PyObject *)a || base == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(cls, a) || __Pyx_InBases(cls, b); +} +#if PY_MAJOR_VERSION == 2 +static int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject* exc_type2) { + PyObject *exception, *value, *tb; + int res; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&exception, &value, &tb); + res = exc_type1 ? PyObject_IsSubclass(err, exc_type1) : 0; + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + if (!res) { + res = PyObject_IsSubclass(err, exc_type2); + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + } + __Pyx_ErrRestore(exception, value, tb); + return res; +} +#else +static CYTHON_INLINE int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject *exc_type2) { + if (exc_type1) { + return __Pyx_IsAnySubtype2((PyTypeObject*)err, (PyTypeObject*)exc_type1, (PyTypeObject*)exc_type2); + } else { + return __Pyx_IsSubtype((PyTypeObject*)err, (PyTypeObject*)exc_type2); + } +} +#endif +static int __Pyx_PyErr_GivenExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + assert(PyExceptionClass_Check(exc_type)); + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; i= 0x030B00A4 + return Py_Version & ~0xFFUL; +#else + const char* rt_version = Py_GetVersion(); + unsigned long version = 0; + unsigned long factor = 0x01000000UL; + unsigned int digit = 0; + int i = 0; + while (factor) { + while ('0' <= rt_version[i] && rt_version[i] <= '9') { + digit = digit * 10 + (unsigned int) (rt_version[i] - '0'); + ++i; + } + version += factor * digit; + if (rt_version[i] != '.') + break; + digit = 0; + factor >>= 8; + ++i; + } + return version; +#endif +} +static int __Pyx_check_binary_version(unsigned long ct_version, unsigned long rt_version, int allow_newer) { + const unsigned long MAJOR_MINOR = 0xFFFF0000UL; + if ((rt_version & MAJOR_MINOR) == (ct_version & MAJOR_MINOR)) + return 0; + if (likely(allow_newer && (rt_version & MAJOR_MINOR) > (ct_version & MAJOR_MINOR))) + return 1; + { + char message[200]; + PyOS_snprintf(message, sizeof(message), + "compile time Python version %d.%d " + "of module '%.100s' " + "%s " + "runtime version %d.%d", + (int) (ct_version >> 24), (int) ((ct_version >> 16) & 0xFF), + __Pyx_MODULE_NAME, + (allow_newer) ? "was newer than" : "does not match", + (int) (rt_version >> 24), (int) ((rt_version >> 16) & 0xFF) + ); + return PyErr_WarnEx(NULL, message, 1); + } +} + +/* InitStrings */ +#if PY_MAJOR_VERSION >= 3 +static int __Pyx_InitString(__Pyx_StringTabEntry t, PyObject **str) { + if (t.is_unicode | t.is_str) { + if (t.intern) { + *str = PyUnicode_InternFromString(t.s); + } else if (t.encoding) { + *str = PyUnicode_Decode(t.s, t.n - 1, t.encoding, NULL); + } else { + *str = PyUnicode_FromStringAndSize(t.s, t.n - 1); + } + } else { + *str = PyBytes_FromStringAndSize(t.s, t.n - 1); + } + if (!*str) + return -1; + if (PyObject_Hash(*str) == -1) + return -1; + return 0; +} +#endif +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t) { + while (t->p) { + #if PY_MAJOR_VERSION >= 3 + __Pyx_InitString(*t, t->p); + #else + if (t->is_unicode) { + *t->p = PyUnicode_DecodeUTF8(t->s, t->n - 1, NULL); + } else if (t->intern) { + *t->p = PyString_InternFromString(t->s); + } else { + *t->p = PyString_FromStringAndSize(t->s, t->n - 1); + } + if (!*t->p) + return -1; + if (PyObject_Hash(*t->p) == -1) + return -1; + #endif + ++t; + } + return 0; +} + +#include +static CYTHON_INLINE Py_ssize_t __Pyx_ssize_strlen(const char *s) { + size_t len = strlen(s); + if (unlikely(len > (size_t) PY_SSIZE_T_MAX)) { + PyErr_SetString(PyExc_OverflowError, "byte string is too long"); + return -1; + } + return (Py_ssize_t) len; +} +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char* c_str) { + Py_ssize_t len = __Pyx_ssize_strlen(c_str); + if (unlikely(len < 0)) return NULL; + return __Pyx_PyUnicode_FromStringAndSize(c_str, len); +} +static CYTHON_INLINE PyObject* __Pyx_PyByteArray_FromString(const char* c_str) { + Py_ssize_t len = __Pyx_ssize_strlen(c_str); + if (unlikely(len < 0)) return NULL; + return PyByteArray_FromStringAndSize(c_str, len); +} +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject* o) { + Py_ssize_t ignore; + return __Pyx_PyObject_AsStringAndSize(o, &ignore); +} +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +#if !CYTHON_PEP393_ENABLED +static const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + char* defenc_c; + PyObject* defenc = _PyUnicode_AsDefaultEncodedString(o, NULL); + if (!defenc) return NULL; + defenc_c = PyBytes_AS_STRING(defenc); +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + { + char* end = defenc_c + PyBytes_GET_SIZE(defenc); + char* c; + for (c = defenc_c; c < end; c++) { + if ((unsigned char) (*c) >= 128) { + PyUnicode_AsASCIIString(o); + return NULL; + } + } + } +#endif + *length = PyBytes_GET_SIZE(defenc); + return defenc_c; +} +#else +static CYTHON_INLINE const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + if (unlikely(__Pyx_PyUnicode_READY(o) == -1)) return NULL; +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + if (likely(PyUnicode_IS_ASCII(o))) { + *length = PyUnicode_GET_LENGTH(o); + return PyUnicode_AsUTF8(o); + } else { + PyUnicode_AsASCIIString(o); + return NULL; + } +#else + return PyUnicode_AsUTF8AndSize(o, length); +#endif +} +#endif +#endif +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject* o, Py_ssize_t *length) { +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT + if ( +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + __Pyx_sys_getdefaultencoding_not_ascii && +#endif + PyUnicode_Check(o)) { + return __Pyx_PyUnicode_AsStringAndSize(o, length); + } else +#endif +#if (!CYTHON_COMPILING_IN_PYPY && !CYTHON_COMPILING_IN_LIMITED_API) || (defined(PyByteArray_AS_STRING) && defined(PyByteArray_GET_SIZE)) + if (PyByteArray_Check(o)) { + *length = PyByteArray_GET_SIZE(o); + return PyByteArray_AS_STRING(o); + } else +#endif + { + char* result; + int r = PyBytes_AsStringAndSize(o, &result, length); + if (unlikely(r < 0)) { + return NULL; + } else { + return result; + } + } +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject* x) { + int is_true = x == Py_True; + if (is_true | (x == Py_False) | (x == Py_None)) return is_true; + else return PyObject_IsTrue(x); +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject* x) { + int retval; + if (unlikely(!x)) return -1; + retval = __Pyx_PyObject_IsTrue(x); + Py_DECREF(x); + return retval; +} +static PyObject* __Pyx_PyNumber_IntOrLongWrongResultType(PyObject* result, const char* type_name) { + __Pyx_TypeName result_type_name = __Pyx_PyType_GetName(Py_TYPE(result)); +#if PY_MAJOR_VERSION >= 3 + if (PyLong_Check(result)) { + if (PyErr_WarnFormat(PyExc_DeprecationWarning, 1, + "__int__ returned non-int (type " __Pyx_FMT_TYPENAME "). " + "The ability to return an instance of a strict subclass of int is deprecated, " + "and may be removed in a future version of Python.", + result_type_name)) { + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; + } + __Pyx_DECREF_TypeName(result_type_name); + return result; + } +#endif + PyErr_Format(PyExc_TypeError, + "__%.4s__ returned non-%.4s (type " __Pyx_FMT_TYPENAME ")", + type_name, type_name, result_type_name); + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x) { +#if CYTHON_USE_TYPE_SLOTS + PyNumberMethods *m; +#endif + const char *name = NULL; + PyObject *res = NULL; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x) || PyLong_Check(x))) +#else + if (likely(PyLong_Check(x))) +#endif + return __Pyx_NewRef(x); +#if CYTHON_USE_TYPE_SLOTS + m = Py_TYPE(x)->tp_as_number; + #if PY_MAJOR_VERSION < 3 + if (m && m->nb_int) { + name = "int"; + res = m->nb_int(x); + } + else if (m && m->nb_long) { + name = "long"; + res = m->nb_long(x); + } + #else + if (likely(m && m->nb_int)) { + name = "int"; + res = m->nb_int(x); + } + #endif +#else + if (!PyBytes_CheckExact(x) && !PyUnicode_CheckExact(x)) { + res = PyNumber_Int(x); + } +#endif + if (likely(res)) { +#if PY_MAJOR_VERSION < 3 + if (unlikely(!PyInt_Check(res) && !PyLong_Check(res))) { +#else + if (unlikely(!PyLong_CheckExact(res))) { +#endif + return __Pyx_PyNumber_IntOrLongWrongResultType(res, name); + } + } + else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_TypeError, + "an integer is required"); + } + return res; +} +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject* b) { + Py_ssize_t ival; + PyObject *x; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_CheckExact(b))) { + if (sizeof(Py_ssize_t) >= sizeof(long)) + return PyInt_AS_LONG(b); + else + return PyInt_AsSsize_t(b); + } +#endif + if (likely(PyLong_CheckExact(b))) { + #if CYTHON_USE_PYLONG_INTERNALS + if (likely(__Pyx_PyLong_IsCompact(b))) { + return __Pyx_PyLong_CompactValue(b); + } else { + const digit* digits = __Pyx_PyLong_Digits(b); + const Py_ssize_t size = __Pyx_PyLong_SignedDigitCount(b); + switch (size) { + case 2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return (Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + } + } + #endif + return PyLong_AsSsize_t(b); + } + x = PyNumber_Index(b); + if (!x) return -1; + ival = PyInt_AsSsize_t(x); + Py_DECREF(x); + return ival; +} +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject* o) { + if (sizeof(Py_hash_t) == sizeof(Py_ssize_t)) { + return (Py_hash_t) __Pyx_PyIndex_AsSsize_t(o); +#if PY_MAJOR_VERSION < 3 + } else if (likely(PyInt_CheckExact(o))) { + return PyInt_AS_LONG(o); +#endif + } else { + Py_ssize_t ival; + PyObject *x; + x = PyNumber_Index(o); + if (!x) return -1; + ival = PyInt_AsLong(x); + Py_DECREF(x); + return ival; + } +} +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b) { + return b ? __Pyx_NewRef(Py_True) : __Pyx_NewRef(Py_False); +} +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t ival) { + return PyInt_FromSize_t(ival); +} + + +/* #### Code section: utility_code_pragmas_end ### */ +#ifdef _MSC_VER +#pragma warning( pop ) +#endif + + + +/* #### Code section: end ### */ +#endif /* Py_PYTHON_H */ diff --git a/selfdrive/boardd/boardd_api_impl.so b/selfdrive/boardd/boardd_api_impl.so new file mode 100755 index 0000000..deccdfb Binary files /dev/null and b/selfdrive/boardd/boardd_api_impl.so differ diff --git a/selfdrive/boardd/can_list_to_can_capnp.cc b/selfdrive/boardd/can_list_to_can_capnp.cc deleted file mode 100644 index 72ca726..0000000 --- a/selfdrive/boardd/can_list_to_can_capnp.cc +++ /dev/null @@ -1,21 +0,0 @@ -#include "cereal/messaging/messaging.h" -#include "selfdrive/boardd/panda.h" - -void can_list_to_can_capnp_cpp(const std::vector &can_list, std::string &out, bool sendCan, bool valid) { - MessageBuilder msg; - auto event = msg.initEvent(valid); - - auto canData = sendCan ? event.initSendcan(can_list.size()) : event.initCan(can_list.size()); - int j = 0; - for (auto it = can_list.begin(); it != can_list.end(); it++, j++) { - auto c = canData[j]; - c.setAddress(it->address); - c.setBusTime(it->busTime); - c.setDat(kj::arrayPtr((uint8_t*)it->dat.data(), it->dat.size())); - c.setSrc(it->src); - } - const uint64_t msg_size = capnp::computeSerializedSizeInWords(msg) * sizeof(capnp::word); - out.resize(msg_size); - kj::ArrayOutputStream output_stream(kj::ArrayPtr((unsigned char *)out.data(), msg_size)); - capnp::writeMessage(output_stream, msg); -} diff --git a/selfdrive/boardd/main.cc b/selfdrive/boardd/main.cc deleted file mode 100644 index cb17a58..0000000 --- a/selfdrive/boardd/main.cc +++ /dev/null @@ -1,22 +0,0 @@ -#include - -#include "selfdrive/boardd/boardd.h" -#include "common/swaglog.h" -#include "common/util.h" -#include "system/hardware/hw.h" - -int main(int argc, char *argv[]) { - LOGW("starting boardd"); - - if (!Hardware::PC()) { - int err; - err = util::set_realtime_priority(54); - assert(err == 0); - err = util::set_core_affinity({4}); - assert(err == 0); - } - - std::vector serials(argv + 1, argv + argc); - boardd_main_thread(serials); - return 0; -} diff --git a/selfdrive/boardd/panda.cc b/selfdrive/boardd/panda.cc deleted file mode 100644 index e075887..0000000 --- a/selfdrive/boardd/panda.cc +++ /dev/null @@ -1,322 +0,0 @@ -#include "selfdrive/boardd/panda.h" - -#include - -#include -#include -#include - -#include "cereal/messaging/messaging.h" -#include "common/swaglog.h" -#include "common/util.h" - -Panda::Panda(std::string serial, uint32_t bus_offset) : bus_offset(bus_offset) { - // try USB first, then SPI - try { - handle = std::make_unique(serial); - LOGW("connected to %s over USB", serial.c_str()); - } catch (std::exception &e) { -#ifndef __APPLE__ - handle = std::make_unique(serial); - LOGW("connected to %s over SPI", serial.c_str()); -#else - throw e; -#endif - } - - hw_type = get_hw_type(); - has_rtc = (hw_type == cereal::PandaState::PandaType::UNO) || - (hw_type == cereal::PandaState::PandaType::DOS) || - (hw_type == cereal::PandaState::PandaType::TRES); - - can_reset_communications(); - - return; -} - -bool Panda::connected() { - return handle->connected; -} - -bool Panda::comms_healthy() { - return handle->comms_healthy; -} - -std::string Panda::hw_serial() { - return handle->hw_serial; -} - -std::vector Panda::list(bool usb_only) { - std::vector serials = PandaUsbHandle::list(); - -#ifndef __APPLE__ - if (!usb_only) { - for (auto s : PandaSpiHandle::list()) { - if (std::find(serials.begin(), serials.end(), s) == serials.end()) { - serials.push_back(s); - } - } - } -#endif - - return serials; -} - -void Panda::set_safety_model(cereal::CarParams::SafetyModel safety_model, uint16_t safety_param) { - handle->control_write(0xdc, (uint16_t)safety_model, safety_param); -} - -void Panda::set_alternative_experience(uint16_t alternative_experience) { - handle->control_write(0xdf, alternative_experience, 0); -} - -cereal::PandaState::PandaType Panda::get_hw_type() { - unsigned char hw_query[1] = {0}; - - handle->control_read(0xc1, 0, 0, hw_query, 1); - return (cereal::PandaState::PandaType)(hw_query[0]); -} - -void Panda::set_rtc(struct tm sys_time) { - // tm struct has year defined as years since 1900 - handle->control_write(0xa1, (uint16_t)(1900 + sys_time.tm_year), 0); - handle->control_write(0xa2, (uint16_t)(1 + sys_time.tm_mon), 0); - handle->control_write(0xa3, (uint16_t)sys_time.tm_mday, 0); - // handle->control_write(0xa4, (uint16_t)(1 + sys_time.tm_wday), 0); - handle->control_write(0xa5, (uint16_t)sys_time.tm_hour, 0); - handle->control_write(0xa6, (uint16_t)sys_time.tm_min, 0); - handle->control_write(0xa7, (uint16_t)sys_time.tm_sec, 0); -} - -struct tm Panda::get_rtc() { - struct __attribute__((packed)) timestamp_t { - uint16_t year; // Starts at 0 - uint8_t month; - uint8_t day; - uint8_t weekday; - uint8_t hour; - uint8_t minute; - uint8_t second; - } rtc_time = {0}; - - handle->control_read(0xa0, 0, 0, (unsigned char*)&rtc_time, sizeof(rtc_time)); - - struct tm new_time = { 0 }; - new_time.tm_year = rtc_time.year - 1900; // tm struct has year defined as years since 1900 - new_time.tm_mon = rtc_time.month - 1; - new_time.tm_mday = rtc_time.day; - new_time.tm_hour = rtc_time.hour; - new_time.tm_min = rtc_time.minute; - new_time.tm_sec = rtc_time.second; - - return new_time; -} - -void Panda::set_fan_speed(uint16_t fan_speed) { - handle->control_write(0xb1, fan_speed, 0); -} - -uint16_t Panda::get_fan_speed() { - uint16_t fan_speed_rpm = 0; - handle->control_read(0xb2, 0, 0, (unsigned char*)&fan_speed_rpm, sizeof(fan_speed_rpm)); - return fan_speed_rpm; -} - -void Panda::set_ir_pwr(uint16_t ir_pwr) { - handle->control_write(0xb0, ir_pwr, 0); -} - -std::optional Panda::get_state() { - health_t health {0}; - int err = handle->control_read(0xd2, 0, 0, (unsigned char*)&health, sizeof(health)); - return err >= 0 ? std::make_optional(health) : std::nullopt; -} - -std::optional Panda::get_can_state(uint16_t can_number) { - can_health_t can_health {0}; - int err = handle->control_read(0xc2, can_number, 0, (unsigned char*)&can_health, sizeof(can_health)); - return err >= 0 ? std::make_optional(can_health) : std::nullopt; -} - -void Panda::set_loopback(bool loopback) { - handle->control_write(0xe5, loopback, 0); -} - -std::optional> Panda::get_firmware_version() { - std::vector fw_sig_buf(128); - int read_1 = handle->control_read(0xd3, 0, 0, &fw_sig_buf[0], 64); - int read_2 = handle->control_read(0xd4, 0, 0, &fw_sig_buf[64], 64); - return ((read_1 == 64) && (read_2 == 64)) ? std::make_optional(fw_sig_buf) : std::nullopt; -} - -std::optional Panda::get_serial() { - char serial_buf[17] = {'\0'}; - int err = handle->control_read(0xd0, 0, 0, (uint8_t*)serial_buf, 16); - return err >= 0 ? std::make_optional(serial_buf) : std::nullopt; -} - -bool Panda::up_to_date() { - if (auto fw_sig = get_firmware_version()) { - for (auto fn : { "panda.bin.signed", "panda_h7.bin.signed" }) { - auto content = util::read_file(std::string("../../panda/board/obj/") + fn); - if (content.size() >= fw_sig->size() && - memcmp(content.data() + content.size() - fw_sig->size(), fw_sig->data(), fw_sig->size()) == 0) { - return true; - } - } - } - return false; -} - -void Panda::set_power_saving(bool power_saving) { - handle->control_write(0xe7, power_saving, 0); -} - -void Panda::enable_deepsleep() { - handle->control_write(0xfb, 0, 0); -} - -void Panda::send_heartbeat(bool engaged) { - handle->control_write(0xf3, engaged, 0); -} - -void Panda::set_can_speed_kbps(uint16_t bus, uint16_t speed) { - handle->control_write(0xde, bus, (speed * 10)); -} - -void Panda::set_data_speed_kbps(uint16_t bus, uint16_t speed) { - handle->control_write(0xf9, bus, (speed * 10)); -} - -void Panda::set_canfd_non_iso(uint16_t bus, bool non_iso) { - handle->control_write(0xfc, bus, non_iso); -} - -static uint8_t len_to_dlc(uint8_t len) { - if (len <= 8) { - return len; - } - if (len <= 24) { - return 8 + ((len - 8) / 4) + ((len % 4) ? 1 : 0); - } else { - return 11 + (len / 16) + ((len % 16) ? 1 : 0); - } -} - -void Panda::pack_can_buffer(const capnp::List::Reader &can_data_list, - std::function write_func) { - int32_t pos = 0; - uint8_t send_buf[2 * USB_TX_SOFT_LIMIT]; - - for (auto cmsg : can_data_list) { - // check if the message is intended for this panda - uint8_t bus = cmsg.getSrc(); - if (bus < bus_offset || bus >= (bus_offset + PANDA_BUS_CNT)) { - continue; - } - auto can_data = cmsg.getDat(); - uint8_t data_len_code = len_to_dlc(can_data.size()); - assert(can_data.size() <= 64); - assert(can_data.size() == dlc_to_len[data_len_code]); - - can_header header = {}; - header.addr = cmsg.getAddress(); - header.extended = (cmsg.getAddress() >= 0x800) ? 1 : 0; - header.data_len_code = data_len_code; - header.bus = bus - bus_offset; - header.checksum = 0; - - memcpy(&send_buf[pos], (uint8_t *)&header, sizeof(can_header)); - memcpy(&send_buf[pos + sizeof(can_header)], (uint8_t *)can_data.begin(), can_data.size()); - uint32_t msg_size = sizeof(can_header) + can_data.size(); - - // set checksum - ((can_header *) &send_buf[pos])->checksum = calculate_checksum(&send_buf[pos], msg_size); - - pos += msg_size; - - if (pos >= USB_TX_SOFT_LIMIT) { - write_func(send_buf, pos); - pos = 0; - } - } - - // send remaining packets - if (pos > 0) write_func(send_buf, pos); -} - -void Panda::can_send(capnp::List::Reader can_data_list) { - pack_can_buffer(can_data_list, [=](uint8_t* data, size_t size) { - handle->bulk_write(3, data, size, 5); - }); -} - -bool Panda::can_receive(std::vector& out_vec) { - // Check if enough space left in buffer to store RECV_SIZE data - assert(receive_buffer_size + RECV_SIZE <= sizeof(receive_buffer)); - - int recv = handle->bulk_read(0x81, &receive_buffer[receive_buffer_size], RECV_SIZE); - if (!comms_healthy()) { - return false; - } - if (recv == RECV_SIZE) { - LOGW("Panda receive buffer full"); - } - receive_buffer_size += recv; - - return (recv <= 0) ? true : unpack_can_buffer(receive_buffer, receive_buffer_size, out_vec); -} - -void Panda::can_reset_communications() { - handle->control_write(0xc0, 0, 0); -} - -bool Panda::unpack_can_buffer(uint8_t *data, uint32_t &size, std::vector &out_vec) { - int pos = 0; - - while (pos <= size - sizeof(can_header)) { - can_header header; - memcpy(&header, &data[pos], sizeof(can_header)); - - const uint8_t data_len = dlc_to_len[header.data_len_code]; - if (pos + sizeof(can_header) + data_len > size) { - // we don't have all the data for this message yet - break; - } - - can_frame &canData = out_vec.emplace_back(); - canData.busTime = 0; - canData.address = header.addr; - canData.src = header.bus + bus_offset; - if (header.rejected) { - canData.src += CAN_REJECTED_BUS_OFFSET; - } - if (header.returned) { - canData.src += CAN_RETURNED_BUS_OFFSET; - } - - if (calculate_checksum(&data[pos], sizeof(can_header) + data_len) != 0) { - LOGE("Panda CAN checksum failed"); - size = 0; - return false; - } - - canData.dat.assign((char *)&data[pos + sizeof(can_header)], data_len); - - pos += sizeof(can_header) + data_len; - } - - // move the overflowing data to the beginning of the buffer for the next round - memmove(data, &data[pos], size - pos); - size -= pos; - - return true; -} - -uint8_t Panda::calculate_checksum(uint8_t *data, uint32_t len) { - uint8_t checksum = 0U; - for (uint32_t i = 0U; i < len; i++) { - checksum ^= data[i]; - } - return checksum; -} diff --git a/selfdrive/boardd/panda.h b/selfdrive/boardd/panda.h deleted file mode 100644 index 9d4b1b2..0000000 --- a/selfdrive/boardd/panda.h +++ /dev/null @@ -1,98 +0,0 @@ -#pragma once - -#include -#include -#include -#include -#include -#include -#include -#include - -#include "cereal/gen/cpp/car.capnp.h" -#include "cereal/gen/cpp/log.capnp.h" -#include "panda/board/health.h" -#include "panda/board/can_definitions.h" -#include "selfdrive/boardd/panda_comms.h" - -#define USB_TX_SOFT_LIMIT (0x100U) -#define USBPACKET_MAX_SIZE (0x40) - -#define RECV_SIZE (0x4000U) - -#define CAN_REJECTED_BUS_OFFSET 0xC0U -#define CAN_RETURNED_BUS_OFFSET 0x80U - -struct __attribute__((packed)) can_header { - uint8_t reserved : 1; - uint8_t bus : 3; - uint8_t data_len_code : 4; - uint8_t rejected : 1; - uint8_t returned : 1; - uint8_t extended : 1; - uint32_t addr : 29; - uint8_t checksum : 8; -}; - -struct can_frame { - long address; - std::string dat; - long busTime; - long src; -}; - - -class Panda { -private: - std::unique_ptr handle; - -public: - Panda(std::string serial="", uint32_t bus_offset=0); - - cereal::PandaState::PandaType hw_type = cereal::PandaState::PandaType::UNKNOWN; - bool has_rtc = false; - const uint32_t bus_offset; - - bool connected(); - bool comms_healthy(); - std::string hw_serial(); - - // Static functions - static std::vector list(bool usb_only=false); - - // Panda functionality - cereal::PandaState::PandaType get_hw_type(); - void set_safety_model(cereal::CarParams::SafetyModel safety_model, uint16_t safety_param=0U); - void set_alternative_experience(uint16_t alternative_experience); - void set_rtc(struct tm sys_time); - struct tm get_rtc(); - void set_fan_speed(uint16_t fan_speed); - uint16_t get_fan_speed(); - void set_ir_pwr(uint16_t ir_pwr); - std::optional get_state(); - std::optional get_can_state(uint16_t can_number); - void set_loopback(bool loopback); - std::optional> get_firmware_version(); - bool up_to_date(); - std::optional get_serial(); - void set_power_saving(bool power_saving); - void enable_deepsleep(); - void send_heartbeat(bool engaged); - void set_can_speed_kbps(uint16_t bus, uint16_t speed); - void set_data_speed_kbps(uint16_t bus, uint16_t speed); - void set_canfd_non_iso(uint16_t bus, bool non_iso); - void can_send(capnp::List::Reader can_data_list); - bool can_receive(std::vector& out_vec); - void can_reset_communications(); - -protected: - // for unit tests - uint8_t receive_buffer[RECV_SIZE + sizeof(can_header) + 64]; - uint32_t receive_buffer_size = 0; - - Panda(uint32_t bus_offset) : bus_offset(bus_offset) {} - void pack_can_buffer(const capnp::List::Reader &can_data_list, - std::function write_func); - bool unpack_can_buffer(uint8_t *data, uint32_t &size, std::vector &out_vec); - uint8_t calculate_checksum(uint8_t *data, uint32_t len); -}; diff --git a/selfdrive/boardd/panda_comms.cc b/selfdrive/boardd/panda_comms.cc deleted file mode 100644 index e2c78ab..0000000 --- a/selfdrive/boardd/panda_comms.cc +++ /dev/null @@ -1,227 +0,0 @@ -#include "selfdrive/boardd/panda.h" - -#include -#include -#include - -#include "common/swaglog.h" - -static libusb_context *init_usb_ctx() { - libusb_context *context = nullptr; - int err = libusb_init(&context); - if (err != 0) { - LOGE("libusb initialization error"); - return nullptr; - } - -#if LIBUSB_API_VERSION >= 0x01000106 - libusb_set_option(context, LIBUSB_OPTION_LOG_LEVEL, LIBUSB_LOG_LEVEL_INFO); -#else - libusb_set_debug(context, 3); -#endif - return context; -} - -PandaUsbHandle::PandaUsbHandle(std::string serial) : PandaCommsHandle(serial) { - // init libusb - ssize_t num_devices; - libusb_device **dev_list = NULL; - int err = 0; - ctx = init_usb_ctx(); - if (!ctx) { goto fail; } - - // connect by serial - num_devices = libusb_get_device_list(ctx, &dev_list); - if (num_devices < 0) { goto fail; } - for (size_t i = 0; i < num_devices; ++i) { - libusb_device_descriptor desc; - libusb_get_device_descriptor(dev_list[i], &desc); - if (desc.idVendor == 0xbbaa && desc.idProduct == 0xddcc) { - int ret = libusb_open(dev_list[i], &dev_handle); - if (dev_handle == NULL || ret < 0) { goto fail; } - - unsigned char desc_serial[26] = { 0 }; - ret = libusb_get_string_descriptor_ascii(dev_handle, desc.iSerialNumber, desc_serial, std::size(desc_serial)); - if (ret < 0) { goto fail; } - - hw_serial = std::string((char *)desc_serial, ret); - if (serial.empty() || serial == hw_serial) { - break; - } - libusb_close(dev_handle); - dev_handle = NULL; - } - } - if (dev_handle == NULL) goto fail; - libusb_free_device_list(dev_list, 1); - dev_list = nullptr; - - if (libusb_kernel_driver_active(dev_handle, 0) == 1) { - libusb_detach_kernel_driver(dev_handle, 0); - } - - err = libusb_set_configuration(dev_handle, 1); - if (err != 0) { goto fail; } - - err = libusb_claim_interface(dev_handle, 0); - if (err != 0) { goto fail; } - - return; - -fail: - if (dev_list != NULL) { - libusb_free_device_list(dev_list, 1); - } - cleanup(); - throw std::runtime_error("Error connecting to panda"); -} - -PandaUsbHandle::~PandaUsbHandle() { - std::lock_guard lk(hw_lock); - cleanup(); - connected = false; -} - -void PandaUsbHandle::cleanup() { - if (dev_handle) { - libusb_release_interface(dev_handle, 0); - libusb_close(dev_handle); - } - - if (ctx) { - libusb_exit(ctx); - } -} - -std::vector PandaUsbHandle::list() { - static std::unique_ptr context(init_usb_ctx(), libusb_exit); - // init libusb - ssize_t num_devices; - libusb_device **dev_list = NULL; - std::vector serials; - if (!context) { return serials; } - - num_devices = libusb_get_device_list(context.get(), &dev_list); - if (num_devices < 0) { - LOGE("libusb can't get device list"); - goto finish; - } - for (size_t i = 0; i < num_devices; ++i) { - libusb_device *device = dev_list[i]; - libusb_device_descriptor desc; - libusb_get_device_descriptor(device, &desc); - if (desc.idVendor == 0xbbaa && desc.idProduct == 0xddcc) { - libusb_device_handle *handle = NULL; - int ret = libusb_open(device, &handle); - if (ret < 0) { goto finish; } - - unsigned char desc_serial[26] = { 0 }; - ret = libusb_get_string_descriptor_ascii(handle, desc.iSerialNumber, desc_serial, std::size(desc_serial)); - libusb_close(handle); - if (ret < 0) { goto finish; } - - serials.push_back(std::string((char *)desc_serial, ret).c_str()); - } - } - -finish: - if (dev_list != NULL) { - libusb_free_device_list(dev_list, 1); - } - return serials; -} - -void PandaUsbHandle::handle_usb_issue(int err, const char func[]) { - LOGE_100("usb error %d \"%s\" in %s", err, libusb_strerror((enum libusb_error)err), func); - if (err == LIBUSB_ERROR_NO_DEVICE) { - LOGE("lost connection"); - connected = false; - } - // TODO: check other errors, is simply retrying okay? -} - -int PandaUsbHandle::control_write(uint8_t bRequest, uint16_t wValue, uint16_t wIndex, unsigned int timeout) { - int err; - const uint8_t bmRequestType = LIBUSB_ENDPOINT_OUT | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_RECIPIENT_DEVICE; - - if (!connected) { - return LIBUSB_ERROR_NO_DEVICE; - } - - std::lock_guard lk(hw_lock); - do { - err = libusb_control_transfer(dev_handle, bmRequestType, bRequest, wValue, wIndex, NULL, 0, timeout); - if (err < 0) handle_usb_issue(err, __func__); - } while (err < 0 && connected); - - return err; -} - -int PandaUsbHandle::control_read(uint8_t bRequest, uint16_t wValue, uint16_t wIndex, unsigned char *data, uint16_t wLength, unsigned int timeout) { - int err; - const uint8_t bmRequestType = LIBUSB_ENDPOINT_IN | LIBUSB_REQUEST_TYPE_VENDOR | LIBUSB_RECIPIENT_DEVICE; - - if (!connected) { - return LIBUSB_ERROR_NO_DEVICE; - } - - std::lock_guard lk(hw_lock); - do { - err = libusb_control_transfer(dev_handle, bmRequestType, bRequest, wValue, wIndex, data, wLength, timeout); - if (err < 0) handle_usb_issue(err, __func__); - } while (err < 0 && connected); - - return err; -} - -int PandaUsbHandle::bulk_write(unsigned char endpoint, unsigned char* data, int length, unsigned int timeout) { - int err; - int transferred = 0; - - if (!connected) { - return 0; - } - - std::lock_guard lk(hw_lock); - do { - // Try sending can messages. If the receive buffer on the panda is full it will NAK - // and libusb will try again. After 5ms, it will time out. We will drop the messages. - err = libusb_bulk_transfer(dev_handle, endpoint, data, length, &transferred, timeout); - - if (err == LIBUSB_ERROR_TIMEOUT) { - LOGW("Transmit buffer full"); - break; - } else if (err != 0 || length != transferred) { - handle_usb_issue(err, __func__); - } - } while (err != 0 && connected); - - return transferred; -} - -int PandaUsbHandle::bulk_read(unsigned char endpoint, unsigned char* data, int length, unsigned int timeout) { - int err; - int transferred = 0; - - if (!connected) { - return 0; - } - - std::lock_guard lk(hw_lock); - - do { - err = libusb_bulk_transfer(dev_handle, endpoint, data, length, &transferred, timeout); - - if (err == LIBUSB_ERROR_TIMEOUT) { - break; // timeout is okay to exit, recv still happened - } else if (err == LIBUSB_ERROR_OVERFLOW) { - comms_healthy = false; - LOGE_100("overflow got 0x%x", transferred); - } else if (err != 0) { - handle_usb_issue(err, __func__); - } - - } while (err != 0 && connected); - - return transferred; -} diff --git a/selfdrive/boardd/panda_comms.h b/selfdrive/boardd/panda_comms.h deleted file mode 100644 index e61d254..0000000 --- a/selfdrive/boardd/panda_comms.h +++ /dev/null @@ -1,82 +0,0 @@ -#pragma once - -#include -#include -#include -#include -#include - -#ifndef __APPLE__ -#include -#endif - -#include - - -#define TIMEOUT 0 -#define SPI_BUF_SIZE 2048 - - -// comms base class -class PandaCommsHandle { -public: - PandaCommsHandle(std::string serial) {} - virtual ~PandaCommsHandle() {} - virtual void cleanup() = 0; - - std::string hw_serial; - std::atomic connected = true; - std::atomic comms_healthy = true; - static std::vector list(); - - // HW communication - virtual int control_write(uint8_t request, uint16_t param1, uint16_t param2, unsigned int timeout=TIMEOUT) = 0; - virtual int control_read(uint8_t request, uint16_t param1, uint16_t param2, unsigned char *data, uint16_t length, unsigned int timeout=TIMEOUT) = 0; - virtual int bulk_write(unsigned char endpoint, unsigned char* data, int length, unsigned int timeout=TIMEOUT) = 0; - virtual int bulk_read(unsigned char endpoint, unsigned char* data, int length, unsigned int timeout=TIMEOUT) = 0; -}; - -class PandaUsbHandle : public PandaCommsHandle { -public: - PandaUsbHandle(std::string serial); - ~PandaUsbHandle(); - int control_write(uint8_t request, uint16_t param1, uint16_t param2, unsigned int timeout=TIMEOUT); - int control_read(uint8_t request, uint16_t param1, uint16_t param2, unsigned char *data, uint16_t length, unsigned int timeout=TIMEOUT); - int bulk_write(unsigned char endpoint, unsigned char* data, int length, unsigned int timeout=TIMEOUT); - int bulk_read(unsigned char endpoint, unsigned char* data, int length, unsigned int timeout=TIMEOUT); - void cleanup(); - - static std::vector list(); - -private: - libusb_context *ctx = NULL; - libusb_device_handle *dev_handle = NULL; - std::recursive_mutex hw_lock; - void handle_usb_issue(int err, const char func[]); -}; - -#ifndef __APPLE__ -class PandaSpiHandle : public PandaCommsHandle { -public: - PandaSpiHandle(std::string serial); - ~PandaSpiHandle(); - int control_write(uint8_t request, uint16_t param1, uint16_t param2, unsigned int timeout=TIMEOUT); - int control_read(uint8_t request, uint16_t param1, uint16_t param2, unsigned char *data, uint16_t length, unsigned int timeout=TIMEOUT); - int bulk_write(unsigned char endpoint, unsigned char* data, int length, unsigned int timeout=TIMEOUT); - int bulk_read(unsigned char endpoint, unsigned char* data, int length, unsigned int timeout=TIMEOUT); - void cleanup(); - - static std::vector list(); - -private: - int spi_fd = -1; - uint8_t tx_buf[SPI_BUF_SIZE]; - uint8_t rx_buf[SPI_BUF_SIZE]; - inline static std::recursive_mutex hw_lock; - - int wait_for_ack(uint8_t ack, uint8_t tx, unsigned int timeout, unsigned int length); - int bulk_transfer(uint8_t endpoint, uint8_t *tx_data, uint16_t tx_len, uint8_t *rx_data, uint16_t rx_len, unsigned int timeout); - int spi_transfer(uint8_t endpoint, uint8_t *tx_data, uint16_t tx_len, uint8_t *rx_data, uint16_t max_rx_len, unsigned int timeout); - int spi_transfer_retry(uint8_t endpoint, uint8_t *tx_data, uint16_t tx_len, uint8_t *rx_data, uint16_t max_rx_len, unsigned int timeout); -}; -#endif diff --git a/selfdrive/boardd/spi.cc b/selfdrive/boardd/spi.cc deleted file mode 100644 index d11e955..0000000 --- a/selfdrive/boardd/spi.cc +++ /dev/null @@ -1,377 +0,0 @@ -#ifndef __APPLE__ -#include -#include -#include - -#include -#include -#include -#include -#include - -#include "common/util.h" -#include "common/timing.h" -#include "common/swaglog.h" -#include "panda/board/comms_definitions.h" -#include "selfdrive/boardd/panda_comms.h" - - -#define SPI_SYNC 0x5AU -#define SPI_HACK 0x79U -#define SPI_DACK 0x85U -#define SPI_NACK 0x1FU -#define SPI_CHECKSUM_START 0xABU - - -enum SpiError { - NACK = -2, - ACK_TIMEOUT = -3, -}; - -struct __attribute__((packed)) spi_header { - uint8_t sync; - uint8_t endpoint; - uint16_t tx_len; - uint16_t max_rx_len; -}; - -const unsigned int SPI_ACK_TIMEOUT = 500; // milliseconds -const std::string SPI_DEVICE = "/dev/spidev0.0"; - -class LockEx { -public: - LockEx(int fd, std::recursive_mutex &m) : fd(fd), m(m) { - m.lock(); - flock(fd, LOCK_EX); - } - - ~LockEx() { - flock(fd, LOCK_UN); - m.unlock(); - } - -private: - int fd; - std::recursive_mutex &m; -}; - - -PandaSpiHandle::PandaSpiHandle(std::string serial) : PandaCommsHandle(serial) { - int ret; - const int uid_len = 12; - uint8_t uid[uid_len] = {0}; - - uint32_t spi_mode = SPI_MODE_0; - uint8_t spi_bits_per_word = 8; - - // 50MHz is the max of the 845. note that some older - // revs of the comma three may not support this speed - uint32_t spi_speed = 50000000; - - if (!util::file_exists(SPI_DEVICE)) { - goto fail; - } - - spi_fd = open(SPI_DEVICE.c_str(), O_RDWR); - if (spi_fd < 0) { - LOGE("failed opening SPI device %d", spi_fd); - goto fail; - } - - // SPI settings - ret = util::safe_ioctl(spi_fd, SPI_IOC_WR_MODE, &spi_mode); - if (ret < 0) { - LOGE("failed setting SPI mode %d", ret); - goto fail; - } - - ret = util::safe_ioctl(spi_fd, SPI_IOC_WR_MAX_SPEED_HZ, &spi_speed); - if (ret < 0) { - LOGE("failed setting SPI speed"); - goto fail; - } - - ret = util::safe_ioctl(spi_fd, SPI_IOC_WR_BITS_PER_WORD, &spi_bits_per_word); - if (ret < 0) { - LOGE("failed setting SPI bits per word"); - goto fail; - } - - // get hw UID/serial - ret = control_read(0xc3, 0, 0, uid, uid_len, 100); - if (ret == uid_len) { - std::stringstream stream; - for (int i = 0; i < uid_len; i++) { - stream << std::hex << std::setw(2) << std::setfill('0') << int(uid[i]); - } - hw_serial = stream.str(); - } else { - LOGD("failed to get serial %d", ret); - goto fail; - } - - if (!serial.empty() && (serial != hw_serial)) { - goto fail; - } - - return; - -fail: - cleanup(); - throw std::runtime_error("Error connecting to panda"); -} - -PandaSpiHandle::~PandaSpiHandle() { - std::lock_guard lk(hw_lock); - cleanup(); -} - -void PandaSpiHandle::cleanup() { - if (spi_fd != -1) { - close(spi_fd); - spi_fd = -1; - } -} - - - -int PandaSpiHandle::control_write(uint8_t request, uint16_t param1, uint16_t param2, unsigned int timeout) { - ControlPacket_t packet = { - .request = request, - .param1 = param1, - .param2 = param2, - .length = 0 - }; - return spi_transfer_retry(0, (uint8_t *) &packet, sizeof(packet), NULL, 0, timeout); -} - -int PandaSpiHandle::control_read(uint8_t request, uint16_t param1, uint16_t param2, unsigned char *data, uint16_t length, unsigned int timeout) { - ControlPacket_t packet = { - .request = request, - .param1 = param1, - .param2 = param2, - .length = length - }; - return spi_transfer_retry(0, (uint8_t *) &packet, sizeof(packet), data, length, timeout); -} - -int PandaSpiHandle::bulk_write(unsigned char endpoint, unsigned char* data, int length, unsigned int timeout) { - return bulk_transfer(endpoint, data, length, NULL, 0, timeout); -} -int PandaSpiHandle::bulk_read(unsigned char endpoint, unsigned char* data, int length, unsigned int timeout) { - return bulk_transfer(endpoint, NULL, 0, data, length, timeout); -} - -int PandaSpiHandle::bulk_transfer(uint8_t endpoint, uint8_t *tx_data, uint16_t tx_len, uint8_t *rx_data, uint16_t rx_len, unsigned int timeout) { - const int xfer_size = SPI_BUF_SIZE - 0x40; - - int ret = 0; - uint16_t length = (tx_data != NULL) ? tx_len : rx_len; - for (int i = 0; i < (int)std::ceil((float)length / xfer_size); i++) { - int d; - if (tx_data != NULL) { - int len = std::min(xfer_size, tx_len - (xfer_size * i)); - d = spi_transfer_retry(endpoint, tx_data + (xfer_size * i), len, NULL, 0, timeout); - } else { - uint16_t to_read = std::min(xfer_size, rx_len - ret); - d = spi_transfer_retry(endpoint, NULL, 0, rx_data + (xfer_size * i), to_read, timeout); - } - - if (d < 0) { - LOGE("SPI: bulk transfer failed with %d", d); - comms_healthy = false; - return d; - } - - ret += d; - if ((rx_data != NULL) && d < xfer_size) { - break; - } - } - - return ret; -} - -std::vector PandaSpiHandle::list() { - try { - PandaSpiHandle sh(""); - return {sh.hw_serial}; - } catch (std::exception &e) { - // no panda on SPI - } - return {}; -} - -void add_checksum(uint8_t *data, int data_len) { - data[data_len] = SPI_CHECKSUM_START; - for (int i=0; i < data_len; i++) { - data[data_len] ^= data[i]; - } -} - -bool check_checksum(uint8_t *data, int data_len) { - uint8_t checksum = SPI_CHECKSUM_START; - for (uint16_t i = 0U; i < data_len; i++) { - checksum ^= data[i]; - } - return checksum == 0U; -} - - -int PandaSpiHandle::spi_transfer_retry(uint8_t endpoint, uint8_t *tx_data, uint16_t tx_len, uint8_t *rx_data, uint16_t max_rx_len, unsigned int timeout) { - int ret; - int nack_count = 0; - int timeout_count = 0; - bool timed_out = false; - double start_time = millis_since_boot(); - - do { - ret = spi_transfer(endpoint, tx_data, tx_len, rx_data, max_rx_len, timeout); - - if (ret < 0) { - timed_out = (timeout != 0) && (timeout_count > 5); - timeout_count += ret == SpiError::ACK_TIMEOUT; - - // give other threads a chance to run - std::this_thread::yield(); - - if (ret == SpiError::NACK) { - // prevent busy waiting while the panda is NACK'ing - // due to full TX buffers - nack_count += 1; - if (nack_count > 3) { - usleep(std::clamp(nack_count*10, 200, 2000)); - } - } - } - } while (ret < 0 && connected && !timed_out); - - if (ret < 0) { - LOGE("transfer failed, after %d tries, %.2fms", timeout_count, millis_since_boot() - start_time); - } - - return ret; -} - -int PandaSpiHandle::wait_for_ack(uint8_t ack, uint8_t tx, unsigned int timeout, unsigned int length) { - double start_millis = millis_since_boot(); - if (timeout == 0) { - timeout = SPI_ACK_TIMEOUT; - } - timeout = std::clamp(timeout, 100U, SPI_ACK_TIMEOUT); - - spi_ioc_transfer transfer = { - .tx_buf = (uint64_t)tx_buf, - .rx_buf = (uint64_t)rx_buf, - .len = length - }; - tx_buf[0] = tx; - - while (true) { - int ret = util::safe_ioctl(spi_fd, SPI_IOC_MESSAGE(1), &transfer); - if (ret < 0) { - LOGE("SPI: failed to send ACK request"); - return ret; - } - - if (rx_buf[0] == ack) { - break; - } else if (rx_buf[0] == SPI_NACK) { - LOGD("SPI: got NACK"); - return SpiError::NACK; - } - - // handle timeout - if (millis_since_boot() - start_millis > timeout) { - LOGD("SPI: timed out waiting for ACK"); - return SpiError::ACK_TIMEOUT; - } - } - - return 0; -} - -int PandaSpiHandle::spi_transfer(uint8_t endpoint, uint8_t *tx_data, uint16_t tx_len, uint8_t *rx_data, uint16_t max_rx_len, unsigned int timeout) { - int ret; - uint16_t rx_data_len; - LockEx lock(spi_fd, hw_lock); - - // needs to be less, since we need to have space for the checksum - assert(tx_len < SPI_BUF_SIZE); - assert(max_rx_len < SPI_BUF_SIZE); - - spi_header header = { - .sync = SPI_SYNC, - .endpoint = endpoint, - .tx_len = tx_len, - .max_rx_len = max_rx_len - }; - - spi_ioc_transfer transfer = { - .tx_buf = (uint64_t)tx_buf, - .rx_buf = (uint64_t)rx_buf - }; - - // Send header - memcpy(tx_buf, &header, sizeof(header)); - add_checksum(tx_buf, sizeof(header)); - transfer.len = sizeof(header) + 1; - ret = util::safe_ioctl(spi_fd, SPI_IOC_MESSAGE(1), &transfer); - if (ret < 0) { - LOGE("SPI: failed to send header"); - goto transfer_fail; - } - - // Wait for (N)ACK - ret = wait_for_ack(SPI_HACK, 0x11, timeout, 1); - if (ret < 0) { - goto transfer_fail; - } - - // Send data - if (tx_data != NULL) { - memcpy(tx_buf, tx_data, tx_len); - } - add_checksum(tx_buf, tx_len); - transfer.len = tx_len + 1; - ret = util::safe_ioctl(spi_fd, SPI_IOC_MESSAGE(1), &transfer); - if (ret < 0) { - LOGE("SPI: failed to send data"); - goto transfer_fail; - } - - // Wait for (N)ACK - ret = wait_for_ack(SPI_DACK, 0x13, timeout, 3); - if (ret < 0) { - goto transfer_fail; - } - - // Read data - rx_data_len = *(uint16_t *)(rx_buf+1); - if (rx_data_len >= SPI_BUF_SIZE) { - LOGE("SPI: RX data len larger than buf size %d", rx_data_len); - goto transfer_fail; - } - - transfer.len = rx_data_len + 1; - transfer.rx_buf = (uint64_t)(rx_buf + 2 + 1); - ret = util::safe_ioctl(spi_fd, SPI_IOC_MESSAGE(1), &transfer); - if (ret < 0) { - LOGE("SPI: failed to read rx data"); - goto transfer_fail; - } - if (!check_checksum(rx_buf, rx_data_len + 4)) { - LOGE("SPI: bad checksum"); - goto transfer_fail; - } - - if (rx_data != NULL) { - memcpy(rx_data, rx_buf + 3, rx_data_len); - } - - return rx_data_len; - -transfer_fail: - return ret; -} -#endif diff --git a/selfdrive/car/toyota/carcontroller.py b/selfdrive/car/toyota/carcontroller.py index 4e5665a..18e6e73 100644 --- a/selfdrive/car/toyota/carcontroller.py +++ b/selfdrive/car/toyota/carcontroller.py @@ -136,8 +136,8 @@ class CarController: pedal_offset = interp(CS.out.vEgo, [0.0, 2.3, MIN_ACC_SPEED + PEDAL_TRANSITION], [-.4, 0.0, 0.2]) pedal_command = PEDAL_SCALE * (actuators.accel + pedal_offset) interceptor_gas_cmd = clip(pedal_command, 0., MAX_INTERCEPTOR_GAS) - elif ((CC.longActive and actuators.accel > 0.) or (not self.CP.openpilotLongitudinalControl and CS.stock_resume_ready)) \ - and self.CP.carFingerprint in STOP_AND_GO_CAR and self.CP.enableGasInterceptor and CS.out.vEgo < 1e-3: + elif self.CP.enableGasInterceptor and CC.longActive and self.CP.carFingerprint in STOP_AND_GO_CAR and actuators.accel > 0.0 \ + and CS.out.standstill: interceptor_gas_cmd = 0.12 else: interceptor_gas_cmd = 0. diff --git a/selfdrive/car/toyota/carstate.py b/selfdrive/car/toyota/carstate.py index a1a0904..52cff5f 100644 --- a/selfdrive/car/toyota/carstate.py +++ b/selfdrive/car/toyota/carstate.py @@ -182,19 +182,7 @@ class CarState(CarStateBase): if self.CP.carFingerprint != CAR.PRIUS_V: self.lkas_hud = copy.copy(cp_cam.vl["LKAS_HUD"]) - # if openpilot does not control longitudinal, in this case, assume 0x343 is on bus0 - # 1) the car is no longer sending standstill - # 2) the car is still in standstill - if not self.CP.openpilotLongitudinalControl: - self.stock_resume_ready = cp.vl["ACC_CONTROL"]["RELEASE_STANDSTILL"] == 1 - # FrogPilot functions - if self.CP.carFingerprint in (TSS2_CAR - RADAR_ACC_CAR) or (self.CP.flags & ToyotaFlags.SMART_DSU and not self.CP.flags & ToyotaFlags.RADAR_CAN_FILTER): - # distance button is wired to the ACC module (camera or radar) - if self.CP.carFingerprint in (TSS2_CAR - RADAR_ACC_CAR): - distance_pressed = cp_acc.vl["ACC_CONTROL"]["DISTANCE"] - else: - distance_pressed = cp.vl["SDSU"]["FD_BUTTON"] # Switch the current state of Experimental Mode if the LKAS button is double pressed if frogpilot_variables.experimental_mode_via_lkas and ret.cruiseState.available and self.CP.carFingerprint != CAR.PRIUS_V: @@ -209,6 +197,19 @@ class CarState(CarStateBase): self.lkas_previously_pressed = lkas_pressed + if self.CP.carFingerprint not in UNSUPPORTED_DSU_CAR: + # Need to subtract by 1 to comply with the personality profiles of "0", "1", and "2" + self.personality_profile = cp.vl["PCM_CRUISE_SM"]["DISTANCE_LINES"] - 1 + + if self.CP.carFingerprint in (TSS2_CAR - RADAR_ACC_CAR) or self.CP.flags & ToyotaFlags.SMART_DSU: + # distance button is wired to the ACC module (camera or radar) + if self.CP.carFingerprint in (TSS2_CAR - RADAR_ACC_CAR): + distance_pressed = cp_acc.vl["ACC_CONTROL"]["DISTANCE"] + else: + distance_pressed = cp.vl["SDSU"]["FD_BUTTON"] + else: + distance_pressed = False + # Distance button functions if ret.cruiseState.available: if distance_pressed: @@ -243,9 +244,6 @@ class CarState(CarStateBase): # Update the distance lines on the dash upon ignition/onroad UI button clicked if frogpilot_variables.personalities_via_wheel and ret.cruiseState.available: - # Need to subtract by 1 to comply with the personality profiles of "0", "1", and "2" - self.personality_profile = cp.vl["PCM_CRUISE_SM"]["DISTANCE_LINES"] - 1 - # Sync with the onroad UI button if self.fpf.personality_changed_via_ui: self.profile_restored = False @@ -341,7 +339,7 @@ class CarState(CarStateBase): if CP.enableBsm: messages.append(("BSM", 1)) - if not CP.openpilotLongitudinalControl or (CP.carFingerprint in RADAR_ACC_CAR and not CP.flags & ToyotaFlags.DISABLE_RADAR.value): + if CP.carFingerprint in RADAR_ACC_CAR and not CP.flags & ToyotaFlags.DISABLE_RADAR.value: if not CP.flags & ToyotaFlags.SMART_DSU.value: messages += [ ("ACC_CONTROL", 33), @@ -355,7 +353,7 @@ class CarState(CarStateBase): ("PRE_COLLISION", 33), ] - if CP.flags & ToyotaFlags.SMART_DSU and not CP.flags & ToyotaFlags.RADAR_CAN_FILTER: + if CP.flags & ToyotaFlags.SMART_DSU: messages += [ ("SDSU", 100), ] @@ -385,7 +383,4 @@ class CarState(CarStateBase): ("PCS_HUD", 1), ] - if not CP.openpilotLongitudinalControl and CP.carFingerprint not in (TSS2_CAR, UNSUPPORTED_DSU_CAR): - messages.append(("ACC_CONTROL", 33)) - return CANParser(DBC[CP.carFingerprint]["pt"], messages, 2) diff --git a/selfdrive/car/toyota/values.py b/selfdrive/car/toyota/values.py index 0190aa9..f91dba6 100644 --- a/selfdrive/car/toyota/values.py +++ b/selfdrive/car/toyota/values.py @@ -47,7 +47,6 @@ class ToyotaFlags(IntFlag): SMART_DSU = 2 DISABLE_RADAR = 4 ZSS = 8 - RADAR_CAN_FILTER = 16 class CAR(StrEnum): diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 0324a08..18db54e 100644 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -986,7 +986,7 @@ class Controls: self.params_memory.put_int("CurrentRandomEvent", 1) self.random_event_triggered = True else: - lac_log.active and self.events.add(EventName.frogSteerSaturated if self.goat_scream else EventName.steerSaturated) + lac_log.active and self.events.add(EventName.frogSteerSaturated if self.goat_scream and self.params_memory.get_int("CurrentHolidayTheme") == 0 else EventName.steerSaturated) elif lac_log.saturated: # TODO probably should not use dpath_points but curvature dpath_points = model_v2.position.y diff --git a/selfdrive/controls/lib/lateral_mpc_lib/SConscript b/selfdrive/controls/lib/lateral_mpc_lib/SConscript deleted file mode 100644 index 49666ab..0000000 --- a/selfdrive/controls/lib/lateral_mpc_lib/SConscript +++ /dev/null @@ -1,89 +0,0 @@ -Import('env', 'envCython', 'arch') - -gen = "c_generated_code" - -casadi_model = [ - f'{gen}/lat_model/lat_expl_ode_fun.c', - f'{gen}/lat_model/lat_expl_vde_forw.c', -] - -casadi_cost_y = [ - f'{gen}/lat_cost/lat_cost_y_fun.c', - f'{gen}/lat_cost/lat_cost_y_fun_jac_ut_xt.c', - f'{gen}/lat_cost/lat_cost_y_hess.c', -] - -casadi_cost_e = [ - f'{gen}/lat_cost/lat_cost_y_e_fun.c', - f'{gen}/lat_cost/lat_cost_y_e_fun_jac_ut_xt.c', - f'{gen}/lat_cost/lat_cost_y_e_hess.c', -] - -casadi_cost_0 = [ - f'{gen}/lat_cost/lat_cost_y_0_fun.c', - f'{gen}/lat_cost/lat_cost_y_0_fun_jac_ut_xt.c', - f'{gen}/lat_cost/lat_cost_y_0_hess.c', -] - -build_files = [f'{gen}/acados_solver_lat.c'] + casadi_model + casadi_cost_y + casadi_cost_e + casadi_cost_0 - -# extra generated files used to trigger a rebuild -generated_files = [ - f'{gen}/Makefile', - - f'{gen}/main_lat.c', - f'{gen}/main_sim_lat.c', - f'{gen}/acados_solver_lat.h', - f'{gen}/acados_sim_solver_lat.h', - f'{gen}/acados_sim_solver_lat.c', - f'{gen}/acados_solver.pxd', - - f'{gen}/lat_model/lat_expl_vde_adj.c', - - f'{gen}/lat_model/lat_model.h', - f'{gen}/lat_constraints/lat_constraints.h', - f'{gen}/lat_cost/lat_cost.h', -] + build_files - -acados_dir = '#third_party/acados' -acados_templates_dir = '#third_party/acados/acados_template/c_templates_tera' - -source_list = ['lat_mpc.py', - '#selfdrive/modeld/constants.py', - f'{acados_dir}/include/acados_c/ocp_nlp_interface.h', - f'{acados_templates_dir}/acados_solver.in.c', -] - -lenv = env.Clone() -lenv.Clean(generated_files, Dir(gen)) - -generated_lat = lenv.Command(generated_files, - source_list, - f"cd {Dir('.').abspath} && python3 lat_mpc.py") - -lenv["CFLAGS"].append("-DACADOS_WITH_QPOASES") -lenv["CXXFLAGS"].append("-DACADOS_WITH_QPOASES") -lenv["CCFLAGS"].append("-Wno-unused") -if arch != "Darwin": - lenv["LINKFLAGS"].append("-Wl,--disable-new-dtags") -lib_solver = lenv.SharedLibrary(f"{gen}/acados_ocp_solver_lat", - build_files, - LIBS=['m', 'acados', 'hpipm', 'blasfeo', 'qpOASES_e']) - -# generate cython stuff -acados_ocp_solver_pyx = File("#third_party/acados/acados_template/acados_ocp_solver_pyx.pyx") -acados_ocp_solver_common = File("#third_party/acados/acados_template/acados_solver_common.pxd") -libacados_ocp_solver_pxd = File(f'{gen}/acados_solver.pxd') -libacados_ocp_solver_c = File(f'{gen}/acados_ocp_solver_pyx.c') - -lenv2 = envCython.Clone() -lenv2["LINKFLAGS"] += [lib_solver[0].get_labspath()] -lenv2.Command(libacados_ocp_solver_c, - [acados_ocp_solver_pyx, acados_ocp_solver_common, libacados_ocp_solver_pxd], - f'cython' + \ - f' -o {libacados_ocp_solver_c.get_labspath()}' + \ - f' -I {libacados_ocp_solver_pxd.get_dir().get_labspath()}' + \ - f' -I {acados_ocp_solver_common.get_dir().get_labspath()}' + \ - f' {acados_ocp_solver_pyx.get_labspath()}') -lib_cython = lenv2.Program(f'{gen}/acados_ocp_solver_pyx.so', [libacados_ocp_solver_c]) -lenv2.Depends(lib_cython, lib_solver) diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/Makefile b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/Makefile new file mode 100644 index 0000000..7520bcd --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/Makefile @@ -0,0 +1,211 @@ +# +# Copyright (c) The acados authors. +# +# This file is part of acados. +# +# The 2-Clause BSD License +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are met: +# +# 1. Redistributions of source code must retain the above copyright notice, +# this list of conditions and the following disclaimer. +# +# 2. Redistributions in binary form must reproduce the above copyright notice, +# this list of conditions and the following disclaimer in the documentation +# and/or other materials provided with the distribution. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE +# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE.; +# + + + + + +# define sources and use make's implicit rules to generate object files (*.o) + +# model +MODEL_SRC= +MODEL_SRC+= lat_model/lat_expl_ode_fun.c +MODEL_SRC+= lat_model/lat_expl_vde_forw.c +MODEL_SRC+= lat_model/lat_expl_vde_adj.c +MODEL_OBJ := $(MODEL_SRC:.c=.o) + +# optimal control problem - mostly CasADi exports +OCP_SRC= +OCP_SRC+= lat_cost/lat_cost_y_0_fun.c +OCP_SRC+= lat_cost/lat_cost_y_0_fun_jac_ut_xt.c +OCP_SRC+= lat_cost/lat_cost_y_0_hess.c +OCP_SRC+= lat_cost/lat_cost_y_fun.c +OCP_SRC+= lat_cost/lat_cost_y_fun_jac_ut_xt.c +OCP_SRC+= lat_cost/lat_cost_y_hess.c +OCP_SRC+= lat_cost/lat_cost_y_e_fun.c +OCP_SRC+= lat_cost/lat_cost_y_e_fun_jac_ut_xt.c +OCP_SRC+= lat_cost/lat_cost_y_e_hess.c + +OCP_SRC+= acados_solver_lat.c +OCP_OBJ := $(OCP_SRC:.c=.o) + +# for sim solver +SIM_SRC= acados_sim_solver_lat.c +SIM_OBJ := $(SIM_SRC:.c=.o) + +# for target example +EX_SRC= main_lat.c +EX_OBJ := $(EX_SRC:.c=.o) +EX_EXE := $(EX_SRC:.c=) + +# for target example_sim +EX_SIM_SRC= main_sim_lat.c +EX_SIM_OBJ := $(EX_SIM_SRC:.c=.o) +EX_SIM_EXE := $(EX_SIM_SRC:.c=) + +# combine model, sim and ocp object files +OBJ= +OBJ+= $(MODEL_OBJ) +OBJ+= $(SIM_OBJ) +OBJ+= $(OCP_OBJ) + +EXTERNAL_DIR= +EXTERNAL_LIB= + +INCLUDE_PATH = /data/openpilot/third_party/acados/include +LIB_PATH = /data/openpilot/third_party/acados/lib + +# preprocessor flags for make's implicit rules +CPPFLAGS+= -I$(INCLUDE_PATH) +CPPFLAGS+= -I$(INCLUDE_PATH)/acados +CPPFLAGS+= -I$(INCLUDE_PATH)/blasfeo/include +CPPFLAGS+= -I$(INCLUDE_PATH)/hpipm/include + + +# define the c-compiler flags for make's implicit rules +CFLAGS = -fPIC -std=c99 -O2#-fno-diagnostics-show-line-numbers -g +# # Debugging +# CFLAGS += -g3 + +# linker flags +LDFLAGS+= -L$(LIB_PATH) + +# link to libraries +LDLIBS+= -lacados +LDLIBS+= -lhpipm +LDLIBS+= -lblasfeo +LDLIBS+= -lm +LDLIBS+= + +# libraries +LIBACADOS_SOLVER=libacados_solver_lat.so +LIBACADOS_OCP_SOLVER=libacados_ocp_solver_lat.so +LIBACADOS_SIM_SOLVER=lib$(SIM_SRC:.c=.so) + +# virtual targets +.PHONY : all clean + +#all: clean example_sim example shared_lib + +all: clean example_sim example +shared_lib: bundled_shared_lib ocp_shared_lib sim_shared_lib + +# some linker targets +example: $(EX_OBJ) $(OBJ) + $(CC) $^ -o $(EX_EXE) $(LDFLAGS) $(LDLIBS) + +example_sim: $(EX_SIM_OBJ) $(MODEL_OBJ) $(SIM_OBJ) + $(CC) $^ -o $(EX_SIM_EXE) $(LDFLAGS) $(LDLIBS) + +bundled_shared_lib: $(OBJ) + $(CC) -shared $^ -o $(LIBACADOS_SOLVER) $(LDFLAGS) $(LDLIBS) + +ocp_shared_lib: $(OCP_OBJ) $(MODEL_OBJ) + $(CC) -shared $^ -o $(LIBACADOS_OCP_SOLVER) $(LDFLAGS) $(LDLIBS) \ + -L$(EXTERNAL_DIR) -l$(EXTERNAL_LIB) + +sim_shared_lib: $(SIM_OBJ) $(MODEL_OBJ) + $(CC) -shared $^ -o $(LIBACADOS_SIM_SOLVER) $(LDFLAGS) $(LDLIBS) + + +# Cython targets +ocp_cython_c: ocp_shared_lib + cython \ + -o acados_ocp_solver_pyx.c \ + -I $(INCLUDE_PATH)/../interfaces/acados_template/acados_template \ + $(INCLUDE_PATH)/../interfaces/acados_template/acados_template/acados_ocp_solver_pyx.pyx \ + -I /data/openpilot/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code \ + +ocp_cython_o: ocp_cython_c + $(CC) $(ACADOS_FLAGS) -c -O2 \ + -fPIC \ + -o acados_ocp_solver_pyx.o \ + -I $(INCLUDE_PATH)/blasfeo/include/ \ + -I $(INCLUDE_PATH)/hpipm/include/ \ + -I $(INCLUDE_PATH) \ + -I /usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/core/include \ + -I /usr/local/pyenv/versions/3.11.4/include/python3.11 \ + acados_ocp_solver_pyx.c \ + +ocp_cython: ocp_cython_o + $(CC) $(ACADOS_FLAGS) -shared \ + -o acados_ocp_solver_pyx.so \ + -Wl,-rpath=$(LIB_PATH) \ + acados_ocp_solver_pyx.o \ + $(abspath .)/libacados_ocp_solver_lat.so \ + $(LDFLAGS) $(LDLIBS) + +# Sim Cython targets +sim_cython_c: sim_shared_lib + cython \ + -o acados_sim_solver_pyx.c \ + -I $(INCLUDE_PATH)/../interfaces/acados_template/acados_template \ + $(INCLUDE_PATH)/../interfaces/acados_template/acados_template/acados_sim_solver_pyx.pyx \ + -I /data/openpilot/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code \ + +sim_cython_o: sim_cython_c + $(CC) $(ACADOS_FLAGS) -c -O2 \ + -fPIC \ + -o acados_sim_solver_pyx.o \ + -I $(INCLUDE_PATH)/blasfeo/include/ \ + -I $(INCLUDE_PATH)/hpipm/include/ \ + -I $(INCLUDE_PATH) \ + -I /usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/core/include \ + -I /usr/local/pyenv/versions/3.11.4/include/python3.11 \ + acados_sim_solver_pyx.c \ + +sim_cython: sim_cython_o + $(CC) $(ACADOS_FLAGS) -shared \ + -o acados_sim_solver_pyx.so \ + -Wl,-rpath=$(LIB_PATH) \ + acados_sim_solver_pyx.o \ + $(abspath .)/libacados_sim_solver_lat.so \ + $(LDFLAGS) $(LDLIBS) + +clean: + $(RM) $(OBJ) $(EX_OBJ) $(EX_SIM_OBJ) + $(RM) $(LIBACADOS_SOLVER) $(LIBACADOS_OCP_SOLVER) $(LIBACADOS_SIM_SOLVER) + $(RM) $(EX_EXE) $(EX_SIM_EXE) + +clean_ocp_shared_lib: + $(RM) $(LIBACADOS_OCP_SOLVER) + $(RM) $(OCP_OBJ) + +clean_ocp_cython: + $(RM) libacados_ocp_solver_lat.so + $(RM) acados_solver_lat.o + $(RM) acados_ocp_solver_pyx.so + $(RM) acados_ocp_solver_pyx.o + +clean_sim_cython: + $(RM) libacados_sim_solver_lat.so + $(RM) acados_sim_solver_lat.o + $(RM) acados_sim_solver_pyx.so + $(RM) acados_sim_solver_pyx.o diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_ocp_solver_pyx.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_ocp_solver_pyx.c new file mode 100644 index 0000000..fcbe6f5 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_ocp_solver_pyx.c @@ -0,0 +1,44066 @@ +/* Generated by Cython 3.0.8 */ + +#ifndef PY_SSIZE_T_CLEAN +#define PY_SSIZE_T_CLEAN +#endif /* PY_SSIZE_T_CLEAN */ +#if defined(CYTHON_LIMITED_API) && 0 + #ifndef Py_LIMITED_API + #if CYTHON_LIMITED_API+0 > 0x03030000 + #define Py_LIMITED_API CYTHON_LIMITED_API + #else + #define Py_LIMITED_API 0x03030000 + #endif + #endif +#endif + +#include "Python.h" +#ifndef Py_PYTHON_H + #error Python headers needed to compile C extensions, please install development version of Python. +#elif PY_VERSION_HEX < 0x02070000 || (0x03000000 <= PY_VERSION_HEX && PY_VERSION_HEX < 0x03030000) + #error Cython requires Python 2.7+ or Python 3.3+. +#else +#if defined(CYTHON_LIMITED_API) && CYTHON_LIMITED_API +#define __PYX_EXTRA_ABI_MODULE_NAME "limited" +#else +#define __PYX_EXTRA_ABI_MODULE_NAME "" +#endif +#define CYTHON_ABI "3_0_8" __PYX_EXTRA_ABI_MODULE_NAME +#define __PYX_ABI_MODULE_NAME "_cython_" CYTHON_ABI +#define __PYX_TYPE_MODULE_PREFIX __PYX_ABI_MODULE_NAME "." +#define CYTHON_HEX_VERSION 0x030008F0 +#define CYTHON_FUTURE_DIVISION 1 +#include +#ifndef offsetof + #define offsetof(type, member) ( (size_t) & ((type*)0) -> member ) +#endif +#if !defined(_WIN32) && !defined(WIN32) && !defined(MS_WINDOWS) + #ifndef __stdcall + #define __stdcall + #endif + #ifndef __cdecl + #define __cdecl + #endif + #ifndef __fastcall + #define __fastcall + #endif +#endif +#ifndef DL_IMPORT + #define DL_IMPORT(t) t +#endif +#ifndef DL_EXPORT + #define DL_EXPORT(t) t +#endif +#define __PYX_COMMA , +#ifndef HAVE_LONG_LONG + #define HAVE_LONG_LONG +#endif +#ifndef PY_LONG_LONG + #define PY_LONG_LONG LONG_LONG +#endif +#ifndef Py_HUGE_VAL + #define Py_HUGE_VAL HUGE_VAL +#endif +#define __PYX_LIMITED_VERSION_HEX PY_VERSION_HEX +#if defined(GRAALVM_PYTHON) + /* For very preliminary testing purposes. Most variables are set the same as PyPy. + The existence of this section does not imply that anything works or is even tested */ + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 1 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(PYPY_VERSION) + #define CYTHON_COMPILING_IN_PYPY 1 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #ifndef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #endif + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #if PY_VERSION_HEX < 0x03090000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE (PY_VERSION_HEX >= 0x030400a1 && PYPY_VERSION_NUM >= 0x07030C00) + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(CYTHON_LIMITED_API) + #ifdef Py_LIMITED_API + #undef __PYX_LIMITED_VERSION_HEX + #define __PYX_LIMITED_VERSION_HEX Py_LIMITED_API + #endif + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 1 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_CLINE_IN_TRACEBACK + #define CYTHON_CLINE_IN_TRACEBACK 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 1 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #endif + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 1 + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(Py_GIL_DISABLED) || defined(Py_NOGIL) + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 1 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #ifndef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 +#else + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 1 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #ifndef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #endif + #ifndef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 1 + #endif + #if PY_MAJOR_VERSION < 3 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #ifndef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 1 + #endif + #ifndef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 1 + #endif + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #if PY_VERSION_HEX < 0x030300F0 || PY_VERSION_HEX >= 0x030B00A2 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #elif !defined(CYTHON_USE_UNICODE_WRITER) + #define CYTHON_USE_UNICODE_WRITER 1 + #endif + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #ifndef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 1 + #endif + #ifndef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL (PY_MAJOR_VERSION < 3 || PY_VERSION_HEX >= 0x03060000 && PY_VERSION_HEX < 0x030C00A6) + #endif + #ifndef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL (PY_VERSION_HEX >= 0x030700A1) + #endif + #ifndef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 1 + #endif + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #endif + #if PY_VERSION_HEX < 0x030400a1 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #elif !defined(CYTHON_USE_TP_FINALIZE) + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #if PY_VERSION_HEX < 0x030600B1 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #elif !defined(CYTHON_USE_DICT_VERSIONS) + #define CYTHON_USE_DICT_VERSIONS (PY_VERSION_HEX < 0x030C00A5) + #endif + #if PY_VERSION_HEX < 0x030700A3 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #elif !defined(CYTHON_USE_EXC_INFO_STACK) + #define CYTHON_USE_EXC_INFO_STACK 1 + #endif + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 1 + #endif +#endif +#if !defined(CYTHON_FAST_PYCCALL) +#define CYTHON_FAST_PYCCALL (CYTHON_FAST_PYCALL && PY_VERSION_HEX >= 0x030600B1) +#endif +#if !defined(CYTHON_VECTORCALL) +#define CYTHON_VECTORCALL (CYTHON_FAST_PYCCALL && PY_VERSION_HEX >= 0x030800B1) +#endif +#define CYTHON_BACKPORT_VECTORCALL (CYTHON_METH_FASTCALL && PY_VERSION_HEX < 0x030800B1) +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_MAJOR_VERSION < 3 + #include "longintrepr.h" + #endif + #undef SHIFT + #undef BASE + #undef MASK + #ifdef SIZEOF_VOID_P + enum { __pyx_check_sizeof_voidp = 1 / (int)(SIZEOF_VOID_P == sizeof(void*)) }; + #endif +#endif +#ifndef __has_attribute + #define __has_attribute(x) 0 +#endif +#ifndef __has_cpp_attribute + #define __has_cpp_attribute(x) 0 +#endif +#ifndef CYTHON_RESTRICT + #if defined(__GNUC__) + #define CYTHON_RESTRICT __restrict__ + #elif defined(_MSC_VER) && _MSC_VER >= 1400 + #define CYTHON_RESTRICT __restrict + #elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define CYTHON_RESTRICT restrict + #else + #define CYTHON_RESTRICT + #endif +#endif +#ifndef CYTHON_UNUSED + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(maybe_unused) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(maybe_unused) + #define CYTHON_UNUSED [[maybe_unused]] + #endif + #endif + #endif +#endif +#ifndef CYTHON_UNUSED +# if defined(__GNUC__) +# if !(defined(__cplusplus)) || (__GNUC__ > 3 || (__GNUC__ == 3 && __GNUC_MINOR__ >= 4)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +# elif defined(__ICC) || (defined(__INTEL_COMPILER) && !defined(_MSC_VER)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +#endif +#ifndef CYTHON_UNUSED_VAR +# if defined(__cplusplus) + template void CYTHON_UNUSED_VAR( const T& ) { } +# else +# define CYTHON_UNUSED_VAR(x) (void)(x) +# endif +#endif +#ifndef CYTHON_MAYBE_UNUSED_VAR + #define CYTHON_MAYBE_UNUSED_VAR(x) CYTHON_UNUSED_VAR(x) +#endif +#ifndef CYTHON_NCP_UNUSED +# if CYTHON_COMPILING_IN_CPYTHON +# define CYTHON_NCP_UNUSED +# else +# define CYTHON_NCP_UNUSED CYTHON_UNUSED +# endif +#endif +#ifndef CYTHON_USE_CPP_STD_MOVE + #if defined(__cplusplus) && (\ + __cplusplus >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1600)) + #define CYTHON_USE_CPP_STD_MOVE 1 + #else + #define CYTHON_USE_CPP_STD_MOVE 0 + #endif +#endif +#define __Pyx_void_to_None(void_result) ((void)(void_result), Py_INCREF(Py_None), Py_None) +#ifdef _MSC_VER + #ifndef _MSC_STDINT_H_ + #if _MSC_VER < 1300 + typedef unsigned char uint8_t; + typedef unsigned short uint16_t; + typedef unsigned int uint32_t; + #else + typedef unsigned __int8 uint8_t; + typedef unsigned __int16 uint16_t; + typedef unsigned __int32 uint32_t; + #endif + #endif + #if _MSC_VER < 1300 + #ifdef _WIN64 + typedef unsigned long long __pyx_uintptr_t; + #else + typedef unsigned int __pyx_uintptr_t; + #endif + #else + #ifdef _WIN64 + typedef unsigned __int64 __pyx_uintptr_t; + #else + typedef unsigned __int32 __pyx_uintptr_t; + #endif + #endif +#else + #include + typedef uintptr_t __pyx_uintptr_t; +#endif +#ifndef CYTHON_FALLTHROUGH + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(fallthrough) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(fallthrough) + #define CYTHON_FALLTHROUGH [[fallthrough]] + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_cpp_attribute(clang::fallthrough) + #define CYTHON_FALLTHROUGH [[clang::fallthrough]] + #elif __has_cpp_attribute(gnu::fallthrough) + #define CYTHON_FALLTHROUGH [[gnu::fallthrough]] + #endif + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_attribute(fallthrough) + #define CYTHON_FALLTHROUGH __attribute__((fallthrough)) + #else + #define CYTHON_FALLTHROUGH + #endif + #endif + #if defined(__clang__) && defined(__apple_build_version__) + #if __apple_build_version__ < 7000000 + #undef CYTHON_FALLTHROUGH + #define CYTHON_FALLTHROUGH + #endif + #endif +#endif +#ifdef __cplusplus + template + struct __PYX_IS_UNSIGNED_IMPL {static const bool value = T(0) < T(-1);}; + #define __PYX_IS_UNSIGNED(type) (__PYX_IS_UNSIGNED_IMPL::value) +#else + #define __PYX_IS_UNSIGNED(type) (((type)-1) > 0) +#endif +#if CYTHON_COMPILING_IN_PYPY == 1 + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x030A0000) +#else + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x03090000) +#endif +#define __PYX_REINTERPRET_FUNCION(func_pointer, other_pointer) ((func_pointer)(void(*)(void))(other_pointer)) + +#ifndef CYTHON_INLINE + #if defined(__clang__) + #define CYTHON_INLINE __inline__ __attribute__ ((__unused__)) + #elif defined(__GNUC__) + #define CYTHON_INLINE __inline__ + #elif defined(_MSC_VER) + #define CYTHON_INLINE __inline + #elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define CYTHON_INLINE inline + #else + #define CYTHON_INLINE + #endif +#endif + +#define __PYX_BUILD_PY_SSIZE_T "n" +#define CYTHON_FORMAT_SSIZE_T "z" +#if PY_MAJOR_VERSION < 3 + #define __Pyx_BUILTIN_MODULE_NAME "__builtin__" + #define __Pyx_DefaultClassType PyClass_Type + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a+k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_BUILTIN_MODULE_NAME "builtins" + #define __Pyx_DefaultClassType PyType_Type +#if CYTHON_COMPILING_IN_LIMITED_API + static CYTHON_INLINE PyObject* __Pyx_PyCode_New(int a, int p, int k, int l, int s, int f, + PyObject *code, PyObject *c, PyObject* n, PyObject *v, + PyObject *fv, PyObject *cell, PyObject* fn, + PyObject *name, int fline, PyObject *lnos) { + PyObject *exception_table = NULL; + PyObject *types_module=NULL, *code_type=NULL, *result=NULL; + #if __PYX_LIMITED_VERSION_HEX < 0x030B0000 + PyObject *version_info; + PyObject *py_minor_version = NULL; + #endif + long minor_version = 0; + PyObject *type, *value, *traceback; + PyErr_Fetch(&type, &value, &traceback); + #if __PYX_LIMITED_VERSION_HEX >= 0x030B0000 + minor_version = 11; + #else + if (!(version_info = PySys_GetObject("version_info"))) goto end; + if (!(py_minor_version = PySequence_GetItem(version_info, 1))) goto end; + minor_version = PyLong_AsLong(py_minor_version); + Py_DECREF(py_minor_version); + if (minor_version == -1 && PyErr_Occurred()) goto end; + #endif + if (!(types_module = PyImport_ImportModule("types"))) goto end; + if (!(code_type = PyObject_GetAttrString(types_module, "CodeType"))) goto end; + if (minor_version <= 7) { + (void)p; + result = PyObject_CallFunction(code_type, "iiiiiOOOOOOiOO", a, k, l, s, f, code, + c, n, v, fn, name, fline, lnos, fv, cell); + } else if (minor_version <= 10) { + result = PyObject_CallFunction(code_type, "iiiiiiOOOOOOiOO", a,p, k, l, s, f, code, + c, n, v, fn, name, fline, lnos, fv, cell); + } else { + if (!(exception_table = PyBytes_FromStringAndSize(NULL, 0))) goto end; + result = PyObject_CallFunction(code_type, "iiiiiiOOOOOOOiOO", a,p, k, l, s, f, code, + c, n, v, fn, name, name, fline, lnos, exception_table, fv, cell); + } + end: + Py_XDECREF(code_type); + Py_XDECREF(exception_table); + Py_XDECREF(types_module); + if (type) { + PyErr_Restore(type, value, traceback); + } + return result; + } + #ifndef CO_OPTIMIZED + #define CO_OPTIMIZED 0x0001 + #endif + #ifndef CO_NEWLOCALS + #define CO_NEWLOCALS 0x0002 + #endif + #ifndef CO_VARARGS + #define CO_VARARGS 0x0004 + #endif + #ifndef CO_VARKEYWORDS + #define CO_VARKEYWORDS 0x0008 + #endif + #ifndef CO_ASYNC_GENERATOR + #define CO_ASYNC_GENERATOR 0x0200 + #endif + #ifndef CO_GENERATOR + #define CO_GENERATOR 0x0020 + #endif + #ifndef CO_COROUTINE + #define CO_COROUTINE 0x0080 + #endif +#elif PY_VERSION_HEX >= 0x030B0000 + static CYTHON_INLINE PyCodeObject* __Pyx_PyCode_New(int a, int p, int k, int l, int s, int f, + PyObject *code, PyObject *c, PyObject* n, PyObject *v, + PyObject *fv, PyObject *cell, PyObject* fn, + PyObject *name, int fline, PyObject *lnos) { + PyCodeObject *result; + PyObject *empty_bytes = PyBytes_FromStringAndSize("", 0); + if (!empty_bytes) return NULL; + result = + #if PY_VERSION_HEX >= 0x030C0000 + PyUnstable_Code_NewWithPosOnlyArgs + #else + PyCode_NewWithPosOnlyArgs + #endif + (a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, name, fline, lnos, empty_bytes); + Py_DECREF(empty_bytes); + return result; + } +#elif PY_VERSION_HEX >= 0x030800B2 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_NewWithPosOnlyArgs(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#endif +#endif +#if PY_VERSION_HEX >= 0x030900A4 || defined(Py_IS_TYPE) + #define __Pyx_IS_TYPE(ob, type) Py_IS_TYPE(ob, type) +#else + #define __Pyx_IS_TYPE(ob, type) (((const PyObject*)ob)->ob_type == (type)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_Is) + #define __Pyx_Py_Is(x, y) Py_Is(x, y) +#else + #define __Pyx_Py_Is(x, y) ((x) == (y)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsNone) + #define __Pyx_Py_IsNone(ob) Py_IsNone(ob) +#else + #define __Pyx_Py_IsNone(ob) __Pyx_Py_Is((ob), Py_None) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsTrue) + #define __Pyx_Py_IsTrue(ob) Py_IsTrue(ob) +#else + #define __Pyx_Py_IsTrue(ob) __Pyx_Py_Is((ob), Py_True) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsFalse) + #define __Pyx_Py_IsFalse(ob) Py_IsFalse(ob) +#else + #define __Pyx_Py_IsFalse(ob) __Pyx_Py_Is((ob), Py_False) +#endif +#define __Pyx_NoneAsNull(obj) (__Pyx_Py_IsNone(obj) ? NULL : (obj)) +#if PY_VERSION_HEX >= 0x030900F0 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_GC_IsFinalized(o) PyObject_GC_IsFinalized(o) +#else + #define __Pyx_PyObject_GC_IsFinalized(o) _PyGC_FINALIZED(o) +#endif +#ifndef CO_COROUTINE + #define CO_COROUTINE 0x80 +#endif +#ifndef CO_ASYNC_GENERATOR + #define CO_ASYNC_GENERATOR 0x200 +#endif +#ifndef Py_TPFLAGS_CHECKTYPES + #define Py_TPFLAGS_CHECKTYPES 0 +#endif +#ifndef Py_TPFLAGS_HAVE_INDEX + #define Py_TPFLAGS_HAVE_INDEX 0 +#endif +#ifndef Py_TPFLAGS_HAVE_NEWBUFFER + #define Py_TPFLAGS_HAVE_NEWBUFFER 0 +#endif +#ifndef Py_TPFLAGS_HAVE_FINALIZE + #define Py_TPFLAGS_HAVE_FINALIZE 0 +#endif +#ifndef Py_TPFLAGS_SEQUENCE + #define Py_TPFLAGS_SEQUENCE 0 +#endif +#ifndef Py_TPFLAGS_MAPPING + #define Py_TPFLAGS_MAPPING 0 +#endif +#ifndef METH_STACKLESS + #define METH_STACKLESS 0 +#endif +#if PY_VERSION_HEX <= 0x030700A3 || !defined(METH_FASTCALL) + #ifndef METH_FASTCALL + #define METH_FASTCALL 0x80 + #endif + typedef PyObject *(*__Pyx_PyCFunctionFast) (PyObject *self, PyObject *const *args, Py_ssize_t nargs); + typedef PyObject *(*__Pyx_PyCFunctionFastWithKeywords) (PyObject *self, PyObject *const *args, + Py_ssize_t nargs, PyObject *kwnames); +#else + #define __Pyx_PyCFunctionFast _PyCFunctionFast + #define __Pyx_PyCFunctionFastWithKeywords _PyCFunctionFastWithKeywords +#endif +#if CYTHON_METH_FASTCALL + #define __Pyx_METH_FASTCALL METH_FASTCALL + #define __Pyx_PyCFunction_FastCall __Pyx_PyCFunctionFast + #define __Pyx_PyCFunction_FastCallWithKeywords __Pyx_PyCFunctionFastWithKeywords +#else + #define __Pyx_METH_FASTCALL METH_VARARGS + #define __Pyx_PyCFunction_FastCall PyCFunction + #define __Pyx_PyCFunction_FastCallWithKeywords PyCFunctionWithKeywords +#endif +#if CYTHON_VECTORCALL + #define __pyx_vectorcallfunc vectorcallfunc + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET PY_VECTORCALL_ARGUMENTS_OFFSET + #define __Pyx_PyVectorcall_NARGS(n) PyVectorcall_NARGS((size_t)(n)) +#elif CYTHON_BACKPORT_VECTORCALL + typedef PyObject *(*__pyx_vectorcallfunc)(PyObject *callable, PyObject *const *args, + size_t nargsf, PyObject *kwnames); + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET ((size_t)1 << (8 * sizeof(size_t) - 1)) + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(((size_t)(n)) & ~__Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET)) +#else + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET 0 + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(n)) +#endif +#if PY_MAJOR_VERSION >= 0x030900B1 +#define __Pyx_PyCFunction_CheckExact(func) PyCFunction_CheckExact(func) +#else +#define __Pyx_PyCFunction_CheckExact(func) PyCFunction_Check(func) +#endif +#define __Pyx_CyOrPyCFunction_Check(func) PyCFunction_Check(func) +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_CyOrPyCFunction_GET_FUNCTION(func) (((PyCFunctionObject*)(func))->m_ml->ml_meth) +#elif !CYTHON_COMPILING_IN_LIMITED_API +#define __Pyx_CyOrPyCFunction_GET_FUNCTION(func) PyCFunction_GET_FUNCTION(func) +#endif +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_CyOrPyCFunction_GET_FLAGS(func) (((PyCFunctionObject*)(func))->m_ml->ml_flags) +static CYTHON_INLINE PyObject* __Pyx_CyOrPyCFunction_GET_SELF(PyObject *func) { + return (__Pyx_CyOrPyCFunction_GET_FLAGS(func) & METH_STATIC) ? NULL : ((PyCFunctionObject*)func)->m_self; +} +#endif +static CYTHON_INLINE int __Pyx__IsSameCFunction(PyObject *func, void *cfunc) { +#if CYTHON_COMPILING_IN_LIMITED_API + return PyCFunction_Check(func) && PyCFunction_GetFunction(func) == (PyCFunction) cfunc; +#else + return PyCFunction_Check(func) && PyCFunction_GET_FUNCTION(func) == (PyCFunction) cfunc; +#endif +} +#define __Pyx_IsSameCFunction(func, cfunc) __Pyx__IsSameCFunction(func, cfunc) +#if __PYX_LIMITED_VERSION_HEX < 0x030900B1 + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) ((void)m, PyType_FromSpecWithBases(s, b)) + typedef PyObject *(*__Pyx_PyCMethod)(PyObject *, PyTypeObject *, PyObject *const *, size_t, PyObject *); +#else + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) PyType_FromModuleAndSpec(m, s, b) + #define __Pyx_PyCMethod PyCMethod +#endif +#ifndef METH_METHOD + #define METH_METHOD 0x200 +#endif +#if CYTHON_COMPILING_IN_PYPY && !defined(PyObject_Malloc) + #define PyObject_Malloc(s) PyMem_Malloc(s) + #define PyObject_Free(p) PyMem_Free(p) + #define PyObject_Realloc(p) PyMem_Realloc(p) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) +#else + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) (frame)->f_lineno = (lineno) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyThreadState_Current PyThreadState_Get() +#elif !CYTHON_FAST_THREAD_STATE + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#elif PY_VERSION_HEX >= 0x030d00A1 + #define __Pyx_PyThreadState_Current PyThreadState_GetUnchecked() +#elif PY_VERSION_HEX >= 0x03060000 + #define __Pyx_PyThreadState_Current _PyThreadState_UncheckedGet() +#elif PY_VERSION_HEX >= 0x03000000 + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#else + #define __Pyx_PyThreadState_Current _PyThreadState_Current +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE void *__Pyx_PyModule_GetState(PyObject *op) +{ + void *result; + result = PyModule_GetState(op); + if (!result) + Py_FatalError("Couldn't find the module state"); + return result; +} +#endif +#define __Pyx_PyObject_GetSlot(obj, name, func_ctype) __Pyx_PyType_GetSlot(Py_TYPE(obj), name, func_ctype) +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((func_ctype) PyType_GetSlot((type), Py_##name)) +#else + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((type)->name) +#endif +#if PY_VERSION_HEX < 0x030700A2 && !defined(PyThread_tss_create) && !defined(Py_tss_NEEDS_INIT) +#include "pythread.h" +#define Py_tss_NEEDS_INIT 0 +typedef int Py_tss_t; +static CYTHON_INLINE int PyThread_tss_create(Py_tss_t *key) { + *key = PyThread_create_key(); + return 0; +} +static CYTHON_INLINE Py_tss_t * PyThread_tss_alloc(void) { + Py_tss_t *key = (Py_tss_t *)PyObject_Malloc(sizeof(Py_tss_t)); + *key = Py_tss_NEEDS_INIT; + return key; +} +static CYTHON_INLINE void PyThread_tss_free(Py_tss_t *key) { + PyObject_Free(key); +} +static CYTHON_INLINE int PyThread_tss_is_created(Py_tss_t *key) { + return *key != Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE void PyThread_tss_delete(Py_tss_t *key) { + PyThread_delete_key(*key); + *key = Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE int PyThread_tss_set(Py_tss_t *key, void *value) { + return PyThread_set_key_value(*key, value); +} +static CYTHON_INLINE void * PyThread_tss_get(Py_tss_t *key) { + return PyThread_get_key_value(*key); +} +#endif +#if PY_MAJOR_VERSION < 3 + #if CYTHON_COMPILING_IN_PYPY + #if PYPY_VERSION_NUM < 0x07030600 + #if defined(__cplusplus) && __cplusplus >= 201402L + [[deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")]] + #elif defined(__GNUC__) || defined(__clang__) + __attribute__ ((__deprecated__("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6"))) + #elif defined(_MSC_VER) + __declspec(deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")) + #endif + static CYTHON_INLINE int PyGILState_Check(void) { + return 0; + } + #else // PYPY_VERSION_NUM < 0x07030600 + #endif // PYPY_VERSION_NUM < 0x07030600 + #else + static CYTHON_INLINE int PyGILState_Check(void) { + PyThreadState * tstate = _PyThreadState_Current; + return tstate && (tstate == PyGILState_GetThisThreadState()); + } + #endif +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030d0000 || defined(_PyDict_NewPresized) +#define __Pyx_PyDict_NewPresized(n) ((n <= 8) ? PyDict_New() : _PyDict_NewPresized(n)) +#else +#define __Pyx_PyDict_NewPresized(n) PyDict_New() +#endif +#if PY_MAJOR_VERSION >= 3 || CYTHON_FUTURE_DIVISION + #define __Pyx_PyNumber_Divide(x,y) PyNumber_TrueDivide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceTrueDivide(x,y) +#else + #define __Pyx_PyNumber_Divide(x,y) PyNumber_Divide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceDivide(x,y) +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX > 0x030600B4 && PY_VERSION_HEX < 0x030d0000 && CYTHON_USE_UNICODE_INTERNALS +#define __Pyx_PyDict_GetItemStrWithError(dict, name) _PyDict_GetItem_KnownHash(dict, name, ((PyASCIIObject *) name)->hash) +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStr(PyObject *dict, PyObject *name) { + PyObject *res = __Pyx_PyDict_GetItemStrWithError(dict, name); + if (res == NULL) PyErr_Clear(); + return res; +} +#elif PY_MAJOR_VERSION >= 3 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07020000) +#define __Pyx_PyDict_GetItemStrWithError PyDict_GetItemWithError +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#else +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStrWithError(PyObject *dict, PyObject *name) { +#if CYTHON_COMPILING_IN_PYPY + return PyDict_GetItem(dict, name); +#else + PyDictEntry *ep; + PyDictObject *mp = (PyDictObject*) dict; + long hash = ((PyStringObject *) name)->ob_shash; + assert(hash != -1); + ep = (mp->ma_lookup)(mp, name, hash); + if (ep == NULL) { + return NULL; + } + return ep->me_value; +#endif +} +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#endif +#if CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyType_GetFlags(tp) (((PyTypeObject *)tp)->tp_flags) + #define __Pyx_PyType_HasFeature(type, feature) ((__Pyx_PyType_GetFlags(type) & (feature)) != 0) + #define __Pyx_PyObject_GetIterNextFunc(obj) (Py_TYPE(obj)->tp_iternext) +#else + #define __Pyx_PyType_GetFlags(tp) (PyType_GetFlags((PyTypeObject *)tp)) + #define __Pyx_PyType_HasFeature(type, feature) PyType_HasFeature(type, feature) + #define __Pyx_PyObject_GetIterNextFunc(obj) PyIter_Next +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_SetItemOnTypeDict(tp, k, v) PyObject_GenericSetAttr((PyObject*)tp, k, v) +#else + #define __Pyx_SetItemOnTypeDict(tp, k, v) PyDict_SetItem(tp->tp_dict, k, v) +#endif +#if CYTHON_USE_TYPE_SPECS && PY_VERSION_HEX >= 0x03080000 +#define __Pyx_PyHeapTypeObject_GC_Del(obj) {\ + PyTypeObject *type = Py_TYPE((PyObject*)obj);\ + assert(__Pyx_PyType_HasFeature(type, Py_TPFLAGS_HEAPTYPE));\ + PyObject_GC_Del(obj);\ + Py_DECREF(type);\ +} +#else +#define __Pyx_PyHeapTypeObject_GC_Del(obj) PyObject_GC_Del(obj) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define CYTHON_PEP393_ENABLED 1 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GetLength(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_ReadChar(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((void)u, 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((void)u, (0)) + #define __Pyx_PyUnicode_DATA(u) ((void*)u) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)k, PyUnicode_ReadChar((PyObject*)(d), i)) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GetLength(u)) +#elif PY_VERSION_HEX > 0x03030000 && defined(PyUnicode_KIND) + #define CYTHON_PEP393_ENABLED 1 + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_READY(op) (0) + #else + #define __Pyx_PyUnicode_READY(op) (likely(PyUnicode_IS_READY(op)) ?\ + 0 : _PyUnicode_Ready((PyObject *)(op))) + #endif + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_LENGTH(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_READ_CHAR(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) PyUnicode_MAX_CHAR_VALUE(u) + #define __Pyx_PyUnicode_KIND(u) ((int)PyUnicode_KIND(u)) + #define __Pyx_PyUnicode_DATA(u) PyUnicode_DATA(u) + #define __Pyx_PyUnicode_READ(k, d, i) PyUnicode_READ(k, d, i) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) PyUnicode_WRITE(k, d, i, (Py_UCS4) ch) + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_LENGTH(u)) + #else + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x03090000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : ((PyCompactUnicodeObject *)(u))->wstr_length)) + #else + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : PyUnicode_GET_SIZE(u))) + #endif + #endif +#else + #define CYTHON_PEP393_ENABLED 0 + #define PyUnicode_1BYTE_KIND 1 + #define PyUnicode_2BYTE_KIND 2 + #define PyUnicode_4BYTE_KIND 4 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_SIZE(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) ((Py_UCS4)(PyUnicode_AS_UNICODE(u)[i])) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((sizeof(Py_UNICODE) == 2) ? 65535U : 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((int)sizeof(Py_UNICODE)) + #define __Pyx_PyUnicode_DATA(u) ((void*)PyUnicode_AS_UNICODE(u)) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)(k), (Py_UCS4)(((Py_UNICODE*)d)[i])) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) (((void)(k)), ((Py_UNICODE*)d)[i] = (Py_UNICODE) ch) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_SIZE(u)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyUnicode_Concat(a, b) PyNumber_Add(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) PyNumber_Add(a, b) +#else + #define __Pyx_PyUnicode_Concat(a, b) PyUnicode_Concat(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) ((unlikely((a) == Py_None) || unlikely((b) == Py_None)) ?\ + PyNumber_Add(a, b) : __Pyx_PyUnicode_Concat(a, b)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #if !defined(PyUnicode_DecodeUnicodeEscape) + #define PyUnicode_DecodeUnicodeEscape(s, size, errors) PyUnicode_Decode(s, size, "unicode_escape", errors) + #endif + #if !defined(PyUnicode_Contains) || (PY_MAJOR_VERSION == 2 && PYPY_VERSION_NUM < 0x07030500) + #undef PyUnicode_Contains + #define PyUnicode_Contains(u, s) PySequence_Contains(u, s) + #endif + #if !defined(PyByteArray_Check) + #define PyByteArray_Check(obj) PyObject_TypeCheck(obj, &PyByteArray_Type) + #endif + #if !defined(PyObject_Format) + #define PyObject_Format(obj, fmt) PyObject_CallMethod(obj, "__format__", "O", fmt) + #endif +#endif +#define __Pyx_PyString_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyString_Check(b) && !PyString_CheckExact(b)))) ? PyNumber_Remainder(a, b) : __Pyx_PyString_Format(a, b)) +#define __Pyx_PyUnicode_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyUnicode_Check(b) && !PyUnicode_CheckExact(b)))) ? PyNumber_Remainder(a, b) : PyUnicode_Format(a, b)) +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyString_Format(a, b) PyUnicode_Format(a, b) +#else + #define __Pyx_PyString_Format(a, b) PyString_Format(a, b) +#endif +#if PY_MAJOR_VERSION < 3 && !defined(PyObject_ASCII) + #define PyObject_ASCII(o) PyObject_Repr(o) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBaseString_Type PyUnicode_Type + #define PyStringObject PyUnicodeObject + #define PyString_Type PyUnicode_Type + #define PyString_Check PyUnicode_Check + #define PyString_CheckExact PyUnicode_CheckExact +#ifndef PyObject_Unicode + #define PyObject_Unicode PyObject_Str +#endif +#endif +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyBaseString_Check(obj) PyUnicode_Check(obj) + #define __Pyx_PyBaseString_CheckExact(obj) PyUnicode_CheckExact(obj) +#else + #define __Pyx_PyBaseString_Check(obj) (PyString_Check(obj) || PyUnicode_Check(obj)) + #define __Pyx_PyBaseString_CheckExact(obj) (PyString_CheckExact(obj) || PyUnicode_CheckExact(obj)) +#endif +#if CYTHON_COMPILING_IN_CPYTHON + #define __Pyx_PySequence_ListKeepNew(obj)\ + (likely(PyList_CheckExact(obj) && Py_REFCNT(obj) == 1) ? __Pyx_NewRef(obj) : PySequence_List(obj)) +#else + #define __Pyx_PySequence_ListKeepNew(obj) PySequence_List(obj) +#endif +#ifndef PySet_CheckExact + #define PySet_CheckExact(obj) __Pyx_IS_TYPE(obj, &PySet_Type) +#endif +#if PY_VERSION_HEX >= 0x030900A4 + #define __Pyx_SET_REFCNT(obj, refcnt) Py_SET_REFCNT(obj, refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SET_SIZE(obj, size) +#else + #define __Pyx_SET_REFCNT(obj, refcnt) Py_REFCNT(obj) = (refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SIZE(obj) = (size) +#endif +#if CYTHON_ASSUME_SAFE_MACROS + #define __Pyx_PySequence_ITEM(o, i) PySequence_ITEM(o, i) + #define __Pyx_PySequence_SIZE(seq) Py_SIZE(seq) + #define __Pyx_PyTuple_SET_ITEM(o, i, v) (PyTuple_SET_ITEM(o, i, v), (0)) + #define __Pyx_PyList_SET_ITEM(o, i, v) (PyList_SET_ITEM(o, i, v), (0)) + #define __Pyx_PyTuple_GET_SIZE(o) PyTuple_GET_SIZE(o) + #define __Pyx_PyList_GET_SIZE(o) PyList_GET_SIZE(o) + #define __Pyx_PySet_GET_SIZE(o) PySet_GET_SIZE(o) + #define __Pyx_PyBytes_GET_SIZE(o) PyBytes_GET_SIZE(o) + #define __Pyx_PyByteArray_GET_SIZE(o) PyByteArray_GET_SIZE(o) +#else + #define __Pyx_PySequence_ITEM(o, i) PySequence_GetItem(o, i) + #define __Pyx_PySequence_SIZE(seq) PySequence_Size(seq) + #define __Pyx_PyTuple_SET_ITEM(o, i, v) PyTuple_SetItem(o, i, v) + #define __Pyx_PyList_SET_ITEM(o, i, v) PyList_SetItem(o, i, v) + #define __Pyx_PyTuple_GET_SIZE(o) PyTuple_Size(o) + #define __Pyx_PyList_GET_SIZE(o) PyList_Size(o) + #define __Pyx_PySet_GET_SIZE(o) PySet_Size(o) + #define __Pyx_PyBytes_GET_SIZE(o) PyBytes_Size(o) + #define __Pyx_PyByteArray_GET_SIZE(o) PyByteArray_Size(o) +#endif +#if PY_VERSION_HEX >= 0x030d00A1 + #define __Pyx_PyImport_AddModuleRef(name) PyImport_AddModuleRef(name) +#else + static CYTHON_INLINE PyObject *__Pyx_PyImport_AddModuleRef(const char *name) { + PyObject *module = PyImport_AddModule(name); + Py_XINCREF(module); + return module; + } +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyIntObject PyLongObject + #define PyInt_Type PyLong_Type + #define PyInt_Check(op) PyLong_Check(op) + #define PyInt_CheckExact(op) PyLong_CheckExact(op) + #define __Pyx_Py3Int_Check(op) PyLong_Check(op) + #define __Pyx_Py3Int_CheckExact(op) PyLong_CheckExact(op) + #define PyInt_FromString PyLong_FromString + #define PyInt_FromUnicode PyLong_FromUnicode + #define PyInt_FromLong PyLong_FromLong + #define PyInt_FromSize_t PyLong_FromSize_t + #define PyInt_FromSsize_t PyLong_FromSsize_t + #define PyInt_AsLong PyLong_AsLong + #define PyInt_AS_LONG PyLong_AS_LONG + #define PyInt_AsSsize_t PyLong_AsSsize_t + #define PyInt_AsUnsignedLongMask PyLong_AsUnsignedLongMask + #define PyInt_AsUnsignedLongLongMask PyLong_AsUnsignedLongLongMask + #define PyNumber_Int PyNumber_Long +#else + #define __Pyx_Py3Int_Check(op) (PyLong_Check(op) || PyInt_Check(op)) + #define __Pyx_Py3Int_CheckExact(op) (PyLong_CheckExact(op) || PyInt_CheckExact(op)) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBoolObject PyLongObject +#endif +#if PY_MAJOR_VERSION >= 3 && CYTHON_COMPILING_IN_PYPY + #ifndef PyUnicode_InternFromString + #define PyUnicode_InternFromString(s) PyUnicode_FromString(s) + #endif +#endif +#if PY_VERSION_HEX < 0x030200A4 + typedef long Py_hash_t; + #define __Pyx_PyInt_FromHash_t PyInt_FromLong + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsHash_t +#else + #define __Pyx_PyInt_FromHash_t PyInt_FromSsize_t + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsSsize_t +#endif +#if CYTHON_USE_ASYNC_SLOTS + #if PY_VERSION_HEX >= 0x030500B1 + #define __Pyx_PyAsyncMethodsStruct PyAsyncMethods + #define __Pyx_PyType_AsAsync(obj) (Py_TYPE(obj)->tp_as_async) + #else + #define __Pyx_PyType_AsAsync(obj) ((__Pyx_PyAsyncMethodsStruct*) (Py_TYPE(obj)->tp_reserved)) + #endif +#else + #define __Pyx_PyType_AsAsync(obj) NULL +#endif +#ifndef __Pyx_PyAsyncMethodsStruct + typedef struct { + unaryfunc am_await; + unaryfunc am_aiter; + unaryfunc am_anext; + } __Pyx_PyAsyncMethodsStruct; +#endif + +#if defined(_WIN32) || defined(WIN32) || defined(MS_WINDOWS) + #if !defined(_USE_MATH_DEFINES) + #define _USE_MATH_DEFINES + #endif +#endif +#include +#ifdef NAN +#define __PYX_NAN() ((float) NAN) +#else +static CYTHON_INLINE float __PYX_NAN() { + float value; + memset(&value, 0xFF, sizeof(value)); + return value; +} +#endif +#if defined(__CYGWIN__) && defined(_LDBL_EQ_DBL) +#define __Pyx_truncl trunc +#else +#define __Pyx_truncl truncl +#endif + +#define __PYX_MARK_ERR_POS(f_index, lineno) \ + { __pyx_filename = __pyx_f[f_index]; (void)__pyx_filename; __pyx_lineno = lineno; (void)__pyx_lineno; __pyx_clineno = __LINE__; (void)__pyx_clineno; } +#define __PYX_ERR(f_index, lineno, Ln_error) \ + { __PYX_MARK_ERR_POS(f_index, lineno) goto Ln_error; } + +#ifdef CYTHON_EXTERN_C + #undef __PYX_EXTERN_C + #define __PYX_EXTERN_C CYTHON_EXTERN_C +#elif defined(__PYX_EXTERN_C) + #ifdef _MSC_VER + #pragma message ("Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead.") + #else + #warning Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead. + #endif +#else + #ifdef __cplusplus + #define __PYX_EXTERN_C extern "C" + #else + #define __PYX_EXTERN_C extern + #endif +#endif + +#define __PYX_HAVE__acados_template__acados_ocp_solver_pyx +#define __PYX_HAVE_API__acados_template__acados_ocp_solver_pyx +/* Early includes */ +#include +#include "acados/ocp_nlp/ocp_nlp_common.h" +#include "acados_c/ocp_nlp_interface.h" +#include "acados_solver_lat.h" +#include + + /* Using NumPy API declarations from "numpy/__init__.cython-30.pxd" */ + +#include "numpy/arrayobject.h" +#include "numpy/ndarrayobject.h" +#include "numpy/ndarraytypes.h" +#include "numpy/arrayscalars.h" +#include "numpy/ufuncobject.h" +#include "pythread.h" +#include +#ifdef _OPENMP +#include +#endif /* _OPENMP */ + +#if defined(PYREX_WITHOUT_ASSERTIONS) && !defined(CYTHON_WITHOUT_ASSERTIONS) +#define CYTHON_WITHOUT_ASSERTIONS +#endif + +typedef struct {PyObject **p; const char *s; const Py_ssize_t n; const char* encoding; + const char is_unicode; const char is_str; const char intern; } __Pyx_StringTabEntry; + +#define __PYX_DEFAULT_STRING_ENCODING_IS_ASCII 0 +#define __PYX_DEFAULT_STRING_ENCODING_IS_UTF8 0 +#define __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT (PY_MAJOR_VERSION >= 3 && __PYX_DEFAULT_STRING_ENCODING_IS_UTF8) +#define __PYX_DEFAULT_STRING_ENCODING "" +#define __Pyx_PyObject_FromString __Pyx_PyBytes_FromString +#define __Pyx_PyObject_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#define __Pyx_uchar_cast(c) ((unsigned char)c) +#define __Pyx_long_cast(x) ((long)x) +#define __Pyx_fits_Py_ssize_t(v, type, is_signed) (\ + (sizeof(type) < sizeof(Py_ssize_t)) ||\ + (sizeof(type) > sizeof(Py_ssize_t) &&\ + likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX) &&\ + (!is_signed || likely(v > (type)PY_SSIZE_T_MIN ||\ + v == (type)PY_SSIZE_T_MIN))) ||\ + (sizeof(type) == sizeof(Py_ssize_t) &&\ + (is_signed || likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX))) ) +static CYTHON_INLINE int __Pyx_is_valid_index(Py_ssize_t i, Py_ssize_t limit) { + return (size_t) i < (size_t) limit; +} +#if defined (__cplusplus) && __cplusplus >= 201103L + #include + #define __Pyx_sst_abs(value) std::abs(value) +#elif SIZEOF_INT >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) abs(value) +#elif SIZEOF_LONG >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) labs(value) +#elif defined (_MSC_VER) + #define __Pyx_sst_abs(value) ((Py_ssize_t)_abs64(value)) +#elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define __Pyx_sst_abs(value) llabs(value) +#elif defined (__GNUC__) + #define __Pyx_sst_abs(value) __builtin_llabs(value) +#else + #define __Pyx_sst_abs(value) ((value<0) ? -value : value) +#endif +static CYTHON_INLINE Py_ssize_t __Pyx_ssize_strlen(const char *s); +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject*); +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject*, Py_ssize_t* length); +static CYTHON_INLINE PyObject* __Pyx_PyByteArray_FromString(const char*); +#define __Pyx_PyByteArray_FromStringAndSize(s, l) PyByteArray_FromStringAndSize((const char*)s, l) +#define __Pyx_PyBytes_FromString PyBytes_FromString +#define __Pyx_PyBytes_FromStringAndSize PyBytes_FromStringAndSize +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char*); +#if PY_MAJOR_VERSION < 3 + #define __Pyx_PyStr_FromString __Pyx_PyBytes_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#else + #define __Pyx_PyStr_FromString __Pyx_PyUnicode_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyUnicode_FromStringAndSize +#endif +#define __Pyx_PyBytes_AsWritableString(s) ((char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableSString(s) ((signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableUString(s) ((unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsString(s) ((const char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsSString(s) ((const signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsUString(s) ((const unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyObject_AsWritableString(s) ((char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableSString(s) ((signed char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableUString(s) ((unsigned char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsSString(s) ((const signed char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsUString(s) ((const unsigned char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_FromCString(s) __Pyx_PyObject_FromString((const char*)s) +#define __Pyx_PyBytes_FromCString(s) __Pyx_PyBytes_FromString((const char*)s) +#define __Pyx_PyByteArray_FromCString(s) __Pyx_PyByteArray_FromString((const char*)s) +#define __Pyx_PyStr_FromCString(s) __Pyx_PyStr_FromString((const char*)s) +#define __Pyx_PyUnicode_FromCString(s) __Pyx_PyUnicode_FromString((const char*)s) +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const wchar_t *u) +{ + const wchar_t *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#else +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const Py_UNICODE *u) +{ + const Py_UNICODE *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#endif +#define __Pyx_PyUnicode_FromOrdinal(o) PyUnicode_FromOrdinal((int)o) +#define __Pyx_PyUnicode_FromUnicode(u) PyUnicode_FromUnicode(u, __Pyx_Py_UNICODE_strlen(u)) +#define __Pyx_PyUnicode_FromUnicodeAndLength PyUnicode_FromUnicode +#define __Pyx_PyUnicode_AsUnicode PyUnicode_AsUnicode +#define __Pyx_NewRef(obj) (Py_INCREF(obj), obj) +#define __Pyx_Owned_Py_None(b) __Pyx_NewRef(Py_None) +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b); +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject*); +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject*); +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x); +#define __Pyx_PySequence_Tuple(obj)\ + (likely(PyTuple_CheckExact(obj)) ? __Pyx_NewRef(obj) : PySequence_Tuple(obj)) +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject*); +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t); +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject*); +#if CYTHON_ASSUME_SAFE_MACROS +#define __pyx_PyFloat_AsDouble(x) (PyFloat_CheckExact(x) ? PyFloat_AS_DOUBLE(x) : PyFloat_AsDouble(x)) +#else +#define __pyx_PyFloat_AsDouble(x) PyFloat_AsDouble(x) +#endif +#define __pyx_PyFloat_AsFloat(x) ((float) __pyx_PyFloat_AsDouble(x)) +#if PY_MAJOR_VERSION >= 3 +#define __Pyx_PyNumber_Int(x) (PyLong_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Long(x)) +#else +#define __Pyx_PyNumber_Int(x) (PyInt_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Int(x)) +#endif +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_VERSION_HEX >= 0x030C00A7 + #ifndef _PyLong_SIGN_MASK + #define _PyLong_SIGN_MASK 3 + #endif + #ifndef _PyLong_NON_SIZE_BITS + #define _PyLong_NON_SIZE_BITS 3 + #endif + #define __Pyx_PyLong_Sign(x) (((PyLongObject*)x)->long_value.lv_tag & _PyLong_SIGN_MASK) + #define __Pyx_PyLong_IsNeg(x) ((__Pyx_PyLong_Sign(x) & 2) != 0) + #define __Pyx_PyLong_IsNonNeg(x) (!__Pyx_PyLong_IsNeg(x)) + #define __Pyx_PyLong_IsZero(x) (__Pyx_PyLong_Sign(x) & 1) + #define __Pyx_PyLong_IsPos(x) (__Pyx_PyLong_Sign(x) == 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) (__Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) ((Py_ssize_t) (((PyLongObject*)x)->long_value.lv_tag >> _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_SignedDigitCount(x)\ + ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * __Pyx_PyLong_DigitCount(x)) + #if defined(PyUnstable_Long_IsCompact) && defined(PyUnstable_Long_CompactValue) + #define __Pyx_PyLong_IsCompact(x) PyUnstable_Long_IsCompact((PyLongObject*) x) + #define __Pyx_PyLong_CompactValue(x) PyUnstable_Long_CompactValue((PyLongObject*) x) + #else + #define __Pyx_PyLong_IsCompact(x) (((PyLongObject*)x)->long_value.lv_tag < (2 << _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_CompactValue(x) ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * (Py_ssize_t) __Pyx_PyLong_Digits(x)[0]) + #endif + typedef Py_ssize_t __Pyx_compact_pylong; + typedef size_t __Pyx_compact_upylong; + #else + #define __Pyx_PyLong_IsNeg(x) (Py_SIZE(x) < 0) + #define __Pyx_PyLong_IsNonNeg(x) (Py_SIZE(x) >= 0) + #define __Pyx_PyLong_IsZero(x) (Py_SIZE(x) == 0) + #define __Pyx_PyLong_IsPos(x) (Py_SIZE(x) > 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) ((Py_SIZE(x) == 0) ? 0 : __Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) __Pyx_sst_abs(Py_SIZE(x)) + #define __Pyx_PyLong_SignedDigitCount(x) Py_SIZE(x) + #define __Pyx_PyLong_IsCompact(x) (Py_SIZE(x) == 0 || Py_SIZE(x) == 1 || Py_SIZE(x) == -1) + #define __Pyx_PyLong_CompactValue(x)\ + ((Py_SIZE(x) == 0) ? (sdigit) 0 : ((Py_SIZE(x) < 0) ? -(sdigit)__Pyx_PyLong_Digits(x)[0] : (sdigit)__Pyx_PyLong_Digits(x)[0])) + typedef sdigit __Pyx_compact_pylong; + typedef digit __Pyx_compact_upylong; + #endif + #if PY_VERSION_HEX >= 0x030C00A5 + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->long_value.ob_digit) + #else + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->ob_digit) + #endif +#endif +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII +#include +static int __Pyx_sys_getdefaultencoding_not_ascii; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + PyObject* ascii_chars_u = NULL; + PyObject* ascii_chars_b = NULL; + const char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + if (strcmp(default_encoding_c, "ascii") == 0) { + __Pyx_sys_getdefaultencoding_not_ascii = 0; + } else { + char ascii_chars[128]; + int c; + for (c = 0; c < 128; c++) { + ascii_chars[c] = (char) c; + } + __Pyx_sys_getdefaultencoding_not_ascii = 1; + ascii_chars_u = PyUnicode_DecodeASCII(ascii_chars, 128, NULL); + if (!ascii_chars_u) goto bad; + ascii_chars_b = PyUnicode_AsEncodedString(ascii_chars_u, default_encoding_c, NULL); + if (!ascii_chars_b || !PyBytes_Check(ascii_chars_b) || memcmp(ascii_chars, PyBytes_AS_STRING(ascii_chars_b), 128) != 0) { + PyErr_Format( + PyExc_ValueError, + "This module compiled with c_string_encoding=ascii, but default encoding '%.200s' is not a superset of ascii.", + default_encoding_c); + goto bad; + } + Py_DECREF(ascii_chars_u); + Py_DECREF(ascii_chars_b); + } + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + Py_XDECREF(ascii_chars_u); + Py_XDECREF(ascii_chars_b); + return -1; +} +#endif +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT && PY_MAJOR_VERSION >= 3 +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_DecodeUTF8(c_str, size, NULL) +#else +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_Decode(c_str, size, __PYX_DEFAULT_STRING_ENCODING, NULL) +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +#include +static char* __PYX_DEFAULT_STRING_ENCODING; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) (const char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + __PYX_DEFAULT_STRING_ENCODING = (char*) malloc(strlen(default_encoding_c) + 1); + if (!__PYX_DEFAULT_STRING_ENCODING) goto bad; + strcpy(__PYX_DEFAULT_STRING_ENCODING, default_encoding_c); + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + return -1; +} +#endif +#endif + + +/* Test for GCC > 2.95 */ +#if defined(__GNUC__) && (__GNUC__ > 2 || (__GNUC__ == 2 && (__GNUC_MINOR__ > 95))) + #define likely(x) __builtin_expect(!!(x), 1) + #define unlikely(x) __builtin_expect(!!(x), 0) +#else /* !__GNUC__ or GCC < 2.95 */ + #define likely(x) (x) + #define unlikely(x) (x) +#endif /* __GNUC__ */ +static CYTHON_INLINE void __Pyx_pretend_to_initialize(void* ptr) { (void)ptr; } + +#if !CYTHON_USE_MODULE_STATE +static PyObject *__pyx_m = NULL; +#endif +static int __pyx_lineno; +static int __pyx_clineno = 0; +static const char * __pyx_cfilenm = __FILE__; +static const char *__pyx_filename; + +/* Header.proto */ +#if !defined(CYTHON_CCOMPLEX) + #if defined(__cplusplus) + #define CYTHON_CCOMPLEX 1 + #elif (defined(_Complex_I) && !defined(_MSC_VER)) || ((defined (__STDC_VERSION__) && __STDC_VERSION__ >= 201112L) && !defined(__STDC_NO_COMPLEX__) && !defined(_MSC_VER)) + #define CYTHON_CCOMPLEX 1 + #else + #define CYTHON_CCOMPLEX 0 + #endif +#endif +#if CYTHON_CCOMPLEX + #ifdef __cplusplus + #include + #else + #include + #endif +#endif +#if CYTHON_CCOMPLEX && !defined(__cplusplus) && defined(__sun__) && defined(__GNUC__) + #undef _Complex_I + #define _Complex_I 1.0fj +#endif + +/* #### Code section: filename_table ### */ + +static const char *__pyx_f[] = { + "third_party/acados/acados_template/acados_ocp_solver_pyx.pyx", + "", + "__init__.cython-30.pxd", + "type.pxd", +}; +/* #### Code section: utility_code_proto_before_types ### */ +/* ForceInitThreads.proto */ +#ifndef __PYX_FORCE_INIT_THREADS + #define __PYX_FORCE_INIT_THREADS 0 +#endif + +/* NoFastGil.proto */ +#define __Pyx_PyGILState_Ensure PyGILState_Ensure +#define __Pyx_PyGILState_Release PyGILState_Release +#define __Pyx_FastGIL_Remember() +#define __Pyx_FastGIL_Forget() +#define __Pyx_FastGilFuncInit() + +/* BufferFormatStructs.proto */ +struct __Pyx_StructField_; +#define __PYX_BUF_FLAGS_PACKED_STRUCT (1 << 0) +typedef struct { + const char* name; + struct __Pyx_StructField_* fields; + size_t size; + size_t arraysize[8]; + int ndim; + char typegroup; + char is_unsigned; + int flags; +} __Pyx_TypeInfo; +typedef struct __Pyx_StructField_ { + __Pyx_TypeInfo* type; + const char* name; + size_t offset; +} __Pyx_StructField; +typedef struct { + __Pyx_StructField* field; + size_t parent_offset; +} __Pyx_BufFmt_StackElem; +typedef struct { + __Pyx_StructField root; + __Pyx_BufFmt_StackElem* head; + size_t fmt_offset; + size_t new_count, enc_count; + size_t struct_alignment; + int is_complex; + char enc_type; + char new_packmode; + char enc_packmode; + char is_valid_array; +} __Pyx_BufFmt_Context; + +/* Atomics.proto */ +#include +#ifndef CYTHON_ATOMICS + #define CYTHON_ATOMICS 1 +#endif +#define __PYX_CYTHON_ATOMICS_ENABLED() CYTHON_ATOMICS +#define __pyx_atomic_int_type int +#define __pyx_nonatomic_int_type int +#if CYTHON_ATOMICS && (defined(__STDC_VERSION__) &&\ + (__STDC_VERSION__ >= 201112L) &&\ + !defined(__STDC_NO_ATOMICS__)) + #include +#elif CYTHON_ATOMICS && (defined(__cplusplus) && (\ + (__cplusplus >= 201103L) ||\ + (defined(_MSC_VER) && _MSC_VER >= 1700))) + #include +#endif +#if CYTHON_ATOMICS && (defined(__STDC_VERSION__) &&\ + (__STDC_VERSION__ >= 201112L) &&\ + !defined(__STDC_NO_ATOMICS__) &&\ + ATOMIC_INT_LOCK_FREE == 2) + #undef __pyx_atomic_int_type + #define __pyx_atomic_int_type atomic_int + #define __pyx_atomic_incr_aligned(value) atomic_fetch_add_explicit(value, 1, memory_order_relaxed) + #define __pyx_atomic_decr_aligned(value) atomic_fetch_sub_explicit(value, 1, memory_order_acq_rel) + #if defined(__PYX_DEBUG_ATOMICS) && defined(_MSC_VER) + #pragma message ("Using standard C atomics") + #elif defined(__PYX_DEBUG_ATOMICS) + #warning "Using standard C atomics" + #endif +#elif CYTHON_ATOMICS && (defined(__cplusplus) && (\ + (__cplusplus >= 201103L) ||\ +\ + (defined(_MSC_VER) && _MSC_VER >= 1700)) &&\ + ATOMIC_INT_LOCK_FREE == 2) + #undef __pyx_atomic_int_type + #define __pyx_atomic_int_type std::atomic_int + #define __pyx_atomic_incr_aligned(value) std::atomic_fetch_add_explicit(value, 1, std::memory_order_relaxed) + #define __pyx_atomic_decr_aligned(value) std::atomic_fetch_sub_explicit(value, 1, std::memory_order_acq_rel) + #if defined(__PYX_DEBUG_ATOMICS) && defined(_MSC_VER) + #pragma message ("Using standard C++ atomics") + #elif defined(__PYX_DEBUG_ATOMICS) + #warning "Using standard C++ atomics" + #endif +#elif CYTHON_ATOMICS && (__GNUC__ >= 5 || (__GNUC__ == 4 &&\ + (__GNUC_MINOR__ > 1 ||\ + (__GNUC_MINOR__ == 1 && __GNUC_PATCHLEVEL__ >= 2)))) + #define __pyx_atomic_incr_aligned(value) __sync_fetch_and_add(value, 1) + #define __pyx_atomic_decr_aligned(value) __sync_fetch_and_sub(value, 1) + #ifdef __PYX_DEBUG_ATOMICS + #warning "Using GNU atomics" + #endif +#elif CYTHON_ATOMICS && defined(_MSC_VER) + #include + #undef __pyx_atomic_int_type + #define __pyx_atomic_int_type long + #undef __pyx_nonatomic_int_type + #define __pyx_nonatomic_int_type long + #pragma intrinsic (_InterlockedExchangeAdd) + #define __pyx_atomic_incr_aligned(value) _InterlockedExchangeAdd(value, 1) + #define __pyx_atomic_decr_aligned(value) _InterlockedExchangeAdd(value, -1) + #ifdef __PYX_DEBUG_ATOMICS + #pragma message ("Using MSVC atomics") + #endif +#else + #undef CYTHON_ATOMICS + #define CYTHON_ATOMICS 0 + #ifdef __PYX_DEBUG_ATOMICS + #warning "Not using atomics" + #endif +#endif +#if CYTHON_ATOMICS + #define __pyx_add_acquisition_count(memview)\ + __pyx_atomic_incr_aligned(__pyx_get_slice_count_pointer(memview)) + #define __pyx_sub_acquisition_count(memview)\ + __pyx_atomic_decr_aligned(__pyx_get_slice_count_pointer(memview)) +#else + #define __pyx_add_acquisition_count(memview)\ + __pyx_add_acquisition_count_locked(__pyx_get_slice_count_pointer(memview), memview->lock) + #define __pyx_sub_acquisition_count(memview)\ + __pyx_sub_acquisition_count_locked(__pyx_get_slice_count_pointer(memview), memview->lock) +#endif + +/* MemviewSliceStruct.proto */ +struct __pyx_memoryview_obj; +typedef struct { + struct __pyx_memoryview_obj *memview; + char *data; + Py_ssize_t shape[8]; + Py_ssize_t strides[8]; + Py_ssize_t suboffsets[8]; +} __Pyx_memviewslice; +#define __Pyx_MemoryView_Len(m) (m.shape[0]) + +/* #### Code section: numeric_typedefs ### */ + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":730 + * # in Cython to enable them only on the right systems. + * + * ctypedef npy_int8 int8_t # <<<<<<<<<<<<<< + * ctypedef npy_int16 int16_t + * ctypedef npy_int32 int32_t + */ +typedef npy_int8 __pyx_t_5numpy_int8_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":731 + * + * ctypedef npy_int8 int8_t + * ctypedef npy_int16 int16_t # <<<<<<<<<<<<<< + * ctypedef npy_int32 int32_t + * ctypedef npy_int64 int64_t + */ +typedef npy_int16 __pyx_t_5numpy_int16_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":732 + * ctypedef npy_int8 int8_t + * ctypedef npy_int16 int16_t + * ctypedef npy_int32 int32_t # <<<<<<<<<<<<<< + * ctypedef npy_int64 int64_t + * #ctypedef npy_int96 int96_t + */ +typedef npy_int32 __pyx_t_5numpy_int32_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":733 + * ctypedef npy_int16 int16_t + * ctypedef npy_int32 int32_t + * ctypedef npy_int64 int64_t # <<<<<<<<<<<<<< + * #ctypedef npy_int96 int96_t + * #ctypedef npy_int128 int128_t + */ +typedef npy_int64 __pyx_t_5numpy_int64_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":737 + * #ctypedef npy_int128 int128_t + * + * ctypedef npy_uint8 uint8_t # <<<<<<<<<<<<<< + * ctypedef npy_uint16 uint16_t + * ctypedef npy_uint32 uint32_t + */ +typedef npy_uint8 __pyx_t_5numpy_uint8_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":738 + * + * ctypedef npy_uint8 uint8_t + * ctypedef npy_uint16 uint16_t # <<<<<<<<<<<<<< + * ctypedef npy_uint32 uint32_t + * ctypedef npy_uint64 uint64_t + */ +typedef npy_uint16 __pyx_t_5numpy_uint16_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":739 + * ctypedef npy_uint8 uint8_t + * ctypedef npy_uint16 uint16_t + * ctypedef npy_uint32 uint32_t # <<<<<<<<<<<<<< + * ctypedef npy_uint64 uint64_t + * #ctypedef npy_uint96 uint96_t + */ +typedef npy_uint32 __pyx_t_5numpy_uint32_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":740 + * ctypedef npy_uint16 uint16_t + * ctypedef npy_uint32 uint32_t + * ctypedef npy_uint64 uint64_t # <<<<<<<<<<<<<< + * #ctypedef npy_uint96 uint96_t + * #ctypedef npy_uint128 uint128_t + */ +typedef npy_uint64 __pyx_t_5numpy_uint64_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":744 + * #ctypedef npy_uint128 uint128_t + * + * ctypedef npy_float32 float32_t # <<<<<<<<<<<<<< + * ctypedef npy_float64 float64_t + * #ctypedef npy_float80 float80_t + */ +typedef npy_float32 __pyx_t_5numpy_float32_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":745 + * + * ctypedef npy_float32 float32_t + * ctypedef npy_float64 float64_t # <<<<<<<<<<<<<< + * #ctypedef npy_float80 float80_t + * #ctypedef npy_float128 float128_t + */ +typedef npy_float64 __pyx_t_5numpy_float64_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":754 + * # The int types are mapped a bit surprising -- + * # numpy.int corresponds to 'l' and numpy.long to 'q' + * ctypedef npy_long int_t # <<<<<<<<<<<<<< + * ctypedef npy_longlong longlong_t + * + */ +typedef npy_long __pyx_t_5numpy_int_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":755 + * # numpy.int corresponds to 'l' and numpy.long to 'q' + * ctypedef npy_long int_t + * ctypedef npy_longlong longlong_t # <<<<<<<<<<<<<< + * + * ctypedef npy_ulong uint_t + */ +typedef npy_longlong __pyx_t_5numpy_longlong_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":757 + * ctypedef npy_longlong longlong_t + * + * ctypedef npy_ulong uint_t # <<<<<<<<<<<<<< + * ctypedef npy_ulonglong ulonglong_t + * + */ +typedef npy_ulong __pyx_t_5numpy_uint_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":758 + * + * ctypedef npy_ulong uint_t + * ctypedef npy_ulonglong ulonglong_t # <<<<<<<<<<<<<< + * + * ctypedef npy_intp intp_t + */ +typedef npy_ulonglong __pyx_t_5numpy_ulonglong_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":760 + * ctypedef npy_ulonglong ulonglong_t + * + * ctypedef npy_intp intp_t # <<<<<<<<<<<<<< + * ctypedef npy_uintp uintp_t + * + */ +typedef npy_intp __pyx_t_5numpy_intp_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":761 + * + * ctypedef npy_intp intp_t + * ctypedef npy_uintp uintp_t # <<<<<<<<<<<<<< + * + * ctypedef npy_double float_t + */ +typedef npy_uintp __pyx_t_5numpy_uintp_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":763 + * ctypedef npy_uintp uintp_t + * + * ctypedef npy_double float_t # <<<<<<<<<<<<<< + * ctypedef npy_double double_t + * ctypedef npy_longdouble longdouble_t + */ +typedef npy_double __pyx_t_5numpy_float_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":764 + * + * ctypedef npy_double float_t + * ctypedef npy_double double_t # <<<<<<<<<<<<<< + * ctypedef npy_longdouble longdouble_t + * + */ +typedef npy_double __pyx_t_5numpy_double_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":765 + * ctypedef npy_double float_t + * ctypedef npy_double double_t + * ctypedef npy_longdouble longdouble_t # <<<<<<<<<<<<<< + * + * ctypedef npy_cfloat cfloat_t + */ +typedef npy_longdouble __pyx_t_5numpy_longdouble_t; +/* #### Code section: complex_type_declarations ### */ +/* Declarations.proto */ +#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #ifdef __cplusplus + typedef ::std::complex< float > __pyx_t_float_complex; + #else + typedef float _Complex __pyx_t_float_complex; + #endif +#else + typedef struct { float real, imag; } __pyx_t_float_complex; +#endif +static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float, float); + +/* Declarations.proto */ +#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #ifdef __cplusplus + typedef ::std::complex< double > __pyx_t_double_complex; + #else + typedef double _Complex __pyx_t_double_complex; + #endif +#else + typedef struct { double real, imag; } __pyx_t_double_complex; +#endif +static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double, double); + +/* #### Code section: type_declarations ### */ + +/*--- Type declarations ---*/ +struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython; +struct __pyx_array_obj; +struct __pyx_MemviewEnum_obj; +struct __pyx_memoryview_obj; +struct __pyx_memoryviewslice_obj; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":767 + * ctypedef npy_longdouble longdouble_t + * + * ctypedef npy_cfloat cfloat_t # <<<<<<<<<<<<<< + * ctypedef npy_cdouble cdouble_t + * ctypedef npy_clongdouble clongdouble_t + */ +typedef npy_cfloat __pyx_t_5numpy_cfloat_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":768 + * + * ctypedef npy_cfloat cfloat_t + * ctypedef npy_cdouble cdouble_t # <<<<<<<<<<<<<< + * ctypedef npy_clongdouble clongdouble_t + * + */ +typedef npy_cdouble __pyx_t_5numpy_cdouble_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":769 + * ctypedef npy_cfloat cfloat_t + * ctypedef npy_cdouble cdouble_t + * ctypedef npy_clongdouble clongdouble_t # <<<<<<<<<<<<<< + * + * ctypedef npy_cdouble complex_t + */ +typedef npy_clongdouble __pyx_t_5numpy_clongdouble_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":771 + * ctypedef npy_clongdouble clongdouble_t + * + * ctypedef npy_cdouble complex_t # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew1(a): + */ +typedef npy_cdouble __pyx_t_5numpy_complex_t; + +/* "acados_template/acados_ocp_solver_pyx.pyx":49 + * + * + * cdef class AcadosOcpSolverCython: # <<<<<<<<<<<<<< + * """ + * Class to interact with the acados ocp solver C object. + */ +struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython { + PyObject_HEAD + lat_solver_capsule *capsule; + void *nlp_opts; + ocp_nlp_dims *nlp_dims; + ocp_nlp_config *nlp_config; + ocp_nlp_out *nlp_out; + ocp_nlp_out *sens_out; + ocp_nlp_in *nlp_in; + ocp_nlp_solver *nlp_solver; + int solver_created; + PyObject *model_name; + int N; + PyObject *nlp_solver_type; +}; + + +/* "View.MemoryView":114 + * @cython.collection_type("sequence") + * @cname("__pyx_array") + * cdef class array: # <<<<<<<<<<<<<< + * + * cdef: + */ +struct __pyx_array_obj { + PyObject_HEAD + struct __pyx_vtabstruct_array *__pyx_vtab; + char *data; + Py_ssize_t len; + char *format; + int ndim; + Py_ssize_t *_shape; + Py_ssize_t *_strides; + Py_ssize_t itemsize; + PyObject *mode; + PyObject *_format; + void (*callback_free_data)(void *); + int free_data; + int dtype_is_object; +}; + + +/* "View.MemoryView":302 + * + * @cname('__pyx_MemviewEnum') + * cdef class Enum(object): # <<<<<<<<<<<<<< + * cdef object name + * def __init__(self, name): + */ +struct __pyx_MemviewEnum_obj { + PyObject_HEAD + PyObject *name; +}; + + +/* "View.MemoryView":337 + * + * @cname('__pyx_memoryview') + * cdef class memoryview: # <<<<<<<<<<<<<< + * + * cdef object obj + */ +struct __pyx_memoryview_obj { + PyObject_HEAD + struct __pyx_vtabstruct_memoryview *__pyx_vtab; + PyObject *obj; + PyObject *_size; + PyObject *_array_interface; + PyThread_type_lock lock; + __pyx_atomic_int_type acquisition_count; + Py_buffer view; + int flags; + int dtype_is_object; + __Pyx_TypeInfo *typeinfo; +}; + + +/* "View.MemoryView":952 + * @cython.collection_type("sequence") + * @cname('__pyx_memoryviewslice') + * cdef class _memoryviewslice(memoryview): # <<<<<<<<<<<<<< + * "Internal class for passing memoryview slices to Python" + * + */ +struct __pyx_memoryviewslice_obj { + struct __pyx_memoryview_obj __pyx_base; + __Pyx_memviewslice from_slice; + PyObject *from_object; + PyObject *(*to_object_func)(char *); + int (*to_dtype_func)(char *, PyObject *); +}; + + + +/* "View.MemoryView":114 + * @cython.collection_type("sequence") + * @cname("__pyx_array") + * cdef class array: # <<<<<<<<<<<<<< + * + * cdef: + */ + +struct __pyx_vtabstruct_array { + PyObject *(*get_memview)(struct __pyx_array_obj *); +}; +static struct __pyx_vtabstruct_array *__pyx_vtabptr_array; + + +/* "View.MemoryView":337 + * + * @cname('__pyx_memoryview') + * cdef class memoryview: # <<<<<<<<<<<<<< + * + * cdef object obj + */ + +struct __pyx_vtabstruct_memoryview { + char *(*get_item_pointer)(struct __pyx_memoryview_obj *, PyObject *); + PyObject *(*is_slice)(struct __pyx_memoryview_obj *, PyObject *); + PyObject *(*setitem_slice_assignment)(struct __pyx_memoryview_obj *, PyObject *, PyObject *); + PyObject *(*setitem_slice_assign_scalar)(struct __pyx_memoryview_obj *, struct __pyx_memoryview_obj *, PyObject *); + PyObject *(*setitem_indexed)(struct __pyx_memoryview_obj *, PyObject *, PyObject *); + PyObject *(*convert_item_to_object)(struct __pyx_memoryview_obj *, char *); + PyObject *(*assign_item_from_object)(struct __pyx_memoryview_obj *, char *, PyObject *); + PyObject *(*_get_base)(struct __pyx_memoryview_obj *); +}; +static struct __pyx_vtabstruct_memoryview *__pyx_vtabptr_memoryview; + + +/* "View.MemoryView":952 + * @cython.collection_type("sequence") + * @cname('__pyx_memoryviewslice') + * cdef class _memoryviewslice(memoryview): # <<<<<<<<<<<<<< + * "Internal class for passing memoryview slices to Python" + * + */ + +struct __pyx_vtabstruct__memoryviewslice { + struct __pyx_vtabstruct_memoryview __pyx_base; +}; +static struct __pyx_vtabstruct__memoryviewslice *__pyx_vtabptr__memoryviewslice; +/* #### Code section: utility_code_proto ### */ + +/* --- Runtime support code (head) --- */ +/* Refnanny.proto */ +#ifndef CYTHON_REFNANNY + #define CYTHON_REFNANNY 0 +#endif +#if CYTHON_REFNANNY + typedef struct { + void (*INCREF)(void*, PyObject*, Py_ssize_t); + void (*DECREF)(void*, PyObject*, Py_ssize_t); + void (*GOTREF)(void*, PyObject*, Py_ssize_t); + void (*GIVEREF)(void*, PyObject*, Py_ssize_t); + void* (*SetupContext)(const char*, Py_ssize_t, const char*); + void (*FinishContext)(void**); + } __Pyx_RefNannyAPIStruct; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNanny = NULL; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname); + #define __Pyx_RefNannyDeclarations void *__pyx_refnanny = NULL; +#ifdef WITH_THREAD + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + if (acquire_gil) {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + PyGILState_Release(__pyx_gilstate_save);\ + } else {\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + } + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } +#else + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__)) + #define __Pyx_RefNannyFinishContextNogil() __Pyx_RefNannyFinishContext() +#endif + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } + #define __Pyx_RefNannyFinishContext()\ + __Pyx_RefNanny->FinishContext(&__pyx_refnanny) + #define __Pyx_INCREF(r) __Pyx_RefNanny->INCREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_DECREF(r) __Pyx_RefNanny->DECREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GOTREF(r) __Pyx_RefNanny->GOTREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GIVEREF(r) __Pyx_RefNanny->GIVEREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_XINCREF(r) do { if((r) == NULL); else {__Pyx_INCREF(r); }} while(0) + #define __Pyx_XDECREF(r) do { if((r) == NULL); else {__Pyx_DECREF(r); }} while(0) + #define __Pyx_XGOTREF(r) do { if((r) == NULL); else {__Pyx_GOTREF(r); }} while(0) + #define __Pyx_XGIVEREF(r) do { if((r) == NULL); else {__Pyx_GIVEREF(r);}} while(0) +#else + #define __Pyx_RefNannyDeclarations + #define __Pyx_RefNannySetupContext(name, acquire_gil) + #define __Pyx_RefNannyFinishContextNogil() + #define __Pyx_RefNannyFinishContext() + #define __Pyx_INCREF(r) Py_INCREF(r) + #define __Pyx_DECREF(r) Py_DECREF(r) + #define __Pyx_GOTREF(r) + #define __Pyx_GIVEREF(r) + #define __Pyx_XINCREF(r) Py_XINCREF(r) + #define __Pyx_XDECREF(r) Py_XDECREF(r) + #define __Pyx_XGOTREF(r) + #define __Pyx_XGIVEREF(r) +#endif +#define __Pyx_Py_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; Py_XDECREF(tmp);\ + } while (0) +#define __Pyx_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_XDECREF(tmp);\ + } while (0) +#define __Pyx_DECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_DECREF(tmp);\ + } while (0) +#define __Pyx_CLEAR(r) do { PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);} while(0) +#define __Pyx_XCLEAR(r) do { if((r) != NULL) {PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);}} while(0) + +/* PyErrExceptionMatches.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_ExceptionMatches(err) __Pyx_PyErr_ExceptionMatchesInState(__pyx_tstate, err) +static CYTHON_INLINE int __Pyx_PyErr_ExceptionMatchesInState(PyThreadState* tstate, PyObject* err); +#else +#define __Pyx_PyErr_ExceptionMatches(err) PyErr_ExceptionMatches(err) +#endif + +/* PyThreadStateGet.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyThreadState_declare PyThreadState *__pyx_tstate; +#define __Pyx_PyThreadState_assign __pyx_tstate = __Pyx_PyThreadState_Current; +#if PY_VERSION_HEX >= 0x030C00A6 +#define __Pyx_PyErr_Occurred() (__pyx_tstate->current_exception != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->current_exception ? (PyObject*) Py_TYPE(__pyx_tstate->current_exception) : (PyObject*) NULL) +#else +#define __Pyx_PyErr_Occurred() (__pyx_tstate->curexc_type != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->curexc_type) +#endif +#else +#define __Pyx_PyThreadState_declare +#define __Pyx_PyThreadState_assign +#define __Pyx_PyErr_Occurred() (PyErr_Occurred() != NULL) +#define __Pyx_PyErr_CurrentExceptionType() PyErr_Occurred() +#endif + +/* PyErrFetchRestore.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_Clear() __Pyx_ErrRestore(NULL, NULL, NULL) +#define __Pyx_ErrRestoreWithState(type, value, tb) __Pyx_ErrRestoreInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) __Pyx_ErrFetchInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) __Pyx_ErrRestoreInState(__pyx_tstate, type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) __Pyx_ErrFetchInState(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb); +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A6 +#define __Pyx_PyErr_SetNone(exc) (Py_INCREF(exc), __Pyx_ErrRestore((exc), NULL, NULL)) +#else +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#endif +#else +#define __Pyx_PyErr_Clear() PyErr_Clear() +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#define __Pyx_ErrRestoreWithState(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestoreInState(tstate, type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchInState(tstate, type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) PyErr_Fetch(type, value, tb) +#endif + +/* PyObjectGetAttrStr.proto */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GetAttrStr(o,n) PyObject_GetAttr(o,n) +#endif + +/* PyObjectGetAttrStrNoError.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name); + +/* GetBuiltinName.proto */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name); + +/* TupleAndListFromArray.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n); +static CYTHON_INLINE PyObject* __Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n); +#endif + +/* IncludeStringH.proto */ +#include + +/* BytesEquals.proto */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals); + +/* UnicodeEquals.proto */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals); + +/* fastcall.proto */ +#if CYTHON_AVOID_BORROWED_REFS + #define __Pyx_Arg_VARARGS(args, i) PySequence_GetItem(args, i) +#elif CYTHON_ASSUME_SAFE_MACROS + #define __Pyx_Arg_VARARGS(args, i) PyTuple_GET_ITEM(args, i) +#else + #define __Pyx_Arg_VARARGS(args, i) PyTuple_GetItem(args, i) +#endif +#if CYTHON_AVOID_BORROWED_REFS + #define __Pyx_Arg_NewRef_VARARGS(arg) __Pyx_NewRef(arg) + #define __Pyx_Arg_XDECREF_VARARGS(arg) Py_XDECREF(arg) +#else + #define __Pyx_Arg_NewRef_VARARGS(arg) arg + #define __Pyx_Arg_XDECREF_VARARGS(arg) +#endif +#define __Pyx_NumKwargs_VARARGS(kwds) PyDict_Size(kwds) +#define __Pyx_KwValues_VARARGS(args, nargs) NULL +#define __Pyx_GetKwValue_VARARGS(kw, kwvalues, s) __Pyx_PyDict_GetItemStrWithError(kw, s) +#define __Pyx_KwargsAsDict_VARARGS(kw, kwvalues) PyDict_Copy(kw) +#if CYTHON_METH_FASTCALL + #define __Pyx_Arg_FASTCALL(args, i) args[i] + #define __Pyx_NumKwargs_FASTCALL(kwds) PyTuple_GET_SIZE(kwds) + #define __Pyx_KwValues_FASTCALL(args, nargs) ((args) + (nargs)) + static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 + CYTHON_UNUSED static PyObject *__Pyx_KwargsAsDict_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues); + #else + #define __Pyx_KwargsAsDict_FASTCALL(kw, kwvalues) _PyStack_AsDict(kwvalues, kw) + #endif + #define __Pyx_Arg_NewRef_FASTCALL(arg) arg /* no-op, __Pyx_Arg_FASTCALL is direct and this needs + to have the same reference counting */ + #define __Pyx_Arg_XDECREF_FASTCALL(arg) +#else + #define __Pyx_Arg_FASTCALL __Pyx_Arg_VARARGS + #define __Pyx_NumKwargs_FASTCALL __Pyx_NumKwargs_VARARGS + #define __Pyx_KwValues_FASTCALL __Pyx_KwValues_VARARGS + #define __Pyx_GetKwValue_FASTCALL __Pyx_GetKwValue_VARARGS + #define __Pyx_KwargsAsDict_FASTCALL __Pyx_KwargsAsDict_VARARGS + #define __Pyx_Arg_NewRef_FASTCALL(arg) __Pyx_Arg_NewRef_VARARGS(arg) + #define __Pyx_Arg_XDECREF_FASTCALL(arg) __Pyx_Arg_XDECREF_VARARGS(arg) +#endif +#if CYTHON_COMPILING_IN_CPYTHON && CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_VARARGS(args, start), stop - start) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_FASTCALL(args, start), stop - start) +#else +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) PyTuple_GetSlice(args, start, stop) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) PyTuple_GetSlice(args, start, stop) +#endif + +/* RaiseArgTupleInvalid.proto */ +static void __Pyx_RaiseArgtupleInvalid(const char* func_name, int exact, + Py_ssize_t num_min, Py_ssize_t num_max, Py_ssize_t num_found); + +/* RaiseDoubleKeywords.proto */ +static void __Pyx_RaiseDoubleKeywordsError(const char* func_name, PyObject* kw_name); + +/* ParseKeywords.proto */ +static int __Pyx_ParseOptionalKeywords(PyObject *kwds, PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, PyObject *values[], Py_ssize_t num_pos_args, + const char* function_name); + +/* ArgTypeTest.proto */ +#define __Pyx_ArgTypeTest(obj, type, none_allowed, name, exact)\ + ((likely(__Pyx_IS_TYPE(obj, type) | (none_allowed && (obj == Py_None)))) ? 1 :\ + __Pyx__ArgTypeTest(obj, type, name, exact)) +static int __Pyx__ArgTypeTest(PyObject *obj, PyTypeObject *type, const char *name, int exact); + +/* RaiseException.proto */ +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause); + +/* PyFunctionFastCall.proto */ +#if CYTHON_FAST_PYCALL +#if !CYTHON_VECTORCALL +#define __Pyx_PyFunction_FastCall(func, args, nargs)\ + __Pyx_PyFunction_FastCallDict((func), (args), (nargs), NULL) +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs); +#endif +#define __Pyx_BUILD_ASSERT_EXPR(cond)\ + (sizeof(char [1 - 2*!(cond)]) - 1) +#ifndef Py_MEMBER_SIZE +#define Py_MEMBER_SIZE(type, member) sizeof(((type *)0)->member) +#endif +#if !CYTHON_VECTORCALL +#if PY_VERSION_HEX >= 0x03080000 + #include "frameobject.h" +#if PY_VERSION_HEX >= 0x030b00a6 && !CYTHON_COMPILING_IN_LIMITED_API + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif + #define __Pxy_PyFrame_Initialize_Offsets() + #define __Pyx_PyFrame_GetLocalsplus(frame) ((frame)->f_localsplus) +#else + static size_t __pyx_pyframe_localsplus_offset = 0; + #include "frameobject.h" + #define __Pxy_PyFrame_Initialize_Offsets()\ + ((void)__Pyx_BUILD_ASSERT_EXPR(sizeof(PyFrameObject) == offsetof(PyFrameObject, f_localsplus) + Py_MEMBER_SIZE(PyFrameObject, f_localsplus)),\ + (void)(__pyx_pyframe_localsplus_offset = ((size_t)PyFrame_Type.tp_basicsize) - Py_MEMBER_SIZE(PyFrameObject, f_localsplus))) + #define __Pyx_PyFrame_GetLocalsplus(frame)\ + (assert(__pyx_pyframe_localsplus_offset), (PyObject **)(((char *)(frame)) + __pyx_pyframe_localsplus_offset)) +#endif +#endif +#endif + +/* PyObjectCall.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw); +#else +#define __Pyx_PyObject_Call(func, arg, kw) PyObject_Call(func, arg, kw) +#endif + +/* PyObjectCallMethO.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg); +#endif + +/* PyObjectFastCall.proto */ +#define __Pyx_PyObject_FastCall(func, args, nargs) __Pyx_PyObject_FastCallDict(func, args, (size_t)(nargs), NULL) +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs); + +/* RaiseUnexpectedTypeError.proto */ +static int __Pyx_RaiseUnexpectedTypeError(const char *expected, PyObject *obj); + +/* GCCDiagnostics.proto */ +#if !defined(__INTEL_COMPILER) && defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 6)) +#define __Pyx_HAS_GCC_DIAGNOSTIC +#endif + +/* BuildPyUnicode.proto */ +static PyObject* __Pyx_PyUnicode_BuildFromAscii(Py_ssize_t ulength, char* chars, int clength, + int prepend_sign, char padding_char); + +/* CIntToPyUnicode.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_int(int value, Py_ssize_t width, char padding_char, char format_char); + +/* CIntToPyUnicode.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_Py_ssize_t(Py_ssize_t value, Py_ssize_t width, char padding_char, char format_char); + +/* JoinPyUnicode.proto */ +static PyObject* __Pyx_PyUnicode_Join(PyObject* value_tuple, Py_ssize_t value_count, Py_ssize_t result_ulength, + Py_UCS4 max_char); + +/* StrEquals.proto */ +#if PY_MAJOR_VERSION >= 3 +#define __Pyx_PyString_Equals __Pyx_PyUnicode_Equals +#else +#define __Pyx_PyString_Equals __Pyx_PyBytes_Equals +#endif + +/* PyObjectFormatSimple.proto */ +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + PyObject_Format(s, f)) +#elif PY_MAJOR_VERSION < 3 + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + likely(PyString_CheckExact(s)) ? PyUnicode_FromEncodedObject(s, NULL, "strict") :\ + PyObject_Format(s, f)) +#elif CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + likely(PyLong_CheckExact(s)) ? PyLong_Type.tp_repr(s) :\ + likely(PyFloat_CheckExact(s)) ? PyFloat_Type.tp_repr(s) :\ + PyObject_Format(s, f)) +#else + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + PyObject_Format(s, f)) +#endif + +CYTHON_UNUSED static int __pyx_array_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +static PyObject *__pyx_array_get_memview(struct __pyx_array_obj *); /*proto*/ +/* GetAttr.proto */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr(PyObject *, PyObject *); + +/* GetItemInt.proto */ +#define __Pyx_GetItemInt(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_Fast(o, (Py_ssize_t)i, is_list, wraparound, boundscheck) :\ + (is_list ? (PyErr_SetString(PyExc_IndexError, "list index out of range"), (PyObject*)NULL) :\ + __Pyx_GetItemInt_Generic(o, to_py_func(i)))) +#define __Pyx_GetItemInt_List(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_List_Fast(o, (Py_ssize_t)i, wraparound, boundscheck) :\ + (PyErr_SetString(PyExc_IndexError, "list index out of range"), (PyObject*)NULL)) +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_List_Fast(PyObject *o, Py_ssize_t i, + int wraparound, int boundscheck); +#define __Pyx_GetItemInt_Tuple(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_Tuple_Fast(o, (Py_ssize_t)i, wraparound, boundscheck) :\ + (PyErr_SetString(PyExc_IndexError, "tuple index out of range"), (PyObject*)NULL)) +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Tuple_Fast(PyObject *o, Py_ssize_t i, + int wraparound, int boundscheck); +static PyObject *__Pyx_GetItemInt_Generic(PyObject *o, PyObject* j); +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Fast(PyObject *o, Py_ssize_t i, + int is_list, int wraparound, int boundscheck); + +/* PyObjectCallOneArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg); + +/* ObjectGetItem.proto */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject *__Pyx_PyObject_GetItem(PyObject *obj, PyObject *key); +#else +#define __Pyx_PyObject_GetItem(obj, key) PyObject_GetItem(obj, key) +#endif + +/* KeywordStringCheck.proto */ +static int __Pyx_CheckKeywordStrings(PyObject *kw, const char* function_name, int kw_allowed); + +/* DivInt[Py_ssize_t].proto */ +static CYTHON_INLINE Py_ssize_t __Pyx_div_Py_ssize_t(Py_ssize_t, Py_ssize_t); + +/* UnaryNegOverflows.proto */ +#define __Pyx_UNARY_NEG_WOULD_OVERFLOW(x)\ + (((x) < 0) & ((unsigned long)(x) == 0-(unsigned long)(x))) + +/* GetAttr3.proto */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr3(PyObject *, PyObject *, PyObject *); + +/* PyDictVersioning.proto */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +#define __PYX_DICT_VERSION_INIT ((PY_UINT64_T) -1) +#define __PYX_GET_DICT_VERSION(dict) (((PyDictObject*)(dict))->ma_version_tag) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var)\ + (version_var) = __PYX_GET_DICT_VERSION(dict);\ + (cache_var) = (value); +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + if (likely(__PYX_GET_DICT_VERSION(DICT) == __pyx_dict_version)) {\ + (VAR) = __pyx_dict_cached_value;\ + } else {\ + (VAR) = __pyx_dict_cached_value = (LOOKUP);\ + __pyx_dict_version = __PYX_GET_DICT_VERSION(DICT);\ + }\ +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj); +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj); +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version); +#else +#define __PYX_GET_DICT_VERSION(dict) (0) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var) +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) (VAR) = (LOOKUP); +#endif + +/* GetModuleGlobalName.proto */ +#if CYTHON_USE_DICT_VERSIONS +#define __Pyx_GetModuleGlobalName(var, name) do {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + (var) = (likely(__pyx_dict_version == __PYX_GET_DICT_VERSION(__pyx_d))) ?\ + (likely(__pyx_dict_cached_value) ? __Pyx_NewRef(__pyx_dict_cached_value) : __Pyx_GetBuiltinName(name)) :\ + __Pyx__GetModuleGlobalName(name, &__pyx_dict_version, &__pyx_dict_cached_value);\ +} while(0) +#define __Pyx_GetModuleGlobalNameUncached(var, name) do {\ + PY_UINT64_T __pyx_dict_version;\ + PyObject *__pyx_dict_cached_value;\ + (var) = __Pyx__GetModuleGlobalName(name, &__pyx_dict_version, &__pyx_dict_cached_value);\ +} while(0) +static PyObject *__Pyx__GetModuleGlobalName(PyObject *name, PY_UINT64_T *dict_version, PyObject **dict_cached_value); +#else +#define __Pyx_GetModuleGlobalName(var, name) (var) = __Pyx__GetModuleGlobalName(name) +#define __Pyx_GetModuleGlobalNameUncached(var, name) (var) = __Pyx__GetModuleGlobalName(name) +static CYTHON_INLINE PyObject *__Pyx__GetModuleGlobalName(PyObject *name); +#endif + +/* AssertionsEnabled.proto */ +#if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX < 0x02070600 && !defined(Py_OptimizeFlag) + #define __Pyx_init_assertions_enabled() (0) + #define __pyx_assertions_enabled() (1) +#elif CYTHON_COMPILING_IN_LIMITED_API || (CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030C0000) + static int __pyx_assertions_enabled_flag; + #define __pyx_assertions_enabled() (__pyx_assertions_enabled_flag) + static int __Pyx_init_assertions_enabled(void) { + PyObject *builtins, *debug, *debug_str; + int flag; + builtins = PyEval_GetBuiltins(); + if (!builtins) goto bad; + debug_str = PyUnicode_FromStringAndSize("__debug__", 9); + if (!debug_str) goto bad; + debug = PyObject_GetItem(builtins, debug_str); + Py_DECREF(debug_str); + if (!debug) goto bad; + flag = PyObject_IsTrue(debug); + Py_DECREF(debug); + if (flag == -1) goto bad; + __pyx_assertions_enabled_flag = flag; + return 0; + bad: + __pyx_assertions_enabled_flag = 1; + return -1; + } +#else + #define __Pyx_init_assertions_enabled() (0) + #define __pyx_assertions_enabled() (!Py_OptimizeFlag) +#endif + +/* RaiseTooManyValuesToUnpack.proto */ +static CYTHON_INLINE void __Pyx_RaiseTooManyValuesError(Py_ssize_t expected); + +/* RaiseNeedMoreValuesToUnpack.proto */ +static CYTHON_INLINE void __Pyx_RaiseNeedMoreValuesError(Py_ssize_t index); + +/* RaiseNoneIterError.proto */ +static CYTHON_INLINE void __Pyx_RaiseNoneNotIterableError(void); + +/* ExtTypeTest.proto */ +static CYTHON_INLINE int __Pyx_TypeTest(PyObject *obj, PyTypeObject *type); + +/* GetTopmostException.proto */ +#if CYTHON_USE_EXC_INFO_STACK && CYTHON_FAST_THREAD_STATE +static _PyErr_StackItem * __Pyx_PyErr_GetTopmostException(PyThreadState *tstate); +#endif + +/* SaveResetException.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_ExceptionSave(type, value, tb) __Pyx__ExceptionSave(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx__ExceptionSave(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#define __Pyx_ExceptionReset(type, value, tb) __Pyx__ExceptionReset(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx__ExceptionReset(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb); +#else +#define __Pyx_ExceptionSave(type, value, tb) PyErr_GetExcInfo(type, value, tb) +#define __Pyx_ExceptionReset(type, value, tb) PyErr_SetExcInfo(type, value, tb) +#endif + +/* GetException.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_GetException(type, value, tb) __Pyx__GetException(__pyx_tstate, type, value, tb) +static int __Pyx__GetException(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#else +static int __Pyx_GetException(PyObject **type, PyObject **value, PyObject **tb); +#endif + +/* SwapException.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_ExceptionSwap(type, value, tb) __Pyx__ExceptionSwap(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx__ExceptionSwap(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#else +static CYTHON_INLINE void __Pyx_ExceptionSwap(PyObject **type, PyObject **value, PyObject **tb); +#endif + +/* Import.proto */ +static PyObject *__Pyx_Import(PyObject *name, PyObject *from_list, int level); + +/* ImportDottedModule.proto */ +static PyObject *__Pyx_ImportDottedModule(PyObject *name, PyObject *parts_tuple); +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_ImportDottedModule_WalkParts(PyObject *module, PyObject *name, PyObject *parts_tuple); +#endif + +/* FastTypeChecks.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_TypeCheck(obj, type) __Pyx_IsSubtype(Py_TYPE(obj), (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) __Pyx_IsAnySubtype2(Py_TYPE(obj), (PyTypeObject *)type1, (PyTypeObject *)type2) +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches(PyObject *err, PyObject *type); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches2(PyObject *err, PyObject *type1, PyObject *type2); +#else +#define __Pyx_TypeCheck(obj, type) PyObject_TypeCheck(obj, (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) (PyObject_TypeCheck(obj, (PyTypeObject *)type1) || PyObject_TypeCheck(obj, (PyTypeObject *)type2)) +#define __Pyx_PyErr_GivenExceptionMatches(err, type) PyErr_GivenExceptionMatches(err, type) +#define __Pyx_PyErr_GivenExceptionMatches2(err, type1, type2) (PyErr_GivenExceptionMatches(err, type1) || PyErr_GivenExceptionMatches(err, type2)) +#endif +#define __Pyx_PyErr_ExceptionMatches2(err1, err2) __Pyx_PyErr_GivenExceptionMatches2(__Pyx_PyErr_CurrentExceptionType(), err1, err2) +#define __Pyx_PyException_Check(obj) __Pyx_TypeCheck(obj, PyExc_Exception) + +CYTHON_UNUSED static int __pyx_memoryview_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +/* ListCompAppend.proto */ +#if CYTHON_USE_PYLIST_INTERNALS && CYTHON_ASSUME_SAFE_MACROS +static CYTHON_INLINE int __Pyx_ListComp_Append(PyObject* list, PyObject* x) { + PyListObject* L = (PyListObject*) list; + Py_ssize_t len = Py_SIZE(list); + if (likely(L->allocated > len)) { + Py_INCREF(x); + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 + L->ob_item[len] = x; + #else + PyList_SET_ITEM(list, len, x); + #endif + __Pyx_SET_SIZE(list, len + 1); + return 0; + } + return PyList_Append(list, x); +} +#else +#define __Pyx_ListComp_Append(L,x) PyList_Append(L,x) +#endif + +/* PySequenceMultiply.proto */ +#define __Pyx_PySequence_Multiply_Left(mul, seq) __Pyx_PySequence_Multiply(seq, mul) +static CYTHON_INLINE PyObject* __Pyx_PySequence_Multiply(PyObject *seq, Py_ssize_t mul); + +/* SetItemInt.proto */ +#define __Pyx_SetItemInt(o, i, v, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_SetItemInt_Fast(o, (Py_ssize_t)i, v, is_list, wraparound, boundscheck) :\ + (is_list ? (PyErr_SetString(PyExc_IndexError, "list assignment index out of range"), -1) :\ + __Pyx_SetItemInt_Generic(o, to_py_func(i), v))) +static int __Pyx_SetItemInt_Generic(PyObject *o, PyObject *j, PyObject *v); +static CYTHON_INLINE int __Pyx_SetItemInt_Fast(PyObject *o, Py_ssize_t i, PyObject *v, + int is_list, int wraparound, int boundscheck); + +/* RaiseUnboundLocalError.proto */ +static CYTHON_INLINE void __Pyx_RaiseUnboundLocalError(const char *varname); + +/* DivInt[long].proto */ +static CYTHON_INLINE long __Pyx_div_long(long, long); + +/* PySequenceContains.proto */ +static CYTHON_INLINE int __Pyx_PySequence_ContainsTF(PyObject* item, PyObject* seq, int eq) { + int result = PySequence_Contains(seq, item); + return unlikely(result < 0) ? result : (result == (eq == Py_EQ)); +} + +/* ImportFrom.proto */ +static PyObject* __Pyx_ImportFrom(PyObject* module, PyObject* name); + +/* HasAttr.proto */ +#if __PYX_LIMITED_VERSION_HEX >= 0x030d00A1 +#define __Pyx_HasAttr(o, n) PyObject_HasAttrWithError(o, n) +#else +static CYTHON_INLINE int __Pyx_HasAttr(PyObject *, PyObject *); +#endif + +/* PyIntCompare.proto */ +static CYTHON_INLINE int __Pyx_PyInt_BoolEqObjC(PyObject *op1, PyObject *op2, long intval, long inplace); + +/* PyIntCompare.proto */ +static CYTHON_INLINE int __Pyx_PyInt_BoolNeObjC(PyObject *op1, PyObject *op2, long intval, long inplace); + +/* IsLittleEndian.proto */ +static CYTHON_INLINE int __Pyx_Is_Little_Endian(void); + +/* BufferFormatCheck.proto */ +static const char* __Pyx_BufFmt_CheckString(__Pyx_BufFmt_Context* ctx, const char* ts); +static void __Pyx_BufFmt_Init(__Pyx_BufFmt_Context* ctx, + __Pyx_BufFmt_StackElem* stack, + __Pyx_TypeInfo* type); + +/* BufferGetAndValidate.proto */ +#define __Pyx_GetBufferAndValidate(buf, obj, dtype, flags, nd, cast, stack)\ + ((obj == Py_None || obj == NULL) ?\ + (__Pyx_ZeroBuffer(buf), 0) :\ + __Pyx__GetBufferAndValidate(buf, obj, dtype, flags, nd, cast, stack)) +static int __Pyx__GetBufferAndValidate(Py_buffer* buf, PyObject* obj, + __Pyx_TypeInfo* dtype, int flags, int nd, int cast, __Pyx_BufFmt_StackElem* stack); +static void __Pyx_ZeroBuffer(Py_buffer* buf); +static CYTHON_INLINE void __Pyx_SafeReleaseBuffer(Py_buffer* info); +static Py_ssize_t __Pyx_minusones[] = { -1, -1, -1, -1, -1, -1, -1, -1 }; +static Py_ssize_t __Pyx_zeros[] = { 0, 0, 0, 0, 0, 0, 0, 0 }; + +/* UnicodeConcatInPlace.proto */ +# if CYTHON_COMPILING_IN_CPYTHON && PY_MAJOR_VERSION >= 3 + #if CYTHON_REFNANNY + #define __Pyx_PyUnicode_ConcatInPlace(left, right) __Pyx_PyUnicode_ConcatInPlaceImpl(&left, right, __pyx_refnanny) + #else + #define __Pyx_PyUnicode_ConcatInPlace(left, right) __Pyx_PyUnicode_ConcatInPlaceImpl(&left, right) + #endif + static CYTHON_INLINE PyObject *__Pyx_PyUnicode_ConcatInPlaceImpl(PyObject **p_left, PyObject *right + #if CYTHON_REFNANNY + , void* __pyx_refnanny + #endif + ); +#else +#define __Pyx_PyUnicode_ConcatInPlace __Pyx_PyUnicode_Concat +#endif +#define __Pyx_PyUnicode_ConcatInPlaceSafe(left, right) ((unlikely((left) == Py_None) || unlikely((right) == Py_None)) ?\ + PyNumber_InPlaceAdd(left, right) : __Pyx_PyUnicode_ConcatInPlace(left, right)) + +/* SliceObject.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetSlice( + PyObject* obj, Py_ssize_t cstart, Py_ssize_t cstop, + PyObject** py_start, PyObject** py_stop, PyObject** py_slice, + int has_cstart, int has_cstop, int wraparound); + +/* PyObject_Str.proto */ +#define __Pyx_PyObject_Str(obj)\ + (likely(PyString_CheckExact(obj)) ? __Pyx_NewRef(obj) : PyObject_Str(obj)) + +/* PyObjectFormat.proto */ +#if CYTHON_USE_UNICODE_WRITER +static PyObject* __Pyx_PyObject_Format(PyObject* s, PyObject* f); +#else +#define __Pyx_PyObject_Format(s, f) PyObject_Format(s, f) +#endif + +/* py_dict_keys.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyDict_Keys(PyObject* d); + +/* UnpackUnboundCMethod.proto */ +typedef struct { + PyObject *type; + PyObject **method_name; + PyCFunction func; + PyObject *method; + int flag; +} __Pyx_CachedCFunction; + +/* CallUnboundCMethod0.proto */ +static PyObject* __Pyx__CallUnboundCMethod0(__Pyx_CachedCFunction* cfunc, PyObject* self); +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_CallUnboundCMethod0(cfunc, self)\ + (likely((cfunc)->func) ?\ + (likely((cfunc)->flag == METH_NOARGS) ? (*((cfunc)->func))(self, NULL) :\ + (PY_VERSION_HEX >= 0x030600B1 && likely((cfunc)->flag == METH_FASTCALL) ?\ + (PY_VERSION_HEX >= 0x030700A0 ?\ + (*(__Pyx_PyCFunctionFast)(void*)(PyCFunction)(cfunc)->func)(self, &__pyx_empty_tuple, 0) :\ + (*(__Pyx_PyCFunctionFastWithKeywords)(void*)(PyCFunction)(cfunc)->func)(self, &__pyx_empty_tuple, 0, NULL)) :\ + (PY_VERSION_HEX >= 0x030700A0 && (cfunc)->flag == (METH_FASTCALL | METH_KEYWORDS) ?\ + (*(__Pyx_PyCFunctionFastWithKeywords)(void*)(PyCFunction)(cfunc)->func)(self, &__pyx_empty_tuple, 0, NULL) :\ + (likely((cfunc)->flag == (METH_VARARGS | METH_KEYWORDS)) ? ((*(PyCFunctionWithKeywords)(void*)(PyCFunction)(cfunc)->func)(self, __pyx_empty_tuple, NULL)) :\ + ((cfunc)->flag == METH_VARARGS ? (*((cfunc)->func))(self, __pyx_empty_tuple) :\ + __Pyx__CallUnboundCMethod0(cfunc, self)))))) :\ + __Pyx__CallUnboundCMethod0(cfunc, self)) +#else +#define __Pyx_CallUnboundCMethod0(cfunc, self) __Pyx__CallUnboundCMethod0(cfunc, self) +#endif + +/* DictGetItem.proto */ +#if PY_MAJOR_VERSION >= 3 && !CYTHON_COMPILING_IN_PYPY +static PyObject *__Pyx_PyDict_GetItem(PyObject *d, PyObject* key); +#define __Pyx_PyObject_Dict_GetItem(obj, name)\ + (likely(PyDict_CheckExact(obj)) ?\ + __Pyx_PyDict_GetItem(obj, name) : PyObject_GetItem(obj, name)) +#else +#define __Pyx_PyDict_GetItem(d, key) PyObject_GetItem(d, key) +#define __Pyx_PyObject_Dict_GetItem(obj, name) PyObject_GetItem(obj, name) +#endif + +/* PyObjectLookupSpecial.proto */ +#if CYTHON_USE_PYTYPE_LOOKUP && CYTHON_USE_TYPE_SLOTS +#define __Pyx_PyObject_LookupSpecialNoError(obj, attr_name) __Pyx__PyObject_LookupSpecial(obj, attr_name, 0) +#define __Pyx_PyObject_LookupSpecial(obj, attr_name) __Pyx__PyObject_LookupSpecial(obj, attr_name, 1) +static CYTHON_INLINE PyObject* __Pyx__PyObject_LookupSpecial(PyObject* obj, PyObject* attr_name, int with_error); +#else +#define __Pyx_PyObject_LookupSpecialNoError(o,n) __Pyx_PyObject_GetAttrStrNoError(o,n) +#define __Pyx_PyObject_LookupSpecial(o,n) __Pyx_PyObject_GetAttrStr(o,n) +#endif + +/* IncludeStructmemberH.proto */ +#include + +/* FixUpExtensionType.proto */ +#if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type); +#endif + +/* FetchSharedCythonModule.proto */ +static PyObject *__Pyx_FetchSharedCythonABIModule(void); + +/* FetchCommonType.proto */ +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type); +#else +static PyTypeObject* __Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases); +#endif + +/* PyMethodNew.proto */ +#if CYTHON_COMPILING_IN_LIMITED_API +static PyObject *__Pyx_PyMethod_New(PyObject *func, PyObject *self, PyObject *typ) { + PyObject *typesModule=NULL, *methodType=NULL, *result=NULL; + CYTHON_UNUSED_VAR(typ); + if (!self) + return __Pyx_NewRef(func); + typesModule = PyImport_ImportModule("types"); + if (!typesModule) return NULL; + methodType = PyObject_GetAttrString(typesModule, "MethodType"); + Py_DECREF(typesModule); + if (!methodType) return NULL; + result = PyObject_CallFunctionObjArgs(methodType, func, self, NULL); + Py_DECREF(methodType); + return result; +} +#elif PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_PyMethod_New(PyObject *func, PyObject *self, PyObject *typ) { + CYTHON_UNUSED_VAR(typ); + if (!self) + return __Pyx_NewRef(func); + return PyMethod_New(func, self); +} +#else + #define __Pyx_PyMethod_New PyMethod_New +#endif + +/* PyVectorcallFastCallDict.proto */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw); +#endif + +/* CythonFunctionShared.proto */ +#define __Pyx_CyFunction_USED +#define __Pyx_CYFUNCTION_STATICMETHOD 0x01 +#define __Pyx_CYFUNCTION_CLASSMETHOD 0x02 +#define __Pyx_CYFUNCTION_CCLASS 0x04 +#define __Pyx_CYFUNCTION_COROUTINE 0x08 +#define __Pyx_CyFunction_GetClosure(f)\ + (((__pyx_CyFunctionObject *) (f))->func_closure) +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_CyFunction_GetClassObj(f)\ + (((__pyx_CyFunctionObject *) (f))->func_classobj) +#else + #define __Pyx_CyFunction_GetClassObj(f)\ + ((PyObject*) ((PyCMethodObject *) (f))->mm_class) +#endif +#define __Pyx_CyFunction_SetClassObj(f, classobj)\ + __Pyx__CyFunction_SetClassObj((__pyx_CyFunctionObject *) (f), (classobj)) +#define __Pyx_CyFunction_Defaults(type, f)\ + ((type *)(((__pyx_CyFunctionObject *) (f))->defaults)) +#define __Pyx_CyFunction_SetDefaultsGetter(f, g)\ + ((__pyx_CyFunctionObject *) (f))->defaults_getter = (g) +typedef struct { +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject_HEAD + PyObject *func; +#elif PY_VERSION_HEX < 0x030900B1 + PyCFunctionObject func; +#else + PyCMethodObject func; +#endif +#if CYTHON_BACKPORT_VECTORCALL + __pyx_vectorcallfunc func_vectorcall; +#endif +#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API + PyObject *func_weakreflist; +#endif + PyObject *func_dict; + PyObject *func_name; + PyObject *func_qualname; + PyObject *func_doc; + PyObject *func_globals; + PyObject *func_code; + PyObject *func_closure; +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + PyObject *func_classobj; +#endif + void *defaults; + int defaults_pyobjects; + size_t defaults_size; + int flags; + PyObject *defaults_tuple; + PyObject *defaults_kwdict; + PyObject *(*defaults_getter)(PyObject *); + PyObject *func_annotations; + PyObject *func_is_coroutine; +} __pyx_CyFunctionObject; +#undef __Pyx_CyOrPyCFunction_Check +#define __Pyx_CyFunction_Check(obj) __Pyx_TypeCheck(obj, __pyx_CyFunctionType) +#define __Pyx_CyOrPyCFunction_Check(obj) __Pyx_TypeCheck2(obj, __pyx_CyFunctionType, &PyCFunction_Type) +#define __Pyx_CyFunction_CheckExact(obj) __Pyx_IS_TYPE(obj, __pyx_CyFunctionType) +static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc); +#undef __Pyx_IsSameCFunction +#define __Pyx_IsSameCFunction(func, cfunc) __Pyx__IsSameCyOrCFunction(func, cfunc) +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject* op, PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj); +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *m, + size_t size, + int pyobjects); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *m, + PyObject *tuple); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *m, + PyObject *dict); +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *m, + PyObject *dict); +static int __pyx_CyFunction_init(PyObject *module); +#if CYTHON_METH_FASTCALL +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +#if CYTHON_BACKPORT_VECTORCALL +#define __Pyx_CyFunction_func_vectorcall(f) (((__pyx_CyFunctionObject*)f)->func_vectorcall) +#else +#define __Pyx_CyFunction_func_vectorcall(f) (((PyCFunctionObject*)f)->vectorcall) +#endif +#endif + +/* CythonFunction.proto */ +static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); + +/* IterFinish.proto */ +static CYTHON_INLINE int __Pyx_IterFinish(void); + +/* PyObjectCallNoArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func); + +/* PyObjectGetMethod.proto */ +static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method); + +/* PyObjectCallMethod0.proto */ +static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name); + +/* UnpackItemEndCheck.proto */ +static int __Pyx_IternextUnpackEndCheck(PyObject *retval, Py_ssize_t expected); + +/* UnpackTupleError.proto */ +static void __Pyx_UnpackTupleError(PyObject *, Py_ssize_t index); + +/* UnpackTuple2.proto */ +#define __Pyx_unpack_tuple2(tuple, value1, value2, is_tuple, has_known_size, decref_tuple)\ + (likely(is_tuple || PyTuple_Check(tuple)) ?\ + (likely(has_known_size || PyTuple_GET_SIZE(tuple) == 2) ?\ + __Pyx_unpack_tuple2_exact(tuple, value1, value2, decref_tuple) :\ + (__Pyx_UnpackTupleError(tuple, 2), -1)) :\ + __Pyx_unpack_tuple2_generic(tuple, value1, value2, has_known_size, decref_tuple)) +static CYTHON_INLINE int __Pyx_unpack_tuple2_exact( + PyObject* tuple, PyObject** value1, PyObject** value2, int decref_tuple); +static int __Pyx_unpack_tuple2_generic( + PyObject* tuple, PyObject** value1, PyObject** value2, int has_known_size, int decref_tuple); + +/* dict_iter.proto */ +static CYTHON_INLINE PyObject* __Pyx_dict_iterator(PyObject* dict, int is_dict, PyObject* method_name, + Py_ssize_t* p_orig_length, int* p_is_dict); +static CYTHON_INLINE int __Pyx_dict_iter_next(PyObject* dict_or_iter, Py_ssize_t orig_length, Py_ssize_t* ppos, + PyObject** pkey, PyObject** pvalue, PyObject** pitem, int is_dict); + +/* PyIntBinop.proto */ +#if !CYTHON_COMPILING_IN_PYPY +static PyObject* __Pyx_PyInt_AddObjC(PyObject *op1, PyObject *op2, long intval, int inplace, int zerodivision_check); +#else +#define __Pyx_PyInt_AddObjC(op1, op2, intval, inplace, zerodivision_check)\ + (inplace ? PyNumber_InPlaceAdd(op1, op2) : PyNumber_Add(op1, op2)) +#endif + +/* BufferIndexError.proto */ +static void __Pyx_RaiseBufferIndexError(int axis); + +#define __Pyx_BufPtrStrided1d(type, buf, i0, s0) (type)((char*)buf + i0 * s0) +/* PyUnicode_Unicode.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_Unicode(PyObject *obj); + +/* PyObject_GenericGetAttrNoDict.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttrNoDict PyObject_GenericGetAttr +#endif + +/* PyObject_GenericGetAttr.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttr PyObject_GenericGetAttr +#endif + +/* ValidateBasesTuple.proto */ +#if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases); +#endif + +/* PyType_Ready.proto */ +CYTHON_UNUSED static int __Pyx_PyType_Ready(PyTypeObject *t); + +/* SetupReduce.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce(PyObject* type_obj); +#endif + +/* SetVTable.proto */ +static int __Pyx_SetVtable(PyTypeObject* typeptr , void* vtable); + +/* GetVTable.proto */ +static void* __Pyx_GetVtable(PyTypeObject *type); + +/* MergeVTables.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_MergeVtables(PyTypeObject *type); +#endif + +/* TypeImport.proto */ +#ifndef __PYX_HAVE_RT_ImportType_proto_3_0_8 +#define __PYX_HAVE_RT_ImportType_proto_3_0_8 +#if defined (__STDC_VERSION__) && __STDC_VERSION__ >= 201112L +#include +#endif +#if (defined (__STDC_VERSION__) && __STDC_VERSION__ >= 201112L) || __cplusplus >= 201103L +#define __PYX_GET_STRUCT_ALIGNMENT_3_0_8(s) alignof(s) +#else +#define __PYX_GET_STRUCT_ALIGNMENT_3_0_8(s) sizeof(void*) +#endif +enum __Pyx_ImportType_CheckSize_3_0_8 { + __Pyx_ImportType_CheckSize_Error_3_0_8 = 0, + __Pyx_ImportType_CheckSize_Warn_3_0_8 = 1, + __Pyx_ImportType_CheckSize_Ignore_3_0_8 = 2 +}; +static PyTypeObject *__Pyx_ImportType_3_0_8(PyObject* module, const char *module_name, const char *class_name, size_t size, size_t alignment, enum __Pyx_ImportType_CheckSize_3_0_8 check_size); +#endif + +/* CLineInTraceback.proto */ +#ifdef CYTHON_CLINE_IN_TRACEBACK +#define __Pyx_CLineForTraceback(tstate, c_line) (((CYTHON_CLINE_IN_TRACEBACK)) ? c_line : 0) +#else +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line); +#endif + +/* CodeObjectCache.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +typedef struct { + PyCodeObject* code_object; + int code_line; +} __Pyx_CodeObjectCacheEntry; +struct __Pyx_CodeObjectCache { + int count; + int max_count; + __Pyx_CodeObjectCacheEntry* entries; +}; +static struct __Pyx_CodeObjectCache __pyx_code_cache = {0,0,NULL}; +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line); +static PyCodeObject *__pyx_find_code_object(int code_line); +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object); +#endif + +/* AddTraceback.proto */ +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename); + +#if PY_MAJOR_VERSION < 3 + static int __Pyx_GetBuffer(PyObject *obj, Py_buffer *view, int flags); + static void __Pyx_ReleaseBuffer(Py_buffer *view); +#else + #define __Pyx_GetBuffer PyObject_GetBuffer + #define __Pyx_ReleaseBuffer PyBuffer_Release +#endif + + +/* BufferStructDeclare.proto */ +typedef struct { + Py_ssize_t shape, strides, suboffsets; +} __Pyx_Buf_DimInfo; +typedef struct { + size_t refcount; + Py_buffer pybuffer; +} __Pyx_Buffer; +typedef struct { + __Pyx_Buffer *rcbuffer; + char *data; + __Pyx_Buf_DimInfo diminfo[8]; +} __Pyx_LocalBuf_ND; + +/* MemviewSliceIsContig.proto */ +static int __pyx_memviewslice_is_contig(const __Pyx_memviewslice mvs, char order, int ndim); + +/* OverlappingSlices.proto */ +static int __pyx_slices_overlap(__Pyx_memviewslice *slice1, + __Pyx_memviewslice *slice2, + int ndim, size_t itemsize); + +/* TypeInfoCompare.proto */ +static int __pyx_typeinfo_cmp(__Pyx_TypeInfo *a, __Pyx_TypeInfo *b); + +/* MemviewSliceValidateAndInit.proto */ +static int __Pyx_ValidateAndInit_memviewslice( + int *axes_specs, + int c_or_f_flag, + int buf_flags, + int ndim, + __Pyx_TypeInfo *dtype, + __Pyx_BufFmt_StackElem stack[], + __Pyx_memviewslice *memviewslice, + PyObject *original_obj); + +/* ObjectToMemviewSlice.proto */ +static CYTHON_INLINE __Pyx_memviewslice __Pyx_PyObject_to_MemoryviewSlice_dcd__double(PyObject *, int writable_flag); + +/* ObjectToMemviewSlice.proto */ +static CYTHON_INLINE __Pyx_memviewslice __Pyx_PyObject_to_MemoryviewSlice_dc_unsigned_char(PyObject *, int writable_flag); + +/* RealImag.proto */ +#if CYTHON_CCOMPLEX + #ifdef __cplusplus + #define __Pyx_CREAL(z) ((z).real()) + #define __Pyx_CIMAG(z) ((z).imag()) + #else + #define __Pyx_CREAL(z) (__real__(z)) + #define __Pyx_CIMAG(z) (__imag__(z)) + #endif +#else + #define __Pyx_CREAL(z) ((z).real) + #define __Pyx_CIMAG(z) ((z).imag) +#endif +#if defined(__cplusplus) && CYTHON_CCOMPLEX\ + && (defined(_WIN32) || defined(__clang__) || (defined(__GNUC__) && (__GNUC__ >= 5 || __GNUC__ == 4 && __GNUC_MINOR__ >= 4 )) || __cplusplus >= 201103) + #define __Pyx_SET_CREAL(z,x) ((z).real(x)) + #define __Pyx_SET_CIMAG(z,y) ((z).imag(y)) +#else + #define __Pyx_SET_CREAL(z,x) __Pyx_CREAL(z) = (x) + #define __Pyx_SET_CIMAG(z,y) __Pyx_CIMAG(z) = (y) +#endif + +/* Arithmetic.proto */ +#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #define __Pyx_c_eq_float(a, b) ((a)==(b)) + #define __Pyx_c_sum_float(a, b) ((a)+(b)) + #define __Pyx_c_diff_float(a, b) ((a)-(b)) + #define __Pyx_c_prod_float(a, b) ((a)*(b)) + #define __Pyx_c_quot_float(a, b) ((a)/(b)) + #define __Pyx_c_neg_float(a) (-(a)) + #ifdef __cplusplus + #define __Pyx_c_is_zero_float(z) ((z)==(float)0) + #define __Pyx_c_conj_float(z) (::std::conj(z)) + #if 1 + #define __Pyx_c_abs_float(z) (::std::abs(z)) + #define __Pyx_c_pow_float(a, b) (::std::pow(a, b)) + #endif + #else + #define __Pyx_c_is_zero_float(z) ((z)==0) + #define __Pyx_c_conj_float(z) (conjf(z)) + #if 1 + #define __Pyx_c_abs_float(z) (cabsf(z)) + #define __Pyx_c_pow_float(a, b) (cpowf(a, b)) + #endif + #endif +#else + static CYTHON_INLINE int __Pyx_c_eq_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_sum_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_diff_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_prod_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_quot_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_neg_float(__pyx_t_float_complex); + static CYTHON_INLINE int __Pyx_c_is_zero_float(__pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_conj_float(__pyx_t_float_complex); + #if 1 + static CYTHON_INLINE float __Pyx_c_abs_float(__pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_pow_float(__pyx_t_float_complex, __pyx_t_float_complex); + #endif +#endif + +/* Arithmetic.proto */ +#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #define __Pyx_c_eq_double(a, b) ((a)==(b)) + #define __Pyx_c_sum_double(a, b) ((a)+(b)) + #define __Pyx_c_diff_double(a, b) ((a)-(b)) + #define __Pyx_c_prod_double(a, b) ((a)*(b)) + #define __Pyx_c_quot_double(a, b) ((a)/(b)) + #define __Pyx_c_neg_double(a) (-(a)) + #ifdef __cplusplus + #define __Pyx_c_is_zero_double(z) ((z)==(double)0) + #define __Pyx_c_conj_double(z) (::std::conj(z)) + #if 1 + #define __Pyx_c_abs_double(z) (::std::abs(z)) + #define __Pyx_c_pow_double(a, b) (::std::pow(a, b)) + #endif + #else + #define __Pyx_c_is_zero_double(z) ((z)==0) + #define __Pyx_c_conj_double(z) (conj(z)) + #if 1 + #define __Pyx_c_abs_double(z) (cabs(z)) + #define __Pyx_c_pow_double(a, b) (cpow(a, b)) + #endif + #endif +#else + static CYTHON_INLINE int __Pyx_c_eq_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_sum_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_diff_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_prod_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_quot_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_neg_double(__pyx_t_double_complex); + static CYTHON_INLINE int __Pyx_c_is_zero_double(__pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_conj_double(__pyx_t_double_complex); + #if 1 + static CYTHON_INLINE double __Pyx_c_abs_double(__pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_pow_double(__pyx_t_double_complex, __pyx_t_double_complex); + #endif +#endif + +/* MemviewSliceCopyTemplate.proto */ +static __Pyx_memviewslice +__pyx_memoryview_copy_new_contig(const __Pyx_memviewslice *from_mvs, + const char *mode, int ndim, + size_t sizeof_dtype, int contig_flag, + int dtype_is_object); + +/* MemviewSliceInit.proto */ +#define __Pyx_BUF_MAX_NDIMS %(BUF_MAX_NDIMS)d +#define __Pyx_MEMVIEW_DIRECT 1 +#define __Pyx_MEMVIEW_PTR 2 +#define __Pyx_MEMVIEW_FULL 4 +#define __Pyx_MEMVIEW_CONTIG 8 +#define __Pyx_MEMVIEW_STRIDED 16 +#define __Pyx_MEMVIEW_FOLLOW 32 +#define __Pyx_IS_C_CONTIG 1 +#define __Pyx_IS_F_CONTIG 2 +static int __Pyx_init_memviewslice( + struct __pyx_memoryview_obj *memview, + int ndim, + __Pyx_memviewslice *memviewslice, + int memview_is_new_reference); +static CYTHON_INLINE int __pyx_add_acquisition_count_locked( + __pyx_atomic_int_type *acquisition_count, PyThread_type_lock lock); +static CYTHON_INLINE int __pyx_sub_acquisition_count_locked( + __pyx_atomic_int_type *acquisition_count, PyThread_type_lock lock); +#define __pyx_get_slice_count_pointer(memview) (&memview->acquisition_count) +#define __PYX_INC_MEMVIEW(slice, have_gil) __Pyx_INC_MEMVIEW(slice, have_gil, __LINE__) +#define __PYX_XCLEAR_MEMVIEW(slice, have_gil) __Pyx_XCLEAR_MEMVIEW(slice, have_gil, __LINE__) +static CYTHON_INLINE void __Pyx_INC_MEMVIEW(__Pyx_memviewslice *, int, int); +static CYTHON_INLINE void __Pyx_XCLEAR_MEMVIEW(__Pyx_memviewslice *, int, int); + +/* CIntFromPy.proto */ +static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_int(int value); + +/* CIntFromPy.proto */ +static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value); + +/* CIntFromPy.proto */ +static CYTHON_INLINE size_t __Pyx_PyInt_As_size_t(PyObject *); + +/* CIntFromPy.proto */ +static CYTHON_INLINE char __Pyx_PyInt_As_char(PyObject *); + +/* FormatTypeName.proto */ +#if CYTHON_COMPILING_IN_LIMITED_API +typedef PyObject *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%U" +static __Pyx_TypeName __Pyx_PyType_GetName(PyTypeObject* tp); +#define __Pyx_DECREF_TypeName(obj) Py_XDECREF(obj) +#else +typedef const char *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%.200s" +#define __Pyx_PyType_GetName(tp) ((tp)->tp_name) +#define __Pyx_DECREF_TypeName(obj) +#endif + +/* CheckBinaryVersion.proto */ +static unsigned long __Pyx_get_runtime_version(void); +static int __Pyx_check_binary_version(unsigned long ct_version, unsigned long rt_version, int allow_newer); + +/* InitStrings.proto */ +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t); + +/* #### Code section: module_declarations ### */ +static PyObject *__pyx_array_get_memview(struct __pyx_array_obj *__pyx_v_self); /* proto*/ +static char *__pyx_memoryview_get_item_pointer(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index); /* proto*/ +static PyObject *__pyx_memoryview_is_slice(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj); /* proto*/ +static PyObject *__pyx_memoryview_setitem_slice_assignment(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_dst, PyObject *__pyx_v_src); /* proto*/ +static PyObject *__pyx_memoryview_setitem_slice_assign_scalar(struct __pyx_memoryview_obj *__pyx_v_self, struct __pyx_memoryview_obj *__pyx_v_dst, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryview_setitem_indexed(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryview_convert_item_to_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp); /* proto*/ +static PyObject *__pyx_memoryview_assign_item_from_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryview__get_base(struct __pyx_memoryview_obj *__pyx_v_self); /* proto*/ +static PyObject *__pyx_memoryviewslice_convert_item_to_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp); /* proto*/ +static PyObject *__pyx_memoryviewslice_assign_item_from_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryviewslice__get_base(struct __pyx_memoryviewslice_obj *__pyx_v_self); /* proto*/ +static CYTHON_INLINE PyObject *__pyx_f_5numpy_7ndarray_4base_base(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE PyArray_Descr *__pyx_f_5numpy_7ndarray_5descr_descr(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE int __pyx_f_5numpy_7ndarray_4ndim_ndim(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_5shape_shape(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_7strides_strides(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE npy_intp __pyx_f_5numpy_7ndarray_4size_size(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE char *__pyx_f_5numpy_7ndarray_4data_data(PyArrayObject *__pyx_v_self); /* proto*/ + +/* Module declarations from "cython.view" */ + +/* Module declarations from "cython.dataclasses" */ + +/* Module declarations from "cython" */ + +/* Module declarations from "libc.string" */ + +/* Module declarations from "libc.stdio" */ + +/* Module declarations from "libc" */ + +/* Module declarations from "acados_solver_common" */ + +/* Module declarations from "acados_solver" */ + +/* Module declarations from "__builtin__" */ + +/* Module declarations from "cpython.type" */ + +/* Module declarations from "cpython" */ + +/* Module declarations from "cpython.object" */ + +/* Module declarations from "cpython.ref" */ + +/* Module declarations from "numpy" */ + +/* Module declarations from "numpy" */ + +/* Module declarations from "acados_template.acados_ocp_solver_pyx" */ +static PyObject *__pyx_collections_abc_Sequence = 0; +static PyObject *generic = 0; +static PyObject *strided = 0; +static PyObject *indirect = 0; +static PyObject *contiguous = 0; +static PyObject *indirect_contiguous = 0; +static int __pyx_memoryview_thread_locks_used; +static PyThread_type_lock __pyx_memoryview_thread_locks[8]; +static CYTHON_INLINE PyObject *__Pyx_carray_to_py_int(int *, Py_ssize_t); /*proto*/ +static CYTHON_INLINE PyObject *__Pyx_carray_to_tuple_int(int *, Py_ssize_t); /*proto*/ +static int __pyx_array_allocate_buffer(struct __pyx_array_obj *); /*proto*/ +static struct __pyx_array_obj *__pyx_array_new(PyObject *, Py_ssize_t, char *, char *, char *); /*proto*/ +static PyObject *__pyx_memoryview_new(PyObject *, int, int, __Pyx_TypeInfo *); /*proto*/ +static CYTHON_INLINE int __pyx_memoryview_check(PyObject *); /*proto*/ +static PyObject *_unellipsify(PyObject *, int); /*proto*/ +static int assert_direct_dimensions(Py_ssize_t *, int); /*proto*/ +static struct __pyx_memoryview_obj *__pyx_memview_slice(struct __pyx_memoryview_obj *, PyObject *); /*proto*/ +static int __pyx_memoryview_slice_memviewslice(__Pyx_memviewslice *, Py_ssize_t, Py_ssize_t, Py_ssize_t, int, int, int *, Py_ssize_t, Py_ssize_t, Py_ssize_t, int, int, int, int); /*proto*/ +static char *__pyx_pybuffer_index(Py_buffer *, char *, Py_ssize_t, Py_ssize_t); /*proto*/ +static int __pyx_memslice_transpose(__Pyx_memviewslice *); /*proto*/ +static PyObject *__pyx_memoryview_fromslice(__Pyx_memviewslice, int, PyObject *(*)(char *), int (*)(char *, PyObject *), int); /*proto*/ +static __Pyx_memviewslice *__pyx_memoryview_get_slice_from_memoryview(struct __pyx_memoryview_obj *, __Pyx_memviewslice *); /*proto*/ +static void __pyx_memoryview_slice_copy(struct __pyx_memoryview_obj *, __Pyx_memviewslice *); /*proto*/ +static PyObject *__pyx_memoryview_copy_object(struct __pyx_memoryview_obj *); /*proto*/ +static PyObject *__pyx_memoryview_copy_object_from_slice(struct __pyx_memoryview_obj *, __Pyx_memviewslice *); /*proto*/ +static Py_ssize_t abs_py_ssize_t(Py_ssize_t); /*proto*/ +static char __pyx_get_best_slice_order(__Pyx_memviewslice *, int); /*proto*/ +static void _copy_strided_to_strided(char *, Py_ssize_t *, char *, Py_ssize_t *, Py_ssize_t *, Py_ssize_t *, int, size_t); /*proto*/ +static void copy_strided_to_strided(__Pyx_memviewslice *, __Pyx_memviewslice *, int, size_t); /*proto*/ +static Py_ssize_t __pyx_memoryview_slice_get_size(__Pyx_memviewslice *, int); /*proto*/ +static Py_ssize_t __pyx_fill_contig_strides_array(Py_ssize_t *, Py_ssize_t *, Py_ssize_t, int, char); /*proto*/ +static void *__pyx_memoryview_copy_data_to_temp(__Pyx_memviewslice *, __Pyx_memviewslice *, char, int); /*proto*/ +static int __pyx_memoryview_err_extents(int, Py_ssize_t, Py_ssize_t); /*proto*/ +static int __pyx_memoryview_err_dim(PyObject *, PyObject *, int); /*proto*/ +static int __pyx_memoryview_err(PyObject *, PyObject *); /*proto*/ +static int __pyx_memoryview_err_no_memory(void); /*proto*/ +static int __pyx_memoryview_copy_contents(__Pyx_memviewslice, __Pyx_memviewslice, int, int, int); /*proto*/ +static void __pyx_memoryview_broadcast_leading(__Pyx_memviewslice *, int, int); /*proto*/ +static void __pyx_memoryview_refcount_copying(__Pyx_memviewslice *, int, int, int); /*proto*/ +static void __pyx_memoryview_refcount_objects_in_slice_with_gil(char *, Py_ssize_t *, Py_ssize_t *, int, int); /*proto*/ +static void __pyx_memoryview_refcount_objects_in_slice(char *, Py_ssize_t *, Py_ssize_t *, int, int); /*proto*/ +static void __pyx_memoryview_slice_assign_scalar(__Pyx_memviewslice *, int, size_t, void *, int); /*proto*/ +static void __pyx_memoryview__slice_assign_scalar(char *, Py_ssize_t *, Py_ssize_t *, int, size_t, void *); /*proto*/ +static PyObject *__pyx_unpickle_Enum__set_state(struct __pyx_MemviewEnum_obj *, PyObject *); /*proto*/ +/* #### Code section: typeinfo ### */ +static __Pyx_TypeInfo __Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t = { "float64_t", NULL, sizeof(__pyx_t_5numpy_float64_t), { 0 }, 0, 'R', 0, 0 }; +static __Pyx_TypeInfo __Pyx_TypeInfo_nn___pyx_t_5numpy_int32_t = { "int32_t", NULL, sizeof(__pyx_t_5numpy_int32_t), { 0 }, 0, __PYX_IS_UNSIGNED(__pyx_t_5numpy_int32_t) ? 'U' : 'I', __PYX_IS_UNSIGNED(__pyx_t_5numpy_int32_t), 0 }; +static __Pyx_TypeInfo __Pyx_TypeInfo_double = { "double", NULL, sizeof(double), { 0 }, 0, 'R', 0, 0 }; +static __Pyx_TypeInfo __Pyx_TypeInfo_unsigned_char = { "unsigned char", NULL, sizeof(unsigned char), { 0 }, 0, __PYX_IS_UNSIGNED(unsigned char) ? 'U' : 'I', __PYX_IS_UNSIGNED(unsigned char), 0 }; +/* #### Code section: before_global_var ### */ +#define __Pyx_MODULE_NAME "acados_template.acados_ocp_solver_pyx" +extern int __pyx_module_is_main_acados_template__acados_ocp_solver_pyx; +int __pyx_module_is_main_acados_template__acados_ocp_solver_pyx = 0; + +/* Implementation of "acados_template.acados_ocp_solver_pyx" */ +/* #### Code section: global_var ### */ +static PyObject *__pyx_builtin_AssertionError; +static PyObject *__pyx_builtin_print; +static PyObject *__pyx_builtin_NotImplementedError; +static PyObject *__pyx_builtin_range; +static PyObject *__pyx_builtin_open; +static PyObject *__pyx_builtin_TypeError; +static PyObject *__pyx_builtin___import__; +static PyObject *__pyx_builtin_ValueError; +static PyObject *__pyx_builtin_MemoryError; +static PyObject *__pyx_builtin_enumerate; +static PyObject *__pyx_builtin_Ellipsis; +static PyObject *__pyx_builtin_id; +static PyObject *__pyx_builtin_IndexError; +static PyObject *__pyx_builtin_ImportError; +/* #### Code section: string_decls ### */ +static const char __pyx_k_[] = ": "; +static const char __pyx_k_0[] = "0"; +static const char __pyx_k_F[] = "F"; +static const char __pyx_k_N[] = "N"; +static const char __pyx_k_O[] = "O"; +static const char __pyx_k_c[] = "c"; +static const char __pyx_k_d[] = "d"; +static const char __pyx_k_f[] = "f"; +static const char __pyx_k_i[] = "i"; +static const char __pyx_k_k[] = "k"; +static const char __pyx_k_m[] = "m"; +static const char __pyx_k_n[] = "n"; +static const char __pyx_k_p[] = "p"; +static const char __pyx_k_r[] = "r"; +static const char __pyx_k_t[] = "t"; +static const char __pyx_k_u[] = "u"; +static const char __pyx_k_w[] = "w"; +static const char __pyx_k_x[] = "x"; +static const char __pyx_k_z[] = "z"; +static const char __pyx_k__2[] = "."; +static const char __pyx_k__3[] = "*"; +static const char __pyx_k__6[] = "'"; +static const char __pyx_k__7[] = ")"; +static const char __pyx_k_ex[] = "ex"; +static const char __pyx_k_gc[] = "gc"; +static const char __pyx_k_id[] = "id"; +static const char __pyx_k_lN[] = "lN"; +static const char __pyx_k_np[] = "np"; +static const char __pyx_k_nx[] = "nx"; +static const char __pyx_k_os[] = "os"; +static const char __pyx_k_pi[] = "pi"; +static const char __pyx_k_sl[] = "sl"; +static const char __pyx_k_su[] = "su"; +static const char __pyx_k_u0[] = "u0"; +static const char __pyx_k_SQP[] = "SQP"; +static const char __pyx_k__16[] = ""; +static const char __pyx_k__17[] = "_"; +static const char __pyx_k__31[] = ", "; +static const char __pyx_k__94[] = "?"; +static const char __pyx_k_abc[] = "abc"; +static const char __pyx_k_and[] = " and "; +static const char __pyx_k_get[] = "get"; +static const char __pyx_k_got[] = " (got "; +static const char __pyx_k_idx[] = "idx"; +static const char __pyx_k_int[] = "int"; +static const char __pyx_k_key[] = "key"; +static const char __pyx_k_lam[] = "lam"; +static const char __pyx_k_lbu[] = "lbu"; +static const char __pyx_k_lbx[] = "lbx"; +static const char __pyx_k_msg[] = "msg"; +static const char __pyx_k_new[] = "__new__"; +static const char __pyx_k_obj[] = "obj"; +static const char __pyx_k_out[] = "out"; +static const char __pyx_k_set[] = "set"; +static const char __pyx_k_sys[] = "sys"; +static const char __pyx_k_t_2[] = "t_"; +static const char __pyx_k_u_2[] = "u_"; +static const char __pyx_k_ubu[] = "ubu"; +static const char __pyx_k_ubx[] = "ubx"; +static const char __pyx_k_x_2[] = "x_"; +static const char __pyx_k_z_2[] = "z_"; +static const char __pyx_k_None[] = "None"; +static const char __pyx_k_TODO[] = "TODO!"; +static const char __pyx_k_base[] = "base"; +static const char __pyx_k_data[] = "data_"; +static const char __pyx_k_dict[] = "__dict__"; +static const char __pyx_k_dims[] = "dims"; +static const char __pyx_k_dump[] = "dump"; +static const char __pyx_k_exit[] = "__exit__"; +static const char __pyx_k_join[] = "join"; +static const char __pyx_k_json[] = "json"; +static const char __pyx_k_keys[] = "keys"; +static const char __pyx_k_load[] = "load"; +static const char __pyx_k_main[] = "__main__"; +static const char __pyx_k_mode[] = "mode"; +static const char __pyx_k_name[] = "name"; +static const char __pyx_k_ndim[] = "ndim"; +static const char __pyx_k_open[] = "open"; +static const char __pyx_k_pack[] = "pack"; +static const char __pyx_k_path[] = "path"; +static const char __pyx_k_pi_2[] = "pi_"; +static const char __pyx_k_self[] = "self"; +static const char __pyx_k_size[] = "size"; +static const char __pyx_k_sl_2[] = "sl_"; +static const char __pyx_k_spec[] = "__spec__"; +static const char __pyx_k_step[] = "step"; +static const char __pyx_k_stop[] = "stop"; +static const char __pyx_k_su_2[] = "su_"; +static const char __pyx_k_test[] = "__test__"; +static const char __pyx_k_yref[] = "yref"; +static const char __pyx_k_ASCII[] = "ASCII"; +static const char __pyx_k_alpha[] = "alpha"; +static const char __pyx_k_array[] = "array"; +static const char __pyx_k_class[] = "__class__"; +static const char __pyx_k_count[] = "count"; +static const char __pyx_k_dtype[] = "dtype"; +static const char __pyx_k_enter[] = "__enter__"; +static const char __pyx_k_error[] = "error"; +static const char __pyx_k_field[] = "field"; +static const char __pyx_k_flags[] = "flags"; +static const char __pyx_k_index[] = "index"; +static const char __pyx_k_int32[] = "int32"; +static const char __pyx_k_lam_2[] = "lam_"; +static const char __pyx_k_numpy[] = "numpy"; +static const char __pyx_k_order[] = "order"; +static const char __pyx_k_print[] = "print"; +static const char __pyx_k_range[] = "range"; +static const char __pyx_k_reset[] = "reset"; +static const char __pyx_k_shape[] = "shape"; +static const char __pyx_k_solve[] = "solve"; +static const char __pyx_k_split[] = "split"; +static const char __pyx_k_stage[] = "stage"; +static const char __pyx_k_start[] = "start"; +static const char __pyx_k_utf_8[] = "utf-8"; +static const char __pyx_k_value[] = "value_"; +static const char __pyx_k_y_ref[] = "y_ref"; +static const char __pyx_k_zeros[] = "zeros"; +static const char __pyx_k_data_2[] = "data"; +static const char __pyx_k_enable[] = "enable"; +static const char __pyx_k_encode[] = "encode"; +static const char __pyx_k_fields[] = "fields"; +static const char __pyx_k_format[] = "format"; +static const char __pyx_k_getcwd[] = "getcwd"; +static const char __pyx_k_import[] = "__import__"; +static const char __pyx_k_indent[] = "indent"; +static const char __pyx_k_isfile[] = "isfile"; +static const char __pyx_k_json_2[] = ".json"; +static const char __pyx_k_name_2[] = "__name__"; +static const char __pyx_k_pickle[] = "pickle"; +static const char __pyx_k_qp_mu0[] = "qp_mu0"; +static const char __pyx_k_reduce[] = "__reduce__"; +static const char __pyx_k_res_eq[] = "res_eq"; +static const char __pyx_k_stat_m[] = "stat_m"; +static const char __pyx_k_stat_n[] = "stat_n"; +static const char __pyx_k_status[] = "status"; +static const char __pyx_k_struct[] = "struct"; +static const char __pyx_k_tol_eq[] = "tol_eq"; +static const char __pyx_k_tolist[] = "tolist"; +static const char __pyx_k_unpack[] = "unpack"; +static const char __pyx_k_update[] = "update"; +static const char __pyx_k_utcnow[] = "utcnow"; +static const char __pyx_k_x0_bar[] = "x0_bar"; +static const char __pyx_k_SQP_RTI[] = "SQP_RTI"; +static const char __pyx_k_default[] = "default"; +static const char __pyx_k_disable[] = "disable"; +static const char __pyx_k_field_2[] = "field_"; +static const char __pyx_k_float64[] = "float64"; +static const char __pyx_k_fortran[] = "fortran"; +static const char __pyx_k_iterate[] = "iterate"; +static const char __pyx_k_memview[] = "memview"; +static const char __pyx_k_ndarray[] = "ndarray"; +static const char __pyx_k_out_mat[] = "out_mat"; +static const char __pyx_k_qp_iter[] = "qp_iter"; +static const char __pyx_k_time_qp[] = "time_qp"; +static const char __pyx_k_value_2[] = "value"; +static const char __pyx_k_z_guess[] = "z_guess"; +static const char __pyx_k_Ellipsis[] = "Ellipsis"; +static const char __pyx_k_Sequence[] = "Sequence"; +static const char __pyx_k_at_stage[] = "\" at stage "; +static const char __pyx_k_cost_set[] = "cost_set"; +static const char __pyx_k_data_len[] = "data_len"; +static const char __pyx_k_datetime[] = "datetime"; +static const char __pyx_k_filename[] = "filename"; +static const char __pyx_k_get_cost[] = "get_cost"; +static const char __pyx_k_getstate[] = "__getstate__"; +static const char __pyx_k_i_string[] = "i_string"; +static const char __pyx_k_itemsize[] = "itemsize"; +static const char __pyx_k_min_size[] = "min_size"; +static const char __pyx_k_n_update[] = "n_update"; +static const char __pyx_k_pyx_type[] = "__pyx_type"; +static const char __pyx_k_register[] = "register"; +static const char __pyx_k_res_comp[] = "res_comp"; +static const char __pyx_k_res_ineq[] = "res_ineq"; +static const char __pyx_k_res_stat[] = "res_stat"; +static const char __pyx_k_setstate[] = "__setstate__"; +static const char __pyx_k_solution[] = "solution"; +static const char __pyx_k_sqp_iter[] = "sqp_iter"; +static const char __pyx_k_strftime[] = "strftime"; +static const char __pyx_k_time_lin[] = "time_lin"; +static const char __pyx_k_time_reg[] = "time_reg"; +static const char __pyx_k_time_sim[] = "time_sim"; +static const char __pyx_k_time_tot[] = "time_tot"; +static const char __pyx_k_tol_comp[] = "tol_comp"; +static const char __pyx_k_tol_ineq[] = "tol_ineq"; +static const char __pyx_k_tol_stat[] = "tol_stat"; +static const char __pyx_k_you_have[] = " (you have "; +static const char __pyx_k_TypeError[] = "TypeError"; +static const char __pyx_k_alpha_min[] = "alpha_min"; +static const char __pyx_k_enumerate[] = "enumerate"; +static const char __pyx_k_for_field[] = " for field \""; +static const char __pyx_k_get_stats[] = "get_stats"; +static const char __pyx_k_int_value[] = "int_value"; +static const char __pyx_k_isenabled[] = "isenabled"; +static const char __pyx_k_overwrite[] = "overwrite"; +static const char __pyx_k_pyx_state[] = "__pyx_state"; +static const char __pyx_k_qp_tol_eq[] = "qp_tol_eq"; +static const char __pyx_k_recompute[] = "recompute"; +static const char __pyx_k_reduce_ex[] = "__reduce_ex__"; +static const char __pyx_k_residuals[] = "residuals"; +static const char __pyx_k_rti_phase[] = "rti_phase"; +static const char __pyx_k_sort_keys[] = "sort_keys"; +static const char __pyx_k_time_glob[] = "time_glob"; +static const char __pyx_k_IndexError[] = "IndexError"; +static const char __pyx_k_ValueError[] = "ValueError"; +static const char __pyx_k_full_stats[] = "full_stats"; +static const char __pyx_k_idx_values[] = "idx_values_"; +static const char __pyx_k_int_fields[] = "int_fields"; +static const char __pyx_k_mem_fields[] = "mem_fields"; +static const char __pyx_k_model_name[] = "model_name"; +static const char __pyx_k_out_fields[] = "out_fields"; +static const char __pyx_k_pyx_result[] = "__pyx_result"; +static const char __pyx_k_pyx_vtable[] = "__pyx_vtable__"; +static const char __pyx_k_qp_tau_min[] = "qp_tau_min"; +static const char __pyx_k_statistics[] = "statistics"; +static const char __pyx_k_xdot_guess[] = "xdot_guess"; +static const char __pyx_k_ImportError[] = "ImportError"; +static const char __pyx_k_MemoryError[] = "MemoryError"; +static const char __pyx_k_PickleError[] = "PickleError"; +static const char __pyx_k_collections[] = "collections"; +static const char __pyx_k_cost_fields[] = "cost_fields"; +static const char __pyx_k_options_set[] = "options_set"; +static const char __pyx_k_print_level[] = "print_level"; +static const char __pyx_k_qp_tol_comp[] = "qp_tol_comp"; +static const char __pyx_k_qp_tol_ineq[] = "qp_tol_ineq"; +static const char __pyx_k_qp_tol_stat[] = "qp_tol_stat"; +static const char __pyx_k_step_length[] = "step_length"; +static const char __pyx_k_time_sim_ad[] = "time_sim_ad"; +static const char __pyx_k_time_sim_la[] = "time_sim_la"; +static const char __pyx_k_value_shape[] = "value_shape"; +static const char __pyx_k_double_value[] = "double_value"; +static const char __pyx_k_get_stat_int[] = "__get_stat_int"; +static const char __pyx_k_initializing[] = "_initializing"; +static const char __pyx_k_is_coroutine[] = "_is_coroutine"; +static const char __pyx_k_load_iterate[] = "load_iterate"; +static const char __pyx_k_param_values[] = "param_values_"; +static const char __pyx_k_pyx_checksum[] = "__pyx_checksum"; +static const char __pyx_k_solve_for_x0[] = "solve_for_x0"; +static const char __pyx_k_string_value[] = "string_value"; +static const char __pyx_k_stringsource[] = ""; +static const char __pyx_k_version_info[] = "version_info"; +static const char __pyx_k_Got_sizes_idx[] = " Got sizes idx "; +static const char __pyx_k_Y_m_d_H_M_S_f[] = "%Y-%m-%d-%H:%M:%S.%f"; +static const char __pyx_k_class_getitem[] = "__class_getitem__"; +static const char __pyx_k_custom_update[] = "custom_update"; +static const char __pyx_k_double_fields[] = "double_fields"; +static const char __pyx_k_get_residuals[] = "get_residuals"; +static const char __pyx_k_globalization[] = "globalization"; +static const char __pyx_k_qp_warm_start[] = "qp_warm_start"; +static const char __pyx_k_reduce_cython[] = "__reduce_cython__"; +static const char __pyx_k_store_iterate[] = "store_iterate"; +static const char __pyx_k_string_fields[] = "string_fields"; +static const char __pyx_k_time_qp_xcond[] = "time_qp_xcond"; +static const char __pyx_k_AssertionError[] = "AssertionError"; +static const char __pyx_k_asfortranarray[] = "asfortranarray"; +static const char __pyx_k_full_step_dual[] = "full_step_dual"; +static const char __pyx_k_get_from_qp_in[] = "get_from_qp_in"; +static const char __pyx_k_new_time_steps[] = "new_time_steps"; +static const char __pyx_k_param_values_2[] = ", param_values "; +static const char __pyx_k_with_dimension[] = " with dimension "; +static const char __pyx_k_View_MemoryView[] = "View.MemoryView"; +static const char __pyx_k_allocate_buffer[] = "allocate_buffer"; +static const char __pyx_k_alpha_reduction[] = "alpha_reduction"; +static const char __pyx_k_collections_abc[] = "collections.abc"; +static const char __pyx_k_constraints_set[] = "constraints_set"; +static const char __pyx_k_dtype_is_object[] = "dtype_is_object"; +static const char __pyx_k_eval_param_sens[] = "eval_param_sens"; +static const char __pyx_k_get_stat_double[] = "__get_stat_double"; +static const char __pyx_k_get_stat_matrix[] = "__get_stat_matrix"; +static const char __pyx_k_nlp_solver_type[] = "nlp_solver_type"; +static const char __pyx_k_pyx_PickleError[] = "__pyx_PickleError"; +static const char __pyx_k_setstate_cython[] = "__setstate_cython__"; +static const char __pyx_k_print_statistics[] = "print_statistics"; +static const char __pyx_k_qp_solver_cond_N[] = "qp_solver_cond_N"; +static const char __pyx_k_ascontiguousarray[] = "ascontiguousarray"; +static const char __pyx_k_pyx_unpickle_Enum[] = "__pyx_unpickle_Enum"; +static const char __pyx_k_set_params_sparse[] = "set_params_sparse"; +static const char __pyx_k_asyncio_coroutines[] = "asyncio.coroutines"; +static const char __pyx_k_cline_in_traceback[] = "cline_in_traceback"; +static const char __pyx_k_constraints_fields[] = "constraints_fields"; +static const char __pyx_k_set_new_time_steps[] = "set_new_time_steps"; +static const char __pyx_k_strided_and_direct[] = ""; +static const char __pyx_k_NotImplementedError[] = "NotImplementedError"; +static const char __pyx_k_get_pointers_solver[] = "__get_pointers_solver"; +static const char __pyx_k_initialize_t_slacks[] = "initialize_t_slacks"; +static const char __pyx_k_reset_qp_solver_mem[] = "reset_qp_solver_mem"; +static const char __pyx_k_time_qp_solver_call[] = "time_qp_solver_call"; +static const char __pyx_k_warm_start_first_qp[] = "warm_start_first_qp"; +static const char __pyx_k_strided_and_indirect[] = ""; +static const char __pyx_k_AcadosOcpSolverCython[] = "AcadosOcpSolverCython"; +static const char __pyx_k_Invalid_shape_in_axis[] = "Invalid shape in axis "; +static const char __pyx_k_contiguous_and_direct[] = ""; +static const char __pyx_k_globalization_use_SOC[] = "globalization_use_SOC"; +static const char __pyx_k_Cannot_index_with_type[] = "Cannot index with type '"; +static const char __pyx_k_MemoryView_of_r_object[] = ""; +static const char __pyx_k_eps_sufficient_descent[] = "eps_sufficient_descent"; +static const char __pyx_k_MemoryView_of_r_at_0x_x[] = ""; +static const char __pyx_k_contiguous_and_indirect[] = ""; +static const char __pyx_k_update_qp_solver_cond_N[] = "update_qp_solver_cond_N"; +static const char __pyx_k_with_dimension_you_have[] = "with dimension {} (you have {})"; +static const char __pyx_k_AcadosOcpSolverCython_get[] = "AcadosOcpSolverCython.get"; +static const char __pyx_k_AcadosOcpSolverCython_set[] = "AcadosOcpSolverCython.set"; +static const char __pyx_k_Dimension_d_is_not_direct[] = "Dimension %d is not direct"; +static const char __pyx_k_stored_current_iterate_in[] = "stored current iterate in "; +static const char __pyx_k_Index_out_of_bounds_axis_d[] = "Index out of bounds (axis %d)"; +static const char __pyx_k_AcadosOcpSolverCython_reset[] = "AcadosOcpSolverCython.reset"; +static const char __pyx_k_AcadosOcpSolverCython_solve[] = "AcadosOcpSolverCython.solve"; +static const char __pyx_k_Step_may_not_be_zero_axis_d[] = "Step may not be zero (axis %d)"; +static const char __pyx_k_itemsize_0_for_cython_array[] = "itemsize <= 0 for cython.array"; +static const char __pyx_k_store_iterate_locals_lambda[] = "store_iterate.."; +static const char __pyx_k_time_solution_sensitivities[] = "time_solution_sensitivities"; +static const char __pyx_k_unable_to_allocate_array_data[] = "unable to allocate array data."; +static const char __pyx_k_AcadosOcpSolverCython_cost_set[] = "AcadosOcpSolverCython.cost_set"; +static const char __pyx_k_AcadosOcpSolverCython_get_cost[] = "AcadosOcpSolverCython.get_cost"; +static const char __pyx_k_param_values__must_be_np_array[] = "param_values_ must be np.array."; +static const char __pyx_k_strided_and_direct_or_indirect[] = ""; +static const char __pyx_k_AcadosOcpSolverCython__get_poin[] = "_AcadosOcpSolverCython__get_pointers_solver"; +static const char __pyx_k_AcadosOcpSolverCython__get_stat[] = "_AcadosOcpSolverCython__get_stat_int"; +static const char __pyx_k_AcadosOcpSolverCython_get_field[] = "AcadosOcpSolverCython.get(): field {} does not exist at final stage {}."; +static const char __pyx_k_AcadosOcpSolverCython_get_is_an[] = "AcadosOcpSolverCython.get(): {} is an invalid argument. \n Possible values are {}."; +static const char __pyx_k_AcadosOcpSolverCython_get_stage[] = "AcadosOcpSolverCython.get(): stage index must be in [0, N], got: {}."; +static const char __pyx_k_AcadosOcpSolverCython_get_stats[] = "AcadosOcpSolverCython.get_stats"; +static const char __pyx_k_AcadosOcpSolverCython_solve_for[] = "AcadosOcpSolverCython.solve_for_x0"; +static const char __pyx_k_AcadosOcpSolverCython_update_qp[] = "AcadosOcpSolverCython.update_qp_solver_cond_N"; +static const char __pyx_k_numpy_core_multiarray_failed_to[] = "numpy.core.multiarray failed to import"; +static const char __pyx_k_AcadosOcpSolverCython___get_poin[] = "AcadosOcpSolverCython.__get_pointers_solver"; +static const char __pyx_k_AcadosOcpSolverCython___get_stat[] = "AcadosOcpSolverCython.__get_stat_int"; +static const char __pyx_k_AcadosOcpSolverCython___reduce_c[] = "AcadosOcpSolverCython.__reduce_cython__"; +static const char __pyx_k_AcadosOcpSolverCython___setstate[] = "AcadosOcpSolverCython.__setstate_cython__"; +static const char __pyx_k_AcadosOcpSolverCython_constraint[] = "AcadosOcpSolverCython.constraints_set(): mismatching dimension"; +static const char __pyx_k_AcadosOcpSolverCython_cost_set_m[] = "AcadosOcpSolverCython.cost_set(): mismatching dimension"; +static const char __pyx_k_AcadosOcpSolverCython_custom_upd[] = "AcadosOcpSolverCython.custom_update"; +static const char __pyx_k_AcadosOcpSolverCython_does_not_s[] = "AcadosOcpSolverCython: does not support set_new_time_steps() since it is only a prototyping feature"; +static const char __pyx_k_AcadosOcpSolverCython_eval_param[] = "AcadosOcpSolverCython.eval_param_sens(): index must be Integer."; +static const char __pyx_k_AcadosOcpSolverCython_get_from_q[] = "AcadosOcpSolverCython.get_from_qp_in"; +static const char __pyx_k_AcadosOcpSolverCython_get_residu[] = "AcadosOcpSolverCython.get_residuals"; +static const char __pyx_k_AcadosOcpSolverCython_load_itera[] = "AcadosOcpSolverCython.load_iterate"; +static const char __pyx_k_AcadosOcpSolverCython_options_se[] = "AcadosOcpSolverCython.options_set() does not support field {}.\n Possible values are {}."; +static const char __pyx_k_AcadosOcpSolverCython_print_stat[] = "AcadosOcpSolverCython.print_statistics"; +static const char __pyx_k_AcadosOcpSolverCython_set_is_not[] = "AcadosOcpSolverCython.set(): {} is not a valid argument. \nPossible values are {}."; +static const char __pyx_k_AcadosOcpSolverCython_set_mismat[] = "AcadosOcpSolverCython.set(): mismatching dimension for field \"{}\" "; +static const char __pyx_k_AcadosOcpSolverCython_set_new_ti[] = "AcadosOcpSolverCython.set_new_time_steps"; +static const char __pyx_k_AcadosOcpSolverCython_set_params[] = "AcadosOcpSolverCython.set_params_sparse"; +static const char __pyx_k_AcadosOcpSolverCython_solve_argu[] = "AcadosOcpSolverCython.solve(): argument 'rti_phase' can take only values 0, 1, 2 for SQP-RTI-type solvers"; +static const char __pyx_k_AcadosOcpSolverCython_store_iter[] = "AcadosOcpSolverCython.store_iterate"; +static const char __pyx_k_All_dimensions_preceding_dimensi[] = "All dimensions preceding dimension %d must be indexed and not sliced"; +static const char __pyx_k_Buffer_view_does_not_expose_stri[] = "Buffer view does not expose strides"; +static const char __pyx_k_Can_only_create_a_buffer_that_is[] = "Can only create a buffer that is contiguous in memory."; +static const char __pyx_k_Cannot_assign_to_read_only_memor[] = "Cannot assign to read-only memoryview"; +static const char __pyx_k_Cannot_create_writable_memory_vi[] = "Cannot create writable memory view from read-only memoryview"; +static const char __pyx_k_Cannot_transpose_memoryview_with[] = "Cannot transpose memoryview with indirect dimensions"; +static const char __pyx_k_Empty_shape_tuple_for_cython_arr[] = "Empty shape tuple for cython.array"; +static const char __pyx_k_Incompatible_checksums_0x_x_vs_0[] = "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))"; +static const char __pyx_k_Indirect_dimensions_not_supporte[] = "Indirect dimensions not supported"; +static const char __pyx_k_Invalid_mode_expected_c_or_fortr[] = "Invalid mode, expected 'c' or 'fortran', got "; +static const char __pyx_k_Out_of_bounds_on_buffer_access_a[] = "Out of bounds on buffer access (axis "; +static const char __pyx_k_Unable_to_convert_item_to_object[] = "Unable to convert item to object"; +static const char __pyx_k_Warning_acados_ocp_solver_reache[] = "Warning: acados_ocp_solver reached maximum iterations."; +static const char __pyx_k_acados_acados_ocp_solver_returne[] = "acados acados_ocp_solver returned status "; +static const char __pyx_k_acados_template_acados_ocp_solve[] = "acados_template.acados_ocp_solver_pyx"; +static const char __pyx_k_alpha_values_are_not_available_f[] = "alpha values are not available for SQP_RTI"; +static const char __pyx_k_constraints_set_value_must_be_nu[] = "constraints_set: value must be numpy array, got "; +static const char __pyx_k_cost_set_value_must_be_numpy_arr[] = "cost_set: value must be numpy array, got "; +static const char __pyx_k_got_differing_extents_in_dimensi[] = "got differing extents in dimension "; +static const char __pyx_k_line_search_use_sufficient_desce[] = "line_search_use_sufficient_descent"; +static const char __pyx_k_load_iterate_failed_file_does_no[] = "load_iterate: failed, file does not exist: "; +static const char __pyx_k_no_default___reduce___due_to_non[] = "no default __reduce__ due to non-trivial __cinit__"; +static const char __pyx_k_numpy_core_umath_failed_to_impor[] = "numpy.core.umath failed to import"; +static const char __pyx_k_param_values__and_idx_values__mu[] = "param_values_ and idx_values_ must be of the same size."; +static const char __pyx_k_set_value_must_be_numpy_array_go[] = "set: value must be numpy array, got "; +static const char __pyx_k_solver_option_must_be_of_type_fl[] = "solver option {} must be of type float. You have {}."; +static const char __pyx_k_solver_option_must_be_of_type_in[] = "solver option {} must be of type int. You have {}."; +static const char __pyx_k_solver_option_must_be_of_type_st[] = "solver option {} must be of type str. You have {}."; +static const char __pyx_k_third_party_acados_acados_templa[] = "third_party/acados/acados_template/acados_ocp_solver_pyx.pyx"; +static const char __pyx_k_unable_to_allocate_shape_and_str[] = "unable to allocate shape and strides."; +static const char __pyx_k_AcadosOcpSolverCython__get_stat_2[] = "_AcadosOcpSolverCython__get_stat_double"; +static const char __pyx_k_AcadosOcpSolverCython__get_stat_3[] = "_AcadosOcpSolverCython__get_stat_matrix"; +static const char __pyx_k_AcadosOcpSolverCython___get_stat_2[] = "AcadosOcpSolverCython.__get_stat_double"; +static const char __pyx_k_AcadosOcpSolverCython___get_stat_3[] = "AcadosOcpSolverCython.__get_stat_matrix"; +static const char __pyx_k_AcadosOcpSolverCython_constraint_2[] = "AcadosOcpSolverCython.constraints_set"; +static const char __pyx_k_AcadosOcpSolverCython_does_not_s_2[] = "AcadosOcpSolverCython: does not support update_qp_solver_cond_N() since it is only a prototyping feature"; +static const char __pyx_k_AcadosOcpSolverCython_eval_param_2[] = "AcadosOcpSolverCython.eval_param_sens(): index must be in [0, nx-1], got: "; +static const char __pyx_k_AcadosOcpSolverCython_eval_param_3[] = "AcadosOcpSolverCython.eval_param_sens"; +static const char __pyx_k_AcadosOcpSolverCython_options_se_2[] = "AcadosOcpSolverCython.options_set"; +static const char __pyx_k_AcadosOcpSolverCython_solve_argu_2[] = "AcadosOcpSolverCython.solve(): argument 'rti_phase' can take only value 0 for SQP-type solvers"; +/* #### Code section: decls ### */ +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array___cinit__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_shape, Py_ssize_t __pyx_v_itemsize, PyObject *__pyx_v_format, PyObject *__pyx_v_mode, int __pyx_v_allocate_buffer); /* proto */ +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_2__getbuffer__(struct __pyx_array_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /* proto */ +static void __pyx_array___pyx_pf_15View_dot_MemoryView_5array_4__dealloc__(struct __pyx_array_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_5array_7memview___get__(struct __pyx_array_obj *__pyx_v_self); /* proto */ +static Py_ssize_t __pyx_array___pyx_pf_15View_dot_MemoryView_5array_6__len__(struct __pyx_array_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_8__getattr__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_attr); /* proto */ +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_10__getitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item); /* proto */ +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_12__setitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value); /* proto */ +static PyObject *__pyx_pf___pyx_array___reduce_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_array_2__setstate_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum___init__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v_name); /* proto */ +static PyObject *__pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum_2__repr__(struct __pyx_MemviewEnum_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_MemviewEnum___reduce_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_MemviewEnum_2__setstate_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview___cinit__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj, int __pyx_v_flags, int __pyx_v_dtype_is_object); /* proto */ +static void __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_2__dealloc__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_4__getitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index); /* proto */ +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_6__setitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value); /* proto */ +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_8__getbuffer__(struct __pyx_memoryview_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_1T___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4base___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_5shape___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_7strides___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_10suboffsets___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4ndim___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_8itemsize___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_6nbytes___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4size___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static Py_ssize_t __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_10__len__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_12__repr__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_14__str__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_16is_c_contig(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_18is_f_contig(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_20copy(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_22copy_fortran(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryview___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryview_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static void __pyx_memoryviewslice___pyx_pf_15View_dot_MemoryView_16_memoryviewslice___dealloc__(struct __pyx_memoryviewslice_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryviewslice___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryviewslice_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView___pyx_unpickle_Enum(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v___pyx_type, long __pyx_v___pyx_checksum, PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython___cinit__(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_model_name, PyObject *__pyx_v_nlp_solver_type, PyObject *__pyx_v_N); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_2__get_pointers_solver(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve_for_x0(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_x0_bar); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6solve(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8reset(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_reset_qp_solver_mem); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10custom_update(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_data_); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12set_new_time_steps(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_new_time_steps); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14update_qp_solver_cond_N(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_qp_solver_cond_N); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16eval_param_sens(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_stage, PyObject *__pyx_v_field); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18get(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20print_statistics(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ +static PyObject *__pyx_lambda_funcdef_lambda(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_x); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22store_iterate(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_filename, PyObject *__pyx_v_overwrite); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_24load_iterate(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_filename); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_26get_stats(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field_); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_28__get_stat_int(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_30__get_stat_double(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_32__get_stat_matrix(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field, PyObject *__pyx_v_n, PyObject *__pyx_v_m); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34get_cost(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36get_residuals(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_recompute); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40cost_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42constraints_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_44get_from_qp_in(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_46options_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_48set_params_sparse(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_idx_values_, PyObject *__pyx_v_param_values_); /* proto */ +static void __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_50__del__(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_52__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_54__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_tp_new_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_array(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_Enum(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_memoryview(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new__memoryviewslice(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static __Pyx_CachedCFunction __pyx_umethod_PyDict_Type_keys = {0, 0, 0, 0, 0}; +/* #### Code section: late_includes ### */ +/* #### Code section: module_state ### */ +typedef struct { + PyObject *__pyx_d; + PyObject *__pyx_b; + PyObject *__pyx_cython_runtime; + PyObject *__pyx_empty_tuple; + PyObject *__pyx_empty_bytes; + PyObject *__pyx_empty_unicode; + #ifdef __Pyx_CyFunction_USED + PyTypeObject *__pyx_CyFunctionType; + #endif + #ifdef __Pyx_FusedFunction_USED + PyTypeObject *__pyx_FusedFunctionType; + #endif + #ifdef __Pyx_Generator_USED + PyTypeObject *__pyx_GeneratorType; + #endif + #ifdef __Pyx_IterableCoroutine_USED + PyTypeObject *__pyx_IterableCoroutineType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineAwaitType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineType; + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + PyTypeObject *__pyx_ptype_7cpython_4type_type; + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + PyTypeObject *__pyx_ptype_5numpy_dtype; + PyTypeObject *__pyx_ptype_5numpy_flatiter; + PyTypeObject *__pyx_ptype_5numpy_broadcast; + PyTypeObject *__pyx_ptype_5numpy_ndarray; + PyTypeObject *__pyx_ptype_5numpy_generic; + PyTypeObject *__pyx_ptype_5numpy_number; + PyTypeObject *__pyx_ptype_5numpy_integer; + PyTypeObject *__pyx_ptype_5numpy_signedinteger; + PyTypeObject *__pyx_ptype_5numpy_unsignedinteger; + PyTypeObject *__pyx_ptype_5numpy_inexact; + PyTypeObject *__pyx_ptype_5numpy_floating; + PyTypeObject *__pyx_ptype_5numpy_complexfloating; + PyTypeObject *__pyx_ptype_5numpy_flexible; + PyTypeObject *__pyx_ptype_5numpy_character; + PyTypeObject *__pyx_ptype_5numpy_ufunc; + #if CYTHON_USE_MODULE_STATE + PyObject *__pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython; + PyObject *__pyx_type___pyx_array; + PyObject *__pyx_type___pyx_MemviewEnum; + PyObject *__pyx_type___pyx_memoryview; + PyObject *__pyx_type___pyx_memoryviewslice; + #endif + PyTypeObject *__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython; + PyTypeObject *__pyx_array_type; + PyTypeObject *__pyx_MemviewEnum_type; + PyTypeObject *__pyx_memoryview_type; + PyTypeObject *__pyx_memoryviewslice_type; + PyObject *__pyx_kp_u_; + PyObject *__pyx_kp_u_0; + PyObject *__pyx_n_s_ASCII; + PyObject *__pyx_n_s_AcadosOcpSolverCython; + PyObject *__pyx_n_s_AcadosOcpSolverCython___get_poin; + PyObject *__pyx_n_s_AcadosOcpSolverCython___get_stat; + PyObject *__pyx_n_s_AcadosOcpSolverCython___get_stat_2; + PyObject *__pyx_n_s_AcadosOcpSolverCython___get_stat_3; + PyObject *__pyx_n_s_AcadosOcpSolverCython___reduce_c; + PyObject *__pyx_n_s_AcadosOcpSolverCython___setstate; + PyObject *__pyx_n_s_AcadosOcpSolverCython__get_poin; + PyObject *__pyx_n_s_AcadosOcpSolverCython__get_stat; + PyObject *__pyx_n_s_AcadosOcpSolverCython__get_stat_2; + PyObject *__pyx_n_s_AcadosOcpSolverCython__get_stat_3; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_constraint; + PyObject *__pyx_n_s_AcadosOcpSolverCython_constraint_2; + PyObject *__pyx_n_s_AcadosOcpSolverCython_cost_set; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_cost_set_m; + PyObject *__pyx_n_s_AcadosOcpSolverCython_custom_upd; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_does_not_s; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_does_not_s_2; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_eval_param; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_eval_param_2; + PyObject *__pyx_n_s_AcadosOcpSolverCython_eval_param_3; + PyObject *__pyx_n_s_AcadosOcpSolverCython_get; + PyObject *__pyx_n_s_AcadosOcpSolverCython_get_cost; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_get_field; + PyObject *__pyx_n_s_AcadosOcpSolverCython_get_from_q; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_get_is_an; + PyObject *__pyx_n_s_AcadosOcpSolverCython_get_residu; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_get_stage; + PyObject *__pyx_n_s_AcadosOcpSolverCython_get_stats; + PyObject *__pyx_n_s_AcadosOcpSolverCython_load_itera; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_options_se; + PyObject *__pyx_n_s_AcadosOcpSolverCython_options_se_2; + PyObject *__pyx_n_s_AcadosOcpSolverCython_print_stat; + PyObject *__pyx_n_s_AcadosOcpSolverCython_reset; + PyObject *__pyx_n_s_AcadosOcpSolverCython_set; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_set_is_not; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_set_mismat; + PyObject *__pyx_n_s_AcadosOcpSolverCython_set_new_ti; + PyObject *__pyx_n_s_AcadosOcpSolverCython_set_params; + PyObject *__pyx_n_s_AcadosOcpSolverCython_solve; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_solve_argu; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_solve_argu_2; + PyObject *__pyx_n_s_AcadosOcpSolverCython_solve_for; + PyObject *__pyx_n_s_AcadosOcpSolverCython_store_iter; + PyObject *__pyx_n_s_AcadosOcpSolverCython_update_qp; + PyObject *__pyx_kp_s_All_dimensions_preceding_dimensi; + PyObject *__pyx_n_s_AssertionError; + PyObject *__pyx_kp_s_Buffer_view_does_not_expose_stri; + PyObject *__pyx_kp_s_Can_only_create_a_buffer_that_is; + PyObject *__pyx_kp_s_Cannot_assign_to_read_only_memor; + PyObject *__pyx_kp_s_Cannot_create_writable_memory_vi; + PyObject *__pyx_kp_u_Cannot_index_with_type; + PyObject *__pyx_kp_s_Cannot_transpose_memoryview_with; + PyObject *__pyx_kp_s_Dimension_d_is_not_direct; + PyObject *__pyx_n_s_Ellipsis; + PyObject *__pyx_kp_s_Empty_shape_tuple_for_cython_arr; + PyObject *__pyx_n_u_F; + PyObject *__pyx_kp_u_Got_sizes_idx; + PyObject *__pyx_n_s_ImportError; + PyObject *__pyx_kp_s_Incompatible_checksums_0x_x_vs_0; + PyObject *__pyx_n_s_IndexError; + PyObject *__pyx_kp_s_Index_out_of_bounds_axis_d; + PyObject *__pyx_kp_s_Indirect_dimensions_not_supporte; + PyObject *__pyx_kp_u_Invalid_mode_expected_c_or_fortr; + PyObject *__pyx_kp_u_Invalid_shape_in_axis; + PyObject *__pyx_n_s_MemoryError; + PyObject *__pyx_kp_s_MemoryView_of_r_at_0x_x; + PyObject *__pyx_kp_s_MemoryView_of_r_object; + PyObject *__pyx_n_s_N; + PyObject *__pyx_kp_u_None; + PyObject *__pyx_n_s_NotImplementedError; + PyObject *__pyx_n_b_O; + PyObject *__pyx_kp_u_Out_of_bounds_on_buffer_access_a; + PyObject *__pyx_n_s_PickleError; + PyObject *__pyx_n_u_SQP; + PyObject *__pyx_n_u_SQP_RTI; + PyObject *__pyx_n_s_Sequence; + PyObject *__pyx_kp_s_Step_may_not_be_zero_axis_d; + PyObject *__pyx_kp_u_TODO; + PyObject *__pyx_n_s_TypeError; + PyObject *__pyx_kp_s_Unable_to_convert_item_to_object; + PyObject *__pyx_n_s_ValueError; + PyObject *__pyx_n_s_View_MemoryView; + PyObject *__pyx_kp_u_Warning_acados_ocp_solver_reache; + PyObject *__pyx_kp_u_Y_m_d_H_M_S_f; + PyObject *__pyx_kp_u__16; + PyObject *__pyx_n_u__17; + PyObject *__pyx_kp_u__2; + PyObject *__pyx_n_s__3; + PyObject *__pyx_kp_u__31; + PyObject *__pyx_kp_u__6; + PyObject *__pyx_kp_u__7; + PyObject *__pyx_n_s__94; + PyObject *__pyx_n_s_abc; + PyObject *__pyx_kp_u_acados_acados_ocp_solver_returne; + PyObject *__pyx_n_s_acados_template_acados_ocp_solve; + PyObject *__pyx_n_s_allocate_buffer; + PyObject *__pyx_n_u_alpha; + PyObject *__pyx_n_u_alpha_min; + PyObject *__pyx_n_u_alpha_reduction; + PyObject *__pyx_kp_u_alpha_values_are_not_available_f; + PyObject *__pyx_kp_u_and; + PyObject *__pyx_n_s_array; + PyObject *__pyx_n_s_ascontiguousarray; + PyObject *__pyx_n_s_asfortranarray; + PyObject *__pyx_n_s_asyncio_coroutines; + PyObject *__pyx_kp_u_at_stage; + PyObject *__pyx_n_s_base; + PyObject *__pyx_n_s_c; + PyObject *__pyx_n_u_c; + PyObject *__pyx_n_s_class; + PyObject *__pyx_n_s_class_getitem; + PyObject *__pyx_n_s_cline_in_traceback; + PyObject *__pyx_n_s_collections; + PyObject *__pyx_kp_s_collections_abc; + PyObject *__pyx_n_s_constraints_fields; + PyObject *__pyx_n_s_constraints_set; + PyObject *__pyx_kp_u_constraints_set_value_must_be_nu; + PyObject *__pyx_kp_s_contiguous_and_direct; + PyObject *__pyx_kp_s_contiguous_and_indirect; + PyObject *__pyx_n_s_cost_fields; + PyObject *__pyx_n_s_cost_set; + PyObject *__pyx_kp_u_cost_set_value_must_be_numpy_arr; + PyObject *__pyx_n_s_count; + PyObject *__pyx_n_s_custom_update; + PyObject *__pyx_n_u_d; + PyObject *__pyx_n_s_data; + PyObject *__pyx_n_s_data_2; + PyObject *__pyx_n_s_data_len; + PyObject *__pyx_n_s_datetime; + PyObject *__pyx_n_s_default; + PyObject *__pyx_n_s_dict; + PyObject *__pyx_n_s_dims; + PyObject *__pyx_kp_u_disable; + PyObject *__pyx_n_s_double_fields; + PyObject *__pyx_n_s_double_value; + PyObject *__pyx_n_s_dtype; + PyObject *__pyx_n_s_dtype_is_object; + PyObject *__pyx_n_s_dump; + PyObject *__pyx_kp_u_enable; + PyObject *__pyx_n_s_encode; + PyObject *__pyx_n_s_enter; + PyObject *__pyx_n_s_enumerate; + PyObject *__pyx_n_u_eps_sufficient_descent; + PyObject *__pyx_n_s_error; + PyObject *__pyx_n_s_eval_param_sens; + PyObject *__pyx_n_u_ex; + PyObject *__pyx_n_s_exit; + PyObject *__pyx_n_s_f; + PyObject *__pyx_n_s_field; + PyObject *__pyx_n_s_field_2; + PyObject *__pyx_n_s_fields; + PyObject *__pyx_n_s_filename; + PyObject *__pyx_n_s_flags; + PyObject *__pyx_n_s_float64; + PyObject *__pyx_kp_u_for_field; + PyObject *__pyx_n_s_format; + PyObject *__pyx_n_s_fortran; + PyObject *__pyx_n_u_fortran; + PyObject *__pyx_n_s_full_stats; + PyObject *__pyx_n_u_full_step_dual; + PyObject *__pyx_kp_u_gc; + PyObject *__pyx_n_s_get; + PyObject *__pyx_n_s_get_cost; + PyObject *__pyx_n_s_get_from_qp_in; + PyObject *__pyx_n_s_get_pointers_solver; + PyObject *__pyx_n_s_get_residuals; + PyObject *__pyx_n_s_get_stat_double; + PyObject *__pyx_n_s_get_stat_int; + PyObject *__pyx_n_s_get_stat_matrix; + PyObject *__pyx_n_s_get_stats; + PyObject *__pyx_n_s_getcwd; + PyObject *__pyx_n_s_getstate; + PyObject *__pyx_n_u_globalization; + PyObject *__pyx_n_u_globalization_use_SOC; + PyObject *__pyx_kp_u_got; + PyObject *__pyx_kp_u_got_differing_extents_in_dimensi; + PyObject *__pyx_n_s_i; + PyObject *__pyx_n_s_i_string; + PyObject *__pyx_n_s_id; + PyObject *__pyx_n_s_idx; + PyObject *__pyx_n_s_idx_values; + PyObject *__pyx_n_s_import; + PyObject *__pyx_n_s_indent; + PyObject *__pyx_n_s_index; + PyObject *__pyx_n_u_initialize_t_slacks; + PyObject *__pyx_n_s_initializing; + PyObject *__pyx_n_s_int; + PyObject *__pyx_n_s_int32; + PyObject *__pyx_n_s_int_fields; + PyObject *__pyx_n_s_int_value; + PyObject *__pyx_n_s_is_coroutine; + PyObject *__pyx_kp_u_isenabled; + PyObject *__pyx_n_s_isfile; + PyObject *__pyx_n_s_itemsize; + PyObject *__pyx_kp_s_itemsize_0_for_cython_array; + PyObject *__pyx_n_u_iterate; + PyObject *__pyx_n_s_join; + PyObject *__pyx_n_s_json; + PyObject *__pyx_kp_u_json_2; + PyObject *__pyx_n_s_k; + PyObject *__pyx_n_s_key; + PyObject *__pyx_n_s_keys; + PyObject *__pyx_n_s_lN; + PyObject *__pyx_n_u_lam; + PyObject *__pyx_n_u_lam_2; + PyObject *__pyx_n_u_lbu; + PyObject *__pyx_n_u_lbx; + PyObject *__pyx_n_u_line_search_use_sufficient_desce; + PyObject *__pyx_n_s_load; + PyObject *__pyx_n_s_load_iterate; + PyObject *__pyx_kp_u_load_iterate_failed_file_does_no; + PyObject *__pyx_n_s_m; + PyObject *__pyx_n_s_main; + PyObject *__pyx_n_s_mem_fields; + PyObject *__pyx_n_s_memview; + PyObject *__pyx_n_s_min_size; + PyObject *__pyx_n_s_mode; + PyObject *__pyx_n_s_model_name; + PyObject *__pyx_n_s_msg; + PyObject *__pyx_n_s_n; + PyObject *__pyx_n_s_n_update; + PyObject *__pyx_n_s_name; + PyObject *__pyx_n_s_name_2; + PyObject *__pyx_n_s_ndarray; + PyObject *__pyx_n_s_ndim; + PyObject *__pyx_n_s_new; + PyObject *__pyx_n_s_new_time_steps; + PyObject *__pyx_n_s_nlp_solver_type; + PyObject *__pyx_kp_s_no_default___reduce___due_to_non; + PyObject *__pyx_n_s_np; + PyObject *__pyx_n_s_numpy; + PyObject *__pyx_kp_u_numpy_core_multiarray_failed_to; + PyObject *__pyx_kp_u_numpy_core_umath_failed_to_impor; + PyObject *__pyx_n_s_nx; + PyObject *__pyx_n_s_obj; + PyObject *__pyx_n_s_open; + PyObject *__pyx_n_s_options_set; + PyObject *__pyx_n_s_order; + PyObject *__pyx_n_s_os; + PyObject *__pyx_n_s_out; + PyObject *__pyx_n_s_out_fields; + PyObject *__pyx_n_s_out_mat; + PyObject *__pyx_n_s_overwrite; + PyObject *__pyx_n_u_p; + PyObject *__pyx_n_s_pack; + PyObject *__pyx_n_s_param_values; + PyObject *__pyx_kp_u_param_values_2; + PyObject *__pyx_kp_u_param_values__and_idx_values__mu; + PyObject *__pyx_kp_u_param_values__must_be_np_array; + PyObject *__pyx_n_s_path; + PyObject *__pyx_n_u_pi; + PyObject *__pyx_n_u_pi_2; + PyObject *__pyx_n_s_pickle; + PyObject *__pyx_n_s_print; + PyObject *__pyx_n_u_print_level; + PyObject *__pyx_n_s_print_statistics; + PyObject *__pyx_n_s_pyx_PickleError; + PyObject *__pyx_n_s_pyx_checksum; + PyObject *__pyx_n_s_pyx_result; + PyObject *__pyx_n_s_pyx_state; + PyObject *__pyx_n_s_pyx_type; + PyObject *__pyx_n_s_pyx_unpickle_Enum; + PyObject *__pyx_n_s_pyx_vtable; + PyObject *__pyx_n_u_qp_iter; + PyObject *__pyx_n_u_qp_mu0; + PyObject *__pyx_n_s_qp_solver_cond_N; + PyObject *__pyx_n_u_qp_tau_min; + PyObject *__pyx_n_u_qp_tol_comp; + PyObject *__pyx_n_u_qp_tol_eq; + PyObject *__pyx_n_u_qp_tol_ineq; + PyObject *__pyx_n_u_qp_tol_stat; + PyObject *__pyx_n_u_qp_warm_start; + PyObject *__pyx_n_u_r; + PyObject *__pyx_n_s_range; + PyObject *__pyx_n_s_recompute; + PyObject *__pyx_n_s_reduce; + PyObject *__pyx_n_s_reduce_cython; + PyObject *__pyx_n_s_reduce_ex; + PyObject *__pyx_n_s_register; + PyObject *__pyx_n_b_res_comp; + PyObject *__pyx_n_b_res_eq; + PyObject *__pyx_n_b_res_ineq; + PyObject *__pyx_n_b_res_stat; + PyObject *__pyx_n_s_reset; + PyObject *__pyx_n_s_reset_qp_solver_mem; + PyObject *__pyx_n_u_residuals; + PyObject *__pyx_n_u_rti_phase; + PyObject *__pyx_n_s_self; + PyObject *__pyx_n_s_set; + PyObject *__pyx_n_s_set_new_time_steps; + PyObject *__pyx_n_s_set_params_sparse; + PyObject *__pyx_kp_u_set_value_must_be_numpy_array_go; + PyObject *__pyx_n_s_setstate; + PyObject *__pyx_n_s_setstate_cython; + PyObject *__pyx_n_s_shape; + PyObject *__pyx_n_s_size; + PyObject *__pyx_n_u_sl; + PyObject *__pyx_n_u_sl_2; + PyObject *__pyx_n_s_solution; + PyObject *__pyx_n_s_solve; + PyObject *__pyx_n_s_solve_for_x0; + PyObject *__pyx_kp_u_solver_option_must_be_of_type_fl; + PyObject *__pyx_kp_u_solver_option_must_be_of_type_in; + PyObject *__pyx_kp_u_solver_option_must_be_of_type_st; + PyObject *__pyx_n_s_sort_keys; + PyObject *__pyx_n_s_spec; + PyObject *__pyx_n_s_split; + PyObject *__pyx_n_s_sqp_iter; + PyObject *__pyx_n_u_sqp_iter; + PyObject *__pyx_n_s_stage; + PyObject *__pyx_n_s_start; + PyObject *__pyx_n_s_stat_m; + PyObject *__pyx_n_u_stat_m; + PyObject *__pyx_n_s_stat_n; + PyObject *__pyx_n_u_stat_n; + PyObject *__pyx_n_u_statistics; + PyObject *__pyx_n_s_status; + PyObject *__pyx_n_s_step; + PyObject *__pyx_n_u_step_length; + PyObject *__pyx_n_s_stop; + PyObject *__pyx_n_s_store_iterate; + PyObject *__pyx_n_s_store_iterate_locals_lambda; + PyObject *__pyx_kp_u_stored_current_iterate_in; + PyObject *__pyx_n_s_strftime; + PyObject *__pyx_kp_s_strided_and_direct; + PyObject *__pyx_kp_s_strided_and_direct_or_indirect; + PyObject *__pyx_kp_s_strided_and_indirect; + PyObject *__pyx_n_s_string_fields; + PyObject *__pyx_n_s_string_value; + PyObject *__pyx_kp_s_stringsource; + PyObject *__pyx_n_s_struct; + PyObject *__pyx_n_u_su; + PyObject *__pyx_n_u_su_2; + PyObject *__pyx_n_s_sys; + PyObject *__pyx_n_u_t; + PyObject *__pyx_n_u_t_2; + PyObject *__pyx_n_s_test; + PyObject *__pyx_kp_s_third_party_acados_acados_templa; + PyObject *__pyx_n_u_time_glob; + PyObject *__pyx_n_u_time_lin; + PyObject *__pyx_n_u_time_qp; + PyObject *__pyx_n_u_time_qp_solver_call; + PyObject *__pyx_n_u_time_qp_xcond; + PyObject *__pyx_n_u_time_reg; + PyObject *__pyx_n_u_time_sim; + PyObject *__pyx_n_u_time_sim_ad; + PyObject *__pyx_n_u_time_sim_la; + PyObject *__pyx_n_u_time_solution_sensitivities; + PyObject *__pyx_n_u_time_tot; + PyObject *__pyx_n_u_tol_comp; + PyObject *__pyx_n_u_tol_eq; + PyObject *__pyx_n_u_tol_ineq; + PyObject *__pyx_n_u_tol_stat; + PyObject *__pyx_n_s_tolist; + PyObject *__pyx_n_u_u; + PyObject *__pyx_n_s_u0; + PyObject *__pyx_n_u_u_2; + PyObject *__pyx_n_u_ubu; + PyObject *__pyx_n_u_ubx; + PyObject *__pyx_kp_s_unable_to_allocate_array_data; + PyObject *__pyx_kp_s_unable_to_allocate_shape_and_str; + PyObject *__pyx_n_s_unpack; + PyObject *__pyx_n_s_update; + PyObject *__pyx_n_s_update_qp_solver_cond_N; + PyObject *__pyx_n_s_utcnow; + PyObject *__pyx_kp_u_utf_8; + PyObject *__pyx_n_s_value; + PyObject *__pyx_n_s_value_2; + PyObject *__pyx_n_s_value_shape; + PyObject *__pyx_n_s_version_info; + PyObject *__pyx_n_u_w; + PyObject *__pyx_n_u_warm_start_first_qp; + PyObject *__pyx_kp_u_with_dimension; + PyObject *__pyx_kp_u_with_dimension_you_have; + PyObject *__pyx_n_b_x; + PyObject *__pyx_n_s_x; + PyObject *__pyx_n_u_x; + PyObject *__pyx_n_s_x0_bar; + PyObject *__pyx_n_u_x_2; + PyObject *__pyx_n_u_xdot_guess; + PyObject *__pyx_n_u_y_ref; + PyObject *__pyx_kp_u_you_have; + PyObject *__pyx_n_u_yref; + PyObject *__pyx_n_u_z; + PyObject *__pyx_n_u_z_2; + PyObject *__pyx_n_b_z_guess; + PyObject *__pyx_n_u_z_guess; + PyObject *__pyx_n_s_zeros; + PyObject *__pyx_int_0; + PyObject *__pyx_int_1; + PyObject *__pyx_int_2; + PyObject *__pyx_int_3; + PyObject *__pyx_int_4; + PyObject *__pyx_int_6; + PyObject *__pyx_int_7; + PyObject *__pyx_int_112105877; + PyObject *__pyx_int_136983863; + PyObject *__pyx_int_184977713; + PyObject *__pyx_int_neg_1; + PyObject *__pyx_int_neg_5; + PyObject *__pyx_slice__5; + PyObject *__pyx_tuple__4; + PyObject *__pyx_tuple__8; + PyObject *__pyx_tuple__9; + PyObject *__pyx_slice__18; + PyObject *__pyx_tuple__10; + PyObject *__pyx_tuple__11; + PyObject *__pyx_tuple__12; + PyObject *__pyx_tuple__13; + PyObject *__pyx_tuple__14; + PyObject *__pyx_tuple__15; + PyObject *__pyx_tuple__19; + PyObject *__pyx_tuple__20; + PyObject *__pyx_tuple__21; + PyObject *__pyx_tuple__22; + PyObject *__pyx_tuple__23; + PyObject *__pyx_tuple__24; + PyObject *__pyx_tuple__25; + PyObject *__pyx_tuple__26; + PyObject *__pyx_tuple__27; + PyObject *__pyx_tuple__28; + PyObject *__pyx_tuple__29; + PyObject *__pyx_tuple__30; + PyObject *__pyx_tuple__32; + PyObject *__pyx_tuple__33; + PyObject *__pyx_tuple__34; + PyObject *__pyx_tuple__35; + PyObject *__pyx_tuple__36; + PyObject *__pyx_tuple__37; + PyObject *__pyx_tuple__38; + PyObject *__pyx_tuple__39; + PyObject *__pyx_tuple__40; + PyObject *__pyx_tuple__41; + PyObject *__pyx_tuple__42; + PyObject *__pyx_tuple__44; + PyObject *__pyx_tuple__46; + PyObject *__pyx_tuple__49; + PyObject *__pyx_tuple__51; + PyObject *__pyx_tuple__53; + PyObject *__pyx_tuple__55; + PyObject *__pyx_tuple__57; + PyObject *__pyx_tuple__59; + PyObject *__pyx_tuple__60; + PyObject *__pyx_tuple__63; + PyObject *__pyx_tuple__65; + PyObject *__pyx_tuple__66; + PyObject *__pyx_tuple__68; + PyObject *__pyx_tuple__70; + PyObject *__pyx_tuple__73; + PyObject *__pyx_tuple__75; + PyObject *__pyx_tuple__77; + PyObject *__pyx_tuple__79; + PyObject *__pyx_tuple__80; + PyObject *__pyx_tuple__82; + PyObject *__pyx_tuple__85; + PyObject *__pyx_tuple__87; + PyObject *__pyx_tuple__89; + PyObject *__pyx_tuple__92; + PyObject *__pyx_codeobj__43; + PyObject *__pyx_codeobj__45; + PyObject *__pyx_codeobj__47; + PyObject *__pyx_codeobj__48; + PyObject *__pyx_codeobj__50; + PyObject *__pyx_codeobj__52; + PyObject *__pyx_codeobj__54; + PyObject *__pyx_codeobj__56; + PyObject *__pyx_codeobj__58; + PyObject *__pyx_codeobj__61; + PyObject *__pyx_codeobj__62; + PyObject *__pyx_codeobj__64; + PyObject *__pyx_codeobj__67; + PyObject *__pyx_codeobj__69; + PyObject *__pyx_codeobj__71; + PyObject *__pyx_codeobj__72; + PyObject *__pyx_codeobj__74; + PyObject *__pyx_codeobj__76; + PyObject *__pyx_codeobj__78; + PyObject *__pyx_codeobj__81; + PyObject *__pyx_codeobj__83; + PyObject *__pyx_codeobj__84; + PyObject *__pyx_codeobj__86; + PyObject *__pyx_codeobj__88; + PyObject *__pyx_codeobj__90; + PyObject *__pyx_codeobj__91; + PyObject *__pyx_codeobj__93; +} __pyx_mstate; + +#if CYTHON_USE_MODULE_STATE +#ifdef __cplusplus +namespace { + extern struct PyModuleDef __pyx_moduledef; +} /* anonymous namespace */ +#else +static struct PyModuleDef __pyx_moduledef; +#endif + +#define __pyx_mstate(o) ((__pyx_mstate *)__Pyx_PyModule_GetState(o)) + +#define __pyx_mstate_global (__pyx_mstate(PyState_FindModule(&__pyx_moduledef))) + +#define __pyx_m (PyState_FindModule(&__pyx_moduledef)) +#else +static __pyx_mstate __pyx_mstate_global_static = +#ifdef __cplusplus + {}; +#else + {0}; +#endif +static __pyx_mstate *__pyx_mstate_global = &__pyx_mstate_global_static; +#endif +/* #### Code section: module_state_clear ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_clear(PyObject *m) { + __pyx_mstate *clear_module_state = __pyx_mstate(m); + if (!clear_module_state) return 0; + Py_CLEAR(clear_module_state->__pyx_d); + Py_CLEAR(clear_module_state->__pyx_b); + Py_CLEAR(clear_module_state->__pyx_cython_runtime); + Py_CLEAR(clear_module_state->__pyx_empty_tuple); + Py_CLEAR(clear_module_state->__pyx_empty_bytes); + Py_CLEAR(clear_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_CLEAR(clear_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_CLEAR(clear_module_state->__pyx_FusedFunctionType); + #endif + Py_CLEAR(clear_module_state->__pyx_ptype_7cpython_4type_type); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_dtype); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_flatiter); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_broadcast); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_ndarray); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_generic); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_number); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_integer); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_signedinteger); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_unsignedinteger); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_inexact); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_floating); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_complexfloating); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_flexible); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_character); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_ufunc); + Py_CLEAR(clear_module_state->__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + Py_CLEAR(clear_module_state->__pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + Py_CLEAR(clear_module_state->__pyx_array_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_array); + Py_CLEAR(clear_module_state->__pyx_MemviewEnum_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_MemviewEnum); + Py_CLEAR(clear_module_state->__pyx_memoryview_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_memoryview); + Py_CLEAR(clear_module_state->__pyx_memoryviewslice_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_memoryviewslice); + Py_CLEAR(clear_module_state->__pyx_kp_u_); + Py_CLEAR(clear_module_state->__pyx_kp_u_0); + Py_CLEAR(clear_module_state->__pyx_n_s_ASCII); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython___get_poin); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython___get_stat); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython___get_stat_2); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython___get_stat_3); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython___reduce_c); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython___setstate); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython__get_poin); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython__get_stat); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython__get_stat_2); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython__get_stat_3); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_constraint); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_constraint_2); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_cost_set); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_cost_set_m); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_custom_upd); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_does_not_s); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_does_not_s_2); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_eval_param); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_eval_param_2); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_eval_param_3); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_get); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_get_cost); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_get_field); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_get_from_q); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_get_is_an); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_get_residu); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_get_stage); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_get_stats); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_load_itera); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_options_se); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_options_se_2); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_print_stat); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_reset); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_set); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_set_is_not); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_set_mismat); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_set_new_ti); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_set_params); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_solve); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_solve_argu); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_solve_argu_2); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_solve_for); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_store_iter); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_update_qp); + Py_CLEAR(clear_module_state->__pyx_kp_s_All_dimensions_preceding_dimensi); + Py_CLEAR(clear_module_state->__pyx_n_s_AssertionError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Buffer_view_does_not_expose_stri); + Py_CLEAR(clear_module_state->__pyx_kp_s_Can_only_create_a_buffer_that_is); + Py_CLEAR(clear_module_state->__pyx_kp_s_Cannot_assign_to_read_only_memor); + Py_CLEAR(clear_module_state->__pyx_kp_s_Cannot_create_writable_memory_vi); + Py_CLEAR(clear_module_state->__pyx_kp_u_Cannot_index_with_type); + Py_CLEAR(clear_module_state->__pyx_kp_s_Cannot_transpose_memoryview_with); + Py_CLEAR(clear_module_state->__pyx_kp_s_Dimension_d_is_not_direct); + Py_CLEAR(clear_module_state->__pyx_n_s_Ellipsis); + Py_CLEAR(clear_module_state->__pyx_kp_s_Empty_shape_tuple_for_cython_arr); + Py_CLEAR(clear_module_state->__pyx_n_u_F); + Py_CLEAR(clear_module_state->__pyx_kp_u_Got_sizes_idx); + Py_CLEAR(clear_module_state->__pyx_n_s_ImportError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0); + Py_CLEAR(clear_module_state->__pyx_n_s_IndexError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Index_out_of_bounds_axis_d); + Py_CLEAR(clear_module_state->__pyx_kp_s_Indirect_dimensions_not_supporte); + Py_CLEAR(clear_module_state->__pyx_kp_u_Invalid_mode_expected_c_or_fortr); + Py_CLEAR(clear_module_state->__pyx_kp_u_Invalid_shape_in_axis); + Py_CLEAR(clear_module_state->__pyx_n_s_MemoryError); + Py_CLEAR(clear_module_state->__pyx_kp_s_MemoryView_of_r_at_0x_x); + Py_CLEAR(clear_module_state->__pyx_kp_s_MemoryView_of_r_object); + Py_CLEAR(clear_module_state->__pyx_n_s_N); + Py_CLEAR(clear_module_state->__pyx_kp_u_None); + Py_CLEAR(clear_module_state->__pyx_n_s_NotImplementedError); + Py_CLEAR(clear_module_state->__pyx_n_b_O); + Py_CLEAR(clear_module_state->__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + Py_CLEAR(clear_module_state->__pyx_n_s_PickleError); + Py_CLEAR(clear_module_state->__pyx_n_u_SQP); + Py_CLEAR(clear_module_state->__pyx_n_u_SQP_RTI); + Py_CLEAR(clear_module_state->__pyx_n_s_Sequence); + Py_CLEAR(clear_module_state->__pyx_kp_s_Step_may_not_be_zero_axis_d); + Py_CLEAR(clear_module_state->__pyx_kp_u_TODO); + Py_CLEAR(clear_module_state->__pyx_n_s_TypeError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Unable_to_convert_item_to_object); + Py_CLEAR(clear_module_state->__pyx_n_s_ValueError); + Py_CLEAR(clear_module_state->__pyx_n_s_View_MemoryView); + Py_CLEAR(clear_module_state->__pyx_kp_u_Warning_acados_ocp_solver_reache); + Py_CLEAR(clear_module_state->__pyx_kp_u_Y_m_d_H_M_S_f); + Py_CLEAR(clear_module_state->__pyx_kp_u__16); + Py_CLEAR(clear_module_state->__pyx_n_u__17); + Py_CLEAR(clear_module_state->__pyx_kp_u__2); + Py_CLEAR(clear_module_state->__pyx_n_s__3); + Py_CLEAR(clear_module_state->__pyx_kp_u__31); + Py_CLEAR(clear_module_state->__pyx_kp_u__6); + Py_CLEAR(clear_module_state->__pyx_kp_u__7); + Py_CLEAR(clear_module_state->__pyx_n_s__94); + Py_CLEAR(clear_module_state->__pyx_n_s_abc); + Py_CLEAR(clear_module_state->__pyx_kp_u_acados_acados_ocp_solver_returne); + Py_CLEAR(clear_module_state->__pyx_n_s_acados_template_acados_ocp_solve); + Py_CLEAR(clear_module_state->__pyx_n_s_allocate_buffer); + Py_CLEAR(clear_module_state->__pyx_n_u_alpha); + Py_CLEAR(clear_module_state->__pyx_n_u_alpha_min); + Py_CLEAR(clear_module_state->__pyx_n_u_alpha_reduction); + Py_CLEAR(clear_module_state->__pyx_kp_u_alpha_values_are_not_available_f); + Py_CLEAR(clear_module_state->__pyx_kp_u_and); + Py_CLEAR(clear_module_state->__pyx_n_s_array); + Py_CLEAR(clear_module_state->__pyx_n_s_ascontiguousarray); + Py_CLEAR(clear_module_state->__pyx_n_s_asfortranarray); + Py_CLEAR(clear_module_state->__pyx_n_s_asyncio_coroutines); + Py_CLEAR(clear_module_state->__pyx_kp_u_at_stage); + Py_CLEAR(clear_module_state->__pyx_n_s_base); + Py_CLEAR(clear_module_state->__pyx_n_s_c); + Py_CLEAR(clear_module_state->__pyx_n_u_c); + Py_CLEAR(clear_module_state->__pyx_n_s_class); + Py_CLEAR(clear_module_state->__pyx_n_s_class_getitem); + Py_CLEAR(clear_module_state->__pyx_n_s_cline_in_traceback); + Py_CLEAR(clear_module_state->__pyx_n_s_collections); + Py_CLEAR(clear_module_state->__pyx_kp_s_collections_abc); + Py_CLEAR(clear_module_state->__pyx_n_s_constraints_fields); + Py_CLEAR(clear_module_state->__pyx_n_s_constraints_set); + Py_CLEAR(clear_module_state->__pyx_kp_u_constraints_set_value_must_be_nu); + Py_CLEAR(clear_module_state->__pyx_kp_s_contiguous_and_direct); + Py_CLEAR(clear_module_state->__pyx_kp_s_contiguous_and_indirect); + Py_CLEAR(clear_module_state->__pyx_n_s_cost_fields); + Py_CLEAR(clear_module_state->__pyx_n_s_cost_set); + Py_CLEAR(clear_module_state->__pyx_kp_u_cost_set_value_must_be_numpy_arr); + Py_CLEAR(clear_module_state->__pyx_n_s_count); + Py_CLEAR(clear_module_state->__pyx_n_s_custom_update); + Py_CLEAR(clear_module_state->__pyx_n_u_d); + Py_CLEAR(clear_module_state->__pyx_n_s_data); + Py_CLEAR(clear_module_state->__pyx_n_s_data_2); + Py_CLEAR(clear_module_state->__pyx_n_s_data_len); + Py_CLEAR(clear_module_state->__pyx_n_s_datetime); + Py_CLEAR(clear_module_state->__pyx_n_s_default); + Py_CLEAR(clear_module_state->__pyx_n_s_dict); + Py_CLEAR(clear_module_state->__pyx_n_s_dims); + Py_CLEAR(clear_module_state->__pyx_kp_u_disable); + Py_CLEAR(clear_module_state->__pyx_n_s_double_fields); + Py_CLEAR(clear_module_state->__pyx_n_s_double_value); + Py_CLEAR(clear_module_state->__pyx_n_s_dtype); + Py_CLEAR(clear_module_state->__pyx_n_s_dtype_is_object); + Py_CLEAR(clear_module_state->__pyx_n_s_dump); + Py_CLEAR(clear_module_state->__pyx_kp_u_enable); + Py_CLEAR(clear_module_state->__pyx_n_s_encode); + Py_CLEAR(clear_module_state->__pyx_n_s_enter); + Py_CLEAR(clear_module_state->__pyx_n_s_enumerate); + Py_CLEAR(clear_module_state->__pyx_n_u_eps_sufficient_descent); + Py_CLEAR(clear_module_state->__pyx_n_s_error); + Py_CLEAR(clear_module_state->__pyx_n_s_eval_param_sens); + Py_CLEAR(clear_module_state->__pyx_n_u_ex); + Py_CLEAR(clear_module_state->__pyx_n_s_exit); + Py_CLEAR(clear_module_state->__pyx_n_s_f); + Py_CLEAR(clear_module_state->__pyx_n_s_field); + Py_CLEAR(clear_module_state->__pyx_n_s_field_2); + Py_CLEAR(clear_module_state->__pyx_n_s_fields); + Py_CLEAR(clear_module_state->__pyx_n_s_filename); + Py_CLEAR(clear_module_state->__pyx_n_s_flags); + Py_CLEAR(clear_module_state->__pyx_n_s_float64); + Py_CLEAR(clear_module_state->__pyx_kp_u_for_field); + Py_CLEAR(clear_module_state->__pyx_n_s_format); + Py_CLEAR(clear_module_state->__pyx_n_s_fortran); + Py_CLEAR(clear_module_state->__pyx_n_u_fortran); + Py_CLEAR(clear_module_state->__pyx_n_s_full_stats); + Py_CLEAR(clear_module_state->__pyx_n_u_full_step_dual); + Py_CLEAR(clear_module_state->__pyx_kp_u_gc); + Py_CLEAR(clear_module_state->__pyx_n_s_get); + Py_CLEAR(clear_module_state->__pyx_n_s_get_cost); + Py_CLEAR(clear_module_state->__pyx_n_s_get_from_qp_in); + Py_CLEAR(clear_module_state->__pyx_n_s_get_pointers_solver); + Py_CLEAR(clear_module_state->__pyx_n_s_get_residuals); + Py_CLEAR(clear_module_state->__pyx_n_s_get_stat_double); + Py_CLEAR(clear_module_state->__pyx_n_s_get_stat_int); + Py_CLEAR(clear_module_state->__pyx_n_s_get_stat_matrix); + Py_CLEAR(clear_module_state->__pyx_n_s_get_stats); + Py_CLEAR(clear_module_state->__pyx_n_s_getcwd); + Py_CLEAR(clear_module_state->__pyx_n_s_getstate); + Py_CLEAR(clear_module_state->__pyx_n_u_globalization); + Py_CLEAR(clear_module_state->__pyx_n_u_globalization_use_SOC); + Py_CLEAR(clear_module_state->__pyx_kp_u_got); + Py_CLEAR(clear_module_state->__pyx_kp_u_got_differing_extents_in_dimensi); + Py_CLEAR(clear_module_state->__pyx_n_s_i); + Py_CLEAR(clear_module_state->__pyx_n_s_i_string); + Py_CLEAR(clear_module_state->__pyx_n_s_id); + Py_CLEAR(clear_module_state->__pyx_n_s_idx); + Py_CLEAR(clear_module_state->__pyx_n_s_idx_values); + Py_CLEAR(clear_module_state->__pyx_n_s_import); + Py_CLEAR(clear_module_state->__pyx_n_s_indent); + Py_CLEAR(clear_module_state->__pyx_n_s_index); + Py_CLEAR(clear_module_state->__pyx_n_u_initialize_t_slacks); + Py_CLEAR(clear_module_state->__pyx_n_s_initializing); + Py_CLEAR(clear_module_state->__pyx_n_s_int); + Py_CLEAR(clear_module_state->__pyx_n_s_int32); + Py_CLEAR(clear_module_state->__pyx_n_s_int_fields); + Py_CLEAR(clear_module_state->__pyx_n_s_int_value); + Py_CLEAR(clear_module_state->__pyx_n_s_is_coroutine); + Py_CLEAR(clear_module_state->__pyx_kp_u_isenabled); + Py_CLEAR(clear_module_state->__pyx_n_s_isfile); + Py_CLEAR(clear_module_state->__pyx_n_s_itemsize); + Py_CLEAR(clear_module_state->__pyx_kp_s_itemsize_0_for_cython_array); + Py_CLEAR(clear_module_state->__pyx_n_u_iterate); + Py_CLEAR(clear_module_state->__pyx_n_s_join); + Py_CLEAR(clear_module_state->__pyx_n_s_json); + Py_CLEAR(clear_module_state->__pyx_kp_u_json_2); + Py_CLEAR(clear_module_state->__pyx_n_s_k); + Py_CLEAR(clear_module_state->__pyx_n_s_key); + Py_CLEAR(clear_module_state->__pyx_n_s_keys); + Py_CLEAR(clear_module_state->__pyx_n_s_lN); + Py_CLEAR(clear_module_state->__pyx_n_u_lam); + Py_CLEAR(clear_module_state->__pyx_n_u_lam_2); + Py_CLEAR(clear_module_state->__pyx_n_u_lbu); + Py_CLEAR(clear_module_state->__pyx_n_u_lbx); + Py_CLEAR(clear_module_state->__pyx_n_u_line_search_use_sufficient_desce); + Py_CLEAR(clear_module_state->__pyx_n_s_load); + Py_CLEAR(clear_module_state->__pyx_n_s_load_iterate); + Py_CLEAR(clear_module_state->__pyx_kp_u_load_iterate_failed_file_does_no); + Py_CLEAR(clear_module_state->__pyx_n_s_m); + Py_CLEAR(clear_module_state->__pyx_n_s_main); + Py_CLEAR(clear_module_state->__pyx_n_s_mem_fields); + Py_CLEAR(clear_module_state->__pyx_n_s_memview); + Py_CLEAR(clear_module_state->__pyx_n_s_min_size); + Py_CLEAR(clear_module_state->__pyx_n_s_mode); + Py_CLEAR(clear_module_state->__pyx_n_s_model_name); + Py_CLEAR(clear_module_state->__pyx_n_s_msg); + Py_CLEAR(clear_module_state->__pyx_n_s_n); + Py_CLEAR(clear_module_state->__pyx_n_s_n_update); + Py_CLEAR(clear_module_state->__pyx_n_s_name); + Py_CLEAR(clear_module_state->__pyx_n_s_name_2); + Py_CLEAR(clear_module_state->__pyx_n_s_ndarray); + Py_CLEAR(clear_module_state->__pyx_n_s_ndim); + Py_CLEAR(clear_module_state->__pyx_n_s_new); + Py_CLEAR(clear_module_state->__pyx_n_s_new_time_steps); + Py_CLEAR(clear_module_state->__pyx_n_s_nlp_solver_type); + Py_CLEAR(clear_module_state->__pyx_kp_s_no_default___reduce___due_to_non); + Py_CLEAR(clear_module_state->__pyx_n_s_np); + Py_CLEAR(clear_module_state->__pyx_n_s_numpy); + Py_CLEAR(clear_module_state->__pyx_kp_u_numpy_core_multiarray_failed_to); + Py_CLEAR(clear_module_state->__pyx_kp_u_numpy_core_umath_failed_to_impor); + Py_CLEAR(clear_module_state->__pyx_n_s_nx); + Py_CLEAR(clear_module_state->__pyx_n_s_obj); + Py_CLEAR(clear_module_state->__pyx_n_s_open); + Py_CLEAR(clear_module_state->__pyx_n_s_options_set); + Py_CLEAR(clear_module_state->__pyx_n_s_order); + Py_CLEAR(clear_module_state->__pyx_n_s_os); + Py_CLEAR(clear_module_state->__pyx_n_s_out); + Py_CLEAR(clear_module_state->__pyx_n_s_out_fields); + Py_CLEAR(clear_module_state->__pyx_n_s_out_mat); + Py_CLEAR(clear_module_state->__pyx_n_s_overwrite); + Py_CLEAR(clear_module_state->__pyx_n_u_p); + Py_CLEAR(clear_module_state->__pyx_n_s_pack); + Py_CLEAR(clear_module_state->__pyx_n_s_param_values); + Py_CLEAR(clear_module_state->__pyx_kp_u_param_values_2); + Py_CLEAR(clear_module_state->__pyx_kp_u_param_values__and_idx_values__mu); + Py_CLEAR(clear_module_state->__pyx_kp_u_param_values__must_be_np_array); + Py_CLEAR(clear_module_state->__pyx_n_s_path); + Py_CLEAR(clear_module_state->__pyx_n_u_pi); + Py_CLEAR(clear_module_state->__pyx_n_u_pi_2); + Py_CLEAR(clear_module_state->__pyx_n_s_pickle); + Py_CLEAR(clear_module_state->__pyx_n_s_print); + Py_CLEAR(clear_module_state->__pyx_n_u_print_level); + Py_CLEAR(clear_module_state->__pyx_n_s_print_statistics); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_PickleError); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_checksum); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_result); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_state); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_type); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_unpickle_Enum); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_vtable); + Py_CLEAR(clear_module_state->__pyx_n_u_qp_iter); + Py_CLEAR(clear_module_state->__pyx_n_u_qp_mu0); + Py_CLEAR(clear_module_state->__pyx_n_s_qp_solver_cond_N); + Py_CLEAR(clear_module_state->__pyx_n_u_qp_tau_min); + Py_CLEAR(clear_module_state->__pyx_n_u_qp_tol_comp); + Py_CLEAR(clear_module_state->__pyx_n_u_qp_tol_eq); + Py_CLEAR(clear_module_state->__pyx_n_u_qp_tol_ineq); + Py_CLEAR(clear_module_state->__pyx_n_u_qp_tol_stat); + Py_CLEAR(clear_module_state->__pyx_n_u_qp_warm_start); + Py_CLEAR(clear_module_state->__pyx_n_u_r); + Py_CLEAR(clear_module_state->__pyx_n_s_range); + Py_CLEAR(clear_module_state->__pyx_n_s_recompute); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_ex); + Py_CLEAR(clear_module_state->__pyx_n_s_register); + Py_CLEAR(clear_module_state->__pyx_n_b_res_comp); + Py_CLEAR(clear_module_state->__pyx_n_b_res_eq); + Py_CLEAR(clear_module_state->__pyx_n_b_res_ineq); + Py_CLEAR(clear_module_state->__pyx_n_b_res_stat); + Py_CLEAR(clear_module_state->__pyx_n_s_reset); + Py_CLEAR(clear_module_state->__pyx_n_s_reset_qp_solver_mem); + Py_CLEAR(clear_module_state->__pyx_n_u_residuals); + Py_CLEAR(clear_module_state->__pyx_n_u_rti_phase); + Py_CLEAR(clear_module_state->__pyx_n_s_self); + Py_CLEAR(clear_module_state->__pyx_n_s_set); + Py_CLEAR(clear_module_state->__pyx_n_s_set_new_time_steps); + Py_CLEAR(clear_module_state->__pyx_n_s_set_params_sparse); + Py_CLEAR(clear_module_state->__pyx_kp_u_set_value_must_be_numpy_array_go); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_shape); + Py_CLEAR(clear_module_state->__pyx_n_s_size); + Py_CLEAR(clear_module_state->__pyx_n_u_sl); + Py_CLEAR(clear_module_state->__pyx_n_u_sl_2); + Py_CLEAR(clear_module_state->__pyx_n_s_solution); + Py_CLEAR(clear_module_state->__pyx_n_s_solve); + Py_CLEAR(clear_module_state->__pyx_n_s_solve_for_x0); + Py_CLEAR(clear_module_state->__pyx_kp_u_solver_option_must_be_of_type_fl); + Py_CLEAR(clear_module_state->__pyx_kp_u_solver_option_must_be_of_type_in); + Py_CLEAR(clear_module_state->__pyx_kp_u_solver_option_must_be_of_type_st); + Py_CLEAR(clear_module_state->__pyx_n_s_sort_keys); + Py_CLEAR(clear_module_state->__pyx_n_s_spec); + Py_CLEAR(clear_module_state->__pyx_n_s_split); + Py_CLEAR(clear_module_state->__pyx_n_s_sqp_iter); + Py_CLEAR(clear_module_state->__pyx_n_u_sqp_iter); + Py_CLEAR(clear_module_state->__pyx_n_s_stage); + Py_CLEAR(clear_module_state->__pyx_n_s_start); + Py_CLEAR(clear_module_state->__pyx_n_s_stat_m); + Py_CLEAR(clear_module_state->__pyx_n_u_stat_m); + Py_CLEAR(clear_module_state->__pyx_n_s_stat_n); + Py_CLEAR(clear_module_state->__pyx_n_u_stat_n); + Py_CLEAR(clear_module_state->__pyx_n_u_statistics); + Py_CLEAR(clear_module_state->__pyx_n_s_status); + Py_CLEAR(clear_module_state->__pyx_n_s_step); + Py_CLEAR(clear_module_state->__pyx_n_u_step_length); + Py_CLEAR(clear_module_state->__pyx_n_s_stop); + Py_CLEAR(clear_module_state->__pyx_n_s_store_iterate); + Py_CLEAR(clear_module_state->__pyx_n_s_store_iterate_locals_lambda); + Py_CLEAR(clear_module_state->__pyx_kp_u_stored_current_iterate_in); + Py_CLEAR(clear_module_state->__pyx_n_s_strftime); + Py_CLEAR(clear_module_state->__pyx_kp_s_strided_and_direct); + Py_CLEAR(clear_module_state->__pyx_kp_s_strided_and_direct_or_indirect); + Py_CLEAR(clear_module_state->__pyx_kp_s_strided_and_indirect); + Py_CLEAR(clear_module_state->__pyx_n_s_string_fields); + Py_CLEAR(clear_module_state->__pyx_n_s_string_value); + Py_CLEAR(clear_module_state->__pyx_kp_s_stringsource); + Py_CLEAR(clear_module_state->__pyx_n_s_struct); + Py_CLEAR(clear_module_state->__pyx_n_u_su); + Py_CLEAR(clear_module_state->__pyx_n_u_su_2); + Py_CLEAR(clear_module_state->__pyx_n_s_sys); + Py_CLEAR(clear_module_state->__pyx_n_u_t); + Py_CLEAR(clear_module_state->__pyx_n_u_t_2); + Py_CLEAR(clear_module_state->__pyx_n_s_test); + Py_CLEAR(clear_module_state->__pyx_kp_s_third_party_acados_acados_templa); + Py_CLEAR(clear_module_state->__pyx_n_u_time_glob); + Py_CLEAR(clear_module_state->__pyx_n_u_time_lin); + Py_CLEAR(clear_module_state->__pyx_n_u_time_qp); + Py_CLEAR(clear_module_state->__pyx_n_u_time_qp_solver_call); + Py_CLEAR(clear_module_state->__pyx_n_u_time_qp_xcond); + Py_CLEAR(clear_module_state->__pyx_n_u_time_reg); + Py_CLEAR(clear_module_state->__pyx_n_u_time_sim); + Py_CLEAR(clear_module_state->__pyx_n_u_time_sim_ad); + Py_CLEAR(clear_module_state->__pyx_n_u_time_sim_la); + Py_CLEAR(clear_module_state->__pyx_n_u_time_solution_sensitivities); + Py_CLEAR(clear_module_state->__pyx_n_u_time_tot); + Py_CLEAR(clear_module_state->__pyx_n_u_tol_comp); + Py_CLEAR(clear_module_state->__pyx_n_u_tol_eq); + Py_CLEAR(clear_module_state->__pyx_n_u_tol_ineq); + Py_CLEAR(clear_module_state->__pyx_n_u_tol_stat); + Py_CLEAR(clear_module_state->__pyx_n_s_tolist); + Py_CLEAR(clear_module_state->__pyx_n_u_u); + Py_CLEAR(clear_module_state->__pyx_n_s_u0); + Py_CLEAR(clear_module_state->__pyx_n_u_u_2); + Py_CLEAR(clear_module_state->__pyx_n_u_ubu); + Py_CLEAR(clear_module_state->__pyx_n_u_ubx); + Py_CLEAR(clear_module_state->__pyx_kp_s_unable_to_allocate_array_data); + Py_CLEAR(clear_module_state->__pyx_kp_s_unable_to_allocate_shape_and_str); + Py_CLEAR(clear_module_state->__pyx_n_s_unpack); + Py_CLEAR(clear_module_state->__pyx_n_s_update); + Py_CLEAR(clear_module_state->__pyx_n_s_update_qp_solver_cond_N); + Py_CLEAR(clear_module_state->__pyx_n_s_utcnow); + Py_CLEAR(clear_module_state->__pyx_kp_u_utf_8); + Py_CLEAR(clear_module_state->__pyx_n_s_value); + Py_CLEAR(clear_module_state->__pyx_n_s_value_2); + Py_CLEAR(clear_module_state->__pyx_n_s_value_shape); + Py_CLEAR(clear_module_state->__pyx_n_s_version_info); + Py_CLEAR(clear_module_state->__pyx_n_u_w); + Py_CLEAR(clear_module_state->__pyx_n_u_warm_start_first_qp); + Py_CLEAR(clear_module_state->__pyx_kp_u_with_dimension); + Py_CLEAR(clear_module_state->__pyx_kp_u_with_dimension_you_have); + Py_CLEAR(clear_module_state->__pyx_n_b_x); + Py_CLEAR(clear_module_state->__pyx_n_s_x); + Py_CLEAR(clear_module_state->__pyx_n_u_x); + Py_CLEAR(clear_module_state->__pyx_n_s_x0_bar); + Py_CLEAR(clear_module_state->__pyx_n_u_x_2); + Py_CLEAR(clear_module_state->__pyx_n_u_xdot_guess); + Py_CLEAR(clear_module_state->__pyx_n_u_y_ref); + Py_CLEAR(clear_module_state->__pyx_kp_u_you_have); + Py_CLEAR(clear_module_state->__pyx_n_u_yref); + Py_CLEAR(clear_module_state->__pyx_n_u_z); + Py_CLEAR(clear_module_state->__pyx_n_u_z_2); + Py_CLEAR(clear_module_state->__pyx_n_b_z_guess); + Py_CLEAR(clear_module_state->__pyx_n_u_z_guess); + Py_CLEAR(clear_module_state->__pyx_n_s_zeros); + Py_CLEAR(clear_module_state->__pyx_int_0); + Py_CLEAR(clear_module_state->__pyx_int_1); + Py_CLEAR(clear_module_state->__pyx_int_2); + Py_CLEAR(clear_module_state->__pyx_int_3); + Py_CLEAR(clear_module_state->__pyx_int_4); + Py_CLEAR(clear_module_state->__pyx_int_6); + Py_CLEAR(clear_module_state->__pyx_int_7); + Py_CLEAR(clear_module_state->__pyx_int_112105877); + Py_CLEAR(clear_module_state->__pyx_int_136983863); + Py_CLEAR(clear_module_state->__pyx_int_184977713); + Py_CLEAR(clear_module_state->__pyx_int_neg_1); + Py_CLEAR(clear_module_state->__pyx_int_neg_5); + Py_CLEAR(clear_module_state->__pyx_slice__5); + Py_CLEAR(clear_module_state->__pyx_tuple__4); + Py_CLEAR(clear_module_state->__pyx_tuple__8); + Py_CLEAR(clear_module_state->__pyx_tuple__9); + Py_CLEAR(clear_module_state->__pyx_slice__18); + Py_CLEAR(clear_module_state->__pyx_tuple__10); + Py_CLEAR(clear_module_state->__pyx_tuple__11); + Py_CLEAR(clear_module_state->__pyx_tuple__12); + Py_CLEAR(clear_module_state->__pyx_tuple__13); + Py_CLEAR(clear_module_state->__pyx_tuple__14); + Py_CLEAR(clear_module_state->__pyx_tuple__15); + Py_CLEAR(clear_module_state->__pyx_tuple__19); + Py_CLEAR(clear_module_state->__pyx_tuple__20); + Py_CLEAR(clear_module_state->__pyx_tuple__21); + Py_CLEAR(clear_module_state->__pyx_tuple__22); + Py_CLEAR(clear_module_state->__pyx_tuple__23); + Py_CLEAR(clear_module_state->__pyx_tuple__24); + Py_CLEAR(clear_module_state->__pyx_tuple__25); + Py_CLEAR(clear_module_state->__pyx_tuple__26); + Py_CLEAR(clear_module_state->__pyx_tuple__27); + Py_CLEAR(clear_module_state->__pyx_tuple__28); + Py_CLEAR(clear_module_state->__pyx_tuple__29); + Py_CLEAR(clear_module_state->__pyx_tuple__30); + Py_CLEAR(clear_module_state->__pyx_tuple__32); + Py_CLEAR(clear_module_state->__pyx_tuple__33); + Py_CLEAR(clear_module_state->__pyx_tuple__34); + Py_CLEAR(clear_module_state->__pyx_tuple__35); + Py_CLEAR(clear_module_state->__pyx_tuple__36); + Py_CLEAR(clear_module_state->__pyx_tuple__37); + Py_CLEAR(clear_module_state->__pyx_tuple__38); + Py_CLEAR(clear_module_state->__pyx_tuple__39); + Py_CLEAR(clear_module_state->__pyx_tuple__40); + Py_CLEAR(clear_module_state->__pyx_tuple__41); + Py_CLEAR(clear_module_state->__pyx_tuple__42); + Py_CLEAR(clear_module_state->__pyx_tuple__44); + Py_CLEAR(clear_module_state->__pyx_tuple__46); + Py_CLEAR(clear_module_state->__pyx_tuple__49); + Py_CLEAR(clear_module_state->__pyx_tuple__51); + Py_CLEAR(clear_module_state->__pyx_tuple__53); + Py_CLEAR(clear_module_state->__pyx_tuple__55); + Py_CLEAR(clear_module_state->__pyx_tuple__57); + Py_CLEAR(clear_module_state->__pyx_tuple__59); + Py_CLEAR(clear_module_state->__pyx_tuple__60); + Py_CLEAR(clear_module_state->__pyx_tuple__63); + Py_CLEAR(clear_module_state->__pyx_tuple__65); + Py_CLEAR(clear_module_state->__pyx_tuple__66); + Py_CLEAR(clear_module_state->__pyx_tuple__68); + Py_CLEAR(clear_module_state->__pyx_tuple__70); + Py_CLEAR(clear_module_state->__pyx_tuple__73); + Py_CLEAR(clear_module_state->__pyx_tuple__75); + Py_CLEAR(clear_module_state->__pyx_tuple__77); + Py_CLEAR(clear_module_state->__pyx_tuple__79); + Py_CLEAR(clear_module_state->__pyx_tuple__80); + Py_CLEAR(clear_module_state->__pyx_tuple__82); + Py_CLEAR(clear_module_state->__pyx_tuple__85); + Py_CLEAR(clear_module_state->__pyx_tuple__87); + Py_CLEAR(clear_module_state->__pyx_tuple__89); + Py_CLEAR(clear_module_state->__pyx_tuple__92); + Py_CLEAR(clear_module_state->__pyx_codeobj__43); + Py_CLEAR(clear_module_state->__pyx_codeobj__45); + Py_CLEAR(clear_module_state->__pyx_codeobj__47); + Py_CLEAR(clear_module_state->__pyx_codeobj__48); + Py_CLEAR(clear_module_state->__pyx_codeobj__50); + Py_CLEAR(clear_module_state->__pyx_codeobj__52); + Py_CLEAR(clear_module_state->__pyx_codeobj__54); + Py_CLEAR(clear_module_state->__pyx_codeobj__56); + Py_CLEAR(clear_module_state->__pyx_codeobj__58); + Py_CLEAR(clear_module_state->__pyx_codeobj__61); + Py_CLEAR(clear_module_state->__pyx_codeobj__62); + Py_CLEAR(clear_module_state->__pyx_codeobj__64); + Py_CLEAR(clear_module_state->__pyx_codeobj__67); + Py_CLEAR(clear_module_state->__pyx_codeobj__69); + Py_CLEAR(clear_module_state->__pyx_codeobj__71); + Py_CLEAR(clear_module_state->__pyx_codeobj__72); + Py_CLEAR(clear_module_state->__pyx_codeobj__74); + Py_CLEAR(clear_module_state->__pyx_codeobj__76); + Py_CLEAR(clear_module_state->__pyx_codeobj__78); + Py_CLEAR(clear_module_state->__pyx_codeobj__81); + Py_CLEAR(clear_module_state->__pyx_codeobj__83); + Py_CLEAR(clear_module_state->__pyx_codeobj__84); + Py_CLEAR(clear_module_state->__pyx_codeobj__86); + Py_CLEAR(clear_module_state->__pyx_codeobj__88); + Py_CLEAR(clear_module_state->__pyx_codeobj__90); + Py_CLEAR(clear_module_state->__pyx_codeobj__91); + Py_CLEAR(clear_module_state->__pyx_codeobj__93); + return 0; +} +#endif +/* #### Code section: module_state_traverse ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { + __pyx_mstate *traverse_module_state = __pyx_mstate(m); + if (!traverse_module_state) return 0; + Py_VISIT(traverse_module_state->__pyx_d); + Py_VISIT(traverse_module_state->__pyx_b); + Py_VISIT(traverse_module_state->__pyx_cython_runtime); + Py_VISIT(traverse_module_state->__pyx_empty_tuple); + Py_VISIT(traverse_module_state->__pyx_empty_bytes); + Py_VISIT(traverse_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_VISIT(traverse_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_VISIT(traverse_module_state->__pyx_FusedFunctionType); + #endif + Py_VISIT(traverse_module_state->__pyx_ptype_7cpython_4type_type); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_dtype); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_flatiter); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_broadcast); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_ndarray); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_generic); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_number); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_integer); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_signedinteger); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_unsignedinteger); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_inexact); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_floating); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_complexfloating); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_flexible); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_character); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_ufunc); + Py_VISIT(traverse_module_state->__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + Py_VISIT(traverse_module_state->__pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + Py_VISIT(traverse_module_state->__pyx_array_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_array); + Py_VISIT(traverse_module_state->__pyx_MemviewEnum_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_MemviewEnum); + Py_VISIT(traverse_module_state->__pyx_memoryview_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_memoryview); + Py_VISIT(traverse_module_state->__pyx_memoryviewslice_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_memoryviewslice); + Py_VISIT(traverse_module_state->__pyx_kp_u_); + Py_VISIT(traverse_module_state->__pyx_kp_u_0); + Py_VISIT(traverse_module_state->__pyx_n_s_ASCII); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython___get_poin); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython___get_stat); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython___get_stat_2); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython___get_stat_3); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython___reduce_c); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython___setstate); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython__get_poin); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython__get_stat); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython__get_stat_2); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython__get_stat_3); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_constraint); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_constraint_2); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_cost_set); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_cost_set_m); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_custom_upd); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_does_not_s); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_does_not_s_2); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_eval_param); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_eval_param_2); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_eval_param_3); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_get); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_get_cost); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_get_field); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_get_from_q); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_get_is_an); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_get_residu); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_get_stage); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_get_stats); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_load_itera); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_options_se); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_options_se_2); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_print_stat); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_reset); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_set); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_set_is_not); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_set_mismat); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_set_new_ti); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_set_params); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_solve); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_solve_argu); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_solve_argu_2); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_solve_for); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_store_iter); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_update_qp); + Py_VISIT(traverse_module_state->__pyx_kp_s_All_dimensions_preceding_dimensi); + Py_VISIT(traverse_module_state->__pyx_n_s_AssertionError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Buffer_view_does_not_expose_stri); + Py_VISIT(traverse_module_state->__pyx_kp_s_Can_only_create_a_buffer_that_is); + Py_VISIT(traverse_module_state->__pyx_kp_s_Cannot_assign_to_read_only_memor); + Py_VISIT(traverse_module_state->__pyx_kp_s_Cannot_create_writable_memory_vi); + Py_VISIT(traverse_module_state->__pyx_kp_u_Cannot_index_with_type); + Py_VISIT(traverse_module_state->__pyx_kp_s_Cannot_transpose_memoryview_with); + Py_VISIT(traverse_module_state->__pyx_kp_s_Dimension_d_is_not_direct); + Py_VISIT(traverse_module_state->__pyx_n_s_Ellipsis); + Py_VISIT(traverse_module_state->__pyx_kp_s_Empty_shape_tuple_for_cython_arr); + Py_VISIT(traverse_module_state->__pyx_n_u_F); + Py_VISIT(traverse_module_state->__pyx_kp_u_Got_sizes_idx); + Py_VISIT(traverse_module_state->__pyx_n_s_ImportError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0); + Py_VISIT(traverse_module_state->__pyx_n_s_IndexError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Index_out_of_bounds_axis_d); + Py_VISIT(traverse_module_state->__pyx_kp_s_Indirect_dimensions_not_supporte); + Py_VISIT(traverse_module_state->__pyx_kp_u_Invalid_mode_expected_c_or_fortr); + Py_VISIT(traverse_module_state->__pyx_kp_u_Invalid_shape_in_axis); + Py_VISIT(traverse_module_state->__pyx_n_s_MemoryError); + Py_VISIT(traverse_module_state->__pyx_kp_s_MemoryView_of_r_at_0x_x); + Py_VISIT(traverse_module_state->__pyx_kp_s_MemoryView_of_r_object); + Py_VISIT(traverse_module_state->__pyx_n_s_N); + Py_VISIT(traverse_module_state->__pyx_kp_u_None); + Py_VISIT(traverse_module_state->__pyx_n_s_NotImplementedError); + Py_VISIT(traverse_module_state->__pyx_n_b_O); + Py_VISIT(traverse_module_state->__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + Py_VISIT(traverse_module_state->__pyx_n_s_PickleError); + Py_VISIT(traverse_module_state->__pyx_n_u_SQP); + Py_VISIT(traverse_module_state->__pyx_n_u_SQP_RTI); + Py_VISIT(traverse_module_state->__pyx_n_s_Sequence); + Py_VISIT(traverse_module_state->__pyx_kp_s_Step_may_not_be_zero_axis_d); + Py_VISIT(traverse_module_state->__pyx_kp_u_TODO); + Py_VISIT(traverse_module_state->__pyx_n_s_TypeError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Unable_to_convert_item_to_object); + Py_VISIT(traverse_module_state->__pyx_n_s_ValueError); + Py_VISIT(traverse_module_state->__pyx_n_s_View_MemoryView); + Py_VISIT(traverse_module_state->__pyx_kp_u_Warning_acados_ocp_solver_reache); + Py_VISIT(traverse_module_state->__pyx_kp_u_Y_m_d_H_M_S_f); + Py_VISIT(traverse_module_state->__pyx_kp_u__16); + Py_VISIT(traverse_module_state->__pyx_n_u__17); + Py_VISIT(traverse_module_state->__pyx_kp_u__2); + Py_VISIT(traverse_module_state->__pyx_n_s__3); + Py_VISIT(traverse_module_state->__pyx_kp_u__31); + Py_VISIT(traverse_module_state->__pyx_kp_u__6); + Py_VISIT(traverse_module_state->__pyx_kp_u__7); + Py_VISIT(traverse_module_state->__pyx_n_s__94); + Py_VISIT(traverse_module_state->__pyx_n_s_abc); + Py_VISIT(traverse_module_state->__pyx_kp_u_acados_acados_ocp_solver_returne); + Py_VISIT(traverse_module_state->__pyx_n_s_acados_template_acados_ocp_solve); + Py_VISIT(traverse_module_state->__pyx_n_s_allocate_buffer); + Py_VISIT(traverse_module_state->__pyx_n_u_alpha); + Py_VISIT(traverse_module_state->__pyx_n_u_alpha_min); + Py_VISIT(traverse_module_state->__pyx_n_u_alpha_reduction); + Py_VISIT(traverse_module_state->__pyx_kp_u_alpha_values_are_not_available_f); + Py_VISIT(traverse_module_state->__pyx_kp_u_and); + Py_VISIT(traverse_module_state->__pyx_n_s_array); + Py_VISIT(traverse_module_state->__pyx_n_s_ascontiguousarray); + Py_VISIT(traverse_module_state->__pyx_n_s_asfortranarray); + Py_VISIT(traverse_module_state->__pyx_n_s_asyncio_coroutines); + Py_VISIT(traverse_module_state->__pyx_kp_u_at_stage); + Py_VISIT(traverse_module_state->__pyx_n_s_base); + Py_VISIT(traverse_module_state->__pyx_n_s_c); + Py_VISIT(traverse_module_state->__pyx_n_u_c); + Py_VISIT(traverse_module_state->__pyx_n_s_class); + Py_VISIT(traverse_module_state->__pyx_n_s_class_getitem); + Py_VISIT(traverse_module_state->__pyx_n_s_cline_in_traceback); + Py_VISIT(traverse_module_state->__pyx_n_s_collections); + Py_VISIT(traverse_module_state->__pyx_kp_s_collections_abc); + Py_VISIT(traverse_module_state->__pyx_n_s_constraints_fields); + Py_VISIT(traverse_module_state->__pyx_n_s_constraints_set); + Py_VISIT(traverse_module_state->__pyx_kp_u_constraints_set_value_must_be_nu); + Py_VISIT(traverse_module_state->__pyx_kp_s_contiguous_and_direct); + Py_VISIT(traverse_module_state->__pyx_kp_s_contiguous_and_indirect); + Py_VISIT(traverse_module_state->__pyx_n_s_cost_fields); + Py_VISIT(traverse_module_state->__pyx_n_s_cost_set); + Py_VISIT(traverse_module_state->__pyx_kp_u_cost_set_value_must_be_numpy_arr); + Py_VISIT(traverse_module_state->__pyx_n_s_count); + Py_VISIT(traverse_module_state->__pyx_n_s_custom_update); + Py_VISIT(traverse_module_state->__pyx_n_u_d); + Py_VISIT(traverse_module_state->__pyx_n_s_data); + Py_VISIT(traverse_module_state->__pyx_n_s_data_2); + Py_VISIT(traverse_module_state->__pyx_n_s_data_len); + Py_VISIT(traverse_module_state->__pyx_n_s_datetime); + Py_VISIT(traverse_module_state->__pyx_n_s_default); + Py_VISIT(traverse_module_state->__pyx_n_s_dict); + Py_VISIT(traverse_module_state->__pyx_n_s_dims); + Py_VISIT(traverse_module_state->__pyx_kp_u_disable); + Py_VISIT(traverse_module_state->__pyx_n_s_double_fields); + Py_VISIT(traverse_module_state->__pyx_n_s_double_value); + Py_VISIT(traverse_module_state->__pyx_n_s_dtype); + Py_VISIT(traverse_module_state->__pyx_n_s_dtype_is_object); + Py_VISIT(traverse_module_state->__pyx_n_s_dump); + Py_VISIT(traverse_module_state->__pyx_kp_u_enable); + Py_VISIT(traverse_module_state->__pyx_n_s_encode); + Py_VISIT(traverse_module_state->__pyx_n_s_enter); + Py_VISIT(traverse_module_state->__pyx_n_s_enumerate); + Py_VISIT(traverse_module_state->__pyx_n_u_eps_sufficient_descent); + Py_VISIT(traverse_module_state->__pyx_n_s_error); + Py_VISIT(traverse_module_state->__pyx_n_s_eval_param_sens); + Py_VISIT(traverse_module_state->__pyx_n_u_ex); + Py_VISIT(traverse_module_state->__pyx_n_s_exit); + Py_VISIT(traverse_module_state->__pyx_n_s_f); + Py_VISIT(traverse_module_state->__pyx_n_s_field); + Py_VISIT(traverse_module_state->__pyx_n_s_field_2); + Py_VISIT(traverse_module_state->__pyx_n_s_fields); + Py_VISIT(traverse_module_state->__pyx_n_s_filename); + Py_VISIT(traverse_module_state->__pyx_n_s_flags); + Py_VISIT(traverse_module_state->__pyx_n_s_float64); + Py_VISIT(traverse_module_state->__pyx_kp_u_for_field); + Py_VISIT(traverse_module_state->__pyx_n_s_format); + Py_VISIT(traverse_module_state->__pyx_n_s_fortran); + Py_VISIT(traverse_module_state->__pyx_n_u_fortran); + Py_VISIT(traverse_module_state->__pyx_n_s_full_stats); + Py_VISIT(traverse_module_state->__pyx_n_u_full_step_dual); + Py_VISIT(traverse_module_state->__pyx_kp_u_gc); + Py_VISIT(traverse_module_state->__pyx_n_s_get); + Py_VISIT(traverse_module_state->__pyx_n_s_get_cost); + Py_VISIT(traverse_module_state->__pyx_n_s_get_from_qp_in); + Py_VISIT(traverse_module_state->__pyx_n_s_get_pointers_solver); + Py_VISIT(traverse_module_state->__pyx_n_s_get_residuals); + Py_VISIT(traverse_module_state->__pyx_n_s_get_stat_double); + Py_VISIT(traverse_module_state->__pyx_n_s_get_stat_int); + Py_VISIT(traverse_module_state->__pyx_n_s_get_stat_matrix); + Py_VISIT(traverse_module_state->__pyx_n_s_get_stats); + Py_VISIT(traverse_module_state->__pyx_n_s_getcwd); + Py_VISIT(traverse_module_state->__pyx_n_s_getstate); + Py_VISIT(traverse_module_state->__pyx_n_u_globalization); + Py_VISIT(traverse_module_state->__pyx_n_u_globalization_use_SOC); + Py_VISIT(traverse_module_state->__pyx_kp_u_got); + Py_VISIT(traverse_module_state->__pyx_kp_u_got_differing_extents_in_dimensi); + Py_VISIT(traverse_module_state->__pyx_n_s_i); + Py_VISIT(traverse_module_state->__pyx_n_s_i_string); + Py_VISIT(traverse_module_state->__pyx_n_s_id); + Py_VISIT(traverse_module_state->__pyx_n_s_idx); + Py_VISIT(traverse_module_state->__pyx_n_s_idx_values); + Py_VISIT(traverse_module_state->__pyx_n_s_import); + Py_VISIT(traverse_module_state->__pyx_n_s_indent); + Py_VISIT(traverse_module_state->__pyx_n_s_index); + Py_VISIT(traverse_module_state->__pyx_n_u_initialize_t_slacks); + Py_VISIT(traverse_module_state->__pyx_n_s_initializing); + Py_VISIT(traverse_module_state->__pyx_n_s_int); + Py_VISIT(traverse_module_state->__pyx_n_s_int32); + Py_VISIT(traverse_module_state->__pyx_n_s_int_fields); + Py_VISIT(traverse_module_state->__pyx_n_s_int_value); + Py_VISIT(traverse_module_state->__pyx_n_s_is_coroutine); + Py_VISIT(traverse_module_state->__pyx_kp_u_isenabled); + Py_VISIT(traverse_module_state->__pyx_n_s_isfile); + Py_VISIT(traverse_module_state->__pyx_n_s_itemsize); + Py_VISIT(traverse_module_state->__pyx_kp_s_itemsize_0_for_cython_array); + Py_VISIT(traverse_module_state->__pyx_n_u_iterate); + Py_VISIT(traverse_module_state->__pyx_n_s_join); + Py_VISIT(traverse_module_state->__pyx_n_s_json); + Py_VISIT(traverse_module_state->__pyx_kp_u_json_2); + Py_VISIT(traverse_module_state->__pyx_n_s_k); + Py_VISIT(traverse_module_state->__pyx_n_s_key); + Py_VISIT(traverse_module_state->__pyx_n_s_keys); + Py_VISIT(traverse_module_state->__pyx_n_s_lN); + Py_VISIT(traverse_module_state->__pyx_n_u_lam); + Py_VISIT(traverse_module_state->__pyx_n_u_lam_2); + Py_VISIT(traverse_module_state->__pyx_n_u_lbu); + Py_VISIT(traverse_module_state->__pyx_n_u_lbx); + Py_VISIT(traverse_module_state->__pyx_n_u_line_search_use_sufficient_desce); + Py_VISIT(traverse_module_state->__pyx_n_s_load); + Py_VISIT(traverse_module_state->__pyx_n_s_load_iterate); + Py_VISIT(traverse_module_state->__pyx_kp_u_load_iterate_failed_file_does_no); + Py_VISIT(traverse_module_state->__pyx_n_s_m); + Py_VISIT(traverse_module_state->__pyx_n_s_main); + Py_VISIT(traverse_module_state->__pyx_n_s_mem_fields); + Py_VISIT(traverse_module_state->__pyx_n_s_memview); + Py_VISIT(traverse_module_state->__pyx_n_s_min_size); + Py_VISIT(traverse_module_state->__pyx_n_s_mode); + Py_VISIT(traverse_module_state->__pyx_n_s_model_name); + Py_VISIT(traverse_module_state->__pyx_n_s_msg); + Py_VISIT(traverse_module_state->__pyx_n_s_n); + Py_VISIT(traverse_module_state->__pyx_n_s_n_update); + Py_VISIT(traverse_module_state->__pyx_n_s_name); + Py_VISIT(traverse_module_state->__pyx_n_s_name_2); + Py_VISIT(traverse_module_state->__pyx_n_s_ndarray); + Py_VISIT(traverse_module_state->__pyx_n_s_ndim); + Py_VISIT(traverse_module_state->__pyx_n_s_new); + Py_VISIT(traverse_module_state->__pyx_n_s_new_time_steps); + Py_VISIT(traverse_module_state->__pyx_n_s_nlp_solver_type); + Py_VISIT(traverse_module_state->__pyx_kp_s_no_default___reduce___due_to_non); + Py_VISIT(traverse_module_state->__pyx_n_s_np); + Py_VISIT(traverse_module_state->__pyx_n_s_numpy); + Py_VISIT(traverse_module_state->__pyx_kp_u_numpy_core_multiarray_failed_to); + Py_VISIT(traverse_module_state->__pyx_kp_u_numpy_core_umath_failed_to_impor); + Py_VISIT(traverse_module_state->__pyx_n_s_nx); + Py_VISIT(traverse_module_state->__pyx_n_s_obj); + Py_VISIT(traverse_module_state->__pyx_n_s_open); + Py_VISIT(traverse_module_state->__pyx_n_s_options_set); + Py_VISIT(traverse_module_state->__pyx_n_s_order); + Py_VISIT(traverse_module_state->__pyx_n_s_os); + Py_VISIT(traverse_module_state->__pyx_n_s_out); + Py_VISIT(traverse_module_state->__pyx_n_s_out_fields); + Py_VISIT(traverse_module_state->__pyx_n_s_out_mat); + Py_VISIT(traverse_module_state->__pyx_n_s_overwrite); + Py_VISIT(traverse_module_state->__pyx_n_u_p); + Py_VISIT(traverse_module_state->__pyx_n_s_pack); + Py_VISIT(traverse_module_state->__pyx_n_s_param_values); + Py_VISIT(traverse_module_state->__pyx_kp_u_param_values_2); + Py_VISIT(traverse_module_state->__pyx_kp_u_param_values__and_idx_values__mu); + Py_VISIT(traverse_module_state->__pyx_kp_u_param_values__must_be_np_array); + Py_VISIT(traverse_module_state->__pyx_n_s_path); + Py_VISIT(traverse_module_state->__pyx_n_u_pi); + Py_VISIT(traverse_module_state->__pyx_n_u_pi_2); + Py_VISIT(traverse_module_state->__pyx_n_s_pickle); + Py_VISIT(traverse_module_state->__pyx_n_s_print); + Py_VISIT(traverse_module_state->__pyx_n_u_print_level); + Py_VISIT(traverse_module_state->__pyx_n_s_print_statistics); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_PickleError); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_checksum); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_result); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_state); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_type); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_unpickle_Enum); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_vtable); + Py_VISIT(traverse_module_state->__pyx_n_u_qp_iter); + Py_VISIT(traverse_module_state->__pyx_n_u_qp_mu0); + Py_VISIT(traverse_module_state->__pyx_n_s_qp_solver_cond_N); + Py_VISIT(traverse_module_state->__pyx_n_u_qp_tau_min); + Py_VISIT(traverse_module_state->__pyx_n_u_qp_tol_comp); + Py_VISIT(traverse_module_state->__pyx_n_u_qp_tol_eq); + Py_VISIT(traverse_module_state->__pyx_n_u_qp_tol_ineq); + Py_VISIT(traverse_module_state->__pyx_n_u_qp_tol_stat); + Py_VISIT(traverse_module_state->__pyx_n_u_qp_warm_start); + Py_VISIT(traverse_module_state->__pyx_n_u_r); + Py_VISIT(traverse_module_state->__pyx_n_s_range); + Py_VISIT(traverse_module_state->__pyx_n_s_recompute); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_ex); + Py_VISIT(traverse_module_state->__pyx_n_s_register); + Py_VISIT(traverse_module_state->__pyx_n_b_res_comp); + Py_VISIT(traverse_module_state->__pyx_n_b_res_eq); + Py_VISIT(traverse_module_state->__pyx_n_b_res_ineq); + Py_VISIT(traverse_module_state->__pyx_n_b_res_stat); + Py_VISIT(traverse_module_state->__pyx_n_s_reset); + Py_VISIT(traverse_module_state->__pyx_n_s_reset_qp_solver_mem); + Py_VISIT(traverse_module_state->__pyx_n_u_residuals); + Py_VISIT(traverse_module_state->__pyx_n_u_rti_phase); + Py_VISIT(traverse_module_state->__pyx_n_s_self); + Py_VISIT(traverse_module_state->__pyx_n_s_set); + Py_VISIT(traverse_module_state->__pyx_n_s_set_new_time_steps); + Py_VISIT(traverse_module_state->__pyx_n_s_set_params_sparse); + Py_VISIT(traverse_module_state->__pyx_kp_u_set_value_must_be_numpy_array_go); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_shape); + Py_VISIT(traverse_module_state->__pyx_n_s_size); + Py_VISIT(traverse_module_state->__pyx_n_u_sl); + Py_VISIT(traverse_module_state->__pyx_n_u_sl_2); + Py_VISIT(traverse_module_state->__pyx_n_s_solution); + Py_VISIT(traverse_module_state->__pyx_n_s_solve); + Py_VISIT(traverse_module_state->__pyx_n_s_solve_for_x0); + Py_VISIT(traverse_module_state->__pyx_kp_u_solver_option_must_be_of_type_fl); + Py_VISIT(traverse_module_state->__pyx_kp_u_solver_option_must_be_of_type_in); + Py_VISIT(traverse_module_state->__pyx_kp_u_solver_option_must_be_of_type_st); + Py_VISIT(traverse_module_state->__pyx_n_s_sort_keys); + Py_VISIT(traverse_module_state->__pyx_n_s_spec); + Py_VISIT(traverse_module_state->__pyx_n_s_split); + Py_VISIT(traverse_module_state->__pyx_n_s_sqp_iter); + Py_VISIT(traverse_module_state->__pyx_n_u_sqp_iter); + Py_VISIT(traverse_module_state->__pyx_n_s_stage); + Py_VISIT(traverse_module_state->__pyx_n_s_start); + Py_VISIT(traverse_module_state->__pyx_n_s_stat_m); + Py_VISIT(traverse_module_state->__pyx_n_u_stat_m); + Py_VISIT(traverse_module_state->__pyx_n_s_stat_n); + Py_VISIT(traverse_module_state->__pyx_n_u_stat_n); + Py_VISIT(traverse_module_state->__pyx_n_u_statistics); + Py_VISIT(traverse_module_state->__pyx_n_s_status); + Py_VISIT(traverse_module_state->__pyx_n_s_step); + Py_VISIT(traverse_module_state->__pyx_n_u_step_length); + Py_VISIT(traverse_module_state->__pyx_n_s_stop); + Py_VISIT(traverse_module_state->__pyx_n_s_store_iterate); + Py_VISIT(traverse_module_state->__pyx_n_s_store_iterate_locals_lambda); + Py_VISIT(traverse_module_state->__pyx_kp_u_stored_current_iterate_in); + Py_VISIT(traverse_module_state->__pyx_n_s_strftime); + Py_VISIT(traverse_module_state->__pyx_kp_s_strided_and_direct); + Py_VISIT(traverse_module_state->__pyx_kp_s_strided_and_direct_or_indirect); + Py_VISIT(traverse_module_state->__pyx_kp_s_strided_and_indirect); + Py_VISIT(traverse_module_state->__pyx_n_s_string_fields); + Py_VISIT(traverse_module_state->__pyx_n_s_string_value); + Py_VISIT(traverse_module_state->__pyx_kp_s_stringsource); + Py_VISIT(traverse_module_state->__pyx_n_s_struct); + Py_VISIT(traverse_module_state->__pyx_n_u_su); + Py_VISIT(traverse_module_state->__pyx_n_u_su_2); + Py_VISIT(traverse_module_state->__pyx_n_s_sys); + Py_VISIT(traverse_module_state->__pyx_n_u_t); + Py_VISIT(traverse_module_state->__pyx_n_u_t_2); + Py_VISIT(traverse_module_state->__pyx_n_s_test); + Py_VISIT(traverse_module_state->__pyx_kp_s_third_party_acados_acados_templa); + Py_VISIT(traverse_module_state->__pyx_n_u_time_glob); + Py_VISIT(traverse_module_state->__pyx_n_u_time_lin); + Py_VISIT(traverse_module_state->__pyx_n_u_time_qp); + Py_VISIT(traverse_module_state->__pyx_n_u_time_qp_solver_call); + Py_VISIT(traverse_module_state->__pyx_n_u_time_qp_xcond); + Py_VISIT(traverse_module_state->__pyx_n_u_time_reg); + Py_VISIT(traverse_module_state->__pyx_n_u_time_sim); + Py_VISIT(traverse_module_state->__pyx_n_u_time_sim_ad); + Py_VISIT(traverse_module_state->__pyx_n_u_time_sim_la); + Py_VISIT(traverse_module_state->__pyx_n_u_time_solution_sensitivities); + Py_VISIT(traverse_module_state->__pyx_n_u_time_tot); + Py_VISIT(traverse_module_state->__pyx_n_u_tol_comp); + Py_VISIT(traverse_module_state->__pyx_n_u_tol_eq); + Py_VISIT(traverse_module_state->__pyx_n_u_tol_ineq); + Py_VISIT(traverse_module_state->__pyx_n_u_tol_stat); + Py_VISIT(traverse_module_state->__pyx_n_s_tolist); + Py_VISIT(traverse_module_state->__pyx_n_u_u); + Py_VISIT(traverse_module_state->__pyx_n_s_u0); + Py_VISIT(traverse_module_state->__pyx_n_u_u_2); + Py_VISIT(traverse_module_state->__pyx_n_u_ubu); + Py_VISIT(traverse_module_state->__pyx_n_u_ubx); + Py_VISIT(traverse_module_state->__pyx_kp_s_unable_to_allocate_array_data); + Py_VISIT(traverse_module_state->__pyx_kp_s_unable_to_allocate_shape_and_str); + Py_VISIT(traverse_module_state->__pyx_n_s_unpack); + Py_VISIT(traverse_module_state->__pyx_n_s_update); + Py_VISIT(traverse_module_state->__pyx_n_s_update_qp_solver_cond_N); + Py_VISIT(traverse_module_state->__pyx_n_s_utcnow); + Py_VISIT(traverse_module_state->__pyx_kp_u_utf_8); + Py_VISIT(traverse_module_state->__pyx_n_s_value); + Py_VISIT(traverse_module_state->__pyx_n_s_value_2); + Py_VISIT(traverse_module_state->__pyx_n_s_value_shape); + Py_VISIT(traverse_module_state->__pyx_n_s_version_info); + Py_VISIT(traverse_module_state->__pyx_n_u_w); + Py_VISIT(traverse_module_state->__pyx_n_u_warm_start_first_qp); + Py_VISIT(traverse_module_state->__pyx_kp_u_with_dimension); + Py_VISIT(traverse_module_state->__pyx_kp_u_with_dimension_you_have); + Py_VISIT(traverse_module_state->__pyx_n_b_x); + Py_VISIT(traverse_module_state->__pyx_n_s_x); + Py_VISIT(traverse_module_state->__pyx_n_u_x); + Py_VISIT(traverse_module_state->__pyx_n_s_x0_bar); + Py_VISIT(traverse_module_state->__pyx_n_u_x_2); + Py_VISIT(traverse_module_state->__pyx_n_u_xdot_guess); + Py_VISIT(traverse_module_state->__pyx_n_u_y_ref); + Py_VISIT(traverse_module_state->__pyx_kp_u_you_have); + Py_VISIT(traverse_module_state->__pyx_n_u_yref); + Py_VISIT(traverse_module_state->__pyx_n_u_z); + Py_VISIT(traverse_module_state->__pyx_n_u_z_2); + Py_VISIT(traverse_module_state->__pyx_n_b_z_guess); + Py_VISIT(traverse_module_state->__pyx_n_u_z_guess); + Py_VISIT(traverse_module_state->__pyx_n_s_zeros); + Py_VISIT(traverse_module_state->__pyx_int_0); + Py_VISIT(traverse_module_state->__pyx_int_1); + Py_VISIT(traverse_module_state->__pyx_int_2); + Py_VISIT(traverse_module_state->__pyx_int_3); + Py_VISIT(traverse_module_state->__pyx_int_4); + Py_VISIT(traverse_module_state->__pyx_int_6); + Py_VISIT(traverse_module_state->__pyx_int_7); + Py_VISIT(traverse_module_state->__pyx_int_112105877); + Py_VISIT(traverse_module_state->__pyx_int_136983863); + Py_VISIT(traverse_module_state->__pyx_int_184977713); + Py_VISIT(traverse_module_state->__pyx_int_neg_1); + Py_VISIT(traverse_module_state->__pyx_int_neg_5); + Py_VISIT(traverse_module_state->__pyx_slice__5); + Py_VISIT(traverse_module_state->__pyx_tuple__4); + Py_VISIT(traverse_module_state->__pyx_tuple__8); + Py_VISIT(traverse_module_state->__pyx_tuple__9); + Py_VISIT(traverse_module_state->__pyx_slice__18); + Py_VISIT(traverse_module_state->__pyx_tuple__10); + Py_VISIT(traverse_module_state->__pyx_tuple__11); + Py_VISIT(traverse_module_state->__pyx_tuple__12); + Py_VISIT(traverse_module_state->__pyx_tuple__13); + Py_VISIT(traverse_module_state->__pyx_tuple__14); + Py_VISIT(traverse_module_state->__pyx_tuple__15); + Py_VISIT(traverse_module_state->__pyx_tuple__19); + Py_VISIT(traverse_module_state->__pyx_tuple__20); + Py_VISIT(traverse_module_state->__pyx_tuple__21); + Py_VISIT(traverse_module_state->__pyx_tuple__22); + Py_VISIT(traverse_module_state->__pyx_tuple__23); + Py_VISIT(traverse_module_state->__pyx_tuple__24); + Py_VISIT(traverse_module_state->__pyx_tuple__25); + Py_VISIT(traverse_module_state->__pyx_tuple__26); + Py_VISIT(traverse_module_state->__pyx_tuple__27); + Py_VISIT(traverse_module_state->__pyx_tuple__28); + Py_VISIT(traverse_module_state->__pyx_tuple__29); + Py_VISIT(traverse_module_state->__pyx_tuple__30); + Py_VISIT(traverse_module_state->__pyx_tuple__32); + Py_VISIT(traverse_module_state->__pyx_tuple__33); + Py_VISIT(traverse_module_state->__pyx_tuple__34); + Py_VISIT(traverse_module_state->__pyx_tuple__35); + Py_VISIT(traverse_module_state->__pyx_tuple__36); + Py_VISIT(traverse_module_state->__pyx_tuple__37); + Py_VISIT(traverse_module_state->__pyx_tuple__38); + Py_VISIT(traverse_module_state->__pyx_tuple__39); + Py_VISIT(traverse_module_state->__pyx_tuple__40); + Py_VISIT(traverse_module_state->__pyx_tuple__41); + Py_VISIT(traverse_module_state->__pyx_tuple__42); + Py_VISIT(traverse_module_state->__pyx_tuple__44); + Py_VISIT(traverse_module_state->__pyx_tuple__46); + Py_VISIT(traverse_module_state->__pyx_tuple__49); + Py_VISIT(traverse_module_state->__pyx_tuple__51); + Py_VISIT(traverse_module_state->__pyx_tuple__53); + Py_VISIT(traverse_module_state->__pyx_tuple__55); + Py_VISIT(traverse_module_state->__pyx_tuple__57); + Py_VISIT(traverse_module_state->__pyx_tuple__59); + Py_VISIT(traverse_module_state->__pyx_tuple__60); + Py_VISIT(traverse_module_state->__pyx_tuple__63); + Py_VISIT(traverse_module_state->__pyx_tuple__65); + Py_VISIT(traverse_module_state->__pyx_tuple__66); + Py_VISIT(traverse_module_state->__pyx_tuple__68); + Py_VISIT(traverse_module_state->__pyx_tuple__70); + Py_VISIT(traverse_module_state->__pyx_tuple__73); + Py_VISIT(traverse_module_state->__pyx_tuple__75); + Py_VISIT(traverse_module_state->__pyx_tuple__77); + Py_VISIT(traverse_module_state->__pyx_tuple__79); + Py_VISIT(traverse_module_state->__pyx_tuple__80); + Py_VISIT(traverse_module_state->__pyx_tuple__82); + Py_VISIT(traverse_module_state->__pyx_tuple__85); + Py_VISIT(traverse_module_state->__pyx_tuple__87); + Py_VISIT(traverse_module_state->__pyx_tuple__89); + Py_VISIT(traverse_module_state->__pyx_tuple__92); + Py_VISIT(traverse_module_state->__pyx_codeobj__43); + Py_VISIT(traverse_module_state->__pyx_codeobj__45); + Py_VISIT(traverse_module_state->__pyx_codeobj__47); + Py_VISIT(traverse_module_state->__pyx_codeobj__48); + Py_VISIT(traverse_module_state->__pyx_codeobj__50); + Py_VISIT(traverse_module_state->__pyx_codeobj__52); + Py_VISIT(traverse_module_state->__pyx_codeobj__54); + Py_VISIT(traverse_module_state->__pyx_codeobj__56); + Py_VISIT(traverse_module_state->__pyx_codeobj__58); + Py_VISIT(traverse_module_state->__pyx_codeobj__61); + Py_VISIT(traverse_module_state->__pyx_codeobj__62); + Py_VISIT(traverse_module_state->__pyx_codeobj__64); + Py_VISIT(traverse_module_state->__pyx_codeobj__67); + Py_VISIT(traverse_module_state->__pyx_codeobj__69); + Py_VISIT(traverse_module_state->__pyx_codeobj__71); + Py_VISIT(traverse_module_state->__pyx_codeobj__72); + Py_VISIT(traverse_module_state->__pyx_codeobj__74); + Py_VISIT(traverse_module_state->__pyx_codeobj__76); + Py_VISIT(traverse_module_state->__pyx_codeobj__78); + Py_VISIT(traverse_module_state->__pyx_codeobj__81); + Py_VISIT(traverse_module_state->__pyx_codeobj__83); + Py_VISIT(traverse_module_state->__pyx_codeobj__84); + Py_VISIT(traverse_module_state->__pyx_codeobj__86); + Py_VISIT(traverse_module_state->__pyx_codeobj__88); + Py_VISIT(traverse_module_state->__pyx_codeobj__90); + Py_VISIT(traverse_module_state->__pyx_codeobj__91); + Py_VISIT(traverse_module_state->__pyx_codeobj__93); + return 0; +} +#endif +/* #### Code section: module_state_defines ### */ +#define __pyx_d __pyx_mstate_global->__pyx_d +#define __pyx_b __pyx_mstate_global->__pyx_b +#define __pyx_cython_runtime __pyx_mstate_global->__pyx_cython_runtime +#define __pyx_empty_tuple __pyx_mstate_global->__pyx_empty_tuple +#define __pyx_empty_bytes __pyx_mstate_global->__pyx_empty_bytes +#define __pyx_empty_unicode __pyx_mstate_global->__pyx_empty_unicode +#ifdef __Pyx_CyFunction_USED +#define __pyx_CyFunctionType __pyx_mstate_global->__pyx_CyFunctionType +#endif +#ifdef __Pyx_FusedFunction_USED +#define __pyx_FusedFunctionType __pyx_mstate_global->__pyx_FusedFunctionType +#endif +#ifdef __Pyx_Generator_USED +#define __pyx_GeneratorType __pyx_mstate_global->__pyx_GeneratorType +#endif +#ifdef __Pyx_IterableCoroutine_USED +#define __pyx_IterableCoroutineType __pyx_mstate_global->__pyx_IterableCoroutineType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineAwaitType __pyx_mstate_global->__pyx_CoroutineAwaitType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineType __pyx_mstate_global->__pyx_CoroutineType +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#define __pyx_ptype_7cpython_4type_type __pyx_mstate_global->__pyx_ptype_7cpython_4type_type +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#define __pyx_ptype_5numpy_dtype __pyx_mstate_global->__pyx_ptype_5numpy_dtype +#define __pyx_ptype_5numpy_flatiter __pyx_mstate_global->__pyx_ptype_5numpy_flatiter +#define __pyx_ptype_5numpy_broadcast __pyx_mstate_global->__pyx_ptype_5numpy_broadcast +#define __pyx_ptype_5numpy_ndarray __pyx_mstate_global->__pyx_ptype_5numpy_ndarray +#define __pyx_ptype_5numpy_generic __pyx_mstate_global->__pyx_ptype_5numpy_generic +#define __pyx_ptype_5numpy_number __pyx_mstate_global->__pyx_ptype_5numpy_number +#define __pyx_ptype_5numpy_integer __pyx_mstate_global->__pyx_ptype_5numpy_integer +#define __pyx_ptype_5numpy_signedinteger __pyx_mstate_global->__pyx_ptype_5numpy_signedinteger +#define __pyx_ptype_5numpy_unsignedinteger __pyx_mstate_global->__pyx_ptype_5numpy_unsignedinteger +#define __pyx_ptype_5numpy_inexact __pyx_mstate_global->__pyx_ptype_5numpy_inexact +#define __pyx_ptype_5numpy_floating __pyx_mstate_global->__pyx_ptype_5numpy_floating +#define __pyx_ptype_5numpy_complexfloating __pyx_mstate_global->__pyx_ptype_5numpy_complexfloating +#define __pyx_ptype_5numpy_flexible __pyx_mstate_global->__pyx_ptype_5numpy_flexible +#define __pyx_ptype_5numpy_character __pyx_mstate_global->__pyx_ptype_5numpy_character +#define __pyx_ptype_5numpy_ufunc __pyx_mstate_global->__pyx_ptype_5numpy_ufunc +#if CYTHON_USE_MODULE_STATE +#define __pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython __pyx_mstate_global->__pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython +#define __pyx_type___pyx_array __pyx_mstate_global->__pyx_type___pyx_array +#define __pyx_type___pyx_MemviewEnum __pyx_mstate_global->__pyx_type___pyx_MemviewEnum +#define __pyx_type___pyx_memoryview __pyx_mstate_global->__pyx_type___pyx_memoryview +#define __pyx_type___pyx_memoryviewslice __pyx_mstate_global->__pyx_type___pyx_memoryviewslice +#endif +#define __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython __pyx_mstate_global->__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython +#define __pyx_array_type __pyx_mstate_global->__pyx_array_type +#define __pyx_MemviewEnum_type __pyx_mstate_global->__pyx_MemviewEnum_type +#define __pyx_memoryview_type __pyx_mstate_global->__pyx_memoryview_type +#define __pyx_memoryviewslice_type __pyx_mstate_global->__pyx_memoryviewslice_type +#define __pyx_kp_u_ __pyx_mstate_global->__pyx_kp_u_ +#define __pyx_kp_u_0 __pyx_mstate_global->__pyx_kp_u_0 +#define __pyx_n_s_ASCII __pyx_mstate_global->__pyx_n_s_ASCII +#define __pyx_n_s_AcadosOcpSolverCython __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython +#define __pyx_n_s_AcadosOcpSolverCython___get_poin __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython___get_poin +#define __pyx_n_s_AcadosOcpSolverCython___get_stat __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython___get_stat +#define __pyx_n_s_AcadosOcpSolverCython___get_stat_2 __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython___get_stat_2 +#define __pyx_n_s_AcadosOcpSolverCython___get_stat_3 __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython___get_stat_3 +#define __pyx_n_s_AcadosOcpSolverCython___reduce_c __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython___reduce_c +#define __pyx_n_s_AcadosOcpSolverCython___setstate __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython___setstate +#define __pyx_n_s_AcadosOcpSolverCython__get_poin __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython__get_poin +#define __pyx_n_s_AcadosOcpSolverCython__get_stat __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython__get_stat +#define __pyx_n_s_AcadosOcpSolverCython__get_stat_2 __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython__get_stat_2 +#define __pyx_n_s_AcadosOcpSolverCython__get_stat_3 __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython__get_stat_3 +#define __pyx_kp_u_AcadosOcpSolverCython_constraint __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_constraint +#define __pyx_n_s_AcadosOcpSolverCython_constraint_2 __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_constraint_2 +#define __pyx_n_s_AcadosOcpSolverCython_cost_set __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_cost_set +#define __pyx_kp_u_AcadosOcpSolverCython_cost_set_m __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_cost_set_m +#define __pyx_n_s_AcadosOcpSolverCython_custom_upd __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_custom_upd +#define __pyx_kp_u_AcadosOcpSolverCython_does_not_s __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_does_not_s +#define __pyx_kp_u_AcadosOcpSolverCython_does_not_s_2 __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_does_not_s_2 +#define __pyx_kp_u_AcadosOcpSolverCython_eval_param __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_eval_param +#define __pyx_kp_u_AcadosOcpSolverCython_eval_param_2 __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_eval_param_2 +#define __pyx_n_s_AcadosOcpSolverCython_eval_param_3 __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_eval_param_3 +#define __pyx_n_s_AcadosOcpSolverCython_get __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_get +#define __pyx_n_s_AcadosOcpSolverCython_get_cost __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_get_cost +#define __pyx_kp_u_AcadosOcpSolverCython_get_field __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_get_field +#define __pyx_n_s_AcadosOcpSolverCython_get_from_q __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_get_from_q +#define __pyx_kp_u_AcadosOcpSolverCython_get_is_an __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_get_is_an +#define __pyx_n_s_AcadosOcpSolverCython_get_residu __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_get_residu +#define __pyx_kp_u_AcadosOcpSolverCython_get_stage __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_get_stage +#define __pyx_n_s_AcadosOcpSolverCython_get_stats __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_get_stats +#define __pyx_n_s_AcadosOcpSolverCython_load_itera __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_load_itera +#define __pyx_kp_u_AcadosOcpSolverCython_options_se __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_options_se +#define __pyx_n_s_AcadosOcpSolverCython_options_se_2 __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_options_se_2 +#define __pyx_n_s_AcadosOcpSolverCython_print_stat __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_print_stat +#define __pyx_n_s_AcadosOcpSolverCython_reset __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_reset +#define __pyx_n_s_AcadosOcpSolverCython_set __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_set +#define __pyx_kp_u_AcadosOcpSolverCython_set_is_not __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_set_is_not +#define __pyx_kp_u_AcadosOcpSolverCython_set_mismat __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_set_mismat +#define __pyx_n_s_AcadosOcpSolverCython_set_new_ti __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_set_new_ti +#define __pyx_n_s_AcadosOcpSolverCython_set_params __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_set_params +#define __pyx_n_s_AcadosOcpSolverCython_solve __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_solve +#define __pyx_kp_u_AcadosOcpSolverCython_solve_argu __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_solve_argu +#define __pyx_kp_u_AcadosOcpSolverCython_solve_argu_2 __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_solve_argu_2 +#define __pyx_n_s_AcadosOcpSolverCython_solve_for __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_solve_for +#define __pyx_n_s_AcadosOcpSolverCython_store_iter __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_store_iter +#define __pyx_n_s_AcadosOcpSolverCython_update_qp __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_update_qp +#define __pyx_kp_s_All_dimensions_preceding_dimensi __pyx_mstate_global->__pyx_kp_s_All_dimensions_preceding_dimensi +#define __pyx_n_s_AssertionError __pyx_mstate_global->__pyx_n_s_AssertionError +#define __pyx_kp_s_Buffer_view_does_not_expose_stri __pyx_mstate_global->__pyx_kp_s_Buffer_view_does_not_expose_stri +#define __pyx_kp_s_Can_only_create_a_buffer_that_is __pyx_mstate_global->__pyx_kp_s_Can_only_create_a_buffer_that_is +#define __pyx_kp_s_Cannot_assign_to_read_only_memor __pyx_mstate_global->__pyx_kp_s_Cannot_assign_to_read_only_memor +#define __pyx_kp_s_Cannot_create_writable_memory_vi __pyx_mstate_global->__pyx_kp_s_Cannot_create_writable_memory_vi +#define __pyx_kp_u_Cannot_index_with_type __pyx_mstate_global->__pyx_kp_u_Cannot_index_with_type +#define __pyx_kp_s_Cannot_transpose_memoryview_with __pyx_mstate_global->__pyx_kp_s_Cannot_transpose_memoryview_with +#define __pyx_kp_s_Dimension_d_is_not_direct __pyx_mstate_global->__pyx_kp_s_Dimension_d_is_not_direct +#define __pyx_n_s_Ellipsis __pyx_mstate_global->__pyx_n_s_Ellipsis +#define __pyx_kp_s_Empty_shape_tuple_for_cython_arr __pyx_mstate_global->__pyx_kp_s_Empty_shape_tuple_for_cython_arr +#define __pyx_n_u_F __pyx_mstate_global->__pyx_n_u_F +#define __pyx_kp_u_Got_sizes_idx __pyx_mstate_global->__pyx_kp_u_Got_sizes_idx +#define __pyx_n_s_ImportError __pyx_mstate_global->__pyx_n_s_ImportError +#define __pyx_kp_s_Incompatible_checksums_0x_x_vs_0 __pyx_mstate_global->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0 +#define __pyx_n_s_IndexError __pyx_mstate_global->__pyx_n_s_IndexError +#define __pyx_kp_s_Index_out_of_bounds_axis_d __pyx_mstate_global->__pyx_kp_s_Index_out_of_bounds_axis_d +#define __pyx_kp_s_Indirect_dimensions_not_supporte __pyx_mstate_global->__pyx_kp_s_Indirect_dimensions_not_supporte +#define __pyx_kp_u_Invalid_mode_expected_c_or_fortr __pyx_mstate_global->__pyx_kp_u_Invalid_mode_expected_c_or_fortr +#define __pyx_kp_u_Invalid_shape_in_axis __pyx_mstate_global->__pyx_kp_u_Invalid_shape_in_axis +#define __pyx_n_s_MemoryError __pyx_mstate_global->__pyx_n_s_MemoryError +#define __pyx_kp_s_MemoryView_of_r_at_0x_x __pyx_mstate_global->__pyx_kp_s_MemoryView_of_r_at_0x_x +#define __pyx_kp_s_MemoryView_of_r_object __pyx_mstate_global->__pyx_kp_s_MemoryView_of_r_object +#define __pyx_n_s_N __pyx_mstate_global->__pyx_n_s_N +#define __pyx_kp_u_None __pyx_mstate_global->__pyx_kp_u_None +#define __pyx_n_s_NotImplementedError __pyx_mstate_global->__pyx_n_s_NotImplementedError +#define __pyx_n_b_O __pyx_mstate_global->__pyx_n_b_O +#define __pyx_kp_u_Out_of_bounds_on_buffer_access_a __pyx_mstate_global->__pyx_kp_u_Out_of_bounds_on_buffer_access_a +#define __pyx_n_s_PickleError __pyx_mstate_global->__pyx_n_s_PickleError +#define __pyx_n_u_SQP __pyx_mstate_global->__pyx_n_u_SQP +#define __pyx_n_u_SQP_RTI __pyx_mstate_global->__pyx_n_u_SQP_RTI +#define __pyx_n_s_Sequence __pyx_mstate_global->__pyx_n_s_Sequence +#define __pyx_kp_s_Step_may_not_be_zero_axis_d __pyx_mstate_global->__pyx_kp_s_Step_may_not_be_zero_axis_d +#define __pyx_kp_u_TODO __pyx_mstate_global->__pyx_kp_u_TODO +#define __pyx_n_s_TypeError __pyx_mstate_global->__pyx_n_s_TypeError +#define __pyx_kp_s_Unable_to_convert_item_to_object __pyx_mstate_global->__pyx_kp_s_Unable_to_convert_item_to_object +#define __pyx_n_s_ValueError __pyx_mstate_global->__pyx_n_s_ValueError +#define __pyx_n_s_View_MemoryView __pyx_mstate_global->__pyx_n_s_View_MemoryView +#define __pyx_kp_u_Warning_acados_ocp_solver_reache __pyx_mstate_global->__pyx_kp_u_Warning_acados_ocp_solver_reache +#define __pyx_kp_u_Y_m_d_H_M_S_f __pyx_mstate_global->__pyx_kp_u_Y_m_d_H_M_S_f +#define __pyx_kp_u__16 __pyx_mstate_global->__pyx_kp_u__16 +#define __pyx_n_u__17 __pyx_mstate_global->__pyx_n_u__17 +#define __pyx_kp_u__2 __pyx_mstate_global->__pyx_kp_u__2 +#define __pyx_n_s__3 __pyx_mstate_global->__pyx_n_s__3 +#define __pyx_kp_u__31 __pyx_mstate_global->__pyx_kp_u__31 +#define __pyx_kp_u__6 __pyx_mstate_global->__pyx_kp_u__6 +#define __pyx_kp_u__7 __pyx_mstate_global->__pyx_kp_u__7 +#define __pyx_n_s__94 __pyx_mstate_global->__pyx_n_s__94 +#define __pyx_n_s_abc __pyx_mstate_global->__pyx_n_s_abc +#define __pyx_kp_u_acados_acados_ocp_solver_returne __pyx_mstate_global->__pyx_kp_u_acados_acados_ocp_solver_returne +#define __pyx_n_s_acados_template_acados_ocp_solve __pyx_mstate_global->__pyx_n_s_acados_template_acados_ocp_solve +#define __pyx_n_s_allocate_buffer __pyx_mstate_global->__pyx_n_s_allocate_buffer +#define __pyx_n_u_alpha __pyx_mstate_global->__pyx_n_u_alpha +#define __pyx_n_u_alpha_min __pyx_mstate_global->__pyx_n_u_alpha_min +#define __pyx_n_u_alpha_reduction __pyx_mstate_global->__pyx_n_u_alpha_reduction +#define __pyx_kp_u_alpha_values_are_not_available_f __pyx_mstate_global->__pyx_kp_u_alpha_values_are_not_available_f +#define __pyx_kp_u_and __pyx_mstate_global->__pyx_kp_u_and +#define __pyx_n_s_array __pyx_mstate_global->__pyx_n_s_array +#define __pyx_n_s_ascontiguousarray __pyx_mstate_global->__pyx_n_s_ascontiguousarray +#define __pyx_n_s_asfortranarray __pyx_mstate_global->__pyx_n_s_asfortranarray +#define __pyx_n_s_asyncio_coroutines __pyx_mstate_global->__pyx_n_s_asyncio_coroutines +#define __pyx_kp_u_at_stage __pyx_mstate_global->__pyx_kp_u_at_stage +#define __pyx_n_s_base __pyx_mstate_global->__pyx_n_s_base +#define __pyx_n_s_c __pyx_mstate_global->__pyx_n_s_c +#define __pyx_n_u_c __pyx_mstate_global->__pyx_n_u_c +#define __pyx_n_s_class __pyx_mstate_global->__pyx_n_s_class +#define __pyx_n_s_class_getitem __pyx_mstate_global->__pyx_n_s_class_getitem +#define __pyx_n_s_cline_in_traceback __pyx_mstate_global->__pyx_n_s_cline_in_traceback +#define __pyx_n_s_collections __pyx_mstate_global->__pyx_n_s_collections +#define __pyx_kp_s_collections_abc __pyx_mstate_global->__pyx_kp_s_collections_abc +#define __pyx_n_s_constraints_fields __pyx_mstate_global->__pyx_n_s_constraints_fields +#define __pyx_n_s_constraints_set __pyx_mstate_global->__pyx_n_s_constraints_set +#define __pyx_kp_u_constraints_set_value_must_be_nu __pyx_mstate_global->__pyx_kp_u_constraints_set_value_must_be_nu +#define __pyx_kp_s_contiguous_and_direct __pyx_mstate_global->__pyx_kp_s_contiguous_and_direct +#define __pyx_kp_s_contiguous_and_indirect __pyx_mstate_global->__pyx_kp_s_contiguous_and_indirect +#define __pyx_n_s_cost_fields __pyx_mstate_global->__pyx_n_s_cost_fields +#define __pyx_n_s_cost_set __pyx_mstate_global->__pyx_n_s_cost_set +#define __pyx_kp_u_cost_set_value_must_be_numpy_arr __pyx_mstate_global->__pyx_kp_u_cost_set_value_must_be_numpy_arr +#define __pyx_n_s_count __pyx_mstate_global->__pyx_n_s_count +#define __pyx_n_s_custom_update __pyx_mstate_global->__pyx_n_s_custom_update +#define __pyx_n_u_d __pyx_mstate_global->__pyx_n_u_d +#define __pyx_n_s_data __pyx_mstate_global->__pyx_n_s_data +#define __pyx_n_s_data_2 __pyx_mstate_global->__pyx_n_s_data_2 +#define __pyx_n_s_data_len __pyx_mstate_global->__pyx_n_s_data_len +#define __pyx_n_s_datetime __pyx_mstate_global->__pyx_n_s_datetime +#define __pyx_n_s_default __pyx_mstate_global->__pyx_n_s_default +#define __pyx_n_s_dict __pyx_mstate_global->__pyx_n_s_dict +#define __pyx_n_s_dims __pyx_mstate_global->__pyx_n_s_dims +#define __pyx_kp_u_disable __pyx_mstate_global->__pyx_kp_u_disable +#define __pyx_n_s_double_fields __pyx_mstate_global->__pyx_n_s_double_fields +#define __pyx_n_s_double_value __pyx_mstate_global->__pyx_n_s_double_value +#define __pyx_n_s_dtype __pyx_mstate_global->__pyx_n_s_dtype +#define __pyx_n_s_dtype_is_object __pyx_mstate_global->__pyx_n_s_dtype_is_object +#define __pyx_n_s_dump __pyx_mstate_global->__pyx_n_s_dump +#define __pyx_kp_u_enable __pyx_mstate_global->__pyx_kp_u_enable +#define __pyx_n_s_encode __pyx_mstate_global->__pyx_n_s_encode +#define __pyx_n_s_enter __pyx_mstate_global->__pyx_n_s_enter +#define __pyx_n_s_enumerate __pyx_mstate_global->__pyx_n_s_enumerate +#define __pyx_n_u_eps_sufficient_descent __pyx_mstate_global->__pyx_n_u_eps_sufficient_descent +#define __pyx_n_s_error __pyx_mstate_global->__pyx_n_s_error +#define __pyx_n_s_eval_param_sens __pyx_mstate_global->__pyx_n_s_eval_param_sens +#define __pyx_n_u_ex __pyx_mstate_global->__pyx_n_u_ex +#define __pyx_n_s_exit __pyx_mstate_global->__pyx_n_s_exit +#define __pyx_n_s_f __pyx_mstate_global->__pyx_n_s_f +#define __pyx_n_s_field __pyx_mstate_global->__pyx_n_s_field +#define __pyx_n_s_field_2 __pyx_mstate_global->__pyx_n_s_field_2 +#define __pyx_n_s_fields __pyx_mstate_global->__pyx_n_s_fields +#define __pyx_n_s_filename __pyx_mstate_global->__pyx_n_s_filename +#define __pyx_n_s_flags __pyx_mstate_global->__pyx_n_s_flags +#define __pyx_n_s_float64 __pyx_mstate_global->__pyx_n_s_float64 +#define __pyx_kp_u_for_field __pyx_mstate_global->__pyx_kp_u_for_field +#define __pyx_n_s_format __pyx_mstate_global->__pyx_n_s_format +#define __pyx_n_s_fortran __pyx_mstate_global->__pyx_n_s_fortran +#define __pyx_n_u_fortran __pyx_mstate_global->__pyx_n_u_fortran +#define __pyx_n_s_full_stats __pyx_mstate_global->__pyx_n_s_full_stats +#define __pyx_n_u_full_step_dual __pyx_mstate_global->__pyx_n_u_full_step_dual +#define __pyx_kp_u_gc __pyx_mstate_global->__pyx_kp_u_gc +#define __pyx_n_s_get __pyx_mstate_global->__pyx_n_s_get +#define __pyx_n_s_get_cost __pyx_mstate_global->__pyx_n_s_get_cost +#define __pyx_n_s_get_from_qp_in __pyx_mstate_global->__pyx_n_s_get_from_qp_in +#define __pyx_n_s_get_pointers_solver __pyx_mstate_global->__pyx_n_s_get_pointers_solver +#define __pyx_n_s_get_residuals __pyx_mstate_global->__pyx_n_s_get_residuals +#define __pyx_n_s_get_stat_double __pyx_mstate_global->__pyx_n_s_get_stat_double +#define __pyx_n_s_get_stat_int __pyx_mstate_global->__pyx_n_s_get_stat_int +#define __pyx_n_s_get_stat_matrix __pyx_mstate_global->__pyx_n_s_get_stat_matrix +#define __pyx_n_s_get_stats __pyx_mstate_global->__pyx_n_s_get_stats +#define __pyx_n_s_getcwd __pyx_mstate_global->__pyx_n_s_getcwd +#define __pyx_n_s_getstate __pyx_mstate_global->__pyx_n_s_getstate +#define __pyx_n_u_globalization __pyx_mstate_global->__pyx_n_u_globalization +#define __pyx_n_u_globalization_use_SOC __pyx_mstate_global->__pyx_n_u_globalization_use_SOC +#define __pyx_kp_u_got __pyx_mstate_global->__pyx_kp_u_got +#define __pyx_kp_u_got_differing_extents_in_dimensi __pyx_mstate_global->__pyx_kp_u_got_differing_extents_in_dimensi +#define __pyx_n_s_i __pyx_mstate_global->__pyx_n_s_i +#define __pyx_n_s_i_string __pyx_mstate_global->__pyx_n_s_i_string +#define __pyx_n_s_id __pyx_mstate_global->__pyx_n_s_id +#define __pyx_n_s_idx __pyx_mstate_global->__pyx_n_s_idx +#define __pyx_n_s_idx_values __pyx_mstate_global->__pyx_n_s_idx_values +#define __pyx_n_s_import __pyx_mstate_global->__pyx_n_s_import +#define __pyx_n_s_indent __pyx_mstate_global->__pyx_n_s_indent +#define __pyx_n_s_index __pyx_mstate_global->__pyx_n_s_index +#define __pyx_n_u_initialize_t_slacks __pyx_mstate_global->__pyx_n_u_initialize_t_slacks +#define __pyx_n_s_initializing __pyx_mstate_global->__pyx_n_s_initializing +#define __pyx_n_s_int __pyx_mstate_global->__pyx_n_s_int +#define __pyx_n_s_int32 __pyx_mstate_global->__pyx_n_s_int32 +#define __pyx_n_s_int_fields __pyx_mstate_global->__pyx_n_s_int_fields +#define __pyx_n_s_int_value __pyx_mstate_global->__pyx_n_s_int_value +#define __pyx_n_s_is_coroutine __pyx_mstate_global->__pyx_n_s_is_coroutine +#define __pyx_kp_u_isenabled __pyx_mstate_global->__pyx_kp_u_isenabled +#define __pyx_n_s_isfile __pyx_mstate_global->__pyx_n_s_isfile +#define __pyx_n_s_itemsize __pyx_mstate_global->__pyx_n_s_itemsize +#define __pyx_kp_s_itemsize_0_for_cython_array __pyx_mstate_global->__pyx_kp_s_itemsize_0_for_cython_array +#define __pyx_n_u_iterate __pyx_mstate_global->__pyx_n_u_iterate +#define __pyx_n_s_join __pyx_mstate_global->__pyx_n_s_join +#define __pyx_n_s_json __pyx_mstate_global->__pyx_n_s_json +#define __pyx_kp_u_json_2 __pyx_mstate_global->__pyx_kp_u_json_2 +#define __pyx_n_s_k __pyx_mstate_global->__pyx_n_s_k +#define __pyx_n_s_key __pyx_mstate_global->__pyx_n_s_key +#define __pyx_n_s_keys __pyx_mstate_global->__pyx_n_s_keys +#define __pyx_n_s_lN __pyx_mstate_global->__pyx_n_s_lN +#define __pyx_n_u_lam __pyx_mstate_global->__pyx_n_u_lam +#define __pyx_n_u_lam_2 __pyx_mstate_global->__pyx_n_u_lam_2 +#define __pyx_n_u_lbu __pyx_mstate_global->__pyx_n_u_lbu +#define __pyx_n_u_lbx __pyx_mstate_global->__pyx_n_u_lbx +#define __pyx_n_u_line_search_use_sufficient_desce __pyx_mstate_global->__pyx_n_u_line_search_use_sufficient_desce +#define __pyx_n_s_load __pyx_mstate_global->__pyx_n_s_load +#define __pyx_n_s_load_iterate __pyx_mstate_global->__pyx_n_s_load_iterate +#define __pyx_kp_u_load_iterate_failed_file_does_no __pyx_mstate_global->__pyx_kp_u_load_iterate_failed_file_does_no +#define __pyx_n_s_m __pyx_mstate_global->__pyx_n_s_m +#define __pyx_n_s_main __pyx_mstate_global->__pyx_n_s_main +#define __pyx_n_s_mem_fields __pyx_mstate_global->__pyx_n_s_mem_fields +#define __pyx_n_s_memview __pyx_mstate_global->__pyx_n_s_memview +#define __pyx_n_s_min_size __pyx_mstate_global->__pyx_n_s_min_size +#define __pyx_n_s_mode __pyx_mstate_global->__pyx_n_s_mode +#define __pyx_n_s_model_name __pyx_mstate_global->__pyx_n_s_model_name +#define __pyx_n_s_msg __pyx_mstate_global->__pyx_n_s_msg +#define __pyx_n_s_n __pyx_mstate_global->__pyx_n_s_n +#define __pyx_n_s_n_update __pyx_mstate_global->__pyx_n_s_n_update +#define __pyx_n_s_name __pyx_mstate_global->__pyx_n_s_name +#define __pyx_n_s_name_2 __pyx_mstate_global->__pyx_n_s_name_2 +#define __pyx_n_s_ndarray __pyx_mstate_global->__pyx_n_s_ndarray +#define __pyx_n_s_ndim __pyx_mstate_global->__pyx_n_s_ndim +#define __pyx_n_s_new __pyx_mstate_global->__pyx_n_s_new +#define __pyx_n_s_new_time_steps __pyx_mstate_global->__pyx_n_s_new_time_steps +#define __pyx_n_s_nlp_solver_type __pyx_mstate_global->__pyx_n_s_nlp_solver_type +#define __pyx_kp_s_no_default___reduce___due_to_non __pyx_mstate_global->__pyx_kp_s_no_default___reduce___due_to_non +#define __pyx_n_s_np __pyx_mstate_global->__pyx_n_s_np +#define __pyx_n_s_numpy __pyx_mstate_global->__pyx_n_s_numpy +#define __pyx_kp_u_numpy_core_multiarray_failed_to __pyx_mstate_global->__pyx_kp_u_numpy_core_multiarray_failed_to +#define __pyx_kp_u_numpy_core_umath_failed_to_impor __pyx_mstate_global->__pyx_kp_u_numpy_core_umath_failed_to_impor +#define __pyx_n_s_nx __pyx_mstate_global->__pyx_n_s_nx +#define __pyx_n_s_obj __pyx_mstate_global->__pyx_n_s_obj +#define __pyx_n_s_open __pyx_mstate_global->__pyx_n_s_open +#define __pyx_n_s_options_set __pyx_mstate_global->__pyx_n_s_options_set +#define __pyx_n_s_order __pyx_mstate_global->__pyx_n_s_order +#define __pyx_n_s_os __pyx_mstate_global->__pyx_n_s_os +#define __pyx_n_s_out __pyx_mstate_global->__pyx_n_s_out +#define __pyx_n_s_out_fields __pyx_mstate_global->__pyx_n_s_out_fields +#define __pyx_n_s_out_mat __pyx_mstate_global->__pyx_n_s_out_mat +#define __pyx_n_s_overwrite __pyx_mstate_global->__pyx_n_s_overwrite +#define __pyx_n_u_p __pyx_mstate_global->__pyx_n_u_p +#define __pyx_n_s_pack __pyx_mstate_global->__pyx_n_s_pack +#define __pyx_n_s_param_values __pyx_mstate_global->__pyx_n_s_param_values +#define __pyx_kp_u_param_values_2 __pyx_mstate_global->__pyx_kp_u_param_values_2 +#define __pyx_kp_u_param_values__and_idx_values__mu __pyx_mstate_global->__pyx_kp_u_param_values__and_idx_values__mu +#define __pyx_kp_u_param_values__must_be_np_array __pyx_mstate_global->__pyx_kp_u_param_values__must_be_np_array +#define __pyx_n_s_path __pyx_mstate_global->__pyx_n_s_path +#define __pyx_n_u_pi __pyx_mstate_global->__pyx_n_u_pi +#define __pyx_n_u_pi_2 __pyx_mstate_global->__pyx_n_u_pi_2 +#define __pyx_n_s_pickle __pyx_mstate_global->__pyx_n_s_pickle +#define __pyx_n_s_print __pyx_mstate_global->__pyx_n_s_print +#define __pyx_n_u_print_level __pyx_mstate_global->__pyx_n_u_print_level +#define __pyx_n_s_print_statistics __pyx_mstate_global->__pyx_n_s_print_statistics +#define __pyx_n_s_pyx_PickleError __pyx_mstate_global->__pyx_n_s_pyx_PickleError +#define __pyx_n_s_pyx_checksum __pyx_mstate_global->__pyx_n_s_pyx_checksum +#define __pyx_n_s_pyx_result __pyx_mstate_global->__pyx_n_s_pyx_result +#define __pyx_n_s_pyx_state __pyx_mstate_global->__pyx_n_s_pyx_state +#define __pyx_n_s_pyx_type __pyx_mstate_global->__pyx_n_s_pyx_type +#define __pyx_n_s_pyx_unpickle_Enum __pyx_mstate_global->__pyx_n_s_pyx_unpickle_Enum +#define __pyx_n_s_pyx_vtable __pyx_mstate_global->__pyx_n_s_pyx_vtable +#define __pyx_n_u_qp_iter __pyx_mstate_global->__pyx_n_u_qp_iter +#define __pyx_n_u_qp_mu0 __pyx_mstate_global->__pyx_n_u_qp_mu0 +#define __pyx_n_s_qp_solver_cond_N __pyx_mstate_global->__pyx_n_s_qp_solver_cond_N +#define __pyx_n_u_qp_tau_min __pyx_mstate_global->__pyx_n_u_qp_tau_min +#define __pyx_n_u_qp_tol_comp __pyx_mstate_global->__pyx_n_u_qp_tol_comp +#define __pyx_n_u_qp_tol_eq __pyx_mstate_global->__pyx_n_u_qp_tol_eq +#define __pyx_n_u_qp_tol_ineq __pyx_mstate_global->__pyx_n_u_qp_tol_ineq +#define __pyx_n_u_qp_tol_stat __pyx_mstate_global->__pyx_n_u_qp_tol_stat +#define __pyx_n_u_qp_warm_start __pyx_mstate_global->__pyx_n_u_qp_warm_start +#define __pyx_n_u_r __pyx_mstate_global->__pyx_n_u_r +#define __pyx_n_s_range __pyx_mstate_global->__pyx_n_s_range +#define __pyx_n_s_recompute __pyx_mstate_global->__pyx_n_s_recompute +#define __pyx_n_s_reduce __pyx_mstate_global->__pyx_n_s_reduce +#define __pyx_n_s_reduce_cython __pyx_mstate_global->__pyx_n_s_reduce_cython +#define __pyx_n_s_reduce_ex __pyx_mstate_global->__pyx_n_s_reduce_ex +#define __pyx_n_s_register __pyx_mstate_global->__pyx_n_s_register +#define __pyx_n_b_res_comp __pyx_mstate_global->__pyx_n_b_res_comp +#define __pyx_n_b_res_eq __pyx_mstate_global->__pyx_n_b_res_eq +#define __pyx_n_b_res_ineq __pyx_mstate_global->__pyx_n_b_res_ineq +#define __pyx_n_b_res_stat __pyx_mstate_global->__pyx_n_b_res_stat +#define __pyx_n_s_reset __pyx_mstate_global->__pyx_n_s_reset +#define __pyx_n_s_reset_qp_solver_mem __pyx_mstate_global->__pyx_n_s_reset_qp_solver_mem +#define __pyx_n_u_residuals __pyx_mstate_global->__pyx_n_u_residuals +#define __pyx_n_u_rti_phase __pyx_mstate_global->__pyx_n_u_rti_phase +#define __pyx_n_s_self __pyx_mstate_global->__pyx_n_s_self +#define __pyx_n_s_set __pyx_mstate_global->__pyx_n_s_set +#define __pyx_n_s_set_new_time_steps __pyx_mstate_global->__pyx_n_s_set_new_time_steps +#define __pyx_n_s_set_params_sparse __pyx_mstate_global->__pyx_n_s_set_params_sparse +#define __pyx_kp_u_set_value_must_be_numpy_array_go __pyx_mstate_global->__pyx_kp_u_set_value_must_be_numpy_array_go +#define __pyx_n_s_setstate __pyx_mstate_global->__pyx_n_s_setstate +#define __pyx_n_s_setstate_cython __pyx_mstate_global->__pyx_n_s_setstate_cython +#define __pyx_n_s_shape __pyx_mstate_global->__pyx_n_s_shape +#define __pyx_n_s_size __pyx_mstate_global->__pyx_n_s_size +#define __pyx_n_u_sl __pyx_mstate_global->__pyx_n_u_sl +#define __pyx_n_u_sl_2 __pyx_mstate_global->__pyx_n_u_sl_2 +#define __pyx_n_s_solution __pyx_mstate_global->__pyx_n_s_solution +#define __pyx_n_s_solve __pyx_mstate_global->__pyx_n_s_solve +#define __pyx_n_s_solve_for_x0 __pyx_mstate_global->__pyx_n_s_solve_for_x0 +#define __pyx_kp_u_solver_option_must_be_of_type_fl __pyx_mstate_global->__pyx_kp_u_solver_option_must_be_of_type_fl +#define __pyx_kp_u_solver_option_must_be_of_type_in __pyx_mstate_global->__pyx_kp_u_solver_option_must_be_of_type_in +#define __pyx_kp_u_solver_option_must_be_of_type_st __pyx_mstate_global->__pyx_kp_u_solver_option_must_be_of_type_st +#define __pyx_n_s_sort_keys __pyx_mstate_global->__pyx_n_s_sort_keys +#define __pyx_n_s_spec __pyx_mstate_global->__pyx_n_s_spec +#define __pyx_n_s_split __pyx_mstate_global->__pyx_n_s_split +#define __pyx_n_s_sqp_iter __pyx_mstate_global->__pyx_n_s_sqp_iter +#define __pyx_n_u_sqp_iter __pyx_mstate_global->__pyx_n_u_sqp_iter +#define __pyx_n_s_stage __pyx_mstate_global->__pyx_n_s_stage +#define __pyx_n_s_start __pyx_mstate_global->__pyx_n_s_start +#define __pyx_n_s_stat_m __pyx_mstate_global->__pyx_n_s_stat_m +#define __pyx_n_u_stat_m __pyx_mstate_global->__pyx_n_u_stat_m +#define __pyx_n_s_stat_n __pyx_mstate_global->__pyx_n_s_stat_n +#define __pyx_n_u_stat_n __pyx_mstate_global->__pyx_n_u_stat_n +#define __pyx_n_u_statistics __pyx_mstate_global->__pyx_n_u_statistics +#define __pyx_n_s_status __pyx_mstate_global->__pyx_n_s_status +#define __pyx_n_s_step __pyx_mstate_global->__pyx_n_s_step +#define __pyx_n_u_step_length __pyx_mstate_global->__pyx_n_u_step_length +#define __pyx_n_s_stop __pyx_mstate_global->__pyx_n_s_stop +#define __pyx_n_s_store_iterate __pyx_mstate_global->__pyx_n_s_store_iterate +#define __pyx_n_s_store_iterate_locals_lambda __pyx_mstate_global->__pyx_n_s_store_iterate_locals_lambda +#define __pyx_kp_u_stored_current_iterate_in __pyx_mstate_global->__pyx_kp_u_stored_current_iterate_in +#define __pyx_n_s_strftime __pyx_mstate_global->__pyx_n_s_strftime +#define __pyx_kp_s_strided_and_direct __pyx_mstate_global->__pyx_kp_s_strided_and_direct +#define __pyx_kp_s_strided_and_direct_or_indirect __pyx_mstate_global->__pyx_kp_s_strided_and_direct_or_indirect +#define __pyx_kp_s_strided_and_indirect __pyx_mstate_global->__pyx_kp_s_strided_and_indirect +#define __pyx_n_s_string_fields __pyx_mstate_global->__pyx_n_s_string_fields +#define __pyx_n_s_string_value __pyx_mstate_global->__pyx_n_s_string_value +#define __pyx_kp_s_stringsource __pyx_mstate_global->__pyx_kp_s_stringsource +#define __pyx_n_s_struct __pyx_mstate_global->__pyx_n_s_struct +#define __pyx_n_u_su __pyx_mstate_global->__pyx_n_u_su +#define __pyx_n_u_su_2 __pyx_mstate_global->__pyx_n_u_su_2 +#define __pyx_n_s_sys __pyx_mstate_global->__pyx_n_s_sys +#define __pyx_n_u_t __pyx_mstate_global->__pyx_n_u_t +#define __pyx_n_u_t_2 __pyx_mstate_global->__pyx_n_u_t_2 +#define __pyx_n_s_test __pyx_mstate_global->__pyx_n_s_test +#define __pyx_kp_s_third_party_acados_acados_templa __pyx_mstate_global->__pyx_kp_s_third_party_acados_acados_templa +#define __pyx_n_u_time_glob __pyx_mstate_global->__pyx_n_u_time_glob +#define __pyx_n_u_time_lin __pyx_mstate_global->__pyx_n_u_time_lin +#define __pyx_n_u_time_qp __pyx_mstate_global->__pyx_n_u_time_qp +#define __pyx_n_u_time_qp_solver_call __pyx_mstate_global->__pyx_n_u_time_qp_solver_call +#define __pyx_n_u_time_qp_xcond __pyx_mstate_global->__pyx_n_u_time_qp_xcond +#define __pyx_n_u_time_reg __pyx_mstate_global->__pyx_n_u_time_reg +#define __pyx_n_u_time_sim __pyx_mstate_global->__pyx_n_u_time_sim +#define __pyx_n_u_time_sim_ad __pyx_mstate_global->__pyx_n_u_time_sim_ad +#define __pyx_n_u_time_sim_la __pyx_mstate_global->__pyx_n_u_time_sim_la +#define __pyx_n_u_time_solution_sensitivities __pyx_mstate_global->__pyx_n_u_time_solution_sensitivities +#define __pyx_n_u_time_tot __pyx_mstate_global->__pyx_n_u_time_tot +#define __pyx_n_u_tol_comp __pyx_mstate_global->__pyx_n_u_tol_comp +#define __pyx_n_u_tol_eq __pyx_mstate_global->__pyx_n_u_tol_eq +#define __pyx_n_u_tol_ineq __pyx_mstate_global->__pyx_n_u_tol_ineq +#define __pyx_n_u_tol_stat __pyx_mstate_global->__pyx_n_u_tol_stat +#define __pyx_n_s_tolist __pyx_mstate_global->__pyx_n_s_tolist +#define __pyx_n_u_u __pyx_mstate_global->__pyx_n_u_u +#define __pyx_n_s_u0 __pyx_mstate_global->__pyx_n_s_u0 +#define __pyx_n_u_u_2 __pyx_mstate_global->__pyx_n_u_u_2 +#define __pyx_n_u_ubu __pyx_mstate_global->__pyx_n_u_ubu +#define __pyx_n_u_ubx __pyx_mstate_global->__pyx_n_u_ubx +#define __pyx_kp_s_unable_to_allocate_array_data __pyx_mstate_global->__pyx_kp_s_unable_to_allocate_array_data +#define __pyx_kp_s_unable_to_allocate_shape_and_str __pyx_mstate_global->__pyx_kp_s_unable_to_allocate_shape_and_str +#define __pyx_n_s_unpack __pyx_mstate_global->__pyx_n_s_unpack +#define __pyx_n_s_update __pyx_mstate_global->__pyx_n_s_update +#define __pyx_n_s_update_qp_solver_cond_N __pyx_mstate_global->__pyx_n_s_update_qp_solver_cond_N +#define __pyx_n_s_utcnow __pyx_mstate_global->__pyx_n_s_utcnow +#define __pyx_kp_u_utf_8 __pyx_mstate_global->__pyx_kp_u_utf_8 +#define __pyx_n_s_value __pyx_mstate_global->__pyx_n_s_value +#define __pyx_n_s_value_2 __pyx_mstate_global->__pyx_n_s_value_2 +#define __pyx_n_s_value_shape __pyx_mstate_global->__pyx_n_s_value_shape +#define __pyx_n_s_version_info __pyx_mstate_global->__pyx_n_s_version_info +#define __pyx_n_u_w __pyx_mstate_global->__pyx_n_u_w +#define __pyx_n_u_warm_start_first_qp __pyx_mstate_global->__pyx_n_u_warm_start_first_qp +#define __pyx_kp_u_with_dimension __pyx_mstate_global->__pyx_kp_u_with_dimension +#define __pyx_kp_u_with_dimension_you_have __pyx_mstate_global->__pyx_kp_u_with_dimension_you_have +#define __pyx_n_b_x __pyx_mstate_global->__pyx_n_b_x +#define __pyx_n_s_x __pyx_mstate_global->__pyx_n_s_x +#define __pyx_n_u_x __pyx_mstate_global->__pyx_n_u_x +#define __pyx_n_s_x0_bar __pyx_mstate_global->__pyx_n_s_x0_bar +#define __pyx_n_u_x_2 __pyx_mstate_global->__pyx_n_u_x_2 +#define __pyx_n_u_xdot_guess __pyx_mstate_global->__pyx_n_u_xdot_guess +#define __pyx_n_u_y_ref __pyx_mstate_global->__pyx_n_u_y_ref +#define __pyx_kp_u_you_have __pyx_mstate_global->__pyx_kp_u_you_have +#define __pyx_n_u_yref __pyx_mstate_global->__pyx_n_u_yref +#define __pyx_n_u_z __pyx_mstate_global->__pyx_n_u_z +#define __pyx_n_u_z_2 __pyx_mstate_global->__pyx_n_u_z_2 +#define __pyx_n_b_z_guess __pyx_mstate_global->__pyx_n_b_z_guess +#define __pyx_n_u_z_guess __pyx_mstate_global->__pyx_n_u_z_guess +#define __pyx_n_s_zeros __pyx_mstate_global->__pyx_n_s_zeros +#define __pyx_int_0 __pyx_mstate_global->__pyx_int_0 +#define __pyx_int_1 __pyx_mstate_global->__pyx_int_1 +#define __pyx_int_2 __pyx_mstate_global->__pyx_int_2 +#define __pyx_int_3 __pyx_mstate_global->__pyx_int_3 +#define __pyx_int_4 __pyx_mstate_global->__pyx_int_4 +#define __pyx_int_6 __pyx_mstate_global->__pyx_int_6 +#define __pyx_int_7 __pyx_mstate_global->__pyx_int_7 +#define __pyx_int_112105877 __pyx_mstate_global->__pyx_int_112105877 +#define __pyx_int_136983863 __pyx_mstate_global->__pyx_int_136983863 +#define __pyx_int_184977713 __pyx_mstate_global->__pyx_int_184977713 +#define __pyx_int_neg_1 __pyx_mstate_global->__pyx_int_neg_1 +#define __pyx_int_neg_5 __pyx_mstate_global->__pyx_int_neg_5 +#define __pyx_slice__5 __pyx_mstate_global->__pyx_slice__5 +#define __pyx_tuple__4 __pyx_mstate_global->__pyx_tuple__4 +#define __pyx_tuple__8 __pyx_mstate_global->__pyx_tuple__8 +#define __pyx_tuple__9 __pyx_mstate_global->__pyx_tuple__9 +#define __pyx_slice__18 __pyx_mstate_global->__pyx_slice__18 +#define __pyx_tuple__10 __pyx_mstate_global->__pyx_tuple__10 +#define __pyx_tuple__11 __pyx_mstate_global->__pyx_tuple__11 +#define __pyx_tuple__12 __pyx_mstate_global->__pyx_tuple__12 +#define __pyx_tuple__13 __pyx_mstate_global->__pyx_tuple__13 +#define __pyx_tuple__14 __pyx_mstate_global->__pyx_tuple__14 +#define __pyx_tuple__15 __pyx_mstate_global->__pyx_tuple__15 +#define __pyx_tuple__19 __pyx_mstate_global->__pyx_tuple__19 +#define __pyx_tuple__20 __pyx_mstate_global->__pyx_tuple__20 +#define __pyx_tuple__21 __pyx_mstate_global->__pyx_tuple__21 +#define __pyx_tuple__22 __pyx_mstate_global->__pyx_tuple__22 +#define __pyx_tuple__23 __pyx_mstate_global->__pyx_tuple__23 +#define __pyx_tuple__24 __pyx_mstate_global->__pyx_tuple__24 +#define __pyx_tuple__25 __pyx_mstate_global->__pyx_tuple__25 +#define __pyx_tuple__26 __pyx_mstate_global->__pyx_tuple__26 +#define __pyx_tuple__27 __pyx_mstate_global->__pyx_tuple__27 +#define __pyx_tuple__28 __pyx_mstate_global->__pyx_tuple__28 +#define __pyx_tuple__29 __pyx_mstate_global->__pyx_tuple__29 +#define __pyx_tuple__30 __pyx_mstate_global->__pyx_tuple__30 +#define __pyx_tuple__32 __pyx_mstate_global->__pyx_tuple__32 +#define __pyx_tuple__33 __pyx_mstate_global->__pyx_tuple__33 +#define __pyx_tuple__34 __pyx_mstate_global->__pyx_tuple__34 +#define __pyx_tuple__35 __pyx_mstate_global->__pyx_tuple__35 +#define __pyx_tuple__36 __pyx_mstate_global->__pyx_tuple__36 +#define __pyx_tuple__37 __pyx_mstate_global->__pyx_tuple__37 +#define __pyx_tuple__38 __pyx_mstate_global->__pyx_tuple__38 +#define __pyx_tuple__39 __pyx_mstate_global->__pyx_tuple__39 +#define __pyx_tuple__40 __pyx_mstate_global->__pyx_tuple__40 +#define __pyx_tuple__41 __pyx_mstate_global->__pyx_tuple__41 +#define __pyx_tuple__42 __pyx_mstate_global->__pyx_tuple__42 +#define __pyx_tuple__44 __pyx_mstate_global->__pyx_tuple__44 +#define __pyx_tuple__46 __pyx_mstate_global->__pyx_tuple__46 +#define __pyx_tuple__49 __pyx_mstate_global->__pyx_tuple__49 +#define __pyx_tuple__51 __pyx_mstate_global->__pyx_tuple__51 +#define __pyx_tuple__53 __pyx_mstate_global->__pyx_tuple__53 +#define __pyx_tuple__55 __pyx_mstate_global->__pyx_tuple__55 +#define __pyx_tuple__57 __pyx_mstate_global->__pyx_tuple__57 +#define __pyx_tuple__59 __pyx_mstate_global->__pyx_tuple__59 +#define __pyx_tuple__60 __pyx_mstate_global->__pyx_tuple__60 +#define __pyx_tuple__63 __pyx_mstate_global->__pyx_tuple__63 +#define __pyx_tuple__65 __pyx_mstate_global->__pyx_tuple__65 +#define __pyx_tuple__66 __pyx_mstate_global->__pyx_tuple__66 +#define __pyx_tuple__68 __pyx_mstate_global->__pyx_tuple__68 +#define __pyx_tuple__70 __pyx_mstate_global->__pyx_tuple__70 +#define __pyx_tuple__73 __pyx_mstate_global->__pyx_tuple__73 +#define __pyx_tuple__75 __pyx_mstate_global->__pyx_tuple__75 +#define __pyx_tuple__77 __pyx_mstate_global->__pyx_tuple__77 +#define __pyx_tuple__79 __pyx_mstate_global->__pyx_tuple__79 +#define __pyx_tuple__80 __pyx_mstate_global->__pyx_tuple__80 +#define __pyx_tuple__82 __pyx_mstate_global->__pyx_tuple__82 +#define __pyx_tuple__85 __pyx_mstate_global->__pyx_tuple__85 +#define __pyx_tuple__87 __pyx_mstate_global->__pyx_tuple__87 +#define __pyx_tuple__89 __pyx_mstate_global->__pyx_tuple__89 +#define __pyx_tuple__92 __pyx_mstate_global->__pyx_tuple__92 +#define __pyx_codeobj__43 __pyx_mstate_global->__pyx_codeobj__43 +#define __pyx_codeobj__45 __pyx_mstate_global->__pyx_codeobj__45 +#define __pyx_codeobj__47 __pyx_mstate_global->__pyx_codeobj__47 +#define __pyx_codeobj__48 __pyx_mstate_global->__pyx_codeobj__48 +#define __pyx_codeobj__50 __pyx_mstate_global->__pyx_codeobj__50 +#define __pyx_codeobj__52 __pyx_mstate_global->__pyx_codeobj__52 +#define __pyx_codeobj__54 __pyx_mstate_global->__pyx_codeobj__54 +#define __pyx_codeobj__56 __pyx_mstate_global->__pyx_codeobj__56 +#define __pyx_codeobj__58 __pyx_mstate_global->__pyx_codeobj__58 +#define __pyx_codeobj__61 __pyx_mstate_global->__pyx_codeobj__61 +#define __pyx_codeobj__62 __pyx_mstate_global->__pyx_codeobj__62 +#define __pyx_codeobj__64 __pyx_mstate_global->__pyx_codeobj__64 +#define __pyx_codeobj__67 __pyx_mstate_global->__pyx_codeobj__67 +#define __pyx_codeobj__69 __pyx_mstate_global->__pyx_codeobj__69 +#define __pyx_codeobj__71 __pyx_mstate_global->__pyx_codeobj__71 +#define __pyx_codeobj__72 __pyx_mstate_global->__pyx_codeobj__72 +#define __pyx_codeobj__74 __pyx_mstate_global->__pyx_codeobj__74 +#define __pyx_codeobj__76 __pyx_mstate_global->__pyx_codeobj__76 +#define __pyx_codeobj__78 __pyx_mstate_global->__pyx_codeobj__78 +#define __pyx_codeobj__81 __pyx_mstate_global->__pyx_codeobj__81 +#define __pyx_codeobj__83 __pyx_mstate_global->__pyx_codeobj__83 +#define __pyx_codeobj__84 __pyx_mstate_global->__pyx_codeobj__84 +#define __pyx_codeobj__86 __pyx_mstate_global->__pyx_codeobj__86 +#define __pyx_codeobj__88 __pyx_mstate_global->__pyx_codeobj__88 +#define __pyx_codeobj__90 __pyx_mstate_global->__pyx_codeobj__90 +#define __pyx_codeobj__91 __pyx_mstate_global->__pyx_codeobj__91 +#define __pyx_codeobj__93 __pyx_mstate_global->__pyx_codeobj__93 +/* #### Code section: module_code ### */ + +/* "carray.to_py":114 + * + * @cname("__Pyx_carray_to_py_int") + * cdef inline list __Pyx_carray_to_py_int(base_type *v, Py_ssize_t length): # <<<<<<<<<<<<<< + * cdef size_t i + * cdef object value + */ + +static CYTHON_INLINE PyObject *__Pyx_carray_to_py_int(int *__pyx_v_v, Py_ssize_t __pyx_v_length) { + size_t __pyx_v_i; + PyObject *__pyx_v_value = 0; + PyObject *__pyx_v_l = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + size_t __pyx_t_2; + size_t __pyx_t_3; + size_t __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_carray_to_py_int", 1); + + /* "carray.to_py":117 + * cdef size_t i + * cdef object value + * l = PyList_New(length) # <<<<<<<<<<<<<< + * for i in range(length): + * value = v[i] + */ + __pyx_t_1 = PyList_New(__pyx_v_length); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 117, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_l = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "carray.to_py":118 + * cdef object value + * l = PyList_New(length) + * for i in range(length): # <<<<<<<<<<<<<< + * value = v[i] + * Py_INCREF(value) + */ + __pyx_t_2 = ((size_t)__pyx_v_length); + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "carray.to_py":119 + * l = PyList_New(length) + * for i in range(length): + * value = v[i] # <<<<<<<<<<<<<< + * Py_INCREF(value) + * PyList_SET_ITEM(l, i, value) + */ + __pyx_t_1 = __Pyx_PyInt_From_int((__pyx_v_v[__pyx_v_i])); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 119, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_XDECREF_SET(__pyx_v_value, __pyx_t_1); + __pyx_t_1 = 0; + + /* "carray.to_py":120 + * for i in range(length): + * value = v[i] + * Py_INCREF(value) # <<<<<<<<<<<<<< + * PyList_SET_ITEM(l, i, value) + * return l + */ + Py_INCREF(__pyx_v_value); + + /* "carray.to_py":121 + * value = v[i] + * Py_INCREF(value) + * PyList_SET_ITEM(l, i, value) # <<<<<<<<<<<<<< + * return l + * + */ + PyList_SET_ITEM(__pyx_v_l, __pyx_v_i, __pyx_v_value); + } + + /* "carray.to_py":122 + * Py_INCREF(value) + * PyList_SET_ITEM(l, i, value) + * return l # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_l); + __pyx_r = __pyx_v_l; + goto __pyx_L0; + + /* "carray.to_py":114 + * + * @cname("__Pyx_carray_to_py_int") + * cdef inline list __Pyx_carray_to_py_int(base_type *v, Py_ssize_t length): # <<<<<<<<<<<<<< + * cdef size_t i + * cdef object value + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("carray.to_py.__Pyx_carray_to_py_int", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_value); + __Pyx_XDECREF(__pyx_v_l); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "carray.to_py":126 + * + * @cname("__Pyx_carray_to_tuple_int") + * cdef inline tuple __Pyx_carray_to_tuple_int(base_type *v, Py_ssize_t length): # <<<<<<<<<<<<<< + * cdef size_t i + * cdef object value + */ + +static CYTHON_INLINE PyObject *__Pyx_carray_to_tuple_int(int *__pyx_v_v, Py_ssize_t __pyx_v_length) { + size_t __pyx_v_i; + PyObject *__pyx_v_value = 0; + PyObject *__pyx_v_t = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + size_t __pyx_t_2; + size_t __pyx_t_3; + size_t __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_carray_to_tuple_int", 1); + + /* "carray.to_py":129 + * cdef size_t i + * cdef object value + * t = PyTuple_New(length) # <<<<<<<<<<<<<< + * for i in range(length): + * value = v[i] + */ + __pyx_t_1 = PyTuple_New(__pyx_v_length); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 129, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_t = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "carray.to_py":130 + * cdef object value + * t = PyTuple_New(length) + * for i in range(length): # <<<<<<<<<<<<<< + * value = v[i] + * Py_INCREF(value) + */ + __pyx_t_2 = ((size_t)__pyx_v_length); + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "carray.to_py":131 + * t = PyTuple_New(length) + * for i in range(length): + * value = v[i] # <<<<<<<<<<<<<< + * Py_INCREF(value) + * PyTuple_SET_ITEM(t, i, value) + */ + __pyx_t_1 = __Pyx_PyInt_From_int((__pyx_v_v[__pyx_v_i])); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 131, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_XDECREF_SET(__pyx_v_value, __pyx_t_1); + __pyx_t_1 = 0; + + /* "carray.to_py":132 + * for i in range(length): + * value = v[i] + * Py_INCREF(value) # <<<<<<<<<<<<<< + * PyTuple_SET_ITEM(t, i, value) + * return t + */ + Py_INCREF(__pyx_v_value); + + /* "carray.to_py":133 + * value = v[i] + * Py_INCREF(value) + * PyTuple_SET_ITEM(t, i, value) # <<<<<<<<<<<<<< + * return t + */ + PyTuple_SET_ITEM(__pyx_v_t, __pyx_v_i, __pyx_v_value); + } + + /* "carray.to_py":134 + * Py_INCREF(value) + * PyTuple_SET_ITEM(t, i, value) + * return t # <<<<<<<<<<<<<< + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_t); + __pyx_r = __pyx_v_t; + goto __pyx_L0; + + /* "carray.to_py":126 + * + * @cname("__Pyx_carray_to_tuple_int") + * cdef inline tuple __Pyx_carray_to_tuple_int(base_type *v, Py_ssize_t length): # <<<<<<<<<<<<<< + * cdef size_t i + * cdef object value + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("carray.to_py.__Pyx_carray_to_tuple_int", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_value); + __Pyx_XDECREF(__pyx_v_t); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":131 + * cdef bint dtype_is_object + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, # <<<<<<<<<<<<<< + * mode="c", bint allocate_buffer=True): + * + */ + +/* Python wrapper */ +static int __pyx_array___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_array___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_shape = 0; + Py_ssize_t __pyx_v_itemsize; + PyObject *__pyx_v_format = 0; + PyObject *__pyx_v_mode = 0; + int __pyx_v_allocate_buffer; + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[5] = {0,0,0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_shape,&__pyx_n_s_itemsize,&__pyx_n_s_format,&__pyx_n_s_mode,&__pyx_n_s_allocate_buffer,0}; + values[3] = __Pyx_Arg_NewRef_VARARGS(((PyObject *)__pyx_n_s_c)); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 5: values[4] = __Pyx_Arg_VARARGS(__pyx_args, 4); + CYTHON_FALLTHROUGH; + case 4: values[3] = __Pyx_Arg_VARARGS(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_shape)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_itemsize)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 3, 5, 1); __PYX_ERR(1, 131, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_format)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 3, 5, 2); __PYX_ERR(1, 131, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 3: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_mode); + if (value) { values[3] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 4: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_allocate_buffer); + if (value) { values[4] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(1, 131, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 5: values[4] = __Pyx_Arg_VARARGS(__pyx_args, 4); + CYTHON_FALLTHROUGH; + case 4: values[3] = __Pyx_Arg_VARARGS(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_shape = ((PyObject*)values[0]); + __pyx_v_itemsize = __Pyx_PyIndex_AsSsize_t(values[1]); if (unlikely((__pyx_v_itemsize == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + __pyx_v_format = values[2]; + __pyx_v_mode = values[3]; + if (values[4]) { + __pyx_v_allocate_buffer = __Pyx_PyObject_IsTrue(values[4]); if (unlikely((__pyx_v_allocate_buffer == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 132, __pyx_L3_error) + } else { + + /* "View.MemoryView":132 + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, + * mode="c", bint allocate_buffer=True): # <<<<<<<<<<<<<< + * + * cdef int idx + */ + __pyx_v_allocate_buffer = ((int)1); + } + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 3, 5, __pyx_nargs); __PYX_ERR(1, 131, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.array.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_shape), (&PyTuple_Type), 1, "shape", 1))) __PYX_ERR(1, 131, __pyx_L1_error) + if (unlikely(((PyObject *)__pyx_v_format) == Py_None)) { + PyErr_Format(PyExc_TypeError, "Argument '%.200s' must not be None", "format"); __PYX_ERR(1, 131, __pyx_L1_error) + } + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array___cinit__(((struct __pyx_array_obj *)__pyx_v_self), __pyx_v_shape, __pyx_v_itemsize, __pyx_v_format, __pyx_v_mode, __pyx_v_allocate_buffer); + + /* "View.MemoryView":131 + * cdef bint dtype_is_object + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, # <<<<<<<<<<<<<< + * mode="c", bint allocate_buffer=True): + * + */ + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = -1; + __pyx_L0:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array___cinit__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_shape, Py_ssize_t __pyx_v_itemsize, PyObject *__pyx_v_format, PyObject *__pyx_v_mode, int __pyx_v_allocate_buffer) { + int __pyx_v_idx; + Py_ssize_t __pyx_v_dim; + char __pyx_v_order; + int __pyx_r; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + int __pyx_t_7; + char *__pyx_t_8; + Py_ssize_t __pyx_t_9; + Py_UCS4 __pyx_t_10; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__cinit__", 0); + __Pyx_INCREF(__pyx_v_format); + + /* "View.MemoryView":137 + * cdef Py_ssize_t dim + * + * self.ndim = len(shape) # <<<<<<<<<<<<<< + * self.itemsize = itemsize + * + */ + if (unlikely(__pyx_v_shape == Py_None)) { + PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); + __PYX_ERR(1, 137, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_PyTuple_GET_SIZE(__pyx_v_shape); if (unlikely(__pyx_t_1 == ((Py_ssize_t)-1))) __PYX_ERR(1, 137, __pyx_L1_error) + __pyx_v_self->ndim = ((int)__pyx_t_1); + + /* "View.MemoryView":138 + * + * self.ndim = len(shape) + * self.itemsize = itemsize # <<<<<<<<<<<<<< + * + * if not self.ndim: + */ + __pyx_v_self->itemsize = __pyx_v_itemsize; + + /* "View.MemoryView":140 + * self.itemsize = itemsize + * + * if not self.ndim: # <<<<<<<<<<<<<< + * raise ValueError, "Empty shape tuple for cython.array" + * + */ + __pyx_t_2 = (!(__pyx_v_self->ndim != 0)); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":141 + * + * if not self.ndim: + * raise ValueError, "Empty shape tuple for cython.array" # <<<<<<<<<<<<<< + * + * if itemsize <= 0: + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Empty_shape_tuple_for_cython_arr, 0, 0); + __PYX_ERR(1, 141, __pyx_L1_error) + + /* "View.MemoryView":140 + * self.itemsize = itemsize + * + * if not self.ndim: # <<<<<<<<<<<<<< + * raise ValueError, "Empty shape tuple for cython.array" + * + */ + } + + /* "View.MemoryView":143 + * raise ValueError, "Empty shape tuple for cython.array" + * + * if itemsize <= 0: # <<<<<<<<<<<<<< + * raise ValueError, "itemsize <= 0 for cython.array" + * + */ + __pyx_t_2 = (__pyx_v_itemsize <= 0); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":144 + * + * if itemsize <= 0: + * raise ValueError, "itemsize <= 0 for cython.array" # <<<<<<<<<<<<<< + * + * if not isinstance(format, bytes): + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_itemsize_0_for_cython_array, 0, 0); + __PYX_ERR(1, 144, __pyx_L1_error) + + /* "View.MemoryView":143 + * raise ValueError, "Empty shape tuple for cython.array" + * + * if itemsize <= 0: # <<<<<<<<<<<<<< + * raise ValueError, "itemsize <= 0 for cython.array" + * + */ + } + + /* "View.MemoryView":146 + * raise ValueError, "itemsize <= 0 for cython.array" + * + * if not isinstance(format, bytes): # <<<<<<<<<<<<<< + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string + */ + __pyx_t_2 = PyBytes_Check(__pyx_v_format); + __pyx_t_3 = (!__pyx_t_2); + if (__pyx_t_3) { + + /* "View.MemoryView":147 + * + * if not isinstance(format, bytes): + * format = format.encode('ASCII') # <<<<<<<<<<<<<< + * self._format = format # keep a reference to the byte string + * self.format = self._format + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_format, __pyx_n_s_encode); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 147, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = NULL; + __pyx_t_7 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_6 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_6)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_6); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_7 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_6, __pyx_n_s_ASCII}; + __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_7, 1+__pyx_t_7); + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 147, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + __Pyx_DECREF_SET(__pyx_v_format, __pyx_t_4); + __pyx_t_4 = 0; + + /* "View.MemoryView":146 + * raise ValueError, "itemsize <= 0 for cython.array" + * + * if not isinstance(format, bytes): # <<<<<<<<<<<<<< + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string + */ + } + + /* "View.MemoryView":148 + * if not isinstance(format, bytes): + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string # <<<<<<<<<<<<<< + * self.format = self._format + * + */ + if (!(likely(PyBytes_CheckExact(__pyx_v_format))||((__pyx_v_format) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_v_format))) __PYX_ERR(1, 148, __pyx_L1_error) + __pyx_t_4 = __pyx_v_format; + __Pyx_INCREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + __Pyx_GOTREF(__pyx_v_self->_format); + __Pyx_DECREF(__pyx_v_self->_format); + __pyx_v_self->_format = ((PyObject*)__pyx_t_4); + __pyx_t_4 = 0; + + /* "View.MemoryView":149 + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string + * self.format = self._format # <<<<<<<<<<<<<< + * + * + */ + if (unlikely(__pyx_v_self->_format == Py_None)) { + PyErr_SetString(PyExc_TypeError, "expected bytes, NoneType found"); + __PYX_ERR(1, 149, __pyx_L1_error) + } + __pyx_t_8 = __Pyx_PyBytes_AsWritableString(__pyx_v_self->_format); if (unlikely((!__pyx_t_8) && PyErr_Occurred())) __PYX_ERR(1, 149, __pyx_L1_error) + __pyx_v_self->format = __pyx_t_8; + + /* "View.MemoryView":152 + * + * + * self._shape = PyObject_Malloc(sizeof(Py_ssize_t)*self.ndim*2) # <<<<<<<<<<<<<< + * self._strides = self._shape + self.ndim + * + */ + __pyx_v_self->_shape = ((Py_ssize_t *)PyObject_Malloc((((sizeof(Py_ssize_t)) * __pyx_v_self->ndim) * 2))); + + /* "View.MemoryView":153 + * + * self._shape = PyObject_Malloc(sizeof(Py_ssize_t)*self.ndim*2) + * self._strides = self._shape + self.ndim # <<<<<<<<<<<<<< + * + * if not self._shape: + */ + __pyx_v_self->_strides = (__pyx_v_self->_shape + __pyx_v_self->ndim); + + /* "View.MemoryView":155 + * self._strides = self._shape + self.ndim + * + * if not self._shape: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate shape and strides." + * + */ + __pyx_t_3 = (!(__pyx_v_self->_shape != 0)); + if (unlikely(__pyx_t_3)) { + + /* "View.MemoryView":156 + * + * if not self._shape: + * raise MemoryError, "unable to allocate shape and strides." # <<<<<<<<<<<<<< + * + * + */ + __Pyx_Raise(__pyx_builtin_MemoryError, __pyx_kp_s_unable_to_allocate_shape_and_str, 0, 0); + __PYX_ERR(1, 156, __pyx_L1_error) + + /* "View.MemoryView":155 + * self._strides = self._shape + self.ndim + * + * if not self._shape: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate shape and strides." + * + */ + } + + /* "View.MemoryView":159 + * + * + * for idx, dim in enumerate(shape): # <<<<<<<<<<<<<< + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + */ + __pyx_t_7 = 0; + __pyx_t_4 = __pyx_v_shape; __Pyx_INCREF(__pyx_t_4); + __pyx_t_1 = 0; + for (;;) { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_4); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 159, __pyx_L1_error) + #endif + if (__pyx_t_1 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_5 = PyTuple_GET_ITEM(__pyx_t_4, __pyx_t_1); __Pyx_INCREF(__pyx_t_5); __pyx_t_1++; if (unlikely((0 < 0))) __PYX_ERR(1, 159, __pyx_L1_error) + #else + __pyx_t_5 = __Pyx_PySequence_ITEM(__pyx_t_4, __pyx_t_1); __pyx_t_1++; if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 159, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + #endif + __pyx_t_9 = __Pyx_PyIndex_AsSsize_t(__pyx_t_5); if (unlikely((__pyx_t_9 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 159, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_v_dim = __pyx_t_9; + __pyx_v_idx = __pyx_t_7; + __pyx_t_7 = (__pyx_t_7 + 1); + + /* "View.MemoryView":160 + * + * for idx, dim in enumerate(shape): + * if dim <= 0: # <<<<<<<<<<<<<< + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + * self._shape[idx] = dim + */ + __pyx_t_3 = (__pyx_v_dim <= 0); + if (unlikely(__pyx_t_3)) { + + /* "View.MemoryView":161 + * for idx, dim in enumerate(shape): + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." # <<<<<<<<<<<<<< + * self._shape[idx] = dim + * + */ + __pyx_t_5 = PyTuple_New(5); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_9 = 0; + __pyx_t_10 = 127; + __Pyx_INCREF(__pyx_kp_u_Invalid_shape_in_axis); + __pyx_t_9 += 22; + __Pyx_GIVEREF(__pyx_kp_u_Invalid_shape_in_axis); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_kp_u_Invalid_shape_in_axis); + __pyx_t_6 = __Pyx_PyUnicode_From_int(__pyx_v_idx, 0, ' ', 'd'); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_9 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_6); + __Pyx_GIVEREF(__pyx_t_6); + PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_6); + __pyx_t_6 = 0; + __Pyx_INCREF(__pyx_kp_u_); + __pyx_t_9 += 2; + __Pyx_GIVEREF(__pyx_kp_u_); + PyTuple_SET_ITEM(__pyx_t_5, 2, __pyx_kp_u_); + __pyx_t_6 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_dim, 0, ' ', 'd'); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_9 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_6); + __Pyx_GIVEREF(__pyx_t_6); + PyTuple_SET_ITEM(__pyx_t_5, 3, __pyx_t_6); + __pyx_t_6 = 0; + __Pyx_INCREF(__pyx_kp_u__2); + __pyx_t_9 += 1; + __Pyx_GIVEREF(__pyx_kp_u__2); + PyTuple_SET_ITEM(__pyx_t_5, 4, __pyx_kp_u__2); + __pyx_t_6 = __Pyx_PyUnicode_Join(__pyx_t_5, 5, __pyx_t_9, __pyx_t_10); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_t_6, 0, 0); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __PYX_ERR(1, 161, __pyx_L1_error) + + /* "View.MemoryView":160 + * + * for idx, dim in enumerate(shape): + * if dim <= 0: # <<<<<<<<<<<<<< + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + * self._shape[idx] = dim + */ + } + + /* "View.MemoryView":162 + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + * self._shape[idx] = dim # <<<<<<<<<<<<<< + * + * cdef char order + */ + (__pyx_v_self->_shape[__pyx_v_idx]) = __pyx_v_dim; + + /* "View.MemoryView":159 + * + * + * for idx, dim in enumerate(shape): # <<<<<<<<<<<<<< + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + */ + } + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "View.MemoryView":165 + * + * cdef char order + * if mode == 'c': # <<<<<<<<<<<<<< + * order = b'C' + * self.mode = u'c' + */ + __pyx_t_3 = (__Pyx_PyString_Equals(__pyx_v_mode, __pyx_n_s_c, Py_EQ)); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(1, 165, __pyx_L1_error) + if (__pyx_t_3) { + + /* "View.MemoryView":166 + * cdef char order + * if mode == 'c': + * order = b'C' # <<<<<<<<<<<<<< + * self.mode = u'c' + * elif mode == 'fortran': + */ + __pyx_v_order = 'C'; + + /* "View.MemoryView":167 + * if mode == 'c': + * order = b'C' + * self.mode = u'c' # <<<<<<<<<<<<<< + * elif mode == 'fortran': + * order = b'F' + */ + __Pyx_INCREF(__pyx_n_u_c); + __Pyx_GIVEREF(__pyx_n_u_c); + __Pyx_GOTREF(__pyx_v_self->mode); + __Pyx_DECREF(__pyx_v_self->mode); + __pyx_v_self->mode = __pyx_n_u_c; + + /* "View.MemoryView":165 + * + * cdef char order + * if mode == 'c': # <<<<<<<<<<<<<< + * order = b'C' + * self.mode = u'c' + */ + goto __pyx_L11; + } + + /* "View.MemoryView":168 + * order = b'C' + * self.mode = u'c' + * elif mode == 'fortran': # <<<<<<<<<<<<<< + * order = b'F' + * self.mode = u'fortran' + */ + __pyx_t_3 = (__Pyx_PyString_Equals(__pyx_v_mode, __pyx_n_s_fortran, Py_EQ)); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(1, 168, __pyx_L1_error) + if (likely(__pyx_t_3)) { + + /* "View.MemoryView":169 + * self.mode = u'c' + * elif mode == 'fortran': + * order = b'F' # <<<<<<<<<<<<<< + * self.mode = u'fortran' + * else: + */ + __pyx_v_order = 'F'; + + /* "View.MemoryView":170 + * elif mode == 'fortran': + * order = b'F' + * self.mode = u'fortran' # <<<<<<<<<<<<<< + * else: + * raise ValueError, f"Invalid mode, expected 'c' or 'fortran', got {mode}" + */ + __Pyx_INCREF(__pyx_n_u_fortran); + __Pyx_GIVEREF(__pyx_n_u_fortran); + __Pyx_GOTREF(__pyx_v_self->mode); + __Pyx_DECREF(__pyx_v_self->mode); + __pyx_v_self->mode = __pyx_n_u_fortran; + + /* "View.MemoryView":168 + * order = b'C' + * self.mode = u'c' + * elif mode == 'fortran': # <<<<<<<<<<<<<< + * order = b'F' + * self.mode = u'fortran' + */ + goto __pyx_L11; + } + + /* "View.MemoryView":172 + * self.mode = u'fortran' + * else: + * raise ValueError, f"Invalid mode, expected 'c' or 'fortran', got {mode}" # <<<<<<<<<<<<<< + * + * self.len = fill_contig_strides_array(self._shape, self._strides, itemsize, self.ndim, order) + */ + /*else*/ { + __pyx_t_4 = __Pyx_PyObject_FormatSimple(__pyx_v_mode, __pyx_empty_unicode); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 172, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_6 = __Pyx_PyUnicode_Concat(__pyx_kp_u_Invalid_mode_expected_c_or_fortr, __pyx_t_4); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 172, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_t_6, 0, 0); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __PYX_ERR(1, 172, __pyx_L1_error) + } + __pyx_L11:; + + /* "View.MemoryView":174 + * raise ValueError, f"Invalid mode, expected 'c' or 'fortran', got {mode}" + * + * self.len = fill_contig_strides_array(self._shape, self._strides, itemsize, self.ndim, order) # <<<<<<<<<<<<<< + * + * self.free_data = allocate_buffer + */ + __pyx_v_self->len = __pyx_fill_contig_strides_array(__pyx_v_self->_shape, __pyx_v_self->_strides, __pyx_v_itemsize, __pyx_v_self->ndim, __pyx_v_order); + + /* "View.MemoryView":176 + * self.len = fill_contig_strides_array(self._shape, self._strides, itemsize, self.ndim, order) + * + * self.free_data = allocate_buffer # <<<<<<<<<<<<<< + * self.dtype_is_object = format == b'O' + * + */ + __pyx_v_self->free_data = __pyx_v_allocate_buffer; + + /* "View.MemoryView":177 + * + * self.free_data = allocate_buffer + * self.dtype_is_object = format == b'O' # <<<<<<<<<<<<<< + * + * if allocate_buffer: + */ + __pyx_t_6 = PyObject_RichCompare(__pyx_v_format, __pyx_n_b_O, Py_EQ); __Pyx_XGOTREF(__pyx_t_6); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 177, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_IsTrue(__pyx_t_6); if (unlikely((__pyx_t_3 == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 177, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __pyx_v_self->dtype_is_object = __pyx_t_3; + + /* "View.MemoryView":179 + * self.dtype_is_object = format == b'O' + * + * if allocate_buffer: # <<<<<<<<<<<<<< + * _allocate_buffer(self) + * + */ + if (__pyx_v_allocate_buffer) { + + /* "View.MemoryView":180 + * + * if allocate_buffer: + * _allocate_buffer(self) # <<<<<<<<<<<<<< + * + * @cname('getbuffer') + */ + __pyx_t_7 = __pyx_array_allocate_buffer(__pyx_v_self); if (unlikely(__pyx_t_7 == ((int)-1))) __PYX_ERR(1, 180, __pyx_L1_error) + + /* "View.MemoryView":179 + * self.dtype_is_object = format == b'O' + * + * if allocate_buffer: # <<<<<<<<<<<<<< + * _allocate_buffer(self) + * + */ + } + + /* "View.MemoryView":131 + * cdef bint dtype_is_object + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, # <<<<<<<<<<<<<< + * mode="c", bint allocate_buffer=True): + * + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("View.MemoryView.array.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_format); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":182 + * _allocate_buffer(self) + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + */ + +/* Python wrapper */ +CYTHON_UNUSED static int __pyx_array_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +CYTHON_UNUSED static int __pyx_array_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getbuffer__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_2__getbuffer__(((struct __pyx_array_obj *)__pyx_v_self), ((Py_buffer *)__pyx_v_info), ((int)__pyx_v_flags)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_2__getbuffer__(struct __pyx_array_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + int __pyx_v_bufmode; + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + char *__pyx_t_2; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + Py_ssize_t *__pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + if (unlikely(__pyx_v_info == NULL)) { + PyErr_SetString(PyExc_BufferError, "PyObject_GetBuffer: view==NULL argument is obsolete"); + return -1; + } + __Pyx_RefNannySetupContext("__getbuffer__", 0); + __pyx_v_info->obj = Py_None; __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(__pyx_v_info->obj); + + /* "View.MemoryView":184 + * @cname('getbuffer') + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 # <<<<<<<<<<<<<< + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": + */ + __pyx_v_bufmode = -1; + + /* "View.MemoryView":185 + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): # <<<<<<<<<<<<<< + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + */ + __pyx_t_1 = ((__pyx_v_flags & ((PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS) | PyBUF_ANY_CONTIGUOUS)) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":186 + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": # <<<<<<<<<<<<<< + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": + */ + __pyx_t_1 = (__Pyx_PyUnicode_Equals(__pyx_v_self->mode, __pyx_n_u_c, Py_EQ)); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 186, __pyx_L1_error) + if (__pyx_t_1) { + + /* "View.MemoryView":187 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS # <<<<<<<<<<<<<< + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + */ + __pyx_v_bufmode = (PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS); + + /* "View.MemoryView":186 + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": # <<<<<<<<<<<<<< + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": + */ + goto __pyx_L4; + } + + /* "View.MemoryView":188 + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": # <<<<<<<<<<<<<< + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): + */ + __pyx_t_1 = (__Pyx_PyUnicode_Equals(__pyx_v_self->mode, __pyx_n_u_fortran, Py_EQ)); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 188, __pyx_L1_error) + if (__pyx_t_1) { + + /* "View.MemoryView":189 + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS # <<<<<<<<<<<<<< + * if not (flags & bufmode): + * raise ValueError, "Can only create a buffer that is contiguous in memory." + */ + __pyx_v_bufmode = (PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS); + + /* "View.MemoryView":188 + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": # <<<<<<<<<<<<<< + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): + */ + } + __pyx_L4:; + + /* "View.MemoryView":190 + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): # <<<<<<<<<<<<<< + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data + */ + __pyx_t_1 = (!((__pyx_v_flags & __pyx_v_bufmode) != 0)); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":191 + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): + * raise ValueError, "Can only create a buffer that is contiguous in memory." # <<<<<<<<<<<<<< + * info.buf = self.data + * info.len = self.len + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Can_only_create_a_buffer_that_is, 0, 0); + __PYX_ERR(1, 191, __pyx_L1_error) + + /* "View.MemoryView":190 + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): # <<<<<<<<<<<<<< + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data + */ + } + + /* "View.MemoryView":185 + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): # <<<<<<<<<<<<<< + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + */ + } + + /* "View.MemoryView":192 + * if not (flags & bufmode): + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data # <<<<<<<<<<<<<< + * info.len = self.len + * + */ + __pyx_t_2 = __pyx_v_self->data; + __pyx_v_info->buf = __pyx_t_2; + + /* "View.MemoryView":193 + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data + * info.len = self.len # <<<<<<<<<<<<<< + * + * if flags & PyBUF_STRIDES: + */ + __pyx_t_3 = __pyx_v_self->len; + __pyx_v_info->len = __pyx_t_3; + + /* "View.MemoryView":195 + * info.len = self.len + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.ndim = self.ndim + * info.shape = self._shape + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_STRIDES) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":196 + * + * if flags & PyBUF_STRIDES: + * info.ndim = self.ndim # <<<<<<<<<<<<<< + * info.shape = self._shape + * info.strides = self._strides + */ + __pyx_t_4 = __pyx_v_self->ndim; + __pyx_v_info->ndim = __pyx_t_4; + + /* "View.MemoryView":197 + * if flags & PyBUF_STRIDES: + * info.ndim = self.ndim + * info.shape = self._shape # <<<<<<<<<<<<<< + * info.strides = self._strides + * else: + */ + __pyx_t_5 = __pyx_v_self->_shape; + __pyx_v_info->shape = __pyx_t_5; + + /* "View.MemoryView":198 + * info.ndim = self.ndim + * info.shape = self._shape + * info.strides = self._strides # <<<<<<<<<<<<<< + * else: + * info.ndim = 1 + */ + __pyx_t_5 = __pyx_v_self->_strides; + __pyx_v_info->strides = __pyx_t_5; + + /* "View.MemoryView":195 + * info.len = self.len + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.ndim = self.ndim + * info.shape = self._shape + */ + goto __pyx_L6; + } + + /* "View.MemoryView":200 + * info.strides = self._strides + * else: + * info.ndim = 1 # <<<<<<<<<<<<<< + * info.shape = &self.len if flags & PyBUF_ND else NULL + * info.strides = NULL + */ + /*else*/ { + __pyx_v_info->ndim = 1; + + /* "View.MemoryView":201 + * else: + * info.ndim = 1 + * info.shape = &self.len if flags & PyBUF_ND else NULL # <<<<<<<<<<<<<< + * info.strides = NULL + * + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_ND) != 0); + if (__pyx_t_1) { + __pyx_t_5 = (&__pyx_v_self->len); + } else { + __pyx_t_5 = NULL; + } + __pyx_v_info->shape = __pyx_t_5; + + /* "View.MemoryView":202 + * info.ndim = 1 + * info.shape = &self.len if flags & PyBUF_ND else NULL + * info.strides = NULL # <<<<<<<<<<<<<< + * + * info.suboffsets = NULL + */ + __pyx_v_info->strides = NULL; + } + __pyx_L6:; + + /* "View.MemoryView":204 + * info.strides = NULL + * + * info.suboffsets = NULL # <<<<<<<<<<<<<< + * info.itemsize = self.itemsize + * info.readonly = 0 + */ + __pyx_v_info->suboffsets = NULL; + + /* "View.MemoryView":205 + * + * info.suboffsets = NULL + * info.itemsize = self.itemsize # <<<<<<<<<<<<<< + * info.readonly = 0 + * info.format = self.format if flags & PyBUF_FORMAT else NULL + */ + __pyx_t_3 = __pyx_v_self->itemsize; + __pyx_v_info->itemsize = __pyx_t_3; + + /* "View.MemoryView":206 + * info.suboffsets = NULL + * info.itemsize = self.itemsize + * info.readonly = 0 # <<<<<<<<<<<<<< + * info.format = self.format if flags & PyBUF_FORMAT else NULL + * info.obj = self + */ + __pyx_v_info->readonly = 0; + + /* "View.MemoryView":207 + * info.itemsize = self.itemsize + * info.readonly = 0 + * info.format = self.format if flags & PyBUF_FORMAT else NULL # <<<<<<<<<<<<<< + * info.obj = self + * + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_FORMAT) != 0); + if (__pyx_t_1) { + __pyx_t_2 = __pyx_v_self->format; + } else { + __pyx_t_2 = NULL; + } + __pyx_v_info->format = __pyx_t_2; + + /* "View.MemoryView":208 + * info.readonly = 0 + * info.format = self.format if flags & PyBUF_FORMAT else NULL + * info.obj = self # <<<<<<<<<<<<<< + * + * def __dealloc__(array self): + */ + __Pyx_INCREF((PyObject *)__pyx_v_self); + __Pyx_GIVEREF((PyObject *)__pyx_v_self); + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); + __pyx_v_info->obj = ((PyObject *)__pyx_v_self); + + /* "View.MemoryView":182 + * _allocate_buffer(self) + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.array.__getbuffer__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + if (__pyx_v_info->obj != NULL) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + goto __pyx_L2; + __pyx_L0:; + if (__pyx_v_info->obj == Py_None) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + __pyx_L2:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":210 + * info.obj = self + * + * def __dealloc__(array self): # <<<<<<<<<<<<<< + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + */ + +/* Python wrapper */ +static void __pyx_array___dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_array___dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_array___pyx_pf_15View_dot_MemoryView_5array_4__dealloc__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_array___pyx_pf_15View_dot_MemoryView_5array_4__dealloc__(struct __pyx_array_obj *__pyx_v_self) { + int __pyx_t_1; + int __pyx_t_2; + + /* "View.MemoryView":211 + * + * def __dealloc__(array self): + * if self.callback_free_data != NULL: # <<<<<<<<<<<<<< + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + */ + __pyx_t_1 = (__pyx_v_self->callback_free_data != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":212 + * def __dealloc__(array self): + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) # <<<<<<<<<<<<<< + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: + */ + __pyx_v_self->callback_free_data(__pyx_v_self->data); + + /* "View.MemoryView":211 + * + * def __dealloc__(array self): + * if self.callback_free_data != NULL: # <<<<<<<<<<<<<< + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":213 + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: # <<<<<<<<<<<<<< + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + */ + if (__pyx_v_self->free_data) { + } else { + __pyx_t_1 = __pyx_v_self->free_data; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_2 = (__pyx_v_self->data != NULL); + __pyx_t_1 = __pyx_t_2; + __pyx_L4_bool_binop_done:; + if (__pyx_t_1) { + + /* "View.MemoryView":214 + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) + */ + if (__pyx_v_self->dtype_is_object) { + + /* "View.MemoryView":215 + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) # <<<<<<<<<<<<<< + * free(self.data) + * PyObject_Free(self._shape) + */ + __pyx_memoryview_refcount_objects_in_slice(__pyx_v_self->data, __pyx_v_self->_shape, __pyx_v_self->_strides, __pyx_v_self->ndim, 0); + + /* "View.MemoryView":214 + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) + */ + } + + /* "View.MemoryView":216 + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) # <<<<<<<<<<<<<< + * PyObject_Free(self._shape) + * + */ + free(__pyx_v_self->data); + + /* "View.MemoryView":213 + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: # <<<<<<<<<<<<<< + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + */ + } + __pyx_L3:; + + /* "View.MemoryView":217 + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) + * PyObject_Free(self._shape) # <<<<<<<<<<<<<< + * + * @property + */ + PyObject_Free(__pyx_v_self->_shape); + + /* "View.MemoryView":210 + * info.obj = self + * + * def __dealloc__(array self): # <<<<<<<<<<<<<< + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + */ + + /* function exit code */ +} + +/* "View.MemoryView":219 + * PyObject_Free(self._shape) + * + * @property # <<<<<<<<<<<<<< + * def memview(self): + * return self.get_memview() + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_5array_7memview_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_5array_7memview_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_5array_7memview___get__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_5array_7memview___get__(struct __pyx_array_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":221 + * @property + * def memview(self): + * return self.get_memview() # <<<<<<<<<<<<<< + * + * @cname('get_memview') + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = ((struct __pyx_vtabstruct_array *)__pyx_v_self->__pyx_vtab)->get_memview(__pyx_v_self); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 221, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":219 + * PyObject_Free(self._shape) + * + * @property # <<<<<<<<<<<<<< + * def memview(self): + * return self.get_memview() + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.array.memview.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":224 + * + * @cname('get_memview') + * cdef get_memview(self): # <<<<<<<<<<<<<< + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE + * return memoryview(self, flags, self.dtype_is_object) + */ + +static PyObject *__pyx_array_get_memview(struct __pyx_array_obj *__pyx_v_self) { + int __pyx_v_flags; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_memview", 1); + + /* "View.MemoryView":225 + * @cname('get_memview') + * cdef get_memview(self): + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE # <<<<<<<<<<<<<< + * return memoryview(self, flags, self.dtype_is_object) + * + */ + __pyx_v_flags = ((PyBUF_ANY_CONTIGUOUS | PyBUF_FORMAT) | PyBUF_WRITABLE); + + /* "View.MemoryView":226 + * cdef get_memview(self): + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE + * return memoryview(self, flags, self.dtype_is_object) # <<<<<<<<<<<<<< + * + * def __len__(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_flags); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_v_self->dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF((PyObject *)__pyx_v_self); + __Pyx_GIVEREF((PyObject *)__pyx_v_self); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, ((PyObject *)__pyx_v_self))) __PYX_ERR(1, 226, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1)) __PYX_ERR(1, 226, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_t_2)) __PYX_ERR(1, 226, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_Call(((PyObject *)__pyx_memoryview_type), __pyx_t_3, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":224 + * + * @cname('get_memview') + * cdef get_memview(self): # <<<<<<<<<<<<<< + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE + * return memoryview(self, flags, self.dtype_is_object) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.array.get_memview", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":228 + * return memoryview(self, flags, self.dtype_is_object) + * + * def __len__(self): # <<<<<<<<<<<<<< + * return self._shape[0] + * + */ + +/* Python wrapper */ +static Py_ssize_t __pyx_array___len__(PyObject *__pyx_v_self); /*proto*/ +static Py_ssize_t __pyx_array___len__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + Py_ssize_t __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__len__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_6__len__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static Py_ssize_t __pyx_array___pyx_pf_15View_dot_MemoryView_5array_6__len__(struct __pyx_array_obj *__pyx_v_self) { + Py_ssize_t __pyx_r; + + /* "View.MemoryView":229 + * + * def __len__(self): + * return self._shape[0] # <<<<<<<<<<<<<< + * + * def __getattr__(self, attr): + */ + __pyx_r = (__pyx_v_self->_shape[0]); + goto __pyx_L0; + + /* "View.MemoryView":228 + * return memoryview(self, flags, self.dtype_is_object) + * + * def __len__(self): # <<<<<<<<<<<<<< + * return self._shape[0] + * + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":231 + * return self._shape[0] + * + * def __getattr__(self, attr): # <<<<<<<<<<<<<< + * return getattr(self.memview, attr) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_array___getattr__(PyObject *__pyx_v_self, PyObject *__pyx_v_attr); /*proto*/ +static PyObject *__pyx_array___getattr__(PyObject *__pyx_v_self, PyObject *__pyx_v_attr) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getattr__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_8__getattr__(((struct __pyx_array_obj *)__pyx_v_self), ((PyObject *)__pyx_v_attr)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_8__getattr__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_attr) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__getattr__", 1); + + /* "View.MemoryView":232 + * + * def __getattr__(self, attr): + * return getattr(self.memview, attr) # <<<<<<<<<<<<<< + * + * def __getitem__(self, item): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_memview); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 232, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_GetAttr(__pyx_t_1, __pyx_v_attr); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 232, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":231 + * return self._shape[0] + * + * def __getattr__(self, attr): # <<<<<<<<<<<<<< + * return getattr(self.memview, attr) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.array.__getattr__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":234 + * return getattr(self.memview, attr) + * + * def __getitem__(self, item): # <<<<<<<<<<<<<< + * return self.memview[item] + * + */ + +/* Python wrapper */ +static PyObject *__pyx_array___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item); /*proto*/ +static PyObject *__pyx_array___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getitem__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_10__getitem__(((struct __pyx_array_obj *)__pyx_v_self), ((PyObject *)__pyx_v_item)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_10__getitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__getitem__", 1); + + /* "View.MemoryView":235 + * + * def __getitem__(self, item): + * return self.memview[item] # <<<<<<<<<<<<<< + * + * def __setitem__(self, item, value): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_memview); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 235, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_t_1, __pyx_v_item); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 235, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":234 + * return getattr(self.memview, attr) + * + * def __getitem__(self, item): # <<<<<<<<<<<<<< + * return self.memview[item] + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.array.__getitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":237 + * return self.memview[item] + * + * def __setitem__(self, item, value): # <<<<<<<<<<<<<< + * self.memview[item] = value + * + */ + +/* Python wrapper */ +static int __pyx_array___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value); /*proto*/ +static int __pyx_array___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setitem__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_12__setitem__(((struct __pyx_array_obj *)__pyx_v_self), ((PyObject *)__pyx_v_item), ((PyObject *)__pyx_v_value)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_12__setitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setitem__", 1); + + /* "View.MemoryView":238 + * + * def __setitem__(self, item, value): + * self.memview[item] = value # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_memview); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 238, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyObject_SetItem(__pyx_t_1, __pyx_v_item, __pyx_v_value) < 0))) __PYX_ERR(1, 238, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "View.MemoryView":237 + * return self.memview[item] + * + * def __setitem__(self, item, value): # <<<<<<<<<<<<<< + * self.memview[item] = value + * + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.array.__setitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_array_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_array_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_array___reduce_cython__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_array___reduce_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.array.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_array_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_array_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.array.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_array_2__setstate_cython__(((struct __pyx_array_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_array_2__setstate_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.array.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":248 + * + * @cname("__pyx_array_allocate_buffer") + * cdef int _allocate_buffer(array self) except -1: # <<<<<<<<<<<<<< + * + * + */ + +static int __pyx_array_allocate_buffer(struct __pyx_array_obj *__pyx_v_self) { + Py_ssize_t __pyx_v_i; + PyObject **__pyx_v_p; + int __pyx_r; + int __pyx_t_1; + Py_ssize_t __pyx_t_2; + Py_ssize_t __pyx_t_3; + Py_ssize_t __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + + /* "View.MemoryView":254 + * cdef PyObject **p + * + * self.free_data = True # <<<<<<<<<<<<<< + * self.data = malloc(self.len) + * if not self.data: + */ + __pyx_v_self->free_data = 1; + + /* "View.MemoryView":255 + * + * self.free_data = True + * self.data = malloc(self.len) # <<<<<<<<<<<<<< + * if not self.data: + * raise MemoryError, "unable to allocate array data." + */ + __pyx_v_self->data = ((char *)malloc(__pyx_v_self->len)); + + /* "View.MemoryView":256 + * self.free_data = True + * self.data = malloc(self.len) + * if not self.data: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate array data." + * + */ + __pyx_t_1 = (!(__pyx_v_self->data != 0)); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":257 + * self.data = malloc(self.len) + * if not self.data: + * raise MemoryError, "unable to allocate array data." # <<<<<<<<<<<<<< + * + * if self.dtype_is_object: + */ + __Pyx_Raise(__pyx_builtin_MemoryError, __pyx_kp_s_unable_to_allocate_array_data, 0, 0); + __PYX_ERR(1, 257, __pyx_L1_error) + + /* "View.MemoryView":256 + * self.free_data = True + * self.data = malloc(self.len) + * if not self.data: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate array data." + * + */ + } + + /* "View.MemoryView":259 + * raise MemoryError, "unable to allocate array data." + * + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * p = self.data + * for i in range(self.len // self.itemsize): + */ + if (__pyx_v_self->dtype_is_object) { + + /* "View.MemoryView":260 + * + * if self.dtype_is_object: + * p = self.data # <<<<<<<<<<<<<< + * for i in range(self.len // self.itemsize): + * p[i] = Py_None + */ + __pyx_v_p = ((PyObject **)__pyx_v_self->data); + + /* "View.MemoryView":261 + * if self.dtype_is_object: + * p = self.data + * for i in range(self.len // self.itemsize): # <<<<<<<<<<<<<< + * p[i] = Py_None + * Py_INCREF(Py_None) + */ + if (unlikely(__pyx_v_self->itemsize == 0)) { + PyErr_SetString(PyExc_ZeroDivisionError, "integer division or modulo by zero"); + __PYX_ERR(1, 261, __pyx_L1_error) + } + else if (sizeof(Py_ssize_t) == sizeof(long) && (!(((Py_ssize_t)-1) > 0)) && unlikely(__pyx_v_self->itemsize == (Py_ssize_t)-1) && unlikely(__Pyx_UNARY_NEG_WOULD_OVERFLOW(__pyx_v_self->len))) { + PyErr_SetString(PyExc_OverflowError, "value too large to perform division"); + __PYX_ERR(1, 261, __pyx_L1_error) + } + __pyx_t_2 = __Pyx_div_Py_ssize_t(__pyx_v_self->len, __pyx_v_self->itemsize); + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":262 + * p = self.data + * for i in range(self.len // self.itemsize): + * p[i] = Py_None # <<<<<<<<<<<<<< + * Py_INCREF(Py_None) + * return 0 + */ + (__pyx_v_p[__pyx_v_i]) = Py_None; + + /* "View.MemoryView":263 + * for i in range(self.len // self.itemsize): + * p[i] = Py_None + * Py_INCREF(Py_None) # <<<<<<<<<<<<<< + * return 0 + * + */ + Py_INCREF(Py_None); + } + + /* "View.MemoryView":259 + * raise MemoryError, "unable to allocate array data." + * + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * p = self.data + * for i in range(self.len // self.itemsize): + */ + } + + /* "View.MemoryView":264 + * p[i] = Py_None + * Py_INCREF(Py_None) + * return 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":248 + * + * @cname("__pyx_array_allocate_buffer") + * cdef int _allocate_buffer(array self) except -1: # <<<<<<<<<<<<<< + * + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._allocate_buffer", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":268 + * + * @cname("__pyx_array_new") + * cdef array array_cwrapper(tuple shape, Py_ssize_t itemsize, char *format, char *c_mode, char *buf): # <<<<<<<<<<<<<< + * cdef array result + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + */ + +static struct __pyx_array_obj *__pyx_array_new(PyObject *__pyx_v_shape, Py_ssize_t __pyx_v_itemsize, char *__pyx_v_format, char *__pyx_v_c_mode, char *__pyx_v_buf) { + struct __pyx_array_obj *__pyx_v_result = 0; + PyObject *__pyx_v_mode = 0; + struct __pyx_array_obj *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("array_cwrapper", 1); + + /* "View.MemoryView":270 + * cdef array array_cwrapper(tuple shape, Py_ssize_t itemsize, char *format, char *c_mode, char *buf): + * cdef array result + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. # <<<<<<<<<<<<<< + * + * if buf is NULL: + */ + __pyx_t_2 = ((__pyx_v_c_mode[0]) == 'f'); + if (__pyx_t_2) { + __Pyx_INCREF(__pyx_n_s_fortran); + __pyx_t_1 = __pyx_n_s_fortran; + } else { + __Pyx_INCREF(__pyx_n_s_c); + __pyx_t_1 = __pyx_n_s_c; + } + __pyx_v_mode = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":272 + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + * + * if buf is NULL: # <<<<<<<<<<<<<< + * result = array.__new__(array, shape, itemsize, format, mode) + * else: + */ + __pyx_t_2 = (__pyx_v_buf == NULL); + if (__pyx_t_2) { + + /* "View.MemoryView":273 + * + * if buf is NULL: + * result = array.__new__(array, shape, itemsize, format, mode) # <<<<<<<<<<<<<< + * else: + * result = array.__new__(array, shape, itemsize, format, mode, allocate_buffer=False) + */ + __pyx_t_1 = PyInt_FromSsize_t(__pyx_v_itemsize); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 273, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyBytes_FromString(__pyx_v_format); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 273, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PyTuple_New(4); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 273, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_INCREF(__pyx_v_shape); + __Pyx_GIVEREF(__pyx_v_shape); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_v_shape)) __PYX_ERR(1, 273, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_t_1)) __PYX_ERR(1, 273, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 2, __pyx_t_3)) __PYX_ERR(1, 273, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_mode); + __Pyx_GIVEREF(__pyx_v_mode); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 3, __pyx_v_mode)) __PYX_ERR(1, 273, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_3 = 0; + __pyx_t_3 = ((PyObject *)__pyx_tp_new_array(((PyTypeObject *)__pyx_array_type), __pyx_t_4, NULL)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 273, __pyx_L1_error) + __Pyx_GOTREF((PyObject *)__pyx_t_3); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_v_result = ((struct __pyx_array_obj *)__pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":272 + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + * + * if buf is NULL: # <<<<<<<<<<<<<< + * result = array.__new__(array, shape, itemsize, format, mode) + * else: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":275 + * result = array.__new__(array, shape, itemsize, format, mode) + * else: + * result = array.__new__(array, shape, itemsize, format, mode, allocate_buffer=False) # <<<<<<<<<<<<<< + * result.data = buf + * + */ + /*else*/ { + __pyx_t_3 = PyInt_FromSsize_t(__pyx_v_itemsize); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = __Pyx_PyBytes_FromString(__pyx_v_format); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_1 = PyTuple_New(4); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v_shape); + __Pyx_GIVEREF(__pyx_v_shape); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v_shape)) __PYX_ERR(1, 275, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_t_3)) __PYX_ERR(1, 275, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_4); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_t_4)) __PYX_ERR(1, 275, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_mode); + __Pyx_GIVEREF(__pyx_v_mode); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 3, __pyx_v_mode)) __PYX_ERR(1, 275, __pyx_L1_error); + __pyx_t_3 = 0; + __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem(__pyx_t_4, __pyx_n_s_allocate_buffer, Py_False) < 0) __PYX_ERR(1, 275, __pyx_L1_error) + __pyx_t_3 = ((PyObject *)__pyx_tp_new_array(((PyTypeObject *)__pyx_array_type), __pyx_t_1, __pyx_t_4)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 275, __pyx_L1_error) + __Pyx_GOTREF((PyObject *)__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_v_result = ((struct __pyx_array_obj *)__pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":276 + * else: + * result = array.__new__(array, shape, itemsize, format, mode, allocate_buffer=False) + * result.data = buf # <<<<<<<<<<<<<< + * + * return result + */ + __pyx_v_result->data = __pyx_v_buf; + } + __pyx_L3:; + + /* "View.MemoryView":278 + * result.data = buf + * + * return result # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF((PyObject *)__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = __pyx_v_result; + goto __pyx_L0; + + /* "View.MemoryView":268 + * + * @cname("__pyx_array_new") + * cdef array array_cwrapper(tuple shape, Py_ssize_t itemsize, char *format, char *c_mode, char *buf): # <<<<<<<<<<<<<< + * cdef array result + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.array_cwrapper", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XDECREF(__pyx_v_mode); + __Pyx_XGIVEREF((PyObject *)__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":304 + * cdef class Enum(object): + * cdef object name + * def __init__(self, name): # <<<<<<<<<<<<<< + * self.name = name + * def __repr__(self): + */ + +/* Python wrapper */ +static int __pyx_MemviewEnum___init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_MemviewEnum___init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_name = 0; + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__init__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_name,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_name)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 304, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__init__") < 0)) __PYX_ERR(1, 304, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + } + __pyx_v_name = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__init__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 304, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.Enum.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum___init__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self), __pyx_v_name); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum___init__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v_name) { + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__init__", 1); + + /* "View.MemoryView":305 + * cdef object name + * def __init__(self, name): + * self.name = name # <<<<<<<<<<<<<< + * def __repr__(self): + * return self.name + */ + __Pyx_INCREF(__pyx_v_name); + __Pyx_GIVEREF(__pyx_v_name); + __Pyx_GOTREF(__pyx_v_self->name); + __Pyx_DECREF(__pyx_v_self->name); + __pyx_v_self->name = __pyx_v_name; + + /* "View.MemoryView":304 + * cdef class Enum(object): + * cdef object name + * def __init__(self, name): # <<<<<<<<<<<<<< + * self.name = name + * def __repr__(self): + */ + + /* function exit code */ + __pyx_r = 0; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":306 + * def __init__(self, name): + * self.name = name + * def __repr__(self): # <<<<<<<<<<<<<< + * return self.name + * + */ + +/* Python wrapper */ +static PyObject *__pyx_MemviewEnum___repr__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_MemviewEnum___repr__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__repr__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum_2__repr__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum_2__repr__(struct __pyx_MemviewEnum_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__repr__", 1); + + /* "View.MemoryView":307 + * self.name = name + * def __repr__(self): + * return self.name # <<<<<<<<<<<<<< + * + * cdef generic = Enum("") + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->name); + __pyx_r = __pyx_v_self->name; + goto __pyx_L0; + + /* "View.MemoryView":306 + * def __init__(self, name): + * self.name = name + * def __repr__(self): # <<<<<<<<<<<<<< + * return self.name + * + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * cdef tuple state + * cdef object _dict + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_MemviewEnum_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_MemviewEnum_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_MemviewEnum___reduce_cython__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_MemviewEnum___reduce_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self) { + PyObject *__pyx_v_state = 0; + PyObject *__pyx_v__dict = 0; + int __pyx_v_use_setstate; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":5 + * cdef object _dict + * cdef bint use_setstate + * state = (self.name,) # <<<<<<<<<<<<<< + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: + */ + __pyx_t_1 = PyTuple_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v_self->name); + __Pyx_GIVEREF(__pyx_v_self->name); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v_self->name)) __PYX_ERR(1, 5, __pyx_L1_error); + __pyx_v_state = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "(tree fragment)":6 + * cdef bint use_setstate + * state = (self.name,) + * _dict = getattr(self, '__dict__', None) # <<<<<<<<<<<<<< + * if _dict is not None: + * state += (_dict,) + */ + __pyx_t_1 = __Pyx_GetAttr3(((PyObject *)__pyx_v_self), __pyx_n_s_dict, Py_None); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v__dict = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":7 + * state = (self.name,) + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: # <<<<<<<<<<<<<< + * state += (_dict,) + * use_setstate = True + */ + __pyx_t_2 = (__pyx_v__dict != Py_None); + if (__pyx_t_2) { + + /* "(tree fragment)":8 + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: + * state += (_dict,) # <<<<<<<<<<<<<< + * use_setstate = True + * else: + */ + __pyx_t_1 = PyTuple_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 8, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v__dict); + __Pyx_GIVEREF(__pyx_v__dict); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v__dict)) __PYX_ERR(1, 8, __pyx_L1_error); + __pyx_t_3 = PyNumber_InPlaceAdd(__pyx_v_state, __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 8, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF_SET(__pyx_v_state, ((PyObject*)__pyx_t_3)); + __pyx_t_3 = 0; + + /* "(tree fragment)":9 + * if _dict is not None: + * state += (_dict,) + * use_setstate = True # <<<<<<<<<<<<<< + * else: + * use_setstate = self.name is not None + */ + __pyx_v_use_setstate = 1; + + /* "(tree fragment)":7 + * state = (self.name,) + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: # <<<<<<<<<<<<<< + * state += (_dict,) + * use_setstate = True + */ + goto __pyx_L3; + } + + /* "(tree fragment)":11 + * use_setstate = True + * else: + * use_setstate = self.name is not None # <<<<<<<<<<<<<< + * if use_setstate: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + */ + /*else*/ { + __pyx_t_2 = (__pyx_v_self->name != Py_None); + __pyx_v_use_setstate = __pyx_t_2; + } + __pyx_L3:; + + /* "(tree fragment)":12 + * else: + * use_setstate = self.name is not None + * if use_setstate: # <<<<<<<<<<<<<< + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + * else: + */ + if (__pyx_v_use_setstate) { + + /* "(tree fragment)":13 + * use_setstate = self.name is not None + * if use_setstate: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state # <<<<<<<<<<<<<< + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_pyx_unpickle_Enum); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = PyTuple_New(3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_GIVEREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, ((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self))))) __PYX_ERR(1, 13, __pyx_L1_error); + __Pyx_INCREF(__pyx_int_136983863); + __Pyx_GIVEREF(__pyx_int_136983863); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_int_136983863)) __PYX_ERR(1, 13, __pyx_L1_error); + __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(Py_None); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 2, Py_None)) __PYX_ERR(1, 13, __pyx_L1_error); + __pyx_t_4 = PyTuple_New(3); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_3)) __PYX_ERR(1, 13, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_t_1)) __PYX_ERR(1, 13, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_state); + __Pyx_GIVEREF(__pyx_v_state); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 2, __pyx_v_state)) __PYX_ERR(1, 13, __pyx_L1_error); + __pyx_t_3 = 0; + __pyx_t_1 = 0; + __pyx_r = __pyx_t_4; + __pyx_t_4 = 0; + goto __pyx_L0; + + /* "(tree fragment)":12 + * else: + * use_setstate = self.name is not None + * if use_setstate: # <<<<<<<<<<<<<< + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + * else: + */ + } + + /* "(tree fragment)":15 + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * __pyx_unpickle_Enum__set_state(self, __pyx_state) + */ + /*else*/ { + __Pyx_XDECREF(__pyx_r); + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_pyx_unpickle_Enum); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_1 = PyTuple_New(3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_GIVEREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, ((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self))))) __PYX_ERR(1, 15, __pyx_L1_error); + __Pyx_INCREF(__pyx_int_136983863); + __Pyx_GIVEREF(__pyx_int_136983863); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_int_136983863)) __PYX_ERR(1, 15, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_state); + __Pyx_GIVEREF(__pyx_v_state); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_v_state)) __PYX_ERR(1, 15, __pyx_L1_error); + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_4); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_4)) __PYX_ERR(1, 15, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1)) __PYX_ERR(1, 15, __pyx_L1_error); + __pyx_t_4 = 0; + __pyx_t_1 = 0; + __pyx_r = __pyx_t_3; + __pyx_t_3 = 0; + goto __pyx_L0; + } + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * cdef tuple state + * cdef object _dict + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.Enum.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_state); + __Pyx_XDECREF(__pyx_v__dict); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":16 + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state(self, __pyx_state) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_MemviewEnum_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_MemviewEnum_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 16, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 16, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 16, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.Enum.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_MemviewEnum_2__setstate_cython__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_MemviewEnum_2__setstate_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":17 + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + * def __setstate_cython__(self, __pyx_state): + * __pyx_unpickle_Enum__set_state(self, __pyx_state) # <<<<<<<<<<<<<< + */ + if (!(likely(PyTuple_CheckExact(__pyx_v___pyx_state))||((__pyx_v___pyx_state) == Py_None) || __Pyx_RaiseUnexpectedTypeError("tuple", __pyx_v___pyx_state))) __PYX_ERR(1, 17, __pyx_L1_error) + __pyx_t_1 = __pyx_unpickle_Enum__set_state(__pyx_v_self, ((PyObject*)__pyx_v___pyx_state)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 17, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":16 + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state(self, __pyx_state) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.Enum.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":349 + * cdef __Pyx_TypeInfo *typeinfo + * + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): # <<<<<<<<<<<<<< + * self.obj = obj + * self.flags = flags + */ + +/* Python wrapper */ +static int __pyx_memoryview___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_memoryview___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_obj = 0; + int __pyx_v_flags; + int __pyx_v_dtype_is_object; + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_obj,&__pyx_n_s_flags,&__pyx_n_s_dtype_is_object,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_obj)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_flags)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 2, 3, 1); __PYX_ERR(1, 349, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_dtype_is_object); + if (value) { values[2] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(1, 349, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_obj = values[0]; + __pyx_v_flags = __Pyx_PyInt_As_int(values[1]); if (unlikely((__pyx_v_flags == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) + if (values[2]) { + __pyx_v_dtype_is_object = __Pyx_PyObject_IsTrue(values[2]); if (unlikely((__pyx_v_dtype_is_object == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) + } else { + __pyx_v_dtype_is_object = ((int)0); + } + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 2, 3, __pyx_nargs); __PYX_ERR(1, 349, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.memoryview.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview___cinit__(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v_obj, __pyx_v_flags, __pyx_v_dtype_is_object); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview___cinit__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj, int __pyx_v_flags, int __pyx_v_dtype_is_object) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + Py_intptr_t __pyx_t_4; + size_t __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__cinit__", 1); + + /* "View.MemoryView":350 + * + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): + * self.obj = obj # <<<<<<<<<<<<<< + * self.flags = flags + * if type(self) is memoryview or obj is not None: + */ + __Pyx_INCREF(__pyx_v_obj); + __Pyx_GIVEREF(__pyx_v_obj); + __Pyx_GOTREF(__pyx_v_self->obj); + __Pyx_DECREF(__pyx_v_self->obj); + __pyx_v_self->obj = __pyx_v_obj; + + /* "View.MemoryView":351 + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): + * self.obj = obj + * self.flags = flags # <<<<<<<<<<<<<< + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) + */ + __pyx_v_self->flags = __pyx_v_flags; + + /* "View.MemoryView":352 + * self.obj = obj + * self.flags = flags + * if type(self) is memoryview or obj is not None: # <<<<<<<<<<<<<< + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: + */ + __pyx_t_2 = (((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self))) == ((PyObject *)__pyx_memoryview_type)); + if (!__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_2 = (__pyx_v_obj != Py_None); + __pyx_t_1 = __pyx_t_2; + __pyx_L4_bool_binop_done:; + if (__pyx_t_1) { + + /* "View.MemoryView":353 + * self.flags = flags + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) # <<<<<<<<<<<<<< + * if self.view.obj == NULL: + * (<__pyx_buffer *> &self.view).obj = Py_None + */ + __pyx_t_3 = __Pyx_GetBuffer(__pyx_v_obj, (&__pyx_v_self->view), __pyx_v_flags); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 353, __pyx_L1_error) + + /* "View.MemoryView":354 + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: # <<<<<<<<<<<<<< + * (<__pyx_buffer *> &self.view).obj = Py_None + * Py_INCREF(Py_None) + */ + __pyx_t_1 = (((PyObject *)__pyx_v_self->view.obj) == NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":355 + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: + * (<__pyx_buffer *> &self.view).obj = Py_None # <<<<<<<<<<<<<< + * Py_INCREF(Py_None) + * + */ + ((Py_buffer *)(&__pyx_v_self->view))->obj = Py_None; + + /* "View.MemoryView":356 + * if self.view.obj == NULL: + * (<__pyx_buffer *> &self.view).obj = Py_None + * Py_INCREF(Py_None) # <<<<<<<<<<<<<< + * + * if not __PYX_CYTHON_ATOMICS_ENABLED(): + */ + Py_INCREF(Py_None); + + /* "View.MemoryView":354 + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: # <<<<<<<<<<<<<< + * (<__pyx_buffer *> &self.view).obj = Py_None + * Py_INCREF(Py_None) + */ + } + + /* "View.MemoryView":352 + * self.obj = obj + * self.flags = flags + * if type(self) is memoryview or obj is not None: # <<<<<<<<<<<<<< + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: + */ + } + + /* "View.MemoryView":358 + * Py_INCREF(Py_None) + * + * if not __PYX_CYTHON_ATOMICS_ENABLED(): # <<<<<<<<<<<<<< + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: + */ + __pyx_t_1 = (!__PYX_CYTHON_ATOMICS_ENABLED()); + if (__pyx_t_1) { + + /* "View.MemoryView":360 + * if not __PYX_CYTHON_ATOMICS_ENABLED(): + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: # <<<<<<<<<<<<<< + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + */ + __pyx_t_1 = (__pyx_memoryview_thread_locks_used < 8); + if (__pyx_t_1) { + + /* "View.MemoryView":361 + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: + */ + __pyx_v_self->lock = (__pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used]); + + /* "View.MemoryView":362 + * if __pyx_memoryview_thread_locks_used < 8: + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 # <<<<<<<<<<<<<< + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() + */ + __pyx_memoryview_thread_locks_used = (__pyx_memoryview_thread_locks_used + 1); + + /* "View.MemoryView":360 + * if not __PYX_CYTHON_ATOMICS_ENABLED(): + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: # <<<<<<<<<<<<<< + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + */ + } + + /* "View.MemoryView":363 + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: # <<<<<<<<<<<<<< + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: + */ + __pyx_t_1 = (__pyx_v_self->lock == NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":364 + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() # <<<<<<<<<<<<<< + * if self.lock is NULL: + * raise MemoryError + */ + __pyx_v_self->lock = PyThread_allocate_lock(); + + /* "View.MemoryView":365 + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + __pyx_t_1 = (__pyx_v_self->lock == NULL); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":366 + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: + * raise MemoryError # <<<<<<<<<<<<<< + * + * if flags & PyBUF_FORMAT: + */ + PyErr_NoMemory(); __PYX_ERR(1, 366, __pyx_L1_error) + + /* "View.MemoryView":365 + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + } + + /* "View.MemoryView":363 + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: # <<<<<<<<<<<<<< + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: + */ + } + + /* "View.MemoryView":358 + * Py_INCREF(Py_None) + * + * if not __PYX_CYTHON_ATOMICS_ENABLED(): # <<<<<<<<<<<<<< + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: + */ + } + + /* "View.MemoryView":368 + * raise MemoryError + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_FORMAT) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":369 + * + * if flags & PyBUF_FORMAT: + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') # <<<<<<<<<<<<<< + * else: + * self.dtype_is_object = dtype_is_object + */ + __pyx_t_2 = ((__pyx_v_self->view.format[0]) == 'O'); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L12_bool_binop_done; + } + __pyx_t_2 = ((__pyx_v_self->view.format[1]) == '\x00'); + __pyx_t_1 = __pyx_t_2; + __pyx_L12_bool_binop_done:; + __pyx_v_self->dtype_is_object = __pyx_t_1; + + /* "View.MemoryView":368 + * raise MemoryError + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') + * else: + */ + goto __pyx_L11; + } + + /* "View.MemoryView":371 + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') + * else: + * self.dtype_is_object = dtype_is_object # <<<<<<<<<<<<<< + * + * assert (&self.acquisition_count) % sizeof(__pyx_atomic_int_type) == 0 + */ + /*else*/ { + __pyx_v_self->dtype_is_object = __pyx_v_dtype_is_object; + } + __pyx_L11:; + + /* "View.MemoryView":373 + * self.dtype_is_object = dtype_is_object + * + * assert (&self.acquisition_count) % sizeof(__pyx_atomic_int_type) == 0 # <<<<<<<<<<<<<< + * self.typeinfo = NULL + * + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_4 = ((Py_intptr_t)((void *)(&__pyx_v_self->acquisition_count))); + __pyx_t_5 = (sizeof(__pyx_atomic_int_type)); + if (unlikely(__pyx_t_5 == 0)) { + PyErr_SetString(PyExc_ZeroDivisionError, "integer division or modulo by zero"); + __PYX_ERR(1, 373, __pyx_L1_error) + } + __pyx_t_1 = ((__pyx_t_4 % __pyx_t_5) == 0); + if (unlikely(!__pyx_t_1)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(1, 373, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(1, 373, __pyx_L1_error) + #endif + + /* "View.MemoryView":374 + * + * assert (&self.acquisition_count) % sizeof(__pyx_atomic_int_type) == 0 + * self.typeinfo = NULL # <<<<<<<<<<<<<< + * + * def __dealloc__(memoryview self): + */ + __pyx_v_self->typeinfo = NULL; + + /* "View.MemoryView":349 + * cdef __Pyx_TypeInfo *typeinfo + * + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): # <<<<<<<<<<<<<< + * self.obj = obj + * self.flags = flags + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":376 + * self.typeinfo = NULL + * + * def __dealloc__(memoryview self): # <<<<<<<<<<<<<< + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + */ + +/* Python wrapper */ +static void __pyx_memoryview___dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_memoryview___dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_2__dealloc__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_2__dealloc__(struct __pyx_memoryview_obj *__pyx_v_self) { + int __pyx_v_i; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + PyThread_type_lock __pyx_t_5; + PyThread_type_lock __pyx_t_6; + + /* "View.MemoryView":377 + * + * def __dealloc__(memoryview self): + * if self.obj is not None: # <<<<<<<<<<<<<< + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + */ + __pyx_t_1 = (__pyx_v_self->obj != Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":378 + * def __dealloc__(memoryview self): + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) # <<<<<<<<<<<<<< + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + * + */ + __Pyx_ReleaseBuffer((&__pyx_v_self->view)); + + /* "View.MemoryView":377 + * + * def __dealloc__(memoryview self): + * if self.obj is not None: # <<<<<<<<<<<<<< + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":379 + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: # <<<<<<<<<<<<<< + * + * (<__pyx_buffer *> &self.view).obj = NULL + */ + __pyx_t_1 = (((Py_buffer *)(&__pyx_v_self->view))->obj == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":381 + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + * + * (<__pyx_buffer *> &self.view).obj = NULL # <<<<<<<<<<<<<< + * Py_DECREF(Py_None) + * + */ + ((Py_buffer *)(&__pyx_v_self->view))->obj = NULL; + + /* "View.MemoryView":382 + * + * (<__pyx_buffer *> &self.view).obj = NULL + * Py_DECREF(Py_None) # <<<<<<<<<<<<<< + * + * cdef int i + */ + Py_DECREF(Py_None); + + /* "View.MemoryView":379 + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: # <<<<<<<<<<<<<< + * + * (<__pyx_buffer *> &self.view).obj = NULL + */ + } + __pyx_L3:; + + /* "View.MemoryView":386 + * cdef int i + * global __pyx_memoryview_thread_locks_used + * if self.lock != NULL: # <<<<<<<<<<<<<< + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: + */ + __pyx_t_1 = (__pyx_v_self->lock != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":387 + * global __pyx_memoryview_thread_locks_used + * if self.lock != NULL: + * for i in range(__pyx_memoryview_thread_locks_used): # <<<<<<<<<<<<<< + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 + */ + __pyx_t_2 = __pyx_memoryview_thread_locks_used; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":388 + * if self.lock != NULL: + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: + */ + __pyx_t_1 = ((__pyx_memoryview_thread_locks[__pyx_v_i]) == __pyx_v_self->lock); + if (__pyx_t_1) { + + /* "View.MemoryView":389 + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 # <<<<<<<<<<<<<< + * if i != __pyx_memoryview_thread_locks_used: + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + */ + __pyx_memoryview_thread_locks_used = (__pyx_memoryview_thread_locks_used - 1); + + /* "View.MemoryView":390 + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + */ + __pyx_t_1 = (__pyx_v_i != __pyx_memoryview_thread_locks_used); + if (__pyx_t_1) { + + /* "View.MemoryView":392 + * if i != __pyx_memoryview_thread_locks_used: + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) # <<<<<<<<<<<<<< + * break + * else: + */ + __pyx_t_5 = (__pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used]); + __pyx_t_6 = (__pyx_memoryview_thread_locks[__pyx_v_i]); + + /* "View.MemoryView":391 + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + * break + */ + (__pyx_memoryview_thread_locks[__pyx_v_i]) = __pyx_t_5; + (__pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used]) = __pyx_t_6; + + /* "View.MemoryView":390 + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + */ + } + + /* "View.MemoryView":393 + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + * break # <<<<<<<<<<<<<< + * else: + * PyThread_free_lock(self.lock) + */ + goto __pyx_L6_break; + + /* "View.MemoryView":388 + * if self.lock != NULL: + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: + */ + } + } + /*else*/ { + + /* "View.MemoryView":395 + * break + * else: + * PyThread_free_lock(self.lock) # <<<<<<<<<<<<<< + * + * cdef char *get_item_pointer(memoryview self, object index) except NULL: + */ + PyThread_free_lock(__pyx_v_self->lock); + } + __pyx_L6_break:; + + /* "View.MemoryView":386 + * cdef int i + * global __pyx_memoryview_thread_locks_used + * if self.lock != NULL: # <<<<<<<<<<<<<< + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: + */ + } + + /* "View.MemoryView":376 + * self.typeinfo = NULL + * + * def __dealloc__(memoryview self): # <<<<<<<<<<<<<< + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + */ + + /* function exit code */ +} + +/* "View.MemoryView":397 + * PyThread_free_lock(self.lock) + * + * cdef char *get_item_pointer(memoryview self, object index) except NULL: # <<<<<<<<<<<<<< + * cdef Py_ssize_t dim + * cdef char *itemp = self.view.buf + */ + +static char *__pyx_memoryview_get_item_pointer(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index) { + Py_ssize_t __pyx_v_dim; + char *__pyx_v_itemp; + PyObject *__pyx_v_idx = NULL; + char *__pyx_r; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + Py_ssize_t __pyx_t_3; + PyObject *(*__pyx_t_4)(PyObject *); + PyObject *__pyx_t_5 = NULL; + Py_ssize_t __pyx_t_6; + char *__pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_item_pointer", 1); + + /* "View.MemoryView":399 + * cdef char *get_item_pointer(memoryview self, object index) except NULL: + * cdef Py_ssize_t dim + * cdef char *itemp = self.view.buf # <<<<<<<<<<<<<< + * + * for dim, idx in enumerate(index): + */ + __pyx_v_itemp = ((char *)__pyx_v_self->view.buf); + + /* "View.MemoryView":401 + * cdef char *itemp = self.view.buf + * + * for dim, idx in enumerate(index): # <<<<<<<<<<<<<< + * itemp = pybuffer_index(&self.view, itemp, idx, dim) + * + */ + __pyx_t_1 = 0; + if (likely(PyList_CheckExact(__pyx_v_index)) || PyTuple_CheckExact(__pyx_v_index)) { + __pyx_t_2 = __pyx_v_index; __Pyx_INCREF(__pyx_t_2); + __pyx_t_3 = 0; + __pyx_t_4 = NULL; + } else { + __pyx_t_3 = -1; __pyx_t_2 = PyObject_GetIter(__pyx_v_index); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 401, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_2); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 401, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_4)) { + if (likely(PyList_CheckExact(__pyx_t_2))) { + { + Py_ssize_t __pyx_temp = __Pyx_PyList_GET_SIZE(__pyx_t_2); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 401, __pyx_L1_error) + #endif + if (__pyx_t_3 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_5 = PyList_GET_ITEM(__pyx_t_2, __pyx_t_3); __Pyx_INCREF(__pyx_t_5); __pyx_t_3++; if (unlikely((0 < 0))) __PYX_ERR(1, 401, __pyx_L1_error) + #else + __pyx_t_5 = __Pyx_PySequence_ITEM(__pyx_t_2, __pyx_t_3); __pyx_t_3++; if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 401, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + #endif + } else { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_2); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 401, __pyx_L1_error) + #endif + if (__pyx_t_3 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_5 = PyTuple_GET_ITEM(__pyx_t_2, __pyx_t_3); __Pyx_INCREF(__pyx_t_5); __pyx_t_3++; if (unlikely((0 < 0))) __PYX_ERR(1, 401, __pyx_L1_error) + #else + __pyx_t_5 = __Pyx_PySequence_ITEM(__pyx_t_2, __pyx_t_3); __pyx_t_3++; if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 401, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + #endif + } + } else { + __pyx_t_5 = __pyx_t_4(__pyx_t_2); + if (unlikely(!__pyx_t_5)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(1, 401, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_5); + } + __Pyx_XDECREF_SET(__pyx_v_idx, __pyx_t_5); + __pyx_t_5 = 0; + __pyx_v_dim = __pyx_t_1; + __pyx_t_1 = (__pyx_t_1 + 1); + + /* "View.MemoryView":402 + * + * for dim, idx in enumerate(index): + * itemp = pybuffer_index(&self.view, itemp, idx, dim) # <<<<<<<<<<<<<< + * + * return itemp + */ + __pyx_t_6 = __Pyx_PyIndex_AsSsize_t(__pyx_v_idx); if (unlikely((__pyx_t_6 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 402, __pyx_L1_error) + __pyx_t_7 = __pyx_pybuffer_index((&__pyx_v_self->view), __pyx_v_itemp, __pyx_t_6, __pyx_v_dim); if (unlikely(__pyx_t_7 == ((char *)NULL))) __PYX_ERR(1, 402, __pyx_L1_error) + __pyx_v_itemp = __pyx_t_7; + + /* "View.MemoryView":401 + * cdef char *itemp = self.view.buf + * + * for dim, idx in enumerate(index): # <<<<<<<<<<<<<< + * itemp = pybuffer_index(&self.view, itemp, idx, dim) + * + */ + } + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":404 + * itemp = pybuffer_index(&self.view, itemp, idx, dim) + * + * return itemp # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = __pyx_v_itemp; + goto __pyx_L0; + + /* "View.MemoryView":397 + * PyThread_free_lock(self.lock) + * + * cdef char *get_item_pointer(memoryview self, object index) except NULL: # <<<<<<<<<<<<<< + * cdef Py_ssize_t dim + * cdef char *itemp = self.view.buf + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.memoryview.get_item_pointer", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_idx); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":407 + * + * + * def __getitem__(memoryview self, object index): # <<<<<<<<<<<<<< + * if index is Ellipsis: + * return self + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index); /*proto*/ +static PyObject *__pyx_memoryview___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getitem__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_4__getitem__(((struct __pyx_memoryview_obj *)__pyx_v_self), ((PyObject *)__pyx_v_index)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_4__getitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index) { + PyObject *__pyx_v_have_slices = NULL; + PyObject *__pyx_v_indices = NULL; + char *__pyx_v_itemp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + char *__pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__getitem__", 1); + + /* "View.MemoryView":408 + * + * def __getitem__(memoryview self, object index): + * if index is Ellipsis: # <<<<<<<<<<<<<< + * return self + * + */ + __pyx_t_1 = (__pyx_v_index == __pyx_builtin_Ellipsis); + if (__pyx_t_1) { + + /* "View.MemoryView":409 + * def __getitem__(memoryview self, object index): + * if index is Ellipsis: + * return self # <<<<<<<<<<<<<< + * + * have_slices, indices = _unellipsify(index, self.view.ndim) + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_self); + __pyx_r = ((PyObject *)__pyx_v_self); + goto __pyx_L0; + + /* "View.MemoryView":408 + * + * def __getitem__(memoryview self, object index): + * if index is Ellipsis: # <<<<<<<<<<<<<< + * return self + * + */ + } + + /* "View.MemoryView":411 + * return self + * + * have_slices, indices = _unellipsify(index, self.view.ndim) # <<<<<<<<<<<<<< + * + * cdef char *itemp + */ + __pyx_t_2 = _unellipsify(__pyx_v_index, __pyx_v_self->view.ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 411, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (likely(__pyx_t_2 != Py_None)) { + PyObject* sequence = __pyx_t_2; + Py_ssize_t size = __Pyx_PySequence_SIZE(sequence); + if (unlikely(size != 2)) { + if (size > 2) __Pyx_RaiseTooManyValuesError(2); + else if (size >= 0) __Pyx_RaiseNeedMoreValuesError(size); + __PYX_ERR(1, 411, __pyx_L1_error) + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_3 = PyTuple_GET_ITEM(sequence, 0); + __pyx_t_4 = PyTuple_GET_ITEM(sequence, 1); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(__pyx_t_4); + #else + __pyx_t_3 = PySequence_ITEM(sequence, 0); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 411, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PySequence_ITEM(sequence, 1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 411, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } else { + __Pyx_RaiseNoneNotIterableError(); __PYX_ERR(1, 411, __pyx_L1_error) + } + __pyx_v_have_slices = __pyx_t_3; + __pyx_t_3 = 0; + __pyx_v_indices = __pyx_t_4; + __pyx_t_4 = 0; + + /* "View.MemoryView":414 + * + * cdef char *itemp + * if have_slices: # <<<<<<<<<<<<<< + * return memview_slice(self, indices) + * else: + */ + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_v_have_slices); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 414, __pyx_L1_error) + if (__pyx_t_1) { + + /* "View.MemoryView":415 + * cdef char *itemp + * if have_slices: + * return memview_slice(self, indices) # <<<<<<<<<<<<<< + * else: + * itemp = self.get_item_pointer(indices) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = ((PyObject *)__pyx_memview_slice(__pyx_v_self, __pyx_v_indices)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 415, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":414 + * + * cdef char *itemp + * if have_slices: # <<<<<<<<<<<<<< + * return memview_slice(self, indices) + * else: + */ + } + + /* "View.MemoryView":417 + * return memview_slice(self, indices) + * else: + * itemp = self.get_item_pointer(indices) # <<<<<<<<<<<<<< + * return self.convert_item_to_object(itemp) + * + */ + /*else*/ { + __pyx_t_5 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->get_item_pointer(__pyx_v_self, __pyx_v_indices); if (unlikely(__pyx_t_5 == ((char *)NULL))) __PYX_ERR(1, 417, __pyx_L1_error) + __pyx_v_itemp = __pyx_t_5; + + /* "View.MemoryView":418 + * else: + * itemp = self.get_item_pointer(indices) + * return self.convert_item_to_object(itemp) # <<<<<<<<<<<<<< + * + * def __setitem__(memoryview self, object index, object value): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->convert_item_to_object(__pyx_v_self, __pyx_v_itemp); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 418, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + } + + /* "View.MemoryView":407 + * + * + * def __getitem__(memoryview self, object index): # <<<<<<<<<<<<<< + * if index is Ellipsis: + * return self + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.memoryview.__getitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_have_slices); + __Pyx_XDECREF(__pyx_v_indices); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":420 + * return self.convert_item_to_object(itemp) + * + * def __setitem__(memoryview self, object index, object value): # <<<<<<<<<<<<<< + * if self.view.readonly: + * raise TypeError, "Cannot assign to read-only memoryview" + */ + +/* Python wrapper */ +static int __pyx_memoryview___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value); /*proto*/ +static int __pyx_memoryview___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setitem__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_6__setitem__(((struct __pyx_memoryview_obj *)__pyx_v_self), ((PyObject *)__pyx_v_index), ((PyObject *)__pyx_v_value)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_6__setitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value) { + PyObject *__pyx_v_have_slices = NULL; + PyObject *__pyx_v_obj = NULL; + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setitem__", 0); + __Pyx_INCREF(__pyx_v_index); + + /* "View.MemoryView":421 + * + * def __setitem__(memoryview self, object index, object value): + * if self.view.readonly: # <<<<<<<<<<<<<< + * raise TypeError, "Cannot assign to read-only memoryview" + * + */ + if (unlikely(__pyx_v_self->view.readonly)) { + + /* "View.MemoryView":422 + * def __setitem__(memoryview self, object index, object value): + * if self.view.readonly: + * raise TypeError, "Cannot assign to read-only memoryview" # <<<<<<<<<<<<<< + * + * have_slices, index = _unellipsify(index, self.view.ndim) + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_Cannot_assign_to_read_only_memor, 0, 0); + __PYX_ERR(1, 422, __pyx_L1_error) + + /* "View.MemoryView":421 + * + * def __setitem__(memoryview self, object index, object value): + * if self.view.readonly: # <<<<<<<<<<<<<< + * raise TypeError, "Cannot assign to read-only memoryview" + * + */ + } + + /* "View.MemoryView":424 + * raise TypeError, "Cannot assign to read-only memoryview" + * + * have_slices, index = _unellipsify(index, self.view.ndim) # <<<<<<<<<<<<<< + * + * if have_slices: + */ + __pyx_t_1 = _unellipsify(__pyx_v_index, __pyx_v_self->view.ndim); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 424, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (likely(__pyx_t_1 != Py_None)) { + PyObject* sequence = __pyx_t_1; + Py_ssize_t size = __Pyx_PySequence_SIZE(sequence); + if (unlikely(size != 2)) { + if (size > 2) __Pyx_RaiseTooManyValuesError(2); + else if (size >= 0) __Pyx_RaiseNeedMoreValuesError(size); + __PYX_ERR(1, 424, __pyx_L1_error) + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_2 = PyTuple_GET_ITEM(sequence, 0); + __pyx_t_3 = PyTuple_GET_ITEM(sequence, 1); + __Pyx_INCREF(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + #else + __pyx_t_2 = PySequence_ITEM(sequence, 0); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 424, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PySequence_ITEM(sequence, 1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 424, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + #endif + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } else { + __Pyx_RaiseNoneNotIterableError(); __PYX_ERR(1, 424, __pyx_L1_error) + } + __pyx_v_have_slices = __pyx_t_2; + __pyx_t_2 = 0; + __Pyx_DECREF_SET(__pyx_v_index, __pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":426 + * have_slices, index = _unellipsify(index, self.view.ndim) + * + * if have_slices: # <<<<<<<<<<<<<< + * obj = self.is_slice(value) + * if obj: + */ + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_v_have_slices); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(1, 426, __pyx_L1_error) + if (__pyx_t_4) { + + /* "View.MemoryView":427 + * + * if have_slices: + * obj = self.is_slice(value) # <<<<<<<<<<<<<< + * if obj: + * self.setitem_slice_assignment(self[index], obj) + */ + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->is_slice(__pyx_v_self, __pyx_v_value); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 427, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_obj = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":428 + * if have_slices: + * obj = self.is_slice(value) + * if obj: # <<<<<<<<<<<<<< + * self.setitem_slice_assignment(self[index], obj) + * else: + */ + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_v_obj); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(1, 428, __pyx_L1_error) + if (__pyx_t_4) { + + /* "View.MemoryView":429 + * obj = self.is_slice(value) + * if obj: + * self.setitem_slice_assignment(self[index], obj) # <<<<<<<<<<<<<< + * else: + * self.setitem_slice_assign_scalar(self[index], value) + */ + __pyx_t_1 = __Pyx_PyObject_GetItem(((PyObject *)__pyx_v_self), __pyx_v_index); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 429, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->setitem_slice_assignment(__pyx_v_self, __pyx_t_1, __pyx_v_obj); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 429, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "View.MemoryView":428 + * if have_slices: + * obj = self.is_slice(value) + * if obj: # <<<<<<<<<<<<<< + * self.setitem_slice_assignment(self[index], obj) + * else: + */ + goto __pyx_L5; + } + + /* "View.MemoryView":431 + * self.setitem_slice_assignment(self[index], obj) + * else: + * self.setitem_slice_assign_scalar(self[index], value) # <<<<<<<<<<<<<< + * else: + * self.setitem_indexed(index, value) + */ + /*else*/ { + __pyx_t_3 = __Pyx_PyObject_GetItem(((PyObject *)__pyx_v_self), __pyx_v_index); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 431, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (!(likely(((__pyx_t_3) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_3, __pyx_memoryview_type))))) __PYX_ERR(1, 431, __pyx_L1_error) + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->setitem_slice_assign_scalar(__pyx_v_self, ((struct __pyx_memoryview_obj *)__pyx_t_3), __pyx_v_value); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 431, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_L5:; + + /* "View.MemoryView":426 + * have_slices, index = _unellipsify(index, self.view.ndim) + * + * if have_slices: # <<<<<<<<<<<<<< + * obj = self.is_slice(value) + * if obj: + */ + goto __pyx_L4; + } + + /* "View.MemoryView":433 + * self.setitem_slice_assign_scalar(self[index], value) + * else: + * self.setitem_indexed(index, value) # <<<<<<<<<<<<<< + * + * cdef is_slice(self, obj): + */ + /*else*/ { + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->setitem_indexed(__pyx_v_self, __pyx_v_index, __pyx_v_value); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 433, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_L4:; + + /* "View.MemoryView":420 + * return self.convert_item_to_object(itemp) + * + * def __setitem__(memoryview self, object index, object value): # <<<<<<<<<<<<<< + * if self.view.readonly: + * raise TypeError, "Cannot assign to read-only memoryview" + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.__setitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_have_slices); + __Pyx_XDECREF(__pyx_v_obj); + __Pyx_XDECREF(__pyx_v_index); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":435 + * self.setitem_indexed(index, value) + * + * cdef is_slice(self, obj): # <<<<<<<<<<<<<< + * if not isinstance(obj, memoryview): + * try: + */ + +static PyObject *__pyx_memoryview_is_slice(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("is_slice", 0); + __Pyx_INCREF(__pyx_v_obj); + + /* "View.MemoryView":436 + * + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): # <<<<<<<<<<<<<< + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + */ + __pyx_t_1 = __Pyx_TypeCheck(__pyx_v_obj, __pyx_memoryview_type); + __pyx_t_2 = (!__pyx_t_1); + if (__pyx_t_2) { + + /* "View.MemoryView":437 + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): + * try: # <<<<<<<<<<<<<< + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_3, &__pyx_t_4, &__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_4); + __Pyx_XGOTREF(__pyx_t_5); + /*try:*/ { + + /* "View.MemoryView":438 + * if not isinstance(obj, memoryview): + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, # <<<<<<<<<<<<<< + * self.dtype_is_object) + * except TypeError: + */ + __pyx_t_6 = __Pyx_PyInt_From_int(((__pyx_v_self->flags & (~PyBUF_WRITABLE)) | PyBUF_ANY_CONTIGUOUS)); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 438, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_6); + + /* "View.MemoryView":439 + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) # <<<<<<<<<<<<<< + * except TypeError: + * return None + */ + __pyx_t_7 = __Pyx_PyBool_FromLong(__pyx_v_self->dtype_is_object); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 439, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_7); + + /* "View.MemoryView":438 + * if not isinstance(obj, memoryview): + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, # <<<<<<<<<<<<<< + * self.dtype_is_object) + * except TypeError: + */ + __pyx_t_8 = PyTuple_New(3); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 438, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_INCREF(__pyx_v_obj); + __Pyx_GIVEREF(__pyx_v_obj); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_8, 0, __pyx_v_obj)) __PYX_ERR(1, 438, __pyx_L4_error); + __Pyx_GIVEREF(__pyx_t_6); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_8, 1, __pyx_t_6)) __PYX_ERR(1, 438, __pyx_L4_error); + __Pyx_GIVEREF(__pyx_t_7); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_8, 2, __pyx_t_7)) __PYX_ERR(1, 438, __pyx_L4_error); + __pyx_t_6 = 0; + __pyx_t_7 = 0; + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_memoryview_type), __pyx_t_8, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 438, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_DECREF_SET(__pyx_v_obj, __pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":437 + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): + * try: # <<<<<<<<<<<<<< + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + */ + } + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + goto __pyx_L9_try_end; + __pyx_L4_error:; + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + + /* "View.MemoryView":440 + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + * except TypeError: # <<<<<<<<<<<<<< + * return None + * + */ + __pyx_t_9 = __Pyx_PyErr_ExceptionMatches(__pyx_builtin_TypeError); + if (__pyx_t_9) { + __Pyx_AddTraceback("View.MemoryView.memoryview.is_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_7, &__pyx_t_8, &__pyx_t_6) < 0) __PYX_ERR(1, 440, __pyx_L6_except_error) + __Pyx_XGOTREF(__pyx_t_7); + __Pyx_XGOTREF(__pyx_t_8); + __Pyx_XGOTREF(__pyx_t_6); + + /* "View.MemoryView":441 + * self.dtype_is_object) + * except TypeError: + * return None # <<<<<<<<<<<<<< + * + * return obj + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L7_except_return; + } + goto __pyx_L6_except_error; + + /* "View.MemoryView":437 + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): + * try: # <<<<<<<<<<<<<< + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + */ + __pyx_L6_except_error:; + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_XGIVEREF(__pyx_t_5); + __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_4, __pyx_t_5); + goto __pyx_L1_error; + __pyx_L7_except_return:; + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_XGIVEREF(__pyx_t_5); + __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_4, __pyx_t_5); + goto __pyx_L0; + __pyx_L9_try_end:; + } + + /* "View.MemoryView":436 + * + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): # <<<<<<<<<<<<<< + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + */ + } + + /* "View.MemoryView":443 + * return None + * + * return obj # <<<<<<<<<<<<<< + * + * cdef setitem_slice_assignment(self, dst, src): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_obj); + __pyx_r = __pyx_v_obj; + goto __pyx_L0; + + /* "View.MemoryView":435 + * self.setitem_indexed(index, value) + * + * cdef is_slice(self, obj): # <<<<<<<<<<<<<< + * if not isinstance(obj, memoryview): + * try: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("View.MemoryView.memoryview.is_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_obj); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":445 + * return obj + * + * cdef setitem_slice_assignment(self, dst, src): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice dst_slice + * cdef __Pyx_memviewslice src_slice + */ + +static PyObject *__pyx_memoryview_setitem_slice_assignment(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_dst, PyObject *__pyx_v_src) { + __Pyx_memviewslice __pyx_v_dst_slice; + __Pyx_memviewslice __pyx_v_src_slice; + __Pyx_memviewslice __pyx_v_msrc; + __Pyx_memviewslice __pyx_v_mdst; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_t_3; + int __pyx_t_4; + int __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("setitem_slice_assignment", 1); + + /* "View.MemoryView":448 + * cdef __Pyx_memviewslice dst_slice + * cdef __Pyx_memviewslice src_slice + * cdef __Pyx_memviewslice msrc = get_slice_from_memview(src, &src_slice)[0] # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice mdst = get_slice_from_memview(dst, &dst_slice)[0] + * + */ + if (!(likely(((__pyx_v_src) == Py_None) || likely(__Pyx_TypeTest(__pyx_v_src, __pyx_memoryview_type))))) __PYX_ERR(1, 448, __pyx_L1_error) + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(((struct __pyx_memoryview_obj *)__pyx_v_src), (&__pyx_v_src_slice)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 448, __pyx_L1_error) + __pyx_v_msrc = (__pyx_t_1[0]); + + /* "View.MemoryView":449 + * cdef __Pyx_memviewslice src_slice + * cdef __Pyx_memviewslice msrc = get_slice_from_memview(src, &src_slice)[0] + * cdef __Pyx_memviewslice mdst = get_slice_from_memview(dst, &dst_slice)[0] # <<<<<<<<<<<<<< + * + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) + */ + if (!(likely(((__pyx_v_dst) == Py_None) || likely(__Pyx_TypeTest(__pyx_v_dst, __pyx_memoryview_type))))) __PYX_ERR(1, 449, __pyx_L1_error) + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(((struct __pyx_memoryview_obj *)__pyx_v_dst), (&__pyx_v_dst_slice)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 449, __pyx_L1_error) + __pyx_v_mdst = (__pyx_t_1[0]); + + /* "View.MemoryView":451 + * cdef __Pyx_memviewslice mdst = get_slice_from_memview(dst, &dst_slice)[0] + * + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) # <<<<<<<<<<<<<< + * + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_src, __pyx_n_s_ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 451, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_PyInt_As_int(__pyx_t_2); if (unlikely((__pyx_t_3 == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 451, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_dst, __pyx_n_s_ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 451, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __Pyx_PyInt_As_int(__pyx_t_2); if (unlikely((__pyx_t_4 == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 451, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_5 = __pyx_memoryview_copy_contents(__pyx_v_msrc, __pyx_v_mdst, __pyx_t_3, __pyx_t_4, __pyx_v_self->dtype_is_object); if (unlikely(__pyx_t_5 == ((int)-1))) __PYX_ERR(1, 451, __pyx_L1_error) + + /* "View.MemoryView":445 + * return obj + * + * cdef setitem_slice_assignment(self, dst, src): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice dst_slice + * cdef __Pyx_memviewslice src_slice + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.setitem_slice_assignment", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":453 + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) + * + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): # <<<<<<<<<<<<<< + * cdef int array[128] + * cdef void *tmp = NULL + */ + +static PyObject *__pyx_memoryview_setitem_slice_assign_scalar(struct __pyx_memoryview_obj *__pyx_v_self, struct __pyx_memoryview_obj *__pyx_v_dst, PyObject *__pyx_v_value) { + int __pyx_v_array[0x80]; + void *__pyx_v_tmp; + void *__pyx_v_item; + __Pyx_memviewslice *__pyx_v_dst_slice; + __Pyx_memviewslice __pyx_v_tmp_slice; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_t_5; + char const *__pyx_t_6; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + PyObject *__pyx_t_9 = NULL; + PyObject *__pyx_t_10 = NULL; + PyObject *__pyx_t_11 = NULL; + PyObject *__pyx_t_12 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("setitem_slice_assign_scalar", 1); + + /* "View.MemoryView":455 + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): + * cdef int array[128] + * cdef void *tmp = NULL # <<<<<<<<<<<<<< + * cdef void *item + * + */ + __pyx_v_tmp = NULL; + + /* "View.MemoryView":460 + * cdef __Pyx_memviewslice *dst_slice + * cdef __Pyx_memviewslice tmp_slice + * dst_slice = get_slice_from_memview(dst, &tmp_slice) # <<<<<<<<<<<<<< + * + * if self.view.itemsize > sizeof(array): + */ + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(__pyx_v_dst, (&__pyx_v_tmp_slice)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 460, __pyx_L1_error) + __pyx_v_dst_slice = __pyx_t_1; + + /* "View.MemoryView":462 + * dst_slice = get_slice_from_memview(dst, &tmp_slice) + * + * if self.view.itemsize > sizeof(array): # <<<<<<<<<<<<<< + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: + */ + __pyx_t_2 = (((size_t)__pyx_v_self->view.itemsize) > (sizeof(__pyx_v_array))); + if (__pyx_t_2) { + + /* "View.MemoryView":463 + * + * if self.view.itemsize > sizeof(array): + * tmp = PyMem_Malloc(self.view.itemsize) # <<<<<<<<<<<<<< + * if tmp == NULL: + * raise MemoryError + */ + __pyx_v_tmp = PyMem_Malloc(__pyx_v_self->view.itemsize); + + /* "View.MemoryView":464 + * if self.view.itemsize > sizeof(array): + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * item = tmp + */ + __pyx_t_2 = (__pyx_v_tmp == NULL); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":465 + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: + * raise MemoryError # <<<<<<<<<<<<<< + * item = tmp + * else: + */ + PyErr_NoMemory(); __PYX_ERR(1, 465, __pyx_L1_error) + + /* "View.MemoryView":464 + * if self.view.itemsize > sizeof(array): + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * item = tmp + */ + } + + /* "View.MemoryView":466 + * if tmp == NULL: + * raise MemoryError + * item = tmp # <<<<<<<<<<<<<< + * else: + * item = array + */ + __pyx_v_item = __pyx_v_tmp; + + /* "View.MemoryView":462 + * dst_slice = get_slice_from_memview(dst, &tmp_slice) + * + * if self.view.itemsize > sizeof(array): # <<<<<<<<<<<<<< + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":468 + * item = tmp + * else: + * item = array # <<<<<<<<<<<<<< + * + * try: + */ + /*else*/ { + __pyx_v_item = ((void *)__pyx_v_array); + } + __pyx_L3:; + + /* "View.MemoryView":470 + * item = array + * + * try: # <<<<<<<<<<<<<< + * if self.dtype_is_object: + * ( item)[0] = value + */ + /*try:*/ { + + /* "View.MemoryView":471 + * + * try: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * ( item)[0] = value + * else: + */ + if (__pyx_v_self->dtype_is_object) { + + /* "View.MemoryView":472 + * try: + * if self.dtype_is_object: + * ( item)[0] = value # <<<<<<<<<<<<<< + * else: + * self.assign_item_from_object( item, value) + */ + (((PyObject **)__pyx_v_item)[0]) = ((PyObject *)__pyx_v_value); + + /* "View.MemoryView":471 + * + * try: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * ( item)[0] = value + * else: + */ + goto __pyx_L8; + } + + /* "View.MemoryView":474 + * ( item)[0] = value + * else: + * self.assign_item_from_object( item, value) # <<<<<<<<<<<<<< + * + * + */ + /*else*/ { + __pyx_t_3 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->assign_item_from_object(__pyx_v_self, ((char *)__pyx_v_item), __pyx_v_value); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 474, __pyx_L6_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_L8:; + + /* "View.MemoryView":478 + * + * + * if self.view.suboffsets != NULL: # <<<<<<<<<<<<<< + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, + */ + __pyx_t_2 = (__pyx_v_self->view.suboffsets != NULL); + if (__pyx_t_2) { + + /* "View.MemoryView":479 + * + * if self.view.suboffsets != NULL: + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) # <<<<<<<<<<<<<< + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, + * item, self.dtype_is_object) + */ + __pyx_t_4 = assert_direct_dimensions(__pyx_v_self->view.suboffsets, __pyx_v_self->view.ndim); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(1, 479, __pyx_L6_error) + + /* "View.MemoryView":478 + * + * + * if self.view.suboffsets != NULL: # <<<<<<<<<<<<<< + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, + */ + } + + /* "View.MemoryView":480 + * if self.view.suboffsets != NULL: + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, # <<<<<<<<<<<<<< + * item, self.dtype_is_object) + * finally: + */ + __pyx_memoryview_slice_assign_scalar(__pyx_v_dst_slice, __pyx_v_dst->view.ndim, __pyx_v_self->view.itemsize, __pyx_v_item, __pyx_v_self->dtype_is_object); + } + + /* "View.MemoryView":483 + * item, self.dtype_is_object) + * finally: + * PyMem_Free(tmp) # <<<<<<<<<<<<<< + * + * cdef setitem_indexed(self, index, value): + */ + /*finally:*/ { + /*normal exit:*/{ + PyMem_Free(__pyx_v_tmp); + goto __pyx_L7; + } + __pyx_L6_error:; + /*exception exit:*/{ + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __pyx_t_7 = 0; __pyx_t_8 = 0; __pyx_t_9 = 0; __pyx_t_10 = 0; __pyx_t_11 = 0; __pyx_t_12 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (PY_MAJOR_VERSION >= 3) __Pyx_ExceptionSwap(&__pyx_t_10, &__pyx_t_11, &__pyx_t_12); + if ((PY_MAJOR_VERSION < 3) || unlikely(__Pyx_GetException(&__pyx_t_7, &__pyx_t_8, &__pyx_t_9) < 0)) __Pyx_ErrFetch(&__pyx_t_7, &__pyx_t_8, &__pyx_t_9); + __Pyx_XGOTREF(__pyx_t_7); + __Pyx_XGOTREF(__pyx_t_8); + __Pyx_XGOTREF(__pyx_t_9); + __Pyx_XGOTREF(__pyx_t_10); + __Pyx_XGOTREF(__pyx_t_11); + __Pyx_XGOTREF(__pyx_t_12); + __pyx_t_4 = __pyx_lineno; __pyx_t_5 = __pyx_clineno; __pyx_t_6 = __pyx_filename; + { + PyMem_Free(__pyx_v_tmp); + } + if (PY_MAJOR_VERSION >= 3) { + __Pyx_XGIVEREF(__pyx_t_10); + __Pyx_XGIVEREF(__pyx_t_11); + __Pyx_XGIVEREF(__pyx_t_12); + __Pyx_ExceptionReset(__pyx_t_10, __pyx_t_11, __pyx_t_12); + } + __Pyx_XGIVEREF(__pyx_t_7); + __Pyx_XGIVEREF(__pyx_t_8); + __Pyx_XGIVEREF(__pyx_t_9); + __Pyx_ErrRestore(__pyx_t_7, __pyx_t_8, __pyx_t_9); + __pyx_t_7 = 0; __pyx_t_8 = 0; __pyx_t_9 = 0; __pyx_t_10 = 0; __pyx_t_11 = 0; __pyx_t_12 = 0; + __pyx_lineno = __pyx_t_4; __pyx_clineno = __pyx_t_5; __pyx_filename = __pyx_t_6; + goto __pyx_L1_error; + } + __pyx_L7:; + } + + /* "View.MemoryView":453 + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) + * + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): # <<<<<<<<<<<<<< + * cdef int array[128] + * cdef void *tmp = NULL + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.setitem_slice_assign_scalar", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":485 + * PyMem_Free(tmp) + * + * cdef setitem_indexed(self, index, value): # <<<<<<<<<<<<<< + * cdef char *itemp = self.get_item_pointer(index) + * self.assign_item_from_object(itemp, value) + */ + +static PyObject *__pyx_memoryview_setitem_indexed(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value) { + char *__pyx_v_itemp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + char *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("setitem_indexed", 1); + + /* "View.MemoryView":486 + * + * cdef setitem_indexed(self, index, value): + * cdef char *itemp = self.get_item_pointer(index) # <<<<<<<<<<<<<< + * self.assign_item_from_object(itemp, value) + * + */ + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->get_item_pointer(__pyx_v_self, __pyx_v_index); if (unlikely(__pyx_t_1 == ((char *)NULL))) __PYX_ERR(1, 486, __pyx_L1_error) + __pyx_v_itemp = __pyx_t_1; + + /* "View.MemoryView":487 + * cdef setitem_indexed(self, index, value): + * cdef char *itemp = self.get_item_pointer(index) + * self.assign_item_from_object(itemp, value) # <<<<<<<<<<<<<< + * + * cdef convert_item_to_object(self, char *itemp): + */ + __pyx_t_2 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->assign_item_from_object(__pyx_v_self, __pyx_v_itemp, __pyx_v_value); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 487, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":485 + * PyMem_Free(tmp) + * + * cdef setitem_indexed(self, index, value): # <<<<<<<<<<<<<< + * cdef char *itemp = self.get_item_pointer(index) + * self.assign_item_from_object(itemp, value) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.setitem_indexed", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":489 + * self.assign_item_from_object(itemp, value) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + +static PyObject *__pyx_memoryview_convert_item_to_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp) { + PyObject *__pyx_v_struct = NULL; + PyObject *__pyx_v_bytesitem = 0; + PyObject *__pyx_v_result = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + int __pyx_t_8; + Py_ssize_t __pyx_t_9; + int __pyx_t_10; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("convert_item_to_object", 1); + + /* "View.MemoryView":492 + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + * import struct # <<<<<<<<<<<<<< + * cdef bytes bytesitem + * + */ + __pyx_t_1 = __Pyx_ImportDottedModule(__pyx_n_s_struct, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 492, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_struct = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":495 + * cdef bytes bytesitem + * + * bytesitem = itemp[:self.view.itemsize] # <<<<<<<<<<<<<< + * try: + * result = struct.unpack(self.view.format, bytesitem) + */ + __pyx_t_1 = __Pyx_PyBytes_FromStringAndSize(__pyx_v_itemp + 0, __pyx_v_self->view.itemsize - 0); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 495, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_bytesitem = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":496 + * + * bytesitem = itemp[:self.view.itemsize] + * try: # <<<<<<<<<<<<<< + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_2, &__pyx_t_3, &__pyx_t_4); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_4); + /*try:*/ { + + /* "View.MemoryView":497 + * bytesitem = itemp[:self.view.itemsize] + * try: + * result = struct.unpack(self.view.format, bytesitem) # <<<<<<<<<<<<<< + * except struct.error: + * raise ValueError, "Unable to convert item to object" + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_unpack); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 497, __pyx_L3_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = __Pyx_PyBytes_FromString(__pyx_v_self->view.format); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 497, __pyx_L3_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_7 = NULL; + __pyx_t_8 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_8 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_7, __pyx_t_6, __pyx_v_bytesitem}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_8, 2+__pyx_t_8); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 497, __pyx_L3_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + __pyx_v_result = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":496 + * + * bytesitem = itemp[:self.view.itemsize] + * try: # <<<<<<<<<<<<<< + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + */ + } + + /* "View.MemoryView":501 + * raise ValueError, "Unable to convert item to object" + * else: + * if len(self.view.format) == 1: # <<<<<<<<<<<<<< + * return result[0] + * return result + */ + /*else:*/ { + __pyx_t_9 = __Pyx_ssize_strlen(__pyx_v_self->view.format); if (unlikely(__pyx_t_9 == ((Py_ssize_t)-1))) __PYX_ERR(1, 501, __pyx_L5_except_error) + __pyx_t_10 = (__pyx_t_9 == 1); + if (__pyx_t_10) { + + /* "View.MemoryView":502 + * else: + * if len(self.view.format) == 1: + * return result[0] # <<<<<<<<<<<<<< + * return result + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_result, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 502, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L6_except_return; + + /* "View.MemoryView":501 + * raise ValueError, "Unable to convert item to object" + * else: + * if len(self.view.format) == 1: # <<<<<<<<<<<<<< + * return result[0] + * return result + */ + } + + /* "View.MemoryView":503 + * if len(self.view.format) == 1: + * return result[0] + * return result # <<<<<<<<<<<<<< + * + * cdef assign_item_from_object(self, char *itemp, object value): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_result); + __pyx_r = __pyx_v_result; + goto __pyx_L6_except_return; + } + __pyx_L3_error:; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":498 + * try: + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: # <<<<<<<<<<<<<< + * raise ValueError, "Unable to convert item to object" + * else: + */ + __Pyx_ErrFetch(&__pyx_t_1, &__pyx_t_5, &__pyx_t_6); + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_error); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 498, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_8 = __Pyx_PyErr_GivenExceptionMatches(__pyx_t_1, __pyx_t_7); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_ErrRestore(__pyx_t_1, __pyx_t_5, __pyx_t_6); + __pyx_t_1 = 0; __pyx_t_5 = 0; __pyx_t_6 = 0; + if (__pyx_t_8) { + __Pyx_AddTraceback("View.MemoryView.memoryview.convert_item_to_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_6, &__pyx_t_5, &__pyx_t_1) < 0) __PYX_ERR(1, 498, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_1); + + /* "View.MemoryView":499 + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + * raise ValueError, "Unable to convert item to object" # <<<<<<<<<<<<<< + * else: + * if len(self.view.format) == 1: + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Unable_to_convert_item_to_object, 0, 0); + __PYX_ERR(1, 499, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "View.MemoryView":496 + * + * bytesitem = itemp[:self.view.itemsize] + * try: # <<<<<<<<<<<<<< + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_ExceptionReset(__pyx_t_2, __pyx_t_3, __pyx_t_4); + goto __pyx_L1_error; + __pyx_L6_except_return:; + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_ExceptionReset(__pyx_t_2, __pyx_t_3, __pyx_t_4); + goto __pyx_L0; + } + + /* "View.MemoryView":489 + * self.assign_item_from_object(itemp, value) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("View.MemoryView.memoryview.convert_item_to_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_struct); + __Pyx_XDECREF(__pyx_v_bytesitem); + __Pyx_XDECREF(__pyx_v_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":505 + * return result + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + +static PyObject *__pyx_memoryview_assign_item_from_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value) { + PyObject *__pyx_v_struct = NULL; + char __pyx_v_c; + PyObject *__pyx_v_bytesvalue = 0; + Py_ssize_t __pyx_v_i; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + Py_ssize_t __pyx_t_7; + PyObject *__pyx_t_8 = NULL; + char *__pyx_t_9; + char *__pyx_t_10; + char *__pyx_t_11; + char *__pyx_t_12; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("assign_item_from_object", 1); + + /* "View.MemoryView":508 + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + * import struct # <<<<<<<<<<<<<< + * cdef char c + * cdef bytes bytesvalue + */ + __pyx_t_1 = __Pyx_ImportDottedModule(__pyx_n_s_struct, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 508, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_struct = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":513 + * cdef Py_ssize_t i + * + * if isinstance(value, tuple): # <<<<<<<<<<<<<< + * bytesvalue = struct.pack(self.view.format, *value) + * else: + */ + __pyx_t_2 = PyTuple_Check(__pyx_v_value); + if (__pyx_t_2) { + + /* "View.MemoryView":514 + * + * if isinstance(value, tuple): + * bytesvalue = struct.pack(self.view.format, *value) # <<<<<<<<<<<<<< + * else: + * bytesvalue = struct.pack(self.view.format, value) + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_pack); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyBytes_FromString(__pyx_v_self->view.format); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PyTuple_New(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_3)) __PYX_ERR(1, 514, __pyx_L1_error); + __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PySequence_Tuple(__pyx_v_value); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = PyNumber_Add(__pyx_t_4, __pyx_t_3); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PyObject_Call(__pyx_t_1, __pyx_t_5, NULL); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (!(likely(PyBytes_CheckExact(__pyx_t_3))||((__pyx_t_3) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_t_3))) __PYX_ERR(1, 514, __pyx_L1_error) + __pyx_v_bytesvalue = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":513 + * cdef Py_ssize_t i + * + * if isinstance(value, tuple): # <<<<<<<<<<<<<< + * bytesvalue = struct.pack(self.view.format, *value) + * else: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":516 + * bytesvalue = struct.pack(self.view.format, *value) + * else: + * bytesvalue = struct.pack(self.view.format, value) # <<<<<<<<<<<<<< + * + * for i, c in enumerate(bytesvalue): + */ + /*else*/ { + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_pack); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 516, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 = __Pyx_PyBytes_FromString(__pyx_v_self->view.format); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 516, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_4 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_4, __pyx_t_1, __pyx_v_value}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 516, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + if (!(likely(PyBytes_CheckExact(__pyx_t_3))||((__pyx_t_3) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_t_3))) __PYX_ERR(1, 516, __pyx_L1_error) + __pyx_v_bytesvalue = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; + } + __pyx_L3:; + + /* "View.MemoryView":518 + * bytesvalue = struct.pack(self.view.format, value) + * + * for i, c in enumerate(bytesvalue): # <<<<<<<<<<<<<< + * itemp[i] = c + * + */ + __pyx_t_7 = 0; + if (unlikely(__pyx_v_bytesvalue == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' is not iterable"); + __PYX_ERR(1, 518, __pyx_L1_error) + } + __Pyx_INCREF(__pyx_v_bytesvalue); + __pyx_t_8 = __pyx_v_bytesvalue; + __pyx_t_10 = PyBytes_AS_STRING(__pyx_t_8); + __pyx_t_11 = (__pyx_t_10 + PyBytes_GET_SIZE(__pyx_t_8)); + for (__pyx_t_12 = __pyx_t_10; __pyx_t_12 < __pyx_t_11; __pyx_t_12++) { + __pyx_t_9 = __pyx_t_12; + __pyx_v_c = (__pyx_t_9[0]); + + /* "View.MemoryView":519 + * + * for i, c in enumerate(bytesvalue): + * itemp[i] = c # <<<<<<<<<<<<<< + * + * @cname('getbuffer') + */ + __pyx_v_i = __pyx_t_7; + + /* "View.MemoryView":518 + * bytesvalue = struct.pack(self.view.format, value) + * + * for i, c in enumerate(bytesvalue): # <<<<<<<<<<<<<< + * itemp[i] = c + * + */ + __pyx_t_7 = (__pyx_t_7 + 1); + + /* "View.MemoryView":519 + * + * for i, c in enumerate(bytesvalue): + * itemp[i] = c # <<<<<<<<<<<<<< + * + * @cname('getbuffer') + */ + (__pyx_v_itemp[__pyx_v_i]) = __pyx_v_c; + } + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + + /* "View.MemoryView":505 + * return result + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("View.MemoryView.memoryview.assign_item_from_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_struct); + __Pyx_XDECREF(__pyx_v_bytesvalue); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":521 + * itemp[i] = c + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: + */ + +/* Python wrapper */ +CYTHON_UNUSED static int __pyx_memoryview_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +CYTHON_UNUSED static int __pyx_memoryview_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getbuffer__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_8__getbuffer__(((struct __pyx_memoryview_obj *)__pyx_v_self), ((Py_buffer *)__pyx_v_info), ((int)__pyx_v_flags)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_8__getbuffer__(struct __pyx_memoryview_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + Py_ssize_t *__pyx_t_3; + char *__pyx_t_4; + void *__pyx_t_5; + int __pyx_t_6; + Py_ssize_t __pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + if (unlikely(__pyx_v_info == NULL)) { + PyErr_SetString(PyExc_BufferError, "PyObject_GetBuffer: view==NULL argument is obsolete"); + return -1; + } + __Pyx_RefNannySetupContext("__getbuffer__", 0); + __pyx_v_info->obj = Py_None; __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(__pyx_v_info->obj); + + /* "View.MemoryView":523 + * @cname('getbuffer') + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: # <<<<<<<<<<<<<< + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + */ + __pyx_t_2 = ((__pyx_v_flags & PyBUF_WRITABLE) != 0); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_1 = __pyx_v_self->view.readonly; + __pyx_L4_bool_binop_done:; + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":524 + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: + * raise ValueError, "Cannot create writable memory view from read-only memoryview" # <<<<<<<<<<<<<< + * + * if flags & PyBUF_ND: + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Cannot_create_writable_memory_vi, 0, 0); + __PYX_ERR(1, 524, __pyx_L1_error) + + /* "View.MemoryView":523 + * @cname('getbuffer') + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: # <<<<<<<<<<<<<< + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + */ + } + + /* "View.MemoryView":526 + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + * if flags & PyBUF_ND: # <<<<<<<<<<<<<< + * info.shape = self.view.shape + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_ND) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":527 + * + * if flags & PyBUF_ND: + * info.shape = self.view.shape # <<<<<<<<<<<<<< + * else: + * info.shape = NULL + */ + __pyx_t_3 = __pyx_v_self->view.shape; + __pyx_v_info->shape = __pyx_t_3; + + /* "View.MemoryView":526 + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + * if flags & PyBUF_ND: # <<<<<<<<<<<<<< + * info.shape = self.view.shape + * else: + */ + goto __pyx_L6; + } + + /* "View.MemoryView":529 + * info.shape = self.view.shape + * else: + * info.shape = NULL # <<<<<<<<<<<<<< + * + * if flags & PyBUF_STRIDES: + */ + /*else*/ { + __pyx_v_info->shape = NULL; + } + __pyx_L6:; + + /* "View.MemoryView":531 + * info.shape = NULL + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.strides = self.view.strides + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_STRIDES) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":532 + * + * if flags & PyBUF_STRIDES: + * info.strides = self.view.strides # <<<<<<<<<<<<<< + * else: + * info.strides = NULL + */ + __pyx_t_3 = __pyx_v_self->view.strides; + __pyx_v_info->strides = __pyx_t_3; + + /* "View.MemoryView":531 + * info.shape = NULL + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.strides = self.view.strides + * else: + */ + goto __pyx_L7; + } + + /* "View.MemoryView":534 + * info.strides = self.view.strides + * else: + * info.strides = NULL # <<<<<<<<<<<<<< + * + * if flags & PyBUF_INDIRECT: + */ + /*else*/ { + __pyx_v_info->strides = NULL; + } + __pyx_L7:; + + /* "View.MemoryView":536 + * info.strides = NULL + * + * if flags & PyBUF_INDIRECT: # <<<<<<<<<<<<<< + * info.suboffsets = self.view.suboffsets + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_INDIRECT) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":537 + * + * if flags & PyBUF_INDIRECT: + * info.suboffsets = self.view.suboffsets # <<<<<<<<<<<<<< + * else: + * info.suboffsets = NULL + */ + __pyx_t_3 = __pyx_v_self->view.suboffsets; + __pyx_v_info->suboffsets = __pyx_t_3; + + /* "View.MemoryView":536 + * info.strides = NULL + * + * if flags & PyBUF_INDIRECT: # <<<<<<<<<<<<<< + * info.suboffsets = self.view.suboffsets + * else: + */ + goto __pyx_L8; + } + + /* "View.MemoryView":539 + * info.suboffsets = self.view.suboffsets + * else: + * info.suboffsets = NULL # <<<<<<<<<<<<<< + * + * if flags & PyBUF_FORMAT: + */ + /*else*/ { + __pyx_v_info->suboffsets = NULL; + } + __pyx_L8:; + + /* "View.MemoryView":541 + * info.suboffsets = NULL + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * info.format = self.view.format + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_FORMAT) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":542 + * + * if flags & PyBUF_FORMAT: + * info.format = self.view.format # <<<<<<<<<<<<<< + * else: + * info.format = NULL + */ + __pyx_t_4 = __pyx_v_self->view.format; + __pyx_v_info->format = __pyx_t_4; + + /* "View.MemoryView":541 + * info.suboffsets = NULL + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * info.format = self.view.format + * else: + */ + goto __pyx_L9; + } + + /* "View.MemoryView":544 + * info.format = self.view.format + * else: + * info.format = NULL # <<<<<<<<<<<<<< + * + * info.buf = self.view.buf + */ + /*else*/ { + __pyx_v_info->format = NULL; + } + __pyx_L9:; + + /* "View.MemoryView":546 + * info.format = NULL + * + * info.buf = self.view.buf # <<<<<<<<<<<<<< + * info.ndim = self.view.ndim + * info.itemsize = self.view.itemsize + */ + __pyx_t_5 = __pyx_v_self->view.buf; + __pyx_v_info->buf = __pyx_t_5; + + /* "View.MemoryView":547 + * + * info.buf = self.view.buf + * info.ndim = self.view.ndim # <<<<<<<<<<<<<< + * info.itemsize = self.view.itemsize + * info.len = self.view.len + */ + __pyx_t_6 = __pyx_v_self->view.ndim; + __pyx_v_info->ndim = __pyx_t_6; + + /* "View.MemoryView":548 + * info.buf = self.view.buf + * info.ndim = self.view.ndim + * info.itemsize = self.view.itemsize # <<<<<<<<<<<<<< + * info.len = self.view.len + * info.readonly = self.view.readonly + */ + __pyx_t_7 = __pyx_v_self->view.itemsize; + __pyx_v_info->itemsize = __pyx_t_7; + + /* "View.MemoryView":549 + * info.ndim = self.view.ndim + * info.itemsize = self.view.itemsize + * info.len = self.view.len # <<<<<<<<<<<<<< + * info.readonly = self.view.readonly + * info.obj = self + */ + __pyx_t_7 = __pyx_v_self->view.len; + __pyx_v_info->len = __pyx_t_7; + + /* "View.MemoryView":550 + * info.itemsize = self.view.itemsize + * info.len = self.view.len + * info.readonly = self.view.readonly # <<<<<<<<<<<<<< + * info.obj = self + * + */ + __pyx_t_1 = __pyx_v_self->view.readonly; + __pyx_v_info->readonly = __pyx_t_1; + + /* "View.MemoryView":551 + * info.len = self.view.len + * info.readonly = self.view.readonly + * info.obj = self # <<<<<<<<<<<<<< + * + * + */ + __Pyx_INCREF((PyObject *)__pyx_v_self); + __Pyx_GIVEREF((PyObject *)__pyx_v_self); + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); + __pyx_v_info->obj = ((PyObject *)__pyx_v_self); + + /* "View.MemoryView":521 + * itemp[i] = c + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__getbuffer__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + if (__pyx_v_info->obj != NULL) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + goto __pyx_L2; + __pyx_L0:; + if (__pyx_v_info->obj == Py_None) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + __pyx_L2:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":554 + * + * + * @property # <<<<<<<<<<<<<< + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_1T_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_1T_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_1T___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_1T___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + struct __pyx_memoryviewslice_obj *__pyx_v_result = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":556 + * @property + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) # <<<<<<<<<<<<<< + * transpose_memslice(&result.from_slice) + * return result + */ + __pyx_t_1 = __pyx_memoryview_copy_object(__pyx_v_self); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 556, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (!(likely(((__pyx_t_1) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_1, __pyx_memoryviewslice_type))))) __PYX_ERR(1, 556, __pyx_L1_error) + __pyx_v_result = ((struct __pyx_memoryviewslice_obj *)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":557 + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) + * transpose_memslice(&result.from_slice) # <<<<<<<<<<<<<< + * return result + * + */ + __pyx_t_2 = __pyx_memslice_transpose((&__pyx_v_result->from_slice)); if (unlikely(__pyx_t_2 == ((int)-1))) __PYX_ERR(1, 557, __pyx_L1_error) + + /* "View.MemoryView":558 + * cdef _memoryviewslice result = memoryview_copy(self) + * transpose_memslice(&result.from_slice) + * return result # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = ((PyObject *)__pyx_v_result); + goto __pyx_L0; + + /* "View.MemoryView":554 + * + * + * @property # <<<<<<<<<<<<<< + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.T.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":560 + * return result + * + * @property # <<<<<<<<<<<<<< + * def base(self): + * return self._get_base() + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4base_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4base_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_4base___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4base___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":562 + * @property + * def base(self): + * return self._get_base() # <<<<<<<<<<<<<< + * + * cdef _get_base(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->_get_base(__pyx_v_self); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 562, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":560 + * return result + * + * @property # <<<<<<<<<<<<<< + * def base(self): + * return self._get_base() + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.base.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":564 + * return self._get_base() + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.obj + * + */ + +static PyObject *__pyx_memoryview__get_base(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("_get_base", 1); + + /* "View.MemoryView":565 + * + * cdef _get_base(self): + * return self.obj # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->obj); + __pyx_r = __pyx_v_self->obj; + goto __pyx_L0; + + /* "View.MemoryView":564 + * return self._get_base() + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.obj + * + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":567 + * return self.obj + * + * @property # <<<<<<<<<<<<<< + * def shape(self): + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_5shape_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_5shape_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_5shape___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_5shape___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_7genexpr__pyx_v_length; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + PyObject *__pyx_t_5 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":569 + * @property + * def shape(self): + * return tuple([length for length in self.view.shape[:self.view.ndim]]) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + { /* enter inner scope */ + __pyx_t_1 = PyList_New(0); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 569, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = (__pyx_v_self->view.shape + __pyx_v_self->view.ndim); + for (__pyx_t_4 = __pyx_v_self->view.shape; __pyx_t_4 < __pyx_t_3; __pyx_t_4++) { + __pyx_t_2 = __pyx_t_4; + __pyx_7genexpr__pyx_v_length = (__pyx_t_2[0]); + __pyx_t_5 = PyInt_FromSsize_t(__pyx_7genexpr__pyx_v_length); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 569, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_1, (PyObject*)__pyx_t_5))) __PYX_ERR(1, 569, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + } /* exit inner scope */ + __pyx_t_5 = PyList_AsTuple(((PyObject*)__pyx_t_1)); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 569, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_5; + __pyx_t_5 = 0; + goto __pyx_L0; + + /* "View.MemoryView":567 + * return self.obj + * + * @property # <<<<<<<<<<<<<< + * def shape(self): + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.memoryview.shape.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":571 + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def strides(self): + * if self.view.strides == NULL: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_7strides_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_7strides_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_7strides___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_7strides___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_8genexpr1__pyx_v_stride; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + Py_ssize_t *__pyx_t_5; + PyObject *__pyx_t_6 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":573 + * @property + * def strides(self): + * if self.view.strides == NULL: # <<<<<<<<<<<<<< + * + * raise ValueError, "Buffer view does not expose strides" + */ + __pyx_t_1 = (__pyx_v_self->view.strides == NULL); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":575 + * if self.view.strides == NULL: + * + * raise ValueError, "Buffer view does not expose strides" # <<<<<<<<<<<<<< + * + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Buffer_view_does_not_expose_stri, 0, 0); + __PYX_ERR(1, 575, __pyx_L1_error) + + /* "View.MemoryView":573 + * @property + * def strides(self): + * if self.view.strides == NULL: # <<<<<<<<<<<<<< + * + * raise ValueError, "Buffer view does not expose strides" + */ + } + + /* "View.MemoryView":577 + * raise ValueError, "Buffer view does not expose strides" + * + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + { /* enter inner scope */ + __pyx_t_2 = PyList_New(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 577, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = (__pyx_v_self->view.strides + __pyx_v_self->view.ndim); + for (__pyx_t_5 = __pyx_v_self->view.strides; __pyx_t_5 < __pyx_t_4; __pyx_t_5++) { + __pyx_t_3 = __pyx_t_5; + __pyx_8genexpr1__pyx_v_stride = (__pyx_t_3[0]); + __pyx_t_6 = PyInt_FromSsize_t(__pyx_8genexpr1__pyx_v_stride); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 577, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_2, (PyObject*)__pyx_t_6))) __PYX_ERR(1, 577, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + } /* exit inner scope */ + __pyx_t_6 = PyList_AsTuple(((PyObject*)__pyx_t_2)); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 577, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_6; + __pyx_t_6 = 0; + goto __pyx_L0; + + /* "View.MemoryView":571 + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def strides(self): + * if self.view.strides == NULL: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("View.MemoryView.memoryview.strides.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":579 + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def suboffsets(self): + * if self.view.suboffsets == NULL: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_10suboffsets_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_10suboffsets_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_10suboffsets___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_10suboffsets___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_8genexpr2__pyx_v_suboffset; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + Py_ssize_t *__pyx_t_5; + PyObject *__pyx_t_6 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":581 + * @property + * def suboffsets(self): + * if self.view.suboffsets == NULL: # <<<<<<<<<<<<<< + * return (-1,) * self.view.ndim + * + */ + __pyx_t_1 = (__pyx_v_self->view.suboffsets == NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":582 + * def suboffsets(self): + * if self.view.suboffsets == NULL: + * return (-1,) * self.view.ndim # <<<<<<<<<<<<<< + * + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PySequence_Multiply(__pyx_tuple__4, __pyx_v_self->view.ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 582, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":581 + * @property + * def suboffsets(self): + * if self.view.suboffsets == NULL: # <<<<<<<<<<<<<< + * return (-1,) * self.view.ndim + * + */ + } + + /* "View.MemoryView":584 + * return (-1,) * self.view.ndim + * + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + { /* enter inner scope */ + __pyx_t_2 = PyList_New(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 584, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = (__pyx_v_self->view.suboffsets + __pyx_v_self->view.ndim); + for (__pyx_t_5 = __pyx_v_self->view.suboffsets; __pyx_t_5 < __pyx_t_4; __pyx_t_5++) { + __pyx_t_3 = __pyx_t_5; + __pyx_8genexpr2__pyx_v_suboffset = (__pyx_t_3[0]); + __pyx_t_6 = PyInt_FromSsize_t(__pyx_8genexpr2__pyx_v_suboffset); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 584, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_2, (PyObject*)__pyx_t_6))) __PYX_ERR(1, 584, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + } /* exit inner scope */ + __pyx_t_6 = PyList_AsTuple(((PyObject*)__pyx_t_2)); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 584, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_6; + __pyx_t_6 = 0; + goto __pyx_L0; + + /* "View.MemoryView":579 + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def suboffsets(self): + * if self.view.suboffsets == NULL: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("View.MemoryView.memoryview.suboffsets.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":586 + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def ndim(self): + * return self.view.ndim + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4ndim_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4ndim_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_4ndim___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4ndim___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":588 + * @property + * def ndim(self): + * return self.view.ndim # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_self->view.ndim); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 588, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":586 + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def ndim(self): + * return self.view.ndim + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.ndim.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":590 + * return self.view.ndim + * + * @property # <<<<<<<<<<<<<< + * def itemsize(self): + * return self.view.itemsize + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_8itemsize_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_8itemsize_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_8itemsize___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_8itemsize___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":592 + * @property + * def itemsize(self): + * return self.view.itemsize # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyInt_FromSsize_t(__pyx_v_self->view.itemsize); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 592, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":590 + * return self.view.ndim + * + * @property # <<<<<<<<<<<<<< + * def itemsize(self): + * return self.view.itemsize + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.itemsize.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":594 + * return self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def nbytes(self): + * return self.size * self.view.itemsize + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_6nbytes_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_6nbytes_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_6nbytes___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_6nbytes___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":596 + * @property + * def nbytes(self): + * return self.size * self.view.itemsize # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_size); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 596, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = PyInt_FromSsize_t(__pyx_v_self->view.itemsize); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 596, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyNumber_Multiply(__pyx_t_1, __pyx_t_2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 596, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_3; + __pyx_t_3 = 0; + goto __pyx_L0; + + /* "View.MemoryView":594 + * return self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def nbytes(self): + * return self.size * self.view.itemsize + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.nbytes.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":598 + * return self.size * self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def size(self): + * if self._size is None: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4size_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4size_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_4size___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4size___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_v_result = NULL; + PyObject *__pyx_v_length = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + PyObject *__pyx_t_5 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":600 + * @property + * def size(self): + * if self._size is None: # <<<<<<<<<<<<<< + * result = 1 + * + */ + __pyx_t_1 = (__pyx_v_self->_size == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":601 + * def size(self): + * if self._size is None: + * result = 1 # <<<<<<<<<<<<<< + * + * for length in self.view.shape[:self.view.ndim]: + */ + __Pyx_INCREF(__pyx_int_1); + __pyx_v_result = __pyx_int_1; + + /* "View.MemoryView":603 + * result = 1 + * + * for length in self.view.shape[:self.view.ndim]: # <<<<<<<<<<<<<< + * result *= length + * + */ + __pyx_t_3 = (__pyx_v_self->view.shape + __pyx_v_self->view.ndim); + for (__pyx_t_4 = __pyx_v_self->view.shape; __pyx_t_4 < __pyx_t_3; __pyx_t_4++) { + __pyx_t_2 = __pyx_t_4; + __pyx_t_5 = PyInt_FromSsize_t((__pyx_t_2[0])); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 603, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_XDECREF_SET(__pyx_v_length, __pyx_t_5); + __pyx_t_5 = 0; + + /* "View.MemoryView":604 + * + * for length in self.view.shape[:self.view.ndim]: + * result *= length # <<<<<<<<<<<<<< + * + * self._size = result + */ + __pyx_t_5 = PyNumber_InPlaceMultiply(__pyx_v_result, __pyx_v_length); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 604, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF_SET(__pyx_v_result, __pyx_t_5); + __pyx_t_5 = 0; + } + + /* "View.MemoryView":606 + * result *= length + * + * self._size = result # <<<<<<<<<<<<<< + * + * return self._size + */ + __Pyx_INCREF(__pyx_v_result); + __Pyx_GIVEREF(__pyx_v_result); + __Pyx_GOTREF(__pyx_v_self->_size); + __Pyx_DECREF(__pyx_v_self->_size); + __pyx_v_self->_size = __pyx_v_result; + + /* "View.MemoryView":600 + * @property + * def size(self): + * if self._size is None: # <<<<<<<<<<<<<< + * result = 1 + * + */ + } + + /* "View.MemoryView":608 + * self._size = result + * + * return self._size # <<<<<<<<<<<<<< + * + * def __len__(self): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->_size); + __pyx_r = __pyx_v_self->_size; + goto __pyx_L0; + + /* "View.MemoryView":598 + * return self.size * self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def size(self): + * if self._size is None: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.memoryview.size.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_result); + __Pyx_XDECREF(__pyx_v_length); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":610 + * return self._size + * + * def __len__(self): # <<<<<<<<<<<<<< + * if self.view.ndim >= 1: + * return self.view.shape[0] + */ + +/* Python wrapper */ +static Py_ssize_t __pyx_memoryview___len__(PyObject *__pyx_v_self); /*proto*/ +static Py_ssize_t __pyx_memoryview___len__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + Py_ssize_t __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__len__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_10__len__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static Py_ssize_t __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_10__len__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_r; + int __pyx_t_1; + + /* "View.MemoryView":611 + * + * def __len__(self): + * if self.view.ndim >= 1: # <<<<<<<<<<<<<< + * return self.view.shape[0] + * + */ + __pyx_t_1 = (__pyx_v_self->view.ndim >= 1); + if (__pyx_t_1) { + + /* "View.MemoryView":612 + * def __len__(self): + * if self.view.ndim >= 1: + * return self.view.shape[0] # <<<<<<<<<<<<<< + * + * return 0 + */ + __pyx_r = (__pyx_v_self->view.shape[0]); + goto __pyx_L0; + + /* "View.MemoryView":611 + * + * def __len__(self): + * if self.view.ndim >= 1: # <<<<<<<<<<<<<< + * return self.view.shape[0] + * + */ + } + + /* "View.MemoryView":614 + * return self.view.shape[0] + * + * return 0 # <<<<<<<<<<<<<< + * + * def __repr__(self): + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":610 + * return self._size + * + * def __len__(self): # <<<<<<<<<<<<<< + * if self.view.ndim >= 1: + * return self.view.shape[0] + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":616 + * return 0 + * + * def __repr__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__, + * id(self)) + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview___repr__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_memoryview___repr__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__repr__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_12__repr__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_12__repr__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__repr__", 1); + + /* "View.MemoryView":617 + * + * def __repr__(self): + * return "" % (self.base.__class__.__name__, # <<<<<<<<<<<<<< + * id(self)) + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_base); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_class); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_name_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":618 + * def __repr__(self): + * return "" % (self.base.__class__.__name__, + * id(self)) # <<<<<<<<<<<<<< + * + * def __str__(self): + */ + __pyx_t_2 = __Pyx_PyObject_CallOneArg(__pyx_builtin_id, ((PyObject *)__pyx_v_self)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 618, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + + /* "View.MemoryView":617 + * + * def __repr__(self): + * return "" % (self.base.__class__.__name__, # <<<<<<<<<<<<<< + * id(self)) + * + */ + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_1)) __PYX_ERR(1, 617, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_2)) __PYX_ERR(1, 617, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyString_Format(__pyx_kp_s_MemoryView_of_r_at_0x_x, __pyx_t_3); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":616 + * return 0 + * + * def __repr__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__, + * id(self)) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.__repr__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":620 + * id(self)) + * + * def __str__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__,) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview___str__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_memoryview___str__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__str__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_14__str__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_14__str__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__str__", 1); + + /* "View.MemoryView":621 + * + * def __str__(self): + * return "" % (self.base.__class__.__name__,) # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_base); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_class); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_name_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = PyTuple_New(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_t_1)) __PYX_ERR(1, 621, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_MemoryView_of_r_object, __pyx_t_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":620 + * id(self)) + * + * def __str__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__,) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.__str__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":624 + * + * + * def is_c_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_is_c_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_is_c_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("is_c_contig (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("is_c_contig", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "is_c_contig", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_16is_c_contig(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_16is_c_contig(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice *__pyx_v_mslice; + __Pyx_memviewslice __pyx_v_tmp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("is_c_contig", 1); + + /* "View.MemoryView":627 + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) # <<<<<<<<<<<<<< + * return slice_is_contig(mslice[0], 'C', self.view.ndim) + * + */ + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(__pyx_v_self, (&__pyx_v_tmp)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 627, __pyx_L1_error) + __pyx_v_mslice = __pyx_t_1; + + /* "View.MemoryView":628 + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) + * return slice_is_contig(mslice[0], 'C', self.view.ndim) # <<<<<<<<<<<<<< + * + * def is_f_contig(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_memviewslice_is_contig((__pyx_v_mslice[0]), 'C', __pyx_v_self->view.ndim)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 628, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":624 + * + * + * def is_c_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.is_c_contig", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":630 + * return slice_is_contig(mslice[0], 'C', self.view.ndim) + * + * def is_f_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_is_f_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_is_f_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("is_f_contig (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("is_f_contig", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "is_f_contig", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_18is_f_contig(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_18is_f_contig(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice *__pyx_v_mslice; + __Pyx_memviewslice __pyx_v_tmp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("is_f_contig", 1); + + /* "View.MemoryView":633 + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) # <<<<<<<<<<<<<< + * return slice_is_contig(mslice[0], 'F', self.view.ndim) + * + */ + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(__pyx_v_self, (&__pyx_v_tmp)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 633, __pyx_L1_error) + __pyx_v_mslice = __pyx_t_1; + + /* "View.MemoryView":634 + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) + * return slice_is_contig(mslice[0], 'F', self.view.ndim) # <<<<<<<<<<<<<< + * + * def copy(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_memviewslice_is_contig((__pyx_v_mslice[0]), 'F', __pyx_v_self->view.ndim)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 634, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":630 + * return slice_is_contig(mslice[0], 'C', self.view.ndim) + * + * def is_f_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.is_f_contig", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":636 + * return slice_is_contig(mslice[0], 'F', self.view.ndim) + * + * def copy(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice mslice + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_copy(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_copy(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("copy (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("copy", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "copy", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_20copy(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_20copy(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice __pyx_v_mslice; + int __pyx_v_flags; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("copy", 1); + + /* "View.MemoryView":638 + * def copy(self): + * cdef __Pyx_memviewslice mslice + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS # <<<<<<<<<<<<<< + * + * slice_copy(self, &mslice) + */ + __pyx_v_flags = (__pyx_v_self->flags & (~PyBUF_F_CONTIGUOUS)); + + /* "View.MemoryView":640 + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS + * + * slice_copy(self, &mslice) # <<<<<<<<<<<<<< + * mslice = slice_copy_contig(&mslice, "c", self.view.ndim, + * self.view.itemsize, + */ + __pyx_memoryview_slice_copy(__pyx_v_self, (&__pyx_v_mslice)); + + /* "View.MemoryView":641 + * + * slice_copy(self, &mslice) + * mslice = slice_copy_contig(&mslice, "c", self.view.ndim, # <<<<<<<<<<<<<< + * self.view.itemsize, + * flags|PyBUF_C_CONTIGUOUS, + */ + __pyx_t_1 = __pyx_memoryview_copy_new_contig((&__pyx_v_mslice), ((char *)"c"), __pyx_v_self->view.ndim, __pyx_v_self->view.itemsize, (__pyx_v_flags | PyBUF_C_CONTIGUOUS), __pyx_v_self->dtype_is_object); if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 641, __pyx_L1_error) + __pyx_v_mslice = __pyx_t_1; + + /* "View.MemoryView":646 + * self.dtype_is_object) + * + * return memoryview_copy_from_slice(self, &mslice) # <<<<<<<<<<<<<< + * + * def copy_fortran(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_memoryview_copy_object_from_slice(__pyx_v_self, (&__pyx_v_mslice)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 646, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":636 + * return slice_is_contig(mslice[0], 'F', self.view.ndim) + * + * def copy(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice mslice + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.copy", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":648 + * return memoryview_copy_from_slice(self, &mslice) + * + * def copy_fortran(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice src, dst + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_copy_fortran(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_copy_fortran(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("copy_fortran (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("copy_fortran", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "copy_fortran", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_22copy_fortran(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_22copy_fortran(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice __pyx_v_src; + __Pyx_memviewslice __pyx_v_dst; + int __pyx_v_flags; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("copy_fortran", 1); + + /* "View.MemoryView":650 + * def copy_fortran(self): + * cdef __Pyx_memviewslice src, dst + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS # <<<<<<<<<<<<<< + * + * slice_copy(self, &src) + */ + __pyx_v_flags = (__pyx_v_self->flags & (~PyBUF_C_CONTIGUOUS)); + + /* "View.MemoryView":652 + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS + * + * slice_copy(self, &src) # <<<<<<<<<<<<<< + * dst = slice_copy_contig(&src, "fortran", self.view.ndim, + * self.view.itemsize, + */ + __pyx_memoryview_slice_copy(__pyx_v_self, (&__pyx_v_src)); + + /* "View.MemoryView":653 + * + * slice_copy(self, &src) + * dst = slice_copy_contig(&src, "fortran", self.view.ndim, # <<<<<<<<<<<<<< + * self.view.itemsize, + * flags|PyBUF_F_CONTIGUOUS, + */ + __pyx_t_1 = __pyx_memoryview_copy_new_contig((&__pyx_v_src), ((char *)"fortran"), __pyx_v_self->view.ndim, __pyx_v_self->view.itemsize, (__pyx_v_flags | PyBUF_F_CONTIGUOUS), __pyx_v_self->dtype_is_object); if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 653, __pyx_L1_error) + __pyx_v_dst = __pyx_t_1; + + /* "View.MemoryView":658 + * self.dtype_is_object) + * + * return memoryview_copy_from_slice(self, &dst) # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_memoryview_copy_object_from_slice(__pyx_v_self, (&__pyx_v_dst)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 658, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":648 + * return memoryview_copy_from_slice(self, &mslice) + * + * def copy_fortran(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice src, dst + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.copy_fortran", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryview_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryview_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_memoryview___reduce_cython__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryview___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryview_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryview_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.memoryview.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_memoryview_2__setstate_cython__(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryview_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":662 + * + * @cname('__pyx_memoryview_new') + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): # <<<<<<<<<<<<<< + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo + */ + +static PyObject *__pyx_memoryview_new(PyObject *__pyx_v_o, int __pyx_v_flags, int __pyx_v_dtype_is_object, __Pyx_TypeInfo *__pyx_v_typeinfo) { + struct __pyx_memoryview_obj *__pyx_v_result = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_cwrapper", 1); + + /* "View.MemoryView":663 + * @cname('__pyx_memoryview_new') + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): + * cdef memoryview result = memoryview(o, flags, dtype_is_object) # <<<<<<<<<<<<<< + * result.typeinfo = typeinfo + * return result + */ + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_flags); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_v_dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_v_o); + __Pyx_GIVEREF(__pyx_v_o); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_v_o)) __PYX_ERR(1, 663, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1)) __PYX_ERR(1, 663, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_t_2)) __PYX_ERR(1, 663, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_Call(((PyObject *)__pyx_memoryview_type), __pyx_t_3, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_v_result = ((struct __pyx_memoryview_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":664 + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo # <<<<<<<<<<<<<< + * return result + * + */ + __pyx_v_result->typeinfo = __pyx_v_typeinfo; + + /* "View.MemoryView":665 + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo + * return result # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_check') + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = ((PyObject *)__pyx_v_result); + goto __pyx_L0; + + /* "View.MemoryView":662 + * + * @cname('__pyx_memoryview_new') + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): # <<<<<<<<<<<<<< + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview_cwrapper", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":668 + * + * @cname('__pyx_memoryview_check') + * cdef inline bint memoryview_check(object o) noexcept: # <<<<<<<<<<<<<< + * return isinstance(o, memoryview) + * + */ + +static CYTHON_INLINE int __pyx_memoryview_check(PyObject *__pyx_v_o) { + int __pyx_r; + int __pyx_t_1; + + /* "View.MemoryView":669 + * @cname('__pyx_memoryview_check') + * cdef inline bint memoryview_check(object o) noexcept: + * return isinstance(o, memoryview) # <<<<<<<<<<<<<< + * + * cdef tuple _unellipsify(object index, int ndim): + */ + __pyx_t_1 = __Pyx_TypeCheck(__pyx_v_o, __pyx_memoryview_type); + __pyx_r = __pyx_t_1; + goto __pyx_L0; + + /* "View.MemoryView":668 + * + * @cname('__pyx_memoryview_check') + * cdef inline bint memoryview_check(object o) noexcept: # <<<<<<<<<<<<<< + * return isinstance(o, memoryview) + * + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":671 + * return isinstance(o, memoryview) + * + * cdef tuple _unellipsify(object index, int ndim): # <<<<<<<<<<<<<< + * """ + * Replace all ellipses with full slices and fill incomplete indices with + */ + +static PyObject *_unellipsify(PyObject *__pyx_v_index, int __pyx_v_ndim) { + Py_ssize_t __pyx_v_idx; + PyObject *__pyx_v_tup = NULL; + PyObject *__pyx_v_result = NULL; + int __pyx_v_have_slices; + int __pyx_v_seen_ellipsis; + PyObject *__pyx_v_item = NULL; + Py_ssize_t __pyx_v_nslices; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + Py_ssize_t __pyx_t_4; + Py_ssize_t __pyx_t_5; + Py_UCS4 __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("_unellipsify", 1); + + /* "View.MemoryView":677 + * """ + * cdef Py_ssize_t idx + * tup = index if isinstance(index, tuple) else (index,) # <<<<<<<<<<<<<< + * + * result = [slice(None)] * ndim + */ + __pyx_t_2 = PyTuple_Check(__pyx_v_index); + if (__pyx_t_2) { + __Pyx_INCREF(((PyObject*)__pyx_v_index)); + __pyx_t_1 = __pyx_v_index; + } else { + __pyx_t_3 = PyTuple_New(1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 677, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_v_index); + __Pyx_GIVEREF(__pyx_v_index); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_v_index)) __PYX_ERR(1, 677, __pyx_L1_error); + __pyx_t_1 = __pyx_t_3; + __pyx_t_3 = 0; + } + __pyx_v_tup = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":679 + * tup = index if isinstance(index, tuple) else (index,) + * + * result = [slice(None)] * ndim # <<<<<<<<<<<<<< + * have_slices = False + * seen_ellipsis = False + */ + __pyx_t_1 = PyList_New(1 * ((__pyx_v_ndim<0) ? 0:__pyx_v_ndim)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 679, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + { Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < __pyx_v_ndim; __pyx_temp++) { + __Pyx_INCREF(__pyx_slice__5); + __Pyx_GIVEREF(__pyx_slice__5); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, __pyx_temp, __pyx_slice__5)) __PYX_ERR(1, 679, __pyx_L1_error); + } + } + __pyx_v_result = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":680 + * + * result = [slice(None)] * ndim + * have_slices = False # <<<<<<<<<<<<<< + * seen_ellipsis = False + * idx = 0 + */ + __pyx_v_have_slices = 0; + + /* "View.MemoryView":681 + * result = [slice(None)] * ndim + * have_slices = False + * seen_ellipsis = False # <<<<<<<<<<<<<< + * idx = 0 + * for item in tup: + */ + __pyx_v_seen_ellipsis = 0; + + /* "View.MemoryView":682 + * have_slices = False + * seen_ellipsis = False + * idx = 0 # <<<<<<<<<<<<<< + * for item in tup: + * if item is Ellipsis: + */ + __pyx_v_idx = 0; + + /* "View.MemoryView":683 + * seen_ellipsis = False + * idx = 0 + * for item in tup: # <<<<<<<<<<<<<< + * if item is Ellipsis: + * if not seen_ellipsis: + */ + if (unlikely(__pyx_v_tup == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not iterable"); + __PYX_ERR(1, 683, __pyx_L1_error) + } + __pyx_t_1 = __pyx_v_tup; __Pyx_INCREF(__pyx_t_1); + __pyx_t_4 = 0; + for (;;) { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_1); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 683, __pyx_L1_error) + #endif + if (__pyx_t_4 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_3 = PyTuple_GET_ITEM(__pyx_t_1, __pyx_t_4); __Pyx_INCREF(__pyx_t_3); __pyx_t_4++; if (unlikely((0 < 0))) __PYX_ERR(1, 683, __pyx_L1_error) + #else + __pyx_t_3 = __Pyx_PySequence_ITEM(__pyx_t_1, __pyx_t_4); __pyx_t_4++; if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 683, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + #endif + __Pyx_XDECREF_SET(__pyx_v_item, __pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":684 + * idx = 0 + * for item in tup: + * if item is Ellipsis: # <<<<<<<<<<<<<< + * if not seen_ellipsis: + * idx += ndim - len(tup) + */ + __pyx_t_2 = (__pyx_v_item == __pyx_builtin_Ellipsis); + if (__pyx_t_2) { + + /* "View.MemoryView":685 + * for item in tup: + * if item is Ellipsis: + * if not seen_ellipsis: # <<<<<<<<<<<<<< + * idx += ndim - len(tup) + * seen_ellipsis = True + */ + __pyx_t_2 = (!__pyx_v_seen_ellipsis); + if (__pyx_t_2) { + + /* "View.MemoryView":686 + * if item is Ellipsis: + * if not seen_ellipsis: + * idx += ndim - len(tup) # <<<<<<<<<<<<<< + * seen_ellipsis = True + * have_slices = True + */ + if (unlikely(__pyx_v_tup == Py_None)) { + PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); + __PYX_ERR(1, 686, __pyx_L1_error) + } + __pyx_t_5 = __Pyx_PyTuple_GET_SIZE(__pyx_v_tup); if (unlikely(__pyx_t_5 == ((Py_ssize_t)-1))) __PYX_ERR(1, 686, __pyx_L1_error) + __pyx_v_idx = (__pyx_v_idx + (__pyx_v_ndim - __pyx_t_5)); + + /* "View.MemoryView":687 + * if not seen_ellipsis: + * idx += ndim - len(tup) + * seen_ellipsis = True # <<<<<<<<<<<<<< + * have_slices = True + * else: + */ + __pyx_v_seen_ellipsis = 1; + + /* "View.MemoryView":685 + * for item in tup: + * if item is Ellipsis: + * if not seen_ellipsis: # <<<<<<<<<<<<<< + * idx += ndim - len(tup) + * seen_ellipsis = True + */ + } + + /* "View.MemoryView":688 + * idx += ndim - len(tup) + * seen_ellipsis = True + * have_slices = True # <<<<<<<<<<<<<< + * else: + * if isinstance(item, slice): + */ + __pyx_v_have_slices = 1; + + /* "View.MemoryView":684 + * idx = 0 + * for item in tup: + * if item is Ellipsis: # <<<<<<<<<<<<<< + * if not seen_ellipsis: + * idx += ndim - len(tup) + */ + goto __pyx_L5; + } + + /* "View.MemoryView":690 + * have_slices = True + * else: + * if isinstance(item, slice): # <<<<<<<<<<<<<< + * have_slices = True + * elif not PyIndex_Check(item): + */ + /*else*/ { + __pyx_t_2 = PySlice_Check(__pyx_v_item); + if (__pyx_t_2) { + + /* "View.MemoryView":691 + * else: + * if isinstance(item, slice): + * have_slices = True # <<<<<<<<<<<<<< + * elif not PyIndex_Check(item): + * raise TypeError, f"Cannot index with type '{type(item)}'" + */ + __pyx_v_have_slices = 1; + + /* "View.MemoryView":690 + * have_slices = True + * else: + * if isinstance(item, slice): # <<<<<<<<<<<<<< + * have_slices = True + * elif not PyIndex_Check(item): + */ + goto __pyx_L7; + } + + /* "View.MemoryView":692 + * if isinstance(item, slice): + * have_slices = True + * elif not PyIndex_Check(item): # <<<<<<<<<<<<<< + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item + */ + __pyx_t_2 = (!(PyIndex_Check(__pyx_v_item) != 0)); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":693 + * have_slices = True + * elif not PyIndex_Check(item): + * raise TypeError, f"Cannot index with type '{type(item)}'" # <<<<<<<<<<<<<< + * result[idx] = item + * idx += 1 + */ + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 693, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = 0; + __pyx_t_6 = 127; + __Pyx_INCREF(__pyx_kp_u_Cannot_index_with_type); + __pyx_t_5 += 24; + __Pyx_GIVEREF(__pyx_kp_u_Cannot_index_with_type); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_kp_u_Cannot_index_with_type); + __pyx_t_7 = __Pyx_PyObject_FormatSimple(((PyObject *)Py_TYPE(__pyx_v_item)), __pyx_empty_unicode); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 693, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_7) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_7) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_7); + __pyx_t_7 = 0; + __Pyx_INCREF(__pyx_kp_u__6); + __pyx_t_5 += 1; + __Pyx_GIVEREF(__pyx_kp_u__6); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_kp_u__6); + __pyx_t_7 = __Pyx_PyUnicode_Join(__pyx_t_3, 3, __pyx_t_5, __pyx_t_6); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 693, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_t_7, 0, 0); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __PYX_ERR(1, 693, __pyx_L1_error) + + /* "View.MemoryView":692 + * if isinstance(item, slice): + * have_slices = True + * elif not PyIndex_Check(item): # <<<<<<<<<<<<<< + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item + */ + } + __pyx_L7:; + + /* "View.MemoryView":694 + * elif not PyIndex_Check(item): + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item # <<<<<<<<<<<<<< + * idx += 1 + * + */ + if (unlikely((__Pyx_SetItemInt(__pyx_v_result, __pyx_v_idx, __pyx_v_item, Py_ssize_t, 1, PyInt_FromSsize_t, 1, 1, 1) < 0))) __PYX_ERR(1, 694, __pyx_L1_error) + } + __pyx_L5:; + + /* "View.MemoryView":695 + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item + * idx += 1 # <<<<<<<<<<<<<< + * + * nslices = ndim - idx + */ + __pyx_v_idx = (__pyx_v_idx + 1); + + /* "View.MemoryView":683 + * seen_ellipsis = False + * idx = 0 + * for item in tup: # <<<<<<<<<<<<<< + * if item is Ellipsis: + * if not seen_ellipsis: + */ + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "View.MemoryView":697 + * idx += 1 + * + * nslices = ndim - idx # <<<<<<<<<<<<<< + * return have_slices or nslices, tuple(result) + * + */ + __pyx_v_nslices = (__pyx_v_ndim - __pyx_v_idx); + + /* "View.MemoryView":698 + * + * nslices = ndim - idx + * return have_slices or nslices, tuple(result) # <<<<<<<<<<<<<< + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + */ + __Pyx_XDECREF(__pyx_r); + if (!__pyx_v_have_slices) { + } else { + __pyx_t_7 = __Pyx_PyBool_FromLong(__pyx_v_have_slices); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_1 = __pyx_t_7; + __pyx_t_7 = 0; + goto __pyx_L9_bool_binop_done; + } + __pyx_t_7 = PyInt_FromSsize_t(__pyx_v_nslices); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_1 = __pyx_t_7; + __pyx_t_7 = 0; + __pyx_L9_bool_binop_done:; + __pyx_t_7 = PyList_AsTuple(__pyx_v_result); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_1)) __PYX_ERR(1, 698, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_7); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_7)) __PYX_ERR(1, 698, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_7 = 0; + __pyx_r = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; + goto __pyx_L0; + + /* "View.MemoryView":671 + * return isinstance(o, memoryview) + * + * cdef tuple _unellipsify(object index, int ndim): # <<<<<<<<<<<<<< + * """ + * Replace all ellipses with full slices and fill incomplete indices with + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("View.MemoryView._unellipsify", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_tup); + __Pyx_XDECREF(__pyx_v_result); + __Pyx_XDECREF(__pyx_v_item); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":700 + * return have_slices or nslices, tuple(result) + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: # <<<<<<<<<<<<<< + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: + */ + +static int assert_direct_dimensions(Py_ssize_t *__pyx_v_suboffsets, int __pyx_v_ndim) { + Py_ssize_t __pyx_v_suboffset; + int __pyx_r; + Py_ssize_t *__pyx_t_1; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + int __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + + /* "View.MemoryView":701 + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + * for suboffset in suboffsets[:ndim]: # <<<<<<<<<<<<<< + * if suboffset >= 0: + * raise ValueError, "Indirect dimensions not supported" + */ + __pyx_t_2 = (__pyx_v_suboffsets + __pyx_v_ndim); + for (__pyx_t_3 = __pyx_v_suboffsets; __pyx_t_3 < __pyx_t_2; __pyx_t_3++) { + __pyx_t_1 = __pyx_t_3; + __pyx_v_suboffset = (__pyx_t_1[0]); + + /* "View.MemoryView":702 + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * raise ValueError, "Indirect dimensions not supported" + * return 0 # return type just used as an error flag + */ + __pyx_t_4 = (__pyx_v_suboffset >= 0); + if (unlikely(__pyx_t_4)) { + + /* "View.MemoryView":703 + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: + * raise ValueError, "Indirect dimensions not supported" # <<<<<<<<<<<<<< + * return 0 # return type just used as an error flag + * + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Indirect_dimensions_not_supporte, 0, 0); + __PYX_ERR(1, 703, __pyx_L1_error) + + /* "View.MemoryView":702 + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * raise ValueError, "Indirect dimensions not supported" + * return 0 # return type just used as an error flag + */ + } + } + + /* "View.MemoryView":704 + * if suboffset >= 0: + * raise ValueError, "Indirect dimensions not supported" + * return 0 # return type just used as an error flag # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":700 + * return have_slices or nslices, tuple(result) + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: # <<<<<<<<<<<<<< + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.assert_direct_dimensions", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":711 + * + * @cname('__pyx_memview_slice') + * cdef memoryview memview_slice(memoryview memview, object indices): # <<<<<<<<<<<<<< + * cdef int new_ndim = 0, suboffset_dim = -1, dim + * cdef bint negative_step + */ + +static struct __pyx_memoryview_obj *__pyx_memview_slice(struct __pyx_memoryview_obj *__pyx_v_memview, PyObject *__pyx_v_indices) { + int __pyx_v_new_ndim; + int __pyx_v_suboffset_dim; + int __pyx_v_dim; + __Pyx_memviewslice __pyx_v_src; + __Pyx_memviewslice __pyx_v_dst; + __Pyx_memviewslice *__pyx_v_p_src; + struct __pyx_memoryviewslice_obj *__pyx_v_memviewsliceobj = 0; + __Pyx_memviewslice *__pyx_v_p_dst; + int *__pyx_v_p_suboffset_dim; + Py_ssize_t __pyx_v_start; + Py_ssize_t __pyx_v_stop; + Py_ssize_t __pyx_v_step; + Py_ssize_t __pyx_v_cindex; + int __pyx_v_have_start; + int __pyx_v_have_stop; + int __pyx_v_have_step; + PyObject *__pyx_v_index = NULL; + struct __pyx_memoryview_obj *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + struct __pyx_memoryview_obj *__pyx_t_3; + char *__pyx_t_4; + int __pyx_t_5; + Py_ssize_t __pyx_t_6; + PyObject *(*__pyx_t_7)(PyObject *); + PyObject *__pyx_t_8 = NULL; + Py_ssize_t __pyx_t_9; + int __pyx_t_10; + Py_ssize_t __pyx_t_11; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memview_slice", 1); + + /* "View.MemoryView":712 + * @cname('__pyx_memview_slice') + * cdef memoryview memview_slice(memoryview memview, object indices): + * cdef int new_ndim = 0, suboffset_dim = -1, dim # <<<<<<<<<<<<<< + * cdef bint negative_step + * cdef __Pyx_memviewslice src, dst + */ + __pyx_v_new_ndim = 0; + __pyx_v_suboffset_dim = -1; + + /* "View.MemoryView":719 + * + * + * memset(&dst, 0, sizeof(dst)) # <<<<<<<<<<<<<< + * + * cdef _memoryviewslice memviewsliceobj + */ + (void)(memset((&__pyx_v_dst), 0, (sizeof(__pyx_v_dst)))); + + /* "View.MemoryView":723 + * cdef _memoryviewslice memviewsliceobj + * + * assert memview.view.ndim > 0 # <<<<<<<<<<<<<< + * + * if isinstance(memview, _memoryviewslice): + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_1 = (__pyx_v_memview->view.ndim > 0); + if (unlikely(!__pyx_t_1)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(1, 723, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(1, 723, __pyx_L1_error) + #endif + + /* "View.MemoryView":725 + * assert memview.view.ndim > 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * memviewsliceobj = memview + * p_src = &memviewsliceobj.from_slice + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":726 + * + * if isinstance(memview, _memoryviewslice): + * memviewsliceobj = memview # <<<<<<<<<<<<<< + * p_src = &memviewsliceobj.from_slice + * else: + */ + if (!(likely(((((PyObject *)__pyx_v_memview)) == Py_None) || likely(__Pyx_TypeTest(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type))))) __PYX_ERR(1, 726, __pyx_L1_error) + __pyx_t_2 = ((PyObject *)__pyx_v_memview); + __Pyx_INCREF(__pyx_t_2); + __pyx_v_memviewsliceobj = ((struct __pyx_memoryviewslice_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":727 + * if isinstance(memview, _memoryviewslice): + * memviewsliceobj = memview + * p_src = &memviewsliceobj.from_slice # <<<<<<<<<<<<<< + * else: + * slice_copy(memview, &src) + */ + __pyx_v_p_src = (&__pyx_v_memviewsliceobj->from_slice); + + /* "View.MemoryView":725 + * assert memview.view.ndim > 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * memviewsliceobj = memview + * p_src = &memviewsliceobj.from_slice + */ + goto __pyx_L3; + } + + /* "View.MemoryView":729 + * p_src = &memviewsliceobj.from_slice + * else: + * slice_copy(memview, &src) # <<<<<<<<<<<<<< + * p_src = &src + * + */ + /*else*/ { + __pyx_memoryview_slice_copy(__pyx_v_memview, (&__pyx_v_src)); + + /* "View.MemoryView":730 + * else: + * slice_copy(memview, &src) + * p_src = &src # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_p_src = (&__pyx_v_src); + } + __pyx_L3:; + + /* "View.MemoryView":736 + * + * + * dst.memview = p_src.memview # <<<<<<<<<<<<<< + * dst.data = p_src.data + * + */ + __pyx_t_3 = __pyx_v_p_src->memview; + __pyx_v_dst.memview = __pyx_t_3; + + /* "View.MemoryView":737 + * + * dst.memview = p_src.memview + * dst.data = p_src.data # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_4 = __pyx_v_p_src->data; + __pyx_v_dst.data = __pyx_t_4; + + /* "View.MemoryView":742 + * + * + * cdef __Pyx_memviewslice *p_dst = &dst # <<<<<<<<<<<<<< + * cdef int *p_suboffset_dim = &suboffset_dim + * cdef Py_ssize_t start, stop, step, cindex + */ + __pyx_v_p_dst = (&__pyx_v_dst); + + /* "View.MemoryView":743 + * + * cdef __Pyx_memviewslice *p_dst = &dst + * cdef int *p_suboffset_dim = &suboffset_dim # <<<<<<<<<<<<<< + * cdef Py_ssize_t start, stop, step, cindex + * cdef bint have_start, have_stop, have_step + */ + __pyx_v_p_suboffset_dim = (&__pyx_v_suboffset_dim); + + /* "View.MemoryView":747 + * cdef bint have_start, have_stop, have_step + * + * for dim, index in enumerate(indices): # <<<<<<<<<<<<<< + * if PyIndex_Check(index): + * cindex = index + */ + __pyx_t_5 = 0; + if (likely(PyList_CheckExact(__pyx_v_indices)) || PyTuple_CheckExact(__pyx_v_indices)) { + __pyx_t_2 = __pyx_v_indices; __Pyx_INCREF(__pyx_t_2); + __pyx_t_6 = 0; + __pyx_t_7 = NULL; + } else { + __pyx_t_6 = -1; __pyx_t_2 = PyObject_GetIter(__pyx_v_indices); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 747, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_7 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_2); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 747, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_7)) { + if (likely(PyList_CheckExact(__pyx_t_2))) { + { + Py_ssize_t __pyx_temp = __Pyx_PyList_GET_SIZE(__pyx_t_2); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 747, __pyx_L1_error) + #endif + if (__pyx_t_6 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_8 = PyList_GET_ITEM(__pyx_t_2, __pyx_t_6); __Pyx_INCREF(__pyx_t_8); __pyx_t_6++; if (unlikely((0 < 0))) __PYX_ERR(1, 747, __pyx_L1_error) + #else + __pyx_t_8 = __Pyx_PySequence_ITEM(__pyx_t_2, __pyx_t_6); __pyx_t_6++; if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 747, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + #endif + } else { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_2); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 747, __pyx_L1_error) + #endif + if (__pyx_t_6 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_8 = PyTuple_GET_ITEM(__pyx_t_2, __pyx_t_6); __Pyx_INCREF(__pyx_t_8); __pyx_t_6++; if (unlikely((0 < 0))) __PYX_ERR(1, 747, __pyx_L1_error) + #else + __pyx_t_8 = __Pyx_PySequence_ITEM(__pyx_t_2, __pyx_t_6); __pyx_t_6++; if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 747, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + #endif + } + } else { + __pyx_t_8 = __pyx_t_7(__pyx_t_2); + if (unlikely(!__pyx_t_8)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(1, 747, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_8); + } + __Pyx_XDECREF_SET(__pyx_v_index, __pyx_t_8); + __pyx_t_8 = 0; + __pyx_v_dim = __pyx_t_5; + __pyx_t_5 = (__pyx_t_5 + 1); + + /* "View.MemoryView":748 + * + * for dim, index in enumerate(indices): + * if PyIndex_Check(index): # <<<<<<<<<<<<<< + * cindex = index + * slice_memviewslice( + */ + __pyx_t_1 = (PyIndex_Check(__pyx_v_index) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":749 + * for dim, index in enumerate(indices): + * if PyIndex_Check(index): + * cindex = index # <<<<<<<<<<<<<< + * slice_memviewslice( + * p_dst, p_src.shape[dim], p_src.strides[dim], p_src.suboffsets[dim], + */ + __pyx_t_9 = __Pyx_PyIndex_AsSsize_t(__pyx_v_index); if (unlikely((__pyx_t_9 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 749, __pyx_L1_error) + __pyx_v_cindex = __pyx_t_9; + + /* "View.MemoryView":750 + * if PyIndex_Check(index): + * cindex = index + * slice_memviewslice( # <<<<<<<<<<<<<< + * p_dst, p_src.shape[dim], p_src.strides[dim], p_src.suboffsets[dim], + * dim, new_ndim, p_suboffset_dim, + */ + __pyx_t_10 = __pyx_memoryview_slice_memviewslice(__pyx_v_p_dst, (__pyx_v_p_src->shape[__pyx_v_dim]), (__pyx_v_p_src->strides[__pyx_v_dim]), (__pyx_v_p_src->suboffsets[__pyx_v_dim]), __pyx_v_dim, __pyx_v_new_ndim, __pyx_v_p_suboffset_dim, __pyx_v_cindex, 0, 0, 0, 0, 0, 0); if (unlikely(__pyx_t_10 == ((int)-1))) __PYX_ERR(1, 750, __pyx_L1_error) + + /* "View.MemoryView":748 + * + * for dim, index in enumerate(indices): + * if PyIndex_Check(index): # <<<<<<<<<<<<<< + * cindex = index + * slice_memviewslice( + */ + goto __pyx_L6; + } + + /* "View.MemoryView":756 + * 0, 0, 0, # have_{start,stop,step} + * False) + * elif index is None: # <<<<<<<<<<<<<< + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 + */ + __pyx_t_1 = (__pyx_v_index == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":757 + * False) + * elif index is None: + * p_dst.shape[new_ndim] = 1 # <<<<<<<<<<<<<< + * p_dst.strides[new_ndim] = 0 + * p_dst.suboffsets[new_ndim] = -1 + */ + (__pyx_v_p_dst->shape[__pyx_v_new_ndim]) = 1; + + /* "View.MemoryView":758 + * elif index is None: + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 # <<<<<<<<<<<<<< + * p_dst.suboffsets[new_ndim] = -1 + * new_ndim += 1 + */ + (__pyx_v_p_dst->strides[__pyx_v_new_ndim]) = 0; + + /* "View.MemoryView":759 + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 + * p_dst.suboffsets[new_ndim] = -1 # <<<<<<<<<<<<<< + * new_ndim += 1 + * else: + */ + (__pyx_v_p_dst->suboffsets[__pyx_v_new_ndim]) = -1L; + + /* "View.MemoryView":760 + * p_dst.strides[new_ndim] = 0 + * p_dst.suboffsets[new_ndim] = -1 + * new_ndim += 1 # <<<<<<<<<<<<<< + * else: + * start = index.start or 0 + */ + __pyx_v_new_ndim = (__pyx_v_new_ndim + 1); + + /* "View.MemoryView":756 + * 0, 0, 0, # have_{start,stop,step} + * False) + * elif index is None: # <<<<<<<<<<<<<< + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 + */ + goto __pyx_L6; + } + + /* "View.MemoryView":762 + * new_ndim += 1 + * else: + * start = index.start or 0 # <<<<<<<<<<<<<< + * stop = index.stop or 0 + * step = index.step or 0 + */ + /*else*/ { + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_start); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 762, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_t_8); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 762, __pyx_L1_error) + if (!__pyx_t_1) { + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } else { + __pyx_t_11 = __Pyx_PyIndex_AsSsize_t(__pyx_t_8); if (unlikely((__pyx_t_11 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 762, __pyx_L1_error) + __pyx_t_9 = __pyx_t_11; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L7_bool_binop_done; + } + __pyx_t_9 = 0; + __pyx_L7_bool_binop_done:; + __pyx_v_start = __pyx_t_9; + + /* "View.MemoryView":763 + * else: + * start = index.start or 0 + * stop = index.stop or 0 # <<<<<<<<<<<<<< + * step = index.step or 0 + * + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_stop); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 763, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_t_8); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 763, __pyx_L1_error) + if (!__pyx_t_1) { + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } else { + __pyx_t_11 = __Pyx_PyIndex_AsSsize_t(__pyx_t_8); if (unlikely((__pyx_t_11 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 763, __pyx_L1_error) + __pyx_t_9 = __pyx_t_11; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L9_bool_binop_done; + } + __pyx_t_9 = 0; + __pyx_L9_bool_binop_done:; + __pyx_v_stop = __pyx_t_9; + + /* "View.MemoryView":764 + * start = index.start or 0 + * stop = index.stop or 0 + * step = index.step or 0 # <<<<<<<<<<<<<< + * + * have_start = index.start is not None + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_step); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 764, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_t_8); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 764, __pyx_L1_error) + if (!__pyx_t_1) { + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } else { + __pyx_t_11 = __Pyx_PyIndex_AsSsize_t(__pyx_t_8); if (unlikely((__pyx_t_11 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 764, __pyx_L1_error) + __pyx_t_9 = __pyx_t_11; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L11_bool_binop_done; + } + __pyx_t_9 = 0; + __pyx_L11_bool_binop_done:; + __pyx_v_step = __pyx_t_9; + + /* "View.MemoryView":766 + * step = index.step or 0 + * + * have_start = index.start is not None # <<<<<<<<<<<<<< + * have_stop = index.stop is not None + * have_step = index.step is not None + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_start); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 766, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = (__pyx_t_8 != Py_None); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_v_have_start = __pyx_t_1; + + /* "View.MemoryView":767 + * + * have_start = index.start is not None + * have_stop = index.stop is not None # <<<<<<<<<<<<<< + * have_step = index.step is not None + * + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_stop); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 767, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = (__pyx_t_8 != Py_None); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_v_have_stop = __pyx_t_1; + + /* "View.MemoryView":768 + * have_start = index.start is not None + * have_stop = index.stop is not None + * have_step = index.step is not None # <<<<<<<<<<<<<< + * + * slice_memviewslice( + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_step); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 768, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = (__pyx_t_8 != Py_None); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_v_have_step = __pyx_t_1; + + /* "View.MemoryView":770 + * have_step = index.step is not None + * + * slice_memviewslice( # <<<<<<<<<<<<<< + * p_dst, p_src.shape[dim], p_src.strides[dim], p_src.suboffsets[dim], + * dim, new_ndim, p_suboffset_dim, + */ + __pyx_t_10 = __pyx_memoryview_slice_memviewslice(__pyx_v_p_dst, (__pyx_v_p_src->shape[__pyx_v_dim]), (__pyx_v_p_src->strides[__pyx_v_dim]), (__pyx_v_p_src->suboffsets[__pyx_v_dim]), __pyx_v_dim, __pyx_v_new_ndim, __pyx_v_p_suboffset_dim, __pyx_v_start, __pyx_v_stop, __pyx_v_step, __pyx_v_have_start, __pyx_v_have_stop, __pyx_v_have_step, 1); if (unlikely(__pyx_t_10 == ((int)-1))) __PYX_ERR(1, 770, __pyx_L1_error) + + /* "View.MemoryView":776 + * have_start, have_stop, have_step, + * True) + * new_ndim += 1 # <<<<<<<<<<<<<< + * + * if isinstance(memview, _memoryviewslice): + */ + __pyx_v_new_ndim = (__pyx_v_new_ndim + 1); + } + __pyx_L6:; + + /* "View.MemoryView":747 + * cdef bint have_start, have_stop, have_step + * + * for dim, index in enumerate(indices): # <<<<<<<<<<<<<< + * if PyIndex_Check(index): + * cindex = index + */ + } + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":778 + * new_ndim += 1 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":779 + * + * if isinstance(memview, _memoryviewslice): + * return memoryview_fromslice(dst, new_ndim, # <<<<<<<<<<<<<< + * memviewsliceobj.to_object_func, + * memviewsliceobj.to_dtype_func, + */ + __Pyx_XDECREF((PyObject *)__pyx_r); + + /* "View.MemoryView":780 + * if isinstance(memview, _memoryviewslice): + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, # <<<<<<<<<<<<<< + * memviewsliceobj.to_dtype_func, + * memview.dtype_is_object) + */ + if (unlikely(!__pyx_v_memviewsliceobj)) { __Pyx_RaiseUnboundLocalError("memviewsliceobj"); __PYX_ERR(1, 780, __pyx_L1_error) } + + /* "View.MemoryView":781 + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, + * memviewsliceobj.to_dtype_func, # <<<<<<<<<<<<<< + * memview.dtype_is_object) + * else: + */ + if (unlikely(!__pyx_v_memviewsliceobj)) { __Pyx_RaiseUnboundLocalError("memviewsliceobj"); __PYX_ERR(1, 781, __pyx_L1_error) } + + /* "View.MemoryView":779 + * + * if isinstance(memview, _memoryviewslice): + * return memoryview_fromslice(dst, new_ndim, # <<<<<<<<<<<<<< + * memviewsliceobj.to_object_func, + * memviewsliceobj.to_dtype_func, + */ + __pyx_t_2 = __pyx_memoryview_fromslice(__pyx_v_dst, __pyx_v_new_ndim, __pyx_v_memviewsliceobj->to_object_func, __pyx_v_memviewsliceobj->to_dtype_func, __pyx_v_memview->dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 779, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (!(likely(((__pyx_t_2) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_2, __pyx_memoryview_type))))) __PYX_ERR(1, 779, __pyx_L1_error) + __pyx_r = ((struct __pyx_memoryview_obj *)__pyx_t_2); + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":778 + * new_ndim += 1 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, + */ + } + + /* "View.MemoryView":784 + * memview.dtype_is_object) + * else: + * return memoryview_fromslice(dst, new_ndim, NULL, NULL, # <<<<<<<<<<<<<< + * memview.dtype_is_object) + * + */ + /*else*/ { + __Pyx_XDECREF((PyObject *)__pyx_r); + + /* "View.MemoryView":785 + * else: + * return memoryview_fromslice(dst, new_ndim, NULL, NULL, + * memview.dtype_is_object) # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = __pyx_memoryview_fromslice(__pyx_v_dst, __pyx_v_new_ndim, NULL, NULL, __pyx_v_memview->dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 784, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + + /* "View.MemoryView":784 + * memview.dtype_is_object) + * else: + * return memoryview_fromslice(dst, new_ndim, NULL, NULL, # <<<<<<<<<<<<<< + * memview.dtype_is_object) + * + */ + if (!(likely(((__pyx_t_2) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_2, __pyx_memoryview_type))))) __PYX_ERR(1, 784, __pyx_L1_error) + __pyx_r = ((struct __pyx_memoryview_obj *)__pyx_t_2); + __pyx_t_2 = 0; + goto __pyx_L0; + } + + /* "View.MemoryView":711 + * + * @cname('__pyx_memview_slice') + * cdef memoryview memview_slice(memoryview memview, object indices): # <<<<<<<<<<<<<< + * cdef int new_ndim = 0, suboffset_dim = -1, dim + * cdef bint negative_step + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("View.MemoryView.memview_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_memviewsliceobj); + __Pyx_XDECREF(__pyx_v_index); + __Pyx_XGIVEREF((PyObject *)__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":793 + * + * @cname('__pyx_memoryview_slice_memviewslice') + * cdef int slice_memviewslice( # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * Py_ssize_t shape, Py_ssize_t stride, Py_ssize_t suboffset, + */ + +static int __pyx_memoryview_slice_memviewslice(__Pyx_memviewslice *__pyx_v_dst, Py_ssize_t __pyx_v_shape, Py_ssize_t __pyx_v_stride, Py_ssize_t __pyx_v_suboffset, int __pyx_v_dim, int __pyx_v_new_ndim, int *__pyx_v_suboffset_dim, Py_ssize_t __pyx_v_start, Py_ssize_t __pyx_v_stop, Py_ssize_t __pyx_v_step, int __pyx_v_have_start, int __pyx_v_have_stop, int __pyx_v_have_step, int __pyx_v_is_slice) { + Py_ssize_t __pyx_v_new_shape; + int __pyx_v_negative_step; + int __pyx_r; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":813 + * cdef bint negative_step + * + * if not is_slice: # <<<<<<<<<<<<<< + * + * if start < 0: + */ + __pyx_t_1 = (!__pyx_v_is_slice); + if (__pyx_t_1) { + + /* "View.MemoryView":815 + * if not is_slice: + * + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if not 0 <= start < shape: + */ + __pyx_t_1 = (__pyx_v_start < 0); + if (__pyx_t_1) { + + /* "View.MemoryView":816 + * + * if start < 0: + * start += shape # <<<<<<<<<<<<<< + * if not 0 <= start < shape: + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) + */ + __pyx_v_start = (__pyx_v_start + __pyx_v_shape); + + /* "View.MemoryView":815 + * if not is_slice: + * + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if not 0 <= start < shape: + */ + } + + /* "View.MemoryView":817 + * if start < 0: + * start += shape + * if not 0 <= start < shape: # <<<<<<<<<<<<<< + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) + * else: + */ + __pyx_t_1 = (0 <= __pyx_v_start); + if (__pyx_t_1) { + __pyx_t_1 = (__pyx_v_start < __pyx_v_shape); + } + __pyx_t_2 = (!__pyx_t_1); + if (__pyx_t_2) { + + /* "View.MemoryView":818 + * start += shape + * if not 0 <= start < shape: + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) # <<<<<<<<<<<<<< + * else: + * + */ + __pyx_t_3 = __pyx_memoryview_err_dim(PyExc_IndexError, __pyx_kp_s_Index_out_of_bounds_axis_d, __pyx_v_dim); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 818, __pyx_L1_error) + + /* "View.MemoryView":817 + * if start < 0: + * start += shape + * if not 0 <= start < shape: # <<<<<<<<<<<<<< + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) + * else: + */ + } + + /* "View.MemoryView":813 + * cdef bint negative_step + * + * if not is_slice: # <<<<<<<<<<<<<< + * + * if start < 0: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":821 + * else: + * + * if have_step: # <<<<<<<<<<<<<< + * negative_step = step < 0 + * if step == 0: + */ + /*else*/ { + __pyx_t_2 = (__pyx_v_have_step != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":822 + * + * if have_step: + * negative_step = step < 0 # <<<<<<<<<<<<<< + * if step == 0: + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + */ + __pyx_v_negative_step = (__pyx_v_step < 0); + + /* "View.MemoryView":823 + * if have_step: + * negative_step = step < 0 + * if step == 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + * else: + */ + __pyx_t_2 = (__pyx_v_step == 0); + if (__pyx_t_2) { + + /* "View.MemoryView":824 + * negative_step = step < 0 + * if step == 0: + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) # <<<<<<<<<<<<<< + * else: + * negative_step = False + */ + __pyx_t_3 = __pyx_memoryview_err_dim(PyExc_ValueError, __pyx_kp_s_Step_may_not_be_zero_axis_d, __pyx_v_dim); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 824, __pyx_L1_error) + + /* "View.MemoryView":823 + * if have_step: + * negative_step = step < 0 + * if step == 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + * else: + */ + } + + /* "View.MemoryView":821 + * else: + * + * if have_step: # <<<<<<<<<<<<<< + * negative_step = step < 0 + * if step == 0: + */ + goto __pyx_L6; + } + + /* "View.MemoryView":826 + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + * else: + * negative_step = False # <<<<<<<<<<<<<< + * step = 1 + * + */ + /*else*/ { + __pyx_v_negative_step = 0; + + /* "View.MemoryView":827 + * else: + * negative_step = False + * step = 1 # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_step = 1; + } + __pyx_L6:; + + /* "View.MemoryView":830 + * + * + * if have_start: # <<<<<<<<<<<<<< + * if start < 0: + * start += shape + */ + __pyx_t_2 = (__pyx_v_have_start != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":831 + * + * if have_start: + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if start < 0: + */ + __pyx_t_2 = (__pyx_v_start < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":832 + * if have_start: + * if start < 0: + * start += shape # <<<<<<<<<<<<<< + * if start < 0: + * start = 0 + */ + __pyx_v_start = (__pyx_v_start + __pyx_v_shape); + + /* "View.MemoryView":833 + * if start < 0: + * start += shape + * if start < 0: # <<<<<<<<<<<<<< + * start = 0 + * elif start >= shape: + */ + __pyx_t_2 = (__pyx_v_start < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":834 + * start += shape + * if start < 0: + * start = 0 # <<<<<<<<<<<<<< + * elif start >= shape: + * if negative_step: + */ + __pyx_v_start = 0; + + /* "View.MemoryView":833 + * if start < 0: + * start += shape + * if start < 0: # <<<<<<<<<<<<<< + * start = 0 + * elif start >= shape: + */ + } + + /* "View.MemoryView":831 + * + * if have_start: + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if start < 0: + */ + goto __pyx_L9; + } + + /* "View.MemoryView":835 + * if start < 0: + * start = 0 + * elif start >= shape: # <<<<<<<<<<<<<< + * if negative_step: + * start = shape - 1 + */ + __pyx_t_2 = (__pyx_v_start >= __pyx_v_shape); + if (__pyx_t_2) { + + /* "View.MemoryView":836 + * start = 0 + * elif start >= shape: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + if (__pyx_v_negative_step) { + + /* "View.MemoryView":837 + * elif start >= shape: + * if negative_step: + * start = shape - 1 # <<<<<<<<<<<<<< + * else: + * start = shape + */ + __pyx_v_start = (__pyx_v_shape - 1); + + /* "View.MemoryView":836 + * start = 0 + * elif start >= shape: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + goto __pyx_L11; + } + + /* "View.MemoryView":839 + * start = shape - 1 + * else: + * start = shape # <<<<<<<<<<<<<< + * else: + * if negative_step: + */ + /*else*/ { + __pyx_v_start = __pyx_v_shape; + } + __pyx_L11:; + + /* "View.MemoryView":835 + * if start < 0: + * start = 0 + * elif start >= shape: # <<<<<<<<<<<<<< + * if negative_step: + * start = shape - 1 + */ + } + __pyx_L9:; + + /* "View.MemoryView":830 + * + * + * if have_start: # <<<<<<<<<<<<<< + * if start < 0: + * start += shape + */ + goto __pyx_L8; + } + + /* "View.MemoryView":841 + * start = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + /*else*/ { + if (__pyx_v_negative_step) { + + /* "View.MemoryView":842 + * else: + * if negative_step: + * start = shape - 1 # <<<<<<<<<<<<<< + * else: + * start = 0 + */ + __pyx_v_start = (__pyx_v_shape - 1); + + /* "View.MemoryView":841 + * start = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + goto __pyx_L12; + } + + /* "View.MemoryView":844 + * start = shape - 1 + * else: + * start = 0 # <<<<<<<<<<<<<< + * + * if have_stop: + */ + /*else*/ { + __pyx_v_start = 0; + } + __pyx_L12:; + } + __pyx_L8:; + + /* "View.MemoryView":846 + * start = 0 + * + * if have_stop: # <<<<<<<<<<<<<< + * if stop < 0: + * stop += shape + */ + __pyx_t_2 = (__pyx_v_have_stop != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":847 + * + * if have_stop: + * if stop < 0: # <<<<<<<<<<<<<< + * stop += shape + * if stop < 0: + */ + __pyx_t_2 = (__pyx_v_stop < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":848 + * if have_stop: + * if stop < 0: + * stop += shape # <<<<<<<<<<<<<< + * if stop < 0: + * stop = 0 + */ + __pyx_v_stop = (__pyx_v_stop + __pyx_v_shape); + + /* "View.MemoryView":849 + * if stop < 0: + * stop += shape + * if stop < 0: # <<<<<<<<<<<<<< + * stop = 0 + * elif stop > shape: + */ + __pyx_t_2 = (__pyx_v_stop < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":850 + * stop += shape + * if stop < 0: + * stop = 0 # <<<<<<<<<<<<<< + * elif stop > shape: + * stop = shape + */ + __pyx_v_stop = 0; + + /* "View.MemoryView":849 + * if stop < 0: + * stop += shape + * if stop < 0: # <<<<<<<<<<<<<< + * stop = 0 + * elif stop > shape: + */ + } + + /* "View.MemoryView":847 + * + * if have_stop: + * if stop < 0: # <<<<<<<<<<<<<< + * stop += shape + * if stop < 0: + */ + goto __pyx_L14; + } + + /* "View.MemoryView":851 + * if stop < 0: + * stop = 0 + * elif stop > shape: # <<<<<<<<<<<<<< + * stop = shape + * else: + */ + __pyx_t_2 = (__pyx_v_stop > __pyx_v_shape); + if (__pyx_t_2) { + + /* "View.MemoryView":852 + * stop = 0 + * elif stop > shape: + * stop = shape # <<<<<<<<<<<<<< + * else: + * if negative_step: + */ + __pyx_v_stop = __pyx_v_shape; + + /* "View.MemoryView":851 + * if stop < 0: + * stop = 0 + * elif stop > shape: # <<<<<<<<<<<<<< + * stop = shape + * else: + */ + } + __pyx_L14:; + + /* "View.MemoryView":846 + * start = 0 + * + * if have_stop: # <<<<<<<<<<<<<< + * if stop < 0: + * stop += shape + */ + goto __pyx_L13; + } + + /* "View.MemoryView":854 + * stop = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * stop = -1 + * else: + */ + /*else*/ { + if (__pyx_v_negative_step) { + + /* "View.MemoryView":855 + * else: + * if negative_step: + * stop = -1 # <<<<<<<<<<<<<< + * else: + * stop = shape + */ + __pyx_v_stop = -1L; + + /* "View.MemoryView":854 + * stop = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * stop = -1 + * else: + */ + goto __pyx_L16; + } + + /* "View.MemoryView":857 + * stop = -1 + * else: + * stop = shape # <<<<<<<<<<<<<< + * + * + */ + /*else*/ { + __pyx_v_stop = __pyx_v_shape; + } + __pyx_L16:; + } + __pyx_L13:; + + /* "View.MemoryView":861 + * + * with cython.cdivision(True): + * new_shape = (stop - start) // step # <<<<<<<<<<<<<< + * + * if (stop - start) - step * new_shape: + */ + __pyx_v_new_shape = ((__pyx_v_stop - __pyx_v_start) / __pyx_v_step); + + /* "View.MemoryView":863 + * new_shape = (stop - start) // step + * + * if (stop - start) - step * new_shape: # <<<<<<<<<<<<<< + * new_shape += 1 + * + */ + __pyx_t_2 = (((__pyx_v_stop - __pyx_v_start) - (__pyx_v_step * __pyx_v_new_shape)) != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":864 + * + * if (stop - start) - step * new_shape: + * new_shape += 1 # <<<<<<<<<<<<<< + * + * if new_shape < 0: + */ + __pyx_v_new_shape = (__pyx_v_new_shape + 1); + + /* "View.MemoryView":863 + * new_shape = (stop - start) // step + * + * if (stop - start) - step * new_shape: # <<<<<<<<<<<<<< + * new_shape += 1 + * + */ + } + + /* "View.MemoryView":866 + * new_shape += 1 + * + * if new_shape < 0: # <<<<<<<<<<<<<< + * new_shape = 0 + * + */ + __pyx_t_2 = (__pyx_v_new_shape < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":867 + * + * if new_shape < 0: + * new_shape = 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_new_shape = 0; + + /* "View.MemoryView":866 + * new_shape += 1 + * + * if new_shape < 0: # <<<<<<<<<<<<<< + * new_shape = 0 + * + */ + } + + /* "View.MemoryView":870 + * + * + * dst.strides[new_ndim] = stride * step # <<<<<<<<<<<<<< + * dst.shape[new_ndim] = new_shape + * dst.suboffsets[new_ndim] = suboffset + */ + (__pyx_v_dst->strides[__pyx_v_new_ndim]) = (__pyx_v_stride * __pyx_v_step); + + /* "View.MemoryView":871 + * + * dst.strides[new_ndim] = stride * step + * dst.shape[new_ndim] = new_shape # <<<<<<<<<<<<<< + * dst.suboffsets[new_ndim] = suboffset + * + */ + (__pyx_v_dst->shape[__pyx_v_new_ndim]) = __pyx_v_new_shape; + + /* "View.MemoryView":872 + * dst.strides[new_ndim] = stride * step + * dst.shape[new_ndim] = new_shape + * dst.suboffsets[new_ndim] = suboffset # <<<<<<<<<<<<<< + * + * + */ + (__pyx_v_dst->suboffsets[__pyx_v_new_ndim]) = __pyx_v_suboffset; + } + __pyx_L3:; + + /* "View.MemoryView":875 + * + * + * if suboffset_dim[0] < 0: # <<<<<<<<<<<<<< + * dst.data += start * stride + * else: + */ + __pyx_t_2 = ((__pyx_v_suboffset_dim[0]) < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":876 + * + * if suboffset_dim[0] < 0: + * dst.data += start * stride # <<<<<<<<<<<<<< + * else: + * dst.suboffsets[suboffset_dim[0]] += start * stride + */ + __pyx_v_dst->data = (__pyx_v_dst->data + (__pyx_v_start * __pyx_v_stride)); + + /* "View.MemoryView":875 + * + * + * if suboffset_dim[0] < 0: # <<<<<<<<<<<<<< + * dst.data += start * stride + * else: + */ + goto __pyx_L19; + } + + /* "View.MemoryView":878 + * dst.data += start * stride + * else: + * dst.suboffsets[suboffset_dim[0]] += start * stride # <<<<<<<<<<<<<< + * + * if suboffset >= 0: + */ + /*else*/ { + __pyx_t_3 = (__pyx_v_suboffset_dim[0]); + (__pyx_v_dst->suboffsets[__pyx_t_3]) = ((__pyx_v_dst->suboffsets[__pyx_t_3]) + (__pyx_v_start * __pyx_v_stride)); + } + __pyx_L19:; + + /* "View.MemoryView":880 + * dst.suboffsets[suboffset_dim[0]] += start * stride + * + * if suboffset >= 0: # <<<<<<<<<<<<<< + * if not is_slice: + * if new_ndim == 0: + */ + __pyx_t_2 = (__pyx_v_suboffset >= 0); + if (__pyx_t_2) { + + /* "View.MemoryView":881 + * + * if suboffset >= 0: + * if not is_slice: # <<<<<<<<<<<<<< + * if new_ndim == 0: + * dst.data = ( dst.data)[0] + suboffset + */ + __pyx_t_2 = (!__pyx_v_is_slice); + if (__pyx_t_2) { + + /* "View.MemoryView":882 + * if suboffset >= 0: + * if not is_slice: + * if new_ndim == 0: # <<<<<<<<<<<<<< + * dst.data = ( dst.data)[0] + suboffset + * else: + */ + __pyx_t_2 = (__pyx_v_new_ndim == 0); + if (__pyx_t_2) { + + /* "View.MemoryView":883 + * if not is_slice: + * if new_ndim == 0: + * dst.data = ( dst.data)[0] + suboffset # <<<<<<<<<<<<<< + * else: + * _err_dim(PyExc_IndexError, "All dimensions preceding dimension %d " + */ + __pyx_v_dst->data = ((((char **)__pyx_v_dst->data)[0]) + __pyx_v_suboffset); + + /* "View.MemoryView":882 + * if suboffset >= 0: + * if not is_slice: + * if new_ndim == 0: # <<<<<<<<<<<<<< + * dst.data = ( dst.data)[0] + suboffset + * else: + */ + goto __pyx_L22; + } + + /* "View.MemoryView":885 + * dst.data = ( dst.data)[0] + suboffset + * else: + * _err_dim(PyExc_IndexError, "All dimensions preceding dimension %d " # <<<<<<<<<<<<<< + * "must be indexed and not sliced", dim) + * else: + */ + /*else*/ { + + /* "View.MemoryView":886 + * else: + * _err_dim(PyExc_IndexError, "All dimensions preceding dimension %d " + * "must be indexed and not sliced", dim) # <<<<<<<<<<<<<< + * else: + * suboffset_dim[0] = new_ndim + */ + __pyx_t_3 = __pyx_memoryview_err_dim(PyExc_IndexError, __pyx_kp_s_All_dimensions_preceding_dimensi, __pyx_v_dim); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 885, __pyx_L1_error) + } + __pyx_L22:; + + /* "View.MemoryView":881 + * + * if suboffset >= 0: + * if not is_slice: # <<<<<<<<<<<<<< + * if new_ndim == 0: + * dst.data = ( dst.data)[0] + suboffset + */ + goto __pyx_L21; + } + + /* "View.MemoryView":888 + * "must be indexed and not sliced", dim) + * else: + * suboffset_dim[0] = new_ndim # <<<<<<<<<<<<<< + * + * return 0 + */ + /*else*/ { + (__pyx_v_suboffset_dim[0]) = __pyx_v_new_ndim; + } + __pyx_L21:; + + /* "View.MemoryView":880 + * dst.suboffsets[suboffset_dim[0]] += start * stride + * + * if suboffset >= 0: # <<<<<<<<<<<<<< + * if not is_slice: + * if new_ndim == 0: + */ + } + + /* "View.MemoryView":890 + * suboffset_dim[0] = new_ndim + * + * return 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":793 + * + * @cname('__pyx_memoryview_slice_memviewslice') + * cdef int slice_memviewslice( # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * Py_ssize_t shape, Py_ssize_t stride, Py_ssize_t suboffset, + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.slice_memviewslice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":896 + * + * @cname('__pyx_pybuffer_index') + * cdef char *pybuffer_index(Py_buffer *view, char *bufp, Py_ssize_t index, # <<<<<<<<<<<<<< + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 + */ + +static char *__pyx_pybuffer_index(Py_buffer *__pyx_v_view, char *__pyx_v_bufp, Py_ssize_t __pyx_v_index, Py_ssize_t __pyx_v_dim) { + Py_ssize_t __pyx_v_shape; + Py_ssize_t __pyx_v_stride; + Py_ssize_t __pyx_v_suboffset; + Py_ssize_t __pyx_v_itemsize; + char *__pyx_v_resultp; + char *__pyx_r; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + Py_UCS4 __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("pybuffer_index", 1); + + /* "View.MemoryView":898 + * cdef char *pybuffer_index(Py_buffer *view, char *bufp, Py_ssize_t index, + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 # <<<<<<<<<<<<<< + * cdef Py_ssize_t itemsize = view.itemsize + * cdef char *resultp + */ + __pyx_v_suboffset = -1L; + + /* "View.MemoryView":899 + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 + * cdef Py_ssize_t itemsize = view.itemsize # <<<<<<<<<<<<<< + * cdef char *resultp + * + */ + __pyx_t_1 = __pyx_v_view->itemsize; + __pyx_v_itemsize = __pyx_t_1; + + /* "View.MemoryView":902 + * cdef char *resultp + * + * if view.ndim == 0: # <<<<<<<<<<<<<< + * shape = view.len // itemsize + * stride = itemsize + */ + __pyx_t_2 = (__pyx_v_view->ndim == 0); + if (__pyx_t_2) { + + /* "View.MemoryView":903 + * + * if view.ndim == 0: + * shape = view.len // itemsize # <<<<<<<<<<<<<< + * stride = itemsize + * else: + */ + if (unlikely(__pyx_v_itemsize == 0)) { + PyErr_SetString(PyExc_ZeroDivisionError, "integer division or modulo by zero"); + __PYX_ERR(1, 903, __pyx_L1_error) + } + else if (sizeof(Py_ssize_t) == sizeof(long) && (!(((Py_ssize_t)-1) > 0)) && unlikely(__pyx_v_itemsize == (Py_ssize_t)-1) && unlikely(__Pyx_UNARY_NEG_WOULD_OVERFLOW(__pyx_v_view->len))) { + PyErr_SetString(PyExc_OverflowError, "value too large to perform division"); + __PYX_ERR(1, 903, __pyx_L1_error) + } + __pyx_v_shape = __Pyx_div_Py_ssize_t(__pyx_v_view->len, __pyx_v_itemsize); + + /* "View.MemoryView":904 + * if view.ndim == 0: + * shape = view.len // itemsize + * stride = itemsize # <<<<<<<<<<<<<< + * else: + * shape = view.shape[dim] + */ + __pyx_v_stride = __pyx_v_itemsize; + + /* "View.MemoryView":902 + * cdef char *resultp + * + * if view.ndim == 0: # <<<<<<<<<<<<<< + * shape = view.len // itemsize + * stride = itemsize + */ + goto __pyx_L3; + } + + /* "View.MemoryView":906 + * stride = itemsize + * else: + * shape = view.shape[dim] # <<<<<<<<<<<<<< + * stride = view.strides[dim] + * if view.suboffsets != NULL: + */ + /*else*/ { + __pyx_v_shape = (__pyx_v_view->shape[__pyx_v_dim]); + + /* "View.MemoryView":907 + * else: + * shape = view.shape[dim] + * stride = view.strides[dim] # <<<<<<<<<<<<<< + * if view.suboffsets != NULL: + * suboffset = view.suboffsets[dim] + */ + __pyx_v_stride = (__pyx_v_view->strides[__pyx_v_dim]); + + /* "View.MemoryView":908 + * shape = view.shape[dim] + * stride = view.strides[dim] + * if view.suboffsets != NULL: # <<<<<<<<<<<<<< + * suboffset = view.suboffsets[dim] + * + */ + __pyx_t_2 = (__pyx_v_view->suboffsets != NULL); + if (__pyx_t_2) { + + /* "View.MemoryView":909 + * stride = view.strides[dim] + * if view.suboffsets != NULL: + * suboffset = view.suboffsets[dim] # <<<<<<<<<<<<<< + * + * if index < 0: + */ + __pyx_v_suboffset = (__pyx_v_view->suboffsets[__pyx_v_dim]); + + /* "View.MemoryView":908 + * shape = view.shape[dim] + * stride = view.strides[dim] + * if view.suboffsets != NULL: # <<<<<<<<<<<<<< + * suboffset = view.suboffsets[dim] + * + */ + } + } + __pyx_L3:; + + /* "View.MemoryView":911 + * suboffset = view.suboffsets[dim] + * + * if index < 0: # <<<<<<<<<<<<<< + * index += view.shape[dim] + * if index < 0: + */ + __pyx_t_2 = (__pyx_v_index < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":912 + * + * if index < 0: + * index += view.shape[dim] # <<<<<<<<<<<<<< + * if index < 0: + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + */ + __pyx_v_index = (__pyx_v_index + (__pyx_v_view->shape[__pyx_v_dim])); + + /* "View.MemoryView":913 + * if index < 0: + * index += view.shape[dim] + * if index < 0: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + __pyx_t_2 = (__pyx_v_index < 0); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":914 + * index += view.shape[dim] + * if index < 0: + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" # <<<<<<<<<<<<<< + * + * if index >= shape: + */ + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 914, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = 0; + __pyx_t_4 = 127; + __Pyx_INCREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_1 += 37; + __Pyx_GIVEREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_5 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_dim, 0, ' ', 'd'); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 914, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_5); + __Pyx_GIVEREF(__pyx_t_5); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_5); + __pyx_t_5 = 0; + __Pyx_INCREF(__pyx_kp_u__7); + __pyx_t_1 += 1; + __Pyx_GIVEREF(__pyx_kp_u__7); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_kp_u__7); + __pyx_t_5 = __Pyx_PyUnicode_Join(__pyx_t_3, 3, __pyx_t_1, __pyx_t_4); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 914, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_builtin_IndexError, __pyx_t_5, 0, 0); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __PYX_ERR(1, 914, __pyx_L1_error) + + /* "View.MemoryView":913 + * if index < 0: + * index += view.shape[dim] + * if index < 0: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + } + + /* "View.MemoryView":911 + * suboffset = view.suboffsets[dim] + * + * if index < 0: # <<<<<<<<<<<<<< + * index += view.shape[dim] + * if index < 0: + */ + } + + /* "View.MemoryView":916 + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + * if index >= shape: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + __pyx_t_2 = (__pyx_v_index >= __pyx_v_shape); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":917 + * + * if index >= shape: + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" # <<<<<<<<<<<<<< + * + * resultp = bufp + index * stride + */ + __pyx_t_5 = PyTuple_New(3); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 917, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 = 0; + __pyx_t_4 = 127; + __Pyx_INCREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_1 += 37; + __Pyx_GIVEREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_3 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_dim, 0, ' ', 'd'); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 917, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_3); + PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_3); + __pyx_t_3 = 0; + __Pyx_INCREF(__pyx_kp_u__7); + __pyx_t_1 += 1; + __Pyx_GIVEREF(__pyx_kp_u__7); + PyTuple_SET_ITEM(__pyx_t_5, 2, __pyx_kp_u__7); + __pyx_t_3 = __Pyx_PyUnicode_Join(__pyx_t_5, 3, __pyx_t_1, __pyx_t_4); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 917, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_Raise(__pyx_builtin_IndexError, __pyx_t_3, 0, 0); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __PYX_ERR(1, 917, __pyx_L1_error) + + /* "View.MemoryView":916 + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + * if index >= shape: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + } + + /* "View.MemoryView":919 + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + * resultp = bufp + index * stride # <<<<<<<<<<<<<< + * if suboffset >= 0: + * resultp = ( resultp)[0] + suboffset + */ + __pyx_v_resultp = (__pyx_v_bufp + (__pyx_v_index * __pyx_v_stride)); + + /* "View.MemoryView":920 + * + * resultp = bufp + index * stride + * if suboffset >= 0: # <<<<<<<<<<<<<< + * resultp = ( resultp)[0] + suboffset + * + */ + __pyx_t_2 = (__pyx_v_suboffset >= 0); + if (__pyx_t_2) { + + /* "View.MemoryView":921 + * resultp = bufp + index * stride + * if suboffset >= 0: + * resultp = ( resultp)[0] + suboffset # <<<<<<<<<<<<<< + * + * return resultp + */ + __pyx_v_resultp = ((((char **)__pyx_v_resultp)[0]) + __pyx_v_suboffset); + + /* "View.MemoryView":920 + * + * resultp = bufp + index * stride + * if suboffset >= 0: # <<<<<<<<<<<<<< + * resultp = ( resultp)[0] + suboffset + * + */ + } + + /* "View.MemoryView":923 + * resultp = ( resultp)[0] + suboffset + * + * return resultp # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = __pyx_v_resultp; + goto __pyx_L0; + + /* "View.MemoryView":896 + * + * @cname('__pyx_pybuffer_index') + * cdef char *pybuffer_index(Py_buffer *view, char *bufp, Py_ssize_t index, # <<<<<<<<<<<<<< + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.pybuffer_index", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":929 + * + * @cname('__pyx_memslice_transpose') + * cdef int transpose_memslice(__Pyx_memviewslice *memslice) except -1 nogil: # <<<<<<<<<<<<<< + * cdef int ndim = memslice.memview.view.ndim + * + */ + +static int __pyx_memslice_transpose(__Pyx_memviewslice *__pyx_v_memslice) { + int __pyx_v_ndim; + Py_ssize_t *__pyx_v_shape; + Py_ssize_t *__pyx_v_strides; + int __pyx_v_i; + int __pyx_v_j; + int __pyx_r; + int __pyx_t_1; + Py_ssize_t *__pyx_t_2; + long __pyx_t_3; + long __pyx_t_4; + Py_ssize_t __pyx_t_5; + Py_ssize_t __pyx_t_6; + int __pyx_t_7; + int __pyx_t_8; + int __pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":930 + * @cname('__pyx_memslice_transpose') + * cdef int transpose_memslice(__Pyx_memviewslice *memslice) except -1 nogil: + * cdef int ndim = memslice.memview.view.ndim # <<<<<<<<<<<<<< + * + * cdef Py_ssize_t *shape = memslice.shape + */ + __pyx_t_1 = __pyx_v_memslice->memview->view.ndim; + __pyx_v_ndim = __pyx_t_1; + + /* "View.MemoryView":932 + * cdef int ndim = memslice.memview.view.ndim + * + * cdef Py_ssize_t *shape = memslice.shape # <<<<<<<<<<<<<< + * cdef Py_ssize_t *strides = memslice.strides + * + */ + __pyx_t_2 = __pyx_v_memslice->shape; + __pyx_v_shape = __pyx_t_2; + + /* "View.MemoryView":933 + * + * cdef Py_ssize_t *shape = memslice.shape + * cdef Py_ssize_t *strides = memslice.strides # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = __pyx_v_memslice->strides; + __pyx_v_strides = __pyx_t_2; + + /* "View.MemoryView":937 + * + * cdef int i, j + * for i in range(ndim // 2): # <<<<<<<<<<<<<< + * j = ndim - 1 - i + * strides[i], strides[j] = strides[j], strides[i] + */ + __pyx_t_3 = __Pyx_div_long(__pyx_v_ndim, 2); + __pyx_t_4 = __pyx_t_3; + for (__pyx_t_1 = 0; __pyx_t_1 < __pyx_t_4; __pyx_t_1+=1) { + __pyx_v_i = __pyx_t_1; + + /* "View.MemoryView":938 + * cdef int i, j + * for i in range(ndim // 2): + * j = ndim - 1 - i # <<<<<<<<<<<<<< + * strides[i], strides[j] = strides[j], strides[i] + * shape[i], shape[j] = shape[j], shape[i] + */ + __pyx_v_j = ((__pyx_v_ndim - 1) - __pyx_v_i); + + /* "View.MemoryView":939 + * for i in range(ndim // 2): + * j = ndim - 1 - i + * strides[i], strides[j] = strides[j], strides[i] # <<<<<<<<<<<<<< + * shape[i], shape[j] = shape[j], shape[i] + * + */ + __pyx_t_5 = (__pyx_v_strides[__pyx_v_j]); + __pyx_t_6 = (__pyx_v_strides[__pyx_v_i]); + (__pyx_v_strides[__pyx_v_i]) = __pyx_t_5; + (__pyx_v_strides[__pyx_v_j]) = __pyx_t_6; + + /* "View.MemoryView":940 + * j = ndim - 1 - i + * strides[i], strides[j] = strides[j], strides[i] + * shape[i], shape[j] = shape[j], shape[i] # <<<<<<<<<<<<<< + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: + */ + __pyx_t_6 = (__pyx_v_shape[__pyx_v_j]); + __pyx_t_5 = (__pyx_v_shape[__pyx_v_i]); + (__pyx_v_shape[__pyx_v_i]) = __pyx_t_6; + (__pyx_v_shape[__pyx_v_j]) = __pyx_t_5; + + /* "View.MemoryView":942 + * shape[i], shape[j] = shape[j], shape[i] + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: # <<<<<<<<<<<<<< + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") + * + */ + __pyx_t_8 = ((__pyx_v_memslice->suboffsets[__pyx_v_i]) >= 0); + if (!__pyx_t_8) { + } else { + __pyx_t_7 = __pyx_t_8; + goto __pyx_L6_bool_binop_done; + } + __pyx_t_8 = ((__pyx_v_memslice->suboffsets[__pyx_v_j]) >= 0); + __pyx_t_7 = __pyx_t_8; + __pyx_L6_bool_binop_done:; + if (__pyx_t_7) { + + /* "View.MemoryView":943 + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") # <<<<<<<<<<<<<< + * + * return 0 + */ + __pyx_t_9 = __pyx_memoryview_err(PyExc_ValueError, __pyx_kp_s_Cannot_transpose_memoryview_with); if (unlikely(__pyx_t_9 == ((int)-1))) __PYX_ERR(1, 943, __pyx_L1_error) + + /* "View.MemoryView":942 + * shape[i], shape[j] = shape[j], shape[i] + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: # <<<<<<<<<<<<<< + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") + * + */ + } + } + + /* "View.MemoryView":945 + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") + * + * return 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":929 + * + * @cname('__pyx_memslice_transpose') + * cdef int transpose_memslice(__Pyx_memviewslice *memslice) except -1 nogil: # <<<<<<<<<<<<<< + * cdef int ndim = memslice.memview.view.ndim + * + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.transpose_memslice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":963 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + */ + +/* Python wrapper */ +static void __pyx_memoryviewslice___dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_memoryviewslice___dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_memoryviewslice___pyx_pf_15View_dot_MemoryView_16_memoryviewslice___dealloc__(((struct __pyx_memoryviewslice_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_memoryviewslice___pyx_pf_15View_dot_MemoryView_16_memoryviewslice___dealloc__(struct __pyx_memoryviewslice_obj *__pyx_v_self) { + + /* "View.MemoryView":964 + * + * def __dealloc__(self): + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) # <<<<<<<<<<<<<< + * + * cdef convert_item_to_object(self, char *itemp): + */ + __PYX_XCLEAR_MEMVIEW((&__pyx_v_self->from_slice), 1); + + /* "View.MemoryView":963 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + */ + + /* function exit code */ +} + +/* "View.MemoryView":966 + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * if self.to_object_func != NULL: + * return self.to_object_func(itemp) + */ + +static PyObject *__pyx_memoryviewslice_convert_item_to_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("convert_item_to_object", 1); + + /* "View.MemoryView":967 + * + * cdef convert_item_to_object(self, char *itemp): + * if self.to_object_func != NULL: # <<<<<<<<<<<<<< + * return self.to_object_func(itemp) + * else: + */ + __pyx_t_1 = (__pyx_v_self->to_object_func != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":968 + * cdef convert_item_to_object(self, char *itemp): + * if self.to_object_func != NULL: + * return self.to_object_func(itemp) # <<<<<<<<<<<<<< + * else: + * return memoryview.convert_item_to_object(self, itemp) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_v_self->to_object_func(__pyx_v_itemp); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 968, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":967 + * + * cdef convert_item_to_object(self, char *itemp): + * if self.to_object_func != NULL: # <<<<<<<<<<<<<< + * return self.to_object_func(itemp) + * else: + */ + } + + /* "View.MemoryView":970 + * return self.to_object_func(itemp) + * else: + * return memoryview.convert_item_to_object(self, itemp) # <<<<<<<<<<<<<< + * + * cdef assign_item_from_object(self, char *itemp, object value): + */ + /*else*/ { + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_memoryview_convert_item_to_object(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v_itemp); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 970, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + } + + /* "View.MemoryView":966 + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * if self.to_object_func != NULL: + * return self.to_object_func(itemp) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.convert_item_to_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":972 + * return memoryview.convert_item_to_object(self, itemp) + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * if self.to_dtype_func != NULL: + * self.to_dtype_func(itemp, value) + */ + +static PyObject *__pyx_memoryviewslice_assign_item_from_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("assign_item_from_object", 1); + + /* "View.MemoryView":973 + * + * cdef assign_item_from_object(self, char *itemp, object value): + * if self.to_dtype_func != NULL: # <<<<<<<<<<<<<< + * self.to_dtype_func(itemp, value) + * else: + */ + __pyx_t_1 = (__pyx_v_self->to_dtype_func != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":974 + * cdef assign_item_from_object(self, char *itemp, object value): + * if self.to_dtype_func != NULL: + * self.to_dtype_func(itemp, value) # <<<<<<<<<<<<<< + * else: + * memoryview.assign_item_from_object(self, itemp, value) + */ + __pyx_t_2 = __pyx_v_self->to_dtype_func(__pyx_v_itemp, __pyx_v_value); if (unlikely(__pyx_t_2 == ((int)0))) __PYX_ERR(1, 974, __pyx_L1_error) + + /* "View.MemoryView":973 + * + * cdef assign_item_from_object(self, char *itemp, object value): + * if self.to_dtype_func != NULL: # <<<<<<<<<<<<<< + * self.to_dtype_func(itemp, value) + * else: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":976 + * self.to_dtype_func(itemp, value) + * else: + * memoryview.assign_item_from_object(self, itemp, value) # <<<<<<<<<<<<<< + * + * cdef _get_base(self): + */ + /*else*/ { + __pyx_t_3 = __pyx_memoryview_assign_item_from_object(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v_itemp, __pyx_v_value); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 976, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_L3:; + + /* "View.MemoryView":972 + * return memoryview.convert_item_to_object(self, itemp) + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * if self.to_dtype_func != NULL: + * self.to_dtype_func(itemp, value) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.assign_item_from_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":978 + * memoryview.assign_item_from_object(self, itemp, value) + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.from_object + * + */ + +static PyObject *__pyx_memoryviewslice__get_base(struct __pyx_memoryviewslice_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("_get_base", 1); + + /* "View.MemoryView":979 + * + * cdef _get_base(self): + * return self.from_object # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->from_object); + __pyx_r = __pyx_v_self->from_object; + goto __pyx_L0; + + /* "View.MemoryView":978 + * memoryview.assign_item_from_object(self, itemp, value) + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.from_object + * + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryviewslice_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryviewslice_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_memoryviewslice___reduce_cython__(((struct __pyx_memoryviewslice_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryviewslice___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryviewslice_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryviewslice_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_memoryviewslice_2__setstate_cython__(((struct __pyx_memoryviewslice_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryviewslice_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":999 + * + * @cname('__pyx_memoryview_fromslice') + * cdef memoryview_fromslice(__Pyx_memviewslice memviewslice, # <<<<<<<<<<<<<< + * int ndim, + * object (*to_object_func)(char *), + */ + +static PyObject *__pyx_memoryview_fromslice(__Pyx_memviewslice __pyx_v_memviewslice, int __pyx_v_ndim, PyObject *(*__pyx_v_to_object_func)(char *), int (*__pyx_v_to_dtype_func)(char *, PyObject *), int __pyx_v_dtype_is_object) { + struct __pyx_memoryviewslice_obj *__pyx_v_result = 0; + Py_ssize_t __pyx_v_suboffset; + PyObject *__pyx_v_length = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + __Pyx_TypeInfo *__pyx_t_4; + Py_buffer __pyx_t_5; + Py_ssize_t *__pyx_t_6; + Py_ssize_t *__pyx_t_7; + Py_ssize_t *__pyx_t_8; + Py_ssize_t __pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_fromslice", 1); + + /* "View.MemoryView":1007 + * cdef _memoryviewslice result + * + * if memviewslice.memview == Py_None: # <<<<<<<<<<<<<< + * return None + * + */ + __pyx_t_1 = (((PyObject *)__pyx_v_memviewslice.memview) == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":1008 + * + * if memviewslice.memview == Py_None: + * return None # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "View.MemoryView":1007 + * cdef _memoryviewslice result + * + * if memviewslice.memview == Py_None: # <<<<<<<<<<<<<< + * return None + * + */ + } + + /* "View.MemoryView":1013 + * + * + * result = _memoryviewslice.__new__(_memoryviewslice, None, 0, dtype_is_object) # <<<<<<<<<<<<<< + * + * result.from_slice = memviewslice + */ + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_v_dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1013, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 1013, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(Py_None); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, Py_None)) __PYX_ERR(1, 1013, __pyx_L1_error); + __Pyx_INCREF(__pyx_int_0); + __Pyx_GIVEREF(__pyx_int_0); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_int_0)) __PYX_ERR(1, 1013, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_t_2)) __PYX_ERR(1, 1013, __pyx_L1_error); + __pyx_t_2 = 0; + __pyx_t_2 = ((PyObject *)__pyx_tp_new__memoryviewslice(((PyTypeObject *)__pyx_memoryviewslice_type), __pyx_t_3, NULL)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1013, __pyx_L1_error) + __Pyx_GOTREF((PyObject *)__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_v_result = ((struct __pyx_memoryviewslice_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":1015 + * result = _memoryviewslice.__new__(_memoryviewslice, None, 0, dtype_is_object) + * + * result.from_slice = memviewslice # <<<<<<<<<<<<<< + * __PYX_INC_MEMVIEW(&memviewslice, 1) + * + */ + __pyx_v_result->from_slice = __pyx_v_memviewslice; + + /* "View.MemoryView":1016 + * + * result.from_slice = memviewslice + * __PYX_INC_MEMVIEW(&memviewslice, 1) # <<<<<<<<<<<<<< + * + * result.from_object = ( memviewslice.memview)._get_base() + */ + __PYX_INC_MEMVIEW((&__pyx_v_memviewslice), 1); + + /* "View.MemoryView":1018 + * __PYX_INC_MEMVIEW(&memviewslice, 1) + * + * result.from_object = ( memviewslice.memview)._get_base() # <<<<<<<<<<<<<< + * result.typeinfo = memviewslice.memview.typeinfo + * + */ + __pyx_t_2 = ((struct __pyx_vtabstruct_memoryview *)((struct __pyx_memoryview_obj *)__pyx_v_memviewslice.memview)->__pyx_vtab)->_get_base(((struct __pyx_memoryview_obj *)__pyx_v_memviewslice.memview)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1018, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + __Pyx_GOTREF(__pyx_v_result->from_object); + __Pyx_DECREF(__pyx_v_result->from_object); + __pyx_v_result->from_object = __pyx_t_2; + __pyx_t_2 = 0; + + /* "View.MemoryView":1019 + * + * result.from_object = ( memviewslice.memview)._get_base() + * result.typeinfo = memviewslice.memview.typeinfo # <<<<<<<<<<<<<< + * + * result.view = memviewslice.memview.view + */ + __pyx_t_4 = __pyx_v_memviewslice.memview->typeinfo; + __pyx_v_result->__pyx_base.typeinfo = __pyx_t_4; + + /* "View.MemoryView":1021 + * result.typeinfo = memviewslice.memview.typeinfo + * + * result.view = memviewslice.memview.view # <<<<<<<<<<<<<< + * result.view.buf = memviewslice.data + * result.view.ndim = ndim + */ + __pyx_t_5 = __pyx_v_memviewslice.memview->view; + __pyx_v_result->__pyx_base.view = __pyx_t_5; + + /* "View.MemoryView":1022 + * + * result.view = memviewslice.memview.view + * result.view.buf = memviewslice.data # <<<<<<<<<<<<<< + * result.view.ndim = ndim + * (<__pyx_buffer *> &result.view).obj = Py_None + */ + __pyx_v_result->__pyx_base.view.buf = ((void *)__pyx_v_memviewslice.data); + + /* "View.MemoryView":1023 + * result.view = memviewslice.memview.view + * result.view.buf = memviewslice.data + * result.view.ndim = ndim # <<<<<<<<<<<<<< + * (<__pyx_buffer *> &result.view).obj = Py_None + * Py_INCREF(Py_None) + */ + __pyx_v_result->__pyx_base.view.ndim = __pyx_v_ndim; + + /* "View.MemoryView":1024 + * result.view.buf = memviewslice.data + * result.view.ndim = ndim + * (<__pyx_buffer *> &result.view).obj = Py_None # <<<<<<<<<<<<<< + * Py_INCREF(Py_None) + * + */ + ((Py_buffer *)(&__pyx_v_result->__pyx_base.view))->obj = Py_None; + + /* "View.MemoryView":1025 + * result.view.ndim = ndim + * (<__pyx_buffer *> &result.view).obj = Py_None + * Py_INCREF(Py_None) # <<<<<<<<<<<<<< + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: + */ + Py_INCREF(Py_None); + + /* "View.MemoryView":1027 + * Py_INCREF(Py_None) + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: # <<<<<<<<<<<<<< + * result.flags = PyBUF_RECORDS + * else: + */ + __pyx_t_1 = ((((struct __pyx_memoryview_obj *)__pyx_v_memviewslice.memview)->flags & PyBUF_WRITABLE) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":1028 + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: + * result.flags = PyBUF_RECORDS # <<<<<<<<<<<<<< + * else: + * result.flags = PyBUF_RECORDS_RO + */ + __pyx_v_result->__pyx_base.flags = PyBUF_RECORDS; + + /* "View.MemoryView":1027 + * Py_INCREF(Py_None) + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: # <<<<<<<<<<<<<< + * result.flags = PyBUF_RECORDS + * else: + */ + goto __pyx_L4; + } + + /* "View.MemoryView":1030 + * result.flags = PyBUF_RECORDS + * else: + * result.flags = PyBUF_RECORDS_RO # <<<<<<<<<<<<<< + * + * result.view.shape = result.from_slice.shape + */ + /*else*/ { + __pyx_v_result->__pyx_base.flags = PyBUF_RECORDS_RO; + } + __pyx_L4:; + + /* "View.MemoryView":1032 + * result.flags = PyBUF_RECORDS_RO + * + * result.view.shape = result.from_slice.shape # <<<<<<<<<<<<<< + * result.view.strides = result.from_slice.strides + * + */ + __pyx_v_result->__pyx_base.view.shape = ((Py_ssize_t *)__pyx_v_result->from_slice.shape); + + /* "View.MemoryView":1033 + * + * result.view.shape = result.from_slice.shape + * result.view.strides = result.from_slice.strides # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_result->__pyx_base.view.strides = ((Py_ssize_t *)__pyx_v_result->from_slice.strides); + + /* "View.MemoryView":1036 + * + * + * result.view.suboffsets = NULL # <<<<<<<<<<<<<< + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: + */ + __pyx_v_result->__pyx_base.view.suboffsets = NULL; + + /* "View.MemoryView":1037 + * + * result.view.suboffsets = NULL + * for suboffset in result.from_slice.suboffsets[:ndim]: # <<<<<<<<<<<<<< + * if suboffset >= 0: + * result.view.suboffsets = result.from_slice.suboffsets + */ + __pyx_t_7 = (__pyx_v_result->from_slice.suboffsets + __pyx_v_ndim); + for (__pyx_t_8 = __pyx_v_result->from_slice.suboffsets; __pyx_t_8 < __pyx_t_7; __pyx_t_8++) { + __pyx_t_6 = __pyx_t_8; + __pyx_v_suboffset = (__pyx_t_6[0]); + + /* "View.MemoryView":1038 + * result.view.suboffsets = NULL + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * result.view.suboffsets = result.from_slice.suboffsets + * break + */ + __pyx_t_1 = (__pyx_v_suboffset >= 0); + if (__pyx_t_1) { + + /* "View.MemoryView":1039 + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: + * result.view.suboffsets = result.from_slice.suboffsets # <<<<<<<<<<<<<< + * break + * + */ + __pyx_v_result->__pyx_base.view.suboffsets = ((Py_ssize_t *)__pyx_v_result->from_slice.suboffsets); + + /* "View.MemoryView":1040 + * if suboffset >= 0: + * result.view.suboffsets = result.from_slice.suboffsets + * break # <<<<<<<<<<<<<< + * + * result.view.len = result.view.itemsize + */ + goto __pyx_L6_break; + + /* "View.MemoryView":1038 + * result.view.suboffsets = NULL + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * result.view.suboffsets = result.from_slice.suboffsets + * break + */ + } + } + __pyx_L6_break:; + + /* "View.MemoryView":1042 + * break + * + * result.view.len = result.view.itemsize # <<<<<<<<<<<<<< + * for length in result.view.shape[:ndim]: + * result.view.len *= length + */ + __pyx_t_9 = __pyx_v_result->__pyx_base.view.itemsize; + __pyx_v_result->__pyx_base.view.len = __pyx_t_9; + + /* "View.MemoryView":1043 + * + * result.view.len = result.view.itemsize + * for length in result.view.shape[:ndim]: # <<<<<<<<<<<<<< + * result.view.len *= length + * + */ + __pyx_t_7 = (__pyx_v_result->__pyx_base.view.shape + __pyx_v_ndim); + for (__pyx_t_8 = __pyx_v_result->__pyx_base.view.shape; __pyx_t_8 < __pyx_t_7; __pyx_t_8++) { + __pyx_t_6 = __pyx_t_8; + __pyx_t_2 = PyInt_FromSsize_t((__pyx_t_6[0])); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1043, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_XDECREF_SET(__pyx_v_length, __pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":1044 + * result.view.len = result.view.itemsize + * for length in result.view.shape[:ndim]: + * result.view.len *= length # <<<<<<<<<<<<<< + * + * result.to_object_func = to_object_func + */ + __pyx_t_2 = PyInt_FromSsize_t(__pyx_v_result->__pyx_base.view.len); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1044, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyNumber_InPlaceMultiply(__pyx_t_2, __pyx_v_length); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 1044, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_9 = __Pyx_PyIndex_AsSsize_t(__pyx_t_3); if (unlikely((__pyx_t_9 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 1044, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_v_result->__pyx_base.view.len = __pyx_t_9; + } + + /* "View.MemoryView":1046 + * result.view.len *= length + * + * result.to_object_func = to_object_func # <<<<<<<<<<<<<< + * result.to_dtype_func = to_dtype_func + * + */ + __pyx_v_result->to_object_func = __pyx_v_to_object_func; + + /* "View.MemoryView":1047 + * + * result.to_object_func = to_object_func + * result.to_dtype_func = to_dtype_func # <<<<<<<<<<<<<< + * + * return result + */ + __pyx_v_result->to_dtype_func = __pyx_v_to_dtype_func; + + /* "View.MemoryView":1049 + * result.to_dtype_func = to_dtype_func + * + * return result # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_get_slice_from_memoryview') + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = ((PyObject *)__pyx_v_result); + goto __pyx_L0; + + /* "View.MemoryView":999 + * + * @cname('__pyx_memoryview_fromslice') + * cdef memoryview_fromslice(__Pyx_memviewslice memviewslice, # <<<<<<<<<<<<<< + * int ndim, + * object (*to_object_func)(char *), + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview_fromslice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XDECREF(__pyx_v_length); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1052 + * + * @cname('__pyx_memoryview_get_slice_from_memoryview') + * cdef __Pyx_memviewslice *get_slice_from_memview(memoryview memview, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + */ + +static __Pyx_memviewslice *__pyx_memoryview_get_slice_from_memoryview(struct __pyx_memoryview_obj *__pyx_v_memview, __Pyx_memviewslice *__pyx_v_mslice) { + struct __pyx_memoryviewslice_obj *__pyx_v_obj = 0; + __Pyx_memviewslice *__pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_slice_from_memview", 1); + + /* "View.MemoryView":1055 + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * obj = memview + * return &obj.from_slice + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":1056 + * cdef _memoryviewslice obj + * if isinstance(memview, _memoryviewslice): + * obj = memview # <<<<<<<<<<<<<< + * return &obj.from_slice + * else: + */ + if (!(likely(((((PyObject *)__pyx_v_memview)) == Py_None) || likely(__Pyx_TypeTest(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type))))) __PYX_ERR(1, 1056, __pyx_L1_error) + __pyx_t_2 = ((PyObject *)__pyx_v_memview); + __Pyx_INCREF(__pyx_t_2); + __pyx_v_obj = ((struct __pyx_memoryviewslice_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":1057 + * if isinstance(memview, _memoryviewslice): + * obj = memview + * return &obj.from_slice # <<<<<<<<<<<<<< + * else: + * slice_copy(memview, mslice) + */ + __pyx_r = (&__pyx_v_obj->from_slice); + goto __pyx_L0; + + /* "View.MemoryView":1055 + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * obj = memview + * return &obj.from_slice + */ + } + + /* "View.MemoryView":1059 + * return &obj.from_slice + * else: + * slice_copy(memview, mslice) # <<<<<<<<<<<<<< + * return mslice + * + */ + /*else*/ { + __pyx_memoryview_slice_copy(__pyx_v_memview, __pyx_v_mslice); + + /* "View.MemoryView":1060 + * else: + * slice_copy(memview, mslice) + * return mslice # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_slice_copy') + */ + __pyx_r = __pyx_v_mslice; + goto __pyx_L0; + } + + /* "View.MemoryView":1052 + * + * @cname('__pyx_memoryview_get_slice_from_memoryview') + * cdef __Pyx_memviewslice *get_slice_from_memview(memoryview memview, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.get_slice_from_memview", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_obj); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1063 + * + * @cname('__pyx_memoryview_slice_copy') + * cdef void slice_copy(memoryview memview, __Pyx_memviewslice *dst) noexcept: # <<<<<<<<<<<<<< + * cdef int dim + * cdef (Py_ssize_t*) shape, strides, suboffsets + */ + +static void __pyx_memoryview_slice_copy(struct __pyx_memoryview_obj *__pyx_v_memview, __Pyx_memviewslice *__pyx_v_dst) { + int __pyx_v_dim; + Py_ssize_t *__pyx_v_shape; + Py_ssize_t *__pyx_v_strides; + Py_ssize_t *__pyx_v_suboffsets; + Py_ssize_t *__pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + Py_ssize_t __pyx_t_5; + int __pyx_t_6; + + /* "View.MemoryView":1067 + * cdef (Py_ssize_t*) shape, strides, suboffsets + * + * shape = memview.view.shape # <<<<<<<<<<<<<< + * strides = memview.view.strides + * suboffsets = memview.view.suboffsets + */ + __pyx_t_1 = __pyx_v_memview->view.shape; + __pyx_v_shape = __pyx_t_1; + + /* "View.MemoryView":1068 + * + * shape = memview.view.shape + * strides = memview.view.strides # <<<<<<<<<<<<<< + * suboffsets = memview.view.suboffsets + * + */ + __pyx_t_1 = __pyx_v_memview->view.strides; + __pyx_v_strides = __pyx_t_1; + + /* "View.MemoryView":1069 + * shape = memview.view.shape + * strides = memview.view.strides + * suboffsets = memview.view.suboffsets # <<<<<<<<<<<<<< + * + * dst.memview = <__pyx_memoryview *> memview + */ + __pyx_t_1 = __pyx_v_memview->view.suboffsets; + __pyx_v_suboffsets = __pyx_t_1; + + /* "View.MemoryView":1071 + * suboffsets = memview.view.suboffsets + * + * dst.memview = <__pyx_memoryview *> memview # <<<<<<<<<<<<<< + * dst.data = memview.view.buf + * + */ + __pyx_v_dst->memview = ((struct __pyx_memoryview_obj *)__pyx_v_memview); + + /* "View.MemoryView":1072 + * + * dst.memview = <__pyx_memoryview *> memview + * dst.data = memview.view.buf # <<<<<<<<<<<<<< + * + * for dim in range(memview.view.ndim): + */ + __pyx_v_dst->data = ((char *)__pyx_v_memview->view.buf); + + /* "View.MemoryView":1074 + * dst.data = memview.view.buf + * + * for dim in range(memview.view.ndim): # <<<<<<<<<<<<<< + * dst.shape[dim] = shape[dim] + * dst.strides[dim] = strides[dim] + */ + __pyx_t_2 = __pyx_v_memview->view.ndim; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_dim = __pyx_t_4; + + /* "View.MemoryView":1075 + * + * for dim in range(memview.view.ndim): + * dst.shape[dim] = shape[dim] # <<<<<<<<<<<<<< + * dst.strides[dim] = strides[dim] + * dst.suboffsets[dim] = suboffsets[dim] if suboffsets else -1 + */ + (__pyx_v_dst->shape[__pyx_v_dim]) = (__pyx_v_shape[__pyx_v_dim]); + + /* "View.MemoryView":1076 + * for dim in range(memview.view.ndim): + * dst.shape[dim] = shape[dim] + * dst.strides[dim] = strides[dim] # <<<<<<<<<<<<<< + * dst.suboffsets[dim] = suboffsets[dim] if suboffsets else -1 + * + */ + (__pyx_v_dst->strides[__pyx_v_dim]) = (__pyx_v_strides[__pyx_v_dim]); + + /* "View.MemoryView":1077 + * dst.shape[dim] = shape[dim] + * dst.strides[dim] = strides[dim] + * dst.suboffsets[dim] = suboffsets[dim] if suboffsets else -1 # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_copy_object') + */ + __pyx_t_6 = (__pyx_v_suboffsets != 0); + if (__pyx_t_6) { + __pyx_t_5 = (__pyx_v_suboffsets[__pyx_v_dim]); + } else { + __pyx_t_5 = -1L; + } + (__pyx_v_dst->suboffsets[__pyx_v_dim]) = __pyx_t_5; + } + + /* "View.MemoryView":1063 + * + * @cname('__pyx_memoryview_slice_copy') + * cdef void slice_copy(memoryview memview, __Pyx_memviewslice *dst) noexcept: # <<<<<<<<<<<<<< + * cdef int dim + * cdef (Py_ssize_t*) shape, strides, suboffsets + */ + + /* function exit code */ +} + +/* "View.MemoryView":1080 + * + * @cname('__pyx_memoryview_copy_object') + * cdef memoryview_copy(memoryview memview): # <<<<<<<<<<<<<< + * "Create a new memoryview object" + * cdef __Pyx_memviewslice memviewslice + */ + +static PyObject *__pyx_memoryview_copy_object(struct __pyx_memoryview_obj *__pyx_v_memview) { + __Pyx_memviewslice __pyx_v_memviewslice; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_copy", 1); + + /* "View.MemoryView":1083 + * "Create a new memoryview object" + * cdef __Pyx_memviewslice memviewslice + * slice_copy(memview, &memviewslice) # <<<<<<<<<<<<<< + * return memoryview_copy_from_slice(memview, &memviewslice) + * + */ + __pyx_memoryview_slice_copy(__pyx_v_memview, (&__pyx_v_memviewslice)); + + /* "View.MemoryView":1084 + * cdef __Pyx_memviewslice memviewslice + * slice_copy(memview, &memviewslice) + * return memoryview_copy_from_slice(memview, &memviewslice) # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_copy_object_from_slice') + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __pyx_memoryview_copy_object_from_slice(__pyx_v_memview, (&__pyx_v_memviewslice)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 1084, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":1080 + * + * @cname('__pyx_memoryview_copy_object') + * cdef memoryview_copy(memoryview memview): # <<<<<<<<<<<<<< + * "Create a new memoryview object" + * cdef __Pyx_memviewslice memviewslice + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview_copy", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1087 + * + * @cname('__pyx_memoryview_copy_object_from_slice') + * cdef memoryview_copy_from_slice(memoryview memview, __Pyx_memviewslice *memviewslice): # <<<<<<<<<<<<<< + * """ + * Create a new memoryview object from a given memoryview object and slice. + */ + +static PyObject *__pyx_memoryview_copy_object_from_slice(struct __pyx_memoryview_obj *__pyx_v_memview, __Pyx_memviewslice *__pyx_v_memviewslice) { + PyObject *(*__pyx_v_to_object_func)(char *); + int (*__pyx_v_to_dtype_func)(char *, PyObject *); + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *(*__pyx_t_2)(char *); + int (*__pyx_t_3)(char *, PyObject *); + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_copy_from_slice", 1); + + /* "View.MemoryView":1094 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * to_object_func = (<_memoryviewslice> memview).to_object_func + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":1095 + * + * if isinstance(memview, _memoryviewslice): + * to_object_func = (<_memoryviewslice> memview).to_object_func # <<<<<<<<<<<<<< + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + * else: + */ + __pyx_t_2 = ((struct __pyx_memoryviewslice_obj *)__pyx_v_memview)->to_object_func; + __pyx_v_to_object_func = __pyx_t_2; + + /* "View.MemoryView":1096 + * if isinstance(memview, _memoryviewslice): + * to_object_func = (<_memoryviewslice> memview).to_object_func + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func # <<<<<<<<<<<<<< + * else: + * to_object_func = NULL + */ + __pyx_t_3 = ((struct __pyx_memoryviewslice_obj *)__pyx_v_memview)->to_dtype_func; + __pyx_v_to_dtype_func = __pyx_t_3; + + /* "View.MemoryView":1094 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * to_object_func = (<_memoryviewslice> memview).to_object_func + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1098 + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + * else: + * to_object_func = NULL # <<<<<<<<<<<<<< + * to_dtype_func = NULL + * + */ + /*else*/ { + __pyx_v_to_object_func = NULL; + + /* "View.MemoryView":1099 + * else: + * to_object_func = NULL + * to_dtype_func = NULL # <<<<<<<<<<<<<< + * + * return memoryview_fromslice(memviewslice[0], memview.view.ndim, + */ + __pyx_v_to_dtype_func = NULL; + } + __pyx_L3:; + + /* "View.MemoryView":1101 + * to_dtype_func = NULL + * + * return memoryview_fromslice(memviewslice[0], memview.view.ndim, # <<<<<<<<<<<<<< + * to_object_func, to_dtype_func, + * memview.dtype_is_object) + */ + __Pyx_XDECREF(__pyx_r); + + /* "View.MemoryView":1103 + * return memoryview_fromslice(memviewslice[0], memview.view.ndim, + * to_object_func, to_dtype_func, + * memview.dtype_is_object) # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_4 = __pyx_memoryview_fromslice((__pyx_v_memviewslice[0]), __pyx_v_memview->view.ndim, __pyx_v_to_object_func, __pyx_v_to_dtype_func, __pyx_v_memview->dtype_is_object); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1101, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_r = __pyx_t_4; + __pyx_t_4 = 0; + goto __pyx_L0; + + /* "View.MemoryView":1087 + * + * @cname('__pyx_memoryview_copy_object_from_slice') + * cdef memoryview_copy_from_slice(memoryview memview, __Pyx_memviewslice *memviewslice): # <<<<<<<<<<<<<< + * """ + * Create a new memoryview object from a given memoryview object and slice. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.memoryview_copy_from_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1109 + * + * + * cdef Py_ssize_t abs_py_ssize_t(Py_ssize_t arg) noexcept nogil: # <<<<<<<<<<<<<< + * return -arg if arg < 0 else arg + * + */ + +static Py_ssize_t abs_py_ssize_t(Py_ssize_t __pyx_v_arg) { + Py_ssize_t __pyx_r; + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + + /* "View.MemoryView":1110 + * + * cdef Py_ssize_t abs_py_ssize_t(Py_ssize_t arg) noexcept nogil: + * return -arg if arg < 0 else arg # <<<<<<<<<<<<<< + * + * @cname('__pyx_get_best_slice_order') + */ + __pyx_t_2 = (__pyx_v_arg < 0); + if (__pyx_t_2) { + __pyx_t_1 = (-__pyx_v_arg); + } else { + __pyx_t_1 = __pyx_v_arg; + } + __pyx_r = __pyx_t_1; + goto __pyx_L0; + + /* "View.MemoryView":1109 + * + * + * cdef Py_ssize_t abs_py_ssize_t(Py_ssize_t arg) noexcept nogil: # <<<<<<<<<<<<<< + * return -arg if arg < 0 else arg + * + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1113 + * + * @cname('__pyx_get_best_slice_order') + * cdef char get_best_order(__Pyx_memviewslice *mslice, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * """ + * Figure out the best memory access order for a given slice. + */ + +static char __pyx_get_best_slice_order(__Pyx_memviewslice *__pyx_v_mslice, int __pyx_v_ndim) { + int __pyx_v_i; + Py_ssize_t __pyx_v_c_stride; + Py_ssize_t __pyx_v_f_stride; + char __pyx_r; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + + /* "View.MemoryView":1118 + * """ + * cdef int i + * cdef Py_ssize_t c_stride = 0 # <<<<<<<<<<<<<< + * cdef Py_ssize_t f_stride = 0 + * + */ + __pyx_v_c_stride = 0; + + /* "View.MemoryView":1119 + * cdef int i + * cdef Py_ssize_t c_stride = 0 + * cdef Py_ssize_t f_stride = 0 # <<<<<<<<<<<<<< + * + * for i in range(ndim - 1, -1, -1): + */ + __pyx_v_f_stride = 0; + + /* "View.MemoryView":1121 + * cdef Py_ssize_t f_stride = 0 + * + * for i in range(ndim - 1, -1, -1): # <<<<<<<<<<<<<< + * if mslice.shape[i] > 1: + * c_stride = mslice.strides[i] + */ + for (__pyx_t_1 = (__pyx_v_ndim - 1); __pyx_t_1 > -1; __pyx_t_1-=1) { + __pyx_v_i = __pyx_t_1; + + /* "View.MemoryView":1122 + * + * for i in range(ndim - 1, -1, -1): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * c_stride = mslice.strides[i] + * break + */ + __pyx_t_2 = ((__pyx_v_mslice->shape[__pyx_v_i]) > 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1123 + * for i in range(ndim - 1, -1, -1): + * if mslice.shape[i] > 1: + * c_stride = mslice.strides[i] # <<<<<<<<<<<<<< + * break + * + */ + __pyx_v_c_stride = (__pyx_v_mslice->strides[__pyx_v_i]); + + /* "View.MemoryView":1124 + * if mslice.shape[i] > 1: + * c_stride = mslice.strides[i] + * break # <<<<<<<<<<<<<< + * + * for i in range(ndim): + */ + goto __pyx_L4_break; + + /* "View.MemoryView":1122 + * + * for i in range(ndim - 1, -1, -1): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * c_stride = mslice.strides[i] + * break + */ + } + } + __pyx_L4_break:; + + /* "View.MemoryView":1126 + * break + * + * for i in range(ndim): # <<<<<<<<<<<<<< + * if mslice.shape[i] > 1: + * f_stride = mslice.strides[i] + */ + __pyx_t_1 = __pyx_v_ndim; + __pyx_t_3 = __pyx_t_1; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1127 + * + * for i in range(ndim): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * f_stride = mslice.strides[i] + * break + */ + __pyx_t_2 = ((__pyx_v_mslice->shape[__pyx_v_i]) > 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1128 + * for i in range(ndim): + * if mslice.shape[i] > 1: + * f_stride = mslice.strides[i] # <<<<<<<<<<<<<< + * break + * + */ + __pyx_v_f_stride = (__pyx_v_mslice->strides[__pyx_v_i]); + + /* "View.MemoryView":1129 + * if mslice.shape[i] > 1: + * f_stride = mslice.strides[i] + * break # <<<<<<<<<<<<<< + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): + */ + goto __pyx_L7_break; + + /* "View.MemoryView":1127 + * + * for i in range(ndim): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * f_stride = mslice.strides[i] + * break + */ + } + } + __pyx_L7_break:; + + /* "View.MemoryView":1131 + * break + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): # <<<<<<<<<<<<<< + * return 'C' + * else: + */ + __pyx_t_2 = (abs_py_ssize_t(__pyx_v_c_stride) <= abs_py_ssize_t(__pyx_v_f_stride)); + if (__pyx_t_2) { + + /* "View.MemoryView":1132 + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): + * return 'C' # <<<<<<<<<<<<<< + * else: + * return 'F' + */ + __pyx_r = 'C'; + goto __pyx_L0; + + /* "View.MemoryView":1131 + * break + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): # <<<<<<<<<<<<<< + * return 'C' + * else: + */ + } + + /* "View.MemoryView":1134 + * return 'C' + * else: + * return 'F' # <<<<<<<<<<<<<< + * + * @cython.cdivision(True) + */ + /*else*/ { + __pyx_r = 'F'; + goto __pyx_L0; + } + + /* "View.MemoryView":1113 + * + * @cname('__pyx_get_best_slice_order') + * cdef char get_best_order(__Pyx_memviewslice *mslice, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * """ + * Figure out the best memory access order for a given slice. + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1137 + * + * @cython.cdivision(True) + * cdef void _copy_strided_to_strided(char *src_data, Py_ssize_t *src_strides, # <<<<<<<<<<<<<< + * char *dst_data, Py_ssize_t *dst_strides, + * Py_ssize_t *src_shape, Py_ssize_t *dst_shape, + */ + +static void _copy_strided_to_strided(char *__pyx_v_src_data, Py_ssize_t *__pyx_v_src_strides, char *__pyx_v_dst_data, Py_ssize_t *__pyx_v_dst_strides, Py_ssize_t *__pyx_v_src_shape, Py_ssize_t *__pyx_v_dst_shape, int __pyx_v_ndim, size_t __pyx_v_itemsize) { + CYTHON_UNUSED Py_ssize_t __pyx_v_i; + CYTHON_UNUSED Py_ssize_t __pyx_v_src_extent; + Py_ssize_t __pyx_v_dst_extent; + Py_ssize_t __pyx_v_src_stride; + Py_ssize_t __pyx_v_dst_stride; + int __pyx_t_1; + int __pyx_t_2; + Py_ssize_t __pyx_t_3; + Py_ssize_t __pyx_t_4; + Py_ssize_t __pyx_t_5; + + /* "View.MemoryView":1144 + * + * cdef Py_ssize_t i + * cdef Py_ssize_t src_extent = src_shape[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t dst_extent = dst_shape[0] + * cdef Py_ssize_t src_stride = src_strides[0] + */ + __pyx_v_src_extent = (__pyx_v_src_shape[0]); + + /* "View.MemoryView":1145 + * cdef Py_ssize_t i + * cdef Py_ssize_t src_extent = src_shape[0] + * cdef Py_ssize_t dst_extent = dst_shape[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t src_stride = src_strides[0] + * cdef Py_ssize_t dst_stride = dst_strides[0] + */ + __pyx_v_dst_extent = (__pyx_v_dst_shape[0]); + + /* "View.MemoryView":1146 + * cdef Py_ssize_t src_extent = src_shape[0] + * cdef Py_ssize_t dst_extent = dst_shape[0] + * cdef Py_ssize_t src_stride = src_strides[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t dst_stride = dst_strides[0] + * + */ + __pyx_v_src_stride = (__pyx_v_src_strides[0]); + + /* "View.MemoryView":1147 + * cdef Py_ssize_t dst_extent = dst_shape[0] + * cdef Py_ssize_t src_stride = src_strides[0] + * cdef Py_ssize_t dst_stride = dst_strides[0] # <<<<<<<<<<<<<< + * + * if ndim == 1: + */ + __pyx_v_dst_stride = (__pyx_v_dst_strides[0]); + + /* "View.MemoryView":1149 + * cdef Py_ssize_t dst_stride = dst_strides[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): + */ + __pyx_t_1 = (__pyx_v_ndim == 1); + if (__pyx_t_1) { + + /* "View.MemoryView":1150 + * + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and # <<<<<<<<<<<<<< + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) + */ + __pyx_t_2 = (__pyx_v_src_stride > 0); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L5_bool_binop_done; + } + __pyx_t_2 = (__pyx_v_dst_stride > 0); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L5_bool_binop_done; + } + + /* "View.MemoryView":1151 + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): # <<<<<<<<<<<<<< + * memcpy(dst_data, src_data, itemsize * dst_extent) + * else: + */ + __pyx_t_2 = (((size_t)__pyx_v_src_stride) == __pyx_v_itemsize); + if (__pyx_t_2) { + __pyx_t_2 = (__pyx_v_itemsize == ((size_t)__pyx_v_dst_stride)); + } + __pyx_t_1 = __pyx_t_2; + __pyx_L5_bool_binop_done:; + + /* "View.MemoryView":1150 + * + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and # <<<<<<<<<<<<<< + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) + */ + if (__pyx_t_1) { + + /* "View.MemoryView":1152 + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) # <<<<<<<<<<<<<< + * else: + * for i in range(dst_extent): + */ + (void)(memcpy(__pyx_v_dst_data, __pyx_v_src_data, (__pyx_v_itemsize * __pyx_v_dst_extent))); + + /* "View.MemoryView":1150 + * + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and # <<<<<<<<<<<<<< + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) + */ + goto __pyx_L4; + } + + /* "View.MemoryView":1154 + * memcpy(dst_data, src_data, itemsize * dst_extent) + * else: + * for i in range(dst_extent): # <<<<<<<<<<<<<< + * memcpy(dst_data, src_data, itemsize) + * src_data += src_stride + */ + /*else*/ { + __pyx_t_3 = __pyx_v_dst_extent; + __pyx_t_4 = __pyx_t_3; + for (__pyx_t_5 = 0; __pyx_t_5 < __pyx_t_4; __pyx_t_5+=1) { + __pyx_v_i = __pyx_t_5; + + /* "View.MemoryView":1155 + * else: + * for i in range(dst_extent): + * memcpy(dst_data, src_data, itemsize) # <<<<<<<<<<<<<< + * src_data += src_stride + * dst_data += dst_stride + */ + (void)(memcpy(__pyx_v_dst_data, __pyx_v_src_data, __pyx_v_itemsize)); + + /* "View.MemoryView":1156 + * for i in range(dst_extent): + * memcpy(dst_data, src_data, itemsize) + * src_data += src_stride # <<<<<<<<<<<<<< + * dst_data += dst_stride + * else: + */ + __pyx_v_src_data = (__pyx_v_src_data + __pyx_v_src_stride); + + /* "View.MemoryView":1157 + * memcpy(dst_data, src_data, itemsize) + * src_data += src_stride + * dst_data += dst_stride # <<<<<<<<<<<<<< + * else: + * for i in range(dst_extent): + */ + __pyx_v_dst_data = (__pyx_v_dst_data + __pyx_v_dst_stride); + } + } + __pyx_L4:; + + /* "View.MemoryView":1149 + * cdef Py_ssize_t dst_stride = dst_strides[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1159 + * dst_data += dst_stride + * else: + * for i in range(dst_extent): # <<<<<<<<<<<<<< + * _copy_strided_to_strided(src_data, src_strides + 1, + * dst_data, dst_strides + 1, + */ + /*else*/ { + __pyx_t_3 = __pyx_v_dst_extent; + __pyx_t_4 = __pyx_t_3; + for (__pyx_t_5 = 0; __pyx_t_5 < __pyx_t_4; __pyx_t_5+=1) { + __pyx_v_i = __pyx_t_5; + + /* "View.MemoryView":1160 + * else: + * for i in range(dst_extent): + * _copy_strided_to_strided(src_data, src_strides + 1, # <<<<<<<<<<<<<< + * dst_data, dst_strides + 1, + * src_shape + 1, dst_shape + 1, + */ + _copy_strided_to_strided(__pyx_v_src_data, (__pyx_v_src_strides + 1), __pyx_v_dst_data, (__pyx_v_dst_strides + 1), (__pyx_v_src_shape + 1), (__pyx_v_dst_shape + 1), (__pyx_v_ndim - 1), __pyx_v_itemsize); + + /* "View.MemoryView":1164 + * src_shape + 1, dst_shape + 1, + * ndim - 1, itemsize) + * src_data += src_stride # <<<<<<<<<<<<<< + * dst_data += dst_stride + * + */ + __pyx_v_src_data = (__pyx_v_src_data + __pyx_v_src_stride); + + /* "View.MemoryView":1165 + * ndim - 1, itemsize) + * src_data += src_stride + * dst_data += dst_stride # <<<<<<<<<<<<<< + * + * cdef void copy_strided_to_strided(__Pyx_memviewslice *src, + */ + __pyx_v_dst_data = (__pyx_v_dst_data + __pyx_v_dst_stride); + } + } + __pyx_L3:; + + /* "View.MemoryView":1137 + * + * @cython.cdivision(True) + * cdef void _copy_strided_to_strided(char *src_data, Py_ssize_t *src_strides, # <<<<<<<<<<<<<< + * char *dst_data, Py_ssize_t *dst_strides, + * Py_ssize_t *src_shape, Py_ssize_t *dst_shape, + */ + + /* function exit code */ +} + +/* "View.MemoryView":1167 + * dst_data += dst_stride + * + * cdef void copy_strided_to_strided(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * int ndim, size_t itemsize) noexcept nogil: + */ + +static void copy_strided_to_strided(__Pyx_memviewslice *__pyx_v_src, __Pyx_memviewslice *__pyx_v_dst, int __pyx_v_ndim, size_t __pyx_v_itemsize) { + + /* "View.MemoryView":1170 + * __Pyx_memviewslice *dst, + * int ndim, size_t itemsize) noexcept nogil: + * _copy_strided_to_strided(src.data, src.strides, dst.data, dst.strides, # <<<<<<<<<<<<<< + * src.shape, dst.shape, ndim, itemsize) + * + */ + _copy_strided_to_strided(__pyx_v_src->data, __pyx_v_src->strides, __pyx_v_dst->data, __pyx_v_dst->strides, __pyx_v_src->shape, __pyx_v_dst->shape, __pyx_v_ndim, __pyx_v_itemsize); + + /* "View.MemoryView":1167 + * dst_data += dst_stride + * + * cdef void copy_strided_to_strided(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * int ndim, size_t itemsize) noexcept nogil: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1174 + * + * @cname('__pyx_memoryview_slice_get_size') + * cdef Py_ssize_t slice_get_size(__Pyx_memviewslice *src, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * "Return the size of the memory occupied by the slice in number of bytes" + * cdef Py_ssize_t shape, size = src.memview.view.itemsize + */ + +static Py_ssize_t __pyx_memoryview_slice_get_size(__Pyx_memviewslice *__pyx_v_src, int __pyx_v_ndim) { + Py_ssize_t __pyx_v_shape; + Py_ssize_t __pyx_v_size; + Py_ssize_t __pyx_r; + Py_ssize_t __pyx_t_1; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + + /* "View.MemoryView":1176 + * cdef Py_ssize_t slice_get_size(__Pyx_memviewslice *src, int ndim) noexcept nogil: + * "Return the size of the memory occupied by the slice in number of bytes" + * cdef Py_ssize_t shape, size = src.memview.view.itemsize # <<<<<<<<<<<<<< + * + * for shape in src.shape[:ndim]: + */ + __pyx_t_1 = __pyx_v_src->memview->view.itemsize; + __pyx_v_size = __pyx_t_1; + + /* "View.MemoryView":1178 + * cdef Py_ssize_t shape, size = src.memview.view.itemsize + * + * for shape in src.shape[:ndim]: # <<<<<<<<<<<<<< + * size *= shape + * + */ + __pyx_t_3 = (__pyx_v_src->shape + __pyx_v_ndim); + for (__pyx_t_4 = __pyx_v_src->shape; __pyx_t_4 < __pyx_t_3; __pyx_t_4++) { + __pyx_t_2 = __pyx_t_4; + __pyx_v_shape = (__pyx_t_2[0]); + + /* "View.MemoryView":1179 + * + * for shape in src.shape[:ndim]: + * size *= shape # <<<<<<<<<<<<<< + * + * return size + */ + __pyx_v_size = (__pyx_v_size * __pyx_v_shape); + } + + /* "View.MemoryView":1181 + * size *= shape + * + * return size # <<<<<<<<<<<<<< + * + * @cname('__pyx_fill_contig_strides_array') + */ + __pyx_r = __pyx_v_size; + goto __pyx_L0; + + /* "View.MemoryView":1174 + * + * @cname('__pyx_memoryview_slice_get_size') + * cdef Py_ssize_t slice_get_size(__Pyx_memviewslice *src, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * "Return the size of the memory occupied by the slice in number of bytes" + * cdef Py_ssize_t shape, size = src.memview.view.itemsize + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1184 + * + * @cname('__pyx_fill_contig_strides_array') + * cdef Py_ssize_t fill_contig_strides_array( # <<<<<<<<<<<<<< + * Py_ssize_t *shape, Py_ssize_t *strides, Py_ssize_t stride, + * int ndim, char order) noexcept nogil: + */ + +static Py_ssize_t __pyx_fill_contig_strides_array(Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, Py_ssize_t __pyx_v_stride, int __pyx_v_ndim, char __pyx_v_order) { + int __pyx_v_idx; + Py_ssize_t __pyx_r; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + + /* "View.MemoryView":1193 + * cdef int idx + * + * if order == 'F': # <<<<<<<<<<<<<< + * for idx in range(ndim): + * strides[idx] = stride + */ + __pyx_t_1 = (__pyx_v_order == 'F'); + if (__pyx_t_1) { + + /* "View.MemoryView":1194 + * + * if order == 'F': + * for idx in range(ndim): # <<<<<<<<<<<<<< + * strides[idx] = stride + * stride *= shape[idx] + */ + __pyx_t_2 = __pyx_v_ndim; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_idx = __pyx_t_4; + + /* "View.MemoryView":1195 + * if order == 'F': + * for idx in range(ndim): + * strides[idx] = stride # <<<<<<<<<<<<<< + * stride *= shape[idx] + * else: + */ + (__pyx_v_strides[__pyx_v_idx]) = __pyx_v_stride; + + /* "View.MemoryView":1196 + * for idx in range(ndim): + * strides[idx] = stride + * stride *= shape[idx] # <<<<<<<<<<<<<< + * else: + * for idx in range(ndim - 1, -1, -1): + */ + __pyx_v_stride = (__pyx_v_stride * (__pyx_v_shape[__pyx_v_idx])); + } + + /* "View.MemoryView":1193 + * cdef int idx + * + * if order == 'F': # <<<<<<<<<<<<<< + * for idx in range(ndim): + * strides[idx] = stride + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1198 + * stride *= shape[idx] + * else: + * for idx in range(ndim - 1, -1, -1): # <<<<<<<<<<<<<< + * strides[idx] = stride + * stride *= shape[idx] + */ + /*else*/ { + for (__pyx_t_2 = (__pyx_v_ndim - 1); __pyx_t_2 > -1; __pyx_t_2-=1) { + __pyx_v_idx = __pyx_t_2; + + /* "View.MemoryView":1199 + * else: + * for idx in range(ndim - 1, -1, -1): + * strides[idx] = stride # <<<<<<<<<<<<<< + * stride *= shape[idx] + * + */ + (__pyx_v_strides[__pyx_v_idx]) = __pyx_v_stride; + + /* "View.MemoryView":1200 + * for idx in range(ndim - 1, -1, -1): + * strides[idx] = stride + * stride *= shape[idx] # <<<<<<<<<<<<<< + * + * return stride + */ + __pyx_v_stride = (__pyx_v_stride * (__pyx_v_shape[__pyx_v_idx])); + } + } + __pyx_L3:; + + /* "View.MemoryView":1202 + * stride *= shape[idx] + * + * return stride # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_copy_data_to_temp') + */ + __pyx_r = __pyx_v_stride; + goto __pyx_L0; + + /* "View.MemoryView":1184 + * + * @cname('__pyx_fill_contig_strides_array') + * cdef Py_ssize_t fill_contig_strides_array( # <<<<<<<<<<<<<< + * Py_ssize_t *shape, Py_ssize_t *strides, Py_ssize_t stride, + * int ndim, char order) noexcept nogil: + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1205 + * + * @cname('__pyx_memoryview_copy_data_to_temp') + * cdef void *copy_data_to_temp(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *tmpslice, + * char order, + */ + +static void *__pyx_memoryview_copy_data_to_temp(__Pyx_memviewslice *__pyx_v_src, __Pyx_memviewslice *__pyx_v_tmpslice, char __pyx_v_order, int __pyx_v_ndim) { + int __pyx_v_i; + void *__pyx_v_result; + size_t __pyx_v_itemsize; + size_t __pyx_v_size; + void *__pyx_r; + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + struct __pyx_memoryview_obj *__pyx_t_4; + int __pyx_t_5; + int __pyx_t_6; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":1216 + * cdef void *result + * + * cdef size_t itemsize = src.memview.view.itemsize # <<<<<<<<<<<<<< + * cdef size_t size = slice_get_size(src, ndim) + * + */ + __pyx_t_1 = __pyx_v_src->memview->view.itemsize; + __pyx_v_itemsize = __pyx_t_1; + + /* "View.MemoryView":1217 + * + * cdef size_t itemsize = src.memview.view.itemsize + * cdef size_t size = slice_get_size(src, ndim) # <<<<<<<<<<<<<< + * + * result = malloc(size) + */ + __pyx_v_size = __pyx_memoryview_slice_get_size(__pyx_v_src, __pyx_v_ndim); + + /* "View.MemoryView":1219 + * cdef size_t size = slice_get_size(src, ndim) + * + * result = malloc(size) # <<<<<<<<<<<<<< + * if not result: + * _err_no_memory() + */ + __pyx_v_result = malloc(__pyx_v_size); + + /* "View.MemoryView":1220 + * + * result = malloc(size) + * if not result: # <<<<<<<<<<<<<< + * _err_no_memory() + * + */ + __pyx_t_2 = (!(__pyx_v_result != 0)); + if (__pyx_t_2) { + + /* "View.MemoryView":1221 + * result = malloc(size) + * if not result: + * _err_no_memory() # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_3 = __pyx_memoryview_err_no_memory(); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 1221, __pyx_L1_error) + + /* "View.MemoryView":1220 + * + * result = malloc(size) + * if not result: # <<<<<<<<<<<<<< + * _err_no_memory() + * + */ + } + + /* "View.MemoryView":1224 + * + * + * tmpslice.data = result # <<<<<<<<<<<<<< + * tmpslice.memview = src.memview + * for i in range(ndim): + */ + __pyx_v_tmpslice->data = ((char *)__pyx_v_result); + + /* "View.MemoryView":1225 + * + * tmpslice.data = result + * tmpslice.memview = src.memview # <<<<<<<<<<<<<< + * for i in range(ndim): + * tmpslice.shape[i] = src.shape[i] + */ + __pyx_t_4 = __pyx_v_src->memview; + __pyx_v_tmpslice->memview = __pyx_t_4; + + /* "View.MemoryView":1226 + * tmpslice.data = result + * tmpslice.memview = src.memview + * for i in range(ndim): # <<<<<<<<<<<<<< + * tmpslice.shape[i] = src.shape[i] + * tmpslice.suboffsets[i] = -1 + */ + __pyx_t_3 = __pyx_v_ndim; + __pyx_t_5 = __pyx_t_3; + for (__pyx_t_6 = 0; __pyx_t_6 < __pyx_t_5; __pyx_t_6+=1) { + __pyx_v_i = __pyx_t_6; + + /* "View.MemoryView":1227 + * tmpslice.memview = src.memview + * for i in range(ndim): + * tmpslice.shape[i] = src.shape[i] # <<<<<<<<<<<<<< + * tmpslice.suboffsets[i] = -1 + * + */ + (__pyx_v_tmpslice->shape[__pyx_v_i]) = (__pyx_v_src->shape[__pyx_v_i]); + + /* "View.MemoryView":1228 + * for i in range(ndim): + * tmpslice.shape[i] = src.shape[i] + * tmpslice.suboffsets[i] = -1 # <<<<<<<<<<<<<< + * + * fill_contig_strides_array(&tmpslice.shape[0], &tmpslice.strides[0], itemsize, ndim, order) + */ + (__pyx_v_tmpslice->suboffsets[__pyx_v_i]) = -1L; + } + + /* "View.MemoryView":1230 + * tmpslice.suboffsets[i] = -1 + * + * fill_contig_strides_array(&tmpslice.shape[0], &tmpslice.strides[0], itemsize, ndim, order) # <<<<<<<<<<<<<< + * + * + */ + (void)(__pyx_fill_contig_strides_array((&(__pyx_v_tmpslice->shape[0])), (&(__pyx_v_tmpslice->strides[0])), __pyx_v_itemsize, __pyx_v_ndim, __pyx_v_order)); + + /* "View.MemoryView":1233 + * + * + * for i in range(ndim): # <<<<<<<<<<<<<< + * if tmpslice.shape[i] == 1: + * tmpslice.strides[i] = 0 + */ + __pyx_t_3 = __pyx_v_ndim; + __pyx_t_5 = __pyx_t_3; + for (__pyx_t_6 = 0; __pyx_t_6 < __pyx_t_5; __pyx_t_6+=1) { + __pyx_v_i = __pyx_t_6; + + /* "View.MemoryView":1234 + * + * for i in range(ndim): + * if tmpslice.shape[i] == 1: # <<<<<<<<<<<<<< + * tmpslice.strides[i] = 0 + * + */ + __pyx_t_2 = ((__pyx_v_tmpslice->shape[__pyx_v_i]) == 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1235 + * for i in range(ndim): + * if tmpslice.shape[i] == 1: + * tmpslice.strides[i] = 0 # <<<<<<<<<<<<<< + * + * if slice_is_contig(src[0], order, ndim): + */ + (__pyx_v_tmpslice->strides[__pyx_v_i]) = 0; + + /* "View.MemoryView":1234 + * + * for i in range(ndim): + * if tmpslice.shape[i] == 1: # <<<<<<<<<<<<<< + * tmpslice.strides[i] = 0 + * + */ + } + } + + /* "View.MemoryView":1237 + * tmpslice.strides[i] = 0 + * + * if slice_is_contig(src[0], order, ndim): # <<<<<<<<<<<<<< + * memcpy(result, src.data, size) + * else: + */ + __pyx_t_2 = __pyx_memviewslice_is_contig((__pyx_v_src[0]), __pyx_v_order, __pyx_v_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1238 + * + * if slice_is_contig(src[0], order, ndim): + * memcpy(result, src.data, size) # <<<<<<<<<<<<<< + * else: + * copy_strided_to_strided(src, tmpslice, ndim, itemsize) + */ + (void)(memcpy(__pyx_v_result, __pyx_v_src->data, __pyx_v_size)); + + /* "View.MemoryView":1237 + * tmpslice.strides[i] = 0 + * + * if slice_is_contig(src[0], order, ndim): # <<<<<<<<<<<<<< + * memcpy(result, src.data, size) + * else: + */ + goto __pyx_L9; + } + + /* "View.MemoryView":1240 + * memcpy(result, src.data, size) + * else: + * copy_strided_to_strided(src, tmpslice, ndim, itemsize) # <<<<<<<<<<<<<< + * + * return result + */ + /*else*/ { + copy_strided_to_strided(__pyx_v_src, __pyx_v_tmpslice, __pyx_v_ndim, __pyx_v_itemsize); + } + __pyx_L9:; + + /* "View.MemoryView":1242 + * copy_strided_to_strided(src, tmpslice, ndim, itemsize) + * + * return result # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = __pyx_v_result; + goto __pyx_L0; + + /* "View.MemoryView":1205 + * + * @cname('__pyx_memoryview_copy_data_to_temp') + * cdef void *copy_data_to_temp(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *tmpslice, + * char order, + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.copy_data_to_temp", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1247 + * + * @cname('__pyx_memoryview_err_extents') + * cdef int _err_extents(int i, Py_ssize_t extent1, # <<<<<<<<<<<<<< + * Py_ssize_t extent2) except -1 with gil: + * raise ValueError, f"got differing extents in dimension {i} (got {extent1} and {extent2})" + */ + +static int __pyx_memoryview_err_extents(int __pyx_v_i, Py_ssize_t __pyx_v_extent1, Py_ssize_t __pyx_v_extent2) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + Py_ssize_t __pyx_t_2; + Py_UCS4 __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_RefNannySetupContext("_err_extents", 0); + + /* "View.MemoryView":1249 + * cdef int _err_extents(int i, Py_ssize_t extent1, + * Py_ssize_t extent2) except -1 with gil: + * raise ValueError, f"got differing extents in dimension {i} (got {extent1} and {extent2})" # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_err_dim') + */ + __pyx_t_1 = PyTuple_New(7); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = 0; + __pyx_t_3 = 127; + __Pyx_INCREF(__pyx_kp_u_got_differing_extents_in_dimensi); + __pyx_t_2 += 35; + __Pyx_GIVEREF(__pyx_kp_u_got_differing_extents_in_dimensi); + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_kp_u_got_differing_extents_in_dimensi); + __pyx_t_4 = __Pyx_PyUnicode_From_int(__pyx_v_i, 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_2 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_t_4); + __pyx_t_4 = 0; + __Pyx_INCREF(__pyx_kp_u_got); + __pyx_t_2 += 6; + __Pyx_GIVEREF(__pyx_kp_u_got); + PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_kp_u_got); + __pyx_t_4 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_extent1, 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_2 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_1, 3, __pyx_t_4); + __pyx_t_4 = 0; + __Pyx_INCREF(__pyx_kp_u_and); + __pyx_t_2 += 5; + __Pyx_GIVEREF(__pyx_kp_u_and); + PyTuple_SET_ITEM(__pyx_t_1, 4, __pyx_kp_u_and); + __pyx_t_4 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_extent2, 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_2 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_1, 5, __pyx_t_4); + __pyx_t_4 = 0; + __Pyx_INCREF(__pyx_kp_u__7); + __pyx_t_2 += 1; + __Pyx_GIVEREF(__pyx_kp_u__7); + PyTuple_SET_ITEM(__pyx_t_1, 6, __pyx_kp_u__7); + __pyx_t_4 = __Pyx_PyUnicode_Join(__pyx_t_1, 7, __pyx_t_2, __pyx_t_3); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_t_4, 0, 0); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __PYX_ERR(1, 1249, __pyx_L1_error) + + /* "View.MemoryView":1247 + * + * @cname('__pyx_memoryview_err_extents') + * cdef int _err_extents(int i, Py_ssize_t extent1, # <<<<<<<<<<<<<< + * Py_ssize_t extent2) except -1 with gil: + * raise ValueError, f"got differing extents in dimension {i} (got {extent1} and {extent2})" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView._err_extents", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __Pyx_RefNannyFinishContext(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1252 + * + * @cname('__pyx_memoryview_err_dim') + * cdef int _err_dim(PyObject *error, str msg, int dim) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg % dim + * + */ + +static int __pyx_memoryview_err_dim(PyObject *__pyx_v_error, PyObject *__pyx_v_msg, int __pyx_v_dim) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_RefNannySetupContext("_err_dim", 0); + __Pyx_INCREF(__pyx_v_msg); + + /* "View.MemoryView":1253 + * @cname('__pyx_memoryview_err_dim') + * cdef int _err_dim(PyObject *error, str msg, int dim) except -1 with gil: + * raise error, msg % dim # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_err') + */ + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_dim); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 1253, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyString_FormatSafe(__pyx_v_msg, __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1253, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(((PyObject *)__pyx_v_error), __pyx_t_2, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(1, 1253, __pyx_L1_error) + + /* "View.MemoryView":1252 + * + * @cname('__pyx_memoryview_err_dim') + * cdef int _err_dim(PyObject *error, str msg, int dim) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg % dim + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView._err_dim", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __Pyx_XDECREF(__pyx_v_msg); + __Pyx_RefNannyFinishContext(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1256 + * + * @cname('__pyx_memoryview_err') + * cdef int _err(PyObject *error, str msg) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg + * + */ + +static int __pyx_memoryview_err(PyObject *__pyx_v_error, PyObject *__pyx_v_msg) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_RefNannySetupContext("_err", 0); + __Pyx_INCREF(__pyx_v_msg); + + /* "View.MemoryView":1257 + * @cname('__pyx_memoryview_err') + * cdef int _err(PyObject *error, str msg) except -1 with gil: + * raise error, msg # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_err_no_memory') + */ + __Pyx_Raise(((PyObject *)__pyx_v_error), __pyx_v_msg, 0, 0); + __PYX_ERR(1, 1257, __pyx_L1_error) + + /* "View.MemoryView":1256 + * + * @cname('__pyx_memoryview_err') + * cdef int _err(PyObject *error, str msg) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._err", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __Pyx_XDECREF(__pyx_v_msg); + __Pyx_RefNannyFinishContext(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1260 + * + * @cname('__pyx_memoryview_err_no_memory') + * cdef int _err_no_memory() except -1 with gil: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + +static int __pyx_memoryview_err_no_memory(void) { + int __pyx_r; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + + /* "View.MemoryView":1261 + * @cname('__pyx_memoryview_err_no_memory') + * cdef int _err_no_memory() except -1 with gil: + * raise MemoryError # <<<<<<<<<<<<<< + * + * + */ + PyErr_NoMemory(); __PYX_ERR(1, 1261, __pyx_L1_error) + + /* "View.MemoryView":1260 + * + * @cname('__pyx_memoryview_err_no_memory') + * cdef int _err_no_memory() except -1 with gil: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._err_no_memory", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1265 + * + * @cname('__pyx_memoryview_copy_contents') + * cdef int memoryview_copy_contents(__Pyx_memviewslice src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice dst, + * int src_ndim, int dst_ndim, + */ + +static int __pyx_memoryview_copy_contents(__Pyx_memviewslice __pyx_v_src, __Pyx_memviewslice __pyx_v_dst, int __pyx_v_src_ndim, int __pyx_v_dst_ndim, int __pyx_v_dtype_is_object) { + void *__pyx_v_tmpdata; + size_t __pyx_v_itemsize; + int __pyx_v_i; + char __pyx_v_order; + int __pyx_v_broadcasting; + int __pyx_v_direct_copy; + __Pyx_memviewslice __pyx_v_tmp; + int __pyx_v_ndim; + int __pyx_r; + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + int __pyx_t_5; + int __pyx_t_6; + void *__pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":1273 + * Check for overlapping memory and verify the shapes. + * """ + * cdef void *tmpdata = NULL # <<<<<<<<<<<<<< + * cdef size_t itemsize = src.memview.view.itemsize + * cdef int i + */ + __pyx_v_tmpdata = NULL; + + /* "View.MemoryView":1274 + * """ + * cdef void *tmpdata = NULL + * cdef size_t itemsize = src.memview.view.itemsize # <<<<<<<<<<<<<< + * cdef int i + * cdef char order = get_best_order(&src, src_ndim) + */ + __pyx_t_1 = __pyx_v_src.memview->view.itemsize; + __pyx_v_itemsize = __pyx_t_1; + + /* "View.MemoryView":1276 + * cdef size_t itemsize = src.memview.view.itemsize + * cdef int i + * cdef char order = get_best_order(&src, src_ndim) # <<<<<<<<<<<<<< + * cdef bint broadcasting = False + * cdef bint direct_copy = False + */ + __pyx_v_order = __pyx_get_best_slice_order((&__pyx_v_src), __pyx_v_src_ndim); + + /* "View.MemoryView":1277 + * cdef int i + * cdef char order = get_best_order(&src, src_ndim) + * cdef bint broadcasting = False # <<<<<<<<<<<<<< + * cdef bint direct_copy = False + * cdef __Pyx_memviewslice tmp + */ + __pyx_v_broadcasting = 0; + + /* "View.MemoryView":1278 + * cdef char order = get_best_order(&src, src_ndim) + * cdef bint broadcasting = False + * cdef bint direct_copy = False # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice tmp + * + */ + __pyx_v_direct_copy = 0; + + /* "View.MemoryView":1281 + * cdef __Pyx_memviewslice tmp + * + * if src_ndim < dst_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: + */ + __pyx_t_2 = (__pyx_v_src_ndim < __pyx_v_dst_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1282 + * + * if src_ndim < dst_ndim: + * broadcast_leading(&src, src_ndim, dst_ndim) # <<<<<<<<<<<<<< + * elif dst_ndim < src_ndim: + * broadcast_leading(&dst, dst_ndim, src_ndim) + */ + __pyx_memoryview_broadcast_leading((&__pyx_v_src), __pyx_v_src_ndim, __pyx_v_dst_ndim); + + /* "View.MemoryView":1281 + * cdef __Pyx_memviewslice tmp + * + * if src_ndim < dst_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1283 + * if src_ndim < dst_ndim: + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&dst, dst_ndim, src_ndim) + * + */ + __pyx_t_2 = (__pyx_v_dst_ndim < __pyx_v_src_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1284 + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: + * broadcast_leading(&dst, dst_ndim, src_ndim) # <<<<<<<<<<<<<< + * + * cdef int ndim = max(src_ndim, dst_ndim) + */ + __pyx_memoryview_broadcast_leading((&__pyx_v_dst), __pyx_v_dst_ndim, __pyx_v_src_ndim); + + /* "View.MemoryView":1283 + * if src_ndim < dst_ndim: + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&dst, dst_ndim, src_ndim) + * + */ + } + __pyx_L3:; + + /* "View.MemoryView":1286 + * broadcast_leading(&dst, dst_ndim, src_ndim) + * + * cdef int ndim = max(src_ndim, dst_ndim) # <<<<<<<<<<<<<< + * + * for i in range(ndim): + */ + __pyx_t_3 = __pyx_v_dst_ndim; + __pyx_t_4 = __pyx_v_src_ndim; + __pyx_t_2 = (__pyx_t_3 > __pyx_t_4); + if (__pyx_t_2) { + __pyx_t_5 = __pyx_t_3; + } else { + __pyx_t_5 = __pyx_t_4; + } + __pyx_v_ndim = __pyx_t_5; + + /* "View.MemoryView":1288 + * cdef int ndim = max(src_ndim, dst_ndim) + * + * for i in range(ndim): # <<<<<<<<<<<<<< + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: + */ + __pyx_t_5 = __pyx_v_ndim; + __pyx_t_3 = __pyx_t_5; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1289 + * + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: # <<<<<<<<<<<<<< + * if src.shape[i] == 1: + * broadcasting = True + */ + __pyx_t_2 = ((__pyx_v_src.shape[__pyx_v_i]) != (__pyx_v_dst.shape[__pyx_v_i])); + if (__pyx_t_2) { + + /* "View.MemoryView":1290 + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: # <<<<<<<<<<<<<< + * broadcasting = True + * src.strides[i] = 0 + */ + __pyx_t_2 = ((__pyx_v_src.shape[__pyx_v_i]) == 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1291 + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: + * broadcasting = True # <<<<<<<<<<<<<< + * src.strides[i] = 0 + * else: + */ + __pyx_v_broadcasting = 1; + + /* "View.MemoryView":1292 + * if src.shape[i] == 1: + * broadcasting = True + * src.strides[i] = 0 # <<<<<<<<<<<<<< + * else: + * _err_extents(i, dst.shape[i], src.shape[i]) + */ + (__pyx_v_src.strides[__pyx_v_i]) = 0; + + /* "View.MemoryView":1290 + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: # <<<<<<<<<<<<<< + * broadcasting = True + * src.strides[i] = 0 + */ + goto __pyx_L7; + } + + /* "View.MemoryView":1294 + * src.strides[i] = 0 + * else: + * _err_extents(i, dst.shape[i], src.shape[i]) # <<<<<<<<<<<<<< + * + * if src.suboffsets[i] >= 0: + */ + /*else*/ { + __pyx_t_6 = __pyx_memoryview_err_extents(__pyx_v_i, (__pyx_v_dst.shape[__pyx_v_i]), (__pyx_v_src.shape[__pyx_v_i])); if (unlikely(__pyx_t_6 == ((int)-1))) __PYX_ERR(1, 1294, __pyx_L1_error) + } + __pyx_L7:; + + /* "View.MemoryView":1289 + * + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: # <<<<<<<<<<<<<< + * if src.shape[i] == 1: + * broadcasting = True + */ + } + + /* "View.MemoryView":1296 + * _err_extents(i, dst.shape[i], src.shape[i]) + * + * if src.suboffsets[i] >= 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + */ + __pyx_t_2 = ((__pyx_v_src.suboffsets[__pyx_v_i]) >= 0); + if (__pyx_t_2) { + + /* "View.MemoryView":1297 + * + * if src.suboffsets[i] >= 0: + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) # <<<<<<<<<<<<<< + * + * if slices_overlap(&src, &dst, ndim, itemsize): + */ + __pyx_t_6 = __pyx_memoryview_err_dim(PyExc_ValueError, __pyx_kp_s_Dimension_d_is_not_direct, __pyx_v_i); if (unlikely(__pyx_t_6 == ((int)-1))) __PYX_ERR(1, 1297, __pyx_L1_error) + + /* "View.MemoryView":1296 + * _err_extents(i, dst.shape[i], src.shape[i]) + * + * if src.suboffsets[i] >= 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + */ + } + } + + /* "View.MemoryView":1299 + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + * if slices_overlap(&src, &dst, ndim, itemsize): # <<<<<<<<<<<<<< + * + * if not slice_is_contig(src, order, ndim): + */ + __pyx_t_2 = __pyx_slices_overlap((&__pyx_v_src), (&__pyx_v_dst), __pyx_v_ndim, __pyx_v_itemsize); + if (__pyx_t_2) { + + /* "View.MemoryView":1301 + * if slices_overlap(&src, &dst, ndim, itemsize): + * + * if not slice_is_contig(src, order, ndim): # <<<<<<<<<<<<<< + * order = get_best_order(&dst, ndim) + * + */ + __pyx_t_2 = (!__pyx_memviewslice_is_contig(__pyx_v_src, __pyx_v_order, __pyx_v_ndim)); + if (__pyx_t_2) { + + /* "View.MemoryView":1302 + * + * if not slice_is_contig(src, order, ndim): + * order = get_best_order(&dst, ndim) # <<<<<<<<<<<<<< + * + * tmpdata = copy_data_to_temp(&src, &tmp, order, ndim) + */ + __pyx_v_order = __pyx_get_best_slice_order((&__pyx_v_dst), __pyx_v_ndim); + + /* "View.MemoryView":1301 + * if slices_overlap(&src, &dst, ndim, itemsize): + * + * if not slice_is_contig(src, order, ndim): # <<<<<<<<<<<<<< + * order = get_best_order(&dst, ndim) + * + */ + } + + /* "View.MemoryView":1304 + * order = get_best_order(&dst, ndim) + * + * tmpdata = copy_data_to_temp(&src, &tmp, order, ndim) # <<<<<<<<<<<<<< + * src = tmp + * + */ + __pyx_t_7 = __pyx_memoryview_copy_data_to_temp((&__pyx_v_src), (&__pyx_v_tmp), __pyx_v_order, __pyx_v_ndim); if (unlikely(__pyx_t_7 == ((void *)NULL))) __PYX_ERR(1, 1304, __pyx_L1_error) + __pyx_v_tmpdata = __pyx_t_7; + + /* "View.MemoryView":1305 + * + * tmpdata = copy_data_to_temp(&src, &tmp, order, ndim) + * src = tmp # <<<<<<<<<<<<<< + * + * if not broadcasting: + */ + __pyx_v_src = __pyx_v_tmp; + + /* "View.MemoryView":1299 + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + * if slices_overlap(&src, &dst, ndim, itemsize): # <<<<<<<<<<<<<< + * + * if not slice_is_contig(src, order, ndim): + */ + } + + /* "View.MemoryView":1307 + * src = tmp + * + * if not broadcasting: # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = (!__pyx_v_broadcasting); + if (__pyx_t_2) { + + /* "View.MemoryView":1310 + * + * + * if slice_is_contig(src, 'C', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): + */ + __pyx_t_2 = __pyx_memviewslice_is_contig(__pyx_v_src, 'C', __pyx_v_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1311 + * + * if slice_is_contig(src, 'C', ndim): + * direct_copy = slice_is_contig(dst, 'C', ndim) # <<<<<<<<<<<<<< + * elif slice_is_contig(src, 'F', ndim): + * direct_copy = slice_is_contig(dst, 'F', ndim) + */ + __pyx_v_direct_copy = __pyx_memviewslice_is_contig(__pyx_v_dst, 'C', __pyx_v_ndim); + + /* "View.MemoryView":1310 + * + * + * if slice_is_contig(src, 'C', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): + */ + goto __pyx_L12; + } + + /* "View.MemoryView":1312 + * if slice_is_contig(src, 'C', ndim): + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + */ + __pyx_t_2 = __pyx_memviewslice_is_contig(__pyx_v_src, 'F', __pyx_v_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1313 + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): + * direct_copy = slice_is_contig(dst, 'F', ndim) # <<<<<<<<<<<<<< + * + * if direct_copy: + */ + __pyx_v_direct_copy = __pyx_memviewslice_is_contig(__pyx_v_dst, 'F', __pyx_v_ndim); + + /* "View.MemoryView":1312 + * if slice_is_contig(src, 'C', ndim): + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + */ + } + __pyx_L12:; + + /* "View.MemoryView":1315 + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + * if direct_copy: # <<<<<<<<<<<<<< + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + */ + if (__pyx_v_direct_copy) { + + /* "View.MemoryView":1317 + * if direct_copy: + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) # <<<<<<<<<<<<<< + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 0); + + /* "View.MemoryView":1318 + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) # <<<<<<<<<<<<<< + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * free(tmpdata) + */ + (void)(memcpy(__pyx_v_dst.data, __pyx_v_src.data, __pyx_memoryview_slice_get_size((&__pyx_v_src), __pyx_v_ndim))); + + /* "View.MemoryView":1319 + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) # <<<<<<<<<<<<<< + * free(tmpdata) + * return 0 + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 1); + + /* "View.MemoryView":1320 + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * free(tmpdata) # <<<<<<<<<<<<<< + * return 0 + * + */ + free(__pyx_v_tmpdata); + + /* "View.MemoryView":1321 + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * free(tmpdata) + * return 0 # <<<<<<<<<<<<<< + * + * if order == 'F' == get_best_order(&dst, ndim): + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":1315 + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + * if direct_copy: # <<<<<<<<<<<<<< + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + */ + } + + /* "View.MemoryView":1307 + * src = tmp + * + * if not broadcasting: # <<<<<<<<<<<<<< + * + * + */ + } + + /* "View.MemoryView":1323 + * return 0 + * + * if order == 'F' == get_best_order(&dst, ndim): # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = (__pyx_v_order == 'F'); + if (__pyx_t_2) { + __pyx_t_2 = ('F' == __pyx_get_best_slice_order((&__pyx_v_dst), __pyx_v_ndim)); + } + if (__pyx_t_2) { + + /* "View.MemoryView":1326 + * + * + * transpose_memslice(&src) # <<<<<<<<<<<<<< + * transpose_memslice(&dst) + * + */ + __pyx_t_5 = __pyx_memslice_transpose((&__pyx_v_src)); if (unlikely(__pyx_t_5 == ((int)-1))) __PYX_ERR(1, 1326, __pyx_L1_error) + + /* "View.MemoryView":1327 + * + * transpose_memslice(&src) + * transpose_memslice(&dst) # <<<<<<<<<<<<<< + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + */ + __pyx_t_5 = __pyx_memslice_transpose((&__pyx_v_dst)); if (unlikely(__pyx_t_5 == ((int)-1))) __PYX_ERR(1, 1327, __pyx_L1_error) + + /* "View.MemoryView":1323 + * return 0 + * + * if order == 'F' == get_best_order(&dst, ndim): # <<<<<<<<<<<<<< + * + * + */ + } + + /* "View.MemoryView":1329 + * transpose_memslice(&dst) + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) # <<<<<<<<<<<<<< + * copy_strided_to_strided(&src, &dst, ndim, itemsize) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 0); + + /* "View.MemoryView":1330 + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * copy_strided_to_strided(&src, &dst, ndim, itemsize) # <<<<<<<<<<<<<< + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * + */ + copy_strided_to_strided((&__pyx_v_src), (&__pyx_v_dst), __pyx_v_ndim, __pyx_v_itemsize); + + /* "View.MemoryView":1331 + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * copy_strided_to_strided(&src, &dst, ndim, itemsize) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) # <<<<<<<<<<<<<< + * + * free(tmpdata) + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 1); + + /* "View.MemoryView":1333 + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * + * free(tmpdata) # <<<<<<<<<<<<<< + * return 0 + * + */ + free(__pyx_v_tmpdata); + + /* "View.MemoryView":1334 + * + * free(tmpdata) + * return 0 # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_broadcast_leading') + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":1265 + * + * @cname('__pyx_memoryview_copy_contents') + * cdef int memoryview_copy_contents(__Pyx_memviewslice src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice dst, + * int src_ndim, int dst_ndim, + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.memoryview_copy_contents", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1337 + * + * @cname('__pyx_memoryview_broadcast_leading') + * cdef void broadcast_leading(__Pyx_memviewslice *mslice, # <<<<<<<<<<<<<< + * int ndim, + * int ndim_other) noexcept nogil: + */ + +static void __pyx_memoryview_broadcast_leading(__Pyx_memviewslice *__pyx_v_mslice, int __pyx_v_ndim, int __pyx_v_ndim_other) { + int __pyx_v_i; + int __pyx_v_offset; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + + /* "View.MemoryView":1341 + * int ndim_other) noexcept nogil: + * cdef int i + * cdef int offset = ndim_other - ndim # <<<<<<<<<<<<<< + * + * for i in range(ndim - 1, -1, -1): + */ + __pyx_v_offset = (__pyx_v_ndim_other - __pyx_v_ndim); + + /* "View.MemoryView":1343 + * cdef int offset = ndim_other - ndim + * + * for i in range(ndim - 1, -1, -1): # <<<<<<<<<<<<<< + * mslice.shape[i + offset] = mslice.shape[i] + * mslice.strides[i + offset] = mslice.strides[i] + */ + for (__pyx_t_1 = (__pyx_v_ndim - 1); __pyx_t_1 > -1; __pyx_t_1-=1) { + __pyx_v_i = __pyx_t_1; + + /* "View.MemoryView":1344 + * + * for i in range(ndim - 1, -1, -1): + * mslice.shape[i + offset] = mslice.shape[i] # <<<<<<<<<<<<<< + * mslice.strides[i + offset] = mslice.strides[i] + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] + */ + (__pyx_v_mslice->shape[(__pyx_v_i + __pyx_v_offset)]) = (__pyx_v_mslice->shape[__pyx_v_i]); + + /* "View.MemoryView":1345 + * for i in range(ndim - 1, -1, -1): + * mslice.shape[i + offset] = mslice.shape[i] + * mslice.strides[i + offset] = mslice.strides[i] # <<<<<<<<<<<<<< + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] + * + */ + (__pyx_v_mslice->strides[(__pyx_v_i + __pyx_v_offset)]) = (__pyx_v_mslice->strides[__pyx_v_i]); + + /* "View.MemoryView":1346 + * mslice.shape[i + offset] = mslice.shape[i] + * mslice.strides[i + offset] = mslice.strides[i] + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] # <<<<<<<<<<<<<< + * + * for i in range(offset): + */ + (__pyx_v_mslice->suboffsets[(__pyx_v_i + __pyx_v_offset)]) = (__pyx_v_mslice->suboffsets[__pyx_v_i]); + } + + /* "View.MemoryView":1348 + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] + * + * for i in range(offset): # <<<<<<<<<<<<<< + * mslice.shape[i] = 1 + * mslice.strides[i] = mslice.strides[0] + */ + __pyx_t_1 = __pyx_v_offset; + __pyx_t_2 = __pyx_t_1; + for (__pyx_t_3 = 0; __pyx_t_3 < __pyx_t_2; __pyx_t_3+=1) { + __pyx_v_i = __pyx_t_3; + + /* "View.MemoryView":1349 + * + * for i in range(offset): + * mslice.shape[i] = 1 # <<<<<<<<<<<<<< + * mslice.strides[i] = mslice.strides[0] + * mslice.suboffsets[i] = -1 + */ + (__pyx_v_mslice->shape[__pyx_v_i]) = 1; + + /* "View.MemoryView":1350 + * for i in range(offset): + * mslice.shape[i] = 1 + * mslice.strides[i] = mslice.strides[0] # <<<<<<<<<<<<<< + * mslice.suboffsets[i] = -1 + * + */ + (__pyx_v_mslice->strides[__pyx_v_i]) = (__pyx_v_mslice->strides[0]); + + /* "View.MemoryView":1351 + * mslice.shape[i] = 1 + * mslice.strides[i] = mslice.strides[0] + * mslice.suboffsets[i] = -1 # <<<<<<<<<<<<<< + * + * + */ + (__pyx_v_mslice->suboffsets[__pyx_v_i]) = -1L; + } + + /* "View.MemoryView":1337 + * + * @cname('__pyx_memoryview_broadcast_leading') + * cdef void broadcast_leading(__Pyx_memviewslice *mslice, # <<<<<<<<<<<<<< + * int ndim, + * int ndim_other) noexcept nogil: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1359 + * + * @cname('__pyx_memoryview_refcount_copying') + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: # <<<<<<<<<<<<<< + * + * if dtype_is_object: + */ + +static void __pyx_memoryview_refcount_copying(__Pyx_memviewslice *__pyx_v_dst, int __pyx_v_dtype_is_object, int __pyx_v_ndim, int __pyx_v_inc) { + + /* "View.MemoryView":1361 + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: + * + * if dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice_with_gil(dst.data, dst.shape, dst.strides, ndim, inc) + * + */ + if (__pyx_v_dtype_is_object) { + + /* "View.MemoryView":1362 + * + * if dtype_is_object: + * refcount_objects_in_slice_with_gil(dst.data, dst.shape, dst.strides, ndim, inc) # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_refcount_objects_in_slice_with_gil') + */ + __pyx_memoryview_refcount_objects_in_slice_with_gil(__pyx_v_dst->data, __pyx_v_dst->shape, __pyx_v_dst->strides, __pyx_v_ndim, __pyx_v_inc); + + /* "View.MemoryView":1361 + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: + * + * if dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice_with_gil(dst.data, dst.shape, dst.strides, ndim, inc) + * + */ + } + + /* "View.MemoryView":1359 + * + * @cname('__pyx_memoryview_refcount_copying') + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: # <<<<<<<<<<<<<< + * + * if dtype_is_object: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1365 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice_with_gil') + * cdef void refcount_objects_in_slice_with_gil(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * bint inc) noexcept with gil: + */ + +static void __pyx_memoryview_refcount_objects_in_slice_with_gil(char *__pyx_v_data, Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, int __pyx_v_ndim, int __pyx_v_inc) { + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + + /* "View.MemoryView":1368 + * Py_ssize_t *strides, int ndim, + * bint inc) noexcept with gil: + * refcount_objects_in_slice(data, shape, strides, ndim, inc) # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_refcount_objects_in_slice') + */ + __pyx_memoryview_refcount_objects_in_slice(__pyx_v_data, __pyx_v_shape, __pyx_v_strides, __pyx_v_ndim, __pyx_v_inc); + + /* "View.MemoryView":1365 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice_with_gil') + * cdef void refcount_objects_in_slice_with_gil(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * bint inc) noexcept with gil: + */ + + /* function exit code */ + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif +} + +/* "View.MemoryView":1371 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice') + * cdef void refcount_objects_in_slice(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, bint inc) noexcept: + * cdef Py_ssize_t i + */ + +static void __pyx_memoryview_refcount_objects_in_slice(char *__pyx_v_data, Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, int __pyx_v_ndim, int __pyx_v_inc) { + CYTHON_UNUSED Py_ssize_t __pyx_v_i; + Py_ssize_t __pyx_v_stride; + Py_ssize_t __pyx_t_1; + Py_ssize_t __pyx_t_2; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + + /* "View.MemoryView":1374 + * Py_ssize_t *strides, int ndim, bint inc) noexcept: + * cdef Py_ssize_t i + * cdef Py_ssize_t stride = strides[0] # <<<<<<<<<<<<<< + * + * for i in range(shape[0]): + */ + __pyx_v_stride = (__pyx_v_strides[0]); + + /* "View.MemoryView":1376 + * cdef Py_ssize_t stride = strides[0] + * + * for i in range(shape[0]): # <<<<<<<<<<<<<< + * if ndim == 1: + * if inc: + */ + __pyx_t_1 = (__pyx_v_shape[0]); + __pyx_t_2 = __pyx_t_1; + for (__pyx_t_3 = 0; __pyx_t_3 < __pyx_t_2; __pyx_t_3+=1) { + __pyx_v_i = __pyx_t_3; + + /* "View.MemoryView":1377 + * + * for i in range(shape[0]): + * if ndim == 1: # <<<<<<<<<<<<<< + * if inc: + * Py_INCREF(( data)[0]) + */ + __pyx_t_4 = (__pyx_v_ndim == 1); + if (__pyx_t_4) { + + /* "View.MemoryView":1378 + * for i in range(shape[0]): + * if ndim == 1: + * if inc: # <<<<<<<<<<<<<< + * Py_INCREF(( data)[0]) + * else: + */ + if (__pyx_v_inc) { + + /* "View.MemoryView":1379 + * if ndim == 1: + * if inc: + * Py_INCREF(( data)[0]) # <<<<<<<<<<<<<< + * else: + * Py_DECREF(( data)[0]) + */ + Py_INCREF((((PyObject **)__pyx_v_data)[0])); + + /* "View.MemoryView":1378 + * for i in range(shape[0]): + * if ndim == 1: + * if inc: # <<<<<<<<<<<<<< + * Py_INCREF(( data)[0]) + * else: + */ + goto __pyx_L6; + } + + /* "View.MemoryView":1381 + * Py_INCREF(( data)[0]) + * else: + * Py_DECREF(( data)[0]) # <<<<<<<<<<<<<< + * else: + * refcount_objects_in_slice(data, shape + 1, strides + 1, ndim - 1, inc) + */ + /*else*/ { + Py_DECREF((((PyObject **)__pyx_v_data)[0])); + } + __pyx_L6:; + + /* "View.MemoryView":1377 + * + * for i in range(shape[0]): + * if ndim == 1: # <<<<<<<<<<<<<< + * if inc: + * Py_INCREF(( data)[0]) + */ + goto __pyx_L5; + } + + /* "View.MemoryView":1383 + * Py_DECREF(( data)[0]) + * else: + * refcount_objects_in_slice(data, shape + 1, strides + 1, ndim - 1, inc) # <<<<<<<<<<<<<< + * + * data += stride + */ + /*else*/ { + __pyx_memoryview_refcount_objects_in_slice(__pyx_v_data, (__pyx_v_shape + 1), (__pyx_v_strides + 1), (__pyx_v_ndim - 1), __pyx_v_inc); + } + __pyx_L5:; + + /* "View.MemoryView":1385 + * refcount_objects_in_slice(data, shape + 1, strides + 1, ndim - 1, inc) + * + * data += stride # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_data = (__pyx_v_data + __pyx_v_stride); + } + + /* "View.MemoryView":1371 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice') + * cdef void refcount_objects_in_slice(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, bint inc) noexcept: + * cdef Py_ssize_t i + */ + + /* function exit code */ +} + +/* "View.MemoryView":1391 + * + * @cname('__pyx_memoryview_slice_assign_scalar') + * cdef void slice_assign_scalar(__Pyx_memviewslice *dst, int ndim, # <<<<<<<<<<<<<< + * size_t itemsize, void *item, + * bint dtype_is_object) noexcept nogil: + */ + +static void __pyx_memoryview_slice_assign_scalar(__Pyx_memviewslice *__pyx_v_dst, int __pyx_v_ndim, size_t __pyx_v_itemsize, void *__pyx_v_item, int __pyx_v_dtype_is_object) { + + /* "View.MemoryView":1394 + * size_t itemsize, void *item, + * bint dtype_is_object) noexcept nogil: + * refcount_copying(dst, dtype_is_object, ndim, inc=False) # <<<<<<<<<<<<<< + * _slice_assign_scalar(dst.data, dst.shape, dst.strides, ndim, itemsize, item) + * refcount_copying(dst, dtype_is_object, ndim, inc=True) + */ + __pyx_memoryview_refcount_copying(__pyx_v_dst, __pyx_v_dtype_is_object, __pyx_v_ndim, 0); + + /* "View.MemoryView":1395 + * bint dtype_is_object) noexcept nogil: + * refcount_copying(dst, dtype_is_object, ndim, inc=False) + * _slice_assign_scalar(dst.data, dst.shape, dst.strides, ndim, itemsize, item) # <<<<<<<<<<<<<< + * refcount_copying(dst, dtype_is_object, ndim, inc=True) + * + */ + __pyx_memoryview__slice_assign_scalar(__pyx_v_dst->data, __pyx_v_dst->shape, __pyx_v_dst->strides, __pyx_v_ndim, __pyx_v_itemsize, __pyx_v_item); + + /* "View.MemoryView":1396 + * refcount_copying(dst, dtype_is_object, ndim, inc=False) + * _slice_assign_scalar(dst.data, dst.shape, dst.strides, ndim, itemsize, item) + * refcount_copying(dst, dtype_is_object, ndim, inc=True) # <<<<<<<<<<<<<< + * + * + */ + __pyx_memoryview_refcount_copying(__pyx_v_dst, __pyx_v_dtype_is_object, __pyx_v_ndim, 1); + + /* "View.MemoryView":1391 + * + * @cname('__pyx_memoryview_slice_assign_scalar') + * cdef void slice_assign_scalar(__Pyx_memviewslice *dst, int ndim, # <<<<<<<<<<<<<< + * size_t itemsize, void *item, + * bint dtype_is_object) noexcept nogil: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1400 + * + * @cname('__pyx_memoryview__slice_assign_scalar') + * cdef void _slice_assign_scalar(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * size_t itemsize, void *item) noexcept nogil: + */ + +static void __pyx_memoryview__slice_assign_scalar(char *__pyx_v_data, Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, int __pyx_v_ndim, size_t __pyx_v_itemsize, void *__pyx_v_item) { + CYTHON_UNUSED Py_ssize_t __pyx_v_i; + Py_ssize_t __pyx_v_stride; + Py_ssize_t __pyx_v_extent; + int __pyx_t_1; + Py_ssize_t __pyx_t_2; + Py_ssize_t __pyx_t_3; + Py_ssize_t __pyx_t_4; + + /* "View.MemoryView":1404 + * size_t itemsize, void *item) noexcept nogil: + * cdef Py_ssize_t i + * cdef Py_ssize_t stride = strides[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t extent = shape[0] + * + */ + __pyx_v_stride = (__pyx_v_strides[0]); + + /* "View.MemoryView":1405 + * cdef Py_ssize_t i + * cdef Py_ssize_t stride = strides[0] + * cdef Py_ssize_t extent = shape[0] # <<<<<<<<<<<<<< + * + * if ndim == 1: + */ + __pyx_v_extent = (__pyx_v_shape[0]); + + /* "View.MemoryView":1407 + * cdef Py_ssize_t extent = shape[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * for i in range(extent): + * memcpy(data, item, itemsize) + */ + __pyx_t_1 = (__pyx_v_ndim == 1); + if (__pyx_t_1) { + + /* "View.MemoryView":1408 + * + * if ndim == 1: + * for i in range(extent): # <<<<<<<<<<<<<< + * memcpy(data, item, itemsize) + * data += stride + */ + __pyx_t_2 = __pyx_v_extent; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1409 + * if ndim == 1: + * for i in range(extent): + * memcpy(data, item, itemsize) # <<<<<<<<<<<<<< + * data += stride + * else: + */ + (void)(memcpy(__pyx_v_data, __pyx_v_item, __pyx_v_itemsize)); + + /* "View.MemoryView":1410 + * for i in range(extent): + * memcpy(data, item, itemsize) + * data += stride # <<<<<<<<<<<<<< + * else: + * for i in range(extent): + */ + __pyx_v_data = (__pyx_v_data + __pyx_v_stride); + } + + /* "View.MemoryView":1407 + * cdef Py_ssize_t extent = shape[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * for i in range(extent): + * memcpy(data, item, itemsize) + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1412 + * data += stride + * else: + * for i in range(extent): # <<<<<<<<<<<<<< + * _slice_assign_scalar(data, shape + 1, strides + 1, ndim - 1, itemsize, item) + * data += stride + */ + /*else*/ { + __pyx_t_2 = __pyx_v_extent; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1413 + * else: + * for i in range(extent): + * _slice_assign_scalar(data, shape + 1, strides + 1, ndim - 1, itemsize, item) # <<<<<<<<<<<<<< + * data += stride + * + */ + __pyx_memoryview__slice_assign_scalar(__pyx_v_data, (__pyx_v_shape + 1), (__pyx_v_strides + 1), (__pyx_v_ndim - 1), __pyx_v_itemsize, __pyx_v_item); + + /* "View.MemoryView":1414 + * for i in range(extent): + * _slice_assign_scalar(data, shape + 1, strides + 1, ndim - 1, itemsize, item) + * data += stride # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_data = (__pyx_v_data + __pyx_v_stride); + } + } + __pyx_L3:; + + /* "View.MemoryView":1400 + * + * @cname('__pyx_memoryview__slice_assign_scalar') + * cdef void _slice_assign_scalar(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * size_t itemsize, void *item) noexcept nogil: + */ + + /* function exit code */ +} + +/* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_1__pyx_unpickle_Enum(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_15View_dot_MemoryView_1__pyx_unpickle_Enum = {"__pyx_unpickle_Enum", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15View_dot_MemoryView_1__pyx_unpickle_Enum, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15View_dot_MemoryView_1__pyx_unpickle_Enum(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v___pyx_type = 0; + long __pyx_v___pyx_checksum; + PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__pyx_unpickle_Enum (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_type,&__pyx_n_s_pyx_checksum,&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_type)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_checksum)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle_Enum", 1, 3, 3, 1); __PYX_ERR(1, 1, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle_Enum", 1, 3, 3, 2); __PYX_ERR(1, 1, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__pyx_unpickle_Enum") < 0)) __PYX_ERR(1, 1, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + } + __pyx_v___pyx_type = values[0]; + __pyx_v___pyx_checksum = __Pyx_PyInt_As_long(values[1]); if (unlikely((__pyx_v___pyx_checksum == (long)-1) && PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + __pyx_v___pyx_state = values[2]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle_Enum", 1, 3, 3, __pyx_nargs); __PYX_ERR(1, 1, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.__pyx_unpickle_Enum", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15View_dot_MemoryView___pyx_unpickle_Enum(__pyx_self, __pyx_v___pyx_type, __pyx_v___pyx_checksum, __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView___pyx_unpickle_Enum(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v___pyx_type, long __pyx_v___pyx_checksum, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_v___pyx_PickleError = 0; + PyObject *__pyx_v___pyx_result = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_unpickle_Enum", 1); + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + */ + __pyx_t_1 = __Pyx_PyInt_From_long(__pyx_v___pyx_checksum); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 4, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = (__Pyx_PySequence_ContainsTF(__pyx_t_1, __pyx_tuple__8, Py_NE)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(1, 4, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (__pyx_t_2) { + + /* "(tree fragment)":5 + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): + * from pickle import PickleError as __pyx_PickleError # <<<<<<<<<<<<<< + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) + */ + __pyx_t_1 = PyList_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_s_PickleError); + __Pyx_GIVEREF(__pyx_n_s_PickleError); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_s_PickleError)) __PYX_ERR(1, 5, __pyx_L1_error); + __pyx_t_3 = __Pyx_Import(__pyx_n_s_pickle, __pyx_t_1, 0); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_ImportFrom(__pyx_t_3, __pyx_n_s_PickleError); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_t_1); + __pyx_v___pyx_PickleError = __pyx_t_1; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "(tree fragment)":6 + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum # <<<<<<<<<<<<<< + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: + */ + __pyx_t_3 = __Pyx_PyInt_From_long(__pyx_v___pyx_checksum); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_Incompatible_checksums_0x_x_vs_0, __pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_v___pyx_PickleError, __pyx_t_1, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(1, 6, __pyx_L1_error) + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + */ + } + + /* "(tree fragment)":7 + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) # <<<<<<<<<<<<<< + * if __pyx_state is not None: + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_MemviewEnum_type), __pyx_n_s_new); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 7, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = NULL; + __pyx_t_5 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_5 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_4, __pyx_v___pyx_type}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_5, 1+__pyx_t_5); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 7, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_v___pyx_result = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":8 + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + */ + __pyx_t_2 = (__pyx_v___pyx_state != Py_None); + if (__pyx_t_2) { + + /* "(tree fragment)":9 + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) # <<<<<<<<<<<<<< + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + */ + if (!(likely(PyTuple_CheckExact(__pyx_v___pyx_state))||((__pyx_v___pyx_state) == Py_None) || __Pyx_RaiseUnexpectedTypeError("tuple", __pyx_v___pyx_state))) __PYX_ERR(1, 9, __pyx_L1_error) + __pyx_t_1 = __pyx_unpickle_Enum__set_state(((struct __pyx_MemviewEnum_obj *)__pyx_v___pyx_result), ((PyObject*)__pyx_v___pyx_state)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 9, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":8 + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + */ + } + + /* "(tree fragment)":10 + * if __pyx_state is not None: + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result # <<<<<<<<<<<<<< + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v___pyx_result); + __pyx_r = __pyx_v___pyx_result; + goto __pyx_L0; + + /* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.__pyx_unpickle_Enum", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v___pyx_PickleError); + __Pyx_XDECREF(__pyx_v___pyx_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":11 + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): # <<<<<<<<<<<<<< + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + */ + +static PyObject *__pyx_unpickle_Enum__set_state(struct __pyx_MemviewEnum_obj *__pyx_v___pyx_result, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + int __pyx_t_8; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_unpickle_Enum__set_state", 1); + + /* "(tree fragment)":12 + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] # <<<<<<<<<<<<<< + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + * __pyx_result.__dict__.update(__pyx_state[1]) + */ + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 12, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 12, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + __Pyx_GOTREF(__pyx_v___pyx_result->name); + __Pyx_DECREF(__pyx_v___pyx_result->name); + __pyx_v___pyx_result->name = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":13 + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): # <<<<<<<<<<<<<< + * __pyx_result.__dict__.update(__pyx_state[1]) + */ + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); + __PYX_ERR(1, 13, __pyx_L1_error) + } + __pyx_t_3 = __Pyx_PyTuple_GET_SIZE(__pyx_v___pyx_state); if (unlikely(__pyx_t_3 == ((Py_ssize_t)-1))) __PYX_ERR(1, 13, __pyx_L1_error) + __pyx_t_4 = (__pyx_t_3 > 1); + if (__pyx_t_4) { + } else { + __pyx_t_2 = __pyx_t_4; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_4 = __Pyx_HasAttr(((PyObject *)__pyx_v___pyx_result), __pyx_n_s_dict); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(1, 13, __pyx_L1_error) + __pyx_t_2 = __pyx_t_4; + __pyx_L4_bool_binop_done:; + if (__pyx_t_2) { + + /* "(tree fragment)":14 + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + * __pyx_result.__dict__.update(__pyx_state[1]) # <<<<<<<<<<<<<< + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v___pyx_result), __pyx_n_s_dict); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_update); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 14, __pyx_L1_error) + } + __pyx_t_5 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_7 = NULL; + __pyx_t_8 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_6))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_6); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_6); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_6, function); + __pyx_t_8 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_7, __pyx_t_5}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_6, __pyx_callargs+1-__pyx_t_8, 1+__pyx_t_8); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":13 + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): # <<<<<<<<<<<<<< + * __pyx_result.__dict__.update(__pyx_state[1]) + */ + } + + /* "(tree fragment)":11 + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): # <<<<<<<<<<<<<< + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("View.MemoryView.__pyx_unpickle_Enum__set_state", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":245 + * + * @property + * cdef inline PyObject* base(self) nogil: # <<<<<<<<<<<<<< + * """Returns a borrowed reference to the object owning the data/memory. + * """ + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_7ndarray_4base_base(PyArrayObject *__pyx_v_self) { + PyObject *__pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":248 + * """Returns a borrowed reference to the object owning the data/memory. + * """ + * return PyArray_BASE(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_BASE(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":245 + * + * @property + * cdef inline PyObject* base(self) nogil: # <<<<<<<<<<<<<< + * """Returns a borrowed reference to the object owning the data/memory. + * """ + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":251 + * + * @property + * cdef inline dtype descr(self): # <<<<<<<<<<<<<< + * """Returns an owned reference to the dtype of the array. + * """ + */ + +static CYTHON_INLINE PyArray_Descr *__pyx_f_5numpy_7ndarray_5descr_descr(PyArrayObject *__pyx_v_self) { + PyArray_Descr *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyArray_Descr *__pyx_t_1; + __Pyx_RefNannySetupContext("descr", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":254 + * """Returns an owned reference to the dtype of the array. + * """ + * return PyArray_DESCR(self) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF((PyObject *)__pyx_r); + __pyx_t_1 = PyArray_DESCR(__pyx_v_self); + __Pyx_INCREF((PyObject *)((PyArray_Descr *)__pyx_t_1)); + __pyx_r = ((PyArray_Descr *)__pyx_t_1); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":251 + * + * @property + * cdef inline dtype descr(self): # <<<<<<<<<<<<<< + * """Returns an owned reference to the dtype of the array. + * """ + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF((PyObject *)__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":257 + * + * @property + * cdef inline int ndim(self) nogil: # <<<<<<<<<<<<<< + * """Returns the number of dimensions in the array. + * """ + */ + +static CYTHON_INLINE int __pyx_f_5numpy_7ndarray_4ndim_ndim(PyArrayObject *__pyx_v_self) { + int __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":260 + * """Returns the number of dimensions in the array. + * """ + * return PyArray_NDIM(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_NDIM(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":257 + * + * @property + * cdef inline int ndim(self) nogil: # <<<<<<<<<<<<<< + * """Returns the number of dimensions in the array. + * """ + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":263 + * + * @property + * cdef inline npy_intp *shape(self) nogil: # <<<<<<<<<<<<<< + * """Returns a pointer to the dimensions/shape of the array. + * The number of elements matches the number of dimensions of the array (ndim). + */ + +static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_5shape_shape(PyArrayObject *__pyx_v_self) { + npy_intp *__pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":268 + * Can return NULL for 0-dimensional arrays. + * """ + * return PyArray_DIMS(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_DIMS(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":263 + * + * @property + * cdef inline npy_intp *shape(self) nogil: # <<<<<<<<<<<<<< + * """Returns a pointer to the dimensions/shape of the array. + * The number of elements matches the number of dimensions of the array (ndim). + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":271 + * + * @property + * cdef inline npy_intp *strides(self) nogil: # <<<<<<<<<<<<<< + * """Returns a pointer to the strides of the array. + * The number of elements matches the number of dimensions of the array (ndim). + */ + +static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_7strides_strides(PyArrayObject *__pyx_v_self) { + npy_intp *__pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":275 + * The number of elements matches the number of dimensions of the array (ndim). + * """ + * return PyArray_STRIDES(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_STRIDES(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":271 + * + * @property + * cdef inline npy_intp *strides(self) nogil: # <<<<<<<<<<<<<< + * """Returns a pointer to the strides of the array. + * The number of elements matches the number of dimensions of the array (ndim). + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":278 + * + * @property + * cdef inline npy_intp size(self) nogil: # <<<<<<<<<<<<<< + * """Returns the total size (in number of elements) of the array. + * """ + */ + +static CYTHON_INLINE npy_intp __pyx_f_5numpy_7ndarray_4size_size(PyArrayObject *__pyx_v_self) { + npy_intp __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":281 + * """Returns the total size (in number of elements) of the array. + * """ + * return PyArray_SIZE(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_SIZE(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":278 + * + * @property + * cdef inline npy_intp size(self) nogil: # <<<<<<<<<<<<<< + * """Returns the total size (in number of elements) of the array. + * """ + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":284 + * + * @property + * cdef inline char* data(self) nogil: # <<<<<<<<<<<<<< + * """The pointer to the data buffer as a char*. + * This is provided for legacy reasons to avoid direct struct field access. + */ + +static CYTHON_INLINE char *__pyx_f_5numpy_7ndarray_4data_data(PyArrayObject *__pyx_v_self) { + char *__pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":290 + * of `PyArray_DATA()` instead, which returns a 'void*'. + * """ + * return PyArray_BYTES(self) # <<<<<<<<<<<<<< + * + * ctypedef unsigned char npy_bool + */ + __pyx_r = PyArray_BYTES(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":284 + * + * @property + * cdef inline char* data(self) nogil: # <<<<<<<<<<<<<< + * """The pointer to the data buffer as a char*. + * This is provided for legacy reasons to avoid direct struct field access. + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":773 + * ctypedef npy_cdouble complex_t + * + * cdef inline object PyArray_MultiIterNew1(a): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(1, a) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew1(PyObject *__pyx_v_a) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew1", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":774 + * + * cdef inline object PyArray_MultiIterNew1(a): + * return PyArray_MultiIterNew(1, a) # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew2(a, b): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(1, ((void *)__pyx_v_a)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 774, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":773 + * ctypedef npy_cdouble complex_t + * + * cdef inline object PyArray_MultiIterNew1(a): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(1, a) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew1", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":776 + * return PyArray_MultiIterNew(1, a) + * + * cdef inline object PyArray_MultiIterNew2(a, b): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(2, a, b) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew2(PyObject *__pyx_v_a, PyObject *__pyx_v_b) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew2", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":777 + * + * cdef inline object PyArray_MultiIterNew2(a, b): + * return PyArray_MultiIterNew(2, a, b) # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew3(a, b, c): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(2, ((void *)__pyx_v_a), ((void *)__pyx_v_b)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 777, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":776 + * return PyArray_MultiIterNew(1, a) + * + * cdef inline object PyArray_MultiIterNew2(a, b): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(2, a, b) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew2", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":779 + * return PyArray_MultiIterNew(2, a, b) + * + * cdef inline object PyArray_MultiIterNew3(a, b, c): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(3, a, b, c) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew3(PyObject *__pyx_v_a, PyObject *__pyx_v_b, PyObject *__pyx_v_c) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew3", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":780 + * + * cdef inline object PyArray_MultiIterNew3(a, b, c): + * return PyArray_MultiIterNew(3, a, b, c) # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew4(a, b, c, d): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(3, ((void *)__pyx_v_a), ((void *)__pyx_v_b), ((void *)__pyx_v_c)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 780, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":779 + * return PyArray_MultiIterNew(2, a, b) + * + * cdef inline object PyArray_MultiIterNew3(a, b, c): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(3, a, b, c) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew3", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":782 + * return PyArray_MultiIterNew(3, a, b, c) + * + * cdef inline object PyArray_MultiIterNew4(a, b, c, d): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(4, a, b, c, d) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew4(PyObject *__pyx_v_a, PyObject *__pyx_v_b, PyObject *__pyx_v_c, PyObject *__pyx_v_d) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew4", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":783 + * + * cdef inline object PyArray_MultiIterNew4(a, b, c, d): + * return PyArray_MultiIterNew(4, a, b, c, d) # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(4, ((void *)__pyx_v_a), ((void *)__pyx_v_b), ((void *)__pyx_v_c), ((void *)__pyx_v_d)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 783, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":782 + * return PyArray_MultiIterNew(3, a, b, c) + * + * cdef inline object PyArray_MultiIterNew4(a, b, c, d): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(4, a, b, c, d) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew4", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":785 + * return PyArray_MultiIterNew(4, a, b, c, d) + * + * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(5, a, b, c, d, e) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew5(PyObject *__pyx_v_a, PyObject *__pyx_v_b, PyObject *__pyx_v_c, PyObject *__pyx_v_d, PyObject *__pyx_v_e) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew5", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":786 + * + * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): + * return PyArray_MultiIterNew(5, a, b, c, d, e) # <<<<<<<<<<<<<< + * + * cdef inline tuple PyDataType_SHAPE(dtype d): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(5, ((void *)__pyx_v_a), ((void *)__pyx_v_b), ((void *)__pyx_v_c), ((void *)__pyx_v_d), ((void *)__pyx_v_e)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 786, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":785 + * return PyArray_MultiIterNew(4, a, b, c, d) + * + * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(5, a, b, c, d, e) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew5", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":788 + * return PyArray_MultiIterNew(5, a, b, c, d, e) + * + * cdef inline tuple PyDataType_SHAPE(dtype d): # <<<<<<<<<<<<<< + * if PyDataType_HASSUBARRAY(d): + * return d.subarray.shape + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyDataType_SHAPE(PyArray_Descr *__pyx_v_d) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + __Pyx_RefNannySetupContext("PyDataType_SHAPE", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":789 + * + * cdef inline tuple PyDataType_SHAPE(dtype d): + * if PyDataType_HASSUBARRAY(d): # <<<<<<<<<<<<<< + * return d.subarray.shape + * else: + */ + __pyx_t_1 = PyDataType_HASSUBARRAY(__pyx_v_d); + if (__pyx_t_1) { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":790 + * cdef inline tuple PyDataType_SHAPE(dtype d): + * if PyDataType_HASSUBARRAY(d): + * return d.subarray.shape # <<<<<<<<<<<<<< + * else: + * return () + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(((PyObject*)__pyx_v_d->subarray->shape)); + __pyx_r = ((PyObject*)__pyx_v_d->subarray->shape); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":789 + * + * cdef inline tuple PyDataType_SHAPE(dtype d): + * if PyDataType_HASSUBARRAY(d): # <<<<<<<<<<<<<< + * return d.subarray.shape + * else: + */ + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":792 + * return d.subarray.shape + * else: + * return () # <<<<<<<<<<<<<< + * + * + */ + /*else*/ { + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_empty_tuple); + __pyx_r = __pyx_empty_tuple; + goto __pyx_L0; + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":788 + * return PyArray_MultiIterNew(5, a, b, c, d, e) + * + * cdef inline tuple PyDataType_SHAPE(dtype d): # <<<<<<<<<<<<<< + * if PyDataType_HASSUBARRAY(d): + * return d.subarray.shape + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":968 + * int _import_umath() except -1 + * + * cdef inline void set_array_base(ndarray arr, object base): # <<<<<<<<<<<<<< + * Py_INCREF(base) # important to do this before stealing the reference below! + * PyArray_SetBaseObject(arr, base) + */ + +static CYTHON_INLINE void __pyx_f_5numpy_set_array_base(PyArrayObject *__pyx_v_arr, PyObject *__pyx_v_base) { + int __pyx_t_1; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":969 + * + * cdef inline void set_array_base(ndarray arr, object base): + * Py_INCREF(base) # important to do this before stealing the reference below! # <<<<<<<<<<<<<< + * PyArray_SetBaseObject(arr, base) + * + */ + Py_INCREF(__pyx_v_base); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":970 + * cdef inline void set_array_base(ndarray arr, object base): + * Py_INCREF(base) # important to do this before stealing the reference below! + * PyArray_SetBaseObject(arr, base) # <<<<<<<<<<<<<< + * + * cdef inline object get_array_base(ndarray arr): + */ + __pyx_t_1 = PyArray_SetBaseObject(__pyx_v_arr, __pyx_v_base); if (unlikely(__pyx_t_1 == ((int)-1))) __PYX_ERR(2, 970, __pyx_L1_error) + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":968 + * int _import_umath() except -1 + * + * cdef inline void set_array_base(ndarray arr, object base): # <<<<<<<<<<<<<< + * Py_INCREF(base) # important to do this before stealing the reference below! + * PyArray_SetBaseObject(arr, base) + */ + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("numpy.set_array_base", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_L0:; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":972 + * PyArray_SetBaseObject(arr, base) + * + * cdef inline object get_array_base(ndarray arr): # <<<<<<<<<<<<<< + * base = PyArray_BASE(arr) + * if base is NULL: + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_get_array_base(PyArrayObject *__pyx_v_arr) { + PyObject *__pyx_v_base; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + __Pyx_RefNannySetupContext("get_array_base", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":973 + * + * cdef inline object get_array_base(ndarray arr): + * base = PyArray_BASE(arr) # <<<<<<<<<<<<<< + * if base is NULL: + * return None + */ + __pyx_v_base = PyArray_BASE(__pyx_v_arr); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":974 + * cdef inline object get_array_base(ndarray arr): + * base = PyArray_BASE(arr) + * if base is NULL: # <<<<<<<<<<<<<< + * return None + * return base + */ + __pyx_t_1 = (__pyx_v_base == NULL); + if (__pyx_t_1) { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":975 + * base = PyArray_BASE(arr) + * if base is NULL: + * return None # <<<<<<<<<<<<<< + * return base + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":974 + * cdef inline object get_array_base(ndarray arr): + * base = PyArray_BASE(arr) + * if base is NULL: # <<<<<<<<<<<<<< + * return None + * return base + */ + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":976 + * if base is NULL: + * return None + * return base # <<<<<<<<<<<<<< + * + * # Versions of the import_* functions which are more suitable for + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(((PyObject *)__pyx_v_base)); + __pyx_r = ((PyObject *)__pyx_v_base); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":972 + * PyArray_SetBaseObject(arr, base) + * + * cdef inline object get_array_base(ndarray arr): # <<<<<<<<<<<<<< + * base = PyArray_BASE(arr) + * if base is NULL: + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":980 + * # Versions of the import_* functions which are more suitable for + * # Cython code. + * cdef inline int import_array() except -1: # <<<<<<<<<<<<<< + * try: + * __pyx_import_array() + */ + +static CYTHON_INLINE int __pyx_f_5numpy_import_array(void) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("import_array", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":981 + * # Cython code. + * cdef inline int import_array() except -1: + * try: # <<<<<<<<<<<<<< + * __pyx_import_array() + * except Exception: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":982 + * cdef inline int import_array() except -1: + * try: + * __pyx_import_array() # <<<<<<<<<<<<<< + * except Exception: + * raise ImportError("numpy.core.multiarray failed to import") + */ + __pyx_t_4 = _import_array(); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(2, 982, __pyx_L3_error) + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":981 + * # Cython code. + * cdef inline int import_array() except -1: + * try: # <<<<<<<<<<<<<< + * __pyx_import_array() + * except Exception: + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L8_try_end; + __pyx_L3_error:; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":983 + * try: + * __pyx_import_array() + * except Exception: # <<<<<<<<<<<<<< + * raise ImportError("numpy.core.multiarray failed to import") + * + */ + __pyx_t_4 = __Pyx_PyErr_ExceptionMatches(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0]))); + if (__pyx_t_4) { + __Pyx_AddTraceback("numpy.import_array", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_6, &__pyx_t_7) < 0) __PYX_ERR(2, 983, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_7); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":984 + * __pyx_import_array() + * except Exception: + * raise ImportError("numpy.core.multiarray failed to import") # <<<<<<<<<<<<<< + * + * cdef inline int import_umath() except -1: + */ + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_builtin_ImportError, __pyx_tuple__9, NULL); if (unlikely(!__pyx_t_8)) __PYX_ERR(2, 984, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_Raise(__pyx_t_8, 0, 0, 0); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __PYX_ERR(2, 984, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":981 + * # Cython code. + * cdef inline int import_array() except -1: + * try: # <<<<<<<<<<<<<< + * __pyx_import_array() + * except Exception: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + goto __pyx_L1_error; + __pyx_L8_try_end:; + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":980 + * # Versions of the import_* functions which are more suitable for + * # Cython code. + * cdef inline int import_array() except -1: # <<<<<<<<<<<<<< + * try: + * __pyx_import_array() + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("numpy.import_array", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":986 + * raise ImportError("numpy.core.multiarray failed to import") + * + * cdef inline int import_umath() except -1: # <<<<<<<<<<<<<< + * try: + * _import_umath() + */ + +static CYTHON_INLINE int __pyx_f_5numpy_import_umath(void) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("import_umath", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":987 + * + * cdef inline int import_umath() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":988 + * cdef inline int import_umath() except -1: + * try: + * _import_umath() # <<<<<<<<<<<<<< + * except Exception: + * raise ImportError("numpy.core.umath failed to import") + */ + __pyx_t_4 = _import_umath(); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(2, 988, __pyx_L3_error) + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":987 + * + * cdef inline int import_umath() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L8_try_end; + __pyx_L3_error:; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":989 + * try: + * _import_umath() + * except Exception: # <<<<<<<<<<<<<< + * raise ImportError("numpy.core.umath failed to import") + * + */ + __pyx_t_4 = __Pyx_PyErr_ExceptionMatches(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0]))); + if (__pyx_t_4) { + __Pyx_AddTraceback("numpy.import_umath", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_6, &__pyx_t_7) < 0) __PYX_ERR(2, 989, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_7); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":990 + * _import_umath() + * except Exception: + * raise ImportError("numpy.core.umath failed to import") # <<<<<<<<<<<<<< + * + * cdef inline int import_ufunc() except -1: + */ + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_builtin_ImportError, __pyx_tuple__10, NULL); if (unlikely(!__pyx_t_8)) __PYX_ERR(2, 990, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_Raise(__pyx_t_8, 0, 0, 0); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __PYX_ERR(2, 990, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":987 + * + * cdef inline int import_umath() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + goto __pyx_L1_error; + __pyx_L8_try_end:; + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":986 + * raise ImportError("numpy.core.multiarray failed to import") + * + * cdef inline int import_umath() except -1: # <<<<<<<<<<<<<< + * try: + * _import_umath() + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("numpy.import_umath", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":992 + * raise ImportError("numpy.core.umath failed to import") + * + * cdef inline int import_ufunc() except -1: # <<<<<<<<<<<<<< + * try: + * _import_umath() + */ + +static CYTHON_INLINE int __pyx_f_5numpy_import_ufunc(void) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("import_ufunc", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":993 + * + * cdef inline int import_ufunc() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":994 + * cdef inline int import_ufunc() except -1: + * try: + * _import_umath() # <<<<<<<<<<<<<< + * except Exception: + * raise ImportError("numpy.core.umath failed to import") + */ + __pyx_t_4 = _import_umath(); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(2, 994, __pyx_L3_error) + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":993 + * + * cdef inline int import_ufunc() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L8_try_end; + __pyx_L3_error:; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":995 + * try: + * _import_umath() + * except Exception: # <<<<<<<<<<<<<< + * raise ImportError("numpy.core.umath failed to import") + * + */ + __pyx_t_4 = __Pyx_PyErr_ExceptionMatches(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0]))); + if (__pyx_t_4) { + __Pyx_AddTraceback("numpy.import_ufunc", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_6, &__pyx_t_7) < 0) __PYX_ERR(2, 995, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_7); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":996 + * _import_umath() + * except Exception: + * raise ImportError("numpy.core.umath failed to import") # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_builtin_ImportError, __pyx_tuple__10, NULL); if (unlikely(!__pyx_t_8)) __PYX_ERR(2, 996, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_Raise(__pyx_t_8, 0, 0, 0); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __PYX_ERR(2, 996, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":993 + * + * cdef inline int import_ufunc() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + goto __pyx_L1_error; + __pyx_L8_try_end:; + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":992 + * raise ImportError("numpy.core.umath failed to import") + * + * cdef inline int import_ufunc() except -1: # <<<<<<<<<<<<<< + * try: + * _import_umath() + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("numpy.import_ufunc", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":999 + * + * + * cdef inline bint is_timedelta64_object(object obj): # <<<<<<<<<<<<<< + * """ + * Cython equivalent of `isinstance(obj, np.timedelta64)` + */ + +static CYTHON_INLINE int __pyx_f_5numpy_is_timedelta64_object(PyObject *__pyx_v_obj) { + int __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1011 + * bool + * """ + * return PyObject_TypeCheck(obj, &PyTimedeltaArrType_Type) # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = PyObject_TypeCheck(__pyx_v_obj, (&PyTimedeltaArrType_Type)); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":999 + * + * + * cdef inline bint is_timedelta64_object(object obj): # <<<<<<<<<<<<<< + * """ + * Cython equivalent of `isinstance(obj, np.timedelta64)` + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1014 + * + * + * cdef inline bint is_datetime64_object(object obj): # <<<<<<<<<<<<<< + * """ + * Cython equivalent of `isinstance(obj, np.datetime64)` + */ + +static CYTHON_INLINE int __pyx_f_5numpy_is_datetime64_object(PyObject *__pyx_v_obj) { + int __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1026 + * bool + * """ + * return PyObject_TypeCheck(obj, &PyDatetimeArrType_Type) # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = PyObject_TypeCheck(__pyx_v_obj, (&PyDatetimeArrType_Type)); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1014 + * + * + * cdef inline bint is_datetime64_object(object obj): # <<<<<<<<<<<<<< + * """ + * Cython equivalent of `isinstance(obj, np.datetime64)` + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1029 + * + * + * cdef inline npy_datetime get_datetime64_value(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the int64 value underlying scalar numpy datetime64 object + */ + +static CYTHON_INLINE npy_datetime __pyx_f_5numpy_get_datetime64_value(PyObject *__pyx_v_obj) { + npy_datetime __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1036 + * also needed. That can be found using `get_datetime64_unit`. + * """ + * return (obj).obval # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = ((PyDatetimeScalarObject *)__pyx_v_obj)->obval; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1029 + * + * + * cdef inline npy_datetime get_datetime64_value(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the int64 value underlying scalar numpy datetime64 object + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1039 + * + * + * cdef inline npy_timedelta get_timedelta64_value(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the int64 value underlying scalar numpy timedelta64 object + */ + +static CYTHON_INLINE npy_timedelta __pyx_f_5numpy_get_timedelta64_value(PyObject *__pyx_v_obj) { + npy_timedelta __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1043 + * returns the int64 value underlying scalar numpy timedelta64 object + * """ + * return (obj).obval # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = ((PyTimedeltaScalarObject *)__pyx_v_obj)->obval; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1039 + * + * + * cdef inline npy_timedelta get_timedelta64_value(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the int64 value underlying scalar numpy timedelta64 object + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1046 + * + * + * cdef inline NPY_DATETIMEUNIT get_datetime64_unit(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the unit part of the dtype for a numpy datetime64 object. + */ + +static CYTHON_INLINE NPY_DATETIMEUNIT __pyx_f_5numpy_get_datetime64_unit(PyObject *__pyx_v_obj) { + NPY_DATETIMEUNIT __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1050 + * returns the unit part of the dtype for a numpy datetime64 object. + * """ + * return (obj).obmeta.base # <<<<<<<<<<<<<< + */ + __pyx_r = ((NPY_DATETIMEUNIT)((PyDatetimeScalarObject *)__pyx_v_obj)->obmeta.base); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1046 + * + * + * cdef inline NPY_DATETIMEUNIT get_datetime64_unit(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the unit part of the dtype for a numpy datetime64 object. + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":70 + * cdef str nlp_solver_type + * + * def __cinit__(self, model_name, nlp_solver_type, N): # <<<<<<<<<<<<<< + * + * self.solver_created = False + */ + +/* Python wrapper */ +static int __pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_model_name = 0; + PyObject *__pyx_v_nlp_solver_type = 0; + PyObject *__pyx_v_N = 0; + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_model_name,&__pyx_n_s_nlp_solver_type,&__pyx_n_s_N,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_model_name)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 70, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_nlp_solver_type)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 70, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 3, 3, 1); __PYX_ERR(0, 70, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_N)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 70, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 3, 3, 2); __PYX_ERR(0, 70, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(0, 70, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + } + __pyx_v_model_name = values[0]; + __pyx_v_nlp_solver_type = values[1]; + __pyx_v_N = values[2]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 70, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython___cinit__(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_model_name, __pyx_v_nlp_solver_type, __pyx_v_N); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython___cinit__(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_model_name, PyObject *__pyx_v_nlp_solver_type, PyObject *__pyx_v_N) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__cinit__", 1); + + /* "acados_template/acados_ocp_solver_pyx.pyx":72 + * def __cinit__(self, model_name, nlp_solver_type, N): + * + * self.solver_created = False # <<<<<<<<<<<<<< + * + * self.N = N + */ + __pyx_v_self->solver_created = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":74 + * self.solver_created = False + * + * self.N = N # <<<<<<<<<<<<<< + * self.model_name = model_name + * self.nlp_solver_type = nlp_solver_type + */ + __pyx_t_1 = __Pyx_PyInt_As_int(__pyx_v_N); if (unlikely((__pyx_t_1 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 74, __pyx_L1_error) + __pyx_v_self->N = __pyx_t_1; + + /* "acados_template/acados_ocp_solver_pyx.pyx":75 + * + * self.N = N + * self.model_name = model_name # <<<<<<<<<<<<<< + * self.nlp_solver_type = nlp_solver_type + * + */ + if (!(likely(PyUnicode_CheckExact(__pyx_v_model_name))||((__pyx_v_model_name) == Py_None) || __Pyx_RaiseUnexpectedTypeError("unicode", __pyx_v_model_name))) __PYX_ERR(0, 75, __pyx_L1_error) + __pyx_t_2 = __pyx_v_model_name; + __Pyx_INCREF(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + __Pyx_GOTREF(__pyx_v_self->model_name); + __Pyx_DECREF(__pyx_v_self->model_name); + __pyx_v_self->model_name = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":76 + * self.N = N + * self.model_name = model_name + * self.nlp_solver_type = nlp_solver_type # <<<<<<<<<<<<<< + * + * # create capsule + */ + if (!(likely(PyUnicode_CheckExact(__pyx_v_nlp_solver_type))||((__pyx_v_nlp_solver_type) == Py_None) || __Pyx_RaiseUnexpectedTypeError("unicode", __pyx_v_nlp_solver_type))) __PYX_ERR(0, 76, __pyx_L1_error) + __pyx_t_2 = __pyx_v_nlp_solver_type; + __Pyx_INCREF(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + __Pyx_GOTREF(__pyx_v_self->nlp_solver_type); + __Pyx_DECREF(__pyx_v_self->nlp_solver_type); + __pyx_v_self->nlp_solver_type = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":79 + * + * # create capsule + * self.capsule = acados_solver.acados_create_capsule() # <<<<<<<<<<<<<< + * + * # create solver + */ + __pyx_v_self->capsule = lat_acados_create_capsule(); + + /* "acados_template/acados_ocp_solver_pyx.pyx":82 + * + * # create solver + * assert acados_solver.acados_create(self.capsule) == 0 # <<<<<<<<<<<<<< + * self.solver_created = True + * + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_3 = (lat_acados_create(__pyx_v_self->capsule) == 0); + if (unlikely(!__pyx_t_3)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(0, 82, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(0, 82, __pyx_L1_error) + #endif + + /* "acados_template/acados_ocp_solver_pyx.pyx":83 + * # create solver + * assert acados_solver.acados_create(self.capsule) == 0 + * self.solver_created = True # <<<<<<<<<<<<<< + * + * # get pointers solver + */ + __pyx_v_self->solver_created = 1; + + /* "acados_template/acados_ocp_solver_pyx.pyx":86 + * + * # get pointers solver + * self.__get_pointers_solver() # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_AcadosOcpSolverCython__get_poin); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 86, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = NULL; + __pyx_t_1 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_4))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_4); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_4); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_4, function); + __pyx_t_1 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_5, NULL}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_1, 0+__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 86, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":70 + * cdef str nlp_solver_type + * + * def __cinit__(self, model_name, nlp_solver_type, N): # <<<<<<<<<<<<<< + * + * self.solver_created = False + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":89 + * + * + * def __get_pointers_solver(self): # <<<<<<<<<<<<<< + * """ + * Private function to get the pointers for solver + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_3_AcadosOcpSolverCython__get_pointers_solver(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_2__get_pointers_solver, "\n Private function to get the pointers for solver\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_3_AcadosOcpSolverCython__get_pointers_solver = {"_AcadosOcpSolverCython__get_pointers_solver", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_3_AcadosOcpSolverCython__get_pointers_solver, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_2__get_pointers_solver}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_3_AcadosOcpSolverCython__get_pointers_solver(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("_AcadosOcpSolverCython__get_pointers_solver (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("_AcadosOcpSolverCython__get_pointers_solver", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "_AcadosOcpSolverCython__get_pointers_solver", 0))) return NULL; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_2__get_pointers_solver(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_2__get_pointers_solver(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("_AcadosOcpSolverCython__get_pointers_solver", 1); + + /* "acados_template/acados_ocp_solver_pyx.pyx":94 + * """ + * # get pointers solver + * self.nlp_opts = acados_solver.acados_get_nlp_opts(self.capsule) # <<<<<<<<<<<<<< + * self.nlp_dims = acados_solver.acados_get_nlp_dims(self.capsule) + * self.nlp_config = acados_solver.acados_get_nlp_config(self.capsule) + */ + __pyx_v_self->nlp_opts = lat_acados_get_nlp_opts(__pyx_v_self->capsule); + + /* "acados_template/acados_ocp_solver_pyx.pyx":95 + * # get pointers solver + * self.nlp_opts = acados_solver.acados_get_nlp_opts(self.capsule) + * self.nlp_dims = acados_solver.acados_get_nlp_dims(self.capsule) # <<<<<<<<<<<<<< + * self.nlp_config = acados_solver.acados_get_nlp_config(self.capsule) + * self.nlp_out = acados_solver.acados_get_nlp_out(self.capsule) + */ + __pyx_v_self->nlp_dims = lat_acados_get_nlp_dims(__pyx_v_self->capsule); + + /* "acados_template/acados_ocp_solver_pyx.pyx":96 + * self.nlp_opts = acados_solver.acados_get_nlp_opts(self.capsule) + * self.nlp_dims = acados_solver.acados_get_nlp_dims(self.capsule) + * self.nlp_config = acados_solver.acados_get_nlp_config(self.capsule) # <<<<<<<<<<<<<< + * self.nlp_out = acados_solver.acados_get_nlp_out(self.capsule) + * self.sens_out = acados_solver.acados_get_sens_out(self.capsule) + */ + __pyx_v_self->nlp_config = lat_acados_get_nlp_config(__pyx_v_self->capsule); + + /* "acados_template/acados_ocp_solver_pyx.pyx":97 + * self.nlp_dims = acados_solver.acados_get_nlp_dims(self.capsule) + * self.nlp_config = acados_solver.acados_get_nlp_config(self.capsule) + * self.nlp_out = acados_solver.acados_get_nlp_out(self.capsule) # <<<<<<<<<<<<<< + * self.sens_out = acados_solver.acados_get_sens_out(self.capsule) + * self.nlp_in = acados_solver.acados_get_nlp_in(self.capsule) + */ + __pyx_v_self->nlp_out = lat_acados_get_nlp_out(__pyx_v_self->capsule); + + /* "acados_template/acados_ocp_solver_pyx.pyx":98 + * self.nlp_config = acados_solver.acados_get_nlp_config(self.capsule) + * self.nlp_out = acados_solver.acados_get_nlp_out(self.capsule) + * self.sens_out = acados_solver.acados_get_sens_out(self.capsule) # <<<<<<<<<<<<<< + * self.nlp_in = acados_solver.acados_get_nlp_in(self.capsule) + * self.nlp_solver = acados_solver.acados_get_nlp_solver(self.capsule) + */ + __pyx_v_self->sens_out = lat_acados_get_sens_out(__pyx_v_self->capsule); + + /* "acados_template/acados_ocp_solver_pyx.pyx":99 + * self.nlp_out = acados_solver.acados_get_nlp_out(self.capsule) + * self.sens_out = acados_solver.acados_get_sens_out(self.capsule) + * self.nlp_in = acados_solver.acados_get_nlp_in(self.capsule) # <<<<<<<<<<<<<< + * self.nlp_solver = acados_solver.acados_get_nlp_solver(self.capsule) + * + */ + __pyx_v_self->nlp_in = lat_acados_get_nlp_in(__pyx_v_self->capsule); + + /* "acados_template/acados_ocp_solver_pyx.pyx":100 + * self.sens_out = acados_solver.acados_get_sens_out(self.capsule) + * self.nlp_in = acados_solver.acados_get_nlp_in(self.capsule) + * self.nlp_solver = acados_solver.acados_get_nlp_solver(self.capsule) # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_self->nlp_solver = lat_acados_get_nlp_solver(__pyx_v_self->capsule); + + /* "acados_template/acados_ocp_solver_pyx.pyx":89 + * + * + * def __get_pointers_solver(self): # <<<<<<<<<<<<<< + * """ + * Private function to get the pointers for solver + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":103 + * + * + * def solve_for_x0(self, x0_bar): # <<<<<<<<<<<<<< + * """ + * Wrapper around `solve()` which sets initial state constraint, solves the OCP, and returns u0. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve_for_x0(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve_for_x0, "\n Wrapper around `solve()` which sets initial state constraint, solves the OCP, and returns u0.\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve_for_x0 = {"solve_for_x0", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve_for_x0, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve_for_x0}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve_for_x0(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_x0_bar = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("solve_for_x0 (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_x0_bar,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_x0_bar)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 103, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "solve_for_x0") < 0)) __PYX_ERR(0, 103, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_x0_bar = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("solve_for_x0", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 103, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.solve_for_x0", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve_for_x0(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_x0_bar); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve_for_x0(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_x0_bar) { + PyObject *__pyx_v_status = NULL; + PyObject *__pyx_v_u0 = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("solve_for_x0", 1); + + /* "acados_template/acados_ocp_solver_pyx.pyx":107 + * Wrapper around `solve()` which sets initial state constraint, solves the OCP, and returns u0. + * """ + * self.set(0, "lbx", x0_bar) # <<<<<<<<<<<<<< + * self.set(0, "ubx", x0_bar) + * + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_set); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 107, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[4] = {__pyx_t_3, __pyx_int_0, __pyx_n_u_lbx, __pyx_v_x0_bar}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 3+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 107, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":108 + * """ + * self.set(0, "lbx", x0_bar) + * self.set(0, "ubx", x0_bar) # <<<<<<<<<<<<<< + * + * status = self.solve() + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_set); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 108, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[4] = {__pyx_t_3, __pyx_int_0, __pyx_n_u_ubx, __pyx_v_x0_bar}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 3+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 108, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":110 + * self.set(0, "ubx", x0_bar) + * + * status = self.solve() # <<<<<<<<<<<<<< + * + * if status == 2: + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_solve); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 110, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, NULL}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 0+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 110, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_v_status = __pyx_t_1; + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":112 + * status = self.solve() + * + * if status == 2: # <<<<<<<<<<<<<< + * print("Warning: acados_ocp_solver reached maximum iterations.") + * elif status != 0: + */ + __pyx_t_5 = (__Pyx_PyInt_BoolEqObjC(__pyx_v_status, __pyx_int_2, 2, 0)); if (unlikely((__pyx_t_5 < 0))) __PYX_ERR(0, 112, __pyx_L1_error) + if (__pyx_t_5) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":113 + * + * if status == 2: + * print("Warning: acados_ocp_solver reached maximum iterations.") # <<<<<<<<<<<<<< + * elif status != 0: + * raise Exception(f'acados acados_ocp_solver returned status {status}') + */ + __pyx_t_1 = __Pyx_PyObject_Call(__pyx_builtin_print, __pyx_tuple__11, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 113, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":112 + * status = self.solve() + * + * if status == 2: # <<<<<<<<<<<<<< + * print("Warning: acados_ocp_solver reached maximum iterations.") + * elif status != 0: + */ + goto __pyx_L3; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":114 + * if status == 2: + * print("Warning: acados_ocp_solver reached maximum iterations.") + * elif status != 0: # <<<<<<<<<<<<<< + * raise Exception(f'acados acados_ocp_solver returned status {status}') + * + */ + __pyx_t_5 = (__Pyx_PyInt_BoolNeObjC(__pyx_v_status, __pyx_int_0, 0, 0)); if (unlikely((__pyx_t_5 < 0))) __PYX_ERR(0, 114, __pyx_L1_error) + if (unlikely(__pyx_t_5)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":115 + * print("Warning: acados_ocp_solver reached maximum iterations.") + * elif status != 0: + * raise Exception(f'acados acados_ocp_solver returned status {status}') # <<<<<<<<<<<<<< + * + * u0 = self.get(0, "u") + */ + __pyx_t_1 = __Pyx_PyObject_FormatSimple(__pyx_v_status, __pyx_empty_unicode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 115, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyUnicode_Concat(__pyx_kp_u_acados_acados_ocp_solver_returne, __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 115, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 115, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 115, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":114 + * if status == 2: + * print("Warning: acados_ocp_solver reached maximum iterations.") + * elif status != 0: # <<<<<<<<<<<<<< + * raise Exception(f'acados acados_ocp_solver returned status {status}') + * + */ + } + __pyx_L3:; + + /* "acados_template/acados_ocp_solver_pyx.pyx":117 + * raise Exception(f'acados acados_ocp_solver returned status {status}') + * + * u0 = self.get(0, "u") # <<<<<<<<<<<<<< + * return u0 + * + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 117, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_Call(__pyx_t_1, __pyx_tuple__12, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 117, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_u0 = __pyx_t_2; + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":118 + * + * u0 = self.get(0, "u") + * return u0 # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_u0); + __pyx_r = __pyx_v_u0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":103 + * + * + * def solve_for_x0(self, x0_bar): # <<<<<<<<<<<<<< + * """ + * Wrapper around `solve()` which sets initial state constraint, solves the OCP, and returns u0. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.solve_for_x0", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_status); + __Pyx_XDECREF(__pyx_v_u0); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":121 + * + * + * def solve(self): # <<<<<<<<<<<<<< + * """ + * Solve the ocp with current input. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7solve(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6solve, "\n Solve the ocp with current input.\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7solve = {"solve", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7solve, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6solve}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7solve(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("solve (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("solve", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "solve", 0))) return NULL; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6solve(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6solve(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("solve", 1); + + /* "acados_template/acados_ocp_solver_pyx.pyx":125 + * Solve the ocp with current input. + * """ + * return acados_solver.acados_solve(self.capsule) # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_int(lat_acados_solve(__pyx_v_self->capsule)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 125, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":121 + * + * + * def solve(self): # <<<<<<<<<<<<<< + * """ + * Solve the ocp with current input. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.solve", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":128 + * + * + * def reset(self, reset_qp_solver_mem=1): # <<<<<<<<<<<<<< + * """ + * Sets current iterate to all zeros. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9reset(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8reset, "\n Sets current iterate to all zeros.\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9reset = {"reset", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9reset, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8reset}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9reset(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_reset_qp_solver_mem = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("reset (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_reset_qp_solver_mem,0}; + values[0] = __Pyx_Arg_NewRef_FASTCALL(((PyObject *)__pyx_int_1)); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_reset_qp_solver_mem); + if (value) { values[0] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 128, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "reset") < 0)) __PYX_ERR(0, 128, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_reset_qp_solver_mem = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("reset", 0, 0, 1, __pyx_nargs); __PYX_ERR(0, 128, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.reset", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8reset(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_reset_qp_solver_mem); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8reset(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_reset_qp_solver_mem) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("reset", 1); + + /* "acados_template/acados_ocp_solver_pyx.pyx":132 + * Sets current iterate to all zeros. + * """ + * return acados_solver.acados_reset(self.capsule, reset_qp_solver_mem) # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_As_int(__pyx_v_reset_qp_solver_mem); if (unlikely((__pyx_t_1 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 132, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyInt_From_int(lat_acados_reset(__pyx_v_self->capsule, __pyx_t_1)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 132, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":128 + * + * + * def reset(self, reset_qp_solver_mem=1): # <<<<<<<<<<<<<< + * """ + * Sets current iterate to all zeros. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.reset", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":135 + * + * + * def custom_update(self, data_): # <<<<<<<<<<<<<< + * """ + * A custom function that can be implemented by a user to be called between solver calls. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11custom_update(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10custom_update, "\n A custom function that can be implemented by a user to be called between solver calls.\n By default this does nothing.\n The idea is to have a convenient wrapper to do complex updates of parameters and numerical data efficiently in C,\n in a function that is compiled into the solver library and can be conveniently used in the Python environment.\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11custom_update = {"custom_update", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11custom_update, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10custom_update}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11custom_update(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_data_ = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("custom_update (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_data,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_data)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 135, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "custom_update") < 0)) __PYX_ERR(0, 135, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_data_ = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("custom_update", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 135, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.custom_update", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10custom_update(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_data_); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10custom_update(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_data_) { + Py_ssize_t __pyx_v_data_len; + PyArrayObject *__pyx_v_data = 0; + __Pyx_LocalBuf_ND __pyx_pybuffernd_data; + __Pyx_Buffer __pyx_pybuffer_data; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyArrayObject *__pyx_t_7 = NULL; + char *__pyx_t_8; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("custom_update", 1); + __pyx_pybuffer_data.pybuffer.buf = NULL; + __pyx_pybuffer_data.refcount = 0; + __pyx_pybuffernd_data.data = NULL; + __pyx_pybuffernd_data.rcbuffer = &__pyx_pybuffer_data; + + /* "acados_template/acados_ocp_solver_pyx.pyx":142 + * in a function that is compiled into the solver library and can be conveniently used in the Python environment. + * """ + * data_len = len(data_) # <<<<<<<<<<<<<< + * cdef cnp.ndarray[cnp.float64_t, ndim=1] data = np.ascontiguousarray(data_, dtype=np.float64) + * + */ + __pyx_t_1 = PyObject_Length(__pyx_v_data_); if (unlikely(__pyx_t_1 == ((Py_ssize_t)-1))) __PYX_ERR(0, 142, __pyx_L1_error) + __pyx_v_data_len = __pyx_t_1; + + /* "acados_template/acados_ocp_solver_pyx.pyx":143 + * """ + * data_len = len(data_) + * cdef cnp.ndarray[cnp.float64_t, ndim=1] data = np.ascontiguousarray(data_, dtype=np.float64) # <<<<<<<<<<<<<< + * + * return acados_solver.acados_custom_update(self.capsule, data.data, data_len) + */ + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_np); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = PyTuple_New(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_INCREF(__pyx_v_data_); + __Pyx_GIVEREF(__pyx_v_data_); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_v_data_)) __PYX_ERR(0, 143, __pyx_L1_error); + __pyx_t_4 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GetModuleGlobalName(__pyx_t_5, __pyx_n_s_np); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_float64); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (PyDict_SetItem(__pyx_t_4, __pyx_n_s_dtype, __pyx_t_6) < 0) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __pyx_t_6 = __Pyx_PyObject_Call(__pyx_t_3, __pyx_t_2, __pyx_t_4); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (!(likely(((__pyx_t_6) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_6, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 143, __pyx_L1_error) + __pyx_t_7 = ((PyArrayObject *)__pyx_t_6); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_data.rcbuffer->pybuffer, (PyObject*)__pyx_t_7, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 1, 0, __pyx_stack) == -1)) { + __pyx_v_data = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_data.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 143, __pyx_L1_error) + } else {__pyx_pybuffernd_data.diminfo[0].strides = __pyx_pybuffernd_data.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_data.diminfo[0].shape = __pyx_pybuffernd_data.rcbuffer->pybuffer.shape[0]; + } + } + __pyx_t_7 = 0; + __pyx_v_data = ((PyArrayObject *)__pyx_t_6); + __pyx_t_6 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":145 + * cdef cnp.ndarray[cnp.float64_t, ndim=1] data = np.ascontiguousarray(data_, dtype=np.float64) + * + * return acados_solver.acados_custom_update(self.capsule, data.data, data_len) # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_8 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_data)); if (unlikely(__pyx_t_8 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 145, __pyx_L1_error) + __pyx_t_6 = __Pyx_PyInt_From_int(lat_acados_custom_update(__pyx_v_self->capsule, ((double *)__pyx_t_8), __pyx_v_data_len)); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 145, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_r = __pyx_t_6; + __pyx_t_6 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":135 + * + * + * def custom_update(self, data_): # <<<<<<<<<<<<<< + * """ + * A custom function that can be implemented by a user to be called between solver calls. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_data.rcbuffer->pybuffer); + __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.custom_update", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + goto __pyx_L2; + __pyx_L0:; + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_data.rcbuffer->pybuffer); + __pyx_L2:; + __Pyx_XDECREF((PyObject *)__pyx_v_data); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":148 + * + * + * def set_new_time_steps(self, new_time_steps): # <<<<<<<<<<<<<< + * """ + * Set new time steps. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13set_new_time_steps(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12set_new_time_steps, "\n Set new time steps.\n Recreates the solver if N changes.\n\n :param new_time_steps: 1 dimensional np array of new time steps for the solver\n\n .. note:: This allows for different use-cases: either set a new size of time-steps or a new distribution of\n the shooting nodes without changing the number, e.g., to reach a different final time. Both cases\n do not require a new code export and compilation.\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13set_new_time_steps = {"set_new_time_steps", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13set_new_time_steps, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12set_new_time_steps}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13set_new_time_steps(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v_new_time_steps = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("set_new_time_steps (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_new_time_steps,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_new_time_steps)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 148, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "set_new_time_steps") < 0)) __PYX_ERR(0, 148, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_new_time_steps = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("set_new_time_steps", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 148, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.set_new_time_steps", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12set_new_time_steps(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_new_time_steps); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12set_new_time_steps(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_new_time_steps) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("set_new_time_steps", 1); + + /* "acados_template/acados_ocp_solver_pyx.pyx":160 + * """ + * + * raise NotImplementedError("AcadosOcpSolverCython: does not support set_new_time_steps() since it is only a prototyping feature") # <<<<<<<<<<<<<< + * # # unlikely but still possible + * # if not self.solver_created: + */ + __pyx_t_1 = __Pyx_PyObject_Call(__pyx_builtin_NotImplementedError, __pyx_tuple__13, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 160, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 160, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":148 + * + * + * def set_new_time_steps(self, new_time_steps): # <<<<<<<<<<<<<< + * """ + * Set new time steps. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.set_new_time_steps", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":199 + * + * + * def update_qp_solver_cond_N(self, qp_solver_cond_N: int): # <<<<<<<<<<<<<< + * """ + * Recreate solver with new value `qp_solver_cond_N` with a partial condensing QP solver. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15update_qp_solver_cond_N(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14update_qp_solver_cond_N, "\n Recreate solver with new value `qp_solver_cond_N` with a partial condensing QP solver.\n This function is relevant for code reuse, i.e., if either `set_new_time_steps(...)` is used or\n the influence of a different `qp_solver_cond_N` is studied without code export and compilation.\n :param qp_solver_cond_N: new number of condensing stages for the solver\n\n .. note:: This function can only be used in combination with a partial condensing QP solver.\n\n .. note:: After `set_new_time_steps(...)` is used and depending on the new number of time steps it might be\n necessary to change `qp_solver_cond_N` as well (using this function), i.e., typically\n `qp_solver_cond_N < N`.\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15update_qp_solver_cond_N = {"update_qp_solver_cond_N", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15update_qp_solver_cond_N, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14update_qp_solver_cond_N}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15update_qp_solver_cond_N(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v_qp_solver_cond_N = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("update_qp_solver_cond_N (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_qp_solver_cond_N,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_qp_solver_cond_N)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 199, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "update_qp_solver_cond_N") < 0)) __PYX_ERR(0, 199, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_qp_solver_cond_N = ((PyObject*)values[0]); + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("update_qp_solver_cond_N", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 199, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.update_qp_solver_cond_N", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_qp_solver_cond_N), (&PyInt_Type), 0, "qp_solver_cond_N", 1))) __PYX_ERR(0, 199, __pyx_L1_error) + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14update_qp_solver_cond_N(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_qp_solver_cond_N); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = NULL; + __pyx_L0:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14update_qp_solver_cond_N(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_qp_solver_cond_N) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("update_qp_solver_cond_N", 1); + + /* "acados_template/acados_ocp_solver_pyx.pyx":212 + * `qp_solver_cond_N < N`. + * """ + * raise NotImplementedError("AcadosOcpSolverCython: does not support update_qp_solver_cond_N() since it is only a prototyping feature") # <<<<<<<<<<<<<< + * + * # # unlikely but still possible + */ + __pyx_t_1 = __Pyx_PyObject_Call(__pyx_builtin_NotImplementedError, __pyx_tuple__14, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 212, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 212, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":199 + * + * + * def update_qp_solver_cond_N(self, qp_solver_cond_N: int): # <<<<<<<<<<<<<< + * """ + * Recreate solver with new value `qp_solver_cond_N` with a partial condensing QP solver. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.update_qp_solver_cond_N", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":233 + * + * + * def eval_param_sens(self, index, stage=0, field="ex"): # <<<<<<<<<<<<<< + * """ + * Calculate the sensitivity of the curent solution with respect to the initial state component of index + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17eval_param_sens(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16eval_param_sens, "\n Calculate the sensitivity of the curent solution with respect to the initial state component of index\n\n :param index: integer corresponding to initial state index in range(nx)\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17eval_param_sens = {"eval_param_sens", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17eval_param_sens, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16eval_param_sens}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17eval_param_sens(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_index = 0; + PyObject *__pyx_v_stage = 0; + PyObject *__pyx_v_field = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("eval_param_sens (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_index,&__pyx_n_s_stage,&__pyx_n_s_field,0}; + values[1] = __Pyx_Arg_NewRef_FASTCALL(((PyObject *)__pyx_int_0)); + values[2] = __Pyx_Arg_NewRef_FASTCALL(((PyObject *)__pyx_n_u_ex)); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_index)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 233, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stage); + if (value) { values[1] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 233, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field); + if (value) { values[2] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 233, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "eval_param_sens") < 0)) __PYX_ERR(0, 233, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_index = values[0]; + __pyx_v_stage = values[1]; + __pyx_v_field = values[2]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("eval_param_sens", 0, 1, 3, __pyx_nargs); __PYX_ERR(0, 233, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.eval_param_sens", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16eval_param_sens(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_index, __pyx_v_stage, __pyx_v_field); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16eval_param_sens(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_stage, PyObject *__pyx_v_field) { + PyObject *__pyx_v_field_ = NULL; + int __pyx_v_nx; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_t_5; + int __pyx_t_6; + char const *__pyx_t_7; + Py_ssize_t __pyx_t_8; + Py_UCS4 __pyx_t_9; + char *__pyx_t_10; + int __pyx_t_11; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("eval_param_sens", 0); + __Pyx_INCREF(__pyx_v_field); + + /* "acados_template/acados_ocp_solver_pyx.pyx":240 + * """ + * + * field_ = field # <<<<<<<<<<<<<< + * field = field_.encode('utf-8') + * + */ + __Pyx_INCREF(__pyx_v_field); + __pyx_v_field_ = __pyx_v_field; + + /* "acados_template/acados_ocp_solver_pyx.pyx":241 + * + * field_ = field + * field = field_.encode('utf-8') # <<<<<<<<<<<<<< + * + * # checks + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_field_, __pyx_n_s_encode); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 241, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_kp_u_utf_8}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 241, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __Pyx_DECREF_SET(__pyx_v_field, __pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":244 + * + * # checks + * if not isinstance(index, int): # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.eval_param_sens(): index must be Integer.') + * + */ + __pyx_t_5 = PyInt_Check(__pyx_v_index); + __pyx_t_6 = (!__pyx_t_5); + if (unlikely(__pyx_t_6)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":245 + * # checks + * if not isinstance(index, int): + * raise Exception('AcadosOcpSolverCython.eval_param_sens(): index must be Integer.') # <<<<<<<<<<<<<< + * + * cdef int nx = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, self.nlp_dims, self.nlp_out, 0, "x".encode('utf-8')) + */ + __pyx_t_1 = __Pyx_PyObject_Call(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_tuple__15, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 245, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 245, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":244 + * + * # checks + * if not isinstance(index, int): # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.eval_param_sens(): index must be Integer.') + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":247 + * raise Exception('AcadosOcpSolverCython.eval_param_sens(): index must be Integer.') + * + * cdef int nx = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, self.nlp_dims, self.nlp_out, 0, "x".encode('utf-8')) # <<<<<<<<<<<<<< + * + * if index < 0 or index > nx: + */ + __pyx_t_7 = __Pyx_PyBytes_AsString(__pyx_n_b_x); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 247, __pyx_L1_error) + __pyx_v_nx = ocp_nlp_dims_get_from_attr(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, 0, __pyx_t_7); + + /* "acados_template/acados_ocp_solver_pyx.pyx":249 + * cdef int nx = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, self.nlp_dims, self.nlp_out, 0, "x".encode('utf-8')) + * + * if index < 0 or index > nx: # <<<<<<<<<<<<<< + * raise Exception(f'AcadosOcpSolverCython.eval_param_sens(): index must be in [0, nx-1], got: {index}.') + * + */ + __pyx_t_1 = PyObject_RichCompare(__pyx_v_index, __pyx_int_0, Py_LT); __Pyx_XGOTREF(__pyx_t_1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 249, __pyx_L1_error) + __pyx_t_5 = __Pyx_PyObject_IsTrue(__pyx_t_1); if (unlikely((__pyx_t_5 < 0))) __PYX_ERR(0, 249, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (!__pyx_t_5) { + } else { + __pyx_t_6 = __pyx_t_5; + goto __pyx_L5_bool_binop_done; + } + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_nx); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = PyObject_RichCompare(__pyx_v_index, __pyx_t_1, Py_GT); __Pyx_XGOTREF(__pyx_t_2); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 249, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_5 = __Pyx_PyObject_IsTrue(__pyx_t_2); if (unlikely((__pyx_t_5 < 0))) __PYX_ERR(0, 249, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_6 = __pyx_t_5; + __pyx_L5_bool_binop_done:; + if (unlikely(__pyx_t_6)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":250 + * + * if index < 0 or index > nx: + * raise Exception(f'AcadosOcpSolverCython.eval_param_sens(): index must be in [0, nx-1], got: {index}.') # <<<<<<<<<<<<<< + * + * # actual eval_param + */ + __pyx_t_2 = PyTuple_New(3); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 250, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_8 = 0; + __pyx_t_9 = 127; + __Pyx_INCREF(__pyx_kp_u_AcadosOcpSolverCython_eval_param_2); + __pyx_t_8 += 74; + __Pyx_GIVEREF(__pyx_kp_u_AcadosOcpSolverCython_eval_param_2); + PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_kp_u_AcadosOcpSolverCython_eval_param_2); + __pyx_t_1 = __Pyx_PyObject_FormatSimple(__pyx_v_index, __pyx_empty_unicode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 250, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_9 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) > __pyx_t_9) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) : __pyx_t_9; + __pyx_t_8 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_2, 1, __pyx_t_1); + __pyx_t_1 = 0; + __Pyx_INCREF(__pyx_kp_u__2); + __pyx_t_8 += 1; + __Pyx_GIVEREF(__pyx_kp_u__2); + PyTuple_SET_ITEM(__pyx_t_2, 2, __pyx_kp_u__2); + __pyx_t_1 = __Pyx_PyUnicode_Join(__pyx_t_2, 3, __pyx_t_8, __pyx_t_9); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 250, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 250, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 250, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":249 + * cdef int nx = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, self.nlp_dims, self.nlp_out, 0, "x".encode('utf-8')) + * + * if index < 0 or index > nx: # <<<<<<<<<<<<<< + * raise Exception(f'AcadosOcpSolverCython.eval_param_sens(): index must be in [0, nx-1], got: {index}.') + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":253 + * + * # actual eval_param + * acados_solver_common.ocp_nlp_eval_param_sens(self.nlp_solver, field, stage, index, self.sens_out) # <<<<<<<<<<<<<< + * + * return + */ + __pyx_t_10 = __Pyx_PyObject_AsWritableString(__pyx_v_field); if (unlikely((!__pyx_t_10) && PyErr_Occurred())) __PYX_ERR(0, 253, __pyx_L1_error) + __pyx_t_4 = __Pyx_PyInt_As_int(__pyx_v_stage); if (unlikely((__pyx_t_4 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 253, __pyx_L1_error) + __pyx_t_11 = __Pyx_PyInt_As_int(__pyx_v_index); if (unlikely((__pyx_t_11 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 253, __pyx_L1_error) + ocp_nlp_eval_param_sens(__pyx_v_self->nlp_solver, __pyx_t_10, __pyx_t_4, __pyx_t_11, __pyx_v_self->sens_out); + + /* "acados_template/acados_ocp_solver_pyx.pyx":255 + * acados_solver_common.ocp_nlp_eval_param_sens(self.nlp_solver, field, stage, index, self.sens_out) + * + * return # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":233 + * + * + * def eval_param_sens(self, index, stage=0, field="ex"): # <<<<<<<<<<<<<< + * """ + * Calculate the sensitivity of the curent solution with respect to the initial state component of index + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.eval_param_sens", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_field_); + __Pyx_XDECREF(__pyx_v_field); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":258 + * + * + * def get(self, int stage, str field_): # <<<<<<<<<<<<<< + * """ + * Get the last solution of the solver: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19get(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18get, "\n Get the last solution of the solver:\n\n :param stage: integer corresponding to shooting node\n :param field: string in ['x', 'u', 'z', 'pi', 'lam', 't', 'sl', 'su',]\n\n .. note:: regarding lam, t: \n\n the inequalities are internally organized in the following order: \n\n [ lbu lbx lg lh lphi ubu ubx ug uh uphi; \n\n lsbu lsbx lsg lsh lsphi usbu usbx usg ush usphi]\n\n .. note:: pi: multipliers for dynamics equality constraints \n\n lam: multipliers for inequalities \n\n t: slack variables corresponding to evaluation of all inequalities (at the solution) \n\n sl: slack variables of soft lower inequality constraints \n\n su: slack variables of soft upper inequality constraints \n\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19get = {"get", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19get, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18get}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19get(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + int __pyx_v_stage; + PyObject *__pyx_v_field_ = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[2] = {0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("get (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_stage,&__pyx_n_s_field_2,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stage)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 258, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field_2)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 258, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("get", 1, 2, 2, 1); __PYX_ERR(0, 258, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "get") < 0)) __PYX_ERR(0, 258, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 2)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + } + __pyx_v_stage = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_stage == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 258, __pyx_L3_error) + __pyx_v_field_ = ((PyObject*)values[1]); + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("get", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 258, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.get", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 258, __pyx_L1_error) + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18get(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_stage, __pyx_v_field_); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = NULL; + __pyx_L0:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18get(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_) { + PyObject *__pyx_v_out_fields = NULL; + PyObject *__pyx_v_field = NULL; + int __pyx_v_dims; + PyArrayObject *__pyx_v_out = 0; + __Pyx_LocalBuf_ND __pyx_pybuffernd_out; + __Pyx_Buffer __pyx_pybuffer_out; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_t_5; + int __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + char const *__pyx_t_8; + PyArrayObject *__pyx_t_9 = NULL; + char const *__pyx_t_10; + char *__pyx_t_11; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get", 1); + __pyx_pybuffer_out.pybuffer.buf = NULL; + __pyx_pybuffer_out.refcount = 0; + __pyx_pybuffernd_out.data = NULL; + __pyx_pybuffernd_out.rcbuffer = &__pyx_pybuffer_out; + + /* "acados_template/acados_ocp_solver_pyx.pyx":277 + * """ + * + * out_fields = ['x', 'u', 'z', 'pi', 'lam', 't', 'sl', 'su'] # <<<<<<<<<<<<<< + * field = field_.encode('utf-8') + * + */ + __pyx_t_1 = PyList_New(8); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 277, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_u_x); + __Pyx_GIVEREF(__pyx_n_u_x); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_u_x)) __PYX_ERR(0, 277, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_u); + __Pyx_GIVEREF(__pyx_n_u_u); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 1, __pyx_n_u_u)) __PYX_ERR(0, 277, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_z); + __Pyx_GIVEREF(__pyx_n_u_z); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 2, __pyx_n_u_z)) __PYX_ERR(0, 277, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_pi); + __Pyx_GIVEREF(__pyx_n_u_pi); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 3, __pyx_n_u_pi)) __PYX_ERR(0, 277, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_lam); + __Pyx_GIVEREF(__pyx_n_u_lam); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 4, __pyx_n_u_lam)) __PYX_ERR(0, 277, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_t); + __Pyx_GIVEREF(__pyx_n_u_t); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 5, __pyx_n_u_t)) __PYX_ERR(0, 277, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_sl); + __Pyx_GIVEREF(__pyx_n_u_sl); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 6, __pyx_n_u_sl)) __PYX_ERR(0, 277, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_su); + __Pyx_GIVEREF(__pyx_n_u_su); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 7, __pyx_n_u_su)) __PYX_ERR(0, 277, __pyx_L1_error); + __pyx_v_out_fields = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":278 + * + * out_fields = ['x', 'u', 'z', 'pi', 'lam', 't', 'sl', 'su'] + * field = field_.encode('utf-8') # <<<<<<<<<<<<<< + * + * if field_ not in out_fields: + */ + if (unlikely(__pyx_v_field_ == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); + __PYX_ERR(0, 278, __pyx_L1_error) + } + __pyx_t_1 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 278, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_field = __pyx_t_1; + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":280 + * field = field_.encode('utf-8') + * + * if field_ not in out_fields: # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.get(): {} is an invalid argument.\ + * \n Possible values are {}.'.format(field_, out_fields)) + */ + __pyx_t_2 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_out_fields, Py_NE)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 280, __pyx_L1_error) + if (unlikely(__pyx_t_2)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":282 + * if field_ not in out_fields: + * raise Exception('AcadosOcpSolverCython.get(): {} is an invalid argument.\ + * \n Possible values are {}.'.format(field_, out_fields)) # <<<<<<<<<<<<<< + * + * if stage < 0 or stage > self.N: + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_get_is_an, __pyx_n_s_format); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 282, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = NULL; + __pyx_t_5 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_5 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_4, __pyx_v_field_, __pyx_v_out_fields}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_5, 2+__pyx_t_5); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 282, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":281 + * + * if field_ not in out_fields: + * raise Exception('AcadosOcpSolverCython.get(): {} is an invalid argument.\ # <<<<<<<<<<<<<< + * \n Possible values are {}.'.format(field_, out_fields)) + * + */ + __pyx_t_3 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 281, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_t_3, 0, 0, 0); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __PYX_ERR(0, 281, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":280 + * field = field_.encode('utf-8') + * + * if field_ not in out_fields: # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.get(): {} is an invalid argument.\ + * \n Possible values are {}.'.format(field_, out_fields)) + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":284 + * \n Possible values are {}.'.format(field_, out_fields)) + * + * if stage < 0 or stage > self.N: # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.get(): stage index must be in [0, N], got: {}.'.format(self.N)) + * + */ + __pyx_t_6 = (__pyx_v_stage < 0); + if (!__pyx_t_6) { + } else { + __pyx_t_2 = __pyx_t_6; + goto __pyx_L5_bool_binop_done; + } + __pyx_t_6 = (__pyx_v_stage > __pyx_v_self->N); + __pyx_t_2 = __pyx_t_6; + __pyx_L5_bool_binop_done:; + if (unlikely(__pyx_t_2)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":285 + * + * if stage < 0 or stage > self.N: + * raise Exception('AcadosOcpSolverCython.get(): stage index must be in [0, N], got: {}.'.format(self.N)) # <<<<<<<<<<<<<< + * + * if stage == self.N and field_ == 'pi': + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_get_stage, __pyx_n_s_format); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 285, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_4 = __Pyx_PyInt_From_int(__pyx_v_self->N); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 285, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_7 = NULL; + __pyx_t_5 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_5 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_7, __pyx_t_4}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_5, 1+__pyx_t_5); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 285, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 285, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 285, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":284 + * \n Possible values are {}.'.format(field_, out_fields)) + * + * if stage < 0 or stage > self.N: # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.get(): stage index must be in [0, N], got: {}.'.format(self.N)) + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":287 + * raise Exception('AcadosOcpSolverCython.get(): stage index must be in [0, N], got: {}.'.format(self.N)) + * + * if stage == self.N and field_ == 'pi': # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.get(): field {} does not exist at final stage {}.'\ + * .format(field_, stage)) + */ + __pyx_t_6 = (__pyx_v_stage == __pyx_v_self->N); + if (__pyx_t_6) { + } else { + __pyx_t_2 = __pyx_t_6; + goto __pyx_L8_bool_binop_done; + } + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_pi, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 287, __pyx_L1_error) + __pyx_t_2 = __pyx_t_6; + __pyx_L8_bool_binop_done:; + if (unlikely(__pyx_t_2)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":289 + * if stage == self.N and field_ == 'pi': + * raise Exception('AcadosOcpSolverCython.get(): field {} does not exist at final stage {}.'\ + * .format(field_, stage)) # <<<<<<<<<<<<<< + * + * cdef int dims = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_get_field, __pyx_n_s_format); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 289, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = __Pyx_PyInt_From_int(__pyx_v_stage); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 289, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_7 = NULL; + __pyx_t_5 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_5 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_7, __pyx_v_field_, __pyx_t_4}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_5, 2+__pyx_t_5); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 289, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":288 + * + * if stage == self.N and field_ == 'pi': + * raise Exception('AcadosOcpSolverCython.get(): field {} does not exist at final stage {}.'\ # <<<<<<<<<<<<<< + * .format(field_, stage)) + * + */ + __pyx_t_3 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 288, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_t_3, 0, 0, 0); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __PYX_ERR(0, 288, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":287 + * raise Exception('AcadosOcpSolverCython.get(): stage index must be in [0, N], got: {}.'.format(self.N)) + * + * if stage == self.N and field_ == 'pi': # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.get(): field {} does not exist at final stage {}.'\ + * .format(field_, stage)) + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":292 + * + * cdef int dims = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, + * self.nlp_dims, self.nlp_out, stage, field) # <<<<<<<<<<<<<< + * + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((dims,)) + */ + __pyx_t_8 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_8) && PyErr_Occurred())) __PYX_ERR(0, 292, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":291 + * .format(field_, stage)) + * + * cdef int dims = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, # <<<<<<<<<<<<<< + * self.nlp_dims, self.nlp_out, stage, field) + * + */ + __pyx_v_dims = ocp_nlp_dims_get_from_attr(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_8); + + /* "acados_template/acados_ocp_solver_pyx.pyx":294 + * self.nlp_dims, self.nlp_out, stage, field) + * + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((dims,)) # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_out_get(self.nlp_config, \ + * self.nlp_dims, self.nlp_out, stage, field, out.data) + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 294, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_zeros); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 294, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_dims); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 294, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = PyTuple_New(1); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 294, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_7, 0, __pyx_t_1)) __PYX_ERR(0, 294, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_1 = NULL; + __pyx_t_5 = 0; + #if CYTHON_UNPACK_METHODS + if (unlikely(PyMethod_Check(__pyx_t_4))) { + __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_4); + if (likely(__pyx_t_1)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_4); + __Pyx_INCREF(__pyx_t_1); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_4, function); + __pyx_t_5 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_1, __pyx_t_7}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_5, 1+__pyx_t_5); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 294, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + if (!(likely(((__pyx_t_3) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_3, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 294, __pyx_L1_error) + __pyx_t_9 = ((PyArrayObject *)__pyx_t_3); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_out.rcbuffer->pybuffer, (PyObject*)__pyx_t_9, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 1, 0, __pyx_stack) == -1)) { + __pyx_v_out = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_out.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 294, __pyx_L1_error) + } else {__pyx_pybuffernd_out.diminfo[0].strides = __pyx_pybuffernd_out.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_out.diminfo[0].shape = __pyx_pybuffernd_out.rcbuffer->pybuffer.shape[0]; + } + } + __pyx_t_9 = 0; + __pyx_v_out = ((PyArrayObject *)__pyx_t_3); + __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":296 + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((dims,)) + * acados_solver_common.ocp_nlp_out_get(self.nlp_config, \ + * self.nlp_dims, self.nlp_out, stage, field, out.data) # <<<<<<<<<<<<<< + * + * return out + */ + __pyx_t_10 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_10) && PyErr_Occurred())) __PYX_ERR(0, 296, __pyx_L1_error) + __pyx_t_11 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_out)); if (unlikely(__pyx_t_11 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 296, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":295 + * + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((dims,)) + * acados_solver_common.ocp_nlp_out_get(self.nlp_config, \ # <<<<<<<<<<<<<< + * self.nlp_dims, self.nlp_out, stage, field, out.data) + * + */ + ocp_nlp_out_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_10, ((void *)__pyx_t_11)); + + /* "acados_template/acados_ocp_solver_pyx.pyx":298 + * self.nlp_dims, self.nlp_out, stage, field, out.data) + * + * return out # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_out); + __pyx_r = ((PyObject *)__pyx_v_out); + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":258 + * + * + * def get(self, int stage, str field_): # <<<<<<<<<<<<<< + * """ + * Get the last solution of the solver: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_7); + { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_out.rcbuffer->pybuffer); + __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.get", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + goto __pyx_L2; + __pyx_L0:; + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_out.rcbuffer->pybuffer); + __pyx_L2:; + __Pyx_XDECREF(__pyx_v_out_fields); + __Pyx_XDECREF(__pyx_v_field); + __Pyx_XDECREF((PyObject *)__pyx_v_out); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":301 + * + * + * def print_statistics(self): # <<<<<<<<<<<<<< + * """ + * prints statistics of previous solver run as a table: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21print_statistics(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20print_statistics, "\n prints statistics of previous solver run as a table:\n - iter: iteration number\n - res_stat: stationarity residual\n - res_eq: residual wrt equality constraints (dynamics)\n - res_ineq: residual wrt inequality constraints (constraints)\n - res_comp: residual wrt complementarity conditions\n - qp_stat: status of QP solver\n - qp_iter: number of QP iterations\n - qp_res_stat: stationarity residual of the last QP solution\n - qp_res_eq: residual wrt equality constraints (dynamics) of the last QP solution\n - qp_res_ineq: residual wrt inequality constraints (constraints) of the last QP solution\n - qp_res_comp: residual wrt complementarity conditions of the last QP solution\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21print_statistics = {"print_statistics", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21print_statistics, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20print_statistics}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21print_statistics(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("print_statistics (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("print_statistics", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "print_statistics", 0))) return NULL; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20print_statistics(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20print_statistics(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("print_statistics", 1); + + /* "acados_template/acados_ocp_solver_pyx.pyx":316 + * - qp_res_comp: residual wrt complementarity conditions of the last QP solution + * """ + * acados_solver.acados_print_stats(self.capsule) # <<<<<<<<<<<<<< + * + * + */ + lat_acados_print_stats(__pyx_v_self->capsule); + + /* "acados_template/acados_ocp_solver_pyx.pyx":301 + * + * + * def print_statistics(self): # <<<<<<<<<<<<<< + * """ + * prints statistics of previous solver run as a table: + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":319 + * + * + * def store_iterate(self, filename='', overwrite=False): # <<<<<<<<<<<<<< + * """ + * Stores the current iterate of the ocp solver in a json file. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23store_iterate(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22store_iterate, "\n Stores the current iterate of the ocp solver in a json file.\n\n :param filename: if not set, use model_name + timestamp + '.json'\n :param overwrite: if false and filename exists add timestamp to filename\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23store_iterate = {"store_iterate", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23store_iterate, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22store_iterate}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23store_iterate(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_filename = 0; + PyObject *__pyx_v_overwrite = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[2] = {0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("store_iterate (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_filename,&__pyx_n_s_overwrite,0}; + values[0] = __Pyx_Arg_NewRef_FASTCALL(((PyObject *)__pyx_kp_u__16)); + values[1] = __Pyx_Arg_NewRef_FASTCALL(((PyObject *)Py_False)); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_filename); + if (value) { values[0] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 319, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 1: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_overwrite); + if (value) { values[1] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 319, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "store_iterate") < 0)) __PYX_ERR(0, 319, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_filename = values[0]; + __pyx_v_overwrite = values[1]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("store_iterate", 0, 0, 2, __pyx_nargs); __PYX_ERR(0, 319, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.store_iterate", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22store_iterate(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_filename, __pyx_v_overwrite); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":358 + * # save + * with open(filename, 'w') as f: + * json.dump(solution, f, default=lambda x: x.tolist(), indent=4, sort_keys=True) # <<<<<<<<<<<<<< + * print("stored current iterate in ", os.path.join(os.getcwd(), filename)) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13store_iterate_lambda(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13store_iterate_lambda = {"lambda", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13store_iterate_lambda, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13store_iterate_lambda(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_x = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("lambda (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_x,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_x)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 358, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "lambda") < 0)) __PYX_ERR(0, 358, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_x = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("lambda", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 358, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.store_iterate.lambda", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_lambda_funcdef_lambda(__pyx_self, __pyx_v_x); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_lambda_funcdef_lambda(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_x) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("lambda", 1); + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_x, __pyx_n_s_tolist); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 358, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, NULL}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 0+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 358, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.store_iterate.lambda", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":319 + * + * + * def store_iterate(self, filename='', overwrite=False): # <<<<<<<<<<<<<< + * """ + * Stores the current iterate of the ocp solver in a json file. + */ + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22store_iterate(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_filename, PyObject *__pyx_v_overwrite) { + PyObject *__pyx_v_json = NULL; + PyObject *__pyx_v_solution = NULL; + Py_ssize_t __pyx_v_lN; + long __pyx_v_i; + PyObject *__pyx_v_i_string = NULL; + PyObject *__pyx_v_k = NULL; + PyObject *__pyx_v_f = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + Py_ssize_t __pyx_t_8; + long __pyx_t_9; + long __pyx_t_10; + long __pyx_t_11; + Py_UCS4 __pyx_t_12; + Py_ssize_t __pyx_t_13; + PyObject *__pyx_t_14 = NULL; + PyObject *__pyx_t_15 = NULL; + PyObject *__pyx_t_16 = NULL; + PyObject *__pyx_t_17 = NULL; + PyObject *__pyx_t_18 = NULL; + PyObject *__pyx_t_19 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("store_iterate", 0); + __Pyx_INCREF(__pyx_v_filename); + + /* "acados_template/acados_ocp_solver_pyx.pyx":326 + * :param overwrite: if false and filename exists add timestamp to filename + * """ + * import json # <<<<<<<<<<<<<< + * if filename == '': + * filename += self.model_name + '_' + 'iterate' + '.json' + */ + __pyx_t_1 = __Pyx_ImportDottedModule(__pyx_n_s_json, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 326, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_json = __pyx_t_1; + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":327 + * """ + * import json + * if filename == '': # <<<<<<<<<<<<<< + * filename += self.model_name + '_' + 'iterate' + '.json' + * + */ + __pyx_t_2 = (__Pyx_PyUnicode_Equals(__pyx_v_filename, __pyx_kp_u__16, Py_EQ)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 327, __pyx_L1_error) + if (__pyx_t_2) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":328 + * import json + * if filename == '': + * filename += self.model_name + '_' + 'iterate' + '.json' # <<<<<<<<<<<<<< + * + * if not overwrite: + */ + __pyx_t_1 = __Pyx_PyUnicode_ConcatSafe(__pyx_v_self->model_name, __pyx_n_u__17); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 328, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyUnicode_ConcatInPlace(__pyx_t_1, __pyx_n_u_iterate); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 328, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyUnicode_ConcatInPlace(__pyx_t_3, __pyx_kp_u_json_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 328, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = PyNumber_InPlaceAdd(__pyx_v_filename, __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 328, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF_SET(__pyx_v_filename, __pyx_t_3); + __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":327 + * """ + * import json + * if filename == '': # <<<<<<<<<<<<<< + * filename += self.model_name + '_' + 'iterate' + '.json' + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":330 + * filename += self.model_name + '_' + 'iterate' + '.json' + * + * if not overwrite: # <<<<<<<<<<<<<< + * # append timestamp + * if os.path.isfile(filename): + */ + __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_v_overwrite); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 330, __pyx_L1_error) + __pyx_t_4 = (!__pyx_t_2); + if (__pyx_t_4) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":332 + * if not overwrite: + * # append timestamp + * if os.path.isfile(filename): # <<<<<<<<<<<<<< + * filename = filename[:-5] + * filename += datetime.utcnow().strftime('%Y-%m-%d-%H:%M:%S.%f') + '.json' + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_os); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 332, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_path); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 332, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_isfile); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 332, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_5, __pyx_v_filename}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 1+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 332, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_t_3); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 332, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + if (__pyx_t_4) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":333 + * # append timestamp + * if os.path.isfile(filename): + * filename = filename[:-5] # <<<<<<<<<<<<<< + * filename += datetime.utcnow().strftime('%Y-%m-%d-%H:%M:%S.%f') + '.json' + * + */ + __pyx_t_3 = __Pyx_PyObject_GetSlice(__pyx_v_filename, 0, -5L, NULL, NULL, &__pyx_slice__18, 0, 1, 1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 333, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF_SET(__pyx_v_filename, __pyx_t_3); + __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":334 + * if os.path.isfile(filename): + * filename = filename[:-5] + * filename += datetime.utcnow().strftime('%Y-%m-%d-%H:%M:%S.%f') + '.json' # <<<<<<<<<<<<<< + * + * # get iterate: + */ + __Pyx_GetModuleGlobalName(__pyx_t_5, __pyx_n_s_datetime); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 334, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_utcnow); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 334, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (unlikely(PyMethod_Check(__pyx_t_7))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_7); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_7); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_7, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_5, NULL}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_7, __pyx_callargs+1-__pyx_t_6, 0+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 334, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + } + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_strftime); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 334, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_7))) { + __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_7); + if (likely(__pyx_t_1)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_7); + __Pyx_INCREF(__pyx_t_1); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_7, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_1, __pyx_kp_u_Y_m_d_H_M_S_f}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_7, __pyx_callargs+1-__pyx_t_6, 1+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 334, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + } + __pyx_t_7 = PyNumber_Add(__pyx_t_3, __pyx_kp_u_json_2); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 334, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = PyNumber_InPlaceAdd(__pyx_v_filename, __pyx_t_7); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 334, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF_SET(__pyx_v_filename, __pyx_t_3); + __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":332 + * if not overwrite: + * # append timestamp + * if os.path.isfile(filename): # <<<<<<<<<<<<<< + * filename = filename[:-5] + * filename += datetime.utcnow().strftime('%Y-%m-%d-%H:%M:%S.%f') + '.json' + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":330 + * filename += self.model_name + '_' + 'iterate' + '.json' + * + * if not overwrite: # <<<<<<<<<<<<<< + * # append timestamp + * if os.path.isfile(filename): + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":337 + * + * # get iterate: + * solution = dict() # <<<<<<<<<<<<<< + * + * lN = len(str(self.N+1)) + */ + __pyx_t_3 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 337, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_v_solution = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":339 + * solution = dict() + * + * lN = len(str(self.N+1)) # <<<<<<<<<<<<<< + * for i in range(self.N+1): + * i_string = f'{i:0{lN}d}' + */ + __pyx_t_3 = __Pyx_PyInt_From_long((__pyx_v_self->N + 1)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 339, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_7 = __Pyx_PyObject_Str(__pyx_t_3); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 339, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_8 = PyObject_Length(__pyx_t_7); if (unlikely(__pyx_t_8 == ((Py_ssize_t)-1))) __PYX_ERR(0, 339, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __pyx_v_lN = __pyx_t_8; + + /* "acados_template/acados_ocp_solver_pyx.pyx":340 + * + * lN = len(str(self.N+1)) + * for i in range(self.N+1): # <<<<<<<<<<<<<< + * i_string = f'{i:0{lN}d}' + * solution['x_'+i_string] = self.get(i,'x') + */ + __pyx_t_9 = (__pyx_v_self->N + 1); + __pyx_t_10 = __pyx_t_9; + for (__pyx_t_11 = 0; __pyx_t_11 < __pyx_t_10; __pyx_t_11+=1) { + __pyx_v_i = __pyx_t_11; + + /* "acados_template/acados_ocp_solver_pyx.pyx":341 + * lN = len(str(self.N+1)) + * for i in range(self.N+1): + * i_string = f'{i:0{lN}d}' # <<<<<<<<<<<<<< + * solution['x_'+i_string] = self.get(i,'x') + * solution['u_'+i_string] = self.get(i,'u') + */ + __pyx_t_7 = __Pyx_PyInt_From_long(__pyx_v_i); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 341, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 341, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_8 = 0; + __pyx_t_12 = 127; + __Pyx_INCREF(__pyx_kp_u_0); + __pyx_t_8 += 1; + __Pyx_GIVEREF(__pyx_kp_u_0); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_kp_u_0); + __pyx_t_1 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_lN, 0, ' ', 'd'); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 341, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_8 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1); + __pyx_t_1 = 0; + __Pyx_INCREF(__pyx_n_u_d); + __pyx_t_8 += 1; + __Pyx_GIVEREF(__pyx_n_u_d); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_n_u_d); + __pyx_t_1 = __Pyx_PyUnicode_Join(__pyx_t_3, 3, __pyx_t_8, __pyx_t_12); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 341, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PyObject_Format(__pyx_t_7, __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 341, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF_SET(__pyx_v_i_string, ((PyObject*)__pyx_t_3)); + __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":342 + * for i in range(self.N+1): + * i_string = f'{i:0{lN}d}' + * solution['x_'+i_string] = self.get(i,'x') # <<<<<<<<<<<<<< + * solution['u_'+i_string] = self.get(i,'u') + * solution['z_'+i_string] = self.get(i,'z') + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 342, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = __Pyx_PyInt_From_long(__pyx_v_i); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 342, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_t_7, __pyx_n_u_x}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 342, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyUnicode_Concat(__pyx_n_u_x_2, __pyx_v_i_string); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 342, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_3) < 0))) __PYX_ERR(0, 342, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":343 + * i_string = f'{i:0{lN}d}' + * solution['x_'+i_string] = self.get(i,'x') + * solution['u_'+i_string] = self.get(i,'u') # <<<<<<<<<<<<<< + * solution['z_'+i_string] = self.get(i,'z') + * solution['lam_'+i_string] = self.get(i,'lam') + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 343, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = __Pyx_PyInt_From_long(__pyx_v_i); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 343, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_t_7, __pyx_n_u_u}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 343, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyUnicode_Concat(__pyx_n_u_u_2, __pyx_v_i_string); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 343, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_3) < 0))) __PYX_ERR(0, 343, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":344 + * solution['x_'+i_string] = self.get(i,'x') + * solution['u_'+i_string] = self.get(i,'u') + * solution['z_'+i_string] = self.get(i,'z') # <<<<<<<<<<<<<< + * solution['lam_'+i_string] = self.get(i,'lam') + * solution['t_'+i_string] = self.get(i, 't') + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 344, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = __Pyx_PyInt_From_long(__pyx_v_i); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 344, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_t_7, __pyx_n_u_z}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 344, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyUnicode_Concat(__pyx_n_u_z_2, __pyx_v_i_string); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 344, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_3) < 0))) __PYX_ERR(0, 344, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":345 + * solution['u_'+i_string] = self.get(i,'u') + * solution['z_'+i_string] = self.get(i,'z') + * solution['lam_'+i_string] = self.get(i,'lam') # <<<<<<<<<<<<<< + * solution['t_'+i_string] = self.get(i, 't') + * solution['sl_'+i_string] = self.get(i, 'sl') + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 345, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = __Pyx_PyInt_From_long(__pyx_v_i); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 345, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_t_7, __pyx_n_u_lam}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 345, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyUnicode_Concat(__pyx_n_u_lam_2, __pyx_v_i_string); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 345, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_3) < 0))) __PYX_ERR(0, 345, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":346 + * solution['z_'+i_string] = self.get(i,'z') + * solution['lam_'+i_string] = self.get(i,'lam') + * solution['t_'+i_string] = self.get(i, 't') # <<<<<<<<<<<<<< + * solution['sl_'+i_string] = self.get(i, 'sl') + * solution['su_'+i_string] = self.get(i, 'su') + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 346, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = __Pyx_PyInt_From_long(__pyx_v_i); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 346, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_t_7, __pyx_n_u_t}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 346, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyUnicode_Concat(__pyx_n_u_t_2, __pyx_v_i_string); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 346, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_3) < 0))) __PYX_ERR(0, 346, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":347 + * solution['lam_'+i_string] = self.get(i,'lam') + * solution['t_'+i_string] = self.get(i, 't') + * solution['sl_'+i_string] = self.get(i, 'sl') # <<<<<<<<<<<<<< + * solution['su_'+i_string] = self.get(i, 'su') + * if i < self.N: + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 347, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = __Pyx_PyInt_From_long(__pyx_v_i); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 347, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_t_7, __pyx_n_u_sl}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 347, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyUnicode_Concat(__pyx_n_u_sl_2, __pyx_v_i_string); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 347, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_3) < 0))) __PYX_ERR(0, 347, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":348 + * solution['t_'+i_string] = self.get(i, 't') + * solution['sl_'+i_string] = self.get(i, 'sl') + * solution['su_'+i_string] = self.get(i, 'su') # <<<<<<<<<<<<<< + * if i < self.N: + * solution['pi_'+i_string] = self.get(i,'pi') + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 348, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = __Pyx_PyInt_From_long(__pyx_v_i); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 348, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_t_7, __pyx_n_u_su}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 348, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyUnicode_Concat(__pyx_n_u_su_2, __pyx_v_i_string); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 348, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_3) < 0))) __PYX_ERR(0, 348, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":349 + * solution['sl_'+i_string] = self.get(i, 'sl') + * solution['su_'+i_string] = self.get(i, 'su') + * if i < self.N: # <<<<<<<<<<<<<< + * solution['pi_'+i_string] = self.get(i,'pi') + * + */ + __pyx_t_4 = (__pyx_v_i < __pyx_v_self->N); + if (__pyx_t_4) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":350 + * solution['su_'+i_string] = self.get(i, 'su') + * if i < self.N: + * solution['pi_'+i_string] = self.get(i,'pi') # <<<<<<<<<<<<<< + * + * for k in list(solution.keys()): + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 350, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = __Pyx_PyInt_From_long(__pyx_v_i); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 350, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_t_7, __pyx_n_u_pi}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 350, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyUnicode_Concat(__pyx_n_u_pi_2, __pyx_v_i_string); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 350, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_3) < 0))) __PYX_ERR(0, 350, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":349 + * solution['sl_'+i_string] = self.get(i, 'sl') + * solution['su_'+i_string] = self.get(i, 'su') + * if i < self.N: # <<<<<<<<<<<<<< + * solution['pi_'+i_string] = self.get(i,'pi') + * + */ + } + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":352 + * solution['pi_'+i_string] = self.get(i,'pi') + * + * for k in list(solution.keys()): # <<<<<<<<<<<<<< + * if len(solution[k]) == 0: + * del solution[k] + */ + __pyx_t_3 = __Pyx_PyDict_Keys(__pyx_v_solution); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 352, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = __Pyx_PySequence_ListKeepNew(__pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 352, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __pyx_t_1; __Pyx_INCREF(__pyx_t_3); + __pyx_t_8 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + for (;;) { + { + Py_ssize_t __pyx_temp = __Pyx_PyList_GET_SIZE(__pyx_t_3); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 352, __pyx_L1_error) + #endif + if (__pyx_t_8 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_1 = PyList_GET_ITEM(__pyx_t_3, __pyx_t_8); __Pyx_INCREF(__pyx_t_1); __pyx_t_8++; if (unlikely((0 < 0))) __PYX_ERR(0, 352, __pyx_L1_error) + #else + __pyx_t_1 = __Pyx_PySequence_ITEM(__pyx_t_3, __pyx_t_8); __pyx_t_8++; if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 352, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + #endif + __Pyx_XDECREF_SET(__pyx_v_k, __pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":353 + * + * for k in list(solution.keys()): + * if len(solution[k]) == 0: # <<<<<<<<<<<<<< + * del solution[k] + * + */ + __pyx_t_1 = __Pyx_PyDict_GetItem(__pyx_v_solution, __pyx_v_k); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 353, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_13 = PyObject_Length(__pyx_t_1); if (unlikely(__pyx_t_13 == ((Py_ssize_t)-1))) __PYX_ERR(0, 353, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_4 = (__pyx_t_13 == 0); + if (__pyx_t_4) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":354 + * for k in list(solution.keys()): + * if len(solution[k]) == 0: + * del solution[k] # <<<<<<<<<<<<<< + * + * # save + */ + if (unlikely((PyDict_DelItem(__pyx_v_solution, __pyx_v_k) < 0))) __PYX_ERR(0, 354, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":353 + * + * for k in list(solution.keys()): + * if len(solution[k]) == 0: # <<<<<<<<<<<<<< + * del solution[k] + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":352 + * solution['pi_'+i_string] = self.get(i,'pi') + * + * for k in list(solution.keys()): # <<<<<<<<<<<<<< + * if len(solution[k]) == 0: + * del solution[k] + */ + } + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":357 + * + * # save + * with open(filename, 'w') as f: # <<<<<<<<<<<<<< + * json.dump(solution, f, default=lambda x: x.tolist(), indent=4, sort_keys=True) + * print("stored current iterate in ", os.path.join(os.getcwd(), filename)) + */ + /*with:*/ { + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 357, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_v_filename); + __Pyx_GIVEREF(__pyx_v_filename); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_v_filename)) __PYX_ERR(0, 357, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_w); + __Pyx_GIVEREF(__pyx_n_u_w); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_n_u_w)) __PYX_ERR(0, 357, __pyx_L1_error); + __pyx_t_1 = __Pyx_PyObject_Call(__pyx_builtin_open, __pyx_t_3, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 357, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_14 = __Pyx_PyObject_LookupSpecial(__pyx_t_1, __pyx_n_s_exit); if (unlikely(!__pyx_t_14)) __PYX_ERR(0, 357, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_14); + __pyx_t_7 = __Pyx_PyObject_LookupSpecial(__pyx_t_1, __pyx_n_s_enter); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 357, __pyx_L13_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_7))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_7); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_7); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_7, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_5, NULL}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_7, __pyx_callargs+1-__pyx_t_6, 0+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 357, __pyx_L13_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + } + __pyx_t_7 = __pyx_t_3; + __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + /*try:*/ { + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_15, &__pyx_t_16, &__pyx_t_17); + __Pyx_XGOTREF(__pyx_t_15); + __Pyx_XGOTREF(__pyx_t_16); + __Pyx_XGOTREF(__pyx_t_17); + /*try:*/ { + __pyx_v_f = __pyx_t_7; + __pyx_t_7 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":358 + * # save + * with open(filename, 'w') as f: + * json.dump(solution, f, default=lambda x: x.tolist(), indent=4, sort_keys=True) # <<<<<<<<<<<<<< + * print("stored current iterate in ", os.path.join(os.getcwd(), filename)) + * + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_v_json, __pyx_n_s_dump); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 358, __pyx_L17_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_1 = PyTuple_New(2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 358, __pyx_L17_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v_solution); + __Pyx_GIVEREF(__pyx_v_solution); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v_solution)) __PYX_ERR(0, 358, __pyx_L17_error); + __Pyx_INCREF(__pyx_v_f); + __Pyx_GIVEREF(__pyx_v_f); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_v_f)) __PYX_ERR(0, 358, __pyx_L17_error); + __pyx_t_3 = __Pyx_PyDict_NewPresized(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 358, __pyx_L17_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13store_iterate_lambda, 0, __pyx_n_s_store_iterate_locals_lambda, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, NULL); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 358, __pyx_L17_error) + __Pyx_GOTREF(__pyx_t_5); + if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_default, __pyx_t_5) < 0) __PYX_ERR(0, 358, __pyx_L17_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_indent, __pyx_int_4) < 0) __PYX_ERR(0, 358, __pyx_L17_error) + if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_sort_keys, Py_True) < 0) __PYX_ERR(0, 358, __pyx_L17_error) + __pyx_t_5 = __Pyx_PyObject_Call(__pyx_t_7, __pyx_t_1, __pyx_t_3); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 358, __pyx_L17_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":357 + * + * # save + * with open(filename, 'w') as f: # <<<<<<<<<<<<<< + * json.dump(solution, f, default=lambda x: x.tolist(), indent=4, sort_keys=True) + * print("stored current iterate in ", os.path.join(os.getcwd(), filename)) + */ + } + __Pyx_XDECREF(__pyx_t_15); __pyx_t_15 = 0; + __Pyx_XDECREF(__pyx_t_16); __pyx_t_16 = 0; + __Pyx_XDECREF(__pyx_t_17); __pyx_t_17 = 0; + goto __pyx_L22_try_end; + __pyx_L17_error:; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + /*except:*/ { + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.store_iterate", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_3, &__pyx_t_1) < 0) __PYX_ERR(0, 357, __pyx_L19_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __pyx_t_7 = PyTuple_Pack(3, __pyx_t_5, __pyx_t_3, __pyx_t_1); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 357, __pyx_L19_except_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_18 = __Pyx_PyObject_Call(__pyx_t_14, __pyx_t_7, NULL); + __Pyx_DECREF(__pyx_t_14); __pyx_t_14 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_18)) __PYX_ERR(0, 357, __pyx_L19_except_error) + __Pyx_GOTREF(__pyx_t_18); + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_t_18); + __Pyx_DECREF(__pyx_t_18); __pyx_t_18 = 0; + if (__pyx_t_4 < 0) __PYX_ERR(0, 357, __pyx_L19_except_error) + __pyx_t_2 = (!__pyx_t_4); + if (unlikely(__pyx_t_2)) { + __Pyx_GIVEREF(__pyx_t_5); + __Pyx_GIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_ErrRestoreWithState(__pyx_t_5, __pyx_t_3, __pyx_t_1); + __pyx_t_5 = 0; __pyx_t_3 = 0; __pyx_t_1 = 0; + __PYX_ERR(0, 357, __pyx_L19_except_error) + } + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + goto __pyx_L18_exception_handled; + } + __pyx_L19_except_error:; + __Pyx_XGIVEREF(__pyx_t_15); + __Pyx_XGIVEREF(__pyx_t_16); + __Pyx_XGIVEREF(__pyx_t_17); + __Pyx_ExceptionReset(__pyx_t_15, __pyx_t_16, __pyx_t_17); + goto __pyx_L1_error; + __pyx_L18_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_15); + __Pyx_XGIVEREF(__pyx_t_16); + __Pyx_XGIVEREF(__pyx_t_17); + __Pyx_ExceptionReset(__pyx_t_15, __pyx_t_16, __pyx_t_17); + __pyx_L22_try_end:; + } + } + /*finally:*/ { + /*normal exit:*/{ + if (__pyx_t_14) { + __pyx_t_17 = __Pyx_PyObject_Call(__pyx_t_14, __pyx_tuple__19, NULL); + __Pyx_DECREF(__pyx_t_14); __pyx_t_14 = 0; + if (unlikely(!__pyx_t_17)) __PYX_ERR(0, 357, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_17); + __Pyx_DECREF(__pyx_t_17); __pyx_t_17 = 0; + } + goto __pyx_L16; + } + __pyx_L16:; + } + goto __pyx_L26; + __pyx_L13_error:; + __Pyx_DECREF(__pyx_t_14); __pyx_t_14 = 0; + goto __pyx_L1_error; + __pyx_L26:; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":359 + * with open(filename, 'w') as f: + * json.dump(solution, f, default=lambda x: x.tolist(), indent=4, sort_keys=True) + * print("stored current iterate in ", os.path.join(os.getcwd(), filename)) # <<<<<<<<<<<<<< + * + * + */ + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_os); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 359, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_path); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 359, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_join); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 359, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_GetModuleGlobalName(__pyx_t_7, __pyx_n_s_os); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 359, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_19 = __Pyx_PyObject_GetAttrStr(__pyx_t_7, __pyx_n_s_getcwd); if (unlikely(!__pyx_t_19)) __PYX_ERR(0, 359, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_19); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __pyx_t_7 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (unlikely(PyMethod_Check(__pyx_t_19))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_19); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_19); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_19, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_7, NULL}; + __pyx_t_5 = __Pyx_PyObject_FastCall(__pyx_t_19, __pyx_callargs+1-__pyx_t_6, 0+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 359, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_19); __pyx_t_19 = 0; + } + __pyx_t_19 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_19 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_19)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_19); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_19, __pyx_t_5, __pyx_v_filename}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_19); __pyx_t_19 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 359, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 359, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_kp_u_stored_current_iterate_in); + __Pyx_GIVEREF(__pyx_kp_u_stored_current_iterate_in); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_kp_u_stored_current_iterate_in)) __PYX_ERR(0, 359, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1)) __PYX_ERR(0, 359, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_Call(__pyx_builtin_print, __pyx_t_3, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 359, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":319 + * + * + * def store_iterate(self, filename='', overwrite=False): # <<<<<<<<<<<<<< + * """ + * Stores the current iterate of the ocp solver in a json file. + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_19); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.store_iterate", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_json); + __Pyx_XDECREF(__pyx_v_solution); + __Pyx_XDECREF(__pyx_v_i_string); + __Pyx_XDECREF(__pyx_v_k); + __Pyx_XDECREF(__pyx_v_f); + __Pyx_XDECREF(__pyx_v_filename); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":362 + * + * + * def load_iterate(self, filename): # <<<<<<<<<<<<<< + * """ + * Loads the iterate stored in json file with filename into the ocp solver. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25load_iterate(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_24load_iterate, "\n Loads the iterate stored in json file with filename into the ocp solver.\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25load_iterate = {"load_iterate", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25load_iterate, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_24load_iterate}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25load_iterate(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_filename = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("load_iterate (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_filename,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_filename)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 362, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "load_iterate") < 0)) __PYX_ERR(0, 362, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_filename = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("load_iterate", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 362, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.load_iterate", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_24load_iterate(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_filename); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_24load_iterate(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_filename) { + PyObject *__pyx_v_json = NULL; + PyObject *__pyx_v_f = NULL; + PyObject *__pyx_v_solution = NULL; + PyObject *__pyx_v_key = NULL; + PyObject *__pyx_v_field = NULL; + PyObject *__pyx_v_stage = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_t_5; + int __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + PyObject *__pyx_t_9 = NULL; + PyObject *__pyx_t_10 = NULL; + PyObject *__pyx_t_11 = NULL; + PyObject *__pyx_t_12 = NULL; + PyObject *__pyx_t_13 = NULL; + Py_ssize_t __pyx_t_14; + Py_ssize_t __pyx_t_15; + int __pyx_t_16; + PyObject *(*__pyx_t_17)(PyObject *); + PyObject *__pyx_t_18 = NULL; + PyObject *__pyx_t_19 = NULL; + PyObject *__pyx_t_20 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("load_iterate", 1); + + /* "acados_template/acados_ocp_solver_pyx.pyx":366 + * Loads the iterate stored in json file with filename into the ocp solver. + * """ + * import json # <<<<<<<<<<<<<< + * if not os.path.isfile(filename): + * raise Exception('load_iterate: failed, file does not exist: ' + os.path.join(os.getcwd(), filename)) + */ + __pyx_t_1 = __Pyx_ImportDottedModule(__pyx_n_s_json, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 366, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_json = __pyx_t_1; + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":367 + * """ + * import json + * if not os.path.isfile(filename): # <<<<<<<<<<<<<< + * raise Exception('load_iterate: failed, file does not exist: ' + os.path.join(os.getcwd(), filename)) + * + */ + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_os); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 367, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_path); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 367, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_isfile); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 367, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_filename}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 367, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_t_5 = __Pyx_PyObject_IsTrue(__pyx_t_1); if (unlikely((__pyx_t_5 < 0))) __PYX_ERR(0, 367, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_6 = (!__pyx_t_5); + if (unlikely(__pyx_t_6)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":368 + * import json + * if not os.path.isfile(filename): + * raise Exception('load_iterate: failed, file does not exist: ' + os.path.join(os.getcwd(), filename)) # <<<<<<<<<<<<<< + * + * with open(filename, 'r') as f: + */ + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_os); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 368, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_path); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 368, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_join); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 368, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_GetModuleGlobalName(__pyx_t_7, __pyx_n_s_os); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 368, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_t_7, __pyx_n_s_getcwd); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 368, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __pyx_t_7 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (unlikely(PyMethod_Check(__pyx_t_8))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_8); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_8); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_8, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_7, NULL}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_8, __pyx_callargs+1-__pyx_t_4, 0+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 368, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } + __pyx_t_8 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_8 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_8)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_8); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_8, __pyx_t_3, __pyx_v_filename}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 2+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 368, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_t_2 = PyNumber_Add(__pyx_kp_u_load_iterate_failed_file_does_no, __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 368, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 368, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 368, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":367 + * """ + * import json + * if not os.path.isfile(filename): # <<<<<<<<<<<<<< + * raise Exception('load_iterate: failed, file does not exist: ' + os.path.join(os.getcwd(), filename)) + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":370 + * raise Exception('load_iterate: failed, file does not exist: ' + os.path.join(os.getcwd(), filename)) + * + * with open(filename, 'r') as f: # <<<<<<<<<<<<<< + * solution = json.load(f) + * + */ + /*with:*/ { + __pyx_t_1 = PyTuple_New(2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 370, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v_filename); + __Pyx_GIVEREF(__pyx_v_filename); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v_filename)) __PYX_ERR(0, 370, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_r); + __Pyx_GIVEREF(__pyx_n_u_r); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_n_u_r)) __PYX_ERR(0, 370, __pyx_L1_error); + __pyx_t_2 = __Pyx_PyObject_Call(__pyx_builtin_open, __pyx_t_1, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 370, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_9 = __Pyx_PyObject_LookupSpecial(__pyx_t_2, __pyx_n_s_exit); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 370, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __pyx_t_3 = __Pyx_PyObject_LookupSpecial(__pyx_t_2, __pyx_n_s_enter); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 370, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_8 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_8 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_8)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_8); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_8, NULL}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_4, 0+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 370, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_t_3 = __pyx_t_1; + __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + /*try:*/ { + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_10, &__pyx_t_11, &__pyx_t_12); + __Pyx_XGOTREF(__pyx_t_10); + __Pyx_XGOTREF(__pyx_t_11); + __Pyx_XGOTREF(__pyx_t_12); + /*try:*/ { + __pyx_v_f = __pyx_t_3; + __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":371 + * + * with open(filename, 'r') as f: + * solution = json.load(f) # <<<<<<<<<<<<<< + * + * for key in solution.keys(): + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_json, __pyx_n_s_load); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 371, __pyx_L8_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_1 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_1)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_1); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_1, __pyx_v_f}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 371, __pyx_L8_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_v_solution = __pyx_t_3; + __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":370 + * raise Exception('load_iterate: failed, file does not exist: ' + os.path.join(os.getcwd(), filename)) + * + * with open(filename, 'r') as f: # <<<<<<<<<<<<<< + * solution = json.load(f) + * + */ + } + __Pyx_XDECREF(__pyx_t_10); __pyx_t_10 = 0; + __Pyx_XDECREF(__pyx_t_11); __pyx_t_11 = 0; + __Pyx_XDECREF(__pyx_t_12); __pyx_t_12 = 0; + goto __pyx_L13_try_end; + __pyx_L8_error:; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + /*except:*/ { + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.load_iterate", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_3, &__pyx_t_2, &__pyx_t_1) < 0) __PYX_ERR(0, 370, __pyx_L10_except_error) + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_1); + __pyx_t_8 = PyTuple_Pack(3, __pyx_t_3, __pyx_t_2, __pyx_t_1); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 370, __pyx_L10_except_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_13 = __Pyx_PyObject_Call(__pyx_t_9, __pyx_t_8, NULL); + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + if (unlikely(!__pyx_t_13)) __PYX_ERR(0, 370, __pyx_L10_except_error) + __Pyx_GOTREF(__pyx_t_13); + __pyx_t_6 = __Pyx_PyObject_IsTrue(__pyx_t_13); + __Pyx_DECREF(__pyx_t_13); __pyx_t_13 = 0; + if (__pyx_t_6 < 0) __PYX_ERR(0, 370, __pyx_L10_except_error) + __pyx_t_5 = (!__pyx_t_6); + if (unlikely(__pyx_t_5)) { + __Pyx_GIVEREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_ErrRestoreWithState(__pyx_t_3, __pyx_t_2, __pyx_t_1); + __pyx_t_3 = 0; __pyx_t_2 = 0; __pyx_t_1 = 0; + __PYX_ERR(0, 370, __pyx_L10_except_error) + } + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + goto __pyx_L9_exception_handled; + } + __pyx_L10_except_error:; + __Pyx_XGIVEREF(__pyx_t_10); + __Pyx_XGIVEREF(__pyx_t_11); + __Pyx_XGIVEREF(__pyx_t_12); + __Pyx_ExceptionReset(__pyx_t_10, __pyx_t_11, __pyx_t_12); + goto __pyx_L1_error; + __pyx_L9_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_10); + __Pyx_XGIVEREF(__pyx_t_11); + __Pyx_XGIVEREF(__pyx_t_12); + __Pyx_ExceptionReset(__pyx_t_10, __pyx_t_11, __pyx_t_12); + __pyx_L13_try_end:; + } + } + /*finally:*/ { + /*normal exit:*/{ + if (__pyx_t_9) { + __pyx_t_12 = __Pyx_PyObject_Call(__pyx_t_9, __pyx_tuple__19, NULL); + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + if (unlikely(!__pyx_t_12)) __PYX_ERR(0, 370, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_12); + __Pyx_DECREF(__pyx_t_12); __pyx_t_12 = 0; + } + goto __pyx_L7; + } + __pyx_L7:; + } + goto __pyx_L17; + __pyx_L4_error:; + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + goto __pyx_L1_error; + __pyx_L17:; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":373 + * solution = json.load(f) + * + * for key in solution.keys(): # <<<<<<<<<<<<<< + * (field, stage) = key.split('_') + * self.set(int(stage), field, np.array(solution[key])) + */ + __pyx_t_14 = 0; + if (unlikely(!__pyx_v_solution)) { __Pyx_RaiseUnboundLocalError("solution"); __PYX_ERR(0, 373, __pyx_L1_error) } + if (unlikely(__pyx_v_solution == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "keys"); + __PYX_ERR(0, 373, __pyx_L1_error) + } + __pyx_t_2 = __Pyx_dict_iterator(__pyx_v_solution, 0, __pyx_n_s_keys, (&__pyx_t_15), (&__pyx_t_4)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 373, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_1); + __pyx_t_1 = __pyx_t_2; + __pyx_t_2 = 0; + while (1) { + __pyx_t_16 = __Pyx_dict_iter_next(__pyx_t_1, __pyx_t_15, &__pyx_t_14, &__pyx_t_2, NULL, NULL, __pyx_t_4); + if (unlikely(__pyx_t_16 == 0)) break; + if (unlikely(__pyx_t_16 == -1)) __PYX_ERR(0, 373, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_XDECREF_SET(__pyx_v_key, __pyx_t_2); + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":374 + * + * for key in solution.keys(): + * (field, stage) = key.split('_') # <<<<<<<<<<<<<< + * self.set(int(stage), field, np.array(solution[key])) + * + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_v_key, __pyx_n_s_split); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 374, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_8 = NULL; + __pyx_t_16 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_8 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_8)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_8); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_16 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_8, __pyx_n_u__17}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_16, 1+__pyx_t_16); + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 374, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + if ((likely(PyTuple_CheckExact(__pyx_t_2))) || (PyList_CheckExact(__pyx_t_2))) { + PyObject* sequence = __pyx_t_2; + Py_ssize_t size = __Pyx_PySequence_SIZE(sequence); + if (unlikely(size != 2)) { + if (size > 2) __Pyx_RaiseTooManyValuesError(2); + else if (size >= 0) __Pyx_RaiseNeedMoreValuesError(size); + __PYX_ERR(0, 374, __pyx_L1_error) + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + if (likely(PyTuple_CheckExact(sequence))) { + __pyx_t_3 = PyTuple_GET_ITEM(sequence, 0); + __pyx_t_8 = PyTuple_GET_ITEM(sequence, 1); + } else { + __pyx_t_3 = PyList_GET_ITEM(sequence, 0); + __pyx_t_8 = PyList_GET_ITEM(sequence, 1); + } + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(__pyx_t_8); + #else + __pyx_t_3 = PySequence_ITEM(sequence, 0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 374, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_8 = PySequence_ITEM(sequence, 1); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 374, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + #endif + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } else { + Py_ssize_t index = -1; + __pyx_t_7 = PyObject_GetIter(__pyx_t_2); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 374, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_17 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_7); + index = 0; __pyx_t_3 = __pyx_t_17(__pyx_t_7); if (unlikely(!__pyx_t_3)) goto __pyx_L20_unpacking_failed; + __Pyx_GOTREF(__pyx_t_3); + index = 1; __pyx_t_8 = __pyx_t_17(__pyx_t_7); if (unlikely(!__pyx_t_8)) goto __pyx_L20_unpacking_failed; + __Pyx_GOTREF(__pyx_t_8); + if (__Pyx_IternextUnpackEndCheck(__pyx_t_17(__pyx_t_7), 2) < 0) __PYX_ERR(0, 374, __pyx_L1_error) + __pyx_t_17 = NULL; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + goto __pyx_L21_unpacking_done; + __pyx_L20_unpacking_failed:; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __pyx_t_17 = NULL; + if (__Pyx_IterFinish() == 0) __Pyx_RaiseNeedMoreValuesError(index); + __PYX_ERR(0, 374, __pyx_L1_error) + __pyx_L21_unpacking_done:; + } + __Pyx_XDECREF_SET(__pyx_v_field, __pyx_t_3); + __pyx_t_3 = 0; + __Pyx_XDECREF_SET(__pyx_v_stage, __pyx_t_8); + __pyx_t_8 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":375 + * for key in solution.keys(): + * (field, stage) = key.split('_') + * self.set(int(stage), field, np.array(solution[key])) # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_set); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 375, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_3 = __Pyx_PyNumber_Int(__pyx_v_stage); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 375, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GetModuleGlobalName(__pyx_t_18, __pyx_n_s_np); if (unlikely(!__pyx_t_18)) __PYX_ERR(0, 375, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_18); + __pyx_t_19 = __Pyx_PyObject_GetAttrStr(__pyx_t_18, __pyx_n_s_array); if (unlikely(!__pyx_t_19)) __PYX_ERR(0, 375, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_19); + __Pyx_DECREF(__pyx_t_18); __pyx_t_18 = 0; + if (unlikely(!__pyx_v_solution)) { __Pyx_RaiseUnboundLocalError("solution"); __PYX_ERR(0, 375, __pyx_L1_error) } + __pyx_t_18 = __Pyx_PyObject_GetItem(__pyx_v_solution, __pyx_v_key); if (unlikely(!__pyx_t_18)) __PYX_ERR(0, 375, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_18); + __pyx_t_20 = NULL; + __pyx_t_16 = 0; + #if CYTHON_UNPACK_METHODS + if (unlikely(PyMethod_Check(__pyx_t_19))) { + __pyx_t_20 = PyMethod_GET_SELF(__pyx_t_19); + if (likely(__pyx_t_20)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_19); + __Pyx_INCREF(__pyx_t_20); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_19, function); + __pyx_t_16 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_20, __pyx_t_18}; + __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_19, __pyx_callargs+1-__pyx_t_16, 1+__pyx_t_16); + __Pyx_XDECREF(__pyx_t_20); __pyx_t_20 = 0; + __Pyx_DECREF(__pyx_t_18); __pyx_t_18 = 0; + if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 375, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_19); __pyx_t_19 = 0; + } + __pyx_t_19 = NULL; + __pyx_t_16 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_8))) { + __pyx_t_19 = PyMethod_GET_SELF(__pyx_t_8); + if (likely(__pyx_t_19)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_8); + __Pyx_INCREF(__pyx_t_19); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_8, function); + __pyx_t_16 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[4] = {__pyx_t_19, __pyx_t_3, __pyx_v_field, __pyx_t_7}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_8, __pyx_callargs+1-__pyx_t_16, 3+__pyx_t_16); + __Pyx_XDECREF(__pyx_t_19); __pyx_t_19 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 375, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":362 + * + * + * def load_iterate(self, filename): # <<<<<<<<<<<<<< + * """ + * Loads the iterate stored in json file with filename into the ocp solver. + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_XDECREF(__pyx_t_18); + __Pyx_XDECREF(__pyx_t_19); + __Pyx_XDECREF(__pyx_t_20); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.load_iterate", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_json); + __Pyx_XDECREF(__pyx_v_f); + __Pyx_XDECREF(__pyx_v_solution); + __Pyx_XDECREF(__pyx_v_key); + __Pyx_XDECREF(__pyx_v_field); + __Pyx_XDECREF(__pyx_v_stage); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":378 + * + * + * def get_stats(self, field_): # <<<<<<<<<<<<<< + * """ + * Get the information of the last solver call. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27get_stats(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_26get_stats, "\n Get the information of the last solver call.\n\n :param field: string in ['statistics', 'time_tot', 'time_lin', 'time_sim', 'time_sim_ad', 'time_sim_la', 'time_qp', 'time_qp_solver_call', 'time_reg', 'sqp_iter']\n Available fileds:\n - time_tot: total CPU time previous call\n - time_lin: CPU time for linearization\n - time_sim: CPU time for integrator\n - time_sim_ad: CPU time for integrator contribution of external function calls\n - time_sim_la: CPU time for integrator contribution of linear algebra\n - time_qp: CPU time qp solution\n - time_qp_solver_call: CPU time inside qp solver (without converting the QP)\n - time_qp_xcond: time_glob: CPU time globalization\n - time_solution_sensitivities: CPU time for previous call to eval_param_sens\n - time_reg: CPU time regularization\n - sqp_iter: number of SQP iterations\n - qp_iter: vector of QP iterations for last SQP call\n - statistics: table with info about last iteration\n - stat_m: number of rows in statistics matrix\n - stat_n: number of columns in statistics matrix\n - residuals: residuals of last iterate\n - alpha: step sizes of SQP iterations\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27get_stats = {"get_stats", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27get_stats, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_26get_stats}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27get_stats(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_field_ = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("get_stats (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_field_2,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field_2)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 378, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "get_stats") < 0)) __PYX_ERR(0, 378, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_field_ = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("get_stats", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 378, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.get_stats", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_26get_stats(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_field_); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_26get_stats(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field_) { + PyObject *__pyx_v_double_fields = NULL; + CYTHON_UNUSED PyObject *__pyx_v_fields = NULL; + PyObject *__pyx_v_field = NULL; + PyObject *__pyx_v_sqp_iter = NULL; + PyObject *__pyx_v_stat_m = NULL; + PyObject *__pyx_v_stat_n = NULL; + PyObject *__pyx_v_min_size = NULL; + PyObject *__pyx_v_full_stats = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_t_5; + int __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_stats", 1); + + /* "acados_template/acados_ocp_solver_pyx.pyx":403 + * """ + * + * double_fields = ['time_tot', # <<<<<<<<<<<<<< + * 'time_lin', + * 'time_sim', + */ + __pyx_t_1 = PyList_New(11); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 403, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_u_time_tot); + __Pyx_GIVEREF(__pyx_n_u_time_tot); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_u_time_tot)) __PYX_ERR(0, 403, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_time_lin); + __Pyx_GIVEREF(__pyx_n_u_time_lin); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 1, __pyx_n_u_time_lin)) __PYX_ERR(0, 403, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_time_sim); + __Pyx_GIVEREF(__pyx_n_u_time_sim); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 2, __pyx_n_u_time_sim)) __PYX_ERR(0, 403, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_time_sim_ad); + __Pyx_GIVEREF(__pyx_n_u_time_sim_ad); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 3, __pyx_n_u_time_sim_ad)) __PYX_ERR(0, 403, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_time_sim_la); + __Pyx_GIVEREF(__pyx_n_u_time_sim_la); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 4, __pyx_n_u_time_sim_la)) __PYX_ERR(0, 403, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_time_qp); + __Pyx_GIVEREF(__pyx_n_u_time_qp); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 5, __pyx_n_u_time_qp)) __PYX_ERR(0, 403, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_time_qp_solver_call); + __Pyx_GIVEREF(__pyx_n_u_time_qp_solver_call); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 6, __pyx_n_u_time_qp_solver_call)) __PYX_ERR(0, 403, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_time_qp_xcond); + __Pyx_GIVEREF(__pyx_n_u_time_qp_xcond); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 7, __pyx_n_u_time_qp_xcond)) __PYX_ERR(0, 403, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_time_glob); + __Pyx_GIVEREF(__pyx_n_u_time_glob); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 8, __pyx_n_u_time_glob)) __PYX_ERR(0, 403, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_time_solution_sensitivities); + __Pyx_GIVEREF(__pyx_n_u_time_solution_sensitivities); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 9, __pyx_n_u_time_solution_sensitivities)) __PYX_ERR(0, 403, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_time_reg); + __Pyx_GIVEREF(__pyx_n_u_time_reg); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 10, __pyx_n_u_time_reg)) __PYX_ERR(0, 403, __pyx_L1_error); + __pyx_v_double_fields = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":415 + * 'time_reg' + * ] + * fields = double_fields + [ # <<<<<<<<<<<<<< + * 'sqp_iter', + * 'qp_iter', + */ + __pyx_t_1 = PyList_New(7); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 415, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_u_sqp_iter); + __Pyx_GIVEREF(__pyx_n_u_sqp_iter); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_u_sqp_iter)) __PYX_ERR(0, 415, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_qp_iter); + __Pyx_GIVEREF(__pyx_n_u_qp_iter); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 1, __pyx_n_u_qp_iter)) __PYX_ERR(0, 415, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_statistics); + __Pyx_GIVEREF(__pyx_n_u_statistics); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 2, __pyx_n_u_statistics)) __PYX_ERR(0, 415, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_stat_m); + __Pyx_GIVEREF(__pyx_n_u_stat_m); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 3, __pyx_n_u_stat_m)) __PYX_ERR(0, 415, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_stat_n); + __Pyx_GIVEREF(__pyx_n_u_stat_n); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 4, __pyx_n_u_stat_n)) __PYX_ERR(0, 415, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_residuals); + __Pyx_GIVEREF(__pyx_n_u_residuals); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 5, __pyx_n_u_residuals)) __PYX_ERR(0, 415, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_alpha); + __Pyx_GIVEREF(__pyx_n_u_alpha); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 6, __pyx_n_u_alpha)) __PYX_ERR(0, 415, __pyx_L1_error); + __pyx_t_2 = PyNumber_Add(__pyx_v_double_fields, __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 415, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_fields = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":424 + * 'alpha', + * ] + * field = field_.encode('utf-8') # <<<<<<<<<<<<<< + * + * if field_ in ['sqp_iter', 'stat_m', 'stat_n']: + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_field_, __pyx_n_s_encode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 424, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_kp_u_utf_8}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 424, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_v_field = __pyx_t_2; + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":426 + * field = field_.encode('utf-8') + * + * if field_ in ['sqp_iter', 'stat_m', 'stat_n']: # <<<<<<<<<<<<<< + * return self.__get_stat_int(field) + * + */ + __Pyx_INCREF(__pyx_v_field_); + __pyx_t_2 = __pyx_v_field_; + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_t_2, __pyx_n_u_sqp_iter, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 426, __pyx_L1_error) + if (!__pyx_t_6) { + } else { + __pyx_t_5 = __pyx_t_6; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_t_2, __pyx_n_u_stat_m, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 426, __pyx_L1_error) + if (!__pyx_t_6) { + } else { + __pyx_t_5 = __pyx_t_6; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_t_2, __pyx_n_u_stat_n, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 426, __pyx_L1_error) + __pyx_t_5 = __pyx_t_6; + __pyx_L4_bool_binop_done:; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_6 = __pyx_t_5; + if (__pyx_t_6) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":427 + * + * if field_ in ['sqp_iter', 'stat_m', 'stat_n']: + * return self.__get_stat_int(field) # <<<<<<<<<<<<<< + * + * elif field_ in double_fields: + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_AcadosOcpSolverCython__get_stat); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 427, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_field}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 427, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":426 + * field = field_.encode('utf-8') + * + * if field_ in ['sqp_iter', 'stat_m', 'stat_n']: # <<<<<<<<<<<<<< + * return self.__get_stat_int(field) + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":429 + * return self.__get_stat_int(field) + * + * elif field_ in double_fields: # <<<<<<<<<<<<<< + * return self.__get_stat_double(field) + * + */ + __pyx_t_6 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_double_fields, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 429, __pyx_L1_error) + if (__pyx_t_6) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":430 + * + * elif field_ in double_fields: + * return self.__get_stat_double(field) # <<<<<<<<<<<<<< + * + * elif field_ == 'statistics': + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_AcadosOcpSolverCython__get_stat_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 430, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_field}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 430, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":429 + * return self.__get_stat_int(field) + * + * elif field_ in double_fields: # <<<<<<<<<<<<<< + * return self.__get_stat_double(field) + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":432 + * return self.__get_stat_double(field) + * + * elif field_ == 'statistics': # <<<<<<<<<<<<<< + * sqp_iter = self.get_stats("sqp_iter") + * stat_m = self.get_stats("stat_m") + */ + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_statistics, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 432, __pyx_L1_error) + if (__pyx_t_6) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":433 + * + * elif field_ == 'statistics': + * sqp_iter = self.get_stats("sqp_iter") # <<<<<<<<<<<<<< + * stat_m = self.get_stats("stat_m") + * stat_n = self.get_stats("stat_n") + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_stats); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 433, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_n_u_sqp_iter}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 433, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_v_sqp_iter = __pyx_t_2; + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":434 + * elif field_ == 'statistics': + * sqp_iter = self.get_stats("sqp_iter") + * stat_m = self.get_stats("stat_m") # <<<<<<<<<<<<<< + * stat_n = self.get_stats("stat_n") + * min_size = min([stat_m, sqp_iter+1]) + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_stats); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 434, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_n_u_stat_m}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 434, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_v_stat_m = __pyx_t_2; + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":435 + * sqp_iter = self.get_stats("sqp_iter") + * stat_m = self.get_stats("stat_m") + * stat_n = self.get_stats("stat_n") # <<<<<<<<<<<<<< + * min_size = min([stat_m, sqp_iter+1]) + * return self.__get_stat_matrix(field, stat_n+1, min_size) + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_stats); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 435, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_n_u_stat_n}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 435, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_v_stat_n = __pyx_t_2; + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":436 + * stat_m = self.get_stats("stat_m") + * stat_n = self.get_stats("stat_n") + * min_size = min([stat_m, sqp_iter+1]) # <<<<<<<<<<<<<< + * return self.__get_stat_matrix(field, stat_n+1, min_size) + * + */ + __pyx_t_2 = __Pyx_PyInt_AddObjC(__pyx_v_sqp_iter, __pyx_int_1, 1, 0, 0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 436, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_INCREF(__pyx_v_stat_m); + __pyx_t_1 = __pyx_v_stat_m; + __pyx_t_7 = PyObject_RichCompare(__pyx_t_2, __pyx_t_1, Py_LT); __Pyx_XGOTREF(__pyx_t_7); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 436, __pyx_L1_error) + __pyx_t_6 = __Pyx_PyObject_IsTrue(__pyx_t_7); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 436, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (__pyx_t_6) { + __Pyx_INCREF(__pyx_t_2); + __pyx_t_3 = __pyx_t_2; + } else { + __Pyx_INCREF(__pyx_t_1); + __pyx_t_3 = __pyx_t_1; + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __pyx_t_3; + __Pyx_INCREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_v_min_size = __pyx_t_2; + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":437 + * stat_n = self.get_stats("stat_n") + * min_size = min([stat_m, sqp_iter+1]) + * return self.__get_stat_matrix(field, stat_n+1, min_size) # <<<<<<<<<<<<<< + * + * elif field_ == 'qp_iter': + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_AcadosOcpSolverCython__get_stat_3); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 437, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = __Pyx_PyInt_AddObjC(__pyx_v_stat_n, __pyx_int_1, 1, 0, 0); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 437, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[4] = {__pyx_t_7, __pyx_v_field, __pyx_t_1, __pyx_v_min_size}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_4, 3+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 437, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":432 + * return self.__get_stat_double(field) + * + * elif field_ == 'statistics': # <<<<<<<<<<<<<< + * sqp_iter = self.get_stats("sqp_iter") + * stat_m = self.get_stats("stat_m") + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":439 + * return self.__get_stat_matrix(field, stat_n+1, min_size) + * + * elif field_ == 'qp_iter': # <<<<<<<<<<<<<< + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': + */ + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_qp_iter, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 439, __pyx_L1_error) + if (__pyx_t_6) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":440 + * + * elif field_ == 'qp_iter': + * full_stats = self.get_stats('statistics') # <<<<<<<<<<<<<< + * if self.nlp_solver_type == 'SQP': + * return full_stats[6, :] + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_stats); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 440, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_1)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_1); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_1, __pyx_n_u_statistics}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 440, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_v_full_stats = __pyx_t_2; + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":441 + * elif field_ == 'qp_iter': + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': # <<<<<<<<<<<<<< + * return full_stats[6, :] + * elif self.nlp_solver_type == 'SQP_RTI': + */ + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_self->nlp_solver_type, __pyx_n_u_SQP, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 441, __pyx_L1_error) + if (__pyx_t_6) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":442 + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': + * return full_stats[6, :] # <<<<<<<<<<<<<< + * elif self.nlp_solver_type == 'SQP_RTI': + * return full_stats[2, :] + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_v_full_stats, __pyx_tuple__20); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 442, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":441 + * elif field_ == 'qp_iter': + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': # <<<<<<<<<<<<<< + * return full_stats[6, :] + * elif self.nlp_solver_type == 'SQP_RTI': + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":443 + * if self.nlp_solver_type == 'SQP': + * return full_stats[6, :] + * elif self.nlp_solver_type == 'SQP_RTI': # <<<<<<<<<<<<<< + * return full_stats[2, :] + * + */ + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_self->nlp_solver_type, __pyx_n_u_SQP_RTI, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 443, __pyx_L1_error) + if (__pyx_t_6) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":444 + * return full_stats[6, :] + * elif self.nlp_solver_type == 'SQP_RTI': + * return full_stats[2, :] # <<<<<<<<<<<<<< + * + * elif field_ == 'alpha': + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_v_full_stats, __pyx_tuple__21); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 444, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":443 + * if self.nlp_solver_type == 'SQP': + * return full_stats[6, :] + * elif self.nlp_solver_type == 'SQP_RTI': # <<<<<<<<<<<<<< + * return full_stats[2, :] + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":439 + * return self.__get_stat_matrix(field, stat_n+1, min_size) + * + * elif field_ == 'qp_iter': # <<<<<<<<<<<<<< + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': + */ + goto __pyx_L3; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":446 + * return full_stats[2, :] + * + * elif field_ == 'alpha': # <<<<<<<<<<<<<< + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': + */ + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_alpha, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 446, __pyx_L1_error) + if (__pyx_t_6) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":447 + * + * elif field_ == 'alpha': + * full_stats = self.get_stats('statistics') # <<<<<<<<<<<<<< + * if self.nlp_solver_type == 'SQP': + * return full_stats[7, :] + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_stats); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 447, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_1)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_1); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_1, __pyx_n_u_statistics}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 447, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_v_full_stats = __pyx_t_2; + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":448 + * elif field_ == 'alpha': + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': # <<<<<<<<<<<<<< + * return full_stats[7, :] + * else: # self.nlp_solver_type == 'SQP_RTI': + */ + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_self->nlp_solver_type, __pyx_n_u_SQP, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 448, __pyx_L1_error) + if (likely(__pyx_t_6)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":449 + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': + * return full_stats[7, :] # <<<<<<<<<<<<<< + * else: # self.nlp_solver_type == 'SQP_RTI': + * raise Exception("alpha values are not available for SQP_RTI") + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_v_full_stats, __pyx_tuple__22); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 449, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":448 + * elif field_ == 'alpha': + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': # <<<<<<<<<<<<<< + * return full_stats[7, :] + * else: # self.nlp_solver_type == 'SQP_RTI': + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":451 + * return full_stats[7, :] + * else: # self.nlp_solver_type == 'SQP_RTI': + * raise Exception("alpha values are not available for SQP_RTI") # <<<<<<<<<<<<<< + * + * elif field_ == 'residuals': + */ + /*else*/ { + __pyx_t_2 = __Pyx_PyObject_Call(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_tuple__23, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 451, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 451, __pyx_L1_error) + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":446 + * return full_stats[2, :] + * + * elif field_ == 'alpha': # <<<<<<<<<<<<<< + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":453 + * raise Exception("alpha values are not available for SQP_RTI") + * + * elif field_ == 'residuals': # <<<<<<<<<<<<<< + * return self.get_residuals() + * + */ + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_residuals, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 453, __pyx_L1_error) + if (likely(__pyx_t_6)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":454 + * + * elif field_ == 'residuals': + * return self.get_residuals() # <<<<<<<<<<<<<< + * + * else: + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_residuals); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 454, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_1)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_1); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_1, NULL}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_4, 0+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 454, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":453 + * raise Exception("alpha values are not available for SQP_RTI") + * + * elif field_ == 'residuals': # <<<<<<<<<<<<<< + * return self.get_residuals() + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":457 + * + * else: + * raise NotImplementedError("TODO!") # <<<<<<<<<<<<<< + * + * + */ + /*else*/ { + __pyx_t_2 = __Pyx_PyObject_Call(__pyx_builtin_NotImplementedError, __pyx_tuple__24, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 457, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 457, __pyx_L1_error) + } + __pyx_L3:; + + /* "acados_template/acados_ocp_solver_pyx.pyx":378 + * + * + * def get_stats(self, field_): # <<<<<<<<<<<<<< + * """ + * Get the information of the last solver call. + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.get_stats", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_double_fields); + __Pyx_XDECREF(__pyx_v_fields); + __Pyx_XDECREF(__pyx_v_field); + __Pyx_XDECREF(__pyx_v_sqp_iter); + __Pyx_XDECREF(__pyx_v_stat_m); + __Pyx_XDECREF(__pyx_v_stat_n); + __Pyx_XDECREF(__pyx_v_min_size); + __Pyx_XDECREF(__pyx_v_full_stats); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":460 + * + * + * def __get_stat_int(self, field): # <<<<<<<<<<<<<< + * cdef int out + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &out) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_int(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_int = {"_AcadosOcpSolverCython__get_stat_int", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_int, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_int(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_field = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("_AcadosOcpSolverCython__get_stat_int (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_field,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 460, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "_AcadosOcpSolverCython__get_stat_int") < 0)) __PYX_ERR(0, 460, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_field = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("_AcadosOcpSolverCython__get_stat_int", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 460, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython._AcadosOcpSolverCython__get_stat_int", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_28__get_stat_int(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_field); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_28__get_stat_int(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field) { + int __pyx_v_out; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + char const *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("_AcadosOcpSolverCython__get_stat_int", 1); + + /* "acados_template/acados_ocp_solver_pyx.pyx":462 + * def __get_stat_int(self, field): + * cdef int out + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &out) # <<<<<<<<<<<<<< + * return out + * + */ + __pyx_t_1 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_1) && PyErr_Occurred())) __PYX_ERR(0, 462, __pyx_L1_error) + ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_t_1, ((void *)(&__pyx_v_out))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":463 + * cdef int out + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &out) + * return out # <<<<<<<<<<<<<< + * + * def __get_stat_double(self, field): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyInt_From_int(__pyx_v_out); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 463, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":460 + * + * + * def __get_stat_int(self, field): # <<<<<<<<<<<<<< + * cdef int out + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &out) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython._AcadosOcpSolverCython__get_stat_int", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":465 + * return out + * + * def __get_stat_double(self, field): # <<<<<<<<<<<<<< + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31_AcadosOcpSolverCython__get_stat_double(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31_AcadosOcpSolverCython__get_stat_double = {"_AcadosOcpSolverCython__get_stat_double", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31_AcadosOcpSolverCython__get_stat_double, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31_AcadosOcpSolverCython__get_stat_double(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_field = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("_AcadosOcpSolverCython__get_stat_double (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_field,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 465, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "_AcadosOcpSolverCython__get_stat_double") < 0)) __PYX_ERR(0, 465, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_field = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("_AcadosOcpSolverCython__get_stat_double", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 465, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython._AcadosOcpSolverCython__get_stat_double", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_30__get_stat_double(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_field); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_30__get_stat_double(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field) { + PyArrayObject *__pyx_v_out = 0; + __Pyx_LocalBuf_ND __pyx_pybuffernd_out; + __Pyx_Buffer __pyx_pybuffer_out; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + PyArrayObject *__pyx_t_5 = NULL; + char const *__pyx_t_6; + char *__pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("_AcadosOcpSolverCython__get_stat_double", 1); + __pyx_pybuffer_out.pybuffer.buf = NULL; + __pyx_pybuffer_out.refcount = 0; + __pyx_pybuffernd_out.data = NULL; + __pyx_pybuffernd_out.rcbuffer = &__pyx_pybuffer_out; + + /* "acados_template/acados_ocp_solver_pyx.pyx":466 + * + * def __get_stat_double(self, field): + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) + * return out + */ + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_np); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 466, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_zeros); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 466, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (unlikely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_2 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_2)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_2); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_2, __pyx_tuple__25}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 466, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + if (!(likely(((__pyx_t_1) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_1, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 466, __pyx_L1_error) + __pyx_t_5 = ((PyArrayObject *)__pyx_t_1); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_out.rcbuffer->pybuffer, (PyObject*)__pyx_t_5, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 1, 0, __pyx_stack) == -1)) { + __pyx_v_out = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_out.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 466, __pyx_L1_error) + } else {__pyx_pybuffernd_out.diminfo[0].strides = __pyx_pybuffernd_out.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_out.diminfo[0].shape = __pyx_pybuffernd_out.rcbuffer->pybuffer.shape[0]; + } + } + __pyx_t_5 = 0; + __pyx_v_out = ((PyArrayObject *)__pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":467 + * def __get_stat_double(self, field): + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) # <<<<<<<<<<<<<< + * return out + * + */ + __pyx_t_6 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_6) && PyErr_Occurred())) __PYX_ERR(0, 467, __pyx_L1_error) + __pyx_t_7 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_out)); if (unlikely(__pyx_t_7 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 467, __pyx_L1_error) + ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_t_6, ((void *)__pyx_t_7)); + + /* "acados_template/acados_ocp_solver_pyx.pyx":468 + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) + * return out # <<<<<<<<<<<<<< + * + * def __get_stat_matrix(self, field, n, m): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_out); + __pyx_r = ((PyObject *)__pyx_v_out); + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":465 + * return out + * + * def __get_stat_double(self, field): # <<<<<<<<<<<<<< + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_out.rcbuffer->pybuffer); + __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython._AcadosOcpSolverCython__get_stat_double", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + goto __pyx_L2; + __pyx_L0:; + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_out.rcbuffer->pybuffer); + __pyx_L2:; + __Pyx_XDECREF((PyObject *)__pyx_v_out); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":470 + * return out + * + * def __get_stat_matrix(self, field, n, m): # <<<<<<<<<<<<<< + * cdef cnp.ndarray[cnp.float64_t, ndim=2] out_mat = np.ascontiguousarray(np.zeros((n, m)), dtype=np.float64) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_mat.data) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33_AcadosOcpSolverCython__get_stat_matrix(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33_AcadosOcpSolverCython__get_stat_matrix = {"_AcadosOcpSolverCython__get_stat_matrix", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33_AcadosOcpSolverCython__get_stat_matrix, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33_AcadosOcpSolverCython__get_stat_matrix(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_field = 0; + PyObject *__pyx_v_n = 0; + PyObject *__pyx_v_m = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("_AcadosOcpSolverCython__get_stat_matrix (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_field,&__pyx_n_s_n,&__pyx_n_s_m,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 470, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_n)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 470, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("_AcadosOcpSolverCython__get_stat_matrix", 1, 3, 3, 1); __PYX_ERR(0, 470, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_m)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 470, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("_AcadosOcpSolverCython__get_stat_matrix", 1, 3, 3, 2); __PYX_ERR(0, 470, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "_AcadosOcpSolverCython__get_stat_matrix") < 0)) __PYX_ERR(0, 470, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + } + __pyx_v_field = values[0]; + __pyx_v_n = values[1]; + __pyx_v_m = values[2]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("_AcadosOcpSolverCython__get_stat_matrix", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 470, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython._AcadosOcpSolverCython__get_stat_matrix", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_32__get_stat_matrix(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_field, __pyx_v_n, __pyx_v_m); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_32__get_stat_matrix(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field, PyObject *__pyx_v_n, PyObject *__pyx_v_m) { + PyArrayObject *__pyx_v_out_mat = 0; + __Pyx_LocalBuf_ND __pyx_pybuffernd_out_mat; + __Pyx_Buffer __pyx_pybuffer_out_mat; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + PyArrayObject *__pyx_t_7 = NULL; + char const *__pyx_t_8; + char *__pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("_AcadosOcpSolverCython__get_stat_matrix", 1); + __pyx_pybuffer_out_mat.pybuffer.buf = NULL; + __pyx_pybuffer_out_mat.refcount = 0; + __pyx_pybuffernd_out_mat.data = NULL; + __pyx_pybuffernd_out_mat.rcbuffer = &__pyx_pybuffer_out_mat; + + /* "acados_template/acados_ocp_solver_pyx.pyx":471 + * + * def __get_stat_matrix(self, field, n, m): + * cdef cnp.ndarray[cnp.float64_t, ndim=2] out_mat = np.ascontiguousarray(np.zeros((n, m)), dtype=np.float64) # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_mat.data) + * return out_mat + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 471, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 471, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_np); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 471, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_zeros); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 471, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 471, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_v_n); + __Pyx_GIVEREF(__pyx_v_n); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_v_n)) __PYX_ERR(0, 471, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_m); + __Pyx_GIVEREF(__pyx_v_m); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_v_m)) __PYX_ERR(0, 471, __pyx_L1_error); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (unlikely(PyMethod_Check(__pyx_t_4))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_4); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_4); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_4, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_5, __pyx_t_3}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_6, 1+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 471, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + __pyx_t_4 = PyTuple_New(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 471, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_1)) __PYX_ERR(0, 471, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 471, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_np); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 471, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_float64); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 471, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + if (PyDict_SetItem(__pyx_t_1, __pyx_n_s_dtype, __pyx_t_5) < 0) __PYX_ERR(0, 471, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_5 = __Pyx_PyObject_Call(__pyx_t_2, __pyx_t_4, __pyx_t_1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 471, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (!(likely(((__pyx_t_5) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_5, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 471, __pyx_L1_error) + __pyx_t_7 = ((PyArrayObject *)__pyx_t_5); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_out_mat.rcbuffer->pybuffer, (PyObject*)__pyx_t_7, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 2, 0, __pyx_stack) == -1)) { + __pyx_v_out_mat = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_out_mat.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 471, __pyx_L1_error) + } else {__pyx_pybuffernd_out_mat.diminfo[0].strides = __pyx_pybuffernd_out_mat.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_out_mat.diminfo[0].shape = __pyx_pybuffernd_out_mat.rcbuffer->pybuffer.shape[0]; __pyx_pybuffernd_out_mat.diminfo[1].strides = __pyx_pybuffernd_out_mat.rcbuffer->pybuffer.strides[1]; __pyx_pybuffernd_out_mat.diminfo[1].shape = __pyx_pybuffernd_out_mat.rcbuffer->pybuffer.shape[1]; + } + } + __pyx_t_7 = 0; + __pyx_v_out_mat = ((PyArrayObject *)__pyx_t_5); + __pyx_t_5 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":472 + * def __get_stat_matrix(self, field, n, m): + * cdef cnp.ndarray[cnp.float64_t, ndim=2] out_mat = np.ascontiguousarray(np.zeros((n, m)), dtype=np.float64) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_mat.data) # <<<<<<<<<<<<<< + * return out_mat + * + */ + __pyx_t_8 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_8) && PyErr_Occurred())) __PYX_ERR(0, 472, __pyx_L1_error) + __pyx_t_9 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_out_mat)); if (unlikely(__pyx_t_9 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 472, __pyx_L1_error) + ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_t_8, ((void *)__pyx_t_9)); + + /* "acados_template/acados_ocp_solver_pyx.pyx":473 + * cdef cnp.ndarray[cnp.float64_t, ndim=2] out_mat = np.ascontiguousarray(np.zeros((n, m)), dtype=np.float64) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_mat.data) + * return out_mat # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_out_mat); + __pyx_r = ((PyObject *)__pyx_v_out_mat); + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":470 + * return out + * + * def __get_stat_matrix(self, field, n, m): # <<<<<<<<<<<<<< + * cdef cnp.ndarray[cnp.float64_t, ndim=2] out_mat = np.ascontiguousarray(np.zeros((n, m)), dtype=np.float64) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_mat.data) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_out_mat.rcbuffer->pybuffer); + __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython._AcadosOcpSolverCython__get_stat_matrix", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + goto __pyx_L2; + __pyx_L0:; + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_out_mat.rcbuffer->pybuffer); + __pyx_L2:; + __Pyx_XDECREF((PyObject *)__pyx_v_out_mat); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":476 + * + * + * def get_cost(self): # <<<<<<<<<<<<<< + * """ + * Returns the cost value of the current solution. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35get_cost(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34get_cost, "\n Returns the cost value of the current solution.\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35get_cost = {"get_cost", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35get_cost, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34get_cost}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35get_cost(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("get_cost (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("get_cost", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "get_cost", 0))) return NULL; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34get_cost(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34get_cost(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { + double __pyx_v_out; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_cost", 1); + + /* "acados_template/acados_ocp_solver_pyx.pyx":481 + * """ + * # compute cost internally + * acados_solver_common.ocp_nlp_eval_cost(self.nlp_solver, self.nlp_in, self.nlp_out) # <<<<<<<<<<<<<< + * + * # create output + */ + ocp_nlp_eval_cost(__pyx_v_self->nlp_solver, __pyx_v_self->nlp_in, __pyx_v_self->nlp_out); + + /* "acados_template/acados_ocp_solver_pyx.pyx":487 + * + * # call getter + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, "cost_value", &out) # <<<<<<<<<<<<<< + * + * return out + */ + ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, ((char const *)"cost_value"), ((void *)(&__pyx_v_out))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":489 + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, "cost_value", &out) + * + * return out # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyFloat_FromDouble(__pyx_v_out); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 489, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":476 + * + * + * def get_cost(self): # <<<<<<<<<<<<<< + * """ + * Returns the cost value of the current solution. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.get_cost", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":492 + * + * + * def get_residuals(self, recompute=False): # <<<<<<<<<<<<<< + * """ + * Returns an array of the form [res_stat, res_eq, res_ineq, res_comp]. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37get_residuals(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36get_residuals, "\n Returns an array of the form [res_stat, res_eq, res_ineq, res_comp].\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37get_residuals = {"get_residuals", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37get_residuals, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36get_residuals}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37get_residuals(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_recompute = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("get_residuals (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_recompute,0}; + values[0] = __Pyx_Arg_NewRef_FASTCALL(((PyObject *)Py_False)); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_recompute); + if (value) { values[0] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 492, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "get_residuals") < 0)) __PYX_ERR(0, 492, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_recompute = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("get_residuals", 0, 0, 1, __pyx_nargs); __PYX_ERR(0, 492, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.get_residuals", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36get_residuals(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_recompute); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36get_residuals(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_recompute) { + PyArrayObject *__pyx_v_out = 0; + double __pyx_v_double_value; + PyObject *__pyx_v_field = NULL; + __Pyx_LocalBuf_ND __pyx_pybuffernd_out; + __Pyx_Buffer __pyx_pybuffer_out; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_t_9; + PyArrayObject *__pyx_t_10 = NULL; + char const *__pyx_t_11; + Py_ssize_t __pyx_t_12; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_residuals", 1); + __pyx_pybuffer_out.pybuffer.buf = NULL; + __pyx_pybuffer_out.refcount = 0; + __pyx_pybuffernd_out.data = NULL; + __pyx_pybuffernd_out.rcbuffer = &__pyx_pybuffer_out; + + /* "acados_template/acados_ocp_solver_pyx.pyx":497 + * """ + * # compute residuals if RTI + * if self.nlp_solver_type == 'SQP_RTI' or recompute: # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_eval_residuals(self.nlp_solver, self.nlp_in, self.nlp_out) + * + */ + __pyx_t_2 = (__Pyx_PyUnicode_Equals(__pyx_v_self->nlp_solver_type, __pyx_n_u_SQP_RTI, Py_EQ)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 497, __pyx_L1_error) + if (!__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_v_recompute); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 497, __pyx_L1_error) + __pyx_t_1 = __pyx_t_2; + __pyx_L4_bool_binop_done:; + if (__pyx_t_1) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":498 + * # compute residuals if RTI + * if self.nlp_solver_type == 'SQP_RTI' or recompute: + * acados_solver_common.ocp_nlp_eval_residuals(self.nlp_solver, self.nlp_in, self.nlp_out) # <<<<<<<<<<<<<< + * + * # create output array + */ + ocp_nlp_eval_residuals(__pyx_v_self->nlp_solver, __pyx_v_self->nlp_in, __pyx_v_self->nlp_out); + + /* "acados_template/acados_ocp_solver_pyx.pyx":497 + * """ + * # compute residuals if RTI + * if self.nlp_solver_type == 'SQP_RTI' or recompute: # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_eval_residuals(self.nlp_solver, self.nlp_in, self.nlp_out) + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":501 + * + * # create output array + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.ascontiguousarray(np.zeros((4,), dtype=np.float64)) # <<<<<<<<<<<<<< + * cdef double double_value + * + */ + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_np); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 501, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 501, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_np); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 501, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_zeros); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 501, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 501, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GetModuleGlobalName(__pyx_t_7, __pyx_n_s_np); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 501, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_t_7, __pyx_n_s_float64); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 501, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (PyDict_SetItem(__pyx_t_4, __pyx_n_s_dtype, __pyx_t_8) < 0) __PYX_ERR(0, 501, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_t_6, __pyx_tuple__27, __pyx_t_4); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 501, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = NULL; + __pyx_t_9 = 0; + #if CYTHON_UNPACK_METHODS + if (unlikely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_9 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_4, __pyx_t_8}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_9, 1+__pyx_t_9); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 501, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + if (!(likely(((__pyx_t_3) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_3, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 501, __pyx_L1_error) + __pyx_t_10 = ((PyArrayObject *)__pyx_t_3); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_out.rcbuffer->pybuffer, (PyObject*)__pyx_t_10, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES| PyBUF_WRITABLE, 1, 0, __pyx_stack) == -1)) { + __pyx_v_out = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_out.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 501, __pyx_L1_error) + } else {__pyx_pybuffernd_out.diminfo[0].strides = __pyx_pybuffernd_out.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_out.diminfo[0].shape = __pyx_pybuffernd_out.rcbuffer->pybuffer.shape[0]; + } + } + __pyx_t_10 = 0; + __pyx_v_out = ((PyArrayObject *)__pyx_t_3); + __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":504 + * cdef double double_value + * + * field = "res_stat".encode('utf-8') # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) + * out[0] = double_value + */ + __Pyx_INCREF(__pyx_n_b_res_stat); + __pyx_v_field = __pyx_n_b_res_stat; + + /* "acados_template/acados_ocp_solver_pyx.pyx":505 + * + * field = "res_stat".encode('utf-8') + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) # <<<<<<<<<<<<<< + * out[0] = double_value + * + */ + __pyx_t_11 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_11) && PyErr_Occurred())) __PYX_ERR(0, 505, __pyx_L1_error) + ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_t_11, ((void *)(&__pyx_v_double_value))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":506 + * field = "res_stat".encode('utf-8') + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) + * out[0] = double_value # <<<<<<<<<<<<<< + * + * field = "res_eq".encode('utf-8') + */ + __pyx_t_12 = 0; + __pyx_t_9 = -1; + if (__pyx_t_12 < 0) { + __pyx_t_12 += __pyx_pybuffernd_out.diminfo[0].shape; + if (unlikely(__pyx_t_12 < 0)) __pyx_t_9 = 0; + } else if (unlikely(__pyx_t_12 >= __pyx_pybuffernd_out.diminfo[0].shape)) __pyx_t_9 = 0; + if (unlikely(__pyx_t_9 != -1)) { + __Pyx_RaiseBufferIndexError(__pyx_t_9); + __PYX_ERR(0, 506, __pyx_L1_error) + } + *__Pyx_BufPtrStrided1d(__pyx_t_5numpy_float64_t *, __pyx_pybuffernd_out.rcbuffer->pybuffer.buf, __pyx_t_12, __pyx_pybuffernd_out.diminfo[0].strides) = __pyx_v_double_value; + + /* "acados_template/acados_ocp_solver_pyx.pyx":508 + * out[0] = double_value + * + * field = "res_eq".encode('utf-8') # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) + * out[1] = double_value + */ + __Pyx_INCREF(__pyx_n_b_res_eq); + __Pyx_DECREF_SET(__pyx_v_field, __pyx_n_b_res_eq); + + /* "acados_template/acados_ocp_solver_pyx.pyx":509 + * + * field = "res_eq".encode('utf-8') + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) # <<<<<<<<<<<<<< + * out[1] = double_value + * + */ + __pyx_t_11 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_11) && PyErr_Occurred())) __PYX_ERR(0, 509, __pyx_L1_error) + ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_t_11, ((void *)(&__pyx_v_double_value))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":510 + * field = "res_eq".encode('utf-8') + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) + * out[1] = double_value # <<<<<<<<<<<<<< + * + * field = "res_ineq".encode('utf-8') + */ + __pyx_t_12 = 1; + __pyx_t_9 = -1; + if (__pyx_t_12 < 0) { + __pyx_t_12 += __pyx_pybuffernd_out.diminfo[0].shape; + if (unlikely(__pyx_t_12 < 0)) __pyx_t_9 = 0; + } else if (unlikely(__pyx_t_12 >= __pyx_pybuffernd_out.diminfo[0].shape)) __pyx_t_9 = 0; + if (unlikely(__pyx_t_9 != -1)) { + __Pyx_RaiseBufferIndexError(__pyx_t_9); + __PYX_ERR(0, 510, __pyx_L1_error) + } + *__Pyx_BufPtrStrided1d(__pyx_t_5numpy_float64_t *, __pyx_pybuffernd_out.rcbuffer->pybuffer.buf, __pyx_t_12, __pyx_pybuffernd_out.diminfo[0].strides) = __pyx_v_double_value; + + /* "acados_template/acados_ocp_solver_pyx.pyx":512 + * out[1] = double_value + * + * field = "res_ineq".encode('utf-8') # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) + * out[2] = double_value + */ + __Pyx_INCREF(__pyx_n_b_res_ineq); + __Pyx_DECREF_SET(__pyx_v_field, __pyx_n_b_res_ineq); + + /* "acados_template/acados_ocp_solver_pyx.pyx":513 + * + * field = "res_ineq".encode('utf-8') + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) # <<<<<<<<<<<<<< + * out[2] = double_value + * + */ + __pyx_t_11 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_11) && PyErr_Occurred())) __PYX_ERR(0, 513, __pyx_L1_error) + ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_t_11, ((void *)(&__pyx_v_double_value))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":514 + * field = "res_ineq".encode('utf-8') + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) + * out[2] = double_value # <<<<<<<<<<<<<< + * + * field = "res_comp".encode('utf-8') + */ + __pyx_t_12 = 2; + __pyx_t_9 = -1; + if (__pyx_t_12 < 0) { + __pyx_t_12 += __pyx_pybuffernd_out.diminfo[0].shape; + if (unlikely(__pyx_t_12 < 0)) __pyx_t_9 = 0; + } else if (unlikely(__pyx_t_12 >= __pyx_pybuffernd_out.diminfo[0].shape)) __pyx_t_9 = 0; + if (unlikely(__pyx_t_9 != -1)) { + __Pyx_RaiseBufferIndexError(__pyx_t_9); + __PYX_ERR(0, 514, __pyx_L1_error) + } + *__Pyx_BufPtrStrided1d(__pyx_t_5numpy_float64_t *, __pyx_pybuffernd_out.rcbuffer->pybuffer.buf, __pyx_t_12, __pyx_pybuffernd_out.diminfo[0].strides) = __pyx_v_double_value; + + /* "acados_template/acados_ocp_solver_pyx.pyx":516 + * out[2] = double_value + * + * field = "res_comp".encode('utf-8') # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) + * out[3] = double_value + */ + __Pyx_INCREF(__pyx_n_b_res_comp); + __Pyx_DECREF_SET(__pyx_v_field, __pyx_n_b_res_comp); + + /* "acados_template/acados_ocp_solver_pyx.pyx":517 + * + * field = "res_comp".encode('utf-8') + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) # <<<<<<<<<<<<<< + * out[3] = double_value + * + */ + __pyx_t_11 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_11) && PyErr_Occurred())) __PYX_ERR(0, 517, __pyx_L1_error) + ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_t_11, ((void *)(&__pyx_v_double_value))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":518 + * field = "res_comp".encode('utf-8') + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) + * out[3] = double_value # <<<<<<<<<<<<<< + * + * return out + */ + __pyx_t_12 = 3; + __pyx_t_9 = -1; + if (__pyx_t_12 < 0) { + __pyx_t_12 += __pyx_pybuffernd_out.diminfo[0].shape; + if (unlikely(__pyx_t_12 < 0)) __pyx_t_9 = 0; + } else if (unlikely(__pyx_t_12 >= __pyx_pybuffernd_out.diminfo[0].shape)) __pyx_t_9 = 0; + if (unlikely(__pyx_t_9 != -1)) { + __Pyx_RaiseBufferIndexError(__pyx_t_9); + __PYX_ERR(0, 518, __pyx_L1_error) + } + *__Pyx_BufPtrStrided1d(__pyx_t_5numpy_float64_t *, __pyx_pybuffernd_out.rcbuffer->pybuffer.buf, __pyx_t_12, __pyx_pybuffernd_out.diminfo[0].strides) = __pyx_v_double_value; + + /* "acados_template/acados_ocp_solver_pyx.pyx":520 + * out[3] = double_value + * + * return out # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_out); + __pyx_r = ((PyObject *)__pyx_v_out); + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":492 + * + * + * def get_residuals(self, recompute=False): # <<<<<<<<<<<<<< + * """ + * Returns an array of the form [res_stat, res_eq, res_ineq, res_comp]. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_out.rcbuffer->pybuffer); + __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.get_residuals", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + goto __pyx_L2; + __pyx_L0:; + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_out.rcbuffer->pybuffer); + __pyx_L2:; + __Pyx_XDECREF((PyObject *)__pyx_v_out); + __Pyx_XDECREF(__pyx_v_field); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":524 + * + * # Note: this function should not be used anymore, better use cost_set, constraints_set + * def set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * + * """ + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39set(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38set, "\n Set numerical data inside the solver.\n\n :param stage: integer corresponding to shooting node\n :param field: string in ['x', 'u', 'pi', 'lam', 't', 'p']\n\n .. note:: regarding lam, t: \n\n the inequalities are internally organized in the following order: \n\n [ lbu lbx lg lh lphi ubu ubx ug uh uphi; \n\n lsbu lsbx lsg lsh lsphi usbu usbx usg ush usphi]\n\n .. note:: pi: multipliers for dynamics equality constraints \n\n lam: multipliers for inequalities \n\n t: slack variables corresponding to evaluation of all inequalities (at the solution) \n\n sl: slack variables of soft lower inequality constraints \n\n su: slack variables of soft upper inequality constraints \n\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39set = {"set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38set}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39set(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + int __pyx_v_stage; + PyObject *__pyx_v_field_ = 0; + PyObject *__pyx_v_value_ = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("set (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_stage,&__pyx_n_s_field_2,&__pyx_n_s_value,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stage)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 524, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field_2)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 524, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("set", 1, 3, 3, 1); __PYX_ERR(0, 524, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_value)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 524, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("set", 1, 3, 3, 2); __PYX_ERR(0, 524, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "set") < 0)) __PYX_ERR(0, 524, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + } + __pyx_v_stage = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_stage == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 524, __pyx_L3_error) + __pyx_v_field_ = ((PyObject*)values[1]); + __pyx_v_value_ = values[2]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("set", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 524, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.set", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 524, __pyx_L1_error) + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38set(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_stage, __pyx_v_field_, __pyx_v_value_); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = NULL; + __pyx_L0:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_) { + PyObject *__pyx_v_cost_fields = NULL; + PyObject *__pyx_v_constraints_fields = NULL; + PyObject *__pyx_v_out_fields = NULL; + PyObject *__pyx_v_mem_fields = NULL; + PyObject *__pyx_v_field = NULL; + PyArrayObject *__pyx_v_value = 0; + PyObject *__pyx_v_dims = NULL; + PyObject *__pyx_v_msg = NULL; + __Pyx_LocalBuf_ND __pyx_pybuffernd_value; + __Pyx_Buffer __pyx_pybuffer_value; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_t_3; + int __pyx_t_4; + Py_ssize_t __pyx_t_5; + Py_UCS4 __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + PyObject *__pyx_t_9 = NULL; + PyArrayObject *__pyx_t_10 = NULL; + char *__pyx_t_11; + npy_intp *__pyx_t_12; + int __pyx_t_13; + char const *__pyx_t_14; + char const *__pyx_t_15; + char const *__pyx_t_16; + char const *__pyx_t_17; + char const *__pyx_t_18; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("set", 1); + __pyx_pybuffer_value.pybuffer.buf = NULL; + __pyx_pybuffer_value.refcount = 0; + __pyx_pybuffernd_value.data = NULL; + __pyx_pybuffernd_value.rcbuffer = &__pyx_pybuffer_value; + + /* "acados_template/acados_ocp_solver_pyx.pyx":543 + * su: slack variables of soft upper inequality constraints \n + * """ + * if not isinstance(value_, np.ndarray): # <<<<<<<<<<<<<< + * raise Exception(f"set: value must be numpy array, got {type(value_)}.") + * cost_fields = ['y_ref', 'yref'] + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 543, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_ndarray); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 543, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_3 = PyObject_IsInstance(__pyx_v_value_, __pyx_t_2); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(0, 543, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_4 = (!__pyx_t_3); + if (unlikely(__pyx_t_4)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":544 + * """ + * if not isinstance(value_, np.ndarray): + * raise Exception(f"set: value must be numpy array, got {type(value_)}.") # <<<<<<<<<<<<<< + * cost_fields = ['y_ref', 'yref'] + * constraints_fields = ['lbx', 'ubx', 'lbu', 'ubu'] + */ + __pyx_t_2 = PyTuple_New(3); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 544, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_5 = 0; + __pyx_t_6 = 127; + __Pyx_INCREF(__pyx_kp_u_set_value_must_be_numpy_array_go); + __pyx_t_5 += 36; + __Pyx_GIVEREF(__pyx_kp_u_set_value_must_be_numpy_array_go); + PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_kp_u_set_value_must_be_numpy_array_go); + __pyx_t_1 = __Pyx_PyObject_FormatSimple(((PyObject *)Py_TYPE(__pyx_v_value_)), __pyx_empty_unicode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 544, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_2, 1, __pyx_t_1); + __pyx_t_1 = 0; + __Pyx_INCREF(__pyx_kp_u__2); + __pyx_t_5 += 1; + __Pyx_GIVEREF(__pyx_kp_u__2); + PyTuple_SET_ITEM(__pyx_t_2, 2, __pyx_kp_u__2); + __pyx_t_1 = __Pyx_PyUnicode_Join(__pyx_t_2, 3, __pyx_t_5, __pyx_t_6); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 544, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 544, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 544, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":543 + * su: slack variables of soft upper inequality constraints \n + * """ + * if not isinstance(value_, np.ndarray): # <<<<<<<<<<<<<< + * raise Exception(f"set: value must be numpy array, got {type(value_)}.") + * cost_fields = ['y_ref', 'yref'] + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":545 + * if not isinstance(value_, np.ndarray): + * raise Exception(f"set: value must be numpy array, got {type(value_)}.") + * cost_fields = ['y_ref', 'yref'] # <<<<<<<<<<<<<< + * constraints_fields = ['lbx', 'ubx', 'lbu', 'ubu'] + * out_fields = ['x', 'u', 'pi', 'lam', 't', 'z', 'sl', 'su'] + */ + __pyx_t_2 = PyList_New(2); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 545, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_INCREF(__pyx_n_u_y_ref); + __Pyx_GIVEREF(__pyx_n_u_y_ref); + if (__Pyx_PyList_SET_ITEM(__pyx_t_2, 0, __pyx_n_u_y_ref)) __PYX_ERR(0, 545, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_yref); + __Pyx_GIVEREF(__pyx_n_u_yref); + if (__Pyx_PyList_SET_ITEM(__pyx_t_2, 1, __pyx_n_u_yref)) __PYX_ERR(0, 545, __pyx_L1_error); + __pyx_v_cost_fields = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":546 + * raise Exception(f"set: value must be numpy array, got {type(value_)}.") + * cost_fields = ['y_ref', 'yref'] + * constraints_fields = ['lbx', 'ubx', 'lbu', 'ubu'] # <<<<<<<<<<<<<< + * out_fields = ['x', 'u', 'pi', 'lam', 't', 'z', 'sl', 'su'] + * mem_fields = ['xdot_guess', 'z_guess'] + */ + __pyx_t_2 = PyList_New(4); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 546, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_INCREF(__pyx_n_u_lbx); + __Pyx_GIVEREF(__pyx_n_u_lbx); + if (__Pyx_PyList_SET_ITEM(__pyx_t_2, 0, __pyx_n_u_lbx)) __PYX_ERR(0, 546, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_ubx); + __Pyx_GIVEREF(__pyx_n_u_ubx); + if (__Pyx_PyList_SET_ITEM(__pyx_t_2, 1, __pyx_n_u_ubx)) __PYX_ERR(0, 546, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_lbu); + __Pyx_GIVEREF(__pyx_n_u_lbu); + if (__Pyx_PyList_SET_ITEM(__pyx_t_2, 2, __pyx_n_u_lbu)) __PYX_ERR(0, 546, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_ubu); + __Pyx_GIVEREF(__pyx_n_u_ubu); + if (__Pyx_PyList_SET_ITEM(__pyx_t_2, 3, __pyx_n_u_ubu)) __PYX_ERR(0, 546, __pyx_L1_error); + __pyx_v_constraints_fields = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":547 + * cost_fields = ['y_ref', 'yref'] + * constraints_fields = ['lbx', 'ubx', 'lbu', 'ubu'] + * out_fields = ['x', 'u', 'pi', 'lam', 't', 'z', 'sl', 'su'] # <<<<<<<<<<<<<< + * mem_fields = ['xdot_guess', 'z_guess'] + * + */ + __pyx_t_2 = PyList_New(8); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 547, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_INCREF(__pyx_n_u_x); + __Pyx_GIVEREF(__pyx_n_u_x); + if (__Pyx_PyList_SET_ITEM(__pyx_t_2, 0, __pyx_n_u_x)) __PYX_ERR(0, 547, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_u); + __Pyx_GIVEREF(__pyx_n_u_u); + if (__Pyx_PyList_SET_ITEM(__pyx_t_2, 1, __pyx_n_u_u)) __PYX_ERR(0, 547, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_pi); + __Pyx_GIVEREF(__pyx_n_u_pi); + if (__Pyx_PyList_SET_ITEM(__pyx_t_2, 2, __pyx_n_u_pi)) __PYX_ERR(0, 547, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_lam); + __Pyx_GIVEREF(__pyx_n_u_lam); + if (__Pyx_PyList_SET_ITEM(__pyx_t_2, 3, __pyx_n_u_lam)) __PYX_ERR(0, 547, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_t); + __Pyx_GIVEREF(__pyx_n_u_t); + if (__Pyx_PyList_SET_ITEM(__pyx_t_2, 4, __pyx_n_u_t)) __PYX_ERR(0, 547, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_z); + __Pyx_GIVEREF(__pyx_n_u_z); + if (__Pyx_PyList_SET_ITEM(__pyx_t_2, 5, __pyx_n_u_z)) __PYX_ERR(0, 547, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_sl); + __Pyx_GIVEREF(__pyx_n_u_sl); + if (__Pyx_PyList_SET_ITEM(__pyx_t_2, 6, __pyx_n_u_sl)) __PYX_ERR(0, 547, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_su); + __Pyx_GIVEREF(__pyx_n_u_su); + if (__Pyx_PyList_SET_ITEM(__pyx_t_2, 7, __pyx_n_u_su)) __PYX_ERR(0, 547, __pyx_L1_error); + __pyx_v_out_fields = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":548 + * constraints_fields = ['lbx', 'ubx', 'lbu', 'ubu'] + * out_fields = ['x', 'u', 'pi', 'lam', 't', 'z', 'sl', 'su'] + * mem_fields = ['xdot_guess', 'z_guess'] # <<<<<<<<<<<<<< + * + * field = field_.encode('utf-8') + */ + __pyx_t_2 = PyList_New(2); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 548, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_INCREF(__pyx_n_u_xdot_guess); + __Pyx_GIVEREF(__pyx_n_u_xdot_guess); + if (__Pyx_PyList_SET_ITEM(__pyx_t_2, 0, __pyx_n_u_xdot_guess)) __PYX_ERR(0, 548, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_z_guess); + __Pyx_GIVEREF(__pyx_n_u_z_guess); + if (__Pyx_PyList_SET_ITEM(__pyx_t_2, 1, __pyx_n_u_z_guess)) __PYX_ERR(0, 548, __pyx_L1_error); + __pyx_v_mem_fields = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":550 + * mem_fields = ['xdot_guess', 'z_guess'] + * + * field = field_.encode('utf-8') # <<<<<<<<<<<<<< + * + * cdef cnp.ndarray[cnp.float64_t, ndim=1] value = np.ascontiguousarray(value_, dtype=np.float64) + */ + if (unlikely(__pyx_v_field_ == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); + __PYX_ERR(0, 550, __pyx_L1_error) + } + __pyx_t_2 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 550, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_v_field = __pyx_t_2; + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":552 + * field = field_.encode('utf-8') + * + * cdef cnp.ndarray[cnp.float64_t, ndim=1] value = np.ascontiguousarray(value_, dtype=np.float64) # <<<<<<<<<<<<<< + * + * # treat parameters separately + */ + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_np); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 552, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 552, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = PyTuple_New(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 552, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_INCREF(__pyx_v_value_); + __Pyx_GIVEREF(__pyx_v_value_); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_v_value_)) __PYX_ERR(0, 552, __pyx_L1_error); + __pyx_t_7 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 552, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_GetModuleGlobalName(__pyx_t_8, __pyx_n_s_np); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 552, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_9 = __Pyx_PyObject_GetAttrStr(__pyx_t_8, __pyx_n_s_float64); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 552, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + if (PyDict_SetItem(__pyx_t_7, __pyx_n_s_dtype, __pyx_t_9) < 0) __PYX_ERR(0, 552, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + __pyx_t_9 = __Pyx_PyObject_Call(__pyx_t_1, __pyx_t_2, __pyx_t_7); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 552, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (!(likely(((__pyx_t_9) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_9, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 552, __pyx_L1_error) + __pyx_t_10 = ((PyArrayObject *)__pyx_t_9); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_value.rcbuffer->pybuffer, (PyObject*)__pyx_t_10, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 1, 0, __pyx_stack) == -1)) { + __pyx_v_value = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_value.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 552, __pyx_L1_error) + } else {__pyx_pybuffernd_value.diminfo[0].strides = __pyx_pybuffernd_value.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_value.diminfo[0].shape = __pyx_pybuffernd_value.rcbuffer->pybuffer.shape[0]; + } + } + __pyx_t_10 = 0; + __pyx_v_value = ((PyArrayObject *)__pyx_t_9); + __pyx_t_9 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":555 + * + * # treat parameters separately + * if field_ == 'p': # <<<<<<<<<<<<<< + * assert acados_solver.acados_update_params(self.capsule, stage, value.data, value.shape[0]) == 0 + * else: + */ + __pyx_t_4 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_p, Py_EQ)); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 555, __pyx_L1_error) + if (__pyx_t_4) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":556 + * # treat parameters separately + * if field_ == 'p': + * assert acados_solver.acados_update_params(self.capsule, stage, value.data, value.shape[0]) == 0 # <<<<<<<<<<<<<< + * else: + * if field_ not in constraints_fields + cost_fields + out_fields: + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_11 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_11 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 556, __pyx_L1_error) + __pyx_t_12 = __pyx_f_5numpy_7ndarray_5shape_shape(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_12 == ((npy_intp *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 556, __pyx_L1_error) + __pyx_t_4 = (lat_acados_update_params(__pyx_v_self->capsule, __pyx_v_stage, ((double *)__pyx_t_11), (__pyx_t_12[0])) == 0); + if (unlikely(!__pyx_t_4)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(0, 556, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(0, 556, __pyx_L1_error) + #endif + + /* "acados_template/acados_ocp_solver_pyx.pyx":555 + * + * # treat parameters separately + * if field_ == 'p': # <<<<<<<<<<<<<< + * assert acados_solver.acados_update_params(self.capsule, stage, value.data, value.shape[0]) == 0 + * else: + */ + goto __pyx_L4; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":558 + * assert acados_solver.acados_update_params(self.capsule, stage, value.data, value.shape[0]) == 0 + * else: + * if field_ not in constraints_fields + cost_fields + out_fields: # <<<<<<<<<<<<<< + * raise Exception("AcadosOcpSolverCython.set(): {} is not a valid argument.\ + * \nPossible values are {}.".format(field, \ + */ + /*else*/ { + __pyx_t_9 = PyNumber_Add(__pyx_v_constraints_fields, __pyx_v_cost_fields); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 558, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __pyx_t_7 = PyNumber_Add(__pyx_t_9, __pyx_v_out_fields); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 558, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + __pyx_t_4 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_t_7, Py_NE)); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 558, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(__pyx_t_4)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":560 + * if field_ not in constraints_fields + cost_fields + out_fields: + * raise Exception("AcadosOcpSolverCython.set(): {} is not a valid argument.\ + * \nPossible values are {}.".format(field, \ # <<<<<<<<<<<<<< + * constraints_fields + cost_fields + out_fields + ['p'])) + * + */ + __pyx_t_9 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_set_is_not, __pyx_n_s_format); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 560, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + + /* "acados_template/acados_ocp_solver_pyx.pyx":561 + * raise Exception("AcadosOcpSolverCython.set(): {} is not a valid argument.\ + * \nPossible values are {}.".format(field, \ + * constraints_fields + cost_fields + out_fields + ['p'])) # <<<<<<<<<<<<<< + * + * dims = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, + */ + __pyx_t_2 = PyNumber_Add(__pyx_v_constraints_fields, __pyx_v_cost_fields); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 561, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_1 = PyNumber_Add(__pyx_t_2, __pyx_v_out_fields); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 561, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = PyList_New(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 561, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_INCREF(__pyx_n_u_p); + __Pyx_GIVEREF(__pyx_n_u_p); + if (__Pyx_PyList_SET_ITEM(__pyx_t_2, 0, __pyx_n_u_p)) __PYX_ERR(0, 561, __pyx_L1_error); + __pyx_t_8 = PyNumber_Add(__pyx_t_1, __pyx_t_2); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 561, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = NULL; + __pyx_t_13 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_9))) { + __pyx_t_2 = PyMethod_GET_SELF(__pyx_t_9); + if (likely(__pyx_t_2)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_9); + __Pyx_INCREF(__pyx_t_2); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_9, function); + __pyx_t_13 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_2, __pyx_v_field, __pyx_t_8}; + __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_9, __pyx_callargs+1-__pyx_t_13, 2+__pyx_t_13); + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 560, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":559 + * else: + * if field_ not in constraints_fields + cost_fields + out_fields: + * raise Exception("AcadosOcpSolverCython.set(): {} is not a valid argument.\ # <<<<<<<<<<<<<< + * \nPossible values are {}.".format(field, \ + * constraints_fields + cost_fields + out_fields + ['p'])) + */ + __pyx_t_9 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_7); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 559, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_Raise(__pyx_t_9, 0, 0, 0); + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + __PYX_ERR(0, 559, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":558 + * assert acados_solver.acados_update_params(self.capsule, stage, value.data, value.shape[0]) == 0 + * else: + * if field_ not in constraints_fields + cost_fields + out_fields: # <<<<<<<<<<<<<< + * raise Exception("AcadosOcpSolverCython.set(): {} is not a valid argument.\ + * \nPossible values are {}.".format(field, \ + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":564 + * + * dims = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, + * self.nlp_dims, self.nlp_out, stage, field) # <<<<<<<<<<<<<< + * + * if value_.shape[0] != dims: + */ + __pyx_t_14 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_14) && PyErr_Occurred())) __PYX_ERR(0, 564, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":563 + * constraints_fields + cost_fields + out_fields + ['p'])) + * + * dims = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, # <<<<<<<<<<<<<< + * self.nlp_dims, self.nlp_out, stage, field) + * + */ + __pyx_t_9 = __Pyx_PyInt_From_int(ocp_nlp_dims_get_from_attr(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_14)); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 563, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __pyx_v_dims = __pyx_t_9; + __pyx_t_9 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":566 + * self.nlp_dims, self.nlp_out, stage, field) + * + * if value_.shape[0] != dims: # <<<<<<<<<<<<<< + * msg = 'AcadosOcpSolverCython.set(): mismatching dimension for field "{}" '.format(field_) + * msg += 'with dimension {} (you have {})'.format(dims, value_.shape[0]) + */ + __pyx_t_9 = __Pyx_PyObject_GetAttrStr(__pyx_v_value_, __pyx_n_s_shape); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 566, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __pyx_t_7 = __Pyx_GetItemInt(__pyx_t_9, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 566, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + __pyx_t_9 = PyObject_RichCompare(__pyx_t_7, __pyx_v_dims, Py_NE); __Pyx_XGOTREF(__pyx_t_9); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 566, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_t_9); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 566, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + if (unlikely(__pyx_t_4)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":567 + * + * if value_.shape[0] != dims: + * msg = 'AcadosOcpSolverCython.set(): mismatching dimension for field "{}" '.format(field_) # <<<<<<<<<<<<<< + * msg += 'with dimension {} (you have {})'.format(dims, value_.shape[0]) + * raise Exception(msg) + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_set_mismat, __pyx_n_s_format); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 567, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_8 = NULL; + __pyx_t_13 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_7))) { + __pyx_t_8 = PyMethod_GET_SELF(__pyx_t_7); + if (likely(__pyx_t_8)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_7); + __Pyx_INCREF(__pyx_t_8); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_7, function); + __pyx_t_13 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_8, __pyx_v_field_}; + __pyx_t_9 = __Pyx_PyObject_FastCall(__pyx_t_7, __pyx_callargs+1-__pyx_t_13, 1+__pyx_t_13); + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 567, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + } + __pyx_v_msg = __pyx_t_9; + __pyx_t_9 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":568 + * if value_.shape[0] != dims: + * msg = 'AcadosOcpSolverCython.set(): mismatching dimension for field "{}" '.format(field_) + * msg += 'with dimension {} (you have {})'.format(dims, value_.shape[0]) # <<<<<<<<<<<<<< + * raise Exception(msg) + * + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_with_dimension_you_have, __pyx_n_s_format); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 568, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_value_, __pyx_n_s_shape); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 568, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_2 = __Pyx_GetItemInt(__pyx_t_8, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 568, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_t_8 = NULL; + __pyx_t_13 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_7))) { + __pyx_t_8 = PyMethod_GET_SELF(__pyx_t_7); + if (likely(__pyx_t_8)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_7); + __Pyx_INCREF(__pyx_t_8); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_7, function); + __pyx_t_13 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_8, __pyx_v_dims, __pyx_t_2}; + __pyx_t_9 = __Pyx_PyObject_FastCall(__pyx_t_7, __pyx_callargs+1-__pyx_t_13, 2+__pyx_t_13); + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 568, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + } + __pyx_t_7 = PyNumber_InPlaceAdd(__pyx_v_msg, __pyx_t_9); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 568, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + __Pyx_DECREF_SET(__pyx_v_msg, __pyx_t_7); + __pyx_t_7 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":569 + * msg = 'AcadosOcpSolverCython.set(): mismatching dimension for field "{}" '.format(field_) + * msg += 'with dimension {} (you have {})'.format(dims, value_.shape[0]) + * raise Exception(msg) # <<<<<<<<<<<<<< + * + * if field_ in constraints_fields: + */ + __pyx_t_7 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_v_msg); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 569, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_Raise(__pyx_t_7, 0, 0, 0); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __PYX_ERR(0, 569, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":566 + * self.nlp_dims, self.nlp_out, stage, field) + * + * if value_.shape[0] != dims: # <<<<<<<<<<<<<< + * msg = 'AcadosOcpSolverCython.set(): mismatching dimension for field "{}" '.format(field_) + * msg += 'with dimension {} (you have {})'.format(dims, value_.shape[0]) + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":571 + * raise Exception(msg) + * + * if field_ in constraints_fields: # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, + * self.nlp_dims, self.nlp_in, stage, field, value.data) + */ + __pyx_t_4 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_constraints_fields, Py_EQ)); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 571, __pyx_L1_error) + if (__pyx_t_4) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":573 + * if field_ in constraints_fields: + * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, + * self.nlp_dims, self.nlp_in, stage, field, value.data) # <<<<<<<<<<<<<< + * elif field_ in cost_fields: + * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, + */ + __pyx_t_15 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_15) && PyErr_Occurred())) __PYX_ERR(0, 573, __pyx_L1_error) + __pyx_t_11 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_11 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 573, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":572 + * + * if field_ in constraints_fields: + * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, # <<<<<<<<<<<<<< + * self.nlp_dims, self.nlp_in, stage, field, value.data) + * elif field_ in cost_fields: + */ + (void)(ocp_nlp_constraints_model_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_in, __pyx_v_stage, __pyx_t_15, ((void *)__pyx_t_11))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":571 + * raise Exception(msg) + * + * if field_ in constraints_fields: # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, + * self.nlp_dims, self.nlp_in, stage, field, value.data) + */ + goto __pyx_L7; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":574 + * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, + * self.nlp_dims, self.nlp_in, stage, field, value.data) + * elif field_ in cost_fields: # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, + * self.nlp_dims, self.nlp_in, stage, field, value.data) + */ + __pyx_t_4 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_cost_fields, Py_EQ)); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 574, __pyx_L1_error) + if (__pyx_t_4) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":576 + * elif field_ in cost_fields: + * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, + * self.nlp_dims, self.nlp_in, stage, field, value.data) # <<<<<<<<<<<<<< + * elif field_ in out_fields: + * acados_solver_common.ocp_nlp_out_set(self.nlp_config, + */ + __pyx_t_16 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_16) && PyErr_Occurred())) __PYX_ERR(0, 576, __pyx_L1_error) + __pyx_t_11 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_11 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 576, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":575 + * self.nlp_dims, self.nlp_in, stage, field, value.data) + * elif field_ in cost_fields: + * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, # <<<<<<<<<<<<<< + * self.nlp_dims, self.nlp_in, stage, field, value.data) + * elif field_ in out_fields: + */ + (void)(ocp_nlp_cost_model_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_in, __pyx_v_stage, __pyx_t_16, ((void *)__pyx_t_11))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":574 + * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, + * self.nlp_dims, self.nlp_in, stage, field, value.data) + * elif field_ in cost_fields: # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, + * self.nlp_dims, self.nlp_in, stage, field, value.data) + */ + goto __pyx_L7; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":577 + * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, + * self.nlp_dims, self.nlp_in, stage, field, value.data) + * elif field_ in out_fields: # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_out_set(self.nlp_config, + * self.nlp_dims, self.nlp_out, stage, field, value.data) + */ + __pyx_t_4 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_out_fields, Py_EQ)); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 577, __pyx_L1_error) + if (__pyx_t_4) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":579 + * elif field_ in out_fields: + * acados_solver_common.ocp_nlp_out_set(self.nlp_config, + * self.nlp_dims, self.nlp_out, stage, field, value.data) # <<<<<<<<<<<<<< + * elif field_ in mem_fields: + * acados_solver_common.ocp_nlp_set(self.nlp_config, \ + */ + __pyx_t_17 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_17) && PyErr_Occurred())) __PYX_ERR(0, 579, __pyx_L1_error) + __pyx_t_11 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_11 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 579, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":578 + * self.nlp_dims, self.nlp_in, stage, field, value.data) + * elif field_ in out_fields: + * acados_solver_common.ocp_nlp_out_set(self.nlp_config, # <<<<<<<<<<<<<< + * self.nlp_dims, self.nlp_out, stage, field, value.data) + * elif field_ in mem_fields: + */ + ocp_nlp_out_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_17, ((void *)__pyx_t_11)); + + /* "acados_template/acados_ocp_solver_pyx.pyx":577 + * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, + * self.nlp_dims, self.nlp_in, stage, field, value.data) + * elif field_ in out_fields: # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_out_set(self.nlp_config, + * self.nlp_dims, self.nlp_out, stage, field, value.data) + */ + goto __pyx_L7; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":580 + * acados_solver_common.ocp_nlp_out_set(self.nlp_config, + * self.nlp_dims, self.nlp_out, stage, field, value.data) + * elif field_ in mem_fields: # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_set(self.nlp_config, \ + * self.nlp_solver, stage, field, value.data) + */ + __pyx_t_4 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_mem_fields, Py_EQ)); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 580, __pyx_L1_error) + if (__pyx_t_4) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":582 + * elif field_ in mem_fields: + * acados_solver_common.ocp_nlp_set(self.nlp_config, \ + * self.nlp_solver, stage, field, value.data) # <<<<<<<<<<<<<< + * + * if field_ == 'z': + */ + __pyx_t_18 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_18) && PyErr_Occurred())) __PYX_ERR(0, 582, __pyx_L1_error) + __pyx_t_11 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_11 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 582, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":581 + * self.nlp_dims, self.nlp_out, stage, field, value.data) + * elif field_ in mem_fields: + * acados_solver_common.ocp_nlp_set(self.nlp_config, \ # <<<<<<<<<<<<<< + * self.nlp_solver, stage, field, value.data) + * + */ + ocp_nlp_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_v_stage, __pyx_t_18, ((void *)__pyx_t_11)); + + /* "acados_template/acados_ocp_solver_pyx.pyx":580 + * acados_solver_common.ocp_nlp_out_set(self.nlp_config, + * self.nlp_dims, self.nlp_out, stage, field, value.data) + * elif field_ in mem_fields: # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_set(self.nlp_config, \ + * self.nlp_solver, stage, field, value.data) + */ + } + __pyx_L7:; + + /* "acados_template/acados_ocp_solver_pyx.pyx":584 + * self.nlp_solver, stage, field, value.data) + * + * if field_ == 'z': # <<<<<<<<<<<<<< + * field = 'z_guess'.encode('utf-8') + * acados_solver_common.ocp_nlp_set(self.nlp_config, \ + */ + __pyx_t_4 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_z, Py_EQ)); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 584, __pyx_L1_error) + if (__pyx_t_4) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":585 + * + * if field_ == 'z': + * field = 'z_guess'.encode('utf-8') # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_set(self.nlp_config, \ + * self.nlp_solver, stage, field, value.data) + */ + __Pyx_INCREF(__pyx_n_b_z_guess); + __Pyx_DECREF_SET(__pyx_v_field, __pyx_n_b_z_guess); + + /* "acados_template/acados_ocp_solver_pyx.pyx":587 + * field = 'z_guess'.encode('utf-8') + * acados_solver_common.ocp_nlp_set(self.nlp_config, \ + * self.nlp_solver, stage, field, value.data) # <<<<<<<<<<<<<< + * return + * + */ + __pyx_t_18 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_18) && PyErr_Occurred())) __PYX_ERR(0, 587, __pyx_L1_error) + __pyx_t_11 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_11 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 587, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":586 + * if field_ == 'z': + * field = 'z_guess'.encode('utf-8') + * acados_solver_common.ocp_nlp_set(self.nlp_config, \ # <<<<<<<<<<<<<< + * self.nlp_solver, stage, field, value.data) + * return + */ + ocp_nlp_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_v_stage, __pyx_t_18, ((void *)__pyx_t_11)); + + /* "acados_template/acados_ocp_solver_pyx.pyx":584 + * self.nlp_solver, stage, field, value.data) + * + * if field_ == 'z': # <<<<<<<<<<<<<< + * field = 'z_guess'.encode('utf-8') + * acados_solver_common.ocp_nlp_set(self.nlp_config, \ + */ + } + } + __pyx_L4:; + + /* "acados_template/acados_ocp_solver_pyx.pyx":588 + * acados_solver_common.ocp_nlp_set(self.nlp_config, \ + * self.nlp_solver, stage, field, value.data) + * return # <<<<<<<<<<<<<< + * + * def cost_set(self, int stage, str field_, value_): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":524 + * + * # Note: this function should not be used anymore, better use cost_set, constraints_set + * def set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * + * """ + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_XDECREF(__pyx_t_9); + { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_value.rcbuffer->pybuffer); + __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.set", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + goto __pyx_L2; + __pyx_L0:; + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_value.rcbuffer->pybuffer); + __pyx_L2:; + __Pyx_XDECREF(__pyx_v_cost_fields); + __Pyx_XDECREF(__pyx_v_constraints_fields); + __Pyx_XDECREF(__pyx_v_out_fields); + __Pyx_XDECREF(__pyx_v_mem_fields); + __Pyx_XDECREF(__pyx_v_field); + __Pyx_XDECREF((PyObject *)__pyx_v_value); + __Pyx_XDECREF(__pyx_v_dims); + __Pyx_XDECREF(__pyx_v_msg); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":590 + * return + * + * def cost_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set numerical data in the cost module of the solver. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41cost_set(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40cost_set, "\n Set numerical data in the cost module of the solver.\n\n :param stage: integer corresponding to shooting node\n :param field: string, e.g. 'yref', 'W', 'ext_cost_num_hess'\n :param value: of appropriate size\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41cost_set = {"cost_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41cost_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40cost_set}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41cost_set(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + int __pyx_v_stage; + PyObject *__pyx_v_field_ = 0; + PyObject *__pyx_v_value_ = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("cost_set (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_stage,&__pyx_n_s_field_2,&__pyx_n_s_value,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stage)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 590, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field_2)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 590, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("cost_set", 1, 3, 3, 1); __PYX_ERR(0, 590, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_value)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 590, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("cost_set", 1, 3, 3, 2); __PYX_ERR(0, 590, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "cost_set") < 0)) __PYX_ERR(0, 590, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + } + __pyx_v_stage = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_stage == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 590, __pyx_L3_error) + __pyx_v_field_ = ((PyObject*)values[1]); + __pyx_v_value_ = values[2]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("cost_set", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 590, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.cost_set", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 590, __pyx_L1_error) + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40cost_set(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_stage, __pyx_v_field_, __pyx_v_value_); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = NULL; + __pyx_L0:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40cost_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_) { + PyObject *__pyx_v_field = NULL; + int __pyx_v_dims[2]; + __Pyx_memviewslice __pyx_v_value = { 0, 0, { 0 }, { 0 }, { 0 } }; + PyObject *__pyx_v_value_shape = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_t_3; + int __pyx_t_4; + Py_ssize_t __pyx_t_5; + Py_UCS4 __pyx_t_6; + char const *__pyx_t_7; + PyObject *__pyx_t_8 = NULL; + PyObject *__pyx_t_9 = NULL; + int __pyx_t_10; + __Pyx_memviewslice __pyx_t_11 = { 0, 0, { 0 }, { 0 }, { 0 } }; + char const *__pyx_t_12; + Py_ssize_t __pyx_t_13; + Py_ssize_t __pyx_t_14; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("cost_set", 1); + + /* "acados_template/acados_ocp_solver_pyx.pyx":598 + * :param value: of appropriate size + * """ + * if not isinstance(value_, np.ndarray): # <<<<<<<<<<<<<< + * raise Exception(f"cost_set: value must be numpy array, got {type(value_)}.") + * field = field_.encode('utf-8') + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 598, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_ndarray); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 598, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_3 = PyObject_IsInstance(__pyx_v_value_, __pyx_t_2); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(0, 598, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_4 = (!__pyx_t_3); + if (unlikely(__pyx_t_4)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":599 + * """ + * if not isinstance(value_, np.ndarray): + * raise Exception(f"cost_set: value must be numpy array, got {type(value_)}.") # <<<<<<<<<<<<<< + * field = field_.encode('utf-8') + * + */ + __pyx_t_2 = PyTuple_New(3); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 599, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_5 = 0; + __pyx_t_6 = 127; + __Pyx_INCREF(__pyx_kp_u_cost_set_value_must_be_numpy_arr); + __pyx_t_5 += 41; + __Pyx_GIVEREF(__pyx_kp_u_cost_set_value_must_be_numpy_arr); + PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_kp_u_cost_set_value_must_be_numpy_arr); + __pyx_t_1 = __Pyx_PyObject_FormatSimple(((PyObject *)Py_TYPE(__pyx_v_value_)), __pyx_empty_unicode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 599, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_2, 1, __pyx_t_1); + __pyx_t_1 = 0; + __Pyx_INCREF(__pyx_kp_u__2); + __pyx_t_5 += 1; + __Pyx_GIVEREF(__pyx_kp_u__2); + PyTuple_SET_ITEM(__pyx_t_2, 2, __pyx_kp_u__2); + __pyx_t_1 = __Pyx_PyUnicode_Join(__pyx_t_2, 3, __pyx_t_5, __pyx_t_6); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 599, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 599, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 599, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":598 + * :param value: of appropriate size + * """ + * if not isinstance(value_, np.ndarray): # <<<<<<<<<<<<<< + * raise Exception(f"cost_set: value must be numpy array, got {type(value_)}.") + * field = field_.encode('utf-8') + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":600 + * if not isinstance(value_, np.ndarray): + * raise Exception(f"cost_set: value must be numpy array, got {type(value_)}.") + * field = field_.encode('utf-8') # <<<<<<<<<<<<<< + * + * cdef int dims[2] + */ + if (unlikely(__pyx_v_field_ == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); + __PYX_ERR(0, 600, __pyx_L1_error) + } + __pyx_t_2 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 600, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_v_field = __pyx_t_2; + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":604 + * cdef int dims[2] + * acados_solver_common.ocp_nlp_cost_dims_get_from_attr(self.nlp_config, \ + * self.nlp_dims, self.nlp_out, stage, field, &dims[0]) # <<<<<<<<<<<<<< + * + * cdef double[::1,:] value + */ + __pyx_t_7 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 604, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":603 + * + * cdef int dims[2] + * acados_solver_common.ocp_nlp_cost_dims_get_from_attr(self.nlp_config, \ # <<<<<<<<<<<<<< + * self.nlp_dims, self.nlp_out, stage, field, &dims[0]) + * + */ + ocp_nlp_cost_dims_get_from_attr(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_7, (&(__pyx_v_dims[0]))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":608 + * cdef double[::1,:] value + * + * value_shape = value_.shape # <<<<<<<<<<<<<< + * if len(value_shape) == 1: + * value_shape = (value_shape[0], 0) + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_value_, __pyx_n_s_shape); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 608, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_v_value_shape = __pyx_t_2; + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":609 + * + * value_shape = value_.shape + * if len(value_shape) == 1: # <<<<<<<<<<<<<< + * value_shape = (value_shape[0], 0) + * value = np.asfortranarray(value_[None,:]) + */ + __pyx_t_5 = PyObject_Length(__pyx_v_value_shape); if (unlikely(__pyx_t_5 == ((Py_ssize_t)-1))) __PYX_ERR(0, 609, __pyx_L1_error) + __pyx_t_4 = (__pyx_t_5 == 1); + if (__pyx_t_4) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":610 + * value_shape = value_.shape + * if len(value_shape) == 1: + * value_shape = (value_shape[0], 0) # <<<<<<<<<<<<<< + * value = np.asfortranarray(value_[None,:]) + * + */ + __pyx_t_2 = __Pyx_GetItemInt(__pyx_v_value_shape, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 610, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_1 = PyTuple_New(2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 610, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_t_2)) __PYX_ERR(0, 610, __pyx_L1_error); + __Pyx_INCREF(__pyx_int_0); + __Pyx_GIVEREF(__pyx_int_0); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_int_0)) __PYX_ERR(0, 610, __pyx_L1_error); + __pyx_t_2 = 0; + __Pyx_DECREF_SET(__pyx_v_value_shape, __pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":611 + * if len(value_shape) == 1: + * value_shape = (value_shape[0], 0) + * value = np.asfortranarray(value_[None,:]) # <<<<<<<<<<<<<< + * + * elif len(value_shape) == 2: + */ + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_np); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 611, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_asfortranarray); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 611, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_v_value_, __pyx_tuple__28); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 611, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_9 = NULL; + __pyx_t_10 = 0; + #if CYTHON_UNPACK_METHODS + if (unlikely(PyMethod_Check(__pyx_t_8))) { + __pyx_t_9 = PyMethod_GET_SELF(__pyx_t_8); + if (likely(__pyx_t_9)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_8); + __Pyx_INCREF(__pyx_t_9); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_8, function); + __pyx_t_10 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_9, __pyx_t_2}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_8, __pyx_callargs+1-__pyx_t_10, 1+__pyx_t_10); + __Pyx_XDECREF(__pyx_t_9); __pyx_t_9 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 611, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } + __pyx_t_11 = __Pyx_PyObject_to_MemoryviewSlice_dcd__double(__pyx_t_1, PyBUF_WRITABLE); if (unlikely(!__pyx_t_11.memview)) __PYX_ERR(0, 611, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_value = __pyx_t_11; + __pyx_t_11.memview = NULL; + __pyx_t_11.data = NULL; + + /* "acados_template/acados_ocp_solver_pyx.pyx":609 + * + * value_shape = value_.shape + * if len(value_shape) == 1: # <<<<<<<<<<<<<< + * value_shape = (value_shape[0], 0) + * value = np.asfortranarray(value_[None,:]) + */ + goto __pyx_L4; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":613 + * value = np.asfortranarray(value_[None,:]) + * + * elif len(value_shape) == 2: # <<<<<<<<<<<<<< + * # Get elements in column major order + * value = np.asfortranarray(value_) + */ + __pyx_t_5 = PyObject_Length(__pyx_v_value_shape); if (unlikely(__pyx_t_5 == ((Py_ssize_t)-1))) __PYX_ERR(0, 613, __pyx_L1_error) + __pyx_t_4 = (__pyx_t_5 == 2); + if (__pyx_t_4) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":615 + * elif len(value_shape) == 2: + * # Get elements in column major order + * value = np.asfortranarray(value_) # <<<<<<<<<<<<<< + * + * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: + */ + __Pyx_GetModuleGlobalName(__pyx_t_8, __pyx_n_s_np); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 615, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_8, __pyx_n_s_asfortranarray); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 615, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_t_8 = NULL; + __pyx_t_10 = 0; + #if CYTHON_UNPACK_METHODS + if (unlikely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_8 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_8)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_8); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_10 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_8, __pyx_v_value_}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_10, 1+__pyx_t_10); + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 615, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_t_11 = __Pyx_PyObject_to_MemoryviewSlice_dcd__double(__pyx_t_1, PyBUF_WRITABLE); if (unlikely(!__pyx_t_11.memview)) __PYX_ERR(0, 615, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_value = __pyx_t_11; + __pyx_t_11.memview = NULL; + __pyx_t_11.data = NULL; + + /* "acados_template/acados_ocp_solver_pyx.pyx":613 + * value = np.asfortranarray(value_[None,:]) + * + * elif len(value_shape) == 2: # <<<<<<<<<<<<<< + * # Get elements in column major order + * value = np.asfortranarray(value_) + */ + } + __pyx_L4:; + + /* "acados_template/acados_ocp_solver_pyx.pyx":617 + * value = np.asfortranarray(value_) + * + * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.cost_set(): mismatching dimension' + + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') + */ + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_value_shape, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyInt_From_int((__pyx_v_dims[0])); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_8 = PyObject_RichCompare(__pyx_t_1, __pyx_t_2, Py_NE); __Pyx_XGOTREF(__pyx_t_8); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_3 = __Pyx_PyObject_IsTrue(__pyx_t_8); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + if (!__pyx_t_3) { + } else { + __pyx_t_4 = __pyx_t_3; + goto __pyx_L6_bool_binop_done; + } + __pyx_t_8 = __Pyx_GetItemInt(__pyx_v_value_shape, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_2 = __Pyx_PyInt_From_int((__pyx_v_dims[1])); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_1 = PyObject_RichCompare(__pyx_t_8, __pyx_t_2, Py_NE); __Pyx_XGOTREF(__pyx_t_1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_3 = __Pyx_PyObject_IsTrue(__pyx_t_1); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_4 = __pyx_t_3; + __pyx_L6_bool_binop_done:; + if (unlikely(__pyx_t_4)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":619 + * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: + * raise Exception('AcadosOcpSolverCython.cost_set(): mismatching dimension' + + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') # <<<<<<<<<<<<<< + * + * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, \ + */ + __pyx_t_1 = PyTuple_New(9); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 619, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = 0; + __pyx_t_6 = 127; + __Pyx_INCREF(__pyx_kp_u_for_field); + __pyx_t_5 += 12; + __Pyx_GIVEREF(__pyx_kp_u_for_field); + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_kp_u_for_field); + __pyx_t_2 = __Pyx_PyUnicode_Unicode(__pyx_v_field_); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 619, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_t_2); + __pyx_t_2 = 0; + __Pyx_INCREF(__pyx_kp_u_at_stage); + __pyx_t_5 += 11; + __Pyx_GIVEREF(__pyx_kp_u_at_stage); + PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_kp_u_at_stage); + __pyx_t_2 = __Pyx_PyUnicode_From_int(__pyx_v_stage, 0, ' ', 'd'); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 619, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_1, 3, __pyx_t_2); + __pyx_t_2 = 0; + __Pyx_INCREF(__pyx_kp_u_with_dimension); + __pyx_t_5 += 16; + __Pyx_GIVEREF(__pyx_kp_u_with_dimension); + PyTuple_SET_ITEM(__pyx_t_1, 4, __pyx_kp_u_with_dimension); + __pyx_t_2 = __Pyx_carray_to_py_int(__pyx_v_dims, 2); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 619, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_8 = __Pyx_PySequence_Tuple(__pyx_t_2); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 619, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_FormatSimple(__pyx_t_8, __pyx_empty_unicode); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 619, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_1, 5, __pyx_t_2); + __pyx_t_2 = 0; + __Pyx_INCREF(__pyx_kp_u_you_have); + __pyx_t_5 += 11; + __Pyx_GIVEREF(__pyx_kp_u_you_have); + PyTuple_SET_ITEM(__pyx_t_1, 6, __pyx_kp_u_you_have); + __pyx_t_2 = __Pyx_PyObject_FormatSimple(__pyx_v_value_shape, __pyx_empty_unicode); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 619, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_1, 7, __pyx_t_2); + __pyx_t_2 = 0; + __Pyx_INCREF(__pyx_kp_u__7); + __pyx_t_5 += 1; + __Pyx_GIVEREF(__pyx_kp_u__7); + PyTuple_SET_ITEM(__pyx_t_1, 8, __pyx_kp_u__7); + __pyx_t_2 = __Pyx_PyUnicode_Join(__pyx_t_1, 9, __pyx_t_5, __pyx_t_6); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 619, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":618 + * + * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: + * raise Exception('AcadosOcpSolverCython.cost_set(): mismatching dimension' + # <<<<<<<<<<<<<< + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') + * + */ + __pyx_t_1 = __Pyx_PyUnicode_Concat(__pyx_kp_u_AcadosOcpSolverCython_cost_set_m, __pyx_t_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 618, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 618, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 618, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":617 + * value = np.asfortranarray(value_) + * + * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.cost_set(): mismatching dimension' + + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":622 + * + * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, \ + * self.nlp_dims, self.nlp_in, stage, field, &value[0][0]) # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_12 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_12) && PyErr_Occurred())) __PYX_ERR(0, 622, __pyx_L1_error) + if (unlikely(!__pyx_v_value.memview)) { __Pyx_RaiseUnboundLocalError("value"); __PYX_ERR(0, 622, __pyx_L1_error) } + __pyx_t_13 = 0; + __pyx_t_14 = 0; + __pyx_t_10 = -1; + if (__pyx_t_13 < 0) { + __pyx_t_13 += __pyx_v_value.shape[0]; + if (unlikely(__pyx_t_13 < 0)) __pyx_t_10 = 0; + } else if (unlikely(__pyx_t_13 >= __pyx_v_value.shape[0])) __pyx_t_10 = 0; + if (__pyx_t_14 < 0) { + __pyx_t_14 += __pyx_v_value.shape[1]; + if (unlikely(__pyx_t_14 < 0)) __pyx_t_10 = 1; + } else if (unlikely(__pyx_t_14 >= __pyx_v_value.shape[1])) __pyx_t_10 = 1; + if (unlikely(__pyx_t_10 != -1)) { + __Pyx_RaiseBufferIndexError(__pyx_t_10); + __PYX_ERR(0, 622, __pyx_L1_error) + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":621 + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') + * + * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, \ # <<<<<<<<<<<<<< + * self.nlp_dims, self.nlp_in, stage, field, &value[0][0]) + * + */ + (void)(ocp_nlp_cost_model_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_in, __pyx_v_stage, __pyx_t_12, ((void *)(&(*((double *) ( /* dim=1 */ (( /* dim=0 */ ((char *) (((double *) __pyx_v_value.data) + __pyx_t_13)) ) + __pyx_t_14 * __pyx_v_value.strides[1]) ))))))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":590 + * return + * + * def cost_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set numerical data in the cost module of the solver. + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_XDECREF(__pyx_t_9); + __PYX_XCLEAR_MEMVIEW(&__pyx_t_11, 1); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.cost_set", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_field); + __PYX_XCLEAR_MEMVIEW(&__pyx_v_value, 1); + __Pyx_XDECREF(__pyx_v_value_shape); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":625 + * + * + * def constraints_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set numerical data in the constraint module of the solver. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43constraints_set(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42constraints_set, "\n Set numerical data in the constraint module of the solver.\n\n :param stage: integer corresponding to shooting node\n :param field: string in ['lbx', 'ubx', 'lbu', 'ubu', 'lg', 'ug', 'lh', 'uh', 'uphi', 'C', 'D']\n :param value: of appropriate size\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43constraints_set = {"constraints_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43constraints_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42constraints_set}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43constraints_set(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + int __pyx_v_stage; + PyObject *__pyx_v_field_ = 0; + PyObject *__pyx_v_value_ = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("constraints_set (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_stage,&__pyx_n_s_field_2,&__pyx_n_s_value,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stage)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 625, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field_2)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 625, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("constraints_set", 1, 3, 3, 1); __PYX_ERR(0, 625, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_value)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 625, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("constraints_set", 1, 3, 3, 2); __PYX_ERR(0, 625, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "constraints_set") < 0)) __PYX_ERR(0, 625, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + } + __pyx_v_stage = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_stage == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 625, __pyx_L3_error) + __pyx_v_field_ = ((PyObject*)values[1]); + __pyx_v_value_ = values[2]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("constraints_set", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 625, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.constraints_set", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 625, __pyx_L1_error) + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42constraints_set(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_stage, __pyx_v_field_, __pyx_v_value_); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = NULL; + __pyx_L0:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42constraints_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_) { + PyObject *__pyx_v_field = NULL; + int __pyx_v_dims[2]; + __Pyx_memviewslice __pyx_v_value = { 0, 0, { 0 }, { 0 }, { 0 } }; + PyObject *__pyx_v_value_shape = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_t_3; + int __pyx_t_4; + Py_ssize_t __pyx_t_5; + Py_UCS4 __pyx_t_6; + char const *__pyx_t_7; + PyObject *__pyx_t_8 = NULL; + PyObject *__pyx_t_9 = NULL; + int __pyx_t_10; + __Pyx_memviewslice __pyx_t_11 = { 0, 0, { 0 }, { 0 }, { 0 } }; + char const *__pyx_t_12; + Py_ssize_t __pyx_t_13; + Py_ssize_t __pyx_t_14; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("constraints_set", 1); + + /* "acados_template/acados_ocp_solver_pyx.pyx":633 + * :param value: of appropriate size + * """ + * if not isinstance(value_, np.ndarray): # <<<<<<<<<<<<<< + * raise Exception(f"constraints_set: value must be numpy array, got {type(value_)}.") + * + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 633, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_ndarray); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 633, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_3 = PyObject_IsInstance(__pyx_v_value_, __pyx_t_2); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(0, 633, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_4 = (!__pyx_t_3); + if (unlikely(__pyx_t_4)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":634 + * """ + * if not isinstance(value_, np.ndarray): + * raise Exception(f"constraints_set: value must be numpy array, got {type(value_)}.") # <<<<<<<<<<<<<< + * + * field = field_.encode('utf-8') + */ + __pyx_t_2 = PyTuple_New(3); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 634, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_5 = 0; + __pyx_t_6 = 127; + __Pyx_INCREF(__pyx_kp_u_constraints_set_value_must_be_nu); + __pyx_t_5 += 48; + __Pyx_GIVEREF(__pyx_kp_u_constraints_set_value_must_be_nu); + PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_kp_u_constraints_set_value_must_be_nu); + __pyx_t_1 = __Pyx_PyObject_FormatSimple(((PyObject *)Py_TYPE(__pyx_v_value_)), __pyx_empty_unicode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 634, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_2, 1, __pyx_t_1); + __pyx_t_1 = 0; + __Pyx_INCREF(__pyx_kp_u__2); + __pyx_t_5 += 1; + __Pyx_GIVEREF(__pyx_kp_u__2); + PyTuple_SET_ITEM(__pyx_t_2, 2, __pyx_kp_u__2); + __pyx_t_1 = __Pyx_PyUnicode_Join(__pyx_t_2, 3, __pyx_t_5, __pyx_t_6); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 634, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 634, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 634, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":633 + * :param value: of appropriate size + * """ + * if not isinstance(value_, np.ndarray): # <<<<<<<<<<<<<< + * raise Exception(f"constraints_set: value must be numpy array, got {type(value_)}.") + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":636 + * raise Exception(f"constraints_set: value must be numpy array, got {type(value_)}.") + * + * field = field_.encode('utf-8') # <<<<<<<<<<<<<< + * + * cdef int dims[2] + */ + if (unlikely(__pyx_v_field_ == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); + __PYX_ERR(0, 636, __pyx_L1_error) + } + __pyx_t_2 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 636, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_v_field = __pyx_t_2; + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":640 + * cdef int dims[2] + * acados_solver_common.ocp_nlp_constraint_dims_get_from_attr(self.nlp_config, \ + * self.nlp_dims, self.nlp_out, stage, field, &dims[0]) # <<<<<<<<<<<<<< + * + * cdef double[::1,:] value + */ + __pyx_t_7 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 640, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":639 + * + * cdef int dims[2] + * acados_solver_common.ocp_nlp_constraint_dims_get_from_attr(self.nlp_config, \ # <<<<<<<<<<<<<< + * self.nlp_dims, self.nlp_out, stage, field, &dims[0]) + * + */ + ocp_nlp_constraint_dims_get_from_attr(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_7, (&(__pyx_v_dims[0]))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":644 + * cdef double[::1,:] value + * + * value_shape = value_.shape # <<<<<<<<<<<<<< + * if len(value_shape) == 1: + * value_shape = (value_shape[0], 0) + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_value_, __pyx_n_s_shape); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 644, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_v_value_shape = __pyx_t_2; + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":645 + * + * value_shape = value_.shape + * if len(value_shape) == 1: # <<<<<<<<<<<<<< + * value_shape = (value_shape[0], 0) + * value = np.asfortranarray(value_[None,:]) + */ + __pyx_t_5 = PyObject_Length(__pyx_v_value_shape); if (unlikely(__pyx_t_5 == ((Py_ssize_t)-1))) __PYX_ERR(0, 645, __pyx_L1_error) + __pyx_t_4 = (__pyx_t_5 == 1); + if (__pyx_t_4) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":646 + * value_shape = value_.shape + * if len(value_shape) == 1: + * value_shape = (value_shape[0], 0) # <<<<<<<<<<<<<< + * value = np.asfortranarray(value_[None,:]) + * + */ + __pyx_t_2 = __Pyx_GetItemInt(__pyx_v_value_shape, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 646, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_1 = PyTuple_New(2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 646, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_t_2)) __PYX_ERR(0, 646, __pyx_L1_error); + __Pyx_INCREF(__pyx_int_0); + __Pyx_GIVEREF(__pyx_int_0); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_int_0)) __PYX_ERR(0, 646, __pyx_L1_error); + __pyx_t_2 = 0; + __Pyx_DECREF_SET(__pyx_v_value_shape, __pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":647 + * if len(value_shape) == 1: + * value_shape = (value_shape[0], 0) + * value = np.asfortranarray(value_[None,:]) # <<<<<<<<<<<<<< + * + * elif len(value_shape) == 2: + */ + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_np); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 647, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_asfortranarray); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 647, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_v_value_, __pyx_tuple__28); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 647, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_9 = NULL; + __pyx_t_10 = 0; + #if CYTHON_UNPACK_METHODS + if (unlikely(PyMethod_Check(__pyx_t_8))) { + __pyx_t_9 = PyMethod_GET_SELF(__pyx_t_8); + if (likely(__pyx_t_9)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_8); + __Pyx_INCREF(__pyx_t_9); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_8, function); + __pyx_t_10 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_9, __pyx_t_2}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_8, __pyx_callargs+1-__pyx_t_10, 1+__pyx_t_10); + __Pyx_XDECREF(__pyx_t_9); __pyx_t_9 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 647, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } + __pyx_t_11 = __Pyx_PyObject_to_MemoryviewSlice_dcd__double(__pyx_t_1, PyBUF_WRITABLE); if (unlikely(!__pyx_t_11.memview)) __PYX_ERR(0, 647, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_value = __pyx_t_11; + __pyx_t_11.memview = NULL; + __pyx_t_11.data = NULL; + + /* "acados_template/acados_ocp_solver_pyx.pyx":645 + * + * value_shape = value_.shape + * if len(value_shape) == 1: # <<<<<<<<<<<<<< + * value_shape = (value_shape[0], 0) + * value = np.asfortranarray(value_[None,:]) + */ + goto __pyx_L4; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":649 + * value = np.asfortranarray(value_[None,:]) + * + * elif len(value_shape) == 2: # <<<<<<<<<<<<<< + * # Get elements in column major order + * value = np.asfortranarray(value_) + */ + __pyx_t_5 = PyObject_Length(__pyx_v_value_shape); if (unlikely(__pyx_t_5 == ((Py_ssize_t)-1))) __PYX_ERR(0, 649, __pyx_L1_error) + __pyx_t_4 = (__pyx_t_5 == 2); + if (__pyx_t_4) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":651 + * elif len(value_shape) == 2: + * # Get elements in column major order + * value = np.asfortranarray(value_) # <<<<<<<<<<<<<< + * + * if value_shape != tuple(dims): + */ + __Pyx_GetModuleGlobalName(__pyx_t_8, __pyx_n_s_np); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 651, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_8, __pyx_n_s_asfortranarray); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 651, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_t_8 = NULL; + __pyx_t_10 = 0; + #if CYTHON_UNPACK_METHODS + if (unlikely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_8 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_8)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_8); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_10 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_8, __pyx_v_value_}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_10, 1+__pyx_t_10); + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 651, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_t_11 = __Pyx_PyObject_to_MemoryviewSlice_dcd__double(__pyx_t_1, PyBUF_WRITABLE); if (unlikely(!__pyx_t_11.memview)) __PYX_ERR(0, 651, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_value = __pyx_t_11; + __pyx_t_11.memview = NULL; + __pyx_t_11.data = NULL; + + /* "acados_template/acados_ocp_solver_pyx.pyx":649 + * value = np.asfortranarray(value_[None,:]) + * + * elif len(value_shape) == 2: # <<<<<<<<<<<<<< + * # Get elements in column major order + * value = np.asfortranarray(value_) + */ + } + __pyx_L4:; + + /* "acados_template/acados_ocp_solver_pyx.pyx":653 + * value = np.asfortranarray(value_) + * + * if value_shape != tuple(dims): # <<<<<<<<<<<<<< + * raise Exception(f'AcadosOcpSolverCython.constraints_set(): mismatching dimension' + + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') + */ + __pyx_t_1 = __Pyx_carray_to_py_int(__pyx_v_dims, 2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 653, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PySequence_Tuple(__pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 653, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = PyObject_RichCompare(__pyx_v_value_shape, __pyx_t_2, Py_NE); __Pyx_XGOTREF(__pyx_t_1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 653, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_t_1); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 653, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(__pyx_t_4)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":655 + * if value_shape != tuple(dims): + * raise Exception(f'AcadosOcpSolverCython.constraints_set(): mismatching dimension' + + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') # <<<<<<<<<<<<<< + * + * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, \ + */ + __pyx_t_1 = PyTuple_New(9); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 655, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = 0; + __pyx_t_6 = 127; + __Pyx_INCREF(__pyx_kp_u_for_field); + __pyx_t_5 += 12; + __Pyx_GIVEREF(__pyx_kp_u_for_field); + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_kp_u_for_field); + __pyx_t_2 = __Pyx_PyUnicode_Unicode(__pyx_v_field_); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 655, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_t_2); + __pyx_t_2 = 0; + __Pyx_INCREF(__pyx_kp_u_at_stage); + __pyx_t_5 += 11; + __Pyx_GIVEREF(__pyx_kp_u_at_stage); + PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_kp_u_at_stage); + __pyx_t_2 = __Pyx_PyUnicode_From_int(__pyx_v_stage, 0, ' ', 'd'); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 655, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_1, 3, __pyx_t_2); + __pyx_t_2 = 0; + __Pyx_INCREF(__pyx_kp_u_with_dimension); + __pyx_t_5 += 16; + __Pyx_GIVEREF(__pyx_kp_u_with_dimension); + PyTuple_SET_ITEM(__pyx_t_1, 4, __pyx_kp_u_with_dimension); + __pyx_t_2 = __Pyx_carray_to_py_int(__pyx_v_dims, 2); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 655, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_8 = __Pyx_PySequence_Tuple(__pyx_t_2); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 655, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_FormatSimple(__pyx_t_8, __pyx_empty_unicode); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 655, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_1, 5, __pyx_t_2); + __pyx_t_2 = 0; + __Pyx_INCREF(__pyx_kp_u_you_have); + __pyx_t_5 += 11; + __Pyx_GIVEREF(__pyx_kp_u_you_have); + PyTuple_SET_ITEM(__pyx_t_1, 6, __pyx_kp_u_you_have); + __pyx_t_2 = __Pyx_PyObject_FormatSimple(__pyx_v_value_shape, __pyx_empty_unicode); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 655, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_1, 7, __pyx_t_2); + __pyx_t_2 = 0; + __Pyx_INCREF(__pyx_kp_u__7); + __pyx_t_5 += 1; + __Pyx_GIVEREF(__pyx_kp_u__7); + PyTuple_SET_ITEM(__pyx_t_1, 8, __pyx_kp_u__7); + __pyx_t_2 = __Pyx_PyUnicode_Join(__pyx_t_1, 9, __pyx_t_5, __pyx_t_6); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 655, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":654 + * + * if value_shape != tuple(dims): + * raise Exception(f'AcadosOcpSolverCython.constraints_set(): mismatching dimension' + # <<<<<<<<<<<<<< + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') + * + */ + __pyx_t_1 = __Pyx_PyUnicode_Concat(__pyx_kp_u_AcadosOcpSolverCython_constraint, __pyx_t_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 654, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 654, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 654, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":653 + * value = np.asfortranarray(value_) + * + * if value_shape != tuple(dims): # <<<<<<<<<<<<<< + * raise Exception(f'AcadosOcpSolverCython.constraints_set(): mismatching dimension' + + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":658 + * + * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, \ + * self.nlp_dims, self.nlp_in, stage, field, &value[0][0]) # <<<<<<<<<<<<<< + * + * return + */ + __pyx_t_12 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_12) && PyErr_Occurred())) __PYX_ERR(0, 658, __pyx_L1_error) + if (unlikely(!__pyx_v_value.memview)) { __Pyx_RaiseUnboundLocalError("value"); __PYX_ERR(0, 658, __pyx_L1_error) } + __pyx_t_13 = 0; + __pyx_t_14 = 0; + __pyx_t_10 = -1; + if (__pyx_t_13 < 0) { + __pyx_t_13 += __pyx_v_value.shape[0]; + if (unlikely(__pyx_t_13 < 0)) __pyx_t_10 = 0; + } else if (unlikely(__pyx_t_13 >= __pyx_v_value.shape[0])) __pyx_t_10 = 0; + if (__pyx_t_14 < 0) { + __pyx_t_14 += __pyx_v_value.shape[1]; + if (unlikely(__pyx_t_14 < 0)) __pyx_t_10 = 1; + } else if (unlikely(__pyx_t_14 >= __pyx_v_value.shape[1])) __pyx_t_10 = 1; + if (unlikely(__pyx_t_10 != -1)) { + __Pyx_RaiseBufferIndexError(__pyx_t_10); + __PYX_ERR(0, 658, __pyx_L1_error) + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":657 + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') + * + * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, \ # <<<<<<<<<<<<<< + * self.nlp_dims, self.nlp_in, stage, field, &value[0][0]) + * + */ + (void)(ocp_nlp_constraints_model_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_in, __pyx_v_stage, __pyx_t_12, ((void *)(&(*((double *) ( /* dim=1 */ (( /* dim=0 */ ((char *) (((double *) __pyx_v_value.data) + __pyx_t_13)) ) + __pyx_t_14 * __pyx_v_value.strides[1]) ))))))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":660 + * self.nlp_dims, self.nlp_in, stage, field, &value[0][0]) + * + * return # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":625 + * + * + * def constraints_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set numerical data in the constraint module of the solver. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_XDECREF(__pyx_t_9); + __PYX_XCLEAR_MEMVIEW(&__pyx_t_11, 1); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.constraints_set", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_field); + __PYX_XCLEAR_MEMVIEW(&__pyx_v_value, 1); + __Pyx_XDECREF(__pyx_v_value_shape); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":663 + * + * + * def get_from_qp_in(self, int stage, str field_): # <<<<<<<<<<<<<< + * """ + * Get numerical data from the dynamics module of the solver: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_45get_from_qp_in(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_44get_from_qp_in, "\n Get numerical data from the dynamics module of the solver:\n\n :param stage: integer corresponding to shooting node\n :param field: string, e.g. 'A'\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_45get_from_qp_in = {"get_from_qp_in", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_45get_from_qp_in, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_44get_from_qp_in}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_45get_from_qp_in(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + int __pyx_v_stage; + PyObject *__pyx_v_field_ = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[2] = {0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("get_from_qp_in (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_stage,&__pyx_n_s_field_2,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stage)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 663, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field_2)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 663, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("get_from_qp_in", 1, 2, 2, 1); __PYX_ERR(0, 663, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "get_from_qp_in") < 0)) __PYX_ERR(0, 663, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 2)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + } + __pyx_v_stage = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_stage == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 663, __pyx_L3_error) + __pyx_v_field_ = ((PyObject*)values[1]); + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("get_from_qp_in", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 663, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.get_from_qp_in", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 663, __pyx_L1_error) + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_44get_from_qp_in(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_stage, __pyx_v_field_); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = NULL; + __pyx_L0:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_44get_from_qp_in(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_) { + PyObject *__pyx_v_field = NULL; + int __pyx_v_dims[2]; + PyArrayObject *__pyx_v_out = 0; + __Pyx_LocalBuf_ND __pyx_pybuffernd_out; + __Pyx_Buffer __pyx_pybuffer_out; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + char const *__pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyArrayObject *__pyx_t_6 = NULL; + char const *__pyx_t_7; + char *__pyx_t_8; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_from_qp_in", 1); + __pyx_pybuffer_out.pybuffer.buf = NULL; + __pyx_pybuffer_out.refcount = 0; + __pyx_pybuffernd_out.data = NULL; + __pyx_pybuffernd_out.rcbuffer = &__pyx_pybuffer_out; + + /* "acados_template/acados_ocp_solver_pyx.pyx":670 + * :param field: string, e.g. 'A' + * """ + * field = field_.encode('utf-8') # <<<<<<<<<<<<<< + * + * # get dims + */ + if (unlikely(__pyx_v_field_ == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); + __PYX_ERR(0, 670, __pyx_L1_error) + } + __pyx_t_1 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 670, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_field = __pyx_t_1; + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":674 + * # get dims + * cdef int[2] dims + * acados_solver_common.ocp_nlp_qp_dims_get_from_attr(self.nlp_config, self.nlp_dims, self.nlp_out, stage, field, &dims[0]) # <<<<<<<<<<<<<< + * + * # create output data + */ + __pyx_t_2 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_2) && PyErr_Occurred())) __PYX_ERR(0, 674, __pyx_L1_error) + ocp_nlp_qp_dims_get_from_attr(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_2, (&(__pyx_v_dims[0]))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":677 + * + * # create output data + * cdef cnp.ndarray[cnp.float64_t, ndim=2] out = np.zeros((dims[0], dims[1]), order='F') # <<<<<<<<<<<<<< + * + * # call getter + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 677, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_zeros); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 677, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyInt_From_int((__pyx_v_dims[0])); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 677, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_4 = __Pyx_PyInt_From_int((__pyx_v_dims[1])); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 677, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = PyTuple_New(2); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 677, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_t_1)) __PYX_ERR(0, 677, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_4); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_4)) __PYX_ERR(0, 677, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_4 = 0; + __pyx_t_4 = PyTuple_New(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 677, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_5); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_5)) __PYX_ERR(0, 677, __pyx_L1_error); + __pyx_t_5 = 0; + __pyx_t_5 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 677, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + if (PyDict_SetItem(__pyx_t_5, __pyx_n_s_order, __pyx_n_u_F) < 0) __PYX_ERR(0, 677, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_Call(__pyx_t_3, __pyx_t_4, __pyx_t_5); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 677, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (!(likely(((__pyx_t_1) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_1, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 677, __pyx_L1_error) + __pyx_t_6 = ((PyArrayObject *)__pyx_t_1); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_out.rcbuffer->pybuffer, (PyObject*)__pyx_t_6, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 2, 0, __pyx_stack) == -1)) { + __pyx_v_out = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_out.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 677, __pyx_L1_error) + } else {__pyx_pybuffernd_out.diminfo[0].strides = __pyx_pybuffernd_out.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_out.diminfo[0].shape = __pyx_pybuffernd_out.rcbuffer->pybuffer.shape[0]; __pyx_pybuffernd_out.diminfo[1].strides = __pyx_pybuffernd_out.rcbuffer->pybuffer.strides[1]; __pyx_pybuffernd_out.diminfo[1].shape = __pyx_pybuffernd_out.rcbuffer->pybuffer.shape[1]; + } + } + __pyx_t_6 = 0; + __pyx_v_out = ((PyArrayObject *)__pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":680 + * + * # call getter + * acados_solver_common.ocp_nlp_get_at_stage(self.nlp_config, self.nlp_dims, self.nlp_solver, stage, field, out.data) # <<<<<<<<<<<<<< + * + * return out + */ + __pyx_t_7 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 680, __pyx_L1_error) + __pyx_t_8 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_out)); if (unlikely(__pyx_t_8 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 680, __pyx_L1_error) + ocp_nlp_get_at_stage(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_solver, __pyx_v_stage, __pyx_t_7, ((void *)__pyx_t_8)); + + /* "acados_template/acados_ocp_solver_pyx.pyx":682 + * acados_solver_common.ocp_nlp_get_at_stage(self.nlp_config, self.nlp_dims, self.nlp_solver, stage, field, out.data) + * + * return out # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_out); + __pyx_r = ((PyObject *)__pyx_v_out); + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":663 + * + * + * def get_from_qp_in(self, int stage, str field_): # <<<<<<<<<<<<<< + * """ + * Get numerical data from the dynamics module of the solver: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_out.rcbuffer->pybuffer); + __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.get_from_qp_in", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + goto __pyx_L2; + __pyx_L0:; + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_out.rcbuffer->pybuffer); + __pyx_L2:; + __Pyx_XDECREF(__pyx_v_field); + __Pyx_XDECREF((PyObject *)__pyx_v_out); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":685 + * + * + * def options_set(self, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set options of the solver. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47options_set(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_46options_set, "\n Set options of the solver.\n\n :param field: string, e.g. 'print_level', 'rti_phase', 'initialize_t_slacks', 'step_length', 'alpha_min', 'alpha_reduction', 'qp_warm_start', 'line_search_use_sufficient_descent', 'full_step_dual', 'globalization_use_SOC', 'qp_tol_stat', 'qp_tol_eq', 'qp_tol_ineq', 'qp_tol_comp', 'qp_tau_min', 'qp_mu0'\n\n :param value: of type int, float, string\n\n - qp_tol_stat: QP solver tolerance stationarity\n - qp_tol_eq: QP solver tolerance equalities\n - qp_tol_ineq: QP solver tolerance inequalities\n - qp_tol_comp: QP solver tolerance complementarity\n - qp_tau_min: for HPIPM QP solvers: minimum value of barrier parameter in HPIPM\n - qp_mu0: for HPIPM QP solvers: initial value for complementarity slackness\n - warm_start_first_qp: indicates if first QP in SQP is warm_started\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47options_set = {"options_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47options_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_46options_set}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47options_set(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_field_ = 0; + PyObject *__pyx_v_value_ = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[2] = {0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("options_set (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_field_2,&__pyx_n_s_value,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field_2)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 685, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_value)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 685, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("options_set", 1, 2, 2, 1); __PYX_ERR(0, 685, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "options_set") < 0)) __PYX_ERR(0, 685, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 2)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + } + __pyx_v_field_ = ((PyObject*)values[0]); + __pyx_v_value_ = values[1]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("options_set", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 685, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.options_set", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 685, __pyx_L1_error) + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_46options_set(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_field_, __pyx_v_value_); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = NULL; + __pyx_L0:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_46options_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_) { + PyObject *__pyx_v_int_fields = NULL; + PyObject *__pyx_v_double_fields = NULL; + PyObject *__pyx_v_string_fields = NULL; + PyObject *__pyx_v_field = NULL; + int __pyx_v_int_value; + double __pyx_v_double_value; + __Pyx_memviewslice __pyx_v_string_value = { 0, 0, { 0 }, { 0 }, { 0 } }; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + int __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + char const *__pyx_t_7; + double __pyx_t_8; + __Pyx_memviewslice __pyx_t_9 = { 0, 0, { 0 }, { 0 }, { 0 } }; + Py_ssize_t __pyx_t_10; + PyObject *__pyx_t_11 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("options_set", 1); + + /* "acados_template/acados_ocp_solver_pyx.pyx":701 + * - warm_start_first_qp: indicates if first QP in SQP is warm_started + * """ + * int_fields = ['print_level', 'rti_phase', 'initialize_t_slacks', 'qp_warm_start', 'line_search_use_sufficient_descent', 'full_step_dual', 'globalization_use_SOC', 'warm_start_first_qp'] # <<<<<<<<<<<<<< + * double_fields = ['step_length', 'tol_eq', 'tol_stat', 'tol_ineq', 'tol_comp', 'alpha_min', 'alpha_reduction', 'eps_sufficient_descent', + * 'qp_tol_stat', 'qp_tol_eq', 'qp_tol_ineq', 'qp_tol_comp', 'qp_tau_min', 'qp_mu0'] + */ + __pyx_t_1 = PyList_New(8); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 701, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_u_print_level); + __Pyx_GIVEREF(__pyx_n_u_print_level); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_u_print_level)) __PYX_ERR(0, 701, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_rti_phase); + __Pyx_GIVEREF(__pyx_n_u_rti_phase); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 1, __pyx_n_u_rti_phase)) __PYX_ERR(0, 701, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_initialize_t_slacks); + __Pyx_GIVEREF(__pyx_n_u_initialize_t_slacks); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 2, __pyx_n_u_initialize_t_slacks)) __PYX_ERR(0, 701, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_qp_warm_start); + __Pyx_GIVEREF(__pyx_n_u_qp_warm_start); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 3, __pyx_n_u_qp_warm_start)) __PYX_ERR(0, 701, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_line_search_use_sufficient_desce); + __Pyx_GIVEREF(__pyx_n_u_line_search_use_sufficient_desce); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 4, __pyx_n_u_line_search_use_sufficient_desce)) __PYX_ERR(0, 701, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_full_step_dual); + __Pyx_GIVEREF(__pyx_n_u_full_step_dual); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 5, __pyx_n_u_full_step_dual)) __PYX_ERR(0, 701, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_globalization_use_SOC); + __Pyx_GIVEREF(__pyx_n_u_globalization_use_SOC); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 6, __pyx_n_u_globalization_use_SOC)) __PYX_ERR(0, 701, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_warm_start_first_qp); + __Pyx_GIVEREF(__pyx_n_u_warm_start_first_qp); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 7, __pyx_n_u_warm_start_first_qp)) __PYX_ERR(0, 701, __pyx_L1_error); + __pyx_v_int_fields = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":702 + * """ + * int_fields = ['print_level', 'rti_phase', 'initialize_t_slacks', 'qp_warm_start', 'line_search_use_sufficient_descent', 'full_step_dual', 'globalization_use_SOC', 'warm_start_first_qp'] + * double_fields = ['step_length', 'tol_eq', 'tol_stat', 'tol_ineq', 'tol_comp', 'alpha_min', 'alpha_reduction', 'eps_sufficient_descent', # <<<<<<<<<<<<<< + * 'qp_tol_stat', 'qp_tol_eq', 'qp_tol_ineq', 'qp_tol_comp', 'qp_tau_min', 'qp_mu0'] + * string_fields = ['globalization'] + */ + __pyx_t_1 = PyList_New(14); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 702, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_u_step_length); + __Pyx_GIVEREF(__pyx_n_u_step_length); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_u_step_length)) __PYX_ERR(0, 702, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_tol_eq); + __Pyx_GIVEREF(__pyx_n_u_tol_eq); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 1, __pyx_n_u_tol_eq)) __PYX_ERR(0, 702, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_tol_stat); + __Pyx_GIVEREF(__pyx_n_u_tol_stat); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 2, __pyx_n_u_tol_stat)) __PYX_ERR(0, 702, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_tol_ineq); + __Pyx_GIVEREF(__pyx_n_u_tol_ineq); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 3, __pyx_n_u_tol_ineq)) __PYX_ERR(0, 702, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_tol_comp); + __Pyx_GIVEREF(__pyx_n_u_tol_comp); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 4, __pyx_n_u_tol_comp)) __PYX_ERR(0, 702, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_alpha_min); + __Pyx_GIVEREF(__pyx_n_u_alpha_min); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 5, __pyx_n_u_alpha_min)) __PYX_ERR(0, 702, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_alpha_reduction); + __Pyx_GIVEREF(__pyx_n_u_alpha_reduction); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 6, __pyx_n_u_alpha_reduction)) __PYX_ERR(0, 702, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_eps_sufficient_descent); + __Pyx_GIVEREF(__pyx_n_u_eps_sufficient_descent); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 7, __pyx_n_u_eps_sufficient_descent)) __PYX_ERR(0, 702, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_qp_tol_stat); + __Pyx_GIVEREF(__pyx_n_u_qp_tol_stat); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 8, __pyx_n_u_qp_tol_stat)) __PYX_ERR(0, 702, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_qp_tol_eq); + __Pyx_GIVEREF(__pyx_n_u_qp_tol_eq); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 9, __pyx_n_u_qp_tol_eq)) __PYX_ERR(0, 702, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_qp_tol_ineq); + __Pyx_GIVEREF(__pyx_n_u_qp_tol_ineq); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 10, __pyx_n_u_qp_tol_ineq)) __PYX_ERR(0, 702, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_qp_tol_comp); + __Pyx_GIVEREF(__pyx_n_u_qp_tol_comp); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 11, __pyx_n_u_qp_tol_comp)) __PYX_ERR(0, 702, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_qp_tau_min); + __Pyx_GIVEREF(__pyx_n_u_qp_tau_min); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 12, __pyx_n_u_qp_tau_min)) __PYX_ERR(0, 702, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_qp_mu0); + __Pyx_GIVEREF(__pyx_n_u_qp_mu0); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 13, __pyx_n_u_qp_mu0)) __PYX_ERR(0, 702, __pyx_L1_error); + __pyx_v_double_fields = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":704 + * double_fields = ['step_length', 'tol_eq', 'tol_stat', 'tol_ineq', 'tol_comp', 'alpha_min', 'alpha_reduction', 'eps_sufficient_descent', + * 'qp_tol_stat', 'qp_tol_eq', 'qp_tol_ineq', 'qp_tol_comp', 'qp_tau_min', 'qp_mu0'] + * string_fields = ['globalization'] # <<<<<<<<<<<<<< + * + * # encode + */ + __pyx_t_1 = PyList_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 704, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_u_globalization); + __Pyx_GIVEREF(__pyx_n_u_globalization); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_u_globalization)) __PYX_ERR(0, 704, __pyx_L1_error); + __pyx_v_string_fields = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":707 + * + * # encode + * field = field_.encode('utf-8') # <<<<<<<<<<<<<< + * + * cdef int int_value + */ + if (unlikely(__pyx_v_field_ == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); + __PYX_ERR(0, 707, __pyx_L1_error) + } + __pyx_t_1 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 707, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_field = __pyx_t_1; + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":714 + * + * # check field availability and type + * if field_ in int_fields: # <<<<<<<<<<<<<< + * if not isinstance(value_, int): + * raise Exception('solver option {} must be of type int. You have {}.'.format(field_, type(value_))) + */ + __pyx_t_2 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_int_fields, Py_EQ)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 714, __pyx_L1_error) + if (__pyx_t_2) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":715 + * # check field availability and type + * if field_ in int_fields: + * if not isinstance(value_, int): # <<<<<<<<<<<<<< + * raise Exception('solver option {} must be of type int. You have {}.'.format(field_, type(value_))) + * + */ + __pyx_t_2 = PyInt_Check(__pyx_v_value_); + __pyx_t_3 = (!__pyx_t_2); + if (unlikely(__pyx_t_3)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":716 + * if field_ in int_fields: + * if not isinstance(value_, int): + * raise Exception('solver option {} must be of type int. You have {}.'.format(field_, type(value_))) # <<<<<<<<<<<<<< + * + * if field_ == 'rti_phase': + */ + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_solver_option_must_be_of_type_in, __pyx_n_s_format); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 716, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_4))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_4); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_4); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_4, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_v_field_, ((PyObject *)Py_TYPE(__pyx_v_value_))}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 716, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + __pyx_t_4 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 716, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_t_4, 0, 0, 0); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __PYX_ERR(0, 716, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":715 + * # check field availability and type + * if field_ in int_fields: + * if not isinstance(value_, int): # <<<<<<<<<<<<<< + * raise Exception('solver option {} must be of type int. You have {}.'.format(field_, type(value_))) + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":718 + * raise Exception('solver option {} must be of type int. You have {}.'.format(field_, type(value_))) + * + * if field_ == 'rti_phase': # <<<<<<<<<<<<<< + * if value_ < 0 or value_ > 2: + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' + */ + __pyx_t_3 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_rti_phase, Py_EQ)); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(0, 718, __pyx_L1_error) + if (__pyx_t_3) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":719 + * + * if field_ == 'rti_phase': + * if value_ < 0 or value_ > 2: # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' + * 'take only values 0, 1, 2 for SQP-RTI-type solvers') + */ + __pyx_t_4 = PyObject_RichCompare(__pyx_v_value_, __pyx_int_0, Py_LT); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 719, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 719, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (!__pyx_t_2) { + } else { + __pyx_t_3 = __pyx_t_2; + goto __pyx_L7_bool_binop_done; + } + __pyx_t_4 = PyObject_RichCompare(__pyx_v_value_, __pyx_int_2, Py_GT); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 719, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 719, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_3 = __pyx_t_2; + __pyx_L7_bool_binop_done:; + if (unlikely(__pyx_t_3)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":720 + * if field_ == 'rti_phase': + * if value_ < 0 or value_ > 2: + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' # <<<<<<<<<<<<<< + * 'take only values 0, 1, 2 for SQP-RTI-type solvers') + * if self.nlp_solver_type != 'SQP_RTI' and value_ > 0: + */ + __pyx_t_4 = __Pyx_PyObject_Call(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_tuple__29, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 720, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_Raise(__pyx_t_4, 0, 0, 0); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __PYX_ERR(0, 720, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":719 + * + * if field_ == 'rti_phase': + * if value_ < 0 or value_ > 2: # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' + * 'take only values 0, 1, 2 for SQP-RTI-type solvers') + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":722 + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' + * 'take only values 0, 1, 2 for SQP-RTI-type solvers') + * if self.nlp_solver_type != 'SQP_RTI' and value_ > 0: # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' + * 'take only value 0 for SQP-type solvers') + */ + __pyx_t_2 = (__Pyx_PyUnicode_Equals(__pyx_v_self->nlp_solver_type, __pyx_n_u_SQP_RTI, Py_NE)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 722, __pyx_L1_error) + if (__pyx_t_2) { + } else { + __pyx_t_3 = __pyx_t_2; + goto __pyx_L10_bool_binop_done; + } + __pyx_t_4 = PyObject_RichCompare(__pyx_v_value_, __pyx_int_0, Py_GT); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 722, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 722, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_3 = __pyx_t_2; + __pyx_L10_bool_binop_done:; + if (unlikely(__pyx_t_3)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":723 + * 'take only values 0, 1, 2 for SQP-RTI-type solvers') + * if self.nlp_solver_type != 'SQP_RTI' and value_ > 0: + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' # <<<<<<<<<<<<<< + * 'take only value 0 for SQP-type solvers') + * + */ + __pyx_t_4 = __Pyx_PyObject_Call(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_tuple__30, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 723, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_Raise(__pyx_t_4, 0, 0, 0); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __PYX_ERR(0, 723, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":722 + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' + * 'take only values 0, 1, 2 for SQP-RTI-type solvers') + * if self.nlp_solver_type != 'SQP_RTI' and value_ > 0: # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' + * 'take only value 0 for SQP-type solvers') + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":718 + * raise Exception('solver option {} must be of type int. You have {}.'.format(field_, type(value_))) + * + * if field_ == 'rti_phase': # <<<<<<<<<<<<<< + * if value_ < 0 or value_ > 2: + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":726 + * 'take only value 0 for SQP-type solvers') + * + * int_value = value_ # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &int_value) + * + */ + __pyx_t_6 = __Pyx_PyInt_As_int(__pyx_v_value_); if (unlikely((__pyx_t_6 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 726, __pyx_L1_error) + __pyx_v_int_value = __pyx_t_6; + + /* "acados_template/acados_ocp_solver_pyx.pyx":727 + * + * int_value = value_ + * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &int_value) # <<<<<<<<<<<<<< + * + * elif field_ in double_fields: + */ + __pyx_t_7 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 727, __pyx_L1_error) + ocp_nlp_solver_opts_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_opts, __pyx_t_7, ((void *)(&__pyx_v_int_value))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":714 + * + * # check field availability and type + * if field_ in int_fields: # <<<<<<<<<<<<<< + * if not isinstance(value_, int): + * raise Exception('solver option {} must be of type int. You have {}.'.format(field_, type(value_))) + */ + goto __pyx_L3; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":729 + * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &int_value) + * + * elif field_ in double_fields: # <<<<<<<<<<<<<< + * if not isinstance(value_, float): + * raise Exception('solver option {} must be of type float. You have {}.'.format(field_, type(value_))) + */ + __pyx_t_3 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_double_fields, Py_EQ)); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(0, 729, __pyx_L1_error) + if (__pyx_t_3) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":730 + * + * elif field_ in double_fields: + * if not isinstance(value_, float): # <<<<<<<<<<<<<< + * raise Exception('solver option {} must be of type float. You have {}.'.format(field_, type(value_))) + * + */ + __pyx_t_3 = PyFloat_Check(__pyx_v_value_); + __pyx_t_2 = (!__pyx_t_3); + if (unlikely(__pyx_t_2)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":731 + * elif field_ in double_fields: + * if not isinstance(value_, float): + * raise Exception('solver option {} must be of type float. You have {}.'.format(field_, type(value_))) # <<<<<<<<<<<<<< + * + * double_value = value_ + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_solver_option_must_be_of_type_fl, __pyx_n_s_format); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 731, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_v_field_, ((PyObject *)Py_TYPE(__pyx_v_value_))}; + __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 731, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_4); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 731, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 731, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":730 + * + * elif field_ in double_fields: + * if not isinstance(value_, float): # <<<<<<<<<<<<<< + * raise Exception('solver option {} must be of type float. You have {}.'.format(field_, type(value_))) + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":733 + * raise Exception('solver option {} must be of type float. You have {}.'.format(field_, type(value_))) + * + * double_value = value_ # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &double_value) + * + */ + __pyx_t_8 = __pyx_PyFloat_AsDouble(__pyx_v_value_); if (unlikely((__pyx_t_8 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 733, __pyx_L1_error) + __pyx_v_double_value = __pyx_t_8; + + /* "acados_template/acados_ocp_solver_pyx.pyx":734 + * + * double_value = value_ + * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &double_value) # <<<<<<<<<<<<<< + * + * elif field_ in string_fields: + */ + __pyx_t_7 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 734, __pyx_L1_error) + ocp_nlp_solver_opts_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_opts, __pyx_t_7, ((void *)(&__pyx_v_double_value))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":729 + * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &int_value) + * + * elif field_ in double_fields: # <<<<<<<<<<<<<< + * if not isinstance(value_, float): + * raise Exception('solver option {} must be of type float. You have {}.'.format(field_, type(value_))) + */ + goto __pyx_L3; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":736 + * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &double_value) + * + * elif field_ in string_fields: # <<<<<<<<<<<<<< + * if not isinstance(value_, bytes): + * raise Exception('solver option {} must be of type str. You have {}.'.format(field_, type(value_))) + */ + __pyx_t_2 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_string_fields, Py_EQ)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 736, __pyx_L1_error) + if (likely(__pyx_t_2)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":737 + * + * elif field_ in string_fields: + * if not isinstance(value_, bytes): # <<<<<<<<<<<<<< + * raise Exception('solver option {} must be of type str. You have {}.'.format(field_, type(value_))) + * + */ + __pyx_t_2 = PyBytes_Check(__pyx_v_value_); + __pyx_t_3 = (!__pyx_t_2); + if (unlikely(__pyx_t_3)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":738 + * elif field_ in string_fields: + * if not isinstance(value_, bytes): + * raise Exception('solver option {} must be of type str. You have {}.'.format(field_, type(value_))) # <<<<<<<<<<<<<< + * + * string_value = value_.encode('utf-8') + */ + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_solver_option_must_be_of_type_st, __pyx_n_s_format); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 738, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_4))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_4); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_4); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_4, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_v_field_, ((PyObject *)Py_TYPE(__pyx_v_value_))}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 738, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + __pyx_t_4 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 738, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_t_4, 0, 0, 0); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __PYX_ERR(0, 738, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":737 + * + * elif field_ in string_fields: + * if not isinstance(value_, bytes): # <<<<<<<<<<<<<< + * raise Exception('solver option {} must be of type str. You have {}.'.format(field_, type(value_))) + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":740 + * raise Exception('solver option {} must be of type str. You have {}.'.format(field_, type(value_))) + * + * string_value = value_.encode('utf-8') # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &string_value[0]) + * + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_value_, __pyx_n_s_encode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 740, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_5, __pyx_kp_u_utf_8}; + __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 1+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 740, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_9 = __Pyx_PyObject_to_MemoryviewSlice_dc_unsigned_char(__pyx_t_4, PyBUF_WRITABLE); if (unlikely(!__pyx_t_9.memview)) __PYX_ERR(0, 740, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_v_string_value = __pyx_t_9; + __pyx_t_9.memview = NULL; + __pyx_t_9.data = NULL; + + /* "acados_template/acados_ocp_solver_pyx.pyx":741 + * + * string_value = value_.encode('utf-8') + * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &string_value[0]) # <<<<<<<<<<<<<< + * + * else: + */ + __pyx_t_7 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 741, __pyx_L1_error) + __pyx_t_10 = 0; + __pyx_t_6 = -1; + if (__pyx_t_10 < 0) { + __pyx_t_10 += __pyx_v_string_value.shape[0]; + if (unlikely(__pyx_t_10 < 0)) __pyx_t_6 = 0; + } else if (unlikely(__pyx_t_10 >= __pyx_v_string_value.shape[0])) __pyx_t_6 = 0; + if (unlikely(__pyx_t_6 != -1)) { + __Pyx_RaiseBufferIndexError(__pyx_t_6); + __PYX_ERR(0, 741, __pyx_L1_error) + } + ocp_nlp_solver_opts_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_opts, __pyx_t_7, ((void *)(&(*((unsigned char *) ( /* dim=0 */ ((char *) (((unsigned char *) __pyx_v_string_value.data) + __pyx_t_10)) )))))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":736 + * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &double_value) + * + * elif field_ in string_fields: # <<<<<<<<<<<<<< + * if not isinstance(value_, bytes): + * raise Exception('solver option {} must be of type str. You have {}.'.format(field_, type(value_))) + */ + goto __pyx_L3; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":744 + * + * else: + * raise Exception('AcadosOcpSolverCython.options_set() does not support field {}.'\ # <<<<<<<<<<<<<< + * '\n Possible values are {}.'.format(field_, ', '.join(int_fields + double_fields + string_fields))) + * + */ + /*else*/ { + + /* "acados_template/acados_ocp_solver_pyx.pyx":745 + * else: + * raise Exception('AcadosOcpSolverCython.options_set() does not support field {}.'\ + * '\n Possible values are {}.'.format(field_, ', '.join(int_fields + double_fields + string_fields))) # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_options_se, __pyx_n_s_format); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 745, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = PyNumber_Add(__pyx_v_int_fields, __pyx_v_double_fields); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 745, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_11 = PyNumber_Add(__pyx_t_5, __pyx_v_string_fields); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 745, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_11); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_5 = PyUnicode_Join(__pyx_kp_u__31, __pyx_t_11); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 745, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; + __pyx_t_11 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_11 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_11)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_11); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_11, __pyx_v_field_, __pyx_t_5}; + __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_11); __pyx_t_11 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 745, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":744 + * + * else: + * raise Exception('AcadosOcpSolverCython.options_set() does not support field {}.'\ # <<<<<<<<<<<<<< + * '\n Possible values are {}.'.format(field_, ', '.join(int_fields + double_fields + string_fields))) + * + */ + __pyx_t_1 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_4); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 744, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 744, __pyx_L1_error) + } + __pyx_L3:; + + /* "acados_template/acados_ocp_solver_pyx.pyx":685 + * + * + * def options_set(self, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set options of the solver. + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __PYX_XCLEAR_MEMVIEW(&__pyx_t_9, 1); + __Pyx_XDECREF(__pyx_t_11); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.options_set", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_int_fields); + __Pyx_XDECREF(__pyx_v_double_fields); + __Pyx_XDECREF(__pyx_v_string_fields); + __Pyx_XDECREF(__pyx_v_field); + __PYX_XCLEAR_MEMVIEW(&__pyx_v_string_value, 1); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":748 + * + * + * def set_params_sparse(self, int stage, idx_values_, param_values_): # <<<<<<<<<<<<<< + * """ + * set parameters of the solvers external function partially: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49set_params_sparse(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_48set_params_sparse, "\n set parameters of the solvers external function partially:\n Pseudo: solver.param[idx_values_] = param_values_;\n Parameters:\n :param stage_: integer corresponding to shooting node\n :param idx_values_: 0 based integer array corresponding to parameter indices to be set\n :param param_values_: new parameter values as numpy array\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49set_params_sparse = {"set_params_sparse", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49set_params_sparse, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_48set_params_sparse}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49set_params_sparse(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + int __pyx_v_stage; + PyObject *__pyx_v_idx_values_ = 0; + PyObject *__pyx_v_param_values_ = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("set_params_sparse (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_stage,&__pyx_n_s_idx_values,&__pyx_n_s_param_values,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stage)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 748, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_idx_values)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 748, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("set_params_sparse", 1, 3, 3, 1); __PYX_ERR(0, 748, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_param_values)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 748, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("set_params_sparse", 1, 3, 3, 2); __PYX_ERR(0, 748, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "set_params_sparse") < 0)) __PYX_ERR(0, 748, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + } + __pyx_v_stage = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_stage == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 748, __pyx_L3_error) + __pyx_v_idx_values_ = values[1]; + __pyx_v_param_values_ = values[2]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("set_params_sparse", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 748, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.set_params_sparse", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_48set_params_sparse(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_stage, __pyx_v_idx_values_, __pyx_v_param_values_); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_48set_params_sparse(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_idx_values_, PyObject *__pyx_v_param_values_) { + PyArrayObject *__pyx_v_value = 0; + PyArrayObject *__pyx_v_idx = 0; + int __pyx_v_n_update; + __Pyx_LocalBuf_ND __pyx_pybuffernd_idx; + __Pyx_Buffer __pyx_pybuffer_idx; + __Pyx_LocalBuf_ND __pyx_pybuffernd_value; + __Pyx_Buffer __pyx_pybuffer_value; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_t_3; + int __pyx_t_4; + Py_ssize_t __pyx_t_5; + PyObject *__pyx_t_6 = NULL; + Py_UCS4 __pyx_t_7; + Py_ssize_t __pyx_t_8; + PyObject *__pyx_t_9 = NULL; + PyObject *__pyx_t_10 = NULL; + PyArrayObject *__pyx_t_11 = NULL; + PyArrayObject *__pyx_t_12 = NULL; + npy_intp *__pyx_t_13; + char *__pyx_t_14; + char *__pyx_t_15; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("set_params_sparse", 1); + __pyx_pybuffer_value.pybuffer.buf = NULL; + __pyx_pybuffer_value.refcount = 0; + __pyx_pybuffernd_value.data = NULL; + __pyx_pybuffernd_value.rcbuffer = &__pyx_pybuffer_value; + __pyx_pybuffer_idx.pybuffer.buf = NULL; + __pyx_pybuffer_idx.refcount = 0; + __pyx_pybuffernd_idx.data = NULL; + __pyx_pybuffernd_idx.rcbuffer = &__pyx_pybuffer_idx; + + /* "acados_template/acados_ocp_solver_pyx.pyx":758 + * """ + * + * if not isinstance(param_values_, np.ndarray): # <<<<<<<<<<<<<< + * raise Exception('param_values_ must be np.array.') + * + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 758, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_ndarray); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 758, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_3 = PyObject_IsInstance(__pyx_v_param_values_, __pyx_t_2); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(0, 758, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_4 = (!__pyx_t_3); + if (unlikely(__pyx_t_4)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":759 + * + * if not isinstance(param_values_, np.ndarray): + * raise Exception('param_values_ must be np.array.') # <<<<<<<<<<<<<< + * + * if param_values_.shape[0] != len(idx_values_): + */ + __pyx_t_2 = __Pyx_PyObject_Call(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_tuple__32, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 759, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 759, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":758 + * """ + * + * if not isinstance(param_values_, np.ndarray): # <<<<<<<<<<<<<< + * raise Exception('param_values_ must be np.array.') + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":761 + * raise Exception('param_values_ must be np.array.') + * + * if param_values_.shape[0] != len(idx_values_): # <<<<<<<<<<<<<< + * raise Exception(f'param_values_ and idx_values_ must be of the same size.' + + * f' Got sizes idx {param_values_.shape[0]}, param_values {len(idx_values_)}.') + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_param_values_, __pyx_n_s_shape); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 761, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_1 = __Pyx_GetItemInt(__pyx_t_2, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 761, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_5 = PyObject_Length(__pyx_v_idx_values_); if (unlikely(__pyx_t_5 == ((Py_ssize_t)-1))) __PYX_ERR(0, 761, __pyx_L1_error) + __pyx_t_2 = PyInt_FromSsize_t(__pyx_t_5); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 761, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_6 = PyObject_RichCompare(__pyx_t_1, __pyx_t_2, Py_NE); __Pyx_XGOTREF(__pyx_t_6); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 761, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_t_6); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 761, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(__pyx_t_4)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":763 + * if param_values_.shape[0] != len(idx_values_): + * raise Exception(f'param_values_ and idx_values_ must be of the same size.' + + * f' Got sizes idx {param_values_.shape[0]}, param_values {len(idx_values_)}.') # <<<<<<<<<<<<<< + * + * # n_update = c_int(len(param_values_)) + */ + __pyx_t_6 = PyTuple_New(5); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 763, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_5 = 0; + __pyx_t_7 = 127; + __Pyx_INCREF(__pyx_kp_u_Got_sizes_idx); + __pyx_t_5 += 15; + __Pyx_GIVEREF(__pyx_kp_u_Got_sizes_idx); + PyTuple_SET_ITEM(__pyx_t_6, 0, __pyx_kp_u_Got_sizes_idx); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_param_values_, __pyx_n_s_shape); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 763, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_1 = __Pyx_GetItemInt(__pyx_t_2, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 763, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_FormatSimple(__pyx_t_1, __pyx_empty_unicode); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 763, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_7 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) > __pyx_t_7) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) : __pyx_t_7; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_6, 1, __pyx_t_2); + __pyx_t_2 = 0; + __Pyx_INCREF(__pyx_kp_u_param_values_2); + __pyx_t_5 += 15; + __Pyx_GIVEREF(__pyx_kp_u_param_values_2); + PyTuple_SET_ITEM(__pyx_t_6, 2, __pyx_kp_u_param_values_2); + __pyx_t_8 = PyObject_Length(__pyx_v_idx_values_); if (unlikely(__pyx_t_8 == ((Py_ssize_t)-1))) __PYX_ERR(0, 763, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_t_8, 0, ' ', 'd'); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 763, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_6, 3, __pyx_t_2); + __pyx_t_2 = 0; + __Pyx_INCREF(__pyx_kp_u__2); + __pyx_t_5 += 1; + __Pyx_GIVEREF(__pyx_kp_u__2); + PyTuple_SET_ITEM(__pyx_t_6, 4, __pyx_kp_u__2); + __pyx_t_2 = __Pyx_PyUnicode_Join(__pyx_t_6, 5, __pyx_t_5, __pyx_t_7); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 763, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":762 + * + * if param_values_.shape[0] != len(idx_values_): + * raise Exception(f'param_values_ and idx_values_ must be of the same size.' + # <<<<<<<<<<<<<< + * f' Got sizes idx {param_values_.shape[0]}, param_values {len(idx_values_)}.') + * + */ + __pyx_t_6 = __Pyx_PyUnicode_Concat(__pyx_kp_u_param_values__and_idx_values__mu, __pyx_t_2); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 762, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_6); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 762, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 762, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":761 + * raise Exception('param_values_ must be np.array.') + * + * if param_values_.shape[0] != len(idx_values_): # <<<<<<<<<<<<<< + * raise Exception(f'param_values_ and idx_values_ must be of the same size.' + + * f' Got sizes idx {param_values_.shape[0]}, param_values {len(idx_values_)}.') + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":777 + * # (self.capsule, stage, idx_data, param_data, n_update) + * + * cdef cnp.ndarray[cnp.float64_t, ndim=1] value = np.ascontiguousarray(param_values_, dtype=np.float64) # <<<<<<<<<<<<<< + * # cdef cnp.ndarray[cnp.intc, ndim=1] idx = np.ascontiguousarray(idx_values_, dtype=np.intc) + * + */ + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_np); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 777, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 777, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = PyTuple_New(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 777, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_INCREF(__pyx_v_param_values_); + __Pyx_GIVEREF(__pyx_v_param_values_); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_v_param_values_)) __PYX_ERR(0, 777, __pyx_L1_error); + __pyx_t_1 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 777, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_GetModuleGlobalName(__pyx_t_9, __pyx_n_s_np); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 777, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __pyx_t_10 = __Pyx_PyObject_GetAttrStr(__pyx_t_9, __pyx_n_s_float64); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 777, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + if (PyDict_SetItem(__pyx_t_1, __pyx_n_s_dtype, __pyx_t_10) < 0) __PYX_ERR(0, 777, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + __pyx_t_10 = __Pyx_PyObject_Call(__pyx_t_6, __pyx_t_2, __pyx_t_1); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 777, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (!(likely(((__pyx_t_10) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_10, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 777, __pyx_L1_error) + __pyx_t_11 = ((PyArrayObject *)__pyx_t_10); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_value.rcbuffer->pybuffer, (PyObject*)__pyx_t_11, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 1, 0, __pyx_stack) == -1)) { + __pyx_v_value = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_value.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 777, __pyx_L1_error) + } else {__pyx_pybuffernd_value.diminfo[0].strides = __pyx_pybuffernd_value.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_value.diminfo[0].shape = __pyx_pybuffernd_value.rcbuffer->pybuffer.shape[0]; + } + } + __pyx_t_11 = 0; + __pyx_v_value = ((PyArrayObject *)__pyx_t_10); + __pyx_t_10 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":784 + * # cdef cnp.ndarray[cnp.int, ndim=1] idx = np.ascontiguousarray(idx_values_, dtype=np.intc) + * + * cdef cnp.ndarray[cnp.int32_t, ndim=1] idx = np.ascontiguousarray(idx_values_, dtype=np.int32) # <<<<<<<<<<<<<< + * cdef int n_update = value.shape[0] + * # print(f"in set_params_sparse Cython n_update {n_update}") + */ + __Pyx_GetModuleGlobalName(__pyx_t_10, __pyx_n_s_np); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 784, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_10, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 784, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + __pyx_t_10 = PyTuple_New(1); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 784, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __Pyx_INCREF(__pyx_v_idx_values_); + __Pyx_GIVEREF(__pyx_v_idx_values_); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_10, 0, __pyx_v_idx_values_)) __PYX_ERR(0, 784, __pyx_L1_error); + __pyx_t_2 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 784, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_GetModuleGlobalName(__pyx_t_6, __pyx_n_s_np); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 784, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_9 = __Pyx_PyObject_GetAttrStr(__pyx_t_6, __pyx_n_s_int32); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 784, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + if (PyDict_SetItem(__pyx_t_2, __pyx_n_s_dtype, __pyx_t_9) < 0) __PYX_ERR(0, 784, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + __pyx_t_9 = __Pyx_PyObject_Call(__pyx_t_1, __pyx_t_10, __pyx_t_2); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 784, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + if (!(likely(((__pyx_t_9) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_9, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 784, __pyx_L1_error) + __pyx_t_12 = ((PyArrayObject *)__pyx_t_9); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_idx.rcbuffer->pybuffer, (PyObject*)__pyx_t_12, &__Pyx_TypeInfo_nn___pyx_t_5numpy_int32_t, PyBUF_FORMAT| PyBUF_STRIDES, 1, 0, __pyx_stack) == -1)) { + __pyx_v_idx = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_idx.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 784, __pyx_L1_error) + } else {__pyx_pybuffernd_idx.diminfo[0].strides = __pyx_pybuffernd_idx.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_idx.diminfo[0].shape = __pyx_pybuffernd_idx.rcbuffer->pybuffer.shape[0]; + } + } + __pyx_t_12 = 0; + __pyx_v_idx = ((PyArrayObject *)__pyx_t_9); + __pyx_t_9 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":785 + * + * cdef cnp.ndarray[cnp.int32_t, ndim=1] idx = np.ascontiguousarray(idx_values_, dtype=np.int32) + * cdef int n_update = value.shape[0] # <<<<<<<<<<<<<< + * # print(f"in set_params_sparse Cython n_update {n_update}") + * + */ + __pyx_t_13 = __pyx_f_5numpy_7ndarray_5shape_shape(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_13 == ((npy_intp *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 785, __pyx_L1_error) + __pyx_v_n_update = (__pyx_t_13[0]); + + /* "acados_template/acados_ocp_solver_pyx.pyx":788 + * # print(f"in set_params_sparse Cython n_update {n_update}") + * + * assert acados_solver.acados_update_params_sparse(self.capsule, stage, idx.data, value.data, n_update) == 0 # <<<<<<<<<<<<<< + * return + * + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_14 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_idx)); if (unlikely(__pyx_t_14 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 788, __pyx_L1_error) + __pyx_t_15 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_15 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 788, __pyx_L1_error) + __pyx_t_4 = (lat_acados_update_params_sparse(__pyx_v_self->capsule, __pyx_v_stage, ((int *)__pyx_t_14), ((double *)__pyx_t_15), __pyx_v_n_update) == 0); + if (unlikely(!__pyx_t_4)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(0, 788, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(0, 788, __pyx_L1_error) + #endif + + /* "acados_template/acados_ocp_solver_pyx.pyx":789 + * + * assert acados_solver.acados_update_params_sparse(self.capsule, stage, idx.data, value.data, n_update) == 0 + * return # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":748 + * + * + * def set_params_sparse(self, int stage, idx_values_, param_values_): # <<<<<<<<<<<<<< + * """ + * set parameters of the solvers external function partially: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_9); + __Pyx_XDECREF(__pyx_t_10); + { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_idx.rcbuffer->pybuffer); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_value.rcbuffer->pybuffer); + __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.set_params_sparse", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + goto __pyx_L2; + __pyx_L0:; + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_idx.rcbuffer->pybuffer); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_value.rcbuffer->pybuffer); + __pyx_L2:; + __Pyx_XDECREF((PyObject *)__pyx_v_value); + __Pyx_XDECREF((PyObject *)__pyx_v_idx); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":792 + * + * + * def __del__(self): # <<<<<<<<<<<<<< + * if self.solver_created: + * acados_solver.acados_free(self.capsule) + */ + +/* Python wrapper */ +static void __pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_51__del__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_51__del__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__del__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_50__del__(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_50__del__(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":793 + * + * def __del__(self): + * if self.solver_created: # <<<<<<<<<<<<<< + * acados_solver.acados_free(self.capsule) + * acados_solver.acados_free_capsule(self.capsule) + */ + if (__pyx_v_self->solver_created) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":794 + * def __del__(self): + * if self.solver_created: + * acados_solver.acados_free(self.capsule) # <<<<<<<<<<<<<< + * acados_solver.acados_free_capsule(self.capsule) + */ + (void)(lat_acados_free(__pyx_v_self->capsule)); + + /* "acados_template/acados_ocp_solver_pyx.pyx":795 + * if self.solver_created: + * acados_solver.acados_free(self.capsule) + * acados_solver.acados_free_capsule(self.capsule) # <<<<<<<<<<<<<< + */ + (void)(lat_acados_free_capsule(__pyx_v_self->capsule)); + + /* "acados_template/acados_ocp_solver_pyx.pyx":793 + * + * def __del__(self): + * if self.solver_created: # <<<<<<<<<<<<<< + * acados_solver.acados_free(self.capsule) + * acados_solver.acados_free_capsule(self.capsule) + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":792 + * + * + * def __del__(self): # <<<<<<<<<<<<<< + * if self.solver_created: + * acados_solver.acados_free(self.capsule) + */ + + /* function exit code */ +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_53__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_53__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_53__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_53__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_52__reduce_cython__(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_52__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_55__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_55__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_55__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_55__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_54__setstate_cython__(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_54__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_tp_new_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython(PyTypeObject *t, PyObject *a, PyObject *k) { + struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)o); + p->model_name = ((PyObject*)Py_None); Py_INCREF(Py_None); + p->nlp_solver_type = ((PyObject*)Py_None); Py_INCREF(Py_None); + if (unlikely(__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_1__cinit__(o, a, k) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +#if CYTHON_USE_TP_FINALIZE +static void __pyx_tp_finalize_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython(PyObject *o) { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_51__del__(o); + PyErr_Restore(etype, eval, etb); +} +#endif + +static void __pyx_tp_dealloc_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython(PyObject *o) { + struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *p = (struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + Py_CLEAR(p->model_name); + Py_CLEAR(p->nlp_solver_type); + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} + +static PyMethodDef __pyx_methods_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython[] = { + {"_AcadosOcpSolverCython__get_pointers_solver", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_3_AcadosOcpSolverCython__get_pointers_solver, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_2__get_pointers_solver}, + {"solve_for_x0", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve_for_x0, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve_for_x0}, + {"solve", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7solve, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6solve}, + {"reset", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9reset, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8reset}, + {"custom_update", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11custom_update, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10custom_update}, + {"set_new_time_steps", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13set_new_time_steps, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12set_new_time_steps}, + {"update_qp_solver_cond_N", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15update_qp_solver_cond_N, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14update_qp_solver_cond_N}, + {"eval_param_sens", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17eval_param_sens, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16eval_param_sens}, + {"get", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19get, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18get}, + {"print_statistics", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21print_statistics, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20print_statistics}, + {"store_iterate", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23store_iterate, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22store_iterate}, + {"load_iterate", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25load_iterate, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_24load_iterate}, + {"get_stats", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27get_stats, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_26get_stats}, + {"_AcadosOcpSolverCython__get_stat_int", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_int, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"_AcadosOcpSolverCython__get_stat_double", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31_AcadosOcpSolverCython__get_stat_double, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"_AcadosOcpSolverCython__get_stat_matrix", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33_AcadosOcpSolverCython__get_stat_matrix, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"get_cost", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35get_cost, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34get_cost}, + {"get_residuals", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37get_residuals, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36get_residuals}, + {"set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38set}, + {"cost_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41cost_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40cost_set}, + {"constraints_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43constraints_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42constraints_set}, + {"get_from_qp_in", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_45get_from_qp_in, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_44get_from_qp_in}, + {"options_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47options_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_46options_set}, + {"set_params_sparse", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49set_params_sparse, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_48set_params_sparse}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_53__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_55__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython}, + {Py_tp_doc, (void *)PyDoc_STR("\n Class to interact with the acados ocp solver C object.\n ")}, + {Py_tp_methods, (void *)__pyx_methods_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython}, + {Py_tp_new, (void *)__pyx_tp_new_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython}, + #if PY_VERSION_HEX >= 0x030400a1 + {Py_tp_finalize, (void *)__pyx_tp_finalize_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython}, + #endif + {0, 0}, +}; +static PyType_Spec __pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython_spec = { + "acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython", + sizeof(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_FINALIZE, + __pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython_slots, +}; +#else + +static PyTypeObject __pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython = { + PyVarObject_HEAD_INIT(0, 0) + "acados_template.acados_ocp_solver_pyx.""AcadosOcpSolverCython", /*tp_name*/ + sizeof(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_FINALIZE, /*tp_flags*/ + PyDoc_STR("\n Class to interact with the acados ocp solver C object.\n "), /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + __pyx_tp_finalize_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif +static struct __pyx_vtabstruct_array __pyx_vtable_array; + +static PyObject *__pyx_tp_new_array(PyTypeObject *t, PyObject *a, PyObject *k) { + struct __pyx_array_obj *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_array_obj *)o); + p->__pyx_vtab = __pyx_vtabptr_array; + p->mode = ((PyObject*)Py_None); Py_INCREF(Py_None); + p->_format = ((PyObject*)Py_None); Py_INCREF(Py_None); + if (unlikely(__pyx_array___cinit__(o, a, k) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static void __pyx_tp_dealloc_array(PyObject *o) { + struct __pyx_array_obj *p = (struct __pyx_array_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_array) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_array___dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + Py_CLEAR(p->mode); + Py_CLEAR(p->_format); + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} +static PyObject *__pyx_sq_item_array(PyObject *o, Py_ssize_t i) { + PyObject *r; + PyObject *x = PyInt_FromSsize_t(i); if(!x) return 0; + r = Py_TYPE(o)->tp_as_mapping->mp_subscript(o, x); + Py_DECREF(x); + return r; +} + +static int __pyx_mp_ass_subscript_array(PyObject *o, PyObject *i, PyObject *v) { + if (v) { + return __pyx_array___setitem__(o, i, v); + } + else { + __Pyx_TypeName o_type_name; + o_type_name = __Pyx_PyType_GetName(Py_TYPE(o)); + PyErr_Format(PyExc_NotImplementedError, + "Subscript deletion not supported by " __Pyx_FMT_TYPENAME, o_type_name); + __Pyx_DECREF_TypeName(o_type_name); + return -1; + } +} + +static PyObject *__pyx_tp_getattro_array(PyObject *o, PyObject *n) { + PyObject *v = __Pyx_PyObject_GenericGetAttr(o, n); + if (!v && PyErr_ExceptionMatches(PyExc_AttributeError)) { + PyErr_Clear(); + v = __pyx_array___getattr__(o, n); + } + return v; +} + +static PyObject *__pyx_getprop___pyx_array_memview(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_5array_7memview_1__get__(o); +} + +static PyMethodDef __pyx_methods_array[] = { + {"__getattr__", (PyCFunction)__pyx_array___getattr__, METH_O|METH_COEXIST, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_array_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_array_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; + +static struct PyGetSetDef __pyx_getsets_array[] = { + {(char *)"memview", __pyx_getprop___pyx_array_memview, 0, (char *)0, 0}, + {0, 0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +#if !CYTHON_COMPILING_IN_LIMITED_API + +static PyBufferProcs __pyx_tp_as_buffer_array = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_array_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; +#endif +static PyType_Slot __pyx_type___pyx_array_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_array}, + {Py_sq_length, (void *)__pyx_array___len__}, + {Py_sq_item, (void *)__pyx_sq_item_array}, + {Py_mp_length, (void *)__pyx_array___len__}, + {Py_mp_subscript, (void *)__pyx_array___getitem__}, + {Py_mp_ass_subscript, (void *)__pyx_mp_ass_subscript_array}, + {Py_tp_getattro, (void *)__pyx_tp_getattro_array}, + #if defined(Py_bf_getbuffer) + {Py_bf_getbuffer, (void *)__pyx_array_getbuffer}, + #endif + {Py_tp_methods, (void *)__pyx_methods_array}, + {Py_tp_getset, (void *)__pyx_getsets_array}, + {Py_tp_new, (void *)__pyx_tp_new_array}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_array_spec = { + "acados_template.acados_ocp_solver_pyx.array", + sizeof(struct __pyx_array_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_SEQUENCE, + __pyx_type___pyx_array_slots, +}; +#else + +static PySequenceMethods __pyx_tp_as_sequence_array = { + __pyx_array___len__, /*sq_length*/ + 0, /*sq_concat*/ + 0, /*sq_repeat*/ + __pyx_sq_item_array, /*sq_item*/ + 0, /*sq_slice*/ + 0, /*sq_ass_item*/ + 0, /*sq_ass_slice*/ + 0, /*sq_contains*/ + 0, /*sq_inplace_concat*/ + 0, /*sq_inplace_repeat*/ +}; + +static PyMappingMethods __pyx_tp_as_mapping_array = { + __pyx_array___len__, /*mp_length*/ + __pyx_array___getitem__, /*mp_subscript*/ + __pyx_mp_ass_subscript_array, /*mp_ass_subscript*/ +}; + +static PyBufferProcs __pyx_tp_as_buffer_array = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_array_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; + +static PyTypeObject __pyx_type___pyx_array = { + PyVarObject_HEAD_INIT(0, 0) + "acados_template.acados_ocp_solver_pyx.""array", /*tp_name*/ + sizeof(struct __pyx_array_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_array, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + &__pyx_tp_as_sequence_array, /*tp_as_sequence*/ + &__pyx_tp_as_mapping_array, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + __pyx_tp_getattro_array, /*tp_getattro*/ + 0, /*tp_setattro*/ + &__pyx_tp_as_buffer_array, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_SEQUENCE, /*tp_flags*/ + 0, /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_array, /*tp_methods*/ + 0, /*tp_members*/ + __pyx_getsets_array, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_array, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyObject *__pyx_tp_new_Enum(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { + struct __pyx_MemviewEnum_obj *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_MemviewEnum_obj *)o); + p->name = Py_None; Py_INCREF(Py_None); + return o; +} + +static void __pyx_tp_dealloc_Enum(PyObject *o) { + struct __pyx_MemviewEnum_obj *p = (struct __pyx_MemviewEnum_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_Enum) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + Py_CLEAR(p->name); + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} + +static int __pyx_tp_traverse_Enum(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_MemviewEnum_obj *p = (struct __pyx_MemviewEnum_obj *)o; + if (p->name) { + e = (*v)(p->name, a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear_Enum(PyObject *o) { + PyObject* tmp; + struct __pyx_MemviewEnum_obj *p = (struct __pyx_MemviewEnum_obj *)o; + tmp = ((PyObject*)p->name); + p->name = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + return 0; +} + +static PyObject *__pyx_specialmethod___pyx_MemviewEnum___repr__(PyObject *self, CYTHON_UNUSED PyObject *arg) { + return __pyx_MemviewEnum___repr__(self); +} + +static PyMethodDef __pyx_methods_Enum[] = { + {"__repr__", (PyCFunction)__pyx_specialmethod___pyx_MemviewEnum___repr__, METH_NOARGS|METH_COEXIST, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_MemviewEnum_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_MemviewEnum_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type___pyx_MemviewEnum_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_Enum}, + {Py_tp_repr, (void *)__pyx_MemviewEnum___repr__}, + {Py_tp_traverse, (void *)__pyx_tp_traverse_Enum}, + {Py_tp_clear, (void *)__pyx_tp_clear_Enum}, + {Py_tp_methods, (void *)__pyx_methods_Enum}, + {Py_tp_init, (void *)__pyx_MemviewEnum___init__}, + {Py_tp_new, (void *)__pyx_tp_new_Enum}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_MemviewEnum_spec = { + "acados_template.acados_ocp_solver_pyx.Enum", + sizeof(struct __pyx_MemviewEnum_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, + __pyx_type___pyx_MemviewEnum_slots, +}; +#else + +static PyTypeObject __pyx_type___pyx_MemviewEnum = { + PyVarObject_HEAD_INIT(0, 0) + "acados_template.acados_ocp_solver_pyx.""Enum", /*tp_name*/ + sizeof(struct __pyx_MemviewEnum_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_Enum, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + __pyx_MemviewEnum___repr__, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, /*tp_flags*/ + 0, /*tp_doc*/ + __pyx_tp_traverse_Enum, /*tp_traverse*/ + __pyx_tp_clear_Enum, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_Enum, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + __pyx_MemviewEnum___init__, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_Enum, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif +static struct __pyx_vtabstruct_memoryview __pyx_vtable_memoryview; + +static PyObject *__pyx_tp_new_memoryview(PyTypeObject *t, PyObject *a, PyObject *k) { + struct __pyx_memoryview_obj *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_memoryview_obj *)o); + p->__pyx_vtab = __pyx_vtabptr_memoryview; + p->obj = Py_None; Py_INCREF(Py_None); + p->_size = Py_None; Py_INCREF(Py_None); + p->_array_interface = Py_None; Py_INCREF(Py_None); + p->view.obj = NULL; + if (unlikely(__pyx_memoryview___cinit__(o, a, k) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static void __pyx_tp_dealloc_memoryview(PyObject *o) { + struct __pyx_memoryview_obj *p = (struct __pyx_memoryview_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_memoryview) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_memoryview___dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + Py_CLEAR(p->obj); + Py_CLEAR(p->_size); + Py_CLEAR(p->_array_interface); + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} + +static int __pyx_tp_traverse_memoryview(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_memoryview_obj *p = (struct __pyx_memoryview_obj *)o; + if (p->obj) { + e = (*v)(p->obj, a); if (e) return e; + } + if (p->_size) { + e = (*v)(p->_size, a); if (e) return e; + } + if (p->_array_interface) { + e = (*v)(p->_array_interface, a); if (e) return e; + } + if (p->view.obj) { + e = (*v)(p->view.obj, a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear_memoryview(PyObject *o) { + PyObject* tmp; + struct __pyx_memoryview_obj *p = (struct __pyx_memoryview_obj *)o; + tmp = ((PyObject*)p->obj); + p->obj = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + tmp = ((PyObject*)p->_size); + p->_size = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + tmp = ((PyObject*)p->_array_interface); + p->_array_interface = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + Py_CLEAR(p->view.obj); + return 0; +} +static PyObject *__pyx_sq_item_memoryview(PyObject *o, Py_ssize_t i) { + PyObject *r; + PyObject *x = PyInt_FromSsize_t(i); if(!x) return 0; + r = Py_TYPE(o)->tp_as_mapping->mp_subscript(o, x); + Py_DECREF(x); + return r; +} + +static int __pyx_mp_ass_subscript_memoryview(PyObject *o, PyObject *i, PyObject *v) { + if (v) { + return __pyx_memoryview___setitem__(o, i, v); + } + else { + __Pyx_TypeName o_type_name; + o_type_name = __Pyx_PyType_GetName(Py_TYPE(o)); + PyErr_Format(PyExc_NotImplementedError, + "Subscript deletion not supported by " __Pyx_FMT_TYPENAME, o_type_name); + __Pyx_DECREF_TypeName(o_type_name); + return -1; + } +} + +static PyObject *__pyx_getprop___pyx_memoryview_T(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_1T_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_base(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_4base_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_shape(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_5shape_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_strides(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_7strides_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_suboffsets(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_10suboffsets_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_ndim(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_4ndim_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_itemsize(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_8itemsize_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_nbytes(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_6nbytes_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_size(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_4size_1__get__(o); +} + +static PyObject *__pyx_specialmethod___pyx_memoryview___repr__(PyObject *self, CYTHON_UNUSED PyObject *arg) { + return __pyx_memoryview___repr__(self); +} + +static PyMethodDef __pyx_methods_memoryview[] = { + {"__repr__", (PyCFunction)__pyx_specialmethod___pyx_memoryview___repr__, METH_NOARGS|METH_COEXIST, 0}, + {"is_c_contig", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_is_c_contig, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"is_f_contig", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_is_f_contig, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"copy", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_copy, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"copy_fortran", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_copy_fortran, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryview_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryview_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; + +static struct PyGetSetDef __pyx_getsets_memoryview[] = { + {(char *)"T", __pyx_getprop___pyx_memoryview_T, 0, (char *)0, 0}, + {(char *)"base", __pyx_getprop___pyx_memoryview_base, 0, (char *)0, 0}, + {(char *)"shape", __pyx_getprop___pyx_memoryview_shape, 0, (char *)0, 0}, + {(char *)"strides", __pyx_getprop___pyx_memoryview_strides, 0, (char *)0, 0}, + {(char *)"suboffsets", __pyx_getprop___pyx_memoryview_suboffsets, 0, (char *)0, 0}, + {(char *)"ndim", __pyx_getprop___pyx_memoryview_ndim, 0, (char *)0, 0}, + {(char *)"itemsize", __pyx_getprop___pyx_memoryview_itemsize, 0, (char *)0, 0}, + {(char *)"nbytes", __pyx_getprop___pyx_memoryview_nbytes, 0, (char *)0, 0}, + {(char *)"size", __pyx_getprop___pyx_memoryview_size, 0, (char *)0, 0}, + {0, 0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +#if !CYTHON_COMPILING_IN_LIMITED_API + +static PyBufferProcs __pyx_tp_as_buffer_memoryview = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_memoryview_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; +#endif +static PyType_Slot __pyx_type___pyx_memoryview_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_memoryview}, + {Py_tp_repr, (void *)__pyx_memoryview___repr__}, + {Py_sq_length, (void *)__pyx_memoryview___len__}, + {Py_sq_item, (void *)__pyx_sq_item_memoryview}, + {Py_mp_length, (void *)__pyx_memoryview___len__}, + {Py_mp_subscript, (void *)__pyx_memoryview___getitem__}, + {Py_mp_ass_subscript, (void *)__pyx_mp_ass_subscript_memoryview}, + {Py_tp_str, (void *)__pyx_memoryview___str__}, + #if defined(Py_bf_getbuffer) + {Py_bf_getbuffer, (void *)__pyx_memoryview_getbuffer}, + #endif + {Py_tp_traverse, (void *)__pyx_tp_traverse_memoryview}, + {Py_tp_clear, (void *)__pyx_tp_clear_memoryview}, + {Py_tp_methods, (void *)__pyx_methods_memoryview}, + {Py_tp_getset, (void *)__pyx_getsets_memoryview}, + {Py_tp_new, (void *)__pyx_tp_new_memoryview}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_memoryview_spec = { + "acados_template.acados_ocp_solver_pyx.memoryview", + sizeof(struct __pyx_memoryview_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, + __pyx_type___pyx_memoryview_slots, +}; +#else + +static PySequenceMethods __pyx_tp_as_sequence_memoryview = { + __pyx_memoryview___len__, /*sq_length*/ + 0, /*sq_concat*/ + 0, /*sq_repeat*/ + __pyx_sq_item_memoryview, /*sq_item*/ + 0, /*sq_slice*/ + 0, /*sq_ass_item*/ + 0, /*sq_ass_slice*/ + 0, /*sq_contains*/ + 0, /*sq_inplace_concat*/ + 0, /*sq_inplace_repeat*/ +}; + +static PyMappingMethods __pyx_tp_as_mapping_memoryview = { + __pyx_memoryview___len__, /*mp_length*/ + __pyx_memoryview___getitem__, /*mp_subscript*/ + __pyx_mp_ass_subscript_memoryview, /*mp_ass_subscript*/ +}; + +static PyBufferProcs __pyx_tp_as_buffer_memoryview = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_memoryview_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; + +static PyTypeObject __pyx_type___pyx_memoryview = { + PyVarObject_HEAD_INIT(0, 0) + "acados_template.acados_ocp_solver_pyx.""memoryview", /*tp_name*/ + sizeof(struct __pyx_memoryview_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_memoryview, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + __pyx_memoryview___repr__, /*tp_repr*/ + 0, /*tp_as_number*/ + &__pyx_tp_as_sequence_memoryview, /*tp_as_sequence*/ + &__pyx_tp_as_mapping_memoryview, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + __pyx_memoryview___str__, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + &__pyx_tp_as_buffer_memoryview, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, /*tp_flags*/ + 0, /*tp_doc*/ + __pyx_tp_traverse_memoryview, /*tp_traverse*/ + __pyx_tp_clear_memoryview, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_memoryview, /*tp_methods*/ + 0, /*tp_members*/ + __pyx_getsets_memoryview, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_memoryview, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif +static struct __pyx_vtabstruct__memoryviewslice __pyx_vtable__memoryviewslice; + +static PyObject *__pyx_tp_new__memoryviewslice(PyTypeObject *t, PyObject *a, PyObject *k) { + struct __pyx_memoryviewslice_obj *p; + PyObject *o = __pyx_tp_new_memoryview(t, a, k); + if (unlikely(!o)) return 0; + p = ((struct __pyx_memoryviewslice_obj *)o); + p->__pyx_base.__pyx_vtab = (struct __pyx_vtabstruct_memoryview*)__pyx_vtabptr__memoryviewslice; + p->from_object = Py_None; Py_INCREF(Py_None); + p->from_slice.memview = NULL; + return o; +} + +static void __pyx_tp_dealloc__memoryviewslice(PyObject *o) { + struct __pyx_memoryviewslice_obj *p = (struct __pyx_memoryviewslice_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc__memoryviewslice) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_memoryviewslice___dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + Py_CLEAR(p->from_object); + PyObject_GC_Track(o); + __pyx_tp_dealloc_memoryview(o); +} + +static int __pyx_tp_traverse__memoryviewslice(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_memoryviewslice_obj *p = (struct __pyx_memoryviewslice_obj *)o; + e = __pyx_tp_traverse_memoryview(o, v, a); if (e) return e; + if (p->from_object) { + e = (*v)(p->from_object, a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear__memoryviewslice(PyObject *o) { + PyObject* tmp; + struct __pyx_memoryviewslice_obj *p = (struct __pyx_memoryviewslice_obj *)o; + __pyx_tp_clear_memoryview(o); + tmp = ((PyObject*)p->from_object); + p->from_object = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + __PYX_XCLEAR_MEMVIEW(&p->from_slice, 1); + return 0; +} + +static PyMethodDef __pyx_methods__memoryviewslice[] = { + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryviewslice_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryviewslice_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type___pyx_memoryviewslice_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc__memoryviewslice}, + {Py_tp_doc, (void *)PyDoc_STR("Internal class for passing memoryview slices to Python")}, + {Py_tp_traverse, (void *)__pyx_tp_traverse__memoryviewslice}, + {Py_tp_clear, (void *)__pyx_tp_clear__memoryviewslice}, + {Py_tp_methods, (void *)__pyx_methods__memoryviewslice}, + {Py_tp_new, (void *)__pyx_tp_new__memoryviewslice}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_memoryviewslice_spec = { + "acados_template.acados_ocp_solver_pyx._memoryviewslice", + sizeof(struct __pyx_memoryviewslice_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_SEQUENCE, + __pyx_type___pyx_memoryviewslice_slots, +}; +#else + +static PyTypeObject __pyx_type___pyx_memoryviewslice = { + PyVarObject_HEAD_INIT(0, 0) + "acados_template.acados_ocp_solver_pyx.""_memoryviewslice", /*tp_name*/ + sizeof(struct __pyx_memoryviewslice_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc__memoryviewslice, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + #if CYTHON_COMPILING_IN_PYPY || 0 + __pyx_memoryview___repr__, /*tp_repr*/ + #else + 0, /*tp_repr*/ + #endif + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + #if CYTHON_COMPILING_IN_PYPY || 0 + __pyx_memoryview___str__, /*tp_str*/ + #else + 0, /*tp_str*/ + #endif + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_SEQUENCE, /*tp_flags*/ + PyDoc_STR("Internal class for passing memoryview slices to Python"), /*tp_doc*/ + __pyx_tp_traverse__memoryviewslice, /*tp_traverse*/ + __pyx_tp_clear__memoryviewslice, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods__memoryviewslice, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new__memoryviewslice, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyMethodDef __pyx_methods[] = { + {0, 0, 0, 0} +}; +#ifndef CYTHON_SMALL_CODE +#if defined(__clang__) + #define CYTHON_SMALL_CODE +#elif defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 3)) + #define CYTHON_SMALL_CODE __attribute__((cold)) +#else + #define CYTHON_SMALL_CODE +#endif +#endif +/* #### Code section: pystring_table ### */ + +static int __Pyx_CreateStringTabAndInitStrings(void) { + __Pyx_StringTabEntry __pyx_string_tab[] = { + {&__pyx_kp_u_, __pyx_k_, sizeof(__pyx_k_), 0, 1, 0, 0}, + {&__pyx_kp_u_0, __pyx_k_0, sizeof(__pyx_k_0), 0, 1, 0, 0}, + {&__pyx_n_s_ASCII, __pyx_k_ASCII, sizeof(__pyx_k_ASCII), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython, __pyx_k_AcadosOcpSolverCython, sizeof(__pyx_k_AcadosOcpSolverCython), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython___get_poin, __pyx_k_AcadosOcpSolverCython___get_poin, sizeof(__pyx_k_AcadosOcpSolverCython___get_poin), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython___get_stat, __pyx_k_AcadosOcpSolverCython___get_stat, sizeof(__pyx_k_AcadosOcpSolverCython___get_stat), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython___get_stat_2, __pyx_k_AcadosOcpSolverCython___get_stat_2, sizeof(__pyx_k_AcadosOcpSolverCython___get_stat_2), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython___get_stat_3, __pyx_k_AcadosOcpSolverCython___get_stat_3, sizeof(__pyx_k_AcadosOcpSolverCython___get_stat_3), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython___reduce_c, __pyx_k_AcadosOcpSolverCython___reduce_c, sizeof(__pyx_k_AcadosOcpSolverCython___reduce_c), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython___setstate, __pyx_k_AcadosOcpSolverCython___setstate, sizeof(__pyx_k_AcadosOcpSolverCython___setstate), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython__get_poin, __pyx_k_AcadosOcpSolverCython__get_poin, sizeof(__pyx_k_AcadosOcpSolverCython__get_poin), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython__get_stat, __pyx_k_AcadosOcpSolverCython__get_stat, sizeof(__pyx_k_AcadosOcpSolverCython__get_stat), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython__get_stat_2, __pyx_k_AcadosOcpSolverCython__get_stat_2, sizeof(__pyx_k_AcadosOcpSolverCython__get_stat_2), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython__get_stat_3, __pyx_k_AcadosOcpSolverCython__get_stat_3, sizeof(__pyx_k_AcadosOcpSolverCython__get_stat_3), 0, 0, 1, 1}, + {&__pyx_kp_u_AcadosOcpSolverCython_constraint, __pyx_k_AcadosOcpSolverCython_constraint, sizeof(__pyx_k_AcadosOcpSolverCython_constraint), 0, 1, 0, 0}, + {&__pyx_n_s_AcadosOcpSolverCython_constraint_2, __pyx_k_AcadosOcpSolverCython_constraint_2, sizeof(__pyx_k_AcadosOcpSolverCython_constraint_2), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython_cost_set, __pyx_k_AcadosOcpSolverCython_cost_set, sizeof(__pyx_k_AcadosOcpSolverCython_cost_set), 0, 0, 1, 1}, + {&__pyx_kp_u_AcadosOcpSolverCython_cost_set_m, __pyx_k_AcadosOcpSolverCython_cost_set_m, sizeof(__pyx_k_AcadosOcpSolverCython_cost_set_m), 0, 1, 0, 0}, + {&__pyx_n_s_AcadosOcpSolverCython_custom_upd, __pyx_k_AcadosOcpSolverCython_custom_upd, sizeof(__pyx_k_AcadosOcpSolverCython_custom_upd), 0, 0, 1, 1}, + {&__pyx_kp_u_AcadosOcpSolverCython_does_not_s, __pyx_k_AcadosOcpSolverCython_does_not_s, sizeof(__pyx_k_AcadosOcpSolverCython_does_not_s), 0, 1, 0, 0}, + {&__pyx_kp_u_AcadosOcpSolverCython_does_not_s_2, __pyx_k_AcadosOcpSolverCython_does_not_s_2, sizeof(__pyx_k_AcadosOcpSolverCython_does_not_s_2), 0, 1, 0, 0}, + {&__pyx_kp_u_AcadosOcpSolverCython_eval_param, __pyx_k_AcadosOcpSolverCython_eval_param, sizeof(__pyx_k_AcadosOcpSolverCython_eval_param), 0, 1, 0, 0}, + {&__pyx_kp_u_AcadosOcpSolverCython_eval_param_2, __pyx_k_AcadosOcpSolverCython_eval_param_2, sizeof(__pyx_k_AcadosOcpSolverCython_eval_param_2), 0, 1, 0, 0}, + {&__pyx_n_s_AcadosOcpSolverCython_eval_param_3, __pyx_k_AcadosOcpSolverCython_eval_param_3, sizeof(__pyx_k_AcadosOcpSolverCython_eval_param_3), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython_get, __pyx_k_AcadosOcpSolverCython_get, sizeof(__pyx_k_AcadosOcpSolverCython_get), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython_get_cost, __pyx_k_AcadosOcpSolverCython_get_cost, sizeof(__pyx_k_AcadosOcpSolverCython_get_cost), 0, 0, 1, 1}, + {&__pyx_kp_u_AcadosOcpSolverCython_get_field, __pyx_k_AcadosOcpSolverCython_get_field, sizeof(__pyx_k_AcadosOcpSolverCython_get_field), 0, 1, 0, 0}, + {&__pyx_n_s_AcadosOcpSolverCython_get_from_q, __pyx_k_AcadosOcpSolverCython_get_from_q, sizeof(__pyx_k_AcadosOcpSolverCython_get_from_q), 0, 0, 1, 1}, + {&__pyx_kp_u_AcadosOcpSolverCython_get_is_an, __pyx_k_AcadosOcpSolverCython_get_is_an, sizeof(__pyx_k_AcadosOcpSolverCython_get_is_an), 0, 1, 0, 0}, + {&__pyx_n_s_AcadosOcpSolverCython_get_residu, __pyx_k_AcadosOcpSolverCython_get_residu, sizeof(__pyx_k_AcadosOcpSolverCython_get_residu), 0, 0, 1, 1}, + {&__pyx_kp_u_AcadosOcpSolverCython_get_stage, __pyx_k_AcadosOcpSolverCython_get_stage, sizeof(__pyx_k_AcadosOcpSolverCython_get_stage), 0, 1, 0, 0}, + {&__pyx_n_s_AcadosOcpSolverCython_get_stats, __pyx_k_AcadosOcpSolverCython_get_stats, sizeof(__pyx_k_AcadosOcpSolverCython_get_stats), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython_load_itera, __pyx_k_AcadosOcpSolverCython_load_itera, sizeof(__pyx_k_AcadosOcpSolverCython_load_itera), 0, 0, 1, 1}, + {&__pyx_kp_u_AcadosOcpSolverCython_options_se, __pyx_k_AcadosOcpSolverCython_options_se, sizeof(__pyx_k_AcadosOcpSolverCython_options_se), 0, 1, 0, 0}, + {&__pyx_n_s_AcadosOcpSolverCython_options_se_2, __pyx_k_AcadosOcpSolverCython_options_se_2, sizeof(__pyx_k_AcadosOcpSolverCython_options_se_2), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython_print_stat, __pyx_k_AcadosOcpSolverCython_print_stat, sizeof(__pyx_k_AcadosOcpSolverCython_print_stat), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython_reset, __pyx_k_AcadosOcpSolverCython_reset, sizeof(__pyx_k_AcadosOcpSolverCython_reset), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython_set, __pyx_k_AcadosOcpSolverCython_set, sizeof(__pyx_k_AcadosOcpSolverCython_set), 0, 0, 1, 1}, + {&__pyx_kp_u_AcadosOcpSolverCython_set_is_not, __pyx_k_AcadosOcpSolverCython_set_is_not, sizeof(__pyx_k_AcadosOcpSolverCython_set_is_not), 0, 1, 0, 0}, + {&__pyx_kp_u_AcadosOcpSolverCython_set_mismat, __pyx_k_AcadosOcpSolverCython_set_mismat, sizeof(__pyx_k_AcadosOcpSolverCython_set_mismat), 0, 1, 0, 0}, + {&__pyx_n_s_AcadosOcpSolverCython_set_new_ti, __pyx_k_AcadosOcpSolverCython_set_new_ti, sizeof(__pyx_k_AcadosOcpSolverCython_set_new_ti), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython_set_params, __pyx_k_AcadosOcpSolverCython_set_params, sizeof(__pyx_k_AcadosOcpSolverCython_set_params), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython_solve, __pyx_k_AcadosOcpSolverCython_solve, sizeof(__pyx_k_AcadosOcpSolverCython_solve), 0, 0, 1, 1}, + {&__pyx_kp_u_AcadosOcpSolverCython_solve_argu, __pyx_k_AcadosOcpSolverCython_solve_argu, sizeof(__pyx_k_AcadosOcpSolverCython_solve_argu), 0, 1, 0, 0}, + {&__pyx_kp_u_AcadosOcpSolverCython_solve_argu_2, __pyx_k_AcadosOcpSolverCython_solve_argu_2, sizeof(__pyx_k_AcadosOcpSolverCython_solve_argu_2), 0, 1, 0, 0}, + {&__pyx_n_s_AcadosOcpSolverCython_solve_for, __pyx_k_AcadosOcpSolverCython_solve_for, sizeof(__pyx_k_AcadosOcpSolverCython_solve_for), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython_store_iter, __pyx_k_AcadosOcpSolverCython_store_iter, sizeof(__pyx_k_AcadosOcpSolverCython_store_iter), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython_update_qp, __pyx_k_AcadosOcpSolverCython_update_qp, sizeof(__pyx_k_AcadosOcpSolverCython_update_qp), 0, 0, 1, 1}, + {&__pyx_kp_s_All_dimensions_preceding_dimensi, __pyx_k_All_dimensions_preceding_dimensi, sizeof(__pyx_k_All_dimensions_preceding_dimensi), 0, 0, 1, 0}, + {&__pyx_n_s_AssertionError, __pyx_k_AssertionError, sizeof(__pyx_k_AssertionError), 0, 0, 1, 1}, + {&__pyx_kp_s_Buffer_view_does_not_expose_stri, __pyx_k_Buffer_view_does_not_expose_stri, sizeof(__pyx_k_Buffer_view_does_not_expose_stri), 0, 0, 1, 0}, + {&__pyx_kp_s_Can_only_create_a_buffer_that_is, __pyx_k_Can_only_create_a_buffer_that_is, sizeof(__pyx_k_Can_only_create_a_buffer_that_is), 0, 0, 1, 0}, + {&__pyx_kp_s_Cannot_assign_to_read_only_memor, __pyx_k_Cannot_assign_to_read_only_memor, sizeof(__pyx_k_Cannot_assign_to_read_only_memor), 0, 0, 1, 0}, + {&__pyx_kp_s_Cannot_create_writable_memory_vi, __pyx_k_Cannot_create_writable_memory_vi, sizeof(__pyx_k_Cannot_create_writable_memory_vi), 0, 0, 1, 0}, + {&__pyx_kp_u_Cannot_index_with_type, __pyx_k_Cannot_index_with_type, sizeof(__pyx_k_Cannot_index_with_type), 0, 1, 0, 0}, + {&__pyx_kp_s_Cannot_transpose_memoryview_with, __pyx_k_Cannot_transpose_memoryview_with, sizeof(__pyx_k_Cannot_transpose_memoryview_with), 0, 0, 1, 0}, + {&__pyx_kp_s_Dimension_d_is_not_direct, __pyx_k_Dimension_d_is_not_direct, sizeof(__pyx_k_Dimension_d_is_not_direct), 0, 0, 1, 0}, + {&__pyx_n_s_Ellipsis, __pyx_k_Ellipsis, sizeof(__pyx_k_Ellipsis), 0, 0, 1, 1}, + {&__pyx_kp_s_Empty_shape_tuple_for_cython_arr, __pyx_k_Empty_shape_tuple_for_cython_arr, sizeof(__pyx_k_Empty_shape_tuple_for_cython_arr), 0, 0, 1, 0}, + {&__pyx_n_u_F, __pyx_k_F, sizeof(__pyx_k_F), 0, 1, 0, 1}, + {&__pyx_kp_u_Got_sizes_idx, __pyx_k_Got_sizes_idx, sizeof(__pyx_k_Got_sizes_idx), 0, 1, 0, 0}, + {&__pyx_n_s_ImportError, __pyx_k_ImportError, sizeof(__pyx_k_ImportError), 0, 0, 1, 1}, + {&__pyx_kp_s_Incompatible_checksums_0x_x_vs_0, __pyx_k_Incompatible_checksums_0x_x_vs_0, sizeof(__pyx_k_Incompatible_checksums_0x_x_vs_0), 0, 0, 1, 0}, + {&__pyx_n_s_IndexError, __pyx_k_IndexError, sizeof(__pyx_k_IndexError), 0, 0, 1, 1}, + {&__pyx_kp_s_Index_out_of_bounds_axis_d, __pyx_k_Index_out_of_bounds_axis_d, sizeof(__pyx_k_Index_out_of_bounds_axis_d), 0, 0, 1, 0}, + {&__pyx_kp_s_Indirect_dimensions_not_supporte, __pyx_k_Indirect_dimensions_not_supporte, sizeof(__pyx_k_Indirect_dimensions_not_supporte), 0, 0, 1, 0}, + {&__pyx_kp_u_Invalid_mode_expected_c_or_fortr, __pyx_k_Invalid_mode_expected_c_or_fortr, sizeof(__pyx_k_Invalid_mode_expected_c_or_fortr), 0, 1, 0, 0}, + {&__pyx_kp_u_Invalid_shape_in_axis, __pyx_k_Invalid_shape_in_axis, sizeof(__pyx_k_Invalid_shape_in_axis), 0, 1, 0, 0}, + {&__pyx_n_s_MemoryError, __pyx_k_MemoryError, sizeof(__pyx_k_MemoryError), 0, 0, 1, 1}, + {&__pyx_kp_s_MemoryView_of_r_at_0x_x, __pyx_k_MemoryView_of_r_at_0x_x, sizeof(__pyx_k_MemoryView_of_r_at_0x_x), 0, 0, 1, 0}, + {&__pyx_kp_s_MemoryView_of_r_object, __pyx_k_MemoryView_of_r_object, sizeof(__pyx_k_MemoryView_of_r_object), 0, 0, 1, 0}, + {&__pyx_n_s_N, __pyx_k_N, sizeof(__pyx_k_N), 0, 0, 1, 1}, + {&__pyx_kp_u_None, __pyx_k_None, sizeof(__pyx_k_None), 0, 1, 0, 0}, + {&__pyx_n_s_NotImplementedError, __pyx_k_NotImplementedError, sizeof(__pyx_k_NotImplementedError), 0, 0, 1, 1}, + {&__pyx_n_b_O, __pyx_k_O, sizeof(__pyx_k_O), 0, 0, 0, 1}, + {&__pyx_kp_u_Out_of_bounds_on_buffer_access_a, __pyx_k_Out_of_bounds_on_buffer_access_a, sizeof(__pyx_k_Out_of_bounds_on_buffer_access_a), 0, 1, 0, 0}, + {&__pyx_n_s_PickleError, __pyx_k_PickleError, sizeof(__pyx_k_PickleError), 0, 0, 1, 1}, + {&__pyx_n_u_SQP, __pyx_k_SQP, sizeof(__pyx_k_SQP), 0, 1, 0, 1}, + {&__pyx_n_u_SQP_RTI, __pyx_k_SQP_RTI, sizeof(__pyx_k_SQP_RTI), 0, 1, 0, 1}, + {&__pyx_n_s_Sequence, __pyx_k_Sequence, sizeof(__pyx_k_Sequence), 0, 0, 1, 1}, + {&__pyx_kp_s_Step_may_not_be_zero_axis_d, __pyx_k_Step_may_not_be_zero_axis_d, sizeof(__pyx_k_Step_may_not_be_zero_axis_d), 0, 0, 1, 0}, + {&__pyx_kp_u_TODO, __pyx_k_TODO, sizeof(__pyx_k_TODO), 0, 1, 0, 0}, + {&__pyx_n_s_TypeError, __pyx_k_TypeError, sizeof(__pyx_k_TypeError), 0, 0, 1, 1}, + {&__pyx_kp_s_Unable_to_convert_item_to_object, __pyx_k_Unable_to_convert_item_to_object, sizeof(__pyx_k_Unable_to_convert_item_to_object), 0, 0, 1, 0}, + {&__pyx_n_s_ValueError, __pyx_k_ValueError, sizeof(__pyx_k_ValueError), 0, 0, 1, 1}, + {&__pyx_n_s_View_MemoryView, __pyx_k_View_MemoryView, sizeof(__pyx_k_View_MemoryView), 0, 0, 1, 1}, + {&__pyx_kp_u_Warning_acados_ocp_solver_reache, __pyx_k_Warning_acados_ocp_solver_reache, sizeof(__pyx_k_Warning_acados_ocp_solver_reache), 0, 1, 0, 0}, + {&__pyx_kp_u_Y_m_d_H_M_S_f, __pyx_k_Y_m_d_H_M_S_f, sizeof(__pyx_k_Y_m_d_H_M_S_f), 0, 1, 0, 0}, + {&__pyx_kp_u__16, __pyx_k__16, sizeof(__pyx_k__16), 0, 1, 0, 0}, + {&__pyx_n_u__17, __pyx_k__17, sizeof(__pyx_k__17), 0, 1, 0, 1}, + {&__pyx_kp_u__2, __pyx_k__2, sizeof(__pyx_k__2), 0, 1, 0, 0}, + {&__pyx_n_s__3, __pyx_k__3, sizeof(__pyx_k__3), 0, 0, 1, 1}, + {&__pyx_kp_u__31, __pyx_k__31, sizeof(__pyx_k__31), 0, 1, 0, 0}, + {&__pyx_kp_u__6, __pyx_k__6, sizeof(__pyx_k__6), 0, 1, 0, 0}, + {&__pyx_kp_u__7, __pyx_k__7, sizeof(__pyx_k__7), 0, 1, 0, 0}, + {&__pyx_n_s__94, __pyx_k__94, sizeof(__pyx_k__94), 0, 0, 1, 1}, + {&__pyx_n_s_abc, __pyx_k_abc, sizeof(__pyx_k_abc), 0, 0, 1, 1}, + {&__pyx_kp_u_acados_acados_ocp_solver_returne, __pyx_k_acados_acados_ocp_solver_returne, sizeof(__pyx_k_acados_acados_ocp_solver_returne), 0, 1, 0, 0}, + {&__pyx_n_s_acados_template_acados_ocp_solve, __pyx_k_acados_template_acados_ocp_solve, sizeof(__pyx_k_acados_template_acados_ocp_solve), 0, 0, 1, 1}, + {&__pyx_n_s_allocate_buffer, __pyx_k_allocate_buffer, sizeof(__pyx_k_allocate_buffer), 0, 0, 1, 1}, + {&__pyx_n_u_alpha, __pyx_k_alpha, sizeof(__pyx_k_alpha), 0, 1, 0, 1}, + {&__pyx_n_u_alpha_min, __pyx_k_alpha_min, sizeof(__pyx_k_alpha_min), 0, 1, 0, 1}, + {&__pyx_n_u_alpha_reduction, __pyx_k_alpha_reduction, sizeof(__pyx_k_alpha_reduction), 0, 1, 0, 1}, + {&__pyx_kp_u_alpha_values_are_not_available_f, __pyx_k_alpha_values_are_not_available_f, sizeof(__pyx_k_alpha_values_are_not_available_f), 0, 1, 0, 0}, + {&__pyx_kp_u_and, __pyx_k_and, sizeof(__pyx_k_and), 0, 1, 0, 0}, + {&__pyx_n_s_array, __pyx_k_array, sizeof(__pyx_k_array), 0, 0, 1, 1}, + {&__pyx_n_s_ascontiguousarray, __pyx_k_ascontiguousarray, sizeof(__pyx_k_ascontiguousarray), 0, 0, 1, 1}, + {&__pyx_n_s_asfortranarray, __pyx_k_asfortranarray, sizeof(__pyx_k_asfortranarray), 0, 0, 1, 1}, + {&__pyx_n_s_asyncio_coroutines, __pyx_k_asyncio_coroutines, sizeof(__pyx_k_asyncio_coroutines), 0, 0, 1, 1}, + {&__pyx_kp_u_at_stage, __pyx_k_at_stage, sizeof(__pyx_k_at_stage), 0, 1, 0, 0}, + {&__pyx_n_s_base, __pyx_k_base, sizeof(__pyx_k_base), 0, 0, 1, 1}, + {&__pyx_n_s_c, __pyx_k_c, sizeof(__pyx_k_c), 0, 0, 1, 1}, + {&__pyx_n_u_c, __pyx_k_c, sizeof(__pyx_k_c), 0, 1, 0, 1}, + {&__pyx_n_s_class, __pyx_k_class, sizeof(__pyx_k_class), 0, 0, 1, 1}, + {&__pyx_n_s_class_getitem, __pyx_k_class_getitem, sizeof(__pyx_k_class_getitem), 0, 0, 1, 1}, + {&__pyx_n_s_cline_in_traceback, __pyx_k_cline_in_traceback, sizeof(__pyx_k_cline_in_traceback), 0, 0, 1, 1}, + {&__pyx_n_s_collections, __pyx_k_collections, sizeof(__pyx_k_collections), 0, 0, 1, 1}, + {&__pyx_kp_s_collections_abc, __pyx_k_collections_abc, sizeof(__pyx_k_collections_abc), 0, 0, 1, 0}, + {&__pyx_n_s_constraints_fields, __pyx_k_constraints_fields, sizeof(__pyx_k_constraints_fields), 0, 0, 1, 1}, + {&__pyx_n_s_constraints_set, __pyx_k_constraints_set, sizeof(__pyx_k_constraints_set), 0, 0, 1, 1}, + {&__pyx_kp_u_constraints_set_value_must_be_nu, __pyx_k_constraints_set_value_must_be_nu, sizeof(__pyx_k_constraints_set_value_must_be_nu), 0, 1, 0, 0}, + {&__pyx_kp_s_contiguous_and_direct, __pyx_k_contiguous_and_direct, sizeof(__pyx_k_contiguous_and_direct), 0, 0, 1, 0}, + {&__pyx_kp_s_contiguous_and_indirect, __pyx_k_contiguous_and_indirect, sizeof(__pyx_k_contiguous_and_indirect), 0, 0, 1, 0}, + {&__pyx_n_s_cost_fields, __pyx_k_cost_fields, sizeof(__pyx_k_cost_fields), 0, 0, 1, 1}, + {&__pyx_n_s_cost_set, __pyx_k_cost_set, sizeof(__pyx_k_cost_set), 0, 0, 1, 1}, + {&__pyx_kp_u_cost_set_value_must_be_numpy_arr, __pyx_k_cost_set_value_must_be_numpy_arr, sizeof(__pyx_k_cost_set_value_must_be_numpy_arr), 0, 1, 0, 0}, + {&__pyx_n_s_count, __pyx_k_count, sizeof(__pyx_k_count), 0, 0, 1, 1}, + {&__pyx_n_s_custom_update, __pyx_k_custom_update, sizeof(__pyx_k_custom_update), 0, 0, 1, 1}, + {&__pyx_n_u_d, __pyx_k_d, sizeof(__pyx_k_d), 0, 1, 0, 1}, + {&__pyx_n_s_data, __pyx_k_data, sizeof(__pyx_k_data), 0, 0, 1, 1}, + {&__pyx_n_s_data_2, __pyx_k_data_2, sizeof(__pyx_k_data_2), 0, 0, 1, 1}, + {&__pyx_n_s_data_len, __pyx_k_data_len, sizeof(__pyx_k_data_len), 0, 0, 1, 1}, + {&__pyx_n_s_datetime, __pyx_k_datetime, sizeof(__pyx_k_datetime), 0, 0, 1, 1}, + {&__pyx_n_s_default, __pyx_k_default, sizeof(__pyx_k_default), 0, 0, 1, 1}, + {&__pyx_n_s_dict, __pyx_k_dict, sizeof(__pyx_k_dict), 0, 0, 1, 1}, + {&__pyx_n_s_dims, __pyx_k_dims, sizeof(__pyx_k_dims), 0, 0, 1, 1}, + {&__pyx_kp_u_disable, __pyx_k_disable, sizeof(__pyx_k_disable), 0, 1, 0, 0}, + {&__pyx_n_s_double_fields, __pyx_k_double_fields, sizeof(__pyx_k_double_fields), 0, 0, 1, 1}, + {&__pyx_n_s_double_value, __pyx_k_double_value, sizeof(__pyx_k_double_value), 0, 0, 1, 1}, + {&__pyx_n_s_dtype, __pyx_k_dtype, sizeof(__pyx_k_dtype), 0, 0, 1, 1}, + {&__pyx_n_s_dtype_is_object, __pyx_k_dtype_is_object, sizeof(__pyx_k_dtype_is_object), 0, 0, 1, 1}, + {&__pyx_n_s_dump, __pyx_k_dump, sizeof(__pyx_k_dump), 0, 0, 1, 1}, + {&__pyx_kp_u_enable, __pyx_k_enable, sizeof(__pyx_k_enable), 0, 1, 0, 0}, + {&__pyx_n_s_encode, __pyx_k_encode, sizeof(__pyx_k_encode), 0, 0, 1, 1}, + {&__pyx_n_s_enter, __pyx_k_enter, sizeof(__pyx_k_enter), 0, 0, 1, 1}, + {&__pyx_n_s_enumerate, __pyx_k_enumerate, sizeof(__pyx_k_enumerate), 0, 0, 1, 1}, + {&__pyx_n_u_eps_sufficient_descent, __pyx_k_eps_sufficient_descent, sizeof(__pyx_k_eps_sufficient_descent), 0, 1, 0, 1}, + {&__pyx_n_s_error, __pyx_k_error, sizeof(__pyx_k_error), 0, 0, 1, 1}, + {&__pyx_n_s_eval_param_sens, __pyx_k_eval_param_sens, sizeof(__pyx_k_eval_param_sens), 0, 0, 1, 1}, + {&__pyx_n_u_ex, __pyx_k_ex, sizeof(__pyx_k_ex), 0, 1, 0, 1}, + {&__pyx_n_s_exit, __pyx_k_exit, sizeof(__pyx_k_exit), 0, 0, 1, 1}, + {&__pyx_n_s_f, __pyx_k_f, sizeof(__pyx_k_f), 0, 0, 1, 1}, + {&__pyx_n_s_field, __pyx_k_field, sizeof(__pyx_k_field), 0, 0, 1, 1}, + {&__pyx_n_s_field_2, __pyx_k_field_2, sizeof(__pyx_k_field_2), 0, 0, 1, 1}, + {&__pyx_n_s_fields, __pyx_k_fields, sizeof(__pyx_k_fields), 0, 0, 1, 1}, + {&__pyx_n_s_filename, __pyx_k_filename, sizeof(__pyx_k_filename), 0, 0, 1, 1}, + {&__pyx_n_s_flags, __pyx_k_flags, sizeof(__pyx_k_flags), 0, 0, 1, 1}, + {&__pyx_n_s_float64, __pyx_k_float64, sizeof(__pyx_k_float64), 0, 0, 1, 1}, + {&__pyx_kp_u_for_field, __pyx_k_for_field, sizeof(__pyx_k_for_field), 0, 1, 0, 0}, + {&__pyx_n_s_format, __pyx_k_format, sizeof(__pyx_k_format), 0, 0, 1, 1}, + {&__pyx_n_s_fortran, __pyx_k_fortran, sizeof(__pyx_k_fortran), 0, 0, 1, 1}, + {&__pyx_n_u_fortran, __pyx_k_fortran, sizeof(__pyx_k_fortran), 0, 1, 0, 1}, + {&__pyx_n_s_full_stats, __pyx_k_full_stats, sizeof(__pyx_k_full_stats), 0, 0, 1, 1}, + {&__pyx_n_u_full_step_dual, __pyx_k_full_step_dual, sizeof(__pyx_k_full_step_dual), 0, 1, 0, 1}, + {&__pyx_kp_u_gc, __pyx_k_gc, sizeof(__pyx_k_gc), 0, 1, 0, 0}, + {&__pyx_n_s_get, __pyx_k_get, sizeof(__pyx_k_get), 0, 0, 1, 1}, + {&__pyx_n_s_get_cost, __pyx_k_get_cost, sizeof(__pyx_k_get_cost), 0, 0, 1, 1}, + {&__pyx_n_s_get_from_qp_in, __pyx_k_get_from_qp_in, sizeof(__pyx_k_get_from_qp_in), 0, 0, 1, 1}, + {&__pyx_n_s_get_pointers_solver, __pyx_k_get_pointers_solver, sizeof(__pyx_k_get_pointers_solver), 0, 0, 1, 1}, + {&__pyx_n_s_get_residuals, __pyx_k_get_residuals, sizeof(__pyx_k_get_residuals), 0, 0, 1, 1}, + {&__pyx_n_s_get_stat_double, __pyx_k_get_stat_double, sizeof(__pyx_k_get_stat_double), 0, 0, 1, 1}, + {&__pyx_n_s_get_stat_int, __pyx_k_get_stat_int, sizeof(__pyx_k_get_stat_int), 0, 0, 1, 1}, + {&__pyx_n_s_get_stat_matrix, __pyx_k_get_stat_matrix, sizeof(__pyx_k_get_stat_matrix), 0, 0, 1, 1}, + {&__pyx_n_s_get_stats, __pyx_k_get_stats, sizeof(__pyx_k_get_stats), 0, 0, 1, 1}, + {&__pyx_n_s_getcwd, __pyx_k_getcwd, sizeof(__pyx_k_getcwd), 0, 0, 1, 1}, + {&__pyx_n_s_getstate, __pyx_k_getstate, sizeof(__pyx_k_getstate), 0, 0, 1, 1}, + {&__pyx_n_u_globalization, __pyx_k_globalization, sizeof(__pyx_k_globalization), 0, 1, 0, 1}, + {&__pyx_n_u_globalization_use_SOC, __pyx_k_globalization_use_SOC, sizeof(__pyx_k_globalization_use_SOC), 0, 1, 0, 1}, + {&__pyx_kp_u_got, __pyx_k_got, sizeof(__pyx_k_got), 0, 1, 0, 0}, + {&__pyx_kp_u_got_differing_extents_in_dimensi, __pyx_k_got_differing_extents_in_dimensi, sizeof(__pyx_k_got_differing_extents_in_dimensi), 0, 1, 0, 0}, + {&__pyx_n_s_i, __pyx_k_i, sizeof(__pyx_k_i), 0, 0, 1, 1}, + {&__pyx_n_s_i_string, __pyx_k_i_string, sizeof(__pyx_k_i_string), 0, 0, 1, 1}, + {&__pyx_n_s_id, __pyx_k_id, sizeof(__pyx_k_id), 0, 0, 1, 1}, + {&__pyx_n_s_idx, __pyx_k_idx, sizeof(__pyx_k_idx), 0, 0, 1, 1}, + {&__pyx_n_s_idx_values, __pyx_k_idx_values, sizeof(__pyx_k_idx_values), 0, 0, 1, 1}, + {&__pyx_n_s_import, __pyx_k_import, sizeof(__pyx_k_import), 0, 0, 1, 1}, + {&__pyx_n_s_indent, __pyx_k_indent, sizeof(__pyx_k_indent), 0, 0, 1, 1}, + {&__pyx_n_s_index, __pyx_k_index, sizeof(__pyx_k_index), 0, 0, 1, 1}, + {&__pyx_n_u_initialize_t_slacks, __pyx_k_initialize_t_slacks, sizeof(__pyx_k_initialize_t_slacks), 0, 1, 0, 1}, + {&__pyx_n_s_initializing, __pyx_k_initializing, sizeof(__pyx_k_initializing), 0, 0, 1, 1}, + {&__pyx_n_s_int, __pyx_k_int, sizeof(__pyx_k_int), 0, 0, 1, 1}, + {&__pyx_n_s_int32, __pyx_k_int32, sizeof(__pyx_k_int32), 0, 0, 1, 1}, + {&__pyx_n_s_int_fields, __pyx_k_int_fields, sizeof(__pyx_k_int_fields), 0, 0, 1, 1}, + {&__pyx_n_s_int_value, __pyx_k_int_value, sizeof(__pyx_k_int_value), 0, 0, 1, 1}, + {&__pyx_n_s_is_coroutine, __pyx_k_is_coroutine, sizeof(__pyx_k_is_coroutine), 0, 0, 1, 1}, + {&__pyx_kp_u_isenabled, __pyx_k_isenabled, sizeof(__pyx_k_isenabled), 0, 1, 0, 0}, + {&__pyx_n_s_isfile, __pyx_k_isfile, sizeof(__pyx_k_isfile), 0, 0, 1, 1}, + {&__pyx_n_s_itemsize, __pyx_k_itemsize, sizeof(__pyx_k_itemsize), 0, 0, 1, 1}, + {&__pyx_kp_s_itemsize_0_for_cython_array, __pyx_k_itemsize_0_for_cython_array, sizeof(__pyx_k_itemsize_0_for_cython_array), 0, 0, 1, 0}, + {&__pyx_n_u_iterate, __pyx_k_iterate, sizeof(__pyx_k_iterate), 0, 1, 0, 1}, + {&__pyx_n_s_join, __pyx_k_join, sizeof(__pyx_k_join), 0, 0, 1, 1}, + {&__pyx_n_s_json, __pyx_k_json, sizeof(__pyx_k_json), 0, 0, 1, 1}, + {&__pyx_kp_u_json_2, __pyx_k_json_2, sizeof(__pyx_k_json_2), 0, 1, 0, 0}, + {&__pyx_n_s_k, __pyx_k_k, sizeof(__pyx_k_k), 0, 0, 1, 1}, + {&__pyx_n_s_key, __pyx_k_key, sizeof(__pyx_k_key), 0, 0, 1, 1}, + {&__pyx_n_s_keys, __pyx_k_keys, sizeof(__pyx_k_keys), 0, 0, 1, 1}, + {&__pyx_n_s_lN, __pyx_k_lN, sizeof(__pyx_k_lN), 0, 0, 1, 1}, + {&__pyx_n_u_lam, __pyx_k_lam, sizeof(__pyx_k_lam), 0, 1, 0, 1}, + {&__pyx_n_u_lam_2, __pyx_k_lam_2, sizeof(__pyx_k_lam_2), 0, 1, 0, 1}, + {&__pyx_n_u_lbu, __pyx_k_lbu, sizeof(__pyx_k_lbu), 0, 1, 0, 1}, + {&__pyx_n_u_lbx, __pyx_k_lbx, sizeof(__pyx_k_lbx), 0, 1, 0, 1}, + {&__pyx_n_u_line_search_use_sufficient_desce, __pyx_k_line_search_use_sufficient_desce, sizeof(__pyx_k_line_search_use_sufficient_desce), 0, 1, 0, 1}, + {&__pyx_n_s_load, __pyx_k_load, sizeof(__pyx_k_load), 0, 0, 1, 1}, + {&__pyx_n_s_load_iterate, __pyx_k_load_iterate, sizeof(__pyx_k_load_iterate), 0, 0, 1, 1}, + {&__pyx_kp_u_load_iterate_failed_file_does_no, __pyx_k_load_iterate_failed_file_does_no, sizeof(__pyx_k_load_iterate_failed_file_does_no), 0, 1, 0, 0}, + {&__pyx_n_s_m, __pyx_k_m, sizeof(__pyx_k_m), 0, 0, 1, 1}, + {&__pyx_n_s_main, __pyx_k_main, sizeof(__pyx_k_main), 0, 0, 1, 1}, + {&__pyx_n_s_mem_fields, __pyx_k_mem_fields, sizeof(__pyx_k_mem_fields), 0, 0, 1, 1}, + {&__pyx_n_s_memview, __pyx_k_memview, sizeof(__pyx_k_memview), 0, 0, 1, 1}, + {&__pyx_n_s_min_size, __pyx_k_min_size, sizeof(__pyx_k_min_size), 0, 0, 1, 1}, + {&__pyx_n_s_mode, __pyx_k_mode, sizeof(__pyx_k_mode), 0, 0, 1, 1}, + {&__pyx_n_s_model_name, __pyx_k_model_name, sizeof(__pyx_k_model_name), 0, 0, 1, 1}, + {&__pyx_n_s_msg, __pyx_k_msg, sizeof(__pyx_k_msg), 0, 0, 1, 1}, + {&__pyx_n_s_n, __pyx_k_n, sizeof(__pyx_k_n), 0, 0, 1, 1}, + {&__pyx_n_s_n_update, __pyx_k_n_update, sizeof(__pyx_k_n_update), 0, 0, 1, 1}, + {&__pyx_n_s_name, __pyx_k_name, sizeof(__pyx_k_name), 0, 0, 1, 1}, + {&__pyx_n_s_name_2, __pyx_k_name_2, sizeof(__pyx_k_name_2), 0, 0, 1, 1}, + {&__pyx_n_s_ndarray, __pyx_k_ndarray, sizeof(__pyx_k_ndarray), 0, 0, 1, 1}, + {&__pyx_n_s_ndim, __pyx_k_ndim, sizeof(__pyx_k_ndim), 0, 0, 1, 1}, + {&__pyx_n_s_new, __pyx_k_new, sizeof(__pyx_k_new), 0, 0, 1, 1}, + {&__pyx_n_s_new_time_steps, __pyx_k_new_time_steps, sizeof(__pyx_k_new_time_steps), 0, 0, 1, 1}, + {&__pyx_n_s_nlp_solver_type, __pyx_k_nlp_solver_type, sizeof(__pyx_k_nlp_solver_type), 0, 0, 1, 1}, + {&__pyx_kp_s_no_default___reduce___due_to_non, __pyx_k_no_default___reduce___due_to_non, sizeof(__pyx_k_no_default___reduce___due_to_non), 0, 0, 1, 0}, + {&__pyx_n_s_np, __pyx_k_np, sizeof(__pyx_k_np), 0, 0, 1, 1}, + {&__pyx_n_s_numpy, __pyx_k_numpy, sizeof(__pyx_k_numpy), 0, 0, 1, 1}, + {&__pyx_kp_u_numpy_core_multiarray_failed_to, __pyx_k_numpy_core_multiarray_failed_to, sizeof(__pyx_k_numpy_core_multiarray_failed_to), 0, 1, 0, 0}, + {&__pyx_kp_u_numpy_core_umath_failed_to_impor, __pyx_k_numpy_core_umath_failed_to_impor, sizeof(__pyx_k_numpy_core_umath_failed_to_impor), 0, 1, 0, 0}, + {&__pyx_n_s_nx, __pyx_k_nx, sizeof(__pyx_k_nx), 0, 0, 1, 1}, + {&__pyx_n_s_obj, __pyx_k_obj, sizeof(__pyx_k_obj), 0, 0, 1, 1}, + {&__pyx_n_s_open, __pyx_k_open, sizeof(__pyx_k_open), 0, 0, 1, 1}, + {&__pyx_n_s_options_set, __pyx_k_options_set, sizeof(__pyx_k_options_set), 0, 0, 1, 1}, + {&__pyx_n_s_order, __pyx_k_order, sizeof(__pyx_k_order), 0, 0, 1, 1}, + {&__pyx_n_s_os, __pyx_k_os, sizeof(__pyx_k_os), 0, 0, 1, 1}, + {&__pyx_n_s_out, __pyx_k_out, sizeof(__pyx_k_out), 0, 0, 1, 1}, + {&__pyx_n_s_out_fields, __pyx_k_out_fields, sizeof(__pyx_k_out_fields), 0, 0, 1, 1}, + {&__pyx_n_s_out_mat, __pyx_k_out_mat, sizeof(__pyx_k_out_mat), 0, 0, 1, 1}, + {&__pyx_n_s_overwrite, __pyx_k_overwrite, sizeof(__pyx_k_overwrite), 0, 0, 1, 1}, + {&__pyx_n_u_p, __pyx_k_p, sizeof(__pyx_k_p), 0, 1, 0, 1}, + {&__pyx_n_s_pack, __pyx_k_pack, sizeof(__pyx_k_pack), 0, 0, 1, 1}, + {&__pyx_n_s_param_values, __pyx_k_param_values, sizeof(__pyx_k_param_values), 0, 0, 1, 1}, + {&__pyx_kp_u_param_values_2, __pyx_k_param_values_2, sizeof(__pyx_k_param_values_2), 0, 1, 0, 0}, + {&__pyx_kp_u_param_values__and_idx_values__mu, __pyx_k_param_values__and_idx_values__mu, sizeof(__pyx_k_param_values__and_idx_values__mu), 0, 1, 0, 0}, + {&__pyx_kp_u_param_values__must_be_np_array, __pyx_k_param_values__must_be_np_array, sizeof(__pyx_k_param_values__must_be_np_array), 0, 1, 0, 0}, + {&__pyx_n_s_path, __pyx_k_path, sizeof(__pyx_k_path), 0, 0, 1, 1}, + {&__pyx_n_u_pi, __pyx_k_pi, sizeof(__pyx_k_pi), 0, 1, 0, 1}, + {&__pyx_n_u_pi_2, __pyx_k_pi_2, sizeof(__pyx_k_pi_2), 0, 1, 0, 1}, + {&__pyx_n_s_pickle, __pyx_k_pickle, sizeof(__pyx_k_pickle), 0, 0, 1, 1}, + {&__pyx_n_s_print, __pyx_k_print, sizeof(__pyx_k_print), 0, 0, 1, 1}, + {&__pyx_n_u_print_level, __pyx_k_print_level, sizeof(__pyx_k_print_level), 0, 1, 0, 1}, + {&__pyx_n_s_print_statistics, __pyx_k_print_statistics, sizeof(__pyx_k_print_statistics), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_PickleError, __pyx_k_pyx_PickleError, sizeof(__pyx_k_pyx_PickleError), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_checksum, __pyx_k_pyx_checksum, sizeof(__pyx_k_pyx_checksum), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_result, __pyx_k_pyx_result, sizeof(__pyx_k_pyx_result), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_state, __pyx_k_pyx_state, sizeof(__pyx_k_pyx_state), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_type, __pyx_k_pyx_type, sizeof(__pyx_k_pyx_type), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_unpickle_Enum, __pyx_k_pyx_unpickle_Enum, sizeof(__pyx_k_pyx_unpickle_Enum), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_vtable, __pyx_k_pyx_vtable, sizeof(__pyx_k_pyx_vtable), 0, 0, 1, 1}, + {&__pyx_n_u_qp_iter, __pyx_k_qp_iter, sizeof(__pyx_k_qp_iter), 0, 1, 0, 1}, + {&__pyx_n_u_qp_mu0, __pyx_k_qp_mu0, sizeof(__pyx_k_qp_mu0), 0, 1, 0, 1}, + {&__pyx_n_s_qp_solver_cond_N, __pyx_k_qp_solver_cond_N, sizeof(__pyx_k_qp_solver_cond_N), 0, 0, 1, 1}, + {&__pyx_n_u_qp_tau_min, __pyx_k_qp_tau_min, sizeof(__pyx_k_qp_tau_min), 0, 1, 0, 1}, + {&__pyx_n_u_qp_tol_comp, __pyx_k_qp_tol_comp, sizeof(__pyx_k_qp_tol_comp), 0, 1, 0, 1}, + {&__pyx_n_u_qp_tol_eq, __pyx_k_qp_tol_eq, sizeof(__pyx_k_qp_tol_eq), 0, 1, 0, 1}, + {&__pyx_n_u_qp_tol_ineq, __pyx_k_qp_tol_ineq, sizeof(__pyx_k_qp_tol_ineq), 0, 1, 0, 1}, + {&__pyx_n_u_qp_tol_stat, __pyx_k_qp_tol_stat, sizeof(__pyx_k_qp_tol_stat), 0, 1, 0, 1}, + {&__pyx_n_u_qp_warm_start, __pyx_k_qp_warm_start, sizeof(__pyx_k_qp_warm_start), 0, 1, 0, 1}, + {&__pyx_n_u_r, __pyx_k_r, sizeof(__pyx_k_r), 0, 1, 0, 1}, + {&__pyx_n_s_range, __pyx_k_range, sizeof(__pyx_k_range), 0, 0, 1, 1}, + {&__pyx_n_s_recompute, __pyx_k_recompute, sizeof(__pyx_k_recompute), 0, 0, 1, 1}, + {&__pyx_n_s_reduce, __pyx_k_reduce, sizeof(__pyx_k_reduce), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_cython, __pyx_k_reduce_cython, sizeof(__pyx_k_reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_ex, __pyx_k_reduce_ex, sizeof(__pyx_k_reduce_ex), 0, 0, 1, 1}, + {&__pyx_n_s_register, __pyx_k_register, sizeof(__pyx_k_register), 0, 0, 1, 1}, + {&__pyx_n_b_res_comp, __pyx_k_res_comp, sizeof(__pyx_k_res_comp), 0, 0, 0, 1}, + {&__pyx_n_b_res_eq, __pyx_k_res_eq, sizeof(__pyx_k_res_eq), 0, 0, 0, 1}, + {&__pyx_n_b_res_ineq, __pyx_k_res_ineq, sizeof(__pyx_k_res_ineq), 0, 0, 0, 1}, + {&__pyx_n_b_res_stat, __pyx_k_res_stat, sizeof(__pyx_k_res_stat), 0, 0, 0, 1}, + {&__pyx_n_s_reset, __pyx_k_reset, sizeof(__pyx_k_reset), 0, 0, 1, 1}, + {&__pyx_n_s_reset_qp_solver_mem, __pyx_k_reset_qp_solver_mem, sizeof(__pyx_k_reset_qp_solver_mem), 0, 0, 1, 1}, + {&__pyx_n_u_residuals, __pyx_k_residuals, sizeof(__pyx_k_residuals), 0, 1, 0, 1}, + {&__pyx_n_u_rti_phase, __pyx_k_rti_phase, sizeof(__pyx_k_rti_phase), 0, 1, 0, 1}, + {&__pyx_n_s_self, __pyx_k_self, sizeof(__pyx_k_self), 0, 0, 1, 1}, + {&__pyx_n_s_set, __pyx_k_set, sizeof(__pyx_k_set), 0, 0, 1, 1}, + {&__pyx_n_s_set_new_time_steps, __pyx_k_set_new_time_steps, sizeof(__pyx_k_set_new_time_steps), 0, 0, 1, 1}, + {&__pyx_n_s_set_params_sparse, __pyx_k_set_params_sparse, sizeof(__pyx_k_set_params_sparse), 0, 0, 1, 1}, + {&__pyx_kp_u_set_value_must_be_numpy_array_go, __pyx_k_set_value_must_be_numpy_array_go, sizeof(__pyx_k_set_value_must_be_numpy_array_go), 0, 1, 0, 0}, + {&__pyx_n_s_setstate, __pyx_k_setstate, sizeof(__pyx_k_setstate), 0, 0, 1, 1}, + {&__pyx_n_s_setstate_cython, __pyx_k_setstate_cython, sizeof(__pyx_k_setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_shape, __pyx_k_shape, sizeof(__pyx_k_shape), 0, 0, 1, 1}, + {&__pyx_n_s_size, __pyx_k_size, sizeof(__pyx_k_size), 0, 0, 1, 1}, + {&__pyx_n_u_sl, __pyx_k_sl, sizeof(__pyx_k_sl), 0, 1, 0, 1}, + {&__pyx_n_u_sl_2, __pyx_k_sl_2, sizeof(__pyx_k_sl_2), 0, 1, 0, 1}, + {&__pyx_n_s_solution, __pyx_k_solution, sizeof(__pyx_k_solution), 0, 0, 1, 1}, + {&__pyx_n_s_solve, __pyx_k_solve, sizeof(__pyx_k_solve), 0, 0, 1, 1}, + {&__pyx_n_s_solve_for_x0, __pyx_k_solve_for_x0, sizeof(__pyx_k_solve_for_x0), 0, 0, 1, 1}, + {&__pyx_kp_u_solver_option_must_be_of_type_fl, __pyx_k_solver_option_must_be_of_type_fl, sizeof(__pyx_k_solver_option_must_be_of_type_fl), 0, 1, 0, 0}, + {&__pyx_kp_u_solver_option_must_be_of_type_in, __pyx_k_solver_option_must_be_of_type_in, sizeof(__pyx_k_solver_option_must_be_of_type_in), 0, 1, 0, 0}, + {&__pyx_kp_u_solver_option_must_be_of_type_st, __pyx_k_solver_option_must_be_of_type_st, sizeof(__pyx_k_solver_option_must_be_of_type_st), 0, 1, 0, 0}, + {&__pyx_n_s_sort_keys, __pyx_k_sort_keys, sizeof(__pyx_k_sort_keys), 0, 0, 1, 1}, + {&__pyx_n_s_spec, __pyx_k_spec, sizeof(__pyx_k_spec), 0, 0, 1, 1}, + {&__pyx_n_s_split, __pyx_k_split, sizeof(__pyx_k_split), 0, 0, 1, 1}, + {&__pyx_n_s_sqp_iter, __pyx_k_sqp_iter, sizeof(__pyx_k_sqp_iter), 0, 0, 1, 1}, + {&__pyx_n_u_sqp_iter, __pyx_k_sqp_iter, sizeof(__pyx_k_sqp_iter), 0, 1, 0, 1}, + {&__pyx_n_s_stage, __pyx_k_stage, sizeof(__pyx_k_stage), 0, 0, 1, 1}, + {&__pyx_n_s_start, __pyx_k_start, sizeof(__pyx_k_start), 0, 0, 1, 1}, + {&__pyx_n_s_stat_m, __pyx_k_stat_m, sizeof(__pyx_k_stat_m), 0, 0, 1, 1}, + {&__pyx_n_u_stat_m, __pyx_k_stat_m, sizeof(__pyx_k_stat_m), 0, 1, 0, 1}, + {&__pyx_n_s_stat_n, __pyx_k_stat_n, sizeof(__pyx_k_stat_n), 0, 0, 1, 1}, + {&__pyx_n_u_stat_n, __pyx_k_stat_n, sizeof(__pyx_k_stat_n), 0, 1, 0, 1}, + {&__pyx_n_u_statistics, __pyx_k_statistics, sizeof(__pyx_k_statistics), 0, 1, 0, 1}, + {&__pyx_n_s_status, __pyx_k_status, sizeof(__pyx_k_status), 0, 0, 1, 1}, + {&__pyx_n_s_step, __pyx_k_step, sizeof(__pyx_k_step), 0, 0, 1, 1}, + {&__pyx_n_u_step_length, __pyx_k_step_length, sizeof(__pyx_k_step_length), 0, 1, 0, 1}, + {&__pyx_n_s_stop, __pyx_k_stop, sizeof(__pyx_k_stop), 0, 0, 1, 1}, + {&__pyx_n_s_store_iterate, __pyx_k_store_iterate, sizeof(__pyx_k_store_iterate), 0, 0, 1, 1}, + {&__pyx_n_s_store_iterate_locals_lambda, __pyx_k_store_iterate_locals_lambda, sizeof(__pyx_k_store_iterate_locals_lambda), 0, 0, 1, 1}, + {&__pyx_kp_u_stored_current_iterate_in, __pyx_k_stored_current_iterate_in, sizeof(__pyx_k_stored_current_iterate_in), 0, 1, 0, 0}, + {&__pyx_n_s_strftime, __pyx_k_strftime, sizeof(__pyx_k_strftime), 0, 0, 1, 1}, + {&__pyx_kp_s_strided_and_direct, __pyx_k_strided_and_direct, sizeof(__pyx_k_strided_and_direct), 0, 0, 1, 0}, + {&__pyx_kp_s_strided_and_direct_or_indirect, __pyx_k_strided_and_direct_or_indirect, sizeof(__pyx_k_strided_and_direct_or_indirect), 0, 0, 1, 0}, + {&__pyx_kp_s_strided_and_indirect, __pyx_k_strided_and_indirect, sizeof(__pyx_k_strided_and_indirect), 0, 0, 1, 0}, + {&__pyx_n_s_string_fields, __pyx_k_string_fields, sizeof(__pyx_k_string_fields), 0, 0, 1, 1}, + {&__pyx_n_s_string_value, __pyx_k_string_value, sizeof(__pyx_k_string_value), 0, 0, 1, 1}, + {&__pyx_kp_s_stringsource, __pyx_k_stringsource, sizeof(__pyx_k_stringsource), 0, 0, 1, 0}, + {&__pyx_n_s_struct, __pyx_k_struct, sizeof(__pyx_k_struct), 0, 0, 1, 1}, + {&__pyx_n_u_su, __pyx_k_su, sizeof(__pyx_k_su), 0, 1, 0, 1}, + {&__pyx_n_u_su_2, __pyx_k_su_2, sizeof(__pyx_k_su_2), 0, 1, 0, 1}, + {&__pyx_n_s_sys, __pyx_k_sys, sizeof(__pyx_k_sys), 0, 0, 1, 1}, + {&__pyx_n_u_t, __pyx_k_t, sizeof(__pyx_k_t), 0, 1, 0, 1}, + {&__pyx_n_u_t_2, __pyx_k_t_2, sizeof(__pyx_k_t_2), 0, 1, 0, 1}, + {&__pyx_n_s_test, __pyx_k_test, sizeof(__pyx_k_test), 0, 0, 1, 1}, + {&__pyx_kp_s_third_party_acados_acados_templa, __pyx_k_third_party_acados_acados_templa, sizeof(__pyx_k_third_party_acados_acados_templa), 0, 0, 1, 0}, + {&__pyx_n_u_time_glob, __pyx_k_time_glob, sizeof(__pyx_k_time_glob), 0, 1, 0, 1}, + {&__pyx_n_u_time_lin, __pyx_k_time_lin, sizeof(__pyx_k_time_lin), 0, 1, 0, 1}, + {&__pyx_n_u_time_qp, __pyx_k_time_qp, sizeof(__pyx_k_time_qp), 0, 1, 0, 1}, + {&__pyx_n_u_time_qp_solver_call, __pyx_k_time_qp_solver_call, sizeof(__pyx_k_time_qp_solver_call), 0, 1, 0, 1}, + {&__pyx_n_u_time_qp_xcond, __pyx_k_time_qp_xcond, sizeof(__pyx_k_time_qp_xcond), 0, 1, 0, 1}, + {&__pyx_n_u_time_reg, __pyx_k_time_reg, sizeof(__pyx_k_time_reg), 0, 1, 0, 1}, + {&__pyx_n_u_time_sim, __pyx_k_time_sim, sizeof(__pyx_k_time_sim), 0, 1, 0, 1}, + {&__pyx_n_u_time_sim_ad, __pyx_k_time_sim_ad, sizeof(__pyx_k_time_sim_ad), 0, 1, 0, 1}, + {&__pyx_n_u_time_sim_la, __pyx_k_time_sim_la, sizeof(__pyx_k_time_sim_la), 0, 1, 0, 1}, + {&__pyx_n_u_time_solution_sensitivities, __pyx_k_time_solution_sensitivities, sizeof(__pyx_k_time_solution_sensitivities), 0, 1, 0, 1}, + {&__pyx_n_u_time_tot, __pyx_k_time_tot, sizeof(__pyx_k_time_tot), 0, 1, 0, 1}, + {&__pyx_n_u_tol_comp, __pyx_k_tol_comp, sizeof(__pyx_k_tol_comp), 0, 1, 0, 1}, + {&__pyx_n_u_tol_eq, __pyx_k_tol_eq, sizeof(__pyx_k_tol_eq), 0, 1, 0, 1}, + {&__pyx_n_u_tol_ineq, __pyx_k_tol_ineq, sizeof(__pyx_k_tol_ineq), 0, 1, 0, 1}, + {&__pyx_n_u_tol_stat, __pyx_k_tol_stat, sizeof(__pyx_k_tol_stat), 0, 1, 0, 1}, + {&__pyx_n_s_tolist, __pyx_k_tolist, sizeof(__pyx_k_tolist), 0, 0, 1, 1}, + {&__pyx_n_u_u, __pyx_k_u, sizeof(__pyx_k_u), 0, 1, 0, 1}, + {&__pyx_n_s_u0, __pyx_k_u0, sizeof(__pyx_k_u0), 0, 0, 1, 1}, + {&__pyx_n_u_u_2, __pyx_k_u_2, sizeof(__pyx_k_u_2), 0, 1, 0, 1}, + {&__pyx_n_u_ubu, __pyx_k_ubu, sizeof(__pyx_k_ubu), 0, 1, 0, 1}, + {&__pyx_n_u_ubx, __pyx_k_ubx, sizeof(__pyx_k_ubx), 0, 1, 0, 1}, + {&__pyx_kp_s_unable_to_allocate_array_data, __pyx_k_unable_to_allocate_array_data, sizeof(__pyx_k_unable_to_allocate_array_data), 0, 0, 1, 0}, + {&__pyx_kp_s_unable_to_allocate_shape_and_str, __pyx_k_unable_to_allocate_shape_and_str, sizeof(__pyx_k_unable_to_allocate_shape_and_str), 0, 0, 1, 0}, + {&__pyx_n_s_unpack, __pyx_k_unpack, sizeof(__pyx_k_unpack), 0, 0, 1, 1}, + {&__pyx_n_s_update, __pyx_k_update, sizeof(__pyx_k_update), 0, 0, 1, 1}, + {&__pyx_n_s_update_qp_solver_cond_N, __pyx_k_update_qp_solver_cond_N, sizeof(__pyx_k_update_qp_solver_cond_N), 0, 0, 1, 1}, + {&__pyx_n_s_utcnow, __pyx_k_utcnow, sizeof(__pyx_k_utcnow), 0, 0, 1, 1}, + {&__pyx_kp_u_utf_8, __pyx_k_utf_8, sizeof(__pyx_k_utf_8), 0, 1, 0, 0}, + {&__pyx_n_s_value, __pyx_k_value, sizeof(__pyx_k_value), 0, 0, 1, 1}, + {&__pyx_n_s_value_2, __pyx_k_value_2, sizeof(__pyx_k_value_2), 0, 0, 1, 1}, + {&__pyx_n_s_value_shape, __pyx_k_value_shape, sizeof(__pyx_k_value_shape), 0, 0, 1, 1}, + {&__pyx_n_s_version_info, __pyx_k_version_info, sizeof(__pyx_k_version_info), 0, 0, 1, 1}, + {&__pyx_n_u_w, __pyx_k_w, sizeof(__pyx_k_w), 0, 1, 0, 1}, + {&__pyx_n_u_warm_start_first_qp, __pyx_k_warm_start_first_qp, sizeof(__pyx_k_warm_start_first_qp), 0, 1, 0, 1}, + {&__pyx_kp_u_with_dimension, __pyx_k_with_dimension, sizeof(__pyx_k_with_dimension), 0, 1, 0, 0}, + {&__pyx_kp_u_with_dimension_you_have, __pyx_k_with_dimension_you_have, sizeof(__pyx_k_with_dimension_you_have), 0, 1, 0, 0}, + {&__pyx_n_b_x, __pyx_k_x, sizeof(__pyx_k_x), 0, 0, 0, 1}, + {&__pyx_n_s_x, __pyx_k_x, sizeof(__pyx_k_x), 0, 0, 1, 1}, + {&__pyx_n_u_x, __pyx_k_x, sizeof(__pyx_k_x), 0, 1, 0, 1}, + {&__pyx_n_s_x0_bar, __pyx_k_x0_bar, sizeof(__pyx_k_x0_bar), 0, 0, 1, 1}, + {&__pyx_n_u_x_2, __pyx_k_x_2, sizeof(__pyx_k_x_2), 0, 1, 0, 1}, + {&__pyx_n_u_xdot_guess, __pyx_k_xdot_guess, sizeof(__pyx_k_xdot_guess), 0, 1, 0, 1}, + {&__pyx_n_u_y_ref, __pyx_k_y_ref, sizeof(__pyx_k_y_ref), 0, 1, 0, 1}, + {&__pyx_kp_u_you_have, __pyx_k_you_have, sizeof(__pyx_k_you_have), 0, 1, 0, 0}, + {&__pyx_n_u_yref, __pyx_k_yref, sizeof(__pyx_k_yref), 0, 1, 0, 1}, + {&__pyx_n_u_z, __pyx_k_z, sizeof(__pyx_k_z), 0, 1, 0, 1}, + {&__pyx_n_u_z_2, __pyx_k_z_2, sizeof(__pyx_k_z_2), 0, 1, 0, 1}, + {&__pyx_n_b_z_guess, __pyx_k_z_guess, sizeof(__pyx_k_z_guess), 0, 0, 0, 1}, + {&__pyx_n_u_z_guess, __pyx_k_z_guess, sizeof(__pyx_k_z_guess), 0, 1, 0, 1}, + {&__pyx_n_s_zeros, __pyx_k_zeros, sizeof(__pyx_k_zeros), 0, 0, 1, 1}, + {0, 0, 0, 0, 0, 0, 0} + }; + return __Pyx_InitStrings(__pyx_string_tab); +} +/* #### Code section: cached_builtins ### */ +static CYTHON_SMALL_CODE int __Pyx_InitCachedBuiltins(void) { + __pyx_builtin_AssertionError = __Pyx_GetBuiltinName(__pyx_n_s_AssertionError); if (!__pyx_builtin_AssertionError) __PYX_ERR(0, 82, __pyx_L1_error) + __pyx_builtin_print = __Pyx_GetBuiltinName(__pyx_n_s_print); if (!__pyx_builtin_print) __PYX_ERR(0, 113, __pyx_L1_error) + __pyx_builtin_NotImplementedError = __Pyx_GetBuiltinName(__pyx_n_s_NotImplementedError); if (!__pyx_builtin_NotImplementedError) __PYX_ERR(0, 160, __pyx_L1_error) + __pyx_builtin_range = __Pyx_GetBuiltinName(__pyx_n_s_range); if (!__pyx_builtin_range) __PYX_ERR(0, 340, __pyx_L1_error) + __pyx_builtin_open = __Pyx_GetBuiltinName(__pyx_n_s_open); if (!__pyx_builtin_open) __PYX_ERR(0, 357, __pyx_L1_error) + __pyx_builtin_TypeError = __Pyx_GetBuiltinName(__pyx_n_s_TypeError); if (!__pyx_builtin_TypeError) __PYX_ERR(1, 2, __pyx_L1_error) + __pyx_builtin___import__ = __Pyx_GetBuiltinName(__pyx_n_s_import); if (!__pyx_builtin___import__) __PYX_ERR(1, 100, __pyx_L1_error) + __pyx_builtin_ValueError = __Pyx_GetBuiltinName(__pyx_n_s_ValueError); if (!__pyx_builtin_ValueError) __PYX_ERR(1, 141, __pyx_L1_error) + __pyx_builtin_MemoryError = __Pyx_GetBuiltinName(__pyx_n_s_MemoryError); if (!__pyx_builtin_MemoryError) __PYX_ERR(1, 156, __pyx_L1_error) + __pyx_builtin_enumerate = __Pyx_GetBuiltinName(__pyx_n_s_enumerate); if (!__pyx_builtin_enumerate) __PYX_ERR(1, 159, __pyx_L1_error) + __pyx_builtin_Ellipsis = __Pyx_GetBuiltinName(__pyx_n_s_Ellipsis); if (!__pyx_builtin_Ellipsis) __PYX_ERR(1, 408, __pyx_L1_error) + __pyx_builtin_id = __Pyx_GetBuiltinName(__pyx_n_s_id); if (!__pyx_builtin_id) __PYX_ERR(1, 618, __pyx_L1_error) + __pyx_builtin_IndexError = __Pyx_GetBuiltinName(__pyx_n_s_IndexError); if (!__pyx_builtin_IndexError) __PYX_ERR(1, 914, __pyx_L1_error) + __pyx_builtin_ImportError = __Pyx_GetBuiltinName(__pyx_n_s_ImportError); if (!__pyx_builtin_ImportError) __PYX_ERR(2, 984, __pyx_L1_error) + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: cached_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_InitCachedConstants", 0); + + /* "View.MemoryView":582 + * def suboffsets(self): + * if self.view.suboffsets == NULL: + * return (-1,) * self.view.ndim # <<<<<<<<<<<<<< + * + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + */ + __pyx_tuple__4 = PyTuple_New(1); if (unlikely(!__pyx_tuple__4)) __PYX_ERR(1, 582, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__4); + __Pyx_INCREF(__pyx_int_neg_1); + __Pyx_GIVEREF(__pyx_int_neg_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_tuple__4, 0, __pyx_int_neg_1)) __PYX_ERR(1, 582, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_tuple__4); + + /* "View.MemoryView":679 + * tup = index if isinstance(index, tuple) else (index,) + * + * result = [slice(None)] * ndim # <<<<<<<<<<<<<< + * have_slices = False + * seen_ellipsis = False + */ + __pyx_slice__5 = PySlice_New(Py_None, Py_None, Py_None); if (unlikely(!__pyx_slice__5)) __PYX_ERR(1, 679, __pyx_L1_error) + __Pyx_GOTREF(__pyx_slice__5); + __Pyx_GIVEREF(__pyx_slice__5); + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + */ + __pyx_tuple__8 = PyTuple_Pack(3, __pyx_int_136983863, __pyx_int_112105877, __pyx_int_184977713); if (unlikely(!__pyx_tuple__8)) __PYX_ERR(1, 4, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__8); + __Pyx_GIVEREF(__pyx_tuple__8); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":984 + * __pyx_import_array() + * except Exception: + * raise ImportError("numpy.core.multiarray failed to import") # <<<<<<<<<<<<<< + * + * cdef inline int import_umath() except -1: + */ + __pyx_tuple__9 = PyTuple_Pack(1, __pyx_kp_u_numpy_core_multiarray_failed_to); if (unlikely(!__pyx_tuple__9)) __PYX_ERR(2, 984, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__9); + __Pyx_GIVEREF(__pyx_tuple__9); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":990 + * _import_umath() + * except Exception: + * raise ImportError("numpy.core.umath failed to import") # <<<<<<<<<<<<<< + * + * cdef inline int import_ufunc() except -1: + */ + __pyx_tuple__10 = PyTuple_Pack(1, __pyx_kp_u_numpy_core_umath_failed_to_impor); if (unlikely(!__pyx_tuple__10)) __PYX_ERR(2, 990, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__10); + __Pyx_GIVEREF(__pyx_tuple__10); + + /* "acados_template/acados_ocp_solver_pyx.pyx":113 + * + * if status == 2: + * print("Warning: acados_ocp_solver reached maximum iterations.") # <<<<<<<<<<<<<< + * elif status != 0: + * raise Exception(f'acados acados_ocp_solver returned status {status}') + */ + __pyx_tuple__11 = PyTuple_Pack(1, __pyx_kp_u_Warning_acados_ocp_solver_reache); if (unlikely(!__pyx_tuple__11)) __PYX_ERR(0, 113, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__11); + __Pyx_GIVEREF(__pyx_tuple__11); + + /* "acados_template/acados_ocp_solver_pyx.pyx":117 + * raise Exception(f'acados acados_ocp_solver returned status {status}') + * + * u0 = self.get(0, "u") # <<<<<<<<<<<<<< + * return u0 + * + */ + __pyx_tuple__12 = PyTuple_Pack(2, __pyx_int_0, __pyx_n_u_u); if (unlikely(!__pyx_tuple__12)) __PYX_ERR(0, 117, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__12); + __Pyx_GIVEREF(__pyx_tuple__12); + + /* "acados_template/acados_ocp_solver_pyx.pyx":160 + * """ + * + * raise NotImplementedError("AcadosOcpSolverCython: does not support set_new_time_steps() since it is only a prototyping feature") # <<<<<<<<<<<<<< + * # # unlikely but still possible + * # if not self.solver_created: + */ + __pyx_tuple__13 = PyTuple_Pack(1, __pyx_kp_u_AcadosOcpSolverCython_does_not_s); if (unlikely(!__pyx_tuple__13)) __PYX_ERR(0, 160, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__13); + __Pyx_GIVEREF(__pyx_tuple__13); + + /* "acados_template/acados_ocp_solver_pyx.pyx":212 + * `qp_solver_cond_N < N`. + * """ + * raise NotImplementedError("AcadosOcpSolverCython: does not support update_qp_solver_cond_N() since it is only a prototyping feature") # <<<<<<<<<<<<<< + * + * # # unlikely but still possible + */ + __pyx_tuple__14 = PyTuple_Pack(1, __pyx_kp_u_AcadosOcpSolverCython_does_not_s_2); if (unlikely(!__pyx_tuple__14)) __PYX_ERR(0, 212, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__14); + __Pyx_GIVEREF(__pyx_tuple__14); + + /* "acados_template/acados_ocp_solver_pyx.pyx":245 + * # checks + * if not isinstance(index, int): + * raise Exception('AcadosOcpSolverCython.eval_param_sens(): index must be Integer.') # <<<<<<<<<<<<<< + * + * cdef int nx = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, self.nlp_dims, self.nlp_out, 0, "x".encode('utf-8')) + */ + __pyx_tuple__15 = PyTuple_Pack(1, __pyx_kp_u_AcadosOcpSolverCython_eval_param); if (unlikely(!__pyx_tuple__15)) __PYX_ERR(0, 245, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__15); + __Pyx_GIVEREF(__pyx_tuple__15); + + /* "acados_template/acados_ocp_solver_pyx.pyx":333 + * # append timestamp + * if os.path.isfile(filename): + * filename = filename[:-5] # <<<<<<<<<<<<<< + * filename += datetime.utcnow().strftime('%Y-%m-%d-%H:%M:%S.%f') + '.json' + * + */ + __pyx_slice__18 = PySlice_New(Py_None, __pyx_int_neg_5, Py_None); if (unlikely(!__pyx_slice__18)) __PYX_ERR(0, 333, __pyx_L1_error) + __Pyx_GOTREF(__pyx_slice__18); + __Pyx_GIVEREF(__pyx_slice__18); + + /* "acados_template/acados_ocp_solver_pyx.pyx":357 + * + * # save + * with open(filename, 'w') as f: # <<<<<<<<<<<<<< + * json.dump(solution, f, default=lambda x: x.tolist(), indent=4, sort_keys=True) + * print("stored current iterate in ", os.path.join(os.getcwd(), filename)) + */ + __pyx_tuple__19 = PyTuple_Pack(3, Py_None, Py_None, Py_None); if (unlikely(!__pyx_tuple__19)) __PYX_ERR(0, 357, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__19); + __Pyx_GIVEREF(__pyx_tuple__19); + + /* "acados_template/acados_ocp_solver_pyx.pyx":442 + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': + * return full_stats[6, :] # <<<<<<<<<<<<<< + * elif self.nlp_solver_type == 'SQP_RTI': + * return full_stats[2, :] + */ + __pyx_tuple__20 = PyTuple_Pack(2, __pyx_int_6, __pyx_slice__5); if (unlikely(!__pyx_tuple__20)) __PYX_ERR(0, 442, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__20); + __Pyx_GIVEREF(__pyx_tuple__20); + + /* "acados_template/acados_ocp_solver_pyx.pyx":444 + * return full_stats[6, :] + * elif self.nlp_solver_type == 'SQP_RTI': + * return full_stats[2, :] # <<<<<<<<<<<<<< + * + * elif field_ == 'alpha': + */ + __pyx_tuple__21 = PyTuple_Pack(2, __pyx_int_2, __pyx_slice__5); if (unlikely(!__pyx_tuple__21)) __PYX_ERR(0, 444, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__21); + __Pyx_GIVEREF(__pyx_tuple__21); + + /* "acados_template/acados_ocp_solver_pyx.pyx":449 + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': + * return full_stats[7, :] # <<<<<<<<<<<<<< + * else: # self.nlp_solver_type == 'SQP_RTI': + * raise Exception("alpha values are not available for SQP_RTI") + */ + __pyx_tuple__22 = PyTuple_Pack(2, __pyx_int_7, __pyx_slice__5); if (unlikely(!__pyx_tuple__22)) __PYX_ERR(0, 449, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__22); + __Pyx_GIVEREF(__pyx_tuple__22); + + /* "acados_template/acados_ocp_solver_pyx.pyx":451 + * return full_stats[7, :] + * else: # self.nlp_solver_type == 'SQP_RTI': + * raise Exception("alpha values are not available for SQP_RTI") # <<<<<<<<<<<<<< + * + * elif field_ == 'residuals': + */ + __pyx_tuple__23 = PyTuple_Pack(1, __pyx_kp_u_alpha_values_are_not_available_f); if (unlikely(!__pyx_tuple__23)) __PYX_ERR(0, 451, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__23); + __Pyx_GIVEREF(__pyx_tuple__23); + + /* "acados_template/acados_ocp_solver_pyx.pyx":457 + * + * else: + * raise NotImplementedError("TODO!") # <<<<<<<<<<<<<< + * + * + */ + __pyx_tuple__24 = PyTuple_Pack(1, __pyx_kp_u_TODO); if (unlikely(!__pyx_tuple__24)) __PYX_ERR(0, 457, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__24); + __Pyx_GIVEREF(__pyx_tuple__24); + + /* "acados_template/acados_ocp_solver_pyx.pyx":466 + * + * def __get_stat_double(self, field): + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) + * return out + */ + __pyx_tuple__25 = PyTuple_Pack(1, __pyx_int_1); if (unlikely(!__pyx_tuple__25)) __PYX_ERR(0, 466, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__25); + __Pyx_GIVEREF(__pyx_tuple__25); + + /* "acados_template/acados_ocp_solver_pyx.pyx":501 + * + * # create output array + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.ascontiguousarray(np.zeros((4,), dtype=np.float64)) # <<<<<<<<<<<<<< + * cdef double double_value + * + */ + __pyx_tuple__26 = PyTuple_Pack(1, __pyx_int_4); if (unlikely(!__pyx_tuple__26)) __PYX_ERR(0, 501, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__26); + __Pyx_GIVEREF(__pyx_tuple__26); + __pyx_tuple__27 = PyTuple_Pack(1, __pyx_tuple__26); if (unlikely(!__pyx_tuple__27)) __PYX_ERR(0, 501, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__27); + __Pyx_GIVEREF(__pyx_tuple__27); + + /* "acados_template/acados_ocp_solver_pyx.pyx":611 + * if len(value_shape) == 1: + * value_shape = (value_shape[0], 0) + * value = np.asfortranarray(value_[None,:]) # <<<<<<<<<<<<<< + * + * elif len(value_shape) == 2: + */ + __pyx_tuple__28 = PyTuple_Pack(2, Py_None, __pyx_slice__5); if (unlikely(!__pyx_tuple__28)) __PYX_ERR(0, 611, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__28); + __Pyx_GIVEREF(__pyx_tuple__28); + + /* "acados_template/acados_ocp_solver_pyx.pyx":720 + * if field_ == 'rti_phase': + * if value_ < 0 or value_ > 2: + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' # <<<<<<<<<<<<<< + * 'take only values 0, 1, 2 for SQP-RTI-type solvers') + * if self.nlp_solver_type != 'SQP_RTI' and value_ > 0: + */ + __pyx_tuple__29 = PyTuple_Pack(1, __pyx_kp_u_AcadosOcpSolverCython_solve_argu); if (unlikely(!__pyx_tuple__29)) __PYX_ERR(0, 720, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__29); + __Pyx_GIVEREF(__pyx_tuple__29); + + /* "acados_template/acados_ocp_solver_pyx.pyx":723 + * 'take only values 0, 1, 2 for SQP-RTI-type solvers') + * if self.nlp_solver_type != 'SQP_RTI' and value_ > 0: + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' # <<<<<<<<<<<<<< + * 'take only value 0 for SQP-type solvers') + * + */ + __pyx_tuple__30 = PyTuple_Pack(1, __pyx_kp_u_AcadosOcpSolverCython_solve_argu_2); if (unlikely(!__pyx_tuple__30)) __PYX_ERR(0, 723, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__30); + __Pyx_GIVEREF(__pyx_tuple__30); + + /* "acados_template/acados_ocp_solver_pyx.pyx":759 + * + * if not isinstance(param_values_, np.ndarray): + * raise Exception('param_values_ must be np.array.') # <<<<<<<<<<<<<< + * + * if param_values_.shape[0] != len(idx_values_): + */ + __pyx_tuple__32 = PyTuple_Pack(1, __pyx_kp_u_param_values__must_be_np_array); if (unlikely(!__pyx_tuple__32)) __PYX_ERR(0, 759, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__32); + __Pyx_GIVEREF(__pyx_tuple__32); + + /* "View.MemoryView":100 + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: + * if __import__("sys").version_info >= (3, 3): # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + */ + __pyx_tuple__33 = PyTuple_Pack(1, __pyx_n_s_sys); if (unlikely(!__pyx_tuple__33)) __PYX_ERR(1, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__33); + __Pyx_GIVEREF(__pyx_tuple__33); + __pyx_tuple__34 = PyTuple_Pack(2, __pyx_int_3, __pyx_int_3); if (unlikely(!__pyx_tuple__34)) __PYX_ERR(1, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__34); + __Pyx_GIVEREF(__pyx_tuple__34); + + /* "View.MemoryView":101 + * try: + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence # <<<<<<<<<<<<<< + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence + */ + __pyx_tuple__35 = PyTuple_Pack(1, __pyx_kp_s_collections_abc); if (unlikely(!__pyx_tuple__35)) __PYX_ERR(1, 101, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__35); + __Pyx_GIVEREF(__pyx_tuple__35); + + /* "View.MemoryView":103 + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence # <<<<<<<<<<<<<< + * except: + * + */ + __pyx_tuple__36 = PyTuple_Pack(1, __pyx_n_s_collections); if (unlikely(!__pyx_tuple__36)) __PYX_ERR(1, 103, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__36); + __Pyx_GIVEREF(__pyx_tuple__36); + + /* "View.MemoryView":309 + * return self.name + * + * cdef generic = Enum("") # <<<<<<<<<<<<<< + * cdef strided = Enum("") # default + * cdef indirect = Enum("") + */ + __pyx_tuple__37 = PyTuple_Pack(1, __pyx_kp_s_strided_and_direct_or_indirect); if (unlikely(!__pyx_tuple__37)) __PYX_ERR(1, 309, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__37); + __Pyx_GIVEREF(__pyx_tuple__37); + + /* "View.MemoryView":310 + * + * cdef generic = Enum("") + * cdef strided = Enum("") # default # <<<<<<<<<<<<<< + * cdef indirect = Enum("") + * + */ + __pyx_tuple__38 = PyTuple_Pack(1, __pyx_kp_s_strided_and_direct); if (unlikely(!__pyx_tuple__38)) __PYX_ERR(1, 310, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__38); + __Pyx_GIVEREF(__pyx_tuple__38); + + /* "View.MemoryView":311 + * cdef generic = Enum("") + * cdef strided = Enum("") # default + * cdef indirect = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_tuple__39 = PyTuple_Pack(1, __pyx_kp_s_strided_and_indirect); if (unlikely(!__pyx_tuple__39)) __PYX_ERR(1, 311, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__39); + __Pyx_GIVEREF(__pyx_tuple__39); + + /* "View.MemoryView":314 + * + * + * cdef contiguous = Enum("") # <<<<<<<<<<<<<< + * cdef indirect_contiguous = Enum("") + * + */ + __pyx_tuple__40 = PyTuple_Pack(1, __pyx_kp_s_contiguous_and_direct); if (unlikely(!__pyx_tuple__40)) __PYX_ERR(1, 314, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__40); + __Pyx_GIVEREF(__pyx_tuple__40); + + /* "View.MemoryView":315 + * + * cdef contiguous = Enum("") + * cdef indirect_contiguous = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_tuple__41 = PyTuple_Pack(1, __pyx_kp_s_contiguous_and_indirect); if (unlikely(!__pyx_tuple__41)) __PYX_ERR(1, 315, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__41); + __Pyx_GIVEREF(__pyx_tuple__41); + + /* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + __pyx_tuple__42 = PyTuple_Pack(5, __pyx_n_s_pyx_type, __pyx_n_s_pyx_checksum, __pyx_n_s_pyx_state, __pyx_n_s_pyx_PickleError, __pyx_n_s_pyx_result); if (unlikely(!__pyx_tuple__42)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__42); + __Pyx_GIVEREF(__pyx_tuple__42); + __pyx_codeobj__43 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__42, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_pyx_unpickle_Enum, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__43)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":89 + * + * + * def __get_pointers_solver(self): # <<<<<<<<<<<<<< + * """ + * Private function to get the pointers for solver + */ + __pyx_tuple__44 = PyTuple_Pack(1, __pyx_n_s_self); if (unlikely(!__pyx_tuple__44)) __PYX_ERR(0, 89, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__44); + __Pyx_GIVEREF(__pyx_tuple__44); + __pyx_codeobj__45 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__44, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_pointers_solver, 89, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__45)) __PYX_ERR(0, 89, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":103 + * + * + * def solve_for_x0(self, x0_bar): # <<<<<<<<<<<<<< + * """ + * Wrapper around `solve()` which sets initial state constraint, solves the OCP, and returns u0. + */ + __pyx_tuple__46 = PyTuple_Pack(4, __pyx_n_s_self, __pyx_n_s_x0_bar, __pyx_n_s_status, __pyx_n_s_u0); if (unlikely(!__pyx_tuple__46)) __PYX_ERR(0, 103, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__46); + __Pyx_GIVEREF(__pyx_tuple__46); + __pyx_codeobj__47 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 4, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__46, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_solve_for_x0, 103, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__47)) __PYX_ERR(0, 103, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":121 + * + * + * def solve(self): # <<<<<<<<<<<<<< + * """ + * Solve the ocp with current input. + */ + __pyx_codeobj__48 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__44, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_solve, 121, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__48)) __PYX_ERR(0, 121, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":128 + * + * + * def reset(self, reset_qp_solver_mem=1): # <<<<<<<<<<<<<< + * """ + * Sets current iterate to all zeros. + */ + __pyx_tuple__49 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_reset_qp_solver_mem); if (unlikely(!__pyx_tuple__49)) __PYX_ERR(0, 128, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__49); + __Pyx_GIVEREF(__pyx_tuple__49); + __pyx_codeobj__50 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__49, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_reset, 128, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__50)) __PYX_ERR(0, 128, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":135 + * + * + * def custom_update(self, data_): # <<<<<<<<<<<<<< + * """ + * A custom function that can be implemented by a user to be called between solver calls. + */ + __pyx_tuple__51 = PyTuple_Pack(4, __pyx_n_s_self, __pyx_n_s_data, __pyx_n_s_data_len, __pyx_n_s_data_2); if (unlikely(!__pyx_tuple__51)) __PYX_ERR(0, 135, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__51); + __Pyx_GIVEREF(__pyx_tuple__51); + __pyx_codeobj__52 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 4, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__51, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_custom_update, 135, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__52)) __PYX_ERR(0, 135, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":148 + * + * + * def set_new_time_steps(self, new_time_steps): # <<<<<<<<<<<<<< + * """ + * Set new time steps. + */ + __pyx_tuple__53 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_new_time_steps); if (unlikely(!__pyx_tuple__53)) __PYX_ERR(0, 148, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__53); + __Pyx_GIVEREF(__pyx_tuple__53); + __pyx_codeobj__54 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__53, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_set_new_time_steps, 148, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__54)) __PYX_ERR(0, 148, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":199 + * + * + * def update_qp_solver_cond_N(self, qp_solver_cond_N: int): # <<<<<<<<<<<<<< + * """ + * Recreate solver with new value `qp_solver_cond_N` with a partial condensing QP solver. + */ + __pyx_tuple__55 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_qp_solver_cond_N); if (unlikely(!__pyx_tuple__55)) __PYX_ERR(0, 199, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__55); + __Pyx_GIVEREF(__pyx_tuple__55); + __pyx_codeobj__56 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__55, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_update_qp_solver_cond_N, 199, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__56)) __PYX_ERR(0, 199, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":233 + * + * + * def eval_param_sens(self, index, stage=0, field="ex"): # <<<<<<<<<<<<<< + * """ + * Calculate the sensitivity of the curent solution with respect to the initial state component of index + */ + __pyx_tuple__57 = PyTuple_Pack(6, __pyx_n_s_self, __pyx_n_s_index, __pyx_n_s_stage, __pyx_n_s_field, __pyx_n_s_field_2, __pyx_n_s_nx); if (unlikely(!__pyx_tuple__57)) __PYX_ERR(0, 233, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__57); + __Pyx_GIVEREF(__pyx_tuple__57); + __pyx_codeobj__58 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 6, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__57, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_eval_param_sens, 233, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__58)) __PYX_ERR(0, 233, __pyx_L1_error) + __pyx_tuple__59 = PyTuple_Pack(2, __pyx_int_0, __pyx_n_u_ex); if (unlikely(!__pyx_tuple__59)) __PYX_ERR(0, 233, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__59); + __Pyx_GIVEREF(__pyx_tuple__59); + + /* "acados_template/acados_ocp_solver_pyx.pyx":258 + * + * + * def get(self, int stage, str field_): # <<<<<<<<<<<<<< + * """ + * Get the last solution of the solver: + */ + __pyx_tuple__60 = PyTuple_Pack(7, __pyx_n_s_self, __pyx_n_s_stage, __pyx_n_s_field_2, __pyx_n_s_out_fields, __pyx_n_s_field, __pyx_n_s_dims, __pyx_n_s_out); if (unlikely(!__pyx_tuple__60)) __PYX_ERR(0, 258, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__60); + __Pyx_GIVEREF(__pyx_tuple__60); + __pyx_codeobj__61 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 7, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__60, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get, 258, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__61)) __PYX_ERR(0, 258, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":301 + * + * + * def print_statistics(self): # <<<<<<<<<<<<<< + * """ + * prints statistics of previous solver run as a table: + */ + __pyx_codeobj__62 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__44, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_print_statistics, 301, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__62)) __PYX_ERR(0, 301, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":319 + * + * + * def store_iterate(self, filename='', overwrite=False): # <<<<<<<<<<<<<< + * """ + * Stores the current iterate of the ocp solver in a json file. + */ + __pyx_tuple__63 = PyTuple_Pack(10, __pyx_n_s_self, __pyx_n_s_filename, __pyx_n_s_overwrite, __pyx_n_s_json, __pyx_n_s_solution, __pyx_n_s_lN, __pyx_n_s_i, __pyx_n_s_i_string, __pyx_n_s_k, __pyx_n_s_f); if (unlikely(!__pyx_tuple__63)) __PYX_ERR(0, 319, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__63); + __Pyx_GIVEREF(__pyx_tuple__63); + __pyx_codeobj__64 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 10, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__63, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_store_iterate, 319, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__64)) __PYX_ERR(0, 319, __pyx_L1_error) + __pyx_tuple__65 = PyTuple_Pack(2, __pyx_kp_u__16, Py_False); if (unlikely(!__pyx_tuple__65)) __PYX_ERR(0, 319, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__65); + __Pyx_GIVEREF(__pyx_tuple__65); + + /* "acados_template/acados_ocp_solver_pyx.pyx":362 + * + * + * def load_iterate(self, filename): # <<<<<<<<<<<<<< + * """ + * Loads the iterate stored in json file with filename into the ocp solver. + */ + __pyx_tuple__66 = PyTuple_Pack(8, __pyx_n_s_self, __pyx_n_s_filename, __pyx_n_s_json, __pyx_n_s_f, __pyx_n_s_solution, __pyx_n_s_key, __pyx_n_s_field, __pyx_n_s_stage); if (unlikely(!__pyx_tuple__66)) __PYX_ERR(0, 362, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__66); + __Pyx_GIVEREF(__pyx_tuple__66); + __pyx_codeobj__67 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 8, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__66, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_load_iterate, 362, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__67)) __PYX_ERR(0, 362, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":378 + * + * + * def get_stats(self, field_): # <<<<<<<<<<<<<< + * """ + * Get the information of the last solver call. + */ + __pyx_tuple__68 = PyTuple_Pack(10, __pyx_n_s_self, __pyx_n_s_field_2, __pyx_n_s_double_fields, __pyx_n_s_fields, __pyx_n_s_field, __pyx_n_s_sqp_iter, __pyx_n_s_stat_m, __pyx_n_s_stat_n, __pyx_n_s_min_size, __pyx_n_s_full_stats); if (unlikely(!__pyx_tuple__68)) __PYX_ERR(0, 378, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__68); + __Pyx_GIVEREF(__pyx_tuple__68); + __pyx_codeobj__69 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 10, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__68, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_stats, 378, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__69)) __PYX_ERR(0, 378, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":460 + * + * + * def __get_stat_int(self, field): # <<<<<<<<<<<<<< + * cdef int out + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &out) + */ + __pyx_tuple__70 = PyTuple_Pack(3, __pyx_n_s_self, __pyx_n_s_field, __pyx_n_s_out); if (unlikely(!__pyx_tuple__70)) __PYX_ERR(0, 460, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__70); + __Pyx_GIVEREF(__pyx_tuple__70); + __pyx_codeobj__71 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__70, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_stat_int, 460, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__71)) __PYX_ERR(0, 460, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":465 + * return out + * + * def __get_stat_double(self, field): # <<<<<<<<<<<<<< + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) + */ + __pyx_codeobj__72 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__70, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_stat_double, 465, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__72)) __PYX_ERR(0, 465, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":470 + * return out + * + * def __get_stat_matrix(self, field, n, m): # <<<<<<<<<<<<<< + * cdef cnp.ndarray[cnp.float64_t, ndim=2] out_mat = np.ascontiguousarray(np.zeros((n, m)), dtype=np.float64) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_mat.data) + */ + __pyx_tuple__73 = PyTuple_Pack(5, __pyx_n_s_self, __pyx_n_s_field, __pyx_n_s_n, __pyx_n_s_m, __pyx_n_s_out_mat); if (unlikely(!__pyx_tuple__73)) __PYX_ERR(0, 470, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__73); + __Pyx_GIVEREF(__pyx_tuple__73); + __pyx_codeobj__74 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__73, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_stat_matrix, 470, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__74)) __PYX_ERR(0, 470, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":476 + * + * + * def get_cost(self): # <<<<<<<<<<<<<< + * """ + * Returns the cost value of the current solution. + */ + __pyx_tuple__75 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_out); if (unlikely(!__pyx_tuple__75)) __PYX_ERR(0, 476, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__75); + __Pyx_GIVEREF(__pyx_tuple__75); + __pyx_codeobj__76 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__75, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_cost, 476, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__76)) __PYX_ERR(0, 476, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":492 + * + * + * def get_residuals(self, recompute=False): # <<<<<<<<<<<<<< + * """ + * Returns an array of the form [res_stat, res_eq, res_ineq, res_comp]. + */ + __pyx_tuple__77 = PyTuple_Pack(5, __pyx_n_s_self, __pyx_n_s_recompute, __pyx_n_s_out, __pyx_n_s_double_value, __pyx_n_s_field); if (unlikely(!__pyx_tuple__77)) __PYX_ERR(0, 492, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__77); + __Pyx_GIVEREF(__pyx_tuple__77); + __pyx_codeobj__78 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__77, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_residuals, 492, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__78)) __PYX_ERR(0, 492, __pyx_L1_error) + __pyx_tuple__79 = PyTuple_Pack(1, Py_False); if (unlikely(!__pyx_tuple__79)) __PYX_ERR(0, 492, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__79); + __Pyx_GIVEREF(__pyx_tuple__79); + + /* "acados_template/acados_ocp_solver_pyx.pyx":524 + * + * # Note: this function should not be used anymore, better use cost_set, constraints_set + * def set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * + * """ + */ + __pyx_tuple__80 = PyTuple_Pack(12, __pyx_n_s_self, __pyx_n_s_stage, __pyx_n_s_field_2, __pyx_n_s_value, __pyx_n_s_cost_fields, __pyx_n_s_constraints_fields, __pyx_n_s_out_fields, __pyx_n_s_mem_fields, __pyx_n_s_field, __pyx_n_s_value_2, __pyx_n_s_dims, __pyx_n_s_msg); if (unlikely(!__pyx_tuple__80)) __PYX_ERR(0, 524, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__80); + __Pyx_GIVEREF(__pyx_tuple__80); + __pyx_codeobj__81 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 12, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__80, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_set, 524, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__81)) __PYX_ERR(0, 524, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":590 + * return + * + * def cost_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set numerical data in the cost module of the solver. + */ + __pyx_tuple__82 = PyTuple_Pack(8, __pyx_n_s_self, __pyx_n_s_stage, __pyx_n_s_field_2, __pyx_n_s_value, __pyx_n_s_field, __pyx_n_s_dims, __pyx_n_s_value_2, __pyx_n_s_value_shape); if (unlikely(!__pyx_tuple__82)) __PYX_ERR(0, 590, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__82); + __Pyx_GIVEREF(__pyx_tuple__82); + __pyx_codeobj__83 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 8, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__82, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_cost_set, 590, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__83)) __PYX_ERR(0, 590, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":625 + * + * + * def constraints_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set numerical data in the constraint module of the solver. + */ + __pyx_codeobj__84 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 8, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__82, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_constraints_set, 625, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__84)) __PYX_ERR(0, 625, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":663 + * + * + * def get_from_qp_in(self, int stage, str field_): # <<<<<<<<<<<<<< + * """ + * Get numerical data from the dynamics module of the solver: + */ + __pyx_tuple__85 = PyTuple_Pack(6, __pyx_n_s_self, __pyx_n_s_stage, __pyx_n_s_field_2, __pyx_n_s_field, __pyx_n_s_dims, __pyx_n_s_out); if (unlikely(!__pyx_tuple__85)) __PYX_ERR(0, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__85); + __Pyx_GIVEREF(__pyx_tuple__85); + __pyx_codeobj__86 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 6, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__85, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_from_qp_in, 663, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__86)) __PYX_ERR(0, 663, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":685 + * + * + * def options_set(self, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set options of the solver. + */ + __pyx_tuple__87 = PyTuple_Pack(10, __pyx_n_s_self, __pyx_n_s_field_2, __pyx_n_s_value, __pyx_n_s_int_fields, __pyx_n_s_double_fields, __pyx_n_s_string_fields, __pyx_n_s_field, __pyx_n_s_int_value, __pyx_n_s_double_value, __pyx_n_s_string_value); if (unlikely(!__pyx_tuple__87)) __PYX_ERR(0, 685, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__87); + __Pyx_GIVEREF(__pyx_tuple__87); + __pyx_codeobj__88 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 10, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__87, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_options_set, 685, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__88)) __PYX_ERR(0, 685, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":748 + * + * + * def set_params_sparse(self, int stage, idx_values_, param_values_): # <<<<<<<<<<<<<< + * """ + * set parameters of the solvers external function partially: + */ + __pyx_tuple__89 = PyTuple_Pack(7, __pyx_n_s_self, __pyx_n_s_stage, __pyx_n_s_idx_values, __pyx_n_s_param_values, __pyx_n_s_value_2, __pyx_n_s_idx, __pyx_n_s_n_update); if (unlikely(!__pyx_tuple__89)) __PYX_ERR(0, 748, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__89); + __Pyx_GIVEREF(__pyx_tuple__89); + __pyx_codeobj__90 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 7, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__89, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_set_params_sparse, 748, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__90)) __PYX_ERR(0, 748, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_codeobj__91 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__44, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__91)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_tuple__92 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_pyx_state); if (unlikely(!__pyx_tuple__92)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__92); + __Pyx_GIVEREF(__pyx_tuple__92); + __pyx_codeobj__93 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__92, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__93)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_RefNannyFinishContext(); + return -1; +} +/* #### Code section: init_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitConstants(void) { + __pyx_umethod_PyDict_Type_keys.type = (PyObject*)&PyDict_Type; + __pyx_umethod_PyDict_Type_keys.method_name = &__pyx_n_s_keys; + if (__Pyx_CreateStringTabAndInitStrings() < 0) __PYX_ERR(0, 1, __pyx_L1_error); + __pyx_int_0 = PyInt_FromLong(0); if (unlikely(!__pyx_int_0)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_1 = PyInt_FromLong(1); if (unlikely(!__pyx_int_1)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_2 = PyInt_FromLong(2); if (unlikely(!__pyx_int_2)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_3 = PyInt_FromLong(3); if (unlikely(!__pyx_int_3)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_4 = PyInt_FromLong(4); if (unlikely(!__pyx_int_4)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_6 = PyInt_FromLong(6); if (unlikely(!__pyx_int_6)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_7 = PyInt_FromLong(7); if (unlikely(!__pyx_int_7)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_112105877 = PyInt_FromLong(112105877L); if (unlikely(!__pyx_int_112105877)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_136983863 = PyInt_FromLong(136983863L); if (unlikely(!__pyx_int_136983863)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_184977713 = PyInt_FromLong(184977713L); if (unlikely(!__pyx_int_184977713)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_neg_1 = PyInt_FromLong(-1); if (unlikely(!__pyx_int_neg_1)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_neg_5 = PyInt_FromLong(-5); if (unlikely(!__pyx_int_neg_5)) __PYX_ERR(0, 1, __pyx_L1_error) + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: init_globals ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitGlobals(void) { + /* AssertionsEnabled.init */ + if (likely(__Pyx_init_assertions_enabled() == 0)); else + +if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 1, __pyx_L1_error) + + /* NumpyImportArray.init */ + /* + * Cython has automatically inserted a call to _import_array since + * you didn't include one when you cimported numpy. To disable this + * add the line + * numpy._import_array + */ +#ifdef NPY_FEATURE_VERSION +#ifndef NO_IMPORT_ARRAY +if (unlikely(_import_array() == -1)) { + PyErr_SetString(PyExc_ImportError, "numpy.core.multiarray failed to import " + "(auto-generated because you didn't call 'numpy.import_array()' after cimporting numpy; " + "use 'numpy._import_array' to disable if you are certain you don't need it)."); +} +#endif +#endif + +if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 1, __pyx_L1_error) + + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: init_module ### */ + +static CYTHON_SMALL_CODE int __Pyx_modinit_global_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_import_code(void); /*proto*/ + +static int __Pyx_modinit_global_init_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_global_init_code", 0); + /*--- Global init code ---*/ + __pyx_collections_abc_Sequence = Py_None; Py_INCREF(Py_None); + generic = Py_None; Py_INCREF(Py_None); + strided = Py_None; Py_INCREF(Py_None); + indirect = Py_None; Py_INCREF(Py_None); + contiguous = Py_None; Py_INCREF(Py_None); + indirect_contiguous = Py_None; Py_INCREF(Py_None); + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_variable_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_export_code", 0); + /*--- Variable export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_export_code", 0); + /*--- Function export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_type_init_code(void) { + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_modinit_type_init_code", 0); + /*--- Type init code ---*/ + #if CYTHON_USE_TYPE_SPECS + __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython_spec, NULL); if (unlikely(!__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython)) __PYX_ERR(0, 49, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython_spec, __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython) < 0) __PYX_ERR(0, 49, __pyx_L1_error) + #else + __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython = &__pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython) < 0) __PYX_ERR(0, 49, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dictoffset && __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_AcadosOcpSolverCython, (PyObject *) __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython) < 0) __PYX_ERR(0, 49, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython) < 0) __PYX_ERR(0, 49, __pyx_L1_error) + #endif + __pyx_vtabptr_array = &__pyx_vtable_array; + __pyx_vtable_array.get_memview = (PyObject *(*)(struct __pyx_array_obj *))__pyx_array_get_memview; + #if CYTHON_USE_TYPE_SPECS + __pyx_array_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_array_spec, NULL); if (unlikely(!__pyx_array_type)) __PYX_ERR(1, 114, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + __pyx_array_type->tp_as_buffer = &__pyx_tp_as_buffer_array; + if (!__pyx_array_type->tp_as_buffer->bf_releasebuffer && __pyx_array_type->tp_base->tp_as_buffer && __pyx_array_type->tp_base->tp_as_buffer->bf_releasebuffer) { + __pyx_array_type->tp_as_buffer->bf_releasebuffer = __pyx_array_type->tp_base->tp_as_buffer->bf_releasebuffer; + } + #elif defined(Py_bf_getbuffer) && defined(Py_bf_releasebuffer) + /* PY_VERSION_HEX >= 0x03090000 || Py_LIMITED_API >= 0x030B0000 */ + #elif defined(_MSC_VER) + #pragma message ("The buffer protocol is not supported in the Limited C-API < 3.11.") + #else + #warning "The buffer protocol is not supported in the Limited C-API < 3.11." + #endif + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_array_spec, __pyx_array_type) < 0) __PYX_ERR(1, 114, __pyx_L1_error) + #else + __pyx_array_type = &__pyx_type___pyx_array; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_array_type) < 0) __PYX_ERR(1, 114, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_array_type->tp_print = 0; + #endif + if (__Pyx_SetVtable(__pyx_array_type, __pyx_vtabptr_array) < 0) __PYX_ERR(1, 114, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_array_type) < 0) __PYX_ERR(1, 114, __pyx_L1_error) + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_array_type) < 0) __PYX_ERR(1, 114, __pyx_L1_error) + #endif + #if CYTHON_USE_TYPE_SPECS + __pyx_MemviewEnum_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_MemviewEnum_spec, NULL); if (unlikely(!__pyx_MemviewEnum_type)) __PYX_ERR(1, 302, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_MemviewEnum_spec, __pyx_MemviewEnum_type) < 0) __PYX_ERR(1, 302, __pyx_L1_error) + #else + __pyx_MemviewEnum_type = &__pyx_type___pyx_MemviewEnum; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_MemviewEnum_type) < 0) __PYX_ERR(1, 302, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_MemviewEnum_type->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_MemviewEnum_type->tp_dictoffset && __pyx_MemviewEnum_type->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_MemviewEnum_type->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_MemviewEnum_type) < 0) __PYX_ERR(1, 302, __pyx_L1_error) + #endif + __pyx_vtabptr_memoryview = &__pyx_vtable_memoryview; + __pyx_vtable_memoryview.get_item_pointer = (char *(*)(struct __pyx_memoryview_obj *, PyObject *))__pyx_memoryview_get_item_pointer; + __pyx_vtable_memoryview.is_slice = (PyObject *(*)(struct __pyx_memoryview_obj *, PyObject *))__pyx_memoryview_is_slice; + __pyx_vtable_memoryview.setitem_slice_assignment = (PyObject *(*)(struct __pyx_memoryview_obj *, PyObject *, PyObject *))__pyx_memoryview_setitem_slice_assignment; + __pyx_vtable_memoryview.setitem_slice_assign_scalar = (PyObject *(*)(struct __pyx_memoryview_obj *, struct __pyx_memoryview_obj *, PyObject *))__pyx_memoryview_setitem_slice_assign_scalar; + __pyx_vtable_memoryview.setitem_indexed = (PyObject *(*)(struct __pyx_memoryview_obj *, PyObject *, PyObject *))__pyx_memoryview_setitem_indexed; + __pyx_vtable_memoryview.convert_item_to_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *))__pyx_memoryview_convert_item_to_object; + __pyx_vtable_memoryview.assign_item_from_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *, PyObject *))__pyx_memoryview_assign_item_from_object; + __pyx_vtable_memoryview._get_base = (PyObject *(*)(struct __pyx_memoryview_obj *))__pyx_memoryview__get_base; + #if CYTHON_USE_TYPE_SPECS + __pyx_memoryview_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_memoryview_spec, NULL); if (unlikely(!__pyx_memoryview_type)) __PYX_ERR(1, 337, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + __pyx_memoryview_type->tp_as_buffer = &__pyx_tp_as_buffer_memoryview; + if (!__pyx_memoryview_type->tp_as_buffer->bf_releasebuffer && __pyx_memoryview_type->tp_base->tp_as_buffer && __pyx_memoryview_type->tp_base->tp_as_buffer->bf_releasebuffer) { + __pyx_memoryview_type->tp_as_buffer->bf_releasebuffer = __pyx_memoryview_type->tp_base->tp_as_buffer->bf_releasebuffer; + } + #elif defined(Py_bf_getbuffer) && defined(Py_bf_releasebuffer) + /* PY_VERSION_HEX >= 0x03090000 || Py_LIMITED_API >= 0x030B0000 */ + #elif defined(_MSC_VER) + #pragma message ("The buffer protocol is not supported in the Limited C-API < 3.11.") + #else + #warning "The buffer protocol is not supported in the Limited C-API < 3.11." + #endif + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_memoryview_spec, __pyx_memoryview_type) < 0) __PYX_ERR(1, 337, __pyx_L1_error) + #else + __pyx_memoryview_type = &__pyx_type___pyx_memoryview; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_memoryview_type) < 0) __PYX_ERR(1, 337, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_memoryview_type->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_memoryview_type->tp_dictoffset && __pyx_memoryview_type->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_memoryview_type->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (__Pyx_SetVtable(__pyx_memoryview_type, __pyx_vtabptr_memoryview) < 0) __PYX_ERR(1, 337, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_memoryview_type) < 0) __PYX_ERR(1, 337, __pyx_L1_error) + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_memoryview_type) < 0) __PYX_ERR(1, 337, __pyx_L1_error) + #endif + __pyx_vtabptr__memoryviewslice = &__pyx_vtable__memoryviewslice; + __pyx_vtable__memoryviewslice.__pyx_base = *__pyx_vtabptr_memoryview; + __pyx_vtable__memoryviewslice.__pyx_base.convert_item_to_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *))__pyx_memoryviewslice_convert_item_to_object; + __pyx_vtable__memoryviewslice.__pyx_base.assign_item_from_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *, PyObject *))__pyx_memoryviewslice_assign_item_from_object; + __pyx_vtable__memoryviewslice.__pyx_base._get_base = (PyObject *(*)(struct __pyx_memoryview_obj *))__pyx_memoryviewslice__get_base; + #if CYTHON_USE_TYPE_SPECS + __pyx_t_1 = PyTuple_Pack(1, (PyObject *)__pyx_memoryview_type); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 952, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_memoryviewslice_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_memoryviewslice_spec, __pyx_t_1); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_memoryviewslice_type)) __PYX_ERR(1, 952, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_memoryviewslice_spec, __pyx_memoryviewslice_type) < 0) __PYX_ERR(1, 952, __pyx_L1_error) + #else + __pyx_memoryviewslice_type = &__pyx_type___pyx_memoryviewslice; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + __pyx_memoryviewslice_type->tp_base = __pyx_memoryview_type; + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_memoryviewslice_type) < 0) __PYX_ERR(1, 952, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_memoryviewslice_type->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_memoryviewslice_type->tp_dictoffset && __pyx_memoryviewslice_type->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_memoryviewslice_type->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (__Pyx_SetVtable(__pyx_memoryviewslice_type, __pyx_vtabptr__memoryviewslice) < 0) __PYX_ERR(1, 952, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_memoryviewslice_type) < 0) __PYX_ERR(1, 952, __pyx_L1_error) + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_memoryviewslice_type) < 0) __PYX_ERR(1, 952, __pyx_L1_error) + #endif + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_RefNannyFinishContext(); + return -1; +} + +static int __Pyx_modinit_type_import_code(void) { + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_modinit_type_import_code", 0); + /*--- Type import code ---*/ + __pyx_t_1 = PyImport_ImportModule(__Pyx_BUILTIN_MODULE_NAME); if (unlikely(!__pyx_t_1)) __PYX_ERR(3, 9, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_ptype_7cpython_4type_type = __Pyx_ImportType_3_0_8(__pyx_t_1, __Pyx_BUILTIN_MODULE_NAME, "type", + #if defined(PYPY_VERSION_NUM) && PYPY_VERSION_NUM < 0x050B0000 + sizeof(PyTypeObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyTypeObject), + #elif CYTHON_COMPILING_IN_LIMITED_API + sizeof(PyTypeObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyTypeObject), + #else + sizeof(PyHeapTypeObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyHeapTypeObject), + #endif + __Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_7cpython_4type_type) __PYX_ERR(3, 9, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = PyImport_ImportModule("numpy"); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 202, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_ptype_5numpy_dtype = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "dtype", sizeof(PyArray_Descr), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyArray_Descr),__Pyx_ImportType_CheckSize_Ignore_3_0_8); if (!__pyx_ptype_5numpy_dtype) __PYX_ERR(2, 202, __pyx_L1_error) + __pyx_ptype_5numpy_flatiter = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "flatiter", sizeof(PyArrayIterObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyArrayIterObject),__Pyx_ImportType_CheckSize_Ignore_3_0_8); if (!__pyx_ptype_5numpy_flatiter) __PYX_ERR(2, 225, __pyx_L1_error) + __pyx_ptype_5numpy_broadcast = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "broadcast", sizeof(PyArrayMultiIterObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyArrayMultiIterObject),__Pyx_ImportType_CheckSize_Ignore_3_0_8); if (!__pyx_ptype_5numpy_broadcast) __PYX_ERR(2, 229, __pyx_L1_error) + __pyx_ptype_5numpy_ndarray = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "ndarray", sizeof(PyArrayObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyArrayObject),__Pyx_ImportType_CheckSize_Ignore_3_0_8); if (!__pyx_ptype_5numpy_ndarray) __PYX_ERR(2, 238, __pyx_L1_error) + __pyx_ptype_5numpy_generic = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "generic", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_generic) __PYX_ERR(2, 809, __pyx_L1_error) + __pyx_ptype_5numpy_number = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "number", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_number) __PYX_ERR(2, 811, __pyx_L1_error) + __pyx_ptype_5numpy_integer = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "integer", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_integer) __PYX_ERR(2, 813, __pyx_L1_error) + __pyx_ptype_5numpy_signedinteger = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "signedinteger", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_signedinteger) __PYX_ERR(2, 815, __pyx_L1_error) + __pyx_ptype_5numpy_unsignedinteger = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "unsignedinteger", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_unsignedinteger) __PYX_ERR(2, 817, __pyx_L1_error) + __pyx_ptype_5numpy_inexact = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "inexact", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_inexact) __PYX_ERR(2, 819, __pyx_L1_error) + __pyx_ptype_5numpy_floating = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "floating", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_floating) __PYX_ERR(2, 821, __pyx_L1_error) + __pyx_ptype_5numpy_complexfloating = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "complexfloating", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_complexfloating) __PYX_ERR(2, 823, __pyx_L1_error) + __pyx_ptype_5numpy_flexible = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "flexible", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_flexible) __PYX_ERR(2, 825, __pyx_L1_error) + __pyx_ptype_5numpy_character = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "character", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_character) __PYX_ERR(2, 827, __pyx_L1_error) + __pyx_ptype_5numpy_ufunc = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "ufunc", sizeof(PyUFuncObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyUFuncObject),__Pyx_ImportType_CheckSize_Ignore_3_0_8); if (!__pyx_ptype_5numpy_ufunc) __PYX_ERR(2, 866, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_RefNannyFinishContext(); + return -1; +} + +static int __Pyx_modinit_variable_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_import_code", 0); + /*--- Variable import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_import_code", 0); + /*--- Function import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + + +#if PY_MAJOR_VERSION >= 3 +#if CYTHON_PEP489_MULTI_PHASE_INIT +static PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def); /*proto*/ +static int __pyx_pymod_exec_acados_ocp_solver_pyx(PyObject* module); /*proto*/ +static PyModuleDef_Slot __pyx_moduledef_slots[] = { + {Py_mod_create, (void*)__pyx_pymod_create}, + {Py_mod_exec, (void*)__pyx_pymod_exec_acados_ocp_solver_pyx}, + {0, NULL} +}; +#endif + +#ifdef __cplusplus +namespace { + struct PyModuleDef __pyx_moduledef = + #else + static struct PyModuleDef __pyx_moduledef = + #endif + { + PyModuleDef_HEAD_INIT, + "acados_ocp_solver_pyx", + 0, /* m_doc */ + #if CYTHON_PEP489_MULTI_PHASE_INIT + 0, /* m_size */ + #elif CYTHON_USE_MODULE_STATE + sizeof(__pyx_mstate), /* m_size */ + #else + -1, /* m_size */ + #endif + __pyx_methods /* m_methods */, + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_moduledef_slots, /* m_slots */ + #else + NULL, /* m_reload */ + #endif + #if CYTHON_USE_MODULE_STATE + __pyx_m_traverse, /* m_traverse */ + __pyx_m_clear, /* m_clear */ + NULL /* m_free */ + #else + NULL, /* m_traverse */ + NULL, /* m_clear */ + NULL /* m_free */ + #endif + }; + #ifdef __cplusplus +} /* anonymous namespace */ +#endif +#endif + +#ifndef CYTHON_NO_PYINIT_EXPORT +#define __Pyx_PyMODINIT_FUNC PyMODINIT_FUNC +#elif PY_MAJOR_VERSION < 3 +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" void +#else +#define __Pyx_PyMODINIT_FUNC void +#endif +#else +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" PyObject * +#else +#define __Pyx_PyMODINIT_FUNC PyObject * +#endif +#endif + + +#if PY_MAJOR_VERSION < 3 +__Pyx_PyMODINIT_FUNC initacados_ocp_solver_pyx(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC initacados_ocp_solver_pyx(void) +#else +__Pyx_PyMODINIT_FUNC PyInit_acados_ocp_solver_pyx(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC PyInit_acados_ocp_solver_pyx(void) +#if CYTHON_PEP489_MULTI_PHASE_INIT +{ + return PyModuleDef_Init(&__pyx_moduledef); +} +static CYTHON_SMALL_CODE int __Pyx_check_single_interpreter(void) { + #if PY_VERSION_HEX >= 0x030700A1 + static PY_INT64_T main_interpreter_id = -1; + PY_INT64_T current_id = PyInterpreterState_GetID(PyThreadState_Get()->interp); + if (main_interpreter_id == -1) { + main_interpreter_id = current_id; + return (unlikely(current_id == -1)) ? -1 : 0; + } else if (unlikely(main_interpreter_id != current_id)) + #else + static PyInterpreterState *main_interpreter = NULL; + PyInterpreterState *current_interpreter = PyThreadState_Get()->interp; + if (!main_interpreter) { + main_interpreter = current_interpreter; + } else if (unlikely(main_interpreter != current_interpreter)) + #endif + { + PyErr_SetString( + PyExc_ImportError, + "Interpreter change detected - this module can only be loaded into one interpreter per process."); + return -1; + } + return 0; +} +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *module, const char* from_name, const char* to_name, int allow_none) +#else +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *moddict, const char* from_name, const char* to_name, int allow_none) +#endif +{ + PyObject *value = PyObject_GetAttrString(spec, from_name); + int result = 0; + if (likely(value)) { + if (allow_none || value != Py_None) { +#if CYTHON_COMPILING_IN_LIMITED_API + result = PyModule_AddObject(module, to_name, value); +#else + result = PyDict_SetItemString(moddict, to_name, value); +#endif + } + Py_DECREF(value); + } else if (PyErr_ExceptionMatches(PyExc_AttributeError)) { + PyErr_Clear(); + } else { + result = -1; + } + return result; +} +static CYTHON_SMALL_CODE PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def) { + PyObject *module = NULL, *moddict, *modname; + CYTHON_UNUSED_VAR(def); + if (__Pyx_check_single_interpreter()) + return NULL; + if (__pyx_m) + return __Pyx_NewRef(__pyx_m); + modname = PyObject_GetAttrString(spec, "name"); + if (unlikely(!modname)) goto bad; + module = PyModule_NewObject(modname); + Py_DECREF(modname); + if (unlikely(!module)) goto bad; +#if CYTHON_COMPILING_IN_LIMITED_API + moddict = module; +#else + moddict = PyModule_GetDict(module); + if (unlikely(!moddict)) goto bad; +#endif + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "loader", "__loader__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "origin", "__file__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "parent", "__package__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "submodule_search_locations", "__path__", 0) < 0)) goto bad; + return module; +bad: + Py_XDECREF(module); + return NULL; +} + + +static CYTHON_SMALL_CODE int __pyx_pymod_exec_acados_ocp_solver_pyx(PyObject *__pyx_pyinit_module) +#endif +#endif +{ + int stringtab_initialized = 0; + #if CYTHON_USE_MODULE_STATE + int pystate_addmodule_run = 0; + #endif + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + static PyThread_type_lock __pyx_t_8[8]; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannyDeclarations + #if CYTHON_PEP489_MULTI_PHASE_INIT + if (__pyx_m) { + if (__pyx_m == __pyx_pyinit_module) return 0; + PyErr_SetString(PyExc_RuntimeError, "Module 'acados_ocp_solver_pyx' has already been imported. Re-initialisation is not supported."); + return -1; + } + #elif PY_MAJOR_VERSION >= 3 + if (__pyx_m) return __Pyx_NewRef(__pyx_m); + #endif + /*--- Module creation code ---*/ + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_m = __pyx_pyinit_module; + Py_INCREF(__pyx_m); + #else + #if PY_MAJOR_VERSION < 3 + __pyx_m = Py_InitModule4("acados_ocp_solver_pyx", __pyx_methods, 0, 0, PYTHON_API_VERSION); Py_XINCREF(__pyx_m); + if (unlikely(!__pyx_m)) __PYX_ERR(0, 1, __pyx_L1_error) + #elif CYTHON_USE_MODULE_STATE + __pyx_t_1 = PyModule_Create(&__pyx_moduledef); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 1, __pyx_L1_error) + { + int add_module_result = PyState_AddModule(__pyx_t_1, &__pyx_moduledef); + __pyx_t_1 = 0; /* transfer ownership from __pyx_t_1 to "acados_ocp_solver_pyx" pseudovariable */ + if (unlikely((add_module_result < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + pystate_addmodule_run = 1; + } + #else + __pyx_m = PyModule_Create(&__pyx_moduledef); + if (unlikely(!__pyx_m)) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #endif + CYTHON_UNUSED_VAR(__pyx_t_1); + __pyx_d = PyModule_GetDict(__pyx_m); if (unlikely(!__pyx_d)) __PYX_ERR(0, 1, __pyx_L1_error) + Py_INCREF(__pyx_d); + __pyx_b = __Pyx_PyImport_AddModuleRef(__Pyx_BUILTIN_MODULE_NAME); if (unlikely(!__pyx_b)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_cython_runtime = __Pyx_PyImport_AddModuleRef((const char *) "cython_runtime"); if (unlikely(!__pyx_cython_runtime)) __PYX_ERR(0, 1, __pyx_L1_error) + if (PyObject_SetAttrString(__pyx_m, "__builtins__", __pyx_b) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #if CYTHON_REFNANNY +__Pyx_RefNanny = __Pyx_RefNannyImportAPI("refnanny"); +if (!__Pyx_RefNanny) { + PyErr_Clear(); + __Pyx_RefNanny = __Pyx_RefNannyImportAPI("Cython.Runtime.refnanny"); + if (!__Pyx_RefNanny) + Py_FatalError("failed to import 'refnanny' module"); +} +#endif + __Pyx_RefNannySetupContext("__Pyx_PyMODINIT_FUNC PyInit_acados_ocp_solver_pyx(void)", 0); + if (__Pyx_check_binary_version(__PYX_LIMITED_VERSION_HEX, __Pyx_get_runtime_version(), CYTHON_COMPILING_IN_LIMITED_API) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #ifdef __Pxy_PyFrame_Initialize_Offsets + __Pxy_PyFrame_Initialize_Offsets(); + #endif + __pyx_empty_tuple = PyTuple_New(0); if (unlikely(!__pyx_empty_tuple)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_empty_bytes = PyBytes_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_bytes)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_empty_unicode = PyUnicode_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_unicode)) __PYX_ERR(0, 1, __pyx_L1_error) + #ifdef __Pyx_CyFunction_USED + if (__pyx_CyFunction_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_FusedFunction_USED + if (__pyx_FusedFunction_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Coroutine_USED + if (__pyx_Coroutine_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Generator_USED + if (__pyx_Generator_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_AsyncGen_USED + if (__pyx_AsyncGen_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_StopAsyncIteration_USED + if (__pyx_StopAsyncIteration_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + /*--- Library function declarations ---*/ + /*--- Threads initialization code ---*/ + #if defined(WITH_THREAD) && PY_VERSION_HEX < 0x030700F0 && defined(__PYX_FORCE_INIT_THREADS) && __PYX_FORCE_INIT_THREADS + PyEval_InitThreads(); + #endif + /*--- Initialize various global constants etc. ---*/ + if (__Pyx_InitConstants() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + stringtab_initialized = 1; + if (__Pyx_InitGlobals() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #if PY_MAJOR_VERSION < 3 && (__PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT) + if (__Pyx_init_sys_getdefaultencoding_params() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + if (__pyx_module_is_main_acados_template__acados_ocp_solver_pyx) { + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_name_2, __pyx_n_s_main) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + } + #if PY_MAJOR_VERSION >= 3 + { + PyObject *modules = PyImport_GetModuleDict(); if (unlikely(!modules)) __PYX_ERR(0, 1, __pyx_L1_error) + if (!PyDict_GetItemString(modules, "acados_template.acados_ocp_solver_pyx")) { + if (unlikely((PyDict_SetItemString(modules, "acados_template.acados_ocp_solver_pyx", __pyx_m) < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + } + } + #endif + /*--- Builtin init code ---*/ + if (__Pyx_InitCachedBuiltins() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + /*--- Constants init code ---*/ + if (__Pyx_InitCachedConstants() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + /*--- Global type/function init code ---*/ + (void)__Pyx_modinit_global_init_code(); + (void)__Pyx_modinit_variable_export_code(); + (void)__Pyx_modinit_function_export_code(); + if (unlikely((__Pyx_modinit_type_init_code() < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + if (unlikely((__Pyx_modinit_type_import_code() < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + (void)__Pyx_modinit_variable_import_code(); + (void)__Pyx_modinit_function_import_code(); + /*--- Execution code ---*/ + #if defined(__Pyx_Generator_USED) || defined(__Pyx_Coroutine_USED) + if (__Pyx_patch_abc() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + + /* "View.MemoryView":99 + * + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: # <<<<<<<<<<<<<< + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "View.MemoryView":100 + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: + * if __import__("sys").version_info >= (3, 3): # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + */ + __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__33, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 100, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_version_info); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 100, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = PyObject_RichCompare(__pyx_t_5, __pyx_tuple__34, Py_GE); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 100, __pyx_L2_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_6 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(1, 100, __pyx_L2_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (__pyx_t_6) { + + /* "View.MemoryView":101 + * try: + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence # <<<<<<<<<<<<<< + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence + */ + __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__35, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 101, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_abc); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 101, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_Sequence); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 101, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XGOTREF(__pyx_collections_abc_Sequence); + __Pyx_DECREF_SET(__pyx_collections_abc_Sequence, __pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + __pyx_t_4 = 0; + + /* "View.MemoryView":100 + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: + * if __import__("sys").version_info >= (3, 3): # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + */ + goto __pyx_L8; + } + + /* "View.MemoryView":103 + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence # <<<<<<<<<<<<<< + * except: + * + */ + /*else*/ { + __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__36, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 103, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_Sequence); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 103, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XGOTREF(__pyx_collections_abc_Sequence); + __Pyx_DECREF_SET(__pyx_collections_abc_Sequence, __pyx_t_5); + __Pyx_GIVEREF(__pyx_t_5); + __pyx_t_5 = 0; + } + __pyx_L8:; + + /* "View.MemoryView":99 + * + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: # <<<<<<<<<<<<<< + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L7_try_end; + __pyx_L2_error:; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "View.MemoryView":104 + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence + * except: # <<<<<<<<<<<<<< + * + * __pyx_collections_abc_Sequence = None + */ + /*except:*/ { + __Pyx_AddTraceback("View.MemoryView", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_4, &__pyx_t_7) < 0) __PYX_ERR(1, 104, __pyx_L4_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_4); + __Pyx_XGOTREF(__pyx_t_7); + + /* "View.MemoryView":106 + * except: + * + * __pyx_collections_abc_Sequence = None # <<<<<<<<<<<<<< + * + * + */ + __Pyx_INCREF(Py_None); + __Pyx_XGOTREF(__pyx_collections_abc_Sequence); + __Pyx_DECREF_SET(__pyx_collections_abc_Sequence, Py_None); + __Pyx_GIVEREF(Py_None); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + goto __pyx_L3_exception_handled; + } + + /* "View.MemoryView":99 + * + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: # <<<<<<<<<<<<<< + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + */ + __pyx_L4_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + goto __pyx_L1_error; + __pyx_L3_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + __pyx_L7_try_end:; + } + + /* "View.MemoryView":241 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_3, &__pyx_t_2, &__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_1); + /*try:*/ { + + /* "View.MemoryView":242 + * + * try: + * count = __pyx_collections_abc_Sequence.count # <<<<<<<<<<<<<< + * index = __pyx_collections_abc_Sequence.index + * except: + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_count); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 242, __pyx_L11_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict(__pyx_array_type, __pyx_n_s_count, __pyx_t_7) < 0) __PYX_ERR(1, 242, __pyx_L11_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_array_type); + + /* "View.MemoryView":243 + * try: + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index # <<<<<<<<<<<<<< + * except: + * pass + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_index); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 243, __pyx_L11_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict(__pyx_array_type, __pyx_n_s_index, __pyx_t_7) < 0) __PYX_ERR(1, 243, __pyx_L11_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_array_type); + + /* "View.MemoryView":241 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + } + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + goto __pyx_L16_try_end; + __pyx_L11_error:; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":244 + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + * except: # <<<<<<<<<<<<<< + * pass + * + */ + /*except:*/ { + __Pyx_ErrRestore(0,0,0); + goto __pyx_L12_exception_handled; + } + __pyx_L12_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_2, __pyx_t_1); + __pyx_L16_try_end:; + } + + /* "View.MemoryView":309 + * return self.name + * + * cdef generic = Enum("") # <<<<<<<<<<<<<< + * cdef strided = Enum("") # default + * cdef indirect = Enum("") + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__37, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 309, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(generic); + __Pyx_DECREF_SET(generic, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":310 + * + * cdef generic = Enum("") + * cdef strided = Enum("") # default # <<<<<<<<<<<<<< + * cdef indirect = Enum("") + * + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__38, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 310, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(strided); + __Pyx_DECREF_SET(strided, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":311 + * cdef generic = Enum("") + * cdef strided = Enum("") # default + * cdef indirect = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__39, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 311, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(indirect); + __Pyx_DECREF_SET(indirect, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":314 + * + * + * cdef contiguous = Enum("") # <<<<<<<<<<<<<< + * cdef indirect_contiguous = Enum("") + * + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__40, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 314, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(contiguous); + __Pyx_DECREF_SET(contiguous, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":315 + * + * cdef contiguous = Enum("") + * cdef indirect_contiguous = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__41, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 315, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(indirect_contiguous); + __Pyx_DECREF_SET(indirect_contiguous, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":323 + * + * + * cdef int __pyx_memoryview_thread_locks_used = 0 # <<<<<<<<<<<<<< + * cdef PyThread_type_lock[8] __pyx_memoryview_thread_locks = [ + * PyThread_allocate_lock(), + */ + __pyx_memoryview_thread_locks_used = 0; + + /* "View.MemoryView":324 + * + * cdef int __pyx_memoryview_thread_locks_used = 0 + * cdef PyThread_type_lock[8] __pyx_memoryview_thread_locks = [ # <<<<<<<<<<<<<< + * PyThread_allocate_lock(), + * PyThread_allocate_lock(), + */ + __pyx_t_8[0] = PyThread_allocate_lock(); + __pyx_t_8[1] = PyThread_allocate_lock(); + __pyx_t_8[2] = PyThread_allocate_lock(); + __pyx_t_8[3] = PyThread_allocate_lock(); + __pyx_t_8[4] = PyThread_allocate_lock(); + __pyx_t_8[5] = PyThread_allocate_lock(); + __pyx_t_8[6] = PyThread_allocate_lock(); + __pyx_t_8[7] = PyThread_allocate_lock(); + memcpy(&(__pyx_memoryview_thread_locks[0]), __pyx_t_8, sizeof(__pyx_memoryview_thread_locks[0]) * (8)); + + /* "View.MemoryView":982 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "View.MemoryView":983 + * + * try: + * count = __pyx_collections_abc_Sequence.count # <<<<<<<<<<<<<< + * index = __pyx_collections_abc_Sequence.index + * except: + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_count); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 983, __pyx_L17_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict(__pyx_memoryviewslice_type, __pyx_n_s_count, __pyx_t_7) < 0) __PYX_ERR(1, 983, __pyx_L17_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_memoryviewslice_type); + + /* "View.MemoryView":984 + * try: + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index # <<<<<<<<<<<<<< + * except: + * pass + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_index); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 984, __pyx_L17_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict(__pyx_memoryviewslice_type, __pyx_n_s_index, __pyx_t_7) < 0) __PYX_ERR(1, 984, __pyx_L17_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_memoryviewslice_type); + + /* "View.MemoryView":982 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L22_try_end; + __pyx_L17_error:; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":985 + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + * except: # <<<<<<<<<<<<<< + * pass + * + */ + /*except:*/ { + __Pyx_ErrRestore(0,0,0); + goto __pyx_L18_exception_handled; + } + __pyx_L18_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + __pyx_L22_try_end:; + } + + /* "View.MemoryView":988 + * pass + * + * try: # <<<<<<<<<<<<<< + * if __pyx_collections_abc_Sequence: + * + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_3, &__pyx_t_2, &__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_1); + /*try:*/ { + + /* "View.MemoryView":989 + * + * try: + * if __pyx_collections_abc_Sequence: # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_6 = __Pyx_PyObject_IsTrue(__pyx_collections_abc_Sequence); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(1, 989, __pyx_L23_error) + if (__pyx_t_6) { + + /* "View.MemoryView":993 + * + * + * __pyx_collections_abc_Sequence.register(_memoryviewslice) # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence.register(array) + * except: + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_register); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 993, __pyx_L23_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_4 = __Pyx_PyObject_CallOneArg(__pyx_t_7, ((PyObject *)__pyx_memoryviewslice_type)); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 993, __pyx_L23_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "View.MemoryView":994 + * + * __pyx_collections_abc_Sequence.register(_memoryviewslice) + * __pyx_collections_abc_Sequence.register(array) # <<<<<<<<<<<<<< + * except: + * pass # ignore failure, it's a minor issue + */ + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_register); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 994, __pyx_L23_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_7 = __Pyx_PyObject_CallOneArg(__pyx_t_4, ((PyObject *)__pyx_array_type)); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 994, __pyx_L23_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":989 + * + * try: + * if __pyx_collections_abc_Sequence: # <<<<<<<<<<<<<< + * + * + */ + } + + /* "View.MemoryView":988 + * pass + * + * try: # <<<<<<<<<<<<<< + * if __pyx_collections_abc_Sequence: + * + */ + } + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + goto __pyx_L28_try_end; + __pyx_L23_error:; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":995 + * __pyx_collections_abc_Sequence.register(_memoryviewslice) + * __pyx_collections_abc_Sequence.register(array) + * except: # <<<<<<<<<<<<<< + * pass # ignore failure, it's a minor issue + * + */ + /*except:*/ { + __Pyx_ErrRestore(0,0,0); + goto __pyx_L24_exception_handled; + } + __pyx_L24_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_2, __pyx_t_1); + __pyx_L28_try_end:; + } + + /* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + __pyx_t_7 = PyCFunction_NewEx(&__pyx_mdef_15View_dot_MemoryView_1__pyx_unpickle_Enum, NULL, __pyx_n_s_View_MemoryView); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_pyx_unpickle_Enum, __pyx_t_7) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":44 + * cimport numpy as cnp + * + * import os # <<<<<<<<<<<<<< + * from datetime import datetime + * import numpy as np + */ + __pyx_t_7 = __Pyx_ImportDottedModule(__pyx_n_s_os, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 44, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_os, __pyx_t_7) < 0) __PYX_ERR(0, 44, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":45 + * + * import os + * from datetime import datetime # <<<<<<<<<<<<<< + * import numpy as np + * + */ + __pyx_t_7 = PyList_New(1); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 45, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_INCREF(__pyx_n_s_datetime); + __Pyx_GIVEREF(__pyx_n_s_datetime); + if (__Pyx_PyList_SET_ITEM(__pyx_t_7, 0, __pyx_n_s_datetime)) __PYX_ERR(0, 45, __pyx_L1_error); + __pyx_t_4 = __Pyx_Import(__pyx_n_s_datetime, __pyx_t_7, 0); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 45, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __pyx_t_7 = __Pyx_ImportFrom(__pyx_t_4, __pyx_n_s_datetime); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 45, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_datetime, __pyx_t_7) < 0) __PYX_ERR(0, 45, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":46 + * import os + * from datetime import datetime + * import numpy as np # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_4 = __Pyx_ImportDottedModule(__pyx_n_s_numpy, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 46, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_np, __pyx_t_4) < 0) __PYX_ERR(0, 46, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":89 + * + * + * def __get_pointers_solver(self): # <<<<<<<<<<<<<< + * """ + * Private function to get the pointers for solver + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_3_AcadosOcpSolverCython__get_pointers_solver, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___get_poin, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__45)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 89, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_AcadosOcpSolverCython__get_poin, __pyx_t_4) < 0) __PYX_ERR(0, 89, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":103 + * + * + * def solve_for_x0(self, x0_bar): # <<<<<<<<<<<<<< + * """ + * Wrapper around `solve()` which sets initial state constraint, solves the OCP, and returns u0. + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve_for_x0, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_solve_for, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__47)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 103, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_solve_for_x0, __pyx_t_4) < 0) __PYX_ERR(0, 103, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":121 + * + * + * def solve(self): # <<<<<<<<<<<<<< + * """ + * Solve the ocp with current input. + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7solve, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_solve, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__48)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 121, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_solve, __pyx_t_4) < 0) __PYX_ERR(0, 121, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":128 + * + * + * def reset(self, reset_qp_solver_mem=1): # <<<<<<<<<<<<<< + * """ + * Sets current iterate to all zeros. + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9reset, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_reset, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__50)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 128, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_4, __pyx_tuple__25); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_reset, __pyx_t_4) < 0) __PYX_ERR(0, 128, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":135 + * + * + * def custom_update(self, data_): # <<<<<<<<<<<<<< + * """ + * A custom function that can be implemented by a user to be called between solver calls. + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11custom_update, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_custom_upd, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__52)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 135, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_custom_update, __pyx_t_4) < 0) __PYX_ERR(0, 135, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":148 + * + * + * def set_new_time_steps(self, new_time_steps): # <<<<<<<<<<<<<< + * """ + * Set new time steps. + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13set_new_time_steps, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_set_new_ti, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__54)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 148, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_set_new_time_steps, __pyx_t_4) < 0) __PYX_ERR(0, 148, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":199 + * + * + * def update_qp_solver_cond_N(self, qp_solver_cond_N: int): # <<<<<<<<<<<<<< + * """ + * Recreate solver with new value `qp_solver_cond_N` with a partial condensing QP solver. + */ + __pyx_t_4 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 199, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem(__pyx_t_4, __pyx_n_s_qp_solver_cond_N, __pyx_n_s_int) < 0) __PYX_ERR(0, 199, __pyx_L1_error) + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15update_qp_solver_cond_N, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_update_qp, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__56)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 199, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_CyFunction_SetAnnotationsDict(__pyx_t_7, __pyx_t_4); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_update_qp_solver_cond_N, __pyx_t_7) < 0) __PYX_ERR(0, 199, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":233 + * + * + * def eval_param_sens(self, index, stage=0, field="ex"): # <<<<<<<<<<<<<< + * """ + * Calculate the sensitivity of the curent solution with respect to the initial state component of index + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17eval_param_sens, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_eval_param_3, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__58)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 233, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_7, __pyx_tuple__59); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_eval_param_sens, __pyx_t_7) < 0) __PYX_ERR(0, 233, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":258 + * + * + * def get(self, int stage, str field_): # <<<<<<<<<<<<<< + * """ + * Get the last solution of the solver: + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19get, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_get, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__61)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 258, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_get, __pyx_t_7) < 0) __PYX_ERR(0, 258, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":301 + * + * + * def print_statistics(self): # <<<<<<<<<<<<<< + * """ + * prints statistics of previous solver run as a table: + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21print_statistics, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_print_stat, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__62)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 301, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_print_statistics, __pyx_t_7) < 0) __PYX_ERR(0, 301, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":319 + * + * + * def store_iterate(self, filename='', overwrite=False): # <<<<<<<<<<<<<< + * """ + * Stores the current iterate of the ocp solver in a json file. + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23store_iterate, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_store_iter, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__64)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 319, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_7, __pyx_tuple__65); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_store_iterate, __pyx_t_7) < 0) __PYX_ERR(0, 319, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":362 + * + * + * def load_iterate(self, filename): # <<<<<<<<<<<<<< + * """ + * Loads the iterate stored in json file with filename into the ocp solver. + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25load_iterate, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_load_itera, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__67)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 362, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_load_iterate, __pyx_t_7) < 0) __PYX_ERR(0, 362, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":378 + * + * + * def get_stats(self, field_): # <<<<<<<<<<<<<< + * """ + * Get the information of the last solver call. + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27get_stats, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_get_stats, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__69)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 378, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_get_stats, __pyx_t_7) < 0) __PYX_ERR(0, 378, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":460 + * + * + * def __get_stat_int(self, field): # <<<<<<<<<<<<<< + * cdef int out + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &out) + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_int, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___get_stat, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__71)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 460, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_AcadosOcpSolverCython__get_stat, __pyx_t_7) < 0) __PYX_ERR(0, 460, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":465 + * return out + * + * def __get_stat_double(self, field): # <<<<<<<<<<<<<< + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31_AcadosOcpSolverCython__get_stat_double, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___get_stat_2, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__72)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 465, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_AcadosOcpSolverCython__get_stat_2, __pyx_t_7) < 0) __PYX_ERR(0, 465, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":470 + * return out + * + * def __get_stat_matrix(self, field, n, m): # <<<<<<<<<<<<<< + * cdef cnp.ndarray[cnp.float64_t, ndim=2] out_mat = np.ascontiguousarray(np.zeros((n, m)), dtype=np.float64) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_mat.data) + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33_AcadosOcpSolverCython__get_stat_matrix, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___get_stat_3, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__74)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 470, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_AcadosOcpSolverCython__get_stat_3, __pyx_t_7) < 0) __PYX_ERR(0, 470, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":476 + * + * + * def get_cost(self): # <<<<<<<<<<<<<< + * """ + * Returns the cost value of the current solution. + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35get_cost, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_get_cost, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__76)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 476, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_get_cost, __pyx_t_7) < 0) __PYX_ERR(0, 476, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":492 + * + * + * def get_residuals(self, recompute=False): # <<<<<<<<<<<<<< + * """ + * Returns an array of the form [res_stat, res_eq, res_ineq, res_comp]. + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37get_residuals, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_get_residu, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__78)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 492, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_7, __pyx_tuple__79); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_get_residuals, __pyx_t_7) < 0) __PYX_ERR(0, 492, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":524 + * + * # Note: this function should not be used anymore, better use cost_set, constraints_set + * def set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * + * """ + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39set, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_set, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__81)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 524, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_set, __pyx_t_7) < 0) __PYX_ERR(0, 524, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":590 + * return + * + * def cost_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set numerical data in the cost module of the solver. + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41cost_set, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_cost_set, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__83)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 590, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_cost_set, __pyx_t_7) < 0) __PYX_ERR(0, 590, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":625 + * + * + * def constraints_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set numerical data in the constraint module of the solver. + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43constraints_set, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_constraint_2, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__84)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 625, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_constraints_set, __pyx_t_7) < 0) __PYX_ERR(0, 625, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":663 + * + * + * def get_from_qp_in(self, int stage, str field_): # <<<<<<<<<<<<<< + * """ + * Get numerical data from the dynamics module of the solver: + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_45get_from_qp_in, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_get_from_q, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__86)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_get_from_qp_in, __pyx_t_7) < 0) __PYX_ERR(0, 663, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":685 + * + * + * def options_set(self, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set options of the solver. + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47options_set, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_options_se_2, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__88)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 685, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_options_set, __pyx_t_7) < 0) __PYX_ERR(0, 685, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":748 + * + * + * def set_params_sparse(self, int stage, idx_values_, param_values_): # <<<<<<<<<<<<<< + * """ + * set parameters of the solvers external function partially: + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49set_params_sparse, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_set_params, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__90)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 748, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_set_params_sparse, __pyx_t_7) < 0) __PYX_ERR(0, 748, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_53__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___reduce_c, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__91)); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_7) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_55__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___setstate, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__93)); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_7) < 0) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":1 + * # -*- coding: future_fstrings -*- # <<<<<<<<<<<<<< + * # + * # Copyright (c) The acados authors. + */ + __pyx_t_7 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_test, __pyx_t_7) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /*--- Wrapped vars code ---*/ + + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_7); + if (__pyx_m) { + if (__pyx_d && stringtab_initialized) { + __Pyx_AddTraceback("init acados_template.acados_ocp_solver_pyx", __pyx_clineno, __pyx_lineno, __pyx_filename); + } + #if !CYTHON_USE_MODULE_STATE + Py_CLEAR(__pyx_m); + #else + Py_DECREF(__pyx_m); + if (pystate_addmodule_run) { + PyObject *tp, *value, *tb; + PyErr_Fetch(&tp, &value, &tb); + PyState_RemoveModule(&__pyx_moduledef); + PyErr_Restore(tp, value, tb); + } + #endif + } else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_ImportError, "init acados_template.acados_ocp_solver_pyx"); + } + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + #if CYTHON_PEP489_MULTI_PHASE_INIT + return (__pyx_m != NULL) ? 0 : -1; + #elif PY_MAJOR_VERSION >= 3 + return __pyx_m; + #else + return; + #endif +} +/* #### Code section: cleanup_globals ### */ +/* #### Code section: cleanup_module ### */ +/* #### Code section: main_method ### */ +/* #### Code section: utility_code_pragmas ### */ +#ifdef _MSC_VER +#pragma warning( push ) +/* Warning 4127: conditional expression is constant + * Cython uses constant conditional expressions to allow in inline functions to be optimized at + * compile-time, so this warning is not useful + */ +#pragma warning( disable : 4127 ) +#endif + + + +/* #### Code section: utility_code_def ### */ + +/* --- Runtime support code --- */ +/* Refnanny */ +#if CYTHON_REFNANNY +static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname) { + PyObject *m = NULL, *p = NULL; + void *r = NULL; + m = PyImport_ImportModule(modname); + if (!m) goto end; + p = PyObject_GetAttrString(m, "RefNannyAPI"); + if (!p) goto end; + r = PyLong_AsVoidPtr(p); +end: + Py_XDECREF(p); + Py_XDECREF(m); + return (__Pyx_RefNannyAPIStruct *)r; +} +#endif + +/* PyErrExceptionMatches */ +#if CYTHON_FAST_THREAD_STATE +static int __Pyx_PyErr_ExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; i= 0x030C00A6 + PyObject *current_exception = tstate->current_exception; + if (unlikely(!current_exception)) return 0; + exc_type = (PyObject*) Py_TYPE(current_exception); + if (exc_type == err) return 1; +#else + exc_type = tstate->curexc_type; + if (exc_type == err) return 1; + if (unlikely(!exc_type)) return 0; +#endif + #if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(exc_type); + #endif + if (unlikely(PyTuple_Check(err))) { + result = __Pyx_PyErr_ExceptionMatchesTuple(exc_type, err); + } else { + result = __Pyx_PyErr_GivenExceptionMatches(exc_type, err); + } + #if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(exc_type); + #endif + return result; +} +#endif + +/* PyErrFetchRestore */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject *tmp_value; + assert(type == NULL || (value != NULL && type == (PyObject*) Py_TYPE(value))); + if (value) { + #if CYTHON_COMPILING_IN_CPYTHON + if (unlikely(((PyBaseExceptionObject*) value)->traceback != tb)) + #endif + PyException_SetTraceback(value, tb); + } + tmp_value = tstate->current_exception; + tstate->current_exception = value; + Py_XDECREF(tmp_value); + Py_XDECREF(type); + Py_XDECREF(tb); +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + tmp_type = tstate->curexc_type; + tmp_value = tstate->curexc_value; + tmp_tb = tstate->curexc_traceback; + tstate->curexc_type = type; + tstate->curexc_value = value; + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); +#endif +} +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject* exc_value; + exc_value = tstate->current_exception; + tstate->current_exception = 0; + *value = exc_value; + *type = NULL; + *tb = NULL; + if (exc_value) { + *type = (PyObject*) Py_TYPE(exc_value); + Py_INCREF(*type); + #if CYTHON_COMPILING_IN_CPYTHON + *tb = ((PyBaseExceptionObject*) exc_value)->traceback; + Py_XINCREF(*tb); + #else + *tb = PyException_GetTraceback(exc_value); + #endif + } +#else + *type = tstate->curexc_type; + *value = tstate->curexc_value; + *tb = tstate->curexc_traceback; + tstate->curexc_type = 0; + tstate->curexc_value = 0; + tstate->curexc_traceback = 0; +#endif +} +#endif + +/* PyObjectGetAttrStr */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name) { + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro)) + return tp->tp_getattro(obj, attr_name); +#if PY_MAJOR_VERSION < 3 + if (likely(tp->tp_getattr)) + return tp->tp_getattr(obj, PyString_AS_STRING(attr_name)); +#endif + return PyObject_GetAttr(obj, attr_name); +} +#endif + +/* PyObjectGetAttrStrNoError */ +#if __PYX_LIMITED_VERSION_HEX < 0x030d00A1 +static void __Pyx_PyObject_GetAttrStr_ClearAttributeError(void) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + if (likely(__Pyx_PyErr_ExceptionMatches(PyExc_AttributeError))) + __Pyx_PyErr_Clear(); +} +#endif +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name) { + PyObject *result; +#if __PYX_LIMITED_VERSION_HEX >= 0x030d00A1 + (void) PyObject_GetOptionalAttr(obj, attr_name, &result); + return result; +#else +#if CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_TYPE_SLOTS && PY_VERSION_HEX >= 0x030700B1 + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro == PyObject_GenericGetAttr)) { + return _PyObject_GenericGetAttrWithDict(obj, attr_name, NULL, 1); + } +#endif + result = __Pyx_PyObject_GetAttrStr(obj, attr_name); + if (unlikely(!result)) { + __Pyx_PyObject_GetAttrStr_ClearAttributeError(); + } + return result; +#endif +} + +/* GetBuiltinName */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name) { + PyObject* result = __Pyx_PyObject_GetAttrStrNoError(__pyx_b, name); + if (unlikely(!result) && !PyErr_Occurred()) { + PyErr_Format(PyExc_NameError, +#if PY_MAJOR_VERSION >= 3 + "name '%U' is not defined", name); +#else + "name '%.200s' is not defined", PyString_AS_STRING(name)); +#endif + } + return result; +} + +/* TupleAndListFromArray */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE void __Pyx_copy_object_array(PyObject *const *CYTHON_RESTRICT src, PyObject** CYTHON_RESTRICT dest, Py_ssize_t length) { + PyObject *v; + Py_ssize_t i; + for (i = 0; i < length; i++) { + v = dest[i] = src[i]; + Py_INCREF(v); + } +} +static CYTHON_INLINE PyObject * +__Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + Py_INCREF(__pyx_empty_tuple); + return __pyx_empty_tuple; + } + res = PyTuple_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyTupleObject*)res)->ob_item, n); + return res; +} +static CYTHON_INLINE PyObject * +__Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + return PyList_New(0); + } + res = PyList_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyListObject*)res)->ob_item, n); + return res; +} +#endif + +/* BytesEquals */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else + if (s1 == s2) { + return (equals == Py_EQ); + } else if (PyBytes_CheckExact(s1) & PyBytes_CheckExact(s2)) { + const char *ps1, *ps2; + Py_ssize_t length = PyBytes_GET_SIZE(s1); + if (length != PyBytes_GET_SIZE(s2)) + return (equals == Py_NE); + ps1 = PyBytes_AS_STRING(s1); + ps2 = PyBytes_AS_STRING(s2); + if (ps1[0] != ps2[0]) { + return (equals == Py_NE); + } else if (length == 1) { + return (equals == Py_EQ); + } else { + int result; +#if CYTHON_USE_UNICODE_INTERNALS && (PY_VERSION_HEX < 0x030B0000) + Py_hash_t hash1, hash2; + hash1 = ((PyBytesObject*)s1)->ob_shash; + hash2 = ((PyBytesObject*)s2)->ob_shash; + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + return (equals == Py_NE); + } +#endif + result = memcmp(ps1, ps2, (size_t)length); + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & PyBytes_CheckExact(s2)) { + return (equals == Py_NE); + } else if ((s2 == Py_None) & PyBytes_CheckExact(s1)) { + return (equals == Py_NE); + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +#endif +} + +/* UnicodeEquals */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else +#if PY_MAJOR_VERSION < 3 + PyObject* owned_ref = NULL; +#endif + int s1_is_unicode, s2_is_unicode; + if (s1 == s2) { + goto return_eq; + } + s1_is_unicode = PyUnicode_CheckExact(s1); + s2_is_unicode = PyUnicode_CheckExact(s2); +#if PY_MAJOR_VERSION < 3 + if ((s1_is_unicode & (!s2_is_unicode)) && PyString_CheckExact(s2)) { + owned_ref = PyUnicode_FromObject(s2); + if (unlikely(!owned_ref)) + return -1; + s2 = owned_ref; + s2_is_unicode = 1; + } else if ((s2_is_unicode & (!s1_is_unicode)) && PyString_CheckExact(s1)) { + owned_ref = PyUnicode_FromObject(s1); + if (unlikely(!owned_ref)) + return -1; + s1 = owned_ref; + s1_is_unicode = 1; + } else if (((!s2_is_unicode) & (!s1_is_unicode))) { + return __Pyx_PyBytes_Equals(s1, s2, equals); + } +#endif + if (s1_is_unicode & s2_is_unicode) { + Py_ssize_t length; + int kind; + void *data1, *data2; + if (unlikely(__Pyx_PyUnicode_READY(s1) < 0) || unlikely(__Pyx_PyUnicode_READY(s2) < 0)) + return -1; + length = __Pyx_PyUnicode_GET_LENGTH(s1); + if (length != __Pyx_PyUnicode_GET_LENGTH(s2)) { + goto return_ne; + } +#if CYTHON_USE_UNICODE_INTERNALS + { + Py_hash_t hash1, hash2; + #if CYTHON_PEP393_ENABLED + hash1 = ((PyASCIIObject*)s1)->hash; + hash2 = ((PyASCIIObject*)s2)->hash; + #else + hash1 = ((PyUnicodeObject*)s1)->hash; + hash2 = ((PyUnicodeObject*)s2)->hash; + #endif + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + goto return_ne; + } + } +#endif + kind = __Pyx_PyUnicode_KIND(s1); + if (kind != __Pyx_PyUnicode_KIND(s2)) { + goto return_ne; + } + data1 = __Pyx_PyUnicode_DATA(s1); + data2 = __Pyx_PyUnicode_DATA(s2); + if (__Pyx_PyUnicode_READ(kind, data1, 0) != __Pyx_PyUnicode_READ(kind, data2, 0)) { + goto return_ne; + } else if (length == 1) { + goto return_eq; + } else { + int result = memcmp(data1, data2, (size_t)(length * kind)); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & s2_is_unicode) { + goto return_ne; + } else if ((s2 == Py_None) & s1_is_unicode) { + goto return_ne; + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +return_eq: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ); +return_ne: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_NE); +#endif +} + +/* fastcall */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s) +{ + Py_ssize_t i, n = PyTuple_GET_SIZE(kwnames); + for (i = 0; i < n; i++) + { + if (s == PyTuple_GET_ITEM(kwnames, i)) return kwvalues[i]; + } + for (i = 0; i < n; i++) + { + int eq = __Pyx_PyUnicode_Equals(s, PyTuple_GET_ITEM(kwnames, i), Py_EQ); + if (unlikely(eq != 0)) { + if (unlikely(eq < 0)) return NULL; + return kwvalues[i]; + } + } + return NULL; +} +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 +CYTHON_UNUSED static PyObject *__Pyx_KwargsAsDict_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues) { + Py_ssize_t i, nkwargs = PyTuple_GET_SIZE(kwnames); + PyObject *dict; + dict = PyDict_New(); + if (unlikely(!dict)) + return NULL; + for (i=0; i= 3 + "%s() got multiple values for keyword argument '%U'", func_name, kw_name); + #else + "%s() got multiple values for keyword argument '%s'", func_name, + PyString_AsString(kw_name)); + #endif +} + +/* ParseKeywords */ +static int __Pyx_ParseOptionalKeywords( + PyObject *kwds, + PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, + PyObject *values[], + Py_ssize_t num_pos_args, + const char* function_name) +{ + PyObject *key = 0, *value = 0; + Py_ssize_t pos = 0; + PyObject*** name; + PyObject*** first_kw_arg = argnames + num_pos_args; + int kwds_is_tuple = CYTHON_METH_FASTCALL && likely(PyTuple_Check(kwds)); + while (1) { + Py_XDECREF(key); key = NULL; + Py_XDECREF(value); value = NULL; + if (kwds_is_tuple) { + Py_ssize_t size; +#if CYTHON_ASSUME_SAFE_MACROS + size = PyTuple_GET_SIZE(kwds); +#else + size = PyTuple_Size(kwds); + if (size < 0) goto bad; +#endif + if (pos >= size) break; +#if CYTHON_AVOID_BORROWED_REFS + key = __Pyx_PySequence_ITEM(kwds, pos); + if (!key) goto bad; +#elif CYTHON_ASSUME_SAFE_MACROS + key = PyTuple_GET_ITEM(kwds, pos); +#else + key = PyTuple_GetItem(kwds, pos); + if (!key) goto bad; +#endif + value = kwvalues[pos]; + pos++; + } + else + { + if (!PyDict_Next(kwds, &pos, &key, &value)) break; +#if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(key); +#endif + } + name = first_kw_arg; + while (*name && (**name != key)) name++; + if (*name) { + values[name-argnames] = value; +#if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(value); + Py_DECREF(key); +#endif + key = NULL; + value = NULL; + continue; + } +#if !CYTHON_AVOID_BORROWED_REFS + Py_INCREF(key); +#endif + Py_INCREF(value); + name = first_kw_arg; + #if PY_MAJOR_VERSION < 3 + if (likely(PyString_Check(key))) { + while (*name) { + if ((CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**name) == PyString_GET_SIZE(key)) + && _PyString_Eq(**name, key)) { + values[name-argnames] = value; +#if CYTHON_AVOID_BORROWED_REFS + value = NULL; +#endif + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + if ((**argname == key) || ( + (CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**argname) == PyString_GET_SIZE(key)) + && _PyString_Eq(**argname, key))) { + goto arg_passed_twice; + } + argname++; + } + } + } else + #endif + if (likely(PyUnicode_Check(key))) { + while (*name) { + int cmp = ( + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**name) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**name, key) + ); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) { + values[name-argnames] = value; +#if CYTHON_AVOID_BORROWED_REFS + value = NULL; +#endif + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + int cmp = (**argname == key) ? 0 : + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**argname) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**argname, key); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) goto arg_passed_twice; + argname++; + } + } + } else + goto invalid_keyword_type; + if (kwds2) { + if (unlikely(PyDict_SetItem(kwds2, key, value))) goto bad; + } else { + goto invalid_keyword; + } + } + Py_XDECREF(key); + Py_XDECREF(value); + return 0; +arg_passed_twice: + __Pyx_RaiseDoubleKeywordsError(function_name, key); + goto bad; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + goto bad; +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif +bad: + Py_XDECREF(key); + Py_XDECREF(value); + return -1; +} + +/* ArgTypeTest */ +static int __Pyx__ArgTypeTest(PyObject *obj, PyTypeObject *type, const char *name, int exact) +{ + __Pyx_TypeName type_name; + __Pyx_TypeName obj_type_name; + if (unlikely(!type)) { + PyErr_SetString(PyExc_SystemError, "Missing type object"); + return 0; + } + else if (exact) { + #if PY_MAJOR_VERSION == 2 + if ((type == &PyBaseString_Type) && likely(__Pyx_PyBaseString_CheckExact(obj))) return 1; + #endif + } + else { + if (likely(__Pyx_TypeCheck(obj, type))) return 1; + } + type_name = __Pyx_PyType_GetName(type); + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "Argument '%.200s' has incorrect type (expected " __Pyx_FMT_TYPENAME + ", got " __Pyx_FMT_TYPENAME ")", name, type_name, obj_type_name); + __Pyx_DECREF_TypeName(type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return 0; +} + +/* RaiseException */ +#if PY_MAJOR_VERSION < 3 +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + __Pyx_PyThreadState_declare + CYTHON_UNUSED_VAR(cause); + Py_XINCREF(type); + if (!value || value == Py_None) + value = NULL; + else + Py_INCREF(value); + if (!tb || tb == Py_None) + tb = NULL; + else { + Py_INCREF(tb); + if (!PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto raise_error; + } + } + if (PyType_Check(type)) { +#if CYTHON_COMPILING_IN_PYPY + if (!value) { + Py_INCREF(Py_None); + value = Py_None; + } +#endif + PyErr_NormalizeException(&type, &value, &tb); + } else { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto raise_error; + } + value = type; + type = (PyObject*) Py_TYPE(type); + Py_INCREF(type); + if (!PyType_IsSubtype((PyTypeObject *)type, (PyTypeObject *)PyExc_BaseException)) { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto raise_error; + } + } + __Pyx_PyThreadState_assign + __Pyx_ErrRestore(type, value, tb); + return; +raise_error: + Py_XDECREF(value); + Py_XDECREF(type); + Py_XDECREF(tb); + return; +} +#else +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + PyObject* owned_instance = NULL; + if (tb == Py_None) { + tb = 0; + } else if (tb && !PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto bad; + } + if (value == Py_None) + value = 0; + if (PyExceptionInstance_Check(type)) { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto bad; + } + value = type; + type = (PyObject*) Py_TYPE(value); + } else if (PyExceptionClass_Check(type)) { + PyObject *instance_class = NULL; + if (value && PyExceptionInstance_Check(value)) { + instance_class = (PyObject*) Py_TYPE(value); + if (instance_class != type) { + int is_subclass = PyObject_IsSubclass(instance_class, type); + if (!is_subclass) { + instance_class = NULL; + } else if (unlikely(is_subclass == -1)) { + goto bad; + } else { + type = instance_class; + } + } + } + if (!instance_class) { + PyObject *args; + if (!value) + args = PyTuple_New(0); + else if (PyTuple_Check(value)) { + Py_INCREF(value); + args = value; + } else + args = PyTuple_Pack(1, value); + if (!args) + goto bad; + owned_instance = PyObject_Call(type, args, NULL); + Py_DECREF(args); + if (!owned_instance) + goto bad; + value = owned_instance; + if (!PyExceptionInstance_Check(value)) { + PyErr_Format(PyExc_TypeError, + "calling %R should have returned an instance of " + "BaseException, not %R", + type, Py_TYPE(value)); + goto bad; + } + } + } else { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto bad; + } + if (cause) { + PyObject *fixed_cause; + if (cause == Py_None) { + fixed_cause = NULL; + } else if (PyExceptionClass_Check(cause)) { + fixed_cause = PyObject_CallObject(cause, NULL); + if (fixed_cause == NULL) + goto bad; + } else if (PyExceptionInstance_Check(cause)) { + fixed_cause = cause; + Py_INCREF(fixed_cause); + } else { + PyErr_SetString(PyExc_TypeError, + "exception causes must derive from " + "BaseException"); + goto bad; + } + PyException_SetCause(value, fixed_cause); + } + PyErr_SetObject(type, value); + if (tb) { + #if PY_VERSION_HEX >= 0x030C00A6 + PyException_SetTraceback(value, tb); + #elif CYTHON_FAST_THREAD_STATE + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject* tmp_tb = tstate->curexc_traceback; + if (tb != tmp_tb) { + Py_INCREF(tb); + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_tb); + } +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + PyErr_Fetch(&tmp_type, &tmp_value, &tmp_tb); + Py_INCREF(tb); + PyErr_Restore(tmp_type, tmp_value, tb); + Py_XDECREF(tmp_tb); +#endif + } +bad: + Py_XDECREF(owned_instance); + return; +} +#endif + +/* PyFunctionFastCall */ +#if CYTHON_FAST_PYCALL && !CYTHON_VECTORCALL +static PyObject* __Pyx_PyFunction_FastCallNoKw(PyCodeObject *co, PyObject **args, Py_ssize_t na, + PyObject *globals) { + PyFrameObject *f; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject **fastlocals; + Py_ssize_t i; + PyObject *result; + assert(globals != NULL); + /* XXX Perhaps we should create a specialized + PyFrame_New() that doesn't take locals, but does + take builtins without sanity checking them. + */ + assert(tstate != NULL); + f = PyFrame_New(tstate, co, globals, NULL); + if (f == NULL) { + return NULL; + } + fastlocals = __Pyx_PyFrame_GetLocalsplus(f); + for (i = 0; i < na; i++) { + Py_INCREF(*args); + fastlocals[i] = *args++; + } + result = PyEval_EvalFrameEx(f,0); + ++tstate->recursion_depth; + Py_DECREF(f); + --tstate->recursion_depth; + return result; +} +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs) { + PyCodeObject *co = (PyCodeObject *)PyFunction_GET_CODE(func); + PyObject *globals = PyFunction_GET_GLOBALS(func); + PyObject *argdefs = PyFunction_GET_DEFAULTS(func); + PyObject *closure; +#if PY_MAJOR_VERSION >= 3 + PyObject *kwdefs; +#endif + PyObject *kwtuple, **k; + PyObject **d; + Py_ssize_t nd; + Py_ssize_t nk; + PyObject *result; + assert(kwargs == NULL || PyDict_Check(kwargs)); + nk = kwargs ? PyDict_Size(kwargs) : 0; + #if PY_MAJOR_VERSION < 3 + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) { + return NULL; + } + #else + if (unlikely(Py_EnterRecursiveCall(" while calling a Python object"))) { + return NULL; + } + #endif + if ( +#if PY_MAJOR_VERSION >= 3 + co->co_kwonlyargcount == 0 && +#endif + likely(kwargs == NULL || nk == 0) && + co->co_flags == (CO_OPTIMIZED | CO_NEWLOCALS | CO_NOFREE)) { + if (argdefs == NULL && co->co_argcount == nargs) { + result = __Pyx_PyFunction_FastCallNoKw(co, args, nargs, globals); + goto done; + } + else if (nargs == 0 && argdefs != NULL + && co->co_argcount == Py_SIZE(argdefs)) { + /* function called with no arguments, but all parameters have + a default value: use default values as arguments .*/ + args = &PyTuple_GET_ITEM(argdefs, 0); + result =__Pyx_PyFunction_FastCallNoKw(co, args, Py_SIZE(argdefs), globals); + goto done; + } + } + if (kwargs != NULL) { + Py_ssize_t pos, i; + kwtuple = PyTuple_New(2 * nk); + if (kwtuple == NULL) { + result = NULL; + goto done; + } + k = &PyTuple_GET_ITEM(kwtuple, 0); + pos = i = 0; + while (PyDict_Next(kwargs, &pos, &k[i], &k[i+1])) { + Py_INCREF(k[i]); + Py_INCREF(k[i+1]); + i += 2; + } + nk = i / 2; + } + else { + kwtuple = NULL; + k = NULL; + } + closure = PyFunction_GET_CLOSURE(func); +#if PY_MAJOR_VERSION >= 3 + kwdefs = PyFunction_GET_KW_DEFAULTS(func); +#endif + if (argdefs != NULL) { + d = &PyTuple_GET_ITEM(argdefs, 0); + nd = Py_SIZE(argdefs); + } + else { + d = NULL; + nd = 0; + } +#if PY_MAJOR_VERSION >= 3 + result = PyEval_EvalCodeEx((PyObject*)co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, kwdefs, closure); +#else + result = PyEval_EvalCodeEx(co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, closure); +#endif + Py_XDECREF(kwtuple); +done: + Py_LeaveRecursiveCall(); + return result; +} +#endif + +/* PyObjectCall */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw) { + PyObject *result; + ternaryfunc call = Py_TYPE(func)->tp_call; + if (unlikely(!call)) + return PyObject_Call(func, arg, kw); + #if PY_MAJOR_VERSION < 3 + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + #else + if (unlikely(Py_EnterRecursiveCall(" while calling a Python object"))) + return NULL; + #endif + result = (*call)(func, arg, kw); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* PyObjectCallMethO */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg) { + PyObject *self, *result; + PyCFunction cfunc; + cfunc = __Pyx_CyOrPyCFunction_GET_FUNCTION(func); + self = __Pyx_CyOrPyCFunction_GET_SELF(func); + #if PY_MAJOR_VERSION < 3 + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + #else + if (unlikely(Py_EnterRecursiveCall(" while calling a Python object"))) + return NULL; + #endif + result = cfunc(self, arg); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* PyObjectFastCall */ +#if PY_VERSION_HEX < 0x03090000 || CYTHON_COMPILING_IN_LIMITED_API +static PyObject* __Pyx_PyObject_FastCall_fallback(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs) { + PyObject *argstuple; + PyObject *result = 0; + size_t i; + argstuple = PyTuple_New((Py_ssize_t)nargs); + if (unlikely(!argstuple)) return NULL; + for (i = 0; i < nargs; i++) { + Py_INCREF(args[i]); + if (__Pyx_PyTuple_SET_ITEM(argstuple, (Py_ssize_t)i, args[i]) < 0) goto bad; + } + result = __Pyx_PyObject_Call(func, argstuple, kwargs); + bad: + Py_DECREF(argstuple); + return result; +} +#endif +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t _nargs, PyObject *kwargs) { + Py_ssize_t nargs = __Pyx_PyVectorcall_NARGS(_nargs); +#if CYTHON_COMPILING_IN_CPYTHON + if (nargs == 0 && kwargs == NULL) { + if (__Pyx_CyOrPyCFunction_Check(func) && likely( __Pyx_CyOrPyCFunction_GET_FLAGS(func) & METH_NOARGS)) + return __Pyx_PyObject_CallMethO(func, NULL); + } + else if (nargs == 1 && kwargs == NULL) { + if (__Pyx_CyOrPyCFunction_Check(func) && likely( __Pyx_CyOrPyCFunction_GET_FLAGS(func) & METH_O)) + return __Pyx_PyObject_CallMethO(func, args[0]); + } +#endif + #if PY_VERSION_HEX < 0x030800B1 + #if CYTHON_FAST_PYCCALL + if (PyCFunction_Check(func)) { + if (kwargs) { + return _PyCFunction_FastCallDict(func, args, nargs, kwargs); + } else { + return _PyCFunction_FastCallKeywords(func, args, nargs, NULL); + } + } + #if PY_VERSION_HEX >= 0x030700A1 + if (!kwargs && __Pyx_IS_TYPE(func, &PyMethodDescr_Type)) { + return _PyMethodDescr_FastCallKeywords(func, args, nargs, NULL); + } + #endif + #endif + #if CYTHON_FAST_PYCALL + if (PyFunction_Check(func)) { + return __Pyx_PyFunction_FastCallDict(func, args, nargs, kwargs); + } + #endif + #endif + if (kwargs == NULL) { + #if CYTHON_VECTORCALL + #if PY_VERSION_HEX < 0x03090000 + vectorcallfunc f = _PyVectorcall_Function(func); + #else + vectorcallfunc f = PyVectorcall_Function(func); + #endif + if (f) { + return f(func, args, (size_t)nargs, NULL); + } + #elif defined(__Pyx_CyFunction_USED) && CYTHON_BACKPORT_VECTORCALL + if (__Pyx_CyFunction_CheckExact(func)) { + __pyx_vectorcallfunc f = __Pyx_CyFunction_func_vectorcall(func); + if (f) return f(func, args, (size_t)nargs, NULL); + } + #endif + } + if (nargs == 0) { + return __Pyx_PyObject_Call(func, __pyx_empty_tuple, kwargs); + } + #if PY_VERSION_HEX >= 0x03090000 && !CYTHON_COMPILING_IN_LIMITED_API + return PyObject_VectorcallDict(func, args, (size_t)nargs, kwargs); + #else + return __Pyx_PyObject_FastCall_fallback(func, args, (size_t)nargs, kwargs); + #endif +} + +/* RaiseUnexpectedTypeError */ +static int +__Pyx_RaiseUnexpectedTypeError(const char *expected, PyObject *obj) +{ + __Pyx_TypeName obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, "Expected %s, got " __Pyx_FMT_TYPENAME, + expected, obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return 0; +} + +/* CIntToDigits */ +static const char DIGIT_PAIRS_10[2*10*10+1] = { + "00010203040506070809" + "10111213141516171819" + "20212223242526272829" + "30313233343536373839" + "40414243444546474849" + "50515253545556575859" + "60616263646566676869" + "70717273747576777879" + "80818283848586878889" + "90919293949596979899" +}; +static const char DIGIT_PAIRS_8[2*8*8+1] = { + "0001020304050607" + "1011121314151617" + "2021222324252627" + "3031323334353637" + "4041424344454647" + "5051525354555657" + "6061626364656667" + "7071727374757677" +}; +static const char DIGITS_HEX[2*16+1] = { + "0123456789abcdef" + "0123456789ABCDEF" +}; + +/* BuildPyUnicode */ +static PyObject* __Pyx_PyUnicode_BuildFromAscii(Py_ssize_t ulength, char* chars, int clength, + int prepend_sign, char padding_char) { + PyObject *uval; + Py_ssize_t uoffset = ulength - clength; +#if CYTHON_USE_UNICODE_INTERNALS + Py_ssize_t i; +#if CYTHON_PEP393_ENABLED + void *udata; + uval = PyUnicode_New(ulength, 127); + if (unlikely(!uval)) return NULL; + udata = PyUnicode_DATA(uval); +#else + Py_UNICODE *udata; + uval = PyUnicode_FromUnicode(NULL, ulength); + if (unlikely(!uval)) return NULL; + udata = PyUnicode_AS_UNICODE(uval); +#endif + if (uoffset > 0) { + i = 0; + if (prepend_sign) { + __Pyx_PyUnicode_WRITE(PyUnicode_1BYTE_KIND, udata, 0, '-'); + i++; + } + for (; i < uoffset; i++) { + __Pyx_PyUnicode_WRITE(PyUnicode_1BYTE_KIND, udata, i, padding_char); + } + } + for (i=0; i < clength; i++) { + __Pyx_PyUnicode_WRITE(PyUnicode_1BYTE_KIND, udata, uoffset+i, chars[i]); + } +#else + { + PyObject *sign = NULL, *padding = NULL; + uval = NULL; + if (uoffset > 0) { + prepend_sign = !!prepend_sign; + if (uoffset > prepend_sign) { + padding = PyUnicode_FromOrdinal(padding_char); + if (likely(padding) && uoffset > prepend_sign + 1) { + PyObject *tmp; + PyObject *repeat = PyInt_FromSsize_t(uoffset - prepend_sign); + if (unlikely(!repeat)) goto done_or_error; + tmp = PyNumber_Multiply(padding, repeat); + Py_DECREF(repeat); + Py_DECREF(padding); + padding = tmp; + } + if (unlikely(!padding)) goto done_or_error; + } + if (prepend_sign) { + sign = PyUnicode_FromOrdinal('-'); + if (unlikely(!sign)) goto done_or_error; + } + } + uval = PyUnicode_DecodeASCII(chars, clength, NULL); + if (likely(uval) && padding) { + PyObject *tmp = PyNumber_Add(padding, uval); + Py_DECREF(uval); + uval = tmp; + } + if (likely(uval) && sign) { + PyObject *tmp = PyNumber_Add(sign, uval); + Py_DECREF(uval); + uval = tmp; + } +done_or_error: + Py_XDECREF(padding); + Py_XDECREF(sign); + } +#endif + return uval; +} + +/* CIntToPyUnicode */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_int(int value, Py_ssize_t width, char padding_char, char format_char) { + char digits[sizeof(int)*3+2]; + char *dpos, *end = digits + sizeof(int)*3+2; + const char *hex_digits = DIGITS_HEX; + Py_ssize_t length, ulength; + int prepend_sign, last_one_off; + int remaining; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (format_char == 'X') { + hex_digits += 16; + format_char = 'x'; + } + remaining = value; + last_one_off = 0; + dpos = end; + do { + int digit_pos; + switch (format_char) { + case 'o': + digit_pos = abs((int)(remaining % (8*8))); + remaining = (int) (remaining / (8*8)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_8 + digit_pos * 2, 2); + last_one_off = (digit_pos < 8); + break; + case 'd': + digit_pos = abs((int)(remaining % (10*10))); + remaining = (int) (remaining / (10*10)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_10 + digit_pos * 2, 2); + last_one_off = (digit_pos < 10); + break; + case 'x': + *(--dpos) = hex_digits[abs((int)(remaining % 16))]; + remaining = (int) (remaining / 16); + break; + default: + assert(0); + break; + } + } while (unlikely(remaining != 0)); + assert(!last_one_off || *dpos == '0'); + dpos += last_one_off; + length = end - dpos; + ulength = length; + prepend_sign = 0; + if (!is_unsigned && value <= neg_one) { + if (padding_char == ' ' || width <= length + 1) { + *(--dpos) = '-'; + ++length; + } else { + prepend_sign = 1; + } + ++ulength; + } + if (width > ulength) { + ulength = width; + } + if (ulength == 1) { + return PyUnicode_FromOrdinal(*dpos); + } + return __Pyx_PyUnicode_BuildFromAscii(ulength, dpos, (int) length, prepend_sign, padding_char); +} + +/* CIntToPyUnicode */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_Py_ssize_t(Py_ssize_t value, Py_ssize_t width, char padding_char, char format_char) { + char digits[sizeof(Py_ssize_t)*3+2]; + char *dpos, *end = digits + sizeof(Py_ssize_t)*3+2; + const char *hex_digits = DIGITS_HEX; + Py_ssize_t length, ulength; + int prepend_sign, last_one_off; + Py_ssize_t remaining; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const Py_ssize_t neg_one = (Py_ssize_t) -1, const_zero = (Py_ssize_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (format_char == 'X') { + hex_digits += 16; + format_char = 'x'; + } + remaining = value; + last_one_off = 0; + dpos = end; + do { + int digit_pos; + switch (format_char) { + case 'o': + digit_pos = abs((int)(remaining % (8*8))); + remaining = (Py_ssize_t) (remaining / (8*8)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_8 + digit_pos * 2, 2); + last_one_off = (digit_pos < 8); + break; + case 'd': + digit_pos = abs((int)(remaining % (10*10))); + remaining = (Py_ssize_t) (remaining / (10*10)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_10 + digit_pos * 2, 2); + last_one_off = (digit_pos < 10); + break; + case 'x': + *(--dpos) = hex_digits[abs((int)(remaining % 16))]; + remaining = (Py_ssize_t) (remaining / 16); + break; + default: + assert(0); + break; + } + } while (unlikely(remaining != 0)); + assert(!last_one_off || *dpos == '0'); + dpos += last_one_off; + length = end - dpos; + ulength = length; + prepend_sign = 0; + if (!is_unsigned && value <= neg_one) { + if (padding_char == ' ' || width <= length + 1) { + *(--dpos) = '-'; + ++length; + } else { + prepend_sign = 1; + } + ++ulength; + } + if (width > ulength) { + ulength = width; + } + if (ulength == 1) { + return PyUnicode_FromOrdinal(*dpos); + } + return __Pyx_PyUnicode_BuildFromAscii(ulength, dpos, (int) length, prepend_sign, padding_char); +} + +/* JoinPyUnicode */ +static PyObject* __Pyx_PyUnicode_Join(PyObject* value_tuple, Py_ssize_t value_count, Py_ssize_t result_ulength, + Py_UCS4 max_char) { +#if CYTHON_USE_UNICODE_INTERNALS && CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + PyObject *result_uval; + int result_ukind, kind_shift; + Py_ssize_t i, char_pos; + void *result_udata; + CYTHON_MAYBE_UNUSED_VAR(max_char); +#if CYTHON_PEP393_ENABLED + result_uval = PyUnicode_New(result_ulength, max_char); + if (unlikely(!result_uval)) return NULL; + result_ukind = (max_char <= 255) ? PyUnicode_1BYTE_KIND : (max_char <= 65535) ? PyUnicode_2BYTE_KIND : PyUnicode_4BYTE_KIND; + kind_shift = (result_ukind == PyUnicode_4BYTE_KIND) ? 2 : result_ukind - 1; + result_udata = PyUnicode_DATA(result_uval); +#else + result_uval = PyUnicode_FromUnicode(NULL, result_ulength); + if (unlikely(!result_uval)) return NULL; + result_ukind = sizeof(Py_UNICODE); + kind_shift = (result_ukind == 4) ? 2 : result_ukind - 1; + result_udata = PyUnicode_AS_UNICODE(result_uval); +#endif + assert(kind_shift == 2 || kind_shift == 1 || kind_shift == 0); + char_pos = 0; + for (i=0; i < value_count; i++) { + int ukind; + Py_ssize_t ulength; + void *udata; + PyObject *uval = PyTuple_GET_ITEM(value_tuple, i); + if (unlikely(__Pyx_PyUnicode_READY(uval))) + goto bad; + ulength = __Pyx_PyUnicode_GET_LENGTH(uval); + if (unlikely(!ulength)) + continue; + if (unlikely((PY_SSIZE_T_MAX >> kind_shift) - ulength < char_pos)) + goto overflow; + ukind = __Pyx_PyUnicode_KIND(uval); + udata = __Pyx_PyUnicode_DATA(uval); + if (!CYTHON_PEP393_ENABLED || ukind == result_ukind) { + memcpy((char *)result_udata + (char_pos << kind_shift), udata, (size_t) (ulength << kind_shift)); + } else { + #if PY_VERSION_HEX >= 0x030d0000 + if (unlikely(PyUnicode_CopyCharacters(result_uval, char_pos, uval, 0, ulength) < 0)) goto bad; + #elif CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030300F0 || defined(_PyUnicode_FastCopyCharacters) + _PyUnicode_FastCopyCharacters(result_uval, char_pos, uval, 0, ulength); + #else + Py_ssize_t j; + for (j=0; j < ulength; j++) { + Py_UCS4 uchar = __Pyx_PyUnicode_READ(ukind, udata, j); + __Pyx_PyUnicode_WRITE(result_ukind, result_udata, char_pos+j, uchar); + } + #endif + } + char_pos += ulength; + } + return result_uval; +overflow: + PyErr_SetString(PyExc_OverflowError, "join() result is too long for a Python string"); +bad: + Py_DECREF(result_uval); + return NULL; +#else + CYTHON_UNUSED_VAR(max_char); + CYTHON_UNUSED_VAR(result_ulength); + CYTHON_UNUSED_VAR(value_count); + return PyUnicode_Join(__pyx_empty_unicode, value_tuple); +#endif +} + +/* GetAttr */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr(PyObject *o, PyObject *n) { +#if CYTHON_USE_TYPE_SLOTS +#if PY_MAJOR_VERSION >= 3 + if (likely(PyUnicode_Check(n))) +#else + if (likely(PyString_Check(n))) +#endif + return __Pyx_PyObject_GetAttrStr(o, n); +#endif + return PyObject_GetAttr(o, n); +} + +/* GetItemInt */ +static PyObject *__Pyx_GetItemInt_Generic(PyObject *o, PyObject* j) { + PyObject *r; + if (unlikely(!j)) return NULL; + r = PyObject_GetItem(o, j); + Py_DECREF(j); + return r; +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_List_Fast(PyObject *o, Py_ssize_t i, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + Py_ssize_t wrapped_i = i; + if (wraparound & unlikely(i < 0)) { + wrapped_i += PyList_GET_SIZE(o); + } + if ((!boundscheck) || likely(__Pyx_is_valid_index(wrapped_i, PyList_GET_SIZE(o)))) { + PyObject *r = PyList_GET_ITEM(o, wrapped_i); + Py_INCREF(r); + return r; + } + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +#else + return PySequence_GetItem(o, i); +#endif +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Tuple_Fast(PyObject *o, Py_ssize_t i, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + Py_ssize_t wrapped_i = i; + if (wraparound & unlikely(i < 0)) { + wrapped_i += PyTuple_GET_SIZE(o); + } + if ((!boundscheck) || likely(__Pyx_is_valid_index(wrapped_i, PyTuple_GET_SIZE(o)))) { + PyObject *r = PyTuple_GET_ITEM(o, wrapped_i); + Py_INCREF(r); + return r; + } + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +#else + return PySequence_GetItem(o, i); +#endif +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Fast(PyObject *o, Py_ssize_t i, int is_list, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS && CYTHON_USE_TYPE_SLOTS + if (is_list || PyList_CheckExact(o)) { + Py_ssize_t n = ((!wraparound) | likely(i >= 0)) ? i : i + PyList_GET_SIZE(o); + if ((!boundscheck) || (likely(__Pyx_is_valid_index(n, PyList_GET_SIZE(o))))) { + PyObject *r = PyList_GET_ITEM(o, n); + Py_INCREF(r); + return r; + } + } + else if (PyTuple_CheckExact(o)) { + Py_ssize_t n = ((!wraparound) | likely(i >= 0)) ? i : i + PyTuple_GET_SIZE(o); + if ((!boundscheck) || likely(__Pyx_is_valid_index(n, PyTuple_GET_SIZE(o)))) { + PyObject *r = PyTuple_GET_ITEM(o, n); + Py_INCREF(r); + return r; + } + } else { + PyMappingMethods *mm = Py_TYPE(o)->tp_as_mapping; + PySequenceMethods *sm = Py_TYPE(o)->tp_as_sequence; + if (mm && mm->mp_subscript) { + PyObject *r, *key = PyInt_FromSsize_t(i); + if (unlikely(!key)) return NULL; + r = mm->mp_subscript(o, key); + Py_DECREF(key); + return r; + } + if (likely(sm && sm->sq_item)) { + if (wraparound && unlikely(i < 0) && likely(sm->sq_length)) { + Py_ssize_t l = sm->sq_length(o); + if (likely(l >= 0)) { + i += l; + } else { + if (!PyErr_ExceptionMatches(PyExc_OverflowError)) + return NULL; + PyErr_Clear(); + } + } + return sm->sq_item(o, i); + } + } +#else + if (is_list || !PyMapping_Check(o)) { + return PySequence_GetItem(o, i); + } +#endif + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +} + +/* PyObjectCallOneArg */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg) { + PyObject *args[2] = {NULL, arg}; + return __Pyx_PyObject_FastCall(func, args+1, 1 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* ObjectGetItem */ +#if CYTHON_USE_TYPE_SLOTS +static PyObject *__Pyx_PyObject_GetIndex(PyObject *obj, PyObject *index) { + PyObject *runerr = NULL; + Py_ssize_t key_value; + key_value = __Pyx_PyIndex_AsSsize_t(index); + if (likely(key_value != -1 || !(runerr = PyErr_Occurred()))) { + return __Pyx_GetItemInt_Fast(obj, key_value, 0, 1, 1); + } + if (PyErr_GivenExceptionMatches(runerr, PyExc_OverflowError)) { + __Pyx_TypeName index_type_name = __Pyx_PyType_GetName(Py_TYPE(index)); + PyErr_Clear(); + PyErr_Format(PyExc_IndexError, + "cannot fit '" __Pyx_FMT_TYPENAME "' into an index-sized integer", index_type_name); + __Pyx_DECREF_TypeName(index_type_name); + } + return NULL; +} +static PyObject *__Pyx_PyObject_GetItem_Slow(PyObject *obj, PyObject *key) { + __Pyx_TypeName obj_type_name; + if (likely(PyType_Check(obj))) { + PyObject *meth = __Pyx_PyObject_GetAttrStrNoError(obj, __pyx_n_s_class_getitem); + if (!meth) { + PyErr_Clear(); + } else { + PyObject *result = __Pyx_PyObject_CallOneArg(meth, key); + Py_DECREF(meth); + return result; + } + } + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "'" __Pyx_FMT_TYPENAME "' object is not subscriptable", obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return NULL; +} +static PyObject *__Pyx_PyObject_GetItem(PyObject *obj, PyObject *key) { + PyTypeObject *tp = Py_TYPE(obj); + PyMappingMethods *mm = tp->tp_as_mapping; + PySequenceMethods *sm = tp->tp_as_sequence; + if (likely(mm && mm->mp_subscript)) { + return mm->mp_subscript(obj, key); + } + if (likely(sm && sm->sq_item)) { + return __Pyx_PyObject_GetIndex(obj, key); + } + return __Pyx_PyObject_GetItem_Slow(obj, key); +} +#endif + +/* KeywordStringCheck */ +static int __Pyx_CheckKeywordStrings( + PyObject *kw, + const char* function_name, + int kw_allowed) +{ + PyObject* key = 0; + Py_ssize_t pos = 0; +#if CYTHON_COMPILING_IN_PYPY + if (!kw_allowed && PyDict_Next(kw, &pos, &key, 0)) + goto invalid_keyword; + return 1; +#else + if (CYTHON_METH_FASTCALL && likely(PyTuple_Check(kw))) { + Py_ssize_t kwsize; +#if CYTHON_ASSUME_SAFE_MACROS + kwsize = PyTuple_GET_SIZE(kw); +#else + kwsize = PyTuple_Size(kw); + if (kwsize < 0) return 0; +#endif + if (unlikely(kwsize == 0)) + return 1; + if (!kw_allowed) { +#if CYTHON_ASSUME_SAFE_MACROS + key = PyTuple_GET_ITEM(kw, 0); +#else + key = PyTuple_GetItem(kw, pos); + if (!key) return 0; +#endif + goto invalid_keyword; + } +#if PY_VERSION_HEX < 0x03090000 + for (pos = 0; pos < kwsize; pos++) { +#if CYTHON_ASSUME_SAFE_MACROS + key = PyTuple_GET_ITEM(kw, pos); +#else + key = PyTuple_GetItem(kw, pos); + if (!key) return 0; +#endif + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } +#endif + return 1; + } + while (PyDict_Next(kw, &pos, &key, 0)) { + #if PY_MAJOR_VERSION < 3 + if (unlikely(!PyString_Check(key))) + #endif + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } + if (!kw_allowed && unlikely(key)) + goto invalid_keyword; + return 1; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + return 0; +#endif +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif + return 0; +} + +/* DivInt[Py_ssize_t] */ +static CYTHON_INLINE Py_ssize_t __Pyx_div_Py_ssize_t(Py_ssize_t a, Py_ssize_t b) { + Py_ssize_t q = a / b; + Py_ssize_t r = a - q*b; + q -= ((r != 0) & ((r ^ b) < 0)); + return q; +} + +/* GetAttr3 */ +#if __PYX_LIMITED_VERSION_HEX < 0x030d00A1 +static PyObject *__Pyx_GetAttr3Default(PyObject *d) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + if (unlikely(!__Pyx_PyErr_ExceptionMatches(PyExc_AttributeError))) + return NULL; + __Pyx_PyErr_Clear(); + Py_INCREF(d); + return d; +} +#endif +static CYTHON_INLINE PyObject *__Pyx_GetAttr3(PyObject *o, PyObject *n, PyObject *d) { + PyObject *r; +#if __PYX_LIMITED_VERSION_HEX >= 0x030d00A1 + int res = PyObject_GetOptionalAttr(o, n, &r); + return (res != 0) ? r : __Pyx_NewRef(d); +#else + #if CYTHON_USE_TYPE_SLOTS + if (likely(PyString_Check(n))) { + r = __Pyx_PyObject_GetAttrStrNoError(o, n); + if (unlikely(!r) && likely(!PyErr_Occurred())) { + r = __Pyx_NewRef(d); + } + return r; + } + #endif + r = PyObject_GetAttr(o, n); + return (likely(r)) ? r : __Pyx_GetAttr3Default(d); +#endif +} + +/* PyDictVersioning */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + return likely(dict) ? __PYX_GET_DICT_VERSION(dict) : 0; +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj) { + PyObject **dictptr = NULL; + Py_ssize_t offset = Py_TYPE(obj)->tp_dictoffset; + if (offset) { +#if CYTHON_COMPILING_IN_CPYTHON + dictptr = (likely(offset > 0)) ? (PyObject **) ((char *)obj + offset) : _PyObject_GetDictPtr(obj); +#else + dictptr = _PyObject_GetDictPtr(obj); +#endif + } + return (dictptr && *dictptr) ? __PYX_GET_DICT_VERSION(*dictptr) : 0; +} +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + if (unlikely(!dict) || unlikely(tp_dict_version != __PYX_GET_DICT_VERSION(dict))) + return 0; + return obj_dict_version == __Pyx_get_object_dict_version(obj); +} +#endif + +/* GetModuleGlobalName */ +#if CYTHON_USE_DICT_VERSIONS +static PyObject *__Pyx__GetModuleGlobalName(PyObject *name, PY_UINT64_T *dict_version, PyObject **dict_cached_value) +#else +static CYTHON_INLINE PyObject *__Pyx__GetModuleGlobalName(PyObject *name) +#endif +{ + PyObject *result; +#if !CYTHON_AVOID_BORROWED_REFS +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030500A1 && PY_VERSION_HEX < 0x030d0000 + result = _PyDict_GetItem_KnownHash(__pyx_d, name, ((PyASCIIObject *) name)->hash); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } else if (unlikely(PyErr_Occurred())) { + return NULL; + } +#elif CYTHON_COMPILING_IN_LIMITED_API + if (unlikely(!__pyx_m)) { + return NULL; + } + result = PyObject_GetAttr(__pyx_m, name); + if (likely(result)) { + return result; + } +#else + result = PyDict_GetItem(__pyx_d, name); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } +#endif +#else + result = PyObject_GetItem(__pyx_d, name); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } + PyErr_Clear(); +#endif + return __Pyx_GetBuiltinName(name); +} + +/* RaiseTooManyValuesToUnpack */ +static CYTHON_INLINE void __Pyx_RaiseTooManyValuesError(Py_ssize_t expected) { + PyErr_Format(PyExc_ValueError, + "too many values to unpack (expected %" CYTHON_FORMAT_SSIZE_T "d)", expected); +} + +/* RaiseNeedMoreValuesToUnpack */ +static CYTHON_INLINE void __Pyx_RaiseNeedMoreValuesError(Py_ssize_t index) { + PyErr_Format(PyExc_ValueError, + "need more than %" CYTHON_FORMAT_SSIZE_T "d value%.1s to unpack", + index, (index == 1) ? "" : "s"); +} + +/* RaiseNoneIterError */ +static CYTHON_INLINE void __Pyx_RaiseNoneNotIterableError(void) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not iterable"); +} + +/* ExtTypeTest */ +static CYTHON_INLINE int __Pyx_TypeTest(PyObject *obj, PyTypeObject *type) { + __Pyx_TypeName obj_type_name; + __Pyx_TypeName type_name; + if (unlikely(!type)) { + PyErr_SetString(PyExc_SystemError, "Missing type object"); + return 0; + } + if (likely(__Pyx_TypeCheck(obj, type))) + return 1; + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + type_name = __Pyx_PyType_GetName(type); + PyErr_Format(PyExc_TypeError, + "Cannot convert " __Pyx_FMT_TYPENAME " to " __Pyx_FMT_TYPENAME, + obj_type_name, type_name); + __Pyx_DECREF_TypeName(obj_type_name); + __Pyx_DECREF_TypeName(type_name); + return 0; +} + +/* GetTopmostException */ +#if CYTHON_USE_EXC_INFO_STACK && CYTHON_FAST_THREAD_STATE +static _PyErr_StackItem * +__Pyx_PyErr_GetTopmostException(PyThreadState *tstate) +{ + _PyErr_StackItem *exc_info = tstate->exc_info; + while ((exc_info->exc_value == NULL || exc_info->exc_value == Py_None) && + exc_info->previous_item != NULL) + { + exc_info = exc_info->previous_item; + } + return exc_info; +} +#endif + +/* SaveResetException */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx__ExceptionSave(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { + #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 + _PyErr_StackItem *exc_info = __Pyx_PyErr_GetTopmostException(tstate); + PyObject *exc_value = exc_info->exc_value; + if (exc_value == NULL || exc_value == Py_None) { + *value = NULL; + *type = NULL; + *tb = NULL; + } else { + *value = exc_value; + Py_INCREF(*value); + *type = (PyObject*) Py_TYPE(exc_value); + Py_INCREF(*type); + *tb = PyException_GetTraceback(exc_value); + } + #elif CYTHON_USE_EXC_INFO_STACK + _PyErr_StackItem *exc_info = __Pyx_PyErr_GetTopmostException(tstate); + *type = exc_info->exc_type; + *value = exc_info->exc_value; + *tb = exc_info->exc_traceback; + Py_XINCREF(*type); + Py_XINCREF(*value); + Py_XINCREF(*tb); + #else + *type = tstate->exc_type; + *value = tstate->exc_value; + *tb = tstate->exc_traceback; + Py_XINCREF(*type); + Py_XINCREF(*value); + Py_XINCREF(*tb); + #endif +} +static CYTHON_INLINE void __Pyx__ExceptionReset(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb) { + #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 + _PyErr_StackItem *exc_info = tstate->exc_info; + PyObject *tmp_value = exc_info->exc_value; + exc_info->exc_value = value; + Py_XDECREF(tmp_value); + Py_XDECREF(type); + Py_XDECREF(tb); + #else + PyObject *tmp_type, *tmp_value, *tmp_tb; + #if CYTHON_USE_EXC_INFO_STACK + _PyErr_StackItem *exc_info = tstate->exc_info; + tmp_type = exc_info->exc_type; + tmp_value = exc_info->exc_value; + tmp_tb = exc_info->exc_traceback; + exc_info->exc_type = type; + exc_info->exc_value = value; + exc_info->exc_traceback = tb; + #else + tmp_type = tstate->exc_type; + tmp_value = tstate->exc_value; + tmp_tb = tstate->exc_traceback; + tstate->exc_type = type; + tstate->exc_value = value; + tstate->exc_traceback = tb; + #endif + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); + #endif +} +#endif + +/* GetException */ +#if CYTHON_FAST_THREAD_STATE +static int __Pyx__GetException(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) +#else +static int __Pyx_GetException(PyObject **type, PyObject **value, PyObject **tb) +#endif +{ + PyObject *local_type = NULL, *local_value, *local_tb = NULL; +#if CYTHON_FAST_THREAD_STATE + PyObject *tmp_type, *tmp_value, *tmp_tb; + #if PY_VERSION_HEX >= 0x030C00A6 + local_value = tstate->current_exception; + tstate->current_exception = 0; + if (likely(local_value)) { + local_type = (PyObject*) Py_TYPE(local_value); + Py_INCREF(local_type); + local_tb = PyException_GetTraceback(local_value); + } + #else + local_type = tstate->curexc_type; + local_value = tstate->curexc_value; + local_tb = tstate->curexc_traceback; + tstate->curexc_type = 0; + tstate->curexc_value = 0; + tstate->curexc_traceback = 0; + #endif +#else + PyErr_Fetch(&local_type, &local_value, &local_tb); +#endif + PyErr_NormalizeException(&local_type, &local_value, &local_tb); +#if CYTHON_FAST_THREAD_STATE && PY_VERSION_HEX >= 0x030C00A6 + if (unlikely(tstate->current_exception)) +#elif CYTHON_FAST_THREAD_STATE + if (unlikely(tstate->curexc_type)) +#else + if (unlikely(PyErr_Occurred())) +#endif + goto bad; + #if PY_MAJOR_VERSION >= 3 + if (local_tb) { + if (unlikely(PyException_SetTraceback(local_value, local_tb) < 0)) + goto bad; + } + #endif + Py_XINCREF(local_tb); + Py_XINCREF(local_type); + Py_XINCREF(local_value); + *type = local_type; + *value = local_value; + *tb = local_tb; +#if CYTHON_FAST_THREAD_STATE + #if CYTHON_USE_EXC_INFO_STACK + { + _PyErr_StackItem *exc_info = tstate->exc_info; + #if PY_VERSION_HEX >= 0x030B00a4 + tmp_value = exc_info->exc_value; + exc_info->exc_value = local_value; + tmp_type = NULL; + tmp_tb = NULL; + Py_XDECREF(local_type); + Py_XDECREF(local_tb); + #else + tmp_type = exc_info->exc_type; + tmp_value = exc_info->exc_value; + tmp_tb = exc_info->exc_traceback; + exc_info->exc_type = local_type; + exc_info->exc_value = local_value; + exc_info->exc_traceback = local_tb; + #endif + } + #else + tmp_type = tstate->exc_type; + tmp_value = tstate->exc_value; + tmp_tb = tstate->exc_traceback; + tstate->exc_type = local_type; + tstate->exc_value = local_value; + tstate->exc_traceback = local_tb; + #endif + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); +#else + PyErr_SetExcInfo(local_type, local_value, local_tb); +#endif + return 0; +bad: + *type = 0; + *value = 0; + *tb = 0; + Py_XDECREF(local_type); + Py_XDECREF(local_value); + Py_XDECREF(local_tb); + return -1; +} + +/* SwapException */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx__ExceptionSwap(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { + PyObject *tmp_type, *tmp_value, *tmp_tb; + #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 + _PyErr_StackItem *exc_info = tstate->exc_info; + tmp_value = exc_info->exc_value; + exc_info->exc_value = *value; + if (tmp_value == NULL || tmp_value == Py_None) { + Py_XDECREF(tmp_value); + tmp_value = NULL; + tmp_type = NULL; + tmp_tb = NULL; + } else { + tmp_type = (PyObject*) Py_TYPE(tmp_value); + Py_INCREF(tmp_type); + #if CYTHON_COMPILING_IN_CPYTHON + tmp_tb = ((PyBaseExceptionObject*) tmp_value)->traceback; + Py_XINCREF(tmp_tb); + #else + tmp_tb = PyException_GetTraceback(tmp_value); + #endif + } + #elif CYTHON_USE_EXC_INFO_STACK + _PyErr_StackItem *exc_info = tstate->exc_info; + tmp_type = exc_info->exc_type; + tmp_value = exc_info->exc_value; + tmp_tb = exc_info->exc_traceback; + exc_info->exc_type = *type; + exc_info->exc_value = *value; + exc_info->exc_traceback = *tb; + #else + tmp_type = tstate->exc_type; + tmp_value = tstate->exc_value; + tmp_tb = tstate->exc_traceback; + tstate->exc_type = *type; + tstate->exc_value = *value; + tstate->exc_traceback = *tb; + #endif + *type = tmp_type; + *value = tmp_value; + *tb = tmp_tb; +} +#else +static CYTHON_INLINE void __Pyx_ExceptionSwap(PyObject **type, PyObject **value, PyObject **tb) { + PyObject *tmp_type, *tmp_value, *tmp_tb; + PyErr_GetExcInfo(&tmp_type, &tmp_value, &tmp_tb); + PyErr_SetExcInfo(*type, *value, *tb); + *type = tmp_type; + *value = tmp_value; + *tb = tmp_tb; +} +#endif + +/* Import */ +static PyObject *__Pyx_Import(PyObject *name, PyObject *from_list, int level) { + PyObject *module = 0; + PyObject *empty_dict = 0; + PyObject *empty_list = 0; + #if PY_MAJOR_VERSION < 3 + PyObject *py_import; + py_import = __Pyx_PyObject_GetAttrStr(__pyx_b, __pyx_n_s_import); + if (unlikely(!py_import)) + goto bad; + if (!from_list) { + empty_list = PyList_New(0); + if (unlikely(!empty_list)) + goto bad; + from_list = empty_list; + } + #endif + empty_dict = PyDict_New(); + if (unlikely(!empty_dict)) + goto bad; + { + #if PY_MAJOR_VERSION >= 3 + if (level == -1) { + if (strchr(__Pyx_MODULE_NAME, '.') != NULL) { + module = PyImport_ImportModuleLevelObject( + name, __pyx_d, empty_dict, from_list, 1); + if (unlikely(!module)) { + if (unlikely(!PyErr_ExceptionMatches(PyExc_ImportError))) + goto bad; + PyErr_Clear(); + } + } + level = 0; + } + #endif + if (!module) { + #if PY_MAJOR_VERSION < 3 + PyObject *py_level = PyInt_FromLong(level); + if (unlikely(!py_level)) + goto bad; + module = PyObject_CallFunctionObjArgs(py_import, + name, __pyx_d, empty_dict, from_list, py_level, (PyObject *)NULL); + Py_DECREF(py_level); + #else + module = PyImport_ImportModuleLevelObject( + name, __pyx_d, empty_dict, from_list, level); + #endif + } + } +bad: + Py_XDECREF(empty_dict); + Py_XDECREF(empty_list); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_import); + #endif + return module; +} + +/* ImportDottedModule */ +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx__ImportDottedModule_Error(PyObject *name, PyObject *parts_tuple, Py_ssize_t count) { + PyObject *partial_name = NULL, *slice = NULL, *sep = NULL; + if (unlikely(PyErr_Occurred())) { + PyErr_Clear(); + } + if (likely(PyTuple_GET_SIZE(parts_tuple) == count)) { + partial_name = name; + } else { + slice = PySequence_GetSlice(parts_tuple, 0, count); + if (unlikely(!slice)) + goto bad; + sep = PyUnicode_FromStringAndSize(".", 1); + if (unlikely(!sep)) + goto bad; + partial_name = PyUnicode_Join(sep, slice); + } + PyErr_Format( +#if PY_MAJOR_VERSION < 3 + PyExc_ImportError, + "No module named '%s'", PyString_AS_STRING(partial_name)); +#else +#if PY_VERSION_HEX >= 0x030600B1 + PyExc_ModuleNotFoundError, +#else + PyExc_ImportError, +#endif + "No module named '%U'", partial_name); +#endif +bad: + Py_XDECREF(sep); + Py_XDECREF(slice); + Py_XDECREF(partial_name); + return NULL; +} +#endif +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx__ImportDottedModule_Lookup(PyObject *name) { + PyObject *imported_module; +#if PY_VERSION_HEX < 0x030700A1 || (CYTHON_COMPILING_IN_PYPY && PYPY_VERSION_NUM < 0x07030400) + PyObject *modules = PyImport_GetModuleDict(); + if (unlikely(!modules)) + return NULL; + imported_module = __Pyx_PyDict_GetItemStr(modules, name); + Py_XINCREF(imported_module); +#else + imported_module = PyImport_GetModule(name); +#endif + return imported_module; +} +#endif +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_ImportDottedModule_WalkParts(PyObject *module, PyObject *name, PyObject *parts_tuple) { + Py_ssize_t i, nparts; + nparts = PyTuple_GET_SIZE(parts_tuple); + for (i=1; i < nparts && module; i++) { + PyObject *part, *submodule; +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + part = PyTuple_GET_ITEM(parts_tuple, i); +#else + part = PySequence_ITEM(parts_tuple, i); +#endif + submodule = __Pyx_PyObject_GetAttrStrNoError(module, part); +#if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(part); +#endif + Py_DECREF(module); + module = submodule; + } + if (unlikely(!module)) { + return __Pyx__ImportDottedModule_Error(name, parts_tuple, i); + } + return module; +} +#endif +static PyObject *__Pyx__ImportDottedModule(PyObject *name, PyObject *parts_tuple) { +#if PY_MAJOR_VERSION < 3 + PyObject *module, *from_list, *star = __pyx_n_s__3; + CYTHON_UNUSED_VAR(parts_tuple); + from_list = PyList_New(1); + if (unlikely(!from_list)) + return NULL; + Py_INCREF(star); + PyList_SET_ITEM(from_list, 0, star); + module = __Pyx_Import(name, from_list, 0); + Py_DECREF(from_list); + return module; +#else + PyObject *imported_module; + PyObject *module = __Pyx_Import(name, NULL, 0); + if (!parts_tuple || unlikely(!module)) + return module; + imported_module = __Pyx__ImportDottedModule_Lookup(name); + if (likely(imported_module)) { + Py_DECREF(module); + return imported_module; + } + PyErr_Clear(); + return __Pyx_ImportDottedModule_WalkParts(module, name, parts_tuple); +#endif +} +static PyObject *__Pyx_ImportDottedModule(PyObject *name, PyObject *parts_tuple) { +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030400B1 + PyObject *module = __Pyx__ImportDottedModule_Lookup(name); + if (likely(module)) { + PyObject *spec = __Pyx_PyObject_GetAttrStrNoError(module, __pyx_n_s_spec); + if (likely(spec)) { + PyObject *unsafe = __Pyx_PyObject_GetAttrStrNoError(spec, __pyx_n_s_initializing); + if (likely(!unsafe || !__Pyx_PyObject_IsTrue(unsafe))) { + Py_DECREF(spec); + spec = NULL; + } + Py_XDECREF(unsafe); + } + if (likely(!spec)) { + PyErr_Clear(); + return module; + } + Py_DECREF(spec); + Py_DECREF(module); + } else if (PyErr_Occurred()) { + PyErr_Clear(); + } +#endif + return __Pyx__ImportDottedModule(name, parts_tuple); +} + +/* FastTypeChecks */ +#if CYTHON_COMPILING_IN_CPYTHON +static int __Pyx_InBases(PyTypeObject *a, PyTypeObject *b) { + while (a) { + a = __Pyx_PyType_GetSlot(a, tp_base, PyTypeObject*); + if (a == b) + return 1; + } + return b == &PyBaseObject_Type; +} +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (a == b) return 1; + mro = a->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + if (PyTuple_GET_ITEM(mro, i) == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(a, b); +} +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (cls == a || cls == b) return 1; + mro = cls->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + PyObject *base = PyTuple_GET_ITEM(mro, i); + if (base == (PyObject *)a || base == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(cls, a) || __Pyx_InBases(cls, b); +} +#if PY_MAJOR_VERSION == 2 +static int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject* exc_type2) { + PyObject *exception, *value, *tb; + int res; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&exception, &value, &tb); + res = exc_type1 ? PyObject_IsSubclass(err, exc_type1) : 0; + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + if (!res) { + res = PyObject_IsSubclass(err, exc_type2); + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + } + __Pyx_ErrRestore(exception, value, tb); + return res; +} +#else +static CYTHON_INLINE int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject *exc_type2) { + if (exc_type1) { + return __Pyx_IsAnySubtype2((PyTypeObject*)err, (PyTypeObject*)exc_type1, (PyTypeObject*)exc_type2); + } else { + return __Pyx_IsSubtype((PyTypeObject*)err, (PyTypeObject*)exc_type2); + } +} +#endif +static int __Pyx_PyErr_GivenExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + assert(PyExceptionClass_Check(exc_type)); + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; itp_as_sequence && type->tp_as_sequence->sq_repeat)) { + return type->tp_as_sequence->sq_repeat(seq, mul); + } else +#endif + { + return __Pyx_PySequence_Multiply_Generic(seq, mul); + } +} + +/* SetItemInt */ +static int __Pyx_SetItemInt_Generic(PyObject *o, PyObject *j, PyObject *v) { + int r; + if (unlikely(!j)) return -1; + r = PyObject_SetItem(o, j, v); + Py_DECREF(j); + return r; +} +static CYTHON_INLINE int __Pyx_SetItemInt_Fast(PyObject *o, Py_ssize_t i, PyObject *v, int is_list, + CYTHON_NCP_UNUSED int wraparound, CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS && CYTHON_USE_TYPE_SLOTS + if (is_list || PyList_CheckExact(o)) { + Py_ssize_t n = (!wraparound) ? i : ((likely(i >= 0)) ? i : i + PyList_GET_SIZE(o)); + if ((!boundscheck) || likely(__Pyx_is_valid_index(n, PyList_GET_SIZE(o)))) { + PyObject* old = PyList_GET_ITEM(o, n); + Py_INCREF(v); + PyList_SET_ITEM(o, n, v); + Py_DECREF(old); + return 1; + } + } else { + PyMappingMethods *mm = Py_TYPE(o)->tp_as_mapping; + PySequenceMethods *sm = Py_TYPE(o)->tp_as_sequence; + if (mm && mm->mp_ass_subscript) { + int r; + PyObject *key = PyInt_FromSsize_t(i); + if (unlikely(!key)) return -1; + r = mm->mp_ass_subscript(o, key, v); + Py_DECREF(key); + return r; + } + if (likely(sm && sm->sq_ass_item)) { + if (wraparound && unlikely(i < 0) && likely(sm->sq_length)) { + Py_ssize_t l = sm->sq_length(o); + if (likely(l >= 0)) { + i += l; + } else { + if (!PyErr_ExceptionMatches(PyExc_OverflowError)) + return -1; + PyErr_Clear(); + } + } + return sm->sq_ass_item(o, i, v); + } + } +#else + if (is_list || !PyMapping_Check(o)) + { + return PySequence_SetItem(o, i, v); + } +#endif + return __Pyx_SetItemInt_Generic(o, PyInt_FromSsize_t(i), v); +} + +/* RaiseUnboundLocalError */ +static CYTHON_INLINE void __Pyx_RaiseUnboundLocalError(const char *varname) { + PyErr_Format(PyExc_UnboundLocalError, "local variable '%s' referenced before assignment", varname); +} + +/* DivInt[long] */ +static CYTHON_INLINE long __Pyx_div_long(long a, long b) { + long q = a / b; + long r = a - q*b; + q -= ((r != 0) & ((r ^ b) < 0)); + return q; +} + +/* ImportFrom */ +static PyObject* __Pyx_ImportFrom(PyObject* module, PyObject* name) { + PyObject* value = __Pyx_PyObject_GetAttrStr(module, name); + if (unlikely(!value) && PyErr_ExceptionMatches(PyExc_AttributeError)) { + const char* module_name_str = 0; + PyObject* module_name = 0; + PyObject* module_dot = 0; + PyObject* full_name = 0; + PyErr_Clear(); + module_name_str = PyModule_GetName(module); + if (unlikely(!module_name_str)) { goto modbad; } + module_name = PyUnicode_FromString(module_name_str); + if (unlikely(!module_name)) { goto modbad; } + module_dot = PyUnicode_Concat(module_name, __pyx_kp_u__2); + if (unlikely(!module_dot)) { goto modbad; } + full_name = PyUnicode_Concat(module_dot, name); + if (unlikely(!full_name)) { goto modbad; } + #if PY_VERSION_HEX < 0x030700A1 || (CYTHON_COMPILING_IN_PYPY && PYPY_VERSION_NUM < 0x07030400) + { + PyObject *modules = PyImport_GetModuleDict(); + if (unlikely(!modules)) + goto modbad; + value = PyObject_GetItem(modules, full_name); + } + #else + value = PyImport_GetModule(full_name); + #endif + modbad: + Py_XDECREF(full_name); + Py_XDECREF(module_dot); + Py_XDECREF(module_name); + } + if (unlikely(!value)) { + PyErr_Format(PyExc_ImportError, + #if PY_MAJOR_VERSION < 3 + "cannot import name %.230s", PyString_AS_STRING(name)); + #else + "cannot import name %S", name); + #endif + } + return value; +} + +/* HasAttr */ +#if __PYX_LIMITED_VERSION_HEX < 0x030d00A1 +static CYTHON_INLINE int __Pyx_HasAttr(PyObject *o, PyObject *n) { + PyObject *r; + if (unlikely(!__Pyx_PyBaseString_Check(n))) { + PyErr_SetString(PyExc_TypeError, + "hasattr(): attribute name must be string"); + return -1; + } + r = __Pyx_GetAttr(o, n); + if (!r) { + PyErr_Clear(); + return 0; + } else { + Py_DECREF(r); + return 1; + } +} +#endif + +/* PyIntCompare */ +static CYTHON_INLINE int __Pyx_PyInt_BoolEqObjC(PyObject *op1, PyObject *op2, long intval, long inplace) { + CYTHON_MAYBE_UNUSED_VAR(intval); + CYTHON_UNUSED_VAR(inplace); + if (op1 == op2) { + return 1; + } + #if PY_MAJOR_VERSION < 3 + if (likely(PyInt_CheckExact(op1))) { + const long b = intval; + long a = PyInt_AS_LONG(op1); + return (a == b); + } + #endif + #if CYTHON_USE_PYLONG_INTERNALS + if (likely(PyLong_CheckExact(op1))) { + int unequal; + unsigned long uintval; + Py_ssize_t size = __Pyx_PyLong_DigitCount(op1); + const digit* digits = __Pyx_PyLong_Digits(op1); + if (intval == 0) { + return (__Pyx_PyLong_IsZero(op1) == 1); + } else if (intval < 0) { + if (__Pyx_PyLong_IsNonNeg(op1)) + return 0; + intval = -intval; + } else { + if (__Pyx_PyLong_IsNeg(op1)) + return 0; + } + uintval = (unsigned long) intval; +#if PyLong_SHIFT * 4 < SIZEOF_LONG*8 + if (uintval >> (PyLong_SHIFT * 4)) { + unequal = (size != 5) || (digits[0] != (uintval & (unsigned long) PyLong_MASK)) + | (digits[1] != ((uintval >> (1 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[2] != ((uintval >> (2 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[3] != ((uintval >> (3 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[4] != ((uintval >> (4 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)); + } else +#endif +#if PyLong_SHIFT * 3 < SIZEOF_LONG*8 + if (uintval >> (PyLong_SHIFT * 3)) { + unequal = (size != 4) || (digits[0] != (uintval & (unsigned long) PyLong_MASK)) + | (digits[1] != ((uintval >> (1 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[2] != ((uintval >> (2 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[3] != ((uintval >> (3 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)); + } else +#endif +#if PyLong_SHIFT * 2 < SIZEOF_LONG*8 + if (uintval >> (PyLong_SHIFT * 2)) { + unequal = (size != 3) || (digits[0] != (uintval & (unsigned long) PyLong_MASK)) + | (digits[1] != ((uintval >> (1 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[2] != ((uintval >> (2 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)); + } else +#endif +#if PyLong_SHIFT * 1 < SIZEOF_LONG*8 + if (uintval >> (PyLong_SHIFT * 1)) { + unequal = (size != 2) || (digits[0] != (uintval & (unsigned long) PyLong_MASK)) + | (digits[1] != ((uintval >> (1 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)); + } else +#endif + unequal = (size != 1) || (((unsigned long) digits[0]) != (uintval & (unsigned long) PyLong_MASK)); + return (unequal == 0); + } + #endif + if (PyFloat_CheckExact(op1)) { + const long b = intval; +#if CYTHON_COMPILING_IN_LIMITED_API + double a = __pyx_PyFloat_AsDouble(op1); +#else + double a = PyFloat_AS_DOUBLE(op1); +#endif + return ((double)a == (double)b); + } + return __Pyx_PyObject_IsTrueAndDecref( + PyObject_RichCompare(op1, op2, Py_EQ)); +} + +/* PyIntCompare */ +static CYTHON_INLINE int __Pyx_PyInt_BoolNeObjC(PyObject *op1, PyObject *op2, long intval, long inplace) { + CYTHON_MAYBE_UNUSED_VAR(intval); + CYTHON_UNUSED_VAR(inplace); + if (op1 == op2) { + return 0; + } + #if PY_MAJOR_VERSION < 3 + if (likely(PyInt_CheckExact(op1))) { + const long b = intval; + long a = PyInt_AS_LONG(op1); + return (a != b); + } + #endif + #if CYTHON_USE_PYLONG_INTERNALS + if (likely(PyLong_CheckExact(op1))) { + int unequal; + unsigned long uintval; + Py_ssize_t size = __Pyx_PyLong_DigitCount(op1); + const digit* digits = __Pyx_PyLong_Digits(op1); + if (intval == 0) { + return (__Pyx_PyLong_IsZero(op1) != 1); + } else if (intval < 0) { + if (__Pyx_PyLong_IsNonNeg(op1)) + return 1; + intval = -intval; + } else { + if (__Pyx_PyLong_IsNeg(op1)) + return 1; + } + uintval = (unsigned long) intval; +#if PyLong_SHIFT * 4 < SIZEOF_LONG*8 + if (uintval >> (PyLong_SHIFT * 4)) { + unequal = (size != 5) || (digits[0] != (uintval & (unsigned long) PyLong_MASK)) + | (digits[1] != ((uintval >> (1 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[2] != ((uintval >> (2 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[3] != ((uintval >> (3 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[4] != ((uintval >> (4 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)); + } else +#endif +#if PyLong_SHIFT * 3 < SIZEOF_LONG*8 + if (uintval >> (PyLong_SHIFT * 3)) { + unequal = (size != 4) || (digits[0] != (uintval & (unsigned long) PyLong_MASK)) + | (digits[1] != ((uintval >> (1 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[2] != ((uintval >> (2 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[3] != ((uintval >> (3 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)); + } else +#endif +#if PyLong_SHIFT * 2 < SIZEOF_LONG*8 + if (uintval >> (PyLong_SHIFT * 2)) { + unequal = (size != 3) || (digits[0] != (uintval & (unsigned long) PyLong_MASK)) + | (digits[1] != ((uintval >> (1 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[2] != ((uintval >> (2 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)); + } else +#endif +#if PyLong_SHIFT * 1 < SIZEOF_LONG*8 + if (uintval >> (PyLong_SHIFT * 1)) { + unequal = (size != 2) || (digits[0] != (uintval & (unsigned long) PyLong_MASK)) + | (digits[1] != ((uintval >> (1 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)); + } else +#endif + unequal = (size != 1) || (((unsigned long) digits[0]) != (uintval & (unsigned long) PyLong_MASK)); + return (unequal != 0); + } + #endif + if (PyFloat_CheckExact(op1)) { + const long b = intval; +#if CYTHON_COMPILING_IN_LIMITED_API + double a = __pyx_PyFloat_AsDouble(op1); +#else + double a = PyFloat_AS_DOUBLE(op1); +#endif + return ((double)a != (double)b); + } + return __Pyx_PyObject_IsTrueAndDecref( + PyObject_RichCompare(op1, op2, Py_NE)); +} + +/* IsLittleEndian */ +static CYTHON_INLINE int __Pyx_Is_Little_Endian(void) +{ + union { + uint32_t u32; + uint8_t u8[4]; + } S; + S.u32 = 0x01020304; + return S.u8[0] == 4; +} + +/* BufferFormatCheck */ +static void __Pyx_BufFmt_Init(__Pyx_BufFmt_Context* ctx, + __Pyx_BufFmt_StackElem* stack, + __Pyx_TypeInfo* type) { + stack[0].field = &ctx->root; + stack[0].parent_offset = 0; + ctx->root.type = type; + ctx->root.name = "buffer dtype"; + ctx->root.offset = 0; + ctx->head = stack; + ctx->head->field = &ctx->root; + ctx->fmt_offset = 0; + ctx->head->parent_offset = 0; + ctx->new_packmode = '@'; + ctx->enc_packmode = '@'; + ctx->new_count = 1; + ctx->enc_count = 0; + ctx->enc_type = 0; + ctx->is_complex = 0; + ctx->is_valid_array = 0; + ctx->struct_alignment = 0; + while (type->typegroup == 'S') { + ++ctx->head; + ctx->head->field = type->fields; + ctx->head->parent_offset = 0; + type = type->fields->type; + } +} +static int __Pyx_BufFmt_ParseNumber(const char** ts) { + int count; + const char* t = *ts; + if (*t < '0' || *t > '9') { + return -1; + } else { + count = *t++ - '0'; + while (*t >= '0' && *t <= '9') { + count *= 10; + count += *t++ - '0'; + } + } + *ts = t; + return count; +} +static int __Pyx_BufFmt_ExpectNumber(const char **ts) { + int number = __Pyx_BufFmt_ParseNumber(ts); + if (number == -1) + PyErr_Format(PyExc_ValueError,\ + "Does not understand character buffer dtype format string ('%c')", **ts); + return number; +} +static void __Pyx_BufFmt_RaiseUnexpectedChar(char ch) { + PyErr_Format(PyExc_ValueError, + "Unexpected format string character: '%c'", ch); +} +static const char* __Pyx_BufFmt_DescribeTypeChar(char ch, int is_complex) { + switch (ch) { + case '?': return "'bool'"; + case 'c': return "'char'"; + case 'b': return "'signed char'"; + case 'B': return "'unsigned char'"; + case 'h': return "'short'"; + case 'H': return "'unsigned short'"; + case 'i': return "'int'"; + case 'I': return "'unsigned int'"; + case 'l': return "'long'"; + case 'L': return "'unsigned long'"; + case 'q': return "'long long'"; + case 'Q': return "'unsigned long long'"; + case 'f': return (is_complex ? "'complex float'" : "'float'"); + case 'd': return (is_complex ? "'complex double'" : "'double'"); + case 'g': return (is_complex ? "'complex long double'" : "'long double'"); + case 'T': return "a struct"; + case 'O': return "Python object"; + case 'P': return "a pointer"; + case 's': case 'p': return "a string"; + case 0: return "end"; + default: return "unparsable format string"; + } +} +static size_t __Pyx_BufFmt_TypeCharToStandardSize(char ch, int is_complex) { + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return 2; + case 'i': case 'I': case 'l': case 'L': return 4; + case 'q': case 'Q': return 8; + case 'f': return (is_complex ? 8 : 4); + case 'd': return (is_complex ? 16 : 8); + case 'g': { + PyErr_SetString(PyExc_ValueError, "Python does not define a standard format string size for long double ('g').."); + return 0; + } + case 'O': case 'P': return sizeof(void*); + default: + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } +} +static size_t __Pyx_BufFmt_TypeCharToNativeSize(char ch, int is_complex) { + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return sizeof(short); + case 'i': case 'I': return sizeof(int); + case 'l': case 'L': return sizeof(long); + #ifdef HAVE_LONG_LONG + case 'q': case 'Q': return sizeof(PY_LONG_LONG); + #endif + case 'f': return sizeof(float) * (is_complex ? 2 : 1); + case 'd': return sizeof(double) * (is_complex ? 2 : 1); + case 'g': return sizeof(long double) * (is_complex ? 2 : 1); + case 'O': case 'P': return sizeof(void*); + default: { + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } + } +} +typedef struct { char c; short x; } __Pyx_st_short; +typedef struct { char c; int x; } __Pyx_st_int; +typedef struct { char c; long x; } __Pyx_st_long; +typedef struct { char c; float x; } __Pyx_st_float; +typedef struct { char c; double x; } __Pyx_st_double; +typedef struct { char c; long double x; } __Pyx_st_longdouble; +typedef struct { char c; void *x; } __Pyx_st_void_p; +#ifdef HAVE_LONG_LONG +typedef struct { char c; PY_LONG_LONG x; } __Pyx_st_longlong; +#endif +static size_t __Pyx_BufFmt_TypeCharToAlignment(char ch, int is_complex) { + CYTHON_UNUSED_VAR(is_complex); + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return sizeof(__Pyx_st_short) - sizeof(short); + case 'i': case 'I': return sizeof(__Pyx_st_int) - sizeof(int); + case 'l': case 'L': return sizeof(__Pyx_st_long) - sizeof(long); +#ifdef HAVE_LONG_LONG + case 'q': case 'Q': return sizeof(__Pyx_st_longlong) - sizeof(PY_LONG_LONG); +#endif + case 'f': return sizeof(__Pyx_st_float) - sizeof(float); + case 'd': return sizeof(__Pyx_st_double) - sizeof(double); + case 'g': return sizeof(__Pyx_st_longdouble) - sizeof(long double); + case 'P': case 'O': return sizeof(__Pyx_st_void_p) - sizeof(void*); + default: + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } +} +/* These are for computing the padding at the end of the struct to align + on the first member of the struct. This will probably the same as above, + but we don't have any guarantees. + */ +typedef struct { short x; char c; } __Pyx_pad_short; +typedef struct { int x; char c; } __Pyx_pad_int; +typedef struct { long x; char c; } __Pyx_pad_long; +typedef struct { float x; char c; } __Pyx_pad_float; +typedef struct { double x; char c; } __Pyx_pad_double; +typedef struct { long double x; char c; } __Pyx_pad_longdouble; +typedef struct { void *x; char c; } __Pyx_pad_void_p; +#ifdef HAVE_LONG_LONG +typedef struct { PY_LONG_LONG x; char c; } __Pyx_pad_longlong; +#endif +static size_t __Pyx_BufFmt_TypeCharToPadding(char ch, int is_complex) { + CYTHON_UNUSED_VAR(is_complex); + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return sizeof(__Pyx_pad_short) - sizeof(short); + case 'i': case 'I': return sizeof(__Pyx_pad_int) - sizeof(int); + case 'l': case 'L': return sizeof(__Pyx_pad_long) - sizeof(long); +#ifdef HAVE_LONG_LONG + case 'q': case 'Q': return sizeof(__Pyx_pad_longlong) - sizeof(PY_LONG_LONG); +#endif + case 'f': return sizeof(__Pyx_pad_float) - sizeof(float); + case 'd': return sizeof(__Pyx_pad_double) - sizeof(double); + case 'g': return sizeof(__Pyx_pad_longdouble) - sizeof(long double); + case 'P': case 'O': return sizeof(__Pyx_pad_void_p) - sizeof(void*); + default: + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } +} +static char __Pyx_BufFmt_TypeCharToGroup(char ch, int is_complex) { + switch (ch) { + case 'c': + return 'H'; + case 'b': case 'h': case 'i': + case 'l': case 'q': case 's': case 'p': + return 'I'; + case '?': case 'B': case 'H': case 'I': case 'L': case 'Q': + return 'U'; + case 'f': case 'd': case 'g': + return (is_complex ? 'C' : 'R'); + case 'O': + return 'O'; + case 'P': + return 'P'; + default: { + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } + } +} +static void __Pyx_BufFmt_RaiseExpected(__Pyx_BufFmt_Context* ctx) { + if (ctx->head == NULL || ctx->head->field == &ctx->root) { + const char* expected; + const char* quote; + if (ctx->head == NULL) { + expected = "end"; + quote = ""; + } else { + expected = ctx->head->field->type->name; + quote = "'"; + } + PyErr_Format(PyExc_ValueError, + "Buffer dtype mismatch, expected %s%s%s but got %s", + quote, expected, quote, + __Pyx_BufFmt_DescribeTypeChar(ctx->enc_type, ctx->is_complex)); + } else { + __Pyx_StructField* field = ctx->head->field; + __Pyx_StructField* parent = (ctx->head - 1)->field; + PyErr_Format(PyExc_ValueError, + "Buffer dtype mismatch, expected '%s' but got %s in '%s.%s'", + field->type->name, __Pyx_BufFmt_DescribeTypeChar(ctx->enc_type, ctx->is_complex), + parent->type->name, field->name); + } +} +static int __Pyx_BufFmt_ProcessTypeChunk(__Pyx_BufFmt_Context* ctx) { + char group; + size_t size, offset, arraysize = 1; + if (ctx->enc_type == 0) return 0; + if (ctx->head->field->type->arraysize[0]) { + int i, ndim = 0; + if (ctx->enc_type == 's' || ctx->enc_type == 'p') { + ctx->is_valid_array = ctx->head->field->type->ndim == 1; + ndim = 1; + if (ctx->enc_count != ctx->head->field->type->arraysize[0]) { + PyErr_Format(PyExc_ValueError, + "Expected a dimension of size %zu, got %zu", + ctx->head->field->type->arraysize[0], ctx->enc_count); + return -1; + } + } + if (!ctx->is_valid_array) { + PyErr_Format(PyExc_ValueError, "Expected %d dimensions, got %d", + ctx->head->field->type->ndim, ndim); + return -1; + } + for (i = 0; i < ctx->head->field->type->ndim; i++) { + arraysize *= ctx->head->field->type->arraysize[i]; + } + ctx->is_valid_array = 0; + ctx->enc_count = 1; + } + group = __Pyx_BufFmt_TypeCharToGroup(ctx->enc_type, ctx->is_complex); + do { + __Pyx_StructField* field = ctx->head->field; + __Pyx_TypeInfo* type = field->type; + if (ctx->enc_packmode == '@' || ctx->enc_packmode == '^') { + size = __Pyx_BufFmt_TypeCharToNativeSize(ctx->enc_type, ctx->is_complex); + } else { + size = __Pyx_BufFmt_TypeCharToStandardSize(ctx->enc_type, ctx->is_complex); + } + if (ctx->enc_packmode == '@') { + size_t align_at = __Pyx_BufFmt_TypeCharToAlignment(ctx->enc_type, ctx->is_complex); + size_t align_mod_offset; + if (align_at == 0) return -1; + align_mod_offset = ctx->fmt_offset % align_at; + if (align_mod_offset > 0) ctx->fmt_offset += align_at - align_mod_offset; + if (ctx->struct_alignment == 0) + ctx->struct_alignment = __Pyx_BufFmt_TypeCharToPadding(ctx->enc_type, + ctx->is_complex); + } + if (type->size != size || type->typegroup != group) { + if (type->typegroup == 'C' && type->fields != NULL) { + size_t parent_offset = ctx->head->parent_offset + field->offset; + ++ctx->head; + ctx->head->field = type->fields; + ctx->head->parent_offset = parent_offset; + continue; + } + if ((type->typegroup == 'H' || group == 'H') && type->size == size) { + } else { + __Pyx_BufFmt_RaiseExpected(ctx); + return -1; + } + } + offset = ctx->head->parent_offset + field->offset; + if (ctx->fmt_offset != offset) { + PyErr_Format(PyExc_ValueError, + "Buffer dtype mismatch; next field is at offset %" CYTHON_FORMAT_SSIZE_T "d but %" CYTHON_FORMAT_SSIZE_T "d expected", + (Py_ssize_t)ctx->fmt_offset, (Py_ssize_t)offset); + return -1; + } + ctx->fmt_offset += size; + if (arraysize) + ctx->fmt_offset += (arraysize - 1) * size; + --ctx->enc_count; + while (1) { + if (field == &ctx->root) { + ctx->head = NULL; + if (ctx->enc_count != 0) { + __Pyx_BufFmt_RaiseExpected(ctx); + return -1; + } + break; + } + ctx->head->field = ++field; + if (field->type == NULL) { + --ctx->head; + field = ctx->head->field; + continue; + } else if (field->type->typegroup == 'S') { + size_t parent_offset = ctx->head->parent_offset + field->offset; + if (field->type->fields->type == NULL) continue; + field = field->type->fields; + ++ctx->head; + ctx->head->field = field; + ctx->head->parent_offset = parent_offset; + break; + } else { + break; + } + } + } while (ctx->enc_count); + ctx->enc_type = 0; + ctx->is_complex = 0; + return 0; +} +static int +__pyx_buffmt_parse_array(__Pyx_BufFmt_Context* ctx, const char** tsp) +{ + const char *ts = *tsp; + int i = 0, number, ndim; + ++ts; + if (ctx->new_count != 1) { + PyErr_SetString(PyExc_ValueError, + "Cannot handle repeated arrays in format string"); + return -1; + } + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return -1; + ndim = ctx->head->field->type->ndim; + while (*ts && *ts != ')') { + switch (*ts) { + case ' ': case '\f': case '\r': case '\n': case '\t': case '\v': continue; + default: break; + } + number = __Pyx_BufFmt_ExpectNumber(&ts); + if (number == -1) return -1; + if (i < ndim && (size_t) number != ctx->head->field->type->arraysize[i]) { + PyErr_Format(PyExc_ValueError, + "Expected a dimension of size %zu, got %d", + ctx->head->field->type->arraysize[i], number); + return -1; + } + if (*ts != ',' && *ts != ')') { + PyErr_Format(PyExc_ValueError, + "Expected a comma in format string, got '%c'", *ts); + return -1; + } + if (*ts == ',') ts++; + i++; + } + if (i != ndim) { + PyErr_Format(PyExc_ValueError, "Expected %d dimension(s), got %d", + ctx->head->field->type->ndim, i); + return -1; + } + if (!*ts) { + PyErr_SetString(PyExc_ValueError, + "Unexpected end of format string, expected ')'"); + return -1; + } + ctx->is_valid_array = 1; + ctx->new_count = 1; + *tsp = ++ts; + return 0; +} +static const char* __Pyx_BufFmt_CheckString(__Pyx_BufFmt_Context* ctx, const char* ts) { + int got_Z = 0; + while (1) { + switch(*ts) { + case 0: + if (ctx->enc_type != 0 && ctx->head == NULL) { + __Pyx_BufFmt_RaiseExpected(ctx); + return NULL; + } + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + if (ctx->head != NULL) { + __Pyx_BufFmt_RaiseExpected(ctx); + return NULL; + } + return ts; + case ' ': + case '\r': + case '\n': + ++ts; + break; + case '<': + if (!__Pyx_Is_Little_Endian()) { + PyErr_SetString(PyExc_ValueError, "Little-endian buffer not supported on big-endian compiler"); + return NULL; + } + ctx->new_packmode = '='; + ++ts; + break; + case '>': + case '!': + if (__Pyx_Is_Little_Endian()) { + PyErr_SetString(PyExc_ValueError, "Big-endian buffer not supported on little-endian compiler"); + return NULL; + } + ctx->new_packmode = '='; + ++ts; + break; + case '=': + case '@': + case '^': + ctx->new_packmode = *ts++; + break; + case 'T': + { + const char* ts_after_sub; + size_t i, struct_count = ctx->new_count; + size_t struct_alignment = ctx->struct_alignment; + ctx->new_count = 1; + ++ts; + if (*ts != '{') { + PyErr_SetString(PyExc_ValueError, "Buffer acquisition: Expected '{' after 'T'"); + return NULL; + } + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->enc_type = 0; + ctx->enc_count = 0; + ctx->struct_alignment = 0; + ++ts; + ts_after_sub = ts; + for (i = 0; i != struct_count; ++i) { + ts_after_sub = __Pyx_BufFmt_CheckString(ctx, ts); + if (!ts_after_sub) return NULL; + } + ts = ts_after_sub; + if (struct_alignment) ctx->struct_alignment = struct_alignment; + } + break; + case '}': + { + size_t alignment = ctx->struct_alignment; + ++ts; + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->enc_type = 0; + if (alignment && ctx->fmt_offset % alignment) { + ctx->fmt_offset += alignment - (ctx->fmt_offset % alignment); + } + } + return ts; + case 'x': + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->fmt_offset += ctx->new_count; + ctx->new_count = 1; + ctx->enc_count = 0; + ctx->enc_type = 0; + ctx->enc_packmode = ctx->new_packmode; + ++ts; + break; + case 'Z': + got_Z = 1; + ++ts; + if (*ts != 'f' && *ts != 'd' && *ts != 'g') { + __Pyx_BufFmt_RaiseUnexpectedChar('Z'); + return NULL; + } + CYTHON_FALLTHROUGH; + case '?': case 'c': case 'b': case 'B': case 'h': case 'H': case 'i': case 'I': + case 'l': case 'L': case 'q': case 'Q': + case 'f': case 'd': case 'g': + case 'O': case 'p': + if ((ctx->enc_type == *ts) && (got_Z == ctx->is_complex) && + (ctx->enc_packmode == ctx->new_packmode) && (!ctx->is_valid_array)) { + ctx->enc_count += ctx->new_count; + ctx->new_count = 1; + got_Z = 0; + ++ts; + break; + } + CYTHON_FALLTHROUGH; + case 's': + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->enc_count = ctx->new_count; + ctx->enc_packmode = ctx->new_packmode; + ctx->enc_type = *ts; + ctx->is_complex = got_Z; + ++ts; + ctx->new_count = 1; + got_Z = 0; + break; + case ':': + ++ts; + while(*ts != ':') ++ts; + ++ts; + break; + case '(': + if (__pyx_buffmt_parse_array(ctx, &ts) < 0) return NULL; + break; + default: + { + int number = __Pyx_BufFmt_ExpectNumber(&ts); + if (number == -1) return NULL; + ctx->new_count = (size_t)number; + } + } + } +} + +/* BufferGetAndValidate */ + static CYTHON_INLINE void __Pyx_SafeReleaseBuffer(Py_buffer* info) { + if (unlikely(info->buf == NULL)) return; + if (info->suboffsets == __Pyx_minusones) info->suboffsets = NULL; + __Pyx_ReleaseBuffer(info); +} +static void __Pyx_ZeroBuffer(Py_buffer* buf) { + buf->buf = NULL; + buf->obj = NULL; + buf->strides = __Pyx_zeros; + buf->shape = __Pyx_zeros; + buf->suboffsets = __Pyx_minusones; +} +static int __Pyx__GetBufferAndValidate( + Py_buffer* buf, PyObject* obj, __Pyx_TypeInfo* dtype, int flags, + int nd, int cast, __Pyx_BufFmt_StackElem* stack) +{ + buf->buf = NULL; + if (unlikely(__Pyx_GetBuffer(obj, buf, flags) == -1)) { + __Pyx_ZeroBuffer(buf); + return -1; + } + if (unlikely(buf->ndim != nd)) { + PyErr_Format(PyExc_ValueError, + "Buffer has wrong number of dimensions (expected %d, got %d)", + nd, buf->ndim); + goto fail; + } + if (!cast) { + __Pyx_BufFmt_Context ctx; + __Pyx_BufFmt_Init(&ctx, stack, dtype); + if (!__Pyx_BufFmt_CheckString(&ctx, buf->format)) goto fail; + } + if (unlikely((size_t)buf->itemsize != dtype->size)) { + PyErr_Format(PyExc_ValueError, + "Item size of buffer (%" CYTHON_FORMAT_SSIZE_T "d byte%s) does not match size of '%s' (%" CYTHON_FORMAT_SSIZE_T "d byte%s)", + buf->itemsize, (buf->itemsize > 1) ? "s" : "", + dtype->name, (Py_ssize_t)dtype->size, (dtype->size > 1) ? "s" : ""); + goto fail; + } + if (buf->suboffsets == NULL) buf->suboffsets = __Pyx_minusones; + return 0; +fail:; + __Pyx_SafeReleaseBuffer(buf); + return -1; +} + +/* UnicodeConcatInPlace */ + # if CYTHON_COMPILING_IN_CPYTHON && PY_MAJOR_VERSION >= 3 +static int +__Pyx_unicode_modifiable(PyObject *unicode) +{ + if (Py_REFCNT(unicode) != 1) + return 0; + if (!PyUnicode_CheckExact(unicode)) + return 0; + if (PyUnicode_CHECK_INTERNED(unicode)) + return 0; + return 1; +} +static CYTHON_INLINE PyObject *__Pyx_PyUnicode_ConcatInPlaceImpl(PyObject **p_left, PyObject *right + #if CYTHON_REFNANNY + , void* __pyx_refnanny + #endif + ) { + PyObject *left = *p_left; + Py_ssize_t left_len, right_len, new_len; + if (unlikely(__Pyx_PyUnicode_READY(left) == -1)) + return NULL; + if (unlikely(__Pyx_PyUnicode_READY(right) == -1)) + return NULL; + left_len = PyUnicode_GET_LENGTH(left); + if (left_len == 0) { + Py_INCREF(right); + return right; + } + right_len = PyUnicode_GET_LENGTH(right); + if (right_len == 0) { + Py_INCREF(left); + return left; + } + if (unlikely(left_len > PY_SSIZE_T_MAX - right_len)) { + PyErr_SetString(PyExc_OverflowError, + "strings are too large to concat"); + return NULL; + } + new_len = left_len + right_len; + if (__Pyx_unicode_modifiable(left) + && PyUnicode_CheckExact(right) + && PyUnicode_KIND(right) <= PyUnicode_KIND(left) + && !(PyUnicode_IS_ASCII(left) && !PyUnicode_IS_ASCII(right))) { + int ret; + __Pyx_GIVEREF(*p_left); + ret = PyUnicode_Resize(p_left, new_len); + __Pyx_GOTREF(*p_left); + if (unlikely(ret != 0)) + return NULL; + #if PY_VERSION_HEX >= 0x030d0000 + if (unlikely(PyUnicode_CopyCharacters(*p_left, left_len, right, 0, right_len) < 0)) return NULL; + #else + _PyUnicode_FastCopyCharacters(*p_left, left_len, right, 0, right_len); + #endif + __Pyx_INCREF(*p_left); + __Pyx_GIVEREF(*p_left); + return *p_left; + } else { + return __Pyx_PyUnicode_Concat(left, right); + } + } +#endif + +/* SliceObject */ + static CYTHON_INLINE PyObject* __Pyx_PyObject_GetSlice(PyObject* obj, + Py_ssize_t cstart, Py_ssize_t cstop, + PyObject** _py_start, PyObject** _py_stop, PyObject** _py_slice, + int has_cstart, int has_cstop, int wraparound) { + __Pyx_TypeName obj_type_name; +#if CYTHON_USE_TYPE_SLOTS + PyMappingMethods* mp; +#if PY_MAJOR_VERSION < 3 + PySequenceMethods* ms = Py_TYPE(obj)->tp_as_sequence; + if (likely(ms && ms->sq_slice)) { + if (!has_cstart) { + if (_py_start && (*_py_start != Py_None)) { + cstart = __Pyx_PyIndex_AsSsize_t(*_py_start); + if ((cstart == (Py_ssize_t)-1) && PyErr_Occurred()) goto bad; + } else + cstart = 0; + } + if (!has_cstop) { + if (_py_stop && (*_py_stop != Py_None)) { + cstop = __Pyx_PyIndex_AsSsize_t(*_py_stop); + if ((cstop == (Py_ssize_t)-1) && PyErr_Occurred()) goto bad; + } else + cstop = PY_SSIZE_T_MAX; + } + if (wraparound && unlikely((cstart < 0) | (cstop < 0)) && likely(ms->sq_length)) { + Py_ssize_t l = ms->sq_length(obj); + if (likely(l >= 0)) { + if (cstop < 0) { + cstop += l; + if (cstop < 0) cstop = 0; + } + if (cstart < 0) { + cstart += l; + if (cstart < 0) cstart = 0; + } + } else { + if (!PyErr_ExceptionMatches(PyExc_OverflowError)) + goto bad; + PyErr_Clear(); + } + } + return ms->sq_slice(obj, cstart, cstop); + } +#else + CYTHON_UNUSED_VAR(wraparound); +#endif + mp = Py_TYPE(obj)->tp_as_mapping; + if (likely(mp && mp->mp_subscript)) +#else + CYTHON_UNUSED_VAR(wraparound); +#endif + { + PyObject* result; + PyObject *py_slice, *py_start, *py_stop; + if (_py_slice) { + py_slice = *_py_slice; + } else { + PyObject* owned_start = NULL; + PyObject* owned_stop = NULL; + if (_py_start) { + py_start = *_py_start; + } else { + if (has_cstart) { + owned_start = py_start = PyInt_FromSsize_t(cstart); + if (unlikely(!py_start)) goto bad; + } else + py_start = Py_None; + } + if (_py_stop) { + py_stop = *_py_stop; + } else { + if (has_cstop) { + owned_stop = py_stop = PyInt_FromSsize_t(cstop); + if (unlikely(!py_stop)) { + Py_XDECREF(owned_start); + goto bad; + } + } else + py_stop = Py_None; + } + py_slice = PySlice_New(py_start, py_stop, Py_None); + Py_XDECREF(owned_start); + Py_XDECREF(owned_stop); + if (unlikely(!py_slice)) goto bad; + } +#if CYTHON_USE_TYPE_SLOTS + result = mp->mp_subscript(obj, py_slice); +#else + result = PyObject_GetItem(obj, py_slice); +#endif + if (!_py_slice) { + Py_DECREF(py_slice); + } + return result; + } + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "'" __Pyx_FMT_TYPENAME "' object is unsliceable", obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); +bad: + return NULL; +} + +/* PyObjectFormat */ + #if CYTHON_USE_UNICODE_WRITER +static PyObject* __Pyx_PyObject_Format(PyObject* obj, PyObject* format_spec) { + int ret; + _PyUnicodeWriter writer; + if (likely(PyFloat_CheckExact(obj))) { +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x03040000 + _PyUnicodeWriter_Init(&writer, 0); +#else + _PyUnicodeWriter_Init(&writer); +#endif + ret = _PyFloat_FormatAdvancedWriter( + &writer, + obj, + format_spec, 0, PyUnicode_GET_LENGTH(format_spec)); + } else if (likely(PyLong_CheckExact(obj))) { +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x03040000 + _PyUnicodeWriter_Init(&writer, 0); +#else + _PyUnicodeWriter_Init(&writer); +#endif + ret = _PyLong_FormatAdvancedWriter( + &writer, + obj, + format_spec, 0, PyUnicode_GET_LENGTH(format_spec)); + } else { + return PyObject_Format(obj, format_spec); + } + if (unlikely(ret == -1)) { + _PyUnicodeWriter_Dealloc(&writer); + return NULL; + } + return _PyUnicodeWriter_Finish(&writer); +} +#endif + +/* UnpackUnboundCMethod */ + static PyObject *__Pyx_SelflessCall(PyObject *method, PyObject *args, PyObject *kwargs) { + PyObject *result; + PyObject *selfless_args = PyTuple_GetSlice(args, 1, PyTuple_Size(args)); + if (unlikely(!selfless_args)) return NULL; + result = PyObject_Call(method, selfless_args, kwargs); + Py_DECREF(selfless_args); + return result; +} +static PyMethodDef __Pyx_UnboundCMethod_Def = { + "CythonUnboundCMethod", + __PYX_REINTERPRET_FUNCION(PyCFunction, __Pyx_SelflessCall), + METH_VARARGS | METH_KEYWORDS, + NULL +}; +static int __Pyx_TryUnpackUnboundCMethod(__Pyx_CachedCFunction* target) { + PyObject *method; + method = __Pyx_PyObject_GetAttrStr(target->type, *target->method_name); + if (unlikely(!method)) + return -1; + target->method = method; +#if CYTHON_COMPILING_IN_CPYTHON + #if PY_MAJOR_VERSION >= 3 + if (likely(__Pyx_TypeCheck(method, &PyMethodDescr_Type))) + #else + if (likely(!__Pyx_CyOrPyCFunction_Check(method))) + #endif + { + PyMethodDescrObject *descr = (PyMethodDescrObject*) method; + target->func = descr->d_method->ml_meth; + target->flag = descr->d_method->ml_flags & ~(METH_CLASS | METH_STATIC | METH_COEXIST | METH_STACKLESS); + } else +#endif +#if CYTHON_COMPILING_IN_PYPY +#else + if (PyCFunction_Check(method)) +#endif + { + PyObject *self; + int self_found; +#if CYTHON_COMPILING_IN_LIMITED_API || CYTHON_COMPILING_IN_PYPY + self = PyObject_GetAttrString(method, "__self__"); + if (!self) { + PyErr_Clear(); + } +#else + self = PyCFunction_GET_SELF(method); +#endif + self_found = (self && self != Py_None); +#if CYTHON_COMPILING_IN_LIMITED_API || CYTHON_COMPILING_IN_PYPY + Py_XDECREF(self); +#endif + if (self_found) { + PyObject *unbound_method = PyCFunction_New(&__Pyx_UnboundCMethod_Def, method); + if (unlikely(!unbound_method)) return -1; + Py_DECREF(method); + target->method = unbound_method; + } + } + return 0; +} + +/* CallUnboundCMethod0 */ + static PyObject* __Pyx__CallUnboundCMethod0(__Pyx_CachedCFunction* cfunc, PyObject* self) { + PyObject *args, *result = NULL; + if (unlikely(!cfunc->method) && unlikely(__Pyx_TryUnpackUnboundCMethod(cfunc) < 0)) return NULL; +#if CYTHON_ASSUME_SAFE_MACROS + args = PyTuple_New(1); + if (unlikely(!args)) goto bad; + Py_INCREF(self); + PyTuple_SET_ITEM(args, 0, self); +#else + args = PyTuple_Pack(1, self); + if (unlikely(!args)) goto bad; +#endif + result = __Pyx_PyObject_Call(cfunc->method, args, NULL); + Py_DECREF(args); +bad: + return result; +} + +/* py_dict_keys */ + static CYTHON_INLINE PyObject* __Pyx_PyDict_Keys(PyObject* d) { + if (PY_MAJOR_VERSION >= 3) + return __Pyx_CallUnboundCMethod0(&__pyx_umethod_PyDict_Type_keys, d); + else + return PyDict_Keys(d); +} + +/* DictGetItem */ + #if PY_MAJOR_VERSION >= 3 && !CYTHON_COMPILING_IN_PYPY +static PyObject *__Pyx_PyDict_GetItem(PyObject *d, PyObject* key) { + PyObject *value; + value = PyDict_GetItemWithError(d, key); + if (unlikely(!value)) { + if (!PyErr_Occurred()) { + if (unlikely(PyTuple_Check(key))) { + PyObject* args = PyTuple_Pack(1, key); + if (likely(args)) { + PyErr_SetObject(PyExc_KeyError, args); + Py_DECREF(args); + } + } else { + PyErr_SetObject(PyExc_KeyError, key); + } + } + return NULL; + } + Py_INCREF(value); + return value; +} +#endif + +/* PyObjectLookupSpecial */ + #if CYTHON_USE_PYTYPE_LOOKUP && CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx__PyObject_LookupSpecial(PyObject* obj, PyObject* attr_name, int with_error) { + PyObject *res; + PyTypeObject *tp = Py_TYPE(obj); +#if PY_MAJOR_VERSION < 3 + if (unlikely(PyInstance_Check(obj))) + return with_error ? __Pyx_PyObject_GetAttrStr(obj, attr_name) : __Pyx_PyObject_GetAttrStrNoError(obj, attr_name); +#endif + res = _PyType_Lookup(tp, attr_name); + if (likely(res)) { + descrgetfunc f = Py_TYPE(res)->tp_descr_get; + if (!f) { + Py_INCREF(res); + } else { + res = f(res, obj, (PyObject *)tp); + } + } else if (with_error) { + PyErr_SetObject(PyExc_AttributeError, attr_name); + } + return res; +} +#endif + +/* FixUpExtensionType */ + #if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type) { +#if PY_VERSION_HEX > 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + CYTHON_UNUSED_VAR(spec); + CYTHON_UNUSED_VAR(type); +#else + const PyType_Slot *slot = spec->slots; + while (slot && slot->slot && slot->slot != Py_tp_members) + slot++; + if (slot && slot->slot == Py_tp_members) { + int changed = 0; +#if !(PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON) + const +#endif + PyMemberDef *memb = (PyMemberDef*) slot->pfunc; + while (memb && memb->name) { + if (memb->name[0] == '_' && memb->name[1] == '_') { +#if PY_VERSION_HEX < 0x030900b1 + if (strcmp(memb->name, "__weaklistoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_weaklistoffset = memb->offset; + changed = 1; + } + else if (strcmp(memb->name, "__dictoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_dictoffset = memb->offset; + changed = 1; + } +#if CYTHON_METH_FASTCALL + else if (strcmp(memb->name, "__vectorcalloffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); +#if PY_VERSION_HEX >= 0x030800b4 + type->tp_vectorcall_offset = memb->offset; +#else + type->tp_print = (printfunc) memb->offset; +#endif + changed = 1; + } +#endif +#else + if ((0)); +#endif +#if PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON + else if (strcmp(memb->name, "__module__") == 0) { + PyObject *descr; + assert(memb->type == T_OBJECT); + assert(memb->flags == 0 || memb->flags == READONLY); + descr = PyDescr_NewMember(type, memb); + if (unlikely(!descr)) + return -1; + if (unlikely(PyDict_SetItem(type->tp_dict, PyDescr_NAME(descr), descr) < 0)) { + Py_DECREF(descr); + return -1; + } + Py_DECREF(descr); + changed = 1; + } +#endif + } + memb++; + } + if (changed) + PyType_Modified(type); + } +#endif + return 0; +} +#endif + +/* FetchSharedCythonModule */ + static PyObject *__Pyx_FetchSharedCythonABIModule(void) { + return __Pyx_PyImport_AddModuleRef((char*) __PYX_ABI_MODULE_NAME); +} + +/* FetchCommonType */ + static int __Pyx_VerifyCachedType(PyObject *cached_type, + const char *name, + Py_ssize_t basicsize, + Py_ssize_t expected_basicsize) { + if (!PyType_Check(cached_type)) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s is not a type object", name); + return -1; + } + if (basicsize != expected_basicsize) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s has the wrong size, try recompiling", + name); + return -1; + } + return 0; +} +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type) { + PyObject* abi_module; + const char* object_name; + PyTypeObject *cached_type = NULL; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + object_name = strrchr(type->tp_name, '.'); + object_name = object_name ? object_name+1 : type->tp_name; + cached_type = (PyTypeObject*) PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + if (__Pyx_VerifyCachedType( + (PyObject *)cached_type, + object_name, + cached_type->tp_basicsize, + type->tp_basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + if (PyType_Ready(type) < 0) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, (PyObject *)type) < 0) + goto bad; + Py_INCREF(type); + cached_type = type; +done: + Py_DECREF(abi_module); + return cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#else +static PyTypeObject *__Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases) { + PyObject *abi_module, *cached_type = NULL; + const char* object_name = strrchr(spec->name, '.'); + object_name = object_name ? object_name+1 : spec->name; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + cached_type = PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + Py_ssize_t basicsize; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *py_basicsize; + py_basicsize = PyObject_GetAttrString(cached_type, "__basicsize__"); + if (unlikely(!py_basicsize)) goto bad; + basicsize = PyLong_AsSsize_t(py_basicsize); + Py_DECREF(py_basicsize); + py_basicsize = 0; + if (unlikely(basicsize == (Py_ssize_t)-1) && PyErr_Occurred()) goto bad; +#else + basicsize = likely(PyType_Check(cached_type)) ? ((PyTypeObject*) cached_type)->tp_basicsize : -1; +#endif + if (__Pyx_VerifyCachedType( + cached_type, + object_name, + basicsize, + spec->basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + CYTHON_UNUSED_VAR(module); + cached_type = __Pyx_PyType_FromModuleAndSpec(abi_module, spec, bases); + if (unlikely(!cached_type)) goto bad; + if (unlikely(__Pyx_fix_up_extension_type_from_spec(spec, (PyTypeObject *) cached_type) < 0)) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, cached_type) < 0) goto bad; +done: + Py_DECREF(abi_module); + assert(cached_type == NULL || PyType_Check(cached_type)); + return (PyTypeObject *) cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#endif + +/* PyVectorcallFastCallDict */ + #if CYTHON_METH_FASTCALL +static PyObject *__Pyx_PyVectorcall_FastCallDict_kw(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + PyObject *res = NULL; + PyObject *kwnames; + PyObject **newargs; + PyObject **kwvalues; + Py_ssize_t i, pos; + size_t j; + PyObject *key, *value; + unsigned long keys_are_strings; + Py_ssize_t nkw = PyDict_GET_SIZE(kw); + newargs = (PyObject **)PyMem_Malloc((nargs + (size_t)nkw) * sizeof(args[0])); + if (unlikely(newargs == NULL)) { + PyErr_NoMemory(); + return NULL; + } + for (j = 0; j < nargs; j++) newargs[j] = args[j]; + kwnames = PyTuple_New(nkw); + if (unlikely(kwnames == NULL)) { + PyMem_Free(newargs); + return NULL; + } + kwvalues = newargs + nargs; + pos = i = 0; + keys_are_strings = Py_TPFLAGS_UNICODE_SUBCLASS; + while (PyDict_Next(kw, &pos, &key, &value)) { + keys_are_strings &= Py_TYPE(key)->tp_flags; + Py_INCREF(key); + Py_INCREF(value); + PyTuple_SET_ITEM(kwnames, i, key); + kwvalues[i] = value; + i++; + } + if (unlikely(!keys_are_strings)) { + PyErr_SetString(PyExc_TypeError, "keywords must be strings"); + goto cleanup; + } + res = vc(func, newargs, nargs, kwnames); +cleanup: + Py_DECREF(kwnames); + for (i = 0; i < nkw; i++) + Py_DECREF(kwvalues[i]); + PyMem_Free(newargs); + return res; +} +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + if (likely(kw == NULL) || PyDict_GET_SIZE(kw) == 0) { + return vc(func, args, nargs, NULL); + } + return __Pyx_PyVectorcall_FastCallDict_kw(func, vc, args, nargs, kw); +} +#endif + +/* CythonFunctionShared */ + #if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc) { + if (__Pyx_CyFunction_Check(func)) { + return PyCFunction_GetFunction(((__pyx_CyFunctionObject*)func)->func) == (PyCFunction) cfunc; + } else if (PyCFunction_Check(func)) { + return PyCFunction_GetFunction(func) == (PyCFunction) cfunc; + } + return 0; +} +#else +static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc) { + return __Pyx_CyOrPyCFunction_Check(func) && __Pyx_CyOrPyCFunction_GET_FUNCTION(func) == (PyCFunction) cfunc; +} +#endif +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj) { +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + __Pyx_Py_XDECREF_SET( + __Pyx_CyFunction_GetClassObj(f), + ((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#else + __Pyx_Py_XDECREF_SET( + ((PyCMethodObject *) (f))->mm_class, + (PyTypeObject*)((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#endif +} +static PyObject * +__Pyx_CyFunction_get_doc(__pyx_CyFunctionObject *op, void *closure) +{ + CYTHON_UNUSED_VAR(closure); + if (unlikely(op->func_doc == NULL)) { +#if CYTHON_COMPILING_IN_LIMITED_API + op->func_doc = PyObject_GetAttrString(op->func, "__doc__"); + if (unlikely(!op->func_doc)) return NULL; +#else + if (((PyCFunctionObject*)op)->m_ml->ml_doc) { +#if PY_MAJOR_VERSION >= 3 + op->func_doc = PyUnicode_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#else + op->func_doc = PyString_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#endif + if (unlikely(op->func_doc == NULL)) + return NULL; + } else { + Py_INCREF(Py_None); + return Py_None; + } +#endif + } + Py_INCREF(op->func_doc); + return op->func_doc; +} +static int +__Pyx_CyFunction_set_doc(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (value == NULL) { + value = Py_None; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_doc, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_name(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_name == NULL)) { +#if CYTHON_COMPILING_IN_LIMITED_API + op->func_name = PyObject_GetAttrString(op->func, "__name__"); +#elif PY_MAJOR_VERSION >= 3 + op->func_name = PyUnicode_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#else + op->func_name = PyString_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#endif + if (unlikely(op->func_name == NULL)) + return NULL; + } + Py_INCREF(op->func_name); + return op->func_name; +} +static int +__Pyx_CyFunction_set_name(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__name__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_name, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_qualname(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_qualname); + return op->func_qualname; +} +static int +__Pyx_CyFunction_set_qualname(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__qualname__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_qualname, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_dict(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_dict == NULL)) { + op->func_dict = PyDict_New(); + if (unlikely(op->func_dict == NULL)) + return NULL; + } + Py_INCREF(op->func_dict); + return op->func_dict; +} +static int +__Pyx_CyFunction_set_dict(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(value == NULL)) { + PyErr_SetString(PyExc_TypeError, + "function's dictionary may not be deleted"); + return -1; + } + if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "setting function's dictionary to a non-dict"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_dict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_globals(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_globals); + return op->func_globals; +} +static PyObject * +__Pyx_CyFunction_get_closure(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(op); + CYTHON_UNUSED_VAR(context); + Py_INCREF(Py_None); + return Py_None; +} +static PyObject * +__Pyx_CyFunction_get_code(__pyx_CyFunctionObject *op, void *context) +{ + PyObject* result = (op->func_code) ? op->func_code : Py_None; + CYTHON_UNUSED_VAR(context); + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_init_defaults(__pyx_CyFunctionObject *op) { + int result = 0; + PyObject *res = op->defaults_getter((PyObject *) op); + if (unlikely(!res)) + return -1; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + op->defaults_tuple = PyTuple_GET_ITEM(res, 0); + Py_INCREF(op->defaults_tuple); + op->defaults_kwdict = PyTuple_GET_ITEM(res, 1); + Py_INCREF(op->defaults_kwdict); + #else + op->defaults_tuple = __Pyx_PySequence_ITEM(res, 0); + if (unlikely(!op->defaults_tuple)) result = -1; + else { + op->defaults_kwdict = __Pyx_PySequence_ITEM(res, 1); + if (unlikely(!op->defaults_kwdict)) result = -1; + } + #endif + Py_DECREF(res); + return result; +} +static int +__Pyx_CyFunction_set_defaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyTuple_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__defaults__ must be set to a tuple object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__defaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_tuple, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_defaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_tuple; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_tuple; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_kwdefaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__kwdefaults__ must be set to a dict object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__kwdefaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_kwdict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_kwdefaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_kwdict; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_kwdict; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_annotations(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value || value == Py_None) { + value = NULL; + } else if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__annotations__ must be set to a dict object"); + return -1; + } + Py_XINCREF(value); + __Pyx_Py_XDECREF_SET(op->func_annotations, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_annotations(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->func_annotations; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + result = PyDict_New(); + if (unlikely(!result)) return NULL; + op->func_annotations = result; + } + Py_INCREF(result); + return result; +} +static PyObject * +__Pyx_CyFunction_get_is_coroutine(__pyx_CyFunctionObject *op, void *context) { + int is_coroutine; + CYTHON_UNUSED_VAR(context); + if (op->func_is_coroutine) { + return __Pyx_NewRef(op->func_is_coroutine); + } + is_coroutine = op->flags & __Pyx_CYFUNCTION_COROUTINE; +#if PY_VERSION_HEX >= 0x03050000 + if (is_coroutine) { + PyObject *module, *fromlist, *marker = __pyx_n_s_is_coroutine; + fromlist = PyList_New(1); + if (unlikely(!fromlist)) return NULL; + Py_INCREF(marker); +#if CYTHON_ASSUME_SAFE_MACROS + PyList_SET_ITEM(fromlist, 0, marker); +#else + if (unlikely(PyList_SetItem(fromlist, 0, marker) < 0)) { + Py_DECREF(marker); + Py_DECREF(fromlist); + return NULL; + } +#endif + module = PyImport_ImportModuleLevelObject(__pyx_n_s_asyncio_coroutines, NULL, NULL, fromlist, 0); + Py_DECREF(fromlist); + if (unlikely(!module)) goto ignore; + op->func_is_coroutine = __Pyx_PyObject_GetAttrStr(module, marker); + Py_DECREF(module); + if (likely(op->func_is_coroutine)) { + return __Pyx_NewRef(op->func_is_coroutine); + } +ignore: + PyErr_Clear(); + } +#endif + op->func_is_coroutine = __Pyx_PyBool_FromLong(is_coroutine); + return __Pyx_NewRef(op->func_is_coroutine); +} +#if CYTHON_COMPILING_IN_LIMITED_API +static PyObject * +__Pyx_CyFunction_get_module(__pyx_CyFunctionObject *op, void *context) { + CYTHON_UNUSED_VAR(context); + return PyObject_GetAttrString(op->func, "__module__"); +} +static int +__Pyx_CyFunction_set_module(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + return PyObject_SetAttrString(op->func, "__module__", value); +} +#endif +static PyGetSetDef __pyx_CyFunction_getsets[] = { + {(char *) "func_doc", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "__doc__", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "func_name", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__name__", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__qualname__", (getter)__Pyx_CyFunction_get_qualname, (setter)__Pyx_CyFunction_set_qualname, 0, 0}, + {(char *) "func_dict", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "__dict__", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "func_globals", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "__globals__", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "func_closure", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "__closure__", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "func_code", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "__code__", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "func_defaults", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__defaults__", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__kwdefaults__", (getter)__Pyx_CyFunction_get_kwdefaults, (setter)__Pyx_CyFunction_set_kwdefaults, 0, 0}, + {(char *) "__annotations__", (getter)__Pyx_CyFunction_get_annotations, (setter)__Pyx_CyFunction_set_annotations, 0, 0}, + {(char *) "_is_coroutine", (getter)__Pyx_CyFunction_get_is_coroutine, 0, 0, 0}, +#if CYTHON_COMPILING_IN_LIMITED_API + {"__module__", (getter)__Pyx_CyFunction_get_module, (setter)__Pyx_CyFunction_set_module, 0, 0}, +#endif + {0, 0, 0, 0, 0} +}; +static PyMemberDef __pyx_CyFunction_members[] = { +#if !CYTHON_COMPILING_IN_LIMITED_API + {(char *) "__module__", T_OBJECT, offsetof(PyCFunctionObject, m_module), 0, 0}, +#endif +#if CYTHON_USE_TYPE_SPECS + {(char *) "__dictoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_dict), READONLY, 0}, +#if CYTHON_METH_FASTCALL +#if CYTHON_BACKPORT_VECTORCALL + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_vectorcall), READONLY, 0}, +#else +#if !CYTHON_COMPILING_IN_LIMITED_API + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(PyCFunctionObject, vectorcall), READONLY, 0}, +#endif +#endif +#endif +#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_weakreflist), READONLY, 0}, +#else + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(PyCFunctionObject, m_weakreflist), READONLY, 0}, +#endif +#endif + {0, 0, 0, 0, 0} +}; +static PyObject * +__Pyx_CyFunction_reduce(__pyx_CyFunctionObject *m, PyObject *args) +{ + CYTHON_UNUSED_VAR(args); +#if PY_MAJOR_VERSION >= 3 + Py_INCREF(m->func_qualname); + return m->func_qualname; +#else + return PyString_FromString(((PyCFunctionObject*)m)->m_ml->ml_name); +#endif +} +static PyMethodDef __pyx_CyFunction_methods[] = { + {"__reduce__", (PyCFunction)__Pyx_CyFunction_reduce, METH_VARARGS, 0}, + {0, 0, 0, 0} +}; +#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API +#define __Pyx_CyFunction_weakreflist(cyfunc) ((cyfunc)->func_weakreflist) +#else +#define __Pyx_CyFunction_weakreflist(cyfunc) (((PyCFunctionObject*)cyfunc)->m_weakreflist) +#endif +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject *op, PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { +#if !CYTHON_COMPILING_IN_LIMITED_API + PyCFunctionObject *cf = (PyCFunctionObject*) op; +#endif + if (unlikely(op == NULL)) + return NULL; +#if CYTHON_COMPILING_IN_LIMITED_API + op->func = PyCFunction_NewEx(ml, (PyObject*)op, module); + if (unlikely(!op->func)) return NULL; +#endif + op->flags = flags; + __Pyx_CyFunction_weakreflist(op) = NULL; +#if !CYTHON_COMPILING_IN_LIMITED_API + cf->m_ml = ml; + cf->m_self = (PyObject *) op; +#endif + Py_XINCREF(closure); + op->func_closure = closure; +#if !CYTHON_COMPILING_IN_LIMITED_API + Py_XINCREF(module); + cf->m_module = module; +#endif + op->func_dict = NULL; + op->func_name = NULL; + Py_INCREF(qualname); + op->func_qualname = qualname; + op->func_doc = NULL; +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + op->func_classobj = NULL; +#else + ((PyCMethodObject*)op)->mm_class = NULL; +#endif + op->func_globals = globals; + Py_INCREF(op->func_globals); + Py_XINCREF(code); + op->func_code = code; + op->defaults_pyobjects = 0; + op->defaults_size = 0; + op->defaults = NULL; + op->defaults_tuple = NULL; + op->defaults_kwdict = NULL; + op->defaults_getter = NULL; + op->func_annotations = NULL; + op->func_is_coroutine = NULL; +#if CYTHON_METH_FASTCALL + switch (ml->ml_flags & (METH_VARARGS | METH_FASTCALL | METH_NOARGS | METH_O | METH_KEYWORDS | METH_METHOD)) { + case METH_NOARGS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_NOARGS; + break; + case METH_O: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_O; + break; + case METH_METHOD | METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD; + break; + case METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS; + break; + case METH_VARARGS | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = NULL; + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + Py_DECREF(op); + return NULL; + } +#endif + return (PyObject *) op; +} +static int +__Pyx_CyFunction_clear(__pyx_CyFunctionObject *m) +{ + Py_CLEAR(m->func_closure); +#if CYTHON_COMPILING_IN_LIMITED_API + Py_CLEAR(m->func); +#else + Py_CLEAR(((PyCFunctionObject*)m)->m_module); +#endif + Py_CLEAR(m->func_dict); + Py_CLEAR(m->func_name); + Py_CLEAR(m->func_qualname); + Py_CLEAR(m->func_doc); + Py_CLEAR(m->func_globals); + Py_CLEAR(m->func_code); +#if !CYTHON_COMPILING_IN_LIMITED_API +#if PY_VERSION_HEX < 0x030900B1 + Py_CLEAR(__Pyx_CyFunction_GetClassObj(m)); +#else + { + PyObject *cls = (PyObject*) ((PyCMethodObject *) (m))->mm_class; + ((PyCMethodObject *) (m))->mm_class = NULL; + Py_XDECREF(cls); + } +#endif +#endif + Py_CLEAR(m->defaults_tuple); + Py_CLEAR(m->defaults_kwdict); + Py_CLEAR(m->func_annotations); + Py_CLEAR(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_XDECREF(pydefaults[i]); + PyObject_Free(m->defaults); + m->defaults = NULL; + } + return 0; +} +static void __Pyx__CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + if (__Pyx_CyFunction_weakreflist(m) != NULL) + PyObject_ClearWeakRefs((PyObject *) m); + __Pyx_CyFunction_clear(m); + __Pyx_PyHeapTypeObject_GC_Del(m); +} +static void __Pyx_CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + PyObject_GC_UnTrack(m); + __Pyx__CyFunction_dealloc(m); +} +static int __Pyx_CyFunction_traverse(__pyx_CyFunctionObject *m, visitproc visit, void *arg) +{ + Py_VISIT(m->func_closure); +#if CYTHON_COMPILING_IN_LIMITED_API + Py_VISIT(m->func); +#else + Py_VISIT(((PyCFunctionObject*)m)->m_module); +#endif + Py_VISIT(m->func_dict); + Py_VISIT(m->func_name); + Py_VISIT(m->func_qualname); + Py_VISIT(m->func_doc); + Py_VISIT(m->func_globals); + Py_VISIT(m->func_code); +#if !CYTHON_COMPILING_IN_LIMITED_API + Py_VISIT(__Pyx_CyFunction_GetClassObj(m)); +#endif + Py_VISIT(m->defaults_tuple); + Py_VISIT(m->defaults_kwdict); + Py_VISIT(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_VISIT(pydefaults[i]); + } + return 0; +} +static PyObject* +__Pyx_CyFunction_repr(__pyx_CyFunctionObject *op) +{ +#if PY_MAJOR_VERSION >= 3 + return PyUnicode_FromFormat("", + op->func_qualname, (void *)op); +#else + return PyString_FromFormat("", + PyString_AsString(op->func_qualname), (void *)op); +#endif +} +static PyObject * __Pyx_CyFunction_CallMethod(PyObject *func, PyObject *self, PyObject *arg, PyObject *kw) { +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *f = ((__pyx_CyFunctionObject*)func)->func; + PyObject *py_name = NULL; + PyCFunction meth; + int flags; + meth = PyCFunction_GetFunction(f); + if (unlikely(!meth)) return NULL; + flags = PyCFunction_GetFlags(f); + if (unlikely(flags < 0)) return NULL; +#else + PyCFunctionObject* f = (PyCFunctionObject*)func; + PyCFunction meth = f->m_ml->ml_meth; + int flags = f->m_ml->ml_flags; +#endif + Py_ssize_t size; + switch (flags & (METH_VARARGS | METH_KEYWORDS | METH_NOARGS | METH_O)) { + case METH_VARARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) + return (*meth)(self, arg); + break; + case METH_VARARGS | METH_KEYWORDS: + return (*(PyCFunctionWithKeywords)(void*)meth)(self, arg, kw); + case METH_NOARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { +#if CYTHON_ASSUME_SAFE_MACROS + size = PyTuple_GET_SIZE(arg); +#else + size = PyTuple_Size(arg); + if (unlikely(size < 0)) return NULL; +#endif + if (likely(size == 0)) + return (*meth)(self, NULL); +#if CYTHON_COMPILING_IN_LIMITED_API + py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); + if (!py_name) return NULL; + PyErr_Format(PyExc_TypeError, + "%.200S() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + py_name, size); + Py_DECREF(py_name); +#else + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); +#endif + return NULL; + } + break; + case METH_O: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { +#if CYTHON_ASSUME_SAFE_MACROS + size = PyTuple_GET_SIZE(arg); +#else + size = PyTuple_Size(arg); + if (unlikely(size < 0)) return NULL; +#endif + if (likely(size == 1)) { + PyObject *result, *arg0; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + arg0 = PyTuple_GET_ITEM(arg, 0); + #else + arg0 = __Pyx_PySequence_ITEM(arg, 0); if (unlikely(!arg0)) return NULL; + #endif + result = (*meth)(self, arg0); + #if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(arg0); + #endif + return result; + } +#if CYTHON_COMPILING_IN_LIMITED_API + py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); + if (!py_name) return NULL; + PyErr_Format(PyExc_TypeError, + "%.200S() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + py_name, size); + Py_DECREF(py_name); +#else + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); +#endif + return NULL; + } + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + return NULL; + } +#if CYTHON_COMPILING_IN_LIMITED_API + py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); + if (!py_name) return NULL; + PyErr_Format(PyExc_TypeError, "%.200S() takes no keyword arguments", + py_name); + Py_DECREF(py_name); +#else + PyErr_Format(PyExc_TypeError, "%.200s() takes no keyword arguments", + f->m_ml->ml_name); +#endif + return NULL; +} +static CYTHON_INLINE PyObject *__Pyx_CyFunction_Call(PyObject *func, PyObject *arg, PyObject *kw) { + PyObject *self, *result; +#if CYTHON_COMPILING_IN_LIMITED_API + self = PyCFunction_GetSelf(((__pyx_CyFunctionObject*)func)->func); + if (unlikely(!self) && PyErr_Occurred()) return NULL; +#else + self = ((PyCFunctionObject*)func)->m_self; +#endif + result = __Pyx_CyFunction_CallMethod(func, self, arg, kw); + return result; +} +static PyObject *__Pyx_CyFunction_CallAsMethod(PyObject *func, PyObject *args, PyObject *kw) { + PyObject *result; + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *) func; +#if CYTHON_METH_FASTCALL + __pyx_vectorcallfunc vc = __Pyx_CyFunction_func_vectorcall(cyfunc); + if (vc) { +#if CYTHON_ASSUME_SAFE_MACROS + return __Pyx_PyVectorcall_FastCallDict(func, vc, &PyTuple_GET_ITEM(args, 0), (size_t)PyTuple_GET_SIZE(args), kw); +#else + (void) &__Pyx_PyVectorcall_FastCallDict; + return PyVectorcall_Call(func, args, kw); +#endif + } +#endif + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + Py_ssize_t argc; + PyObject *new_args; + PyObject *self; +#if CYTHON_ASSUME_SAFE_MACROS + argc = PyTuple_GET_SIZE(args); +#else + argc = PyTuple_Size(args); + if (unlikely(!argc) < 0) return NULL; +#endif + new_args = PyTuple_GetSlice(args, 1, argc); + if (unlikely(!new_args)) + return NULL; + self = PyTuple_GetItem(args, 0); + if (unlikely(!self)) { + Py_DECREF(new_args); +#if PY_MAJOR_VERSION > 2 + PyErr_Format(PyExc_TypeError, + "unbound method %.200S() needs an argument", + cyfunc->func_qualname); +#else + PyErr_SetString(PyExc_TypeError, + "unbound method needs an argument"); +#endif + return NULL; + } + result = __Pyx_CyFunction_CallMethod(func, self, new_args, kw); + Py_DECREF(new_args); + } else { + result = __Pyx_CyFunction_Call(func, args, kw); + } + return result; +} +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE int __Pyx_CyFunction_Vectorcall_CheckArgs(__pyx_CyFunctionObject *cyfunc, Py_ssize_t nargs, PyObject *kwnames) +{ + int ret = 0; + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + if (unlikely(nargs < 1)) { + PyErr_Format(PyExc_TypeError, "%.200s() needs an argument", + ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + ret = 1; + } + if (unlikely(kwnames) && unlikely(PyTuple_GET_SIZE(kwnames))) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no keyword arguments", ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + return ret; +} +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 0)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, NULL); +} +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 1)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, args[0]); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((_PyCFunctionFastWithKeywords)(void(*)(void))def->ml_meth)(self, args, nargs, kwnames); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; + PyTypeObject *cls = (PyTypeObject *) __Pyx_CyFunction_GetClassObj(cyfunc); +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((__Pyx_PyCMethod)(void(*)(void))def->ml_meth)(self, cls, args, (size_t)nargs, kwnames); +} +#endif +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_CyFunctionType_slots[] = { + {Py_tp_dealloc, (void *)__Pyx_CyFunction_dealloc}, + {Py_tp_repr, (void *)__Pyx_CyFunction_repr}, + {Py_tp_call, (void *)__Pyx_CyFunction_CallAsMethod}, + {Py_tp_traverse, (void *)__Pyx_CyFunction_traverse}, + {Py_tp_clear, (void *)__Pyx_CyFunction_clear}, + {Py_tp_methods, (void *)__pyx_CyFunction_methods}, + {Py_tp_members, (void *)__pyx_CyFunction_members}, + {Py_tp_getset, (void *)__pyx_CyFunction_getsets}, + {Py_tp_descr_get, (void *)__Pyx_PyMethod_New}, + {0, 0}, +}; +static PyType_Spec __pyx_CyFunctionType_spec = { + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#if (defined(_Py_TPFLAGS_HAVE_VECTORCALL) && CYTHON_METH_FASTCALL) + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + __pyx_CyFunctionType_slots +}; +#else +static PyTypeObject __pyx_CyFunctionType_type = { + PyVarObject_HEAD_INIT(0, 0) + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, + (destructor) __Pyx_CyFunction_dealloc, +#if !CYTHON_METH_FASTCALL + 0, +#elif CYTHON_BACKPORT_VECTORCALL + (printfunc)offsetof(__pyx_CyFunctionObject, func_vectorcall), +#else + offsetof(PyCFunctionObject, vectorcall), +#endif + 0, + 0, +#if PY_MAJOR_VERSION < 3 + 0, +#else + 0, +#endif + (reprfunc) __Pyx_CyFunction_repr, + 0, + 0, + 0, + 0, + __Pyx_CyFunction_CallAsMethod, + 0, + 0, + 0, + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#if defined(_Py_TPFLAGS_HAVE_VECTORCALL) && CYTHON_METH_FASTCALL + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + 0, + (traverseproc) __Pyx_CyFunction_traverse, + (inquiry) __Pyx_CyFunction_clear, + 0, +#if PY_VERSION_HEX < 0x030500A0 + offsetof(__pyx_CyFunctionObject, func_weakreflist), +#else + offsetof(PyCFunctionObject, m_weakreflist), +#endif + 0, + 0, + __pyx_CyFunction_methods, + __pyx_CyFunction_members, + __pyx_CyFunction_getsets, + 0, + 0, + __Pyx_PyMethod_New, + 0, + offsetof(__pyx_CyFunctionObject, func_dict), + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, +#if PY_VERSION_HEX >= 0x030400a1 + 0, +#endif +#if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, +#endif +#if __PYX_NEED_TP_PRINT_SLOT + 0, +#endif +#if PY_VERSION_HEX >= 0x030C0000 + 0, +#endif +#if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, +#endif +}; +#endif +static int __pyx_CyFunction_init(PyObject *module) { +#if CYTHON_USE_TYPE_SPECS + __pyx_CyFunctionType = __Pyx_FetchCommonTypeFromSpec(module, &__pyx_CyFunctionType_spec, NULL); +#else + CYTHON_UNUSED_VAR(module); + __pyx_CyFunctionType = __Pyx_FetchCommonType(&__pyx_CyFunctionType_type); +#endif + if (unlikely(__pyx_CyFunctionType == NULL)) { + return -1; + } + return 0; +} +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *func, size_t size, int pyobjects) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults = PyObject_Malloc(size); + if (unlikely(!m->defaults)) + return PyErr_NoMemory(); + memset(m->defaults, 0, size); + m->defaults_pyobjects = pyobjects; + m->defaults_size = size; + return m->defaults; +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *func, PyObject *tuple) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_tuple = tuple; + Py_INCREF(tuple); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_kwdict = dict; + Py_INCREF(dict); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->func_annotations = dict; + Py_INCREF(dict); +} + +/* CythonFunction */ + static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { + PyObject *op = __Pyx_CyFunction_Init( + PyObject_GC_New(__pyx_CyFunctionObject, __pyx_CyFunctionType), + ml, flags, qualname, closure, module, globals, code + ); + if (likely(op)) { + PyObject_GC_Track(op); + } + return op; +} + +/* IterFinish */ + static CYTHON_INLINE int __Pyx_IterFinish(void) { + PyObject* exc_type; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + exc_type = __Pyx_PyErr_CurrentExceptionType(); + if (unlikely(exc_type)) { + if (unlikely(!__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) + return -1; + __Pyx_PyErr_Clear(); + return 0; + } + return 0; +} + +/* PyObjectCallNoArg */ + static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func) { + PyObject *arg[2] = {NULL, NULL}; + return __Pyx_PyObject_FastCall(func, arg + 1, 0 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* PyObjectGetMethod */ + static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method) { + PyObject *attr; +#if CYTHON_UNPACK_METHODS && CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_PYTYPE_LOOKUP + __Pyx_TypeName type_name; + PyTypeObject *tp = Py_TYPE(obj); + PyObject *descr; + descrgetfunc f = NULL; + PyObject **dictptr, *dict; + int meth_found = 0; + assert (*method == NULL); + if (unlikely(tp->tp_getattro != PyObject_GenericGetAttr)) { + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; + } + if (unlikely(tp->tp_dict == NULL) && unlikely(PyType_Ready(tp) < 0)) { + return 0; + } + descr = _PyType_Lookup(tp, name); + if (likely(descr != NULL)) { + Py_INCREF(descr); +#if defined(Py_TPFLAGS_METHOD_DESCRIPTOR) && Py_TPFLAGS_METHOD_DESCRIPTOR + if (__Pyx_PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_METHOD_DESCRIPTOR)) +#elif PY_MAJOR_VERSION >= 3 + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type))) + #endif +#else + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr))) + #endif +#endif + { + meth_found = 1; + } else { + f = Py_TYPE(descr)->tp_descr_get; + if (f != NULL && PyDescr_IsData(descr)) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + } + } + dictptr = _PyObject_GetDictPtr(obj); + if (dictptr != NULL && (dict = *dictptr) != NULL) { + Py_INCREF(dict); + attr = __Pyx_PyDict_GetItemStr(dict, name); + if (attr != NULL) { + Py_INCREF(attr); + Py_DECREF(dict); + Py_XDECREF(descr); + goto try_unpack; + } + Py_DECREF(dict); + } + if (meth_found) { + *method = descr; + return 1; + } + if (f != NULL) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + if (likely(descr != NULL)) { + *method = descr; + return 0; + } + type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return 0; +#else + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; +#endif +try_unpack: +#if CYTHON_UNPACK_METHODS + if (likely(attr) && PyMethod_Check(attr) && likely(PyMethod_GET_SELF(attr) == obj)) { + PyObject *function = PyMethod_GET_FUNCTION(attr); + Py_INCREF(function); + Py_DECREF(attr); + *method = function; + return 1; + } +#endif + *method = attr; + return 0; +} + +/* PyObjectCallMethod0 */ + static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name) { + PyObject *method = NULL, *result = NULL; + int is_method = __Pyx_PyObject_GetMethod(obj, method_name, &method); + if (likely(is_method)) { + result = __Pyx_PyObject_CallOneArg(method, obj); + Py_DECREF(method); + return result; + } + if (unlikely(!method)) goto bad; + result = __Pyx_PyObject_CallNoArg(method); + Py_DECREF(method); +bad: + return result; +} + +/* UnpackItemEndCheck */ + static int __Pyx_IternextUnpackEndCheck(PyObject *retval, Py_ssize_t expected) { + if (unlikely(retval)) { + Py_DECREF(retval); + __Pyx_RaiseTooManyValuesError(expected); + return -1; + } + return __Pyx_IterFinish(); +} + +/* UnpackTupleError */ + static void __Pyx_UnpackTupleError(PyObject *t, Py_ssize_t index) { + if (t == Py_None) { + __Pyx_RaiseNoneNotIterableError(); + } else if (PyTuple_GET_SIZE(t) < index) { + __Pyx_RaiseNeedMoreValuesError(PyTuple_GET_SIZE(t)); + } else { + __Pyx_RaiseTooManyValuesError(index); + } +} + +/* UnpackTuple2 */ + static CYTHON_INLINE int __Pyx_unpack_tuple2_exact( + PyObject* tuple, PyObject** pvalue1, PyObject** pvalue2, int decref_tuple) { + PyObject *value1 = NULL, *value2 = NULL; +#if CYTHON_COMPILING_IN_PYPY + value1 = PySequence_ITEM(tuple, 0); if (unlikely(!value1)) goto bad; + value2 = PySequence_ITEM(tuple, 1); if (unlikely(!value2)) goto bad; +#else + value1 = PyTuple_GET_ITEM(tuple, 0); Py_INCREF(value1); + value2 = PyTuple_GET_ITEM(tuple, 1); Py_INCREF(value2); +#endif + if (decref_tuple) { + Py_DECREF(tuple); + } + *pvalue1 = value1; + *pvalue2 = value2; + return 0; +#if CYTHON_COMPILING_IN_PYPY +bad: + Py_XDECREF(value1); + Py_XDECREF(value2); + if (decref_tuple) { Py_XDECREF(tuple); } + return -1; +#endif +} +static int __Pyx_unpack_tuple2_generic(PyObject* tuple, PyObject** pvalue1, PyObject** pvalue2, + int has_known_size, int decref_tuple) { + Py_ssize_t index; + PyObject *value1 = NULL, *value2 = NULL, *iter = NULL; + iternextfunc iternext; + iter = PyObject_GetIter(tuple); + if (unlikely(!iter)) goto bad; + if (decref_tuple) { Py_DECREF(tuple); tuple = NULL; } + iternext = __Pyx_PyObject_GetIterNextFunc(iter); + value1 = iternext(iter); if (unlikely(!value1)) { index = 0; goto unpacking_failed; } + value2 = iternext(iter); if (unlikely(!value2)) { index = 1; goto unpacking_failed; } + if (!has_known_size && unlikely(__Pyx_IternextUnpackEndCheck(iternext(iter), 2))) goto bad; + Py_DECREF(iter); + *pvalue1 = value1; + *pvalue2 = value2; + return 0; +unpacking_failed: + if (!has_known_size && __Pyx_IterFinish() == 0) + __Pyx_RaiseNeedMoreValuesError(index); +bad: + Py_XDECREF(iter); + Py_XDECREF(value1); + Py_XDECREF(value2); + if (decref_tuple) { Py_XDECREF(tuple); } + return -1; +} + +/* dict_iter */ + #if CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 +#include +#endif +static CYTHON_INLINE PyObject* __Pyx_dict_iterator(PyObject* iterable, int is_dict, PyObject* method_name, + Py_ssize_t* p_orig_length, int* p_source_is_dict) { + is_dict = is_dict || likely(PyDict_CheckExact(iterable)); + *p_source_is_dict = is_dict; + if (is_dict) { +#if !CYTHON_COMPILING_IN_PYPY + *p_orig_length = PyDict_Size(iterable); + Py_INCREF(iterable); + return iterable; +#elif PY_MAJOR_VERSION >= 3 + static PyObject *py_items = NULL, *py_keys = NULL, *py_values = NULL; + PyObject **pp = NULL; + if (method_name) { + const char *name = PyUnicode_AsUTF8(method_name); + if (strcmp(name, "iteritems") == 0) pp = &py_items; + else if (strcmp(name, "iterkeys") == 0) pp = &py_keys; + else if (strcmp(name, "itervalues") == 0) pp = &py_values; + if (pp) { + if (!*pp) { + *pp = PyUnicode_FromString(name + 4); + if (!*pp) + return NULL; + } + method_name = *pp; + } + } +#endif + } + *p_orig_length = 0; + if (method_name) { + PyObject* iter; + iterable = __Pyx_PyObject_CallMethod0(iterable, method_name); + if (!iterable) + return NULL; +#if !CYTHON_COMPILING_IN_PYPY + if (PyTuple_CheckExact(iterable) || PyList_CheckExact(iterable)) + return iterable; +#endif + iter = PyObject_GetIter(iterable); + Py_DECREF(iterable); + return iter; + } + return PyObject_GetIter(iterable); +} +static CYTHON_INLINE int __Pyx_dict_iter_next( + PyObject* iter_obj, CYTHON_NCP_UNUSED Py_ssize_t orig_length, CYTHON_NCP_UNUSED Py_ssize_t* ppos, + PyObject** pkey, PyObject** pvalue, PyObject** pitem, int source_is_dict) { + PyObject* next_item; +#if !CYTHON_COMPILING_IN_PYPY + if (source_is_dict) { + PyObject *key, *value; + if (unlikely(orig_length != PyDict_Size(iter_obj))) { + PyErr_SetString(PyExc_RuntimeError, "dictionary changed size during iteration"); + return -1; + } + if (unlikely(!PyDict_Next(iter_obj, ppos, &key, &value))) { + return 0; + } + if (pitem) { + PyObject* tuple = PyTuple_New(2); + if (unlikely(!tuple)) { + return -1; + } + Py_INCREF(key); + Py_INCREF(value); + PyTuple_SET_ITEM(tuple, 0, key); + PyTuple_SET_ITEM(tuple, 1, value); + *pitem = tuple; + } else { + if (pkey) { + Py_INCREF(key); + *pkey = key; + } + if (pvalue) { + Py_INCREF(value); + *pvalue = value; + } + } + return 1; + } else if (PyTuple_CheckExact(iter_obj)) { + Py_ssize_t pos = *ppos; + if (unlikely(pos >= PyTuple_GET_SIZE(iter_obj))) return 0; + *ppos = pos + 1; + next_item = PyTuple_GET_ITEM(iter_obj, pos); + Py_INCREF(next_item); + } else if (PyList_CheckExact(iter_obj)) { + Py_ssize_t pos = *ppos; + if (unlikely(pos >= PyList_GET_SIZE(iter_obj))) return 0; + *ppos = pos + 1; + next_item = PyList_GET_ITEM(iter_obj, pos); + Py_INCREF(next_item); + } else +#endif + { + next_item = PyIter_Next(iter_obj); + if (unlikely(!next_item)) { + return __Pyx_IterFinish(); + } + } + if (pitem) { + *pitem = next_item; + } else if (pkey && pvalue) { + if (__Pyx_unpack_tuple2(next_item, pkey, pvalue, source_is_dict, source_is_dict, 1)) + return -1; + } else if (pkey) { + *pkey = next_item; + } else { + *pvalue = next_item; + } + return 1; +} + +/* PyIntBinop */ + #if !CYTHON_COMPILING_IN_PYPY +static PyObject* __Pyx_PyInt_AddObjC(PyObject *op1, PyObject *op2, long intval, int inplace, int zerodivision_check) { + CYTHON_MAYBE_UNUSED_VAR(intval); + CYTHON_MAYBE_UNUSED_VAR(inplace); + CYTHON_UNUSED_VAR(zerodivision_check); + #if PY_MAJOR_VERSION < 3 + if (likely(PyInt_CheckExact(op1))) { + const long b = intval; + long x; + long a = PyInt_AS_LONG(op1); + + x = (long)((unsigned long)a + (unsigned long)b); + if (likely((x^a) >= 0 || (x^b) >= 0)) + return PyInt_FromLong(x); + return PyLong_Type.tp_as_number->nb_add(op1, op2); + } + #endif + #if CYTHON_USE_PYLONG_INTERNALS + if (likely(PyLong_CheckExact(op1))) { + const long b = intval; + long a, x; +#ifdef HAVE_LONG_LONG + const PY_LONG_LONG llb = intval; + PY_LONG_LONG lla, llx; +#endif + if (unlikely(__Pyx_PyLong_IsZero(op1))) { + return __Pyx_NewRef(op2); + } + if (likely(__Pyx_PyLong_IsCompact(op1))) { + a = __Pyx_PyLong_CompactValue(op1); + } else { + const digit* digits = __Pyx_PyLong_Digits(op1); + const Py_ssize_t size = __Pyx_PyLong_SignedDigitCount(op1); + switch (size) { + case -2: + if (8 * sizeof(long) - 1 > 2 * PyLong_SHIFT) { + a = -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0])); + break; + #ifdef HAVE_LONG_LONG + } else if (8 * sizeof(PY_LONG_LONG) - 1 > 2 * PyLong_SHIFT) { + lla = -(PY_LONG_LONG) (((((unsigned PY_LONG_LONG)digits[1]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[0])); + goto long_long; + #endif + } + CYTHON_FALLTHROUGH; + case 2: + if (8 * sizeof(long) - 1 > 2 * PyLong_SHIFT) { + a = (long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0])); + break; + #ifdef HAVE_LONG_LONG + } else if (8 * sizeof(PY_LONG_LONG) - 1 > 2 * PyLong_SHIFT) { + lla = (PY_LONG_LONG) (((((unsigned PY_LONG_LONG)digits[1]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[0])); + goto long_long; + #endif + } + CYTHON_FALLTHROUGH; + case -3: + if (8 * sizeof(long) - 1 > 3 * PyLong_SHIFT) { + a = -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0])); + break; + #ifdef HAVE_LONG_LONG + } else if (8 * sizeof(PY_LONG_LONG) - 1 > 3 * PyLong_SHIFT) { + lla = -(PY_LONG_LONG) (((((((unsigned PY_LONG_LONG)digits[2]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[1]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[0])); + goto long_long; + #endif + } + CYTHON_FALLTHROUGH; + case 3: + if (8 * sizeof(long) - 1 > 3 * PyLong_SHIFT) { + a = (long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0])); + break; + #ifdef HAVE_LONG_LONG + } else if (8 * sizeof(PY_LONG_LONG) - 1 > 3 * PyLong_SHIFT) { + lla = (PY_LONG_LONG) (((((((unsigned PY_LONG_LONG)digits[2]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[1]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[0])); + goto long_long; + #endif + } + CYTHON_FALLTHROUGH; + case -4: + if (8 * sizeof(long) - 1 > 4 * PyLong_SHIFT) { + a = -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0])); + break; + #ifdef HAVE_LONG_LONG + } else if (8 * sizeof(PY_LONG_LONG) - 1 > 4 * PyLong_SHIFT) { + lla = -(PY_LONG_LONG) (((((((((unsigned PY_LONG_LONG)digits[3]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[2]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[1]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[0])); + goto long_long; + #endif + } + CYTHON_FALLTHROUGH; + case 4: + if (8 * sizeof(long) - 1 > 4 * PyLong_SHIFT) { + a = (long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0])); + break; + #ifdef HAVE_LONG_LONG + } else if (8 * sizeof(PY_LONG_LONG) - 1 > 4 * PyLong_SHIFT) { + lla = (PY_LONG_LONG) (((((((((unsigned PY_LONG_LONG)digits[3]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[2]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[1]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[0])); + goto long_long; + #endif + } + CYTHON_FALLTHROUGH; + default: return PyLong_Type.tp_as_number->nb_add(op1, op2); + } + } + x = a + b; + return PyLong_FromLong(x); +#ifdef HAVE_LONG_LONG + long_long: + llx = lla + llb; + return PyLong_FromLongLong(llx); +#endif + + + } + #endif + if (PyFloat_CheckExact(op1)) { + const long b = intval; +#if CYTHON_COMPILING_IN_LIMITED_API + double a = __pyx_PyFloat_AsDouble(op1); +#else + double a = PyFloat_AS_DOUBLE(op1); +#endif + double result; + + PyFPE_START_PROTECT("add", return NULL) + result = ((double)a) + (double)b; + PyFPE_END_PROTECT(result) + return PyFloat_FromDouble(result); + } + return (inplace ? PyNumber_InPlaceAdd : PyNumber_Add)(op1, op2); +} +#endif + +/* BufferIndexError */ + static void __Pyx_RaiseBufferIndexError(int axis) { + PyErr_Format(PyExc_IndexError, + "Out of bounds on buffer access (axis %d)", axis); +} + +/* PyUnicode_Unicode */ + static CYTHON_INLINE PyObject* __Pyx_PyUnicode_Unicode(PyObject *obj) { + if (unlikely(obj == Py_None)) + obj = __pyx_kp_u_None; + return __Pyx_NewRef(obj); +} + +/* PyObject_GenericGetAttrNoDict */ + #if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject *__Pyx_RaiseGenericGetAttributeError(PyTypeObject *tp, PyObject *attr_name) { + __Pyx_TypeName type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, attr_name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(attr_name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name) { + PyObject *descr; + PyTypeObject *tp = Py_TYPE(obj); + if (unlikely(!PyString_Check(attr_name))) { + return PyObject_GenericGetAttr(obj, attr_name); + } + assert(!tp->tp_dictoffset); + descr = _PyType_Lookup(tp, attr_name); + if (unlikely(!descr)) { + return __Pyx_RaiseGenericGetAttributeError(tp, attr_name); + } + Py_INCREF(descr); + #if PY_MAJOR_VERSION < 3 + if (likely(PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_HAVE_CLASS))) + #endif + { + descrgetfunc f = Py_TYPE(descr)->tp_descr_get; + if (unlikely(f)) { + PyObject *res = f(descr, obj, (PyObject *)tp); + Py_DECREF(descr); + return res; + } + } + return descr; +} +#endif + +/* PyObject_GenericGetAttr */ + #if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name) { + if (unlikely(Py_TYPE(obj)->tp_dictoffset)) { + return PyObject_GenericGetAttr(obj, attr_name); + } + return __Pyx_PyObject_GenericGetAttrNoDict(obj, attr_name); +} +#endif + +/* ValidateBasesTuple */ + #if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases) { + Py_ssize_t i, n; +#if CYTHON_ASSUME_SAFE_MACROS + n = PyTuple_GET_SIZE(bases); +#else + n = PyTuple_Size(bases); + if (n < 0) return -1; +#endif + for (i = 1; i < n; i++) + { +#if CYTHON_AVOID_BORROWED_REFS + PyObject *b0 = PySequence_GetItem(bases, i); + if (!b0) return -1; +#elif CYTHON_ASSUME_SAFE_MACROS + PyObject *b0 = PyTuple_GET_ITEM(bases, i); +#else + PyObject *b0 = PyTuple_GetItem(bases, i); + if (!b0) return -1; +#endif + PyTypeObject *b; +#if PY_MAJOR_VERSION < 3 + if (PyClass_Check(b0)) + { + PyErr_Format(PyExc_TypeError, "base class '%.200s' is an old-style class", + PyString_AS_STRING(((PyClassObject*)b0)->cl_name)); +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + return -1; + } +#endif + b = (PyTypeObject*) b0; + if (!__Pyx_PyType_HasFeature(b, Py_TPFLAGS_HEAPTYPE)) + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "base class '" __Pyx_FMT_TYPENAME "' is not a heap type", b_name); + __Pyx_DECREF_TypeName(b_name); +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + return -1; + } + if (dictoffset == 0) + { + Py_ssize_t b_dictoffset = 0; +#if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + b_dictoffset = b->tp_dictoffset; +#else + PyObject *py_b_dictoffset = PyObject_GetAttrString((PyObject*)b, "__dictoffset__"); + if (!py_b_dictoffset) goto dictoffset_return; + b_dictoffset = PyLong_AsSsize_t(py_b_dictoffset); + Py_DECREF(py_b_dictoffset); + if (b_dictoffset == -1 && PyErr_Occurred()) goto dictoffset_return; +#endif + if (b_dictoffset) { + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "extension type '%.200s' has no __dict__ slot, " + "but base type '" __Pyx_FMT_TYPENAME "' has: " + "either add 'cdef dict __dict__' to the extension type " + "or add '__slots__ = [...]' to the base type", + type_name, b_name); + __Pyx_DECREF_TypeName(b_name); + } +#if !(CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY) + dictoffset_return: +#endif +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + return -1; + } + } +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + } + return 0; +} +#endif + +/* PyType_Ready */ + static int __Pyx_PyType_Ready(PyTypeObject *t) { +#if CYTHON_USE_TYPE_SPECS || !(CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API) || defined(PYSTON_MAJOR_VERSION) + (void)__Pyx_PyObject_CallMethod0; +#if CYTHON_USE_TYPE_SPECS + (void)__Pyx_validate_bases_tuple; +#endif + return PyType_Ready(t); +#else + int r; + PyObject *bases = __Pyx_PyType_GetSlot(t, tp_bases, PyObject*); + if (bases && unlikely(__Pyx_validate_bases_tuple(t->tp_name, t->tp_dictoffset, bases) == -1)) + return -1; +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + { + int gc_was_enabled; + #if PY_VERSION_HEX >= 0x030A00b1 + gc_was_enabled = PyGC_Disable(); + (void)__Pyx_PyObject_CallMethod0; + #else + PyObject *ret, *py_status; + PyObject *gc = NULL; + #if PY_VERSION_HEX >= 0x030700a1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM+0 >= 0x07030400) + gc = PyImport_GetModule(__pyx_kp_u_gc); + #endif + if (unlikely(!gc)) gc = PyImport_Import(__pyx_kp_u_gc); + if (unlikely(!gc)) return -1; + py_status = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_isenabled); + if (unlikely(!py_status)) { + Py_DECREF(gc); + return -1; + } + gc_was_enabled = __Pyx_PyObject_IsTrue(py_status); + Py_DECREF(py_status); + if (gc_was_enabled > 0) { + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_disable); + if (unlikely(!ret)) { + Py_DECREF(gc); + return -1; + } + Py_DECREF(ret); + } else if (unlikely(gc_was_enabled == -1)) { + Py_DECREF(gc); + return -1; + } + #endif + t->tp_flags |= Py_TPFLAGS_HEAPTYPE; +#if PY_VERSION_HEX >= 0x030A0000 + t->tp_flags |= Py_TPFLAGS_IMMUTABLETYPE; +#endif +#else + (void)__Pyx_PyObject_CallMethod0; +#endif + r = PyType_Ready(t); +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + t->tp_flags &= ~Py_TPFLAGS_HEAPTYPE; + #if PY_VERSION_HEX >= 0x030A00b1 + if (gc_was_enabled) + PyGC_Enable(); + #else + if (gc_was_enabled) { + PyObject *tp, *v, *tb; + PyErr_Fetch(&tp, &v, &tb); + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_enable); + if (likely(ret || r == -1)) { + Py_XDECREF(ret); + PyErr_Restore(tp, v, tb); + } else { + Py_XDECREF(tp); + Py_XDECREF(v); + Py_XDECREF(tb); + r = -1; + } + } + Py_DECREF(gc); + #endif + } +#endif + return r; +#endif +} + +/* SetupReduce */ + #if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce_is_named(PyObject* meth, PyObject* name) { + int ret; + PyObject *name_attr; + name_attr = __Pyx_PyObject_GetAttrStrNoError(meth, __pyx_n_s_name_2); + if (likely(name_attr)) { + ret = PyObject_RichCompareBool(name_attr, name, Py_EQ); + } else { + ret = -1; + } + if (unlikely(ret < 0)) { + PyErr_Clear(); + ret = 0; + } + Py_XDECREF(name_attr); + return ret; +} +static int __Pyx_setup_reduce(PyObject* type_obj) { + int ret = 0; + PyObject *object_reduce = NULL; + PyObject *object_getstate = NULL; + PyObject *object_reduce_ex = NULL; + PyObject *reduce = NULL; + PyObject *reduce_ex = NULL; + PyObject *reduce_cython = NULL; + PyObject *setstate = NULL; + PyObject *setstate_cython = NULL; + PyObject *getstate = NULL; +#if CYTHON_USE_PYTYPE_LOOKUP + getstate = _PyType_Lookup((PyTypeObject*)type_obj, __pyx_n_s_getstate); +#else + getstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_getstate); + if (!getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (getstate) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_getstate = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_getstate); +#else + object_getstate = __Pyx_PyObject_GetAttrStrNoError((PyObject*)&PyBaseObject_Type, __pyx_n_s_getstate); + if (!object_getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (object_getstate != getstate) { + goto __PYX_GOOD; + } + } +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce_ex = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#else + object_reduce_ex = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#endif + reduce_ex = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce_ex); if (unlikely(!reduce_ex)) goto __PYX_BAD; + if (reduce_ex == object_reduce_ex) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#else + object_reduce = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#endif + reduce = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce); if (unlikely(!reduce)) goto __PYX_BAD; + if (reduce == object_reduce || __Pyx_setup_reduce_is_named(reduce, __pyx_n_s_reduce_cython)) { + reduce_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_reduce_cython); + if (likely(reduce_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce, reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (reduce == object_reduce || PyErr_Occurred()) { + goto __PYX_BAD; + } + setstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate); + if (!setstate) PyErr_Clear(); + if (!setstate || __Pyx_setup_reduce_is_named(setstate, __pyx_n_s_setstate_cython)) { + setstate_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate_cython); + if (likely(setstate_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate, setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (!setstate || PyErr_Occurred()) { + goto __PYX_BAD; + } + } + PyType_Modified((PyTypeObject*)type_obj); + } + } + goto __PYX_GOOD; +__PYX_BAD: + if (!PyErr_Occurred()) { + __Pyx_TypeName type_obj_name = + __Pyx_PyType_GetName((PyTypeObject*)type_obj); + PyErr_Format(PyExc_RuntimeError, + "Unable to initialize pickling for " __Pyx_FMT_TYPENAME, type_obj_name); + __Pyx_DECREF_TypeName(type_obj_name); + } + ret = -1; +__PYX_GOOD: +#if !CYTHON_USE_PYTYPE_LOOKUP + Py_XDECREF(object_reduce); + Py_XDECREF(object_reduce_ex); + Py_XDECREF(object_getstate); + Py_XDECREF(getstate); +#endif + Py_XDECREF(reduce); + Py_XDECREF(reduce_ex); + Py_XDECREF(reduce_cython); + Py_XDECREF(setstate); + Py_XDECREF(setstate_cython); + return ret; +} +#endif + +/* SetVTable */ + static int __Pyx_SetVtable(PyTypeObject *type, void *vtable) { + PyObject *ob = PyCapsule_New(vtable, 0, 0); + if (unlikely(!ob)) + goto bad; +#if CYTHON_COMPILING_IN_LIMITED_API + if (unlikely(PyObject_SetAttr((PyObject *) type, __pyx_n_s_pyx_vtable, ob) < 0)) +#else + if (unlikely(PyDict_SetItem(type->tp_dict, __pyx_n_s_pyx_vtable, ob) < 0)) +#endif + goto bad; + Py_DECREF(ob); + return 0; +bad: + Py_XDECREF(ob); + return -1; +} + +/* GetVTable */ + static void* __Pyx_GetVtable(PyTypeObject *type) { + void* ptr; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *ob = PyObject_GetAttr((PyObject *)type, __pyx_n_s_pyx_vtable); +#else + PyObject *ob = PyObject_GetItem(type->tp_dict, __pyx_n_s_pyx_vtable); +#endif + if (!ob) + goto bad; + ptr = PyCapsule_GetPointer(ob, 0); + if (!ptr && !PyErr_Occurred()) + PyErr_SetString(PyExc_RuntimeError, "invalid vtable found for imported type"); + Py_DECREF(ob); + return ptr; +bad: + Py_XDECREF(ob); + return NULL; +} + +/* MergeVTables */ + #if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_MergeVtables(PyTypeObject *type) { + int i; + void** base_vtables; + __Pyx_TypeName tp_base_name; + __Pyx_TypeName base_name; + void* unknown = (void*)-1; + PyObject* bases = type->tp_bases; + int base_depth = 0; + { + PyTypeObject* base = type->tp_base; + while (base) { + base_depth += 1; + base = base->tp_base; + } + } + base_vtables = (void**) malloc(sizeof(void*) * (size_t)(base_depth + 1)); + base_vtables[0] = unknown; + for (i = 1; i < PyTuple_GET_SIZE(bases); i++) { + void* base_vtable = __Pyx_GetVtable(((PyTypeObject*)PyTuple_GET_ITEM(bases, i))); + if (base_vtable != NULL) { + int j; + PyTypeObject* base = type->tp_base; + for (j = 0; j < base_depth; j++) { + if (base_vtables[j] == unknown) { + base_vtables[j] = __Pyx_GetVtable(base); + base_vtables[j + 1] = unknown; + } + if (base_vtables[j] == base_vtable) { + break; + } else if (base_vtables[j] == NULL) { + goto bad; + } + base = base->tp_base; + } + } + } + PyErr_Clear(); + free(base_vtables); + return 0; +bad: + tp_base_name = __Pyx_PyType_GetName(type->tp_base); + base_name = __Pyx_PyType_GetName((PyTypeObject*)PyTuple_GET_ITEM(bases, i)); + PyErr_Format(PyExc_TypeError, + "multiple bases have vtable conflict: '" __Pyx_FMT_TYPENAME "' and '" __Pyx_FMT_TYPENAME "'", tp_base_name, base_name); + __Pyx_DECREF_TypeName(tp_base_name); + __Pyx_DECREF_TypeName(base_name); + free(base_vtables); + return -1; +} +#endif + +/* TypeImport */ + #ifndef __PYX_HAVE_RT_ImportType_3_0_8 +#define __PYX_HAVE_RT_ImportType_3_0_8 +static PyTypeObject *__Pyx_ImportType_3_0_8(PyObject *module, const char *module_name, const char *class_name, + size_t size, size_t alignment, enum __Pyx_ImportType_CheckSize_3_0_8 check_size) +{ + PyObject *result = 0; + char warning[200]; + Py_ssize_t basicsize; + Py_ssize_t itemsize; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *py_basicsize; + PyObject *py_itemsize; +#endif + result = PyObject_GetAttrString(module, class_name); + if (!result) + goto bad; + if (!PyType_Check(result)) { + PyErr_Format(PyExc_TypeError, + "%.200s.%.200s is not a type object", + module_name, class_name); + goto bad; + } +#if !CYTHON_COMPILING_IN_LIMITED_API + basicsize = ((PyTypeObject *)result)->tp_basicsize; + itemsize = ((PyTypeObject *)result)->tp_itemsize; +#else + py_basicsize = PyObject_GetAttrString(result, "__basicsize__"); + if (!py_basicsize) + goto bad; + basicsize = PyLong_AsSsize_t(py_basicsize); + Py_DECREF(py_basicsize); + py_basicsize = 0; + if (basicsize == (Py_ssize_t)-1 && PyErr_Occurred()) + goto bad; + py_itemsize = PyObject_GetAttrString(result, "__itemsize__"); + if (!py_itemsize) + goto bad; + itemsize = PyLong_AsSsize_t(py_itemsize); + Py_DECREF(py_itemsize); + py_itemsize = 0; + if (itemsize == (Py_ssize_t)-1 && PyErr_Occurred()) + goto bad; +#endif + if (itemsize) { + if (size % alignment) { + alignment = size % alignment; + } + if (itemsize < (Py_ssize_t)alignment) + itemsize = (Py_ssize_t)alignment; + } + if ((size_t)(basicsize + itemsize) < size) { + PyErr_Format(PyExc_ValueError, + "%.200s.%.200s size changed, may indicate binary incompatibility. " + "Expected %zd from C header, got %zd from PyObject", + module_name, class_name, size, basicsize+itemsize); + goto bad; + } + if (check_size == __Pyx_ImportType_CheckSize_Error_3_0_8 && + ((size_t)basicsize > size || (size_t)(basicsize + itemsize) < size)) { + PyErr_Format(PyExc_ValueError, + "%.200s.%.200s size changed, may indicate binary incompatibility. " + "Expected %zd from C header, got %zd-%zd from PyObject", + module_name, class_name, size, basicsize, basicsize+itemsize); + goto bad; + } + else if (check_size == __Pyx_ImportType_CheckSize_Warn_3_0_8 && (size_t)basicsize > size) { + PyOS_snprintf(warning, sizeof(warning), + "%s.%s size changed, may indicate binary incompatibility. " + "Expected %zd from C header, got %zd from PyObject", + module_name, class_name, size, basicsize); + if (PyErr_WarnEx(NULL, warning, 0) < 0) goto bad; + } + return (PyTypeObject *)result; +bad: + Py_XDECREF(result); + return NULL; +} +#endif + +/* CLineInTraceback */ + #ifndef CYTHON_CLINE_IN_TRACEBACK +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line) { + PyObject *use_cline; + PyObject *ptype, *pvalue, *ptraceback; +#if CYTHON_COMPILING_IN_CPYTHON + PyObject **cython_runtime_dict; +#endif + CYTHON_MAYBE_UNUSED_VAR(tstate); + if (unlikely(!__pyx_cython_runtime)) { + return c_line; + } + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); +#if CYTHON_COMPILING_IN_CPYTHON + cython_runtime_dict = _PyObject_GetDictPtr(__pyx_cython_runtime); + if (likely(cython_runtime_dict)) { + __PYX_PY_DICT_LOOKUP_IF_MODIFIED( + use_cline, *cython_runtime_dict, + __Pyx_PyDict_GetItemStr(*cython_runtime_dict, __pyx_n_s_cline_in_traceback)) + } else +#endif + { + PyObject *use_cline_obj = __Pyx_PyObject_GetAttrStrNoError(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback); + if (use_cline_obj) { + use_cline = PyObject_Not(use_cline_obj) ? Py_False : Py_True; + Py_DECREF(use_cline_obj); + } else { + PyErr_Clear(); + use_cline = NULL; + } + } + if (!use_cline) { + c_line = 0; + (void) PyObject_SetAttr(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback, Py_False); + } + else if (use_cline == Py_False || (use_cline != Py_True && PyObject_Not(use_cline) != 0)) { + c_line = 0; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + return c_line; +} +#endif + +/* CodeObjectCache */ + #if !CYTHON_COMPILING_IN_LIMITED_API +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line) { + int start = 0, mid = 0, end = count - 1; + if (end >= 0 && code_line > entries[end].code_line) { + return count; + } + while (start < end) { + mid = start + (end - start) / 2; + if (code_line < entries[mid].code_line) { + end = mid; + } else if (code_line > entries[mid].code_line) { + start = mid + 1; + } else { + return mid; + } + } + if (code_line <= entries[mid].code_line) { + return mid; + } else { + return mid + 1; + } +} +static PyCodeObject *__pyx_find_code_object(int code_line) { + PyCodeObject* code_object; + int pos; + if (unlikely(!code_line) || unlikely(!__pyx_code_cache.entries)) { + return NULL; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if (unlikely(pos >= __pyx_code_cache.count) || unlikely(__pyx_code_cache.entries[pos].code_line != code_line)) { + return NULL; + } + code_object = __pyx_code_cache.entries[pos].code_object; + Py_INCREF(code_object); + return code_object; +} +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object) { + int pos, i; + __Pyx_CodeObjectCacheEntry* entries = __pyx_code_cache.entries; + if (unlikely(!code_line)) { + return; + } + if (unlikely(!entries)) { + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Malloc(64*sizeof(__Pyx_CodeObjectCacheEntry)); + if (likely(entries)) { + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = 64; + __pyx_code_cache.count = 1; + entries[0].code_line = code_line; + entries[0].code_object = code_object; + Py_INCREF(code_object); + } + return; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if ((pos < __pyx_code_cache.count) && unlikely(__pyx_code_cache.entries[pos].code_line == code_line)) { + PyCodeObject* tmp = entries[pos].code_object; + entries[pos].code_object = code_object; + Py_DECREF(tmp); + return; + } + if (__pyx_code_cache.count == __pyx_code_cache.max_count) { + int new_max = __pyx_code_cache.max_count + 64; + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Realloc( + __pyx_code_cache.entries, ((size_t)new_max) * sizeof(__Pyx_CodeObjectCacheEntry)); + if (unlikely(!entries)) { + return; + } + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = new_max; + } + for (i=__pyx_code_cache.count; i>pos; i--) { + entries[i] = entries[i-1]; + } + entries[pos].code_line = code_line; + entries[pos].code_object = code_object; + __pyx_code_cache.count++; + Py_INCREF(code_object); +} +#endif + +/* AddTraceback */ + #include "compile.h" +#include "frameobject.h" +#include "traceback.h" +#if PY_VERSION_HEX >= 0x030b00a6 && !CYTHON_COMPILING_IN_LIMITED_API + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static PyObject *__Pyx_PyCode_Replace_For_AddTraceback(PyObject *code, PyObject *scratch_dict, + PyObject *firstlineno, PyObject *name) { + PyObject *replace = NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "co_firstlineno", firstlineno))) return NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "co_name", name))) return NULL; + replace = PyObject_GetAttrString(code, "replace"); + if (likely(replace)) { + PyObject *result; + result = PyObject_Call(replace, __pyx_empty_tuple, scratch_dict); + Py_DECREF(replace); + return result; + } + PyErr_Clear(); + #if __PYX_LIMITED_VERSION_HEX < 0x030780000 + { + PyObject *compiled = NULL, *result = NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "code", code))) return NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "type", (PyObject*)(&PyType_Type)))) return NULL; + compiled = Py_CompileString( + "out = type(code)(\n" + " code.co_argcount, code.co_kwonlyargcount, code.co_nlocals, code.co_stacksize,\n" + " code.co_flags, code.co_code, code.co_consts, code.co_names,\n" + " code.co_varnames, code.co_filename, co_name, co_firstlineno,\n" + " code.co_lnotab)\n", "", Py_file_input); + if (!compiled) return NULL; + result = PyEval_EvalCode(compiled, scratch_dict, scratch_dict); + Py_DECREF(compiled); + if (!result) PyErr_Print(); + Py_DECREF(result); + result = PyDict_GetItemString(scratch_dict, "out"); + if (result) Py_INCREF(result); + return result; + } + #else + return NULL; + #endif +} +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + PyObject *code_object = NULL, *py_py_line = NULL, *py_funcname = NULL, *dict = NULL; + PyObject *replace = NULL, *getframe = NULL, *frame = NULL; + PyObject *exc_type, *exc_value, *exc_traceback; + int success = 0; + if (c_line) { + (void) __pyx_cfilenm; + (void) __Pyx_CLineForTraceback(__Pyx_PyThreadState_Current, c_line); + } + PyErr_Fetch(&exc_type, &exc_value, &exc_traceback); + code_object = Py_CompileString("_getframe()", filename, Py_eval_input); + if (unlikely(!code_object)) goto bad; + py_py_line = PyLong_FromLong(py_line); + if (unlikely(!py_py_line)) goto bad; + py_funcname = PyUnicode_FromString(funcname); + if (unlikely(!py_funcname)) goto bad; + dict = PyDict_New(); + if (unlikely(!dict)) goto bad; + { + PyObject *old_code_object = code_object; + code_object = __Pyx_PyCode_Replace_For_AddTraceback(code_object, dict, py_py_line, py_funcname); + Py_DECREF(old_code_object); + } + if (unlikely(!code_object)) goto bad; + getframe = PySys_GetObject("_getframe"); + if (unlikely(!getframe)) goto bad; + if (unlikely(PyDict_SetItemString(dict, "_getframe", getframe))) goto bad; + frame = PyEval_EvalCode(code_object, dict, dict); + if (unlikely(!frame) || frame == Py_None) goto bad; + success = 1; + bad: + PyErr_Restore(exc_type, exc_value, exc_traceback); + Py_XDECREF(code_object); + Py_XDECREF(py_py_line); + Py_XDECREF(py_funcname); + Py_XDECREF(dict); + Py_XDECREF(replace); + if (success) { + PyTraceBack_Here( + (struct _frame*)frame); + } + Py_XDECREF(frame); +} +#else +static PyCodeObject* __Pyx_CreateCodeObjectForTraceback( + const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = NULL; + PyObject *py_funcname = NULL; + #if PY_MAJOR_VERSION < 3 + PyObject *py_srcfile = NULL; + py_srcfile = PyString_FromString(filename); + if (!py_srcfile) goto bad; + #endif + if (c_line) { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + #else + py_funcname = PyUnicode_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + funcname = PyUnicode_AsUTF8(py_funcname); + if (!funcname) goto bad; + #endif + } + else { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromString(funcname); + if (!py_funcname) goto bad; + #endif + } + #if PY_MAJOR_VERSION < 3 + py_code = __Pyx_PyCode_New( + 0, + 0, + 0, + 0, + 0, + 0, + __pyx_empty_bytes, /*PyObject *code,*/ + __pyx_empty_tuple, /*PyObject *consts,*/ + __pyx_empty_tuple, /*PyObject *names,*/ + __pyx_empty_tuple, /*PyObject *varnames,*/ + __pyx_empty_tuple, /*PyObject *freevars,*/ + __pyx_empty_tuple, /*PyObject *cellvars,*/ + py_srcfile, /*PyObject *filename,*/ + py_funcname, /*PyObject *name,*/ + py_line, + __pyx_empty_bytes /*PyObject *lnotab*/ + ); + Py_DECREF(py_srcfile); + #else + py_code = PyCode_NewEmpty(filename, funcname, py_line); + #endif + Py_XDECREF(py_funcname); + return py_code; +bad: + Py_XDECREF(py_funcname); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_srcfile); + #endif + return NULL; +} +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = 0; + PyFrameObject *py_frame = 0; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject *ptype, *pvalue, *ptraceback; + if (c_line) { + c_line = __Pyx_CLineForTraceback(tstate, c_line); + } + py_code = __pyx_find_code_object(c_line ? -c_line : py_line); + if (!py_code) { + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); + py_code = __Pyx_CreateCodeObjectForTraceback( + funcname, c_line, py_line, filename); + if (!py_code) { + /* If the code object creation fails, then we should clear the + fetched exception references and propagate the new exception */ + Py_XDECREF(ptype); + Py_XDECREF(pvalue); + Py_XDECREF(ptraceback); + goto bad; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + __pyx_insert_code_object(c_line ? -c_line : py_line, py_code); + } + py_frame = PyFrame_New( + tstate, /*PyThreadState *tstate,*/ + py_code, /*PyCodeObject *code,*/ + __pyx_d, /*PyObject *globals,*/ + 0 /*PyObject *locals*/ + ); + if (!py_frame) goto bad; + __Pyx_PyFrame_SetLineNumber(py_frame, py_line); + PyTraceBack_Here(py_frame); +bad: + Py_XDECREF(py_code); + Py_XDECREF(py_frame); +} +#endif + +#if PY_MAJOR_VERSION < 3 +static int __Pyx_GetBuffer(PyObject *obj, Py_buffer *view, int flags) { + __Pyx_TypeName obj_type_name; + if (PyObject_CheckBuffer(obj)) return PyObject_GetBuffer(obj, view, flags); + if (__Pyx_TypeCheck(obj, __pyx_array_type)) return __pyx_array_getbuffer(obj, view, flags); + if (__Pyx_TypeCheck(obj, __pyx_memoryview_type)) return __pyx_memoryview_getbuffer(obj, view, flags); + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "'" __Pyx_FMT_TYPENAME "' does not have the buffer interface", + obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return -1; +} +static void __Pyx_ReleaseBuffer(Py_buffer *view) { + PyObject *obj = view->obj; + if (!obj) return; + if (PyObject_CheckBuffer(obj)) { + PyBuffer_Release(view); + return; + } + if ((0)) {} + view->obj = NULL; + Py_DECREF(obj); +} +#endif + + + /* MemviewSliceIsContig */ + static int +__pyx_memviewslice_is_contig(const __Pyx_memviewslice mvs, char order, int ndim) +{ + int i, index, step, start; + Py_ssize_t itemsize = mvs.memview->view.itemsize; + if (order == 'F') { + step = 1; + start = 0; + } else { + step = -1; + start = ndim - 1; + } + for (i = 0; i < ndim; i++) { + index = start + step * i; + if (mvs.suboffsets[index] >= 0 || mvs.strides[index] != itemsize) + return 0; + itemsize *= mvs.shape[index]; + } + return 1; +} + +/* OverlappingSlices */ + static void +__pyx_get_array_memory_extents(__Pyx_memviewslice *slice, + void **out_start, void **out_end, + int ndim, size_t itemsize) +{ + char *start, *end; + int i; + start = end = slice->data; + for (i = 0; i < ndim; i++) { + Py_ssize_t stride = slice->strides[i]; + Py_ssize_t extent = slice->shape[i]; + if (extent == 0) { + *out_start = *out_end = start; + return; + } else { + if (stride > 0) + end += stride * (extent - 1); + else + start += stride * (extent - 1); + } + } + *out_start = start; + *out_end = end + itemsize; +} +static int +__pyx_slices_overlap(__Pyx_memviewslice *slice1, + __Pyx_memviewslice *slice2, + int ndim, size_t itemsize) +{ + void *start1, *end1, *start2, *end2; + __pyx_get_array_memory_extents(slice1, &start1, &end1, ndim, itemsize); + __pyx_get_array_memory_extents(slice2, &start2, &end2, ndim, itemsize); + return (start1 < end2) && (start2 < end1); +} + +/* CIntFromPyVerify */ + #define __PYX_VERIFY_RETURN_INT(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 0) +#define __PYX_VERIFY_RETURN_INT_EXC(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 1) +#define __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, exc)\ + {\ + func_type value = func_value;\ + if (sizeof(target_type) < sizeof(func_type)) {\ + if (unlikely(value != (func_type) (target_type) value)) {\ + func_type zero = 0;\ + if (exc && unlikely(value == (func_type)-1 && PyErr_Occurred()))\ + return (target_type) -1;\ + if (is_unsigned && unlikely(value < zero))\ + goto raise_neg_overflow;\ + else\ + goto raise_overflow;\ + }\ + }\ + return (target_type) value;\ + } + +/* TypeInfoCompare */ + static int +__pyx_typeinfo_cmp(__Pyx_TypeInfo *a, __Pyx_TypeInfo *b) +{ + int i; + if (!a || !b) + return 0; + if (a == b) + return 1; + if (a->size != b->size || a->typegroup != b->typegroup || + a->is_unsigned != b->is_unsigned || a->ndim != b->ndim) { + if (a->typegroup == 'H' || b->typegroup == 'H') { + return a->size == b->size; + } else { + return 0; + } + } + if (a->ndim) { + for (i = 0; i < a->ndim; i++) + if (a->arraysize[i] != b->arraysize[i]) + return 0; + } + if (a->typegroup == 'S') { + if (a->flags != b->flags) + return 0; + if (a->fields || b->fields) { + if (!(a->fields && b->fields)) + return 0; + for (i = 0; a->fields[i].type && b->fields[i].type; i++) { + __Pyx_StructField *field_a = a->fields + i; + __Pyx_StructField *field_b = b->fields + i; + if (field_a->offset != field_b->offset || + !__pyx_typeinfo_cmp(field_a->type, field_b->type)) + return 0; + } + return !a->fields[i].type && !b->fields[i].type; + } + } + return 1; +} + +/* MemviewSliceValidateAndInit */ + static int +__pyx_check_strides(Py_buffer *buf, int dim, int ndim, int spec) +{ + if (buf->shape[dim] <= 1) + return 1; + if (buf->strides) { + if (spec & __Pyx_MEMVIEW_CONTIG) { + if (spec & (__Pyx_MEMVIEW_PTR|__Pyx_MEMVIEW_FULL)) { + if (unlikely(buf->strides[dim] != sizeof(void *))) { + PyErr_Format(PyExc_ValueError, + "Buffer is not indirectly contiguous " + "in dimension %d.", dim); + goto fail; + } + } else if (unlikely(buf->strides[dim] != buf->itemsize)) { + PyErr_SetString(PyExc_ValueError, + "Buffer and memoryview are not contiguous " + "in the same dimension."); + goto fail; + } + } + if (spec & __Pyx_MEMVIEW_FOLLOW) { + Py_ssize_t stride = buf->strides[dim]; + if (stride < 0) + stride = -stride; + if (unlikely(stride < buf->itemsize)) { + PyErr_SetString(PyExc_ValueError, + "Buffer and memoryview are not contiguous " + "in the same dimension."); + goto fail; + } + } + } else { + if (unlikely(spec & __Pyx_MEMVIEW_CONTIG && dim != ndim - 1)) { + PyErr_Format(PyExc_ValueError, + "C-contiguous buffer is not contiguous in " + "dimension %d", dim); + goto fail; + } else if (unlikely(spec & (__Pyx_MEMVIEW_PTR))) { + PyErr_Format(PyExc_ValueError, + "C-contiguous buffer is not indirect in " + "dimension %d", dim); + goto fail; + } else if (unlikely(buf->suboffsets)) { + PyErr_SetString(PyExc_ValueError, + "Buffer exposes suboffsets but no strides"); + goto fail; + } + } + return 1; +fail: + return 0; +} +static int +__pyx_check_suboffsets(Py_buffer *buf, int dim, int ndim, int spec) +{ + CYTHON_UNUSED_VAR(ndim); + if (spec & __Pyx_MEMVIEW_DIRECT) { + if (unlikely(buf->suboffsets && buf->suboffsets[dim] >= 0)) { + PyErr_Format(PyExc_ValueError, + "Buffer not compatible with direct access " + "in dimension %d.", dim); + goto fail; + } + } + if (spec & __Pyx_MEMVIEW_PTR) { + if (unlikely(!buf->suboffsets || (buf->suboffsets[dim] < 0))) { + PyErr_Format(PyExc_ValueError, + "Buffer is not indirectly accessible " + "in dimension %d.", dim); + goto fail; + } + } + return 1; +fail: + return 0; +} +static int +__pyx_verify_contig(Py_buffer *buf, int ndim, int c_or_f_flag) +{ + int i; + if (c_or_f_flag & __Pyx_IS_F_CONTIG) { + Py_ssize_t stride = 1; + for (i = 0; i < ndim; i++) { + if (unlikely(stride * buf->itemsize != buf->strides[i] && buf->shape[i] > 1)) { + PyErr_SetString(PyExc_ValueError, + "Buffer not fortran contiguous."); + goto fail; + } + stride = stride * buf->shape[i]; + } + } else if (c_or_f_flag & __Pyx_IS_C_CONTIG) { + Py_ssize_t stride = 1; + for (i = ndim - 1; i >- 1; i--) { + if (unlikely(stride * buf->itemsize != buf->strides[i] && buf->shape[i] > 1)) { + PyErr_SetString(PyExc_ValueError, + "Buffer not C contiguous."); + goto fail; + } + stride = stride * buf->shape[i]; + } + } + return 1; +fail: + return 0; +} +static int __Pyx_ValidateAndInit_memviewslice( + int *axes_specs, + int c_or_f_flag, + int buf_flags, + int ndim, + __Pyx_TypeInfo *dtype, + __Pyx_BufFmt_StackElem stack[], + __Pyx_memviewslice *memviewslice, + PyObject *original_obj) +{ + struct __pyx_memoryview_obj *memview, *new_memview; + __Pyx_RefNannyDeclarations + Py_buffer *buf; + int i, spec = 0, retval = -1; + __Pyx_BufFmt_Context ctx; + int from_memoryview = __pyx_memoryview_check(original_obj); + __Pyx_RefNannySetupContext("ValidateAndInit_memviewslice", 0); + if (from_memoryview && __pyx_typeinfo_cmp(dtype, ((struct __pyx_memoryview_obj *) + original_obj)->typeinfo)) { + memview = (struct __pyx_memoryview_obj *) original_obj; + new_memview = NULL; + } else { + memview = (struct __pyx_memoryview_obj *) __pyx_memoryview_new( + original_obj, buf_flags, 0, dtype); + new_memview = memview; + if (unlikely(!memview)) + goto fail; + } + buf = &memview->view; + if (unlikely(buf->ndim != ndim)) { + PyErr_Format(PyExc_ValueError, + "Buffer has wrong number of dimensions (expected %d, got %d)", + ndim, buf->ndim); + goto fail; + } + if (new_memview) { + __Pyx_BufFmt_Init(&ctx, stack, dtype); + if (unlikely(!__Pyx_BufFmt_CheckString(&ctx, buf->format))) goto fail; + } + if (unlikely((unsigned) buf->itemsize != dtype->size)) { + PyErr_Format(PyExc_ValueError, + "Item size of buffer (%" CYTHON_FORMAT_SSIZE_T "u byte%s) " + "does not match size of '%s' (%" CYTHON_FORMAT_SSIZE_T "u byte%s)", + buf->itemsize, + (buf->itemsize > 1) ? "s" : "", + dtype->name, + dtype->size, + (dtype->size > 1) ? "s" : ""); + goto fail; + } + if (buf->len > 0) { + for (i = 0; i < ndim; i++) { + spec = axes_specs[i]; + if (unlikely(!__pyx_check_strides(buf, i, ndim, spec))) + goto fail; + if (unlikely(!__pyx_check_suboffsets(buf, i, ndim, spec))) + goto fail; + } + if (unlikely(buf->strides && !__pyx_verify_contig(buf, ndim, c_or_f_flag))) + goto fail; + } + if (unlikely(__Pyx_init_memviewslice(memview, ndim, memviewslice, + new_memview != NULL) == -1)) { + goto fail; + } + retval = 0; + goto no_fail; +fail: + Py_XDECREF(new_memview); + retval = -1; +no_fail: + __Pyx_RefNannyFinishContext(); + return retval; +} + +/* ObjectToMemviewSlice */ + static CYTHON_INLINE __Pyx_memviewslice __Pyx_PyObject_to_MemoryviewSlice_dcd__double(PyObject *obj, int writable_flag) { + __Pyx_memviewslice result = { 0, 0, { 0 }, { 0 }, { 0 } }; + __Pyx_BufFmt_StackElem stack[1]; + int axes_specs[] = { (__Pyx_MEMVIEW_DIRECT | __Pyx_MEMVIEW_CONTIG), (__Pyx_MEMVIEW_DIRECT | __Pyx_MEMVIEW_FOLLOW) }; + int retcode; + if (obj == Py_None) { + result.memview = (struct __pyx_memoryview_obj *) Py_None; + return result; + } + retcode = __Pyx_ValidateAndInit_memviewslice(axes_specs, __Pyx_IS_F_CONTIG, + (PyBUF_F_CONTIGUOUS | PyBUF_FORMAT) | writable_flag, 2, + &__Pyx_TypeInfo_double, stack, + &result, obj); + if (unlikely(retcode == -1)) + goto __pyx_fail; + return result; +__pyx_fail: + result.memview = NULL; + result.data = NULL; + return result; +} + +/* ObjectToMemviewSlice */ + static CYTHON_INLINE __Pyx_memviewslice __Pyx_PyObject_to_MemoryviewSlice_dc_unsigned_char(PyObject *obj, int writable_flag) { + __Pyx_memviewslice result = { 0, 0, { 0 }, { 0 }, { 0 } }; + __Pyx_BufFmt_StackElem stack[1]; + int axes_specs[] = { (__Pyx_MEMVIEW_DIRECT | __Pyx_MEMVIEW_CONTIG) }; + int retcode; + if (obj == Py_None) { + result.memview = (struct __pyx_memoryview_obj *) Py_None; + return result; + } + retcode = __Pyx_ValidateAndInit_memviewslice(axes_specs, __Pyx_IS_C_CONTIG, + (PyBUF_C_CONTIGUOUS | PyBUF_FORMAT) | writable_flag, 1, + &__Pyx_TypeInfo_unsigned_char, stack, + &result, obj); + if (unlikely(retcode == -1)) + goto __pyx_fail; + return result; +__pyx_fail: + result.memview = NULL; + result.data = NULL; + return result; +} + +/* Declarations */ + #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #ifdef __cplusplus + static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float x, float y) { + return ::std::complex< float >(x, y); + } + #else + static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float x, float y) { + return x + y*(__pyx_t_float_complex)_Complex_I; + } + #endif +#else + static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float x, float y) { + __pyx_t_float_complex z; + z.real = x; + z.imag = y; + return z; + } +#endif + +/* Arithmetic */ + #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) +#else + static CYTHON_INLINE int __Pyx_c_eq_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + return (a.real == b.real) && (a.imag == b.imag); + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_sum_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + __pyx_t_float_complex z; + z.real = a.real + b.real; + z.imag = a.imag + b.imag; + return z; + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_diff_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + __pyx_t_float_complex z; + z.real = a.real - b.real; + z.imag = a.imag - b.imag; + return z; + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_prod_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + __pyx_t_float_complex z; + z.real = a.real * b.real - a.imag * b.imag; + z.imag = a.real * b.imag + a.imag * b.real; + return z; + } + #if 1 + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_quot_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + if (b.imag == 0) { + return __pyx_t_float_complex_from_parts(a.real / b.real, a.imag / b.real); + } else if (fabsf(b.real) >= fabsf(b.imag)) { + if (b.real == 0 && b.imag == 0) { + return __pyx_t_float_complex_from_parts(a.real / b.real, a.imag / b.imag); + } else { + float r = b.imag / b.real; + float s = (float)(1.0) / (b.real + b.imag * r); + return __pyx_t_float_complex_from_parts( + (a.real + a.imag * r) * s, (a.imag - a.real * r) * s); + } + } else { + float r = b.real / b.imag; + float s = (float)(1.0) / (b.imag + b.real * r); + return __pyx_t_float_complex_from_parts( + (a.real * r + a.imag) * s, (a.imag * r - a.real) * s); + } + } + #else + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_quot_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + if (b.imag == 0) { + return __pyx_t_float_complex_from_parts(a.real / b.real, a.imag / b.real); + } else { + float denom = b.real * b.real + b.imag * b.imag; + return __pyx_t_float_complex_from_parts( + (a.real * b.real + a.imag * b.imag) / denom, + (a.imag * b.real - a.real * b.imag) / denom); + } + } + #endif + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_neg_float(__pyx_t_float_complex a) { + __pyx_t_float_complex z; + z.real = -a.real; + z.imag = -a.imag; + return z; + } + static CYTHON_INLINE int __Pyx_c_is_zero_float(__pyx_t_float_complex a) { + return (a.real == 0) && (a.imag == 0); + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_conj_float(__pyx_t_float_complex a) { + __pyx_t_float_complex z; + z.real = a.real; + z.imag = -a.imag; + return z; + } + #if 1 + static CYTHON_INLINE float __Pyx_c_abs_float(__pyx_t_float_complex z) { + #if !defined(HAVE_HYPOT) || defined(_MSC_VER) + return sqrtf(z.real*z.real + z.imag*z.imag); + #else + return hypotf(z.real, z.imag); + #endif + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_pow_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + __pyx_t_float_complex z; + float r, lnr, theta, z_r, z_theta; + if (b.imag == 0 && b.real == (int)b.real) { + if (b.real < 0) { + float denom = a.real * a.real + a.imag * a.imag; + a.real = a.real / denom; + a.imag = -a.imag / denom; + b.real = -b.real; + } + switch ((int)b.real) { + case 0: + z.real = 1; + z.imag = 0; + return z; + case 1: + return a; + case 2: + return __Pyx_c_prod_float(a, a); + case 3: + z = __Pyx_c_prod_float(a, a); + return __Pyx_c_prod_float(z, a); + case 4: + z = __Pyx_c_prod_float(a, a); + return __Pyx_c_prod_float(z, z); + } + } + if (a.imag == 0) { + if (a.real == 0) { + return a; + } else if ((b.imag == 0) && (a.real >= 0)) { + z.real = powf(a.real, b.real); + z.imag = 0; + return z; + } else if (a.real > 0) { + r = a.real; + theta = 0; + } else { + r = -a.real; + theta = atan2f(0.0, -1.0); + } + } else { + r = __Pyx_c_abs_float(a); + theta = atan2f(a.imag, a.real); + } + lnr = logf(r); + z_r = expf(lnr * b.real - theta * b.imag); + z_theta = theta * b.real + lnr * b.imag; + z.real = z_r * cosf(z_theta); + z.imag = z_r * sinf(z_theta); + return z; + } + #endif +#endif + +/* Declarations */ + #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #ifdef __cplusplus + static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double x, double y) { + return ::std::complex< double >(x, y); + } + #else + static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double x, double y) { + return x + y*(__pyx_t_double_complex)_Complex_I; + } + #endif +#else + static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double x, double y) { + __pyx_t_double_complex z; + z.real = x; + z.imag = y; + return z; + } +#endif + +/* Arithmetic */ + #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) +#else + static CYTHON_INLINE int __Pyx_c_eq_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + return (a.real == b.real) && (a.imag == b.imag); + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_sum_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + __pyx_t_double_complex z; + z.real = a.real + b.real; + z.imag = a.imag + b.imag; + return z; + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_diff_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + __pyx_t_double_complex z; + z.real = a.real - b.real; + z.imag = a.imag - b.imag; + return z; + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_prod_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + __pyx_t_double_complex z; + z.real = a.real * b.real - a.imag * b.imag; + z.imag = a.real * b.imag + a.imag * b.real; + return z; + } + #if 1 + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_quot_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + if (b.imag == 0) { + return __pyx_t_double_complex_from_parts(a.real / b.real, a.imag / b.real); + } else if (fabs(b.real) >= fabs(b.imag)) { + if (b.real == 0 && b.imag == 0) { + return __pyx_t_double_complex_from_parts(a.real / b.real, a.imag / b.imag); + } else { + double r = b.imag / b.real; + double s = (double)(1.0) / (b.real + b.imag * r); + return __pyx_t_double_complex_from_parts( + (a.real + a.imag * r) * s, (a.imag - a.real * r) * s); + } + } else { + double r = b.real / b.imag; + double s = (double)(1.0) / (b.imag + b.real * r); + return __pyx_t_double_complex_from_parts( + (a.real * r + a.imag) * s, (a.imag * r - a.real) * s); + } + } + #else + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_quot_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + if (b.imag == 0) { + return __pyx_t_double_complex_from_parts(a.real / b.real, a.imag / b.real); + } else { + double denom = b.real * b.real + b.imag * b.imag; + return __pyx_t_double_complex_from_parts( + (a.real * b.real + a.imag * b.imag) / denom, + (a.imag * b.real - a.real * b.imag) / denom); + } + } + #endif + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_neg_double(__pyx_t_double_complex a) { + __pyx_t_double_complex z; + z.real = -a.real; + z.imag = -a.imag; + return z; + } + static CYTHON_INLINE int __Pyx_c_is_zero_double(__pyx_t_double_complex a) { + return (a.real == 0) && (a.imag == 0); + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_conj_double(__pyx_t_double_complex a) { + __pyx_t_double_complex z; + z.real = a.real; + z.imag = -a.imag; + return z; + } + #if 1 + static CYTHON_INLINE double __Pyx_c_abs_double(__pyx_t_double_complex z) { + #if !defined(HAVE_HYPOT) || defined(_MSC_VER) + return sqrt(z.real*z.real + z.imag*z.imag); + #else + return hypot(z.real, z.imag); + #endif + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_pow_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + __pyx_t_double_complex z; + double r, lnr, theta, z_r, z_theta; + if (b.imag == 0 && b.real == (int)b.real) { + if (b.real < 0) { + double denom = a.real * a.real + a.imag * a.imag; + a.real = a.real / denom; + a.imag = -a.imag / denom; + b.real = -b.real; + } + switch ((int)b.real) { + case 0: + z.real = 1; + z.imag = 0; + return z; + case 1: + return a; + case 2: + return __Pyx_c_prod_double(a, a); + case 3: + z = __Pyx_c_prod_double(a, a); + return __Pyx_c_prod_double(z, a); + case 4: + z = __Pyx_c_prod_double(a, a); + return __Pyx_c_prod_double(z, z); + } + } + if (a.imag == 0) { + if (a.real == 0) { + return a; + } else if ((b.imag == 0) && (a.real >= 0)) { + z.real = pow(a.real, b.real); + z.imag = 0; + return z; + } else if (a.real > 0) { + r = a.real; + theta = 0; + } else { + r = -a.real; + theta = atan2(0.0, -1.0); + } + } else { + r = __Pyx_c_abs_double(a); + theta = atan2(a.imag, a.real); + } + lnr = log(r); + z_r = exp(lnr * b.real - theta * b.imag); + z_theta = theta * b.real + lnr * b.imag; + z.real = z_r * cos(z_theta); + z.imag = z_r * sin(z_theta); + return z; + } + #endif +#endif + +/* MemviewSliceCopyTemplate */ + static __Pyx_memviewslice +__pyx_memoryview_copy_new_contig(const __Pyx_memviewslice *from_mvs, + const char *mode, int ndim, + size_t sizeof_dtype, int contig_flag, + int dtype_is_object) +{ + __Pyx_RefNannyDeclarations + int i; + __Pyx_memviewslice new_mvs = { 0, 0, { 0 }, { 0 }, { 0 } }; + struct __pyx_memoryview_obj *from_memview = from_mvs->memview; + Py_buffer *buf = &from_memview->view; + PyObject *shape_tuple = NULL; + PyObject *temp_int = NULL; + struct __pyx_array_obj *array_obj = NULL; + struct __pyx_memoryview_obj *memview_obj = NULL; + __Pyx_RefNannySetupContext("__pyx_memoryview_copy_new_contig", 0); + for (i = 0; i < ndim; i++) { + if (unlikely(from_mvs->suboffsets[i] >= 0)) { + PyErr_Format(PyExc_ValueError, "Cannot copy memoryview slice with " + "indirect dimensions (axis %d)", i); + goto fail; + } + } + shape_tuple = PyTuple_New(ndim); + if (unlikely(!shape_tuple)) { + goto fail; + } + __Pyx_GOTREF(shape_tuple); + for(i = 0; i < ndim; i++) { + temp_int = PyInt_FromSsize_t(from_mvs->shape[i]); + if(unlikely(!temp_int)) { + goto fail; + } else { + PyTuple_SET_ITEM(shape_tuple, i, temp_int); + temp_int = NULL; + } + } + array_obj = __pyx_array_new(shape_tuple, sizeof_dtype, buf->format, (char *) mode, NULL); + if (unlikely(!array_obj)) { + goto fail; + } + __Pyx_GOTREF(array_obj); + memview_obj = (struct __pyx_memoryview_obj *) __pyx_memoryview_new( + (PyObject *) array_obj, contig_flag, + dtype_is_object, + from_mvs->memview->typeinfo); + if (unlikely(!memview_obj)) + goto fail; + if (unlikely(__Pyx_init_memviewslice(memview_obj, ndim, &new_mvs, 1) < 0)) + goto fail; + if (unlikely(__pyx_memoryview_copy_contents(*from_mvs, new_mvs, ndim, ndim, + dtype_is_object) < 0)) + goto fail; + goto no_fail; +fail: + __Pyx_XDECREF(new_mvs.memview); + new_mvs.memview = NULL; + new_mvs.data = NULL; +no_fail: + __Pyx_XDECREF(shape_tuple); + __Pyx_XDECREF(temp_int); + __Pyx_XDECREF(array_obj); + __Pyx_RefNannyFinishContext(); + return new_mvs; +} + +/* MemviewSliceInit */ + static int +__Pyx_init_memviewslice(struct __pyx_memoryview_obj *memview, + int ndim, + __Pyx_memviewslice *memviewslice, + int memview_is_new_reference) +{ + __Pyx_RefNannyDeclarations + int i, retval=-1; + Py_buffer *buf = &memview->view; + __Pyx_RefNannySetupContext("init_memviewslice", 0); + if (unlikely(memviewslice->memview || memviewslice->data)) { + PyErr_SetString(PyExc_ValueError, + "memviewslice is already initialized!"); + goto fail; + } + if (buf->strides) { + for (i = 0; i < ndim; i++) { + memviewslice->strides[i] = buf->strides[i]; + } + } else { + Py_ssize_t stride = buf->itemsize; + for (i = ndim - 1; i >= 0; i--) { + memviewslice->strides[i] = stride; + stride *= buf->shape[i]; + } + } + for (i = 0; i < ndim; i++) { + memviewslice->shape[i] = buf->shape[i]; + if (buf->suboffsets) { + memviewslice->suboffsets[i] = buf->suboffsets[i]; + } else { + memviewslice->suboffsets[i] = -1; + } + } + memviewslice->memview = memview; + memviewslice->data = (char *)buf->buf; + if (__pyx_add_acquisition_count(memview) == 0 && !memview_is_new_reference) { + Py_INCREF(memview); + } + retval = 0; + goto no_fail; +fail: + memviewslice->memview = 0; + memviewslice->data = 0; + retval = -1; +no_fail: + __Pyx_RefNannyFinishContext(); + return retval; +} +#ifndef Py_NO_RETURN +#define Py_NO_RETURN +#endif +static void __pyx_fatalerror(const char *fmt, ...) Py_NO_RETURN { + va_list vargs; + char msg[200]; +#if PY_VERSION_HEX >= 0x030A0000 || defined(HAVE_STDARG_PROTOTYPES) + va_start(vargs, fmt); +#else + va_start(vargs); +#endif + vsnprintf(msg, 200, fmt, vargs); + va_end(vargs); + Py_FatalError(msg); +} +static CYTHON_INLINE int +__pyx_add_acquisition_count_locked(__pyx_atomic_int_type *acquisition_count, + PyThread_type_lock lock) +{ + int result; + PyThread_acquire_lock(lock, 1); + result = (*acquisition_count)++; + PyThread_release_lock(lock); + return result; +} +static CYTHON_INLINE int +__pyx_sub_acquisition_count_locked(__pyx_atomic_int_type *acquisition_count, + PyThread_type_lock lock) +{ + int result; + PyThread_acquire_lock(lock, 1); + result = (*acquisition_count)--; + PyThread_release_lock(lock); + return result; +} +static CYTHON_INLINE void +__Pyx_INC_MEMVIEW(__Pyx_memviewslice *memslice, int have_gil, int lineno) +{ + __pyx_nonatomic_int_type old_acquisition_count; + struct __pyx_memoryview_obj *memview = memslice->memview; + if (unlikely(!memview || (PyObject *) memview == Py_None)) { + return; + } + old_acquisition_count = __pyx_add_acquisition_count(memview); + if (unlikely(old_acquisition_count <= 0)) { + if (likely(old_acquisition_count == 0)) { + if (have_gil) { + Py_INCREF((PyObject *) memview); + } else { + PyGILState_STATE _gilstate = PyGILState_Ensure(); + Py_INCREF((PyObject *) memview); + PyGILState_Release(_gilstate); + } + } else { + __pyx_fatalerror("Acquisition count is %d (line %d)", + old_acquisition_count+1, lineno); + } + } +} +static CYTHON_INLINE void __Pyx_XCLEAR_MEMVIEW(__Pyx_memviewslice *memslice, + int have_gil, int lineno) { + __pyx_nonatomic_int_type old_acquisition_count; + struct __pyx_memoryview_obj *memview = memslice->memview; + if (unlikely(!memview || (PyObject *) memview == Py_None)) { + memslice->memview = NULL; + return; + } + old_acquisition_count = __pyx_sub_acquisition_count(memview); + memslice->data = NULL; + if (likely(old_acquisition_count > 1)) { + memslice->memview = NULL; + } else if (likely(old_acquisition_count == 1)) { + if (have_gil) { + Py_CLEAR(memslice->memview); + } else { + PyGILState_STATE _gilstate = PyGILState_Ensure(); + Py_CLEAR(memslice->memview); + PyGILState_Release(_gilstate); + } + } else { + __pyx_fatalerror("Acquisition count is %d (line %d)", + old_acquisition_count-1, lineno); + } +} + +/* CIntFromPy */ + static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(int) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(int, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (int) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 2 * PyLong_SHIFT)) { + return (int) (((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 3 * PyLong_SHIFT)) { + return (int) (((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 4 * PyLong_SHIFT)) { + return (int) (((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(int) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(int) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) ((((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) ((((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) ((((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(int) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + int val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (int) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (int) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (int) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (int) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(int) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(int) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((int) 1) << (sizeof(int) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (int) -1; + } + } else { + int val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (int) -1; + val = __Pyx_PyInt_As_int(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to int"); + return (int) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to int"); + return (int) -1; +} + +/* CIntToPy */ + static CYTHON_INLINE PyObject* __Pyx_PyInt_From_int(int value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(int) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(int) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(int) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(int) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(int) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; +#if !CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030d0000 + return _PyLong_FromByteArray(bytes, sizeof(int), + little, !is_unsigned); +#else + PyObject *from_bytes, *result = NULL; + PyObject *py_bytes = NULL, *arg_tuple = NULL, *kwds = NULL, *order_str = NULL; + from_bytes = PyObject_GetAttrString((PyObject*)&PyLong_Type, "from_bytes"); + if (!from_bytes) return NULL; + py_bytes = PyBytes_FromStringAndSize((char*)bytes, sizeof(int)); + if (!py_bytes) goto limited_bad; + order_str = PyUnicode_FromString(little ? "little" : "big"); + if (!order_str) goto limited_bad; + arg_tuple = PyTuple_Pack(2, py_bytes, order_str); + if (!arg_tuple) goto limited_bad; + if (!is_unsigned) { + kwds = PyDict_New(); + if (!kwds) goto limited_bad; + if (PyDict_SetItemString(kwds, "signed", __Pyx_NewRef(Py_True))) goto limited_bad; + } + result = PyObject_Call(from_bytes, arg_tuple, kwds); + limited_bad: + Py_XDECREF(kwds); + Py_XDECREF(arg_tuple); + Py_XDECREF(order_str); + Py_XDECREF(py_bytes); + Py_XDECREF(from_bytes); + return result; +#endif + } +} + +/* CIntFromPy */ + static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(long) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(long, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (long) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 2 * PyLong_SHIFT)) { + return (long) (((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 3 * PyLong_SHIFT)) { + return (long) (((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 4 * PyLong_SHIFT)) { + return (long) (((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(long) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(long) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) ((((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) ((((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) ((((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(long) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + long val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (long) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (long) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (long) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (long) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(long) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(long) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((long) 1) << (sizeof(long) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (long) -1; + } + } else { + long val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (long) -1; + val = __Pyx_PyInt_As_long(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to long"); + return (long) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to long"); + return (long) -1; +} + +/* CIntToPy */ + static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(long) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(long) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(long) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; +#if !CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030d0000 + return _PyLong_FromByteArray(bytes, sizeof(long), + little, !is_unsigned); +#else + PyObject *from_bytes, *result = NULL; + PyObject *py_bytes = NULL, *arg_tuple = NULL, *kwds = NULL, *order_str = NULL; + from_bytes = PyObject_GetAttrString((PyObject*)&PyLong_Type, "from_bytes"); + if (!from_bytes) return NULL; + py_bytes = PyBytes_FromStringAndSize((char*)bytes, sizeof(long)); + if (!py_bytes) goto limited_bad; + order_str = PyUnicode_FromString(little ? "little" : "big"); + if (!order_str) goto limited_bad; + arg_tuple = PyTuple_Pack(2, py_bytes, order_str); + if (!arg_tuple) goto limited_bad; + if (!is_unsigned) { + kwds = PyDict_New(); + if (!kwds) goto limited_bad; + if (PyDict_SetItemString(kwds, "signed", __Pyx_NewRef(Py_True))) goto limited_bad; + } + result = PyObject_Call(from_bytes, arg_tuple, kwds); + limited_bad: + Py_XDECREF(kwds); + Py_XDECREF(arg_tuple); + Py_XDECREF(order_str); + Py_XDECREF(py_bytes); + Py_XDECREF(from_bytes); + return result; +#endif + } +} + +/* CIntFromPy */ + static CYTHON_INLINE size_t __Pyx_PyInt_As_size_t(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const size_t neg_one = (size_t) -1, const_zero = (size_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(size_t) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(size_t, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (size_t) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(size_t, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(size_t) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) >= 2 * PyLong_SHIFT)) { + return (size_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(size_t) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) >= 3 * PyLong_SHIFT)) { + return (size_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(size_t) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) >= 4 * PyLong_SHIFT)) { + return (size_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (size_t) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(size_t) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(size_t) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(size_t, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(size_t) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 2 * PyLong_SHIFT)) { + return (size_t) (((size_t)-1)*(((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(size_t) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 2 * PyLong_SHIFT)) { + return (size_t) ((((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(size_t) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 3 * PyLong_SHIFT)) { + return (size_t) (((size_t)-1)*(((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(size_t) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 3 * PyLong_SHIFT)) { + return (size_t) ((((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(size_t) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 4 * PyLong_SHIFT)) { + return (size_t) (((size_t)-1)*(((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(size_t) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 4 * PyLong_SHIFT)) { + return (size_t) ((((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(size_t) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(size_t) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + size_t val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (size_t) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (size_t) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (size_t) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (size_t) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (size_t) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(size_t) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((size_t) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(size_t) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((size_t) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((size_t) 1) << (sizeof(size_t) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (size_t) -1; + } + } else { + size_t val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (size_t) -1; + val = __Pyx_PyInt_As_size_t(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to size_t"); + return (size_t) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to size_t"); + return (size_t) -1; +} + +/* CIntFromPy */ + static CYTHON_INLINE char __Pyx_PyInt_As_char(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const char neg_one = (char) -1, const_zero = (char) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(char) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(char, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (char) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(char, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(char) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) >= 2 * PyLong_SHIFT)) { + return (char) (((((char)digits[1]) << PyLong_SHIFT) | (char)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(char) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) >= 3 * PyLong_SHIFT)) { + return (char) (((((((char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(char) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) >= 4 * PyLong_SHIFT)) { + return (char) (((((((((char)digits[3]) << PyLong_SHIFT) | (char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (char) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(char) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(char, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(char) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(char, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(char, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(char) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 2 * PyLong_SHIFT)) { + return (char) (((char)-1)*(((((char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(char) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 2 * PyLong_SHIFT)) { + return (char) ((((((char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(char) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 3 * PyLong_SHIFT)) { + return (char) (((char)-1)*(((((((char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(char) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 3 * PyLong_SHIFT)) { + return (char) ((((((((char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(char) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 4 * PyLong_SHIFT)) { + return (char) (((char)-1)*(((((((((char)digits[3]) << PyLong_SHIFT) | (char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(char) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 4 * PyLong_SHIFT)) { + return (char) ((((((((((char)digits[3]) << PyLong_SHIFT) | (char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(char) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(char, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(char) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(char, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + char val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (char) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (char) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (char) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (char) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (char) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(char) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((char) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(char) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((char) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((char) 1) << (sizeof(char) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (char) -1; + } + } else { + char val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (char) -1; + val = __Pyx_PyInt_As_char(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to char"); + return (char) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to char"); + return (char) -1; +} + +/* FormatTypeName */ + #if CYTHON_COMPILING_IN_LIMITED_API +static __Pyx_TypeName +__Pyx_PyType_GetName(PyTypeObject* tp) +{ + PyObject *name = __Pyx_PyObject_GetAttrStr((PyObject *)tp, + __pyx_n_s_name_2); + if (unlikely(name == NULL) || unlikely(!PyUnicode_Check(name))) { + PyErr_Clear(); + Py_XDECREF(name); + name = __Pyx_NewRef(__pyx_n_s__94); + } + return name; +} +#endif + +/* CheckBinaryVersion */ + static unsigned long __Pyx_get_runtime_version(void) { +#if __PYX_LIMITED_VERSION_HEX >= 0x030B00A4 + return Py_Version & ~0xFFUL; +#else + const char* rt_version = Py_GetVersion(); + unsigned long version = 0; + unsigned long factor = 0x01000000UL; + unsigned int digit = 0; + int i = 0; + while (factor) { + while ('0' <= rt_version[i] && rt_version[i] <= '9') { + digit = digit * 10 + (unsigned int) (rt_version[i] - '0'); + ++i; + } + version += factor * digit; + if (rt_version[i] != '.') + break; + digit = 0; + factor >>= 8; + ++i; + } + return version; +#endif +} +static int __Pyx_check_binary_version(unsigned long ct_version, unsigned long rt_version, int allow_newer) { + const unsigned long MAJOR_MINOR = 0xFFFF0000UL; + if ((rt_version & MAJOR_MINOR) == (ct_version & MAJOR_MINOR)) + return 0; + if (likely(allow_newer && (rt_version & MAJOR_MINOR) > (ct_version & MAJOR_MINOR))) + return 1; + { + char message[200]; + PyOS_snprintf(message, sizeof(message), + "compile time Python version %d.%d " + "of module '%.100s' " + "%s " + "runtime version %d.%d", + (int) (ct_version >> 24), (int) ((ct_version >> 16) & 0xFF), + __Pyx_MODULE_NAME, + (allow_newer) ? "was newer than" : "does not match", + (int) (rt_version >> 24), (int) ((rt_version >> 16) & 0xFF) + ); + return PyErr_WarnEx(NULL, message, 1); + } +} + +/* InitStrings */ + #if PY_MAJOR_VERSION >= 3 +static int __Pyx_InitString(__Pyx_StringTabEntry t, PyObject **str) { + if (t.is_unicode | t.is_str) { + if (t.intern) { + *str = PyUnicode_InternFromString(t.s); + } else if (t.encoding) { + *str = PyUnicode_Decode(t.s, t.n - 1, t.encoding, NULL); + } else { + *str = PyUnicode_FromStringAndSize(t.s, t.n - 1); + } + } else { + *str = PyBytes_FromStringAndSize(t.s, t.n - 1); + } + if (!*str) + return -1; + if (PyObject_Hash(*str) == -1) + return -1; + return 0; +} +#endif +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t) { + while (t->p) { + #if PY_MAJOR_VERSION >= 3 + __Pyx_InitString(*t, t->p); + #else + if (t->is_unicode) { + *t->p = PyUnicode_DecodeUTF8(t->s, t->n - 1, NULL); + } else if (t->intern) { + *t->p = PyString_InternFromString(t->s); + } else { + *t->p = PyString_FromStringAndSize(t->s, t->n - 1); + } + if (!*t->p) + return -1; + if (PyObject_Hash(*t->p) == -1) + return -1; + #endif + ++t; + } + return 0; +} + +#include +static CYTHON_INLINE Py_ssize_t __Pyx_ssize_strlen(const char *s) { + size_t len = strlen(s); + if (unlikely(len > (size_t) PY_SSIZE_T_MAX)) { + PyErr_SetString(PyExc_OverflowError, "byte string is too long"); + return -1; + } + return (Py_ssize_t) len; +} +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char* c_str) { + Py_ssize_t len = __Pyx_ssize_strlen(c_str); + if (unlikely(len < 0)) return NULL; + return __Pyx_PyUnicode_FromStringAndSize(c_str, len); +} +static CYTHON_INLINE PyObject* __Pyx_PyByteArray_FromString(const char* c_str) { + Py_ssize_t len = __Pyx_ssize_strlen(c_str); + if (unlikely(len < 0)) return NULL; + return PyByteArray_FromStringAndSize(c_str, len); +} +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject* o) { + Py_ssize_t ignore; + return __Pyx_PyObject_AsStringAndSize(o, &ignore); +} +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +#if !CYTHON_PEP393_ENABLED +static const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + char* defenc_c; + PyObject* defenc = _PyUnicode_AsDefaultEncodedString(o, NULL); + if (!defenc) return NULL; + defenc_c = PyBytes_AS_STRING(defenc); +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + { + char* end = defenc_c + PyBytes_GET_SIZE(defenc); + char* c; + for (c = defenc_c; c < end; c++) { + if ((unsigned char) (*c) >= 128) { + PyUnicode_AsASCIIString(o); + return NULL; + } + } + } +#endif + *length = PyBytes_GET_SIZE(defenc); + return defenc_c; +} +#else +static CYTHON_INLINE const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + if (unlikely(__Pyx_PyUnicode_READY(o) == -1)) return NULL; +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + if (likely(PyUnicode_IS_ASCII(o))) { + *length = PyUnicode_GET_LENGTH(o); + return PyUnicode_AsUTF8(o); + } else { + PyUnicode_AsASCIIString(o); + return NULL; + } +#else + return PyUnicode_AsUTF8AndSize(o, length); +#endif +} +#endif +#endif +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject* o, Py_ssize_t *length) { +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT + if ( +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + __Pyx_sys_getdefaultencoding_not_ascii && +#endif + PyUnicode_Check(o)) { + return __Pyx_PyUnicode_AsStringAndSize(o, length); + } else +#endif +#if (!CYTHON_COMPILING_IN_PYPY && !CYTHON_COMPILING_IN_LIMITED_API) || (defined(PyByteArray_AS_STRING) && defined(PyByteArray_GET_SIZE)) + if (PyByteArray_Check(o)) { + *length = PyByteArray_GET_SIZE(o); + return PyByteArray_AS_STRING(o); + } else +#endif + { + char* result; + int r = PyBytes_AsStringAndSize(o, &result, length); + if (unlikely(r < 0)) { + return NULL; + } else { + return result; + } + } +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject* x) { + int is_true = x == Py_True; + if (is_true | (x == Py_False) | (x == Py_None)) return is_true; + else return PyObject_IsTrue(x); +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject* x) { + int retval; + if (unlikely(!x)) return -1; + retval = __Pyx_PyObject_IsTrue(x); + Py_DECREF(x); + return retval; +} +static PyObject* __Pyx_PyNumber_IntOrLongWrongResultType(PyObject* result, const char* type_name) { + __Pyx_TypeName result_type_name = __Pyx_PyType_GetName(Py_TYPE(result)); +#if PY_MAJOR_VERSION >= 3 + if (PyLong_Check(result)) { + if (PyErr_WarnFormat(PyExc_DeprecationWarning, 1, + "__int__ returned non-int (type " __Pyx_FMT_TYPENAME "). " + "The ability to return an instance of a strict subclass of int is deprecated, " + "and may be removed in a future version of Python.", + result_type_name)) { + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; + } + __Pyx_DECREF_TypeName(result_type_name); + return result; + } +#endif + PyErr_Format(PyExc_TypeError, + "__%.4s__ returned non-%.4s (type " __Pyx_FMT_TYPENAME ")", + type_name, type_name, result_type_name); + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x) { +#if CYTHON_USE_TYPE_SLOTS + PyNumberMethods *m; +#endif + const char *name = NULL; + PyObject *res = NULL; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x) || PyLong_Check(x))) +#else + if (likely(PyLong_Check(x))) +#endif + return __Pyx_NewRef(x); +#if CYTHON_USE_TYPE_SLOTS + m = Py_TYPE(x)->tp_as_number; + #if PY_MAJOR_VERSION < 3 + if (m && m->nb_int) { + name = "int"; + res = m->nb_int(x); + } + else if (m && m->nb_long) { + name = "long"; + res = m->nb_long(x); + } + #else + if (likely(m && m->nb_int)) { + name = "int"; + res = m->nb_int(x); + } + #endif +#else + if (!PyBytes_CheckExact(x) && !PyUnicode_CheckExact(x)) { + res = PyNumber_Int(x); + } +#endif + if (likely(res)) { +#if PY_MAJOR_VERSION < 3 + if (unlikely(!PyInt_Check(res) && !PyLong_Check(res))) { +#else + if (unlikely(!PyLong_CheckExact(res))) { +#endif + return __Pyx_PyNumber_IntOrLongWrongResultType(res, name); + } + } + else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_TypeError, + "an integer is required"); + } + return res; +} +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject* b) { + Py_ssize_t ival; + PyObject *x; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_CheckExact(b))) { + if (sizeof(Py_ssize_t) >= sizeof(long)) + return PyInt_AS_LONG(b); + else + return PyInt_AsSsize_t(b); + } +#endif + if (likely(PyLong_CheckExact(b))) { + #if CYTHON_USE_PYLONG_INTERNALS + if (likely(__Pyx_PyLong_IsCompact(b))) { + return __Pyx_PyLong_CompactValue(b); + } else { + const digit* digits = __Pyx_PyLong_Digits(b); + const Py_ssize_t size = __Pyx_PyLong_SignedDigitCount(b); + switch (size) { + case 2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return (Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + } + } + #endif + return PyLong_AsSsize_t(b); + } + x = PyNumber_Index(b); + if (!x) return -1; + ival = PyInt_AsSsize_t(x); + Py_DECREF(x); + return ival; +} +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject* o) { + if (sizeof(Py_hash_t) == sizeof(Py_ssize_t)) { + return (Py_hash_t) __Pyx_PyIndex_AsSsize_t(o); +#if PY_MAJOR_VERSION < 3 + } else if (likely(PyInt_CheckExact(o))) { + return PyInt_AS_LONG(o); +#endif + } else { + Py_ssize_t ival; + PyObject *x; + x = PyNumber_Index(o); + if (!x) return -1; + ival = PyInt_AsLong(x); + Py_DECREF(x); + return ival; + } +} +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b) { + return b ? __Pyx_NewRef(Py_True) : __Pyx_NewRef(Py_False); +} +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t ival) { + return PyInt_FromSize_t(ival); +} + + +/* #### Code section: utility_code_pragmas_end ### */ +#ifdef _MSC_VER +#pragma warning( pop ) +#endif + + + +/* #### Code section: end ### */ +#endif /* Py_PYTHON_H */ diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_ocp_solver_pyx.so b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_ocp_solver_pyx.so new file mode 100755 index 0000000..6f6f3e8 Binary files /dev/null and b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_ocp_solver_pyx.so differ diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_sim_solver_lat.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_sim_solver_lat.c new file mode 100644 index 0000000..0594aa2 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_sim_solver_lat.c @@ -0,0 +1,290 @@ +/* + * Copyright (c) The acados authors. + * + * This file is part of acados. + * + * The 2-Clause BSD License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE.; + */ +// standard +#include +#include + +// acados +#include "acados_c/external_function_interface.h" +#include "acados_c/sim_interface.h" +#include "acados_c/external_function_interface.h" + +#include "acados/sim/sim_common.h" +#include "acados/utils/external_function_generic.h" +#include "acados/utils/print.h" + + +// example specific +#include "lat_model/lat_model.h" +#include "acados_sim_solver_lat.h" + + +// ** solver data ** + +sim_solver_capsule * lat_acados_sim_solver_create_capsule() +{ + void* capsule_mem = malloc(sizeof(sim_solver_capsule)); + sim_solver_capsule *capsule = (sim_solver_capsule *) capsule_mem; + + return capsule; +} + + +int lat_acados_sim_solver_free_capsule(sim_solver_capsule * capsule) +{ + free(capsule); + return 0; +} + + +int lat_acados_sim_create(sim_solver_capsule * capsule) +{ + // initialize + const int nx = LAT_NX; + const int nu = LAT_NU; + const int nz = LAT_NZ; + const int np = LAT_NP; + bool tmp_bool; + + + double Tsim = 0.009765625; + + + // explicit ode + capsule->sim_forw_vde_casadi = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)); + capsule->sim_vde_adj_casadi = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)); + capsule->sim_expl_ode_fun_casadi = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)); + + capsule->sim_forw_vde_casadi->casadi_fun = &lat_expl_vde_forw; + capsule->sim_forw_vde_casadi->casadi_n_in = &lat_expl_vde_forw_n_in; + capsule->sim_forw_vde_casadi->casadi_n_out = &lat_expl_vde_forw_n_out; + capsule->sim_forw_vde_casadi->casadi_sparsity_in = &lat_expl_vde_forw_sparsity_in; + capsule->sim_forw_vde_casadi->casadi_sparsity_out = &lat_expl_vde_forw_sparsity_out; + capsule->sim_forw_vde_casadi->casadi_work = &lat_expl_vde_forw_work; + external_function_param_casadi_create(capsule->sim_forw_vde_casadi, np); + + capsule->sim_vde_adj_casadi->casadi_fun = &lat_expl_vde_adj; + capsule->sim_vde_adj_casadi->casadi_n_in = &lat_expl_vde_adj_n_in; + capsule->sim_vde_adj_casadi->casadi_n_out = &lat_expl_vde_adj_n_out; + capsule->sim_vde_adj_casadi->casadi_sparsity_in = &lat_expl_vde_adj_sparsity_in; + capsule->sim_vde_adj_casadi->casadi_sparsity_out = &lat_expl_vde_adj_sparsity_out; + capsule->sim_vde_adj_casadi->casadi_work = &lat_expl_vde_adj_work; + external_function_param_casadi_create(capsule->sim_vde_adj_casadi, np); + + capsule->sim_expl_ode_fun_casadi->casadi_fun = &lat_expl_ode_fun; + capsule->sim_expl_ode_fun_casadi->casadi_n_in = &lat_expl_ode_fun_n_in; + capsule->sim_expl_ode_fun_casadi->casadi_n_out = &lat_expl_ode_fun_n_out; + capsule->sim_expl_ode_fun_casadi->casadi_sparsity_in = &lat_expl_ode_fun_sparsity_in; + capsule->sim_expl_ode_fun_casadi->casadi_sparsity_out = &lat_expl_ode_fun_sparsity_out; + capsule->sim_expl_ode_fun_casadi->casadi_work = &lat_expl_ode_fun_work; + external_function_param_casadi_create(capsule->sim_expl_ode_fun_casadi, np); + + + + // sim plan & config + sim_solver_plan_t plan; + plan.sim_solver = ERK; + + // create correct config based on plan + sim_config * lat_sim_config = sim_config_create(plan); + capsule->acados_sim_config = lat_sim_config; + + // sim dims + void *lat_sim_dims = sim_dims_create(lat_sim_config); + capsule->acados_sim_dims = lat_sim_dims; + sim_dims_set(lat_sim_config, lat_sim_dims, "nx", &nx); + sim_dims_set(lat_sim_config, lat_sim_dims, "nu", &nu); + sim_dims_set(lat_sim_config, lat_sim_dims, "nz", &nz); + + + // sim opts + sim_opts *lat_sim_opts = sim_opts_create(lat_sim_config, lat_sim_dims); + capsule->acados_sim_opts = lat_sim_opts; + int tmp_int = 3; + sim_opts_set(lat_sim_config, lat_sim_opts, "newton_iter", &tmp_int); + double tmp_double = 0.0; + sim_opts_set(lat_sim_config, lat_sim_opts, "newton_tol", &tmp_double); + sim_collocation_type collocation_type = GAUSS_LEGENDRE; + sim_opts_set(lat_sim_config, lat_sim_opts, "collocation_type", &collocation_type); + + + tmp_int = 4; + sim_opts_set(lat_sim_config, lat_sim_opts, "num_stages", &tmp_int); + tmp_int = 1; + sim_opts_set(lat_sim_config, lat_sim_opts, "num_steps", &tmp_int); + tmp_bool = 0; + sim_opts_set(lat_sim_config, lat_sim_opts, "jac_reuse", &tmp_bool); + + + // sim in / out + sim_in *lat_sim_in = sim_in_create(lat_sim_config, lat_sim_dims); + capsule->acados_sim_in = lat_sim_in; + sim_out *lat_sim_out = sim_out_create(lat_sim_config, lat_sim_dims); + capsule->acados_sim_out = lat_sim_out; + + sim_in_set(lat_sim_config, lat_sim_dims, + lat_sim_in, "T", &Tsim); + + // model functions + lat_sim_config->model_set(lat_sim_in->model, + "expl_vde_forw", capsule->sim_forw_vde_casadi); + lat_sim_config->model_set(lat_sim_in->model, + "expl_vde_adj", capsule->sim_vde_adj_casadi); + lat_sim_config->model_set(lat_sim_in->model, + "expl_ode_fun", capsule->sim_expl_ode_fun_casadi); + + // sim solver + sim_solver *lat_sim_solver = sim_solver_create(lat_sim_config, + lat_sim_dims, lat_sim_opts); + capsule->acados_sim_solver = lat_sim_solver; + + + /* initialize parameter values */ + double* p = calloc(np, sizeof(double)); + + + lat_acados_sim_update_params(capsule, p, np); + free(p); + + + /* initialize input */ + // x + double x0[4]; + for (int ii = 0; ii < 4; ii++) + x0[ii] = 0.0; + + sim_in_set(lat_sim_config, lat_sim_dims, + lat_sim_in, "x", x0); + + + // u + double u0[1]; + for (int ii = 0; ii < 1; ii++) + u0[ii] = 0.0; + + sim_in_set(lat_sim_config, lat_sim_dims, + lat_sim_in, "u", u0); + + // S_forw + double S_forw[20]; + for (int ii = 0; ii < 20; ii++) + S_forw[ii] = 0.0; + for (int ii = 0; ii < 4; ii++) + S_forw[ii + ii * 4 ] = 1.0; + + + sim_in_set(lat_sim_config, lat_sim_dims, + lat_sim_in, "S_forw", S_forw); + + int status = sim_precompute(lat_sim_solver, lat_sim_in, lat_sim_out); + + return status; +} + + +int lat_acados_sim_solve(sim_solver_capsule *capsule) +{ + // integrate dynamics using acados sim_solver + int status = sim_solve(capsule->acados_sim_solver, + capsule->acados_sim_in, capsule->acados_sim_out); + if (status != 0) + printf("error in lat_acados_sim_solve()! Exiting.\n"); + + return status; +} + + +int lat_acados_sim_free(sim_solver_capsule *capsule) +{ + // free memory + sim_solver_destroy(capsule->acados_sim_solver); + sim_in_destroy(capsule->acados_sim_in); + sim_out_destroy(capsule->acados_sim_out); + sim_opts_destroy(capsule->acados_sim_opts); + sim_dims_destroy(capsule->acados_sim_dims); + sim_config_destroy(capsule->acados_sim_config); + + // free external function + external_function_param_casadi_free(capsule->sim_forw_vde_casadi); + external_function_param_casadi_free(capsule->sim_vde_adj_casadi); + external_function_param_casadi_free(capsule->sim_expl_ode_fun_casadi); + + return 0; +} + + +int lat_acados_sim_update_params(sim_solver_capsule *capsule, double *p, int np) +{ + int status = 0; + int casadi_np = LAT_NP; + + if (casadi_np != np) { + printf("lat_acados_sim_update_params: trying to set %i parameters for external functions." + " External function has %i parameters. Exiting.\n", np, casadi_np); + exit(1); + } + capsule->sim_forw_vde_casadi[0].set_param(capsule->sim_forw_vde_casadi, p); + capsule->sim_vde_adj_casadi[0].set_param(capsule->sim_vde_adj_casadi, p); + capsule->sim_expl_ode_fun_casadi[0].set_param(capsule->sim_expl_ode_fun_casadi, p); + + return status; +} + +/* getters pointers to C objects*/ +sim_config * lat_acados_get_sim_config(sim_solver_capsule *capsule) +{ + return capsule->acados_sim_config; +}; + +sim_in * lat_acados_get_sim_in(sim_solver_capsule *capsule) +{ + return capsule->acados_sim_in; +}; + +sim_out * lat_acados_get_sim_out(sim_solver_capsule *capsule) +{ + return capsule->acados_sim_out; +}; + +void * lat_acados_get_sim_dims(sim_solver_capsule *capsule) +{ + return capsule->acados_sim_dims; +}; + +sim_opts * lat_acados_get_sim_opts(sim_solver_capsule *capsule) +{ + return capsule->acados_sim_opts; +}; + +sim_solver * lat_acados_get_sim_solver(sim_solver_capsule *capsule) +{ + return capsule->acados_sim_solver; +}; + diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_solver.pxd b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_solver.pxd new file mode 100644 index 0000000..208a515 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_solver.pxd @@ -0,0 +1,62 @@ +# +# Copyright (c) The acados authors. +# +# This file is part of acados. +# +# The 2-Clause BSD License +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are met: +# +# 1. Redistributions of source code must retain the above copyright notice, +# this list of conditions and the following disclaimer. +# +# 2. Redistributions in binary form must reproduce the above copyright notice, +# this list of conditions and the following disclaimer in the documentation +# and/or other materials provided with the distribution. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE +# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE.; +# + +cimport acados_solver_common + +cdef extern from "acados_solver_lat.h": + ctypedef struct nlp_solver_capsule "lat_solver_capsule": + pass + + nlp_solver_capsule * acados_create_capsule "lat_acados_create_capsule"() + int acados_free_capsule "lat_acados_free_capsule"(nlp_solver_capsule *capsule) + + int acados_create "lat_acados_create"(nlp_solver_capsule * capsule) + + int acados_create_with_discretization "lat_acados_create_with_discretization"(nlp_solver_capsule * capsule, int n_time_steps, double* new_time_steps) + int acados_update_time_steps "lat_acados_update_time_steps"(nlp_solver_capsule * capsule, int N, double* new_time_steps) + int acados_update_qp_solver_cond_N "lat_acados_update_qp_solver_cond_N"(nlp_solver_capsule * capsule, int qp_solver_cond_N) + + int acados_update_params "lat_acados_update_params"(nlp_solver_capsule * capsule, int stage, double *value, int np_) + int acados_update_params_sparse "lat_acados_update_params_sparse"(nlp_solver_capsule * capsule, int stage, int *idx, double *p, int n_update) + int acados_solve "lat_acados_solve"(nlp_solver_capsule * capsule) + int acados_reset "lat_acados_reset"(nlp_solver_capsule * capsule, int reset_qp_solver_mem) + int acados_free "lat_acados_free"(nlp_solver_capsule * capsule) + void acados_print_stats "lat_acados_print_stats"(nlp_solver_capsule * capsule) + + int acados_custom_update "lat_acados_custom_update"(nlp_solver_capsule* capsule, double * data, int data_len) + + acados_solver_common.ocp_nlp_in *acados_get_nlp_in "lat_acados_get_nlp_in"(nlp_solver_capsule * capsule) + acados_solver_common.ocp_nlp_out *acados_get_nlp_out "lat_acados_get_nlp_out"(nlp_solver_capsule * capsule) + acados_solver_common.ocp_nlp_out *acados_get_sens_out "lat_acados_get_sens_out"(nlp_solver_capsule * capsule) + acados_solver_common.ocp_nlp_solver *acados_get_nlp_solver "lat_acados_get_nlp_solver"(nlp_solver_capsule * capsule) + acados_solver_common.ocp_nlp_config *acados_get_nlp_config "lat_acados_get_nlp_config"(nlp_solver_capsule * capsule) + void *acados_get_nlp_opts "lat_acados_get_nlp_opts"(nlp_solver_capsule * capsule) + acados_solver_common.ocp_nlp_dims *acados_get_nlp_dims "lat_acados_get_nlp_dims"(nlp_solver_capsule * capsule) + acados_solver_common.ocp_nlp_plan *acados_get_nlp_plan "lat_acados_get_nlp_plan"(nlp_solver_capsule * capsule) diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_solver_lat.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_solver_lat.c new file mode 100644 index 0000000..3ecc293 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/acados_solver_lat.c @@ -0,0 +1,1034 @@ +/* + * Copyright (c) The acados authors. + * + * This file is part of acados. + * + * The 2-Clause BSD License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE.; + */ + +// standard +#include +#include +#include +// acados +// #include "acados/utils/print.h" +#include "acados_c/ocp_nlp_interface.h" +#include "acados_c/external_function_interface.h" + +// example specific +#include "lat_model/lat_model.h" +#include "lat_constraints/lat_constraints.h" +#include "lat_cost/lat_cost.h" + + + + +#include "acados_solver_lat.h" + +#define NX LAT_NX +#define NZ LAT_NZ +#define NU LAT_NU +#define NP LAT_NP +#define NBX LAT_NBX +#define NBX0 LAT_NBX0 +#define NBU LAT_NBU +#define NSBX LAT_NSBX +#define NSBU LAT_NSBU +#define NSH LAT_NSH +#define NSG LAT_NSG +#define NSPHI LAT_NSPHI +#define NSHN LAT_NSHN +#define NSGN LAT_NSGN +#define NSPHIN LAT_NSPHIN +#define NSBXN LAT_NSBXN +#define NS LAT_NS +#define NSN LAT_NSN +#define NG LAT_NG +#define NBXN LAT_NBXN +#define NGN LAT_NGN +#define NY0 LAT_NY0 +#define NY LAT_NY +#define NYN LAT_NYN +// #define N LAT_N +#define NH LAT_NH +#define NPHI LAT_NPHI +#define NHN LAT_NHN +#define NPHIN LAT_NPHIN +#define NR LAT_NR + + +// ** solver data ** + +lat_solver_capsule * lat_acados_create_capsule(void) +{ + void* capsule_mem = malloc(sizeof(lat_solver_capsule)); + lat_solver_capsule *capsule = (lat_solver_capsule *) capsule_mem; + + return capsule; +} + + +int lat_acados_free_capsule(lat_solver_capsule *capsule) +{ + free(capsule); + return 0; +} + + +int lat_acados_create(lat_solver_capsule* capsule) +{ + int N_shooting_intervals = LAT_N; + double* new_time_steps = NULL; // NULL -> don't alter the code generated time-steps + return lat_acados_create_with_discretization(capsule, N_shooting_intervals, new_time_steps); +} + + +int lat_acados_update_time_steps(lat_solver_capsule* capsule, int N, double* new_time_steps) +{ + if (N != capsule->nlp_solver_plan->N) { + fprintf(stderr, "lat_acados_update_time_steps: given number of time steps (= %d) " \ + "differs from the currently allocated number of " \ + "time steps (= %d)!\n" \ + "Please recreate with new discretization and provide a new vector of time_stamps!\n", + N, capsule->nlp_solver_plan->N); + return 1; + } + + ocp_nlp_config * nlp_config = capsule->nlp_config; + ocp_nlp_dims * nlp_dims = capsule->nlp_dims; + ocp_nlp_in * nlp_in = capsule->nlp_in; + + for (int i = 0; i < N; i++) + { + ocp_nlp_in_set(nlp_config, nlp_dims, nlp_in, i, "Ts", &new_time_steps[i]); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "scaling", &new_time_steps[i]); + } + return 0; +} + +/** + * Internal function for lat_acados_create: step 1 + */ +void lat_acados_create_1_set_plan(ocp_nlp_plan_t* nlp_solver_plan, const int N) +{ + assert(N == nlp_solver_plan->N); + + /************************************************ + * plan + ************************************************/ + nlp_solver_plan->nlp_solver = SQP_RTI; + + nlp_solver_plan->ocp_qp_solver_plan.qp_solver = PARTIAL_CONDENSING_HPIPM; + + nlp_solver_plan->nlp_cost[0] = NONLINEAR_LS; + for (int i = 1; i < N; i++) + nlp_solver_plan->nlp_cost[i] = NONLINEAR_LS; + + nlp_solver_plan->nlp_cost[N] = NONLINEAR_LS; + + for (int i = 0; i < N; i++) + { + nlp_solver_plan->nlp_dynamics[i] = CONTINUOUS_MODEL; + nlp_solver_plan->sim_solver_plan[i].sim_solver = ERK; + } + + for (int i = 0; i < N; i++) + {nlp_solver_plan->nlp_constraints[i] = BGH; + } + nlp_solver_plan->nlp_constraints[N] = BGH; +} + + +/** + * Internal function for lat_acados_create: step 2 + */ +ocp_nlp_dims* lat_acados_create_2_create_and_set_dimensions(lat_solver_capsule* capsule) +{ + ocp_nlp_plan_t* nlp_solver_plan = capsule->nlp_solver_plan; + const int N = nlp_solver_plan->N; + ocp_nlp_config* nlp_config = capsule->nlp_config; + + /************************************************ + * dimensions + ************************************************/ + #define NINTNP1MEMS 17 + int* intNp1mem = (int*)malloc( (N+1)*sizeof(int)*NINTNP1MEMS ); + + int* nx = intNp1mem + (N+1)*0; + int* nu = intNp1mem + (N+1)*1; + int* nbx = intNp1mem + (N+1)*2; + int* nbu = intNp1mem + (N+1)*3; + int* nsbx = intNp1mem + (N+1)*4; + int* nsbu = intNp1mem + (N+1)*5; + int* nsg = intNp1mem + (N+1)*6; + int* nsh = intNp1mem + (N+1)*7; + int* nsphi = intNp1mem + (N+1)*8; + int* ns = intNp1mem + (N+1)*9; + int* ng = intNp1mem + (N+1)*10; + int* nh = intNp1mem + (N+1)*11; + int* nphi = intNp1mem + (N+1)*12; + int* nz = intNp1mem + (N+1)*13; + int* ny = intNp1mem + (N+1)*14; + int* nr = intNp1mem + (N+1)*15; + int* nbxe = intNp1mem + (N+1)*16; + + for (int i = 0; i < N+1; i++) + { + // common + nx[i] = NX; + nu[i] = NU; + nz[i] = NZ; + ns[i] = NS; + // cost + ny[i] = NY; + // constraints + nbx[i] = NBX; + nbu[i] = NBU; + nsbx[i] = NSBX; + nsbu[i] = NSBU; + nsg[i] = NSG; + nsh[i] = NSH; + nsphi[i] = NSPHI; + ng[i] = NG; + nh[i] = NH; + nphi[i] = NPHI; + nr[i] = NR; + nbxe[i] = 0; + } + + // for initial state + nbx[0] = NBX0; + nsbx[0] = 0; + ns[0] = NS - NSBX; + nbxe[0] = 4; + ny[0] = NY0; + + // terminal - common + nu[N] = 0; + nz[N] = 0; + ns[N] = NSN; + // cost + ny[N] = NYN; + // constraint + nbx[N] = NBXN; + nbu[N] = 0; + ng[N] = NGN; + nh[N] = NHN; + nphi[N] = NPHIN; + nr[N] = 0; + + nsbx[N] = NSBXN; + nsbu[N] = 0; + nsg[N] = NSGN; + nsh[N] = NSHN; + nsphi[N] = NSPHIN; + + /* create and set ocp_nlp_dims */ + ocp_nlp_dims * nlp_dims = ocp_nlp_dims_create(nlp_config); + + ocp_nlp_dims_set_opt_vars(nlp_config, nlp_dims, "nx", nx); + ocp_nlp_dims_set_opt_vars(nlp_config, nlp_dims, "nu", nu); + ocp_nlp_dims_set_opt_vars(nlp_config, nlp_dims, "nz", nz); + ocp_nlp_dims_set_opt_vars(nlp_config, nlp_dims, "ns", ns); + + for (int i = 0; i <= N; i++) + { + ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "nbx", &nbx[i]); + ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "nbu", &nbu[i]); + ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "nsbx", &nsbx[i]); + ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "nsbu", &nsbu[i]); + ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "ng", &ng[i]); + ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "nsg", &nsg[i]); + ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "nbxe", &nbxe[i]); + } + ocp_nlp_dims_set_cost(nlp_config, nlp_dims, 0, "ny", &ny[0]); + for (int i = 1; i < N; i++) + ocp_nlp_dims_set_cost(nlp_config, nlp_dims, i, "ny", &ny[i]); + + for (int i = 0; i < N; i++) + { + } + ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, N, "nh", &nh[N]); + ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, N, "nsh", &nsh[N]); + ocp_nlp_dims_set_cost(nlp_config, nlp_dims, N, "ny", &ny[N]); + free(intNp1mem); +return nlp_dims; +} + + +/** + * Internal function for lat_acados_create: step 3 + */ +void lat_acados_create_3_create_and_set_functions(lat_solver_capsule* capsule) +{ + const int N = capsule->nlp_solver_plan->N; + + /************************************************ + * external functions + ************************************************/ + +#define MAP_CASADI_FNC(__CAPSULE_FNC__, __MODEL_BASE_FNC__) do{ \ + capsule->__CAPSULE_FNC__.casadi_fun = & __MODEL_BASE_FNC__ ;\ + capsule->__CAPSULE_FNC__.casadi_n_in = & __MODEL_BASE_FNC__ ## _n_in; \ + capsule->__CAPSULE_FNC__.casadi_n_out = & __MODEL_BASE_FNC__ ## _n_out; \ + capsule->__CAPSULE_FNC__.casadi_sparsity_in = & __MODEL_BASE_FNC__ ## _sparsity_in; \ + capsule->__CAPSULE_FNC__.casadi_sparsity_out = & __MODEL_BASE_FNC__ ## _sparsity_out; \ + capsule->__CAPSULE_FNC__.casadi_work = & __MODEL_BASE_FNC__ ## _work; \ + external_function_param_casadi_create(&capsule->__CAPSULE_FNC__ , 2); \ + }while(false) + + + + + // explicit ode + capsule->forw_vde_casadi = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); + for (int i = 0; i < N; i++) { + MAP_CASADI_FNC(forw_vde_casadi[i], lat_expl_vde_forw); + } + + capsule->expl_ode_fun = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); + for (int i = 0; i < N; i++) { + MAP_CASADI_FNC(expl_ode_fun[i], lat_expl_ode_fun); + } + + + // nonlinear least squares function + MAP_CASADI_FNC(cost_y_0_fun, lat_cost_y_0_fun); + MAP_CASADI_FNC(cost_y_0_fun_jac_ut_xt, lat_cost_y_0_fun_jac_ut_xt); + MAP_CASADI_FNC(cost_y_0_hess, lat_cost_y_0_hess); + // nonlinear least squares cost + capsule->cost_y_fun = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); + for (int i = 0; i < N-1; i++) + { + MAP_CASADI_FNC(cost_y_fun[i], lat_cost_y_fun); + } + + capsule->cost_y_fun_jac_ut_xt = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); + for (int i = 0; i < N-1; i++) + { + MAP_CASADI_FNC(cost_y_fun_jac_ut_xt[i], lat_cost_y_fun_jac_ut_xt); + } + + capsule->cost_y_hess = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); + for (int i = 0; i < N-1; i++) + { + MAP_CASADI_FNC(cost_y_hess[i], lat_cost_y_hess); + } + // nonlinear least square function + MAP_CASADI_FNC(cost_y_e_fun, lat_cost_y_e_fun); + MAP_CASADI_FNC(cost_y_e_fun_jac_ut_xt, lat_cost_y_e_fun_jac_ut_xt); + MAP_CASADI_FNC(cost_y_e_hess, lat_cost_y_e_hess); + +#undef MAP_CASADI_FNC +} + + +/** + * Internal function for lat_acados_create: step 4 + */ +void lat_acados_create_4_set_default_parameters(lat_solver_capsule* capsule) { + const int N = capsule->nlp_solver_plan->N; + // initialize parameters to nominal value + double* p = calloc(NP, sizeof(double)); + + for (int i = 0; i <= N; i++) { + lat_acados_update_params(capsule, i, p, NP); + } + free(p); +} + + +/** + * Internal function for lat_acados_create: step 5 + */ +void lat_acados_create_5_set_nlp_in(lat_solver_capsule* capsule, const int N, double* new_time_steps) +{ + assert(N == capsule->nlp_solver_plan->N); + ocp_nlp_config* nlp_config = capsule->nlp_config; + ocp_nlp_dims* nlp_dims = capsule->nlp_dims; + + /************************************************ + * nlp_in + ************************************************/ +// ocp_nlp_in * nlp_in = ocp_nlp_in_create(nlp_config, nlp_dims); +// capsule->nlp_in = nlp_in; + ocp_nlp_in * nlp_in = capsule->nlp_in; + + // set up time_steps + + + if (new_time_steps) { + lat_acados_update_time_steps(capsule, N, new_time_steps); + } else {// time_steps are different + double* time_steps = malloc(N*sizeof(double)); + time_steps[0] = 0.009765625; + time_steps[1] = 0.029296875; + time_steps[2] = 0.048828125; + time_steps[3] = 0.068359375; + time_steps[4] = 0.087890625; + time_steps[5] = 0.107421875; + time_steps[6] = 0.126953125; + time_steps[7] = 0.146484375; + time_steps[8] = 0.166015625; + time_steps[9] = 0.185546875; + time_steps[10] = 0.205078125; + time_steps[11] = 0.224609375; + time_steps[12] = 0.244140625; + time_steps[13] = 0.263671875; + time_steps[14] = 0.283203125; + time_steps[15] = 0.302734375; + time_steps[16] = 0.322265625; + time_steps[17] = 0.341796875; + time_steps[18] = 0.361328125; + time_steps[19] = 0.380859375; + time_steps[20] = 0.400390625; + time_steps[21] = 0.419921875; + time_steps[22] = 0.439453125; + time_steps[23] = 0.458984375; + time_steps[24] = 0.478515625; + time_steps[25] = 0.498046875; + time_steps[26] = 0.517578125; + time_steps[27] = 0.537109375; + time_steps[28] = 0.556640625; + time_steps[29] = 0.576171875; + time_steps[30] = 0.595703125; + time_steps[31] = 0.615234375; + lat_acados_update_time_steps(capsule, N, time_steps); + free(time_steps); + } + + /**** Dynamics ****/ + for (int i = 0; i < N; i++) + { + ocp_nlp_dynamics_model_set(nlp_config, nlp_dims, nlp_in, i, "expl_vde_forw", &capsule->forw_vde_casadi[i]); + ocp_nlp_dynamics_model_set(nlp_config, nlp_dims, nlp_in, i, "expl_ode_fun", &capsule->expl_ode_fun[i]); + + } + + /**** Cost ****/ + double* yref_0 = calloc(NY0, sizeof(double)); + // change only the non-zero elements: + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "yref", yref_0); + free(yref_0); + double* yref = calloc(NY, sizeof(double)); + // change only the non-zero elements: + + for (int i = 1; i < N; i++) + { + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "yref", yref); + } + free(yref); + double* yref_e = calloc(NYN, sizeof(double)); + // change only the non-zero elements: + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "yref", yref_e); + free(yref_e); + double* W_0 = calloc(NY0*NY0, sizeof(double)); + // change only the non-zero elements: + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "W", W_0); + free(W_0); + double* W = calloc(NY*NY, sizeof(double)); + // change only the non-zero elements: + + for (int i = 1; i < N; i++) + { + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "W", W); + } + free(W); + double* W_e = calloc(NYN*NYN, sizeof(double)); + // change only the non-zero elements: + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "W", W_e); + free(W_e); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "nls_y_fun", &capsule->cost_y_0_fun); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "nls_y_fun_jac", &capsule->cost_y_0_fun_jac_ut_xt); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "nls_y_hess", &capsule->cost_y_0_hess); + for (int i = 1; i < N; i++) + { + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "nls_y_fun", &capsule->cost_y_fun[i-1]); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "nls_y_fun_jac", &capsule->cost_y_fun_jac_ut_xt[i-1]); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "nls_y_hess", &capsule->cost_y_hess[i-1]); + } + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "nls_y_fun", &capsule->cost_y_e_fun); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "nls_y_fun_jac", &capsule->cost_y_e_fun_jac_ut_xt); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "nls_y_hess", &capsule->cost_y_e_hess); + + + + /**** Constraints ****/ + + // bounds for initial stage + // x0 + int* idxbx0 = malloc(NBX0 * sizeof(int)); + idxbx0[0] = 0; + idxbx0[1] = 1; + idxbx0[2] = 2; + idxbx0[3] = 3; + + double* lubx0 = calloc(2*NBX0, sizeof(double)); + double* lbx0 = lubx0; + double* ubx0 = lubx0 + NBX0; + // change only the non-zero elements: + + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "idxbx", idxbx0); + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "lbx", lbx0); + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "ubx", ubx0); + free(idxbx0); + free(lubx0); + // idxbxe_0 + int* idxbxe_0 = malloc(4 * sizeof(int)); + + idxbxe_0[0] = 0; + idxbxe_0[1] = 1; + idxbxe_0[2] = 2; + idxbxe_0[3] = 3; + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "idxbxe", idxbxe_0); + free(idxbxe_0); + + /* constraints that are the same for initial and intermediate */ + + + + + + + + + // x + int* idxbx = malloc(NBX * sizeof(int)); + + idxbx[0] = 2; + idxbx[1] = 3; + double* lubx = calloc(2*NBX, sizeof(double)); + double* lbx = lubx; + double* ubx = lubx + NBX; + + lbx[0] = -1.5707963267948966; + ubx[0] = 1.5707963267948966; + lbx[1] = -0.8726646259971648; + ubx[1] = 0.8726646259971648; + + for (int i = 1; i < N; i++) + { + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "idxbx", idxbx); + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "lbx", lbx); + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "ubx", ubx); + } + free(idxbx); + free(lubx); + + + + + + + + /* terminal constraints */ + + + + + + + + + + + + + + + +} + + +/** + * Internal function for lat_acados_create: step 6 + */ +void lat_acados_create_6_set_opts(lat_solver_capsule* capsule) +{ + const int N = capsule->nlp_solver_plan->N; + ocp_nlp_config* nlp_config = capsule->nlp_config; + void *nlp_opts = capsule->nlp_opts; + + /************************************************ + * opts + ************************************************/ + + + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "globalization", "fixed_step");int full_step_dual = 0; + ocp_nlp_solver_opts_set(nlp_config, capsule->nlp_opts, "full_step_dual", &full_step_dual); + + // set collocation type (relevant for implicit integrators) + sim_collocation_type collocation_type = GAUSS_LEGENDRE; + for (int i = 0; i < N; i++) + ocp_nlp_solver_opts_set_at_stage(nlp_config, nlp_opts, i, "dynamics_collocation_type", &collocation_type); + + // set up sim_method_num_steps + // all sim_method_num_steps are identical + int sim_method_num_steps = 1; + for (int i = 0; i < N; i++) + ocp_nlp_solver_opts_set_at_stage(nlp_config, nlp_opts, i, "dynamics_num_steps", &sim_method_num_steps); + + // set up sim_method_num_stages + // all sim_method_num_stages are identical + int sim_method_num_stages = 4; + for (int i = 0; i < N; i++) + ocp_nlp_solver_opts_set_at_stage(nlp_config, nlp_opts, i, "dynamics_num_stages", &sim_method_num_stages); + + int newton_iter_val = 3; + for (int i = 0; i < N; i++) + ocp_nlp_solver_opts_set_at_stage(nlp_config, nlp_opts, i, "dynamics_newton_iter", &newton_iter_val); + + + // set up sim_method_jac_reuse + bool tmp_bool = (bool) 0; + for (int i = 0; i < N; i++) + ocp_nlp_solver_opts_set_at_stage(nlp_config, nlp_opts, i, "dynamics_jac_reuse", &tmp_bool); + + double nlp_solver_step_length = 1.0; + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "step_length", &nlp_solver_step_length); + + double levenberg_marquardt = 0.0; + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "levenberg_marquardt", &levenberg_marquardt); + + /* options QP solver */ + int qp_solver_cond_N; + + const int qp_solver_cond_N_ori = 1; + qp_solver_cond_N = N < qp_solver_cond_N_ori ? N : qp_solver_cond_N_ori; // use the minimum value here + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_cond_N", &qp_solver_cond_N); + + int nlp_solver_ext_qp_res = 0; + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "ext_qp_res", &nlp_solver_ext_qp_res); + // set HPIPM mode: should be done before setting other QP solver options + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_hpipm_mode", "BALANCE"); + + + + int qp_solver_iter_max = 1; + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_iter_max", &qp_solver_iter_max); + +int print_level = 0; + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "print_level", &print_level); + int qp_solver_cond_ric_alg = 1; + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_cond_ric_alg", &qp_solver_cond_ric_alg); + + int qp_solver_ric_alg = 1; + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_ric_alg", &qp_solver_ric_alg); + + + int ext_cost_num_hess = 0; +} + + +/** + * Internal function for lat_acados_create: step 7 + */ +void lat_acados_create_7_set_nlp_out(lat_solver_capsule* capsule) +{ + const int N = capsule->nlp_solver_plan->N; + ocp_nlp_config* nlp_config = capsule->nlp_config; + ocp_nlp_dims* nlp_dims = capsule->nlp_dims; + ocp_nlp_out* nlp_out = capsule->nlp_out; + + // initialize primal solution + double* xu0 = calloc(NX+NU, sizeof(double)); + double* x0 = xu0; + + // initialize with x0 + + + + double* u0 = xu0 + NX; + + for (int i = 0; i < N; i++) + { + // x0 + ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, i, "x", x0); + // u0 + ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, i, "u", u0); + } + ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, N, "x", x0); + free(xu0); +} + + +/** + * Internal function for lat_acados_create: step 8 + */ +//void lat_acados_create_8_create_solver(lat_solver_capsule* capsule) +//{ +// capsule->nlp_solver = ocp_nlp_solver_create(capsule->nlp_config, capsule->nlp_dims, capsule->nlp_opts); +//} + +/** + * Internal function for lat_acados_create: step 9 + */ +int lat_acados_create_9_precompute(lat_solver_capsule* capsule) { + int status = ocp_nlp_precompute(capsule->nlp_solver, capsule->nlp_in, capsule->nlp_out); + + if (status != ACADOS_SUCCESS) { + printf("\nocp_nlp_precompute failed!\n\n"); + exit(1); + } + + return status; +} + + +int lat_acados_create_with_discretization(lat_solver_capsule* capsule, int N, double* new_time_steps) +{ + // If N does not match the number of shooting intervals used for code generation, new_time_steps must be given. + if (N != LAT_N && !new_time_steps) { + fprintf(stderr, "lat_acados_create_with_discretization: new_time_steps is NULL " \ + "but the number of shooting intervals (= %d) differs from the number of " \ + "shooting intervals (= %d) during code generation! Please provide a new vector of time_stamps!\n", \ + N, LAT_N); + return 1; + } + + // number of expected runtime parameters + capsule->nlp_np = NP; + + // 1) create and set nlp_solver_plan; create nlp_config + capsule->nlp_solver_plan = ocp_nlp_plan_create(N); + lat_acados_create_1_set_plan(capsule->nlp_solver_plan, N); + capsule->nlp_config = ocp_nlp_config_create(*capsule->nlp_solver_plan); + + // 3) create and set dimensions + capsule->nlp_dims = lat_acados_create_2_create_and_set_dimensions(capsule); + lat_acados_create_3_create_and_set_functions(capsule); + + // 4) set default parameters in functions + lat_acados_create_4_set_default_parameters(capsule); + + // 5) create and set nlp_in + capsule->nlp_in = ocp_nlp_in_create(capsule->nlp_config, capsule->nlp_dims); + lat_acados_create_5_set_nlp_in(capsule, N, new_time_steps); + + // 6) create and set nlp_opts + capsule->nlp_opts = ocp_nlp_solver_opts_create(capsule->nlp_config, capsule->nlp_dims); + lat_acados_create_6_set_opts(capsule); + + // 7) create and set nlp_out + // 7.1) nlp_out + capsule->nlp_out = ocp_nlp_out_create(capsule->nlp_config, capsule->nlp_dims); + // 7.2) sens_out + capsule->sens_out = ocp_nlp_out_create(capsule->nlp_config, capsule->nlp_dims); + lat_acados_create_7_set_nlp_out(capsule); + + // 8) create solver + capsule->nlp_solver = ocp_nlp_solver_create(capsule->nlp_config, capsule->nlp_dims, capsule->nlp_opts); + //lat_acados_create_8_create_solver(capsule); + + // 9) do precomputations + int status = lat_acados_create_9_precompute(capsule); + + return status; +} + +/** + * This function is for updating an already initialized solver with a different number of qp_cond_N. It is useful for code reuse after code export. + */ +int lat_acados_update_qp_solver_cond_N(lat_solver_capsule* capsule, int qp_solver_cond_N) +{ + // 1) destroy solver + ocp_nlp_solver_destroy(capsule->nlp_solver); + + // 2) set new value for "qp_cond_N" + const int N = capsule->nlp_solver_plan->N; + if(qp_solver_cond_N > N) + printf("Warning: qp_solver_cond_N = %d > N = %d\n", qp_solver_cond_N, N); + ocp_nlp_solver_opts_set(capsule->nlp_config, capsule->nlp_opts, "qp_cond_N", &qp_solver_cond_N); + + // 3) continue with the remaining steps from lat_acados_create_with_discretization(...): + // -> 8) create solver + capsule->nlp_solver = ocp_nlp_solver_create(capsule->nlp_config, capsule->nlp_dims, capsule->nlp_opts); + + // -> 9) do precomputations + int status = lat_acados_create_9_precompute(capsule); + return status; +} + + +int lat_acados_reset(lat_solver_capsule* capsule, int reset_qp_solver_mem) +{ + + // set initialization to all zeros + + const int N = capsule->nlp_solver_plan->N; + ocp_nlp_config* nlp_config = capsule->nlp_config; + ocp_nlp_dims* nlp_dims = capsule->nlp_dims; + ocp_nlp_out* nlp_out = capsule->nlp_out; + ocp_nlp_in* nlp_in = capsule->nlp_in; + ocp_nlp_solver* nlp_solver = capsule->nlp_solver; + + double* buffer = calloc(NX+NU+NZ+2*NS+2*NSN+NBX+NBU+NG+NH+NPHI+NBX0+NBXN+NHN+NPHIN+NGN, sizeof(double)); + + for(int i=0; i reset memory + int qp_status; + ocp_nlp_get(capsule->nlp_config, capsule->nlp_solver, "qp_status", &qp_status); + if (reset_qp_solver_mem || (qp_status == 3)) + { + // printf("\nin reset qp_status %d -> resetting QP memory\n", qp_status); + ocp_nlp_solver_reset_qp_memory(nlp_solver, nlp_in, nlp_out); + } + + free(buffer); + return 0; +} + + + + +int lat_acados_update_params(lat_solver_capsule* capsule, int stage, double *p, int np) +{ + int solver_status = 0; + + int casadi_np = 2; + if (casadi_np != np) { + printf("acados_update_params: trying to set %i parameters for external functions." + " External function has %i parameters. Exiting.\n", np, casadi_np); + exit(1); + } + + const int N = capsule->nlp_solver_plan->N; + if (stage < N && stage >= 0) + { + capsule->forw_vde_casadi[stage].set_param(capsule->forw_vde_casadi+stage, p); + capsule->expl_ode_fun[stage].set_param(capsule->expl_ode_fun+stage, p); + + + // constraints + + + // cost + if (stage == 0) + { + capsule->cost_y_0_fun.set_param(&capsule->cost_y_0_fun, p); + capsule->cost_y_0_fun_jac_ut_xt.set_param(&capsule->cost_y_0_fun_jac_ut_xt, p); + capsule->cost_y_0_hess.set_param(&capsule->cost_y_0_hess, p); + } + else // 0 < stage < N + { + capsule->cost_y_fun[stage-1].set_param(capsule->cost_y_fun+stage-1, p); + capsule->cost_y_fun_jac_ut_xt[stage-1].set_param(capsule->cost_y_fun_jac_ut_xt+stage-1, p); + capsule->cost_y_hess[stage-1].set_param(capsule->cost_y_hess+stage-1, p); + } + } + + else // stage == N + { + // terminal shooting node has no dynamics + // cost + capsule->cost_y_e_fun.set_param(&capsule->cost_y_e_fun, p); + capsule->cost_y_e_fun_jac_ut_xt.set_param(&capsule->cost_y_e_fun_jac_ut_xt, p); + capsule->cost_y_e_hess.set_param(&capsule->cost_y_e_hess, p); + // constraints + + } + + return solver_status; +} + + +int lat_acados_update_params_sparse(lat_solver_capsule * capsule, int stage, int *idx, double *p, int n_update) +{ + int solver_status = 0; + + int casadi_np = 2; + if (casadi_np < n_update) { + printf("lat_acados_update_params_sparse: trying to set %d parameters for external functions." + " External function has %d parameters. Exiting.\n", n_update, casadi_np); + exit(1); + } + // for (int i = 0; i < n_update; i++) + // { + // if (idx[i] > casadi_np) { + // printf("lat_acados_update_params_sparse: attempt to set parameters with index %d, while" + // " external functions only has %d parameters. Exiting.\n", idx[i], casadi_np); + // exit(1); + // } + // printf("param %d value %e\n", idx[i], p[i]); + // } + const int N = capsule->nlp_solver_plan->N; + if (stage < N && stage >= 0) + { + capsule->forw_vde_casadi[stage].set_param_sparse(capsule->forw_vde_casadi+stage, n_update, idx, p); + capsule->expl_ode_fun[stage].set_param_sparse(capsule->expl_ode_fun+stage, n_update, idx, p); + + + // constraints + + + // cost + if (stage == 0) + { + capsule->cost_y_0_fun.set_param_sparse(&capsule->cost_y_0_fun, n_update, idx, p); + capsule->cost_y_0_fun_jac_ut_xt.set_param_sparse(&capsule->cost_y_0_fun_jac_ut_xt, n_update, idx, p); + capsule->cost_y_0_hess.set_param_sparse(&capsule->cost_y_0_hess, n_update, idx, p); + } + else // 0 < stage < N + { + capsule->cost_y_fun[stage-1].set_param_sparse(capsule->cost_y_fun+stage-1, n_update, idx, p); + capsule->cost_y_fun_jac_ut_xt[stage-1].set_param_sparse(capsule->cost_y_fun_jac_ut_xt+stage-1, n_update, idx, p); + capsule->cost_y_hess[stage-1].set_param_sparse(capsule->cost_y_hess+stage-1, n_update, idx, p); + } + } + + else // stage == N + { + // terminal shooting node has no dynamics + // cost + capsule->cost_y_e_fun.set_param_sparse(&capsule->cost_y_e_fun, n_update, idx, p); + capsule->cost_y_e_fun_jac_ut_xt.set_param_sparse(&capsule->cost_y_e_fun_jac_ut_xt, n_update, idx, p); + capsule->cost_y_e_hess.set_param_sparse(&capsule->cost_y_e_hess, n_update, idx, p); + // constraints + + } + + + return solver_status; +} + +int lat_acados_solve(lat_solver_capsule* capsule) +{ + // solve NLP + int solver_status = ocp_nlp_solve(capsule->nlp_solver, capsule->nlp_in, capsule->nlp_out); + + return solver_status; +} + + +int lat_acados_free(lat_solver_capsule* capsule) +{ + // before destroying, keep some info + const int N = capsule->nlp_solver_plan->N; + // free memory + ocp_nlp_solver_opts_destroy(capsule->nlp_opts); + ocp_nlp_in_destroy(capsule->nlp_in); + ocp_nlp_out_destroy(capsule->nlp_out); + ocp_nlp_out_destroy(capsule->sens_out); + ocp_nlp_solver_destroy(capsule->nlp_solver); + ocp_nlp_dims_destroy(capsule->nlp_dims); + ocp_nlp_config_destroy(capsule->nlp_config); + ocp_nlp_plan_destroy(capsule->nlp_solver_plan); + + /* free external function */ + // dynamics + for (int i = 0; i < N; i++) + { + external_function_param_casadi_free(&capsule->forw_vde_casadi[i]); + external_function_param_casadi_free(&capsule->expl_ode_fun[i]); + } + free(capsule->forw_vde_casadi); + free(capsule->expl_ode_fun); + + // cost + external_function_param_casadi_free(&capsule->cost_y_0_fun); + external_function_param_casadi_free(&capsule->cost_y_0_fun_jac_ut_xt); + external_function_param_casadi_free(&capsule->cost_y_0_hess); + for (int i = 0; i < N - 1; i++) + { + external_function_param_casadi_free(&capsule->cost_y_fun[i]); + external_function_param_casadi_free(&capsule->cost_y_fun_jac_ut_xt[i]); + external_function_param_casadi_free(&capsule->cost_y_hess[i]); + } + free(capsule->cost_y_fun); + free(capsule->cost_y_fun_jac_ut_xt); + free(capsule->cost_y_hess); + external_function_param_casadi_free(&capsule->cost_y_e_fun); + external_function_param_casadi_free(&capsule->cost_y_e_fun_jac_ut_xt); + external_function_param_casadi_free(&capsule->cost_y_e_hess); + + // constraints + + return 0; +} + + +void lat_acados_print_stats(lat_solver_capsule* capsule) +{ + int sqp_iter, stat_m, stat_n, tmp_int; + ocp_nlp_get(capsule->nlp_config, capsule->nlp_solver, "sqp_iter", &sqp_iter); + ocp_nlp_get(capsule->nlp_config, capsule->nlp_solver, "stat_n", &stat_n); + ocp_nlp_get(capsule->nlp_config, capsule->nlp_solver, "stat_m", &stat_m); + + + double stat[1200]; + ocp_nlp_get(capsule->nlp_config, capsule->nlp_solver, "statistics", stat); + + int nrow = sqp_iter+1 < stat_m ? sqp_iter+1 : stat_m; + + printf("iter\tres_stat\tres_eq\t\tres_ineq\tres_comp\tqp_stat\tqp_iter\talpha"); + if (stat_n > 8) + printf("\t\tqp_res_stat\tqp_res_eq\tqp_res_ineq\tqp_res_comp"); + printf("\n"); + printf("iter\tqp_stat\tqp_iter\n"); + for (int i = 0; i < nrow; i++) + { + for (int j = 0; j < stat_n + 1; j++) + { + tmp_int = (int) stat[i + j * nrow]; + printf("%d\t", tmp_int); + } + printf("\n"); + } +} + +int lat_acados_custom_update(lat_solver_capsule* capsule, double* data, int data_len) +{ + (void)capsule; + (void)data; + (void)data_len; + printf("\ndummy function that can be called in between solver calls to update parameters or numerical data efficiently in C.\n"); + printf("nothing set yet..\n"); + return 1; + +} + + + +ocp_nlp_in *lat_acados_get_nlp_in(lat_solver_capsule* capsule) { return capsule->nlp_in; } +ocp_nlp_out *lat_acados_get_nlp_out(lat_solver_capsule* capsule) { return capsule->nlp_out; } +ocp_nlp_out *lat_acados_get_sens_out(lat_solver_capsule* capsule) { return capsule->sens_out; } +ocp_nlp_solver *lat_acados_get_nlp_solver(lat_solver_capsule* capsule) { return capsule->nlp_solver; } +ocp_nlp_config *lat_acados_get_nlp_config(lat_solver_capsule* capsule) { return capsule->nlp_config; } +void *lat_acados_get_nlp_opts(lat_solver_capsule* capsule) { return capsule->nlp_opts; } +ocp_nlp_dims *lat_acados_get_nlp_dims(lat_solver_capsule* capsule) { return capsule->nlp_dims; } +ocp_nlp_plan_t *lat_acados_get_nlp_plan(lat_solver_capsule* capsule) { return capsule->nlp_solver_plan; } diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_0_fun.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_0_fun.c new file mode 100644 index 0000000..14e04af --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_0_fun.c @@ -0,0 +1,167 @@ +/* This file was automatically generated by CasADi 3.6.4. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) lat_cost_y_0_fun_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) +#define casadi_s4 CASADI_PREFIX(s4) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +static const casadi_int casadi_s0[8] = {4, 1, 0, 4, 0, 1, 2, 3}; +static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; +static const casadi_int casadi_s2[3] = {0, 0, 0}; +static const casadi_int casadi_s3[6] = {2, 1, 0, 2, 0, 1}; +static const casadi_int casadi_s4[9] = {5, 1, 0, 5, 0, 1, 2, 3, 4}; + +/* lat_cost_y_0_fun:(i0[4],i1,i2[],i3[2])->(o0[5]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a2; + a0=arg[0]? arg[0][1] : 0; + if (res[0]!=0) res[0][0]=a0; + a0=arg[3]? arg[3][0] : 0; + a1=10.; + a1=(a0+a1); + a2=arg[0]? arg[0][2] : 0; + a2=(a1*a2); + if (res[0]!=0) res[0][1]=a2; + a2=arg[0]? arg[0][3] : 0; + a2=(a1*a2); + if (res[0]!=0) res[0][2]=a2; + a2=arg[1]? arg[1][0] : 0; + a1=(a1*a2); + if (res[0]!=0) res[0][3]=a1; + a1=1.0000000000000001e-01; + a0=(a0+a1); + a2=(a2/a0); + if (res[0]!=0) res[0][4]=a2; + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_0_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_0_fun_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_0_fun_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_0_fun_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_0_fun_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_0_fun_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_0_fun_incref(void) { +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_0_fun_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_0_fun_n_in(void) { return 4;} + +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_0_fun_n_out(void) { return 1;} + +CASADI_SYMBOL_EXPORT casadi_real lat_cost_y_0_fun_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_cost_y_0_fun_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_cost_y_0_fun_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_0_fun_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + case 3: return casadi_s3; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_0_fun_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s4; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_0_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 4; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_0_fun_jac_ut_xt.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_0_fun_jac_ut_xt.c new file mode 100644 index 0000000..848abc6 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_0_fun_jac_ut_xt.c @@ -0,0 +1,182 @@ +/* This file was automatically generated by CasADi 3.6.4. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) lat_cost_y_0_fun_jac_ut_xt_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) +#define casadi_s4 CASADI_PREFIX(s4) +#define casadi_s5 CASADI_PREFIX(s5) +#define casadi_s6 CASADI_PREFIX(s6) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +static const casadi_int casadi_s0[8] = {4, 1, 0, 4, 0, 1, 2, 3}; +static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; +static const casadi_int casadi_s2[3] = {0, 0, 0}; +static const casadi_int casadi_s3[6] = {2, 1, 0, 2, 0, 1}; +static const casadi_int casadi_s4[9] = {5, 1, 0, 5, 0, 1, 2, 3, 4}; +static const casadi_int casadi_s5[13] = {5, 5, 0, 1, 2, 3, 4, 5, 2, 3, 4, 0, 0}; +static const casadi_int casadi_s6[3] = {5, 0, 0}; + +/* lat_cost_y_0_fun_jac_ut_xt:(i0[4],i1,i2[],i3[2])->(o0[5],o1[5x5,5nz],o2[5x0]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a2, a3; + a0=arg[0]? arg[0][1] : 0; + if (res[0]!=0) res[0][0]=a0; + a0=arg[3]? arg[3][0] : 0; + a1=10.; + a1=(a0+a1); + a2=arg[0]? arg[0][2] : 0; + a2=(a1*a2); + if (res[0]!=0) res[0][1]=a2; + a2=arg[0]? arg[0][3] : 0; + a2=(a1*a2); + if (res[0]!=0) res[0][2]=a2; + a2=arg[1]? arg[1][0] : 0; + a3=(a1*a2); + if (res[0]!=0) res[0][3]=a3; + a3=1.0000000000000001e-01; + a0=(a0+a3); + a2=(a2/a0); + if (res[0]!=0) res[0][4]=a2; + a2=1.; + if (res[1]!=0) res[1][0]=a2; + if (res[1]!=0) res[1][1]=a1; + if (res[1]!=0) res[1][2]=a1; + if (res[1]!=0) res[1][3]=a1; + a0=(1./a0); + if (res[1]!=0) res[1][4]=a0; + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_0_fun_jac_ut_xt(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_0_fun_jac_ut_xt_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_0_fun_jac_ut_xt_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_0_fun_jac_ut_xt_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_0_fun_jac_ut_xt_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_0_fun_jac_ut_xt_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_0_fun_jac_ut_xt_incref(void) { +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_0_fun_jac_ut_xt_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_0_fun_jac_ut_xt_n_in(void) { return 4;} + +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_0_fun_jac_ut_xt_n_out(void) { return 3;} + +CASADI_SYMBOL_EXPORT casadi_real lat_cost_y_0_fun_jac_ut_xt_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_cost_y_0_fun_jac_ut_xt_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_cost_y_0_fun_jac_ut_xt_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + case 1: return "o1"; + case 2: return "o2"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_0_fun_jac_ut_xt_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + case 3: return casadi_s3; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_0_fun_jac_ut_xt_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s4; + case 1: return casadi_s5; + case 2: return casadi_s6; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_0_fun_jac_ut_xt_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 4; + if (sz_res) *sz_res = 3; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_0_hess.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_0_hess.c new file mode 100644 index 0000000..8a52618 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_0_hess.c @@ -0,0 +1,152 @@ +/* This file was automatically generated by CasADi 3.6.4. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) lat_cost_y_0_hess_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) +#define casadi_s4 CASADI_PREFIX(s4) +#define casadi_s5 CASADI_PREFIX(s5) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +static const casadi_int casadi_s0[8] = {4, 1, 0, 4, 0, 1, 2, 3}; +static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; +static const casadi_int casadi_s2[3] = {0, 0, 0}; +static const casadi_int casadi_s3[9] = {5, 1, 0, 5, 0, 1, 2, 3, 4}; +static const casadi_int casadi_s4[6] = {2, 1, 0, 2, 0, 1}; +static const casadi_int casadi_s5[8] = {5, 5, 0, 0, 0, 0, 0, 0}; + +/* lat_cost_y_0_hess:(i0[4],i1,i2[],i3[5],i4[2])->(o0[5x5,0nz]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_0_hess(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_0_hess_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_0_hess_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_0_hess_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_0_hess_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_0_hess_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_0_hess_incref(void) { +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_0_hess_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_0_hess_n_in(void) { return 5;} + +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_0_hess_n_out(void) { return 1;} + +CASADI_SYMBOL_EXPORT casadi_real lat_cost_y_0_hess_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_cost_y_0_hess_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + case 4: return "i4"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_cost_y_0_hess_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_0_hess_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + case 3: return casadi_s3; + case 4: return casadi_s4; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_0_hess_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s5; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_0_hess_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 5; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_e_fun.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_e_fun.c new file mode 100644 index 0000000..9a7044c --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_e_fun.c @@ -0,0 +1,158 @@ +/* This file was automatically generated by CasADi 3.6.4. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) lat_cost_y_e_fun_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +static const casadi_int casadi_s0[8] = {4, 1, 0, 4, 0, 1, 2, 3}; +static const casadi_int casadi_s1[3] = {0, 0, 0}; +static const casadi_int casadi_s2[6] = {2, 1, 0, 2, 0, 1}; +static const casadi_int casadi_s3[7] = {3, 1, 0, 3, 0, 1, 2}; + +/* lat_cost_y_e_fun:(i0[4],i1[],i2[],i3[2])->(o0[3]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1; + a0=arg[0]? arg[0][1] : 0; + if (res[0]!=0) res[0][0]=a0; + a0=arg[3]? arg[3][0] : 0; + a1=10.; + a0=(a0+a1); + a1=arg[0]? arg[0][2] : 0; + a1=(a0*a1); + if (res[0]!=0) res[0][1]=a1; + a1=arg[0]? arg[0][3] : 0; + a0=(a0*a1); + if (res[0]!=0) res[0][2]=a0; + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_e_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_e_fun_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_e_fun_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_e_fun_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_e_fun_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_e_fun_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_e_fun_incref(void) { +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_e_fun_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_e_fun_n_in(void) { return 4;} + +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_e_fun_n_out(void) { return 1;} + +CASADI_SYMBOL_EXPORT casadi_real lat_cost_y_e_fun_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_cost_y_e_fun_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_cost_y_e_fun_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_e_fun_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s1; + case 3: return casadi_s2; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_e_fun_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s3; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_e_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 4; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_e_fun_jac_ut_xt.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_e_fun_jac_ut_xt.c new file mode 100644 index 0000000..c1b19ac --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_e_fun_jac_ut_xt.c @@ -0,0 +1,170 @@ +/* This file was automatically generated by CasADi 3.6.4. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) lat_cost_y_e_fun_jac_ut_xt_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) +#define casadi_s4 CASADI_PREFIX(s4) +#define casadi_s5 CASADI_PREFIX(s5) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +static const casadi_int casadi_s0[8] = {4, 1, 0, 4, 0, 1, 2, 3}; +static const casadi_int casadi_s1[3] = {0, 0, 0}; +static const casadi_int casadi_s2[6] = {2, 1, 0, 2, 0, 1}; +static const casadi_int casadi_s3[7] = {3, 1, 0, 3, 0, 1, 2}; +static const casadi_int casadi_s4[9] = {4, 3, 0, 1, 2, 3, 1, 2, 3}; +static const casadi_int casadi_s5[3] = {3, 0, 0}; + +/* lat_cost_y_e_fun_jac_ut_xt:(i0[4],i1[],i2[],i3[2])->(o0[3],o1[4x3,3nz],o2[3x0]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1; + a0=arg[0]? arg[0][1] : 0; + if (res[0]!=0) res[0][0]=a0; + a0=arg[3]? arg[3][0] : 0; + a1=10.; + a0=(a0+a1); + a1=arg[0]? arg[0][2] : 0; + a1=(a0*a1); + if (res[0]!=0) res[0][1]=a1; + a1=arg[0]? arg[0][3] : 0; + a1=(a0*a1); + if (res[0]!=0) res[0][2]=a1; + a1=1.; + if (res[1]!=0) res[1][0]=a1; + if (res[1]!=0) res[1][1]=a0; + if (res[1]!=0) res[1][2]=a0; + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_e_fun_jac_ut_xt(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_e_fun_jac_ut_xt_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_e_fun_jac_ut_xt_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_e_fun_jac_ut_xt_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_e_fun_jac_ut_xt_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_e_fun_jac_ut_xt_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_e_fun_jac_ut_xt_incref(void) { +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_e_fun_jac_ut_xt_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_e_fun_jac_ut_xt_n_in(void) { return 4;} + +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_e_fun_jac_ut_xt_n_out(void) { return 3;} + +CASADI_SYMBOL_EXPORT casadi_real lat_cost_y_e_fun_jac_ut_xt_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_cost_y_e_fun_jac_ut_xt_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_cost_y_e_fun_jac_ut_xt_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + case 1: return "o1"; + case 2: return "o2"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_e_fun_jac_ut_xt_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s1; + case 3: return casadi_s2; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_e_fun_jac_ut_xt_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s3; + case 1: return casadi_s4; + case 2: return casadi_s5; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_e_fun_jac_ut_xt_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 4; + if (sz_res) *sz_res = 3; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_e_hess.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_e_hess.c new file mode 100644 index 0000000..6da9aac --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_e_hess.c @@ -0,0 +1,150 @@ +/* This file was automatically generated by CasADi 3.6.4. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) lat_cost_y_e_hess_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) +#define casadi_s4 CASADI_PREFIX(s4) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +static const casadi_int casadi_s0[8] = {4, 1, 0, 4, 0, 1, 2, 3}; +static const casadi_int casadi_s1[3] = {0, 0, 0}; +static const casadi_int casadi_s2[7] = {3, 1, 0, 3, 0, 1, 2}; +static const casadi_int casadi_s3[6] = {2, 1, 0, 2, 0, 1}; +static const casadi_int casadi_s4[7] = {4, 4, 0, 0, 0, 0, 0}; + +/* lat_cost_y_e_hess:(i0[4],i1[],i2[],i3[3],i4[2])->(o0[4x4,0nz]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_e_hess(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_e_hess_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_e_hess_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_e_hess_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_e_hess_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_e_hess_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_e_hess_incref(void) { +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_e_hess_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_e_hess_n_in(void) { return 5;} + +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_e_hess_n_out(void) { return 1;} + +CASADI_SYMBOL_EXPORT casadi_real lat_cost_y_e_hess_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_cost_y_e_hess_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + case 4: return "i4"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_cost_y_e_hess_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_e_hess_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s1; + case 3: return casadi_s2; + case 4: return casadi_s3; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_e_hess_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s4; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_e_hess_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 5; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_fun.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_fun.c new file mode 100644 index 0000000..8b2aec1 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_fun.c @@ -0,0 +1,167 @@ +/* This file was automatically generated by CasADi 3.6.4. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) lat_cost_y_fun_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) +#define casadi_s4 CASADI_PREFIX(s4) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +static const casadi_int casadi_s0[8] = {4, 1, 0, 4, 0, 1, 2, 3}; +static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; +static const casadi_int casadi_s2[3] = {0, 0, 0}; +static const casadi_int casadi_s3[6] = {2, 1, 0, 2, 0, 1}; +static const casadi_int casadi_s4[9] = {5, 1, 0, 5, 0, 1, 2, 3, 4}; + +/* lat_cost_y_fun:(i0[4],i1,i2[],i3[2])->(o0[5]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a2; + a0=arg[0]? arg[0][1] : 0; + if (res[0]!=0) res[0][0]=a0; + a0=arg[3]? arg[3][0] : 0; + a1=10.; + a1=(a0+a1); + a2=arg[0]? arg[0][2] : 0; + a2=(a1*a2); + if (res[0]!=0) res[0][1]=a2; + a2=arg[0]? arg[0][3] : 0; + a2=(a1*a2); + if (res[0]!=0) res[0][2]=a2; + a2=arg[1]? arg[1][0] : 0; + a1=(a1*a2); + if (res[0]!=0) res[0][3]=a1; + a1=1.0000000000000001e-01; + a0=(a0+a1); + a2=(a2/a0); + if (res[0]!=0) res[0][4]=a2; + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_fun_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_fun_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_fun_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_fun_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_fun_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_fun_incref(void) { +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_fun_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_fun_n_in(void) { return 4;} + +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_fun_n_out(void) { return 1;} + +CASADI_SYMBOL_EXPORT casadi_real lat_cost_y_fun_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_cost_y_fun_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_cost_y_fun_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_fun_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + case 3: return casadi_s3; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_fun_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s4; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 4; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_fun_jac_ut_xt.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_fun_jac_ut_xt.c new file mode 100644 index 0000000..42e7ca7 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_fun_jac_ut_xt.c @@ -0,0 +1,182 @@ +/* This file was automatically generated by CasADi 3.6.4. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) lat_cost_y_fun_jac_ut_xt_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) +#define casadi_s4 CASADI_PREFIX(s4) +#define casadi_s5 CASADI_PREFIX(s5) +#define casadi_s6 CASADI_PREFIX(s6) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +static const casadi_int casadi_s0[8] = {4, 1, 0, 4, 0, 1, 2, 3}; +static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; +static const casadi_int casadi_s2[3] = {0, 0, 0}; +static const casadi_int casadi_s3[6] = {2, 1, 0, 2, 0, 1}; +static const casadi_int casadi_s4[9] = {5, 1, 0, 5, 0, 1, 2, 3, 4}; +static const casadi_int casadi_s5[13] = {5, 5, 0, 1, 2, 3, 4, 5, 2, 3, 4, 0, 0}; +static const casadi_int casadi_s6[3] = {5, 0, 0}; + +/* lat_cost_y_fun_jac_ut_xt:(i0[4],i1,i2[],i3[2])->(o0[5],o1[5x5,5nz],o2[5x0]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a2, a3; + a0=arg[0]? arg[0][1] : 0; + if (res[0]!=0) res[0][0]=a0; + a0=arg[3]? arg[3][0] : 0; + a1=10.; + a1=(a0+a1); + a2=arg[0]? arg[0][2] : 0; + a2=(a1*a2); + if (res[0]!=0) res[0][1]=a2; + a2=arg[0]? arg[0][3] : 0; + a2=(a1*a2); + if (res[0]!=0) res[0][2]=a2; + a2=arg[1]? arg[1][0] : 0; + a3=(a1*a2); + if (res[0]!=0) res[0][3]=a3; + a3=1.0000000000000001e-01; + a0=(a0+a3); + a2=(a2/a0); + if (res[0]!=0) res[0][4]=a2; + a2=1.; + if (res[1]!=0) res[1][0]=a2; + if (res[1]!=0) res[1][1]=a1; + if (res[1]!=0) res[1][2]=a1; + if (res[1]!=0) res[1][3]=a1; + a0=(1./a0); + if (res[1]!=0) res[1][4]=a0; + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_fun_jac_ut_xt(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_fun_jac_ut_xt_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_fun_jac_ut_xt_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_fun_jac_ut_xt_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_fun_jac_ut_xt_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_fun_jac_ut_xt_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_fun_jac_ut_xt_incref(void) { +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_fun_jac_ut_xt_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_fun_jac_ut_xt_n_in(void) { return 4;} + +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_fun_jac_ut_xt_n_out(void) { return 3;} + +CASADI_SYMBOL_EXPORT casadi_real lat_cost_y_fun_jac_ut_xt_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_cost_y_fun_jac_ut_xt_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_cost_y_fun_jac_ut_xt_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + case 1: return "o1"; + case 2: return "o2"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_fun_jac_ut_xt_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + case 3: return casadi_s3; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_fun_jac_ut_xt_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s4; + case 1: return casadi_s5; + case 2: return casadi_s6; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_fun_jac_ut_xt_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 4; + if (sz_res) *sz_res = 3; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_hess.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_hess.c new file mode 100644 index 0000000..422fe45 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_cost/lat_cost_y_hess.c @@ -0,0 +1,152 @@ +/* This file was automatically generated by CasADi 3.6.4. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) lat_cost_y_hess_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) +#define casadi_s4 CASADI_PREFIX(s4) +#define casadi_s5 CASADI_PREFIX(s5) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +static const casadi_int casadi_s0[8] = {4, 1, 0, 4, 0, 1, 2, 3}; +static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; +static const casadi_int casadi_s2[3] = {0, 0, 0}; +static const casadi_int casadi_s3[9] = {5, 1, 0, 5, 0, 1, 2, 3, 4}; +static const casadi_int casadi_s4[6] = {2, 1, 0, 2, 0, 1}; +static const casadi_int casadi_s5[8] = {5, 5, 0, 0, 0, 0, 0, 0}; + +/* lat_cost_y_hess:(i0[4],i1,i2[],i3[5],i4[2])->(o0[5x5,0nz]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_hess(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_hess_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_hess_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_hess_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_hess_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_hess_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_hess_incref(void) { +} + +CASADI_SYMBOL_EXPORT void lat_cost_y_hess_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_hess_n_in(void) { return 5;} + +CASADI_SYMBOL_EXPORT casadi_int lat_cost_y_hess_n_out(void) { return 1;} + +CASADI_SYMBOL_EXPORT casadi_real lat_cost_y_hess_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_cost_y_hess_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + case 4: return "i4"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_cost_y_hess_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_hess_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + case 3: return casadi_s3; + case 4: return casadi_s4; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_cost_y_hess_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s5; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int lat_cost_y_hess_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 5; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_model/lat_expl_ode_fun.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_model/lat_expl_ode_fun.c new file mode 100644 index 0000000..df55b59 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_model/lat_expl_ode_fun.c @@ -0,0 +1,164 @@ +/* This file was automatically generated by CasADi 3.6.4. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) lat_expl_ode_fun_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +static const casadi_int casadi_s0[8] = {4, 1, 0, 4, 0, 1, 2, 3}; +static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; +static const casadi_int casadi_s2[6] = {2, 1, 0, 2, 0, 1}; + +/* lat_expl_ode_fun:(i0[4],i1,i2[2])->(o0[4]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a2, a3, a4, a5; + a0=arg[2]? arg[2][0] : 0; + a1=arg[0]? arg[0][2] : 0; + a2=cos(a1); + a2=(a0*a2); + a3=arg[2]? arg[2][1] : 0; + a4=sin(a1); + a4=(a3*a4); + a5=arg[0]? arg[0][3] : 0; + a4=(a4*a5); + a2=(a2-a4); + if (res[0]!=0) res[0][0]=a2; + a2=sin(a1); + a0=(a0*a2); + a1=cos(a1); + a3=(a3*a1); + a3=(a3*a5); + a0=(a0+a3); + if (res[0]!=0) res[0][1]=a0; + if (res[0]!=0) res[0][2]=a5; + a5=arg[1]? arg[1][0] : 0; + if (res[0]!=0) res[0][3]=a5; + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_expl_ode_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int lat_expl_ode_fun_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_expl_ode_fun_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_expl_ode_fun_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int lat_expl_ode_fun_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_expl_ode_fun_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void lat_expl_ode_fun_incref(void) { +} + +CASADI_SYMBOL_EXPORT void lat_expl_ode_fun_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int lat_expl_ode_fun_n_in(void) { return 3;} + +CASADI_SYMBOL_EXPORT casadi_int lat_expl_ode_fun_n_out(void) { return 1;} + +CASADI_SYMBOL_EXPORT casadi_real lat_expl_ode_fun_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_expl_ode_fun_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_expl_ode_fun_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_expl_ode_fun_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_expl_ode_fun_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int lat_expl_ode_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 3; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_model/lat_expl_vde_adj.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_model/lat_expl_vde_adj.c new file mode 100644 index 0000000..6be7e00 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_model/lat_expl_vde_adj.c @@ -0,0 +1,186 @@ +/* This file was automatically generated by CasADi 3.6.4. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) lat_expl_vde_adj_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +static const casadi_int casadi_s0[8] = {4, 1, 0, 4, 0, 1, 2, 3}; +static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; +static const casadi_int casadi_s2[6] = {2, 1, 0, 2, 0, 1}; +static const casadi_int casadi_s3[9] = {5, 1, 0, 5, 0, 1, 2, 3, 4}; + +/* lat_expl_vde_adj:(i0[4],i1[4],i2,i3[2])->(o0[5]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a2, a3, a4, a5, a6, a7; + a0=0.; + if (res[0]!=0) res[0][0]=a0; + if (res[0]!=0) res[0][1]=a0; + a0=arg[0]? arg[0][2] : 0; + a1=cos(a0); + a2=arg[3]? arg[3][0] : 0; + a3=arg[1]? arg[1][1] : 0; + a4=(a2*a3); + a1=(a1*a4); + a4=sin(a0); + a5=arg[3]? arg[3][1] : 0; + a6=arg[0]? arg[0][3] : 0; + a7=(a6*a3); + a7=(a5*a7); + a4=(a4*a7); + a1=(a1-a4); + a4=cos(a0); + a7=arg[1]? arg[1][0] : 0; + a6=(a6*a7); + a6=(a5*a6); + a4=(a4*a6); + a1=(a1-a4); + a4=sin(a0); + a2=(a2*a7); + a4=(a4*a2); + a1=(a1-a4); + if (res[0]!=0) res[0][2]=a1; + a1=arg[1]? arg[1][2] : 0; + a4=cos(a0); + a4=(a5*a4); + a4=(a4*a3); + a1=(a1+a4); + a0=sin(a0); + a5=(a5*a0); + a5=(a5*a7); + a1=(a1-a5); + if (res[0]!=0) res[0][3]=a1; + a1=arg[1]? arg[1][3] : 0; + if (res[0]!=0) res[0][4]=a1; + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_expl_vde_adj(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int lat_expl_vde_adj_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_expl_vde_adj_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_expl_vde_adj_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int lat_expl_vde_adj_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_expl_vde_adj_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void lat_expl_vde_adj_incref(void) { +} + +CASADI_SYMBOL_EXPORT void lat_expl_vde_adj_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int lat_expl_vde_adj_n_in(void) { return 4;} + +CASADI_SYMBOL_EXPORT casadi_int lat_expl_vde_adj_n_out(void) { return 1;} + +CASADI_SYMBOL_EXPORT casadi_real lat_expl_vde_adj_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_expl_vde_adj_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_expl_vde_adj_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_expl_vde_adj_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s0; + case 2: return casadi_s1; + case 3: return casadi_s2; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_expl_vde_adj_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s3; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int lat_expl_vde_adj_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 4; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_model/lat_expl_vde_forw.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_model/lat_expl_vde_forw.c new file mode 100644 index 0000000..664e146 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/lat_model/lat_expl_vde_forw.c @@ -0,0 +1,299 @@ +/* This file was automatically generated by CasADi 3.6.4. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) lat_expl_vde_forw_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +static const casadi_int casadi_s0[8] = {4, 1, 0, 4, 0, 1, 2, 3}; +static const casadi_int casadi_s1[23] = {4, 4, 0, 4, 8, 12, 16, 0, 1, 2, 3, 0, 1, 2, 3, 0, 1, 2, 3, 0, 1, 2, 3}; +static const casadi_int casadi_s2[5] = {1, 1, 0, 1, 0}; +static const casadi_int casadi_s3[6] = {2, 1, 0, 2, 0, 1}; + +/* lat_expl_vde_forw:(i0[4],i1[4x4],i2[4],i3,i4[2])->(o0[4],o1[4x4],o2[4]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a10, a11, a12, a13, a14, a15, a2, a3, a4, a5, a6, a7, a8, a9; + a0=arg[4]? arg[4][0] : 0; + a1=arg[0]? arg[0][2] : 0; + a2=cos(a1); + a2=(a0*a2); + a3=arg[4]? arg[4][1] : 0; + a4=sin(a1); + a4=(a3*a4); + a5=arg[0]? arg[0][3] : 0; + a6=(a4*a5); + a2=(a2-a6); + if (res[0]!=0) res[0][0]=a2; + a2=sin(a1); + a2=(a0*a2); + a6=cos(a1); + a6=(a3*a6); + a7=(a6*a5); + a2=(a2+a7); + if (res[0]!=0) res[0][1]=a2; + if (res[0]!=0) res[0][2]=a5; + a2=arg[3]? arg[3][0] : 0; + if (res[0]!=0) res[0][3]=a2; + a2=sin(a1); + a7=arg[1]? arg[1][2] : 0; + a8=(a2*a7); + a8=(a0*a8); + a9=cos(a1); + a10=(a9*a7); + a10=(a3*a10); + a10=(a5*a10); + a11=arg[1]? arg[1][3] : 0; + a12=(a4*a11); + a10=(a10+a12); + a8=(a8+a10); + a8=(-a8); + if (res[1]!=0) res[1][0]=a8; + a8=cos(a1); + a10=(a8*a7); + a10=(a0*a10); + a12=(a6*a11); + a13=sin(a1); + a7=(a13*a7); + a7=(a3*a7); + a7=(a5*a7); + a12=(a12-a7); + a10=(a10+a12); + if (res[1]!=0) res[1][1]=a10; + if (res[1]!=0) res[1][2]=a11; + a11=0.; + if (res[1]!=0) res[1][3]=a11; + a10=arg[1]? arg[1][6] : 0; + a12=(a2*a10); + a12=(a0*a12); + a7=(a9*a10); + a7=(a3*a7); + a7=(a5*a7); + a14=arg[1]? arg[1][7] : 0; + a15=(a4*a14); + a7=(a7+a15); + a12=(a12+a7); + a12=(-a12); + if (res[1]!=0) res[1][4]=a12; + a12=(a8*a10); + a12=(a0*a12); + a7=(a6*a14); + a10=(a13*a10); + a10=(a3*a10); + a10=(a5*a10); + a7=(a7-a10); + a12=(a12+a7); + if (res[1]!=0) res[1][5]=a12; + if (res[1]!=0) res[1][6]=a14; + if (res[1]!=0) res[1][7]=a11; + a14=arg[1]? arg[1][10] : 0; + a12=(a2*a14); + a12=(a0*a12); + a7=(a9*a14); + a7=(a3*a7); + a7=(a5*a7); + a10=arg[1]? arg[1][11] : 0; + a15=(a4*a10); + a7=(a7+a15); + a12=(a12+a7); + a12=(-a12); + if (res[1]!=0) res[1][8]=a12; + a12=(a8*a14); + a12=(a0*a12); + a7=(a6*a10); + a14=(a13*a14); + a14=(a3*a14); + a14=(a5*a14); + a7=(a7-a14); + a12=(a12+a7); + if (res[1]!=0) res[1][9]=a12; + if (res[1]!=0) res[1][10]=a10; + if (res[1]!=0) res[1][11]=a11; + a10=arg[1]? arg[1][14] : 0; + a2=(a2*a10); + a2=(a0*a2); + a9=(a9*a10); + a9=(a3*a9); + a9=(a5*a9); + a12=arg[1]? arg[1][15] : 0; + a7=(a4*a12); + a9=(a9+a7); + a2=(a2+a9); + a2=(-a2); + if (res[1]!=0) res[1][12]=a2; + a8=(a8*a10); + a8=(a0*a8); + a2=(a6*a12); + a13=(a13*a10); + a13=(a3*a13); + a13=(a5*a13); + a2=(a2-a13); + a8=(a8+a2); + if (res[1]!=0) res[1][13]=a8; + if (res[1]!=0) res[1][14]=a12; + if (res[1]!=0) res[1][15]=a11; + a11=sin(a1); + a12=arg[2]? arg[2][2] : 0; + a11=(a11*a12); + a11=(a0*a11); + a8=cos(a1); + a8=(a8*a12); + a8=(a3*a8); + a8=(a5*a8); + a2=arg[2]? arg[2][3] : 0; + a4=(a4*a2); + a8=(a8+a4); + a11=(a11+a8); + a11=(-a11); + if (res[2]!=0) res[2][0]=a11; + a11=cos(a1); + a11=(a11*a12); + a0=(a0*a11); + a6=(a6*a2); + a1=sin(a1); + a1=(a1*a12); + a3=(a3*a1); + a5=(a5*a3); + a6=(a6-a5); + a0=(a0+a6); + if (res[2]!=0) res[2][1]=a0; + if (res[2]!=0) res[2][2]=a2; + a2=1.; + if (res[2]!=0) res[2][3]=a2; + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_expl_vde_forw(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int lat_expl_vde_forw_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int lat_expl_vde_forw_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_expl_vde_forw_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int lat_expl_vde_forw_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void lat_expl_vde_forw_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void lat_expl_vde_forw_incref(void) { +} + +CASADI_SYMBOL_EXPORT void lat_expl_vde_forw_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int lat_expl_vde_forw_n_in(void) { return 5;} + +CASADI_SYMBOL_EXPORT casadi_int lat_expl_vde_forw_n_out(void) { return 3;} + +CASADI_SYMBOL_EXPORT casadi_real lat_expl_vde_forw_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_expl_vde_forw_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + case 4: return "i4"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* lat_expl_vde_forw_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + case 1: return "o1"; + case 2: return "o2"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_expl_vde_forw_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s0; + case 3: return casadi_s2; + case 4: return casadi_s3; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* lat_expl_vde_forw_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s0; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int lat_expl_vde_forw_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 5; + if (sz_res) *sz_res = 3; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/libacados_ocp_solver_lat.so b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/libacados_ocp_solver_lat.so new file mode 100755 index 0000000..7ed2658 Binary files /dev/null and b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/libacados_ocp_solver_lat.so differ diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/main_lat.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/main_lat.c new file mode 100644 index 0000000..01fbdc6 --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/main_lat.c @@ -0,0 +1,216 @@ +/* + * Copyright (c) The acados authors. + * + * This file is part of acados. + * + * The 2-Clause BSD License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE.; + */ + + +// standard +#include +#include +// acados +#include "acados/utils/print.h" +#include "acados/utils/math.h" +#include "acados_c/ocp_nlp_interface.h" +#include "acados_c/external_function_interface.h" +#include "acados_solver_lat.h" + +// blasfeo +#include "blasfeo/include/blasfeo_d_aux_ext_dep.h" + +#define NX LAT_NX +#define NZ LAT_NZ +#define NU LAT_NU +#define NP LAT_NP +#define NBX LAT_NBX +#define NBX0 LAT_NBX0 +#define NBU LAT_NBU +#define NSBX LAT_NSBX +#define NSBU LAT_NSBU +#define NSH LAT_NSH +#define NSG LAT_NSG +#define NSPHI LAT_NSPHI +#define NSHN LAT_NSHN +#define NSGN LAT_NSGN +#define NSPHIN LAT_NSPHIN +#define NSBXN LAT_NSBXN +#define NS LAT_NS +#define NSN LAT_NSN +#define NG LAT_NG +#define NBXN LAT_NBXN +#define NGN LAT_NGN +#define NY0 LAT_NY0 +#define NY LAT_NY +#define NYN LAT_NYN +#define NH LAT_NH +#define NPHI LAT_NPHI +#define NHN LAT_NHN +#define NPHIN LAT_NPHIN +#define NR LAT_NR + + +int main() +{ + + lat_solver_capsule *acados_ocp_capsule = lat_acados_create_capsule(); + // there is an opportunity to change the number of shooting intervals in C without new code generation + int N = LAT_N; + // allocate the array and fill it accordingly + double* new_time_steps = NULL; + int status = lat_acados_create_with_discretization(acados_ocp_capsule, N, new_time_steps); + + if (status) + { + printf("lat_acados_create() returned status %d. Exiting.\n", status); + exit(1); + } + + ocp_nlp_config *nlp_config = lat_acados_get_nlp_config(acados_ocp_capsule); + ocp_nlp_dims *nlp_dims = lat_acados_get_nlp_dims(acados_ocp_capsule); + ocp_nlp_in *nlp_in = lat_acados_get_nlp_in(acados_ocp_capsule); + ocp_nlp_out *nlp_out = lat_acados_get_nlp_out(acados_ocp_capsule); + ocp_nlp_solver *nlp_solver = lat_acados_get_nlp_solver(acados_ocp_capsule); + void *nlp_opts = lat_acados_get_nlp_opts(acados_ocp_capsule); + + // initial condition + int idxbx0[NBX0]; + idxbx0[0] = 0; + idxbx0[1] = 1; + idxbx0[2] = 2; + idxbx0[3] = 3; + + double lbx0[NBX0]; + double ubx0[NBX0]; + lbx0[0] = 0.0; + ubx0[0] = 0.0; + lbx0[1] = 0.0; + ubx0[1] = 0.0; + lbx0[2] = 0.0; + ubx0[2] = 0.0; + lbx0[3] = 0.0; + ubx0[3] = 0.0; + + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "idxbx", idxbx0); + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "lbx", lbx0); + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "ubx", ubx0); + + // initialization for state values + double x_init[NX]; + x_init[0] = 0.0; + x_init[1] = 0.0; + x_init[2] = 0.0; + x_init[3] = 0.0; + + // initial value for control input + double u0[NU]; + u0[0] = 0.0; + // set parameters + double p[NP]; + p[0] = 0.0; + p[1] = 0.0; + + for (int ii = 0; ii <= N; ii++) + { + lat_acados_update_params(acados_ocp_capsule, ii, p, NP); + } + + + // prepare evaluation + int NTIMINGS = 1; + double min_time = 1e12; + double kkt_norm_inf; + double elapsed_time; + int sqp_iter; + + double xtraj[NX * (N+1)]; + double utraj[NU * N]; + + + // solve ocp in loop + int rti_phase = 0; + + for (int ii = 0; ii < NTIMINGS; ii++) + { + // initialize solution + for (int i = 0; i < N; i++) + { + ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, i, "x", x_init); + ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, i, "u", u0); + } + ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, N, "x", x_init); + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "rti_phase", &rti_phase); + status = lat_acados_solve(acados_ocp_capsule); + ocp_nlp_get(nlp_config, nlp_solver, "time_tot", &elapsed_time); + min_time = MIN(elapsed_time, min_time); + } + + /* print solution and statistics */ + for (int ii = 0; ii <= nlp_dims->N; ii++) + ocp_nlp_out_get(nlp_config, nlp_dims, nlp_out, ii, "x", &xtraj[ii*NX]); + for (int ii = 0; ii < nlp_dims->N; ii++) + ocp_nlp_out_get(nlp_config, nlp_dims, nlp_out, ii, "u", &utraj[ii*NU]); + + printf("\n--- xtraj ---\n"); + d_print_exp_tran_mat( NX, N+1, xtraj, NX); + printf("\n--- utraj ---\n"); + d_print_exp_tran_mat( NU, N, utraj, NU ); + // ocp_nlp_out_print(nlp_solver->dims, nlp_out); + + printf("\nsolved ocp %d times, solution printed above\n\n", NTIMINGS); + + if (status == ACADOS_SUCCESS) + { + printf("lat_acados_solve(): SUCCESS!\n"); + } + else + { + printf("lat_acados_solve() failed with status %d.\n", status); + } + + // get solution + ocp_nlp_out_get(nlp_config, nlp_dims, nlp_out, 0, "kkt_norm_inf", &kkt_norm_inf); + ocp_nlp_get(nlp_config, nlp_solver, "sqp_iter", &sqp_iter); + + lat_acados_print_stats(acados_ocp_capsule); + + printf("\nSolver info:\n"); + printf(" SQP iterations %2d\n minimum time for %d solve %f [ms]\n KKT %e\n", + sqp_iter, NTIMINGS, min_time*1000, kkt_norm_inf); + + // free solver + status = lat_acados_free(acados_ocp_capsule); + if (status) { + printf("lat_acados_free() returned status %d. \n", status); + } + // free solver capsule + status = lat_acados_free_capsule(acados_ocp_capsule); + if (status) { + printf("lat_acados_free_capsule() returned status %d. \n", status); + } + + return status; +} diff --git a/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/main_sim_lat.c b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/main_sim_lat.c new file mode 100644 index 0000000..77bf8dd --- /dev/null +++ b/selfdrive/controls/lib/lateral_mpc_lib/c_generated_code/main_sim_lat.c @@ -0,0 +1,125 @@ +/* + * Copyright (c) The acados authors. + * + * This file is part of acados. + * + * The 2-Clause BSD License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE.; + */ + + +// standard +#include +#include +// acados +#include "acados/utils/print.h" +#include "acados/utils/math.h" +#include "acados_c/sim_interface.h" +#include "acados_sim_solver_lat.h" + +#define NX LAT_NX +#define NZ LAT_NZ +#define NU LAT_NU +#define NP LAT_NP + + +int main() +{ + int status = 0; + sim_solver_capsule *capsule = lat_acados_sim_solver_create_capsule(); + status = lat_acados_sim_create(capsule); + + if (status) + { + printf("acados_create() returned status %d. Exiting.\n", status); + exit(1); + } + + sim_config *acados_sim_config = lat_acados_get_sim_config(capsule); + sim_in *acados_sim_in = lat_acados_get_sim_in(capsule); + sim_out *acados_sim_out = lat_acados_get_sim_out(capsule); + void *acados_sim_dims = lat_acados_get_sim_dims(capsule); + + // initial condition + double x_current[NX]; + x_current[0] = 0.0; + x_current[1] = 0.0; + x_current[2] = 0.0; + x_current[3] = 0.0; + + + x_current[0] = 0.0; + x_current[1] = 0.0; + x_current[2] = 0.0; + x_current[3] = 0.0; + + + + + // initial value for control input + double u0[NU]; + u0[0] = 0.0; + // set parameters + double p[NP]; + p[0] = 0.0; + p[1] = 0.0; + + lat_acados_sim_update_params(capsule, p, NP); + + + int n_sim_steps = 3; + // solve ocp in loop + for (int ii = 0; ii < n_sim_steps; ii++) + { + sim_in_set(acados_sim_config, acados_sim_dims, + acados_sim_in, "x", x_current); + status = lat_acados_sim_solve(capsule); + + if (status != ACADOS_SUCCESS) + { + printf("acados_solve() failed with status %d.\n", status); + } + + sim_out_get(acados_sim_config, acados_sim_dims, + acados_sim_out, "x", x_current); + + printf("\nx_current, %d\n", ii); + for (int jj = 0; jj < NX; jj++) + { + printf("%e\n", x_current[jj]); + } + } + + printf("\nPerformed %d simulation steps with acados integrator successfully.\n\n", n_sim_steps); + + // free solver + status = lat_acados_sim_free(capsule); + if (status) { + printf("lat_acados_sim_free() returned status %d. \n", status); + } + + lat_acados_sim_solver_free_capsule(capsule); + + return status; +} diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/SConscript b/selfdrive/controls/lib/longitudinal_mpc_lib/SConscript deleted file mode 100644 index 79afa1d..0000000 --- a/selfdrive/controls/lib/longitudinal_mpc_lib/SConscript +++ /dev/null @@ -1,96 +0,0 @@ -Import('env', 'envCython', 'arch', 'messaging_python', 'common_python') - -gen = "c_generated_code" - -casadi_model = [ - f'{gen}/long_model/long_expl_ode_fun.c', - f'{gen}/long_model/long_expl_vde_forw.c', -] - -casadi_cost_y = [ - f'{gen}/long_cost/long_cost_y_fun.c', - f'{gen}/long_cost/long_cost_y_fun_jac_ut_xt.c', - f'{gen}/long_cost/long_cost_y_hess.c', -] - -casadi_cost_e = [ - f'{gen}/long_cost/long_cost_y_e_fun.c', - f'{gen}/long_cost/long_cost_y_e_fun_jac_ut_xt.c', - f'{gen}/long_cost/long_cost_y_e_hess.c', -] - -casadi_cost_0 = [ - f'{gen}/long_cost/long_cost_y_0_fun.c', - f'{gen}/long_cost/long_cost_y_0_fun_jac_ut_xt.c', - f'{gen}/long_cost/long_cost_y_0_hess.c', -] - -casadi_constraints = [ - f'{gen}/long_constraints/long_constr_h_fun.c', - f'{gen}/long_constraints/long_constr_h_fun_jac_uxt_zt.c', -] - -build_files = [f'{gen}/acados_solver_long.c'] + casadi_model + casadi_cost_y + casadi_cost_e + \ - casadi_cost_0 + casadi_constraints - -# extra generated files used to trigger a rebuild -generated_files = [ - f'{gen}/Makefile', - - f'{gen}/main_long.c', - f'{gen}/main_sim_long.c', - f'{gen}/acados_solver_long.h', - f'{gen}/acados_sim_solver_long.h', - f'{gen}/acados_sim_solver_long.c', - f'{gen}/acados_solver.pxd', - - f'{gen}/long_model/long_expl_vde_adj.c', - - f'{gen}/long_model/long_model.h', - f'{gen}/long_constraints/long_constraints.h', - f'{gen}/long_cost/long_cost.h', -] + build_files - -acados_dir = '#third_party/acados' -acados_templates_dir = '#third_party/acados/acados_template/c_templates_tera' - -source_list = ['long_mpc.py', - '#selfdrive/modeld/constants.py', - f'{acados_dir}/include/acados_c/ocp_nlp_interface.h', - f'{acados_templates_dir}/acados_solver.in.c', -] - -lenv = env.Clone() -lenv.Clean(generated_files, Dir(gen)) - -generated_long = lenv.Command(generated_files, - source_list, - f"cd {Dir('.').abspath} && python3 long_mpc.py") -lenv.Depends(generated_long, [messaging_python, common_python]) - -lenv["CFLAGS"].append("-DACADOS_WITH_QPOASES") -lenv["CXXFLAGS"].append("-DACADOS_WITH_QPOASES") -lenv["CCFLAGS"].append("-Wno-unused") -if arch != "Darwin": - lenv["LINKFLAGS"].append("-Wl,--disable-new-dtags") -lib_solver = lenv.SharedLibrary(f"{gen}/acados_ocp_solver_long", - build_files, - LIBS=['m', 'acados', 'hpipm', 'blasfeo', 'qpOASES_e']) - -# generate cython stuff -acados_ocp_solver_pyx = File("#third_party/acados/acados_template/acados_ocp_solver_pyx.pyx") -acados_ocp_solver_common = File("#third_party/acados/acados_template/acados_solver_common.pxd") -libacados_ocp_solver_pxd = File(f'{gen}/acados_solver.pxd') -libacados_ocp_solver_c = File(f'{gen}/acados_ocp_solver_pyx.c') - -lenv2 = envCython.Clone() -lenv2["LINKFLAGS"] += [lib_solver[0].get_labspath()] -lenv2.Command(libacados_ocp_solver_c, - [acados_ocp_solver_pyx, acados_ocp_solver_common, libacados_ocp_solver_pxd], - f'cython' + \ - f' -o {libacados_ocp_solver_c.get_labspath()}' + \ - f' -I {libacados_ocp_solver_pxd.get_dir().get_labspath()}' + \ - f' -I {acados_ocp_solver_common.get_dir().get_labspath()}' + \ - f' {acados_ocp_solver_pyx.get_labspath()}') -lib_cython = lenv2.Program(f'{gen}/acados_ocp_solver_pyx.so', [libacados_ocp_solver_c]) -lenv2.Depends(lib_cython, lib_solver) diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/Makefile b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/Makefile new file mode 100644 index 0000000..411a77b --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/Makefile @@ -0,0 +1,213 @@ +# +# Copyright (c) The acados authors. +# +# This file is part of acados. +# +# The 2-Clause BSD License +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are met: +# +# 1. Redistributions of source code must retain the above copyright notice, +# this list of conditions and the following disclaimer. +# +# 2. Redistributions in binary form must reproduce the above copyright notice, +# this list of conditions and the following disclaimer in the documentation +# and/or other materials provided with the distribution. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE +# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE.; +# + + + + + +# define sources and use make's implicit rules to generate object files (*.o) + +# model +MODEL_SRC= +MODEL_SRC+= long_model/long_expl_ode_fun.c +MODEL_SRC+= long_model/long_expl_vde_forw.c +MODEL_SRC+= long_model/long_expl_vde_adj.c +MODEL_OBJ := $(MODEL_SRC:.c=.o) + +# optimal control problem - mostly CasADi exports +OCP_SRC= +OCP_SRC+= long_constraints/long_constr_h_fun_jac_uxt_zt.c +OCP_SRC+= long_constraints/long_constr_h_fun.c +OCP_SRC+= long_cost/long_cost_y_0_fun.c +OCP_SRC+= long_cost/long_cost_y_0_fun_jac_ut_xt.c +OCP_SRC+= long_cost/long_cost_y_0_hess.c +OCP_SRC+= long_cost/long_cost_y_fun.c +OCP_SRC+= long_cost/long_cost_y_fun_jac_ut_xt.c +OCP_SRC+= long_cost/long_cost_y_hess.c +OCP_SRC+= long_cost/long_cost_y_e_fun.c +OCP_SRC+= long_cost/long_cost_y_e_fun_jac_ut_xt.c +OCP_SRC+= long_cost/long_cost_y_e_hess.c + +OCP_SRC+= acados_solver_long.c +OCP_OBJ := $(OCP_SRC:.c=.o) + +# for sim solver +SIM_SRC= acados_sim_solver_long.c +SIM_OBJ := $(SIM_SRC:.c=.o) + +# for target example +EX_SRC= main_long.c +EX_OBJ := $(EX_SRC:.c=.o) +EX_EXE := $(EX_SRC:.c=) + +# for target example_sim +EX_SIM_SRC= main_sim_long.c +EX_SIM_OBJ := $(EX_SIM_SRC:.c=.o) +EX_SIM_EXE := $(EX_SIM_SRC:.c=) + +# combine model, sim and ocp object files +OBJ= +OBJ+= $(MODEL_OBJ) +OBJ+= $(SIM_OBJ) +OBJ+= $(OCP_OBJ) + +EXTERNAL_DIR= +EXTERNAL_LIB= + +INCLUDE_PATH = /data/openpilot/third_party/acados/include +LIB_PATH = /data/openpilot/third_party/acados/lib + +# preprocessor flags for make's implicit rules +CPPFLAGS+= -I$(INCLUDE_PATH) +CPPFLAGS+= -I$(INCLUDE_PATH)/acados +CPPFLAGS+= -I$(INCLUDE_PATH)/blasfeo/include +CPPFLAGS+= -I$(INCLUDE_PATH)/hpipm/include + + +# define the c-compiler flags for make's implicit rules +CFLAGS = -fPIC -std=c99 -O2#-fno-diagnostics-show-line-numbers -g +# # Debugging +# CFLAGS += -g3 + +# linker flags +LDFLAGS+= -L$(LIB_PATH) + +# link to libraries +LDLIBS+= -lacados +LDLIBS+= -lhpipm +LDLIBS+= -lblasfeo +LDLIBS+= -lm +LDLIBS+= + +# libraries +LIBACADOS_SOLVER=libacados_solver_long.so +LIBACADOS_OCP_SOLVER=libacados_ocp_solver_long.so +LIBACADOS_SIM_SOLVER=lib$(SIM_SRC:.c=.so) + +# virtual targets +.PHONY : all clean + +#all: clean example_sim example shared_lib + +all: clean example_sim example +shared_lib: bundled_shared_lib ocp_shared_lib sim_shared_lib + +# some linker targets +example: $(EX_OBJ) $(OBJ) + $(CC) $^ -o $(EX_EXE) $(LDFLAGS) $(LDLIBS) + +example_sim: $(EX_SIM_OBJ) $(MODEL_OBJ) $(SIM_OBJ) + $(CC) $^ -o $(EX_SIM_EXE) $(LDFLAGS) $(LDLIBS) + +bundled_shared_lib: $(OBJ) + $(CC) -shared $^ -o $(LIBACADOS_SOLVER) $(LDFLAGS) $(LDLIBS) + +ocp_shared_lib: $(OCP_OBJ) $(MODEL_OBJ) + $(CC) -shared $^ -o $(LIBACADOS_OCP_SOLVER) $(LDFLAGS) $(LDLIBS) \ + -L$(EXTERNAL_DIR) -l$(EXTERNAL_LIB) + +sim_shared_lib: $(SIM_OBJ) $(MODEL_OBJ) + $(CC) -shared $^ -o $(LIBACADOS_SIM_SOLVER) $(LDFLAGS) $(LDLIBS) + + +# Cython targets +ocp_cython_c: ocp_shared_lib + cython \ + -o acados_ocp_solver_pyx.c \ + -I $(INCLUDE_PATH)/../interfaces/acados_template/acados_template \ + $(INCLUDE_PATH)/../interfaces/acados_template/acados_template/acados_ocp_solver_pyx.pyx \ + -I /data/openpilot/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code \ + +ocp_cython_o: ocp_cython_c + $(CC) $(ACADOS_FLAGS) -c -O2 \ + -fPIC \ + -o acados_ocp_solver_pyx.o \ + -I $(INCLUDE_PATH)/blasfeo/include/ \ + -I $(INCLUDE_PATH)/hpipm/include/ \ + -I $(INCLUDE_PATH) \ + -I /usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/core/include \ + -I /usr/local/pyenv/versions/3.11.4/include/python3.11 \ + acados_ocp_solver_pyx.c \ + +ocp_cython: ocp_cython_o + $(CC) $(ACADOS_FLAGS) -shared \ + -o acados_ocp_solver_pyx.so \ + -Wl,-rpath=$(LIB_PATH) \ + acados_ocp_solver_pyx.o \ + $(abspath .)/libacados_ocp_solver_long.so \ + $(LDFLAGS) $(LDLIBS) + +# Sim Cython targets +sim_cython_c: sim_shared_lib + cython \ + -o acados_sim_solver_pyx.c \ + -I $(INCLUDE_PATH)/../interfaces/acados_template/acados_template \ + $(INCLUDE_PATH)/../interfaces/acados_template/acados_template/acados_sim_solver_pyx.pyx \ + -I /data/openpilot/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code \ + +sim_cython_o: sim_cython_c + $(CC) $(ACADOS_FLAGS) -c -O2 \ + -fPIC \ + -o acados_sim_solver_pyx.o \ + -I $(INCLUDE_PATH)/blasfeo/include/ \ + -I $(INCLUDE_PATH)/hpipm/include/ \ + -I $(INCLUDE_PATH) \ + -I /usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/core/include \ + -I /usr/local/pyenv/versions/3.11.4/include/python3.11 \ + acados_sim_solver_pyx.c \ + +sim_cython: sim_cython_o + $(CC) $(ACADOS_FLAGS) -shared \ + -o acados_sim_solver_pyx.so \ + -Wl,-rpath=$(LIB_PATH) \ + acados_sim_solver_pyx.o \ + $(abspath .)/libacados_sim_solver_long.so \ + $(LDFLAGS) $(LDLIBS) + +clean: + $(RM) $(OBJ) $(EX_OBJ) $(EX_SIM_OBJ) + $(RM) $(LIBACADOS_SOLVER) $(LIBACADOS_OCP_SOLVER) $(LIBACADOS_SIM_SOLVER) + $(RM) $(EX_EXE) $(EX_SIM_EXE) + +clean_ocp_shared_lib: + $(RM) $(LIBACADOS_OCP_SOLVER) + $(RM) $(OCP_OBJ) + +clean_ocp_cython: + $(RM) libacados_ocp_solver_long.so + $(RM) acados_solver_long.o + $(RM) acados_ocp_solver_pyx.so + $(RM) acados_ocp_solver_pyx.o + +clean_sim_cython: + $(RM) libacados_sim_solver_long.so + $(RM) acados_sim_solver_long.o + $(RM) acados_sim_solver_pyx.so + $(RM) acados_sim_solver_pyx.o diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_ocp_solver_pyx.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_ocp_solver_pyx.c new file mode 100644 index 0000000..82838e8 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_ocp_solver_pyx.c @@ -0,0 +1,44066 @@ +/* Generated by Cython 3.0.8 */ + +#ifndef PY_SSIZE_T_CLEAN +#define PY_SSIZE_T_CLEAN +#endif /* PY_SSIZE_T_CLEAN */ +#if defined(CYTHON_LIMITED_API) && 0 + #ifndef Py_LIMITED_API + #if CYTHON_LIMITED_API+0 > 0x03030000 + #define Py_LIMITED_API CYTHON_LIMITED_API + #else + #define Py_LIMITED_API 0x03030000 + #endif + #endif +#endif + +#include "Python.h" +#ifndef Py_PYTHON_H + #error Python headers needed to compile C extensions, please install development version of Python. +#elif PY_VERSION_HEX < 0x02070000 || (0x03000000 <= PY_VERSION_HEX && PY_VERSION_HEX < 0x03030000) + #error Cython requires Python 2.7+ or Python 3.3+. +#else +#if defined(CYTHON_LIMITED_API) && CYTHON_LIMITED_API +#define __PYX_EXTRA_ABI_MODULE_NAME "limited" +#else +#define __PYX_EXTRA_ABI_MODULE_NAME "" +#endif +#define CYTHON_ABI "3_0_8" __PYX_EXTRA_ABI_MODULE_NAME +#define __PYX_ABI_MODULE_NAME "_cython_" CYTHON_ABI +#define __PYX_TYPE_MODULE_PREFIX __PYX_ABI_MODULE_NAME "." +#define CYTHON_HEX_VERSION 0x030008F0 +#define CYTHON_FUTURE_DIVISION 1 +#include +#ifndef offsetof + #define offsetof(type, member) ( (size_t) & ((type*)0) -> member ) +#endif +#if !defined(_WIN32) && !defined(WIN32) && !defined(MS_WINDOWS) + #ifndef __stdcall + #define __stdcall + #endif + #ifndef __cdecl + #define __cdecl + #endif + #ifndef __fastcall + #define __fastcall + #endif +#endif +#ifndef DL_IMPORT + #define DL_IMPORT(t) t +#endif +#ifndef DL_EXPORT + #define DL_EXPORT(t) t +#endif +#define __PYX_COMMA , +#ifndef HAVE_LONG_LONG + #define HAVE_LONG_LONG +#endif +#ifndef PY_LONG_LONG + #define PY_LONG_LONG LONG_LONG +#endif +#ifndef Py_HUGE_VAL + #define Py_HUGE_VAL HUGE_VAL +#endif +#define __PYX_LIMITED_VERSION_HEX PY_VERSION_HEX +#if defined(GRAALVM_PYTHON) + /* For very preliminary testing purposes. Most variables are set the same as PyPy. + The existence of this section does not imply that anything works or is even tested */ + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 1 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(PYPY_VERSION) + #define CYTHON_COMPILING_IN_PYPY 1 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #ifndef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #endif + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #if PY_VERSION_HEX < 0x03090000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE (PY_VERSION_HEX >= 0x030400a1 && PYPY_VERSION_NUM >= 0x07030C00) + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(CYTHON_LIMITED_API) + #ifdef Py_LIMITED_API + #undef __PYX_LIMITED_VERSION_HEX + #define __PYX_LIMITED_VERSION_HEX Py_LIMITED_API + #endif + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 1 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_CLINE_IN_TRACEBACK + #define CYTHON_CLINE_IN_TRACEBACK 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 1 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #endif + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 1 + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(Py_GIL_DISABLED) || defined(Py_NOGIL) + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 1 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #ifndef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 +#else + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 1 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #ifndef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #endif + #ifndef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 1 + #endif + #if PY_MAJOR_VERSION < 3 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #ifndef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 1 + #endif + #ifndef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 1 + #endif + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #if PY_VERSION_HEX < 0x030300F0 || PY_VERSION_HEX >= 0x030B00A2 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #elif !defined(CYTHON_USE_UNICODE_WRITER) + #define CYTHON_USE_UNICODE_WRITER 1 + #endif + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #ifndef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 1 + #endif + #ifndef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL (PY_MAJOR_VERSION < 3 || PY_VERSION_HEX >= 0x03060000 && PY_VERSION_HEX < 0x030C00A6) + #endif + #ifndef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL (PY_VERSION_HEX >= 0x030700A1) + #endif + #ifndef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 1 + #endif + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #endif + #if PY_VERSION_HEX < 0x030400a1 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #elif !defined(CYTHON_USE_TP_FINALIZE) + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #if PY_VERSION_HEX < 0x030600B1 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #elif !defined(CYTHON_USE_DICT_VERSIONS) + #define CYTHON_USE_DICT_VERSIONS (PY_VERSION_HEX < 0x030C00A5) + #endif + #if PY_VERSION_HEX < 0x030700A3 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #elif !defined(CYTHON_USE_EXC_INFO_STACK) + #define CYTHON_USE_EXC_INFO_STACK 1 + #endif + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 1 + #endif +#endif +#if !defined(CYTHON_FAST_PYCCALL) +#define CYTHON_FAST_PYCCALL (CYTHON_FAST_PYCALL && PY_VERSION_HEX >= 0x030600B1) +#endif +#if !defined(CYTHON_VECTORCALL) +#define CYTHON_VECTORCALL (CYTHON_FAST_PYCCALL && PY_VERSION_HEX >= 0x030800B1) +#endif +#define CYTHON_BACKPORT_VECTORCALL (CYTHON_METH_FASTCALL && PY_VERSION_HEX < 0x030800B1) +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_MAJOR_VERSION < 3 + #include "longintrepr.h" + #endif + #undef SHIFT + #undef BASE + #undef MASK + #ifdef SIZEOF_VOID_P + enum { __pyx_check_sizeof_voidp = 1 / (int)(SIZEOF_VOID_P == sizeof(void*)) }; + #endif +#endif +#ifndef __has_attribute + #define __has_attribute(x) 0 +#endif +#ifndef __has_cpp_attribute + #define __has_cpp_attribute(x) 0 +#endif +#ifndef CYTHON_RESTRICT + #if defined(__GNUC__) + #define CYTHON_RESTRICT __restrict__ + #elif defined(_MSC_VER) && _MSC_VER >= 1400 + #define CYTHON_RESTRICT __restrict + #elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define CYTHON_RESTRICT restrict + #else + #define CYTHON_RESTRICT + #endif +#endif +#ifndef CYTHON_UNUSED + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(maybe_unused) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(maybe_unused) + #define CYTHON_UNUSED [[maybe_unused]] + #endif + #endif + #endif +#endif +#ifndef CYTHON_UNUSED +# if defined(__GNUC__) +# if !(defined(__cplusplus)) || (__GNUC__ > 3 || (__GNUC__ == 3 && __GNUC_MINOR__ >= 4)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +# elif defined(__ICC) || (defined(__INTEL_COMPILER) && !defined(_MSC_VER)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +#endif +#ifndef CYTHON_UNUSED_VAR +# if defined(__cplusplus) + template void CYTHON_UNUSED_VAR( const T& ) { } +# else +# define CYTHON_UNUSED_VAR(x) (void)(x) +# endif +#endif +#ifndef CYTHON_MAYBE_UNUSED_VAR + #define CYTHON_MAYBE_UNUSED_VAR(x) CYTHON_UNUSED_VAR(x) +#endif +#ifndef CYTHON_NCP_UNUSED +# if CYTHON_COMPILING_IN_CPYTHON +# define CYTHON_NCP_UNUSED +# else +# define CYTHON_NCP_UNUSED CYTHON_UNUSED +# endif +#endif +#ifndef CYTHON_USE_CPP_STD_MOVE + #if defined(__cplusplus) && (\ + __cplusplus >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1600)) + #define CYTHON_USE_CPP_STD_MOVE 1 + #else + #define CYTHON_USE_CPP_STD_MOVE 0 + #endif +#endif +#define __Pyx_void_to_None(void_result) ((void)(void_result), Py_INCREF(Py_None), Py_None) +#ifdef _MSC_VER + #ifndef _MSC_STDINT_H_ + #if _MSC_VER < 1300 + typedef unsigned char uint8_t; + typedef unsigned short uint16_t; + typedef unsigned int uint32_t; + #else + typedef unsigned __int8 uint8_t; + typedef unsigned __int16 uint16_t; + typedef unsigned __int32 uint32_t; + #endif + #endif + #if _MSC_VER < 1300 + #ifdef _WIN64 + typedef unsigned long long __pyx_uintptr_t; + #else + typedef unsigned int __pyx_uintptr_t; + #endif + #else + #ifdef _WIN64 + typedef unsigned __int64 __pyx_uintptr_t; + #else + typedef unsigned __int32 __pyx_uintptr_t; + #endif + #endif +#else + #include + typedef uintptr_t __pyx_uintptr_t; +#endif +#ifndef CYTHON_FALLTHROUGH + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(fallthrough) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(fallthrough) + #define CYTHON_FALLTHROUGH [[fallthrough]] + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_cpp_attribute(clang::fallthrough) + #define CYTHON_FALLTHROUGH [[clang::fallthrough]] + #elif __has_cpp_attribute(gnu::fallthrough) + #define CYTHON_FALLTHROUGH [[gnu::fallthrough]] + #endif + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_attribute(fallthrough) + #define CYTHON_FALLTHROUGH __attribute__((fallthrough)) + #else + #define CYTHON_FALLTHROUGH + #endif + #endif + #if defined(__clang__) && defined(__apple_build_version__) + #if __apple_build_version__ < 7000000 + #undef CYTHON_FALLTHROUGH + #define CYTHON_FALLTHROUGH + #endif + #endif +#endif +#ifdef __cplusplus + template + struct __PYX_IS_UNSIGNED_IMPL {static const bool value = T(0) < T(-1);}; + #define __PYX_IS_UNSIGNED(type) (__PYX_IS_UNSIGNED_IMPL::value) +#else + #define __PYX_IS_UNSIGNED(type) (((type)-1) > 0) +#endif +#if CYTHON_COMPILING_IN_PYPY == 1 + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x030A0000) +#else + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x03090000) +#endif +#define __PYX_REINTERPRET_FUNCION(func_pointer, other_pointer) ((func_pointer)(void(*)(void))(other_pointer)) + +#ifndef CYTHON_INLINE + #if defined(__clang__) + #define CYTHON_INLINE __inline__ __attribute__ ((__unused__)) + #elif defined(__GNUC__) + #define CYTHON_INLINE __inline__ + #elif defined(_MSC_VER) + #define CYTHON_INLINE __inline + #elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define CYTHON_INLINE inline + #else + #define CYTHON_INLINE + #endif +#endif + +#define __PYX_BUILD_PY_SSIZE_T "n" +#define CYTHON_FORMAT_SSIZE_T "z" +#if PY_MAJOR_VERSION < 3 + #define __Pyx_BUILTIN_MODULE_NAME "__builtin__" + #define __Pyx_DefaultClassType PyClass_Type + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a+k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_BUILTIN_MODULE_NAME "builtins" + #define __Pyx_DefaultClassType PyType_Type +#if CYTHON_COMPILING_IN_LIMITED_API + static CYTHON_INLINE PyObject* __Pyx_PyCode_New(int a, int p, int k, int l, int s, int f, + PyObject *code, PyObject *c, PyObject* n, PyObject *v, + PyObject *fv, PyObject *cell, PyObject* fn, + PyObject *name, int fline, PyObject *lnos) { + PyObject *exception_table = NULL; + PyObject *types_module=NULL, *code_type=NULL, *result=NULL; + #if __PYX_LIMITED_VERSION_HEX < 0x030B0000 + PyObject *version_info; + PyObject *py_minor_version = NULL; + #endif + long minor_version = 0; + PyObject *type, *value, *traceback; + PyErr_Fetch(&type, &value, &traceback); + #if __PYX_LIMITED_VERSION_HEX >= 0x030B0000 + minor_version = 11; + #else + if (!(version_info = PySys_GetObject("version_info"))) goto end; + if (!(py_minor_version = PySequence_GetItem(version_info, 1))) goto end; + minor_version = PyLong_AsLong(py_minor_version); + Py_DECREF(py_minor_version); + if (minor_version == -1 && PyErr_Occurred()) goto end; + #endif + if (!(types_module = PyImport_ImportModule("types"))) goto end; + if (!(code_type = PyObject_GetAttrString(types_module, "CodeType"))) goto end; + if (minor_version <= 7) { + (void)p; + result = PyObject_CallFunction(code_type, "iiiiiOOOOOOiOO", a, k, l, s, f, code, + c, n, v, fn, name, fline, lnos, fv, cell); + } else if (minor_version <= 10) { + result = PyObject_CallFunction(code_type, "iiiiiiOOOOOOiOO", a,p, k, l, s, f, code, + c, n, v, fn, name, fline, lnos, fv, cell); + } else { + if (!(exception_table = PyBytes_FromStringAndSize(NULL, 0))) goto end; + result = PyObject_CallFunction(code_type, "iiiiiiOOOOOOOiOO", a,p, k, l, s, f, code, + c, n, v, fn, name, name, fline, lnos, exception_table, fv, cell); + } + end: + Py_XDECREF(code_type); + Py_XDECREF(exception_table); + Py_XDECREF(types_module); + if (type) { + PyErr_Restore(type, value, traceback); + } + return result; + } + #ifndef CO_OPTIMIZED + #define CO_OPTIMIZED 0x0001 + #endif + #ifndef CO_NEWLOCALS + #define CO_NEWLOCALS 0x0002 + #endif + #ifndef CO_VARARGS + #define CO_VARARGS 0x0004 + #endif + #ifndef CO_VARKEYWORDS + #define CO_VARKEYWORDS 0x0008 + #endif + #ifndef CO_ASYNC_GENERATOR + #define CO_ASYNC_GENERATOR 0x0200 + #endif + #ifndef CO_GENERATOR + #define CO_GENERATOR 0x0020 + #endif + #ifndef CO_COROUTINE + #define CO_COROUTINE 0x0080 + #endif +#elif PY_VERSION_HEX >= 0x030B0000 + static CYTHON_INLINE PyCodeObject* __Pyx_PyCode_New(int a, int p, int k, int l, int s, int f, + PyObject *code, PyObject *c, PyObject* n, PyObject *v, + PyObject *fv, PyObject *cell, PyObject* fn, + PyObject *name, int fline, PyObject *lnos) { + PyCodeObject *result; + PyObject *empty_bytes = PyBytes_FromStringAndSize("", 0); + if (!empty_bytes) return NULL; + result = + #if PY_VERSION_HEX >= 0x030C0000 + PyUnstable_Code_NewWithPosOnlyArgs + #else + PyCode_NewWithPosOnlyArgs + #endif + (a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, name, fline, lnos, empty_bytes); + Py_DECREF(empty_bytes); + return result; + } +#elif PY_VERSION_HEX >= 0x030800B2 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_NewWithPosOnlyArgs(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#endif +#endif +#if PY_VERSION_HEX >= 0x030900A4 || defined(Py_IS_TYPE) + #define __Pyx_IS_TYPE(ob, type) Py_IS_TYPE(ob, type) +#else + #define __Pyx_IS_TYPE(ob, type) (((const PyObject*)ob)->ob_type == (type)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_Is) + #define __Pyx_Py_Is(x, y) Py_Is(x, y) +#else + #define __Pyx_Py_Is(x, y) ((x) == (y)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsNone) + #define __Pyx_Py_IsNone(ob) Py_IsNone(ob) +#else + #define __Pyx_Py_IsNone(ob) __Pyx_Py_Is((ob), Py_None) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsTrue) + #define __Pyx_Py_IsTrue(ob) Py_IsTrue(ob) +#else + #define __Pyx_Py_IsTrue(ob) __Pyx_Py_Is((ob), Py_True) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsFalse) + #define __Pyx_Py_IsFalse(ob) Py_IsFalse(ob) +#else + #define __Pyx_Py_IsFalse(ob) __Pyx_Py_Is((ob), Py_False) +#endif +#define __Pyx_NoneAsNull(obj) (__Pyx_Py_IsNone(obj) ? NULL : (obj)) +#if PY_VERSION_HEX >= 0x030900F0 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_GC_IsFinalized(o) PyObject_GC_IsFinalized(o) +#else + #define __Pyx_PyObject_GC_IsFinalized(o) _PyGC_FINALIZED(o) +#endif +#ifndef CO_COROUTINE + #define CO_COROUTINE 0x80 +#endif +#ifndef CO_ASYNC_GENERATOR + #define CO_ASYNC_GENERATOR 0x200 +#endif +#ifndef Py_TPFLAGS_CHECKTYPES + #define Py_TPFLAGS_CHECKTYPES 0 +#endif +#ifndef Py_TPFLAGS_HAVE_INDEX + #define Py_TPFLAGS_HAVE_INDEX 0 +#endif +#ifndef Py_TPFLAGS_HAVE_NEWBUFFER + #define Py_TPFLAGS_HAVE_NEWBUFFER 0 +#endif +#ifndef Py_TPFLAGS_HAVE_FINALIZE + #define Py_TPFLAGS_HAVE_FINALIZE 0 +#endif +#ifndef Py_TPFLAGS_SEQUENCE + #define Py_TPFLAGS_SEQUENCE 0 +#endif +#ifndef Py_TPFLAGS_MAPPING + #define Py_TPFLAGS_MAPPING 0 +#endif +#ifndef METH_STACKLESS + #define METH_STACKLESS 0 +#endif +#if PY_VERSION_HEX <= 0x030700A3 || !defined(METH_FASTCALL) + #ifndef METH_FASTCALL + #define METH_FASTCALL 0x80 + #endif + typedef PyObject *(*__Pyx_PyCFunctionFast) (PyObject *self, PyObject *const *args, Py_ssize_t nargs); + typedef PyObject *(*__Pyx_PyCFunctionFastWithKeywords) (PyObject *self, PyObject *const *args, + Py_ssize_t nargs, PyObject *kwnames); +#else + #define __Pyx_PyCFunctionFast _PyCFunctionFast + #define __Pyx_PyCFunctionFastWithKeywords _PyCFunctionFastWithKeywords +#endif +#if CYTHON_METH_FASTCALL + #define __Pyx_METH_FASTCALL METH_FASTCALL + #define __Pyx_PyCFunction_FastCall __Pyx_PyCFunctionFast + #define __Pyx_PyCFunction_FastCallWithKeywords __Pyx_PyCFunctionFastWithKeywords +#else + #define __Pyx_METH_FASTCALL METH_VARARGS + #define __Pyx_PyCFunction_FastCall PyCFunction + #define __Pyx_PyCFunction_FastCallWithKeywords PyCFunctionWithKeywords +#endif +#if CYTHON_VECTORCALL + #define __pyx_vectorcallfunc vectorcallfunc + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET PY_VECTORCALL_ARGUMENTS_OFFSET + #define __Pyx_PyVectorcall_NARGS(n) PyVectorcall_NARGS((size_t)(n)) +#elif CYTHON_BACKPORT_VECTORCALL + typedef PyObject *(*__pyx_vectorcallfunc)(PyObject *callable, PyObject *const *args, + size_t nargsf, PyObject *kwnames); + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET ((size_t)1 << (8 * sizeof(size_t) - 1)) + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(((size_t)(n)) & ~__Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET)) +#else + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET 0 + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(n)) +#endif +#if PY_MAJOR_VERSION >= 0x030900B1 +#define __Pyx_PyCFunction_CheckExact(func) PyCFunction_CheckExact(func) +#else +#define __Pyx_PyCFunction_CheckExact(func) PyCFunction_Check(func) +#endif +#define __Pyx_CyOrPyCFunction_Check(func) PyCFunction_Check(func) +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_CyOrPyCFunction_GET_FUNCTION(func) (((PyCFunctionObject*)(func))->m_ml->ml_meth) +#elif !CYTHON_COMPILING_IN_LIMITED_API +#define __Pyx_CyOrPyCFunction_GET_FUNCTION(func) PyCFunction_GET_FUNCTION(func) +#endif +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_CyOrPyCFunction_GET_FLAGS(func) (((PyCFunctionObject*)(func))->m_ml->ml_flags) +static CYTHON_INLINE PyObject* __Pyx_CyOrPyCFunction_GET_SELF(PyObject *func) { + return (__Pyx_CyOrPyCFunction_GET_FLAGS(func) & METH_STATIC) ? NULL : ((PyCFunctionObject*)func)->m_self; +} +#endif +static CYTHON_INLINE int __Pyx__IsSameCFunction(PyObject *func, void *cfunc) { +#if CYTHON_COMPILING_IN_LIMITED_API + return PyCFunction_Check(func) && PyCFunction_GetFunction(func) == (PyCFunction) cfunc; +#else + return PyCFunction_Check(func) && PyCFunction_GET_FUNCTION(func) == (PyCFunction) cfunc; +#endif +} +#define __Pyx_IsSameCFunction(func, cfunc) __Pyx__IsSameCFunction(func, cfunc) +#if __PYX_LIMITED_VERSION_HEX < 0x030900B1 + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) ((void)m, PyType_FromSpecWithBases(s, b)) + typedef PyObject *(*__Pyx_PyCMethod)(PyObject *, PyTypeObject *, PyObject *const *, size_t, PyObject *); +#else + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) PyType_FromModuleAndSpec(m, s, b) + #define __Pyx_PyCMethod PyCMethod +#endif +#ifndef METH_METHOD + #define METH_METHOD 0x200 +#endif +#if CYTHON_COMPILING_IN_PYPY && !defined(PyObject_Malloc) + #define PyObject_Malloc(s) PyMem_Malloc(s) + #define PyObject_Free(p) PyMem_Free(p) + #define PyObject_Realloc(p) PyMem_Realloc(p) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) +#else + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) (frame)->f_lineno = (lineno) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyThreadState_Current PyThreadState_Get() +#elif !CYTHON_FAST_THREAD_STATE + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#elif PY_VERSION_HEX >= 0x030d00A1 + #define __Pyx_PyThreadState_Current PyThreadState_GetUnchecked() +#elif PY_VERSION_HEX >= 0x03060000 + #define __Pyx_PyThreadState_Current _PyThreadState_UncheckedGet() +#elif PY_VERSION_HEX >= 0x03000000 + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#else + #define __Pyx_PyThreadState_Current _PyThreadState_Current +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE void *__Pyx_PyModule_GetState(PyObject *op) +{ + void *result; + result = PyModule_GetState(op); + if (!result) + Py_FatalError("Couldn't find the module state"); + return result; +} +#endif +#define __Pyx_PyObject_GetSlot(obj, name, func_ctype) __Pyx_PyType_GetSlot(Py_TYPE(obj), name, func_ctype) +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((func_ctype) PyType_GetSlot((type), Py_##name)) +#else + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((type)->name) +#endif +#if PY_VERSION_HEX < 0x030700A2 && !defined(PyThread_tss_create) && !defined(Py_tss_NEEDS_INIT) +#include "pythread.h" +#define Py_tss_NEEDS_INIT 0 +typedef int Py_tss_t; +static CYTHON_INLINE int PyThread_tss_create(Py_tss_t *key) { + *key = PyThread_create_key(); + return 0; +} +static CYTHON_INLINE Py_tss_t * PyThread_tss_alloc(void) { + Py_tss_t *key = (Py_tss_t *)PyObject_Malloc(sizeof(Py_tss_t)); + *key = Py_tss_NEEDS_INIT; + return key; +} +static CYTHON_INLINE void PyThread_tss_free(Py_tss_t *key) { + PyObject_Free(key); +} +static CYTHON_INLINE int PyThread_tss_is_created(Py_tss_t *key) { + return *key != Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE void PyThread_tss_delete(Py_tss_t *key) { + PyThread_delete_key(*key); + *key = Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE int PyThread_tss_set(Py_tss_t *key, void *value) { + return PyThread_set_key_value(*key, value); +} +static CYTHON_INLINE void * PyThread_tss_get(Py_tss_t *key) { + return PyThread_get_key_value(*key); +} +#endif +#if PY_MAJOR_VERSION < 3 + #if CYTHON_COMPILING_IN_PYPY + #if PYPY_VERSION_NUM < 0x07030600 + #if defined(__cplusplus) && __cplusplus >= 201402L + [[deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")]] + #elif defined(__GNUC__) || defined(__clang__) + __attribute__ ((__deprecated__("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6"))) + #elif defined(_MSC_VER) + __declspec(deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")) + #endif + static CYTHON_INLINE int PyGILState_Check(void) { + return 0; + } + #else // PYPY_VERSION_NUM < 0x07030600 + #endif // PYPY_VERSION_NUM < 0x07030600 + #else + static CYTHON_INLINE int PyGILState_Check(void) { + PyThreadState * tstate = _PyThreadState_Current; + return tstate && (tstate == PyGILState_GetThisThreadState()); + } + #endif +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030d0000 || defined(_PyDict_NewPresized) +#define __Pyx_PyDict_NewPresized(n) ((n <= 8) ? PyDict_New() : _PyDict_NewPresized(n)) +#else +#define __Pyx_PyDict_NewPresized(n) PyDict_New() +#endif +#if PY_MAJOR_VERSION >= 3 || CYTHON_FUTURE_DIVISION + #define __Pyx_PyNumber_Divide(x,y) PyNumber_TrueDivide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceTrueDivide(x,y) +#else + #define __Pyx_PyNumber_Divide(x,y) PyNumber_Divide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceDivide(x,y) +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX > 0x030600B4 && PY_VERSION_HEX < 0x030d0000 && CYTHON_USE_UNICODE_INTERNALS +#define __Pyx_PyDict_GetItemStrWithError(dict, name) _PyDict_GetItem_KnownHash(dict, name, ((PyASCIIObject *) name)->hash) +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStr(PyObject *dict, PyObject *name) { + PyObject *res = __Pyx_PyDict_GetItemStrWithError(dict, name); + if (res == NULL) PyErr_Clear(); + return res; +} +#elif PY_MAJOR_VERSION >= 3 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07020000) +#define __Pyx_PyDict_GetItemStrWithError PyDict_GetItemWithError +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#else +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStrWithError(PyObject *dict, PyObject *name) { +#if CYTHON_COMPILING_IN_PYPY + return PyDict_GetItem(dict, name); +#else + PyDictEntry *ep; + PyDictObject *mp = (PyDictObject*) dict; + long hash = ((PyStringObject *) name)->ob_shash; + assert(hash != -1); + ep = (mp->ma_lookup)(mp, name, hash); + if (ep == NULL) { + return NULL; + } + return ep->me_value; +#endif +} +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#endif +#if CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyType_GetFlags(tp) (((PyTypeObject *)tp)->tp_flags) + #define __Pyx_PyType_HasFeature(type, feature) ((__Pyx_PyType_GetFlags(type) & (feature)) != 0) + #define __Pyx_PyObject_GetIterNextFunc(obj) (Py_TYPE(obj)->tp_iternext) +#else + #define __Pyx_PyType_GetFlags(tp) (PyType_GetFlags((PyTypeObject *)tp)) + #define __Pyx_PyType_HasFeature(type, feature) PyType_HasFeature(type, feature) + #define __Pyx_PyObject_GetIterNextFunc(obj) PyIter_Next +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_SetItemOnTypeDict(tp, k, v) PyObject_GenericSetAttr((PyObject*)tp, k, v) +#else + #define __Pyx_SetItemOnTypeDict(tp, k, v) PyDict_SetItem(tp->tp_dict, k, v) +#endif +#if CYTHON_USE_TYPE_SPECS && PY_VERSION_HEX >= 0x03080000 +#define __Pyx_PyHeapTypeObject_GC_Del(obj) {\ + PyTypeObject *type = Py_TYPE((PyObject*)obj);\ + assert(__Pyx_PyType_HasFeature(type, Py_TPFLAGS_HEAPTYPE));\ + PyObject_GC_Del(obj);\ + Py_DECREF(type);\ +} +#else +#define __Pyx_PyHeapTypeObject_GC_Del(obj) PyObject_GC_Del(obj) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define CYTHON_PEP393_ENABLED 1 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GetLength(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_ReadChar(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((void)u, 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((void)u, (0)) + #define __Pyx_PyUnicode_DATA(u) ((void*)u) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)k, PyUnicode_ReadChar((PyObject*)(d), i)) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GetLength(u)) +#elif PY_VERSION_HEX > 0x03030000 && defined(PyUnicode_KIND) + #define CYTHON_PEP393_ENABLED 1 + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_READY(op) (0) + #else + #define __Pyx_PyUnicode_READY(op) (likely(PyUnicode_IS_READY(op)) ?\ + 0 : _PyUnicode_Ready((PyObject *)(op))) + #endif + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_LENGTH(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_READ_CHAR(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) PyUnicode_MAX_CHAR_VALUE(u) + #define __Pyx_PyUnicode_KIND(u) ((int)PyUnicode_KIND(u)) + #define __Pyx_PyUnicode_DATA(u) PyUnicode_DATA(u) + #define __Pyx_PyUnicode_READ(k, d, i) PyUnicode_READ(k, d, i) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) PyUnicode_WRITE(k, d, i, (Py_UCS4) ch) + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_LENGTH(u)) + #else + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x03090000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : ((PyCompactUnicodeObject *)(u))->wstr_length)) + #else + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : PyUnicode_GET_SIZE(u))) + #endif + #endif +#else + #define CYTHON_PEP393_ENABLED 0 + #define PyUnicode_1BYTE_KIND 1 + #define PyUnicode_2BYTE_KIND 2 + #define PyUnicode_4BYTE_KIND 4 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_SIZE(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) ((Py_UCS4)(PyUnicode_AS_UNICODE(u)[i])) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((sizeof(Py_UNICODE) == 2) ? 65535U : 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((int)sizeof(Py_UNICODE)) + #define __Pyx_PyUnicode_DATA(u) ((void*)PyUnicode_AS_UNICODE(u)) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)(k), (Py_UCS4)(((Py_UNICODE*)d)[i])) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) (((void)(k)), ((Py_UNICODE*)d)[i] = (Py_UNICODE) ch) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_SIZE(u)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyUnicode_Concat(a, b) PyNumber_Add(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) PyNumber_Add(a, b) +#else + #define __Pyx_PyUnicode_Concat(a, b) PyUnicode_Concat(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) ((unlikely((a) == Py_None) || unlikely((b) == Py_None)) ?\ + PyNumber_Add(a, b) : __Pyx_PyUnicode_Concat(a, b)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #if !defined(PyUnicode_DecodeUnicodeEscape) + #define PyUnicode_DecodeUnicodeEscape(s, size, errors) PyUnicode_Decode(s, size, "unicode_escape", errors) + #endif + #if !defined(PyUnicode_Contains) || (PY_MAJOR_VERSION == 2 && PYPY_VERSION_NUM < 0x07030500) + #undef PyUnicode_Contains + #define PyUnicode_Contains(u, s) PySequence_Contains(u, s) + #endif + #if !defined(PyByteArray_Check) + #define PyByteArray_Check(obj) PyObject_TypeCheck(obj, &PyByteArray_Type) + #endif + #if !defined(PyObject_Format) + #define PyObject_Format(obj, fmt) PyObject_CallMethod(obj, "__format__", "O", fmt) + #endif +#endif +#define __Pyx_PyString_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyString_Check(b) && !PyString_CheckExact(b)))) ? PyNumber_Remainder(a, b) : __Pyx_PyString_Format(a, b)) +#define __Pyx_PyUnicode_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyUnicode_Check(b) && !PyUnicode_CheckExact(b)))) ? PyNumber_Remainder(a, b) : PyUnicode_Format(a, b)) +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyString_Format(a, b) PyUnicode_Format(a, b) +#else + #define __Pyx_PyString_Format(a, b) PyString_Format(a, b) +#endif +#if PY_MAJOR_VERSION < 3 && !defined(PyObject_ASCII) + #define PyObject_ASCII(o) PyObject_Repr(o) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBaseString_Type PyUnicode_Type + #define PyStringObject PyUnicodeObject + #define PyString_Type PyUnicode_Type + #define PyString_Check PyUnicode_Check + #define PyString_CheckExact PyUnicode_CheckExact +#ifndef PyObject_Unicode + #define PyObject_Unicode PyObject_Str +#endif +#endif +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyBaseString_Check(obj) PyUnicode_Check(obj) + #define __Pyx_PyBaseString_CheckExact(obj) PyUnicode_CheckExact(obj) +#else + #define __Pyx_PyBaseString_Check(obj) (PyString_Check(obj) || PyUnicode_Check(obj)) + #define __Pyx_PyBaseString_CheckExact(obj) (PyString_CheckExact(obj) || PyUnicode_CheckExact(obj)) +#endif +#if CYTHON_COMPILING_IN_CPYTHON + #define __Pyx_PySequence_ListKeepNew(obj)\ + (likely(PyList_CheckExact(obj) && Py_REFCNT(obj) == 1) ? __Pyx_NewRef(obj) : PySequence_List(obj)) +#else + #define __Pyx_PySequence_ListKeepNew(obj) PySequence_List(obj) +#endif +#ifndef PySet_CheckExact + #define PySet_CheckExact(obj) __Pyx_IS_TYPE(obj, &PySet_Type) +#endif +#if PY_VERSION_HEX >= 0x030900A4 + #define __Pyx_SET_REFCNT(obj, refcnt) Py_SET_REFCNT(obj, refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SET_SIZE(obj, size) +#else + #define __Pyx_SET_REFCNT(obj, refcnt) Py_REFCNT(obj) = (refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SIZE(obj) = (size) +#endif +#if CYTHON_ASSUME_SAFE_MACROS + #define __Pyx_PySequence_ITEM(o, i) PySequence_ITEM(o, i) + #define __Pyx_PySequence_SIZE(seq) Py_SIZE(seq) + #define __Pyx_PyTuple_SET_ITEM(o, i, v) (PyTuple_SET_ITEM(o, i, v), (0)) + #define __Pyx_PyList_SET_ITEM(o, i, v) (PyList_SET_ITEM(o, i, v), (0)) + #define __Pyx_PyTuple_GET_SIZE(o) PyTuple_GET_SIZE(o) + #define __Pyx_PyList_GET_SIZE(o) PyList_GET_SIZE(o) + #define __Pyx_PySet_GET_SIZE(o) PySet_GET_SIZE(o) + #define __Pyx_PyBytes_GET_SIZE(o) PyBytes_GET_SIZE(o) + #define __Pyx_PyByteArray_GET_SIZE(o) PyByteArray_GET_SIZE(o) +#else + #define __Pyx_PySequence_ITEM(o, i) PySequence_GetItem(o, i) + #define __Pyx_PySequence_SIZE(seq) PySequence_Size(seq) + #define __Pyx_PyTuple_SET_ITEM(o, i, v) PyTuple_SetItem(o, i, v) + #define __Pyx_PyList_SET_ITEM(o, i, v) PyList_SetItem(o, i, v) + #define __Pyx_PyTuple_GET_SIZE(o) PyTuple_Size(o) + #define __Pyx_PyList_GET_SIZE(o) PyList_Size(o) + #define __Pyx_PySet_GET_SIZE(o) PySet_Size(o) + #define __Pyx_PyBytes_GET_SIZE(o) PyBytes_Size(o) + #define __Pyx_PyByteArray_GET_SIZE(o) PyByteArray_Size(o) +#endif +#if PY_VERSION_HEX >= 0x030d00A1 + #define __Pyx_PyImport_AddModuleRef(name) PyImport_AddModuleRef(name) +#else + static CYTHON_INLINE PyObject *__Pyx_PyImport_AddModuleRef(const char *name) { + PyObject *module = PyImport_AddModule(name); + Py_XINCREF(module); + return module; + } +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyIntObject PyLongObject + #define PyInt_Type PyLong_Type + #define PyInt_Check(op) PyLong_Check(op) + #define PyInt_CheckExact(op) PyLong_CheckExact(op) + #define __Pyx_Py3Int_Check(op) PyLong_Check(op) + #define __Pyx_Py3Int_CheckExact(op) PyLong_CheckExact(op) + #define PyInt_FromString PyLong_FromString + #define PyInt_FromUnicode PyLong_FromUnicode + #define PyInt_FromLong PyLong_FromLong + #define PyInt_FromSize_t PyLong_FromSize_t + #define PyInt_FromSsize_t PyLong_FromSsize_t + #define PyInt_AsLong PyLong_AsLong + #define PyInt_AS_LONG PyLong_AS_LONG + #define PyInt_AsSsize_t PyLong_AsSsize_t + #define PyInt_AsUnsignedLongMask PyLong_AsUnsignedLongMask + #define PyInt_AsUnsignedLongLongMask PyLong_AsUnsignedLongLongMask + #define PyNumber_Int PyNumber_Long +#else + #define __Pyx_Py3Int_Check(op) (PyLong_Check(op) || PyInt_Check(op)) + #define __Pyx_Py3Int_CheckExact(op) (PyLong_CheckExact(op) || PyInt_CheckExact(op)) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBoolObject PyLongObject +#endif +#if PY_MAJOR_VERSION >= 3 && CYTHON_COMPILING_IN_PYPY + #ifndef PyUnicode_InternFromString + #define PyUnicode_InternFromString(s) PyUnicode_FromString(s) + #endif +#endif +#if PY_VERSION_HEX < 0x030200A4 + typedef long Py_hash_t; + #define __Pyx_PyInt_FromHash_t PyInt_FromLong + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsHash_t +#else + #define __Pyx_PyInt_FromHash_t PyInt_FromSsize_t + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsSsize_t +#endif +#if CYTHON_USE_ASYNC_SLOTS + #if PY_VERSION_HEX >= 0x030500B1 + #define __Pyx_PyAsyncMethodsStruct PyAsyncMethods + #define __Pyx_PyType_AsAsync(obj) (Py_TYPE(obj)->tp_as_async) + #else + #define __Pyx_PyType_AsAsync(obj) ((__Pyx_PyAsyncMethodsStruct*) (Py_TYPE(obj)->tp_reserved)) + #endif +#else + #define __Pyx_PyType_AsAsync(obj) NULL +#endif +#ifndef __Pyx_PyAsyncMethodsStruct + typedef struct { + unaryfunc am_await; + unaryfunc am_aiter; + unaryfunc am_anext; + } __Pyx_PyAsyncMethodsStruct; +#endif + +#if defined(_WIN32) || defined(WIN32) || defined(MS_WINDOWS) + #if !defined(_USE_MATH_DEFINES) + #define _USE_MATH_DEFINES + #endif +#endif +#include +#ifdef NAN +#define __PYX_NAN() ((float) NAN) +#else +static CYTHON_INLINE float __PYX_NAN() { + float value; + memset(&value, 0xFF, sizeof(value)); + return value; +} +#endif +#if defined(__CYGWIN__) && defined(_LDBL_EQ_DBL) +#define __Pyx_truncl trunc +#else +#define __Pyx_truncl truncl +#endif + +#define __PYX_MARK_ERR_POS(f_index, lineno) \ + { __pyx_filename = __pyx_f[f_index]; (void)__pyx_filename; __pyx_lineno = lineno; (void)__pyx_lineno; __pyx_clineno = __LINE__; (void)__pyx_clineno; } +#define __PYX_ERR(f_index, lineno, Ln_error) \ + { __PYX_MARK_ERR_POS(f_index, lineno) goto Ln_error; } + +#ifdef CYTHON_EXTERN_C + #undef __PYX_EXTERN_C + #define __PYX_EXTERN_C CYTHON_EXTERN_C +#elif defined(__PYX_EXTERN_C) + #ifdef _MSC_VER + #pragma message ("Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead.") + #else + #warning Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead. + #endif +#else + #ifdef __cplusplus + #define __PYX_EXTERN_C extern "C" + #else + #define __PYX_EXTERN_C extern + #endif +#endif + +#define __PYX_HAVE__acados_template__acados_ocp_solver_pyx +#define __PYX_HAVE_API__acados_template__acados_ocp_solver_pyx +/* Early includes */ +#include +#include "acados/ocp_nlp/ocp_nlp_common.h" +#include "acados_c/ocp_nlp_interface.h" +#include "acados_solver_long.h" +#include + + /* Using NumPy API declarations from "numpy/__init__.cython-30.pxd" */ + +#include "numpy/arrayobject.h" +#include "numpy/ndarrayobject.h" +#include "numpy/ndarraytypes.h" +#include "numpy/arrayscalars.h" +#include "numpy/ufuncobject.h" +#include "pythread.h" +#include +#ifdef _OPENMP +#include +#endif /* _OPENMP */ + +#if defined(PYREX_WITHOUT_ASSERTIONS) && !defined(CYTHON_WITHOUT_ASSERTIONS) +#define CYTHON_WITHOUT_ASSERTIONS +#endif + +typedef struct {PyObject **p; const char *s; const Py_ssize_t n; const char* encoding; + const char is_unicode; const char is_str; const char intern; } __Pyx_StringTabEntry; + +#define __PYX_DEFAULT_STRING_ENCODING_IS_ASCII 0 +#define __PYX_DEFAULT_STRING_ENCODING_IS_UTF8 0 +#define __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT (PY_MAJOR_VERSION >= 3 && __PYX_DEFAULT_STRING_ENCODING_IS_UTF8) +#define __PYX_DEFAULT_STRING_ENCODING "" +#define __Pyx_PyObject_FromString __Pyx_PyBytes_FromString +#define __Pyx_PyObject_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#define __Pyx_uchar_cast(c) ((unsigned char)c) +#define __Pyx_long_cast(x) ((long)x) +#define __Pyx_fits_Py_ssize_t(v, type, is_signed) (\ + (sizeof(type) < sizeof(Py_ssize_t)) ||\ + (sizeof(type) > sizeof(Py_ssize_t) &&\ + likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX) &&\ + (!is_signed || likely(v > (type)PY_SSIZE_T_MIN ||\ + v == (type)PY_SSIZE_T_MIN))) ||\ + (sizeof(type) == sizeof(Py_ssize_t) &&\ + (is_signed || likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX))) ) +static CYTHON_INLINE int __Pyx_is_valid_index(Py_ssize_t i, Py_ssize_t limit) { + return (size_t) i < (size_t) limit; +} +#if defined (__cplusplus) && __cplusplus >= 201103L + #include + #define __Pyx_sst_abs(value) std::abs(value) +#elif SIZEOF_INT >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) abs(value) +#elif SIZEOF_LONG >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) labs(value) +#elif defined (_MSC_VER) + #define __Pyx_sst_abs(value) ((Py_ssize_t)_abs64(value)) +#elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define __Pyx_sst_abs(value) llabs(value) +#elif defined (__GNUC__) + #define __Pyx_sst_abs(value) __builtin_llabs(value) +#else + #define __Pyx_sst_abs(value) ((value<0) ? -value : value) +#endif +static CYTHON_INLINE Py_ssize_t __Pyx_ssize_strlen(const char *s); +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject*); +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject*, Py_ssize_t* length); +static CYTHON_INLINE PyObject* __Pyx_PyByteArray_FromString(const char*); +#define __Pyx_PyByteArray_FromStringAndSize(s, l) PyByteArray_FromStringAndSize((const char*)s, l) +#define __Pyx_PyBytes_FromString PyBytes_FromString +#define __Pyx_PyBytes_FromStringAndSize PyBytes_FromStringAndSize +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char*); +#if PY_MAJOR_VERSION < 3 + #define __Pyx_PyStr_FromString __Pyx_PyBytes_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#else + #define __Pyx_PyStr_FromString __Pyx_PyUnicode_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyUnicode_FromStringAndSize +#endif +#define __Pyx_PyBytes_AsWritableString(s) ((char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableSString(s) ((signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableUString(s) ((unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsString(s) ((const char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsSString(s) ((const signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsUString(s) ((const unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyObject_AsWritableString(s) ((char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableSString(s) ((signed char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableUString(s) ((unsigned char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsSString(s) ((const signed char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsUString(s) ((const unsigned char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_FromCString(s) __Pyx_PyObject_FromString((const char*)s) +#define __Pyx_PyBytes_FromCString(s) __Pyx_PyBytes_FromString((const char*)s) +#define __Pyx_PyByteArray_FromCString(s) __Pyx_PyByteArray_FromString((const char*)s) +#define __Pyx_PyStr_FromCString(s) __Pyx_PyStr_FromString((const char*)s) +#define __Pyx_PyUnicode_FromCString(s) __Pyx_PyUnicode_FromString((const char*)s) +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const wchar_t *u) +{ + const wchar_t *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#else +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const Py_UNICODE *u) +{ + const Py_UNICODE *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#endif +#define __Pyx_PyUnicode_FromOrdinal(o) PyUnicode_FromOrdinal((int)o) +#define __Pyx_PyUnicode_FromUnicode(u) PyUnicode_FromUnicode(u, __Pyx_Py_UNICODE_strlen(u)) +#define __Pyx_PyUnicode_FromUnicodeAndLength PyUnicode_FromUnicode +#define __Pyx_PyUnicode_AsUnicode PyUnicode_AsUnicode +#define __Pyx_NewRef(obj) (Py_INCREF(obj), obj) +#define __Pyx_Owned_Py_None(b) __Pyx_NewRef(Py_None) +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b); +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject*); +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject*); +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x); +#define __Pyx_PySequence_Tuple(obj)\ + (likely(PyTuple_CheckExact(obj)) ? __Pyx_NewRef(obj) : PySequence_Tuple(obj)) +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject*); +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t); +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject*); +#if CYTHON_ASSUME_SAFE_MACROS +#define __pyx_PyFloat_AsDouble(x) (PyFloat_CheckExact(x) ? PyFloat_AS_DOUBLE(x) : PyFloat_AsDouble(x)) +#else +#define __pyx_PyFloat_AsDouble(x) PyFloat_AsDouble(x) +#endif +#define __pyx_PyFloat_AsFloat(x) ((float) __pyx_PyFloat_AsDouble(x)) +#if PY_MAJOR_VERSION >= 3 +#define __Pyx_PyNumber_Int(x) (PyLong_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Long(x)) +#else +#define __Pyx_PyNumber_Int(x) (PyInt_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Int(x)) +#endif +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_VERSION_HEX >= 0x030C00A7 + #ifndef _PyLong_SIGN_MASK + #define _PyLong_SIGN_MASK 3 + #endif + #ifndef _PyLong_NON_SIZE_BITS + #define _PyLong_NON_SIZE_BITS 3 + #endif + #define __Pyx_PyLong_Sign(x) (((PyLongObject*)x)->long_value.lv_tag & _PyLong_SIGN_MASK) + #define __Pyx_PyLong_IsNeg(x) ((__Pyx_PyLong_Sign(x) & 2) != 0) + #define __Pyx_PyLong_IsNonNeg(x) (!__Pyx_PyLong_IsNeg(x)) + #define __Pyx_PyLong_IsZero(x) (__Pyx_PyLong_Sign(x) & 1) + #define __Pyx_PyLong_IsPos(x) (__Pyx_PyLong_Sign(x) == 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) (__Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) ((Py_ssize_t) (((PyLongObject*)x)->long_value.lv_tag >> _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_SignedDigitCount(x)\ + ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * __Pyx_PyLong_DigitCount(x)) + #if defined(PyUnstable_Long_IsCompact) && defined(PyUnstable_Long_CompactValue) + #define __Pyx_PyLong_IsCompact(x) PyUnstable_Long_IsCompact((PyLongObject*) x) + #define __Pyx_PyLong_CompactValue(x) PyUnstable_Long_CompactValue((PyLongObject*) x) + #else + #define __Pyx_PyLong_IsCompact(x) (((PyLongObject*)x)->long_value.lv_tag < (2 << _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_CompactValue(x) ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * (Py_ssize_t) __Pyx_PyLong_Digits(x)[0]) + #endif + typedef Py_ssize_t __Pyx_compact_pylong; + typedef size_t __Pyx_compact_upylong; + #else + #define __Pyx_PyLong_IsNeg(x) (Py_SIZE(x) < 0) + #define __Pyx_PyLong_IsNonNeg(x) (Py_SIZE(x) >= 0) + #define __Pyx_PyLong_IsZero(x) (Py_SIZE(x) == 0) + #define __Pyx_PyLong_IsPos(x) (Py_SIZE(x) > 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) ((Py_SIZE(x) == 0) ? 0 : __Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) __Pyx_sst_abs(Py_SIZE(x)) + #define __Pyx_PyLong_SignedDigitCount(x) Py_SIZE(x) + #define __Pyx_PyLong_IsCompact(x) (Py_SIZE(x) == 0 || Py_SIZE(x) == 1 || Py_SIZE(x) == -1) + #define __Pyx_PyLong_CompactValue(x)\ + ((Py_SIZE(x) == 0) ? (sdigit) 0 : ((Py_SIZE(x) < 0) ? -(sdigit)__Pyx_PyLong_Digits(x)[0] : (sdigit)__Pyx_PyLong_Digits(x)[0])) + typedef sdigit __Pyx_compact_pylong; + typedef digit __Pyx_compact_upylong; + #endif + #if PY_VERSION_HEX >= 0x030C00A5 + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->long_value.ob_digit) + #else + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->ob_digit) + #endif +#endif +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII +#include +static int __Pyx_sys_getdefaultencoding_not_ascii; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + PyObject* ascii_chars_u = NULL; + PyObject* ascii_chars_b = NULL; + const char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + if (strcmp(default_encoding_c, "ascii") == 0) { + __Pyx_sys_getdefaultencoding_not_ascii = 0; + } else { + char ascii_chars[128]; + int c; + for (c = 0; c < 128; c++) { + ascii_chars[c] = (char) c; + } + __Pyx_sys_getdefaultencoding_not_ascii = 1; + ascii_chars_u = PyUnicode_DecodeASCII(ascii_chars, 128, NULL); + if (!ascii_chars_u) goto bad; + ascii_chars_b = PyUnicode_AsEncodedString(ascii_chars_u, default_encoding_c, NULL); + if (!ascii_chars_b || !PyBytes_Check(ascii_chars_b) || memcmp(ascii_chars, PyBytes_AS_STRING(ascii_chars_b), 128) != 0) { + PyErr_Format( + PyExc_ValueError, + "This module compiled with c_string_encoding=ascii, but default encoding '%.200s' is not a superset of ascii.", + default_encoding_c); + goto bad; + } + Py_DECREF(ascii_chars_u); + Py_DECREF(ascii_chars_b); + } + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + Py_XDECREF(ascii_chars_u); + Py_XDECREF(ascii_chars_b); + return -1; +} +#endif +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT && PY_MAJOR_VERSION >= 3 +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_DecodeUTF8(c_str, size, NULL) +#else +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_Decode(c_str, size, __PYX_DEFAULT_STRING_ENCODING, NULL) +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +#include +static char* __PYX_DEFAULT_STRING_ENCODING; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) (const char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + __PYX_DEFAULT_STRING_ENCODING = (char*) malloc(strlen(default_encoding_c) + 1); + if (!__PYX_DEFAULT_STRING_ENCODING) goto bad; + strcpy(__PYX_DEFAULT_STRING_ENCODING, default_encoding_c); + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + return -1; +} +#endif +#endif + + +/* Test for GCC > 2.95 */ +#if defined(__GNUC__) && (__GNUC__ > 2 || (__GNUC__ == 2 && (__GNUC_MINOR__ > 95))) + #define likely(x) __builtin_expect(!!(x), 1) + #define unlikely(x) __builtin_expect(!!(x), 0) +#else /* !__GNUC__ or GCC < 2.95 */ + #define likely(x) (x) + #define unlikely(x) (x) +#endif /* __GNUC__ */ +static CYTHON_INLINE void __Pyx_pretend_to_initialize(void* ptr) { (void)ptr; } + +#if !CYTHON_USE_MODULE_STATE +static PyObject *__pyx_m = NULL; +#endif +static int __pyx_lineno; +static int __pyx_clineno = 0; +static const char * __pyx_cfilenm = __FILE__; +static const char *__pyx_filename; + +/* Header.proto */ +#if !defined(CYTHON_CCOMPLEX) + #if defined(__cplusplus) + #define CYTHON_CCOMPLEX 1 + #elif (defined(_Complex_I) && !defined(_MSC_VER)) || ((defined (__STDC_VERSION__) && __STDC_VERSION__ >= 201112L) && !defined(__STDC_NO_COMPLEX__) && !defined(_MSC_VER)) + #define CYTHON_CCOMPLEX 1 + #else + #define CYTHON_CCOMPLEX 0 + #endif +#endif +#if CYTHON_CCOMPLEX + #ifdef __cplusplus + #include + #else + #include + #endif +#endif +#if CYTHON_CCOMPLEX && !defined(__cplusplus) && defined(__sun__) && defined(__GNUC__) + #undef _Complex_I + #define _Complex_I 1.0fj +#endif + +/* #### Code section: filename_table ### */ + +static const char *__pyx_f[] = { + "third_party/acados/acados_template/acados_ocp_solver_pyx.pyx", + "", + "__init__.cython-30.pxd", + "type.pxd", +}; +/* #### Code section: utility_code_proto_before_types ### */ +/* ForceInitThreads.proto */ +#ifndef __PYX_FORCE_INIT_THREADS + #define __PYX_FORCE_INIT_THREADS 0 +#endif + +/* NoFastGil.proto */ +#define __Pyx_PyGILState_Ensure PyGILState_Ensure +#define __Pyx_PyGILState_Release PyGILState_Release +#define __Pyx_FastGIL_Remember() +#define __Pyx_FastGIL_Forget() +#define __Pyx_FastGilFuncInit() + +/* BufferFormatStructs.proto */ +struct __Pyx_StructField_; +#define __PYX_BUF_FLAGS_PACKED_STRUCT (1 << 0) +typedef struct { + const char* name; + struct __Pyx_StructField_* fields; + size_t size; + size_t arraysize[8]; + int ndim; + char typegroup; + char is_unsigned; + int flags; +} __Pyx_TypeInfo; +typedef struct __Pyx_StructField_ { + __Pyx_TypeInfo* type; + const char* name; + size_t offset; +} __Pyx_StructField; +typedef struct { + __Pyx_StructField* field; + size_t parent_offset; +} __Pyx_BufFmt_StackElem; +typedef struct { + __Pyx_StructField root; + __Pyx_BufFmt_StackElem* head; + size_t fmt_offset; + size_t new_count, enc_count; + size_t struct_alignment; + int is_complex; + char enc_type; + char new_packmode; + char enc_packmode; + char is_valid_array; +} __Pyx_BufFmt_Context; + +/* Atomics.proto */ +#include +#ifndef CYTHON_ATOMICS + #define CYTHON_ATOMICS 1 +#endif +#define __PYX_CYTHON_ATOMICS_ENABLED() CYTHON_ATOMICS +#define __pyx_atomic_int_type int +#define __pyx_nonatomic_int_type int +#if CYTHON_ATOMICS && (defined(__STDC_VERSION__) &&\ + (__STDC_VERSION__ >= 201112L) &&\ + !defined(__STDC_NO_ATOMICS__)) + #include +#elif CYTHON_ATOMICS && (defined(__cplusplus) && (\ + (__cplusplus >= 201103L) ||\ + (defined(_MSC_VER) && _MSC_VER >= 1700))) + #include +#endif +#if CYTHON_ATOMICS && (defined(__STDC_VERSION__) &&\ + (__STDC_VERSION__ >= 201112L) &&\ + !defined(__STDC_NO_ATOMICS__) &&\ + ATOMIC_INT_LOCK_FREE == 2) + #undef __pyx_atomic_int_type + #define __pyx_atomic_int_type atomic_int + #define __pyx_atomic_incr_aligned(value) atomic_fetch_add_explicit(value, 1, memory_order_relaxed) + #define __pyx_atomic_decr_aligned(value) atomic_fetch_sub_explicit(value, 1, memory_order_acq_rel) + #if defined(__PYX_DEBUG_ATOMICS) && defined(_MSC_VER) + #pragma message ("Using standard C atomics") + #elif defined(__PYX_DEBUG_ATOMICS) + #warning "Using standard C atomics" + #endif +#elif CYTHON_ATOMICS && (defined(__cplusplus) && (\ + (__cplusplus >= 201103L) ||\ +\ + (defined(_MSC_VER) && _MSC_VER >= 1700)) &&\ + ATOMIC_INT_LOCK_FREE == 2) + #undef __pyx_atomic_int_type + #define __pyx_atomic_int_type std::atomic_int + #define __pyx_atomic_incr_aligned(value) std::atomic_fetch_add_explicit(value, 1, std::memory_order_relaxed) + #define __pyx_atomic_decr_aligned(value) std::atomic_fetch_sub_explicit(value, 1, std::memory_order_acq_rel) + #if defined(__PYX_DEBUG_ATOMICS) && defined(_MSC_VER) + #pragma message ("Using standard C++ atomics") + #elif defined(__PYX_DEBUG_ATOMICS) + #warning "Using standard C++ atomics" + #endif +#elif CYTHON_ATOMICS && (__GNUC__ >= 5 || (__GNUC__ == 4 &&\ + (__GNUC_MINOR__ > 1 ||\ + (__GNUC_MINOR__ == 1 && __GNUC_PATCHLEVEL__ >= 2)))) + #define __pyx_atomic_incr_aligned(value) __sync_fetch_and_add(value, 1) + #define __pyx_atomic_decr_aligned(value) __sync_fetch_and_sub(value, 1) + #ifdef __PYX_DEBUG_ATOMICS + #warning "Using GNU atomics" + #endif +#elif CYTHON_ATOMICS && defined(_MSC_VER) + #include + #undef __pyx_atomic_int_type + #define __pyx_atomic_int_type long + #undef __pyx_nonatomic_int_type + #define __pyx_nonatomic_int_type long + #pragma intrinsic (_InterlockedExchangeAdd) + #define __pyx_atomic_incr_aligned(value) _InterlockedExchangeAdd(value, 1) + #define __pyx_atomic_decr_aligned(value) _InterlockedExchangeAdd(value, -1) + #ifdef __PYX_DEBUG_ATOMICS + #pragma message ("Using MSVC atomics") + #endif +#else + #undef CYTHON_ATOMICS + #define CYTHON_ATOMICS 0 + #ifdef __PYX_DEBUG_ATOMICS + #warning "Not using atomics" + #endif +#endif +#if CYTHON_ATOMICS + #define __pyx_add_acquisition_count(memview)\ + __pyx_atomic_incr_aligned(__pyx_get_slice_count_pointer(memview)) + #define __pyx_sub_acquisition_count(memview)\ + __pyx_atomic_decr_aligned(__pyx_get_slice_count_pointer(memview)) +#else + #define __pyx_add_acquisition_count(memview)\ + __pyx_add_acquisition_count_locked(__pyx_get_slice_count_pointer(memview), memview->lock) + #define __pyx_sub_acquisition_count(memview)\ + __pyx_sub_acquisition_count_locked(__pyx_get_slice_count_pointer(memview), memview->lock) +#endif + +/* MemviewSliceStruct.proto */ +struct __pyx_memoryview_obj; +typedef struct { + struct __pyx_memoryview_obj *memview; + char *data; + Py_ssize_t shape[8]; + Py_ssize_t strides[8]; + Py_ssize_t suboffsets[8]; +} __Pyx_memviewslice; +#define __Pyx_MemoryView_Len(m) (m.shape[0]) + +/* #### Code section: numeric_typedefs ### */ + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":730 + * # in Cython to enable them only on the right systems. + * + * ctypedef npy_int8 int8_t # <<<<<<<<<<<<<< + * ctypedef npy_int16 int16_t + * ctypedef npy_int32 int32_t + */ +typedef npy_int8 __pyx_t_5numpy_int8_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":731 + * + * ctypedef npy_int8 int8_t + * ctypedef npy_int16 int16_t # <<<<<<<<<<<<<< + * ctypedef npy_int32 int32_t + * ctypedef npy_int64 int64_t + */ +typedef npy_int16 __pyx_t_5numpy_int16_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":732 + * ctypedef npy_int8 int8_t + * ctypedef npy_int16 int16_t + * ctypedef npy_int32 int32_t # <<<<<<<<<<<<<< + * ctypedef npy_int64 int64_t + * #ctypedef npy_int96 int96_t + */ +typedef npy_int32 __pyx_t_5numpy_int32_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":733 + * ctypedef npy_int16 int16_t + * ctypedef npy_int32 int32_t + * ctypedef npy_int64 int64_t # <<<<<<<<<<<<<< + * #ctypedef npy_int96 int96_t + * #ctypedef npy_int128 int128_t + */ +typedef npy_int64 __pyx_t_5numpy_int64_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":737 + * #ctypedef npy_int128 int128_t + * + * ctypedef npy_uint8 uint8_t # <<<<<<<<<<<<<< + * ctypedef npy_uint16 uint16_t + * ctypedef npy_uint32 uint32_t + */ +typedef npy_uint8 __pyx_t_5numpy_uint8_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":738 + * + * ctypedef npy_uint8 uint8_t + * ctypedef npy_uint16 uint16_t # <<<<<<<<<<<<<< + * ctypedef npy_uint32 uint32_t + * ctypedef npy_uint64 uint64_t + */ +typedef npy_uint16 __pyx_t_5numpy_uint16_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":739 + * ctypedef npy_uint8 uint8_t + * ctypedef npy_uint16 uint16_t + * ctypedef npy_uint32 uint32_t # <<<<<<<<<<<<<< + * ctypedef npy_uint64 uint64_t + * #ctypedef npy_uint96 uint96_t + */ +typedef npy_uint32 __pyx_t_5numpy_uint32_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":740 + * ctypedef npy_uint16 uint16_t + * ctypedef npy_uint32 uint32_t + * ctypedef npy_uint64 uint64_t # <<<<<<<<<<<<<< + * #ctypedef npy_uint96 uint96_t + * #ctypedef npy_uint128 uint128_t + */ +typedef npy_uint64 __pyx_t_5numpy_uint64_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":744 + * #ctypedef npy_uint128 uint128_t + * + * ctypedef npy_float32 float32_t # <<<<<<<<<<<<<< + * ctypedef npy_float64 float64_t + * #ctypedef npy_float80 float80_t + */ +typedef npy_float32 __pyx_t_5numpy_float32_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":745 + * + * ctypedef npy_float32 float32_t + * ctypedef npy_float64 float64_t # <<<<<<<<<<<<<< + * #ctypedef npy_float80 float80_t + * #ctypedef npy_float128 float128_t + */ +typedef npy_float64 __pyx_t_5numpy_float64_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":754 + * # The int types are mapped a bit surprising -- + * # numpy.int corresponds to 'l' and numpy.long to 'q' + * ctypedef npy_long int_t # <<<<<<<<<<<<<< + * ctypedef npy_longlong longlong_t + * + */ +typedef npy_long __pyx_t_5numpy_int_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":755 + * # numpy.int corresponds to 'l' and numpy.long to 'q' + * ctypedef npy_long int_t + * ctypedef npy_longlong longlong_t # <<<<<<<<<<<<<< + * + * ctypedef npy_ulong uint_t + */ +typedef npy_longlong __pyx_t_5numpy_longlong_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":757 + * ctypedef npy_longlong longlong_t + * + * ctypedef npy_ulong uint_t # <<<<<<<<<<<<<< + * ctypedef npy_ulonglong ulonglong_t + * + */ +typedef npy_ulong __pyx_t_5numpy_uint_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":758 + * + * ctypedef npy_ulong uint_t + * ctypedef npy_ulonglong ulonglong_t # <<<<<<<<<<<<<< + * + * ctypedef npy_intp intp_t + */ +typedef npy_ulonglong __pyx_t_5numpy_ulonglong_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":760 + * ctypedef npy_ulonglong ulonglong_t + * + * ctypedef npy_intp intp_t # <<<<<<<<<<<<<< + * ctypedef npy_uintp uintp_t + * + */ +typedef npy_intp __pyx_t_5numpy_intp_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":761 + * + * ctypedef npy_intp intp_t + * ctypedef npy_uintp uintp_t # <<<<<<<<<<<<<< + * + * ctypedef npy_double float_t + */ +typedef npy_uintp __pyx_t_5numpy_uintp_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":763 + * ctypedef npy_uintp uintp_t + * + * ctypedef npy_double float_t # <<<<<<<<<<<<<< + * ctypedef npy_double double_t + * ctypedef npy_longdouble longdouble_t + */ +typedef npy_double __pyx_t_5numpy_float_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":764 + * + * ctypedef npy_double float_t + * ctypedef npy_double double_t # <<<<<<<<<<<<<< + * ctypedef npy_longdouble longdouble_t + * + */ +typedef npy_double __pyx_t_5numpy_double_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":765 + * ctypedef npy_double float_t + * ctypedef npy_double double_t + * ctypedef npy_longdouble longdouble_t # <<<<<<<<<<<<<< + * + * ctypedef npy_cfloat cfloat_t + */ +typedef npy_longdouble __pyx_t_5numpy_longdouble_t; +/* #### Code section: complex_type_declarations ### */ +/* Declarations.proto */ +#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #ifdef __cplusplus + typedef ::std::complex< float > __pyx_t_float_complex; + #else + typedef float _Complex __pyx_t_float_complex; + #endif +#else + typedef struct { float real, imag; } __pyx_t_float_complex; +#endif +static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float, float); + +/* Declarations.proto */ +#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #ifdef __cplusplus + typedef ::std::complex< double > __pyx_t_double_complex; + #else + typedef double _Complex __pyx_t_double_complex; + #endif +#else + typedef struct { double real, imag; } __pyx_t_double_complex; +#endif +static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double, double); + +/* #### Code section: type_declarations ### */ + +/*--- Type declarations ---*/ +struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython; +struct __pyx_array_obj; +struct __pyx_MemviewEnum_obj; +struct __pyx_memoryview_obj; +struct __pyx_memoryviewslice_obj; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":767 + * ctypedef npy_longdouble longdouble_t + * + * ctypedef npy_cfloat cfloat_t # <<<<<<<<<<<<<< + * ctypedef npy_cdouble cdouble_t + * ctypedef npy_clongdouble clongdouble_t + */ +typedef npy_cfloat __pyx_t_5numpy_cfloat_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":768 + * + * ctypedef npy_cfloat cfloat_t + * ctypedef npy_cdouble cdouble_t # <<<<<<<<<<<<<< + * ctypedef npy_clongdouble clongdouble_t + * + */ +typedef npy_cdouble __pyx_t_5numpy_cdouble_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":769 + * ctypedef npy_cfloat cfloat_t + * ctypedef npy_cdouble cdouble_t + * ctypedef npy_clongdouble clongdouble_t # <<<<<<<<<<<<<< + * + * ctypedef npy_cdouble complex_t + */ +typedef npy_clongdouble __pyx_t_5numpy_clongdouble_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":771 + * ctypedef npy_clongdouble clongdouble_t + * + * ctypedef npy_cdouble complex_t # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew1(a): + */ +typedef npy_cdouble __pyx_t_5numpy_complex_t; + +/* "acados_template/acados_ocp_solver_pyx.pyx":49 + * + * + * cdef class AcadosOcpSolverCython: # <<<<<<<<<<<<<< + * """ + * Class to interact with the acados ocp solver C object. + */ +struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython { + PyObject_HEAD + long_solver_capsule *capsule; + void *nlp_opts; + ocp_nlp_dims *nlp_dims; + ocp_nlp_config *nlp_config; + ocp_nlp_out *nlp_out; + ocp_nlp_out *sens_out; + ocp_nlp_in *nlp_in; + ocp_nlp_solver *nlp_solver; + int solver_created; + PyObject *model_name; + int N; + PyObject *nlp_solver_type; +}; + + +/* "View.MemoryView":114 + * @cython.collection_type("sequence") + * @cname("__pyx_array") + * cdef class array: # <<<<<<<<<<<<<< + * + * cdef: + */ +struct __pyx_array_obj { + PyObject_HEAD + struct __pyx_vtabstruct_array *__pyx_vtab; + char *data; + Py_ssize_t len; + char *format; + int ndim; + Py_ssize_t *_shape; + Py_ssize_t *_strides; + Py_ssize_t itemsize; + PyObject *mode; + PyObject *_format; + void (*callback_free_data)(void *); + int free_data; + int dtype_is_object; +}; + + +/* "View.MemoryView":302 + * + * @cname('__pyx_MemviewEnum') + * cdef class Enum(object): # <<<<<<<<<<<<<< + * cdef object name + * def __init__(self, name): + */ +struct __pyx_MemviewEnum_obj { + PyObject_HEAD + PyObject *name; +}; + + +/* "View.MemoryView":337 + * + * @cname('__pyx_memoryview') + * cdef class memoryview: # <<<<<<<<<<<<<< + * + * cdef object obj + */ +struct __pyx_memoryview_obj { + PyObject_HEAD + struct __pyx_vtabstruct_memoryview *__pyx_vtab; + PyObject *obj; + PyObject *_size; + PyObject *_array_interface; + PyThread_type_lock lock; + __pyx_atomic_int_type acquisition_count; + Py_buffer view; + int flags; + int dtype_is_object; + __Pyx_TypeInfo *typeinfo; +}; + + +/* "View.MemoryView":952 + * @cython.collection_type("sequence") + * @cname('__pyx_memoryviewslice') + * cdef class _memoryviewslice(memoryview): # <<<<<<<<<<<<<< + * "Internal class for passing memoryview slices to Python" + * + */ +struct __pyx_memoryviewslice_obj { + struct __pyx_memoryview_obj __pyx_base; + __Pyx_memviewslice from_slice; + PyObject *from_object; + PyObject *(*to_object_func)(char *); + int (*to_dtype_func)(char *, PyObject *); +}; + + + +/* "View.MemoryView":114 + * @cython.collection_type("sequence") + * @cname("__pyx_array") + * cdef class array: # <<<<<<<<<<<<<< + * + * cdef: + */ + +struct __pyx_vtabstruct_array { + PyObject *(*get_memview)(struct __pyx_array_obj *); +}; +static struct __pyx_vtabstruct_array *__pyx_vtabptr_array; + + +/* "View.MemoryView":337 + * + * @cname('__pyx_memoryview') + * cdef class memoryview: # <<<<<<<<<<<<<< + * + * cdef object obj + */ + +struct __pyx_vtabstruct_memoryview { + char *(*get_item_pointer)(struct __pyx_memoryview_obj *, PyObject *); + PyObject *(*is_slice)(struct __pyx_memoryview_obj *, PyObject *); + PyObject *(*setitem_slice_assignment)(struct __pyx_memoryview_obj *, PyObject *, PyObject *); + PyObject *(*setitem_slice_assign_scalar)(struct __pyx_memoryview_obj *, struct __pyx_memoryview_obj *, PyObject *); + PyObject *(*setitem_indexed)(struct __pyx_memoryview_obj *, PyObject *, PyObject *); + PyObject *(*convert_item_to_object)(struct __pyx_memoryview_obj *, char *); + PyObject *(*assign_item_from_object)(struct __pyx_memoryview_obj *, char *, PyObject *); + PyObject *(*_get_base)(struct __pyx_memoryview_obj *); +}; +static struct __pyx_vtabstruct_memoryview *__pyx_vtabptr_memoryview; + + +/* "View.MemoryView":952 + * @cython.collection_type("sequence") + * @cname('__pyx_memoryviewslice') + * cdef class _memoryviewslice(memoryview): # <<<<<<<<<<<<<< + * "Internal class for passing memoryview slices to Python" + * + */ + +struct __pyx_vtabstruct__memoryviewslice { + struct __pyx_vtabstruct_memoryview __pyx_base; +}; +static struct __pyx_vtabstruct__memoryviewslice *__pyx_vtabptr__memoryviewslice; +/* #### Code section: utility_code_proto ### */ + +/* --- Runtime support code (head) --- */ +/* Refnanny.proto */ +#ifndef CYTHON_REFNANNY + #define CYTHON_REFNANNY 0 +#endif +#if CYTHON_REFNANNY + typedef struct { + void (*INCREF)(void*, PyObject*, Py_ssize_t); + void (*DECREF)(void*, PyObject*, Py_ssize_t); + void (*GOTREF)(void*, PyObject*, Py_ssize_t); + void (*GIVEREF)(void*, PyObject*, Py_ssize_t); + void* (*SetupContext)(const char*, Py_ssize_t, const char*); + void (*FinishContext)(void**); + } __Pyx_RefNannyAPIStruct; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNanny = NULL; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname); + #define __Pyx_RefNannyDeclarations void *__pyx_refnanny = NULL; +#ifdef WITH_THREAD + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + if (acquire_gil) {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + PyGILState_Release(__pyx_gilstate_save);\ + } else {\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + } + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } +#else + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__)) + #define __Pyx_RefNannyFinishContextNogil() __Pyx_RefNannyFinishContext() +#endif + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } + #define __Pyx_RefNannyFinishContext()\ + __Pyx_RefNanny->FinishContext(&__pyx_refnanny) + #define __Pyx_INCREF(r) __Pyx_RefNanny->INCREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_DECREF(r) __Pyx_RefNanny->DECREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GOTREF(r) __Pyx_RefNanny->GOTREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GIVEREF(r) __Pyx_RefNanny->GIVEREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_XINCREF(r) do { if((r) == NULL); else {__Pyx_INCREF(r); }} while(0) + #define __Pyx_XDECREF(r) do { if((r) == NULL); else {__Pyx_DECREF(r); }} while(0) + #define __Pyx_XGOTREF(r) do { if((r) == NULL); else {__Pyx_GOTREF(r); }} while(0) + #define __Pyx_XGIVEREF(r) do { if((r) == NULL); else {__Pyx_GIVEREF(r);}} while(0) +#else + #define __Pyx_RefNannyDeclarations + #define __Pyx_RefNannySetupContext(name, acquire_gil) + #define __Pyx_RefNannyFinishContextNogil() + #define __Pyx_RefNannyFinishContext() + #define __Pyx_INCREF(r) Py_INCREF(r) + #define __Pyx_DECREF(r) Py_DECREF(r) + #define __Pyx_GOTREF(r) + #define __Pyx_GIVEREF(r) + #define __Pyx_XINCREF(r) Py_XINCREF(r) + #define __Pyx_XDECREF(r) Py_XDECREF(r) + #define __Pyx_XGOTREF(r) + #define __Pyx_XGIVEREF(r) +#endif +#define __Pyx_Py_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; Py_XDECREF(tmp);\ + } while (0) +#define __Pyx_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_XDECREF(tmp);\ + } while (0) +#define __Pyx_DECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_DECREF(tmp);\ + } while (0) +#define __Pyx_CLEAR(r) do { PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);} while(0) +#define __Pyx_XCLEAR(r) do { if((r) != NULL) {PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);}} while(0) + +/* PyErrExceptionMatches.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_ExceptionMatches(err) __Pyx_PyErr_ExceptionMatchesInState(__pyx_tstate, err) +static CYTHON_INLINE int __Pyx_PyErr_ExceptionMatchesInState(PyThreadState* tstate, PyObject* err); +#else +#define __Pyx_PyErr_ExceptionMatches(err) PyErr_ExceptionMatches(err) +#endif + +/* PyThreadStateGet.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyThreadState_declare PyThreadState *__pyx_tstate; +#define __Pyx_PyThreadState_assign __pyx_tstate = __Pyx_PyThreadState_Current; +#if PY_VERSION_HEX >= 0x030C00A6 +#define __Pyx_PyErr_Occurred() (__pyx_tstate->current_exception != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->current_exception ? (PyObject*) Py_TYPE(__pyx_tstate->current_exception) : (PyObject*) NULL) +#else +#define __Pyx_PyErr_Occurred() (__pyx_tstate->curexc_type != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->curexc_type) +#endif +#else +#define __Pyx_PyThreadState_declare +#define __Pyx_PyThreadState_assign +#define __Pyx_PyErr_Occurred() (PyErr_Occurred() != NULL) +#define __Pyx_PyErr_CurrentExceptionType() PyErr_Occurred() +#endif + +/* PyErrFetchRestore.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_Clear() __Pyx_ErrRestore(NULL, NULL, NULL) +#define __Pyx_ErrRestoreWithState(type, value, tb) __Pyx_ErrRestoreInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) __Pyx_ErrFetchInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) __Pyx_ErrRestoreInState(__pyx_tstate, type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) __Pyx_ErrFetchInState(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb); +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A6 +#define __Pyx_PyErr_SetNone(exc) (Py_INCREF(exc), __Pyx_ErrRestore((exc), NULL, NULL)) +#else +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#endif +#else +#define __Pyx_PyErr_Clear() PyErr_Clear() +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#define __Pyx_ErrRestoreWithState(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestoreInState(tstate, type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchInState(tstate, type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) PyErr_Fetch(type, value, tb) +#endif + +/* PyObjectGetAttrStr.proto */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GetAttrStr(o,n) PyObject_GetAttr(o,n) +#endif + +/* PyObjectGetAttrStrNoError.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name); + +/* GetBuiltinName.proto */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name); + +/* TupleAndListFromArray.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n); +static CYTHON_INLINE PyObject* __Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n); +#endif + +/* IncludeStringH.proto */ +#include + +/* BytesEquals.proto */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals); + +/* UnicodeEquals.proto */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals); + +/* fastcall.proto */ +#if CYTHON_AVOID_BORROWED_REFS + #define __Pyx_Arg_VARARGS(args, i) PySequence_GetItem(args, i) +#elif CYTHON_ASSUME_SAFE_MACROS + #define __Pyx_Arg_VARARGS(args, i) PyTuple_GET_ITEM(args, i) +#else + #define __Pyx_Arg_VARARGS(args, i) PyTuple_GetItem(args, i) +#endif +#if CYTHON_AVOID_BORROWED_REFS + #define __Pyx_Arg_NewRef_VARARGS(arg) __Pyx_NewRef(arg) + #define __Pyx_Arg_XDECREF_VARARGS(arg) Py_XDECREF(arg) +#else + #define __Pyx_Arg_NewRef_VARARGS(arg) arg + #define __Pyx_Arg_XDECREF_VARARGS(arg) +#endif +#define __Pyx_NumKwargs_VARARGS(kwds) PyDict_Size(kwds) +#define __Pyx_KwValues_VARARGS(args, nargs) NULL +#define __Pyx_GetKwValue_VARARGS(kw, kwvalues, s) __Pyx_PyDict_GetItemStrWithError(kw, s) +#define __Pyx_KwargsAsDict_VARARGS(kw, kwvalues) PyDict_Copy(kw) +#if CYTHON_METH_FASTCALL + #define __Pyx_Arg_FASTCALL(args, i) args[i] + #define __Pyx_NumKwargs_FASTCALL(kwds) PyTuple_GET_SIZE(kwds) + #define __Pyx_KwValues_FASTCALL(args, nargs) ((args) + (nargs)) + static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 + CYTHON_UNUSED static PyObject *__Pyx_KwargsAsDict_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues); + #else + #define __Pyx_KwargsAsDict_FASTCALL(kw, kwvalues) _PyStack_AsDict(kwvalues, kw) + #endif + #define __Pyx_Arg_NewRef_FASTCALL(arg) arg /* no-op, __Pyx_Arg_FASTCALL is direct and this needs + to have the same reference counting */ + #define __Pyx_Arg_XDECREF_FASTCALL(arg) +#else + #define __Pyx_Arg_FASTCALL __Pyx_Arg_VARARGS + #define __Pyx_NumKwargs_FASTCALL __Pyx_NumKwargs_VARARGS + #define __Pyx_KwValues_FASTCALL __Pyx_KwValues_VARARGS + #define __Pyx_GetKwValue_FASTCALL __Pyx_GetKwValue_VARARGS + #define __Pyx_KwargsAsDict_FASTCALL __Pyx_KwargsAsDict_VARARGS + #define __Pyx_Arg_NewRef_FASTCALL(arg) __Pyx_Arg_NewRef_VARARGS(arg) + #define __Pyx_Arg_XDECREF_FASTCALL(arg) __Pyx_Arg_XDECREF_VARARGS(arg) +#endif +#if CYTHON_COMPILING_IN_CPYTHON && CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_VARARGS(args, start), stop - start) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_FASTCALL(args, start), stop - start) +#else +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) PyTuple_GetSlice(args, start, stop) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) PyTuple_GetSlice(args, start, stop) +#endif + +/* RaiseArgTupleInvalid.proto */ +static void __Pyx_RaiseArgtupleInvalid(const char* func_name, int exact, + Py_ssize_t num_min, Py_ssize_t num_max, Py_ssize_t num_found); + +/* RaiseDoubleKeywords.proto */ +static void __Pyx_RaiseDoubleKeywordsError(const char* func_name, PyObject* kw_name); + +/* ParseKeywords.proto */ +static int __Pyx_ParseOptionalKeywords(PyObject *kwds, PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, PyObject *values[], Py_ssize_t num_pos_args, + const char* function_name); + +/* ArgTypeTest.proto */ +#define __Pyx_ArgTypeTest(obj, type, none_allowed, name, exact)\ + ((likely(__Pyx_IS_TYPE(obj, type) | (none_allowed && (obj == Py_None)))) ? 1 :\ + __Pyx__ArgTypeTest(obj, type, name, exact)) +static int __Pyx__ArgTypeTest(PyObject *obj, PyTypeObject *type, const char *name, int exact); + +/* RaiseException.proto */ +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause); + +/* PyFunctionFastCall.proto */ +#if CYTHON_FAST_PYCALL +#if !CYTHON_VECTORCALL +#define __Pyx_PyFunction_FastCall(func, args, nargs)\ + __Pyx_PyFunction_FastCallDict((func), (args), (nargs), NULL) +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs); +#endif +#define __Pyx_BUILD_ASSERT_EXPR(cond)\ + (sizeof(char [1 - 2*!(cond)]) - 1) +#ifndef Py_MEMBER_SIZE +#define Py_MEMBER_SIZE(type, member) sizeof(((type *)0)->member) +#endif +#if !CYTHON_VECTORCALL +#if PY_VERSION_HEX >= 0x03080000 + #include "frameobject.h" +#if PY_VERSION_HEX >= 0x030b00a6 && !CYTHON_COMPILING_IN_LIMITED_API + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif + #define __Pxy_PyFrame_Initialize_Offsets() + #define __Pyx_PyFrame_GetLocalsplus(frame) ((frame)->f_localsplus) +#else + static size_t __pyx_pyframe_localsplus_offset = 0; + #include "frameobject.h" + #define __Pxy_PyFrame_Initialize_Offsets()\ + ((void)__Pyx_BUILD_ASSERT_EXPR(sizeof(PyFrameObject) == offsetof(PyFrameObject, f_localsplus) + Py_MEMBER_SIZE(PyFrameObject, f_localsplus)),\ + (void)(__pyx_pyframe_localsplus_offset = ((size_t)PyFrame_Type.tp_basicsize) - Py_MEMBER_SIZE(PyFrameObject, f_localsplus))) + #define __Pyx_PyFrame_GetLocalsplus(frame)\ + (assert(__pyx_pyframe_localsplus_offset), (PyObject **)(((char *)(frame)) + __pyx_pyframe_localsplus_offset)) +#endif +#endif +#endif + +/* PyObjectCall.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw); +#else +#define __Pyx_PyObject_Call(func, arg, kw) PyObject_Call(func, arg, kw) +#endif + +/* PyObjectCallMethO.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg); +#endif + +/* PyObjectFastCall.proto */ +#define __Pyx_PyObject_FastCall(func, args, nargs) __Pyx_PyObject_FastCallDict(func, args, (size_t)(nargs), NULL) +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs); + +/* RaiseUnexpectedTypeError.proto */ +static int __Pyx_RaiseUnexpectedTypeError(const char *expected, PyObject *obj); + +/* GCCDiagnostics.proto */ +#if !defined(__INTEL_COMPILER) && defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 6)) +#define __Pyx_HAS_GCC_DIAGNOSTIC +#endif + +/* BuildPyUnicode.proto */ +static PyObject* __Pyx_PyUnicode_BuildFromAscii(Py_ssize_t ulength, char* chars, int clength, + int prepend_sign, char padding_char); + +/* CIntToPyUnicode.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_int(int value, Py_ssize_t width, char padding_char, char format_char); + +/* CIntToPyUnicode.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_Py_ssize_t(Py_ssize_t value, Py_ssize_t width, char padding_char, char format_char); + +/* JoinPyUnicode.proto */ +static PyObject* __Pyx_PyUnicode_Join(PyObject* value_tuple, Py_ssize_t value_count, Py_ssize_t result_ulength, + Py_UCS4 max_char); + +/* StrEquals.proto */ +#if PY_MAJOR_VERSION >= 3 +#define __Pyx_PyString_Equals __Pyx_PyUnicode_Equals +#else +#define __Pyx_PyString_Equals __Pyx_PyBytes_Equals +#endif + +/* PyObjectFormatSimple.proto */ +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + PyObject_Format(s, f)) +#elif PY_MAJOR_VERSION < 3 + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + likely(PyString_CheckExact(s)) ? PyUnicode_FromEncodedObject(s, NULL, "strict") :\ + PyObject_Format(s, f)) +#elif CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + likely(PyLong_CheckExact(s)) ? PyLong_Type.tp_repr(s) :\ + likely(PyFloat_CheckExact(s)) ? PyFloat_Type.tp_repr(s) :\ + PyObject_Format(s, f)) +#else + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + PyObject_Format(s, f)) +#endif + +CYTHON_UNUSED static int __pyx_array_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +static PyObject *__pyx_array_get_memview(struct __pyx_array_obj *); /*proto*/ +/* GetAttr.proto */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr(PyObject *, PyObject *); + +/* GetItemInt.proto */ +#define __Pyx_GetItemInt(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_Fast(o, (Py_ssize_t)i, is_list, wraparound, boundscheck) :\ + (is_list ? (PyErr_SetString(PyExc_IndexError, "list index out of range"), (PyObject*)NULL) :\ + __Pyx_GetItemInt_Generic(o, to_py_func(i)))) +#define __Pyx_GetItemInt_List(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_List_Fast(o, (Py_ssize_t)i, wraparound, boundscheck) :\ + (PyErr_SetString(PyExc_IndexError, "list index out of range"), (PyObject*)NULL)) +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_List_Fast(PyObject *o, Py_ssize_t i, + int wraparound, int boundscheck); +#define __Pyx_GetItemInt_Tuple(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_Tuple_Fast(o, (Py_ssize_t)i, wraparound, boundscheck) :\ + (PyErr_SetString(PyExc_IndexError, "tuple index out of range"), (PyObject*)NULL)) +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Tuple_Fast(PyObject *o, Py_ssize_t i, + int wraparound, int boundscheck); +static PyObject *__Pyx_GetItemInt_Generic(PyObject *o, PyObject* j); +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Fast(PyObject *o, Py_ssize_t i, + int is_list, int wraparound, int boundscheck); + +/* PyObjectCallOneArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg); + +/* ObjectGetItem.proto */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject *__Pyx_PyObject_GetItem(PyObject *obj, PyObject *key); +#else +#define __Pyx_PyObject_GetItem(obj, key) PyObject_GetItem(obj, key) +#endif + +/* KeywordStringCheck.proto */ +static int __Pyx_CheckKeywordStrings(PyObject *kw, const char* function_name, int kw_allowed); + +/* DivInt[Py_ssize_t].proto */ +static CYTHON_INLINE Py_ssize_t __Pyx_div_Py_ssize_t(Py_ssize_t, Py_ssize_t); + +/* UnaryNegOverflows.proto */ +#define __Pyx_UNARY_NEG_WOULD_OVERFLOW(x)\ + (((x) < 0) & ((unsigned long)(x) == 0-(unsigned long)(x))) + +/* GetAttr3.proto */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr3(PyObject *, PyObject *, PyObject *); + +/* PyDictVersioning.proto */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +#define __PYX_DICT_VERSION_INIT ((PY_UINT64_T) -1) +#define __PYX_GET_DICT_VERSION(dict) (((PyDictObject*)(dict))->ma_version_tag) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var)\ + (version_var) = __PYX_GET_DICT_VERSION(dict);\ + (cache_var) = (value); +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + if (likely(__PYX_GET_DICT_VERSION(DICT) == __pyx_dict_version)) {\ + (VAR) = __pyx_dict_cached_value;\ + } else {\ + (VAR) = __pyx_dict_cached_value = (LOOKUP);\ + __pyx_dict_version = __PYX_GET_DICT_VERSION(DICT);\ + }\ +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj); +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj); +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version); +#else +#define __PYX_GET_DICT_VERSION(dict) (0) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var) +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) (VAR) = (LOOKUP); +#endif + +/* GetModuleGlobalName.proto */ +#if CYTHON_USE_DICT_VERSIONS +#define __Pyx_GetModuleGlobalName(var, name) do {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + (var) = (likely(__pyx_dict_version == __PYX_GET_DICT_VERSION(__pyx_d))) ?\ + (likely(__pyx_dict_cached_value) ? __Pyx_NewRef(__pyx_dict_cached_value) : __Pyx_GetBuiltinName(name)) :\ + __Pyx__GetModuleGlobalName(name, &__pyx_dict_version, &__pyx_dict_cached_value);\ +} while(0) +#define __Pyx_GetModuleGlobalNameUncached(var, name) do {\ + PY_UINT64_T __pyx_dict_version;\ + PyObject *__pyx_dict_cached_value;\ + (var) = __Pyx__GetModuleGlobalName(name, &__pyx_dict_version, &__pyx_dict_cached_value);\ +} while(0) +static PyObject *__Pyx__GetModuleGlobalName(PyObject *name, PY_UINT64_T *dict_version, PyObject **dict_cached_value); +#else +#define __Pyx_GetModuleGlobalName(var, name) (var) = __Pyx__GetModuleGlobalName(name) +#define __Pyx_GetModuleGlobalNameUncached(var, name) (var) = __Pyx__GetModuleGlobalName(name) +static CYTHON_INLINE PyObject *__Pyx__GetModuleGlobalName(PyObject *name); +#endif + +/* AssertionsEnabled.proto */ +#if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX < 0x02070600 && !defined(Py_OptimizeFlag) + #define __Pyx_init_assertions_enabled() (0) + #define __pyx_assertions_enabled() (1) +#elif CYTHON_COMPILING_IN_LIMITED_API || (CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030C0000) + static int __pyx_assertions_enabled_flag; + #define __pyx_assertions_enabled() (__pyx_assertions_enabled_flag) + static int __Pyx_init_assertions_enabled(void) { + PyObject *builtins, *debug, *debug_str; + int flag; + builtins = PyEval_GetBuiltins(); + if (!builtins) goto bad; + debug_str = PyUnicode_FromStringAndSize("__debug__", 9); + if (!debug_str) goto bad; + debug = PyObject_GetItem(builtins, debug_str); + Py_DECREF(debug_str); + if (!debug) goto bad; + flag = PyObject_IsTrue(debug); + Py_DECREF(debug); + if (flag == -1) goto bad; + __pyx_assertions_enabled_flag = flag; + return 0; + bad: + __pyx_assertions_enabled_flag = 1; + return -1; + } +#else + #define __Pyx_init_assertions_enabled() (0) + #define __pyx_assertions_enabled() (!Py_OptimizeFlag) +#endif + +/* RaiseTooManyValuesToUnpack.proto */ +static CYTHON_INLINE void __Pyx_RaiseTooManyValuesError(Py_ssize_t expected); + +/* RaiseNeedMoreValuesToUnpack.proto */ +static CYTHON_INLINE void __Pyx_RaiseNeedMoreValuesError(Py_ssize_t index); + +/* RaiseNoneIterError.proto */ +static CYTHON_INLINE void __Pyx_RaiseNoneNotIterableError(void); + +/* ExtTypeTest.proto */ +static CYTHON_INLINE int __Pyx_TypeTest(PyObject *obj, PyTypeObject *type); + +/* GetTopmostException.proto */ +#if CYTHON_USE_EXC_INFO_STACK && CYTHON_FAST_THREAD_STATE +static _PyErr_StackItem * __Pyx_PyErr_GetTopmostException(PyThreadState *tstate); +#endif + +/* SaveResetException.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_ExceptionSave(type, value, tb) __Pyx__ExceptionSave(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx__ExceptionSave(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#define __Pyx_ExceptionReset(type, value, tb) __Pyx__ExceptionReset(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx__ExceptionReset(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb); +#else +#define __Pyx_ExceptionSave(type, value, tb) PyErr_GetExcInfo(type, value, tb) +#define __Pyx_ExceptionReset(type, value, tb) PyErr_SetExcInfo(type, value, tb) +#endif + +/* GetException.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_GetException(type, value, tb) __Pyx__GetException(__pyx_tstate, type, value, tb) +static int __Pyx__GetException(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#else +static int __Pyx_GetException(PyObject **type, PyObject **value, PyObject **tb); +#endif + +/* SwapException.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_ExceptionSwap(type, value, tb) __Pyx__ExceptionSwap(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx__ExceptionSwap(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#else +static CYTHON_INLINE void __Pyx_ExceptionSwap(PyObject **type, PyObject **value, PyObject **tb); +#endif + +/* Import.proto */ +static PyObject *__Pyx_Import(PyObject *name, PyObject *from_list, int level); + +/* ImportDottedModule.proto */ +static PyObject *__Pyx_ImportDottedModule(PyObject *name, PyObject *parts_tuple); +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_ImportDottedModule_WalkParts(PyObject *module, PyObject *name, PyObject *parts_tuple); +#endif + +/* FastTypeChecks.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_TypeCheck(obj, type) __Pyx_IsSubtype(Py_TYPE(obj), (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) __Pyx_IsAnySubtype2(Py_TYPE(obj), (PyTypeObject *)type1, (PyTypeObject *)type2) +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches(PyObject *err, PyObject *type); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches2(PyObject *err, PyObject *type1, PyObject *type2); +#else +#define __Pyx_TypeCheck(obj, type) PyObject_TypeCheck(obj, (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) (PyObject_TypeCheck(obj, (PyTypeObject *)type1) || PyObject_TypeCheck(obj, (PyTypeObject *)type2)) +#define __Pyx_PyErr_GivenExceptionMatches(err, type) PyErr_GivenExceptionMatches(err, type) +#define __Pyx_PyErr_GivenExceptionMatches2(err, type1, type2) (PyErr_GivenExceptionMatches(err, type1) || PyErr_GivenExceptionMatches(err, type2)) +#endif +#define __Pyx_PyErr_ExceptionMatches2(err1, err2) __Pyx_PyErr_GivenExceptionMatches2(__Pyx_PyErr_CurrentExceptionType(), err1, err2) +#define __Pyx_PyException_Check(obj) __Pyx_TypeCheck(obj, PyExc_Exception) + +CYTHON_UNUSED static int __pyx_memoryview_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +/* ListCompAppend.proto */ +#if CYTHON_USE_PYLIST_INTERNALS && CYTHON_ASSUME_SAFE_MACROS +static CYTHON_INLINE int __Pyx_ListComp_Append(PyObject* list, PyObject* x) { + PyListObject* L = (PyListObject*) list; + Py_ssize_t len = Py_SIZE(list); + if (likely(L->allocated > len)) { + Py_INCREF(x); + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 + L->ob_item[len] = x; + #else + PyList_SET_ITEM(list, len, x); + #endif + __Pyx_SET_SIZE(list, len + 1); + return 0; + } + return PyList_Append(list, x); +} +#else +#define __Pyx_ListComp_Append(L,x) PyList_Append(L,x) +#endif + +/* PySequenceMultiply.proto */ +#define __Pyx_PySequence_Multiply_Left(mul, seq) __Pyx_PySequence_Multiply(seq, mul) +static CYTHON_INLINE PyObject* __Pyx_PySequence_Multiply(PyObject *seq, Py_ssize_t mul); + +/* SetItemInt.proto */ +#define __Pyx_SetItemInt(o, i, v, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_SetItemInt_Fast(o, (Py_ssize_t)i, v, is_list, wraparound, boundscheck) :\ + (is_list ? (PyErr_SetString(PyExc_IndexError, "list assignment index out of range"), -1) :\ + __Pyx_SetItemInt_Generic(o, to_py_func(i), v))) +static int __Pyx_SetItemInt_Generic(PyObject *o, PyObject *j, PyObject *v); +static CYTHON_INLINE int __Pyx_SetItemInt_Fast(PyObject *o, Py_ssize_t i, PyObject *v, + int is_list, int wraparound, int boundscheck); + +/* RaiseUnboundLocalError.proto */ +static CYTHON_INLINE void __Pyx_RaiseUnboundLocalError(const char *varname); + +/* DivInt[long].proto */ +static CYTHON_INLINE long __Pyx_div_long(long, long); + +/* PySequenceContains.proto */ +static CYTHON_INLINE int __Pyx_PySequence_ContainsTF(PyObject* item, PyObject* seq, int eq) { + int result = PySequence_Contains(seq, item); + return unlikely(result < 0) ? result : (result == (eq == Py_EQ)); +} + +/* ImportFrom.proto */ +static PyObject* __Pyx_ImportFrom(PyObject* module, PyObject* name); + +/* HasAttr.proto */ +#if __PYX_LIMITED_VERSION_HEX >= 0x030d00A1 +#define __Pyx_HasAttr(o, n) PyObject_HasAttrWithError(o, n) +#else +static CYTHON_INLINE int __Pyx_HasAttr(PyObject *, PyObject *); +#endif + +/* PyIntCompare.proto */ +static CYTHON_INLINE int __Pyx_PyInt_BoolEqObjC(PyObject *op1, PyObject *op2, long intval, long inplace); + +/* PyIntCompare.proto */ +static CYTHON_INLINE int __Pyx_PyInt_BoolNeObjC(PyObject *op1, PyObject *op2, long intval, long inplace); + +/* IsLittleEndian.proto */ +static CYTHON_INLINE int __Pyx_Is_Little_Endian(void); + +/* BufferFormatCheck.proto */ +static const char* __Pyx_BufFmt_CheckString(__Pyx_BufFmt_Context* ctx, const char* ts); +static void __Pyx_BufFmt_Init(__Pyx_BufFmt_Context* ctx, + __Pyx_BufFmt_StackElem* stack, + __Pyx_TypeInfo* type); + +/* BufferGetAndValidate.proto */ +#define __Pyx_GetBufferAndValidate(buf, obj, dtype, flags, nd, cast, stack)\ + ((obj == Py_None || obj == NULL) ?\ + (__Pyx_ZeroBuffer(buf), 0) :\ + __Pyx__GetBufferAndValidate(buf, obj, dtype, flags, nd, cast, stack)) +static int __Pyx__GetBufferAndValidate(Py_buffer* buf, PyObject* obj, + __Pyx_TypeInfo* dtype, int flags, int nd, int cast, __Pyx_BufFmt_StackElem* stack); +static void __Pyx_ZeroBuffer(Py_buffer* buf); +static CYTHON_INLINE void __Pyx_SafeReleaseBuffer(Py_buffer* info); +static Py_ssize_t __Pyx_minusones[] = { -1, -1, -1, -1, -1, -1, -1, -1 }; +static Py_ssize_t __Pyx_zeros[] = { 0, 0, 0, 0, 0, 0, 0, 0 }; + +/* UnicodeConcatInPlace.proto */ +# if CYTHON_COMPILING_IN_CPYTHON && PY_MAJOR_VERSION >= 3 + #if CYTHON_REFNANNY + #define __Pyx_PyUnicode_ConcatInPlace(left, right) __Pyx_PyUnicode_ConcatInPlaceImpl(&left, right, __pyx_refnanny) + #else + #define __Pyx_PyUnicode_ConcatInPlace(left, right) __Pyx_PyUnicode_ConcatInPlaceImpl(&left, right) + #endif + static CYTHON_INLINE PyObject *__Pyx_PyUnicode_ConcatInPlaceImpl(PyObject **p_left, PyObject *right + #if CYTHON_REFNANNY + , void* __pyx_refnanny + #endif + ); +#else +#define __Pyx_PyUnicode_ConcatInPlace __Pyx_PyUnicode_Concat +#endif +#define __Pyx_PyUnicode_ConcatInPlaceSafe(left, right) ((unlikely((left) == Py_None) || unlikely((right) == Py_None)) ?\ + PyNumber_InPlaceAdd(left, right) : __Pyx_PyUnicode_ConcatInPlace(left, right)) + +/* SliceObject.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetSlice( + PyObject* obj, Py_ssize_t cstart, Py_ssize_t cstop, + PyObject** py_start, PyObject** py_stop, PyObject** py_slice, + int has_cstart, int has_cstop, int wraparound); + +/* PyObject_Str.proto */ +#define __Pyx_PyObject_Str(obj)\ + (likely(PyString_CheckExact(obj)) ? __Pyx_NewRef(obj) : PyObject_Str(obj)) + +/* PyObjectFormat.proto */ +#if CYTHON_USE_UNICODE_WRITER +static PyObject* __Pyx_PyObject_Format(PyObject* s, PyObject* f); +#else +#define __Pyx_PyObject_Format(s, f) PyObject_Format(s, f) +#endif + +/* py_dict_keys.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyDict_Keys(PyObject* d); + +/* UnpackUnboundCMethod.proto */ +typedef struct { + PyObject *type; + PyObject **method_name; + PyCFunction func; + PyObject *method; + int flag; +} __Pyx_CachedCFunction; + +/* CallUnboundCMethod0.proto */ +static PyObject* __Pyx__CallUnboundCMethod0(__Pyx_CachedCFunction* cfunc, PyObject* self); +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_CallUnboundCMethod0(cfunc, self)\ + (likely((cfunc)->func) ?\ + (likely((cfunc)->flag == METH_NOARGS) ? (*((cfunc)->func))(self, NULL) :\ + (PY_VERSION_HEX >= 0x030600B1 && likely((cfunc)->flag == METH_FASTCALL) ?\ + (PY_VERSION_HEX >= 0x030700A0 ?\ + (*(__Pyx_PyCFunctionFast)(void*)(PyCFunction)(cfunc)->func)(self, &__pyx_empty_tuple, 0) :\ + (*(__Pyx_PyCFunctionFastWithKeywords)(void*)(PyCFunction)(cfunc)->func)(self, &__pyx_empty_tuple, 0, NULL)) :\ + (PY_VERSION_HEX >= 0x030700A0 && (cfunc)->flag == (METH_FASTCALL | METH_KEYWORDS) ?\ + (*(__Pyx_PyCFunctionFastWithKeywords)(void*)(PyCFunction)(cfunc)->func)(self, &__pyx_empty_tuple, 0, NULL) :\ + (likely((cfunc)->flag == (METH_VARARGS | METH_KEYWORDS)) ? ((*(PyCFunctionWithKeywords)(void*)(PyCFunction)(cfunc)->func)(self, __pyx_empty_tuple, NULL)) :\ + ((cfunc)->flag == METH_VARARGS ? (*((cfunc)->func))(self, __pyx_empty_tuple) :\ + __Pyx__CallUnboundCMethod0(cfunc, self)))))) :\ + __Pyx__CallUnboundCMethod0(cfunc, self)) +#else +#define __Pyx_CallUnboundCMethod0(cfunc, self) __Pyx__CallUnboundCMethod0(cfunc, self) +#endif + +/* DictGetItem.proto */ +#if PY_MAJOR_VERSION >= 3 && !CYTHON_COMPILING_IN_PYPY +static PyObject *__Pyx_PyDict_GetItem(PyObject *d, PyObject* key); +#define __Pyx_PyObject_Dict_GetItem(obj, name)\ + (likely(PyDict_CheckExact(obj)) ?\ + __Pyx_PyDict_GetItem(obj, name) : PyObject_GetItem(obj, name)) +#else +#define __Pyx_PyDict_GetItem(d, key) PyObject_GetItem(d, key) +#define __Pyx_PyObject_Dict_GetItem(obj, name) PyObject_GetItem(obj, name) +#endif + +/* PyObjectLookupSpecial.proto */ +#if CYTHON_USE_PYTYPE_LOOKUP && CYTHON_USE_TYPE_SLOTS +#define __Pyx_PyObject_LookupSpecialNoError(obj, attr_name) __Pyx__PyObject_LookupSpecial(obj, attr_name, 0) +#define __Pyx_PyObject_LookupSpecial(obj, attr_name) __Pyx__PyObject_LookupSpecial(obj, attr_name, 1) +static CYTHON_INLINE PyObject* __Pyx__PyObject_LookupSpecial(PyObject* obj, PyObject* attr_name, int with_error); +#else +#define __Pyx_PyObject_LookupSpecialNoError(o,n) __Pyx_PyObject_GetAttrStrNoError(o,n) +#define __Pyx_PyObject_LookupSpecial(o,n) __Pyx_PyObject_GetAttrStr(o,n) +#endif + +/* IncludeStructmemberH.proto */ +#include + +/* FixUpExtensionType.proto */ +#if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type); +#endif + +/* FetchSharedCythonModule.proto */ +static PyObject *__Pyx_FetchSharedCythonABIModule(void); + +/* FetchCommonType.proto */ +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type); +#else +static PyTypeObject* __Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases); +#endif + +/* PyMethodNew.proto */ +#if CYTHON_COMPILING_IN_LIMITED_API +static PyObject *__Pyx_PyMethod_New(PyObject *func, PyObject *self, PyObject *typ) { + PyObject *typesModule=NULL, *methodType=NULL, *result=NULL; + CYTHON_UNUSED_VAR(typ); + if (!self) + return __Pyx_NewRef(func); + typesModule = PyImport_ImportModule("types"); + if (!typesModule) return NULL; + methodType = PyObject_GetAttrString(typesModule, "MethodType"); + Py_DECREF(typesModule); + if (!methodType) return NULL; + result = PyObject_CallFunctionObjArgs(methodType, func, self, NULL); + Py_DECREF(methodType); + return result; +} +#elif PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_PyMethod_New(PyObject *func, PyObject *self, PyObject *typ) { + CYTHON_UNUSED_VAR(typ); + if (!self) + return __Pyx_NewRef(func); + return PyMethod_New(func, self); +} +#else + #define __Pyx_PyMethod_New PyMethod_New +#endif + +/* PyVectorcallFastCallDict.proto */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw); +#endif + +/* CythonFunctionShared.proto */ +#define __Pyx_CyFunction_USED +#define __Pyx_CYFUNCTION_STATICMETHOD 0x01 +#define __Pyx_CYFUNCTION_CLASSMETHOD 0x02 +#define __Pyx_CYFUNCTION_CCLASS 0x04 +#define __Pyx_CYFUNCTION_COROUTINE 0x08 +#define __Pyx_CyFunction_GetClosure(f)\ + (((__pyx_CyFunctionObject *) (f))->func_closure) +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_CyFunction_GetClassObj(f)\ + (((__pyx_CyFunctionObject *) (f))->func_classobj) +#else + #define __Pyx_CyFunction_GetClassObj(f)\ + ((PyObject*) ((PyCMethodObject *) (f))->mm_class) +#endif +#define __Pyx_CyFunction_SetClassObj(f, classobj)\ + __Pyx__CyFunction_SetClassObj((__pyx_CyFunctionObject *) (f), (classobj)) +#define __Pyx_CyFunction_Defaults(type, f)\ + ((type *)(((__pyx_CyFunctionObject *) (f))->defaults)) +#define __Pyx_CyFunction_SetDefaultsGetter(f, g)\ + ((__pyx_CyFunctionObject *) (f))->defaults_getter = (g) +typedef struct { +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject_HEAD + PyObject *func; +#elif PY_VERSION_HEX < 0x030900B1 + PyCFunctionObject func; +#else + PyCMethodObject func; +#endif +#if CYTHON_BACKPORT_VECTORCALL + __pyx_vectorcallfunc func_vectorcall; +#endif +#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API + PyObject *func_weakreflist; +#endif + PyObject *func_dict; + PyObject *func_name; + PyObject *func_qualname; + PyObject *func_doc; + PyObject *func_globals; + PyObject *func_code; + PyObject *func_closure; +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + PyObject *func_classobj; +#endif + void *defaults; + int defaults_pyobjects; + size_t defaults_size; + int flags; + PyObject *defaults_tuple; + PyObject *defaults_kwdict; + PyObject *(*defaults_getter)(PyObject *); + PyObject *func_annotations; + PyObject *func_is_coroutine; +} __pyx_CyFunctionObject; +#undef __Pyx_CyOrPyCFunction_Check +#define __Pyx_CyFunction_Check(obj) __Pyx_TypeCheck(obj, __pyx_CyFunctionType) +#define __Pyx_CyOrPyCFunction_Check(obj) __Pyx_TypeCheck2(obj, __pyx_CyFunctionType, &PyCFunction_Type) +#define __Pyx_CyFunction_CheckExact(obj) __Pyx_IS_TYPE(obj, __pyx_CyFunctionType) +static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc); +#undef __Pyx_IsSameCFunction +#define __Pyx_IsSameCFunction(func, cfunc) __Pyx__IsSameCyOrCFunction(func, cfunc) +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject* op, PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj); +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *m, + size_t size, + int pyobjects); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *m, + PyObject *tuple); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *m, + PyObject *dict); +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *m, + PyObject *dict); +static int __pyx_CyFunction_init(PyObject *module); +#if CYTHON_METH_FASTCALL +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +#if CYTHON_BACKPORT_VECTORCALL +#define __Pyx_CyFunction_func_vectorcall(f) (((__pyx_CyFunctionObject*)f)->func_vectorcall) +#else +#define __Pyx_CyFunction_func_vectorcall(f) (((PyCFunctionObject*)f)->vectorcall) +#endif +#endif + +/* CythonFunction.proto */ +static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); + +/* IterFinish.proto */ +static CYTHON_INLINE int __Pyx_IterFinish(void); + +/* PyObjectCallNoArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func); + +/* PyObjectGetMethod.proto */ +static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method); + +/* PyObjectCallMethod0.proto */ +static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name); + +/* UnpackItemEndCheck.proto */ +static int __Pyx_IternextUnpackEndCheck(PyObject *retval, Py_ssize_t expected); + +/* UnpackTupleError.proto */ +static void __Pyx_UnpackTupleError(PyObject *, Py_ssize_t index); + +/* UnpackTuple2.proto */ +#define __Pyx_unpack_tuple2(tuple, value1, value2, is_tuple, has_known_size, decref_tuple)\ + (likely(is_tuple || PyTuple_Check(tuple)) ?\ + (likely(has_known_size || PyTuple_GET_SIZE(tuple) == 2) ?\ + __Pyx_unpack_tuple2_exact(tuple, value1, value2, decref_tuple) :\ + (__Pyx_UnpackTupleError(tuple, 2), -1)) :\ + __Pyx_unpack_tuple2_generic(tuple, value1, value2, has_known_size, decref_tuple)) +static CYTHON_INLINE int __Pyx_unpack_tuple2_exact( + PyObject* tuple, PyObject** value1, PyObject** value2, int decref_tuple); +static int __Pyx_unpack_tuple2_generic( + PyObject* tuple, PyObject** value1, PyObject** value2, int has_known_size, int decref_tuple); + +/* dict_iter.proto */ +static CYTHON_INLINE PyObject* __Pyx_dict_iterator(PyObject* dict, int is_dict, PyObject* method_name, + Py_ssize_t* p_orig_length, int* p_is_dict); +static CYTHON_INLINE int __Pyx_dict_iter_next(PyObject* dict_or_iter, Py_ssize_t orig_length, Py_ssize_t* ppos, + PyObject** pkey, PyObject** pvalue, PyObject** pitem, int is_dict); + +/* PyIntBinop.proto */ +#if !CYTHON_COMPILING_IN_PYPY +static PyObject* __Pyx_PyInt_AddObjC(PyObject *op1, PyObject *op2, long intval, int inplace, int zerodivision_check); +#else +#define __Pyx_PyInt_AddObjC(op1, op2, intval, inplace, zerodivision_check)\ + (inplace ? PyNumber_InPlaceAdd(op1, op2) : PyNumber_Add(op1, op2)) +#endif + +/* BufferIndexError.proto */ +static void __Pyx_RaiseBufferIndexError(int axis); + +#define __Pyx_BufPtrStrided1d(type, buf, i0, s0) (type)((char*)buf + i0 * s0) +/* PyUnicode_Unicode.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_Unicode(PyObject *obj); + +/* PyObject_GenericGetAttrNoDict.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttrNoDict PyObject_GenericGetAttr +#endif + +/* PyObject_GenericGetAttr.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttr PyObject_GenericGetAttr +#endif + +/* ValidateBasesTuple.proto */ +#if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases); +#endif + +/* PyType_Ready.proto */ +CYTHON_UNUSED static int __Pyx_PyType_Ready(PyTypeObject *t); + +/* SetupReduce.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce(PyObject* type_obj); +#endif + +/* SetVTable.proto */ +static int __Pyx_SetVtable(PyTypeObject* typeptr , void* vtable); + +/* GetVTable.proto */ +static void* __Pyx_GetVtable(PyTypeObject *type); + +/* MergeVTables.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_MergeVtables(PyTypeObject *type); +#endif + +/* TypeImport.proto */ +#ifndef __PYX_HAVE_RT_ImportType_proto_3_0_8 +#define __PYX_HAVE_RT_ImportType_proto_3_0_8 +#if defined (__STDC_VERSION__) && __STDC_VERSION__ >= 201112L +#include +#endif +#if (defined (__STDC_VERSION__) && __STDC_VERSION__ >= 201112L) || __cplusplus >= 201103L +#define __PYX_GET_STRUCT_ALIGNMENT_3_0_8(s) alignof(s) +#else +#define __PYX_GET_STRUCT_ALIGNMENT_3_0_8(s) sizeof(void*) +#endif +enum __Pyx_ImportType_CheckSize_3_0_8 { + __Pyx_ImportType_CheckSize_Error_3_0_8 = 0, + __Pyx_ImportType_CheckSize_Warn_3_0_8 = 1, + __Pyx_ImportType_CheckSize_Ignore_3_0_8 = 2 +}; +static PyTypeObject *__Pyx_ImportType_3_0_8(PyObject* module, const char *module_name, const char *class_name, size_t size, size_t alignment, enum __Pyx_ImportType_CheckSize_3_0_8 check_size); +#endif + +/* CLineInTraceback.proto */ +#ifdef CYTHON_CLINE_IN_TRACEBACK +#define __Pyx_CLineForTraceback(tstate, c_line) (((CYTHON_CLINE_IN_TRACEBACK)) ? c_line : 0) +#else +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line); +#endif + +/* CodeObjectCache.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +typedef struct { + PyCodeObject* code_object; + int code_line; +} __Pyx_CodeObjectCacheEntry; +struct __Pyx_CodeObjectCache { + int count; + int max_count; + __Pyx_CodeObjectCacheEntry* entries; +}; +static struct __Pyx_CodeObjectCache __pyx_code_cache = {0,0,NULL}; +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line); +static PyCodeObject *__pyx_find_code_object(int code_line); +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object); +#endif + +/* AddTraceback.proto */ +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename); + +#if PY_MAJOR_VERSION < 3 + static int __Pyx_GetBuffer(PyObject *obj, Py_buffer *view, int flags); + static void __Pyx_ReleaseBuffer(Py_buffer *view); +#else + #define __Pyx_GetBuffer PyObject_GetBuffer + #define __Pyx_ReleaseBuffer PyBuffer_Release +#endif + + +/* BufferStructDeclare.proto */ +typedef struct { + Py_ssize_t shape, strides, suboffsets; +} __Pyx_Buf_DimInfo; +typedef struct { + size_t refcount; + Py_buffer pybuffer; +} __Pyx_Buffer; +typedef struct { + __Pyx_Buffer *rcbuffer; + char *data; + __Pyx_Buf_DimInfo diminfo[8]; +} __Pyx_LocalBuf_ND; + +/* MemviewSliceIsContig.proto */ +static int __pyx_memviewslice_is_contig(const __Pyx_memviewslice mvs, char order, int ndim); + +/* OverlappingSlices.proto */ +static int __pyx_slices_overlap(__Pyx_memviewslice *slice1, + __Pyx_memviewslice *slice2, + int ndim, size_t itemsize); + +/* TypeInfoCompare.proto */ +static int __pyx_typeinfo_cmp(__Pyx_TypeInfo *a, __Pyx_TypeInfo *b); + +/* MemviewSliceValidateAndInit.proto */ +static int __Pyx_ValidateAndInit_memviewslice( + int *axes_specs, + int c_or_f_flag, + int buf_flags, + int ndim, + __Pyx_TypeInfo *dtype, + __Pyx_BufFmt_StackElem stack[], + __Pyx_memviewslice *memviewslice, + PyObject *original_obj); + +/* ObjectToMemviewSlice.proto */ +static CYTHON_INLINE __Pyx_memviewslice __Pyx_PyObject_to_MemoryviewSlice_dcd__double(PyObject *, int writable_flag); + +/* ObjectToMemviewSlice.proto */ +static CYTHON_INLINE __Pyx_memviewslice __Pyx_PyObject_to_MemoryviewSlice_dc_unsigned_char(PyObject *, int writable_flag); + +/* RealImag.proto */ +#if CYTHON_CCOMPLEX + #ifdef __cplusplus + #define __Pyx_CREAL(z) ((z).real()) + #define __Pyx_CIMAG(z) ((z).imag()) + #else + #define __Pyx_CREAL(z) (__real__(z)) + #define __Pyx_CIMAG(z) (__imag__(z)) + #endif +#else + #define __Pyx_CREAL(z) ((z).real) + #define __Pyx_CIMAG(z) ((z).imag) +#endif +#if defined(__cplusplus) && CYTHON_CCOMPLEX\ + && (defined(_WIN32) || defined(__clang__) || (defined(__GNUC__) && (__GNUC__ >= 5 || __GNUC__ == 4 && __GNUC_MINOR__ >= 4 )) || __cplusplus >= 201103) + #define __Pyx_SET_CREAL(z,x) ((z).real(x)) + #define __Pyx_SET_CIMAG(z,y) ((z).imag(y)) +#else + #define __Pyx_SET_CREAL(z,x) __Pyx_CREAL(z) = (x) + #define __Pyx_SET_CIMAG(z,y) __Pyx_CIMAG(z) = (y) +#endif + +/* Arithmetic.proto */ +#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #define __Pyx_c_eq_float(a, b) ((a)==(b)) + #define __Pyx_c_sum_float(a, b) ((a)+(b)) + #define __Pyx_c_diff_float(a, b) ((a)-(b)) + #define __Pyx_c_prod_float(a, b) ((a)*(b)) + #define __Pyx_c_quot_float(a, b) ((a)/(b)) + #define __Pyx_c_neg_float(a) (-(a)) + #ifdef __cplusplus + #define __Pyx_c_is_zero_float(z) ((z)==(float)0) + #define __Pyx_c_conj_float(z) (::std::conj(z)) + #if 1 + #define __Pyx_c_abs_float(z) (::std::abs(z)) + #define __Pyx_c_pow_float(a, b) (::std::pow(a, b)) + #endif + #else + #define __Pyx_c_is_zero_float(z) ((z)==0) + #define __Pyx_c_conj_float(z) (conjf(z)) + #if 1 + #define __Pyx_c_abs_float(z) (cabsf(z)) + #define __Pyx_c_pow_float(a, b) (cpowf(a, b)) + #endif + #endif +#else + static CYTHON_INLINE int __Pyx_c_eq_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_sum_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_diff_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_prod_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_quot_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_neg_float(__pyx_t_float_complex); + static CYTHON_INLINE int __Pyx_c_is_zero_float(__pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_conj_float(__pyx_t_float_complex); + #if 1 + static CYTHON_INLINE float __Pyx_c_abs_float(__pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_pow_float(__pyx_t_float_complex, __pyx_t_float_complex); + #endif +#endif + +/* Arithmetic.proto */ +#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #define __Pyx_c_eq_double(a, b) ((a)==(b)) + #define __Pyx_c_sum_double(a, b) ((a)+(b)) + #define __Pyx_c_diff_double(a, b) ((a)-(b)) + #define __Pyx_c_prod_double(a, b) ((a)*(b)) + #define __Pyx_c_quot_double(a, b) ((a)/(b)) + #define __Pyx_c_neg_double(a) (-(a)) + #ifdef __cplusplus + #define __Pyx_c_is_zero_double(z) ((z)==(double)0) + #define __Pyx_c_conj_double(z) (::std::conj(z)) + #if 1 + #define __Pyx_c_abs_double(z) (::std::abs(z)) + #define __Pyx_c_pow_double(a, b) (::std::pow(a, b)) + #endif + #else + #define __Pyx_c_is_zero_double(z) ((z)==0) + #define __Pyx_c_conj_double(z) (conj(z)) + #if 1 + #define __Pyx_c_abs_double(z) (cabs(z)) + #define __Pyx_c_pow_double(a, b) (cpow(a, b)) + #endif + #endif +#else + static CYTHON_INLINE int __Pyx_c_eq_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_sum_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_diff_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_prod_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_quot_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_neg_double(__pyx_t_double_complex); + static CYTHON_INLINE int __Pyx_c_is_zero_double(__pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_conj_double(__pyx_t_double_complex); + #if 1 + static CYTHON_INLINE double __Pyx_c_abs_double(__pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_pow_double(__pyx_t_double_complex, __pyx_t_double_complex); + #endif +#endif + +/* MemviewSliceCopyTemplate.proto */ +static __Pyx_memviewslice +__pyx_memoryview_copy_new_contig(const __Pyx_memviewslice *from_mvs, + const char *mode, int ndim, + size_t sizeof_dtype, int contig_flag, + int dtype_is_object); + +/* MemviewSliceInit.proto */ +#define __Pyx_BUF_MAX_NDIMS %(BUF_MAX_NDIMS)d +#define __Pyx_MEMVIEW_DIRECT 1 +#define __Pyx_MEMVIEW_PTR 2 +#define __Pyx_MEMVIEW_FULL 4 +#define __Pyx_MEMVIEW_CONTIG 8 +#define __Pyx_MEMVIEW_STRIDED 16 +#define __Pyx_MEMVIEW_FOLLOW 32 +#define __Pyx_IS_C_CONTIG 1 +#define __Pyx_IS_F_CONTIG 2 +static int __Pyx_init_memviewslice( + struct __pyx_memoryview_obj *memview, + int ndim, + __Pyx_memviewslice *memviewslice, + int memview_is_new_reference); +static CYTHON_INLINE int __pyx_add_acquisition_count_locked( + __pyx_atomic_int_type *acquisition_count, PyThread_type_lock lock); +static CYTHON_INLINE int __pyx_sub_acquisition_count_locked( + __pyx_atomic_int_type *acquisition_count, PyThread_type_lock lock); +#define __pyx_get_slice_count_pointer(memview) (&memview->acquisition_count) +#define __PYX_INC_MEMVIEW(slice, have_gil) __Pyx_INC_MEMVIEW(slice, have_gil, __LINE__) +#define __PYX_XCLEAR_MEMVIEW(slice, have_gil) __Pyx_XCLEAR_MEMVIEW(slice, have_gil, __LINE__) +static CYTHON_INLINE void __Pyx_INC_MEMVIEW(__Pyx_memviewslice *, int, int); +static CYTHON_INLINE void __Pyx_XCLEAR_MEMVIEW(__Pyx_memviewslice *, int, int); + +/* CIntFromPy.proto */ +static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_int(int value); + +/* CIntFromPy.proto */ +static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value); + +/* CIntFromPy.proto */ +static CYTHON_INLINE size_t __Pyx_PyInt_As_size_t(PyObject *); + +/* CIntFromPy.proto */ +static CYTHON_INLINE char __Pyx_PyInt_As_char(PyObject *); + +/* FormatTypeName.proto */ +#if CYTHON_COMPILING_IN_LIMITED_API +typedef PyObject *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%U" +static __Pyx_TypeName __Pyx_PyType_GetName(PyTypeObject* tp); +#define __Pyx_DECREF_TypeName(obj) Py_XDECREF(obj) +#else +typedef const char *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%.200s" +#define __Pyx_PyType_GetName(tp) ((tp)->tp_name) +#define __Pyx_DECREF_TypeName(obj) +#endif + +/* CheckBinaryVersion.proto */ +static unsigned long __Pyx_get_runtime_version(void); +static int __Pyx_check_binary_version(unsigned long ct_version, unsigned long rt_version, int allow_newer); + +/* InitStrings.proto */ +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t); + +/* #### Code section: module_declarations ### */ +static PyObject *__pyx_array_get_memview(struct __pyx_array_obj *__pyx_v_self); /* proto*/ +static char *__pyx_memoryview_get_item_pointer(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index); /* proto*/ +static PyObject *__pyx_memoryview_is_slice(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj); /* proto*/ +static PyObject *__pyx_memoryview_setitem_slice_assignment(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_dst, PyObject *__pyx_v_src); /* proto*/ +static PyObject *__pyx_memoryview_setitem_slice_assign_scalar(struct __pyx_memoryview_obj *__pyx_v_self, struct __pyx_memoryview_obj *__pyx_v_dst, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryview_setitem_indexed(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryview_convert_item_to_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp); /* proto*/ +static PyObject *__pyx_memoryview_assign_item_from_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryview__get_base(struct __pyx_memoryview_obj *__pyx_v_self); /* proto*/ +static PyObject *__pyx_memoryviewslice_convert_item_to_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp); /* proto*/ +static PyObject *__pyx_memoryviewslice_assign_item_from_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryviewslice__get_base(struct __pyx_memoryviewslice_obj *__pyx_v_self); /* proto*/ +static CYTHON_INLINE PyObject *__pyx_f_5numpy_7ndarray_4base_base(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE PyArray_Descr *__pyx_f_5numpy_7ndarray_5descr_descr(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE int __pyx_f_5numpy_7ndarray_4ndim_ndim(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_5shape_shape(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_7strides_strides(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE npy_intp __pyx_f_5numpy_7ndarray_4size_size(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE char *__pyx_f_5numpy_7ndarray_4data_data(PyArrayObject *__pyx_v_self); /* proto*/ + +/* Module declarations from "cython.view" */ + +/* Module declarations from "cython.dataclasses" */ + +/* Module declarations from "cython" */ + +/* Module declarations from "libc.string" */ + +/* Module declarations from "libc.stdio" */ + +/* Module declarations from "libc" */ + +/* Module declarations from "acados_solver_common" */ + +/* Module declarations from "acados_solver" */ + +/* Module declarations from "__builtin__" */ + +/* Module declarations from "cpython.type" */ + +/* Module declarations from "cpython" */ + +/* Module declarations from "cpython.object" */ + +/* Module declarations from "cpython.ref" */ + +/* Module declarations from "numpy" */ + +/* Module declarations from "numpy" */ + +/* Module declarations from "acados_template.acados_ocp_solver_pyx" */ +static PyObject *__pyx_collections_abc_Sequence = 0; +static PyObject *generic = 0; +static PyObject *strided = 0; +static PyObject *indirect = 0; +static PyObject *contiguous = 0; +static PyObject *indirect_contiguous = 0; +static int __pyx_memoryview_thread_locks_used; +static PyThread_type_lock __pyx_memoryview_thread_locks[8]; +static CYTHON_INLINE PyObject *__Pyx_carray_to_py_int(int *, Py_ssize_t); /*proto*/ +static CYTHON_INLINE PyObject *__Pyx_carray_to_tuple_int(int *, Py_ssize_t); /*proto*/ +static int __pyx_array_allocate_buffer(struct __pyx_array_obj *); /*proto*/ +static struct __pyx_array_obj *__pyx_array_new(PyObject *, Py_ssize_t, char *, char *, char *); /*proto*/ +static PyObject *__pyx_memoryview_new(PyObject *, int, int, __Pyx_TypeInfo *); /*proto*/ +static CYTHON_INLINE int __pyx_memoryview_check(PyObject *); /*proto*/ +static PyObject *_unellipsify(PyObject *, int); /*proto*/ +static int assert_direct_dimensions(Py_ssize_t *, int); /*proto*/ +static struct __pyx_memoryview_obj *__pyx_memview_slice(struct __pyx_memoryview_obj *, PyObject *); /*proto*/ +static int __pyx_memoryview_slice_memviewslice(__Pyx_memviewslice *, Py_ssize_t, Py_ssize_t, Py_ssize_t, int, int, int *, Py_ssize_t, Py_ssize_t, Py_ssize_t, int, int, int, int); /*proto*/ +static char *__pyx_pybuffer_index(Py_buffer *, char *, Py_ssize_t, Py_ssize_t); /*proto*/ +static int __pyx_memslice_transpose(__Pyx_memviewslice *); /*proto*/ +static PyObject *__pyx_memoryview_fromslice(__Pyx_memviewslice, int, PyObject *(*)(char *), int (*)(char *, PyObject *), int); /*proto*/ +static __Pyx_memviewslice *__pyx_memoryview_get_slice_from_memoryview(struct __pyx_memoryview_obj *, __Pyx_memviewslice *); /*proto*/ +static void __pyx_memoryview_slice_copy(struct __pyx_memoryview_obj *, __Pyx_memviewslice *); /*proto*/ +static PyObject *__pyx_memoryview_copy_object(struct __pyx_memoryview_obj *); /*proto*/ +static PyObject *__pyx_memoryview_copy_object_from_slice(struct __pyx_memoryview_obj *, __Pyx_memviewslice *); /*proto*/ +static Py_ssize_t abs_py_ssize_t(Py_ssize_t); /*proto*/ +static char __pyx_get_best_slice_order(__Pyx_memviewslice *, int); /*proto*/ +static void _copy_strided_to_strided(char *, Py_ssize_t *, char *, Py_ssize_t *, Py_ssize_t *, Py_ssize_t *, int, size_t); /*proto*/ +static void copy_strided_to_strided(__Pyx_memviewslice *, __Pyx_memviewslice *, int, size_t); /*proto*/ +static Py_ssize_t __pyx_memoryview_slice_get_size(__Pyx_memviewslice *, int); /*proto*/ +static Py_ssize_t __pyx_fill_contig_strides_array(Py_ssize_t *, Py_ssize_t *, Py_ssize_t, int, char); /*proto*/ +static void *__pyx_memoryview_copy_data_to_temp(__Pyx_memviewslice *, __Pyx_memviewslice *, char, int); /*proto*/ +static int __pyx_memoryview_err_extents(int, Py_ssize_t, Py_ssize_t); /*proto*/ +static int __pyx_memoryview_err_dim(PyObject *, PyObject *, int); /*proto*/ +static int __pyx_memoryview_err(PyObject *, PyObject *); /*proto*/ +static int __pyx_memoryview_err_no_memory(void); /*proto*/ +static int __pyx_memoryview_copy_contents(__Pyx_memviewslice, __Pyx_memviewslice, int, int, int); /*proto*/ +static void __pyx_memoryview_broadcast_leading(__Pyx_memviewslice *, int, int); /*proto*/ +static void __pyx_memoryview_refcount_copying(__Pyx_memviewslice *, int, int, int); /*proto*/ +static void __pyx_memoryview_refcount_objects_in_slice_with_gil(char *, Py_ssize_t *, Py_ssize_t *, int, int); /*proto*/ +static void __pyx_memoryview_refcount_objects_in_slice(char *, Py_ssize_t *, Py_ssize_t *, int, int); /*proto*/ +static void __pyx_memoryview_slice_assign_scalar(__Pyx_memviewslice *, int, size_t, void *, int); /*proto*/ +static void __pyx_memoryview__slice_assign_scalar(char *, Py_ssize_t *, Py_ssize_t *, int, size_t, void *); /*proto*/ +static PyObject *__pyx_unpickle_Enum__set_state(struct __pyx_MemviewEnum_obj *, PyObject *); /*proto*/ +/* #### Code section: typeinfo ### */ +static __Pyx_TypeInfo __Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t = { "float64_t", NULL, sizeof(__pyx_t_5numpy_float64_t), { 0 }, 0, 'R', 0, 0 }; +static __Pyx_TypeInfo __Pyx_TypeInfo_nn___pyx_t_5numpy_int32_t = { "int32_t", NULL, sizeof(__pyx_t_5numpy_int32_t), { 0 }, 0, __PYX_IS_UNSIGNED(__pyx_t_5numpy_int32_t) ? 'U' : 'I', __PYX_IS_UNSIGNED(__pyx_t_5numpy_int32_t), 0 }; +static __Pyx_TypeInfo __Pyx_TypeInfo_double = { "double", NULL, sizeof(double), { 0 }, 0, 'R', 0, 0 }; +static __Pyx_TypeInfo __Pyx_TypeInfo_unsigned_char = { "unsigned char", NULL, sizeof(unsigned char), { 0 }, 0, __PYX_IS_UNSIGNED(unsigned char) ? 'U' : 'I', __PYX_IS_UNSIGNED(unsigned char), 0 }; +/* #### Code section: before_global_var ### */ +#define __Pyx_MODULE_NAME "acados_template.acados_ocp_solver_pyx" +extern int __pyx_module_is_main_acados_template__acados_ocp_solver_pyx; +int __pyx_module_is_main_acados_template__acados_ocp_solver_pyx = 0; + +/* Implementation of "acados_template.acados_ocp_solver_pyx" */ +/* #### Code section: global_var ### */ +static PyObject *__pyx_builtin_AssertionError; +static PyObject *__pyx_builtin_print; +static PyObject *__pyx_builtin_NotImplementedError; +static PyObject *__pyx_builtin_range; +static PyObject *__pyx_builtin_open; +static PyObject *__pyx_builtin_TypeError; +static PyObject *__pyx_builtin___import__; +static PyObject *__pyx_builtin_ValueError; +static PyObject *__pyx_builtin_MemoryError; +static PyObject *__pyx_builtin_enumerate; +static PyObject *__pyx_builtin_Ellipsis; +static PyObject *__pyx_builtin_id; +static PyObject *__pyx_builtin_IndexError; +static PyObject *__pyx_builtin_ImportError; +/* #### Code section: string_decls ### */ +static const char __pyx_k_[] = ": "; +static const char __pyx_k_0[] = "0"; +static const char __pyx_k_F[] = "F"; +static const char __pyx_k_N[] = "N"; +static const char __pyx_k_O[] = "O"; +static const char __pyx_k_c[] = "c"; +static const char __pyx_k_d[] = "d"; +static const char __pyx_k_f[] = "f"; +static const char __pyx_k_i[] = "i"; +static const char __pyx_k_k[] = "k"; +static const char __pyx_k_m[] = "m"; +static const char __pyx_k_n[] = "n"; +static const char __pyx_k_p[] = "p"; +static const char __pyx_k_r[] = "r"; +static const char __pyx_k_t[] = "t"; +static const char __pyx_k_u[] = "u"; +static const char __pyx_k_w[] = "w"; +static const char __pyx_k_x[] = "x"; +static const char __pyx_k_z[] = "z"; +static const char __pyx_k__2[] = "."; +static const char __pyx_k__3[] = "*"; +static const char __pyx_k__6[] = "'"; +static const char __pyx_k__7[] = ")"; +static const char __pyx_k_ex[] = "ex"; +static const char __pyx_k_gc[] = "gc"; +static const char __pyx_k_id[] = "id"; +static const char __pyx_k_lN[] = "lN"; +static const char __pyx_k_np[] = "np"; +static const char __pyx_k_nx[] = "nx"; +static const char __pyx_k_os[] = "os"; +static const char __pyx_k_pi[] = "pi"; +static const char __pyx_k_sl[] = "sl"; +static const char __pyx_k_su[] = "su"; +static const char __pyx_k_u0[] = "u0"; +static const char __pyx_k_SQP[] = "SQP"; +static const char __pyx_k__16[] = ""; +static const char __pyx_k__17[] = "_"; +static const char __pyx_k__31[] = ", "; +static const char __pyx_k__94[] = "?"; +static const char __pyx_k_abc[] = "abc"; +static const char __pyx_k_and[] = " and "; +static const char __pyx_k_get[] = "get"; +static const char __pyx_k_got[] = " (got "; +static const char __pyx_k_idx[] = "idx"; +static const char __pyx_k_int[] = "int"; +static const char __pyx_k_key[] = "key"; +static const char __pyx_k_lam[] = "lam"; +static const char __pyx_k_lbu[] = "lbu"; +static const char __pyx_k_lbx[] = "lbx"; +static const char __pyx_k_msg[] = "msg"; +static const char __pyx_k_new[] = "__new__"; +static const char __pyx_k_obj[] = "obj"; +static const char __pyx_k_out[] = "out"; +static const char __pyx_k_set[] = "set"; +static const char __pyx_k_sys[] = "sys"; +static const char __pyx_k_t_2[] = "t_"; +static const char __pyx_k_u_2[] = "u_"; +static const char __pyx_k_ubu[] = "ubu"; +static const char __pyx_k_ubx[] = "ubx"; +static const char __pyx_k_x_2[] = "x_"; +static const char __pyx_k_z_2[] = "z_"; +static const char __pyx_k_None[] = "None"; +static const char __pyx_k_TODO[] = "TODO!"; +static const char __pyx_k_base[] = "base"; +static const char __pyx_k_data[] = "data_"; +static const char __pyx_k_dict[] = "__dict__"; +static const char __pyx_k_dims[] = "dims"; +static const char __pyx_k_dump[] = "dump"; +static const char __pyx_k_exit[] = "__exit__"; +static const char __pyx_k_join[] = "join"; +static const char __pyx_k_json[] = "json"; +static const char __pyx_k_keys[] = "keys"; +static const char __pyx_k_load[] = "load"; +static const char __pyx_k_main[] = "__main__"; +static const char __pyx_k_mode[] = "mode"; +static const char __pyx_k_name[] = "name"; +static const char __pyx_k_ndim[] = "ndim"; +static const char __pyx_k_open[] = "open"; +static const char __pyx_k_pack[] = "pack"; +static const char __pyx_k_path[] = "path"; +static const char __pyx_k_pi_2[] = "pi_"; +static const char __pyx_k_self[] = "self"; +static const char __pyx_k_size[] = "size"; +static const char __pyx_k_sl_2[] = "sl_"; +static const char __pyx_k_spec[] = "__spec__"; +static const char __pyx_k_step[] = "step"; +static const char __pyx_k_stop[] = "stop"; +static const char __pyx_k_su_2[] = "su_"; +static const char __pyx_k_test[] = "__test__"; +static const char __pyx_k_yref[] = "yref"; +static const char __pyx_k_ASCII[] = "ASCII"; +static const char __pyx_k_alpha[] = "alpha"; +static const char __pyx_k_array[] = "array"; +static const char __pyx_k_class[] = "__class__"; +static const char __pyx_k_count[] = "count"; +static const char __pyx_k_dtype[] = "dtype"; +static const char __pyx_k_enter[] = "__enter__"; +static const char __pyx_k_error[] = "error"; +static const char __pyx_k_field[] = "field"; +static const char __pyx_k_flags[] = "flags"; +static const char __pyx_k_index[] = "index"; +static const char __pyx_k_int32[] = "int32"; +static const char __pyx_k_lam_2[] = "lam_"; +static const char __pyx_k_numpy[] = "numpy"; +static const char __pyx_k_order[] = "order"; +static const char __pyx_k_print[] = "print"; +static const char __pyx_k_range[] = "range"; +static const char __pyx_k_reset[] = "reset"; +static const char __pyx_k_shape[] = "shape"; +static const char __pyx_k_solve[] = "solve"; +static const char __pyx_k_split[] = "split"; +static const char __pyx_k_stage[] = "stage"; +static const char __pyx_k_start[] = "start"; +static const char __pyx_k_utf_8[] = "utf-8"; +static const char __pyx_k_value[] = "value_"; +static const char __pyx_k_y_ref[] = "y_ref"; +static const char __pyx_k_zeros[] = "zeros"; +static const char __pyx_k_data_2[] = "data"; +static const char __pyx_k_enable[] = "enable"; +static const char __pyx_k_encode[] = "encode"; +static const char __pyx_k_fields[] = "fields"; +static const char __pyx_k_format[] = "format"; +static const char __pyx_k_getcwd[] = "getcwd"; +static const char __pyx_k_import[] = "__import__"; +static const char __pyx_k_indent[] = "indent"; +static const char __pyx_k_isfile[] = "isfile"; +static const char __pyx_k_json_2[] = ".json"; +static const char __pyx_k_name_2[] = "__name__"; +static const char __pyx_k_pickle[] = "pickle"; +static const char __pyx_k_qp_mu0[] = "qp_mu0"; +static const char __pyx_k_reduce[] = "__reduce__"; +static const char __pyx_k_res_eq[] = "res_eq"; +static const char __pyx_k_stat_m[] = "stat_m"; +static const char __pyx_k_stat_n[] = "stat_n"; +static const char __pyx_k_status[] = "status"; +static const char __pyx_k_struct[] = "struct"; +static const char __pyx_k_tol_eq[] = "tol_eq"; +static const char __pyx_k_tolist[] = "tolist"; +static const char __pyx_k_unpack[] = "unpack"; +static const char __pyx_k_update[] = "update"; +static const char __pyx_k_utcnow[] = "utcnow"; +static const char __pyx_k_x0_bar[] = "x0_bar"; +static const char __pyx_k_SQP_RTI[] = "SQP_RTI"; +static const char __pyx_k_default[] = "default"; +static const char __pyx_k_disable[] = "disable"; +static const char __pyx_k_field_2[] = "field_"; +static const char __pyx_k_float64[] = "float64"; +static const char __pyx_k_fortran[] = "fortran"; +static const char __pyx_k_iterate[] = "iterate"; +static const char __pyx_k_memview[] = "memview"; +static const char __pyx_k_ndarray[] = "ndarray"; +static const char __pyx_k_out_mat[] = "out_mat"; +static const char __pyx_k_qp_iter[] = "qp_iter"; +static const char __pyx_k_time_qp[] = "time_qp"; +static const char __pyx_k_value_2[] = "value"; +static const char __pyx_k_z_guess[] = "z_guess"; +static const char __pyx_k_Ellipsis[] = "Ellipsis"; +static const char __pyx_k_Sequence[] = "Sequence"; +static const char __pyx_k_at_stage[] = "\" at stage "; +static const char __pyx_k_cost_set[] = "cost_set"; +static const char __pyx_k_data_len[] = "data_len"; +static const char __pyx_k_datetime[] = "datetime"; +static const char __pyx_k_filename[] = "filename"; +static const char __pyx_k_get_cost[] = "get_cost"; +static const char __pyx_k_getstate[] = "__getstate__"; +static const char __pyx_k_i_string[] = "i_string"; +static const char __pyx_k_itemsize[] = "itemsize"; +static const char __pyx_k_min_size[] = "min_size"; +static const char __pyx_k_n_update[] = "n_update"; +static const char __pyx_k_pyx_type[] = "__pyx_type"; +static const char __pyx_k_register[] = "register"; +static const char __pyx_k_res_comp[] = "res_comp"; +static const char __pyx_k_res_ineq[] = "res_ineq"; +static const char __pyx_k_res_stat[] = "res_stat"; +static const char __pyx_k_setstate[] = "__setstate__"; +static const char __pyx_k_solution[] = "solution"; +static const char __pyx_k_sqp_iter[] = "sqp_iter"; +static const char __pyx_k_strftime[] = "strftime"; +static const char __pyx_k_time_lin[] = "time_lin"; +static const char __pyx_k_time_reg[] = "time_reg"; +static const char __pyx_k_time_sim[] = "time_sim"; +static const char __pyx_k_time_tot[] = "time_tot"; +static const char __pyx_k_tol_comp[] = "tol_comp"; +static const char __pyx_k_tol_ineq[] = "tol_ineq"; +static const char __pyx_k_tol_stat[] = "tol_stat"; +static const char __pyx_k_you_have[] = " (you have "; +static const char __pyx_k_TypeError[] = "TypeError"; +static const char __pyx_k_alpha_min[] = "alpha_min"; +static const char __pyx_k_enumerate[] = "enumerate"; +static const char __pyx_k_for_field[] = " for field \""; +static const char __pyx_k_get_stats[] = "get_stats"; +static const char __pyx_k_int_value[] = "int_value"; +static const char __pyx_k_isenabled[] = "isenabled"; +static const char __pyx_k_overwrite[] = "overwrite"; +static const char __pyx_k_pyx_state[] = "__pyx_state"; +static const char __pyx_k_qp_tol_eq[] = "qp_tol_eq"; +static const char __pyx_k_recompute[] = "recompute"; +static const char __pyx_k_reduce_ex[] = "__reduce_ex__"; +static const char __pyx_k_residuals[] = "residuals"; +static const char __pyx_k_rti_phase[] = "rti_phase"; +static const char __pyx_k_sort_keys[] = "sort_keys"; +static const char __pyx_k_time_glob[] = "time_glob"; +static const char __pyx_k_IndexError[] = "IndexError"; +static const char __pyx_k_ValueError[] = "ValueError"; +static const char __pyx_k_full_stats[] = "full_stats"; +static const char __pyx_k_idx_values[] = "idx_values_"; +static const char __pyx_k_int_fields[] = "int_fields"; +static const char __pyx_k_mem_fields[] = "mem_fields"; +static const char __pyx_k_model_name[] = "model_name"; +static const char __pyx_k_out_fields[] = "out_fields"; +static const char __pyx_k_pyx_result[] = "__pyx_result"; +static const char __pyx_k_pyx_vtable[] = "__pyx_vtable__"; +static const char __pyx_k_qp_tau_min[] = "qp_tau_min"; +static const char __pyx_k_statistics[] = "statistics"; +static const char __pyx_k_xdot_guess[] = "xdot_guess"; +static const char __pyx_k_ImportError[] = "ImportError"; +static const char __pyx_k_MemoryError[] = "MemoryError"; +static const char __pyx_k_PickleError[] = "PickleError"; +static const char __pyx_k_collections[] = "collections"; +static const char __pyx_k_cost_fields[] = "cost_fields"; +static const char __pyx_k_options_set[] = "options_set"; +static const char __pyx_k_print_level[] = "print_level"; +static const char __pyx_k_qp_tol_comp[] = "qp_tol_comp"; +static const char __pyx_k_qp_tol_ineq[] = "qp_tol_ineq"; +static const char __pyx_k_qp_tol_stat[] = "qp_tol_stat"; +static const char __pyx_k_step_length[] = "step_length"; +static const char __pyx_k_time_sim_ad[] = "time_sim_ad"; +static const char __pyx_k_time_sim_la[] = "time_sim_la"; +static const char __pyx_k_value_shape[] = "value_shape"; +static const char __pyx_k_double_value[] = "double_value"; +static const char __pyx_k_get_stat_int[] = "__get_stat_int"; +static const char __pyx_k_initializing[] = "_initializing"; +static const char __pyx_k_is_coroutine[] = "_is_coroutine"; +static const char __pyx_k_load_iterate[] = "load_iterate"; +static const char __pyx_k_param_values[] = "param_values_"; +static const char __pyx_k_pyx_checksum[] = "__pyx_checksum"; +static const char __pyx_k_solve_for_x0[] = "solve_for_x0"; +static const char __pyx_k_string_value[] = "string_value"; +static const char __pyx_k_stringsource[] = ""; +static const char __pyx_k_version_info[] = "version_info"; +static const char __pyx_k_Got_sizes_idx[] = " Got sizes idx "; +static const char __pyx_k_Y_m_d_H_M_S_f[] = "%Y-%m-%d-%H:%M:%S.%f"; +static const char __pyx_k_class_getitem[] = "__class_getitem__"; +static const char __pyx_k_custom_update[] = "custom_update"; +static const char __pyx_k_double_fields[] = "double_fields"; +static const char __pyx_k_get_residuals[] = "get_residuals"; +static const char __pyx_k_globalization[] = "globalization"; +static const char __pyx_k_qp_warm_start[] = "qp_warm_start"; +static const char __pyx_k_reduce_cython[] = "__reduce_cython__"; +static const char __pyx_k_store_iterate[] = "store_iterate"; +static const char __pyx_k_string_fields[] = "string_fields"; +static const char __pyx_k_time_qp_xcond[] = "time_qp_xcond"; +static const char __pyx_k_AssertionError[] = "AssertionError"; +static const char __pyx_k_asfortranarray[] = "asfortranarray"; +static const char __pyx_k_full_step_dual[] = "full_step_dual"; +static const char __pyx_k_get_from_qp_in[] = "get_from_qp_in"; +static const char __pyx_k_new_time_steps[] = "new_time_steps"; +static const char __pyx_k_param_values_2[] = ", param_values "; +static const char __pyx_k_with_dimension[] = " with dimension "; +static const char __pyx_k_View_MemoryView[] = "View.MemoryView"; +static const char __pyx_k_allocate_buffer[] = "allocate_buffer"; +static const char __pyx_k_alpha_reduction[] = "alpha_reduction"; +static const char __pyx_k_collections_abc[] = "collections.abc"; +static const char __pyx_k_constraints_set[] = "constraints_set"; +static const char __pyx_k_dtype_is_object[] = "dtype_is_object"; +static const char __pyx_k_eval_param_sens[] = "eval_param_sens"; +static const char __pyx_k_get_stat_double[] = "__get_stat_double"; +static const char __pyx_k_get_stat_matrix[] = "__get_stat_matrix"; +static const char __pyx_k_nlp_solver_type[] = "nlp_solver_type"; +static const char __pyx_k_pyx_PickleError[] = "__pyx_PickleError"; +static const char __pyx_k_setstate_cython[] = "__setstate_cython__"; +static const char __pyx_k_print_statistics[] = "print_statistics"; +static const char __pyx_k_qp_solver_cond_N[] = "qp_solver_cond_N"; +static const char __pyx_k_ascontiguousarray[] = "ascontiguousarray"; +static const char __pyx_k_pyx_unpickle_Enum[] = "__pyx_unpickle_Enum"; +static const char __pyx_k_set_params_sparse[] = "set_params_sparse"; +static const char __pyx_k_asyncio_coroutines[] = "asyncio.coroutines"; +static const char __pyx_k_cline_in_traceback[] = "cline_in_traceback"; +static const char __pyx_k_constraints_fields[] = "constraints_fields"; +static const char __pyx_k_set_new_time_steps[] = "set_new_time_steps"; +static const char __pyx_k_strided_and_direct[] = ""; +static const char __pyx_k_NotImplementedError[] = "NotImplementedError"; +static const char __pyx_k_get_pointers_solver[] = "__get_pointers_solver"; +static const char __pyx_k_initialize_t_slacks[] = "initialize_t_slacks"; +static const char __pyx_k_reset_qp_solver_mem[] = "reset_qp_solver_mem"; +static const char __pyx_k_time_qp_solver_call[] = "time_qp_solver_call"; +static const char __pyx_k_warm_start_first_qp[] = "warm_start_first_qp"; +static const char __pyx_k_strided_and_indirect[] = ""; +static const char __pyx_k_AcadosOcpSolverCython[] = "AcadosOcpSolverCython"; +static const char __pyx_k_Invalid_shape_in_axis[] = "Invalid shape in axis "; +static const char __pyx_k_contiguous_and_direct[] = ""; +static const char __pyx_k_globalization_use_SOC[] = "globalization_use_SOC"; +static const char __pyx_k_Cannot_index_with_type[] = "Cannot index with type '"; +static const char __pyx_k_MemoryView_of_r_object[] = ""; +static const char __pyx_k_eps_sufficient_descent[] = "eps_sufficient_descent"; +static const char __pyx_k_MemoryView_of_r_at_0x_x[] = ""; +static const char __pyx_k_contiguous_and_indirect[] = ""; +static const char __pyx_k_update_qp_solver_cond_N[] = "update_qp_solver_cond_N"; +static const char __pyx_k_with_dimension_you_have[] = "with dimension {} (you have {})"; +static const char __pyx_k_AcadosOcpSolverCython_get[] = "AcadosOcpSolverCython.get"; +static const char __pyx_k_AcadosOcpSolverCython_set[] = "AcadosOcpSolverCython.set"; +static const char __pyx_k_Dimension_d_is_not_direct[] = "Dimension %d is not direct"; +static const char __pyx_k_stored_current_iterate_in[] = "stored current iterate in "; +static const char __pyx_k_Index_out_of_bounds_axis_d[] = "Index out of bounds (axis %d)"; +static const char __pyx_k_AcadosOcpSolverCython_reset[] = "AcadosOcpSolverCython.reset"; +static const char __pyx_k_AcadosOcpSolverCython_solve[] = "AcadosOcpSolverCython.solve"; +static const char __pyx_k_Step_may_not_be_zero_axis_d[] = "Step may not be zero (axis %d)"; +static const char __pyx_k_itemsize_0_for_cython_array[] = "itemsize <= 0 for cython.array"; +static const char __pyx_k_store_iterate_locals_lambda[] = "store_iterate.."; +static const char __pyx_k_time_solution_sensitivities[] = "time_solution_sensitivities"; +static const char __pyx_k_unable_to_allocate_array_data[] = "unable to allocate array data."; +static const char __pyx_k_AcadosOcpSolverCython_cost_set[] = "AcadosOcpSolverCython.cost_set"; +static const char __pyx_k_AcadosOcpSolverCython_get_cost[] = "AcadosOcpSolverCython.get_cost"; +static const char __pyx_k_param_values__must_be_np_array[] = "param_values_ must be np.array."; +static const char __pyx_k_strided_and_direct_or_indirect[] = ""; +static const char __pyx_k_AcadosOcpSolverCython__get_poin[] = "_AcadosOcpSolverCython__get_pointers_solver"; +static const char __pyx_k_AcadosOcpSolverCython__get_stat[] = "_AcadosOcpSolverCython__get_stat_int"; +static const char __pyx_k_AcadosOcpSolverCython_get_field[] = "AcadosOcpSolverCython.get(): field {} does not exist at final stage {}."; +static const char __pyx_k_AcadosOcpSolverCython_get_is_an[] = "AcadosOcpSolverCython.get(): {} is an invalid argument. \n Possible values are {}."; +static const char __pyx_k_AcadosOcpSolverCython_get_stage[] = "AcadosOcpSolverCython.get(): stage index must be in [0, N], got: {}."; +static const char __pyx_k_AcadosOcpSolverCython_get_stats[] = "AcadosOcpSolverCython.get_stats"; +static const char __pyx_k_AcadosOcpSolverCython_solve_for[] = "AcadosOcpSolverCython.solve_for_x0"; +static const char __pyx_k_AcadosOcpSolverCython_update_qp[] = "AcadosOcpSolverCython.update_qp_solver_cond_N"; +static const char __pyx_k_numpy_core_multiarray_failed_to[] = "numpy.core.multiarray failed to import"; +static const char __pyx_k_AcadosOcpSolverCython___get_poin[] = "AcadosOcpSolverCython.__get_pointers_solver"; +static const char __pyx_k_AcadosOcpSolverCython___get_stat[] = "AcadosOcpSolverCython.__get_stat_int"; +static const char __pyx_k_AcadosOcpSolverCython___reduce_c[] = "AcadosOcpSolverCython.__reduce_cython__"; +static const char __pyx_k_AcadosOcpSolverCython___setstate[] = "AcadosOcpSolverCython.__setstate_cython__"; +static const char __pyx_k_AcadosOcpSolverCython_constraint[] = "AcadosOcpSolverCython.constraints_set(): mismatching dimension"; +static const char __pyx_k_AcadosOcpSolverCython_cost_set_m[] = "AcadosOcpSolverCython.cost_set(): mismatching dimension"; +static const char __pyx_k_AcadosOcpSolverCython_custom_upd[] = "AcadosOcpSolverCython.custom_update"; +static const char __pyx_k_AcadosOcpSolverCython_does_not_s[] = "AcadosOcpSolverCython: does not support set_new_time_steps() since it is only a prototyping feature"; +static const char __pyx_k_AcadosOcpSolverCython_eval_param[] = "AcadosOcpSolverCython.eval_param_sens(): index must be Integer."; +static const char __pyx_k_AcadosOcpSolverCython_get_from_q[] = "AcadosOcpSolverCython.get_from_qp_in"; +static const char __pyx_k_AcadosOcpSolverCython_get_residu[] = "AcadosOcpSolverCython.get_residuals"; +static const char __pyx_k_AcadosOcpSolverCython_load_itera[] = "AcadosOcpSolverCython.load_iterate"; +static const char __pyx_k_AcadosOcpSolverCython_options_se[] = "AcadosOcpSolverCython.options_set() does not support field {}.\n Possible values are {}."; +static const char __pyx_k_AcadosOcpSolverCython_print_stat[] = "AcadosOcpSolverCython.print_statistics"; +static const char __pyx_k_AcadosOcpSolverCython_set_is_not[] = "AcadosOcpSolverCython.set(): {} is not a valid argument. \nPossible values are {}."; +static const char __pyx_k_AcadosOcpSolverCython_set_mismat[] = "AcadosOcpSolverCython.set(): mismatching dimension for field \"{}\" "; +static const char __pyx_k_AcadosOcpSolverCython_set_new_ti[] = "AcadosOcpSolverCython.set_new_time_steps"; +static const char __pyx_k_AcadosOcpSolverCython_set_params[] = "AcadosOcpSolverCython.set_params_sparse"; +static const char __pyx_k_AcadosOcpSolverCython_solve_argu[] = "AcadosOcpSolverCython.solve(): argument 'rti_phase' can take only values 0, 1, 2 for SQP-RTI-type solvers"; +static const char __pyx_k_AcadosOcpSolverCython_store_iter[] = "AcadosOcpSolverCython.store_iterate"; +static const char __pyx_k_All_dimensions_preceding_dimensi[] = "All dimensions preceding dimension %d must be indexed and not sliced"; +static const char __pyx_k_Buffer_view_does_not_expose_stri[] = "Buffer view does not expose strides"; +static const char __pyx_k_Can_only_create_a_buffer_that_is[] = "Can only create a buffer that is contiguous in memory."; +static const char __pyx_k_Cannot_assign_to_read_only_memor[] = "Cannot assign to read-only memoryview"; +static const char __pyx_k_Cannot_create_writable_memory_vi[] = "Cannot create writable memory view from read-only memoryview"; +static const char __pyx_k_Cannot_transpose_memoryview_with[] = "Cannot transpose memoryview with indirect dimensions"; +static const char __pyx_k_Empty_shape_tuple_for_cython_arr[] = "Empty shape tuple for cython.array"; +static const char __pyx_k_Incompatible_checksums_0x_x_vs_0[] = "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))"; +static const char __pyx_k_Indirect_dimensions_not_supporte[] = "Indirect dimensions not supported"; +static const char __pyx_k_Invalid_mode_expected_c_or_fortr[] = "Invalid mode, expected 'c' or 'fortran', got "; +static const char __pyx_k_Out_of_bounds_on_buffer_access_a[] = "Out of bounds on buffer access (axis "; +static const char __pyx_k_Unable_to_convert_item_to_object[] = "Unable to convert item to object"; +static const char __pyx_k_Warning_acados_ocp_solver_reache[] = "Warning: acados_ocp_solver reached maximum iterations."; +static const char __pyx_k_acados_acados_ocp_solver_returne[] = "acados acados_ocp_solver returned status "; +static const char __pyx_k_acados_template_acados_ocp_solve[] = "acados_template.acados_ocp_solver_pyx"; +static const char __pyx_k_alpha_values_are_not_available_f[] = "alpha values are not available for SQP_RTI"; +static const char __pyx_k_constraints_set_value_must_be_nu[] = "constraints_set: value must be numpy array, got "; +static const char __pyx_k_cost_set_value_must_be_numpy_arr[] = "cost_set: value must be numpy array, got "; +static const char __pyx_k_got_differing_extents_in_dimensi[] = "got differing extents in dimension "; +static const char __pyx_k_line_search_use_sufficient_desce[] = "line_search_use_sufficient_descent"; +static const char __pyx_k_load_iterate_failed_file_does_no[] = "load_iterate: failed, file does not exist: "; +static const char __pyx_k_no_default___reduce___due_to_non[] = "no default __reduce__ due to non-trivial __cinit__"; +static const char __pyx_k_numpy_core_umath_failed_to_impor[] = "numpy.core.umath failed to import"; +static const char __pyx_k_param_values__and_idx_values__mu[] = "param_values_ and idx_values_ must be of the same size."; +static const char __pyx_k_set_value_must_be_numpy_array_go[] = "set: value must be numpy array, got "; +static const char __pyx_k_solver_option_must_be_of_type_fl[] = "solver option {} must be of type float. You have {}."; +static const char __pyx_k_solver_option_must_be_of_type_in[] = "solver option {} must be of type int. You have {}."; +static const char __pyx_k_solver_option_must_be_of_type_st[] = "solver option {} must be of type str. You have {}."; +static const char __pyx_k_third_party_acados_acados_templa[] = "third_party/acados/acados_template/acados_ocp_solver_pyx.pyx"; +static const char __pyx_k_unable_to_allocate_shape_and_str[] = "unable to allocate shape and strides."; +static const char __pyx_k_AcadosOcpSolverCython__get_stat_2[] = "_AcadosOcpSolverCython__get_stat_double"; +static const char __pyx_k_AcadosOcpSolverCython__get_stat_3[] = "_AcadosOcpSolverCython__get_stat_matrix"; +static const char __pyx_k_AcadosOcpSolverCython___get_stat_2[] = "AcadosOcpSolverCython.__get_stat_double"; +static const char __pyx_k_AcadosOcpSolverCython___get_stat_3[] = "AcadosOcpSolverCython.__get_stat_matrix"; +static const char __pyx_k_AcadosOcpSolverCython_constraint_2[] = "AcadosOcpSolverCython.constraints_set"; +static const char __pyx_k_AcadosOcpSolverCython_does_not_s_2[] = "AcadosOcpSolverCython: does not support update_qp_solver_cond_N() since it is only a prototyping feature"; +static const char __pyx_k_AcadosOcpSolverCython_eval_param_2[] = "AcadosOcpSolverCython.eval_param_sens(): index must be in [0, nx-1], got: "; +static const char __pyx_k_AcadosOcpSolverCython_eval_param_3[] = "AcadosOcpSolverCython.eval_param_sens"; +static const char __pyx_k_AcadosOcpSolverCython_options_se_2[] = "AcadosOcpSolverCython.options_set"; +static const char __pyx_k_AcadosOcpSolverCython_solve_argu_2[] = "AcadosOcpSolverCython.solve(): argument 'rti_phase' can take only value 0 for SQP-type solvers"; +/* #### Code section: decls ### */ +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array___cinit__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_shape, Py_ssize_t __pyx_v_itemsize, PyObject *__pyx_v_format, PyObject *__pyx_v_mode, int __pyx_v_allocate_buffer); /* proto */ +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_2__getbuffer__(struct __pyx_array_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /* proto */ +static void __pyx_array___pyx_pf_15View_dot_MemoryView_5array_4__dealloc__(struct __pyx_array_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_5array_7memview___get__(struct __pyx_array_obj *__pyx_v_self); /* proto */ +static Py_ssize_t __pyx_array___pyx_pf_15View_dot_MemoryView_5array_6__len__(struct __pyx_array_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_8__getattr__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_attr); /* proto */ +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_10__getitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item); /* proto */ +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_12__setitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value); /* proto */ +static PyObject *__pyx_pf___pyx_array___reduce_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_array_2__setstate_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum___init__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v_name); /* proto */ +static PyObject *__pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum_2__repr__(struct __pyx_MemviewEnum_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_MemviewEnum___reduce_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_MemviewEnum_2__setstate_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview___cinit__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj, int __pyx_v_flags, int __pyx_v_dtype_is_object); /* proto */ +static void __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_2__dealloc__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_4__getitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index); /* proto */ +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_6__setitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value); /* proto */ +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_8__getbuffer__(struct __pyx_memoryview_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_1T___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4base___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_5shape___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_7strides___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_10suboffsets___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4ndim___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_8itemsize___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_6nbytes___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4size___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static Py_ssize_t __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_10__len__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_12__repr__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_14__str__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_16is_c_contig(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_18is_f_contig(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_20copy(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_22copy_fortran(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryview___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryview_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static void __pyx_memoryviewslice___pyx_pf_15View_dot_MemoryView_16_memoryviewslice___dealloc__(struct __pyx_memoryviewslice_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryviewslice___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryviewslice_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView___pyx_unpickle_Enum(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v___pyx_type, long __pyx_v___pyx_checksum, PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython___cinit__(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_model_name, PyObject *__pyx_v_nlp_solver_type, PyObject *__pyx_v_N); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_2__get_pointers_solver(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve_for_x0(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_x0_bar); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6solve(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8reset(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_reset_qp_solver_mem); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10custom_update(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_data_); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12set_new_time_steps(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_new_time_steps); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14update_qp_solver_cond_N(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_qp_solver_cond_N); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16eval_param_sens(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_stage, PyObject *__pyx_v_field); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18get(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20print_statistics(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ +static PyObject *__pyx_lambda_funcdef_lambda(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_x); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22store_iterate(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_filename, PyObject *__pyx_v_overwrite); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_24load_iterate(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_filename); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_26get_stats(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field_); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_28__get_stat_int(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_30__get_stat_double(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_32__get_stat_matrix(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field, PyObject *__pyx_v_n, PyObject *__pyx_v_m); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34get_cost(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36get_residuals(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_recompute); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40cost_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42constraints_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_44get_from_qp_in(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_46options_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_48set_params_sparse(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_idx_values_, PyObject *__pyx_v_param_values_); /* proto */ +static void __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_50__del__(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_52__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_54__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_tp_new_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_array(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_Enum(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_memoryview(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new__memoryviewslice(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static __Pyx_CachedCFunction __pyx_umethod_PyDict_Type_keys = {0, 0, 0, 0, 0}; +/* #### Code section: late_includes ### */ +/* #### Code section: module_state ### */ +typedef struct { + PyObject *__pyx_d; + PyObject *__pyx_b; + PyObject *__pyx_cython_runtime; + PyObject *__pyx_empty_tuple; + PyObject *__pyx_empty_bytes; + PyObject *__pyx_empty_unicode; + #ifdef __Pyx_CyFunction_USED + PyTypeObject *__pyx_CyFunctionType; + #endif + #ifdef __Pyx_FusedFunction_USED + PyTypeObject *__pyx_FusedFunctionType; + #endif + #ifdef __Pyx_Generator_USED + PyTypeObject *__pyx_GeneratorType; + #endif + #ifdef __Pyx_IterableCoroutine_USED + PyTypeObject *__pyx_IterableCoroutineType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineAwaitType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineType; + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + PyTypeObject *__pyx_ptype_7cpython_4type_type; + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + PyTypeObject *__pyx_ptype_5numpy_dtype; + PyTypeObject *__pyx_ptype_5numpy_flatiter; + PyTypeObject *__pyx_ptype_5numpy_broadcast; + PyTypeObject *__pyx_ptype_5numpy_ndarray; + PyTypeObject *__pyx_ptype_5numpy_generic; + PyTypeObject *__pyx_ptype_5numpy_number; + PyTypeObject *__pyx_ptype_5numpy_integer; + PyTypeObject *__pyx_ptype_5numpy_signedinteger; + PyTypeObject *__pyx_ptype_5numpy_unsignedinteger; + PyTypeObject *__pyx_ptype_5numpy_inexact; + PyTypeObject *__pyx_ptype_5numpy_floating; + PyTypeObject *__pyx_ptype_5numpy_complexfloating; + PyTypeObject *__pyx_ptype_5numpy_flexible; + PyTypeObject *__pyx_ptype_5numpy_character; + PyTypeObject *__pyx_ptype_5numpy_ufunc; + #if CYTHON_USE_MODULE_STATE + PyObject *__pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython; + PyObject *__pyx_type___pyx_array; + PyObject *__pyx_type___pyx_MemviewEnum; + PyObject *__pyx_type___pyx_memoryview; + PyObject *__pyx_type___pyx_memoryviewslice; + #endif + PyTypeObject *__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython; + PyTypeObject *__pyx_array_type; + PyTypeObject *__pyx_MemviewEnum_type; + PyTypeObject *__pyx_memoryview_type; + PyTypeObject *__pyx_memoryviewslice_type; + PyObject *__pyx_kp_u_; + PyObject *__pyx_kp_u_0; + PyObject *__pyx_n_s_ASCII; + PyObject *__pyx_n_s_AcadosOcpSolverCython; + PyObject *__pyx_n_s_AcadosOcpSolverCython___get_poin; + PyObject *__pyx_n_s_AcadosOcpSolverCython___get_stat; + PyObject *__pyx_n_s_AcadosOcpSolverCython___get_stat_2; + PyObject *__pyx_n_s_AcadosOcpSolverCython___get_stat_3; + PyObject *__pyx_n_s_AcadosOcpSolverCython___reduce_c; + PyObject *__pyx_n_s_AcadosOcpSolverCython___setstate; + PyObject *__pyx_n_s_AcadosOcpSolverCython__get_poin; + PyObject *__pyx_n_s_AcadosOcpSolverCython__get_stat; + PyObject *__pyx_n_s_AcadosOcpSolverCython__get_stat_2; + PyObject *__pyx_n_s_AcadosOcpSolverCython__get_stat_3; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_constraint; + PyObject *__pyx_n_s_AcadosOcpSolverCython_constraint_2; + PyObject *__pyx_n_s_AcadosOcpSolverCython_cost_set; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_cost_set_m; + PyObject *__pyx_n_s_AcadosOcpSolverCython_custom_upd; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_does_not_s; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_does_not_s_2; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_eval_param; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_eval_param_2; + PyObject *__pyx_n_s_AcadosOcpSolverCython_eval_param_3; + PyObject *__pyx_n_s_AcadosOcpSolverCython_get; + PyObject *__pyx_n_s_AcadosOcpSolverCython_get_cost; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_get_field; + PyObject *__pyx_n_s_AcadosOcpSolverCython_get_from_q; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_get_is_an; + PyObject *__pyx_n_s_AcadosOcpSolverCython_get_residu; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_get_stage; + PyObject *__pyx_n_s_AcadosOcpSolverCython_get_stats; + PyObject *__pyx_n_s_AcadosOcpSolverCython_load_itera; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_options_se; + PyObject *__pyx_n_s_AcadosOcpSolverCython_options_se_2; + PyObject *__pyx_n_s_AcadosOcpSolverCython_print_stat; + PyObject *__pyx_n_s_AcadosOcpSolverCython_reset; + PyObject *__pyx_n_s_AcadosOcpSolverCython_set; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_set_is_not; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_set_mismat; + PyObject *__pyx_n_s_AcadosOcpSolverCython_set_new_ti; + PyObject *__pyx_n_s_AcadosOcpSolverCython_set_params; + PyObject *__pyx_n_s_AcadosOcpSolverCython_solve; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_solve_argu; + PyObject *__pyx_kp_u_AcadosOcpSolverCython_solve_argu_2; + PyObject *__pyx_n_s_AcadosOcpSolverCython_solve_for; + PyObject *__pyx_n_s_AcadosOcpSolverCython_store_iter; + PyObject *__pyx_n_s_AcadosOcpSolverCython_update_qp; + PyObject *__pyx_kp_s_All_dimensions_preceding_dimensi; + PyObject *__pyx_n_s_AssertionError; + PyObject *__pyx_kp_s_Buffer_view_does_not_expose_stri; + PyObject *__pyx_kp_s_Can_only_create_a_buffer_that_is; + PyObject *__pyx_kp_s_Cannot_assign_to_read_only_memor; + PyObject *__pyx_kp_s_Cannot_create_writable_memory_vi; + PyObject *__pyx_kp_u_Cannot_index_with_type; + PyObject *__pyx_kp_s_Cannot_transpose_memoryview_with; + PyObject *__pyx_kp_s_Dimension_d_is_not_direct; + PyObject *__pyx_n_s_Ellipsis; + PyObject *__pyx_kp_s_Empty_shape_tuple_for_cython_arr; + PyObject *__pyx_n_u_F; + PyObject *__pyx_kp_u_Got_sizes_idx; + PyObject *__pyx_n_s_ImportError; + PyObject *__pyx_kp_s_Incompatible_checksums_0x_x_vs_0; + PyObject *__pyx_n_s_IndexError; + PyObject *__pyx_kp_s_Index_out_of_bounds_axis_d; + PyObject *__pyx_kp_s_Indirect_dimensions_not_supporte; + PyObject *__pyx_kp_u_Invalid_mode_expected_c_or_fortr; + PyObject *__pyx_kp_u_Invalid_shape_in_axis; + PyObject *__pyx_n_s_MemoryError; + PyObject *__pyx_kp_s_MemoryView_of_r_at_0x_x; + PyObject *__pyx_kp_s_MemoryView_of_r_object; + PyObject *__pyx_n_s_N; + PyObject *__pyx_kp_u_None; + PyObject *__pyx_n_s_NotImplementedError; + PyObject *__pyx_n_b_O; + PyObject *__pyx_kp_u_Out_of_bounds_on_buffer_access_a; + PyObject *__pyx_n_s_PickleError; + PyObject *__pyx_n_u_SQP; + PyObject *__pyx_n_u_SQP_RTI; + PyObject *__pyx_n_s_Sequence; + PyObject *__pyx_kp_s_Step_may_not_be_zero_axis_d; + PyObject *__pyx_kp_u_TODO; + PyObject *__pyx_n_s_TypeError; + PyObject *__pyx_kp_s_Unable_to_convert_item_to_object; + PyObject *__pyx_n_s_ValueError; + PyObject *__pyx_n_s_View_MemoryView; + PyObject *__pyx_kp_u_Warning_acados_ocp_solver_reache; + PyObject *__pyx_kp_u_Y_m_d_H_M_S_f; + PyObject *__pyx_kp_u__16; + PyObject *__pyx_n_u__17; + PyObject *__pyx_kp_u__2; + PyObject *__pyx_n_s__3; + PyObject *__pyx_kp_u__31; + PyObject *__pyx_kp_u__6; + PyObject *__pyx_kp_u__7; + PyObject *__pyx_n_s__94; + PyObject *__pyx_n_s_abc; + PyObject *__pyx_kp_u_acados_acados_ocp_solver_returne; + PyObject *__pyx_n_s_acados_template_acados_ocp_solve; + PyObject *__pyx_n_s_allocate_buffer; + PyObject *__pyx_n_u_alpha; + PyObject *__pyx_n_u_alpha_min; + PyObject *__pyx_n_u_alpha_reduction; + PyObject *__pyx_kp_u_alpha_values_are_not_available_f; + PyObject *__pyx_kp_u_and; + PyObject *__pyx_n_s_array; + PyObject *__pyx_n_s_ascontiguousarray; + PyObject *__pyx_n_s_asfortranarray; + PyObject *__pyx_n_s_asyncio_coroutines; + PyObject *__pyx_kp_u_at_stage; + PyObject *__pyx_n_s_base; + PyObject *__pyx_n_s_c; + PyObject *__pyx_n_u_c; + PyObject *__pyx_n_s_class; + PyObject *__pyx_n_s_class_getitem; + PyObject *__pyx_n_s_cline_in_traceback; + PyObject *__pyx_n_s_collections; + PyObject *__pyx_kp_s_collections_abc; + PyObject *__pyx_n_s_constraints_fields; + PyObject *__pyx_n_s_constraints_set; + PyObject *__pyx_kp_u_constraints_set_value_must_be_nu; + PyObject *__pyx_kp_s_contiguous_and_direct; + PyObject *__pyx_kp_s_contiguous_and_indirect; + PyObject *__pyx_n_s_cost_fields; + PyObject *__pyx_n_s_cost_set; + PyObject *__pyx_kp_u_cost_set_value_must_be_numpy_arr; + PyObject *__pyx_n_s_count; + PyObject *__pyx_n_s_custom_update; + PyObject *__pyx_n_u_d; + PyObject *__pyx_n_s_data; + PyObject *__pyx_n_s_data_2; + PyObject *__pyx_n_s_data_len; + PyObject *__pyx_n_s_datetime; + PyObject *__pyx_n_s_default; + PyObject *__pyx_n_s_dict; + PyObject *__pyx_n_s_dims; + PyObject *__pyx_kp_u_disable; + PyObject *__pyx_n_s_double_fields; + PyObject *__pyx_n_s_double_value; + PyObject *__pyx_n_s_dtype; + PyObject *__pyx_n_s_dtype_is_object; + PyObject *__pyx_n_s_dump; + PyObject *__pyx_kp_u_enable; + PyObject *__pyx_n_s_encode; + PyObject *__pyx_n_s_enter; + PyObject *__pyx_n_s_enumerate; + PyObject *__pyx_n_u_eps_sufficient_descent; + PyObject *__pyx_n_s_error; + PyObject *__pyx_n_s_eval_param_sens; + PyObject *__pyx_n_u_ex; + PyObject *__pyx_n_s_exit; + PyObject *__pyx_n_s_f; + PyObject *__pyx_n_s_field; + PyObject *__pyx_n_s_field_2; + PyObject *__pyx_n_s_fields; + PyObject *__pyx_n_s_filename; + PyObject *__pyx_n_s_flags; + PyObject *__pyx_n_s_float64; + PyObject *__pyx_kp_u_for_field; + PyObject *__pyx_n_s_format; + PyObject *__pyx_n_s_fortran; + PyObject *__pyx_n_u_fortran; + PyObject *__pyx_n_s_full_stats; + PyObject *__pyx_n_u_full_step_dual; + PyObject *__pyx_kp_u_gc; + PyObject *__pyx_n_s_get; + PyObject *__pyx_n_s_get_cost; + PyObject *__pyx_n_s_get_from_qp_in; + PyObject *__pyx_n_s_get_pointers_solver; + PyObject *__pyx_n_s_get_residuals; + PyObject *__pyx_n_s_get_stat_double; + PyObject *__pyx_n_s_get_stat_int; + PyObject *__pyx_n_s_get_stat_matrix; + PyObject *__pyx_n_s_get_stats; + PyObject *__pyx_n_s_getcwd; + PyObject *__pyx_n_s_getstate; + PyObject *__pyx_n_u_globalization; + PyObject *__pyx_n_u_globalization_use_SOC; + PyObject *__pyx_kp_u_got; + PyObject *__pyx_kp_u_got_differing_extents_in_dimensi; + PyObject *__pyx_n_s_i; + PyObject *__pyx_n_s_i_string; + PyObject *__pyx_n_s_id; + PyObject *__pyx_n_s_idx; + PyObject *__pyx_n_s_idx_values; + PyObject *__pyx_n_s_import; + PyObject *__pyx_n_s_indent; + PyObject *__pyx_n_s_index; + PyObject *__pyx_n_u_initialize_t_slacks; + PyObject *__pyx_n_s_initializing; + PyObject *__pyx_n_s_int; + PyObject *__pyx_n_s_int32; + PyObject *__pyx_n_s_int_fields; + PyObject *__pyx_n_s_int_value; + PyObject *__pyx_n_s_is_coroutine; + PyObject *__pyx_kp_u_isenabled; + PyObject *__pyx_n_s_isfile; + PyObject *__pyx_n_s_itemsize; + PyObject *__pyx_kp_s_itemsize_0_for_cython_array; + PyObject *__pyx_n_u_iterate; + PyObject *__pyx_n_s_join; + PyObject *__pyx_n_s_json; + PyObject *__pyx_kp_u_json_2; + PyObject *__pyx_n_s_k; + PyObject *__pyx_n_s_key; + PyObject *__pyx_n_s_keys; + PyObject *__pyx_n_s_lN; + PyObject *__pyx_n_u_lam; + PyObject *__pyx_n_u_lam_2; + PyObject *__pyx_n_u_lbu; + PyObject *__pyx_n_u_lbx; + PyObject *__pyx_n_u_line_search_use_sufficient_desce; + PyObject *__pyx_n_s_load; + PyObject *__pyx_n_s_load_iterate; + PyObject *__pyx_kp_u_load_iterate_failed_file_does_no; + PyObject *__pyx_n_s_m; + PyObject *__pyx_n_s_main; + PyObject *__pyx_n_s_mem_fields; + PyObject *__pyx_n_s_memview; + PyObject *__pyx_n_s_min_size; + PyObject *__pyx_n_s_mode; + PyObject *__pyx_n_s_model_name; + PyObject *__pyx_n_s_msg; + PyObject *__pyx_n_s_n; + PyObject *__pyx_n_s_n_update; + PyObject *__pyx_n_s_name; + PyObject *__pyx_n_s_name_2; + PyObject *__pyx_n_s_ndarray; + PyObject *__pyx_n_s_ndim; + PyObject *__pyx_n_s_new; + PyObject *__pyx_n_s_new_time_steps; + PyObject *__pyx_n_s_nlp_solver_type; + PyObject *__pyx_kp_s_no_default___reduce___due_to_non; + PyObject *__pyx_n_s_np; + PyObject *__pyx_n_s_numpy; + PyObject *__pyx_kp_u_numpy_core_multiarray_failed_to; + PyObject *__pyx_kp_u_numpy_core_umath_failed_to_impor; + PyObject *__pyx_n_s_nx; + PyObject *__pyx_n_s_obj; + PyObject *__pyx_n_s_open; + PyObject *__pyx_n_s_options_set; + PyObject *__pyx_n_s_order; + PyObject *__pyx_n_s_os; + PyObject *__pyx_n_s_out; + PyObject *__pyx_n_s_out_fields; + PyObject *__pyx_n_s_out_mat; + PyObject *__pyx_n_s_overwrite; + PyObject *__pyx_n_u_p; + PyObject *__pyx_n_s_pack; + PyObject *__pyx_n_s_param_values; + PyObject *__pyx_kp_u_param_values_2; + PyObject *__pyx_kp_u_param_values__and_idx_values__mu; + PyObject *__pyx_kp_u_param_values__must_be_np_array; + PyObject *__pyx_n_s_path; + PyObject *__pyx_n_u_pi; + PyObject *__pyx_n_u_pi_2; + PyObject *__pyx_n_s_pickle; + PyObject *__pyx_n_s_print; + PyObject *__pyx_n_u_print_level; + PyObject *__pyx_n_s_print_statistics; + PyObject *__pyx_n_s_pyx_PickleError; + PyObject *__pyx_n_s_pyx_checksum; + PyObject *__pyx_n_s_pyx_result; + PyObject *__pyx_n_s_pyx_state; + PyObject *__pyx_n_s_pyx_type; + PyObject *__pyx_n_s_pyx_unpickle_Enum; + PyObject *__pyx_n_s_pyx_vtable; + PyObject *__pyx_n_u_qp_iter; + PyObject *__pyx_n_u_qp_mu0; + PyObject *__pyx_n_s_qp_solver_cond_N; + PyObject *__pyx_n_u_qp_tau_min; + PyObject *__pyx_n_u_qp_tol_comp; + PyObject *__pyx_n_u_qp_tol_eq; + PyObject *__pyx_n_u_qp_tol_ineq; + PyObject *__pyx_n_u_qp_tol_stat; + PyObject *__pyx_n_u_qp_warm_start; + PyObject *__pyx_n_u_r; + PyObject *__pyx_n_s_range; + PyObject *__pyx_n_s_recompute; + PyObject *__pyx_n_s_reduce; + PyObject *__pyx_n_s_reduce_cython; + PyObject *__pyx_n_s_reduce_ex; + PyObject *__pyx_n_s_register; + PyObject *__pyx_n_b_res_comp; + PyObject *__pyx_n_b_res_eq; + PyObject *__pyx_n_b_res_ineq; + PyObject *__pyx_n_b_res_stat; + PyObject *__pyx_n_s_reset; + PyObject *__pyx_n_s_reset_qp_solver_mem; + PyObject *__pyx_n_u_residuals; + PyObject *__pyx_n_u_rti_phase; + PyObject *__pyx_n_s_self; + PyObject *__pyx_n_s_set; + PyObject *__pyx_n_s_set_new_time_steps; + PyObject *__pyx_n_s_set_params_sparse; + PyObject *__pyx_kp_u_set_value_must_be_numpy_array_go; + PyObject *__pyx_n_s_setstate; + PyObject *__pyx_n_s_setstate_cython; + PyObject *__pyx_n_s_shape; + PyObject *__pyx_n_s_size; + PyObject *__pyx_n_u_sl; + PyObject *__pyx_n_u_sl_2; + PyObject *__pyx_n_s_solution; + PyObject *__pyx_n_s_solve; + PyObject *__pyx_n_s_solve_for_x0; + PyObject *__pyx_kp_u_solver_option_must_be_of_type_fl; + PyObject *__pyx_kp_u_solver_option_must_be_of_type_in; + PyObject *__pyx_kp_u_solver_option_must_be_of_type_st; + PyObject *__pyx_n_s_sort_keys; + PyObject *__pyx_n_s_spec; + PyObject *__pyx_n_s_split; + PyObject *__pyx_n_s_sqp_iter; + PyObject *__pyx_n_u_sqp_iter; + PyObject *__pyx_n_s_stage; + PyObject *__pyx_n_s_start; + PyObject *__pyx_n_s_stat_m; + PyObject *__pyx_n_u_stat_m; + PyObject *__pyx_n_s_stat_n; + PyObject *__pyx_n_u_stat_n; + PyObject *__pyx_n_u_statistics; + PyObject *__pyx_n_s_status; + PyObject *__pyx_n_s_step; + PyObject *__pyx_n_u_step_length; + PyObject *__pyx_n_s_stop; + PyObject *__pyx_n_s_store_iterate; + PyObject *__pyx_n_s_store_iterate_locals_lambda; + PyObject *__pyx_kp_u_stored_current_iterate_in; + PyObject *__pyx_n_s_strftime; + PyObject *__pyx_kp_s_strided_and_direct; + PyObject *__pyx_kp_s_strided_and_direct_or_indirect; + PyObject *__pyx_kp_s_strided_and_indirect; + PyObject *__pyx_n_s_string_fields; + PyObject *__pyx_n_s_string_value; + PyObject *__pyx_kp_s_stringsource; + PyObject *__pyx_n_s_struct; + PyObject *__pyx_n_u_su; + PyObject *__pyx_n_u_su_2; + PyObject *__pyx_n_s_sys; + PyObject *__pyx_n_u_t; + PyObject *__pyx_n_u_t_2; + PyObject *__pyx_n_s_test; + PyObject *__pyx_kp_s_third_party_acados_acados_templa; + PyObject *__pyx_n_u_time_glob; + PyObject *__pyx_n_u_time_lin; + PyObject *__pyx_n_u_time_qp; + PyObject *__pyx_n_u_time_qp_solver_call; + PyObject *__pyx_n_u_time_qp_xcond; + PyObject *__pyx_n_u_time_reg; + PyObject *__pyx_n_u_time_sim; + PyObject *__pyx_n_u_time_sim_ad; + PyObject *__pyx_n_u_time_sim_la; + PyObject *__pyx_n_u_time_solution_sensitivities; + PyObject *__pyx_n_u_time_tot; + PyObject *__pyx_n_u_tol_comp; + PyObject *__pyx_n_u_tol_eq; + PyObject *__pyx_n_u_tol_ineq; + PyObject *__pyx_n_u_tol_stat; + PyObject *__pyx_n_s_tolist; + PyObject *__pyx_n_u_u; + PyObject *__pyx_n_s_u0; + PyObject *__pyx_n_u_u_2; + PyObject *__pyx_n_u_ubu; + PyObject *__pyx_n_u_ubx; + PyObject *__pyx_kp_s_unable_to_allocate_array_data; + PyObject *__pyx_kp_s_unable_to_allocate_shape_and_str; + PyObject *__pyx_n_s_unpack; + PyObject *__pyx_n_s_update; + PyObject *__pyx_n_s_update_qp_solver_cond_N; + PyObject *__pyx_n_s_utcnow; + PyObject *__pyx_kp_u_utf_8; + PyObject *__pyx_n_s_value; + PyObject *__pyx_n_s_value_2; + PyObject *__pyx_n_s_value_shape; + PyObject *__pyx_n_s_version_info; + PyObject *__pyx_n_u_w; + PyObject *__pyx_n_u_warm_start_first_qp; + PyObject *__pyx_kp_u_with_dimension; + PyObject *__pyx_kp_u_with_dimension_you_have; + PyObject *__pyx_n_b_x; + PyObject *__pyx_n_s_x; + PyObject *__pyx_n_u_x; + PyObject *__pyx_n_s_x0_bar; + PyObject *__pyx_n_u_x_2; + PyObject *__pyx_n_u_xdot_guess; + PyObject *__pyx_n_u_y_ref; + PyObject *__pyx_kp_u_you_have; + PyObject *__pyx_n_u_yref; + PyObject *__pyx_n_u_z; + PyObject *__pyx_n_u_z_2; + PyObject *__pyx_n_b_z_guess; + PyObject *__pyx_n_u_z_guess; + PyObject *__pyx_n_s_zeros; + PyObject *__pyx_int_0; + PyObject *__pyx_int_1; + PyObject *__pyx_int_2; + PyObject *__pyx_int_3; + PyObject *__pyx_int_4; + PyObject *__pyx_int_6; + PyObject *__pyx_int_7; + PyObject *__pyx_int_112105877; + PyObject *__pyx_int_136983863; + PyObject *__pyx_int_184977713; + PyObject *__pyx_int_neg_1; + PyObject *__pyx_int_neg_5; + PyObject *__pyx_slice__5; + PyObject *__pyx_tuple__4; + PyObject *__pyx_tuple__8; + PyObject *__pyx_tuple__9; + PyObject *__pyx_slice__18; + PyObject *__pyx_tuple__10; + PyObject *__pyx_tuple__11; + PyObject *__pyx_tuple__12; + PyObject *__pyx_tuple__13; + PyObject *__pyx_tuple__14; + PyObject *__pyx_tuple__15; + PyObject *__pyx_tuple__19; + PyObject *__pyx_tuple__20; + PyObject *__pyx_tuple__21; + PyObject *__pyx_tuple__22; + PyObject *__pyx_tuple__23; + PyObject *__pyx_tuple__24; + PyObject *__pyx_tuple__25; + PyObject *__pyx_tuple__26; + PyObject *__pyx_tuple__27; + PyObject *__pyx_tuple__28; + PyObject *__pyx_tuple__29; + PyObject *__pyx_tuple__30; + PyObject *__pyx_tuple__32; + PyObject *__pyx_tuple__33; + PyObject *__pyx_tuple__34; + PyObject *__pyx_tuple__35; + PyObject *__pyx_tuple__36; + PyObject *__pyx_tuple__37; + PyObject *__pyx_tuple__38; + PyObject *__pyx_tuple__39; + PyObject *__pyx_tuple__40; + PyObject *__pyx_tuple__41; + PyObject *__pyx_tuple__42; + PyObject *__pyx_tuple__44; + PyObject *__pyx_tuple__46; + PyObject *__pyx_tuple__49; + PyObject *__pyx_tuple__51; + PyObject *__pyx_tuple__53; + PyObject *__pyx_tuple__55; + PyObject *__pyx_tuple__57; + PyObject *__pyx_tuple__59; + PyObject *__pyx_tuple__60; + PyObject *__pyx_tuple__63; + PyObject *__pyx_tuple__65; + PyObject *__pyx_tuple__66; + PyObject *__pyx_tuple__68; + PyObject *__pyx_tuple__70; + PyObject *__pyx_tuple__73; + PyObject *__pyx_tuple__75; + PyObject *__pyx_tuple__77; + PyObject *__pyx_tuple__79; + PyObject *__pyx_tuple__80; + PyObject *__pyx_tuple__82; + PyObject *__pyx_tuple__85; + PyObject *__pyx_tuple__87; + PyObject *__pyx_tuple__89; + PyObject *__pyx_tuple__92; + PyObject *__pyx_codeobj__43; + PyObject *__pyx_codeobj__45; + PyObject *__pyx_codeobj__47; + PyObject *__pyx_codeobj__48; + PyObject *__pyx_codeobj__50; + PyObject *__pyx_codeobj__52; + PyObject *__pyx_codeobj__54; + PyObject *__pyx_codeobj__56; + PyObject *__pyx_codeobj__58; + PyObject *__pyx_codeobj__61; + PyObject *__pyx_codeobj__62; + PyObject *__pyx_codeobj__64; + PyObject *__pyx_codeobj__67; + PyObject *__pyx_codeobj__69; + PyObject *__pyx_codeobj__71; + PyObject *__pyx_codeobj__72; + PyObject *__pyx_codeobj__74; + PyObject *__pyx_codeobj__76; + PyObject *__pyx_codeobj__78; + PyObject *__pyx_codeobj__81; + PyObject *__pyx_codeobj__83; + PyObject *__pyx_codeobj__84; + PyObject *__pyx_codeobj__86; + PyObject *__pyx_codeobj__88; + PyObject *__pyx_codeobj__90; + PyObject *__pyx_codeobj__91; + PyObject *__pyx_codeobj__93; +} __pyx_mstate; + +#if CYTHON_USE_MODULE_STATE +#ifdef __cplusplus +namespace { + extern struct PyModuleDef __pyx_moduledef; +} /* anonymous namespace */ +#else +static struct PyModuleDef __pyx_moduledef; +#endif + +#define __pyx_mstate(o) ((__pyx_mstate *)__Pyx_PyModule_GetState(o)) + +#define __pyx_mstate_global (__pyx_mstate(PyState_FindModule(&__pyx_moduledef))) + +#define __pyx_m (PyState_FindModule(&__pyx_moduledef)) +#else +static __pyx_mstate __pyx_mstate_global_static = +#ifdef __cplusplus + {}; +#else + {0}; +#endif +static __pyx_mstate *__pyx_mstate_global = &__pyx_mstate_global_static; +#endif +/* #### Code section: module_state_clear ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_clear(PyObject *m) { + __pyx_mstate *clear_module_state = __pyx_mstate(m); + if (!clear_module_state) return 0; + Py_CLEAR(clear_module_state->__pyx_d); + Py_CLEAR(clear_module_state->__pyx_b); + Py_CLEAR(clear_module_state->__pyx_cython_runtime); + Py_CLEAR(clear_module_state->__pyx_empty_tuple); + Py_CLEAR(clear_module_state->__pyx_empty_bytes); + Py_CLEAR(clear_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_CLEAR(clear_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_CLEAR(clear_module_state->__pyx_FusedFunctionType); + #endif + Py_CLEAR(clear_module_state->__pyx_ptype_7cpython_4type_type); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_dtype); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_flatiter); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_broadcast); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_ndarray); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_generic); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_number); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_integer); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_signedinteger); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_unsignedinteger); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_inexact); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_floating); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_complexfloating); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_flexible); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_character); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_ufunc); + Py_CLEAR(clear_module_state->__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + Py_CLEAR(clear_module_state->__pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + Py_CLEAR(clear_module_state->__pyx_array_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_array); + Py_CLEAR(clear_module_state->__pyx_MemviewEnum_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_MemviewEnum); + Py_CLEAR(clear_module_state->__pyx_memoryview_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_memoryview); + Py_CLEAR(clear_module_state->__pyx_memoryviewslice_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_memoryviewslice); + Py_CLEAR(clear_module_state->__pyx_kp_u_); + Py_CLEAR(clear_module_state->__pyx_kp_u_0); + Py_CLEAR(clear_module_state->__pyx_n_s_ASCII); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython___get_poin); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython___get_stat); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython___get_stat_2); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython___get_stat_3); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython___reduce_c); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython___setstate); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython__get_poin); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython__get_stat); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython__get_stat_2); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython__get_stat_3); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_constraint); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_constraint_2); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_cost_set); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_cost_set_m); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_custom_upd); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_does_not_s); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_does_not_s_2); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_eval_param); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_eval_param_2); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_eval_param_3); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_get); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_get_cost); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_get_field); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_get_from_q); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_get_is_an); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_get_residu); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_get_stage); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_get_stats); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_load_itera); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_options_se); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_options_se_2); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_print_stat); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_reset); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_set); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_set_is_not); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_set_mismat); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_set_new_ti); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_set_params); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_solve); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_solve_argu); + Py_CLEAR(clear_module_state->__pyx_kp_u_AcadosOcpSolverCython_solve_argu_2); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_solve_for); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_store_iter); + Py_CLEAR(clear_module_state->__pyx_n_s_AcadosOcpSolverCython_update_qp); + Py_CLEAR(clear_module_state->__pyx_kp_s_All_dimensions_preceding_dimensi); + Py_CLEAR(clear_module_state->__pyx_n_s_AssertionError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Buffer_view_does_not_expose_stri); + Py_CLEAR(clear_module_state->__pyx_kp_s_Can_only_create_a_buffer_that_is); + Py_CLEAR(clear_module_state->__pyx_kp_s_Cannot_assign_to_read_only_memor); + Py_CLEAR(clear_module_state->__pyx_kp_s_Cannot_create_writable_memory_vi); + Py_CLEAR(clear_module_state->__pyx_kp_u_Cannot_index_with_type); + Py_CLEAR(clear_module_state->__pyx_kp_s_Cannot_transpose_memoryview_with); + Py_CLEAR(clear_module_state->__pyx_kp_s_Dimension_d_is_not_direct); + Py_CLEAR(clear_module_state->__pyx_n_s_Ellipsis); + Py_CLEAR(clear_module_state->__pyx_kp_s_Empty_shape_tuple_for_cython_arr); + Py_CLEAR(clear_module_state->__pyx_n_u_F); + Py_CLEAR(clear_module_state->__pyx_kp_u_Got_sizes_idx); + Py_CLEAR(clear_module_state->__pyx_n_s_ImportError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0); + Py_CLEAR(clear_module_state->__pyx_n_s_IndexError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Index_out_of_bounds_axis_d); + Py_CLEAR(clear_module_state->__pyx_kp_s_Indirect_dimensions_not_supporte); + Py_CLEAR(clear_module_state->__pyx_kp_u_Invalid_mode_expected_c_or_fortr); + Py_CLEAR(clear_module_state->__pyx_kp_u_Invalid_shape_in_axis); + Py_CLEAR(clear_module_state->__pyx_n_s_MemoryError); + Py_CLEAR(clear_module_state->__pyx_kp_s_MemoryView_of_r_at_0x_x); + Py_CLEAR(clear_module_state->__pyx_kp_s_MemoryView_of_r_object); + Py_CLEAR(clear_module_state->__pyx_n_s_N); + Py_CLEAR(clear_module_state->__pyx_kp_u_None); + Py_CLEAR(clear_module_state->__pyx_n_s_NotImplementedError); + Py_CLEAR(clear_module_state->__pyx_n_b_O); + Py_CLEAR(clear_module_state->__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + Py_CLEAR(clear_module_state->__pyx_n_s_PickleError); + Py_CLEAR(clear_module_state->__pyx_n_u_SQP); + Py_CLEAR(clear_module_state->__pyx_n_u_SQP_RTI); + Py_CLEAR(clear_module_state->__pyx_n_s_Sequence); + Py_CLEAR(clear_module_state->__pyx_kp_s_Step_may_not_be_zero_axis_d); + Py_CLEAR(clear_module_state->__pyx_kp_u_TODO); + Py_CLEAR(clear_module_state->__pyx_n_s_TypeError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Unable_to_convert_item_to_object); + Py_CLEAR(clear_module_state->__pyx_n_s_ValueError); + Py_CLEAR(clear_module_state->__pyx_n_s_View_MemoryView); + Py_CLEAR(clear_module_state->__pyx_kp_u_Warning_acados_ocp_solver_reache); + Py_CLEAR(clear_module_state->__pyx_kp_u_Y_m_d_H_M_S_f); + Py_CLEAR(clear_module_state->__pyx_kp_u__16); + Py_CLEAR(clear_module_state->__pyx_n_u__17); + Py_CLEAR(clear_module_state->__pyx_kp_u__2); + Py_CLEAR(clear_module_state->__pyx_n_s__3); + Py_CLEAR(clear_module_state->__pyx_kp_u__31); + Py_CLEAR(clear_module_state->__pyx_kp_u__6); + Py_CLEAR(clear_module_state->__pyx_kp_u__7); + Py_CLEAR(clear_module_state->__pyx_n_s__94); + Py_CLEAR(clear_module_state->__pyx_n_s_abc); + Py_CLEAR(clear_module_state->__pyx_kp_u_acados_acados_ocp_solver_returne); + Py_CLEAR(clear_module_state->__pyx_n_s_acados_template_acados_ocp_solve); + Py_CLEAR(clear_module_state->__pyx_n_s_allocate_buffer); + Py_CLEAR(clear_module_state->__pyx_n_u_alpha); + Py_CLEAR(clear_module_state->__pyx_n_u_alpha_min); + Py_CLEAR(clear_module_state->__pyx_n_u_alpha_reduction); + Py_CLEAR(clear_module_state->__pyx_kp_u_alpha_values_are_not_available_f); + Py_CLEAR(clear_module_state->__pyx_kp_u_and); + Py_CLEAR(clear_module_state->__pyx_n_s_array); + Py_CLEAR(clear_module_state->__pyx_n_s_ascontiguousarray); + Py_CLEAR(clear_module_state->__pyx_n_s_asfortranarray); + Py_CLEAR(clear_module_state->__pyx_n_s_asyncio_coroutines); + Py_CLEAR(clear_module_state->__pyx_kp_u_at_stage); + Py_CLEAR(clear_module_state->__pyx_n_s_base); + Py_CLEAR(clear_module_state->__pyx_n_s_c); + Py_CLEAR(clear_module_state->__pyx_n_u_c); + Py_CLEAR(clear_module_state->__pyx_n_s_class); + Py_CLEAR(clear_module_state->__pyx_n_s_class_getitem); + Py_CLEAR(clear_module_state->__pyx_n_s_cline_in_traceback); + Py_CLEAR(clear_module_state->__pyx_n_s_collections); + Py_CLEAR(clear_module_state->__pyx_kp_s_collections_abc); + Py_CLEAR(clear_module_state->__pyx_n_s_constraints_fields); + Py_CLEAR(clear_module_state->__pyx_n_s_constraints_set); + Py_CLEAR(clear_module_state->__pyx_kp_u_constraints_set_value_must_be_nu); + Py_CLEAR(clear_module_state->__pyx_kp_s_contiguous_and_direct); + Py_CLEAR(clear_module_state->__pyx_kp_s_contiguous_and_indirect); + Py_CLEAR(clear_module_state->__pyx_n_s_cost_fields); + Py_CLEAR(clear_module_state->__pyx_n_s_cost_set); + Py_CLEAR(clear_module_state->__pyx_kp_u_cost_set_value_must_be_numpy_arr); + Py_CLEAR(clear_module_state->__pyx_n_s_count); + Py_CLEAR(clear_module_state->__pyx_n_s_custom_update); + Py_CLEAR(clear_module_state->__pyx_n_u_d); + Py_CLEAR(clear_module_state->__pyx_n_s_data); + Py_CLEAR(clear_module_state->__pyx_n_s_data_2); + Py_CLEAR(clear_module_state->__pyx_n_s_data_len); + Py_CLEAR(clear_module_state->__pyx_n_s_datetime); + Py_CLEAR(clear_module_state->__pyx_n_s_default); + Py_CLEAR(clear_module_state->__pyx_n_s_dict); + Py_CLEAR(clear_module_state->__pyx_n_s_dims); + Py_CLEAR(clear_module_state->__pyx_kp_u_disable); + Py_CLEAR(clear_module_state->__pyx_n_s_double_fields); + Py_CLEAR(clear_module_state->__pyx_n_s_double_value); + Py_CLEAR(clear_module_state->__pyx_n_s_dtype); + Py_CLEAR(clear_module_state->__pyx_n_s_dtype_is_object); + Py_CLEAR(clear_module_state->__pyx_n_s_dump); + Py_CLEAR(clear_module_state->__pyx_kp_u_enable); + Py_CLEAR(clear_module_state->__pyx_n_s_encode); + Py_CLEAR(clear_module_state->__pyx_n_s_enter); + Py_CLEAR(clear_module_state->__pyx_n_s_enumerate); + Py_CLEAR(clear_module_state->__pyx_n_u_eps_sufficient_descent); + Py_CLEAR(clear_module_state->__pyx_n_s_error); + Py_CLEAR(clear_module_state->__pyx_n_s_eval_param_sens); + Py_CLEAR(clear_module_state->__pyx_n_u_ex); + Py_CLEAR(clear_module_state->__pyx_n_s_exit); + Py_CLEAR(clear_module_state->__pyx_n_s_f); + Py_CLEAR(clear_module_state->__pyx_n_s_field); + Py_CLEAR(clear_module_state->__pyx_n_s_field_2); + Py_CLEAR(clear_module_state->__pyx_n_s_fields); + Py_CLEAR(clear_module_state->__pyx_n_s_filename); + Py_CLEAR(clear_module_state->__pyx_n_s_flags); + Py_CLEAR(clear_module_state->__pyx_n_s_float64); + Py_CLEAR(clear_module_state->__pyx_kp_u_for_field); + Py_CLEAR(clear_module_state->__pyx_n_s_format); + Py_CLEAR(clear_module_state->__pyx_n_s_fortran); + Py_CLEAR(clear_module_state->__pyx_n_u_fortran); + Py_CLEAR(clear_module_state->__pyx_n_s_full_stats); + Py_CLEAR(clear_module_state->__pyx_n_u_full_step_dual); + Py_CLEAR(clear_module_state->__pyx_kp_u_gc); + Py_CLEAR(clear_module_state->__pyx_n_s_get); + Py_CLEAR(clear_module_state->__pyx_n_s_get_cost); + Py_CLEAR(clear_module_state->__pyx_n_s_get_from_qp_in); + Py_CLEAR(clear_module_state->__pyx_n_s_get_pointers_solver); + Py_CLEAR(clear_module_state->__pyx_n_s_get_residuals); + Py_CLEAR(clear_module_state->__pyx_n_s_get_stat_double); + Py_CLEAR(clear_module_state->__pyx_n_s_get_stat_int); + Py_CLEAR(clear_module_state->__pyx_n_s_get_stat_matrix); + Py_CLEAR(clear_module_state->__pyx_n_s_get_stats); + Py_CLEAR(clear_module_state->__pyx_n_s_getcwd); + Py_CLEAR(clear_module_state->__pyx_n_s_getstate); + Py_CLEAR(clear_module_state->__pyx_n_u_globalization); + Py_CLEAR(clear_module_state->__pyx_n_u_globalization_use_SOC); + Py_CLEAR(clear_module_state->__pyx_kp_u_got); + Py_CLEAR(clear_module_state->__pyx_kp_u_got_differing_extents_in_dimensi); + Py_CLEAR(clear_module_state->__pyx_n_s_i); + Py_CLEAR(clear_module_state->__pyx_n_s_i_string); + Py_CLEAR(clear_module_state->__pyx_n_s_id); + Py_CLEAR(clear_module_state->__pyx_n_s_idx); + Py_CLEAR(clear_module_state->__pyx_n_s_idx_values); + Py_CLEAR(clear_module_state->__pyx_n_s_import); + Py_CLEAR(clear_module_state->__pyx_n_s_indent); + Py_CLEAR(clear_module_state->__pyx_n_s_index); + Py_CLEAR(clear_module_state->__pyx_n_u_initialize_t_slacks); + Py_CLEAR(clear_module_state->__pyx_n_s_initializing); + Py_CLEAR(clear_module_state->__pyx_n_s_int); + Py_CLEAR(clear_module_state->__pyx_n_s_int32); + Py_CLEAR(clear_module_state->__pyx_n_s_int_fields); + Py_CLEAR(clear_module_state->__pyx_n_s_int_value); + Py_CLEAR(clear_module_state->__pyx_n_s_is_coroutine); + Py_CLEAR(clear_module_state->__pyx_kp_u_isenabled); + Py_CLEAR(clear_module_state->__pyx_n_s_isfile); + Py_CLEAR(clear_module_state->__pyx_n_s_itemsize); + Py_CLEAR(clear_module_state->__pyx_kp_s_itemsize_0_for_cython_array); + Py_CLEAR(clear_module_state->__pyx_n_u_iterate); + Py_CLEAR(clear_module_state->__pyx_n_s_join); + Py_CLEAR(clear_module_state->__pyx_n_s_json); + Py_CLEAR(clear_module_state->__pyx_kp_u_json_2); + Py_CLEAR(clear_module_state->__pyx_n_s_k); + Py_CLEAR(clear_module_state->__pyx_n_s_key); + Py_CLEAR(clear_module_state->__pyx_n_s_keys); + Py_CLEAR(clear_module_state->__pyx_n_s_lN); + Py_CLEAR(clear_module_state->__pyx_n_u_lam); + Py_CLEAR(clear_module_state->__pyx_n_u_lam_2); + Py_CLEAR(clear_module_state->__pyx_n_u_lbu); + Py_CLEAR(clear_module_state->__pyx_n_u_lbx); + Py_CLEAR(clear_module_state->__pyx_n_u_line_search_use_sufficient_desce); + Py_CLEAR(clear_module_state->__pyx_n_s_load); + Py_CLEAR(clear_module_state->__pyx_n_s_load_iterate); + Py_CLEAR(clear_module_state->__pyx_kp_u_load_iterate_failed_file_does_no); + Py_CLEAR(clear_module_state->__pyx_n_s_m); + Py_CLEAR(clear_module_state->__pyx_n_s_main); + Py_CLEAR(clear_module_state->__pyx_n_s_mem_fields); + Py_CLEAR(clear_module_state->__pyx_n_s_memview); + Py_CLEAR(clear_module_state->__pyx_n_s_min_size); + Py_CLEAR(clear_module_state->__pyx_n_s_mode); + Py_CLEAR(clear_module_state->__pyx_n_s_model_name); + Py_CLEAR(clear_module_state->__pyx_n_s_msg); + Py_CLEAR(clear_module_state->__pyx_n_s_n); + Py_CLEAR(clear_module_state->__pyx_n_s_n_update); + Py_CLEAR(clear_module_state->__pyx_n_s_name); + Py_CLEAR(clear_module_state->__pyx_n_s_name_2); + Py_CLEAR(clear_module_state->__pyx_n_s_ndarray); + Py_CLEAR(clear_module_state->__pyx_n_s_ndim); + Py_CLEAR(clear_module_state->__pyx_n_s_new); + Py_CLEAR(clear_module_state->__pyx_n_s_new_time_steps); + Py_CLEAR(clear_module_state->__pyx_n_s_nlp_solver_type); + Py_CLEAR(clear_module_state->__pyx_kp_s_no_default___reduce___due_to_non); + Py_CLEAR(clear_module_state->__pyx_n_s_np); + Py_CLEAR(clear_module_state->__pyx_n_s_numpy); + Py_CLEAR(clear_module_state->__pyx_kp_u_numpy_core_multiarray_failed_to); + Py_CLEAR(clear_module_state->__pyx_kp_u_numpy_core_umath_failed_to_impor); + Py_CLEAR(clear_module_state->__pyx_n_s_nx); + Py_CLEAR(clear_module_state->__pyx_n_s_obj); + Py_CLEAR(clear_module_state->__pyx_n_s_open); + Py_CLEAR(clear_module_state->__pyx_n_s_options_set); + Py_CLEAR(clear_module_state->__pyx_n_s_order); + Py_CLEAR(clear_module_state->__pyx_n_s_os); + Py_CLEAR(clear_module_state->__pyx_n_s_out); + Py_CLEAR(clear_module_state->__pyx_n_s_out_fields); + Py_CLEAR(clear_module_state->__pyx_n_s_out_mat); + Py_CLEAR(clear_module_state->__pyx_n_s_overwrite); + Py_CLEAR(clear_module_state->__pyx_n_u_p); + Py_CLEAR(clear_module_state->__pyx_n_s_pack); + Py_CLEAR(clear_module_state->__pyx_n_s_param_values); + Py_CLEAR(clear_module_state->__pyx_kp_u_param_values_2); + Py_CLEAR(clear_module_state->__pyx_kp_u_param_values__and_idx_values__mu); + Py_CLEAR(clear_module_state->__pyx_kp_u_param_values__must_be_np_array); + Py_CLEAR(clear_module_state->__pyx_n_s_path); + Py_CLEAR(clear_module_state->__pyx_n_u_pi); + Py_CLEAR(clear_module_state->__pyx_n_u_pi_2); + Py_CLEAR(clear_module_state->__pyx_n_s_pickle); + Py_CLEAR(clear_module_state->__pyx_n_s_print); + Py_CLEAR(clear_module_state->__pyx_n_u_print_level); + Py_CLEAR(clear_module_state->__pyx_n_s_print_statistics); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_PickleError); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_checksum); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_result); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_state); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_type); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_unpickle_Enum); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_vtable); + Py_CLEAR(clear_module_state->__pyx_n_u_qp_iter); + Py_CLEAR(clear_module_state->__pyx_n_u_qp_mu0); + Py_CLEAR(clear_module_state->__pyx_n_s_qp_solver_cond_N); + Py_CLEAR(clear_module_state->__pyx_n_u_qp_tau_min); + Py_CLEAR(clear_module_state->__pyx_n_u_qp_tol_comp); + Py_CLEAR(clear_module_state->__pyx_n_u_qp_tol_eq); + Py_CLEAR(clear_module_state->__pyx_n_u_qp_tol_ineq); + Py_CLEAR(clear_module_state->__pyx_n_u_qp_tol_stat); + Py_CLEAR(clear_module_state->__pyx_n_u_qp_warm_start); + Py_CLEAR(clear_module_state->__pyx_n_u_r); + Py_CLEAR(clear_module_state->__pyx_n_s_range); + Py_CLEAR(clear_module_state->__pyx_n_s_recompute); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_ex); + Py_CLEAR(clear_module_state->__pyx_n_s_register); + Py_CLEAR(clear_module_state->__pyx_n_b_res_comp); + Py_CLEAR(clear_module_state->__pyx_n_b_res_eq); + Py_CLEAR(clear_module_state->__pyx_n_b_res_ineq); + Py_CLEAR(clear_module_state->__pyx_n_b_res_stat); + Py_CLEAR(clear_module_state->__pyx_n_s_reset); + Py_CLEAR(clear_module_state->__pyx_n_s_reset_qp_solver_mem); + Py_CLEAR(clear_module_state->__pyx_n_u_residuals); + Py_CLEAR(clear_module_state->__pyx_n_u_rti_phase); + Py_CLEAR(clear_module_state->__pyx_n_s_self); + Py_CLEAR(clear_module_state->__pyx_n_s_set); + Py_CLEAR(clear_module_state->__pyx_n_s_set_new_time_steps); + Py_CLEAR(clear_module_state->__pyx_n_s_set_params_sparse); + Py_CLEAR(clear_module_state->__pyx_kp_u_set_value_must_be_numpy_array_go); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_shape); + Py_CLEAR(clear_module_state->__pyx_n_s_size); + Py_CLEAR(clear_module_state->__pyx_n_u_sl); + Py_CLEAR(clear_module_state->__pyx_n_u_sl_2); + Py_CLEAR(clear_module_state->__pyx_n_s_solution); + Py_CLEAR(clear_module_state->__pyx_n_s_solve); + Py_CLEAR(clear_module_state->__pyx_n_s_solve_for_x0); + Py_CLEAR(clear_module_state->__pyx_kp_u_solver_option_must_be_of_type_fl); + Py_CLEAR(clear_module_state->__pyx_kp_u_solver_option_must_be_of_type_in); + Py_CLEAR(clear_module_state->__pyx_kp_u_solver_option_must_be_of_type_st); + Py_CLEAR(clear_module_state->__pyx_n_s_sort_keys); + Py_CLEAR(clear_module_state->__pyx_n_s_spec); + Py_CLEAR(clear_module_state->__pyx_n_s_split); + Py_CLEAR(clear_module_state->__pyx_n_s_sqp_iter); + Py_CLEAR(clear_module_state->__pyx_n_u_sqp_iter); + Py_CLEAR(clear_module_state->__pyx_n_s_stage); + Py_CLEAR(clear_module_state->__pyx_n_s_start); + Py_CLEAR(clear_module_state->__pyx_n_s_stat_m); + Py_CLEAR(clear_module_state->__pyx_n_u_stat_m); + Py_CLEAR(clear_module_state->__pyx_n_s_stat_n); + Py_CLEAR(clear_module_state->__pyx_n_u_stat_n); + Py_CLEAR(clear_module_state->__pyx_n_u_statistics); + Py_CLEAR(clear_module_state->__pyx_n_s_status); + Py_CLEAR(clear_module_state->__pyx_n_s_step); + Py_CLEAR(clear_module_state->__pyx_n_u_step_length); + Py_CLEAR(clear_module_state->__pyx_n_s_stop); + Py_CLEAR(clear_module_state->__pyx_n_s_store_iterate); + Py_CLEAR(clear_module_state->__pyx_n_s_store_iterate_locals_lambda); + Py_CLEAR(clear_module_state->__pyx_kp_u_stored_current_iterate_in); + Py_CLEAR(clear_module_state->__pyx_n_s_strftime); + Py_CLEAR(clear_module_state->__pyx_kp_s_strided_and_direct); + Py_CLEAR(clear_module_state->__pyx_kp_s_strided_and_direct_or_indirect); + Py_CLEAR(clear_module_state->__pyx_kp_s_strided_and_indirect); + Py_CLEAR(clear_module_state->__pyx_n_s_string_fields); + Py_CLEAR(clear_module_state->__pyx_n_s_string_value); + Py_CLEAR(clear_module_state->__pyx_kp_s_stringsource); + Py_CLEAR(clear_module_state->__pyx_n_s_struct); + Py_CLEAR(clear_module_state->__pyx_n_u_su); + Py_CLEAR(clear_module_state->__pyx_n_u_su_2); + Py_CLEAR(clear_module_state->__pyx_n_s_sys); + Py_CLEAR(clear_module_state->__pyx_n_u_t); + Py_CLEAR(clear_module_state->__pyx_n_u_t_2); + Py_CLEAR(clear_module_state->__pyx_n_s_test); + Py_CLEAR(clear_module_state->__pyx_kp_s_third_party_acados_acados_templa); + Py_CLEAR(clear_module_state->__pyx_n_u_time_glob); + Py_CLEAR(clear_module_state->__pyx_n_u_time_lin); + Py_CLEAR(clear_module_state->__pyx_n_u_time_qp); + Py_CLEAR(clear_module_state->__pyx_n_u_time_qp_solver_call); + Py_CLEAR(clear_module_state->__pyx_n_u_time_qp_xcond); + Py_CLEAR(clear_module_state->__pyx_n_u_time_reg); + Py_CLEAR(clear_module_state->__pyx_n_u_time_sim); + Py_CLEAR(clear_module_state->__pyx_n_u_time_sim_ad); + Py_CLEAR(clear_module_state->__pyx_n_u_time_sim_la); + Py_CLEAR(clear_module_state->__pyx_n_u_time_solution_sensitivities); + Py_CLEAR(clear_module_state->__pyx_n_u_time_tot); + Py_CLEAR(clear_module_state->__pyx_n_u_tol_comp); + Py_CLEAR(clear_module_state->__pyx_n_u_tol_eq); + Py_CLEAR(clear_module_state->__pyx_n_u_tol_ineq); + Py_CLEAR(clear_module_state->__pyx_n_u_tol_stat); + Py_CLEAR(clear_module_state->__pyx_n_s_tolist); + Py_CLEAR(clear_module_state->__pyx_n_u_u); + Py_CLEAR(clear_module_state->__pyx_n_s_u0); + Py_CLEAR(clear_module_state->__pyx_n_u_u_2); + Py_CLEAR(clear_module_state->__pyx_n_u_ubu); + Py_CLEAR(clear_module_state->__pyx_n_u_ubx); + Py_CLEAR(clear_module_state->__pyx_kp_s_unable_to_allocate_array_data); + Py_CLEAR(clear_module_state->__pyx_kp_s_unable_to_allocate_shape_and_str); + Py_CLEAR(clear_module_state->__pyx_n_s_unpack); + Py_CLEAR(clear_module_state->__pyx_n_s_update); + Py_CLEAR(clear_module_state->__pyx_n_s_update_qp_solver_cond_N); + Py_CLEAR(clear_module_state->__pyx_n_s_utcnow); + Py_CLEAR(clear_module_state->__pyx_kp_u_utf_8); + Py_CLEAR(clear_module_state->__pyx_n_s_value); + Py_CLEAR(clear_module_state->__pyx_n_s_value_2); + Py_CLEAR(clear_module_state->__pyx_n_s_value_shape); + Py_CLEAR(clear_module_state->__pyx_n_s_version_info); + Py_CLEAR(clear_module_state->__pyx_n_u_w); + Py_CLEAR(clear_module_state->__pyx_n_u_warm_start_first_qp); + Py_CLEAR(clear_module_state->__pyx_kp_u_with_dimension); + Py_CLEAR(clear_module_state->__pyx_kp_u_with_dimension_you_have); + Py_CLEAR(clear_module_state->__pyx_n_b_x); + Py_CLEAR(clear_module_state->__pyx_n_s_x); + Py_CLEAR(clear_module_state->__pyx_n_u_x); + Py_CLEAR(clear_module_state->__pyx_n_s_x0_bar); + Py_CLEAR(clear_module_state->__pyx_n_u_x_2); + Py_CLEAR(clear_module_state->__pyx_n_u_xdot_guess); + Py_CLEAR(clear_module_state->__pyx_n_u_y_ref); + Py_CLEAR(clear_module_state->__pyx_kp_u_you_have); + Py_CLEAR(clear_module_state->__pyx_n_u_yref); + Py_CLEAR(clear_module_state->__pyx_n_u_z); + Py_CLEAR(clear_module_state->__pyx_n_u_z_2); + Py_CLEAR(clear_module_state->__pyx_n_b_z_guess); + Py_CLEAR(clear_module_state->__pyx_n_u_z_guess); + Py_CLEAR(clear_module_state->__pyx_n_s_zeros); + Py_CLEAR(clear_module_state->__pyx_int_0); + Py_CLEAR(clear_module_state->__pyx_int_1); + Py_CLEAR(clear_module_state->__pyx_int_2); + Py_CLEAR(clear_module_state->__pyx_int_3); + Py_CLEAR(clear_module_state->__pyx_int_4); + Py_CLEAR(clear_module_state->__pyx_int_6); + Py_CLEAR(clear_module_state->__pyx_int_7); + Py_CLEAR(clear_module_state->__pyx_int_112105877); + Py_CLEAR(clear_module_state->__pyx_int_136983863); + Py_CLEAR(clear_module_state->__pyx_int_184977713); + Py_CLEAR(clear_module_state->__pyx_int_neg_1); + Py_CLEAR(clear_module_state->__pyx_int_neg_5); + Py_CLEAR(clear_module_state->__pyx_slice__5); + Py_CLEAR(clear_module_state->__pyx_tuple__4); + Py_CLEAR(clear_module_state->__pyx_tuple__8); + Py_CLEAR(clear_module_state->__pyx_tuple__9); + Py_CLEAR(clear_module_state->__pyx_slice__18); + Py_CLEAR(clear_module_state->__pyx_tuple__10); + Py_CLEAR(clear_module_state->__pyx_tuple__11); + Py_CLEAR(clear_module_state->__pyx_tuple__12); + Py_CLEAR(clear_module_state->__pyx_tuple__13); + Py_CLEAR(clear_module_state->__pyx_tuple__14); + Py_CLEAR(clear_module_state->__pyx_tuple__15); + Py_CLEAR(clear_module_state->__pyx_tuple__19); + Py_CLEAR(clear_module_state->__pyx_tuple__20); + Py_CLEAR(clear_module_state->__pyx_tuple__21); + Py_CLEAR(clear_module_state->__pyx_tuple__22); + Py_CLEAR(clear_module_state->__pyx_tuple__23); + Py_CLEAR(clear_module_state->__pyx_tuple__24); + Py_CLEAR(clear_module_state->__pyx_tuple__25); + Py_CLEAR(clear_module_state->__pyx_tuple__26); + Py_CLEAR(clear_module_state->__pyx_tuple__27); + Py_CLEAR(clear_module_state->__pyx_tuple__28); + Py_CLEAR(clear_module_state->__pyx_tuple__29); + Py_CLEAR(clear_module_state->__pyx_tuple__30); + Py_CLEAR(clear_module_state->__pyx_tuple__32); + Py_CLEAR(clear_module_state->__pyx_tuple__33); + Py_CLEAR(clear_module_state->__pyx_tuple__34); + Py_CLEAR(clear_module_state->__pyx_tuple__35); + Py_CLEAR(clear_module_state->__pyx_tuple__36); + Py_CLEAR(clear_module_state->__pyx_tuple__37); + Py_CLEAR(clear_module_state->__pyx_tuple__38); + Py_CLEAR(clear_module_state->__pyx_tuple__39); + Py_CLEAR(clear_module_state->__pyx_tuple__40); + Py_CLEAR(clear_module_state->__pyx_tuple__41); + Py_CLEAR(clear_module_state->__pyx_tuple__42); + Py_CLEAR(clear_module_state->__pyx_tuple__44); + Py_CLEAR(clear_module_state->__pyx_tuple__46); + Py_CLEAR(clear_module_state->__pyx_tuple__49); + Py_CLEAR(clear_module_state->__pyx_tuple__51); + Py_CLEAR(clear_module_state->__pyx_tuple__53); + Py_CLEAR(clear_module_state->__pyx_tuple__55); + Py_CLEAR(clear_module_state->__pyx_tuple__57); + Py_CLEAR(clear_module_state->__pyx_tuple__59); + Py_CLEAR(clear_module_state->__pyx_tuple__60); + Py_CLEAR(clear_module_state->__pyx_tuple__63); + Py_CLEAR(clear_module_state->__pyx_tuple__65); + Py_CLEAR(clear_module_state->__pyx_tuple__66); + Py_CLEAR(clear_module_state->__pyx_tuple__68); + Py_CLEAR(clear_module_state->__pyx_tuple__70); + Py_CLEAR(clear_module_state->__pyx_tuple__73); + Py_CLEAR(clear_module_state->__pyx_tuple__75); + Py_CLEAR(clear_module_state->__pyx_tuple__77); + Py_CLEAR(clear_module_state->__pyx_tuple__79); + Py_CLEAR(clear_module_state->__pyx_tuple__80); + Py_CLEAR(clear_module_state->__pyx_tuple__82); + Py_CLEAR(clear_module_state->__pyx_tuple__85); + Py_CLEAR(clear_module_state->__pyx_tuple__87); + Py_CLEAR(clear_module_state->__pyx_tuple__89); + Py_CLEAR(clear_module_state->__pyx_tuple__92); + Py_CLEAR(clear_module_state->__pyx_codeobj__43); + Py_CLEAR(clear_module_state->__pyx_codeobj__45); + Py_CLEAR(clear_module_state->__pyx_codeobj__47); + Py_CLEAR(clear_module_state->__pyx_codeobj__48); + Py_CLEAR(clear_module_state->__pyx_codeobj__50); + Py_CLEAR(clear_module_state->__pyx_codeobj__52); + Py_CLEAR(clear_module_state->__pyx_codeobj__54); + Py_CLEAR(clear_module_state->__pyx_codeobj__56); + Py_CLEAR(clear_module_state->__pyx_codeobj__58); + Py_CLEAR(clear_module_state->__pyx_codeobj__61); + Py_CLEAR(clear_module_state->__pyx_codeobj__62); + Py_CLEAR(clear_module_state->__pyx_codeobj__64); + Py_CLEAR(clear_module_state->__pyx_codeobj__67); + Py_CLEAR(clear_module_state->__pyx_codeobj__69); + Py_CLEAR(clear_module_state->__pyx_codeobj__71); + Py_CLEAR(clear_module_state->__pyx_codeobj__72); + Py_CLEAR(clear_module_state->__pyx_codeobj__74); + Py_CLEAR(clear_module_state->__pyx_codeobj__76); + Py_CLEAR(clear_module_state->__pyx_codeobj__78); + Py_CLEAR(clear_module_state->__pyx_codeobj__81); + Py_CLEAR(clear_module_state->__pyx_codeobj__83); + Py_CLEAR(clear_module_state->__pyx_codeobj__84); + Py_CLEAR(clear_module_state->__pyx_codeobj__86); + Py_CLEAR(clear_module_state->__pyx_codeobj__88); + Py_CLEAR(clear_module_state->__pyx_codeobj__90); + Py_CLEAR(clear_module_state->__pyx_codeobj__91); + Py_CLEAR(clear_module_state->__pyx_codeobj__93); + return 0; +} +#endif +/* #### Code section: module_state_traverse ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { + __pyx_mstate *traverse_module_state = __pyx_mstate(m); + if (!traverse_module_state) return 0; + Py_VISIT(traverse_module_state->__pyx_d); + Py_VISIT(traverse_module_state->__pyx_b); + Py_VISIT(traverse_module_state->__pyx_cython_runtime); + Py_VISIT(traverse_module_state->__pyx_empty_tuple); + Py_VISIT(traverse_module_state->__pyx_empty_bytes); + Py_VISIT(traverse_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_VISIT(traverse_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_VISIT(traverse_module_state->__pyx_FusedFunctionType); + #endif + Py_VISIT(traverse_module_state->__pyx_ptype_7cpython_4type_type); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_dtype); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_flatiter); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_broadcast); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_ndarray); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_generic); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_number); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_integer); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_signedinteger); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_unsignedinteger); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_inexact); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_floating); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_complexfloating); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_flexible); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_character); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_ufunc); + Py_VISIT(traverse_module_state->__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + Py_VISIT(traverse_module_state->__pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + Py_VISIT(traverse_module_state->__pyx_array_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_array); + Py_VISIT(traverse_module_state->__pyx_MemviewEnum_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_MemviewEnum); + Py_VISIT(traverse_module_state->__pyx_memoryview_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_memoryview); + Py_VISIT(traverse_module_state->__pyx_memoryviewslice_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_memoryviewslice); + Py_VISIT(traverse_module_state->__pyx_kp_u_); + Py_VISIT(traverse_module_state->__pyx_kp_u_0); + Py_VISIT(traverse_module_state->__pyx_n_s_ASCII); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython___get_poin); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython___get_stat); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython___get_stat_2); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython___get_stat_3); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython___reduce_c); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython___setstate); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython__get_poin); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython__get_stat); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython__get_stat_2); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython__get_stat_3); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_constraint); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_constraint_2); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_cost_set); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_cost_set_m); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_custom_upd); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_does_not_s); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_does_not_s_2); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_eval_param); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_eval_param_2); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_eval_param_3); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_get); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_get_cost); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_get_field); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_get_from_q); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_get_is_an); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_get_residu); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_get_stage); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_get_stats); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_load_itera); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_options_se); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_options_se_2); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_print_stat); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_reset); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_set); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_set_is_not); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_set_mismat); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_set_new_ti); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_set_params); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_solve); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_solve_argu); + Py_VISIT(traverse_module_state->__pyx_kp_u_AcadosOcpSolverCython_solve_argu_2); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_solve_for); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_store_iter); + Py_VISIT(traverse_module_state->__pyx_n_s_AcadosOcpSolverCython_update_qp); + Py_VISIT(traverse_module_state->__pyx_kp_s_All_dimensions_preceding_dimensi); + Py_VISIT(traverse_module_state->__pyx_n_s_AssertionError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Buffer_view_does_not_expose_stri); + Py_VISIT(traverse_module_state->__pyx_kp_s_Can_only_create_a_buffer_that_is); + Py_VISIT(traverse_module_state->__pyx_kp_s_Cannot_assign_to_read_only_memor); + Py_VISIT(traverse_module_state->__pyx_kp_s_Cannot_create_writable_memory_vi); + Py_VISIT(traverse_module_state->__pyx_kp_u_Cannot_index_with_type); + Py_VISIT(traverse_module_state->__pyx_kp_s_Cannot_transpose_memoryview_with); + Py_VISIT(traverse_module_state->__pyx_kp_s_Dimension_d_is_not_direct); + Py_VISIT(traverse_module_state->__pyx_n_s_Ellipsis); + Py_VISIT(traverse_module_state->__pyx_kp_s_Empty_shape_tuple_for_cython_arr); + Py_VISIT(traverse_module_state->__pyx_n_u_F); + Py_VISIT(traverse_module_state->__pyx_kp_u_Got_sizes_idx); + Py_VISIT(traverse_module_state->__pyx_n_s_ImportError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0); + Py_VISIT(traverse_module_state->__pyx_n_s_IndexError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Index_out_of_bounds_axis_d); + Py_VISIT(traverse_module_state->__pyx_kp_s_Indirect_dimensions_not_supporte); + Py_VISIT(traverse_module_state->__pyx_kp_u_Invalid_mode_expected_c_or_fortr); + Py_VISIT(traverse_module_state->__pyx_kp_u_Invalid_shape_in_axis); + Py_VISIT(traverse_module_state->__pyx_n_s_MemoryError); + Py_VISIT(traverse_module_state->__pyx_kp_s_MemoryView_of_r_at_0x_x); + Py_VISIT(traverse_module_state->__pyx_kp_s_MemoryView_of_r_object); + Py_VISIT(traverse_module_state->__pyx_n_s_N); + Py_VISIT(traverse_module_state->__pyx_kp_u_None); + Py_VISIT(traverse_module_state->__pyx_n_s_NotImplementedError); + Py_VISIT(traverse_module_state->__pyx_n_b_O); + Py_VISIT(traverse_module_state->__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + Py_VISIT(traverse_module_state->__pyx_n_s_PickleError); + Py_VISIT(traverse_module_state->__pyx_n_u_SQP); + Py_VISIT(traverse_module_state->__pyx_n_u_SQP_RTI); + Py_VISIT(traverse_module_state->__pyx_n_s_Sequence); + Py_VISIT(traverse_module_state->__pyx_kp_s_Step_may_not_be_zero_axis_d); + Py_VISIT(traverse_module_state->__pyx_kp_u_TODO); + Py_VISIT(traverse_module_state->__pyx_n_s_TypeError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Unable_to_convert_item_to_object); + Py_VISIT(traverse_module_state->__pyx_n_s_ValueError); + Py_VISIT(traverse_module_state->__pyx_n_s_View_MemoryView); + Py_VISIT(traverse_module_state->__pyx_kp_u_Warning_acados_ocp_solver_reache); + Py_VISIT(traverse_module_state->__pyx_kp_u_Y_m_d_H_M_S_f); + Py_VISIT(traverse_module_state->__pyx_kp_u__16); + Py_VISIT(traverse_module_state->__pyx_n_u__17); + Py_VISIT(traverse_module_state->__pyx_kp_u__2); + Py_VISIT(traverse_module_state->__pyx_n_s__3); + Py_VISIT(traverse_module_state->__pyx_kp_u__31); + Py_VISIT(traverse_module_state->__pyx_kp_u__6); + Py_VISIT(traverse_module_state->__pyx_kp_u__7); + Py_VISIT(traverse_module_state->__pyx_n_s__94); + Py_VISIT(traverse_module_state->__pyx_n_s_abc); + Py_VISIT(traverse_module_state->__pyx_kp_u_acados_acados_ocp_solver_returne); + Py_VISIT(traverse_module_state->__pyx_n_s_acados_template_acados_ocp_solve); + Py_VISIT(traverse_module_state->__pyx_n_s_allocate_buffer); + Py_VISIT(traverse_module_state->__pyx_n_u_alpha); + Py_VISIT(traverse_module_state->__pyx_n_u_alpha_min); + Py_VISIT(traverse_module_state->__pyx_n_u_alpha_reduction); + Py_VISIT(traverse_module_state->__pyx_kp_u_alpha_values_are_not_available_f); + Py_VISIT(traverse_module_state->__pyx_kp_u_and); + Py_VISIT(traverse_module_state->__pyx_n_s_array); + Py_VISIT(traverse_module_state->__pyx_n_s_ascontiguousarray); + Py_VISIT(traverse_module_state->__pyx_n_s_asfortranarray); + Py_VISIT(traverse_module_state->__pyx_n_s_asyncio_coroutines); + Py_VISIT(traverse_module_state->__pyx_kp_u_at_stage); + Py_VISIT(traverse_module_state->__pyx_n_s_base); + Py_VISIT(traverse_module_state->__pyx_n_s_c); + Py_VISIT(traverse_module_state->__pyx_n_u_c); + Py_VISIT(traverse_module_state->__pyx_n_s_class); + Py_VISIT(traverse_module_state->__pyx_n_s_class_getitem); + Py_VISIT(traverse_module_state->__pyx_n_s_cline_in_traceback); + Py_VISIT(traverse_module_state->__pyx_n_s_collections); + Py_VISIT(traverse_module_state->__pyx_kp_s_collections_abc); + Py_VISIT(traverse_module_state->__pyx_n_s_constraints_fields); + Py_VISIT(traverse_module_state->__pyx_n_s_constraints_set); + Py_VISIT(traverse_module_state->__pyx_kp_u_constraints_set_value_must_be_nu); + Py_VISIT(traverse_module_state->__pyx_kp_s_contiguous_and_direct); + Py_VISIT(traverse_module_state->__pyx_kp_s_contiguous_and_indirect); + Py_VISIT(traverse_module_state->__pyx_n_s_cost_fields); + Py_VISIT(traverse_module_state->__pyx_n_s_cost_set); + Py_VISIT(traverse_module_state->__pyx_kp_u_cost_set_value_must_be_numpy_arr); + Py_VISIT(traverse_module_state->__pyx_n_s_count); + Py_VISIT(traverse_module_state->__pyx_n_s_custom_update); + Py_VISIT(traverse_module_state->__pyx_n_u_d); + Py_VISIT(traverse_module_state->__pyx_n_s_data); + Py_VISIT(traverse_module_state->__pyx_n_s_data_2); + Py_VISIT(traverse_module_state->__pyx_n_s_data_len); + Py_VISIT(traverse_module_state->__pyx_n_s_datetime); + Py_VISIT(traverse_module_state->__pyx_n_s_default); + Py_VISIT(traverse_module_state->__pyx_n_s_dict); + Py_VISIT(traverse_module_state->__pyx_n_s_dims); + Py_VISIT(traverse_module_state->__pyx_kp_u_disable); + Py_VISIT(traverse_module_state->__pyx_n_s_double_fields); + Py_VISIT(traverse_module_state->__pyx_n_s_double_value); + Py_VISIT(traverse_module_state->__pyx_n_s_dtype); + Py_VISIT(traverse_module_state->__pyx_n_s_dtype_is_object); + Py_VISIT(traverse_module_state->__pyx_n_s_dump); + Py_VISIT(traverse_module_state->__pyx_kp_u_enable); + Py_VISIT(traverse_module_state->__pyx_n_s_encode); + Py_VISIT(traverse_module_state->__pyx_n_s_enter); + Py_VISIT(traverse_module_state->__pyx_n_s_enumerate); + Py_VISIT(traverse_module_state->__pyx_n_u_eps_sufficient_descent); + Py_VISIT(traverse_module_state->__pyx_n_s_error); + Py_VISIT(traverse_module_state->__pyx_n_s_eval_param_sens); + Py_VISIT(traverse_module_state->__pyx_n_u_ex); + Py_VISIT(traverse_module_state->__pyx_n_s_exit); + Py_VISIT(traverse_module_state->__pyx_n_s_f); + Py_VISIT(traverse_module_state->__pyx_n_s_field); + Py_VISIT(traverse_module_state->__pyx_n_s_field_2); + Py_VISIT(traverse_module_state->__pyx_n_s_fields); + Py_VISIT(traverse_module_state->__pyx_n_s_filename); + Py_VISIT(traverse_module_state->__pyx_n_s_flags); + Py_VISIT(traverse_module_state->__pyx_n_s_float64); + Py_VISIT(traverse_module_state->__pyx_kp_u_for_field); + Py_VISIT(traverse_module_state->__pyx_n_s_format); + Py_VISIT(traverse_module_state->__pyx_n_s_fortran); + Py_VISIT(traverse_module_state->__pyx_n_u_fortran); + Py_VISIT(traverse_module_state->__pyx_n_s_full_stats); + Py_VISIT(traverse_module_state->__pyx_n_u_full_step_dual); + Py_VISIT(traverse_module_state->__pyx_kp_u_gc); + Py_VISIT(traverse_module_state->__pyx_n_s_get); + Py_VISIT(traverse_module_state->__pyx_n_s_get_cost); + Py_VISIT(traverse_module_state->__pyx_n_s_get_from_qp_in); + Py_VISIT(traverse_module_state->__pyx_n_s_get_pointers_solver); + Py_VISIT(traverse_module_state->__pyx_n_s_get_residuals); + Py_VISIT(traverse_module_state->__pyx_n_s_get_stat_double); + Py_VISIT(traverse_module_state->__pyx_n_s_get_stat_int); + Py_VISIT(traverse_module_state->__pyx_n_s_get_stat_matrix); + Py_VISIT(traverse_module_state->__pyx_n_s_get_stats); + Py_VISIT(traverse_module_state->__pyx_n_s_getcwd); + Py_VISIT(traverse_module_state->__pyx_n_s_getstate); + Py_VISIT(traverse_module_state->__pyx_n_u_globalization); + Py_VISIT(traverse_module_state->__pyx_n_u_globalization_use_SOC); + Py_VISIT(traverse_module_state->__pyx_kp_u_got); + Py_VISIT(traverse_module_state->__pyx_kp_u_got_differing_extents_in_dimensi); + Py_VISIT(traverse_module_state->__pyx_n_s_i); + Py_VISIT(traverse_module_state->__pyx_n_s_i_string); + Py_VISIT(traverse_module_state->__pyx_n_s_id); + Py_VISIT(traverse_module_state->__pyx_n_s_idx); + Py_VISIT(traverse_module_state->__pyx_n_s_idx_values); + Py_VISIT(traverse_module_state->__pyx_n_s_import); + Py_VISIT(traverse_module_state->__pyx_n_s_indent); + Py_VISIT(traverse_module_state->__pyx_n_s_index); + Py_VISIT(traverse_module_state->__pyx_n_u_initialize_t_slacks); + Py_VISIT(traverse_module_state->__pyx_n_s_initializing); + Py_VISIT(traverse_module_state->__pyx_n_s_int); + Py_VISIT(traverse_module_state->__pyx_n_s_int32); + Py_VISIT(traverse_module_state->__pyx_n_s_int_fields); + Py_VISIT(traverse_module_state->__pyx_n_s_int_value); + Py_VISIT(traverse_module_state->__pyx_n_s_is_coroutine); + Py_VISIT(traverse_module_state->__pyx_kp_u_isenabled); + Py_VISIT(traverse_module_state->__pyx_n_s_isfile); + Py_VISIT(traverse_module_state->__pyx_n_s_itemsize); + Py_VISIT(traverse_module_state->__pyx_kp_s_itemsize_0_for_cython_array); + Py_VISIT(traverse_module_state->__pyx_n_u_iterate); + Py_VISIT(traverse_module_state->__pyx_n_s_join); + Py_VISIT(traverse_module_state->__pyx_n_s_json); + Py_VISIT(traverse_module_state->__pyx_kp_u_json_2); + Py_VISIT(traverse_module_state->__pyx_n_s_k); + Py_VISIT(traverse_module_state->__pyx_n_s_key); + Py_VISIT(traverse_module_state->__pyx_n_s_keys); + Py_VISIT(traverse_module_state->__pyx_n_s_lN); + Py_VISIT(traverse_module_state->__pyx_n_u_lam); + Py_VISIT(traverse_module_state->__pyx_n_u_lam_2); + Py_VISIT(traverse_module_state->__pyx_n_u_lbu); + Py_VISIT(traverse_module_state->__pyx_n_u_lbx); + Py_VISIT(traverse_module_state->__pyx_n_u_line_search_use_sufficient_desce); + Py_VISIT(traverse_module_state->__pyx_n_s_load); + Py_VISIT(traverse_module_state->__pyx_n_s_load_iterate); + Py_VISIT(traverse_module_state->__pyx_kp_u_load_iterate_failed_file_does_no); + Py_VISIT(traverse_module_state->__pyx_n_s_m); + Py_VISIT(traverse_module_state->__pyx_n_s_main); + Py_VISIT(traverse_module_state->__pyx_n_s_mem_fields); + Py_VISIT(traverse_module_state->__pyx_n_s_memview); + Py_VISIT(traverse_module_state->__pyx_n_s_min_size); + Py_VISIT(traverse_module_state->__pyx_n_s_mode); + Py_VISIT(traverse_module_state->__pyx_n_s_model_name); + Py_VISIT(traverse_module_state->__pyx_n_s_msg); + Py_VISIT(traverse_module_state->__pyx_n_s_n); + Py_VISIT(traverse_module_state->__pyx_n_s_n_update); + Py_VISIT(traverse_module_state->__pyx_n_s_name); + Py_VISIT(traverse_module_state->__pyx_n_s_name_2); + Py_VISIT(traverse_module_state->__pyx_n_s_ndarray); + Py_VISIT(traverse_module_state->__pyx_n_s_ndim); + Py_VISIT(traverse_module_state->__pyx_n_s_new); + Py_VISIT(traverse_module_state->__pyx_n_s_new_time_steps); + Py_VISIT(traverse_module_state->__pyx_n_s_nlp_solver_type); + Py_VISIT(traverse_module_state->__pyx_kp_s_no_default___reduce___due_to_non); + Py_VISIT(traverse_module_state->__pyx_n_s_np); + Py_VISIT(traverse_module_state->__pyx_n_s_numpy); + Py_VISIT(traverse_module_state->__pyx_kp_u_numpy_core_multiarray_failed_to); + Py_VISIT(traverse_module_state->__pyx_kp_u_numpy_core_umath_failed_to_impor); + Py_VISIT(traverse_module_state->__pyx_n_s_nx); + Py_VISIT(traverse_module_state->__pyx_n_s_obj); + Py_VISIT(traverse_module_state->__pyx_n_s_open); + Py_VISIT(traverse_module_state->__pyx_n_s_options_set); + Py_VISIT(traverse_module_state->__pyx_n_s_order); + Py_VISIT(traverse_module_state->__pyx_n_s_os); + Py_VISIT(traverse_module_state->__pyx_n_s_out); + Py_VISIT(traverse_module_state->__pyx_n_s_out_fields); + Py_VISIT(traverse_module_state->__pyx_n_s_out_mat); + Py_VISIT(traverse_module_state->__pyx_n_s_overwrite); + Py_VISIT(traverse_module_state->__pyx_n_u_p); + Py_VISIT(traverse_module_state->__pyx_n_s_pack); + Py_VISIT(traverse_module_state->__pyx_n_s_param_values); + Py_VISIT(traverse_module_state->__pyx_kp_u_param_values_2); + Py_VISIT(traverse_module_state->__pyx_kp_u_param_values__and_idx_values__mu); + Py_VISIT(traverse_module_state->__pyx_kp_u_param_values__must_be_np_array); + Py_VISIT(traverse_module_state->__pyx_n_s_path); + Py_VISIT(traverse_module_state->__pyx_n_u_pi); + Py_VISIT(traverse_module_state->__pyx_n_u_pi_2); + Py_VISIT(traverse_module_state->__pyx_n_s_pickle); + Py_VISIT(traverse_module_state->__pyx_n_s_print); + Py_VISIT(traverse_module_state->__pyx_n_u_print_level); + Py_VISIT(traverse_module_state->__pyx_n_s_print_statistics); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_PickleError); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_checksum); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_result); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_state); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_type); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_unpickle_Enum); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_vtable); + Py_VISIT(traverse_module_state->__pyx_n_u_qp_iter); + Py_VISIT(traverse_module_state->__pyx_n_u_qp_mu0); + Py_VISIT(traverse_module_state->__pyx_n_s_qp_solver_cond_N); + Py_VISIT(traverse_module_state->__pyx_n_u_qp_tau_min); + Py_VISIT(traverse_module_state->__pyx_n_u_qp_tol_comp); + Py_VISIT(traverse_module_state->__pyx_n_u_qp_tol_eq); + Py_VISIT(traverse_module_state->__pyx_n_u_qp_tol_ineq); + Py_VISIT(traverse_module_state->__pyx_n_u_qp_tol_stat); + Py_VISIT(traverse_module_state->__pyx_n_u_qp_warm_start); + Py_VISIT(traverse_module_state->__pyx_n_u_r); + Py_VISIT(traverse_module_state->__pyx_n_s_range); + Py_VISIT(traverse_module_state->__pyx_n_s_recompute); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_ex); + Py_VISIT(traverse_module_state->__pyx_n_s_register); + Py_VISIT(traverse_module_state->__pyx_n_b_res_comp); + Py_VISIT(traverse_module_state->__pyx_n_b_res_eq); + Py_VISIT(traverse_module_state->__pyx_n_b_res_ineq); + Py_VISIT(traverse_module_state->__pyx_n_b_res_stat); + Py_VISIT(traverse_module_state->__pyx_n_s_reset); + Py_VISIT(traverse_module_state->__pyx_n_s_reset_qp_solver_mem); + Py_VISIT(traverse_module_state->__pyx_n_u_residuals); + Py_VISIT(traverse_module_state->__pyx_n_u_rti_phase); + Py_VISIT(traverse_module_state->__pyx_n_s_self); + Py_VISIT(traverse_module_state->__pyx_n_s_set); + Py_VISIT(traverse_module_state->__pyx_n_s_set_new_time_steps); + Py_VISIT(traverse_module_state->__pyx_n_s_set_params_sparse); + Py_VISIT(traverse_module_state->__pyx_kp_u_set_value_must_be_numpy_array_go); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_shape); + Py_VISIT(traverse_module_state->__pyx_n_s_size); + Py_VISIT(traverse_module_state->__pyx_n_u_sl); + Py_VISIT(traverse_module_state->__pyx_n_u_sl_2); + Py_VISIT(traverse_module_state->__pyx_n_s_solution); + Py_VISIT(traverse_module_state->__pyx_n_s_solve); + Py_VISIT(traverse_module_state->__pyx_n_s_solve_for_x0); + Py_VISIT(traverse_module_state->__pyx_kp_u_solver_option_must_be_of_type_fl); + Py_VISIT(traverse_module_state->__pyx_kp_u_solver_option_must_be_of_type_in); + Py_VISIT(traverse_module_state->__pyx_kp_u_solver_option_must_be_of_type_st); + Py_VISIT(traverse_module_state->__pyx_n_s_sort_keys); + Py_VISIT(traverse_module_state->__pyx_n_s_spec); + Py_VISIT(traverse_module_state->__pyx_n_s_split); + Py_VISIT(traverse_module_state->__pyx_n_s_sqp_iter); + Py_VISIT(traverse_module_state->__pyx_n_u_sqp_iter); + Py_VISIT(traverse_module_state->__pyx_n_s_stage); + Py_VISIT(traverse_module_state->__pyx_n_s_start); + Py_VISIT(traverse_module_state->__pyx_n_s_stat_m); + Py_VISIT(traverse_module_state->__pyx_n_u_stat_m); + Py_VISIT(traverse_module_state->__pyx_n_s_stat_n); + Py_VISIT(traverse_module_state->__pyx_n_u_stat_n); + Py_VISIT(traverse_module_state->__pyx_n_u_statistics); + Py_VISIT(traverse_module_state->__pyx_n_s_status); + Py_VISIT(traverse_module_state->__pyx_n_s_step); + Py_VISIT(traverse_module_state->__pyx_n_u_step_length); + Py_VISIT(traverse_module_state->__pyx_n_s_stop); + Py_VISIT(traverse_module_state->__pyx_n_s_store_iterate); + Py_VISIT(traverse_module_state->__pyx_n_s_store_iterate_locals_lambda); + Py_VISIT(traverse_module_state->__pyx_kp_u_stored_current_iterate_in); + Py_VISIT(traverse_module_state->__pyx_n_s_strftime); + Py_VISIT(traverse_module_state->__pyx_kp_s_strided_and_direct); + Py_VISIT(traverse_module_state->__pyx_kp_s_strided_and_direct_or_indirect); + Py_VISIT(traverse_module_state->__pyx_kp_s_strided_and_indirect); + Py_VISIT(traverse_module_state->__pyx_n_s_string_fields); + Py_VISIT(traverse_module_state->__pyx_n_s_string_value); + Py_VISIT(traverse_module_state->__pyx_kp_s_stringsource); + Py_VISIT(traverse_module_state->__pyx_n_s_struct); + Py_VISIT(traverse_module_state->__pyx_n_u_su); + Py_VISIT(traverse_module_state->__pyx_n_u_su_2); + Py_VISIT(traverse_module_state->__pyx_n_s_sys); + Py_VISIT(traverse_module_state->__pyx_n_u_t); + Py_VISIT(traverse_module_state->__pyx_n_u_t_2); + Py_VISIT(traverse_module_state->__pyx_n_s_test); + Py_VISIT(traverse_module_state->__pyx_kp_s_third_party_acados_acados_templa); + Py_VISIT(traverse_module_state->__pyx_n_u_time_glob); + Py_VISIT(traverse_module_state->__pyx_n_u_time_lin); + Py_VISIT(traverse_module_state->__pyx_n_u_time_qp); + Py_VISIT(traverse_module_state->__pyx_n_u_time_qp_solver_call); + Py_VISIT(traverse_module_state->__pyx_n_u_time_qp_xcond); + Py_VISIT(traverse_module_state->__pyx_n_u_time_reg); + Py_VISIT(traverse_module_state->__pyx_n_u_time_sim); + Py_VISIT(traverse_module_state->__pyx_n_u_time_sim_ad); + Py_VISIT(traverse_module_state->__pyx_n_u_time_sim_la); + Py_VISIT(traverse_module_state->__pyx_n_u_time_solution_sensitivities); + Py_VISIT(traverse_module_state->__pyx_n_u_time_tot); + Py_VISIT(traverse_module_state->__pyx_n_u_tol_comp); + Py_VISIT(traverse_module_state->__pyx_n_u_tol_eq); + Py_VISIT(traverse_module_state->__pyx_n_u_tol_ineq); + Py_VISIT(traverse_module_state->__pyx_n_u_tol_stat); + Py_VISIT(traverse_module_state->__pyx_n_s_tolist); + Py_VISIT(traverse_module_state->__pyx_n_u_u); + Py_VISIT(traverse_module_state->__pyx_n_s_u0); + Py_VISIT(traverse_module_state->__pyx_n_u_u_2); + Py_VISIT(traverse_module_state->__pyx_n_u_ubu); + Py_VISIT(traverse_module_state->__pyx_n_u_ubx); + Py_VISIT(traverse_module_state->__pyx_kp_s_unable_to_allocate_array_data); + Py_VISIT(traverse_module_state->__pyx_kp_s_unable_to_allocate_shape_and_str); + Py_VISIT(traverse_module_state->__pyx_n_s_unpack); + Py_VISIT(traverse_module_state->__pyx_n_s_update); + Py_VISIT(traverse_module_state->__pyx_n_s_update_qp_solver_cond_N); + Py_VISIT(traverse_module_state->__pyx_n_s_utcnow); + Py_VISIT(traverse_module_state->__pyx_kp_u_utf_8); + Py_VISIT(traverse_module_state->__pyx_n_s_value); + Py_VISIT(traverse_module_state->__pyx_n_s_value_2); + Py_VISIT(traverse_module_state->__pyx_n_s_value_shape); + Py_VISIT(traverse_module_state->__pyx_n_s_version_info); + Py_VISIT(traverse_module_state->__pyx_n_u_w); + Py_VISIT(traverse_module_state->__pyx_n_u_warm_start_first_qp); + Py_VISIT(traverse_module_state->__pyx_kp_u_with_dimension); + Py_VISIT(traverse_module_state->__pyx_kp_u_with_dimension_you_have); + Py_VISIT(traverse_module_state->__pyx_n_b_x); + Py_VISIT(traverse_module_state->__pyx_n_s_x); + Py_VISIT(traverse_module_state->__pyx_n_u_x); + Py_VISIT(traverse_module_state->__pyx_n_s_x0_bar); + Py_VISIT(traverse_module_state->__pyx_n_u_x_2); + Py_VISIT(traverse_module_state->__pyx_n_u_xdot_guess); + Py_VISIT(traverse_module_state->__pyx_n_u_y_ref); + Py_VISIT(traverse_module_state->__pyx_kp_u_you_have); + Py_VISIT(traverse_module_state->__pyx_n_u_yref); + Py_VISIT(traverse_module_state->__pyx_n_u_z); + Py_VISIT(traverse_module_state->__pyx_n_u_z_2); + Py_VISIT(traverse_module_state->__pyx_n_b_z_guess); + Py_VISIT(traverse_module_state->__pyx_n_u_z_guess); + Py_VISIT(traverse_module_state->__pyx_n_s_zeros); + Py_VISIT(traverse_module_state->__pyx_int_0); + Py_VISIT(traverse_module_state->__pyx_int_1); + Py_VISIT(traverse_module_state->__pyx_int_2); + Py_VISIT(traverse_module_state->__pyx_int_3); + Py_VISIT(traverse_module_state->__pyx_int_4); + Py_VISIT(traverse_module_state->__pyx_int_6); + Py_VISIT(traverse_module_state->__pyx_int_7); + Py_VISIT(traverse_module_state->__pyx_int_112105877); + Py_VISIT(traverse_module_state->__pyx_int_136983863); + Py_VISIT(traverse_module_state->__pyx_int_184977713); + Py_VISIT(traverse_module_state->__pyx_int_neg_1); + Py_VISIT(traverse_module_state->__pyx_int_neg_5); + Py_VISIT(traverse_module_state->__pyx_slice__5); + Py_VISIT(traverse_module_state->__pyx_tuple__4); + Py_VISIT(traverse_module_state->__pyx_tuple__8); + Py_VISIT(traverse_module_state->__pyx_tuple__9); + Py_VISIT(traverse_module_state->__pyx_slice__18); + Py_VISIT(traverse_module_state->__pyx_tuple__10); + Py_VISIT(traverse_module_state->__pyx_tuple__11); + Py_VISIT(traverse_module_state->__pyx_tuple__12); + Py_VISIT(traverse_module_state->__pyx_tuple__13); + Py_VISIT(traverse_module_state->__pyx_tuple__14); + Py_VISIT(traverse_module_state->__pyx_tuple__15); + Py_VISIT(traverse_module_state->__pyx_tuple__19); + Py_VISIT(traverse_module_state->__pyx_tuple__20); + Py_VISIT(traverse_module_state->__pyx_tuple__21); + Py_VISIT(traverse_module_state->__pyx_tuple__22); + Py_VISIT(traverse_module_state->__pyx_tuple__23); + Py_VISIT(traverse_module_state->__pyx_tuple__24); + Py_VISIT(traverse_module_state->__pyx_tuple__25); + Py_VISIT(traverse_module_state->__pyx_tuple__26); + Py_VISIT(traverse_module_state->__pyx_tuple__27); + Py_VISIT(traverse_module_state->__pyx_tuple__28); + Py_VISIT(traverse_module_state->__pyx_tuple__29); + Py_VISIT(traverse_module_state->__pyx_tuple__30); + Py_VISIT(traverse_module_state->__pyx_tuple__32); + Py_VISIT(traverse_module_state->__pyx_tuple__33); + Py_VISIT(traverse_module_state->__pyx_tuple__34); + Py_VISIT(traverse_module_state->__pyx_tuple__35); + Py_VISIT(traverse_module_state->__pyx_tuple__36); + Py_VISIT(traverse_module_state->__pyx_tuple__37); + Py_VISIT(traverse_module_state->__pyx_tuple__38); + Py_VISIT(traverse_module_state->__pyx_tuple__39); + Py_VISIT(traverse_module_state->__pyx_tuple__40); + Py_VISIT(traverse_module_state->__pyx_tuple__41); + Py_VISIT(traverse_module_state->__pyx_tuple__42); + Py_VISIT(traverse_module_state->__pyx_tuple__44); + Py_VISIT(traverse_module_state->__pyx_tuple__46); + Py_VISIT(traverse_module_state->__pyx_tuple__49); + Py_VISIT(traverse_module_state->__pyx_tuple__51); + Py_VISIT(traverse_module_state->__pyx_tuple__53); + Py_VISIT(traverse_module_state->__pyx_tuple__55); + Py_VISIT(traverse_module_state->__pyx_tuple__57); + Py_VISIT(traverse_module_state->__pyx_tuple__59); + Py_VISIT(traverse_module_state->__pyx_tuple__60); + Py_VISIT(traverse_module_state->__pyx_tuple__63); + Py_VISIT(traverse_module_state->__pyx_tuple__65); + Py_VISIT(traverse_module_state->__pyx_tuple__66); + Py_VISIT(traverse_module_state->__pyx_tuple__68); + Py_VISIT(traverse_module_state->__pyx_tuple__70); + Py_VISIT(traverse_module_state->__pyx_tuple__73); + Py_VISIT(traverse_module_state->__pyx_tuple__75); + Py_VISIT(traverse_module_state->__pyx_tuple__77); + Py_VISIT(traverse_module_state->__pyx_tuple__79); + Py_VISIT(traverse_module_state->__pyx_tuple__80); + Py_VISIT(traverse_module_state->__pyx_tuple__82); + Py_VISIT(traverse_module_state->__pyx_tuple__85); + Py_VISIT(traverse_module_state->__pyx_tuple__87); + Py_VISIT(traverse_module_state->__pyx_tuple__89); + Py_VISIT(traverse_module_state->__pyx_tuple__92); + Py_VISIT(traverse_module_state->__pyx_codeobj__43); + Py_VISIT(traverse_module_state->__pyx_codeobj__45); + Py_VISIT(traverse_module_state->__pyx_codeobj__47); + Py_VISIT(traverse_module_state->__pyx_codeobj__48); + Py_VISIT(traverse_module_state->__pyx_codeobj__50); + Py_VISIT(traverse_module_state->__pyx_codeobj__52); + Py_VISIT(traverse_module_state->__pyx_codeobj__54); + Py_VISIT(traverse_module_state->__pyx_codeobj__56); + Py_VISIT(traverse_module_state->__pyx_codeobj__58); + Py_VISIT(traverse_module_state->__pyx_codeobj__61); + Py_VISIT(traverse_module_state->__pyx_codeobj__62); + Py_VISIT(traverse_module_state->__pyx_codeobj__64); + Py_VISIT(traverse_module_state->__pyx_codeobj__67); + Py_VISIT(traverse_module_state->__pyx_codeobj__69); + Py_VISIT(traverse_module_state->__pyx_codeobj__71); + Py_VISIT(traverse_module_state->__pyx_codeobj__72); + Py_VISIT(traverse_module_state->__pyx_codeobj__74); + Py_VISIT(traverse_module_state->__pyx_codeobj__76); + Py_VISIT(traverse_module_state->__pyx_codeobj__78); + Py_VISIT(traverse_module_state->__pyx_codeobj__81); + Py_VISIT(traverse_module_state->__pyx_codeobj__83); + Py_VISIT(traverse_module_state->__pyx_codeobj__84); + Py_VISIT(traverse_module_state->__pyx_codeobj__86); + Py_VISIT(traverse_module_state->__pyx_codeobj__88); + Py_VISIT(traverse_module_state->__pyx_codeobj__90); + Py_VISIT(traverse_module_state->__pyx_codeobj__91); + Py_VISIT(traverse_module_state->__pyx_codeobj__93); + return 0; +} +#endif +/* #### Code section: module_state_defines ### */ +#define __pyx_d __pyx_mstate_global->__pyx_d +#define __pyx_b __pyx_mstate_global->__pyx_b +#define __pyx_cython_runtime __pyx_mstate_global->__pyx_cython_runtime +#define __pyx_empty_tuple __pyx_mstate_global->__pyx_empty_tuple +#define __pyx_empty_bytes __pyx_mstate_global->__pyx_empty_bytes +#define __pyx_empty_unicode __pyx_mstate_global->__pyx_empty_unicode +#ifdef __Pyx_CyFunction_USED +#define __pyx_CyFunctionType __pyx_mstate_global->__pyx_CyFunctionType +#endif +#ifdef __Pyx_FusedFunction_USED +#define __pyx_FusedFunctionType __pyx_mstate_global->__pyx_FusedFunctionType +#endif +#ifdef __Pyx_Generator_USED +#define __pyx_GeneratorType __pyx_mstate_global->__pyx_GeneratorType +#endif +#ifdef __Pyx_IterableCoroutine_USED +#define __pyx_IterableCoroutineType __pyx_mstate_global->__pyx_IterableCoroutineType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineAwaitType __pyx_mstate_global->__pyx_CoroutineAwaitType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineType __pyx_mstate_global->__pyx_CoroutineType +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#define __pyx_ptype_7cpython_4type_type __pyx_mstate_global->__pyx_ptype_7cpython_4type_type +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#define __pyx_ptype_5numpy_dtype __pyx_mstate_global->__pyx_ptype_5numpy_dtype +#define __pyx_ptype_5numpy_flatiter __pyx_mstate_global->__pyx_ptype_5numpy_flatiter +#define __pyx_ptype_5numpy_broadcast __pyx_mstate_global->__pyx_ptype_5numpy_broadcast +#define __pyx_ptype_5numpy_ndarray __pyx_mstate_global->__pyx_ptype_5numpy_ndarray +#define __pyx_ptype_5numpy_generic __pyx_mstate_global->__pyx_ptype_5numpy_generic +#define __pyx_ptype_5numpy_number __pyx_mstate_global->__pyx_ptype_5numpy_number +#define __pyx_ptype_5numpy_integer __pyx_mstate_global->__pyx_ptype_5numpy_integer +#define __pyx_ptype_5numpy_signedinteger __pyx_mstate_global->__pyx_ptype_5numpy_signedinteger +#define __pyx_ptype_5numpy_unsignedinteger __pyx_mstate_global->__pyx_ptype_5numpy_unsignedinteger +#define __pyx_ptype_5numpy_inexact __pyx_mstate_global->__pyx_ptype_5numpy_inexact +#define __pyx_ptype_5numpy_floating __pyx_mstate_global->__pyx_ptype_5numpy_floating +#define __pyx_ptype_5numpy_complexfloating __pyx_mstate_global->__pyx_ptype_5numpy_complexfloating +#define __pyx_ptype_5numpy_flexible __pyx_mstate_global->__pyx_ptype_5numpy_flexible +#define __pyx_ptype_5numpy_character __pyx_mstate_global->__pyx_ptype_5numpy_character +#define __pyx_ptype_5numpy_ufunc __pyx_mstate_global->__pyx_ptype_5numpy_ufunc +#if CYTHON_USE_MODULE_STATE +#define __pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython __pyx_mstate_global->__pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython +#define __pyx_type___pyx_array __pyx_mstate_global->__pyx_type___pyx_array +#define __pyx_type___pyx_MemviewEnum __pyx_mstate_global->__pyx_type___pyx_MemviewEnum +#define __pyx_type___pyx_memoryview __pyx_mstate_global->__pyx_type___pyx_memoryview +#define __pyx_type___pyx_memoryviewslice __pyx_mstate_global->__pyx_type___pyx_memoryviewslice +#endif +#define __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython __pyx_mstate_global->__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython +#define __pyx_array_type __pyx_mstate_global->__pyx_array_type +#define __pyx_MemviewEnum_type __pyx_mstate_global->__pyx_MemviewEnum_type +#define __pyx_memoryview_type __pyx_mstate_global->__pyx_memoryview_type +#define __pyx_memoryviewslice_type __pyx_mstate_global->__pyx_memoryviewslice_type +#define __pyx_kp_u_ __pyx_mstate_global->__pyx_kp_u_ +#define __pyx_kp_u_0 __pyx_mstate_global->__pyx_kp_u_0 +#define __pyx_n_s_ASCII __pyx_mstate_global->__pyx_n_s_ASCII +#define __pyx_n_s_AcadosOcpSolverCython __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython +#define __pyx_n_s_AcadosOcpSolverCython___get_poin __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython___get_poin +#define __pyx_n_s_AcadosOcpSolverCython___get_stat __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython___get_stat +#define __pyx_n_s_AcadosOcpSolverCython___get_stat_2 __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython___get_stat_2 +#define __pyx_n_s_AcadosOcpSolverCython___get_stat_3 __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython___get_stat_3 +#define __pyx_n_s_AcadosOcpSolverCython___reduce_c __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython___reduce_c +#define __pyx_n_s_AcadosOcpSolverCython___setstate __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython___setstate +#define __pyx_n_s_AcadosOcpSolverCython__get_poin __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython__get_poin +#define __pyx_n_s_AcadosOcpSolverCython__get_stat __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython__get_stat +#define __pyx_n_s_AcadosOcpSolverCython__get_stat_2 __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython__get_stat_2 +#define __pyx_n_s_AcadosOcpSolverCython__get_stat_3 __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython__get_stat_3 +#define __pyx_kp_u_AcadosOcpSolverCython_constraint __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_constraint +#define __pyx_n_s_AcadosOcpSolverCython_constraint_2 __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_constraint_2 +#define __pyx_n_s_AcadosOcpSolverCython_cost_set __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_cost_set +#define __pyx_kp_u_AcadosOcpSolverCython_cost_set_m __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_cost_set_m +#define __pyx_n_s_AcadosOcpSolverCython_custom_upd __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_custom_upd +#define __pyx_kp_u_AcadosOcpSolverCython_does_not_s __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_does_not_s +#define __pyx_kp_u_AcadosOcpSolverCython_does_not_s_2 __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_does_not_s_2 +#define __pyx_kp_u_AcadosOcpSolverCython_eval_param __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_eval_param +#define __pyx_kp_u_AcadosOcpSolverCython_eval_param_2 __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_eval_param_2 +#define __pyx_n_s_AcadosOcpSolverCython_eval_param_3 __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_eval_param_3 +#define __pyx_n_s_AcadosOcpSolverCython_get __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_get +#define __pyx_n_s_AcadosOcpSolverCython_get_cost __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_get_cost +#define __pyx_kp_u_AcadosOcpSolverCython_get_field __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_get_field +#define __pyx_n_s_AcadosOcpSolverCython_get_from_q __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_get_from_q +#define __pyx_kp_u_AcadosOcpSolverCython_get_is_an __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_get_is_an +#define __pyx_n_s_AcadosOcpSolverCython_get_residu __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_get_residu +#define __pyx_kp_u_AcadosOcpSolverCython_get_stage __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_get_stage +#define __pyx_n_s_AcadosOcpSolverCython_get_stats __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_get_stats +#define __pyx_n_s_AcadosOcpSolverCython_load_itera __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_load_itera +#define __pyx_kp_u_AcadosOcpSolverCython_options_se __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_options_se +#define __pyx_n_s_AcadosOcpSolverCython_options_se_2 __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_options_se_2 +#define __pyx_n_s_AcadosOcpSolverCython_print_stat __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_print_stat +#define __pyx_n_s_AcadosOcpSolverCython_reset __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_reset +#define __pyx_n_s_AcadosOcpSolverCython_set __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_set +#define __pyx_kp_u_AcadosOcpSolverCython_set_is_not __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_set_is_not +#define __pyx_kp_u_AcadosOcpSolverCython_set_mismat __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_set_mismat +#define __pyx_n_s_AcadosOcpSolverCython_set_new_ti __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_set_new_ti +#define __pyx_n_s_AcadosOcpSolverCython_set_params __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_set_params +#define __pyx_n_s_AcadosOcpSolverCython_solve __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_solve +#define __pyx_kp_u_AcadosOcpSolverCython_solve_argu __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_solve_argu +#define __pyx_kp_u_AcadosOcpSolverCython_solve_argu_2 __pyx_mstate_global->__pyx_kp_u_AcadosOcpSolverCython_solve_argu_2 +#define __pyx_n_s_AcadosOcpSolverCython_solve_for __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_solve_for +#define __pyx_n_s_AcadosOcpSolverCython_store_iter __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_store_iter +#define __pyx_n_s_AcadosOcpSolverCython_update_qp __pyx_mstate_global->__pyx_n_s_AcadosOcpSolverCython_update_qp +#define __pyx_kp_s_All_dimensions_preceding_dimensi __pyx_mstate_global->__pyx_kp_s_All_dimensions_preceding_dimensi +#define __pyx_n_s_AssertionError __pyx_mstate_global->__pyx_n_s_AssertionError +#define __pyx_kp_s_Buffer_view_does_not_expose_stri __pyx_mstate_global->__pyx_kp_s_Buffer_view_does_not_expose_stri +#define __pyx_kp_s_Can_only_create_a_buffer_that_is __pyx_mstate_global->__pyx_kp_s_Can_only_create_a_buffer_that_is +#define __pyx_kp_s_Cannot_assign_to_read_only_memor __pyx_mstate_global->__pyx_kp_s_Cannot_assign_to_read_only_memor +#define __pyx_kp_s_Cannot_create_writable_memory_vi __pyx_mstate_global->__pyx_kp_s_Cannot_create_writable_memory_vi +#define __pyx_kp_u_Cannot_index_with_type __pyx_mstate_global->__pyx_kp_u_Cannot_index_with_type +#define __pyx_kp_s_Cannot_transpose_memoryview_with __pyx_mstate_global->__pyx_kp_s_Cannot_transpose_memoryview_with +#define __pyx_kp_s_Dimension_d_is_not_direct __pyx_mstate_global->__pyx_kp_s_Dimension_d_is_not_direct +#define __pyx_n_s_Ellipsis __pyx_mstate_global->__pyx_n_s_Ellipsis +#define __pyx_kp_s_Empty_shape_tuple_for_cython_arr __pyx_mstate_global->__pyx_kp_s_Empty_shape_tuple_for_cython_arr +#define __pyx_n_u_F __pyx_mstate_global->__pyx_n_u_F +#define __pyx_kp_u_Got_sizes_idx __pyx_mstate_global->__pyx_kp_u_Got_sizes_idx +#define __pyx_n_s_ImportError __pyx_mstate_global->__pyx_n_s_ImportError +#define __pyx_kp_s_Incompatible_checksums_0x_x_vs_0 __pyx_mstate_global->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0 +#define __pyx_n_s_IndexError __pyx_mstate_global->__pyx_n_s_IndexError +#define __pyx_kp_s_Index_out_of_bounds_axis_d __pyx_mstate_global->__pyx_kp_s_Index_out_of_bounds_axis_d +#define __pyx_kp_s_Indirect_dimensions_not_supporte __pyx_mstate_global->__pyx_kp_s_Indirect_dimensions_not_supporte +#define __pyx_kp_u_Invalid_mode_expected_c_or_fortr __pyx_mstate_global->__pyx_kp_u_Invalid_mode_expected_c_or_fortr +#define __pyx_kp_u_Invalid_shape_in_axis __pyx_mstate_global->__pyx_kp_u_Invalid_shape_in_axis +#define __pyx_n_s_MemoryError __pyx_mstate_global->__pyx_n_s_MemoryError +#define __pyx_kp_s_MemoryView_of_r_at_0x_x __pyx_mstate_global->__pyx_kp_s_MemoryView_of_r_at_0x_x +#define __pyx_kp_s_MemoryView_of_r_object __pyx_mstate_global->__pyx_kp_s_MemoryView_of_r_object +#define __pyx_n_s_N __pyx_mstate_global->__pyx_n_s_N +#define __pyx_kp_u_None __pyx_mstate_global->__pyx_kp_u_None +#define __pyx_n_s_NotImplementedError __pyx_mstate_global->__pyx_n_s_NotImplementedError +#define __pyx_n_b_O __pyx_mstate_global->__pyx_n_b_O +#define __pyx_kp_u_Out_of_bounds_on_buffer_access_a __pyx_mstate_global->__pyx_kp_u_Out_of_bounds_on_buffer_access_a +#define __pyx_n_s_PickleError __pyx_mstate_global->__pyx_n_s_PickleError +#define __pyx_n_u_SQP __pyx_mstate_global->__pyx_n_u_SQP +#define __pyx_n_u_SQP_RTI __pyx_mstate_global->__pyx_n_u_SQP_RTI +#define __pyx_n_s_Sequence __pyx_mstate_global->__pyx_n_s_Sequence +#define __pyx_kp_s_Step_may_not_be_zero_axis_d __pyx_mstate_global->__pyx_kp_s_Step_may_not_be_zero_axis_d +#define __pyx_kp_u_TODO __pyx_mstate_global->__pyx_kp_u_TODO +#define __pyx_n_s_TypeError __pyx_mstate_global->__pyx_n_s_TypeError +#define __pyx_kp_s_Unable_to_convert_item_to_object __pyx_mstate_global->__pyx_kp_s_Unable_to_convert_item_to_object +#define __pyx_n_s_ValueError __pyx_mstate_global->__pyx_n_s_ValueError +#define __pyx_n_s_View_MemoryView __pyx_mstate_global->__pyx_n_s_View_MemoryView +#define __pyx_kp_u_Warning_acados_ocp_solver_reache __pyx_mstate_global->__pyx_kp_u_Warning_acados_ocp_solver_reache +#define __pyx_kp_u_Y_m_d_H_M_S_f __pyx_mstate_global->__pyx_kp_u_Y_m_d_H_M_S_f +#define __pyx_kp_u__16 __pyx_mstate_global->__pyx_kp_u__16 +#define __pyx_n_u__17 __pyx_mstate_global->__pyx_n_u__17 +#define __pyx_kp_u__2 __pyx_mstate_global->__pyx_kp_u__2 +#define __pyx_n_s__3 __pyx_mstate_global->__pyx_n_s__3 +#define __pyx_kp_u__31 __pyx_mstate_global->__pyx_kp_u__31 +#define __pyx_kp_u__6 __pyx_mstate_global->__pyx_kp_u__6 +#define __pyx_kp_u__7 __pyx_mstate_global->__pyx_kp_u__7 +#define __pyx_n_s__94 __pyx_mstate_global->__pyx_n_s__94 +#define __pyx_n_s_abc __pyx_mstate_global->__pyx_n_s_abc +#define __pyx_kp_u_acados_acados_ocp_solver_returne __pyx_mstate_global->__pyx_kp_u_acados_acados_ocp_solver_returne +#define __pyx_n_s_acados_template_acados_ocp_solve __pyx_mstate_global->__pyx_n_s_acados_template_acados_ocp_solve +#define __pyx_n_s_allocate_buffer __pyx_mstate_global->__pyx_n_s_allocate_buffer +#define __pyx_n_u_alpha __pyx_mstate_global->__pyx_n_u_alpha +#define __pyx_n_u_alpha_min __pyx_mstate_global->__pyx_n_u_alpha_min +#define __pyx_n_u_alpha_reduction __pyx_mstate_global->__pyx_n_u_alpha_reduction +#define __pyx_kp_u_alpha_values_are_not_available_f __pyx_mstate_global->__pyx_kp_u_alpha_values_are_not_available_f +#define __pyx_kp_u_and __pyx_mstate_global->__pyx_kp_u_and +#define __pyx_n_s_array __pyx_mstate_global->__pyx_n_s_array +#define __pyx_n_s_ascontiguousarray __pyx_mstate_global->__pyx_n_s_ascontiguousarray +#define __pyx_n_s_asfortranarray __pyx_mstate_global->__pyx_n_s_asfortranarray +#define __pyx_n_s_asyncio_coroutines __pyx_mstate_global->__pyx_n_s_asyncio_coroutines +#define __pyx_kp_u_at_stage __pyx_mstate_global->__pyx_kp_u_at_stage +#define __pyx_n_s_base __pyx_mstate_global->__pyx_n_s_base +#define __pyx_n_s_c __pyx_mstate_global->__pyx_n_s_c +#define __pyx_n_u_c __pyx_mstate_global->__pyx_n_u_c +#define __pyx_n_s_class __pyx_mstate_global->__pyx_n_s_class +#define __pyx_n_s_class_getitem __pyx_mstate_global->__pyx_n_s_class_getitem +#define __pyx_n_s_cline_in_traceback __pyx_mstate_global->__pyx_n_s_cline_in_traceback +#define __pyx_n_s_collections __pyx_mstate_global->__pyx_n_s_collections +#define __pyx_kp_s_collections_abc __pyx_mstate_global->__pyx_kp_s_collections_abc +#define __pyx_n_s_constraints_fields __pyx_mstate_global->__pyx_n_s_constraints_fields +#define __pyx_n_s_constraints_set __pyx_mstate_global->__pyx_n_s_constraints_set +#define __pyx_kp_u_constraints_set_value_must_be_nu __pyx_mstate_global->__pyx_kp_u_constraints_set_value_must_be_nu +#define __pyx_kp_s_contiguous_and_direct __pyx_mstate_global->__pyx_kp_s_contiguous_and_direct +#define __pyx_kp_s_contiguous_and_indirect __pyx_mstate_global->__pyx_kp_s_contiguous_and_indirect +#define __pyx_n_s_cost_fields __pyx_mstate_global->__pyx_n_s_cost_fields +#define __pyx_n_s_cost_set __pyx_mstate_global->__pyx_n_s_cost_set +#define __pyx_kp_u_cost_set_value_must_be_numpy_arr __pyx_mstate_global->__pyx_kp_u_cost_set_value_must_be_numpy_arr +#define __pyx_n_s_count __pyx_mstate_global->__pyx_n_s_count +#define __pyx_n_s_custom_update __pyx_mstate_global->__pyx_n_s_custom_update +#define __pyx_n_u_d __pyx_mstate_global->__pyx_n_u_d +#define __pyx_n_s_data __pyx_mstate_global->__pyx_n_s_data +#define __pyx_n_s_data_2 __pyx_mstate_global->__pyx_n_s_data_2 +#define __pyx_n_s_data_len __pyx_mstate_global->__pyx_n_s_data_len +#define __pyx_n_s_datetime __pyx_mstate_global->__pyx_n_s_datetime +#define __pyx_n_s_default __pyx_mstate_global->__pyx_n_s_default +#define __pyx_n_s_dict __pyx_mstate_global->__pyx_n_s_dict +#define __pyx_n_s_dims __pyx_mstate_global->__pyx_n_s_dims +#define __pyx_kp_u_disable __pyx_mstate_global->__pyx_kp_u_disable +#define __pyx_n_s_double_fields __pyx_mstate_global->__pyx_n_s_double_fields +#define __pyx_n_s_double_value __pyx_mstate_global->__pyx_n_s_double_value +#define __pyx_n_s_dtype __pyx_mstate_global->__pyx_n_s_dtype +#define __pyx_n_s_dtype_is_object __pyx_mstate_global->__pyx_n_s_dtype_is_object +#define __pyx_n_s_dump __pyx_mstate_global->__pyx_n_s_dump +#define __pyx_kp_u_enable __pyx_mstate_global->__pyx_kp_u_enable +#define __pyx_n_s_encode __pyx_mstate_global->__pyx_n_s_encode +#define __pyx_n_s_enter __pyx_mstate_global->__pyx_n_s_enter +#define __pyx_n_s_enumerate __pyx_mstate_global->__pyx_n_s_enumerate +#define __pyx_n_u_eps_sufficient_descent __pyx_mstate_global->__pyx_n_u_eps_sufficient_descent +#define __pyx_n_s_error __pyx_mstate_global->__pyx_n_s_error +#define __pyx_n_s_eval_param_sens __pyx_mstate_global->__pyx_n_s_eval_param_sens +#define __pyx_n_u_ex __pyx_mstate_global->__pyx_n_u_ex +#define __pyx_n_s_exit __pyx_mstate_global->__pyx_n_s_exit +#define __pyx_n_s_f __pyx_mstate_global->__pyx_n_s_f +#define __pyx_n_s_field __pyx_mstate_global->__pyx_n_s_field +#define __pyx_n_s_field_2 __pyx_mstate_global->__pyx_n_s_field_2 +#define __pyx_n_s_fields __pyx_mstate_global->__pyx_n_s_fields +#define __pyx_n_s_filename __pyx_mstate_global->__pyx_n_s_filename +#define __pyx_n_s_flags __pyx_mstate_global->__pyx_n_s_flags +#define __pyx_n_s_float64 __pyx_mstate_global->__pyx_n_s_float64 +#define __pyx_kp_u_for_field __pyx_mstate_global->__pyx_kp_u_for_field +#define __pyx_n_s_format __pyx_mstate_global->__pyx_n_s_format +#define __pyx_n_s_fortran __pyx_mstate_global->__pyx_n_s_fortran +#define __pyx_n_u_fortran __pyx_mstate_global->__pyx_n_u_fortran +#define __pyx_n_s_full_stats __pyx_mstate_global->__pyx_n_s_full_stats +#define __pyx_n_u_full_step_dual __pyx_mstate_global->__pyx_n_u_full_step_dual +#define __pyx_kp_u_gc __pyx_mstate_global->__pyx_kp_u_gc +#define __pyx_n_s_get __pyx_mstate_global->__pyx_n_s_get +#define __pyx_n_s_get_cost __pyx_mstate_global->__pyx_n_s_get_cost +#define __pyx_n_s_get_from_qp_in __pyx_mstate_global->__pyx_n_s_get_from_qp_in +#define __pyx_n_s_get_pointers_solver __pyx_mstate_global->__pyx_n_s_get_pointers_solver +#define __pyx_n_s_get_residuals __pyx_mstate_global->__pyx_n_s_get_residuals +#define __pyx_n_s_get_stat_double __pyx_mstate_global->__pyx_n_s_get_stat_double +#define __pyx_n_s_get_stat_int __pyx_mstate_global->__pyx_n_s_get_stat_int +#define __pyx_n_s_get_stat_matrix __pyx_mstate_global->__pyx_n_s_get_stat_matrix +#define __pyx_n_s_get_stats __pyx_mstate_global->__pyx_n_s_get_stats +#define __pyx_n_s_getcwd __pyx_mstate_global->__pyx_n_s_getcwd +#define __pyx_n_s_getstate __pyx_mstate_global->__pyx_n_s_getstate +#define __pyx_n_u_globalization __pyx_mstate_global->__pyx_n_u_globalization +#define __pyx_n_u_globalization_use_SOC __pyx_mstate_global->__pyx_n_u_globalization_use_SOC +#define __pyx_kp_u_got __pyx_mstate_global->__pyx_kp_u_got +#define __pyx_kp_u_got_differing_extents_in_dimensi __pyx_mstate_global->__pyx_kp_u_got_differing_extents_in_dimensi +#define __pyx_n_s_i __pyx_mstate_global->__pyx_n_s_i +#define __pyx_n_s_i_string __pyx_mstate_global->__pyx_n_s_i_string +#define __pyx_n_s_id __pyx_mstate_global->__pyx_n_s_id +#define __pyx_n_s_idx __pyx_mstate_global->__pyx_n_s_idx +#define __pyx_n_s_idx_values __pyx_mstate_global->__pyx_n_s_idx_values +#define __pyx_n_s_import __pyx_mstate_global->__pyx_n_s_import +#define __pyx_n_s_indent __pyx_mstate_global->__pyx_n_s_indent +#define __pyx_n_s_index __pyx_mstate_global->__pyx_n_s_index +#define __pyx_n_u_initialize_t_slacks __pyx_mstate_global->__pyx_n_u_initialize_t_slacks +#define __pyx_n_s_initializing __pyx_mstate_global->__pyx_n_s_initializing +#define __pyx_n_s_int __pyx_mstate_global->__pyx_n_s_int +#define __pyx_n_s_int32 __pyx_mstate_global->__pyx_n_s_int32 +#define __pyx_n_s_int_fields __pyx_mstate_global->__pyx_n_s_int_fields +#define __pyx_n_s_int_value __pyx_mstate_global->__pyx_n_s_int_value +#define __pyx_n_s_is_coroutine __pyx_mstate_global->__pyx_n_s_is_coroutine +#define __pyx_kp_u_isenabled __pyx_mstate_global->__pyx_kp_u_isenabled +#define __pyx_n_s_isfile __pyx_mstate_global->__pyx_n_s_isfile +#define __pyx_n_s_itemsize __pyx_mstate_global->__pyx_n_s_itemsize +#define __pyx_kp_s_itemsize_0_for_cython_array __pyx_mstate_global->__pyx_kp_s_itemsize_0_for_cython_array +#define __pyx_n_u_iterate __pyx_mstate_global->__pyx_n_u_iterate +#define __pyx_n_s_join __pyx_mstate_global->__pyx_n_s_join +#define __pyx_n_s_json __pyx_mstate_global->__pyx_n_s_json +#define __pyx_kp_u_json_2 __pyx_mstate_global->__pyx_kp_u_json_2 +#define __pyx_n_s_k __pyx_mstate_global->__pyx_n_s_k +#define __pyx_n_s_key __pyx_mstate_global->__pyx_n_s_key +#define __pyx_n_s_keys __pyx_mstate_global->__pyx_n_s_keys +#define __pyx_n_s_lN __pyx_mstate_global->__pyx_n_s_lN +#define __pyx_n_u_lam __pyx_mstate_global->__pyx_n_u_lam +#define __pyx_n_u_lam_2 __pyx_mstate_global->__pyx_n_u_lam_2 +#define __pyx_n_u_lbu __pyx_mstate_global->__pyx_n_u_lbu +#define __pyx_n_u_lbx __pyx_mstate_global->__pyx_n_u_lbx +#define __pyx_n_u_line_search_use_sufficient_desce __pyx_mstate_global->__pyx_n_u_line_search_use_sufficient_desce +#define __pyx_n_s_load __pyx_mstate_global->__pyx_n_s_load +#define __pyx_n_s_load_iterate __pyx_mstate_global->__pyx_n_s_load_iterate +#define __pyx_kp_u_load_iterate_failed_file_does_no __pyx_mstate_global->__pyx_kp_u_load_iterate_failed_file_does_no +#define __pyx_n_s_m __pyx_mstate_global->__pyx_n_s_m +#define __pyx_n_s_main __pyx_mstate_global->__pyx_n_s_main +#define __pyx_n_s_mem_fields __pyx_mstate_global->__pyx_n_s_mem_fields +#define __pyx_n_s_memview __pyx_mstate_global->__pyx_n_s_memview +#define __pyx_n_s_min_size __pyx_mstate_global->__pyx_n_s_min_size +#define __pyx_n_s_mode __pyx_mstate_global->__pyx_n_s_mode +#define __pyx_n_s_model_name __pyx_mstate_global->__pyx_n_s_model_name +#define __pyx_n_s_msg __pyx_mstate_global->__pyx_n_s_msg +#define __pyx_n_s_n __pyx_mstate_global->__pyx_n_s_n +#define __pyx_n_s_n_update __pyx_mstate_global->__pyx_n_s_n_update +#define __pyx_n_s_name __pyx_mstate_global->__pyx_n_s_name +#define __pyx_n_s_name_2 __pyx_mstate_global->__pyx_n_s_name_2 +#define __pyx_n_s_ndarray __pyx_mstate_global->__pyx_n_s_ndarray +#define __pyx_n_s_ndim __pyx_mstate_global->__pyx_n_s_ndim +#define __pyx_n_s_new __pyx_mstate_global->__pyx_n_s_new +#define __pyx_n_s_new_time_steps __pyx_mstate_global->__pyx_n_s_new_time_steps +#define __pyx_n_s_nlp_solver_type __pyx_mstate_global->__pyx_n_s_nlp_solver_type +#define __pyx_kp_s_no_default___reduce___due_to_non __pyx_mstate_global->__pyx_kp_s_no_default___reduce___due_to_non +#define __pyx_n_s_np __pyx_mstate_global->__pyx_n_s_np +#define __pyx_n_s_numpy __pyx_mstate_global->__pyx_n_s_numpy +#define __pyx_kp_u_numpy_core_multiarray_failed_to __pyx_mstate_global->__pyx_kp_u_numpy_core_multiarray_failed_to +#define __pyx_kp_u_numpy_core_umath_failed_to_impor __pyx_mstate_global->__pyx_kp_u_numpy_core_umath_failed_to_impor +#define __pyx_n_s_nx __pyx_mstate_global->__pyx_n_s_nx +#define __pyx_n_s_obj __pyx_mstate_global->__pyx_n_s_obj +#define __pyx_n_s_open __pyx_mstate_global->__pyx_n_s_open +#define __pyx_n_s_options_set __pyx_mstate_global->__pyx_n_s_options_set +#define __pyx_n_s_order __pyx_mstate_global->__pyx_n_s_order +#define __pyx_n_s_os __pyx_mstate_global->__pyx_n_s_os +#define __pyx_n_s_out __pyx_mstate_global->__pyx_n_s_out +#define __pyx_n_s_out_fields __pyx_mstate_global->__pyx_n_s_out_fields +#define __pyx_n_s_out_mat __pyx_mstate_global->__pyx_n_s_out_mat +#define __pyx_n_s_overwrite __pyx_mstate_global->__pyx_n_s_overwrite +#define __pyx_n_u_p __pyx_mstate_global->__pyx_n_u_p +#define __pyx_n_s_pack __pyx_mstate_global->__pyx_n_s_pack +#define __pyx_n_s_param_values __pyx_mstate_global->__pyx_n_s_param_values +#define __pyx_kp_u_param_values_2 __pyx_mstate_global->__pyx_kp_u_param_values_2 +#define __pyx_kp_u_param_values__and_idx_values__mu __pyx_mstate_global->__pyx_kp_u_param_values__and_idx_values__mu +#define __pyx_kp_u_param_values__must_be_np_array __pyx_mstate_global->__pyx_kp_u_param_values__must_be_np_array +#define __pyx_n_s_path __pyx_mstate_global->__pyx_n_s_path +#define __pyx_n_u_pi __pyx_mstate_global->__pyx_n_u_pi +#define __pyx_n_u_pi_2 __pyx_mstate_global->__pyx_n_u_pi_2 +#define __pyx_n_s_pickle __pyx_mstate_global->__pyx_n_s_pickle +#define __pyx_n_s_print __pyx_mstate_global->__pyx_n_s_print +#define __pyx_n_u_print_level __pyx_mstate_global->__pyx_n_u_print_level +#define __pyx_n_s_print_statistics __pyx_mstate_global->__pyx_n_s_print_statistics +#define __pyx_n_s_pyx_PickleError __pyx_mstate_global->__pyx_n_s_pyx_PickleError +#define __pyx_n_s_pyx_checksum __pyx_mstate_global->__pyx_n_s_pyx_checksum +#define __pyx_n_s_pyx_result __pyx_mstate_global->__pyx_n_s_pyx_result +#define __pyx_n_s_pyx_state __pyx_mstate_global->__pyx_n_s_pyx_state +#define __pyx_n_s_pyx_type __pyx_mstate_global->__pyx_n_s_pyx_type +#define __pyx_n_s_pyx_unpickle_Enum __pyx_mstate_global->__pyx_n_s_pyx_unpickle_Enum +#define __pyx_n_s_pyx_vtable __pyx_mstate_global->__pyx_n_s_pyx_vtable +#define __pyx_n_u_qp_iter __pyx_mstate_global->__pyx_n_u_qp_iter +#define __pyx_n_u_qp_mu0 __pyx_mstate_global->__pyx_n_u_qp_mu0 +#define __pyx_n_s_qp_solver_cond_N __pyx_mstate_global->__pyx_n_s_qp_solver_cond_N +#define __pyx_n_u_qp_tau_min __pyx_mstate_global->__pyx_n_u_qp_tau_min +#define __pyx_n_u_qp_tol_comp __pyx_mstate_global->__pyx_n_u_qp_tol_comp +#define __pyx_n_u_qp_tol_eq __pyx_mstate_global->__pyx_n_u_qp_tol_eq +#define __pyx_n_u_qp_tol_ineq __pyx_mstate_global->__pyx_n_u_qp_tol_ineq +#define __pyx_n_u_qp_tol_stat __pyx_mstate_global->__pyx_n_u_qp_tol_stat +#define __pyx_n_u_qp_warm_start __pyx_mstate_global->__pyx_n_u_qp_warm_start +#define __pyx_n_u_r __pyx_mstate_global->__pyx_n_u_r +#define __pyx_n_s_range __pyx_mstate_global->__pyx_n_s_range +#define __pyx_n_s_recompute __pyx_mstate_global->__pyx_n_s_recompute +#define __pyx_n_s_reduce __pyx_mstate_global->__pyx_n_s_reduce +#define __pyx_n_s_reduce_cython __pyx_mstate_global->__pyx_n_s_reduce_cython +#define __pyx_n_s_reduce_ex __pyx_mstate_global->__pyx_n_s_reduce_ex +#define __pyx_n_s_register __pyx_mstate_global->__pyx_n_s_register +#define __pyx_n_b_res_comp __pyx_mstate_global->__pyx_n_b_res_comp +#define __pyx_n_b_res_eq __pyx_mstate_global->__pyx_n_b_res_eq +#define __pyx_n_b_res_ineq __pyx_mstate_global->__pyx_n_b_res_ineq +#define __pyx_n_b_res_stat __pyx_mstate_global->__pyx_n_b_res_stat +#define __pyx_n_s_reset __pyx_mstate_global->__pyx_n_s_reset +#define __pyx_n_s_reset_qp_solver_mem __pyx_mstate_global->__pyx_n_s_reset_qp_solver_mem +#define __pyx_n_u_residuals __pyx_mstate_global->__pyx_n_u_residuals +#define __pyx_n_u_rti_phase __pyx_mstate_global->__pyx_n_u_rti_phase +#define __pyx_n_s_self __pyx_mstate_global->__pyx_n_s_self +#define __pyx_n_s_set __pyx_mstate_global->__pyx_n_s_set +#define __pyx_n_s_set_new_time_steps __pyx_mstate_global->__pyx_n_s_set_new_time_steps +#define __pyx_n_s_set_params_sparse __pyx_mstate_global->__pyx_n_s_set_params_sparse +#define __pyx_kp_u_set_value_must_be_numpy_array_go __pyx_mstate_global->__pyx_kp_u_set_value_must_be_numpy_array_go +#define __pyx_n_s_setstate __pyx_mstate_global->__pyx_n_s_setstate +#define __pyx_n_s_setstate_cython __pyx_mstate_global->__pyx_n_s_setstate_cython +#define __pyx_n_s_shape __pyx_mstate_global->__pyx_n_s_shape +#define __pyx_n_s_size __pyx_mstate_global->__pyx_n_s_size +#define __pyx_n_u_sl __pyx_mstate_global->__pyx_n_u_sl +#define __pyx_n_u_sl_2 __pyx_mstate_global->__pyx_n_u_sl_2 +#define __pyx_n_s_solution __pyx_mstate_global->__pyx_n_s_solution +#define __pyx_n_s_solve __pyx_mstate_global->__pyx_n_s_solve +#define __pyx_n_s_solve_for_x0 __pyx_mstate_global->__pyx_n_s_solve_for_x0 +#define __pyx_kp_u_solver_option_must_be_of_type_fl __pyx_mstate_global->__pyx_kp_u_solver_option_must_be_of_type_fl +#define __pyx_kp_u_solver_option_must_be_of_type_in __pyx_mstate_global->__pyx_kp_u_solver_option_must_be_of_type_in +#define __pyx_kp_u_solver_option_must_be_of_type_st __pyx_mstate_global->__pyx_kp_u_solver_option_must_be_of_type_st +#define __pyx_n_s_sort_keys __pyx_mstate_global->__pyx_n_s_sort_keys +#define __pyx_n_s_spec __pyx_mstate_global->__pyx_n_s_spec +#define __pyx_n_s_split __pyx_mstate_global->__pyx_n_s_split +#define __pyx_n_s_sqp_iter __pyx_mstate_global->__pyx_n_s_sqp_iter +#define __pyx_n_u_sqp_iter __pyx_mstate_global->__pyx_n_u_sqp_iter +#define __pyx_n_s_stage __pyx_mstate_global->__pyx_n_s_stage +#define __pyx_n_s_start __pyx_mstate_global->__pyx_n_s_start +#define __pyx_n_s_stat_m __pyx_mstate_global->__pyx_n_s_stat_m +#define __pyx_n_u_stat_m __pyx_mstate_global->__pyx_n_u_stat_m +#define __pyx_n_s_stat_n __pyx_mstate_global->__pyx_n_s_stat_n +#define __pyx_n_u_stat_n __pyx_mstate_global->__pyx_n_u_stat_n +#define __pyx_n_u_statistics __pyx_mstate_global->__pyx_n_u_statistics +#define __pyx_n_s_status __pyx_mstate_global->__pyx_n_s_status +#define __pyx_n_s_step __pyx_mstate_global->__pyx_n_s_step +#define __pyx_n_u_step_length __pyx_mstate_global->__pyx_n_u_step_length +#define __pyx_n_s_stop __pyx_mstate_global->__pyx_n_s_stop +#define __pyx_n_s_store_iterate __pyx_mstate_global->__pyx_n_s_store_iterate +#define __pyx_n_s_store_iterate_locals_lambda __pyx_mstate_global->__pyx_n_s_store_iterate_locals_lambda +#define __pyx_kp_u_stored_current_iterate_in __pyx_mstate_global->__pyx_kp_u_stored_current_iterate_in +#define __pyx_n_s_strftime __pyx_mstate_global->__pyx_n_s_strftime +#define __pyx_kp_s_strided_and_direct __pyx_mstate_global->__pyx_kp_s_strided_and_direct +#define __pyx_kp_s_strided_and_direct_or_indirect __pyx_mstate_global->__pyx_kp_s_strided_and_direct_or_indirect +#define __pyx_kp_s_strided_and_indirect __pyx_mstate_global->__pyx_kp_s_strided_and_indirect +#define __pyx_n_s_string_fields __pyx_mstate_global->__pyx_n_s_string_fields +#define __pyx_n_s_string_value __pyx_mstate_global->__pyx_n_s_string_value +#define __pyx_kp_s_stringsource __pyx_mstate_global->__pyx_kp_s_stringsource +#define __pyx_n_s_struct __pyx_mstate_global->__pyx_n_s_struct +#define __pyx_n_u_su __pyx_mstate_global->__pyx_n_u_su +#define __pyx_n_u_su_2 __pyx_mstate_global->__pyx_n_u_su_2 +#define __pyx_n_s_sys __pyx_mstate_global->__pyx_n_s_sys +#define __pyx_n_u_t __pyx_mstate_global->__pyx_n_u_t +#define __pyx_n_u_t_2 __pyx_mstate_global->__pyx_n_u_t_2 +#define __pyx_n_s_test __pyx_mstate_global->__pyx_n_s_test +#define __pyx_kp_s_third_party_acados_acados_templa __pyx_mstate_global->__pyx_kp_s_third_party_acados_acados_templa +#define __pyx_n_u_time_glob __pyx_mstate_global->__pyx_n_u_time_glob +#define __pyx_n_u_time_lin __pyx_mstate_global->__pyx_n_u_time_lin +#define __pyx_n_u_time_qp __pyx_mstate_global->__pyx_n_u_time_qp +#define __pyx_n_u_time_qp_solver_call __pyx_mstate_global->__pyx_n_u_time_qp_solver_call +#define __pyx_n_u_time_qp_xcond __pyx_mstate_global->__pyx_n_u_time_qp_xcond +#define __pyx_n_u_time_reg __pyx_mstate_global->__pyx_n_u_time_reg +#define __pyx_n_u_time_sim __pyx_mstate_global->__pyx_n_u_time_sim +#define __pyx_n_u_time_sim_ad __pyx_mstate_global->__pyx_n_u_time_sim_ad +#define __pyx_n_u_time_sim_la __pyx_mstate_global->__pyx_n_u_time_sim_la +#define __pyx_n_u_time_solution_sensitivities __pyx_mstate_global->__pyx_n_u_time_solution_sensitivities +#define __pyx_n_u_time_tot __pyx_mstate_global->__pyx_n_u_time_tot +#define __pyx_n_u_tol_comp __pyx_mstate_global->__pyx_n_u_tol_comp +#define __pyx_n_u_tol_eq __pyx_mstate_global->__pyx_n_u_tol_eq +#define __pyx_n_u_tol_ineq __pyx_mstate_global->__pyx_n_u_tol_ineq +#define __pyx_n_u_tol_stat __pyx_mstate_global->__pyx_n_u_tol_stat +#define __pyx_n_s_tolist __pyx_mstate_global->__pyx_n_s_tolist +#define __pyx_n_u_u __pyx_mstate_global->__pyx_n_u_u +#define __pyx_n_s_u0 __pyx_mstate_global->__pyx_n_s_u0 +#define __pyx_n_u_u_2 __pyx_mstate_global->__pyx_n_u_u_2 +#define __pyx_n_u_ubu __pyx_mstate_global->__pyx_n_u_ubu +#define __pyx_n_u_ubx __pyx_mstate_global->__pyx_n_u_ubx +#define __pyx_kp_s_unable_to_allocate_array_data __pyx_mstate_global->__pyx_kp_s_unable_to_allocate_array_data +#define __pyx_kp_s_unable_to_allocate_shape_and_str __pyx_mstate_global->__pyx_kp_s_unable_to_allocate_shape_and_str +#define __pyx_n_s_unpack __pyx_mstate_global->__pyx_n_s_unpack +#define __pyx_n_s_update __pyx_mstate_global->__pyx_n_s_update +#define __pyx_n_s_update_qp_solver_cond_N __pyx_mstate_global->__pyx_n_s_update_qp_solver_cond_N +#define __pyx_n_s_utcnow __pyx_mstate_global->__pyx_n_s_utcnow +#define __pyx_kp_u_utf_8 __pyx_mstate_global->__pyx_kp_u_utf_8 +#define __pyx_n_s_value __pyx_mstate_global->__pyx_n_s_value +#define __pyx_n_s_value_2 __pyx_mstate_global->__pyx_n_s_value_2 +#define __pyx_n_s_value_shape __pyx_mstate_global->__pyx_n_s_value_shape +#define __pyx_n_s_version_info __pyx_mstate_global->__pyx_n_s_version_info +#define __pyx_n_u_w __pyx_mstate_global->__pyx_n_u_w +#define __pyx_n_u_warm_start_first_qp __pyx_mstate_global->__pyx_n_u_warm_start_first_qp +#define __pyx_kp_u_with_dimension __pyx_mstate_global->__pyx_kp_u_with_dimension +#define __pyx_kp_u_with_dimension_you_have __pyx_mstate_global->__pyx_kp_u_with_dimension_you_have +#define __pyx_n_b_x __pyx_mstate_global->__pyx_n_b_x +#define __pyx_n_s_x __pyx_mstate_global->__pyx_n_s_x +#define __pyx_n_u_x __pyx_mstate_global->__pyx_n_u_x +#define __pyx_n_s_x0_bar __pyx_mstate_global->__pyx_n_s_x0_bar +#define __pyx_n_u_x_2 __pyx_mstate_global->__pyx_n_u_x_2 +#define __pyx_n_u_xdot_guess __pyx_mstate_global->__pyx_n_u_xdot_guess +#define __pyx_n_u_y_ref __pyx_mstate_global->__pyx_n_u_y_ref +#define __pyx_kp_u_you_have __pyx_mstate_global->__pyx_kp_u_you_have +#define __pyx_n_u_yref __pyx_mstate_global->__pyx_n_u_yref +#define __pyx_n_u_z __pyx_mstate_global->__pyx_n_u_z +#define __pyx_n_u_z_2 __pyx_mstate_global->__pyx_n_u_z_2 +#define __pyx_n_b_z_guess __pyx_mstate_global->__pyx_n_b_z_guess +#define __pyx_n_u_z_guess __pyx_mstate_global->__pyx_n_u_z_guess +#define __pyx_n_s_zeros __pyx_mstate_global->__pyx_n_s_zeros +#define __pyx_int_0 __pyx_mstate_global->__pyx_int_0 +#define __pyx_int_1 __pyx_mstate_global->__pyx_int_1 +#define __pyx_int_2 __pyx_mstate_global->__pyx_int_2 +#define __pyx_int_3 __pyx_mstate_global->__pyx_int_3 +#define __pyx_int_4 __pyx_mstate_global->__pyx_int_4 +#define __pyx_int_6 __pyx_mstate_global->__pyx_int_6 +#define __pyx_int_7 __pyx_mstate_global->__pyx_int_7 +#define __pyx_int_112105877 __pyx_mstate_global->__pyx_int_112105877 +#define __pyx_int_136983863 __pyx_mstate_global->__pyx_int_136983863 +#define __pyx_int_184977713 __pyx_mstate_global->__pyx_int_184977713 +#define __pyx_int_neg_1 __pyx_mstate_global->__pyx_int_neg_1 +#define __pyx_int_neg_5 __pyx_mstate_global->__pyx_int_neg_5 +#define __pyx_slice__5 __pyx_mstate_global->__pyx_slice__5 +#define __pyx_tuple__4 __pyx_mstate_global->__pyx_tuple__4 +#define __pyx_tuple__8 __pyx_mstate_global->__pyx_tuple__8 +#define __pyx_tuple__9 __pyx_mstate_global->__pyx_tuple__9 +#define __pyx_slice__18 __pyx_mstate_global->__pyx_slice__18 +#define __pyx_tuple__10 __pyx_mstate_global->__pyx_tuple__10 +#define __pyx_tuple__11 __pyx_mstate_global->__pyx_tuple__11 +#define __pyx_tuple__12 __pyx_mstate_global->__pyx_tuple__12 +#define __pyx_tuple__13 __pyx_mstate_global->__pyx_tuple__13 +#define __pyx_tuple__14 __pyx_mstate_global->__pyx_tuple__14 +#define __pyx_tuple__15 __pyx_mstate_global->__pyx_tuple__15 +#define __pyx_tuple__19 __pyx_mstate_global->__pyx_tuple__19 +#define __pyx_tuple__20 __pyx_mstate_global->__pyx_tuple__20 +#define __pyx_tuple__21 __pyx_mstate_global->__pyx_tuple__21 +#define __pyx_tuple__22 __pyx_mstate_global->__pyx_tuple__22 +#define __pyx_tuple__23 __pyx_mstate_global->__pyx_tuple__23 +#define __pyx_tuple__24 __pyx_mstate_global->__pyx_tuple__24 +#define __pyx_tuple__25 __pyx_mstate_global->__pyx_tuple__25 +#define __pyx_tuple__26 __pyx_mstate_global->__pyx_tuple__26 +#define __pyx_tuple__27 __pyx_mstate_global->__pyx_tuple__27 +#define __pyx_tuple__28 __pyx_mstate_global->__pyx_tuple__28 +#define __pyx_tuple__29 __pyx_mstate_global->__pyx_tuple__29 +#define __pyx_tuple__30 __pyx_mstate_global->__pyx_tuple__30 +#define __pyx_tuple__32 __pyx_mstate_global->__pyx_tuple__32 +#define __pyx_tuple__33 __pyx_mstate_global->__pyx_tuple__33 +#define __pyx_tuple__34 __pyx_mstate_global->__pyx_tuple__34 +#define __pyx_tuple__35 __pyx_mstate_global->__pyx_tuple__35 +#define __pyx_tuple__36 __pyx_mstate_global->__pyx_tuple__36 +#define __pyx_tuple__37 __pyx_mstate_global->__pyx_tuple__37 +#define __pyx_tuple__38 __pyx_mstate_global->__pyx_tuple__38 +#define __pyx_tuple__39 __pyx_mstate_global->__pyx_tuple__39 +#define __pyx_tuple__40 __pyx_mstate_global->__pyx_tuple__40 +#define __pyx_tuple__41 __pyx_mstate_global->__pyx_tuple__41 +#define __pyx_tuple__42 __pyx_mstate_global->__pyx_tuple__42 +#define __pyx_tuple__44 __pyx_mstate_global->__pyx_tuple__44 +#define __pyx_tuple__46 __pyx_mstate_global->__pyx_tuple__46 +#define __pyx_tuple__49 __pyx_mstate_global->__pyx_tuple__49 +#define __pyx_tuple__51 __pyx_mstate_global->__pyx_tuple__51 +#define __pyx_tuple__53 __pyx_mstate_global->__pyx_tuple__53 +#define __pyx_tuple__55 __pyx_mstate_global->__pyx_tuple__55 +#define __pyx_tuple__57 __pyx_mstate_global->__pyx_tuple__57 +#define __pyx_tuple__59 __pyx_mstate_global->__pyx_tuple__59 +#define __pyx_tuple__60 __pyx_mstate_global->__pyx_tuple__60 +#define __pyx_tuple__63 __pyx_mstate_global->__pyx_tuple__63 +#define __pyx_tuple__65 __pyx_mstate_global->__pyx_tuple__65 +#define __pyx_tuple__66 __pyx_mstate_global->__pyx_tuple__66 +#define __pyx_tuple__68 __pyx_mstate_global->__pyx_tuple__68 +#define __pyx_tuple__70 __pyx_mstate_global->__pyx_tuple__70 +#define __pyx_tuple__73 __pyx_mstate_global->__pyx_tuple__73 +#define __pyx_tuple__75 __pyx_mstate_global->__pyx_tuple__75 +#define __pyx_tuple__77 __pyx_mstate_global->__pyx_tuple__77 +#define __pyx_tuple__79 __pyx_mstate_global->__pyx_tuple__79 +#define __pyx_tuple__80 __pyx_mstate_global->__pyx_tuple__80 +#define __pyx_tuple__82 __pyx_mstate_global->__pyx_tuple__82 +#define __pyx_tuple__85 __pyx_mstate_global->__pyx_tuple__85 +#define __pyx_tuple__87 __pyx_mstate_global->__pyx_tuple__87 +#define __pyx_tuple__89 __pyx_mstate_global->__pyx_tuple__89 +#define __pyx_tuple__92 __pyx_mstate_global->__pyx_tuple__92 +#define __pyx_codeobj__43 __pyx_mstate_global->__pyx_codeobj__43 +#define __pyx_codeobj__45 __pyx_mstate_global->__pyx_codeobj__45 +#define __pyx_codeobj__47 __pyx_mstate_global->__pyx_codeobj__47 +#define __pyx_codeobj__48 __pyx_mstate_global->__pyx_codeobj__48 +#define __pyx_codeobj__50 __pyx_mstate_global->__pyx_codeobj__50 +#define __pyx_codeobj__52 __pyx_mstate_global->__pyx_codeobj__52 +#define __pyx_codeobj__54 __pyx_mstate_global->__pyx_codeobj__54 +#define __pyx_codeobj__56 __pyx_mstate_global->__pyx_codeobj__56 +#define __pyx_codeobj__58 __pyx_mstate_global->__pyx_codeobj__58 +#define __pyx_codeobj__61 __pyx_mstate_global->__pyx_codeobj__61 +#define __pyx_codeobj__62 __pyx_mstate_global->__pyx_codeobj__62 +#define __pyx_codeobj__64 __pyx_mstate_global->__pyx_codeobj__64 +#define __pyx_codeobj__67 __pyx_mstate_global->__pyx_codeobj__67 +#define __pyx_codeobj__69 __pyx_mstate_global->__pyx_codeobj__69 +#define __pyx_codeobj__71 __pyx_mstate_global->__pyx_codeobj__71 +#define __pyx_codeobj__72 __pyx_mstate_global->__pyx_codeobj__72 +#define __pyx_codeobj__74 __pyx_mstate_global->__pyx_codeobj__74 +#define __pyx_codeobj__76 __pyx_mstate_global->__pyx_codeobj__76 +#define __pyx_codeobj__78 __pyx_mstate_global->__pyx_codeobj__78 +#define __pyx_codeobj__81 __pyx_mstate_global->__pyx_codeobj__81 +#define __pyx_codeobj__83 __pyx_mstate_global->__pyx_codeobj__83 +#define __pyx_codeobj__84 __pyx_mstate_global->__pyx_codeobj__84 +#define __pyx_codeobj__86 __pyx_mstate_global->__pyx_codeobj__86 +#define __pyx_codeobj__88 __pyx_mstate_global->__pyx_codeobj__88 +#define __pyx_codeobj__90 __pyx_mstate_global->__pyx_codeobj__90 +#define __pyx_codeobj__91 __pyx_mstate_global->__pyx_codeobj__91 +#define __pyx_codeobj__93 __pyx_mstate_global->__pyx_codeobj__93 +/* #### Code section: module_code ### */ + +/* "carray.to_py":114 + * + * @cname("__Pyx_carray_to_py_int") + * cdef inline list __Pyx_carray_to_py_int(base_type *v, Py_ssize_t length): # <<<<<<<<<<<<<< + * cdef size_t i + * cdef object value + */ + +static CYTHON_INLINE PyObject *__Pyx_carray_to_py_int(int *__pyx_v_v, Py_ssize_t __pyx_v_length) { + size_t __pyx_v_i; + PyObject *__pyx_v_value = 0; + PyObject *__pyx_v_l = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + size_t __pyx_t_2; + size_t __pyx_t_3; + size_t __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_carray_to_py_int", 1); + + /* "carray.to_py":117 + * cdef size_t i + * cdef object value + * l = PyList_New(length) # <<<<<<<<<<<<<< + * for i in range(length): + * value = v[i] + */ + __pyx_t_1 = PyList_New(__pyx_v_length); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 117, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_l = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "carray.to_py":118 + * cdef object value + * l = PyList_New(length) + * for i in range(length): # <<<<<<<<<<<<<< + * value = v[i] + * Py_INCREF(value) + */ + __pyx_t_2 = ((size_t)__pyx_v_length); + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "carray.to_py":119 + * l = PyList_New(length) + * for i in range(length): + * value = v[i] # <<<<<<<<<<<<<< + * Py_INCREF(value) + * PyList_SET_ITEM(l, i, value) + */ + __pyx_t_1 = __Pyx_PyInt_From_int((__pyx_v_v[__pyx_v_i])); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 119, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_XDECREF_SET(__pyx_v_value, __pyx_t_1); + __pyx_t_1 = 0; + + /* "carray.to_py":120 + * for i in range(length): + * value = v[i] + * Py_INCREF(value) # <<<<<<<<<<<<<< + * PyList_SET_ITEM(l, i, value) + * return l + */ + Py_INCREF(__pyx_v_value); + + /* "carray.to_py":121 + * value = v[i] + * Py_INCREF(value) + * PyList_SET_ITEM(l, i, value) # <<<<<<<<<<<<<< + * return l + * + */ + PyList_SET_ITEM(__pyx_v_l, __pyx_v_i, __pyx_v_value); + } + + /* "carray.to_py":122 + * Py_INCREF(value) + * PyList_SET_ITEM(l, i, value) + * return l # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_l); + __pyx_r = __pyx_v_l; + goto __pyx_L0; + + /* "carray.to_py":114 + * + * @cname("__Pyx_carray_to_py_int") + * cdef inline list __Pyx_carray_to_py_int(base_type *v, Py_ssize_t length): # <<<<<<<<<<<<<< + * cdef size_t i + * cdef object value + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("carray.to_py.__Pyx_carray_to_py_int", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_value); + __Pyx_XDECREF(__pyx_v_l); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "carray.to_py":126 + * + * @cname("__Pyx_carray_to_tuple_int") + * cdef inline tuple __Pyx_carray_to_tuple_int(base_type *v, Py_ssize_t length): # <<<<<<<<<<<<<< + * cdef size_t i + * cdef object value + */ + +static CYTHON_INLINE PyObject *__Pyx_carray_to_tuple_int(int *__pyx_v_v, Py_ssize_t __pyx_v_length) { + size_t __pyx_v_i; + PyObject *__pyx_v_value = 0; + PyObject *__pyx_v_t = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + size_t __pyx_t_2; + size_t __pyx_t_3; + size_t __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_carray_to_tuple_int", 1); + + /* "carray.to_py":129 + * cdef size_t i + * cdef object value + * t = PyTuple_New(length) # <<<<<<<<<<<<<< + * for i in range(length): + * value = v[i] + */ + __pyx_t_1 = PyTuple_New(__pyx_v_length); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 129, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_t = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "carray.to_py":130 + * cdef object value + * t = PyTuple_New(length) + * for i in range(length): # <<<<<<<<<<<<<< + * value = v[i] + * Py_INCREF(value) + */ + __pyx_t_2 = ((size_t)__pyx_v_length); + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "carray.to_py":131 + * t = PyTuple_New(length) + * for i in range(length): + * value = v[i] # <<<<<<<<<<<<<< + * Py_INCREF(value) + * PyTuple_SET_ITEM(t, i, value) + */ + __pyx_t_1 = __Pyx_PyInt_From_int((__pyx_v_v[__pyx_v_i])); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 131, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_XDECREF_SET(__pyx_v_value, __pyx_t_1); + __pyx_t_1 = 0; + + /* "carray.to_py":132 + * for i in range(length): + * value = v[i] + * Py_INCREF(value) # <<<<<<<<<<<<<< + * PyTuple_SET_ITEM(t, i, value) + * return t + */ + Py_INCREF(__pyx_v_value); + + /* "carray.to_py":133 + * value = v[i] + * Py_INCREF(value) + * PyTuple_SET_ITEM(t, i, value) # <<<<<<<<<<<<<< + * return t + */ + PyTuple_SET_ITEM(__pyx_v_t, __pyx_v_i, __pyx_v_value); + } + + /* "carray.to_py":134 + * Py_INCREF(value) + * PyTuple_SET_ITEM(t, i, value) + * return t # <<<<<<<<<<<<<< + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_t); + __pyx_r = __pyx_v_t; + goto __pyx_L0; + + /* "carray.to_py":126 + * + * @cname("__Pyx_carray_to_tuple_int") + * cdef inline tuple __Pyx_carray_to_tuple_int(base_type *v, Py_ssize_t length): # <<<<<<<<<<<<<< + * cdef size_t i + * cdef object value + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("carray.to_py.__Pyx_carray_to_tuple_int", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_value); + __Pyx_XDECREF(__pyx_v_t); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":131 + * cdef bint dtype_is_object + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, # <<<<<<<<<<<<<< + * mode="c", bint allocate_buffer=True): + * + */ + +/* Python wrapper */ +static int __pyx_array___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_array___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_shape = 0; + Py_ssize_t __pyx_v_itemsize; + PyObject *__pyx_v_format = 0; + PyObject *__pyx_v_mode = 0; + int __pyx_v_allocate_buffer; + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[5] = {0,0,0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_shape,&__pyx_n_s_itemsize,&__pyx_n_s_format,&__pyx_n_s_mode,&__pyx_n_s_allocate_buffer,0}; + values[3] = __Pyx_Arg_NewRef_VARARGS(((PyObject *)__pyx_n_s_c)); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 5: values[4] = __Pyx_Arg_VARARGS(__pyx_args, 4); + CYTHON_FALLTHROUGH; + case 4: values[3] = __Pyx_Arg_VARARGS(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_shape)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_itemsize)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 3, 5, 1); __PYX_ERR(1, 131, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_format)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 3, 5, 2); __PYX_ERR(1, 131, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 3: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_mode); + if (value) { values[3] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 4: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_allocate_buffer); + if (value) { values[4] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(1, 131, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 5: values[4] = __Pyx_Arg_VARARGS(__pyx_args, 4); + CYTHON_FALLTHROUGH; + case 4: values[3] = __Pyx_Arg_VARARGS(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_shape = ((PyObject*)values[0]); + __pyx_v_itemsize = __Pyx_PyIndex_AsSsize_t(values[1]); if (unlikely((__pyx_v_itemsize == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 131, __pyx_L3_error) + __pyx_v_format = values[2]; + __pyx_v_mode = values[3]; + if (values[4]) { + __pyx_v_allocate_buffer = __Pyx_PyObject_IsTrue(values[4]); if (unlikely((__pyx_v_allocate_buffer == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 132, __pyx_L3_error) + } else { + + /* "View.MemoryView":132 + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, + * mode="c", bint allocate_buffer=True): # <<<<<<<<<<<<<< + * + * cdef int idx + */ + __pyx_v_allocate_buffer = ((int)1); + } + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 3, 5, __pyx_nargs); __PYX_ERR(1, 131, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.array.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_shape), (&PyTuple_Type), 1, "shape", 1))) __PYX_ERR(1, 131, __pyx_L1_error) + if (unlikely(((PyObject *)__pyx_v_format) == Py_None)) { + PyErr_Format(PyExc_TypeError, "Argument '%.200s' must not be None", "format"); __PYX_ERR(1, 131, __pyx_L1_error) + } + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array___cinit__(((struct __pyx_array_obj *)__pyx_v_self), __pyx_v_shape, __pyx_v_itemsize, __pyx_v_format, __pyx_v_mode, __pyx_v_allocate_buffer); + + /* "View.MemoryView":131 + * cdef bint dtype_is_object + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, # <<<<<<<<<<<<<< + * mode="c", bint allocate_buffer=True): + * + */ + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = -1; + __pyx_L0:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array___cinit__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_shape, Py_ssize_t __pyx_v_itemsize, PyObject *__pyx_v_format, PyObject *__pyx_v_mode, int __pyx_v_allocate_buffer) { + int __pyx_v_idx; + Py_ssize_t __pyx_v_dim; + char __pyx_v_order; + int __pyx_r; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + int __pyx_t_7; + char *__pyx_t_8; + Py_ssize_t __pyx_t_9; + Py_UCS4 __pyx_t_10; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__cinit__", 0); + __Pyx_INCREF(__pyx_v_format); + + /* "View.MemoryView":137 + * cdef Py_ssize_t dim + * + * self.ndim = len(shape) # <<<<<<<<<<<<<< + * self.itemsize = itemsize + * + */ + if (unlikely(__pyx_v_shape == Py_None)) { + PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); + __PYX_ERR(1, 137, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_PyTuple_GET_SIZE(__pyx_v_shape); if (unlikely(__pyx_t_1 == ((Py_ssize_t)-1))) __PYX_ERR(1, 137, __pyx_L1_error) + __pyx_v_self->ndim = ((int)__pyx_t_1); + + /* "View.MemoryView":138 + * + * self.ndim = len(shape) + * self.itemsize = itemsize # <<<<<<<<<<<<<< + * + * if not self.ndim: + */ + __pyx_v_self->itemsize = __pyx_v_itemsize; + + /* "View.MemoryView":140 + * self.itemsize = itemsize + * + * if not self.ndim: # <<<<<<<<<<<<<< + * raise ValueError, "Empty shape tuple for cython.array" + * + */ + __pyx_t_2 = (!(__pyx_v_self->ndim != 0)); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":141 + * + * if not self.ndim: + * raise ValueError, "Empty shape tuple for cython.array" # <<<<<<<<<<<<<< + * + * if itemsize <= 0: + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Empty_shape_tuple_for_cython_arr, 0, 0); + __PYX_ERR(1, 141, __pyx_L1_error) + + /* "View.MemoryView":140 + * self.itemsize = itemsize + * + * if not self.ndim: # <<<<<<<<<<<<<< + * raise ValueError, "Empty shape tuple for cython.array" + * + */ + } + + /* "View.MemoryView":143 + * raise ValueError, "Empty shape tuple for cython.array" + * + * if itemsize <= 0: # <<<<<<<<<<<<<< + * raise ValueError, "itemsize <= 0 for cython.array" + * + */ + __pyx_t_2 = (__pyx_v_itemsize <= 0); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":144 + * + * if itemsize <= 0: + * raise ValueError, "itemsize <= 0 for cython.array" # <<<<<<<<<<<<<< + * + * if not isinstance(format, bytes): + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_itemsize_0_for_cython_array, 0, 0); + __PYX_ERR(1, 144, __pyx_L1_error) + + /* "View.MemoryView":143 + * raise ValueError, "Empty shape tuple for cython.array" + * + * if itemsize <= 0: # <<<<<<<<<<<<<< + * raise ValueError, "itemsize <= 0 for cython.array" + * + */ + } + + /* "View.MemoryView":146 + * raise ValueError, "itemsize <= 0 for cython.array" + * + * if not isinstance(format, bytes): # <<<<<<<<<<<<<< + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string + */ + __pyx_t_2 = PyBytes_Check(__pyx_v_format); + __pyx_t_3 = (!__pyx_t_2); + if (__pyx_t_3) { + + /* "View.MemoryView":147 + * + * if not isinstance(format, bytes): + * format = format.encode('ASCII') # <<<<<<<<<<<<<< + * self._format = format # keep a reference to the byte string + * self.format = self._format + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_format, __pyx_n_s_encode); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 147, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = NULL; + __pyx_t_7 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_6 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_6)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_6); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_7 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_6, __pyx_n_s_ASCII}; + __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_7, 1+__pyx_t_7); + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 147, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + __Pyx_DECREF_SET(__pyx_v_format, __pyx_t_4); + __pyx_t_4 = 0; + + /* "View.MemoryView":146 + * raise ValueError, "itemsize <= 0 for cython.array" + * + * if not isinstance(format, bytes): # <<<<<<<<<<<<<< + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string + */ + } + + /* "View.MemoryView":148 + * if not isinstance(format, bytes): + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string # <<<<<<<<<<<<<< + * self.format = self._format + * + */ + if (!(likely(PyBytes_CheckExact(__pyx_v_format))||((__pyx_v_format) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_v_format))) __PYX_ERR(1, 148, __pyx_L1_error) + __pyx_t_4 = __pyx_v_format; + __Pyx_INCREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + __Pyx_GOTREF(__pyx_v_self->_format); + __Pyx_DECREF(__pyx_v_self->_format); + __pyx_v_self->_format = ((PyObject*)__pyx_t_4); + __pyx_t_4 = 0; + + /* "View.MemoryView":149 + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string + * self.format = self._format # <<<<<<<<<<<<<< + * + * + */ + if (unlikely(__pyx_v_self->_format == Py_None)) { + PyErr_SetString(PyExc_TypeError, "expected bytes, NoneType found"); + __PYX_ERR(1, 149, __pyx_L1_error) + } + __pyx_t_8 = __Pyx_PyBytes_AsWritableString(__pyx_v_self->_format); if (unlikely((!__pyx_t_8) && PyErr_Occurred())) __PYX_ERR(1, 149, __pyx_L1_error) + __pyx_v_self->format = __pyx_t_8; + + /* "View.MemoryView":152 + * + * + * self._shape = PyObject_Malloc(sizeof(Py_ssize_t)*self.ndim*2) # <<<<<<<<<<<<<< + * self._strides = self._shape + self.ndim + * + */ + __pyx_v_self->_shape = ((Py_ssize_t *)PyObject_Malloc((((sizeof(Py_ssize_t)) * __pyx_v_self->ndim) * 2))); + + /* "View.MemoryView":153 + * + * self._shape = PyObject_Malloc(sizeof(Py_ssize_t)*self.ndim*2) + * self._strides = self._shape + self.ndim # <<<<<<<<<<<<<< + * + * if not self._shape: + */ + __pyx_v_self->_strides = (__pyx_v_self->_shape + __pyx_v_self->ndim); + + /* "View.MemoryView":155 + * self._strides = self._shape + self.ndim + * + * if not self._shape: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate shape and strides." + * + */ + __pyx_t_3 = (!(__pyx_v_self->_shape != 0)); + if (unlikely(__pyx_t_3)) { + + /* "View.MemoryView":156 + * + * if not self._shape: + * raise MemoryError, "unable to allocate shape and strides." # <<<<<<<<<<<<<< + * + * + */ + __Pyx_Raise(__pyx_builtin_MemoryError, __pyx_kp_s_unable_to_allocate_shape_and_str, 0, 0); + __PYX_ERR(1, 156, __pyx_L1_error) + + /* "View.MemoryView":155 + * self._strides = self._shape + self.ndim + * + * if not self._shape: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate shape and strides." + * + */ + } + + /* "View.MemoryView":159 + * + * + * for idx, dim in enumerate(shape): # <<<<<<<<<<<<<< + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + */ + __pyx_t_7 = 0; + __pyx_t_4 = __pyx_v_shape; __Pyx_INCREF(__pyx_t_4); + __pyx_t_1 = 0; + for (;;) { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_4); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 159, __pyx_L1_error) + #endif + if (__pyx_t_1 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_5 = PyTuple_GET_ITEM(__pyx_t_4, __pyx_t_1); __Pyx_INCREF(__pyx_t_5); __pyx_t_1++; if (unlikely((0 < 0))) __PYX_ERR(1, 159, __pyx_L1_error) + #else + __pyx_t_5 = __Pyx_PySequence_ITEM(__pyx_t_4, __pyx_t_1); __pyx_t_1++; if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 159, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + #endif + __pyx_t_9 = __Pyx_PyIndex_AsSsize_t(__pyx_t_5); if (unlikely((__pyx_t_9 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 159, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_v_dim = __pyx_t_9; + __pyx_v_idx = __pyx_t_7; + __pyx_t_7 = (__pyx_t_7 + 1); + + /* "View.MemoryView":160 + * + * for idx, dim in enumerate(shape): + * if dim <= 0: # <<<<<<<<<<<<<< + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + * self._shape[idx] = dim + */ + __pyx_t_3 = (__pyx_v_dim <= 0); + if (unlikely(__pyx_t_3)) { + + /* "View.MemoryView":161 + * for idx, dim in enumerate(shape): + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." # <<<<<<<<<<<<<< + * self._shape[idx] = dim + * + */ + __pyx_t_5 = PyTuple_New(5); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_9 = 0; + __pyx_t_10 = 127; + __Pyx_INCREF(__pyx_kp_u_Invalid_shape_in_axis); + __pyx_t_9 += 22; + __Pyx_GIVEREF(__pyx_kp_u_Invalid_shape_in_axis); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_kp_u_Invalid_shape_in_axis); + __pyx_t_6 = __Pyx_PyUnicode_From_int(__pyx_v_idx, 0, ' ', 'd'); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_9 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_6); + __Pyx_GIVEREF(__pyx_t_6); + PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_6); + __pyx_t_6 = 0; + __Pyx_INCREF(__pyx_kp_u_); + __pyx_t_9 += 2; + __Pyx_GIVEREF(__pyx_kp_u_); + PyTuple_SET_ITEM(__pyx_t_5, 2, __pyx_kp_u_); + __pyx_t_6 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_dim, 0, ' ', 'd'); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_9 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_6); + __Pyx_GIVEREF(__pyx_t_6); + PyTuple_SET_ITEM(__pyx_t_5, 3, __pyx_t_6); + __pyx_t_6 = 0; + __Pyx_INCREF(__pyx_kp_u__2); + __pyx_t_9 += 1; + __Pyx_GIVEREF(__pyx_kp_u__2); + PyTuple_SET_ITEM(__pyx_t_5, 4, __pyx_kp_u__2); + __pyx_t_6 = __Pyx_PyUnicode_Join(__pyx_t_5, 5, __pyx_t_9, __pyx_t_10); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_t_6, 0, 0); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __PYX_ERR(1, 161, __pyx_L1_error) + + /* "View.MemoryView":160 + * + * for idx, dim in enumerate(shape): + * if dim <= 0: # <<<<<<<<<<<<<< + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + * self._shape[idx] = dim + */ + } + + /* "View.MemoryView":162 + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + * self._shape[idx] = dim # <<<<<<<<<<<<<< + * + * cdef char order + */ + (__pyx_v_self->_shape[__pyx_v_idx]) = __pyx_v_dim; + + /* "View.MemoryView":159 + * + * + * for idx, dim in enumerate(shape): # <<<<<<<<<<<<<< + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + */ + } + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "View.MemoryView":165 + * + * cdef char order + * if mode == 'c': # <<<<<<<<<<<<<< + * order = b'C' + * self.mode = u'c' + */ + __pyx_t_3 = (__Pyx_PyString_Equals(__pyx_v_mode, __pyx_n_s_c, Py_EQ)); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(1, 165, __pyx_L1_error) + if (__pyx_t_3) { + + /* "View.MemoryView":166 + * cdef char order + * if mode == 'c': + * order = b'C' # <<<<<<<<<<<<<< + * self.mode = u'c' + * elif mode == 'fortran': + */ + __pyx_v_order = 'C'; + + /* "View.MemoryView":167 + * if mode == 'c': + * order = b'C' + * self.mode = u'c' # <<<<<<<<<<<<<< + * elif mode == 'fortran': + * order = b'F' + */ + __Pyx_INCREF(__pyx_n_u_c); + __Pyx_GIVEREF(__pyx_n_u_c); + __Pyx_GOTREF(__pyx_v_self->mode); + __Pyx_DECREF(__pyx_v_self->mode); + __pyx_v_self->mode = __pyx_n_u_c; + + /* "View.MemoryView":165 + * + * cdef char order + * if mode == 'c': # <<<<<<<<<<<<<< + * order = b'C' + * self.mode = u'c' + */ + goto __pyx_L11; + } + + /* "View.MemoryView":168 + * order = b'C' + * self.mode = u'c' + * elif mode == 'fortran': # <<<<<<<<<<<<<< + * order = b'F' + * self.mode = u'fortran' + */ + __pyx_t_3 = (__Pyx_PyString_Equals(__pyx_v_mode, __pyx_n_s_fortran, Py_EQ)); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(1, 168, __pyx_L1_error) + if (likely(__pyx_t_3)) { + + /* "View.MemoryView":169 + * self.mode = u'c' + * elif mode == 'fortran': + * order = b'F' # <<<<<<<<<<<<<< + * self.mode = u'fortran' + * else: + */ + __pyx_v_order = 'F'; + + /* "View.MemoryView":170 + * elif mode == 'fortran': + * order = b'F' + * self.mode = u'fortran' # <<<<<<<<<<<<<< + * else: + * raise ValueError, f"Invalid mode, expected 'c' or 'fortran', got {mode}" + */ + __Pyx_INCREF(__pyx_n_u_fortran); + __Pyx_GIVEREF(__pyx_n_u_fortran); + __Pyx_GOTREF(__pyx_v_self->mode); + __Pyx_DECREF(__pyx_v_self->mode); + __pyx_v_self->mode = __pyx_n_u_fortran; + + /* "View.MemoryView":168 + * order = b'C' + * self.mode = u'c' + * elif mode == 'fortran': # <<<<<<<<<<<<<< + * order = b'F' + * self.mode = u'fortran' + */ + goto __pyx_L11; + } + + /* "View.MemoryView":172 + * self.mode = u'fortran' + * else: + * raise ValueError, f"Invalid mode, expected 'c' or 'fortran', got {mode}" # <<<<<<<<<<<<<< + * + * self.len = fill_contig_strides_array(self._shape, self._strides, itemsize, self.ndim, order) + */ + /*else*/ { + __pyx_t_4 = __Pyx_PyObject_FormatSimple(__pyx_v_mode, __pyx_empty_unicode); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 172, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_6 = __Pyx_PyUnicode_Concat(__pyx_kp_u_Invalid_mode_expected_c_or_fortr, __pyx_t_4); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 172, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_t_6, 0, 0); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __PYX_ERR(1, 172, __pyx_L1_error) + } + __pyx_L11:; + + /* "View.MemoryView":174 + * raise ValueError, f"Invalid mode, expected 'c' or 'fortran', got {mode}" + * + * self.len = fill_contig_strides_array(self._shape, self._strides, itemsize, self.ndim, order) # <<<<<<<<<<<<<< + * + * self.free_data = allocate_buffer + */ + __pyx_v_self->len = __pyx_fill_contig_strides_array(__pyx_v_self->_shape, __pyx_v_self->_strides, __pyx_v_itemsize, __pyx_v_self->ndim, __pyx_v_order); + + /* "View.MemoryView":176 + * self.len = fill_contig_strides_array(self._shape, self._strides, itemsize, self.ndim, order) + * + * self.free_data = allocate_buffer # <<<<<<<<<<<<<< + * self.dtype_is_object = format == b'O' + * + */ + __pyx_v_self->free_data = __pyx_v_allocate_buffer; + + /* "View.MemoryView":177 + * + * self.free_data = allocate_buffer + * self.dtype_is_object = format == b'O' # <<<<<<<<<<<<<< + * + * if allocate_buffer: + */ + __pyx_t_6 = PyObject_RichCompare(__pyx_v_format, __pyx_n_b_O, Py_EQ); __Pyx_XGOTREF(__pyx_t_6); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 177, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_IsTrue(__pyx_t_6); if (unlikely((__pyx_t_3 == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 177, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __pyx_v_self->dtype_is_object = __pyx_t_3; + + /* "View.MemoryView":179 + * self.dtype_is_object = format == b'O' + * + * if allocate_buffer: # <<<<<<<<<<<<<< + * _allocate_buffer(self) + * + */ + if (__pyx_v_allocate_buffer) { + + /* "View.MemoryView":180 + * + * if allocate_buffer: + * _allocate_buffer(self) # <<<<<<<<<<<<<< + * + * @cname('getbuffer') + */ + __pyx_t_7 = __pyx_array_allocate_buffer(__pyx_v_self); if (unlikely(__pyx_t_7 == ((int)-1))) __PYX_ERR(1, 180, __pyx_L1_error) + + /* "View.MemoryView":179 + * self.dtype_is_object = format == b'O' + * + * if allocate_buffer: # <<<<<<<<<<<<<< + * _allocate_buffer(self) + * + */ + } + + /* "View.MemoryView":131 + * cdef bint dtype_is_object + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, # <<<<<<<<<<<<<< + * mode="c", bint allocate_buffer=True): + * + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("View.MemoryView.array.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_format); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":182 + * _allocate_buffer(self) + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + */ + +/* Python wrapper */ +CYTHON_UNUSED static int __pyx_array_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +CYTHON_UNUSED static int __pyx_array_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getbuffer__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_2__getbuffer__(((struct __pyx_array_obj *)__pyx_v_self), ((Py_buffer *)__pyx_v_info), ((int)__pyx_v_flags)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_2__getbuffer__(struct __pyx_array_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + int __pyx_v_bufmode; + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + char *__pyx_t_2; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + Py_ssize_t *__pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + if (unlikely(__pyx_v_info == NULL)) { + PyErr_SetString(PyExc_BufferError, "PyObject_GetBuffer: view==NULL argument is obsolete"); + return -1; + } + __Pyx_RefNannySetupContext("__getbuffer__", 0); + __pyx_v_info->obj = Py_None; __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(__pyx_v_info->obj); + + /* "View.MemoryView":184 + * @cname('getbuffer') + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 # <<<<<<<<<<<<<< + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": + */ + __pyx_v_bufmode = -1; + + /* "View.MemoryView":185 + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): # <<<<<<<<<<<<<< + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + */ + __pyx_t_1 = ((__pyx_v_flags & ((PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS) | PyBUF_ANY_CONTIGUOUS)) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":186 + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": # <<<<<<<<<<<<<< + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": + */ + __pyx_t_1 = (__Pyx_PyUnicode_Equals(__pyx_v_self->mode, __pyx_n_u_c, Py_EQ)); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 186, __pyx_L1_error) + if (__pyx_t_1) { + + /* "View.MemoryView":187 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS # <<<<<<<<<<<<<< + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + */ + __pyx_v_bufmode = (PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS); + + /* "View.MemoryView":186 + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": # <<<<<<<<<<<<<< + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": + */ + goto __pyx_L4; + } + + /* "View.MemoryView":188 + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": # <<<<<<<<<<<<<< + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): + */ + __pyx_t_1 = (__Pyx_PyUnicode_Equals(__pyx_v_self->mode, __pyx_n_u_fortran, Py_EQ)); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 188, __pyx_L1_error) + if (__pyx_t_1) { + + /* "View.MemoryView":189 + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS # <<<<<<<<<<<<<< + * if not (flags & bufmode): + * raise ValueError, "Can only create a buffer that is contiguous in memory." + */ + __pyx_v_bufmode = (PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS); + + /* "View.MemoryView":188 + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": # <<<<<<<<<<<<<< + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): + */ + } + __pyx_L4:; + + /* "View.MemoryView":190 + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): # <<<<<<<<<<<<<< + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data + */ + __pyx_t_1 = (!((__pyx_v_flags & __pyx_v_bufmode) != 0)); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":191 + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): + * raise ValueError, "Can only create a buffer that is contiguous in memory." # <<<<<<<<<<<<<< + * info.buf = self.data + * info.len = self.len + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Can_only_create_a_buffer_that_is, 0, 0); + __PYX_ERR(1, 191, __pyx_L1_error) + + /* "View.MemoryView":190 + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): # <<<<<<<<<<<<<< + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data + */ + } + + /* "View.MemoryView":185 + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): # <<<<<<<<<<<<<< + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + */ + } + + /* "View.MemoryView":192 + * if not (flags & bufmode): + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data # <<<<<<<<<<<<<< + * info.len = self.len + * + */ + __pyx_t_2 = __pyx_v_self->data; + __pyx_v_info->buf = __pyx_t_2; + + /* "View.MemoryView":193 + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data + * info.len = self.len # <<<<<<<<<<<<<< + * + * if flags & PyBUF_STRIDES: + */ + __pyx_t_3 = __pyx_v_self->len; + __pyx_v_info->len = __pyx_t_3; + + /* "View.MemoryView":195 + * info.len = self.len + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.ndim = self.ndim + * info.shape = self._shape + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_STRIDES) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":196 + * + * if flags & PyBUF_STRIDES: + * info.ndim = self.ndim # <<<<<<<<<<<<<< + * info.shape = self._shape + * info.strides = self._strides + */ + __pyx_t_4 = __pyx_v_self->ndim; + __pyx_v_info->ndim = __pyx_t_4; + + /* "View.MemoryView":197 + * if flags & PyBUF_STRIDES: + * info.ndim = self.ndim + * info.shape = self._shape # <<<<<<<<<<<<<< + * info.strides = self._strides + * else: + */ + __pyx_t_5 = __pyx_v_self->_shape; + __pyx_v_info->shape = __pyx_t_5; + + /* "View.MemoryView":198 + * info.ndim = self.ndim + * info.shape = self._shape + * info.strides = self._strides # <<<<<<<<<<<<<< + * else: + * info.ndim = 1 + */ + __pyx_t_5 = __pyx_v_self->_strides; + __pyx_v_info->strides = __pyx_t_5; + + /* "View.MemoryView":195 + * info.len = self.len + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.ndim = self.ndim + * info.shape = self._shape + */ + goto __pyx_L6; + } + + /* "View.MemoryView":200 + * info.strides = self._strides + * else: + * info.ndim = 1 # <<<<<<<<<<<<<< + * info.shape = &self.len if flags & PyBUF_ND else NULL + * info.strides = NULL + */ + /*else*/ { + __pyx_v_info->ndim = 1; + + /* "View.MemoryView":201 + * else: + * info.ndim = 1 + * info.shape = &self.len if flags & PyBUF_ND else NULL # <<<<<<<<<<<<<< + * info.strides = NULL + * + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_ND) != 0); + if (__pyx_t_1) { + __pyx_t_5 = (&__pyx_v_self->len); + } else { + __pyx_t_5 = NULL; + } + __pyx_v_info->shape = __pyx_t_5; + + /* "View.MemoryView":202 + * info.ndim = 1 + * info.shape = &self.len if flags & PyBUF_ND else NULL + * info.strides = NULL # <<<<<<<<<<<<<< + * + * info.suboffsets = NULL + */ + __pyx_v_info->strides = NULL; + } + __pyx_L6:; + + /* "View.MemoryView":204 + * info.strides = NULL + * + * info.suboffsets = NULL # <<<<<<<<<<<<<< + * info.itemsize = self.itemsize + * info.readonly = 0 + */ + __pyx_v_info->suboffsets = NULL; + + /* "View.MemoryView":205 + * + * info.suboffsets = NULL + * info.itemsize = self.itemsize # <<<<<<<<<<<<<< + * info.readonly = 0 + * info.format = self.format if flags & PyBUF_FORMAT else NULL + */ + __pyx_t_3 = __pyx_v_self->itemsize; + __pyx_v_info->itemsize = __pyx_t_3; + + /* "View.MemoryView":206 + * info.suboffsets = NULL + * info.itemsize = self.itemsize + * info.readonly = 0 # <<<<<<<<<<<<<< + * info.format = self.format if flags & PyBUF_FORMAT else NULL + * info.obj = self + */ + __pyx_v_info->readonly = 0; + + /* "View.MemoryView":207 + * info.itemsize = self.itemsize + * info.readonly = 0 + * info.format = self.format if flags & PyBUF_FORMAT else NULL # <<<<<<<<<<<<<< + * info.obj = self + * + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_FORMAT) != 0); + if (__pyx_t_1) { + __pyx_t_2 = __pyx_v_self->format; + } else { + __pyx_t_2 = NULL; + } + __pyx_v_info->format = __pyx_t_2; + + /* "View.MemoryView":208 + * info.readonly = 0 + * info.format = self.format if flags & PyBUF_FORMAT else NULL + * info.obj = self # <<<<<<<<<<<<<< + * + * def __dealloc__(array self): + */ + __Pyx_INCREF((PyObject *)__pyx_v_self); + __Pyx_GIVEREF((PyObject *)__pyx_v_self); + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); + __pyx_v_info->obj = ((PyObject *)__pyx_v_self); + + /* "View.MemoryView":182 + * _allocate_buffer(self) + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.array.__getbuffer__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + if (__pyx_v_info->obj != NULL) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + goto __pyx_L2; + __pyx_L0:; + if (__pyx_v_info->obj == Py_None) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + __pyx_L2:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":210 + * info.obj = self + * + * def __dealloc__(array self): # <<<<<<<<<<<<<< + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + */ + +/* Python wrapper */ +static void __pyx_array___dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_array___dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_array___pyx_pf_15View_dot_MemoryView_5array_4__dealloc__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_array___pyx_pf_15View_dot_MemoryView_5array_4__dealloc__(struct __pyx_array_obj *__pyx_v_self) { + int __pyx_t_1; + int __pyx_t_2; + + /* "View.MemoryView":211 + * + * def __dealloc__(array self): + * if self.callback_free_data != NULL: # <<<<<<<<<<<<<< + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + */ + __pyx_t_1 = (__pyx_v_self->callback_free_data != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":212 + * def __dealloc__(array self): + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) # <<<<<<<<<<<<<< + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: + */ + __pyx_v_self->callback_free_data(__pyx_v_self->data); + + /* "View.MemoryView":211 + * + * def __dealloc__(array self): + * if self.callback_free_data != NULL: # <<<<<<<<<<<<<< + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":213 + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: # <<<<<<<<<<<<<< + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + */ + if (__pyx_v_self->free_data) { + } else { + __pyx_t_1 = __pyx_v_self->free_data; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_2 = (__pyx_v_self->data != NULL); + __pyx_t_1 = __pyx_t_2; + __pyx_L4_bool_binop_done:; + if (__pyx_t_1) { + + /* "View.MemoryView":214 + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) + */ + if (__pyx_v_self->dtype_is_object) { + + /* "View.MemoryView":215 + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) # <<<<<<<<<<<<<< + * free(self.data) + * PyObject_Free(self._shape) + */ + __pyx_memoryview_refcount_objects_in_slice(__pyx_v_self->data, __pyx_v_self->_shape, __pyx_v_self->_strides, __pyx_v_self->ndim, 0); + + /* "View.MemoryView":214 + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) + */ + } + + /* "View.MemoryView":216 + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) # <<<<<<<<<<<<<< + * PyObject_Free(self._shape) + * + */ + free(__pyx_v_self->data); + + /* "View.MemoryView":213 + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: # <<<<<<<<<<<<<< + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + */ + } + __pyx_L3:; + + /* "View.MemoryView":217 + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) + * PyObject_Free(self._shape) # <<<<<<<<<<<<<< + * + * @property + */ + PyObject_Free(__pyx_v_self->_shape); + + /* "View.MemoryView":210 + * info.obj = self + * + * def __dealloc__(array self): # <<<<<<<<<<<<<< + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + */ + + /* function exit code */ +} + +/* "View.MemoryView":219 + * PyObject_Free(self._shape) + * + * @property # <<<<<<<<<<<<<< + * def memview(self): + * return self.get_memview() + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_5array_7memview_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_5array_7memview_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_5array_7memview___get__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_5array_7memview___get__(struct __pyx_array_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":221 + * @property + * def memview(self): + * return self.get_memview() # <<<<<<<<<<<<<< + * + * @cname('get_memview') + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = ((struct __pyx_vtabstruct_array *)__pyx_v_self->__pyx_vtab)->get_memview(__pyx_v_self); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 221, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":219 + * PyObject_Free(self._shape) + * + * @property # <<<<<<<<<<<<<< + * def memview(self): + * return self.get_memview() + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.array.memview.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":224 + * + * @cname('get_memview') + * cdef get_memview(self): # <<<<<<<<<<<<<< + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE + * return memoryview(self, flags, self.dtype_is_object) + */ + +static PyObject *__pyx_array_get_memview(struct __pyx_array_obj *__pyx_v_self) { + int __pyx_v_flags; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_memview", 1); + + /* "View.MemoryView":225 + * @cname('get_memview') + * cdef get_memview(self): + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE # <<<<<<<<<<<<<< + * return memoryview(self, flags, self.dtype_is_object) + * + */ + __pyx_v_flags = ((PyBUF_ANY_CONTIGUOUS | PyBUF_FORMAT) | PyBUF_WRITABLE); + + /* "View.MemoryView":226 + * cdef get_memview(self): + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE + * return memoryview(self, flags, self.dtype_is_object) # <<<<<<<<<<<<<< + * + * def __len__(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_flags); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_v_self->dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF((PyObject *)__pyx_v_self); + __Pyx_GIVEREF((PyObject *)__pyx_v_self); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, ((PyObject *)__pyx_v_self))) __PYX_ERR(1, 226, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1)) __PYX_ERR(1, 226, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_t_2)) __PYX_ERR(1, 226, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_Call(((PyObject *)__pyx_memoryview_type), __pyx_t_3, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":224 + * + * @cname('get_memview') + * cdef get_memview(self): # <<<<<<<<<<<<<< + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE + * return memoryview(self, flags, self.dtype_is_object) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.array.get_memview", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":228 + * return memoryview(self, flags, self.dtype_is_object) + * + * def __len__(self): # <<<<<<<<<<<<<< + * return self._shape[0] + * + */ + +/* Python wrapper */ +static Py_ssize_t __pyx_array___len__(PyObject *__pyx_v_self); /*proto*/ +static Py_ssize_t __pyx_array___len__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + Py_ssize_t __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__len__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_6__len__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static Py_ssize_t __pyx_array___pyx_pf_15View_dot_MemoryView_5array_6__len__(struct __pyx_array_obj *__pyx_v_self) { + Py_ssize_t __pyx_r; + + /* "View.MemoryView":229 + * + * def __len__(self): + * return self._shape[0] # <<<<<<<<<<<<<< + * + * def __getattr__(self, attr): + */ + __pyx_r = (__pyx_v_self->_shape[0]); + goto __pyx_L0; + + /* "View.MemoryView":228 + * return memoryview(self, flags, self.dtype_is_object) + * + * def __len__(self): # <<<<<<<<<<<<<< + * return self._shape[0] + * + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":231 + * return self._shape[0] + * + * def __getattr__(self, attr): # <<<<<<<<<<<<<< + * return getattr(self.memview, attr) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_array___getattr__(PyObject *__pyx_v_self, PyObject *__pyx_v_attr); /*proto*/ +static PyObject *__pyx_array___getattr__(PyObject *__pyx_v_self, PyObject *__pyx_v_attr) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getattr__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_8__getattr__(((struct __pyx_array_obj *)__pyx_v_self), ((PyObject *)__pyx_v_attr)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_8__getattr__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_attr) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__getattr__", 1); + + /* "View.MemoryView":232 + * + * def __getattr__(self, attr): + * return getattr(self.memview, attr) # <<<<<<<<<<<<<< + * + * def __getitem__(self, item): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_memview); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 232, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_GetAttr(__pyx_t_1, __pyx_v_attr); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 232, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":231 + * return self._shape[0] + * + * def __getattr__(self, attr): # <<<<<<<<<<<<<< + * return getattr(self.memview, attr) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.array.__getattr__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":234 + * return getattr(self.memview, attr) + * + * def __getitem__(self, item): # <<<<<<<<<<<<<< + * return self.memview[item] + * + */ + +/* Python wrapper */ +static PyObject *__pyx_array___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item); /*proto*/ +static PyObject *__pyx_array___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getitem__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_10__getitem__(((struct __pyx_array_obj *)__pyx_v_self), ((PyObject *)__pyx_v_item)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_10__getitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__getitem__", 1); + + /* "View.MemoryView":235 + * + * def __getitem__(self, item): + * return self.memview[item] # <<<<<<<<<<<<<< + * + * def __setitem__(self, item, value): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_memview); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 235, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_t_1, __pyx_v_item); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 235, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":234 + * return getattr(self.memview, attr) + * + * def __getitem__(self, item): # <<<<<<<<<<<<<< + * return self.memview[item] + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.array.__getitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":237 + * return self.memview[item] + * + * def __setitem__(self, item, value): # <<<<<<<<<<<<<< + * self.memview[item] = value + * + */ + +/* Python wrapper */ +static int __pyx_array___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value); /*proto*/ +static int __pyx_array___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setitem__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_12__setitem__(((struct __pyx_array_obj *)__pyx_v_self), ((PyObject *)__pyx_v_item), ((PyObject *)__pyx_v_value)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_12__setitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setitem__", 1); + + /* "View.MemoryView":238 + * + * def __setitem__(self, item, value): + * self.memview[item] = value # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_memview); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 238, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyObject_SetItem(__pyx_t_1, __pyx_v_item, __pyx_v_value) < 0))) __PYX_ERR(1, 238, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "View.MemoryView":237 + * return self.memview[item] + * + * def __setitem__(self, item, value): # <<<<<<<<<<<<<< + * self.memview[item] = value + * + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.array.__setitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_array_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_array_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_array___reduce_cython__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_array___reduce_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.array.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_array_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_array_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.array.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_array_2__setstate_cython__(((struct __pyx_array_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_array_2__setstate_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.array.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":248 + * + * @cname("__pyx_array_allocate_buffer") + * cdef int _allocate_buffer(array self) except -1: # <<<<<<<<<<<<<< + * + * + */ + +static int __pyx_array_allocate_buffer(struct __pyx_array_obj *__pyx_v_self) { + Py_ssize_t __pyx_v_i; + PyObject **__pyx_v_p; + int __pyx_r; + int __pyx_t_1; + Py_ssize_t __pyx_t_2; + Py_ssize_t __pyx_t_3; + Py_ssize_t __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + + /* "View.MemoryView":254 + * cdef PyObject **p + * + * self.free_data = True # <<<<<<<<<<<<<< + * self.data = malloc(self.len) + * if not self.data: + */ + __pyx_v_self->free_data = 1; + + /* "View.MemoryView":255 + * + * self.free_data = True + * self.data = malloc(self.len) # <<<<<<<<<<<<<< + * if not self.data: + * raise MemoryError, "unable to allocate array data." + */ + __pyx_v_self->data = ((char *)malloc(__pyx_v_self->len)); + + /* "View.MemoryView":256 + * self.free_data = True + * self.data = malloc(self.len) + * if not self.data: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate array data." + * + */ + __pyx_t_1 = (!(__pyx_v_self->data != 0)); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":257 + * self.data = malloc(self.len) + * if not self.data: + * raise MemoryError, "unable to allocate array data." # <<<<<<<<<<<<<< + * + * if self.dtype_is_object: + */ + __Pyx_Raise(__pyx_builtin_MemoryError, __pyx_kp_s_unable_to_allocate_array_data, 0, 0); + __PYX_ERR(1, 257, __pyx_L1_error) + + /* "View.MemoryView":256 + * self.free_data = True + * self.data = malloc(self.len) + * if not self.data: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate array data." + * + */ + } + + /* "View.MemoryView":259 + * raise MemoryError, "unable to allocate array data." + * + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * p = self.data + * for i in range(self.len // self.itemsize): + */ + if (__pyx_v_self->dtype_is_object) { + + /* "View.MemoryView":260 + * + * if self.dtype_is_object: + * p = self.data # <<<<<<<<<<<<<< + * for i in range(self.len // self.itemsize): + * p[i] = Py_None + */ + __pyx_v_p = ((PyObject **)__pyx_v_self->data); + + /* "View.MemoryView":261 + * if self.dtype_is_object: + * p = self.data + * for i in range(self.len // self.itemsize): # <<<<<<<<<<<<<< + * p[i] = Py_None + * Py_INCREF(Py_None) + */ + if (unlikely(__pyx_v_self->itemsize == 0)) { + PyErr_SetString(PyExc_ZeroDivisionError, "integer division or modulo by zero"); + __PYX_ERR(1, 261, __pyx_L1_error) + } + else if (sizeof(Py_ssize_t) == sizeof(long) && (!(((Py_ssize_t)-1) > 0)) && unlikely(__pyx_v_self->itemsize == (Py_ssize_t)-1) && unlikely(__Pyx_UNARY_NEG_WOULD_OVERFLOW(__pyx_v_self->len))) { + PyErr_SetString(PyExc_OverflowError, "value too large to perform division"); + __PYX_ERR(1, 261, __pyx_L1_error) + } + __pyx_t_2 = __Pyx_div_Py_ssize_t(__pyx_v_self->len, __pyx_v_self->itemsize); + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":262 + * p = self.data + * for i in range(self.len // self.itemsize): + * p[i] = Py_None # <<<<<<<<<<<<<< + * Py_INCREF(Py_None) + * return 0 + */ + (__pyx_v_p[__pyx_v_i]) = Py_None; + + /* "View.MemoryView":263 + * for i in range(self.len // self.itemsize): + * p[i] = Py_None + * Py_INCREF(Py_None) # <<<<<<<<<<<<<< + * return 0 + * + */ + Py_INCREF(Py_None); + } + + /* "View.MemoryView":259 + * raise MemoryError, "unable to allocate array data." + * + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * p = self.data + * for i in range(self.len // self.itemsize): + */ + } + + /* "View.MemoryView":264 + * p[i] = Py_None + * Py_INCREF(Py_None) + * return 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":248 + * + * @cname("__pyx_array_allocate_buffer") + * cdef int _allocate_buffer(array self) except -1: # <<<<<<<<<<<<<< + * + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._allocate_buffer", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":268 + * + * @cname("__pyx_array_new") + * cdef array array_cwrapper(tuple shape, Py_ssize_t itemsize, char *format, char *c_mode, char *buf): # <<<<<<<<<<<<<< + * cdef array result + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + */ + +static struct __pyx_array_obj *__pyx_array_new(PyObject *__pyx_v_shape, Py_ssize_t __pyx_v_itemsize, char *__pyx_v_format, char *__pyx_v_c_mode, char *__pyx_v_buf) { + struct __pyx_array_obj *__pyx_v_result = 0; + PyObject *__pyx_v_mode = 0; + struct __pyx_array_obj *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("array_cwrapper", 1); + + /* "View.MemoryView":270 + * cdef array array_cwrapper(tuple shape, Py_ssize_t itemsize, char *format, char *c_mode, char *buf): + * cdef array result + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. # <<<<<<<<<<<<<< + * + * if buf is NULL: + */ + __pyx_t_2 = ((__pyx_v_c_mode[0]) == 'f'); + if (__pyx_t_2) { + __Pyx_INCREF(__pyx_n_s_fortran); + __pyx_t_1 = __pyx_n_s_fortran; + } else { + __Pyx_INCREF(__pyx_n_s_c); + __pyx_t_1 = __pyx_n_s_c; + } + __pyx_v_mode = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":272 + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + * + * if buf is NULL: # <<<<<<<<<<<<<< + * result = array.__new__(array, shape, itemsize, format, mode) + * else: + */ + __pyx_t_2 = (__pyx_v_buf == NULL); + if (__pyx_t_2) { + + /* "View.MemoryView":273 + * + * if buf is NULL: + * result = array.__new__(array, shape, itemsize, format, mode) # <<<<<<<<<<<<<< + * else: + * result = array.__new__(array, shape, itemsize, format, mode, allocate_buffer=False) + */ + __pyx_t_1 = PyInt_FromSsize_t(__pyx_v_itemsize); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 273, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyBytes_FromString(__pyx_v_format); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 273, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PyTuple_New(4); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 273, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_INCREF(__pyx_v_shape); + __Pyx_GIVEREF(__pyx_v_shape); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_v_shape)) __PYX_ERR(1, 273, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_t_1)) __PYX_ERR(1, 273, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 2, __pyx_t_3)) __PYX_ERR(1, 273, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_mode); + __Pyx_GIVEREF(__pyx_v_mode); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 3, __pyx_v_mode)) __PYX_ERR(1, 273, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_3 = 0; + __pyx_t_3 = ((PyObject *)__pyx_tp_new_array(((PyTypeObject *)__pyx_array_type), __pyx_t_4, NULL)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 273, __pyx_L1_error) + __Pyx_GOTREF((PyObject *)__pyx_t_3); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_v_result = ((struct __pyx_array_obj *)__pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":272 + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + * + * if buf is NULL: # <<<<<<<<<<<<<< + * result = array.__new__(array, shape, itemsize, format, mode) + * else: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":275 + * result = array.__new__(array, shape, itemsize, format, mode) + * else: + * result = array.__new__(array, shape, itemsize, format, mode, allocate_buffer=False) # <<<<<<<<<<<<<< + * result.data = buf + * + */ + /*else*/ { + __pyx_t_3 = PyInt_FromSsize_t(__pyx_v_itemsize); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = __Pyx_PyBytes_FromString(__pyx_v_format); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_1 = PyTuple_New(4); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v_shape); + __Pyx_GIVEREF(__pyx_v_shape); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v_shape)) __PYX_ERR(1, 275, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_t_3)) __PYX_ERR(1, 275, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_4); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_t_4)) __PYX_ERR(1, 275, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_mode); + __Pyx_GIVEREF(__pyx_v_mode); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 3, __pyx_v_mode)) __PYX_ERR(1, 275, __pyx_L1_error); + __pyx_t_3 = 0; + __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem(__pyx_t_4, __pyx_n_s_allocate_buffer, Py_False) < 0) __PYX_ERR(1, 275, __pyx_L1_error) + __pyx_t_3 = ((PyObject *)__pyx_tp_new_array(((PyTypeObject *)__pyx_array_type), __pyx_t_1, __pyx_t_4)); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 275, __pyx_L1_error) + __Pyx_GOTREF((PyObject *)__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_v_result = ((struct __pyx_array_obj *)__pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":276 + * else: + * result = array.__new__(array, shape, itemsize, format, mode, allocate_buffer=False) + * result.data = buf # <<<<<<<<<<<<<< + * + * return result + */ + __pyx_v_result->data = __pyx_v_buf; + } + __pyx_L3:; + + /* "View.MemoryView":278 + * result.data = buf + * + * return result # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF((PyObject *)__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = __pyx_v_result; + goto __pyx_L0; + + /* "View.MemoryView":268 + * + * @cname("__pyx_array_new") + * cdef array array_cwrapper(tuple shape, Py_ssize_t itemsize, char *format, char *c_mode, char *buf): # <<<<<<<<<<<<<< + * cdef array result + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.array_cwrapper", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XDECREF(__pyx_v_mode); + __Pyx_XGIVEREF((PyObject *)__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":304 + * cdef class Enum(object): + * cdef object name + * def __init__(self, name): # <<<<<<<<<<<<<< + * self.name = name + * def __repr__(self): + */ + +/* Python wrapper */ +static int __pyx_MemviewEnum___init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_MemviewEnum___init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_name = 0; + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__init__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_name,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_name)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 304, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__init__") < 0)) __PYX_ERR(1, 304, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + } + __pyx_v_name = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__init__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 304, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.Enum.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum___init__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self), __pyx_v_name); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum___init__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v_name) { + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__init__", 1); + + /* "View.MemoryView":305 + * cdef object name + * def __init__(self, name): + * self.name = name # <<<<<<<<<<<<<< + * def __repr__(self): + * return self.name + */ + __Pyx_INCREF(__pyx_v_name); + __Pyx_GIVEREF(__pyx_v_name); + __Pyx_GOTREF(__pyx_v_self->name); + __Pyx_DECREF(__pyx_v_self->name); + __pyx_v_self->name = __pyx_v_name; + + /* "View.MemoryView":304 + * cdef class Enum(object): + * cdef object name + * def __init__(self, name): # <<<<<<<<<<<<<< + * self.name = name + * def __repr__(self): + */ + + /* function exit code */ + __pyx_r = 0; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":306 + * def __init__(self, name): + * self.name = name + * def __repr__(self): # <<<<<<<<<<<<<< + * return self.name + * + */ + +/* Python wrapper */ +static PyObject *__pyx_MemviewEnum___repr__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_MemviewEnum___repr__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__repr__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum_2__repr__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum_2__repr__(struct __pyx_MemviewEnum_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__repr__", 1); + + /* "View.MemoryView":307 + * self.name = name + * def __repr__(self): + * return self.name # <<<<<<<<<<<<<< + * + * cdef generic = Enum("") + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->name); + __pyx_r = __pyx_v_self->name; + goto __pyx_L0; + + /* "View.MemoryView":306 + * def __init__(self, name): + * self.name = name + * def __repr__(self): # <<<<<<<<<<<<<< + * return self.name + * + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * cdef tuple state + * cdef object _dict + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_MemviewEnum_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_MemviewEnum_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_MemviewEnum___reduce_cython__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_MemviewEnum___reduce_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self) { + PyObject *__pyx_v_state = 0; + PyObject *__pyx_v__dict = 0; + int __pyx_v_use_setstate; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":5 + * cdef object _dict + * cdef bint use_setstate + * state = (self.name,) # <<<<<<<<<<<<<< + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: + */ + __pyx_t_1 = PyTuple_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v_self->name); + __Pyx_GIVEREF(__pyx_v_self->name); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v_self->name)) __PYX_ERR(1, 5, __pyx_L1_error); + __pyx_v_state = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "(tree fragment)":6 + * cdef bint use_setstate + * state = (self.name,) + * _dict = getattr(self, '__dict__', None) # <<<<<<<<<<<<<< + * if _dict is not None: + * state += (_dict,) + */ + __pyx_t_1 = __Pyx_GetAttr3(((PyObject *)__pyx_v_self), __pyx_n_s_dict, Py_None); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v__dict = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":7 + * state = (self.name,) + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: # <<<<<<<<<<<<<< + * state += (_dict,) + * use_setstate = True + */ + __pyx_t_2 = (__pyx_v__dict != Py_None); + if (__pyx_t_2) { + + /* "(tree fragment)":8 + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: + * state += (_dict,) # <<<<<<<<<<<<<< + * use_setstate = True + * else: + */ + __pyx_t_1 = PyTuple_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 8, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v__dict); + __Pyx_GIVEREF(__pyx_v__dict); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v__dict)) __PYX_ERR(1, 8, __pyx_L1_error); + __pyx_t_3 = PyNumber_InPlaceAdd(__pyx_v_state, __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 8, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF_SET(__pyx_v_state, ((PyObject*)__pyx_t_3)); + __pyx_t_3 = 0; + + /* "(tree fragment)":9 + * if _dict is not None: + * state += (_dict,) + * use_setstate = True # <<<<<<<<<<<<<< + * else: + * use_setstate = self.name is not None + */ + __pyx_v_use_setstate = 1; + + /* "(tree fragment)":7 + * state = (self.name,) + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: # <<<<<<<<<<<<<< + * state += (_dict,) + * use_setstate = True + */ + goto __pyx_L3; + } + + /* "(tree fragment)":11 + * use_setstate = True + * else: + * use_setstate = self.name is not None # <<<<<<<<<<<<<< + * if use_setstate: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + */ + /*else*/ { + __pyx_t_2 = (__pyx_v_self->name != Py_None); + __pyx_v_use_setstate = __pyx_t_2; + } + __pyx_L3:; + + /* "(tree fragment)":12 + * else: + * use_setstate = self.name is not None + * if use_setstate: # <<<<<<<<<<<<<< + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + * else: + */ + if (__pyx_v_use_setstate) { + + /* "(tree fragment)":13 + * use_setstate = self.name is not None + * if use_setstate: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state # <<<<<<<<<<<<<< + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_pyx_unpickle_Enum); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = PyTuple_New(3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_GIVEREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, ((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self))))) __PYX_ERR(1, 13, __pyx_L1_error); + __Pyx_INCREF(__pyx_int_136983863); + __Pyx_GIVEREF(__pyx_int_136983863); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_int_136983863)) __PYX_ERR(1, 13, __pyx_L1_error); + __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(Py_None); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 2, Py_None)) __PYX_ERR(1, 13, __pyx_L1_error); + __pyx_t_4 = PyTuple_New(3); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_3)) __PYX_ERR(1, 13, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_t_1)) __PYX_ERR(1, 13, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_state); + __Pyx_GIVEREF(__pyx_v_state); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 2, __pyx_v_state)) __PYX_ERR(1, 13, __pyx_L1_error); + __pyx_t_3 = 0; + __pyx_t_1 = 0; + __pyx_r = __pyx_t_4; + __pyx_t_4 = 0; + goto __pyx_L0; + + /* "(tree fragment)":12 + * else: + * use_setstate = self.name is not None + * if use_setstate: # <<<<<<<<<<<<<< + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + * else: + */ + } + + /* "(tree fragment)":15 + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * __pyx_unpickle_Enum__set_state(self, __pyx_state) + */ + /*else*/ { + __Pyx_XDECREF(__pyx_r); + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_pyx_unpickle_Enum); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_1 = PyTuple_New(3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_GIVEREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, ((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self))))) __PYX_ERR(1, 15, __pyx_L1_error); + __Pyx_INCREF(__pyx_int_136983863); + __Pyx_GIVEREF(__pyx_int_136983863); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_int_136983863)) __PYX_ERR(1, 15, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_state); + __Pyx_GIVEREF(__pyx_v_state); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_v_state)) __PYX_ERR(1, 15, __pyx_L1_error); + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_4); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_4)) __PYX_ERR(1, 15, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1)) __PYX_ERR(1, 15, __pyx_L1_error); + __pyx_t_4 = 0; + __pyx_t_1 = 0; + __pyx_r = __pyx_t_3; + __pyx_t_3 = 0; + goto __pyx_L0; + } + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * cdef tuple state + * cdef object _dict + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.Enum.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_state); + __Pyx_XDECREF(__pyx_v__dict); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":16 + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state(self, __pyx_state) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_MemviewEnum_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_MemviewEnum_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 16, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 16, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 16, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.Enum.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_MemviewEnum_2__setstate_cython__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_MemviewEnum_2__setstate_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":17 + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + * def __setstate_cython__(self, __pyx_state): + * __pyx_unpickle_Enum__set_state(self, __pyx_state) # <<<<<<<<<<<<<< + */ + if (!(likely(PyTuple_CheckExact(__pyx_v___pyx_state))||((__pyx_v___pyx_state) == Py_None) || __Pyx_RaiseUnexpectedTypeError("tuple", __pyx_v___pyx_state))) __PYX_ERR(1, 17, __pyx_L1_error) + __pyx_t_1 = __pyx_unpickle_Enum__set_state(__pyx_v_self, ((PyObject*)__pyx_v___pyx_state)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 17, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":16 + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state(self, __pyx_state) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.Enum.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":349 + * cdef __Pyx_TypeInfo *typeinfo + * + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): # <<<<<<<<<<<<<< + * self.obj = obj + * self.flags = flags + */ + +/* Python wrapper */ +static int __pyx_memoryview___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_memoryview___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_obj = 0; + int __pyx_v_flags; + int __pyx_v_dtype_is_object; + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_obj,&__pyx_n_s_flags,&__pyx_n_s_dtype_is_object,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_obj)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_flags)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 2, 3, 1); __PYX_ERR(1, 349, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_dtype_is_object); + if (value) { values[2] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(1, 349, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_obj = values[0]; + __pyx_v_flags = __Pyx_PyInt_As_int(values[1]); if (unlikely((__pyx_v_flags == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) + if (values[2]) { + __pyx_v_dtype_is_object = __Pyx_PyObject_IsTrue(values[2]); if (unlikely((__pyx_v_dtype_is_object == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 349, __pyx_L3_error) + } else { + __pyx_v_dtype_is_object = ((int)0); + } + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 2, 3, __pyx_nargs); __PYX_ERR(1, 349, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.memoryview.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview___cinit__(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v_obj, __pyx_v_flags, __pyx_v_dtype_is_object); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview___cinit__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj, int __pyx_v_flags, int __pyx_v_dtype_is_object) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + Py_intptr_t __pyx_t_4; + size_t __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__cinit__", 1); + + /* "View.MemoryView":350 + * + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): + * self.obj = obj # <<<<<<<<<<<<<< + * self.flags = flags + * if type(self) is memoryview or obj is not None: + */ + __Pyx_INCREF(__pyx_v_obj); + __Pyx_GIVEREF(__pyx_v_obj); + __Pyx_GOTREF(__pyx_v_self->obj); + __Pyx_DECREF(__pyx_v_self->obj); + __pyx_v_self->obj = __pyx_v_obj; + + /* "View.MemoryView":351 + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): + * self.obj = obj + * self.flags = flags # <<<<<<<<<<<<<< + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) + */ + __pyx_v_self->flags = __pyx_v_flags; + + /* "View.MemoryView":352 + * self.obj = obj + * self.flags = flags + * if type(self) is memoryview or obj is not None: # <<<<<<<<<<<<<< + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: + */ + __pyx_t_2 = (((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self))) == ((PyObject *)__pyx_memoryview_type)); + if (!__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_2 = (__pyx_v_obj != Py_None); + __pyx_t_1 = __pyx_t_2; + __pyx_L4_bool_binop_done:; + if (__pyx_t_1) { + + /* "View.MemoryView":353 + * self.flags = flags + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) # <<<<<<<<<<<<<< + * if self.view.obj == NULL: + * (<__pyx_buffer *> &self.view).obj = Py_None + */ + __pyx_t_3 = __Pyx_GetBuffer(__pyx_v_obj, (&__pyx_v_self->view), __pyx_v_flags); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 353, __pyx_L1_error) + + /* "View.MemoryView":354 + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: # <<<<<<<<<<<<<< + * (<__pyx_buffer *> &self.view).obj = Py_None + * Py_INCREF(Py_None) + */ + __pyx_t_1 = (((PyObject *)__pyx_v_self->view.obj) == NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":355 + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: + * (<__pyx_buffer *> &self.view).obj = Py_None # <<<<<<<<<<<<<< + * Py_INCREF(Py_None) + * + */ + ((Py_buffer *)(&__pyx_v_self->view))->obj = Py_None; + + /* "View.MemoryView":356 + * if self.view.obj == NULL: + * (<__pyx_buffer *> &self.view).obj = Py_None + * Py_INCREF(Py_None) # <<<<<<<<<<<<<< + * + * if not __PYX_CYTHON_ATOMICS_ENABLED(): + */ + Py_INCREF(Py_None); + + /* "View.MemoryView":354 + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: # <<<<<<<<<<<<<< + * (<__pyx_buffer *> &self.view).obj = Py_None + * Py_INCREF(Py_None) + */ + } + + /* "View.MemoryView":352 + * self.obj = obj + * self.flags = flags + * if type(self) is memoryview or obj is not None: # <<<<<<<<<<<<<< + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: + */ + } + + /* "View.MemoryView":358 + * Py_INCREF(Py_None) + * + * if not __PYX_CYTHON_ATOMICS_ENABLED(): # <<<<<<<<<<<<<< + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: + */ + __pyx_t_1 = (!__PYX_CYTHON_ATOMICS_ENABLED()); + if (__pyx_t_1) { + + /* "View.MemoryView":360 + * if not __PYX_CYTHON_ATOMICS_ENABLED(): + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: # <<<<<<<<<<<<<< + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + */ + __pyx_t_1 = (__pyx_memoryview_thread_locks_used < 8); + if (__pyx_t_1) { + + /* "View.MemoryView":361 + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: + */ + __pyx_v_self->lock = (__pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used]); + + /* "View.MemoryView":362 + * if __pyx_memoryview_thread_locks_used < 8: + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 # <<<<<<<<<<<<<< + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() + */ + __pyx_memoryview_thread_locks_used = (__pyx_memoryview_thread_locks_used + 1); + + /* "View.MemoryView":360 + * if not __PYX_CYTHON_ATOMICS_ENABLED(): + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: # <<<<<<<<<<<<<< + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + */ + } + + /* "View.MemoryView":363 + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: # <<<<<<<<<<<<<< + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: + */ + __pyx_t_1 = (__pyx_v_self->lock == NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":364 + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() # <<<<<<<<<<<<<< + * if self.lock is NULL: + * raise MemoryError + */ + __pyx_v_self->lock = PyThread_allocate_lock(); + + /* "View.MemoryView":365 + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + __pyx_t_1 = (__pyx_v_self->lock == NULL); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":366 + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: + * raise MemoryError # <<<<<<<<<<<<<< + * + * if flags & PyBUF_FORMAT: + */ + PyErr_NoMemory(); __PYX_ERR(1, 366, __pyx_L1_error) + + /* "View.MemoryView":365 + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + } + + /* "View.MemoryView":363 + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: # <<<<<<<<<<<<<< + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: + */ + } + + /* "View.MemoryView":358 + * Py_INCREF(Py_None) + * + * if not __PYX_CYTHON_ATOMICS_ENABLED(): # <<<<<<<<<<<<<< + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: + */ + } + + /* "View.MemoryView":368 + * raise MemoryError + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_FORMAT) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":369 + * + * if flags & PyBUF_FORMAT: + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') # <<<<<<<<<<<<<< + * else: + * self.dtype_is_object = dtype_is_object + */ + __pyx_t_2 = ((__pyx_v_self->view.format[0]) == 'O'); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L12_bool_binop_done; + } + __pyx_t_2 = ((__pyx_v_self->view.format[1]) == '\x00'); + __pyx_t_1 = __pyx_t_2; + __pyx_L12_bool_binop_done:; + __pyx_v_self->dtype_is_object = __pyx_t_1; + + /* "View.MemoryView":368 + * raise MemoryError + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') + * else: + */ + goto __pyx_L11; + } + + /* "View.MemoryView":371 + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') + * else: + * self.dtype_is_object = dtype_is_object # <<<<<<<<<<<<<< + * + * assert (&self.acquisition_count) % sizeof(__pyx_atomic_int_type) == 0 + */ + /*else*/ { + __pyx_v_self->dtype_is_object = __pyx_v_dtype_is_object; + } + __pyx_L11:; + + /* "View.MemoryView":373 + * self.dtype_is_object = dtype_is_object + * + * assert (&self.acquisition_count) % sizeof(__pyx_atomic_int_type) == 0 # <<<<<<<<<<<<<< + * self.typeinfo = NULL + * + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_4 = ((Py_intptr_t)((void *)(&__pyx_v_self->acquisition_count))); + __pyx_t_5 = (sizeof(__pyx_atomic_int_type)); + if (unlikely(__pyx_t_5 == 0)) { + PyErr_SetString(PyExc_ZeroDivisionError, "integer division or modulo by zero"); + __PYX_ERR(1, 373, __pyx_L1_error) + } + __pyx_t_1 = ((__pyx_t_4 % __pyx_t_5) == 0); + if (unlikely(!__pyx_t_1)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(1, 373, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(1, 373, __pyx_L1_error) + #endif + + /* "View.MemoryView":374 + * + * assert (&self.acquisition_count) % sizeof(__pyx_atomic_int_type) == 0 + * self.typeinfo = NULL # <<<<<<<<<<<<<< + * + * def __dealloc__(memoryview self): + */ + __pyx_v_self->typeinfo = NULL; + + /* "View.MemoryView":349 + * cdef __Pyx_TypeInfo *typeinfo + * + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): # <<<<<<<<<<<<<< + * self.obj = obj + * self.flags = flags + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":376 + * self.typeinfo = NULL + * + * def __dealloc__(memoryview self): # <<<<<<<<<<<<<< + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + */ + +/* Python wrapper */ +static void __pyx_memoryview___dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_memoryview___dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_2__dealloc__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_2__dealloc__(struct __pyx_memoryview_obj *__pyx_v_self) { + int __pyx_v_i; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + PyThread_type_lock __pyx_t_5; + PyThread_type_lock __pyx_t_6; + + /* "View.MemoryView":377 + * + * def __dealloc__(memoryview self): + * if self.obj is not None: # <<<<<<<<<<<<<< + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + */ + __pyx_t_1 = (__pyx_v_self->obj != Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":378 + * def __dealloc__(memoryview self): + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) # <<<<<<<<<<<<<< + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + * + */ + __Pyx_ReleaseBuffer((&__pyx_v_self->view)); + + /* "View.MemoryView":377 + * + * def __dealloc__(memoryview self): + * if self.obj is not None: # <<<<<<<<<<<<<< + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":379 + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: # <<<<<<<<<<<<<< + * + * (<__pyx_buffer *> &self.view).obj = NULL + */ + __pyx_t_1 = (((Py_buffer *)(&__pyx_v_self->view))->obj == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":381 + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + * + * (<__pyx_buffer *> &self.view).obj = NULL # <<<<<<<<<<<<<< + * Py_DECREF(Py_None) + * + */ + ((Py_buffer *)(&__pyx_v_self->view))->obj = NULL; + + /* "View.MemoryView":382 + * + * (<__pyx_buffer *> &self.view).obj = NULL + * Py_DECREF(Py_None) # <<<<<<<<<<<<<< + * + * cdef int i + */ + Py_DECREF(Py_None); + + /* "View.MemoryView":379 + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: # <<<<<<<<<<<<<< + * + * (<__pyx_buffer *> &self.view).obj = NULL + */ + } + __pyx_L3:; + + /* "View.MemoryView":386 + * cdef int i + * global __pyx_memoryview_thread_locks_used + * if self.lock != NULL: # <<<<<<<<<<<<<< + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: + */ + __pyx_t_1 = (__pyx_v_self->lock != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":387 + * global __pyx_memoryview_thread_locks_used + * if self.lock != NULL: + * for i in range(__pyx_memoryview_thread_locks_used): # <<<<<<<<<<<<<< + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 + */ + __pyx_t_2 = __pyx_memoryview_thread_locks_used; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":388 + * if self.lock != NULL: + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: + */ + __pyx_t_1 = ((__pyx_memoryview_thread_locks[__pyx_v_i]) == __pyx_v_self->lock); + if (__pyx_t_1) { + + /* "View.MemoryView":389 + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 # <<<<<<<<<<<<<< + * if i != __pyx_memoryview_thread_locks_used: + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + */ + __pyx_memoryview_thread_locks_used = (__pyx_memoryview_thread_locks_used - 1); + + /* "View.MemoryView":390 + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + */ + __pyx_t_1 = (__pyx_v_i != __pyx_memoryview_thread_locks_used); + if (__pyx_t_1) { + + /* "View.MemoryView":392 + * if i != __pyx_memoryview_thread_locks_used: + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) # <<<<<<<<<<<<<< + * break + * else: + */ + __pyx_t_5 = (__pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used]); + __pyx_t_6 = (__pyx_memoryview_thread_locks[__pyx_v_i]); + + /* "View.MemoryView":391 + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + * break + */ + (__pyx_memoryview_thread_locks[__pyx_v_i]) = __pyx_t_5; + (__pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used]) = __pyx_t_6; + + /* "View.MemoryView":390 + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + */ + } + + /* "View.MemoryView":393 + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + * break # <<<<<<<<<<<<<< + * else: + * PyThread_free_lock(self.lock) + */ + goto __pyx_L6_break; + + /* "View.MemoryView":388 + * if self.lock != NULL: + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: + */ + } + } + /*else*/ { + + /* "View.MemoryView":395 + * break + * else: + * PyThread_free_lock(self.lock) # <<<<<<<<<<<<<< + * + * cdef char *get_item_pointer(memoryview self, object index) except NULL: + */ + PyThread_free_lock(__pyx_v_self->lock); + } + __pyx_L6_break:; + + /* "View.MemoryView":386 + * cdef int i + * global __pyx_memoryview_thread_locks_used + * if self.lock != NULL: # <<<<<<<<<<<<<< + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: + */ + } + + /* "View.MemoryView":376 + * self.typeinfo = NULL + * + * def __dealloc__(memoryview self): # <<<<<<<<<<<<<< + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + */ + + /* function exit code */ +} + +/* "View.MemoryView":397 + * PyThread_free_lock(self.lock) + * + * cdef char *get_item_pointer(memoryview self, object index) except NULL: # <<<<<<<<<<<<<< + * cdef Py_ssize_t dim + * cdef char *itemp = self.view.buf + */ + +static char *__pyx_memoryview_get_item_pointer(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index) { + Py_ssize_t __pyx_v_dim; + char *__pyx_v_itemp; + PyObject *__pyx_v_idx = NULL; + char *__pyx_r; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + Py_ssize_t __pyx_t_3; + PyObject *(*__pyx_t_4)(PyObject *); + PyObject *__pyx_t_5 = NULL; + Py_ssize_t __pyx_t_6; + char *__pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_item_pointer", 1); + + /* "View.MemoryView":399 + * cdef char *get_item_pointer(memoryview self, object index) except NULL: + * cdef Py_ssize_t dim + * cdef char *itemp = self.view.buf # <<<<<<<<<<<<<< + * + * for dim, idx in enumerate(index): + */ + __pyx_v_itemp = ((char *)__pyx_v_self->view.buf); + + /* "View.MemoryView":401 + * cdef char *itemp = self.view.buf + * + * for dim, idx in enumerate(index): # <<<<<<<<<<<<<< + * itemp = pybuffer_index(&self.view, itemp, idx, dim) + * + */ + __pyx_t_1 = 0; + if (likely(PyList_CheckExact(__pyx_v_index)) || PyTuple_CheckExact(__pyx_v_index)) { + __pyx_t_2 = __pyx_v_index; __Pyx_INCREF(__pyx_t_2); + __pyx_t_3 = 0; + __pyx_t_4 = NULL; + } else { + __pyx_t_3 = -1; __pyx_t_2 = PyObject_GetIter(__pyx_v_index); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 401, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_2); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 401, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_4)) { + if (likely(PyList_CheckExact(__pyx_t_2))) { + { + Py_ssize_t __pyx_temp = __Pyx_PyList_GET_SIZE(__pyx_t_2); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 401, __pyx_L1_error) + #endif + if (__pyx_t_3 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_5 = PyList_GET_ITEM(__pyx_t_2, __pyx_t_3); __Pyx_INCREF(__pyx_t_5); __pyx_t_3++; if (unlikely((0 < 0))) __PYX_ERR(1, 401, __pyx_L1_error) + #else + __pyx_t_5 = __Pyx_PySequence_ITEM(__pyx_t_2, __pyx_t_3); __pyx_t_3++; if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 401, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + #endif + } else { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_2); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 401, __pyx_L1_error) + #endif + if (__pyx_t_3 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_5 = PyTuple_GET_ITEM(__pyx_t_2, __pyx_t_3); __Pyx_INCREF(__pyx_t_5); __pyx_t_3++; if (unlikely((0 < 0))) __PYX_ERR(1, 401, __pyx_L1_error) + #else + __pyx_t_5 = __Pyx_PySequence_ITEM(__pyx_t_2, __pyx_t_3); __pyx_t_3++; if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 401, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + #endif + } + } else { + __pyx_t_5 = __pyx_t_4(__pyx_t_2); + if (unlikely(!__pyx_t_5)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(1, 401, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_5); + } + __Pyx_XDECREF_SET(__pyx_v_idx, __pyx_t_5); + __pyx_t_5 = 0; + __pyx_v_dim = __pyx_t_1; + __pyx_t_1 = (__pyx_t_1 + 1); + + /* "View.MemoryView":402 + * + * for dim, idx in enumerate(index): + * itemp = pybuffer_index(&self.view, itemp, idx, dim) # <<<<<<<<<<<<<< + * + * return itemp + */ + __pyx_t_6 = __Pyx_PyIndex_AsSsize_t(__pyx_v_idx); if (unlikely((__pyx_t_6 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 402, __pyx_L1_error) + __pyx_t_7 = __pyx_pybuffer_index((&__pyx_v_self->view), __pyx_v_itemp, __pyx_t_6, __pyx_v_dim); if (unlikely(__pyx_t_7 == ((char *)NULL))) __PYX_ERR(1, 402, __pyx_L1_error) + __pyx_v_itemp = __pyx_t_7; + + /* "View.MemoryView":401 + * cdef char *itemp = self.view.buf + * + * for dim, idx in enumerate(index): # <<<<<<<<<<<<<< + * itemp = pybuffer_index(&self.view, itemp, idx, dim) + * + */ + } + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":404 + * itemp = pybuffer_index(&self.view, itemp, idx, dim) + * + * return itemp # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = __pyx_v_itemp; + goto __pyx_L0; + + /* "View.MemoryView":397 + * PyThread_free_lock(self.lock) + * + * cdef char *get_item_pointer(memoryview self, object index) except NULL: # <<<<<<<<<<<<<< + * cdef Py_ssize_t dim + * cdef char *itemp = self.view.buf + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.memoryview.get_item_pointer", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_idx); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":407 + * + * + * def __getitem__(memoryview self, object index): # <<<<<<<<<<<<<< + * if index is Ellipsis: + * return self + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index); /*proto*/ +static PyObject *__pyx_memoryview___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getitem__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_4__getitem__(((struct __pyx_memoryview_obj *)__pyx_v_self), ((PyObject *)__pyx_v_index)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_4__getitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index) { + PyObject *__pyx_v_have_slices = NULL; + PyObject *__pyx_v_indices = NULL; + char *__pyx_v_itemp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + char *__pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__getitem__", 1); + + /* "View.MemoryView":408 + * + * def __getitem__(memoryview self, object index): + * if index is Ellipsis: # <<<<<<<<<<<<<< + * return self + * + */ + __pyx_t_1 = (__pyx_v_index == __pyx_builtin_Ellipsis); + if (__pyx_t_1) { + + /* "View.MemoryView":409 + * def __getitem__(memoryview self, object index): + * if index is Ellipsis: + * return self # <<<<<<<<<<<<<< + * + * have_slices, indices = _unellipsify(index, self.view.ndim) + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_self); + __pyx_r = ((PyObject *)__pyx_v_self); + goto __pyx_L0; + + /* "View.MemoryView":408 + * + * def __getitem__(memoryview self, object index): + * if index is Ellipsis: # <<<<<<<<<<<<<< + * return self + * + */ + } + + /* "View.MemoryView":411 + * return self + * + * have_slices, indices = _unellipsify(index, self.view.ndim) # <<<<<<<<<<<<<< + * + * cdef char *itemp + */ + __pyx_t_2 = _unellipsify(__pyx_v_index, __pyx_v_self->view.ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 411, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (likely(__pyx_t_2 != Py_None)) { + PyObject* sequence = __pyx_t_2; + Py_ssize_t size = __Pyx_PySequence_SIZE(sequence); + if (unlikely(size != 2)) { + if (size > 2) __Pyx_RaiseTooManyValuesError(2); + else if (size >= 0) __Pyx_RaiseNeedMoreValuesError(size); + __PYX_ERR(1, 411, __pyx_L1_error) + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_3 = PyTuple_GET_ITEM(sequence, 0); + __pyx_t_4 = PyTuple_GET_ITEM(sequence, 1); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(__pyx_t_4); + #else + __pyx_t_3 = PySequence_ITEM(sequence, 0); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 411, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PySequence_ITEM(sequence, 1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 411, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } else { + __Pyx_RaiseNoneNotIterableError(); __PYX_ERR(1, 411, __pyx_L1_error) + } + __pyx_v_have_slices = __pyx_t_3; + __pyx_t_3 = 0; + __pyx_v_indices = __pyx_t_4; + __pyx_t_4 = 0; + + /* "View.MemoryView":414 + * + * cdef char *itemp + * if have_slices: # <<<<<<<<<<<<<< + * return memview_slice(self, indices) + * else: + */ + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_v_have_slices); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 414, __pyx_L1_error) + if (__pyx_t_1) { + + /* "View.MemoryView":415 + * cdef char *itemp + * if have_slices: + * return memview_slice(self, indices) # <<<<<<<<<<<<<< + * else: + * itemp = self.get_item_pointer(indices) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = ((PyObject *)__pyx_memview_slice(__pyx_v_self, __pyx_v_indices)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 415, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":414 + * + * cdef char *itemp + * if have_slices: # <<<<<<<<<<<<<< + * return memview_slice(self, indices) + * else: + */ + } + + /* "View.MemoryView":417 + * return memview_slice(self, indices) + * else: + * itemp = self.get_item_pointer(indices) # <<<<<<<<<<<<<< + * return self.convert_item_to_object(itemp) + * + */ + /*else*/ { + __pyx_t_5 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->get_item_pointer(__pyx_v_self, __pyx_v_indices); if (unlikely(__pyx_t_5 == ((char *)NULL))) __PYX_ERR(1, 417, __pyx_L1_error) + __pyx_v_itemp = __pyx_t_5; + + /* "View.MemoryView":418 + * else: + * itemp = self.get_item_pointer(indices) + * return self.convert_item_to_object(itemp) # <<<<<<<<<<<<<< + * + * def __setitem__(memoryview self, object index, object value): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->convert_item_to_object(__pyx_v_self, __pyx_v_itemp); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 418, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + } + + /* "View.MemoryView":407 + * + * + * def __getitem__(memoryview self, object index): # <<<<<<<<<<<<<< + * if index is Ellipsis: + * return self + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.memoryview.__getitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_have_slices); + __Pyx_XDECREF(__pyx_v_indices); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":420 + * return self.convert_item_to_object(itemp) + * + * def __setitem__(memoryview self, object index, object value): # <<<<<<<<<<<<<< + * if self.view.readonly: + * raise TypeError, "Cannot assign to read-only memoryview" + */ + +/* Python wrapper */ +static int __pyx_memoryview___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value); /*proto*/ +static int __pyx_memoryview___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setitem__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_6__setitem__(((struct __pyx_memoryview_obj *)__pyx_v_self), ((PyObject *)__pyx_v_index), ((PyObject *)__pyx_v_value)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_6__setitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value) { + PyObject *__pyx_v_have_slices = NULL; + PyObject *__pyx_v_obj = NULL; + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setitem__", 0); + __Pyx_INCREF(__pyx_v_index); + + /* "View.MemoryView":421 + * + * def __setitem__(memoryview self, object index, object value): + * if self.view.readonly: # <<<<<<<<<<<<<< + * raise TypeError, "Cannot assign to read-only memoryview" + * + */ + if (unlikely(__pyx_v_self->view.readonly)) { + + /* "View.MemoryView":422 + * def __setitem__(memoryview self, object index, object value): + * if self.view.readonly: + * raise TypeError, "Cannot assign to read-only memoryview" # <<<<<<<<<<<<<< + * + * have_slices, index = _unellipsify(index, self.view.ndim) + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_Cannot_assign_to_read_only_memor, 0, 0); + __PYX_ERR(1, 422, __pyx_L1_error) + + /* "View.MemoryView":421 + * + * def __setitem__(memoryview self, object index, object value): + * if self.view.readonly: # <<<<<<<<<<<<<< + * raise TypeError, "Cannot assign to read-only memoryview" + * + */ + } + + /* "View.MemoryView":424 + * raise TypeError, "Cannot assign to read-only memoryview" + * + * have_slices, index = _unellipsify(index, self.view.ndim) # <<<<<<<<<<<<<< + * + * if have_slices: + */ + __pyx_t_1 = _unellipsify(__pyx_v_index, __pyx_v_self->view.ndim); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 424, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (likely(__pyx_t_1 != Py_None)) { + PyObject* sequence = __pyx_t_1; + Py_ssize_t size = __Pyx_PySequence_SIZE(sequence); + if (unlikely(size != 2)) { + if (size > 2) __Pyx_RaiseTooManyValuesError(2); + else if (size >= 0) __Pyx_RaiseNeedMoreValuesError(size); + __PYX_ERR(1, 424, __pyx_L1_error) + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_2 = PyTuple_GET_ITEM(sequence, 0); + __pyx_t_3 = PyTuple_GET_ITEM(sequence, 1); + __Pyx_INCREF(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + #else + __pyx_t_2 = PySequence_ITEM(sequence, 0); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 424, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PySequence_ITEM(sequence, 1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 424, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + #endif + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } else { + __Pyx_RaiseNoneNotIterableError(); __PYX_ERR(1, 424, __pyx_L1_error) + } + __pyx_v_have_slices = __pyx_t_2; + __pyx_t_2 = 0; + __Pyx_DECREF_SET(__pyx_v_index, __pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":426 + * have_slices, index = _unellipsify(index, self.view.ndim) + * + * if have_slices: # <<<<<<<<<<<<<< + * obj = self.is_slice(value) + * if obj: + */ + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_v_have_slices); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(1, 426, __pyx_L1_error) + if (__pyx_t_4) { + + /* "View.MemoryView":427 + * + * if have_slices: + * obj = self.is_slice(value) # <<<<<<<<<<<<<< + * if obj: + * self.setitem_slice_assignment(self[index], obj) + */ + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->is_slice(__pyx_v_self, __pyx_v_value); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 427, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_obj = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":428 + * if have_slices: + * obj = self.is_slice(value) + * if obj: # <<<<<<<<<<<<<< + * self.setitem_slice_assignment(self[index], obj) + * else: + */ + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_v_obj); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(1, 428, __pyx_L1_error) + if (__pyx_t_4) { + + /* "View.MemoryView":429 + * obj = self.is_slice(value) + * if obj: + * self.setitem_slice_assignment(self[index], obj) # <<<<<<<<<<<<<< + * else: + * self.setitem_slice_assign_scalar(self[index], value) + */ + __pyx_t_1 = __Pyx_PyObject_GetItem(((PyObject *)__pyx_v_self), __pyx_v_index); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 429, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->setitem_slice_assignment(__pyx_v_self, __pyx_t_1, __pyx_v_obj); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 429, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "View.MemoryView":428 + * if have_slices: + * obj = self.is_slice(value) + * if obj: # <<<<<<<<<<<<<< + * self.setitem_slice_assignment(self[index], obj) + * else: + */ + goto __pyx_L5; + } + + /* "View.MemoryView":431 + * self.setitem_slice_assignment(self[index], obj) + * else: + * self.setitem_slice_assign_scalar(self[index], value) # <<<<<<<<<<<<<< + * else: + * self.setitem_indexed(index, value) + */ + /*else*/ { + __pyx_t_3 = __Pyx_PyObject_GetItem(((PyObject *)__pyx_v_self), __pyx_v_index); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 431, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (!(likely(((__pyx_t_3) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_3, __pyx_memoryview_type))))) __PYX_ERR(1, 431, __pyx_L1_error) + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->setitem_slice_assign_scalar(__pyx_v_self, ((struct __pyx_memoryview_obj *)__pyx_t_3), __pyx_v_value); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 431, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_L5:; + + /* "View.MemoryView":426 + * have_slices, index = _unellipsify(index, self.view.ndim) + * + * if have_slices: # <<<<<<<<<<<<<< + * obj = self.is_slice(value) + * if obj: + */ + goto __pyx_L4; + } + + /* "View.MemoryView":433 + * self.setitem_slice_assign_scalar(self[index], value) + * else: + * self.setitem_indexed(index, value) # <<<<<<<<<<<<<< + * + * cdef is_slice(self, obj): + */ + /*else*/ { + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->setitem_indexed(__pyx_v_self, __pyx_v_index, __pyx_v_value); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 433, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_L4:; + + /* "View.MemoryView":420 + * return self.convert_item_to_object(itemp) + * + * def __setitem__(memoryview self, object index, object value): # <<<<<<<<<<<<<< + * if self.view.readonly: + * raise TypeError, "Cannot assign to read-only memoryview" + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.__setitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_have_slices); + __Pyx_XDECREF(__pyx_v_obj); + __Pyx_XDECREF(__pyx_v_index); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":435 + * self.setitem_indexed(index, value) + * + * cdef is_slice(self, obj): # <<<<<<<<<<<<<< + * if not isinstance(obj, memoryview): + * try: + */ + +static PyObject *__pyx_memoryview_is_slice(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("is_slice", 0); + __Pyx_INCREF(__pyx_v_obj); + + /* "View.MemoryView":436 + * + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): # <<<<<<<<<<<<<< + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + */ + __pyx_t_1 = __Pyx_TypeCheck(__pyx_v_obj, __pyx_memoryview_type); + __pyx_t_2 = (!__pyx_t_1); + if (__pyx_t_2) { + + /* "View.MemoryView":437 + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): + * try: # <<<<<<<<<<<<<< + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_3, &__pyx_t_4, &__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_4); + __Pyx_XGOTREF(__pyx_t_5); + /*try:*/ { + + /* "View.MemoryView":438 + * if not isinstance(obj, memoryview): + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, # <<<<<<<<<<<<<< + * self.dtype_is_object) + * except TypeError: + */ + __pyx_t_6 = __Pyx_PyInt_From_int(((__pyx_v_self->flags & (~PyBUF_WRITABLE)) | PyBUF_ANY_CONTIGUOUS)); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 438, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_6); + + /* "View.MemoryView":439 + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) # <<<<<<<<<<<<<< + * except TypeError: + * return None + */ + __pyx_t_7 = __Pyx_PyBool_FromLong(__pyx_v_self->dtype_is_object); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 439, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_7); + + /* "View.MemoryView":438 + * if not isinstance(obj, memoryview): + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, # <<<<<<<<<<<<<< + * self.dtype_is_object) + * except TypeError: + */ + __pyx_t_8 = PyTuple_New(3); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 438, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_INCREF(__pyx_v_obj); + __Pyx_GIVEREF(__pyx_v_obj); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_8, 0, __pyx_v_obj)) __PYX_ERR(1, 438, __pyx_L4_error); + __Pyx_GIVEREF(__pyx_t_6); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_8, 1, __pyx_t_6)) __PYX_ERR(1, 438, __pyx_L4_error); + __Pyx_GIVEREF(__pyx_t_7); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_8, 2, __pyx_t_7)) __PYX_ERR(1, 438, __pyx_L4_error); + __pyx_t_6 = 0; + __pyx_t_7 = 0; + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_memoryview_type), __pyx_t_8, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 438, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_DECREF_SET(__pyx_v_obj, __pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":437 + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): + * try: # <<<<<<<<<<<<<< + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + */ + } + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + goto __pyx_L9_try_end; + __pyx_L4_error:; + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + + /* "View.MemoryView":440 + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + * except TypeError: # <<<<<<<<<<<<<< + * return None + * + */ + __pyx_t_9 = __Pyx_PyErr_ExceptionMatches(__pyx_builtin_TypeError); + if (__pyx_t_9) { + __Pyx_AddTraceback("View.MemoryView.memoryview.is_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_7, &__pyx_t_8, &__pyx_t_6) < 0) __PYX_ERR(1, 440, __pyx_L6_except_error) + __Pyx_XGOTREF(__pyx_t_7); + __Pyx_XGOTREF(__pyx_t_8); + __Pyx_XGOTREF(__pyx_t_6); + + /* "View.MemoryView":441 + * self.dtype_is_object) + * except TypeError: + * return None # <<<<<<<<<<<<<< + * + * return obj + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L7_except_return; + } + goto __pyx_L6_except_error; + + /* "View.MemoryView":437 + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): + * try: # <<<<<<<<<<<<<< + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + */ + __pyx_L6_except_error:; + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_XGIVEREF(__pyx_t_5); + __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_4, __pyx_t_5); + goto __pyx_L1_error; + __pyx_L7_except_return:; + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_XGIVEREF(__pyx_t_5); + __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_4, __pyx_t_5); + goto __pyx_L0; + __pyx_L9_try_end:; + } + + /* "View.MemoryView":436 + * + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): # <<<<<<<<<<<<<< + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + */ + } + + /* "View.MemoryView":443 + * return None + * + * return obj # <<<<<<<<<<<<<< + * + * cdef setitem_slice_assignment(self, dst, src): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_obj); + __pyx_r = __pyx_v_obj; + goto __pyx_L0; + + /* "View.MemoryView":435 + * self.setitem_indexed(index, value) + * + * cdef is_slice(self, obj): # <<<<<<<<<<<<<< + * if not isinstance(obj, memoryview): + * try: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("View.MemoryView.memoryview.is_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_obj); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":445 + * return obj + * + * cdef setitem_slice_assignment(self, dst, src): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice dst_slice + * cdef __Pyx_memviewslice src_slice + */ + +static PyObject *__pyx_memoryview_setitem_slice_assignment(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_dst, PyObject *__pyx_v_src) { + __Pyx_memviewslice __pyx_v_dst_slice; + __Pyx_memviewslice __pyx_v_src_slice; + __Pyx_memviewslice __pyx_v_msrc; + __Pyx_memviewslice __pyx_v_mdst; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_t_3; + int __pyx_t_4; + int __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("setitem_slice_assignment", 1); + + /* "View.MemoryView":448 + * cdef __Pyx_memviewslice dst_slice + * cdef __Pyx_memviewslice src_slice + * cdef __Pyx_memviewslice msrc = get_slice_from_memview(src, &src_slice)[0] # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice mdst = get_slice_from_memview(dst, &dst_slice)[0] + * + */ + if (!(likely(((__pyx_v_src) == Py_None) || likely(__Pyx_TypeTest(__pyx_v_src, __pyx_memoryview_type))))) __PYX_ERR(1, 448, __pyx_L1_error) + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(((struct __pyx_memoryview_obj *)__pyx_v_src), (&__pyx_v_src_slice)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 448, __pyx_L1_error) + __pyx_v_msrc = (__pyx_t_1[0]); + + /* "View.MemoryView":449 + * cdef __Pyx_memviewslice src_slice + * cdef __Pyx_memviewslice msrc = get_slice_from_memview(src, &src_slice)[0] + * cdef __Pyx_memviewslice mdst = get_slice_from_memview(dst, &dst_slice)[0] # <<<<<<<<<<<<<< + * + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) + */ + if (!(likely(((__pyx_v_dst) == Py_None) || likely(__Pyx_TypeTest(__pyx_v_dst, __pyx_memoryview_type))))) __PYX_ERR(1, 449, __pyx_L1_error) + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(((struct __pyx_memoryview_obj *)__pyx_v_dst), (&__pyx_v_dst_slice)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 449, __pyx_L1_error) + __pyx_v_mdst = (__pyx_t_1[0]); + + /* "View.MemoryView":451 + * cdef __Pyx_memviewslice mdst = get_slice_from_memview(dst, &dst_slice)[0] + * + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) # <<<<<<<<<<<<<< + * + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_src, __pyx_n_s_ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 451, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_PyInt_As_int(__pyx_t_2); if (unlikely((__pyx_t_3 == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 451, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_dst, __pyx_n_s_ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 451, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __Pyx_PyInt_As_int(__pyx_t_2); if (unlikely((__pyx_t_4 == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 451, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_5 = __pyx_memoryview_copy_contents(__pyx_v_msrc, __pyx_v_mdst, __pyx_t_3, __pyx_t_4, __pyx_v_self->dtype_is_object); if (unlikely(__pyx_t_5 == ((int)-1))) __PYX_ERR(1, 451, __pyx_L1_error) + + /* "View.MemoryView":445 + * return obj + * + * cdef setitem_slice_assignment(self, dst, src): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice dst_slice + * cdef __Pyx_memviewslice src_slice + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.setitem_slice_assignment", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":453 + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) + * + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): # <<<<<<<<<<<<<< + * cdef int array[128] + * cdef void *tmp = NULL + */ + +static PyObject *__pyx_memoryview_setitem_slice_assign_scalar(struct __pyx_memoryview_obj *__pyx_v_self, struct __pyx_memoryview_obj *__pyx_v_dst, PyObject *__pyx_v_value) { + int __pyx_v_array[0x80]; + void *__pyx_v_tmp; + void *__pyx_v_item; + __Pyx_memviewslice *__pyx_v_dst_slice; + __Pyx_memviewslice __pyx_v_tmp_slice; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_t_5; + char const *__pyx_t_6; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + PyObject *__pyx_t_9 = NULL; + PyObject *__pyx_t_10 = NULL; + PyObject *__pyx_t_11 = NULL; + PyObject *__pyx_t_12 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("setitem_slice_assign_scalar", 1); + + /* "View.MemoryView":455 + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): + * cdef int array[128] + * cdef void *tmp = NULL # <<<<<<<<<<<<<< + * cdef void *item + * + */ + __pyx_v_tmp = NULL; + + /* "View.MemoryView":460 + * cdef __Pyx_memviewslice *dst_slice + * cdef __Pyx_memviewslice tmp_slice + * dst_slice = get_slice_from_memview(dst, &tmp_slice) # <<<<<<<<<<<<<< + * + * if self.view.itemsize > sizeof(array): + */ + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(__pyx_v_dst, (&__pyx_v_tmp_slice)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 460, __pyx_L1_error) + __pyx_v_dst_slice = __pyx_t_1; + + /* "View.MemoryView":462 + * dst_slice = get_slice_from_memview(dst, &tmp_slice) + * + * if self.view.itemsize > sizeof(array): # <<<<<<<<<<<<<< + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: + */ + __pyx_t_2 = (((size_t)__pyx_v_self->view.itemsize) > (sizeof(__pyx_v_array))); + if (__pyx_t_2) { + + /* "View.MemoryView":463 + * + * if self.view.itemsize > sizeof(array): + * tmp = PyMem_Malloc(self.view.itemsize) # <<<<<<<<<<<<<< + * if tmp == NULL: + * raise MemoryError + */ + __pyx_v_tmp = PyMem_Malloc(__pyx_v_self->view.itemsize); + + /* "View.MemoryView":464 + * if self.view.itemsize > sizeof(array): + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * item = tmp + */ + __pyx_t_2 = (__pyx_v_tmp == NULL); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":465 + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: + * raise MemoryError # <<<<<<<<<<<<<< + * item = tmp + * else: + */ + PyErr_NoMemory(); __PYX_ERR(1, 465, __pyx_L1_error) + + /* "View.MemoryView":464 + * if self.view.itemsize > sizeof(array): + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * item = tmp + */ + } + + /* "View.MemoryView":466 + * if tmp == NULL: + * raise MemoryError + * item = tmp # <<<<<<<<<<<<<< + * else: + * item = array + */ + __pyx_v_item = __pyx_v_tmp; + + /* "View.MemoryView":462 + * dst_slice = get_slice_from_memview(dst, &tmp_slice) + * + * if self.view.itemsize > sizeof(array): # <<<<<<<<<<<<<< + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":468 + * item = tmp + * else: + * item = array # <<<<<<<<<<<<<< + * + * try: + */ + /*else*/ { + __pyx_v_item = ((void *)__pyx_v_array); + } + __pyx_L3:; + + /* "View.MemoryView":470 + * item = array + * + * try: # <<<<<<<<<<<<<< + * if self.dtype_is_object: + * ( item)[0] = value + */ + /*try:*/ { + + /* "View.MemoryView":471 + * + * try: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * ( item)[0] = value + * else: + */ + if (__pyx_v_self->dtype_is_object) { + + /* "View.MemoryView":472 + * try: + * if self.dtype_is_object: + * ( item)[0] = value # <<<<<<<<<<<<<< + * else: + * self.assign_item_from_object( item, value) + */ + (((PyObject **)__pyx_v_item)[0]) = ((PyObject *)__pyx_v_value); + + /* "View.MemoryView":471 + * + * try: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * ( item)[0] = value + * else: + */ + goto __pyx_L8; + } + + /* "View.MemoryView":474 + * ( item)[0] = value + * else: + * self.assign_item_from_object( item, value) # <<<<<<<<<<<<<< + * + * + */ + /*else*/ { + __pyx_t_3 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->assign_item_from_object(__pyx_v_self, ((char *)__pyx_v_item), __pyx_v_value); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 474, __pyx_L6_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_L8:; + + /* "View.MemoryView":478 + * + * + * if self.view.suboffsets != NULL: # <<<<<<<<<<<<<< + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, + */ + __pyx_t_2 = (__pyx_v_self->view.suboffsets != NULL); + if (__pyx_t_2) { + + /* "View.MemoryView":479 + * + * if self.view.suboffsets != NULL: + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) # <<<<<<<<<<<<<< + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, + * item, self.dtype_is_object) + */ + __pyx_t_4 = assert_direct_dimensions(__pyx_v_self->view.suboffsets, __pyx_v_self->view.ndim); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(1, 479, __pyx_L6_error) + + /* "View.MemoryView":478 + * + * + * if self.view.suboffsets != NULL: # <<<<<<<<<<<<<< + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, + */ + } + + /* "View.MemoryView":480 + * if self.view.suboffsets != NULL: + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, # <<<<<<<<<<<<<< + * item, self.dtype_is_object) + * finally: + */ + __pyx_memoryview_slice_assign_scalar(__pyx_v_dst_slice, __pyx_v_dst->view.ndim, __pyx_v_self->view.itemsize, __pyx_v_item, __pyx_v_self->dtype_is_object); + } + + /* "View.MemoryView":483 + * item, self.dtype_is_object) + * finally: + * PyMem_Free(tmp) # <<<<<<<<<<<<<< + * + * cdef setitem_indexed(self, index, value): + */ + /*finally:*/ { + /*normal exit:*/{ + PyMem_Free(__pyx_v_tmp); + goto __pyx_L7; + } + __pyx_L6_error:; + /*exception exit:*/{ + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __pyx_t_7 = 0; __pyx_t_8 = 0; __pyx_t_9 = 0; __pyx_t_10 = 0; __pyx_t_11 = 0; __pyx_t_12 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (PY_MAJOR_VERSION >= 3) __Pyx_ExceptionSwap(&__pyx_t_10, &__pyx_t_11, &__pyx_t_12); + if ((PY_MAJOR_VERSION < 3) || unlikely(__Pyx_GetException(&__pyx_t_7, &__pyx_t_8, &__pyx_t_9) < 0)) __Pyx_ErrFetch(&__pyx_t_7, &__pyx_t_8, &__pyx_t_9); + __Pyx_XGOTREF(__pyx_t_7); + __Pyx_XGOTREF(__pyx_t_8); + __Pyx_XGOTREF(__pyx_t_9); + __Pyx_XGOTREF(__pyx_t_10); + __Pyx_XGOTREF(__pyx_t_11); + __Pyx_XGOTREF(__pyx_t_12); + __pyx_t_4 = __pyx_lineno; __pyx_t_5 = __pyx_clineno; __pyx_t_6 = __pyx_filename; + { + PyMem_Free(__pyx_v_tmp); + } + if (PY_MAJOR_VERSION >= 3) { + __Pyx_XGIVEREF(__pyx_t_10); + __Pyx_XGIVEREF(__pyx_t_11); + __Pyx_XGIVEREF(__pyx_t_12); + __Pyx_ExceptionReset(__pyx_t_10, __pyx_t_11, __pyx_t_12); + } + __Pyx_XGIVEREF(__pyx_t_7); + __Pyx_XGIVEREF(__pyx_t_8); + __Pyx_XGIVEREF(__pyx_t_9); + __Pyx_ErrRestore(__pyx_t_7, __pyx_t_8, __pyx_t_9); + __pyx_t_7 = 0; __pyx_t_8 = 0; __pyx_t_9 = 0; __pyx_t_10 = 0; __pyx_t_11 = 0; __pyx_t_12 = 0; + __pyx_lineno = __pyx_t_4; __pyx_clineno = __pyx_t_5; __pyx_filename = __pyx_t_6; + goto __pyx_L1_error; + } + __pyx_L7:; + } + + /* "View.MemoryView":453 + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) + * + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): # <<<<<<<<<<<<<< + * cdef int array[128] + * cdef void *tmp = NULL + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.setitem_slice_assign_scalar", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":485 + * PyMem_Free(tmp) + * + * cdef setitem_indexed(self, index, value): # <<<<<<<<<<<<<< + * cdef char *itemp = self.get_item_pointer(index) + * self.assign_item_from_object(itemp, value) + */ + +static PyObject *__pyx_memoryview_setitem_indexed(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value) { + char *__pyx_v_itemp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + char *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("setitem_indexed", 1); + + /* "View.MemoryView":486 + * + * cdef setitem_indexed(self, index, value): + * cdef char *itemp = self.get_item_pointer(index) # <<<<<<<<<<<<<< + * self.assign_item_from_object(itemp, value) + * + */ + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->get_item_pointer(__pyx_v_self, __pyx_v_index); if (unlikely(__pyx_t_1 == ((char *)NULL))) __PYX_ERR(1, 486, __pyx_L1_error) + __pyx_v_itemp = __pyx_t_1; + + /* "View.MemoryView":487 + * cdef setitem_indexed(self, index, value): + * cdef char *itemp = self.get_item_pointer(index) + * self.assign_item_from_object(itemp, value) # <<<<<<<<<<<<<< + * + * cdef convert_item_to_object(self, char *itemp): + */ + __pyx_t_2 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->assign_item_from_object(__pyx_v_self, __pyx_v_itemp, __pyx_v_value); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 487, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":485 + * PyMem_Free(tmp) + * + * cdef setitem_indexed(self, index, value): # <<<<<<<<<<<<<< + * cdef char *itemp = self.get_item_pointer(index) + * self.assign_item_from_object(itemp, value) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.setitem_indexed", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":489 + * self.assign_item_from_object(itemp, value) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + +static PyObject *__pyx_memoryview_convert_item_to_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp) { + PyObject *__pyx_v_struct = NULL; + PyObject *__pyx_v_bytesitem = 0; + PyObject *__pyx_v_result = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + int __pyx_t_8; + Py_ssize_t __pyx_t_9; + int __pyx_t_10; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("convert_item_to_object", 1); + + /* "View.MemoryView":492 + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + * import struct # <<<<<<<<<<<<<< + * cdef bytes bytesitem + * + */ + __pyx_t_1 = __Pyx_ImportDottedModule(__pyx_n_s_struct, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 492, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_struct = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":495 + * cdef bytes bytesitem + * + * bytesitem = itemp[:self.view.itemsize] # <<<<<<<<<<<<<< + * try: + * result = struct.unpack(self.view.format, bytesitem) + */ + __pyx_t_1 = __Pyx_PyBytes_FromStringAndSize(__pyx_v_itemp + 0, __pyx_v_self->view.itemsize - 0); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 495, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_bytesitem = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":496 + * + * bytesitem = itemp[:self.view.itemsize] + * try: # <<<<<<<<<<<<<< + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_2, &__pyx_t_3, &__pyx_t_4); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_4); + /*try:*/ { + + /* "View.MemoryView":497 + * bytesitem = itemp[:self.view.itemsize] + * try: + * result = struct.unpack(self.view.format, bytesitem) # <<<<<<<<<<<<<< + * except struct.error: + * raise ValueError, "Unable to convert item to object" + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_unpack); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 497, __pyx_L3_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = __Pyx_PyBytes_FromString(__pyx_v_self->view.format); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 497, __pyx_L3_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_7 = NULL; + __pyx_t_8 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_8 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_7, __pyx_t_6, __pyx_v_bytesitem}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_8, 2+__pyx_t_8); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 497, __pyx_L3_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + __pyx_v_result = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":496 + * + * bytesitem = itemp[:self.view.itemsize] + * try: # <<<<<<<<<<<<<< + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + */ + } + + /* "View.MemoryView":501 + * raise ValueError, "Unable to convert item to object" + * else: + * if len(self.view.format) == 1: # <<<<<<<<<<<<<< + * return result[0] + * return result + */ + /*else:*/ { + __pyx_t_9 = __Pyx_ssize_strlen(__pyx_v_self->view.format); if (unlikely(__pyx_t_9 == ((Py_ssize_t)-1))) __PYX_ERR(1, 501, __pyx_L5_except_error) + __pyx_t_10 = (__pyx_t_9 == 1); + if (__pyx_t_10) { + + /* "View.MemoryView":502 + * else: + * if len(self.view.format) == 1: + * return result[0] # <<<<<<<<<<<<<< + * return result + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_result, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 502, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L6_except_return; + + /* "View.MemoryView":501 + * raise ValueError, "Unable to convert item to object" + * else: + * if len(self.view.format) == 1: # <<<<<<<<<<<<<< + * return result[0] + * return result + */ + } + + /* "View.MemoryView":503 + * if len(self.view.format) == 1: + * return result[0] + * return result # <<<<<<<<<<<<<< + * + * cdef assign_item_from_object(self, char *itemp, object value): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_result); + __pyx_r = __pyx_v_result; + goto __pyx_L6_except_return; + } + __pyx_L3_error:; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":498 + * try: + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: # <<<<<<<<<<<<<< + * raise ValueError, "Unable to convert item to object" + * else: + */ + __Pyx_ErrFetch(&__pyx_t_1, &__pyx_t_5, &__pyx_t_6); + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_error); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 498, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_8 = __Pyx_PyErr_GivenExceptionMatches(__pyx_t_1, __pyx_t_7); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_ErrRestore(__pyx_t_1, __pyx_t_5, __pyx_t_6); + __pyx_t_1 = 0; __pyx_t_5 = 0; __pyx_t_6 = 0; + if (__pyx_t_8) { + __Pyx_AddTraceback("View.MemoryView.memoryview.convert_item_to_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_6, &__pyx_t_5, &__pyx_t_1) < 0) __PYX_ERR(1, 498, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_1); + + /* "View.MemoryView":499 + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + * raise ValueError, "Unable to convert item to object" # <<<<<<<<<<<<<< + * else: + * if len(self.view.format) == 1: + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Unable_to_convert_item_to_object, 0, 0); + __PYX_ERR(1, 499, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "View.MemoryView":496 + * + * bytesitem = itemp[:self.view.itemsize] + * try: # <<<<<<<<<<<<<< + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_ExceptionReset(__pyx_t_2, __pyx_t_3, __pyx_t_4); + goto __pyx_L1_error; + __pyx_L6_except_return:; + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_ExceptionReset(__pyx_t_2, __pyx_t_3, __pyx_t_4); + goto __pyx_L0; + } + + /* "View.MemoryView":489 + * self.assign_item_from_object(itemp, value) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("View.MemoryView.memoryview.convert_item_to_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_struct); + __Pyx_XDECREF(__pyx_v_bytesitem); + __Pyx_XDECREF(__pyx_v_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":505 + * return result + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + +static PyObject *__pyx_memoryview_assign_item_from_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value) { + PyObject *__pyx_v_struct = NULL; + char __pyx_v_c; + PyObject *__pyx_v_bytesvalue = 0; + Py_ssize_t __pyx_v_i; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + Py_ssize_t __pyx_t_7; + PyObject *__pyx_t_8 = NULL; + char *__pyx_t_9; + char *__pyx_t_10; + char *__pyx_t_11; + char *__pyx_t_12; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("assign_item_from_object", 1); + + /* "View.MemoryView":508 + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + * import struct # <<<<<<<<<<<<<< + * cdef char c + * cdef bytes bytesvalue + */ + __pyx_t_1 = __Pyx_ImportDottedModule(__pyx_n_s_struct, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 508, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_struct = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":513 + * cdef Py_ssize_t i + * + * if isinstance(value, tuple): # <<<<<<<<<<<<<< + * bytesvalue = struct.pack(self.view.format, *value) + * else: + */ + __pyx_t_2 = PyTuple_Check(__pyx_v_value); + if (__pyx_t_2) { + + /* "View.MemoryView":514 + * + * if isinstance(value, tuple): + * bytesvalue = struct.pack(self.view.format, *value) # <<<<<<<<<<<<<< + * else: + * bytesvalue = struct.pack(self.view.format, value) + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_pack); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyBytes_FromString(__pyx_v_self->view.format); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PyTuple_New(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_3)) __PYX_ERR(1, 514, __pyx_L1_error); + __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PySequence_Tuple(__pyx_v_value); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = PyNumber_Add(__pyx_t_4, __pyx_t_3); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PyObject_Call(__pyx_t_1, __pyx_t_5, NULL); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (!(likely(PyBytes_CheckExact(__pyx_t_3))||((__pyx_t_3) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_t_3))) __PYX_ERR(1, 514, __pyx_L1_error) + __pyx_v_bytesvalue = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":513 + * cdef Py_ssize_t i + * + * if isinstance(value, tuple): # <<<<<<<<<<<<<< + * bytesvalue = struct.pack(self.view.format, *value) + * else: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":516 + * bytesvalue = struct.pack(self.view.format, *value) + * else: + * bytesvalue = struct.pack(self.view.format, value) # <<<<<<<<<<<<<< + * + * for i, c in enumerate(bytesvalue): + */ + /*else*/ { + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_pack); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 516, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 = __Pyx_PyBytes_FromString(__pyx_v_self->view.format); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 516, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_4 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_4, __pyx_t_1, __pyx_v_value}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 516, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + if (!(likely(PyBytes_CheckExact(__pyx_t_3))||((__pyx_t_3) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_t_3))) __PYX_ERR(1, 516, __pyx_L1_error) + __pyx_v_bytesvalue = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; + } + __pyx_L3:; + + /* "View.MemoryView":518 + * bytesvalue = struct.pack(self.view.format, value) + * + * for i, c in enumerate(bytesvalue): # <<<<<<<<<<<<<< + * itemp[i] = c + * + */ + __pyx_t_7 = 0; + if (unlikely(__pyx_v_bytesvalue == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' is not iterable"); + __PYX_ERR(1, 518, __pyx_L1_error) + } + __Pyx_INCREF(__pyx_v_bytesvalue); + __pyx_t_8 = __pyx_v_bytesvalue; + __pyx_t_10 = PyBytes_AS_STRING(__pyx_t_8); + __pyx_t_11 = (__pyx_t_10 + PyBytes_GET_SIZE(__pyx_t_8)); + for (__pyx_t_12 = __pyx_t_10; __pyx_t_12 < __pyx_t_11; __pyx_t_12++) { + __pyx_t_9 = __pyx_t_12; + __pyx_v_c = (__pyx_t_9[0]); + + /* "View.MemoryView":519 + * + * for i, c in enumerate(bytesvalue): + * itemp[i] = c # <<<<<<<<<<<<<< + * + * @cname('getbuffer') + */ + __pyx_v_i = __pyx_t_7; + + /* "View.MemoryView":518 + * bytesvalue = struct.pack(self.view.format, value) + * + * for i, c in enumerate(bytesvalue): # <<<<<<<<<<<<<< + * itemp[i] = c + * + */ + __pyx_t_7 = (__pyx_t_7 + 1); + + /* "View.MemoryView":519 + * + * for i, c in enumerate(bytesvalue): + * itemp[i] = c # <<<<<<<<<<<<<< + * + * @cname('getbuffer') + */ + (__pyx_v_itemp[__pyx_v_i]) = __pyx_v_c; + } + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + + /* "View.MemoryView":505 + * return result + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("View.MemoryView.memoryview.assign_item_from_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_struct); + __Pyx_XDECREF(__pyx_v_bytesvalue); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":521 + * itemp[i] = c + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: + */ + +/* Python wrapper */ +CYTHON_UNUSED static int __pyx_memoryview_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +CYTHON_UNUSED static int __pyx_memoryview_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getbuffer__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_8__getbuffer__(((struct __pyx_memoryview_obj *)__pyx_v_self), ((Py_buffer *)__pyx_v_info), ((int)__pyx_v_flags)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_8__getbuffer__(struct __pyx_memoryview_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + Py_ssize_t *__pyx_t_3; + char *__pyx_t_4; + void *__pyx_t_5; + int __pyx_t_6; + Py_ssize_t __pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + if (unlikely(__pyx_v_info == NULL)) { + PyErr_SetString(PyExc_BufferError, "PyObject_GetBuffer: view==NULL argument is obsolete"); + return -1; + } + __Pyx_RefNannySetupContext("__getbuffer__", 0); + __pyx_v_info->obj = Py_None; __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(__pyx_v_info->obj); + + /* "View.MemoryView":523 + * @cname('getbuffer') + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: # <<<<<<<<<<<<<< + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + */ + __pyx_t_2 = ((__pyx_v_flags & PyBUF_WRITABLE) != 0); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_1 = __pyx_v_self->view.readonly; + __pyx_L4_bool_binop_done:; + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":524 + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: + * raise ValueError, "Cannot create writable memory view from read-only memoryview" # <<<<<<<<<<<<<< + * + * if flags & PyBUF_ND: + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Cannot_create_writable_memory_vi, 0, 0); + __PYX_ERR(1, 524, __pyx_L1_error) + + /* "View.MemoryView":523 + * @cname('getbuffer') + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: # <<<<<<<<<<<<<< + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + */ + } + + /* "View.MemoryView":526 + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + * if flags & PyBUF_ND: # <<<<<<<<<<<<<< + * info.shape = self.view.shape + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_ND) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":527 + * + * if flags & PyBUF_ND: + * info.shape = self.view.shape # <<<<<<<<<<<<<< + * else: + * info.shape = NULL + */ + __pyx_t_3 = __pyx_v_self->view.shape; + __pyx_v_info->shape = __pyx_t_3; + + /* "View.MemoryView":526 + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + * if flags & PyBUF_ND: # <<<<<<<<<<<<<< + * info.shape = self.view.shape + * else: + */ + goto __pyx_L6; + } + + /* "View.MemoryView":529 + * info.shape = self.view.shape + * else: + * info.shape = NULL # <<<<<<<<<<<<<< + * + * if flags & PyBUF_STRIDES: + */ + /*else*/ { + __pyx_v_info->shape = NULL; + } + __pyx_L6:; + + /* "View.MemoryView":531 + * info.shape = NULL + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.strides = self.view.strides + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_STRIDES) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":532 + * + * if flags & PyBUF_STRIDES: + * info.strides = self.view.strides # <<<<<<<<<<<<<< + * else: + * info.strides = NULL + */ + __pyx_t_3 = __pyx_v_self->view.strides; + __pyx_v_info->strides = __pyx_t_3; + + /* "View.MemoryView":531 + * info.shape = NULL + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.strides = self.view.strides + * else: + */ + goto __pyx_L7; + } + + /* "View.MemoryView":534 + * info.strides = self.view.strides + * else: + * info.strides = NULL # <<<<<<<<<<<<<< + * + * if flags & PyBUF_INDIRECT: + */ + /*else*/ { + __pyx_v_info->strides = NULL; + } + __pyx_L7:; + + /* "View.MemoryView":536 + * info.strides = NULL + * + * if flags & PyBUF_INDIRECT: # <<<<<<<<<<<<<< + * info.suboffsets = self.view.suboffsets + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_INDIRECT) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":537 + * + * if flags & PyBUF_INDIRECT: + * info.suboffsets = self.view.suboffsets # <<<<<<<<<<<<<< + * else: + * info.suboffsets = NULL + */ + __pyx_t_3 = __pyx_v_self->view.suboffsets; + __pyx_v_info->suboffsets = __pyx_t_3; + + /* "View.MemoryView":536 + * info.strides = NULL + * + * if flags & PyBUF_INDIRECT: # <<<<<<<<<<<<<< + * info.suboffsets = self.view.suboffsets + * else: + */ + goto __pyx_L8; + } + + /* "View.MemoryView":539 + * info.suboffsets = self.view.suboffsets + * else: + * info.suboffsets = NULL # <<<<<<<<<<<<<< + * + * if flags & PyBUF_FORMAT: + */ + /*else*/ { + __pyx_v_info->suboffsets = NULL; + } + __pyx_L8:; + + /* "View.MemoryView":541 + * info.suboffsets = NULL + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * info.format = self.view.format + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_FORMAT) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":542 + * + * if flags & PyBUF_FORMAT: + * info.format = self.view.format # <<<<<<<<<<<<<< + * else: + * info.format = NULL + */ + __pyx_t_4 = __pyx_v_self->view.format; + __pyx_v_info->format = __pyx_t_4; + + /* "View.MemoryView":541 + * info.suboffsets = NULL + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * info.format = self.view.format + * else: + */ + goto __pyx_L9; + } + + /* "View.MemoryView":544 + * info.format = self.view.format + * else: + * info.format = NULL # <<<<<<<<<<<<<< + * + * info.buf = self.view.buf + */ + /*else*/ { + __pyx_v_info->format = NULL; + } + __pyx_L9:; + + /* "View.MemoryView":546 + * info.format = NULL + * + * info.buf = self.view.buf # <<<<<<<<<<<<<< + * info.ndim = self.view.ndim + * info.itemsize = self.view.itemsize + */ + __pyx_t_5 = __pyx_v_self->view.buf; + __pyx_v_info->buf = __pyx_t_5; + + /* "View.MemoryView":547 + * + * info.buf = self.view.buf + * info.ndim = self.view.ndim # <<<<<<<<<<<<<< + * info.itemsize = self.view.itemsize + * info.len = self.view.len + */ + __pyx_t_6 = __pyx_v_self->view.ndim; + __pyx_v_info->ndim = __pyx_t_6; + + /* "View.MemoryView":548 + * info.buf = self.view.buf + * info.ndim = self.view.ndim + * info.itemsize = self.view.itemsize # <<<<<<<<<<<<<< + * info.len = self.view.len + * info.readonly = self.view.readonly + */ + __pyx_t_7 = __pyx_v_self->view.itemsize; + __pyx_v_info->itemsize = __pyx_t_7; + + /* "View.MemoryView":549 + * info.ndim = self.view.ndim + * info.itemsize = self.view.itemsize + * info.len = self.view.len # <<<<<<<<<<<<<< + * info.readonly = self.view.readonly + * info.obj = self + */ + __pyx_t_7 = __pyx_v_self->view.len; + __pyx_v_info->len = __pyx_t_7; + + /* "View.MemoryView":550 + * info.itemsize = self.view.itemsize + * info.len = self.view.len + * info.readonly = self.view.readonly # <<<<<<<<<<<<<< + * info.obj = self + * + */ + __pyx_t_1 = __pyx_v_self->view.readonly; + __pyx_v_info->readonly = __pyx_t_1; + + /* "View.MemoryView":551 + * info.len = self.view.len + * info.readonly = self.view.readonly + * info.obj = self # <<<<<<<<<<<<<< + * + * + */ + __Pyx_INCREF((PyObject *)__pyx_v_self); + __Pyx_GIVEREF((PyObject *)__pyx_v_self); + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); + __pyx_v_info->obj = ((PyObject *)__pyx_v_self); + + /* "View.MemoryView":521 + * itemp[i] = c + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__getbuffer__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + if (__pyx_v_info->obj != NULL) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + goto __pyx_L2; + __pyx_L0:; + if (__pyx_v_info->obj == Py_None) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + __pyx_L2:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":554 + * + * + * @property # <<<<<<<<<<<<<< + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_1T_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_1T_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_1T___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_1T___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + struct __pyx_memoryviewslice_obj *__pyx_v_result = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":556 + * @property + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) # <<<<<<<<<<<<<< + * transpose_memslice(&result.from_slice) + * return result + */ + __pyx_t_1 = __pyx_memoryview_copy_object(__pyx_v_self); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 556, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (!(likely(((__pyx_t_1) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_1, __pyx_memoryviewslice_type))))) __PYX_ERR(1, 556, __pyx_L1_error) + __pyx_v_result = ((struct __pyx_memoryviewslice_obj *)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":557 + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) + * transpose_memslice(&result.from_slice) # <<<<<<<<<<<<<< + * return result + * + */ + __pyx_t_2 = __pyx_memslice_transpose((&__pyx_v_result->from_slice)); if (unlikely(__pyx_t_2 == ((int)-1))) __PYX_ERR(1, 557, __pyx_L1_error) + + /* "View.MemoryView":558 + * cdef _memoryviewslice result = memoryview_copy(self) + * transpose_memslice(&result.from_slice) + * return result # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = ((PyObject *)__pyx_v_result); + goto __pyx_L0; + + /* "View.MemoryView":554 + * + * + * @property # <<<<<<<<<<<<<< + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.T.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":560 + * return result + * + * @property # <<<<<<<<<<<<<< + * def base(self): + * return self._get_base() + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4base_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4base_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_4base___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4base___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":562 + * @property + * def base(self): + * return self._get_base() # <<<<<<<<<<<<<< + * + * cdef _get_base(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->_get_base(__pyx_v_self); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 562, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":560 + * return result + * + * @property # <<<<<<<<<<<<<< + * def base(self): + * return self._get_base() + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.base.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":564 + * return self._get_base() + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.obj + * + */ + +static PyObject *__pyx_memoryview__get_base(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("_get_base", 1); + + /* "View.MemoryView":565 + * + * cdef _get_base(self): + * return self.obj # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->obj); + __pyx_r = __pyx_v_self->obj; + goto __pyx_L0; + + /* "View.MemoryView":564 + * return self._get_base() + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.obj + * + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":567 + * return self.obj + * + * @property # <<<<<<<<<<<<<< + * def shape(self): + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_5shape_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_5shape_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_5shape___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_5shape___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_7genexpr__pyx_v_length; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + PyObject *__pyx_t_5 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":569 + * @property + * def shape(self): + * return tuple([length for length in self.view.shape[:self.view.ndim]]) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + { /* enter inner scope */ + __pyx_t_1 = PyList_New(0); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 569, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = (__pyx_v_self->view.shape + __pyx_v_self->view.ndim); + for (__pyx_t_4 = __pyx_v_self->view.shape; __pyx_t_4 < __pyx_t_3; __pyx_t_4++) { + __pyx_t_2 = __pyx_t_4; + __pyx_7genexpr__pyx_v_length = (__pyx_t_2[0]); + __pyx_t_5 = PyInt_FromSsize_t(__pyx_7genexpr__pyx_v_length); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 569, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_1, (PyObject*)__pyx_t_5))) __PYX_ERR(1, 569, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + } /* exit inner scope */ + __pyx_t_5 = PyList_AsTuple(((PyObject*)__pyx_t_1)); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 569, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_5; + __pyx_t_5 = 0; + goto __pyx_L0; + + /* "View.MemoryView":567 + * return self.obj + * + * @property # <<<<<<<<<<<<<< + * def shape(self): + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.memoryview.shape.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":571 + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def strides(self): + * if self.view.strides == NULL: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_7strides_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_7strides_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_7strides___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_7strides___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_8genexpr1__pyx_v_stride; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + Py_ssize_t *__pyx_t_5; + PyObject *__pyx_t_6 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":573 + * @property + * def strides(self): + * if self.view.strides == NULL: # <<<<<<<<<<<<<< + * + * raise ValueError, "Buffer view does not expose strides" + */ + __pyx_t_1 = (__pyx_v_self->view.strides == NULL); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":575 + * if self.view.strides == NULL: + * + * raise ValueError, "Buffer view does not expose strides" # <<<<<<<<<<<<<< + * + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Buffer_view_does_not_expose_stri, 0, 0); + __PYX_ERR(1, 575, __pyx_L1_error) + + /* "View.MemoryView":573 + * @property + * def strides(self): + * if self.view.strides == NULL: # <<<<<<<<<<<<<< + * + * raise ValueError, "Buffer view does not expose strides" + */ + } + + /* "View.MemoryView":577 + * raise ValueError, "Buffer view does not expose strides" + * + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + { /* enter inner scope */ + __pyx_t_2 = PyList_New(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 577, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = (__pyx_v_self->view.strides + __pyx_v_self->view.ndim); + for (__pyx_t_5 = __pyx_v_self->view.strides; __pyx_t_5 < __pyx_t_4; __pyx_t_5++) { + __pyx_t_3 = __pyx_t_5; + __pyx_8genexpr1__pyx_v_stride = (__pyx_t_3[0]); + __pyx_t_6 = PyInt_FromSsize_t(__pyx_8genexpr1__pyx_v_stride); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 577, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_2, (PyObject*)__pyx_t_6))) __PYX_ERR(1, 577, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + } /* exit inner scope */ + __pyx_t_6 = PyList_AsTuple(((PyObject*)__pyx_t_2)); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 577, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_6; + __pyx_t_6 = 0; + goto __pyx_L0; + + /* "View.MemoryView":571 + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def strides(self): + * if self.view.strides == NULL: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("View.MemoryView.memoryview.strides.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":579 + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def suboffsets(self): + * if self.view.suboffsets == NULL: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_10suboffsets_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_10suboffsets_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_10suboffsets___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_10suboffsets___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_8genexpr2__pyx_v_suboffset; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + Py_ssize_t *__pyx_t_5; + PyObject *__pyx_t_6 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":581 + * @property + * def suboffsets(self): + * if self.view.suboffsets == NULL: # <<<<<<<<<<<<<< + * return (-1,) * self.view.ndim + * + */ + __pyx_t_1 = (__pyx_v_self->view.suboffsets == NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":582 + * def suboffsets(self): + * if self.view.suboffsets == NULL: + * return (-1,) * self.view.ndim # <<<<<<<<<<<<<< + * + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PySequence_Multiply(__pyx_tuple__4, __pyx_v_self->view.ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 582, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":581 + * @property + * def suboffsets(self): + * if self.view.suboffsets == NULL: # <<<<<<<<<<<<<< + * return (-1,) * self.view.ndim + * + */ + } + + /* "View.MemoryView":584 + * return (-1,) * self.view.ndim + * + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + { /* enter inner scope */ + __pyx_t_2 = PyList_New(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 584, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = (__pyx_v_self->view.suboffsets + __pyx_v_self->view.ndim); + for (__pyx_t_5 = __pyx_v_self->view.suboffsets; __pyx_t_5 < __pyx_t_4; __pyx_t_5++) { + __pyx_t_3 = __pyx_t_5; + __pyx_8genexpr2__pyx_v_suboffset = (__pyx_t_3[0]); + __pyx_t_6 = PyInt_FromSsize_t(__pyx_8genexpr2__pyx_v_suboffset); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 584, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_2, (PyObject*)__pyx_t_6))) __PYX_ERR(1, 584, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + } /* exit inner scope */ + __pyx_t_6 = PyList_AsTuple(((PyObject*)__pyx_t_2)); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 584, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_6; + __pyx_t_6 = 0; + goto __pyx_L0; + + /* "View.MemoryView":579 + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def suboffsets(self): + * if self.view.suboffsets == NULL: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("View.MemoryView.memoryview.suboffsets.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":586 + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def ndim(self): + * return self.view.ndim + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4ndim_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4ndim_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_4ndim___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4ndim___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":588 + * @property + * def ndim(self): + * return self.view.ndim # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_self->view.ndim); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 588, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":586 + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def ndim(self): + * return self.view.ndim + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.ndim.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":590 + * return self.view.ndim + * + * @property # <<<<<<<<<<<<<< + * def itemsize(self): + * return self.view.itemsize + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_8itemsize_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_8itemsize_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_8itemsize___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_8itemsize___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":592 + * @property + * def itemsize(self): + * return self.view.itemsize # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyInt_FromSsize_t(__pyx_v_self->view.itemsize); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 592, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":590 + * return self.view.ndim + * + * @property # <<<<<<<<<<<<<< + * def itemsize(self): + * return self.view.itemsize + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.itemsize.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":594 + * return self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def nbytes(self): + * return self.size * self.view.itemsize + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_6nbytes_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_6nbytes_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_6nbytes___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_6nbytes___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":596 + * @property + * def nbytes(self): + * return self.size * self.view.itemsize # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_size); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 596, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = PyInt_FromSsize_t(__pyx_v_self->view.itemsize); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 596, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyNumber_Multiply(__pyx_t_1, __pyx_t_2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 596, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_3; + __pyx_t_3 = 0; + goto __pyx_L0; + + /* "View.MemoryView":594 + * return self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def nbytes(self): + * return self.size * self.view.itemsize + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.nbytes.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":598 + * return self.size * self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def size(self): + * if self._size is None: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4size_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4size_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_4size___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4size___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_v_result = NULL; + PyObject *__pyx_v_length = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + PyObject *__pyx_t_5 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":600 + * @property + * def size(self): + * if self._size is None: # <<<<<<<<<<<<<< + * result = 1 + * + */ + __pyx_t_1 = (__pyx_v_self->_size == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":601 + * def size(self): + * if self._size is None: + * result = 1 # <<<<<<<<<<<<<< + * + * for length in self.view.shape[:self.view.ndim]: + */ + __Pyx_INCREF(__pyx_int_1); + __pyx_v_result = __pyx_int_1; + + /* "View.MemoryView":603 + * result = 1 + * + * for length in self.view.shape[:self.view.ndim]: # <<<<<<<<<<<<<< + * result *= length + * + */ + __pyx_t_3 = (__pyx_v_self->view.shape + __pyx_v_self->view.ndim); + for (__pyx_t_4 = __pyx_v_self->view.shape; __pyx_t_4 < __pyx_t_3; __pyx_t_4++) { + __pyx_t_2 = __pyx_t_4; + __pyx_t_5 = PyInt_FromSsize_t((__pyx_t_2[0])); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 603, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_XDECREF_SET(__pyx_v_length, __pyx_t_5); + __pyx_t_5 = 0; + + /* "View.MemoryView":604 + * + * for length in self.view.shape[:self.view.ndim]: + * result *= length # <<<<<<<<<<<<<< + * + * self._size = result + */ + __pyx_t_5 = PyNumber_InPlaceMultiply(__pyx_v_result, __pyx_v_length); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 604, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF_SET(__pyx_v_result, __pyx_t_5); + __pyx_t_5 = 0; + } + + /* "View.MemoryView":606 + * result *= length + * + * self._size = result # <<<<<<<<<<<<<< + * + * return self._size + */ + __Pyx_INCREF(__pyx_v_result); + __Pyx_GIVEREF(__pyx_v_result); + __Pyx_GOTREF(__pyx_v_self->_size); + __Pyx_DECREF(__pyx_v_self->_size); + __pyx_v_self->_size = __pyx_v_result; + + /* "View.MemoryView":600 + * @property + * def size(self): + * if self._size is None: # <<<<<<<<<<<<<< + * result = 1 + * + */ + } + + /* "View.MemoryView":608 + * self._size = result + * + * return self._size # <<<<<<<<<<<<<< + * + * def __len__(self): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->_size); + __pyx_r = __pyx_v_self->_size; + goto __pyx_L0; + + /* "View.MemoryView":598 + * return self.size * self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def size(self): + * if self._size is None: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.memoryview.size.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_result); + __Pyx_XDECREF(__pyx_v_length); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":610 + * return self._size + * + * def __len__(self): # <<<<<<<<<<<<<< + * if self.view.ndim >= 1: + * return self.view.shape[0] + */ + +/* Python wrapper */ +static Py_ssize_t __pyx_memoryview___len__(PyObject *__pyx_v_self); /*proto*/ +static Py_ssize_t __pyx_memoryview___len__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + Py_ssize_t __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__len__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_10__len__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static Py_ssize_t __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_10__len__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_r; + int __pyx_t_1; + + /* "View.MemoryView":611 + * + * def __len__(self): + * if self.view.ndim >= 1: # <<<<<<<<<<<<<< + * return self.view.shape[0] + * + */ + __pyx_t_1 = (__pyx_v_self->view.ndim >= 1); + if (__pyx_t_1) { + + /* "View.MemoryView":612 + * def __len__(self): + * if self.view.ndim >= 1: + * return self.view.shape[0] # <<<<<<<<<<<<<< + * + * return 0 + */ + __pyx_r = (__pyx_v_self->view.shape[0]); + goto __pyx_L0; + + /* "View.MemoryView":611 + * + * def __len__(self): + * if self.view.ndim >= 1: # <<<<<<<<<<<<<< + * return self.view.shape[0] + * + */ + } + + /* "View.MemoryView":614 + * return self.view.shape[0] + * + * return 0 # <<<<<<<<<<<<<< + * + * def __repr__(self): + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":610 + * return self._size + * + * def __len__(self): # <<<<<<<<<<<<<< + * if self.view.ndim >= 1: + * return self.view.shape[0] + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":616 + * return 0 + * + * def __repr__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__, + * id(self)) + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview___repr__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_memoryview___repr__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__repr__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_12__repr__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_12__repr__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__repr__", 1); + + /* "View.MemoryView":617 + * + * def __repr__(self): + * return "" % (self.base.__class__.__name__, # <<<<<<<<<<<<<< + * id(self)) + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_base); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_class); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_name_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":618 + * def __repr__(self): + * return "" % (self.base.__class__.__name__, + * id(self)) # <<<<<<<<<<<<<< + * + * def __str__(self): + */ + __pyx_t_2 = __Pyx_PyObject_CallOneArg(__pyx_builtin_id, ((PyObject *)__pyx_v_self)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 618, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + + /* "View.MemoryView":617 + * + * def __repr__(self): + * return "" % (self.base.__class__.__name__, # <<<<<<<<<<<<<< + * id(self)) + * + */ + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_1)) __PYX_ERR(1, 617, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_2)) __PYX_ERR(1, 617, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyString_Format(__pyx_kp_s_MemoryView_of_r_at_0x_x, __pyx_t_3); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":616 + * return 0 + * + * def __repr__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__, + * id(self)) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.__repr__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":620 + * id(self)) + * + * def __str__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__,) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview___str__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_memoryview___str__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__str__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_14__str__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_14__str__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__str__", 1); + + /* "View.MemoryView":621 + * + * def __str__(self): + * return "" % (self.base.__class__.__name__,) # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_base); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_class); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_name_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = PyTuple_New(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_t_1)) __PYX_ERR(1, 621, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_MemoryView_of_r_object, __pyx_t_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":620 + * id(self)) + * + * def __str__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__,) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.__str__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":624 + * + * + * def is_c_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_is_c_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_is_c_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("is_c_contig (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("is_c_contig", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "is_c_contig", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_16is_c_contig(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_16is_c_contig(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice *__pyx_v_mslice; + __Pyx_memviewslice __pyx_v_tmp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("is_c_contig", 1); + + /* "View.MemoryView":627 + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) # <<<<<<<<<<<<<< + * return slice_is_contig(mslice[0], 'C', self.view.ndim) + * + */ + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(__pyx_v_self, (&__pyx_v_tmp)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 627, __pyx_L1_error) + __pyx_v_mslice = __pyx_t_1; + + /* "View.MemoryView":628 + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) + * return slice_is_contig(mslice[0], 'C', self.view.ndim) # <<<<<<<<<<<<<< + * + * def is_f_contig(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_memviewslice_is_contig((__pyx_v_mslice[0]), 'C', __pyx_v_self->view.ndim)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 628, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":624 + * + * + * def is_c_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.is_c_contig", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":630 + * return slice_is_contig(mslice[0], 'C', self.view.ndim) + * + * def is_f_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_is_f_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_is_f_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("is_f_contig (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("is_f_contig", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "is_f_contig", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_18is_f_contig(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_18is_f_contig(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice *__pyx_v_mslice; + __Pyx_memviewslice __pyx_v_tmp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("is_f_contig", 1); + + /* "View.MemoryView":633 + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) # <<<<<<<<<<<<<< + * return slice_is_contig(mslice[0], 'F', self.view.ndim) + * + */ + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(__pyx_v_self, (&__pyx_v_tmp)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(1, 633, __pyx_L1_error) + __pyx_v_mslice = __pyx_t_1; + + /* "View.MemoryView":634 + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) + * return slice_is_contig(mslice[0], 'F', self.view.ndim) # <<<<<<<<<<<<<< + * + * def copy(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_memviewslice_is_contig((__pyx_v_mslice[0]), 'F', __pyx_v_self->view.ndim)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 634, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":630 + * return slice_is_contig(mslice[0], 'C', self.view.ndim) + * + * def is_f_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.is_f_contig", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":636 + * return slice_is_contig(mslice[0], 'F', self.view.ndim) + * + * def copy(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice mslice + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_copy(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_copy(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("copy (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("copy", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "copy", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_20copy(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_20copy(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice __pyx_v_mslice; + int __pyx_v_flags; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("copy", 1); + + /* "View.MemoryView":638 + * def copy(self): + * cdef __Pyx_memviewslice mslice + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS # <<<<<<<<<<<<<< + * + * slice_copy(self, &mslice) + */ + __pyx_v_flags = (__pyx_v_self->flags & (~PyBUF_F_CONTIGUOUS)); + + /* "View.MemoryView":640 + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS + * + * slice_copy(self, &mslice) # <<<<<<<<<<<<<< + * mslice = slice_copy_contig(&mslice, "c", self.view.ndim, + * self.view.itemsize, + */ + __pyx_memoryview_slice_copy(__pyx_v_self, (&__pyx_v_mslice)); + + /* "View.MemoryView":641 + * + * slice_copy(self, &mslice) + * mslice = slice_copy_contig(&mslice, "c", self.view.ndim, # <<<<<<<<<<<<<< + * self.view.itemsize, + * flags|PyBUF_C_CONTIGUOUS, + */ + __pyx_t_1 = __pyx_memoryview_copy_new_contig((&__pyx_v_mslice), ((char *)"c"), __pyx_v_self->view.ndim, __pyx_v_self->view.itemsize, (__pyx_v_flags | PyBUF_C_CONTIGUOUS), __pyx_v_self->dtype_is_object); if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 641, __pyx_L1_error) + __pyx_v_mslice = __pyx_t_1; + + /* "View.MemoryView":646 + * self.dtype_is_object) + * + * return memoryview_copy_from_slice(self, &mslice) # <<<<<<<<<<<<<< + * + * def copy_fortran(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_memoryview_copy_object_from_slice(__pyx_v_self, (&__pyx_v_mslice)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 646, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":636 + * return slice_is_contig(mslice[0], 'F', self.view.ndim) + * + * def copy(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice mslice + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.copy", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":648 + * return memoryview_copy_from_slice(self, &mslice) + * + * def copy_fortran(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice src, dst + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_copy_fortran(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_copy_fortran(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("copy_fortran (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("copy_fortran", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "copy_fortran", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_22copy_fortran(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_22copy_fortran(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice __pyx_v_src; + __Pyx_memviewslice __pyx_v_dst; + int __pyx_v_flags; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("copy_fortran", 1); + + /* "View.MemoryView":650 + * def copy_fortran(self): + * cdef __Pyx_memviewslice src, dst + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS # <<<<<<<<<<<<<< + * + * slice_copy(self, &src) + */ + __pyx_v_flags = (__pyx_v_self->flags & (~PyBUF_C_CONTIGUOUS)); + + /* "View.MemoryView":652 + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS + * + * slice_copy(self, &src) # <<<<<<<<<<<<<< + * dst = slice_copy_contig(&src, "fortran", self.view.ndim, + * self.view.itemsize, + */ + __pyx_memoryview_slice_copy(__pyx_v_self, (&__pyx_v_src)); + + /* "View.MemoryView":653 + * + * slice_copy(self, &src) + * dst = slice_copy_contig(&src, "fortran", self.view.ndim, # <<<<<<<<<<<<<< + * self.view.itemsize, + * flags|PyBUF_F_CONTIGUOUS, + */ + __pyx_t_1 = __pyx_memoryview_copy_new_contig((&__pyx_v_src), ((char *)"fortran"), __pyx_v_self->view.ndim, __pyx_v_self->view.itemsize, (__pyx_v_flags | PyBUF_F_CONTIGUOUS), __pyx_v_self->dtype_is_object); if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 653, __pyx_L1_error) + __pyx_v_dst = __pyx_t_1; + + /* "View.MemoryView":658 + * self.dtype_is_object) + * + * return memoryview_copy_from_slice(self, &dst) # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_memoryview_copy_object_from_slice(__pyx_v_self, (&__pyx_v_dst)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 658, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":648 + * return memoryview_copy_from_slice(self, &mslice) + * + * def copy_fortran(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice src, dst + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.copy_fortran", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryview_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryview_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_memoryview___reduce_cython__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryview___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryview_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryview_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.memoryview.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_memoryview_2__setstate_cython__(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryview_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":662 + * + * @cname('__pyx_memoryview_new') + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): # <<<<<<<<<<<<<< + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo + */ + +static PyObject *__pyx_memoryview_new(PyObject *__pyx_v_o, int __pyx_v_flags, int __pyx_v_dtype_is_object, __Pyx_TypeInfo *__pyx_v_typeinfo) { + struct __pyx_memoryview_obj *__pyx_v_result = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_cwrapper", 1); + + /* "View.MemoryView":663 + * @cname('__pyx_memoryview_new') + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): + * cdef memoryview result = memoryview(o, flags, dtype_is_object) # <<<<<<<<<<<<<< + * result.typeinfo = typeinfo + * return result + */ + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_flags); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_v_dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_v_o); + __Pyx_GIVEREF(__pyx_v_o); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_v_o)) __PYX_ERR(1, 663, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1)) __PYX_ERR(1, 663, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_t_2)) __PYX_ERR(1, 663, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_Call(((PyObject *)__pyx_memoryview_type), __pyx_t_3, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_v_result = ((struct __pyx_memoryview_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":664 + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo # <<<<<<<<<<<<<< + * return result + * + */ + __pyx_v_result->typeinfo = __pyx_v_typeinfo; + + /* "View.MemoryView":665 + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo + * return result # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_check') + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = ((PyObject *)__pyx_v_result); + goto __pyx_L0; + + /* "View.MemoryView":662 + * + * @cname('__pyx_memoryview_new') + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): # <<<<<<<<<<<<<< + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview_cwrapper", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":668 + * + * @cname('__pyx_memoryview_check') + * cdef inline bint memoryview_check(object o) noexcept: # <<<<<<<<<<<<<< + * return isinstance(o, memoryview) + * + */ + +static CYTHON_INLINE int __pyx_memoryview_check(PyObject *__pyx_v_o) { + int __pyx_r; + int __pyx_t_1; + + /* "View.MemoryView":669 + * @cname('__pyx_memoryview_check') + * cdef inline bint memoryview_check(object o) noexcept: + * return isinstance(o, memoryview) # <<<<<<<<<<<<<< + * + * cdef tuple _unellipsify(object index, int ndim): + */ + __pyx_t_1 = __Pyx_TypeCheck(__pyx_v_o, __pyx_memoryview_type); + __pyx_r = __pyx_t_1; + goto __pyx_L0; + + /* "View.MemoryView":668 + * + * @cname('__pyx_memoryview_check') + * cdef inline bint memoryview_check(object o) noexcept: # <<<<<<<<<<<<<< + * return isinstance(o, memoryview) + * + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":671 + * return isinstance(o, memoryview) + * + * cdef tuple _unellipsify(object index, int ndim): # <<<<<<<<<<<<<< + * """ + * Replace all ellipses with full slices and fill incomplete indices with + */ + +static PyObject *_unellipsify(PyObject *__pyx_v_index, int __pyx_v_ndim) { + Py_ssize_t __pyx_v_idx; + PyObject *__pyx_v_tup = NULL; + PyObject *__pyx_v_result = NULL; + int __pyx_v_have_slices; + int __pyx_v_seen_ellipsis; + PyObject *__pyx_v_item = NULL; + Py_ssize_t __pyx_v_nslices; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + Py_ssize_t __pyx_t_4; + Py_ssize_t __pyx_t_5; + Py_UCS4 __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("_unellipsify", 1); + + /* "View.MemoryView":677 + * """ + * cdef Py_ssize_t idx + * tup = index if isinstance(index, tuple) else (index,) # <<<<<<<<<<<<<< + * + * result = [slice(None)] * ndim + */ + __pyx_t_2 = PyTuple_Check(__pyx_v_index); + if (__pyx_t_2) { + __Pyx_INCREF(((PyObject*)__pyx_v_index)); + __pyx_t_1 = __pyx_v_index; + } else { + __pyx_t_3 = PyTuple_New(1); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 677, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_v_index); + __Pyx_GIVEREF(__pyx_v_index); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_v_index)) __PYX_ERR(1, 677, __pyx_L1_error); + __pyx_t_1 = __pyx_t_3; + __pyx_t_3 = 0; + } + __pyx_v_tup = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":679 + * tup = index if isinstance(index, tuple) else (index,) + * + * result = [slice(None)] * ndim # <<<<<<<<<<<<<< + * have_slices = False + * seen_ellipsis = False + */ + __pyx_t_1 = PyList_New(1 * ((__pyx_v_ndim<0) ? 0:__pyx_v_ndim)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 679, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + { Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < __pyx_v_ndim; __pyx_temp++) { + __Pyx_INCREF(__pyx_slice__5); + __Pyx_GIVEREF(__pyx_slice__5); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, __pyx_temp, __pyx_slice__5)) __PYX_ERR(1, 679, __pyx_L1_error); + } + } + __pyx_v_result = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":680 + * + * result = [slice(None)] * ndim + * have_slices = False # <<<<<<<<<<<<<< + * seen_ellipsis = False + * idx = 0 + */ + __pyx_v_have_slices = 0; + + /* "View.MemoryView":681 + * result = [slice(None)] * ndim + * have_slices = False + * seen_ellipsis = False # <<<<<<<<<<<<<< + * idx = 0 + * for item in tup: + */ + __pyx_v_seen_ellipsis = 0; + + /* "View.MemoryView":682 + * have_slices = False + * seen_ellipsis = False + * idx = 0 # <<<<<<<<<<<<<< + * for item in tup: + * if item is Ellipsis: + */ + __pyx_v_idx = 0; + + /* "View.MemoryView":683 + * seen_ellipsis = False + * idx = 0 + * for item in tup: # <<<<<<<<<<<<<< + * if item is Ellipsis: + * if not seen_ellipsis: + */ + if (unlikely(__pyx_v_tup == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not iterable"); + __PYX_ERR(1, 683, __pyx_L1_error) + } + __pyx_t_1 = __pyx_v_tup; __Pyx_INCREF(__pyx_t_1); + __pyx_t_4 = 0; + for (;;) { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_1); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 683, __pyx_L1_error) + #endif + if (__pyx_t_4 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_3 = PyTuple_GET_ITEM(__pyx_t_1, __pyx_t_4); __Pyx_INCREF(__pyx_t_3); __pyx_t_4++; if (unlikely((0 < 0))) __PYX_ERR(1, 683, __pyx_L1_error) + #else + __pyx_t_3 = __Pyx_PySequence_ITEM(__pyx_t_1, __pyx_t_4); __pyx_t_4++; if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 683, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + #endif + __Pyx_XDECREF_SET(__pyx_v_item, __pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":684 + * idx = 0 + * for item in tup: + * if item is Ellipsis: # <<<<<<<<<<<<<< + * if not seen_ellipsis: + * idx += ndim - len(tup) + */ + __pyx_t_2 = (__pyx_v_item == __pyx_builtin_Ellipsis); + if (__pyx_t_2) { + + /* "View.MemoryView":685 + * for item in tup: + * if item is Ellipsis: + * if not seen_ellipsis: # <<<<<<<<<<<<<< + * idx += ndim - len(tup) + * seen_ellipsis = True + */ + __pyx_t_2 = (!__pyx_v_seen_ellipsis); + if (__pyx_t_2) { + + /* "View.MemoryView":686 + * if item is Ellipsis: + * if not seen_ellipsis: + * idx += ndim - len(tup) # <<<<<<<<<<<<<< + * seen_ellipsis = True + * have_slices = True + */ + if (unlikely(__pyx_v_tup == Py_None)) { + PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); + __PYX_ERR(1, 686, __pyx_L1_error) + } + __pyx_t_5 = __Pyx_PyTuple_GET_SIZE(__pyx_v_tup); if (unlikely(__pyx_t_5 == ((Py_ssize_t)-1))) __PYX_ERR(1, 686, __pyx_L1_error) + __pyx_v_idx = (__pyx_v_idx + (__pyx_v_ndim - __pyx_t_5)); + + /* "View.MemoryView":687 + * if not seen_ellipsis: + * idx += ndim - len(tup) + * seen_ellipsis = True # <<<<<<<<<<<<<< + * have_slices = True + * else: + */ + __pyx_v_seen_ellipsis = 1; + + /* "View.MemoryView":685 + * for item in tup: + * if item is Ellipsis: + * if not seen_ellipsis: # <<<<<<<<<<<<<< + * idx += ndim - len(tup) + * seen_ellipsis = True + */ + } + + /* "View.MemoryView":688 + * idx += ndim - len(tup) + * seen_ellipsis = True + * have_slices = True # <<<<<<<<<<<<<< + * else: + * if isinstance(item, slice): + */ + __pyx_v_have_slices = 1; + + /* "View.MemoryView":684 + * idx = 0 + * for item in tup: + * if item is Ellipsis: # <<<<<<<<<<<<<< + * if not seen_ellipsis: + * idx += ndim - len(tup) + */ + goto __pyx_L5; + } + + /* "View.MemoryView":690 + * have_slices = True + * else: + * if isinstance(item, slice): # <<<<<<<<<<<<<< + * have_slices = True + * elif not PyIndex_Check(item): + */ + /*else*/ { + __pyx_t_2 = PySlice_Check(__pyx_v_item); + if (__pyx_t_2) { + + /* "View.MemoryView":691 + * else: + * if isinstance(item, slice): + * have_slices = True # <<<<<<<<<<<<<< + * elif not PyIndex_Check(item): + * raise TypeError, f"Cannot index with type '{type(item)}'" + */ + __pyx_v_have_slices = 1; + + /* "View.MemoryView":690 + * have_slices = True + * else: + * if isinstance(item, slice): # <<<<<<<<<<<<<< + * have_slices = True + * elif not PyIndex_Check(item): + */ + goto __pyx_L7; + } + + /* "View.MemoryView":692 + * if isinstance(item, slice): + * have_slices = True + * elif not PyIndex_Check(item): # <<<<<<<<<<<<<< + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item + */ + __pyx_t_2 = (!(PyIndex_Check(__pyx_v_item) != 0)); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":693 + * have_slices = True + * elif not PyIndex_Check(item): + * raise TypeError, f"Cannot index with type '{type(item)}'" # <<<<<<<<<<<<<< + * result[idx] = item + * idx += 1 + */ + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 693, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = 0; + __pyx_t_6 = 127; + __Pyx_INCREF(__pyx_kp_u_Cannot_index_with_type); + __pyx_t_5 += 24; + __Pyx_GIVEREF(__pyx_kp_u_Cannot_index_with_type); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_kp_u_Cannot_index_with_type); + __pyx_t_7 = __Pyx_PyObject_FormatSimple(((PyObject *)Py_TYPE(__pyx_v_item)), __pyx_empty_unicode); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 693, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_7) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_7) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_7); + __pyx_t_7 = 0; + __Pyx_INCREF(__pyx_kp_u__6); + __pyx_t_5 += 1; + __Pyx_GIVEREF(__pyx_kp_u__6); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_kp_u__6); + __pyx_t_7 = __Pyx_PyUnicode_Join(__pyx_t_3, 3, __pyx_t_5, __pyx_t_6); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 693, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_t_7, 0, 0); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __PYX_ERR(1, 693, __pyx_L1_error) + + /* "View.MemoryView":692 + * if isinstance(item, slice): + * have_slices = True + * elif not PyIndex_Check(item): # <<<<<<<<<<<<<< + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item + */ + } + __pyx_L7:; + + /* "View.MemoryView":694 + * elif not PyIndex_Check(item): + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item # <<<<<<<<<<<<<< + * idx += 1 + * + */ + if (unlikely((__Pyx_SetItemInt(__pyx_v_result, __pyx_v_idx, __pyx_v_item, Py_ssize_t, 1, PyInt_FromSsize_t, 1, 1, 1) < 0))) __PYX_ERR(1, 694, __pyx_L1_error) + } + __pyx_L5:; + + /* "View.MemoryView":695 + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item + * idx += 1 # <<<<<<<<<<<<<< + * + * nslices = ndim - idx + */ + __pyx_v_idx = (__pyx_v_idx + 1); + + /* "View.MemoryView":683 + * seen_ellipsis = False + * idx = 0 + * for item in tup: # <<<<<<<<<<<<<< + * if item is Ellipsis: + * if not seen_ellipsis: + */ + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "View.MemoryView":697 + * idx += 1 + * + * nslices = ndim - idx # <<<<<<<<<<<<<< + * return have_slices or nslices, tuple(result) + * + */ + __pyx_v_nslices = (__pyx_v_ndim - __pyx_v_idx); + + /* "View.MemoryView":698 + * + * nslices = ndim - idx + * return have_slices or nslices, tuple(result) # <<<<<<<<<<<<<< + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + */ + __Pyx_XDECREF(__pyx_r); + if (!__pyx_v_have_slices) { + } else { + __pyx_t_7 = __Pyx_PyBool_FromLong(__pyx_v_have_slices); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_1 = __pyx_t_7; + __pyx_t_7 = 0; + goto __pyx_L9_bool_binop_done; + } + __pyx_t_7 = PyInt_FromSsize_t(__pyx_v_nslices); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_1 = __pyx_t_7; + __pyx_t_7 = 0; + __pyx_L9_bool_binop_done:; + __pyx_t_7 = PyList_AsTuple(__pyx_v_result); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_1)) __PYX_ERR(1, 698, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_7); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_7)) __PYX_ERR(1, 698, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_7 = 0; + __pyx_r = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; + goto __pyx_L0; + + /* "View.MemoryView":671 + * return isinstance(o, memoryview) + * + * cdef tuple _unellipsify(object index, int ndim): # <<<<<<<<<<<<<< + * """ + * Replace all ellipses with full slices and fill incomplete indices with + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("View.MemoryView._unellipsify", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_tup); + __Pyx_XDECREF(__pyx_v_result); + __Pyx_XDECREF(__pyx_v_item); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":700 + * return have_slices or nslices, tuple(result) + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: # <<<<<<<<<<<<<< + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: + */ + +static int assert_direct_dimensions(Py_ssize_t *__pyx_v_suboffsets, int __pyx_v_ndim) { + Py_ssize_t __pyx_v_suboffset; + int __pyx_r; + Py_ssize_t *__pyx_t_1; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + int __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + + /* "View.MemoryView":701 + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + * for suboffset in suboffsets[:ndim]: # <<<<<<<<<<<<<< + * if suboffset >= 0: + * raise ValueError, "Indirect dimensions not supported" + */ + __pyx_t_2 = (__pyx_v_suboffsets + __pyx_v_ndim); + for (__pyx_t_3 = __pyx_v_suboffsets; __pyx_t_3 < __pyx_t_2; __pyx_t_3++) { + __pyx_t_1 = __pyx_t_3; + __pyx_v_suboffset = (__pyx_t_1[0]); + + /* "View.MemoryView":702 + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * raise ValueError, "Indirect dimensions not supported" + * return 0 # return type just used as an error flag + */ + __pyx_t_4 = (__pyx_v_suboffset >= 0); + if (unlikely(__pyx_t_4)) { + + /* "View.MemoryView":703 + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: + * raise ValueError, "Indirect dimensions not supported" # <<<<<<<<<<<<<< + * return 0 # return type just used as an error flag + * + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Indirect_dimensions_not_supporte, 0, 0); + __PYX_ERR(1, 703, __pyx_L1_error) + + /* "View.MemoryView":702 + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * raise ValueError, "Indirect dimensions not supported" + * return 0 # return type just used as an error flag + */ + } + } + + /* "View.MemoryView":704 + * if suboffset >= 0: + * raise ValueError, "Indirect dimensions not supported" + * return 0 # return type just used as an error flag # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":700 + * return have_slices or nslices, tuple(result) + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: # <<<<<<<<<<<<<< + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.assert_direct_dimensions", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":711 + * + * @cname('__pyx_memview_slice') + * cdef memoryview memview_slice(memoryview memview, object indices): # <<<<<<<<<<<<<< + * cdef int new_ndim = 0, suboffset_dim = -1, dim + * cdef bint negative_step + */ + +static struct __pyx_memoryview_obj *__pyx_memview_slice(struct __pyx_memoryview_obj *__pyx_v_memview, PyObject *__pyx_v_indices) { + int __pyx_v_new_ndim; + int __pyx_v_suboffset_dim; + int __pyx_v_dim; + __Pyx_memviewslice __pyx_v_src; + __Pyx_memviewslice __pyx_v_dst; + __Pyx_memviewslice *__pyx_v_p_src; + struct __pyx_memoryviewslice_obj *__pyx_v_memviewsliceobj = 0; + __Pyx_memviewslice *__pyx_v_p_dst; + int *__pyx_v_p_suboffset_dim; + Py_ssize_t __pyx_v_start; + Py_ssize_t __pyx_v_stop; + Py_ssize_t __pyx_v_step; + Py_ssize_t __pyx_v_cindex; + int __pyx_v_have_start; + int __pyx_v_have_stop; + int __pyx_v_have_step; + PyObject *__pyx_v_index = NULL; + struct __pyx_memoryview_obj *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + struct __pyx_memoryview_obj *__pyx_t_3; + char *__pyx_t_4; + int __pyx_t_5; + Py_ssize_t __pyx_t_6; + PyObject *(*__pyx_t_7)(PyObject *); + PyObject *__pyx_t_8 = NULL; + Py_ssize_t __pyx_t_9; + int __pyx_t_10; + Py_ssize_t __pyx_t_11; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memview_slice", 1); + + /* "View.MemoryView":712 + * @cname('__pyx_memview_slice') + * cdef memoryview memview_slice(memoryview memview, object indices): + * cdef int new_ndim = 0, suboffset_dim = -1, dim # <<<<<<<<<<<<<< + * cdef bint negative_step + * cdef __Pyx_memviewslice src, dst + */ + __pyx_v_new_ndim = 0; + __pyx_v_suboffset_dim = -1; + + /* "View.MemoryView":719 + * + * + * memset(&dst, 0, sizeof(dst)) # <<<<<<<<<<<<<< + * + * cdef _memoryviewslice memviewsliceobj + */ + (void)(memset((&__pyx_v_dst), 0, (sizeof(__pyx_v_dst)))); + + /* "View.MemoryView":723 + * cdef _memoryviewslice memviewsliceobj + * + * assert memview.view.ndim > 0 # <<<<<<<<<<<<<< + * + * if isinstance(memview, _memoryviewslice): + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_1 = (__pyx_v_memview->view.ndim > 0); + if (unlikely(!__pyx_t_1)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(1, 723, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(1, 723, __pyx_L1_error) + #endif + + /* "View.MemoryView":725 + * assert memview.view.ndim > 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * memviewsliceobj = memview + * p_src = &memviewsliceobj.from_slice + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":726 + * + * if isinstance(memview, _memoryviewslice): + * memviewsliceobj = memview # <<<<<<<<<<<<<< + * p_src = &memviewsliceobj.from_slice + * else: + */ + if (!(likely(((((PyObject *)__pyx_v_memview)) == Py_None) || likely(__Pyx_TypeTest(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type))))) __PYX_ERR(1, 726, __pyx_L1_error) + __pyx_t_2 = ((PyObject *)__pyx_v_memview); + __Pyx_INCREF(__pyx_t_2); + __pyx_v_memviewsliceobj = ((struct __pyx_memoryviewslice_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":727 + * if isinstance(memview, _memoryviewslice): + * memviewsliceobj = memview + * p_src = &memviewsliceobj.from_slice # <<<<<<<<<<<<<< + * else: + * slice_copy(memview, &src) + */ + __pyx_v_p_src = (&__pyx_v_memviewsliceobj->from_slice); + + /* "View.MemoryView":725 + * assert memview.view.ndim > 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * memviewsliceobj = memview + * p_src = &memviewsliceobj.from_slice + */ + goto __pyx_L3; + } + + /* "View.MemoryView":729 + * p_src = &memviewsliceobj.from_slice + * else: + * slice_copy(memview, &src) # <<<<<<<<<<<<<< + * p_src = &src + * + */ + /*else*/ { + __pyx_memoryview_slice_copy(__pyx_v_memview, (&__pyx_v_src)); + + /* "View.MemoryView":730 + * else: + * slice_copy(memview, &src) + * p_src = &src # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_p_src = (&__pyx_v_src); + } + __pyx_L3:; + + /* "View.MemoryView":736 + * + * + * dst.memview = p_src.memview # <<<<<<<<<<<<<< + * dst.data = p_src.data + * + */ + __pyx_t_3 = __pyx_v_p_src->memview; + __pyx_v_dst.memview = __pyx_t_3; + + /* "View.MemoryView":737 + * + * dst.memview = p_src.memview + * dst.data = p_src.data # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_4 = __pyx_v_p_src->data; + __pyx_v_dst.data = __pyx_t_4; + + /* "View.MemoryView":742 + * + * + * cdef __Pyx_memviewslice *p_dst = &dst # <<<<<<<<<<<<<< + * cdef int *p_suboffset_dim = &suboffset_dim + * cdef Py_ssize_t start, stop, step, cindex + */ + __pyx_v_p_dst = (&__pyx_v_dst); + + /* "View.MemoryView":743 + * + * cdef __Pyx_memviewslice *p_dst = &dst + * cdef int *p_suboffset_dim = &suboffset_dim # <<<<<<<<<<<<<< + * cdef Py_ssize_t start, stop, step, cindex + * cdef bint have_start, have_stop, have_step + */ + __pyx_v_p_suboffset_dim = (&__pyx_v_suboffset_dim); + + /* "View.MemoryView":747 + * cdef bint have_start, have_stop, have_step + * + * for dim, index in enumerate(indices): # <<<<<<<<<<<<<< + * if PyIndex_Check(index): + * cindex = index + */ + __pyx_t_5 = 0; + if (likely(PyList_CheckExact(__pyx_v_indices)) || PyTuple_CheckExact(__pyx_v_indices)) { + __pyx_t_2 = __pyx_v_indices; __Pyx_INCREF(__pyx_t_2); + __pyx_t_6 = 0; + __pyx_t_7 = NULL; + } else { + __pyx_t_6 = -1; __pyx_t_2 = PyObject_GetIter(__pyx_v_indices); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 747, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_7 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_2); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 747, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_7)) { + if (likely(PyList_CheckExact(__pyx_t_2))) { + { + Py_ssize_t __pyx_temp = __Pyx_PyList_GET_SIZE(__pyx_t_2); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 747, __pyx_L1_error) + #endif + if (__pyx_t_6 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_8 = PyList_GET_ITEM(__pyx_t_2, __pyx_t_6); __Pyx_INCREF(__pyx_t_8); __pyx_t_6++; if (unlikely((0 < 0))) __PYX_ERR(1, 747, __pyx_L1_error) + #else + __pyx_t_8 = __Pyx_PySequence_ITEM(__pyx_t_2, __pyx_t_6); __pyx_t_6++; if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 747, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + #endif + } else { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_2); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(1, 747, __pyx_L1_error) + #endif + if (__pyx_t_6 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_8 = PyTuple_GET_ITEM(__pyx_t_2, __pyx_t_6); __Pyx_INCREF(__pyx_t_8); __pyx_t_6++; if (unlikely((0 < 0))) __PYX_ERR(1, 747, __pyx_L1_error) + #else + __pyx_t_8 = __Pyx_PySequence_ITEM(__pyx_t_2, __pyx_t_6); __pyx_t_6++; if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 747, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + #endif + } + } else { + __pyx_t_8 = __pyx_t_7(__pyx_t_2); + if (unlikely(!__pyx_t_8)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(1, 747, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_8); + } + __Pyx_XDECREF_SET(__pyx_v_index, __pyx_t_8); + __pyx_t_8 = 0; + __pyx_v_dim = __pyx_t_5; + __pyx_t_5 = (__pyx_t_5 + 1); + + /* "View.MemoryView":748 + * + * for dim, index in enumerate(indices): + * if PyIndex_Check(index): # <<<<<<<<<<<<<< + * cindex = index + * slice_memviewslice( + */ + __pyx_t_1 = (PyIndex_Check(__pyx_v_index) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":749 + * for dim, index in enumerate(indices): + * if PyIndex_Check(index): + * cindex = index # <<<<<<<<<<<<<< + * slice_memviewslice( + * p_dst, p_src.shape[dim], p_src.strides[dim], p_src.suboffsets[dim], + */ + __pyx_t_9 = __Pyx_PyIndex_AsSsize_t(__pyx_v_index); if (unlikely((__pyx_t_9 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 749, __pyx_L1_error) + __pyx_v_cindex = __pyx_t_9; + + /* "View.MemoryView":750 + * if PyIndex_Check(index): + * cindex = index + * slice_memviewslice( # <<<<<<<<<<<<<< + * p_dst, p_src.shape[dim], p_src.strides[dim], p_src.suboffsets[dim], + * dim, new_ndim, p_suboffset_dim, + */ + __pyx_t_10 = __pyx_memoryview_slice_memviewslice(__pyx_v_p_dst, (__pyx_v_p_src->shape[__pyx_v_dim]), (__pyx_v_p_src->strides[__pyx_v_dim]), (__pyx_v_p_src->suboffsets[__pyx_v_dim]), __pyx_v_dim, __pyx_v_new_ndim, __pyx_v_p_suboffset_dim, __pyx_v_cindex, 0, 0, 0, 0, 0, 0); if (unlikely(__pyx_t_10 == ((int)-1))) __PYX_ERR(1, 750, __pyx_L1_error) + + /* "View.MemoryView":748 + * + * for dim, index in enumerate(indices): + * if PyIndex_Check(index): # <<<<<<<<<<<<<< + * cindex = index + * slice_memviewslice( + */ + goto __pyx_L6; + } + + /* "View.MemoryView":756 + * 0, 0, 0, # have_{start,stop,step} + * False) + * elif index is None: # <<<<<<<<<<<<<< + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 + */ + __pyx_t_1 = (__pyx_v_index == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":757 + * False) + * elif index is None: + * p_dst.shape[new_ndim] = 1 # <<<<<<<<<<<<<< + * p_dst.strides[new_ndim] = 0 + * p_dst.suboffsets[new_ndim] = -1 + */ + (__pyx_v_p_dst->shape[__pyx_v_new_ndim]) = 1; + + /* "View.MemoryView":758 + * elif index is None: + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 # <<<<<<<<<<<<<< + * p_dst.suboffsets[new_ndim] = -1 + * new_ndim += 1 + */ + (__pyx_v_p_dst->strides[__pyx_v_new_ndim]) = 0; + + /* "View.MemoryView":759 + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 + * p_dst.suboffsets[new_ndim] = -1 # <<<<<<<<<<<<<< + * new_ndim += 1 + * else: + */ + (__pyx_v_p_dst->suboffsets[__pyx_v_new_ndim]) = -1L; + + /* "View.MemoryView":760 + * p_dst.strides[new_ndim] = 0 + * p_dst.suboffsets[new_ndim] = -1 + * new_ndim += 1 # <<<<<<<<<<<<<< + * else: + * start = index.start or 0 + */ + __pyx_v_new_ndim = (__pyx_v_new_ndim + 1); + + /* "View.MemoryView":756 + * 0, 0, 0, # have_{start,stop,step} + * False) + * elif index is None: # <<<<<<<<<<<<<< + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 + */ + goto __pyx_L6; + } + + /* "View.MemoryView":762 + * new_ndim += 1 + * else: + * start = index.start or 0 # <<<<<<<<<<<<<< + * stop = index.stop or 0 + * step = index.step or 0 + */ + /*else*/ { + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_start); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 762, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_t_8); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 762, __pyx_L1_error) + if (!__pyx_t_1) { + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } else { + __pyx_t_11 = __Pyx_PyIndex_AsSsize_t(__pyx_t_8); if (unlikely((__pyx_t_11 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 762, __pyx_L1_error) + __pyx_t_9 = __pyx_t_11; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L7_bool_binop_done; + } + __pyx_t_9 = 0; + __pyx_L7_bool_binop_done:; + __pyx_v_start = __pyx_t_9; + + /* "View.MemoryView":763 + * else: + * start = index.start or 0 + * stop = index.stop or 0 # <<<<<<<<<<<<<< + * step = index.step or 0 + * + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_stop); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 763, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_t_8); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 763, __pyx_L1_error) + if (!__pyx_t_1) { + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } else { + __pyx_t_11 = __Pyx_PyIndex_AsSsize_t(__pyx_t_8); if (unlikely((__pyx_t_11 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 763, __pyx_L1_error) + __pyx_t_9 = __pyx_t_11; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L9_bool_binop_done; + } + __pyx_t_9 = 0; + __pyx_L9_bool_binop_done:; + __pyx_v_stop = __pyx_t_9; + + /* "View.MemoryView":764 + * start = index.start or 0 + * stop = index.stop or 0 + * step = index.step or 0 # <<<<<<<<<<<<<< + * + * have_start = index.start is not None + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_step); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 764, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_t_8); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(1, 764, __pyx_L1_error) + if (!__pyx_t_1) { + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } else { + __pyx_t_11 = __Pyx_PyIndex_AsSsize_t(__pyx_t_8); if (unlikely((__pyx_t_11 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 764, __pyx_L1_error) + __pyx_t_9 = __pyx_t_11; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L11_bool_binop_done; + } + __pyx_t_9 = 0; + __pyx_L11_bool_binop_done:; + __pyx_v_step = __pyx_t_9; + + /* "View.MemoryView":766 + * step = index.step or 0 + * + * have_start = index.start is not None # <<<<<<<<<<<<<< + * have_stop = index.stop is not None + * have_step = index.step is not None + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_start); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 766, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = (__pyx_t_8 != Py_None); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_v_have_start = __pyx_t_1; + + /* "View.MemoryView":767 + * + * have_start = index.start is not None + * have_stop = index.stop is not None # <<<<<<<<<<<<<< + * have_step = index.step is not None + * + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_stop); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 767, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = (__pyx_t_8 != Py_None); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_v_have_stop = __pyx_t_1; + + /* "View.MemoryView":768 + * have_start = index.start is not None + * have_stop = index.stop is not None + * have_step = index.step is not None # <<<<<<<<<<<<<< + * + * slice_memviewslice( + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_step); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 768, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = (__pyx_t_8 != Py_None); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_v_have_step = __pyx_t_1; + + /* "View.MemoryView":770 + * have_step = index.step is not None + * + * slice_memviewslice( # <<<<<<<<<<<<<< + * p_dst, p_src.shape[dim], p_src.strides[dim], p_src.suboffsets[dim], + * dim, new_ndim, p_suboffset_dim, + */ + __pyx_t_10 = __pyx_memoryview_slice_memviewslice(__pyx_v_p_dst, (__pyx_v_p_src->shape[__pyx_v_dim]), (__pyx_v_p_src->strides[__pyx_v_dim]), (__pyx_v_p_src->suboffsets[__pyx_v_dim]), __pyx_v_dim, __pyx_v_new_ndim, __pyx_v_p_suboffset_dim, __pyx_v_start, __pyx_v_stop, __pyx_v_step, __pyx_v_have_start, __pyx_v_have_stop, __pyx_v_have_step, 1); if (unlikely(__pyx_t_10 == ((int)-1))) __PYX_ERR(1, 770, __pyx_L1_error) + + /* "View.MemoryView":776 + * have_start, have_stop, have_step, + * True) + * new_ndim += 1 # <<<<<<<<<<<<<< + * + * if isinstance(memview, _memoryviewslice): + */ + __pyx_v_new_ndim = (__pyx_v_new_ndim + 1); + } + __pyx_L6:; + + /* "View.MemoryView":747 + * cdef bint have_start, have_stop, have_step + * + * for dim, index in enumerate(indices): # <<<<<<<<<<<<<< + * if PyIndex_Check(index): + * cindex = index + */ + } + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":778 + * new_ndim += 1 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":779 + * + * if isinstance(memview, _memoryviewslice): + * return memoryview_fromslice(dst, new_ndim, # <<<<<<<<<<<<<< + * memviewsliceobj.to_object_func, + * memviewsliceobj.to_dtype_func, + */ + __Pyx_XDECREF((PyObject *)__pyx_r); + + /* "View.MemoryView":780 + * if isinstance(memview, _memoryviewslice): + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, # <<<<<<<<<<<<<< + * memviewsliceobj.to_dtype_func, + * memview.dtype_is_object) + */ + if (unlikely(!__pyx_v_memviewsliceobj)) { __Pyx_RaiseUnboundLocalError("memviewsliceobj"); __PYX_ERR(1, 780, __pyx_L1_error) } + + /* "View.MemoryView":781 + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, + * memviewsliceobj.to_dtype_func, # <<<<<<<<<<<<<< + * memview.dtype_is_object) + * else: + */ + if (unlikely(!__pyx_v_memviewsliceobj)) { __Pyx_RaiseUnboundLocalError("memviewsliceobj"); __PYX_ERR(1, 781, __pyx_L1_error) } + + /* "View.MemoryView":779 + * + * if isinstance(memview, _memoryviewslice): + * return memoryview_fromslice(dst, new_ndim, # <<<<<<<<<<<<<< + * memviewsliceobj.to_object_func, + * memviewsliceobj.to_dtype_func, + */ + __pyx_t_2 = __pyx_memoryview_fromslice(__pyx_v_dst, __pyx_v_new_ndim, __pyx_v_memviewsliceobj->to_object_func, __pyx_v_memviewsliceobj->to_dtype_func, __pyx_v_memview->dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 779, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (!(likely(((__pyx_t_2) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_2, __pyx_memoryview_type))))) __PYX_ERR(1, 779, __pyx_L1_error) + __pyx_r = ((struct __pyx_memoryview_obj *)__pyx_t_2); + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":778 + * new_ndim += 1 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, + */ + } + + /* "View.MemoryView":784 + * memview.dtype_is_object) + * else: + * return memoryview_fromslice(dst, new_ndim, NULL, NULL, # <<<<<<<<<<<<<< + * memview.dtype_is_object) + * + */ + /*else*/ { + __Pyx_XDECREF((PyObject *)__pyx_r); + + /* "View.MemoryView":785 + * else: + * return memoryview_fromslice(dst, new_ndim, NULL, NULL, + * memview.dtype_is_object) # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = __pyx_memoryview_fromslice(__pyx_v_dst, __pyx_v_new_ndim, NULL, NULL, __pyx_v_memview->dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 784, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + + /* "View.MemoryView":784 + * memview.dtype_is_object) + * else: + * return memoryview_fromslice(dst, new_ndim, NULL, NULL, # <<<<<<<<<<<<<< + * memview.dtype_is_object) + * + */ + if (!(likely(((__pyx_t_2) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_2, __pyx_memoryview_type))))) __PYX_ERR(1, 784, __pyx_L1_error) + __pyx_r = ((struct __pyx_memoryview_obj *)__pyx_t_2); + __pyx_t_2 = 0; + goto __pyx_L0; + } + + /* "View.MemoryView":711 + * + * @cname('__pyx_memview_slice') + * cdef memoryview memview_slice(memoryview memview, object indices): # <<<<<<<<<<<<<< + * cdef int new_ndim = 0, suboffset_dim = -1, dim + * cdef bint negative_step + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("View.MemoryView.memview_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_memviewsliceobj); + __Pyx_XDECREF(__pyx_v_index); + __Pyx_XGIVEREF((PyObject *)__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":793 + * + * @cname('__pyx_memoryview_slice_memviewslice') + * cdef int slice_memviewslice( # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * Py_ssize_t shape, Py_ssize_t stride, Py_ssize_t suboffset, + */ + +static int __pyx_memoryview_slice_memviewslice(__Pyx_memviewslice *__pyx_v_dst, Py_ssize_t __pyx_v_shape, Py_ssize_t __pyx_v_stride, Py_ssize_t __pyx_v_suboffset, int __pyx_v_dim, int __pyx_v_new_ndim, int *__pyx_v_suboffset_dim, Py_ssize_t __pyx_v_start, Py_ssize_t __pyx_v_stop, Py_ssize_t __pyx_v_step, int __pyx_v_have_start, int __pyx_v_have_stop, int __pyx_v_have_step, int __pyx_v_is_slice) { + Py_ssize_t __pyx_v_new_shape; + int __pyx_v_negative_step; + int __pyx_r; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":813 + * cdef bint negative_step + * + * if not is_slice: # <<<<<<<<<<<<<< + * + * if start < 0: + */ + __pyx_t_1 = (!__pyx_v_is_slice); + if (__pyx_t_1) { + + /* "View.MemoryView":815 + * if not is_slice: + * + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if not 0 <= start < shape: + */ + __pyx_t_1 = (__pyx_v_start < 0); + if (__pyx_t_1) { + + /* "View.MemoryView":816 + * + * if start < 0: + * start += shape # <<<<<<<<<<<<<< + * if not 0 <= start < shape: + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) + */ + __pyx_v_start = (__pyx_v_start + __pyx_v_shape); + + /* "View.MemoryView":815 + * if not is_slice: + * + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if not 0 <= start < shape: + */ + } + + /* "View.MemoryView":817 + * if start < 0: + * start += shape + * if not 0 <= start < shape: # <<<<<<<<<<<<<< + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) + * else: + */ + __pyx_t_1 = (0 <= __pyx_v_start); + if (__pyx_t_1) { + __pyx_t_1 = (__pyx_v_start < __pyx_v_shape); + } + __pyx_t_2 = (!__pyx_t_1); + if (__pyx_t_2) { + + /* "View.MemoryView":818 + * start += shape + * if not 0 <= start < shape: + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) # <<<<<<<<<<<<<< + * else: + * + */ + __pyx_t_3 = __pyx_memoryview_err_dim(PyExc_IndexError, __pyx_kp_s_Index_out_of_bounds_axis_d, __pyx_v_dim); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 818, __pyx_L1_error) + + /* "View.MemoryView":817 + * if start < 0: + * start += shape + * if not 0 <= start < shape: # <<<<<<<<<<<<<< + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) + * else: + */ + } + + /* "View.MemoryView":813 + * cdef bint negative_step + * + * if not is_slice: # <<<<<<<<<<<<<< + * + * if start < 0: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":821 + * else: + * + * if have_step: # <<<<<<<<<<<<<< + * negative_step = step < 0 + * if step == 0: + */ + /*else*/ { + __pyx_t_2 = (__pyx_v_have_step != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":822 + * + * if have_step: + * negative_step = step < 0 # <<<<<<<<<<<<<< + * if step == 0: + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + */ + __pyx_v_negative_step = (__pyx_v_step < 0); + + /* "View.MemoryView":823 + * if have_step: + * negative_step = step < 0 + * if step == 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + * else: + */ + __pyx_t_2 = (__pyx_v_step == 0); + if (__pyx_t_2) { + + /* "View.MemoryView":824 + * negative_step = step < 0 + * if step == 0: + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) # <<<<<<<<<<<<<< + * else: + * negative_step = False + */ + __pyx_t_3 = __pyx_memoryview_err_dim(PyExc_ValueError, __pyx_kp_s_Step_may_not_be_zero_axis_d, __pyx_v_dim); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 824, __pyx_L1_error) + + /* "View.MemoryView":823 + * if have_step: + * negative_step = step < 0 + * if step == 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + * else: + */ + } + + /* "View.MemoryView":821 + * else: + * + * if have_step: # <<<<<<<<<<<<<< + * negative_step = step < 0 + * if step == 0: + */ + goto __pyx_L6; + } + + /* "View.MemoryView":826 + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + * else: + * negative_step = False # <<<<<<<<<<<<<< + * step = 1 + * + */ + /*else*/ { + __pyx_v_negative_step = 0; + + /* "View.MemoryView":827 + * else: + * negative_step = False + * step = 1 # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_step = 1; + } + __pyx_L6:; + + /* "View.MemoryView":830 + * + * + * if have_start: # <<<<<<<<<<<<<< + * if start < 0: + * start += shape + */ + __pyx_t_2 = (__pyx_v_have_start != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":831 + * + * if have_start: + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if start < 0: + */ + __pyx_t_2 = (__pyx_v_start < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":832 + * if have_start: + * if start < 0: + * start += shape # <<<<<<<<<<<<<< + * if start < 0: + * start = 0 + */ + __pyx_v_start = (__pyx_v_start + __pyx_v_shape); + + /* "View.MemoryView":833 + * if start < 0: + * start += shape + * if start < 0: # <<<<<<<<<<<<<< + * start = 0 + * elif start >= shape: + */ + __pyx_t_2 = (__pyx_v_start < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":834 + * start += shape + * if start < 0: + * start = 0 # <<<<<<<<<<<<<< + * elif start >= shape: + * if negative_step: + */ + __pyx_v_start = 0; + + /* "View.MemoryView":833 + * if start < 0: + * start += shape + * if start < 0: # <<<<<<<<<<<<<< + * start = 0 + * elif start >= shape: + */ + } + + /* "View.MemoryView":831 + * + * if have_start: + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if start < 0: + */ + goto __pyx_L9; + } + + /* "View.MemoryView":835 + * if start < 0: + * start = 0 + * elif start >= shape: # <<<<<<<<<<<<<< + * if negative_step: + * start = shape - 1 + */ + __pyx_t_2 = (__pyx_v_start >= __pyx_v_shape); + if (__pyx_t_2) { + + /* "View.MemoryView":836 + * start = 0 + * elif start >= shape: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + if (__pyx_v_negative_step) { + + /* "View.MemoryView":837 + * elif start >= shape: + * if negative_step: + * start = shape - 1 # <<<<<<<<<<<<<< + * else: + * start = shape + */ + __pyx_v_start = (__pyx_v_shape - 1); + + /* "View.MemoryView":836 + * start = 0 + * elif start >= shape: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + goto __pyx_L11; + } + + /* "View.MemoryView":839 + * start = shape - 1 + * else: + * start = shape # <<<<<<<<<<<<<< + * else: + * if negative_step: + */ + /*else*/ { + __pyx_v_start = __pyx_v_shape; + } + __pyx_L11:; + + /* "View.MemoryView":835 + * if start < 0: + * start = 0 + * elif start >= shape: # <<<<<<<<<<<<<< + * if negative_step: + * start = shape - 1 + */ + } + __pyx_L9:; + + /* "View.MemoryView":830 + * + * + * if have_start: # <<<<<<<<<<<<<< + * if start < 0: + * start += shape + */ + goto __pyx_L8; + } + + /* "View.MemoryView":841 + * start = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + /*else*/ { + if (__pyx_v_negative_step) { + + /* "View.MemoryView":842 + * else: + * if negative_step: + * start = shape - 1 # <<<<<<<<<<<<<< + * else: + * start = 0 + */ + __pyx_v_start = (__pyx_v_shape - 1); + + /* "View.MemoryView":841 + * start = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + goto __pyx_L12; + } + + /* "View.MemoryView":844 + * start = shape - 1 + * else: + * start = 0 # <<<<<<<<<<<<<< + * + * if have_stop: + */ + /*else*/ { + __pyx_v_start = 0; + } + __pyx_L12:; + } + __pyx_L8:; + + /* "View.MemoryView":846 + * start = 0 + * + * if have_stop: # <<<<<<<<<<<<<< + * if stop < 0: + * stop += shape + */ + __pyx_t_2 = (__pyx_v_have_stop != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":847 + * + * if have_stop: + * if stop < 0: # <<<<<<<<<<<<<< + * stop += shape + * if stop < 0: + */ + __pyx_t_2 = (__pyx_v_stop < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":848 + * if have_stop: + * if stop < 0: + * stop += shape # <<<<<<<<<<<<<< + * if stop < 0: + * stop = 0 + */ + __pyx_v_stop = (__pyx_v_stop + __pyx_v_shape); + + /* "View.MemoryView":849 + * if stop < 0: + * stop += shape + * if stop < 0: # <<<<<<<<<<<<<< + * stop = 0 + * elif stop > shape: + */ + __pyx_t_2 = (__pyx_v_stop < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":850 + * stop += shape + * if stop < 0: + * stop = 0 # <<<<<<<<<<<<<< + * elif stop > shape: + * stop = shape + */ + __pyx_v_stop = 0; + + /* "View.MemoryView":849 + * if stop < 0: + * stop += shape + * if stop < 0: # <<<<<<<<<<<<<< + * stop = 0 + * elif stop > shape: + */ + } + + /* "View.MemoryView":847 + * + * if have_stop: + * if stop < 0: # <<<<<<<<<<<<<< + * stop += shape + * if stop < 0: + */ + goto __pyx_L14; + } + + /* "View.MemoryView":851 + * if stop < 0: + * stop = 0 + * elif stop > shape: # <<<<<<<<<<<<<< + * stop = shape + * else: + */ + __pyx_t_2 = (__pyx_v_stop > __pyx_v_shape); + if (__pyx_t_2) { + + /* "View.MemoryView":852 + * stop = 0 + * elif stop > shape: + * stop = shape # <<<<<<<<<<<<<< + * else: + * if negative_step: + */ + __pyx_v_stop = __pyx_v_shape; + + /* "View.MemoryView":851 + * if stop < 0: + * stop = 0 + * elif stop > shape: # <<<<<<<<<<<<<< + * stop = shape + * else: + */ + } + __pyx_L14:; + + /* "View.MemoryView":846 + * start = 0 + * + * if have_stop: # <<<<<<<<<<<<<< + * if stop < 0: + * stop += shape + */ + goto __pyx_L13; + } + + /* "View.MemoryView":854 + * stop = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * stop = -1 + * else: + */ + /*else*/ { + if (__pyx_v_negative_step) { + + /* "View.MemoryView":855 + * else: + * if negative_step: + * stop = -1 # <<<<<<<<<<<<<< + * else: + * stop = shape + */ + __pyx_v_stop = -1L; + + /* "View.MemoryView":854 + * stop = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * stop = -1 + * else: + */ + goto __pyx_L16; + } + + /* "View.MemoryView":857 + * stop = -1 + * else: + * stop = shape # <<<<<<<<<<<<<< + * + * + */ + /*else*/ { + __pyx_v_stop = __pyx_v_shape; + } + __pyx_L16:; + } + __pyx_L13:; + + /* "View.MemoryView":861 + * + * with cython.cdivision(True): + * new_shape = (stop - start) // step # <<<<<<<<<<<<<< + * + * if (stop - start) - step * new_shape: + */ + __pyx_v_new_shape = ((__pyx_v_stop - __pyx_v_start) / __pyx_v_step); + + /* "View.MemoryView":863 + * new_shape = (stop - start) // step + * + * if (stop - start) - step * new_shape: # <<<<<<<<<<<<<< + * new_shape += 1 + * + */ + __pyx_t_2 = (((__pyx_v_stop - __pyx_v_start) - (__pyx_v_step * __pyx_v_new_shape)) != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":864 + * + * if (stop - start) - step * new_shape: + * new_shape += 1 # <<<<<<<<<<<<<< + * + * if new_shape < 0: + */ + __pyx_v_new_shape = (__pyx_v_new_shape + 1); + + /* "View.MemoryView":863 + * new_shape = (stop - start) // step + * + * if (stop - start) - step * new_shape: # <<<<<<<<<<<<<< + * new_shape += 1 + * + */ + } + + /* "View.MemoryView":866 + * new_shape += 1 + * + * if new_shape < 0: # <<<<<<<<<<<<<< + * new_shape = 0 + * + */ + __pyx_t_2 = (__pyx_v_new_shape < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":867 + * + * if new_shape < 0: + * new_shape = 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_new_shape = 0; + + /* "View.MemoryView":866 + * new_shape += 1 + * + * if new_shape < 0: # <<<<<<<<<<<<<< + * new_shape = 0 + * + */ + } + + /* "View.MemoryView":870 + * + * + * dst.strides[new_ndim] = stride * step # <<<<<<<<<<<<<< + * dst.shape[new_ndim] = new_shape + * dst.suboffsets[new_ndim] = suboffset + */ + (__pyx_v_dst->strides[__pyx_v_new_ndim]) = (__pyx_v_stride * __pyx_v_step); + + /* "View.MemoryView":871 + * + * dst.strides[new_ndim] = stride * step + * dst.shape[new_ndim] = new_shape # <<<<<<<<<<<<<< + * dst.suboffsets[new_ndim] = suboffset + * + */ + (__pyx_v_dst->shape[__pyx_v_new_ndim]) = __pyx_v_new_shape; + + /* "View.MemoryView":872 + * dst.strides[new_ndim] = stride * step + * dst.shape[new_ndim] = new_shape + * dst.suboffsets[new_ndim] = suboffset # <<<<<<<<<<<<<< + * + * + */ + (__pyx_v_dst->suboffsets[__pyx_v_new_ndim]) = __pyx_v_suboffset; + } + __pyx_L3:; + + /* "View.MemoryView":875 + * + * + * if suboffset_dim[0] < 0: # <<<<<<<<<<<<<< + * dst.data += start * stride + * else: + */ + __pyx_t_2 = ((__pyx_v_suboffset_dim[0]) < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":876 + * + * if suboffset_dim[0] < 0: + * dst.data += start * stride # <<<<<<<<<<<<<< + * else: + * dst.suboffsets[suboffset_dim[0]] += start * stride + */ + __pyx_v_dst->data = (__pyx_v_dst->data + (__pyx_v_start * __pyx_v_stride)); + + /* "View.MemoryView":875 + * + * + * if suboffset_dim[0] < 0: # <<<<<<<<<<<<<< + * dst.data += start * stride + * else: + */ + goto __pyx_L19; + } + + /* "View.MemoryView":878 + * dst.data += start * stride + * else: + * dst.suboffsets[suboffset_dim[0]] += start * stride # <<<<<<<<<<<<<< + * + * if suboffset >= 0: + */ + /*else*/ { + __pyx_t_3 = (__pyx_v_suboffset_dim[0]); + (__pyx_v_dst->suboffsets[__pyx_t_3]) = ((__pyx_v_dst->suboffsets[__pyx_t_3]) + (__pyx_v_start * __pyx_v_stride)); + } + __pyx_L19:; + + /* "View.MemoryView":880 + * dst.suboffsets[suboffset_dim[0]] += start * stride + * + * if suboffset >= 0: # <<<<<<<<<<<<<< + * if not is_slice: + * if new_ndim == 0: + */ + __pyx_t_2 = (__pyx_v_suboffset >= 0); + if (__pyx_t_2) { + + /* "View.MemoryView":881 + * + * if suboffset >= 0: + * if not is_slice: # <<<<<<<<<<<<<< + * if new_ndim == 0: + * dst.data = ( dst.data)[0] + suboffset + */ + __pyx_t_2 = (!__pyx_v_is_slice); + if (__pyx_t_2) { + + /* "View.MemoryView":882 + * if suboffset >= 0: + * if not is_slice: + * if new_ndim == 0: # <<<<<<<<<<<<<< + * dst.data = ( dst.data)[0] + suboffset + * else: + */ + __pyx_t_2 = (__pyx_v_new_ndim == 0); + if (__pyx_t_2) { + + /* "View.MemoryView":883 + * if not is_slice: + * if new_ndim == 0: + * dst.data = ( dst.data)[0] + suboffset # <<<<<<<<<<<<<< + * else: + * _err_dim(PyExc_IndexError, "All dimensions preceding dimension %d " + */ + __pyx_v_dst->data = ((((char **)__pyx_v_dst->data)[0]) + __pyx_v_suboffset); + + /* "View.MemoryView":882 + * if suboffset >= 0: + * if not is_slice: + * if new_ndim == 0: # <<<<<<<<<<<<<< + * dst.data = ( dst.data)[0] + suboffset + * else: + */ + goto __pyx_L22; + } + + /* "View.MemoryView":885 + * dst.data = ( dst.data)[0] + suboffset + * else: + * _err_dim(PyExc_IndexError, "All dimensions preceding dimension %d " # <<<<<<<<<<<<<< + * "must be indexed and not sliced", dim) + * else: + */ + /*else*/ { + + /* "View.MemoryView":886 + * else: + * _err_dim(PyExc_IndexError, "All dimensions preceding dimension %d " + * "must be indexed and not sliced", dim) # <<<<<<<<<<<<<< + * else: + * suboffset_dim[0] = new_ndim + */ + __pyx_t_3 = __pyx_memoryview_err_dim(PyExc_IndexError, __pyx_kp_s_All_dimensions_preceding_dimensi, __pyx_v_dim); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 885, __pyx_L1_error) + } + __pyx_L22:; + + /* "View.MemoryView":881 + * + * if suboffset >= 0: + * if not is_slice: # <<<<<<<<<<<<<< + * if new_ndim == 0: + * dst.data = ( dst.data)[0] + suboffset + */ + goto __pyx_L21; + } + + /* "View.MemoryView":888 + * "must be indexed and not sliced", dim) + * else: + * suboffset_dim[0] = new_ndim # <<<<<<<<<<<<<< + * + * return 0 + */ + /*else*/ { + (__pyx_v_suboffset_dim[0]) = __pyx_v_new_ndim; + } + __pyx_L21:; + + /* "View.MemoryView":880 + * dst.suboffsets[suboffset_dim[0]] += start * stride + * + * if suboffset >= 0: # <<<<<<<<<<<<<< + * if not is_slice: + * if new_ndim == 0: + */ + } + + /* "View.MemoryView":890 + * suboffset_dim[0] = new_ndim + * + * return 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":793 + * + * @cname('__pyx_memoryview_slice_memviewslice') + * cdef int slice_memviewslice( # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * Py_ssize_t shape, Py_ssize_t stride, Py_ssize_t suboffset, + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.slice_memviewslice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":896 + * + * @cname('__pyx_pybuffer_index') + * cdef char *pybuffer_index(Py_buffer *view, char *bufp, Py_ssize_t index, # <<<<<<<<<<<<<< + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 + */ + +static char *__pyx_pybuffer_index(Py_buffer *__pyx_v_view, char *__pyx_v_bufp, Py_ssize_t __pyx_v_index, Py_ssize_t __pyx_v_dim) { + Py_ssize_t __pyx_v_shape; + Py_ssize_t __pyx_v_stride; + Py_ssize_t __pyx_v_suboffset; + Py_ssize_t __pyx_v_itemsize; + char *__pyx_v_resultp; + char *__pyx_r; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + Py_UCS4 __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("pybuffer_index", 1); + + /* "View.MemoryView":898 + * cdef char *pybuffer_index(Py_buffer *view, char *bufp, Py_ssize_t index, + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 # <<<<<<<<<<<<<< + * cdef Py_ssize_t itemsize = view.itemsize + * cdef char *resultp + */ + __pyx_v_suboffset = -1L; + + /* "View.MemoryView":899 + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 + * cdef Py_ssize_t itemsize = view.itemsize # <<<<<<<<<<<<<< + * cdef char *resultp + * + */ + __pyx_t_1 = __pyx_v_view->itemsize; + __pyx_v_itemsize = __pyx_t_1; + + /* "View.MemoryView":902 + * cdef char *resultp + * + * if view.ndim == 0: # <<<<<<<<<<<<<< + * shape = view.len // itemsize + * stride = itemsize + */ + __pyx_t_2 = (__pyx_v_view->ndim == 0); + if (__pyx_t_2) { + + /* "View.MemoryView":903 + * + * if view.ndim == 0: + * shape = view.len // itemsize # <<<<<<<<<<<<<< + * stride = itemsize + * else: + */ + if (unlikely(__pyx_v_itemsize == 0)) { + PyErr_SetString(PyExc_ZeroDivisionError, "integer division or modulo by zero"); + __PYX_ERR(1, 903, __pyx_L1_error) + } + else if (sizeof(Py_ssize_t) == sizeof(long) && (!(((Py_ssize_t)-1) > 0)) && unlikely(__pyx_v_itemsize == (Py_ssize_t)-1) && unlikely(__Pyx_UNARY_NEG_WOULD_OVERFLOW(__pyx_v_view->len))) { + PyErr_SetString(PyExc_OverflowError, "value too large to perform division"); + __PYX_ERR(1, 903, __pyx_L1_error) + } + __pyx_v_shape = __Pyx_div_Py_ssize_t(__pyx_v_view->len, __pyx_v_itemsize); + + /* "View.MemoryView":904 + * if view.ndim == 0: + * shape = view.len // itemsize + * stride = itemsize # <<<<<<<<<<<<<< + * else: + * shape = view.shape[dim] + */ + __pyx_v_stride = __pyx_v_itemsize; + + /* "View.MemoryView":902 + * cdef char *resultp + * + * if view.ndim == 0: # <<<<<<<<<<<<<< + * shape = view.len // itemsize + * stride = itemsize + */ + goto __pyx_L3; + } + + /* "View.MemoryView":906 + * stride = itemsize + * else: + * shape = view.shape[dim] # <<<<<<<<<<<<<< + * stride = view.strides[dim] + * if view.suboffsets != NULL: + */ + /*else*/ { + __pyx_v_shape = (__pyx_v_view->shape[__pyx_v_dim]); + + /* "View.MemoryView":907 + * else: + * shape = view.shape[dim] + * stride = view.strides[dim] # <<<<<<<<<<<<<< + * if view.suboffsets != NULL: + * suboffset = view.suboffsets[dim] + */ + __pyx_v_stride = (__pyx_v_view->strides[__pyx_v_dim]); + + /* "View.MemoryView":908 + * shape = view.shape[dim] + * stride = view.strides[dim] + * if view.suboffsets != NULL: # <<<<<<<<<<<<<< + * suboffset = view.suboffsets[dim] + * + */ + __pyx_t_2 = (__pyx_v_view->suboffsets != NULL); + if (__pyx_t_2) { + + /* "View.MemoryView":909 + * stride = view.strides[dim] + * if view.suboffsets != NULL: + * suboffset = view.suboffsets[dim] # <<<<<<<<<<<<<< + * + * if index < 0: + */ + __pyx_v_suboffset = (__pyx_v_view->suboffsets[__pyx_v_dim]); + + /* "View.MemoryView":908 + * shape = view.shape[dim] + * stride = view.strides[dim] + * if view.suboffsets != NULL: # <<<<<<<<<<<<<< + * suboffset = view.suboffsets[dim] + * + */ + } + } + __pyx_L3:; + + /* "View.MemoryView":911 + * suboffset = view.suboffsets[dim] + * + * if index < 0: # <<<<<<<<<<<<<< + * index += view.shape[dim] + * if index < 0: + */ + __pyx_t_2 = (__pyx_v_index < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":912 + * + * if index < 0: + * index += view.shape[dim] # <<<<<<<<<<<<<< + * if index < 0: + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + */ + __pyx_v_index = (__pyx_v_index + (__pyx_v_view->shape[__pyx_v_dim])); + + /* "View.MemoryView":913 + * if index < 0: + * index += view.shape[dim] + * if index < 0: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + __pyx_t_2 = (__pyx_v_index < 0); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":914 + * index += view.shape[dim] + * if index < 0: + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" # <<<<<<<<<<<<<< + * + * if index >= shape: + */ + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 914, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = 0; + __pyx_t_4 = 127; + __Pyx_INCREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_1 += 37; + __Pyx_GIVEREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_5 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_dim, 0, ' ', 'd'); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 914, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_5); + __Pyx_GIVEREF(__pyx_t_5); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_5); + __pyx_t_5 = 0; + __Pyx_INCREF(__pyx_kp_u__7); + __pyx_t_1 += 1; + __Pyx_GIVEREF(__pyx_kp_u__7); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_kp_u__7); + __pyx_t_5 = __Pyx_PyUnicode_Join(__pyx_t_3, 3, __pyx_t_1, __pyx_t_4); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 914, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_builtin_IndexError, __pyx_t_5, 0, 0); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __PYX_ERR(1, 914, __pyx_L1_error) + + /* "View.MemoryView":913 + * if index < 0: + * index += view.shape[dim] + * if index < 0: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + } + + /* "View.MemoryView":911 + * suboffset = view.suboffsets[dim] + * + * if index < 0: # <<<<<<<<<<<<<< + * index += view.shape[dim] + * if index < 0: + */ + } + + /* "View.MemoryView":916 + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + * if index >= shape: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + __pyx_t_2 = (__pyx_v_index >= __pyx_v_shape); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":917 + * + * if index >= shape: + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" # <<<<<<<<<<<<<< + * + * resultp = bufp + index * stride + */ + __pyx_t_5 = PyTuple_New(3); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 917, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 = 0; + __pyx_t_4 = 127; + __Pyx_INCREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_1 += 37; + __Pyx_GIVEREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_3 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_dim, 0, ' ', 'd'); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 917, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_3); + PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_3); + __pyx_t_3 = 0; + __Pyx_INCREF(__pyx_kp_u__7); + __pyx_t_1 += 1; + __Pyx_GIVEREF(__pyx_kp_u__7); + PyTuple_SET_ITEM(__pyx_t_5, 2, __pyx_kp_u__7); + __pyx_t_3 = __Pyx_PyUnicode_Join(__pyx_t_5, 3, __pyx_t_1, __pyx_t_4); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 917, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_Raise(__pyx_builtin_IndexError, __pyx_t_3, 0, 0); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __PYX_ERR(1, 917, __pyx_L1_error) + + /* "View.MemoryView":916 + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + * if index >= shape: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + } + + /* "View.MemoryView":919 + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + * resultp = bufp + index * stride # <<<<<<<<<<<<<< + * if suboffset >= 0: + * resultp = ( resultp)[0] + suboffset + */ + __pyx_v_resultp = (__pyx_v_bufp + (__pyx_v_index * __pyx_v_stride)); + + /* "View.MemoryView":920 + * + * resultp = bufp + index * stride + * if suboffset >= 0: # <<<<<<<<<<<<<< + * resultp = ( resultp)[0] + suboffset + * + */ + __pyx_t_2 = (__pyx_v_suboffset >= 0); + if (__pyx_t_2) { + + /* "View.MemoryView":921 + * resultp = bufp + index * stride + * if suboffset >= 0: + * resultp = ( resultp)[0] + suboffset # <<<<<<<<<<<<<< + * + * return resultp + */ + __pyx_v_resultp = ((((char **)__pyx_v_resultp)[0]) + __pyx_v_suboffset); + + /* "View.MemoryView":920 + * + * resultp = bufp + index * stride + * if suboffset >= 0: # <<<<<<<<<<<<<< + * resultp = ( resultp)[0] + suboffset + * + */ + } + + /* "View.MemoryView":923 + * resultp = ( resultp)[0] + suboffset + * + * return resultp # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = __pyx_v_resultp; + goto __pyx_L0; + + /* "View.MemoryView":896 + * + * @cname('__pyx_pybuffer_index') + * cdef char *pybuffer_index(Py_buffer *view, char *bufp, Py_ssize_t index, # <<<<<<<<<<<<<< + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.pybuffer_index", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":929 + * + * @cname('__pyx_memslice_transpose') + * cdef int transpose_memslice(__Pyx_memviewslice *memslice) except -1 nogil: # <<<<<<<<<<<<<< + * cdef int ndim = memslice.memview.view.ndim + * + */ + +static int __pyx_memslice_transpose(__Pyx_memviewslice *__pyx_v_memslice) { + int __pyx_v_ndim; + Py_ssize_t *__pyx_v_shape; + Py_ssize_t *__pyx_v_strides; + int __pyx_v_i; + int __pyx_v_j; + int __pyx_r; + int __pyx_t_1; + Py_ssize_t *__pyx_t_2; + long __pyx_t_3; + long __pyx_t_4; + Py_ssize_t __pyx_t_5; + Py_ssize_t __pyx_t_6; + int __pyx_t_7; + int __pyx_t_8; + int __pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":930 + * @cname('__pyx_memslice_transpose') + * cdef int transpose_memslice(__Pyx_memviewslice *memslice) except -1 nogil: + * cdef int ndim = memslice.memview.view.ndim # <<<<<<<<<<<<<< + * + * cdef Py_ssize_t *shape = memslice.shape + */ + __pyx_t_1 = __pyx_v_memslice->memview->view.ndim; + __pyx_v_ndim = __pyx_t_1; + + /* "View.MemoryView":932 + * cdef int ndim = memslice.memview.view.ndim + * + * cdef Py_ssize_t *shape = memslice.shape # <<<<<<<<<<<<<< + * cdef Py_ssize_t *strides = memslice.strides + * + */ + __pyx_t_2 = __pyx_v_memslice->shape; + __pyx_v_shape = __pyx_t_2; + + /* "View.MemoryView":933 + * + * cdef Py_ssize_t *shape = memslice.shape + * cdef Py_ssize_t *strides = memslice.strides # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = __pyx_v_memslice->strides; + __pyx_v_strides = __pyx_t_2; + + /* "View.MemoryView":937 + * + * cdef int i, j + * for i in range(ndim // 2): # <<<<<<<<<<<<<< + * j = ndim - 1 - i + * strides[i], strides[j] = strides[j], strides[i] + */ + __pyx_t_3 = __Pyx_div_long(__pyx_v_ndim, 2); + __pyx_t_4 = __pyx_t_3; + for (__pyx_t_1 = 0; __pyx_t_1 < __pyx_t_4; __pyx_t_1+=1) { + __pyx_v_i = __pyx_t_1; + + /* "View.MemoryView":938 + * cdef int i, j + * for i in range(ndim // 2): + * j = ndim - 1 - i # <<<<<<<<<<<<<< + * strides[i], strides[j] = strides[j], strides[i] + * shape[i], shape[j] = shape[j], shape[i] + */ + __pyx_v_j = ((__pyx_v_ndim - 1) - __pyx_v_i); + + /* "View.MemoryView":939 + * for i in range(ndim // 2): + * j = ndim - 1 - i + * strides[i], strides[j] = strides[j], strides[i] # <<<<<<<<<<<<<< + * shape[i], shape[j] = shape[j], shape[i] + * + */ + __pyx_t_5 = (__pyx_v_strides[__pyx_v_j]); + __pyx_t_6 = (__pyx_v_strides[__pyx_v_i]); + (__pyx_v_strides[__pyx_v_i]) = __pyx_t_5; + (__pyx_v_strides[__pyx_v_j]) = __pyx_t_6; + + /* "View.MemoryView":940 + * j = ndim - 1 - i + * strides[i], strides[j] = strides[j], strides[i] + * shape[i], shape[j] = shape[j], shape[i] # <<<<<<<<<<<<<< + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: + */ + __pyx_t_6 = (__pyx_v_shape[__pyx_v_j]); + __pyx_t_5 = (__pyx_v_shape[__pyx_v_i]); + (__pyx_v_shape[__pyx_v_i]) = __pyx_t_6; + (__pyx_v_shape[__pyx_v_j]) = __pyx_t_5; + + /* "View.MemoryView":942 + * shape[i], shape[j] = shape[j], shape[i] + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: # <<<<<<<<<<<<<< + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") + * + */ + __pyx_t_8 = ((__pyx_v_memslice->suboffsets[__pyx_v_i]) >= 0); + if (!__pyx_t_8) { + } else { + __pyx_t_7 = __pyx_t_8; + goto __pyx_L6_bool_binop_done; + } + __pyx_t_8 = ((__pyx_v_memslice->suboffsets[__pyx_v_j]) >= 0); + __pyx_t_7 = __pyx_t_8; + __pyx_L6_bool_binop_done:; + if (__pyx_t_7) { + + /* "View.MemoryView":943 + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") # <<<<<<<<<<<<<< + * + * return 0 + */ + __pyx_t_9 = __pyx_memoryview_err(PyExc_ValueError, __pyx_kp_s_Cannot_transpose_memoryview_with); if (unlikely(__pyx_t_9 == ((int)-1))) __PYX_ERR(1, 943, __pyx_L1_error) + + /* "View.MemoryView":942 + * shape[i], shape[j] = shape[j], shape[i] + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: # <<<<<<<<<<<<<< + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") + * + */ + } + } + + /* "View.MemoryView":945 + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") + * + * return 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":929 + * + * @cname('__pyx_memslice_transpose') + * cdef int transpose_memslice(__Pyx_memviewslice *memslice) except -1 nogil: # <<<<<<<<<<<<<< + * cdef int ndim = memslice.memview.view.ndim + * + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.transpose_memslice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":963 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + */ + +/* Python wrapper */ +static void __pyx_memoryviewslice___dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_memoryviewslice___dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_memoryviewslice___pyx_pf_15View_dot_MemoryView_16_memoryviewslice___dealloc__(((struct __pyx_memoryviewslice_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_memoryviewslice___pyx_pf_15View_dot_MemoryView_16_memoryviewslice___dealloc__(struct __pyx_memoryviewslice_obj *__pyx_v_self) { + + /* "View.MemoryView":964 + * + * def __dealloc__(self): + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) # <<<<<<<<<<<<<< + * + * cdef convert_item_to_object(self, char *itemp): + */ + __PYX_XCLEAR_MEMVIEW((&__pyx_v_self->from_slice), 1); + + /* "View.MemoryView":963 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + */ + + /* function exit code */ +} + +/* "View.MemoryView":966 + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * if self.to_object_func != NULL: + * return self.to_object_func(itemp) + */ + +static PyObject *__pyx_memoryviewslice_convert_item_to_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("convert_item_to_object", 1); + + /* "View.MemoryView":967 + * + * cdef convert_item_to_object(self, char *itemp): + * if self.to_object_func != NULL: # <<<<<<<<<<<<<< + * return self.to_object_func(itemp) + * else: + */ + __pyx_t_1 = (__pyx_v_self->to_object_func != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":968 + * cdef convert_item_to_object(self, char *itemp): + * if self.to_object_func != NULL: + * return self.to_object_func(itemp) # <<<<<<<<<<<<<< + * else: + * return memoryview.convert_item_to_object(self, itemp) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_v_self->to_object_func(__pyx_v_itemp); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 968, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":967 + * + * cdef convert_item_to_object(self, char *itemp): + * if self.to_object_func != NULL: # <<<<<<<<<<<<<< + * return self.to_object_func(itemp) + * else: + */ + } + + /* "View.MemoryView":970 + * return self.to_object_func(itemp) + * else: + * return memoryview.convert_item_to_object(self, itemp) # <<<<<<<<<<<<<< + * + * cdef assign_item_from_object(self, char *itemp, object value): + */ + /*else*/ { + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_memoryview_convert_item_to_object(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v_itemp); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 970, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + } + + /* "View.MemoryView":966 + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * if self.to_object_func != NULL: + * return self.to_object_func(itemp) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.convert_item_to_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":972 + * return memoryview.convert_item_to_object(self, itemp) + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * if self.to_dtype_func != NULL: + * self.to_dtype_func(itemp, value) + */ + +static PyObject *__pyx_memoryviewslice_assign_item_from_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("assign_item_from_object", 1); + + /* "View.MemoryView":973 + * + * cdef assign_item_from_object(self, char *itemp, object value): + * if self.to_dtype_func != NULL: # <<<<<<<<<<<<<< + * self.to_dtype_func(itemp, value) + * else: + */ + __pyx_t_1 = (__pyx_v_self->to_dtype_func != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":974 + * cdef assign_item_from_object(self, char *itemp, object value): + * if self.to_dtype_func != NULL: + * self.to_dtype_func(itemp, value) # <<<<<<<<<<<<<< + * else: + * memoryview.assign_item_from_object(self, itemp, value) + */ + __pyx_t_2 = __pyx_v_self->to_dtype_func(__pyx_v_itemp, __pyx_v_value); if (unlikely(__pyx_t_2 == ((int)0))) __PYX_ERR(1, 974, __pyx_L1_error) + + /* "View.MemoryView":973 + * + * cdef assign_item_from_object(self, char *itemp, object value): + * if self.to_dtype_func != NULL: # <<<<<<<<<<<<<< + * self.to_dtype_func(itemp, value) + * else: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":976 + * self.to_dtype_func(itemp, value) + * else: + * memoryview.assign_item_from_object(self, itemp, value) # <<<<<<<<<<<<<< + * + * cdef _get_base(self): + */ + /*else*/ { + __pyx_t_3 = __pyx_memoryview_assign_item_from_object(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v_itemp, __pyx_v_value); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 976, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_L3:; + + /* "View.MemoryView":972 + * return memoryview.convert_item_to_object(self, itemp) + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * if self.to_dtype_func != NULL: + * self.to_dtype_func(itemp, value) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.assign_item_from_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":978 + * memoryview.assign_item_from_object(self, itemp, value) + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.from_object + * + */ + +static PyObject *__pyx_memoryviewslice__get_base(struct __pyx_memoryviewslice_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("_get_base", 1); + + /* "View.MemoryView":979 + * + * cdef _get_base(self): + * return self.from_object # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->from_object); + __pyx_r = __pyx_v_self->from_object; + goto __pyx_L0; + + /* "View.MemoryView":978 + * memoryview.assign_item_from_object(self, itemp, value) + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.from_object + * + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryviewslice_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryviewslice_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_memoryviewslice___reduce_cython__(((struct __pyx_memoryviewslice_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryviewslice___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryviewslice_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryviewslice_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_memoryviewslice_2__setstate_cython__(((struct __pyx_memoryviewslice_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryviewslice_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":999 + * + * @cname('__pyx_memoryview_fromslice') + * cdef memoryview_fromslice(__Pyx_memviewslice memviewslice, # <<<<<<<<<<<<<< + * int ndim, + * object (*to_object_func)(char *), + */ + +static PyObject *__pyx_memoryview_fromslice(__Pyx_memviewslice __pyx_v_memviewslice, int __pyx_v_ndim, PyObject *(*__pyx_v_to_object_func)(char *), int (*__pyx_v_to_dtype_func)(char *, PyObject *), int __pyx_v_dtype_is_object) { + struct __pyx_memoryviewslice_obj *__pyx_v_result = 0; + Py_ssize_t __pyx_v_suboffset; + PyObject *__pyx_v_length = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + __Pyx_TypeInfo *__pyx_t_4; + Py_buffer __pyx_t_5; + Py_ssize_t *__pyx_t_6; + Py_ssize_t *__pyx_t_7; + Py_ssize_t *__pyx_t_8; + Py_ssize_t __pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_fromslice", 1); + + /* "View.MemoryView":1007 + * cdef _memoryviewslice result + * + * if memviewslice.memview == Py_None: # <<<<<<<<<<<<<< + * return None + * + */ + __pyx_t_1 = (((PyObject *)__pyx_v_memviewslice.memview) == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":1008 + * + * if memviewslice.memview == Py_None: + * return None # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "View.MemoryView":1007 + * cdef _memoryviewslice result + * + * if memviewslice.memview == Py_None: # <<<<<<<<<<<<<< + * return None + * + */ + } + + /* "View.MemoryView":1013 + * + * + * result = _memoryviewslice.__new__(_memoryviewslice, None, 0, dtype_is_object) # <<<<<<<<<<<<<< + * + * result.from_slice = memviewslice + */ + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_v_dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1013, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 1013, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(Py_None); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, Py_None)) __PYX_ERR(1, 1013, __pyx_L1_error); + __Pyx_INCREF(__pyx_int_0); + __Pyx_GIVEREF(__pyx_int_0); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_int_0)) __PYX_ERR(1, 1013, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_t_2)) __PYX_ERR(1, 1013, __pyx_L1_error); + __pyx_t_2 = 0; + __pyx_t_2 = ((PyObject *)__pyx_tp_new__memoryviewslice(((PyTypeObject *)__pyx_memoryviewslice_type), __pyx_t_3, NULL)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1013, __pyx_L1_error) + __Pyx_GOTREF((PyObject *)__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_v_result = ((struct __pyx_memoryviewslice_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":1015 + * result = _memoryviewslice.__new__(_memoryviewslice, None, 0, dtype_is_object) + * + * result.from_slice = memviewslice # <<<<<<<<<<<<<< + * __PYX_INC_MEMVIEW(&memviewslice, 1) + * + */ + __pyx_v_result->from_slice = __pyx_v_memviewslice; + + /* "View.MemoryView":1016 + * + * result.from_slice = memviewslice + * __PYX_INC_MEMVIEW(&memviewslice, 1) # <<<<<<<<<<<<<< + * + * result.from_object = ( memviewslice.memview)._get_base() + */ + __PYX_INC_MEMVIEW((&__pyx_v_memviewslice), 1); + + /* "View.MemoryView":1018 + * __PYX_INC_MEMVIEW(&memviewslice, 1) + * + * result.from_object = ( memviewslice.memview)._get_base() # <<<<<<<<<<<<<< + * result.typeinfo = memviewslice.memview.typeinfo + * + */ + __pyx_t_2 = ((struct __pyx_vtabstruct_memoryview *)((struct __pyx_memoryview_obj *)__pyx_v_memviewslice.memview)->__pyx_vtab)->_get_base(((struct __pyx_memoryview_obj *)__pyx_v_memviewslice.memview)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1018, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + __Pyx_GOTREF(__pyx_v_result->from_object); + __Pyx_DECREF(__pyx_v_result->from_object); + __pyx_v_result->from_object = __pyx_t_2; + __pyx_t_2 = 0; + + /* "View.MemoryView":1019 + * + * result.from_object = ( memviewslice.memview)._get_base() + * result.typeinfo = memviewslice.memview.typeinfo # <<<<<<<<<<<<<< + * + * result.view = memviewslice.memview.view + */ + __pyx_t_4 = __pyx_v_memviewslice.memview->typeinfo; + __pyx_v_result->__pyx_base.typeinfo = __pyx_t_4; + + /* "View.MemoryView":1021 + * result.typeinfo = memviewslice.memview.typeinfo + * + * result.view = memviewslice.memview.view # <<<<<<<<<<<<<< + * result.view.buf = memviewslice.data + * result.view.ndim = ndim + */ + __pyx_t_5 = __pyx_v_memviewslice.memview->view; + __pyx_v_result->__pyx_base.view = __pyx_t_5; + + /* "View.MemoryView":1022 + * + * result.view = memviewslice.memview.view + * result.view.buf = memviewslice.data # <<<<<<<<<<<<<< + * result.view.ndim = ndim + * (<__pyx_buffer *> &result.view).obj = Py_None + */ + __pyx_v_result->__pyx_base.view.buf = ((void *)__pyx_v_memviewslice.data); + + /* "View.MemoryView":1023 + * result.view = memviewslice.memview.view + * result.view.buf = memviewslice.data + * result.view.ndim = ndim # <<<<<<<<<<<<<< + * (<__pyx_buffer *> &result.view).obj = Py_None + * Py_INCREF(Py_None) + */ + __pyx_v_result->__pyx_base.view.ndim = __pyx_v_ndim; + + /* "View.MemoryView":1024 + * result.view.buf = memviewslice.data + * result.view.ndim = ndim + * (<__pyx_buffer *> &result.view).obj = Py_None # <<<<<<<<<<<<<< + * Py_INCREF(Py_None) + * + */ + ((Py_buffer *)(&__pyx_v_result->__pyx_base.view))->obj = Py_None; + + /* "View.MemoryView":1025 + * result.view.ndim = ndim + * (<__pyx_buffer *> &result.view).obj = Py_None + * Py_INCREF(Py_None) # <<<<<<<<<<<<<< + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: + */ + Py_INCREF(Py_None); + + /* "View.MemoryView":1027 + * Py_INCREF(Py_None) + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: # <<<<<<<<<<<<<< + * result.flags = PyBUF_RECORDS + * else: + */ + __pyx_t_1 = ((((struct __pyx_memoryview_obj *)__pyx_v_memviewslice.memview)->flags & PyBUF_WRITABLE) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":1028 + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: + * result.flags = PyBUF_RECORDS # <<<<<<<<<<<<<< + * else: + * result.flags = PyBUF_RECORDS_RO + */ + __pyx_v_result->__pyx_base.flags = PyBUF_RECORDS; + + /* "View.MemoryView":1027 + * Py_INCREF(Py_None) + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: # <<<<<<<<<<<<<< + * result.flags = PyBUF_RECORDS + * else: + */ + goto __pyx_L4; + } + + /* "View.MemoryView":1030 + * result.flags = PyBUF_RECORDS + * else: + * result.flags = PyBUF_RECORDS_RO # <<<<<<<<<<<<<< + * + * result.view.shape = result.from_slice.shape + */ + /*else*/ { + __pyx_v_result->__pyx_base.flags = PyBUF_RECORDS_RO; + } + __pyx_L4:; + + /* "View.MemoryView":1032 + * result.flags = PyBUF_RECORDS_RO + * + * result.view.shape = result.from_slice.shape # <<<<<<<<<<<<<< + * result.view.strides = result.from_slice.strides + * + */ + __pyx_v_result->__pyx_base.view.shape = ((Py_ssize_t *)__pyx_v_result->from_slice.shape); + + /* "View.MemoryView":1033 + * + * result.view.shape = result.from_slice.shape + * result.view.strides = result.from_slice.strides # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_result->__pyx_base.view.strides = ((Py_ssize_t *)__pyx_v_result->from_slice.strides); + + /* "View.MemoryView":1036 + * + * + * result.view.suboffsets = NULL # <<<<<<<<<<<<<< + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: + */ + __pyx_v_result->__pyx_base.view.suboffsets = NULL; + + /* "View.MemoryView":1037 + * + * result.view.suboffsets = NULL + * for suboffset in result.from_slice.suboffsets[:ndim]: # <<<<<<<<<<<<<< + * if suboffset >= 0: + * result.view.suboffsets = result.from_slice.suboffsets + */ + __pyx_t_7 = (__pyx_v_result->from_slice.suboffsets + __pyx_v_ndim); + for (__pyx_t_8 = __pyx_v_result->from_slice.suboffsets; __pyx_t_8 < __pyx_t_7; __pyx_t_8++) { + __pyx_t_6 = __pyx_t_8; + __pyx_v_suboffset = (__pyx_t_6[0]); + + /* "View.MemoryView":1038 + * result.view.suboffsets = NULL + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * result.view.suboffsets = result.from_slice.suboffsets + * break + */ + __pyx_t_1 = (__pyx_v_suboffset >= 0); + if (__pyx_t_1) { + + /* "View.MemoryView":1039 + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: + * result.view.suboffsets = result.from_slice.suboffsets # <<<<<<<<<<<<<< + * break + * + */ + __pyx_v_result->__pyx_base.view.suboffsets = ((Py_ssize_t *)__pyx_v_result->from_slice.suboffsets); + + /* "View.MemoryView":1040 + * if suboffset >= 0: + * result.view.suboffsets = result.from_slice.suboffsets + * break # <<<<<<<<<<<<<< + * + * result.view.len = result.view.itemsize + */ + goto __pyx_L6_break; + + /* "View.MemoryView":1038 + * result.view.suboffsets = NULL + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * result.view.suboffsets = result.from_slice.suboffsets + * break + */ + } + } + __pyx_L6_break:; + + /* "View.MemoryView":1042 + * break + * + * result.view.len = result.view.itemsize # <<<<<<<<<<<<<< + * for length in result.view.shape[:ndim]: + * result.view.len *= length + */ + __pyx_t_9 = __pyx_v_result->__pyx_base.view.itemsize; + __pyx_v_result->__pyx_base.view.len = __pyx_t_9; + + /* "View.MemoryView":1043 + * + * result.view.len = result.view.itemsize + * for length in result.view.shape[:ndim]: # <<<<<<<<<<<<<< + * result.view.len *= length + * + */ + __pyx_t_7 = (__pyx_v_result->__pyx_base.view.shape + __pyx_v_ndim); + for (__pyx_t_8 = __pyx_v_result->__pyx_base.view.shape; __pyx_t_8 < __pyx_t_7; __pyx_t_8++) { + __pyx_t_6 = __pyx_t_8; + __pyx_t_2 = PyInt_FromSsize_t((__pyx_t_6[0])); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1043, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_XDECREF_SET(__pyx_v_length, __pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":1044 + * result.view.len = result.view.itemsize + * for length in result.view.shape[:ndim]: + * result.view.len *= length # <<<<<<<<<<<<<< + * + * result.to_object_func = to_object_func + */ + __pyx_t_2 = PyInt_FromSsize_t(__pyx_v_result->__pyx_base.view.len); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1044, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyNumber_InPlaceMultiply(__pyx_t_2, __pyx_v_length); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 1044, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_9 = __Pyx_PyIndex_AsSsize_t(__pyx_t_3); if (unlikely((__pyx_t_9 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(1, 1044, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_v_result->__pyx_base.view.len = __pyx_t_9; + } + + /* "View.MemoryView":1046 + * result.view.len *= length + * + * result.to_object_func = to_object_func # <<<<<<<<<<<<<< + * result.to_dtype_func = to_dtype_func + * + */ + __pyx_v_result->to_object_func = __pyx_v_to_object_func; + + /* "View.MemoryView":1047 + * + * result.to_object_func = to_object_func + * result.to_dtype_func = to_dtype_func # <<<<<<<<<<<<<< + * + * return result + */ + __pyx_v_result->to_dtype_func = __pyx_v_to_dtype_func; + + /* "View.MemoryView":1049 + * result.to_dtype_func = to_dtype_func + * + * return result # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_get_slice_from_memoryview') + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = ((PyObject *)__pyx_v_result); + goto __pyx_L0; + + /* "View.MemoryView":999 + * + * @cname('__pyx_memoryview_fromslice') + * cdef memoryview_fromslice(__Pyx_memviewslice memviewslice, # <<<<<<<<<<<<<< + * int ndim, + * object (*to_object_func)(char *), + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview_fromslice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XDECREF(__pyx_v_length); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1052 + * + * @cname('__pyx_memoryview_get_slice_from_memoryview') + * cdef __Pyx_memviewslice *get_slice_from_memview(memoryview memview, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + */ + +static __Pyx_memviewslice *__pyx_memoryview_get_slice_from_memoryview(struct __pyx_memoryview_obj *__pyx_v_memview, __Pyx_memviewslice *__pyx_v_mslice) { + struct __pyx_memoryviewslice_obj *__pyx_v_obj = 0; + __Pyx_memviewslice *__pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_slice_from_memview", 1); + + /* "View.MemoryView":1055 + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * obj = memview + * return &obj.from_slice + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":1056 + * cdef _memoryviewslice obj + * if isinstance(memview, _memoryviewslice): + * obj = memview # <<<<<<<<<<<<<< + * return &obj.from_slice + * else: + */ + if (!(likely(((((PyObject *)__pyx_v_memview)) == Py_None) || likely(__Pyx_TypeTest(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type))))) __PYX_ERR(1, 1056, __pyx_L1_error) + __pyx_t_2 = ((PyObject *)__pyx_v_memview); + __Pyx_INCREF(__pyx_t_2); + __pyx_v_obj = ((struct __pyx_memoryviewslice_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":1057 + * if isinstance(memview, _memoryviewslice): + * obj = memview + * return &obj.from_slice # <<<<<<<<<<<<<< + * else: + * slice_copy(memview, mslice) + */ + __pyx_r = (&__pyx_v_obj->from_slice); + goto __pyx_L0; + + /* "View.MemoryView":1055 + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * obj = memview + * return &obj.from_slice + */ + } + + /* "View.MemoryView":1059 + * return &obj.from_slice + * else: + * slice_copy(memview, mslice) # <<<<<<<<<<<<<< + * return mslice + * + */ + /*else*/ { + __pyx_memoryview_slice_copy(__pyx_v_memview, __pyx_v_mslice); + + /* "View.MemoryView":1060 + * else: + * slice_copy(memview, mslice) + * return mslice # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_slice_copy') + */ + __pyx_r = __pyx_v_mslice; + goto __pyx_L0; + } + + /* "View.MemoryView":1052 + * + * @cname('__pyx_memoryview_get_slice_from_memoryview') + * cdef __Pyx_memviewslice *get_slice_from_memview(memoryview memview, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.get_slice_from_memview", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_obj); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1063 + * + * @cname('__pyx_memoryview_slice_copy') + * cdef void slice_copy(memoryview memview, __Pyx_memviewslice *dst) noexcept: # <<<<<<<<<<<<<< + * cdef int dim + * cdef (Py_ssize_t*) shape, strides, suboffsets + */ + +static void __pyx_memoryview_slice_copy(struct __pyx_memoryview_obj *__pyx_v_memview, __Pyx_memviewslice *__pyx_v_dst) { + int __pyx_v_dim; + Py_ssize_t *__pyx_v_shape; + Py_ssize_t *__pyx_v_strides; + Py_ssize_t *__pyx_v_suboffsets; + Py_ssize_t *__pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + Py_ssize_t __pyx_t_5; + int __pyx_t_6; + + /* "View.MemoryView":1067 + * cdef (Py_ssize_t*) shape, strides, suboffsets + * + * shape = memview.view.shape # <<<<<<<<<<<<<< + * strides = memview.view.strides + * suboffsets = memview.view.suboffsets + */ + __pyx_t_1 = __pyx_v_memview->view.shape; + __pyx_v_shape = __pyx_t_1; + + /* "View.MemoryView":1068 + * + * shape = memview.view.shape + * strides = memview.view.strides # <<<<<<<<<<<<<< + * suboffsets = memview.view.suboffsets + * + */ + __pyx_t_1 = __pyx_v_memview->view.strides; + __pyx_v_strides = __pyx_t_1; + + /* "View.MemoryView":1069 + * shape = memview.view.shape + * strides = memview.view.strides + * suboffsets = memview.view.suboffsets # <<<<<<<<<<<<<< + * + * dst.memview = <__pyx_memoryview *> memview + */ + __pyx_t_1 = __pyx_v_memview->view.suboffsets; + __pyx_v_suboffsets = __pyx_t_1; + + /* "View.MemoryView":1071 + * suboffsets = memview.view.suboffsets + * + * dst.memview = <__pyx_memoryview *> memview # <<<<<<<<<<<<<< + * dst.data = memview.view.buf + * + */ + __pyx_v_dst->memview = ((struct __pyx_memoryview_obj *)__pyx_v_memview); + + /* "View.MemoryView":1072 + * + * dst.memview = <__pyx_memoryview *> memview + * dst.data = memview.view.buf # <<<<<<<<<<<<<< + * + * for dim in range(memview.view.ndim): + */ + __pyx_v_dst->data = ((char *)__pyx_v_memview->view.buf); + + /* "View.MemoryView":1074 + * dst.data = memview.view.buf + * + * for dim in range(memview.view.ndim): # <<<<<<<<<<<<<< + * dst.shape[dim] = shape[dim] + * dst.strides[dim] = strides[dim] + */ + __pyx_t_2 = __pyx_v_memview->view.ndim; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_dim = __pyx_t_4; + + /* "View.MemoryView":1075 + * + * for dim in range(memview.view.ndim): + * dst.shape[dim] = shape[dim] # <<<<<<<<<<<<<< + * dst.strides[dim] = strides[dim] + * dst.suboffsets[dim] = suboffsets[dim] if suboffsets else -1 + */ + (__pyx_v_dst->shape[__pyx_v_dim]) = (__pyx_v_shape[__pyx_v_dim]); + + /* "View.MemoryView":1076 + * for dim in range(memview.view.ndim): + * dst.shape[dim] = shape[dim] + * dst.strides[dim] = strides[dim] # <<<<<<<<<<<<<< + * dst.suboffsets[dim] = suboffsets[dim] if suboffsets else -1 + * + */ + (__pyx_v_dst->strides[__pyx_v_dim]) = (__pyx_v_strides[__pyx_v_dim]); + + /* "View.MemoryView":1077 + * dst.shape[dim] = shape[dim] + * dst.strides[dim] = strides[dim] + * dst.suboffsets[dim] = suboffsets[dim] if suboffsets else -1 # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_copy_object') + */ + __pyx_t_6 = (__pyx_v_suboffsets != 0); + if (__pyx_t_6) { + __pyx_t_5 = (__pyx_v_suboffsets[__pyx_v_dim]); + } else { + __pyx_t_5 = -1L; + } + (__pyx_v_dst->suboffsets[__pyx_v_dim]) = __pyx_t_5; + } + + /* "View.MemoryView":1063 + * + * @cname('__pyx_memoryview_slice_copy') + * cdef void slice_copy(memoryview memview, __Pyx_memviewslice *dst) noexcept: # <<<<<<<<<<<<<< + * cdef int dim + * cdef (Py_ssize_t*) shape, strides, suboffsets + */ + + /* function exit code */ +} + +/* "View.MemoryView":1080 + * + * @cname('__pyx_memoryview_copy_object') + * cdef memoryview_copy(memoryview memview): # <<<<<<<<<<<<<< + * "Create a new memoryview object" + * cdef __Pyx_memviewslice memviewslice + */ + +static PyObject *__pyx_memoryview_copy_object(struct __pyx_memoryview_obj *__pyx_v_memview) { + __Pyx_memviewslice __pyx_v_memviewslice; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_copy", 1); + + /* "View.MemoryView":1083 + * "Create a new memoryview object" + * cdef __Pyx_memviewslice memviewslice + * slice_copy(memview, &memviewslice) # <<<<<<<<<<<<<< + * return memoryview_copy_from_slice(memview, &memviewslice) + * + */ + __pyx_memoryview_slice_copy(__pyx_v_memview, (&__pyx_v_memviewslice)); + + /* "View.MemoryView":1084 + * cdef __Pyx_memviewslice memviewslice + * slice_copy(memview, &memviewslice) + * return memoryview_copy_from_slice(memview, &memviewslice) # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_copy_object_from_slice') + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __pyx_memoryview_copy_object_from_slice(__pyx_v_memview, (&__pyx_v_memviewslice)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 1084, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":1080 + * + * @cname('__pyx_memoryview_copy_object') + * cdef memoryview_copy(memoryview memview): # <<<<<<<<<<<<<< + * "Create a new memoryview object" + * cdef __Pyx_memviewslice memviewslice + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview_copy", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1087 + * + * @cname('__pyx_memoryview_copy_object_from_slice') + * cdef memoryview_copy_from_slice(memoryview memview, __Pyx_memviewslice *memviewslice): # <<<<<<<<<<<<<< + * """ + * Create a new memoryview object from a given memoryview object and slice. + */ + +static PyObject *__pyx_memoryview_copy_object_from_slice(struct __pyx_memoryview_obj *__pyx_v_memview, __Pyx_memviewslice *__pyx_v_memviewslice) { + PyObject *(*__pyx_v_to_object_func)(char *); + int (*__pyx_v_to_dtype_func)(char *, PyObject *); + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *(*__pyx_t_2)(char *); + int (*__pyx_t_3)(char *, PyObject *); + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_copy_from_slice", 1); + + /* "View.MemoryView":1094 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * to_object_func = (<_memoryviewslice> memview).to_object_func + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":1095 + * + * if isinstance(memview, _memoryviewslice): + * to_object_func = (<_memoryviewslice> memview).to_object_func # <<<<<<<<<<<<<< + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + * else: + */ + __pyx_t_2 = ((struct __pyx_memoryviewslice_obj *)__pyx_v_memview)->to_object_func; + __pyx_v_to_object_func = __pyx_t_2; + + /* "View.MemoryView":1096 + * if isinstance(memview, _memoryviewslice): + * to_object_func = (<_memoryviewslice> memview).to_object_func + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func # <<<<<<<<<<<<<< + * else: + * to_object_func = NULL + */ + __pyx_t_3 = ((struct __pyx_memoryviewslice_obj *)__pyx_v_memview)->to_dtype_func; + __pyx_v_to_dtype_func = __pyx_t_3; + + /* "View.MemoryView":1094 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * to_object_func = (<_memoryviewslice> memview).to_object_func + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1098 + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + * else: + * to_object_func = NULL # <<<<<<<<<<<<<< + * to_dtype_func = NULL + * + */ + /*else*/ { + __pyx_v_to_object_func = NULL; + + /* "View.MemoryView":1099 + * else: + * to_object_func = NULL + * to_dtype_func = NULL # <<<<<<<<<<<<<< + * + * return memoryview_fromslice(memviewslice[0], memview.view.ndim, + */ + __pyx_v_to_dtype_func = NULL; + } + __pyx_L3:; + + /* "View.MemoryView":1101 + * to_dtype_func = NULL + * + * return memoryview_fromslice(memviewslice[0], memview.view.ndim, # <<<<<<<<<<<<<< + * to_object_func, to_dtype_func, + * memview.dtype_is_object) + */ + __Pyx_XDECREF(__pyx_r); + + /* "View.MemoryView":1103 + * return memoryview_fromslice(memviewslice[0], memview.view.ndim, + * to_object_func, to_dtype_func, + * memview.dtype_is_object) # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_4 = __pyx_memoryview_fromslice((__pyx_v_memviewslice[0]), __pyx_v_memview->view.ndim, __pyx_v_to_object_func, __pyx_v_to_dtype_func, __pyx_v_memview->dtype_is_object); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1101, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_r = __pyx_t_4; + __pyx_t_4 = 0; + goto __pyx_L0; + + /* "View.MemoryView":1087 + * + * @cname('__pyx_memoryview_copy_object_from_slice') + * cdef memoryview_copy_from_slice(memoryview memview, __Pyx_memviewslice *memviewslice): # <<<<<<<<<<<<<< + * """ + * Create a new memoryview object from a given memoryview object and slice. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.memoryview_copy_from_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1109 + * + * + * cdef Py_ssize_t abs_py_ssize_t(Py_ssize_t arg) noexcept nogil: # <<<<<<<<<<<<<< + * return -arg if arg < 0 else arg + * + */ + +static Py_ssize_t abs_py_ssize_t(Py_ssize_t __pyx_v_arg) { + Py_ssize_t __pyx_r; + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + + /* "View.MemoryView":1110 + * + * cdef Py_ssize_t abs_py_ssize_t(Py_ssize_t arg) noexcept nogil: + * return -arg if arg < 0 else arg # <<<<<<<<<<<<<< + * + * @cname('__pyx_get_best_slice_order') + */ + __pyx_t_2 = (__pyx_v_arg < 0); + if (__pyx_t_2) { + __pyx_t_1 = (-__pyx_v_arg); + } else { + __pyx_t_1 = __pyx_v_arg; + } + __pyx_r = __pyx_t_1; + goto __pyx_L0; + + /* "View.MemoryView":1109 + * + * + * cdef Py_ssize_t abs_py_ssize_t(Py_ssize_t arg) noexcept nogil: # <<<<<<<<<<<<<< + * return -arg if arg < 0 else arg + * + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1113 + * + * @cname('__pyx_get_best_slice_order') + * cdef char get_best_order(__Pyx_memviewslice *mslice, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * """ + * Figure out the best memory access order for a given slice. + */ + +static char __pyx_get_best_slice_order(__Pyx_memviewslice *__pyx_v_mslice, int __pyx_v_ndim) { + int __pyx_v_i; + Py_ssize_t __pyx_v_c_stride; + Py_ssize_t __pyx_v_f_stride; + char __pyx_r; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + + /* "View.MemoryView":1118 + * """ + * cdef int i + * cdef Py_ssize_t c_stride = 0 # <<<<<<<<<<<<<< + * cdef Py_ssize_t f_stride = 0 + * + */ + __pyx_v_c_stride = 0; + + /* "View.MemoryView":1119 + * cdef int i + * cdef Py_ssize_t c_stride = 0 + * cdef Py_ssize_t f_stride = 0 # <<<<<<<<<<<<<< + * + * for i in range(ndim - 1, -1, -1): + */ + __pyx_v_f_stride = 0; + + /* "View.MemoryView":1121 + * cdef Py_ssize_t f_stride = 0 + * + * for i in range(ndim - 1, -1, -1): # <<<<<<<<<<<<<< + * if mslice.shape[i] > 1: + * c_stride = mslice.strides[i] + */ + for (__pyx_t_1 = (__pyx_v_ndim - 1); __pyx_t_1 > -1; __pyx_t_1-=1) { + __pyx_v_i = __pyx_t_1; + + /* "View.MemoryView":1122 + * + * for i in range(ndim - 1, -1, -1): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * c_stride = mslice.strides[i] + * break + */ + __pyx_t_2 = ((__pyx_v_mslice->shape[__pyx_v_i]) > 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1123 + * for i in range(ndim - 1, -1, -1): + * if mslice.shape[i] > 1: + * c_stride = mslice.strides[i] # <<<<<<<<<<<<<< + * break + * + */ + __pyx_v_c_stride = (__pyx_v_mslice->strides[__pyx_v_i]); + + /* "View.MemoryView":1124 + * if mslice.shape[i] > 1: + * c_stride = mslice.strides[i] + * break # <<<<<<<<<<<<<< + * + * for i in range(ndim): + */ + goto __pyx_L4_break; + + /* "View.MemoryView":1122 + * + * for i in range(ndim - 1, -1, -1): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * c_stride = mslice.strides[i] + * break + */ + } + } + __pyx_L4_break:; + + /* "View.MemoryView":1126 + * break + * + * for i in range(ndim): # <<<<<<<<<<<<<< + * if mslice.shape[i] > 1: + * f_stride = mslice.strides[i] + */ + __pyx_t_1 = __pyx_v_ndim; + __pyx_t_3 = __pyx_t_1; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1127 + * + * for i in range(ndim): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * f_stride = mslice.strides[i] + * break + */ + __pyx_t_2 = ((__pyx_v_mslice->shape[__pyx_v_i]) > 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1128 + * for i in range(ndim): + * if mslice.shape[i] > 1: + * f_stride = mslice.strides[i] # <<<<<<<<<<<<<< + * break + * + */ + __pyx_v_f_stride = (__pyx_v_mslice->strides[__pyx_v_i]); + + /* "View.MemoryView":1129 + * if mslice.shape[i] > 1: + * f_stride = mslice.strides[i] + * break # <<<<<<<<<<<<<< + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): + */ + goto __pyx_L7_break; + + /* "View.MemoryView":1127 + * + * for i in range(ndim): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * f_stride = mslice.strides[i] + * break + */ + } + } + __pyx_L7_break:; + + /* "View.MemoryView":1131 + * break + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): # <<<<<<<<<<<<<< + * return 'C' + * else: + */ + __pyx_t_2 = (abs_py_ssize_t(__pyx_v_c_stride) <= abs_py_ssize_t(__pyx_v_f_stride)); + if (__pyx_t_2) { + + /* "View.MemoryView":1132 + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): + * return 'C' # <<<<<<<<<<<<<< + * else: + * return 'F' + */ + __pyx_r = 'C'; + goto __pyx_L0; + + /* "View.MemoryView":1131 + * break + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): # <<<<<<<<<<<<<< + * return 'C' + * else: + */ + } + + /* "View.MemoryView":1134 + * return 'C' + * else: + * return 'F' # <<<<<<<<<<<<<< + * + * @cython.cdivision(True) + */ + /*else*/ { + __pyx_r = 'F'; + goto __pyx_L0; + } + + /* "View.MemoryView":1113 + * + * @cname('__pyx_get_best_slice_order') + * cdef char get_best_order(__Pyx_memviewslice *mslice, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * """ + * Figure out the best memory access order for a given slice. + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1137 + * + * @cython.cdivision(True) + * cdef void _copy_strided_to_strided(char *src_data, Py_ssize_t *src_strides, # <<<<<<<<<<<<<< + * char *dst_data, Py_ssize_t *dst_strides, + * Py_ssize_t *src_shape, Py_ssize_t *dst_shape, + */ + +static void _copy_strided_to_strided(char *__pyx_v_src_data, Py_ssize_t *__pyx_v_src_strides, char *__pyx_v_dst_data, Py_ssize_t *__pyx_v_dst_strides, Py_ssize_t *__pyx_v_src_shape, Py_ssize_t *__pyx_v_dst_shape, int __pyx_v_ndim, size_t __pyx_v_itemsize) { + CYTHON_UNUSED Py_ssize_t __pyx_v_i; + CYTHON_UNUSED Py_ssize_t __pyx_v_src_extent; + Py_ssize_t __pyx_v_dst_extent; + Py_ssize_t __pyx_v_src_stride; + Py_ssize_t __pyx_v_dst_stride; + int __pyx_t_1; + int __pyx_t_2; + Py_ssize_t __pyx_t_3; + Py_ssize_t __pyx_t_4; + Py_ssize_t __pyx_t_5; + + /* "View.MemoryView":1144 + * + * cdef Py_ssize_t i + * cdef Py_ssize_t src_extent = src_shape[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t dst_extent = dst_shape[0] + * cdef Py_ssize_t src_stride = src_strides[0] + */ + __pyx_v_src_extent = (__pyx_v_src_shape[0]); + + /* "View.MemoryView":1145 + * cdef Py_ssize_t i + * cdef Py_ssize_t src_extent = src_shape[0] + * cdef Py_ssize_t dst_extent = dst_shape[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t src_stride = src_strides[0] + * cdef Py_ssize_t dst_stride = dst_strides[0] + */ + __pyx_v_dst_extent = (__pyx_v_dst_shape[0]); + + /* "View.MemoryView":1146 + * cdef Py_ssize_t src_extent = src_shape[0] + * cdef Py_ssize_t dst_extent = dst_shape[0] + * cdef Py_ssize_t src_stride = src_strides[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t dst_stride = dst_strides[0] + * + */ + __pyx_v_src_stride = (__pyx_v_src_strides[0]); + + /* "View.MemoryView":1147 + * cdef Py_ssize_t dst_extent = dst_shape[0] + * cdef Py_ssize_t src_stride = src_strides[0] + * cdef Py_ssize_t dst_stride = dst_strides[0] # <<<<<<<<<<<<<< + * + * if ndim == 1: + */ + __pyx_v_dst_stride = (__pyx_v_dst_strides[0]); + + /* "View.MemoryView":1149 + * cdef Py_ssize_t dst_stride = dst_strides[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): + */ + __pyx_t_1 = (__pyx_v_ndim == 1); + if (__pyx_t_1) { + + /* "View.MemoryView":1150 + * + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and # <<<<<<<<<<<<<< + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) + */ + __pyx_t_2 = (__pyx_v_src_stride > 0); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L5_bool_binop_done; + } + __pyx_t_2 = (__pyx_v_dst_stride > 0); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L5_bool_binop_done; + } + + /* "View.MemoryView":1151 + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): # <<<<<<<<<<<<<< + * memcpy(dst_data, src_data, itemsize * dst_extent) + * else: + */ + __pyx_t_2 = (((size_t)__pyx_v_src_stride) == __pyx_v_itemsize); + if (__pyx_t_2) { + __pyx_t_2 = (__pyx_v_itemsize == ((size_t)__pyx_v_dst_stride)); + } + __pyx_t_1 = __pyx_t_2; + __pyx_L5_bool_binop_done:; + + /* "View.MemoryView":1150 + * + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and # <<<<<<<<<<<<<< + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) + */ + if (__pyx_t_1) { + + /* "View.MemoryView":1152 + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) # <<<<<<<<<<<<<< + * else: + * for i in range(dst_extent): + */ + (void)(memcpy(__pyx_v_dst_data, __pyx_v_src_data, (__pyx_v_itemsize * __pyx_v_dst_extent))); + + /* "View.MemoryView":1150 + * + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and # <<<<<<<<<<<<<< + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) + */ + goto __pyx_L4; + } + + /* "View.MemoryView":1154 + * memcpy(dst_data, src_data, itemsize * dst_extent) + * else: + * for i in range(dst_extent): # <<<<<<<<<<<<<< + * memcpy(dst_data, src_data, itemsize) + * src_data += src_stride + */ + /*else*/ { + __pyx_t_3 = __pyx_v_dst_extent; + __pyx_t_4 = __pyx_t_3; + for (__pyx_t_5 = 0; __pyx_t_5 < __pyx_t_4; __pyx_t_5+=1) { + __pyx_v_i = __pyx_t_5; + + /* "View.MemoryView":1155 + * else: + * for i in range(dst_extent): + * memcpy(dst_data, src_data, itemsize) # <<<<<<<<<<<<<< + * src_data += src_stride + * dst_data += dst_stride + */ + (void)(memcpy(__pyx_v_dst_data, __pyx_v_src_data, __pyx_v_itemsize)); + + /* "View.MemoryView":1156 + * for i in range(dst_extent): + * memcpy(dst_data, src_data, itemsize) + * src_data += src_stride # <<<<<<<<<<<<<< + * dst_data += dst_stride + * else: + */ + __pyx_v_src_data = (__pyx_v_src_data + __pyx_v_src_stride); + + /* "View.MemoryView":1157 + * memcpy(dst_data, src_data, itemsize) + * src_data += src_stride + * dst_data += dst_stride # <<<<<<<<<<<<<< + * else: + * for i in range(dst_extent): + */ + __pyx_v_dst_data = (__pyx_v_dst_data + __pyx_v_dst_stride); + } + } + __pyx_L4:; + + /* "View.MemoryView":1149 + * cdef Py_ssize_t dst_stride = dst_strides[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1159 + * dst_data += dst_stride + * else: + * for i in range(dst_extent): # <<<<<<<<<<<<<< + * _copy_strided_to_strided(src_data, src_strides + 1, + * dst_data, dst_strides + 1, + */ + /*else*/ { + __pyx_t_3 = __pyx_v_dst_extent; + __pyx_t_4 = __pyx_t_3; + for (__pyx_t_5 = 0; __pyx_t_5 < __pyx_t_4; __pyx_t_5+=1) { + __pyx_v_i = __pyx_t_5; + + /* "View.MemoryView":1160 + * else: + * for i in range(dst_extent): + * _copy_strided_to_strided(src_data, src_strides + 1, # <<<<<<<<<<<<<< + * dst_data, dst_strides + 1, + * src_shape + 1, dst_shape + 1, + */ + _copy_strided_to_strided(__pyx_v_src_data, (__pyx_v_src_strides + 1), __pyx_v_dst_data, (__pyx_v_dst_strides + 1), (__pyx_v_src_shape + 1), (__pyx_v_dst_shape + 1), (__pyx_v_ndim - 1), __pyx_v_itemsize); + + /* "View.MemoryView":1164 + * src_shape + 1, dst_shape + 1, + * ndim - 1, itemsize) + * src_data += src_stride # <<<<<<<<<<<<<< + * dst_data += dst_stride + * + */ + __pyx_v_src_data = (__pyx_v_src_data + __pyx_v_src_stride); + + /* "View.MemoryView":1165 + * ndim - 1, itemsize) + * src_data += src_stride + * dst_data += dst_stride # <<<<<<<<<<<<<< + * + * cdef void copy_strided_to_strided(__Pyx_memviewslice *src, + */ + __pyx_v_dst_data = (__pyx_v_dst_data + __pyx_v_dst_stride); + } + } + __pyx_L3:; + + /* "View.MemoryView":1137 + * + * @cython.cdivision(True) + * cdef void _copy_strided_to_strided(char *src_data, Py_ssize_t *src_strides, # <<<<<<<<<<<<<< + * char *dst_data, Py_ssize_t *dst_strides, + * Py_ssize_t *src_shape, Py_ssize_t *dst_shape, + */ + + /* function exit code */ +} + +/* "View.MemoryView":1167 + * dst_data += dst_stride + * + * cdef void copy_strided_to_strided(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * int ndim, size_t itemsize) noexcept nogil: + */ + +static void copy_strided_to_strided(__Pyx_memviewslice *__pyx_v_src, __Pyx_memviewslice *__pyx_v_dst, int __pyx_v_ndim, size_t __pyx_v_itemsize) { + + /* "View.MemoryView":1170 + * __Pyx_memviewslice *dst, + * int ndim, size_t itemsize) noexcept nogil: + * _copy_strided_to_strided(src.data, src.strides, dst.data, dst.strides, # <<<<<<<<<<<<<< + * src.shape, dst.shape, ndim, itemsize) + * + */ + _copy_strided_to_strided(__pyx_v_src->data, __pyx_v_src->strides, __pyx_v_dst->data, __pyx_v_dst->strides, __pyx_v_src->shape, __pyx_v_dst->shape, __pyx_v_ndim, __pyx_v_itemsize); + + /* "View.MemoryView":1167 + * dst_data += dst_stride + * + * cdef void copy_strided_to_strided(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * int ndim, size_t itemsize) noexcept nogil: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1174 + * + * @cname('__pyx_memoryview_slice_get_size') + * cdef Py_ssize_t slice_get_size(__Pyx_memviewslice *src, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * "Return the size of the memory occupied by the slice in number of bytes" + * cdef Py_ssize_t shape, size = src.memview.view.itemsize + */ + +static Py_ssize_t __pyx_memoryview_slice_get_size(__Pyx_memviewslice *__pyx_v_src, int __pyx_v_ndim) { + Py_ssize_t __pyx_v_shape; + Py_ssize_t __pyx_v_size; + Py_ssize_t __pyx_r; + Py_ssize_t __pyx_t_1; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + + /* "View.MemoryView":1176 + * cdef Py_ssize_t slice_get_size(__Pyx_memviewslice *src, int ndim) noexcept nogil: + * "Return the size of the memory occupied by the slice in number of bytes" + * cdef Py_ssize_t shape, size = src.memview.view.itemsize # <<<<<<<<<<<<<< + * + * for shape in src.shape[:ndim]: + */ + __pyx_t_1 = __pyx_v_src->memview->view.itemsize; + __pyx_v_size = __pyx_t_1; + + /* "View.MemoryView":1178 + * cdef Py_ssize_t shape, size = src.memview.view.itemsize + * + * for shape in src.shape[:ndim]: # <<<<<<<<<<<<<< + * size *= shape + * + */ + __pyx_t_3 = (__pyx_v_src->shape + __pyx_v_ndim); + for (__pyx_t_4 = __pyx_v_src->shape; __pyx_t_4 < __pyx_t_3; __pyx_t_4++) { + __pyx_t_2 = __pyx_t_4; + __pyx_v_shape = (__pyx_t_2[0]); + + /* "View.MemoryView":1179 + * + * for shape in src.shape[:ndim]: + * size *= shape # <<<<<<<<<<<<<< + * + * return size + */ + __pyx_v_size = (__pyx_v_size * __pyx_v_shape); + } + + /* "View.MemoryView":1181 + * size *= shape + * + * return size # <<<<<<<<<<<<<< + * + * @cname('__pyx_fill_contig_strides_array') + */ + __pyx_r = __pyx_v_size; + goto __pyx_L0; + + /* "View.MemoryView":1174 + * + * @cname('__pyx_memoryview_slice_get_size') + * cdef Py_ssize_t slice_get_size(__Pyx_memviewslice *src, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * "Return the size of the memory occupied by the slice in number of bytes" + * cdef Py_ssize_t shape, size = src.memview.view.itemsize + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1184 + * + * @cname('__pyx_fill_contig_strides_array') + * cdef Py_ssize_t fill_contig_strides_array( # <<<<<<<<<<<<<< + * Py_ssize_t *shape, Py_ssize_t *strides, Py_ssize_t stride, + * int ndim, char order) noexcept nogil: + */ + +static Py_ssize_t __pyx_fill_contig_strides_array(Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, Py_ssize_t __pyx_v_stride, int __pyx_v_ndim, char __pyx_v_order) { + int __pyx_v_idx; + Py_ssize_t __pyx_r; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + + /* "View.MemoryView":1193 + * cdef int idx + * + * if order == 'F': # <<<<<<<<<<<<<< + * for idx in range(ndim): + * strides[idx] = stride + */ + __pyx_t_1 = (__pyx_v_order == 'F'); + if (__pyx_t_1) { + + /* "View.MemoryView":1194 + * + * if order == 'F': + * for idx in range(ndim): # <<<<<<<<<<<<<< + * strides[idx] = stride + * stride *= shape[idx] + */ + __pyx_t_2 = __pyx_v_ndim; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_idx = __pyx_t_4; + + /* "View.MemoryView":1195 + * if order == 'F': + * for idx in range(ndim): + * strides[idx] = stride # <<<<<<<<<<<<<< + * stride *= shape[idx] + * else: + */ + (__pyx_v_strides[__pyx_v_idx]) = __pyx_v_stride; + + /* "View.MemoryView":1196 + * for idx in range(ndim): + * strides[idx] = stride + * stride *= shape[idx] # <<<<<<<<<<<<<< + * else: + * for idx in range(ndim - 1, -1, -1): + */ + __pyx_v_stride = (__pyx_v_stride * (__pyx_v_shape[__pyx_v_idx])); + } + + /* "View.MemoryView":1193 + * cdef int idx + * + * if order == 'F': # <<<<<<<<<<<<<< + * for idx in range(ndim): + * strides[idx] = stride + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1198 + * stride *= shape[idx] + * else: + * for idx in range(ndim - 1, -1, -1): # <<<<<<<<<<<<<< + * strides[idx] = stride + * stride *= shape[idx] + */ + /*else*/ { + for (__pyx_t_2 = (__pyx_v_ndim - 1); __pyx_t_2 > -1; __pyx_t_2-=1) { + __pyx_v_idx = __pyx_t_2; + + /* "View.MemoryView":1199 + * else: + * for idx in range(ndim - 1, -1, -1): + * strides[idx] = stride # <<<<<<<<<<<<<< + * stride *= shape[idx] + * + */ + (__pyx_v_strides[__pyx_v_idx]) = __pyx_v_stride; + + /* "View.MemoryView":1200 + * for idx in range(ndim - 1, -1, -1): + * strides[idx] = stride + * stride *= shape[idx] # <<<<<<<<<<<<<< + * + * return stride + */ + __pyx_v_stride = (__pyx_v_stride * (__pyx_v_shape[__pyx_v_idx])); + } + } + __pyx_L3:; + + /* "View.MemoryView":1202 + * stride *= shape[idx] + * + * return stride # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_copy_data_to_temp') + */ + __pyx_r = __pyx_v_stride; + goto __pyx_L0; + + /* "View.MemoryView":1184 + * + * @cname('__pyx_fill_contig_strides_array') + * cdef Py_ssize_t fill_contig_strides_array( # <<<<<<<<<<<<<< + * Py_ssize_t *shape, Py_ssize_t *strides, Py_ssize_t stride, + * int ndim, char order) noexcept nogil: + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1205 + * + * @cname('__pyx_memoryview_copy_data_to_temp') + * cdef void *copy_data_to_temp(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *tmpslice, + * char order, + */ + +static void *__pyx_memoryview_copy_data_to_temp(__Pyx_memviewslice *__pyx_v_src, __Pyx_memviewslice *__pyx_v_tmpslice, char __pyx_v_order, int __pyx_v_ndim) { + int __pyx_v_i; + void *__pyx_v_result; + size_t __pyx_v_itemsize; + size_t __pyx_v_size; + void *__pyx_r; + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + struct __pyx_memoryview_obj *__pyx_t_4; + int __pyx_t_5; + int __pyx_t_6; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":1216 + * cdef void *result + * + * cdef size_t itemsize = src.memview.view.itemsize # <<<<<<<<<<<<<< + * cdef size_t size = slice_get_size(src, ndim) + * + */ + __pyx_t_1 = __pyx_v_src->memview->view.itemsize; + __pyx_v_itemsize = __pyx_t_1; + + /* "View.MemoryView":1217 + * + * cdef size_t itemsize = src.memview.view.itemsize + * cdef size_t size = slice_get_size(src, ndim) # <<<<<<<<<<<<<< + * + * result = malloc(size) + */ + __pyx_v_size = __pyx_memoryview_slice_get_size(__pyx_v_src, __pyx_v_ndim); + + /* "View.MemoryView":1219 + * cdef size_t size = slice_get_size(src, ndim) + * + * result = malloc(size) # <<<<<<<<<<<<<< + * if not result: + * _err_no_memory() + */ + __pyx_v_result = malloc(__pyx_v_size); + + /* "View.MemoryView":1220 + * + * result = malloc(size) + * if not result: # <<<<<<<<<<<<<< + * _err_no_memory() + * + */ + __pyx_t_2 = (!(__pyx_v_result != 0)); + if (__pyx_t_2) { + + /* "View.MemoryView":1221 + * result = malloc(size) + * if not result: + * _err_no_memory() # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_3 = __pyx_memoryview_err_no_memory(); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(1, 1221, __pyx_L1_error) + + /* "View.MemoryView":1220 + * + * result = malloc(size) + * if not result: # <<<<<<<<<<<<<< + * _err_no_memory() + * + */ + } + + /* "View.MemoryView":1224 + * + * + * tmpslice.data = result # <<<<<<<<<<<<<< + * tmpslice.memview = src.memview + * for i in range(ndim): + */ + __pyx_v_tmpslice->data = ((char *)__pyx_v_result); + + /* "View.MemoryView":1225 + * + * tmpslice.data = result + * tmpslice.memview = src.memview # <<<<<<<<<<<<<< + * for i in range(ndim): + * tmpslice.shape[i] = src.shape[i] + */ + __pyx_t_4 = __pyx_v_src->memview; + __pyx_v_tmpslice->memview = __pyx_t_4; + + /* "View.MemoryView":1226 + * tmpslice.data = result + * tmpslice.memview = src.memview + * for i in range(ndim): # <<<<<<<<<<<<<< + * tmpslice.shape[i] = src.shape[i] + * tmpslice.suboffsets[i] = -1 + */ + __pyx_t_3 = __pyx_v_ndim; + __pyx_t_5 = __pyx_t_3; + for (__pyx_t_6 = 0; __pyx_t_6 < __pyx_t_5; __pyx_t_6+=1) { + __pyx_v_i = __pyx_t_6; + + /* "View.MemoryView":1227 + * tmpslice.memview = src.memview + * for i in range(ndim): + * tmpslice.shape[i] = src.shape[i] # <<<<<<<<<<<<<< + * tmpslice.suboffsets[i] = -1 + * + */ + (__pyx_v_tmpslice->shape[__pyx_v_i]) = (__pyx_v_src->shape[__pyx_v_i]); + + /* "View.MemoryView":1228 + * for i in range(ndim): + * tmpslice.shape[i] = src.shape[i] + * tmpslice.suboffsets[i] = -1 # <<<<<<<<<<<<<< + * + * fill_contig_strides_array(&tmpslice.shape[0], &tmpslice.strides[0], itemsize, ndim, order) + */ + (__pyx_v_tmpslice->suboffsets[__pyx_v_i]) = -1L; + } + + /* "View.MemoryView":1230 + * tmpslice.suboffsets[i] = -1 + * + * fill_contig_strides_array(&tmpslice.shape[0], &tmpslice.strides[0], itemsize, ndim, order) # <<<<<<<<<<<<<< + * + * + */ + (void)(__pyx_fill_contig_strides_array((&(__pyx_v_tmpslice->shape[0])), (&(__pyx_v_tmpslice->strides[0])), __pyx_v_itemsize, __pyx_v_ndim, __pyx_v_order)); + + /* "View.MemoryView":1233 + * + * + * for i in range(ndim): # <<<<<<<<<<<<<< + * if tmpslice.shape[i] == 1: + * tmpslice.strides[i] = 0 + */ + __pyx_t_3 = __pyx_v_ndim; + __pyx_t_5 = __pyx_t_3; + for (__pyx_t_6 = 0; __pyx_t_6 < __pyx_t_5; __pyx_t_6+=1) { + __pyx_v_i = __pyx_t_6; + + /* "View.MemoryView":1234 + * + * for i in range(ndim): + * if tmpslice.shape[i] == 1: # <<<<<<<<<<<<<< + * tmpslice.strides[i] = 0 + * + */ + __pyx_t_2 = ((__pyx_v_tmpslice->shape[__pyx_v_i]) == 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1235 + * for i in range(ndim): + * if tmpslice.shape[i] == 1: + * tmpslice.strides[i] = 0 # <<<<<<<<<<<<<< + * + * if slice_is_contig(src[0], order, ndim): + */ + (__pyx_v_tmpslice->strides[__pyx_v_i]) = 0; + + /* "View.MemoryView":1234 + * + * for i in range(ndim): + * if tmpslice.shape[i] == 1: # <<<<<<<<<<<<<< + * tmpslice.strides[i] = 0 + * + */ + } + } + + /* "View.MemoryView":1237 + * tmpslice.strides[i] = 0 + * + * if slice_is_contig(src[0], order, ndim): # <<<<<<<<<<<<<< + * memcpy(result, src.data, size) + * else: + */ + __pyx_t_2 = __pyx_memviewslice_is_contig((__pyx_v_src[0]), __pyx_v_order, __pyx_v_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1238 + * + * if slice_is_contig(src[0], order, ndim): + * memcpy(result, src.data, size) # <<<<<<<<<<<<<< + * else: + * copy_strided_to_strided(src, tmpslice, ndim, itemsize) + */ + (void)(memcpy(__pyx_v_result, __pyx_v_src->data, __pyx_v_size)); + + /* "View.MemoryView":1237 + * tmpslice.strides[i] = 0 + * + * if slice_is_contig(src[0], order, ndim): # <<<<<<<<<<<<<< + * memcpy(result, src.data, size) + * else: + */ + goto __pyx_L9; + } + + /* "View.MemoryView":1240 + * memcpy(result, src.data, size) + * else: + * copy_strided_to_strided(src, tmpslice, ndim, itemsize) # <<<<<<<<<<<<<< + * + * return result + */ + /*else*/ { + copy_strided_to_strided(__pyx_v_src, __pyx_v_tmpslice, __pyx_v_ndim, __pyx_v_itemsize); + } + __pyx_L9:; + + /* "View.MemoryView":1242 + * copy_strided_to_strided(src, tmpslice, ndim, itemsize) + * + * return result # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = __pyx_v_result; + goto __pyx_L0; + + /* "View.MemoryView":1205 + * + * @cname('__pyx_memoryview_copy_data_to_temp') + * cdef void *copy_data_to_temp(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *tmpslice, + * char order, + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.copy_data_to_temp", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1247 + * + * @cname('__pyx_memoryview_err_extents') + * cdef int _err_extents(int i, Py_ssize_t extent1, # <<<<<<<<<<<<<< + * Py_ssize_t extent2) except -1 with gil: + * raise ValueError, f"got differing extents in dimension {i} (got {extent1} and {extent2})" + */ + +static int __pyx_memoryview_err_extents(int __pyx_v_i, Py_ssize_t __pyx_v_extent1, Py_ssize_t __pyx_v_extent2) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + Py_ssize_t __pyx_t_2; + Py_UCS4 __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_RefNannySetupContext("_err_extents", 0); + + /* "View.MemoryView":1249 + * cdef int _err_extents(int i, Py_ssize_t extent1, + * Py_ssize_t extent2) except -1 with gil: + * raise ValueError, f"got differing extents in dimension {i} (got {extent1} and {extent2})" # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_err_dim') + */ + __pyx_t_1 = PyTuple_New(7); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = 0; + __pyx_t_3 = 127; + __Pyx_INCREF(__pyx_kp_u_got_differing_extents_in_dimensi); + __pyx_t_2 += 35; + __Pyx_GIVEREF(__pyx_kp_u_got_differing_extents_in_dimensi); + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_kp_u_got_differing_extents_in_dimensi); + __pyx_t_4 = __Pyx_PyUnicode_From_int(__pyx_v_i, 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_2 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_t_4); + __pyx_t_4 = 0; + __Pyx_INCREF(__pyx_kp_u_got); + __pyx_t_2 += 6; + __Pyx_GIVEREF(__pyx_kp_u_got); + PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_kp_u_got); + __pyx_t_4 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_extent1, 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_2 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_1, 3, __pyx_t_4); + __pyx_t_4 = 0; + __Pyx_INCREF(__pyx_kp_u_and); + __pyx_t_2 += 5; + __Pyx_GIVEREF(__pyx_kp_u_and); + PyTuple_SET_ITEM(__pyx_t_1, 4, __pyx_kp_u_and); + __pyx_t_4 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_extent2, 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_2 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_1, 5, __pyx_t_4); + __pyx_t_4 = 0; + __Pyx_INCREF(__pyx_kp_u__7); + __pyx_t_2 += 1; + __Pyx_GIVEREF(__pyx_kp_u__7); + PyTuple_SET_ITEM(__pyx_t_1, 6, __pyx_kp_u__7); + __pyx_t_4 = __Pyx_PyUnicode_Join(__pyx_t_1, 7, __pyx_t_2, __pyx_t_3); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_t_4, 0, 0); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __PYX_ERR(1, 1249, __pyx_L1_error) + + /* "View.MemoryView":1247 + * + * @cname('__pyx_memoryview_err_extents') + * cdef int _err_extents(int i, Py_ssize_t extent1, # <<<<<<<<<<<<<< + * Py_ssize_t extent2) except -1 with gil: + * raise ValueError, f"got differing extents in dimension {i} (got {extent1} and {extent2})" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView._err_extents", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __Pyx_RefNannyFinishContext(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1252 + * + * @cname('__pyx_memoryview_err_dim') + * cdef int _err_dim(PyObject *error, str msg, int dim) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg % dim + * + */ + +static int __pyx_memoryview_err_dim(PyObject *__pyx_v_error, PyObject *__pyx_v_msg, int __pyx_v_dim) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_RefNannySetupContext("_err_dim", 0); + __Pyx_INCREF(__pyx_v_msg); + + /* "View.MemoryView":1253 + * @cname('__pyx_memoryview_err_dim') + * cdef int _err_dim(PyObject *error, str msg, int dim) except -1 with gil: + * raise error, msg % dim # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_err') + */ + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_dim); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 1253, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyString_FormatSafe(__pyx_v_msg, __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 1253, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(((PyObject *)__pyx_v_error), __pyx_t_2, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(1, 1253, __pyx_L1_error) + + /* "View.MemoryView":1252 + * + * @cname('__pyx_memoryview_err_dim') + * cdef int _err_dim(PyObject *error, str msg, int dim) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg % dim + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView._err_dim", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __Pyx_XDECREF(__pyx_v_msg); + __Pyx_RefNannyFinishContext(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1256 + * + * @cname('__pyx_memoryview_err') + * cdef int _err(PyObject *error, str msg) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg + * + */ + +static int __pyx_memoryview_err(PyObject *__pyx_v_error, PyObject *__pyx_v_msg) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_RefNannySetupContext("_err", 0); + __Pyx_INCREF(__pyx_v_msg); + + /* "View.MemoryView":1257 + * @cname('__pyx_memoryview_err') + * cdef int _err(PyObject *error, str msg) except -1 with gil: + * raise error, msg # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_err_no_memory') + */ + __Pyx_Raise(((PyObject *)__pyx_v_error), __pyx_v_msg, 0, 0); + __PYX_ERR(1, 1257, __pyx_L1_error) + + /* "View.MemoryView":1256 + * + * @cname('__pyx_memoryview_err') + * cdef int _err(PyObject *error, str msg) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._err", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __Pyx_XDECREF(__pyx_v_msg); + __Pyx_RefNannyFinishContext(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1260 + * + * @cname('__pyx_memoryview_err_no_memory') + * cdef int _err_no_memory() except -1 with gil: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + +static int __pyx_memoryview_err_no_memory(void) { + int __pyx_r; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + + /* "View.MemoryView":1261 + * @cname('__pyx_memoryview_err_no_memory') + * cdef int _err_no_memory() except -1 with gil: + * raise MemoryError # <<<<<<<<<<<<<< + * + * + */ + PyErr_NoMemory(); __PYX_ERR(1, 1261, __pyx_L1_error) + + /* "View.MemoryView":1260 + * + * @cname('__pyx_memoryview_err_no_memory') + * cdef int _err_no_memory() except -1 with gil: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._err_no_memory", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1265 + * + * @cname('__pyx_memoryview_copy_contents') + * cdef int memoryview_copy_contents(__Pyx_memviewslice src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice dst, + * int src_ndim, int dst_ndim, + */ + +static int __pyx_memoryview_copy_contents(__Pyx_memviewslice __pyx_v_src, __Pyx_memviewslice __pyx_v_dst, int __pyx_v_src_ndim, int __pyx_v_dst_ndim, int __pyx_v_dtype_is_object) { + void *__pyx_v_tmpdata; + size_t __pyx_v_itemsize; + int __pyx_v_i; + char __pyx_v_order; + int __pyx_v_broadcasting; + int __pyx_v_direct_copy; + __Pyx_memviewslice __pyx_v_tmp; + int __pyx_v_ndim; + int __pyx_r; + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + int __pyx_t_5; + int __pyx_t_6; + void *__pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":1273 + * Check for overlapping memory and verify the shapes. + * """ + * cdef void *tmpdata = NULL # <<<<<<<<<<<<<< + * cdef size_t itemsize = src.memview.view.itemsize + * cdef int i + */ + __pyx_v_tmpdata = NULL; + + /* "View.MemoryView":1274 + * """ + * cdef void *tmpdata = NULL + * cdef size_t itemsize = src.memview.view.itemsize # <<<<<<<<<<<<<< + * cdef int i + * cdef char order = get_best_order(&src, src_ndim) + */ + __pyx_t_1 = __pyx_v_src.memview->view.itemsize; + __pyx_v_itemsize = __pyx_t_1; + + /* "View.MemoryView":1276 + * cdef size_t itemsize = src.memview.view.itemsize + * cdef int i + * cdef char order = get_best_order(&src, src_ndim) # <<<<<<<<<<<<<< + * cdef bint broadcasting = False + * cdef bint direct_copy = False + */ + __pyx_v_order = __pyx_get_best_slice_order((&__pyx_v_src), __pyx_v_src_ndim); + + /* "View.MemoryView":1277 + * cdef int i + * cdef char order = get_best_order(&src, src_ndim) + * cdef bint broadcasting = False # <<<<<<<<<<<<<< + * cdef bint direct_copy = False + * cdef __Pyx_memviewslice tmp + */ + __pyx_v_broadcasting = 0; + + /* "View.MemoryView":1278 + * cdef char order = get_best_order(&src, src_ndim) + * cdef bint broadcasting = False + * cdef bint direct_copy = False # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice tmp + * + */ + __pyx_v_direct_copy = 0; + + /* "View.MemoryView":1281 + * cdef __Pyx_memviewslice tmp + * + * if src_ndim < dst_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: + */ + __pyx_t_2 = (__pyx_v_src_ndim < __pyx_v_dst_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1282 + * + * if src_ndim < dst_ndim: + * broadcast_leading(&src, src_ndim, dst_ndim) # <<<<<<<<<<<<<< + * elif dst_ndim < src_ndim: + * broadcast_leading(&dst, dst_ndim, src_ndim) + */ + __pyx_memoryview_broadcast_leading((&__pyx_v_src), __pyx_v_src_ndim, __pyx_v_dst_ndim); + + /* "View.MemoryView":1281 + * cdef __Pyx_memviewslice tmp + * + * if src_ndim < dst_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1283 + * if src_ndim < dst_ndim: + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&dst, dst_ndim, src_ndim) + * + */ + __pyx_t_2 = (__pyx_v_dst_ndim < __pyx_v_src_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1284 + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: + * broadcast_leading(&dst, dst_ndim, src_ndim) # <<<<<<<<<<<<<< + * + * cdef int ndim = max(src_ndim, dst_ndim) + */ + __pyx_memoryview_broadcast_leading((&__pyx_v_dst), __pyx_v_dst_ndim, __pyx_v_src_ndim); + + /* "View.MemoryView":1283 + * if src_ndim < dst_ndim: + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&dst, dst_ndim, src_ndim) + * + */ + } + __pyx_L3:; + + /* "View.MemoryView":1286 + * broadcast_leading(&dst, dst_ndim, src_ndim) + * + * cdef int ndim = max(src_ndim, dst_ndim) # <<<<<<<<<<<<<< + * + * for i in range(ndim): + */ + __pyx_t_3 = __pyx_v_dst_ndim; + __pyx_t_4 = __pyx_v_src_ndim; + __pyx_t_2 = (__pyx_t_3 > __pyx_t_4); + if (__pyx_t_2) { + __pyx_t_5 = __pyx_t_3; + } else { + __pyx_t_5 = __pyx_t_4; + } + __pyx_v_ndim = __pyx_t_5; + + /* "View.MemoryView":1288 + * cdef int ndim = max(src_ndim, dst_ndim) + * + * for i in range(ndim): # <<<<<<<<<<<<<< + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: + */ + __pyx_t_5 = __pyx_v_ndim; + __pyx_t_3 = __pyx_t_5; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1289 + * + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: # <<<<<<<<<<<<<< + * if src.shape[i] == 1: + * broadcasting = True + */ + __pyx_t_2 = ((__pyx_v_src.shape[__pyx_v_i]) != (__pyx_v_dst.shape[__pyx_v_i])); + if (__pyx_t_2) { + + /* "View.MemoryView":1290 + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: # <<<<<<<<<<<<<< + * broadcasting = True + * src.strides[i] = 0 + */ + __pyx_t_2 = ((__pyx_v_src.shape[__pyx_v_i]) == 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1291 + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: + * broadcasting = True # <<<<<<<<<<<<<< + * src.strides[i] = 0 + * else: + */ + __pyx_v_broadcasting = 1; + + /* "View.MemoryView":1292 + * if src.shape[i] == 1: + * broadcasting = True + * src.strides[i] = 0 # <<<<<<<<<<<<<< + * else: + * _err_extents(i, dst.shape[i], src.shape[i]) + */ + (__pyx_v_src.strides[__pyx_v_i]) = 0; + + /* "View.MemoryView":1290 + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: # <<<<<<<<<<<<<< + * broadcasting = True + * src.strides[i] = 0 + */ + goto __pyx_L7; + } + + /* "View.MemoryView":1294 + * src.strides[i] = 0 + * else: + * _err_extents(i, dst.shape[i], src.shape[i]) # <<<<<<<<<<<<<< + * + * if src.suboffsets[i] >= 0: + */ + /*else*/ { + __pyx_t_6 = __pyx_memoryview_err_extents(__pyx_v_i, (__pyx_v_dst.shape[__pyx_v_i]), (__pyx_v_src.shape[__pyx_v_i])); if (unlikely(__pyx_t_6 == ((int)-1))) __PYX_ERR(1, 1294, __pyx_L1_error) + } + __pyx_L7:; + + /* "View.MemoryView":1289 + * + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: # <<<<<<<<<<<<<< + * if src.shape[i] == 1: + * broadcasting = True + */ + } + + /* "View.MemoryView":1296 + * _err_extents(i, dst.shape[i], src.shape[i]) + * + * if src.suboffsets[i] >= 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + */ + __pyx_t_2 = ((__pyx_v_src.suboffsets[__pyx_v_i]) >= 0); + if (__pyx_t_2) { + + /* "View.MemoryView":1297 + * + * if src.suboffsets[i] >= 0: + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) # <<<<<<<<<<<<<< + * + * if slices_overlap(&src, &dst, ndim, itemsize): + */ + __pyx_t_6 = __pyx_memoryview_err_dim(PyExc_ValueError, __pyx_kp_s_Dimension_d_is_not_direct, __pyx_v_i); if (unlikely(__pyx_t_6 == ((int)-1))) __PYX_ERR(1, 1297, __pyx_L1_error) + + /* "View.MemoryView":1296 + * _err_extents(i, dst.shape[i], src.shape[i]) + * + * if src.suboffsets[i] >= 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + */ + } + } + + /* "View.MemoryView":1299 + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + * if slices_overlap(&src, &dst, ndim, itemsize): # <<<<<<<<<<<<<< + * + * if not slice_is_contig(src, order, ndim): + */ + __pyx_t_2 = __pyx_slices_overlap((&__pyx_v_src), (&__pyx_v_dst), __pyx_v_ndim, __pyx_v_itemsize); + if (__pyx_t_2) { + + /* "View.MemoryView":1301 + * if slices_overlap(&src, &dst, ndim, itemsize): + * + * if not slice_is_contig(src, order, ndim): # <<<<<<<<<<<<<< + * order = get_best_order(&dst, ndim) + * + */ + __pyx_t_2 = (!__pyx_memviewslice_is_contig(__pyx_v_src, __pyx_v_order, __pyx_v_ndim)); + if (__pyx_t_2) { + + /* "View.MemoryView":1302 + * + * if not slice_is_contig(src, order, ndim): + * order = get_best_order(&dst, ndim) # <<<<<<<<<<<<<< + * + * tmpdata = copy_data_to_temp(&src, &tmp, order, ndim) + */ + __pyx_v_order = __pyx_get_best_slice_order((&__pyx_v_dst), __pyx_v_ndim); + + /* "View.MemoryView":1301 + * if slices_overlap(&src, &dst, ndim, itemsize): + * + * if not slice_is_contig(src, order, ndim): # <<<<<<<<<<<<<< + * order = get_best_order(&dst, ndim) + * + */ + } + + /* "View.MemoryView":1304 + * order = get_best_order(&dst, ndim) + * + * tmpdata = copy_data_to_temp(&src, &tmp, order, ndim) # <<<<<<<<<<<<<< + * src = tmp + * + */ + __pyx_t_7 = __pyx_memoryview_copy_data_to_temp((&__pyx_v_src), (&__pyx_v_tmp), __pyx_v_order, __pyx_v_ndim); if (unlikely(__pyx_t_7 == ((void *)NULL))) __PYX_ERR(1, 1304, __pyx_L1_error) + __pyx_v_tmpdata = __pyx_t_7; + + /* "View.MemoryView":1305 + * + * tmpdata = copy_data_to_temp(&src, &tmp, order, ndim) + * src = tmp # <<<<<<<<<<<<<< + * + * if not broadcasting: + */ + __pyx_v_src = __pyx_v_tmp; + + /* "View.MemoryView":1299 + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + * if slices_overlap(&src, &dst, ndim, itemsize): # <<<<<<<<<<<<<< + * + * if not slice_is_contig(src, order, ndim): + */ + } + + /* "View.MemoryView":1307 + * src = tmp + * + * if not broadcasting: # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = (!__pyx_v_broadcasting); + if (__pyx_t_2) { + + /* "View.MemoryView":1310 + * + * + * if slice_is_contig(src, 'C', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): + */ + __pyx_t_2 = __pyx_memviewslice_is_contig(__pyx_v_src, 'C', __pyx_v_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1311 + * + * if slice_is_contig(src, 'C', ndim): + * direct_copy = slice_is_contig(dst, 'C', ndim) # <<<<<<<<<<<<<< + * elif slice_is_contig(src, 'F', ndim): + * direct_copy = slice_is_contig(dst, 'F', ndim) + */ + __pyx_v_direct_copy = __pyx_memviewslice_is_contig(__pyx_v_dst, 'C', __pyx_v_ndim); + + /* "View.MemoryView":1310 + * + * + * if slice_is_contig(src, 'C', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): + */ + goto __pyx_L12; + } + + /* "View.MemoryView":1312 + * if slice_is_contig(src, 'C', ndim): + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + */ + __pyx_t_2 = __pyx_memviewslice_is_contig(__pyx_v_src, 'F', __pyx_v_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1313 + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): + * direct_copy = slice_is_contig(dst, 'F', ndim) # <<<<<<<<<<<<<< + * + * if direct_copy: + */ + __pyx_v_direct_copy = __pyx_memviewslice_is_contig(__pyx_v_dst, 'F', __pyx_v_ndim); + + /* "View.MemoryView":1312 + * if slice_is_contig(src, 'C', ndim): + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + */ + } + __pyx_L12:; + + /* "View.MemoryView":1315 + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + * if direct_copy: # <<<<<<<<<<<<<< + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + */ + if (__pyx_v_direct_copy) { + + /* "View.MemoryView":1317 + * if direct_copy: + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) # <<<<<<<<<<<<<< + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 0); + + /* "View.MemoryView":1318 + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) # <<<<<<<<<<<<<< + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * free(tmpdata) + */ + (void)(memcpy(__pyx_v_dst.data, __pyx_v_src.data, __pyx_memoryview_slice_get_size((&__pyx_v_src), __pyx_v_ndim))); + + /* "View.MemoryView":1319 + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) # <<<<<<<<<<<<<< + * free(tmpdata) + * return 0 + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 1); + + /* "View.MemoryView":1320 + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * free(tmpdata) # <<<<<<<<<<<<<< + * return 0 + * + */ + free(__pyx_v_tmpdata); + + /* "View.MemoryView":1321 + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * free(tmpdata) + * return 0 # <<<<<<<<<<<<<< + * + * if order == 'F' == get_best_order(&dst, ndim): + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":1315 + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + * if direct_copy: # <<<<<<<<<<<<<< + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + */ + } + + /* "View.MemoryView":1307 + * src = tmp + * + * if not broadcasting: # <<<<<<<<<<<<<< + * + * + */ + } + + /* "View.MemoryView":1323 + * return 0 + * + * if order == 'F' == get_best_order(&dst, ndim): # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = (__pyx_v_order == 'F'); + if (__pyx_t_2) { + __pyx_t_2 = ('F' == __pyx_get_best_slice_order((&__pyx_v_dst), __pyx_v_ndim)); + } + if (__pyx_t_2) { + + /* "View.MemoryView":1326 + * + * + * transpose_memslice(&src) # <<<<<<<<<<<<<< + * transpose_memslice(&dst) + * + */ + __pyx_t_5 = __pyx_memslice_transpose((&__pyx_v_src)); if (unlikely(__pyx_t_5 == ((int)-1))) __PYX_ERR(1, 1326, __pyx_L1_error) + + /* "View.MemoryView":1327 + * + * transpose_memslice(&src) + * transpose_memslice(&dst) # <<<<<<<<<<<<<< + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + */ + __pyx_t_5 = __pyx_memslice_transpose((&__pyx_v_dst)); if (unlikely(__pyx_t_5 == ((int)-1))) __PYX_ERR(1, 1327, __pyx_L1_error) + + /* "View.MemoryView":1323 + * return 0 + * + * if order == 'F' == get_best_order(&dst, ndim): # <<<<<<<<<<<<<< + * + * + */ + } + + /* "View.MemoryView":1329 + * transpose_memslice(&dst) + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) # <<<<<<<<<<<<<< + * copy_strided_to_strided(&src, &dst, ndim, itemsize) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 0); + + /* "View.MemoryView":1330 + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * copy_strided_to_strided(&src, &dst, ndim, itemsize) # <<<<<<<<<<<<<< + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * + */ + copy_strided_to_strided((&__pyx_v_src), (&__pyx_v_dst), __pyx_v_ndim, __pyx_v_itemsize); + + /* "View.MemoryView":1331 + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * copy_strided_to_strided(&src, &dst, ndim, itemsize) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) # <<<<<<<<<<<<<< + * + * free(tmpdata) + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 1); + + /* "View.MemoryView":1333 + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * + * free(tmpdata) # <<<<<<<<<<<<<< + * return 0 + * + */ + free(__pyx_v_tmpdata); + + /* "View.MemoryView":1334 + * + * free(tmpdata) + * return 0 # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_broadcast_leading') + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":1265 + * + * @cname('__pyx_memoryview_copy_contents') + * cdef int memoryview_copy_contents(__Pyx_memviewslice src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice dst, + * int src_ndim, int dst_ndim, + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.memoryview_copy_contents", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1337 + * + * @cname('__pyx_memoryview_broadcast_leading') + * cdef void broadcast_leading(__Pyx_memviewslice *mslice, # <<<<<<<<<<<<<< + * int ndim, + * int ndim_other) noexcept nogil: + */ + +static void __pyx_memoryview_broadcast_leading(__Pyx_memviewslice *__pyx_v_mslice, int __pyx_v_ndim, int __pyx_v_ndim_other) { + int __pyx_v_i; + int __pyx_v_offset; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + + /* "View.MemoryView":1341 + * int ndim_other) noexcept nogil: + * cdef int i + * cdef int offset = ndim_other - ndim # <<<<<<<<<<<<<< + * + * for i in range(ndim - 1, -1, -1): + */ + __pyx_v_offset = (__pyx_v_ndim_other - __pyx_v_ndim); + + /* "View.MemoryView":1343 + * cdef int offset = ndim_other - ndim + * + * for i in range(ndim - 1, -1, -1): # <<<<<<<<<<<<<< + * mslice.shape[i + offset] = mslice.shape[i] + * mslice.strides[i + offset] = mslice.strides[i] + */ + for (__pyx_t_1 = (__pyx_v_ndim - 1); __pyx_t_1 > -1; __pyx_t_1-=1) { + __pyx_v_i = __pyx_t_1; + + /* "View.MemoryView":1344 + * + * for i in range(ndim - 1, -1, -1): + * mslice.shape[i + offset] = mslice.shape[i] # <<<<<<<<<<<<<< + * mslice.strides[i + offset] = mslice.strides[i] + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] + */ + (__pyx_v_mslice->shape[(__pyx_v_i + __pyx_v_offset)]) = (__pyx_v_mslice->shape[__pyx_v_i]); + + /* "View.MemoryView":1345 + * for i in range(ndim - 1, -1, -1): + * mslice.shape[i + offset] = mslice.shape[i] + * mslice.strides[i + offset] = mslice.strides[i] # <<<<<<<<<<<<<< + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] + * + */ + (__pyx_v_mslice->strides[(__pyx_v_i + __pyx_v_offset)]) = (__pyx_v_mslice->strides[__pyx_v_i]); + + /* "View.MemoryView":1346 + * mslice.shape[i + offset] = mslice.shape[i] + * mslice.strides[i + offset] = mslice.strides[i] + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] # <<<<<<<<<<<<<< + * + * for i in range(offset): + */ + (__pyx_v_mslice->suboffsets[(__pyx_v_i + __pyx_v_offset)]) = (__pyx_v_mslice->suboffsets[__pyx_v_i]); + } + + /* "View.MemoryView":1348 + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] + * + * for i in range(offset): # <<<<<<<<<<<<<< + * mslice.shape[i] = 1 + * mslice.strides[i] = mslice.strides[0] + */ + __pyx_t_1 = __pyx_v_offset; + __pyx_t_2 = __pyx_t_1; + for (__pyx_t_3 = 0; __pyx_t_3 < __pyx_t_2; __pyx_t_3+=1) { + __pyx_v_i = __pyx_t_3; + + /* "View.MemoryView":1349 + * + * for i in range(offset): + * mslice.shape[i] = 1 # <<<<<<<<<<<<<< + * mslice.strides[i] = mslice.strides[0] + * mslice.suboffsets[i] = -1 + */ + (__pyx_v_mslice->shape[__pyx_v_i]) = 1; + + /* "View.MemoryView":1350 + * for i in range(offset): + * mslice.shape[i] = 1 + * mslice.strides[i] = mslice.strides[0] # <<<<<<<<<<<<<< + * mslice.suboffsets[i] = -1 + * + */ + (__pyx_v_mslice->strides[__pyx_v_i]) = (__pyx_v_mslice->strides[0]); + + /* "View.MemoryView":1351 + * mslice.shape[i] = 1 + * mslice.strides[i] = mslice.strides[0] + * mslice.suboffsets[i] = -1 # <<<<<<<<<<<<<< + * + * + */ + (__pyx_v_mslice->suboffsets[__pyx_v_i]) = -1L; + } + + /* "View.MemoryView":1337 + * + * @cname('__pyx_memoryview_broadcast_leading') + * cdef void broadcast_leading(__Pyx_memviewslice *mslice, # <<<<<<<<<<<<<< + * int ndim, + * int ndim_other) noexcept nogil: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1359 + * + * @cname('__pyx_memoryview_refcount_copying') + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: # <<<<<<<<<<<<<< + * + * if dtype_is_object: + */ + +static void __pyx_memoryview_refcount_copying(__Pyx_memviewslice *__pyx_v_dst, int __pyx_v_dtype_is_object, int __pyx_v_ndim, int __pyx_v_inc) { + + /* "View.MemoryView":1361 + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: + * + * if dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice_with_gil(dst.data, dst.shape, dst.strides, ndim, inc) + * + */ + if (__pyx_v_dtype_is_object) { + + /* "View.MemoryView":1362 + * + * if dtype_is_object: + * refcount_objects_in_slice_with_gil(dst.data, dst.shape, dst.strides, ndim, inc) # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_refcount_objects_in_slice_with_gil') + */ + __pyx_memoryview_refcount_objects_in_slice_with_gil(__pyx_v_dst->data, __pyx_v_dst->shape, __pyx_v_dst->strides, __pyx_v_ndim, __pyx_v_inc); + + /* "View.MemoryView":1361 + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: + * + * if dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice_with_gil(dst.data, dst.shape, dst.strides, ndim, inc) + * + */ + } + + /* "View.MemoryView":1359 + * + * @cname('__pyx_memoryview_refcount_copying') + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: # <<<<<<<<<<<<<< + * + * if dtype_is_object: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1365 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice_with_gil') + * cdef void refcount_objects_in_slice_with_gil(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * bint inc) noexcept with gil: + */ + +static void __pyx_memoryview_refcount_objects_in_slice_with_gil(char *__pyx_v_data, Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, int __pyx_v_ndim, int __pyx_v_inc) { + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + + /* "View.MemoryView":1368 + * Py_ssize_t *strides, int ndim, + * bint inc) noexcept with gil: + * refcount_objects_in_slice(data, shape, strides, ndim, inc) # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_refcount_objects_in_slice') + */ + __pyx_memoryview_refcount_objects_in_slice(__pyx_v_data, __pyx_v_shape, __pyx_v_strides, __pyx_v_ndim, __pyx_v_inc); + + /* "View.MemoryView":1365 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice_with_gil') + * cdef void refcount_objects_in_slice_with_gil(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * bint inc) noexcept with gil: + */ + + /* function exit code */ + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif +} + +/* "View.MemoryView":1371 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice') + * cdef void refcount_objects_in_slice(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, bint inc) noexcept: + * cdef Py_ssize_t i + */ + +static void __pyx_memoryview_refcount_objects_in_slice(char *__pyx_v_data, Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, int __pyx_v_ndim, int __pyx_v_inc) { + CYTHON_UNUSED Py_ssize_t __pyx_v_i; + Py_ssize_t __pyx_v_stride; + Py_ssize_t __pyx_t_1; + Py_ssize_t __pyx_t_2; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + + /* "View.MemoryView":1374 + * Py_ssize_t *strides, int ndim, bint inc) noexcept: + * cdef Py_ssize_t i + * cdef Py_ssize_t stride = strides[0] # <<<<<<<<<<<<<< + * + * for i in range(shape[0]): + */ + __pyx_v_stride = (__pyx_v_strides[0]); + + /* "View.MemoryView":1376 + * cdef Py_ssize_t stride = strides[0] + * + * for i in range(shape[0]): # <<<<<<<<<<<<<< + * if ndim == 1: + * if inc: + */ + __pyx_t_1 = (__pyx_v_shape[0]); + __pyx_t_2 = __pyx_t_1; + for (__pyx_t_3 = 0; __pyx_t_3 < __pyx_t_2; __pyx_t_3+=1) { + __pyx_v_i = __pyx_t_3; + + /* "View.MemoryView":1377 + * + * for i in range(shape[0]): + * if ndim == 1: # <<<<<<<<<<<<<< + * if inc: + * Py_INCREF(( data)[0]) + */ + __pyx_t_4 = (__pyx_v_ndim == 1); + if (__pyx_t_4) { + + /* "View.MemoryView":1378 + * for i in range(shape[0]): + * if ndim == 1: + * if inc: # <<<<<<<<<<<<<< + * Py_INCREF(( data)[0]) + * else: + */ + if (__pyx_v_inc) { + + /* "View.MemoryView":1379 + * if ndim == 1: + * if inc: + * Py_INCREF(( data)[0]) # <<<<<<<<<<<<<< + * else: + * Py_DECREF(( data)[0]) + */ + Py_INCREF((((PyObject **)__pyx_v_data)[0])); + + /* "View.MemoryView":1378 + * for i in range(shape[0]): + * if ndim == 1: + * if inc: # <<<<<<<<<<<<<< + * Py_INCREF(( data)[0]) + * else: + */ + goto __pyx_L6; + } + + /* "View.MemoryView":1381 + * Py_INCREF(( data)[0]) + * else: + * Py_DECREF(( data)[0]) # <<<<<<<<<<<<<< + * else: + * refcount_objects_in_slice(data, shape + 1, strides + 1, ndim - 1, inc) + */ + /*else*/ { + Py_DECREF((((PyObject **)__pyx_v_data)[0])); + } + __pyx_L6:; + + /* "View.MemoryView":1377 + * + * for i in range(shape[0]): + * if ndim == 1: # <<<<<<<<<<<<<< + * if inc: + * Py_INCREF(( data)[0]) + */ + goto __pyx_L5; + } + + /* "View.MemoryView":1383 + * Py_DECREF(( data)[0]) + * else: + * refcount_objects_in_slice(data, shape + 1, strides + 1, ndim - 1, inc) # <<<<<<<<<<<<<< + * + * data += stride + */ + /*else*/ { + __pyx_memoryview_refcount_objects_in_slice(__pyx_v_data, (__pyx_v_shape + 1), (__pyx_v_strides + 1), (__pyx_v_ndim - 1), __pyx_v_inc); + } + __pyx_L5:; + + /* "View.MemoryView":1385 + * refcount_objects_in_slice(data, shape + 1, strides + 1, ndim - 1, inc) + * + * data += stride # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_data = (__pyx_v_data + __pyx_v_stride); + } + + /* "View.MemoryView":1371 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice') + * cdef void refcount_objects_in_slice(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, bint inc) noexcept: + * cdef Py_ssize_t i + */ + + /* function exit code */ +} + +/* "View.MemoryView":1391 + * + * @cname('__pyx_memoryview_slice_assign_scalar') + * cdef void slice_assign_scalar(__Pyx_memviewslice *dst, int ndim, # <<<<<<<<<<<<<< + * size_t itemsize, void *item, + * bint dtype_is_object) noexcept nogil: + */ + +static void __pyx_memoryview_slice_assign_scalar(__Pyx_memviewslice *__pyx_v_dst, int __pyx_v_ndim, size_t __pyx_v_itemsize, void *__pyx_v_item, int __pyx_v_dtype_is_object) { + + /* "View.MemoryView":1394 + * size_t itemsize, void *item, + * bint dtype_is_object) noexcept nogil: + * refcount_copying(dst, dtype_is_object, ndim, inc=False) # <<<<<<<<<<<<<< + * _slice_assign_scalar(dst.data, dst.shape, dst.strides, ndim, itemsize, item) + * refcount_copying(dst, dtype_is_object, ndim, inc=True) + */ + __pyx_memoryview_refcount_copying(__pyx_v_dst, __pyx_v_dtype_is_object, __pyx_v_ndim, 0); + + /* "View.MemoryView":1395 + * bint dtype_is_object) noexcept nogil: + * refcount_copying(dst, dtype_is_object, ndim, inc=False) + * _slice_assign_scalar(dst.data, dst.shape, dst.strides, ndim, itemsize, item) # <<<<<<<<<<<<<< + * refcount_copying(dst, dtype_is_object, ndim, inc=True) + * + */ + __pyx_memoryview__slice_assign_scalar(__pyx_v_dst->data, __pyx_v_dst->shape, __pyx_v_dst->strides, __pyx_v_ndim, __pyx_v_itemsize, __pyx_v_item); + + /* "View.MemoryView":1396 + * refcount_copying(dst, dtype_is_object, ndim, inc=False) + * _slice_assign_scalar(dst.data, dst.shape, dst.strides, ndim, itemsize, item) + * refcount_copying(dst, dtype_is_object, ndim, inc=True) # <<<<<<<<<<<<<< + * + * + */ + __pyx_memoryview_refcount_copying(__pyx_v_dst, __pyx_v_dtype_is_object, __pyx_v_ndim, 1); + + /* "View.MemoryView":1391 + * + * @cname('__pyx_memoryview_slice_assign_scalar') + * cdef void slice_assign_scalar(__Pyx_memviewslice *dst, int ndim, # <<<<<<<<<<<<<< + * size_t itemsize, void *item, + * bint dtype_is_object) noexcept nogil: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1400 + * + * @cname('__pyx_memoryview__slice_assign_scalar') + * cdef void _slice_assign_scalar(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * size_t itemsize, void *item) noexcept nogil: + */ + +static void __pyx_memoryview__slice_assign_scalar(char *__pyx_v_data, Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, int __pyx_v_ndim, size_t __pyx_v_itemsize, void *__pyx_v_item) { + CYTHON_UNUSED Py_ssize_t __pyx_v_i; + Py_ssize_t __pyx_v_stride; + Py_ssize_t __pyx_v_extent; + int __pyx_t_1; + Py_ssize_t __pyx_t_2; + Py_ssize_t __pyx_t_3; + Py_ssize_t __pyx_t_4; + + /* "View.MemoryView":1404 + * size_t itemsize, void *item) noexcept nogil: + * cdef Py_ssize_t i + * cdef Py_ssize_t stride = strides[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t extent = shape[0] + * + */ + __pyx_v_stride = (__pyx_v_strides[0]); + + /* "View.MemoryView":1405 + * cdef Py_ssize_t i + * cdef Py_ssize_t stride = strides[0] + * cdef Py_ssize_t extent = shape[0] # <<<<<<<<<<<<<< + * + * if ndim == 1: + */ + __pyx_v_extent = (__pyx_v_shape[0]); + + /* "View.MemoryView":1407 + * cdef Py_ssize_t extent = shape[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * for i in range(extent): + * memcpy(data, item, itemsize) + */ + __pyx_t_1 = (__pyx_v_ndim == 1); + if (__pyx_t_1) { + + /* "View.MemoryView":1408 + * + * if ndim == 1: + * for i in range(extent): # <<<<<<<<<<<<<< + * memcpy(data, item, itemsize) + * data += stride + */ + __pyx_t_2 = __pyx_v_extent; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1409 + * if ndim == 1: + * for i in range(extent): + * memcpy(data, item, itemsize) # <<<<<<<<<<<<<< + * data += stride + * else: + */ + (void)(memcpy(__pyx_v_data, __pyx_v_item, __pyx_v_itemsize)); + + /* "View.MemoryView":1410 + * for i in range(extent): + * memcpy(data, item, itemsize) + * data += stride # <<<<<<<<<<<<<< + * else: + * for i in range(extent): + */ + __pyx_v_data = (__pyx_v_data + __pyx_v_stride); + } + + /* "View.MemoryView":1407 + * cdef Py_ssize_t extent = shape[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * for i in range(extent): + * memcpy(data, item, itemsize) + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1412 + * data += stride + * else: + * for i in range(extent): # <<<<<<<<<<<<<< + * _slice_assign_scalar(data, shape + 1, strides + 1, ndim - 1, itemsize, item) + * data += stride + */ + /*else*/ { + __pyx_t_2 = __pyx_v_extent; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1413 + * else: + * for i in range(extent): + * _slice_assign_scalar(data, shape + 1, strides + 1, ndim - 1, itemsize, item) # <<<<<<<<<<<<<< + * data += stride + * + */ + __pyx_memoryview__slice_assign_scalar(__pyx_v_data, (__pyx_v_shape + 1), (__pyx_v_strides + 1), (__pyx_v_ndim - 1), __pyx_v_itemsize, __pyx_v_item); + + /* "View.MemoryView":1414 + * for i in range(extent): + * _slice_assign_scalar(data, shape + 1, strides + 1, ndim - 1, itemsize, item) + * data += stride # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_data = (__pyx_v_data + __pyx_v_stride); + } + } + __pyx_L3:; + + /* "View.MemoryView":1400 + * + * @cname('__pyx_memoryview__slice_assign_scalar') + * cdef void _slice_assign_scalar(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * size_t itemsize, void *item) noexcept nogil: + */ + + /* function exit code */ +} + +/* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_1__pyx_unpickle_Enum(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_15View_dot_MemoryView_1__pyx_unpickle_Enum = {"__pyx_unpickle_Enum", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15View_dot_MemoryView_1__pyx_unpickle_Enum, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15View_dot_MemoryView_1__pyx_unpickle_Enum(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v___pyx_type = 0; + long __pyx_v___pyx_checksum; + PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__pyx_unpickle_Enum (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_type,&__pyx_n_s_pyx_checksum,&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_type)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_checksum)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle_Enum", 1, 3, 3, 1); __PYX_ERR(1, 1, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle_Enum", 1, 3, 3, 2); __PYX_ERR(1, 1, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__pyx_unpickle_Enum") < 0)) __PYX_ERR(1, 1, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + } + __pyx_v___pyx_type = values[0]; + __pyx_v___pyx_checksum = __Pyx_PyInt_As_long(values[1]); if (unlikely((__pyx_v___pyx_checksum == (long)-1) && PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L3_error) + __pyx_v___pyx_state = values[2]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle_Enum", 1, 3, 3, __pyx_nargs); __PYX_ERR(1, 1, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.__pyx_unpickle_Enum", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15View_dot_MemoryView___pyx_unpickle_Enum(__pyx_self, __pyx_v___pyx_type, __pyx_v___pyx_checksum, __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView___pyx_unpickle_Enum(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v___pyx_type, long __pyx_v___pyx_checksum, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_v___pyx_PickleError = 0; + PyObject *__pyx_v___pyx_result = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_unpickle_Enum", 1); + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + */ + __pyx_t_1 = __Pyx_PyInt_From_long(__pyx_v___pyx_checksum); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 4, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = (__Pyx_PySequence_ContainsTF(__pyx_t_1, __pyx_tuple__8, Py_NE)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(1, 4, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (__pyx_t_2) { + + /* "(tree fragment)":5 + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): + * from pickle import PickleError as __pyx_PickleError # <<<<<<<<<<<<<< + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) + */ + __pyx_t_1 = PyList_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_s_PickleError); + __Pyx_GIVEREF(__pyx_n_s_PickleError); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_s_PickleError)) __PYX_ERR(1, 5, __pyx_L1_error); + __pyx_t_3 = __Pyx_Import(__pyx_n_s_pickle, __pyx_t_1, 0); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_ImportFrom(__pyx_t_3, __pyx_n_s_PickleError); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_t_1); + __pyx_v___pyx_PickleError = __pyx_t_1; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "(tree fragment)":6 + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum # <<<<<<<<<<<<<< + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: + */ + __pyx_t_3 = __Pyx_PyInt_From_long(__pyx_v___pyx_checksum); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_Incompatible_checksums_0x_x_vs_0, __pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_v___pyx_PickleError, __pyx_t_1, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(1, 6, __pyx_L1_error) + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + */ + } + + /* "(tree fragment)":7 + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) # <<<<<<<<<<<<<< + * if __pyx_state is not None: + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_MemviewEnum_type), __pyx_n_s_new); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 7, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = NULL; + __pyx_t_5 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_5 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_4, __pyx_v___pyx_type}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_5, 1+__pyx_t_5); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 7, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_v___pyx_result = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":8 + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + */ + __pyx_t_2 = (__pyx_v___pyx_state != Py_None); + if (__pyx_t_2) { + + /* "(tree fragment)":9 + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) # <<<<<<<<<<<<<< + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + */ + if (!(likely(PyTuple_CheckExact(__pyx_v___pyx_state))||((__pyx_v___pyx_state) == Py_None) || __Pyx_RaiseUnexpectedTypeError("tuple", __pyx_v___pyx_state))) __PYX_ERR(1, 9, __pyx_L1_error) + __pyx_t_1 = __pyx_unpickle_Enum__set_state(((struct __pyx_MemviewEnum_obj *)__pyx_v___pyx_result), ((PyObject*)__pyx_v___pyx_state)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 9, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":8 + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + */ + } + + /* "(tree fragment)":10 + * if __pyx_state is not None: + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result # <<<<<<<<<<<<<< + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v___pyx_result); + __pyx_r = __pyx_v___pyx_result; + goto __pyx_L0; + + /* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.__pyx_unpickle_Enum", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v___pyx_PickleError); + __Pyx_XDECREF(__pyx_v___pyx_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":11 + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): # <<<<<<<<<<<<<< + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + */ + +static PyObject *__pyx_unpickle_Enum__set_state(struct __pyx_MemviewEnum_obj *__pyx_v___pyx_result, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + int __pyx_t_8; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_unpickle_Enum__set_state", 1); + + /* "(tree fragment)":12 + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] # <<<<<<<<<<<<<< + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + * __pyx_result.__dict__.update(__pyx_state[1]) + */ + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 12, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 12, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + __Pyx_GOTREF(__pyx_v___pyx_result->name); + __Pyx_DECREF(__pyx_v___pyx_result->name); + __pyx_v___pyx_result->name = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":13 + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): # <<<<<<<<<<<<<< + * __pyx_result.__dict__.update(__pyx_state[1]) + */ + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); + __PYX_ERR(1, 13, __pyx_L1_error) + } + __pyx_t_3 = __Pyx_PyTuple_GET_SIZE(__pyx_v___pyx_state); if (unlikely(__pyx_t_3 == ((Py_ssize_t)-1))) __PYX_ERR(1, 13, __pyx_L1_error) + __pyx_t_4 = (__pyx_t_3 > 1); + if (__pyx_t_4) { + } else { + __pyx_t_2 = __pyx_t_4; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_4 = __Pyx_HasAttr(((PyObject *)__pyx_v___pyx_result), __pyx_n_s_dict); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(1, 13, __pyx_L1_error) + __pyx_t_2 = __pyx_t_4; + __pyx_L4_bool_binop_done:; + if (__pyx_t_2) { + + /* "(tree fragment)":14 + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + * __pyx_result.__dict__.update(__pyx_state[1]) # <<<<<<<<<<<<<< + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v___pyx_result), __pyx_n_s_dict); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_update); if (unlikely(!__pyx_t_6)) __PYX_ERR(1, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(1, 14, __pyx_L1_error) + } + __pyx_t_5 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_7 = NULL; + __pyx_t_8 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_6))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_6); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_6); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_6, function); + __pyx_t_8 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_7, __pyx_t_5}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_6, __pyx_callargs+1-__pyx_t_8, 1+__pyx_t_8); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":13 + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): # <<<<<<<<<<<<<< + * __pyx_result.__dict__.update(__pyx_state[1]) + */ + } + + /* "(tree fragment)":11 + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): # <<<<<<<<<<<<<< + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("View.MemoryView.__pyx_unpickle_Enum__set_state", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":245 + * + * @property + * cdef inline PyObject* base(self) nogil: # <<<<<<<<<<<<<< + * """Returns a borrowed reference to the object owning the data/memory. + * """ + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_7ndarray_4base_base(PyArrayObject *__pyx_v_self) { + PyObject *__pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":248 + * """Returns a borrowed reference to the object owning the data/memory. + * """ + * return PyArray_BASE(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_BASE(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":245 + * + * @property + * cdef inline PyObject* base(self) nogil: # <<<<<<<<<<<<<< + * """Returns a borrowed reference to the object owning the data/memory. + * """ + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":251 + * + * @property + * cdef inline dtype descr(self): # <<<<<<<<<<<<<< + * """Returns an owned reference to the dtype of the array. + * """ + */ + +static CYTHON_INLINE PyArray_Descr *__pyx_f_5numpy_7ndarray_5descr_descr(PyArrayObject *__pyx_v_self) { + PyArray_Descr *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyArray_Descr *__pyx_t_1; + __Pyx_RefNannySetupContext("descr", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":254 + * """Returns an owned reference to the dtype of the array. + * """ + * return PyArray_DESCR(self) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF((PyObject *)__pyx_r); + __pyx_t_1 = PyArray_DESCR(__pyx_v_self); + __Pyx_INCREF((PyObject *)((PyArray_Descr *)__pyx_t_1)); + __pyx_r = ((PyArray_Descr *)__pyx_t_1); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":251 + * + * @property + * cdef inline dtype descr(self): # <<<<<<<<<<<<<< + * """Returns an owned reference to the dtype of the array. + * """ + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF((PyObject *)__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":257 + * + * @property + * cdef inline int ndim(self) nogil: # <<<<<<<<<<<<<< + * """Returns the number of dimensions in the array. + * """ + */ + +static CYTHON_INLINE int __pyx_f_5numpy_7ndarray_4ndim_ndim(PyArrayObject *__pyx_v_self) { + int __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":260 + * """Returns the number of dimensions in the array. + * """ + * return PyArray_NDIM(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_NDIM(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":257 + * + * @property + * cdef inline int ndim(self) nogil: # <<<<<<<<<<<<<< + * """Returns the number of dimensions in the array. + * """ + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":263 + * + * @property + * cdef inline npy_intp *shape(self) nogil: # <<<<<<<<<<<<<< + * """Returns a pointer to the dimensions/shape of the array. + * The number of elements matches the number of dimensions of the array (ndim). + */ + +static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_5shape_shape(PyArrayObject *__pyx_v_self) { + npy_intp *__pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":268 + * Can return NULL for 0-dimensional arrays. + * """ + * return PyArray_DIMS(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_DIMS(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":263 + * + * @property + * cdef inline npy_intp *shape(self) nogil: # <<<<<<<<<<<<<< + * """Returns a pointer to the dimensions/shape of the array. + * The number of elements matches the number of dimensions of the array (ndim). + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":271 + * + * @property + * cdef inline npy_intp *strides(self) nogil: # <<<<<<<<<<<<<< + * """Returns a pointer to the strides of the array. + * The number of elements matches the number of dimensions of the array (ndim). + */ + +static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_7strides_strides(PyArrayObject *__pyx_v_self) { + npy_intp *__pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":275 + * The number of elements matches the number of dimensions of the array (ndim). + * """ + * return PyArray_STRIDES(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_STRIDES(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":271 + * + * @property + * cdef inline npy_intp *strides(self) nogil: # <<<<<<<<<<<<<< + * """Returns a pointer to the strides of the array. + * The number of elements matches the number of dimensions of the array (ndim). + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":278 + * + * @property + * cdef inline npy_intp size(self) nogil: # <<<<<<<<<<<<<< + * """Returns the total size (in number of elements) of the array. + * """ + */ + +static CYTHON_INLINE npy_intp __pyx_f_5numpy_7ndarray_4size_size(PyArrayObject *__pyx_v_self) { + npy_intp __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":281 + * """Returns the total size (in number of elements) of the array. + * """ + * return PyArray_SIZE(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_SIZE(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":278 + * + * @property + * cdef inline npy_intp size(self) nogil: # <<<<<<<<<<<<<< + * """Returns the total size (in number of elements) of the array. + * """ + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":284 + * + * @property + * cdef inline char* data(self) nogil: # <<<<<<<<<<<<<< + * """The pointer to the data buffer as a char*. + * This is provided for legacy reasons to avoid direct struct field access. + */ + +static CYTHON_INLINE char *__pyx_f_5numpy_7ndarray_4data_data(PyArrayObject *__pyx_v_self) { + char *__pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":290 + * of `PyArray_DATA()` instead, which returns a 'void*'. + * """ + * return PyArray_BYTES(self) # <<<<<<<<<<<<<< + * + * ctypedef unsigned char npy_bool + */ + __pyx_r = PyArray_BYTES(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":284 + * + * @property + * cdef inline char* data(self) nogil: # <<<<<<<<<<<<<< + * """The pointer to the data buffer as a char*. + * This is provided for legacy reasons to avoid direct struct field access. + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":773 + * ctypedef npy_cdouble complex_t + * + * cdef inline object PyArray_MultiIterNew1(a): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(1, a) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew1(PyObject *__pyx_v_a) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew1", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":774 + * + * cdef inline object PyArray_MultiIterNew1(a): + * return PyArray_MultiIterNew(1, a) # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew2(a, b): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(1, ((void *)__pyx_v_a)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 774, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":773 + * ctypedef npy_cdouble complex_t + * + * cdef inline object PyArray_MultiIterNew1(a): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(1, a) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew1", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":776 + * return PyArray_MultiIterNew(1, a) + * + * cdef inline object PyArray_MultiIterNew2(a, b): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(2, a, b) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew2(PyObject *__pyx_v_a, PyObject *__pyx_v_b) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew2", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":777 + * + * cdef inline object PyArray_MultiIterNew2(a, b): + * return PyArray_MultiIterNew(2, a, b) # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew3(a, b, c): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(2, ((void *)__pyx_v_a), ((void *)__pyx_v_b)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 777, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":776 + * return PyArray_MultiIterNew(1, a) + * + * cdef inline object PyArray_MultiIterNew2(a, b): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(2, a, b) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew2", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":779 + * return PyArray_MultiIterNew(2, a, b) + * + * cdef inline object PyArray_MultiIterNew3(a, b, c): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(3, a, b, c) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew3(PyObject *__pyx_v_a, PyObject *__pyx_v_b, PyObject *__pyx_v_c) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew3", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":780 + * + * cdef inline object PyArray_MultiIterNew3(a, b, c): + * return PyArray_MultiIterNew(3, a, b, c) # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew4(a, b, c, d): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(3, ((void *)__pyx_v_a), ((void *)__pyx_v_b), ((void *)__pyx_v_c)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 780, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":779 + * return PyArray_MultiIterNew(2, a, b) + * + * cdef inline object PyArray_MultiIterNew3(a, b, c): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(3, a, b, c) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew3", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":782 + * return PyArray_MultiIterNew(3, a, b, c) + * + * cdef inline object PyArray_MultiIterNew4(a, b, c, d): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(4, a, b, c, d) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew4(PyObject *__pyx_v_a, PyObject *__pyx_v_b, PyObject *__pyx_v_c, PyObject *__pyx_v_d) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew4", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":783 + * + * cdef inline object PyArray_MultiIterNew4(a, b, c, d): + * return PyArray_MultiIterNew(4, a, b, c, d) # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(4, ((void *)__pyx_v_a), ((void *)__pyx_v_b), ((void *)__pyx_v_c), ((void *)__pyx_v_d)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 783, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":782 + * return PyArray_MultiIterNew(3, a, b, c) + * + * cdef inline object PyArray_MultiIterNew4(a, b, c, d): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(4, a, b, c, d) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew4", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":785 + * return PyArray_MultiIterNew(4, a, b, c, d) + * + * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(5, a, b, c, d, e) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew5(PyObject *__pyx_v_a, PyObject *__pyx_v_b, PyObject *__pyx_v_c, PyObject *__pyx_v_d, PyObject *__pyx_v_e) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew5", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":786 + * + * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): + * return PyArray_MultiIterNew(5, a, b, c, d, e) # <<<<<<<<<<<<<< + * + * cdef inline tuple PyDataType_SHAPE(dtype d): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(5, ((void *)__pyx_v_a), ((void *)__pyx_v_b), ((void *)__pyx_v_c), ((void *)__pyx_v_d), ((void *)__pyx_v_e)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 786, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":785 + * return PyArray_MultiIterNew(4, a, b, c, d) + * + * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(5, a, b, c, d, e) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew5", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":788 + * return PyArray_MultiIterNew(5, a, b, c, d, e) + * + * cdef inline tuple PyDataType_SHAPE(dtype d): # <<<<<<<<<<<<<< + * if PyDataType_HASSUBARRAY(d): + * return d.subarray.shape + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyDataType_SHAPE(PyArray_Descr *__pyx_v_d) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + __Pyx_RefNannySetupContext("PyDataType_SHAPE", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":789 + * + * cdef inline tuple PyDataType_SHAPE(dtype d): + * if PyDataType_HASSUBARRAY(d): # <<<<<<<<<<<<<< + * return d.subarray.shape + * else: + */ + __pyx_t_1 = PyDataType_HASSUBARRAY(__pyx_v_d); + if (__pyx_t_1) { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":790 + * cdef inline tuple PyDataType_SHAPE(dtype d): + * if PyDataType_HASSUBARRAY(d): + * return d.subarray.shape # <<<<<<<<<<<<<< + * else: + * return () + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(((PyObject*)__pyx_v_d->subarray->shape)); + __pyx_r = ((PyObject*)__pyx_v_d->subarray->shape); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":789 + * + * cdef inline tuple PyDataType_SHAPE(dtype d): + * if PyDataType_HASSUBARRAY(d): # <<<<<<<<<<<<<< + * return d.subarray.shape + * else: + */ + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":792 + * return d.subarray.shape + * else: + * return () # <<<<<<<<<<<<<< + * + * + */ + /*else*/ { + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_empty_tuple); + __pyx_r = __pyx_empty_tuple; + goto __pyx_L0; + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":788 + * return PyArray_MultiIterNew(5, a, b, c, d, e) + * + * cdef inline tuple PyDataType_SHAPE(dtype d): # <<<<<<<<<<<<<< + * if PyDataType_HASSUBARRAY(d): + * return d.subarray.shape + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":968 + * int _import_umath() except -1 + * + * cdef inline void set_array_base(ndarray arr, object base): # <<<<<<<<<<<<<< + * Py_INCREF(base) # important to do this before stealing the reference below! + * PyArray_SetBaseObject(arr, base) + */ + +static CYTHON_INLINE void __pyx_f_5numpy_set_array_base(PyArrayObject *__pyx_v_arr, PyObject *__pyx_v_base) { + int __pyx_t_1; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":969 + * + * cdef inline void set_array_base(ndarray arr, object base): + * Py_INCREF(base) # important to do this before stealing the reference below! # <<<<<<<<<<<<<< + * PyArray_SetBaseObject(arr, base) + * + */ + Py_INCREF(__pyx_v_base); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":970 + * cdef inline void set_array_base(ndarray arr, object base): + * Py_INCREF(base) # important to do this before stealing the reference below! + * PyArray_SetBaseObject(arr, base) # <<<<<<<<<<<<<< + * + * cdef inline object get_array_base(ndarray arr): + */ + __pyx_t_1 = PyArray_SetBaseObject(__pyx_v_arr, __pyx_v_base); if (unlikely(__pyx_t_1 == ((int)-1))) __PYX_ERR(2, 970, __pyx_L1_error) + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":968 + * int _import_umath() except -1 + * + * cdef inline void set_array_base(ndarray arr, object base): # <<<<<<<<<<<<<< + * Py_INCREF(base) # important to do this before stealing the reference below! + * PyArray_SetBaseObject(arr, base) + */ + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("numpy.set_array_base", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_L0:; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":972 + * PyArray_SetBaseObject(arr, base) + * + * cdef inline object get_array_base(ndarray arr): # <<<<<<<<<<<<<< + * base = PyArray_BASE(arr) + * if base is NULL: + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_get_array_base(PyArrayObject *__pyx_v_arr) { + PyObject *__pyx_v_base; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + __Pyx_RefNannySetupContext("get_array_base", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":973 + * + * cdef inline object get_array_base(ndarray arr): + * base = PyArray_BASE(arr) # <<<<<<<<<<<<<< + * if base is NULL: + * return None + */ + __pyx_v_base = PyArray_BASE(__pyx_v_arr); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":974 + * cdef inline object get_array_base(ndarray arr): + * base = PyArray_BASE(arr) + * if base is NULL: # <<<<<<<<<<<<<< + * return None + * return base + */ + __pyx_t_1 = (__pyx_v_base == NULL); + if (__pyx_t_1) { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":975 + * base = PyArray_BASE(arr) + * if base is NULL: + * return None # <<<<<<<<<<<<<< + * return base + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":974 + * cdef inline object get_array_base(ndarray arr): + * base = PyArray_BASE(arr) + * if base is NULL: # <<<<<<<<<<<<<< + * return None + * return base + */ + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":976 + * if base is NULL: + * return None + * return base # <<<<<<<<<<<<<< + * + * # Versions of the import_* functions which are more suitable for + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(((PyObject *)__pyx_v_base)); + __pyx_r = ((PyObject *)__pyx_v_base); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":972 + * PyArray_SetBaseObject(arr, base) + * + * cdef inline object get_array_base(ndarray arr): # <<<<<<<<<<<<<< + * base = PyArray_BASE(arr) + * if base is NULL: + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":980 + * # Versions of the import_* functions which are more suitable for + * # Cython code. + * cdef inline int import_array() except -1: # <<<<<<<<<<<<<< + * try: + * __pyx_import_array() + */ + +static CYTHON_INLINE int __pyx_f_5numpy_import_array(void) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("import_array", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":981 + * # Cython code. + * cdef inline int import_array() except -1: + * try: # <<<<<<<<<<<<<< + * __pyx_import_array() + * except Exception: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":982 + * cdef inline int import_array() except -1: + * try: + * __pyx_import_array() # <<<<<<<<<<<<<< + * except Exception: + * raise ImportError("numpy.core.multiarray failed to import") + */ + __pyx_t_4 = _import_array(); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(2, 982, __pyx_L3_error) + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":981 + * # Cython code. + * cdef inline int import_array() except -1: + * try: # <<<<<<<<<<<<<< + * __pyx_import_array() + * except Exception: + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L8_try_end; + __pyx_L3_error:; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":983 + * try: + * __pyx_import_array() + * except Exception: # <<<<<<<<<<<<<< + * raise ImportError("numpy.core.multiarray failed to import") + * + */ + __pyx_t_4 = __Pyx_PyErr_ExceptionMatches(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0]))); + if (__pyx_t_4) { + __Pyx_AddTraceback("numpy.import_array", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_6, &__pyx_t_7) < 0) __PYX_ERR(2, 983, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_7); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":984 + * __pyx_import_array() + * except Exception: + * raise ImportError("numpy.core.multiarray failed to import") # <<<<<<<<<<<<<< + * + * cdef inline int import_umath() except -1: + */ + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_builtin_ImportError, __pyx_tuple__9, NULL); if (unlikely(!__pyx_t_8)) __PYX_ERR(2, 984, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_Raise(__pyx_t_8, 0, 0, 0); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __PYX_ERR(2, 984, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":981 + * # Cython code. + * cdef inline int import_array() except -1: + * try: # <<<<<<<<<<<<<< + * __pyx_import_array() + * except Exception: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + goto __pyx_L1_error; + __pyx_L8_try_end:; + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":980 + * # Versions of the import_* functions which are more suitable for + * # Cython code. + * cdef inline int import_array() except -1: # <<<<<<<<<<<<<< + * try: + * __pyx_import_array() + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("numpy.import_array", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":986 + * raise ImportError("numpy.core.multiarray failed to import") + * + * cdef inline int import_umath() except -1: # <<<<<<<<<<<<<< + * try: + * _import_umath() + */ + +static CYTHON_INLINE int __pyx_f_5numpy_import_umath(void) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("import_umath", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":987 + * + * cdef inline int import_umath() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":988 + * cdef inline int import_umath() except -1: + * try: + * _import_umath() # <<<<<<<<<<<<<< + * except Exception: + * raise ImportError("numpy.core.umath failed to import") + */ + __pyx_t_4 = _import_umath(); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(2, 988, __pyx_L3_error) + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":987 + * + * cdef inline int import_umath() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L8_try_end; + __pyx_L3_error:; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":989 + * try: + * _import_umath() + * except Exception: # <<<<<<<<<<<<<< + * raise ImportError("numpy.core.umath failed to import") + * + */ + __pyx_t_4 = __Pyx_PyErr_ExceptionMatches(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0]))); + if (__pyx_t_4) { + __Pyx_AddTraceback("numpy.import_umath", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_6, &__pyx_t_7) < 0) __PYX_ERR(2, 989, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_7); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":990 + * _import_umath() + * except Exception: + * raise ImportError("numpy.core.umath failed to import") # <<<<<<<<<<<<<< + * + * cdef inline int import_ufunc() except -1: + */ + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_builtin_ImportError, __pyx_tuple__10, NULL); if (unlikely(!__pyx_t_8)) __PYX_ERR(2, 990, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_Raise(__pyx_t_8, 0, 0, 0); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __PYX_ERR(2, 990, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":987 + * + * cdef inline int import_umath() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + goto __pyx_L1_error; + __pyx_L8_try_end:; + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":986 + * raise ImportError("numpy.core.multiarray failed to import") + * + * cdef inline int import_umath() except -1: # <<<<<<<<<<<<<< + * try: + * _import_umath() + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("numpy.import_umath", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":992 + * raise ImportError("numpy.core.umath failed to import") + * + * cdef inline int import_ufunc() except -1: # <<<<<<<<<<<<<< + * try: + * _import_umath() + */ + +static CYTHON_INLINE int __pyx_f_5numpy_import_ufunc(void) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("import_ufunc", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":993 + * + * cdef inline int import_ufunc() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":994 + * cdef inline int import_ufunc() except -1: + * try: + * _import_umath() # <<<<<<<<<<<<<< + * except Exception: + * raise ImportError("numpy.core.umath failed to import") + */ + __pyx_t_4 = _import_umath(); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(2, 994, __pyx_L3_error) + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":993 + * + * cdef inline int import_ufunc() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L8_try_end; + __pyx_L3_error:; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":995 + * try: + * _import_umath() + * except Exception: # <<<<<<<<<<<<<< + * raise ImportError("numpy.core.umath failed to import") + * + */ + __pyx_t_4 = __Pyx_PyErr_ExceptionMatches(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0]))); + if (__pyx_t_4) { + __Pyx_AddTraceback("numpy.import_ufunc", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_6, &__pyx_t_7) < 0) __PYX_ERR(2, 995, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_7); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":996 + * _import_umath() + * except Exception: + * raise ImportError("numpy.core.umath failed to import") # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_builtin_ImportError, __pyx_tuple__10, NULL); if (unlikely(!__pyx_t_8)) __PYX_ERR(2, 996, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_Raise(__pyx_t_8, 0, 0, 0); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __PYX_ERR(2, 996, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":993 + * + * cdef inline int import_ufunc() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + goto __pyx_L1_error; + __pyx_L8_try_end:; + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":992 + * raise ImportError("numpy.core.umath failed to import") + * + * cdef inline int import_ufunc() except -1: # <<<<<<<<<<<<<< + * try: + * _import_umath() + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("numpy.import_ufunc", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":999 + * + * + * cdef inline bint is_timedelta64_object(object obj): # <<<<<<<<<<<<<< + * """ + * Cython equivalent of `isinstance(obj, np.timedelta64)` + */ + +static CYTHON_INLINE int __pyx_f_5numpy_is_timedelta64_object(PyObject *__pyx_v_obj) { + int __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1011 + * bool + * """ + * return PyObject_TypeCheck(obj, &PyTimedeltaArrType_Type) # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = PyObject_TypeCheck(__pyx_v_obj, (&PyTimedeltaArrType_Type)); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":999 + * + * + * cdef inline bint is_timedelta64_object(object obj): # <<<<<<<<<<<<<< + * """ + * Cython equivalent of `isinstance(obj, np.timedelta64)` + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1014 + * + * + * cdef inline bint is_datetime64_object(object obj): # <<<<<<<<<<<<<< + * """ + * Cython equivalent of `isinstance(obj, np.datetime64)` + */ + +static CYTHON_INLINE int __pyx_f_5numpy_is_datetime64_object(PyObject *__pyx_v_obj) { + int __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1026 + * bool + * """ + * return PyObject_TypeCheck(obj, &PyDatetimeArrType_Type) # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = PyObject_TypeCheck(__pyx_v_obj, (&PyDatetimeArrType_Type)); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1014 + * + * + * cdef inline bint is_datetime64_object(object obj): # <<<<<<<<<<<<<< + * """ + * Cython equivalent of `isinstance(obj, np.datetime64)` + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1029 + * + * + * cdef inline npy_datetime get_datetime64_value(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the int64 value underlying scalar numpy datetime64 object + */ + +static CYTHON_INLINE npy_datetime __pyx_f_5numpy_get_datetime64_value(PyObject *__pyx_v_obj) { + npy_datetime __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1036 + * also needed. That can be found using `get_datetime64_unit`. + * """ + * return (obj).obval # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = ((PyDatetimeScalarObject *)__pyx_v_obj)->obval; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1029 + * + * + * cdef inline npy_datetime get_datetime64_value(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the int64 value underlying scalar numpy datetime64 object + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1039 + * + * + * cdef inline npy_timedelta get_timedelta64_value(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the int64 value underlying scalar numpy timedelta64 object + */ + +static CYTHON_INLINE npy_timedelta __pyx_f_5numpy_get_timedelta64_value(PyObject *__pyx_v_obj) { + npy_timedelta __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1043 + * returns the int64 value underlying scalar numpy timedelta64 object + * """ + * return (obj).obval # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = ((PyTimedeltaScalarObject *)__pyx_v_obj)->obval; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1039 + * + * + * cdef inline npy_timedelta get_timedelta64_value(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the int64 value underlying scalar numpy timedelta64 object + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1046 + * + * + * cdef inline NPY_DATETIMEUNIT get_datetime64_unit(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the unit part of the dtype for a numpy datetime64 object. + */ + +static CYTHON_INLINE NPY_DATETIMEUNIT __pyx_f_5numpy_get_datetime64_unit(PyObject *__pyx_v_obj) { + NPY_DATETIMEUNIT __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1050 + * returns the unit part of the dtype for a numpy datetime64 object. + * """ + * return (obj).obmeta.base # <<<<<<<<<<<<<< + */ + __pyx_r = ((NPY_DATETIMEUNIT)((PyDatetimeScalarObject *)__pyx_v_obj)->obmeta.base); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1046 + * + * + * cdef inline NPY_DATETIMEUNIT get_datetime64_unit(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the unit part of the dtype for a numpy datetime64 object. + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":70 + * cdef str nlp_solver_type + * + * def __cinit__(self, model_name, nlp_solver_type, N): # <<<<<<<<<<<<<< + * + * self.solver_created = False + */ + +/* Python wrapper */ +static int __pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_model_name = 0; + PyObject *__pyx_v_nlp_solver_type = 0; + PyObject *__pyx_v_N = 0; + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_model_name,&__pyx_n_s_nlp_solver_type,&__pyx_n_s_N,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_model_name)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 70, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_nlp_solver_type)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 70, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 3, 3, 1); __PYX_ERR(0, 70, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_N)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 70, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 3, 3, 2); __PYX_ERR(0, 70, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(0, 70, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + } + __pyx_v_model_name = values[0]; + __pyx_v_nlp_solver_type = values[1]; + __pyx_v_N = values[2]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 70, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython___cinit__(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_model_name, __pyx_v_nlp_solver_type, __pyx_v_N); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython___cinit__(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_model_name, PyObject *__pyx_v_nlp_solver_type, PyObject *__pyx_v_N) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__cinit__", 1); + + /* "acados_template/acados_ocp_solver_pyx.pyx":72 + * def __cinit__(self, model_name, nlp_solver_type, N): + * + * self.solver_created = False # <<<<<<<<<<<<<< + * + * self.N = N + */ + __pyx_v_self->solver_created = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":74 + * self.solver_created = False + * + * self.N = N # <<<<<<<<<<<<<< + * self.model_name = model_name + * self.nlp_solver_type = nlp_solver_type + */ + __pyx_t_1 = __Pyx_PyInt_As_int(__pyx_v_N); if (unlikely((__pyx_t_1 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 74, __pyx_L1_error) + __pyx_v_self->N = __pyx_t_1; + + /* "acados_template/acados_ocp_solver_pyx.pyx":75 + * + * self.N = N + * self.model_name = model_name # <<<<<<<<<<<<<< + * self.nlp_solver_type = nlp_solver_type + * + */ + if (!(likely(PyUnicode_CheckExact(__pyx_v_model_name))||((__pyx_v_model_name) == Py_None) || __Pyx_RaiseUnexpectedTypeError("unicode", __pyx_v_model_name))) __PYX_ERR(0, 75, __pyx_L1_error) + __pyx_t_2 = __pyx_v_model_name; + __Pyx_INCREF(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + __Pyx_GOTREF(__pyx_v_self->model_name); + __Pyx_DECREF(__pyx_v_self->model_name); + __pyx_v_self->model_name = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":76 + * self.N = N + * self.model_name = model_name + * self.nlp_solver_type = nlp_solver_type # <<<<<<<<<<<<<< + * + * # create capsule + */ + if (!(likely(PyUnicode_CheckExact(__pyx_v_nlp_solver_type))||((__pyx_v_nlp_solver_type) == Py_None) || __Pyx_RaiseUnexpectedTypeError("unicode", __pyx_v_nlp_solver_type))) __PYX_ERR(0, 76, __pyx_L1_error) + __pyx_t_2 = __pyx_v_nlp_solver_type; + __Pyx_INCREF(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + __Pyx_GOTREF(__pyx_v_self->nlp_solver_type); + __Pyx_DECREF(__pyx_v_self->nlp_solver_type); + __pyx_v_self->nlp_solver_type = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":79 + * + * # create capsule + * self.capsule = acados_solver.acados_create_capsule() # <<<<<<<<<<<<<< + * + * # create solver + */ + __pyx_v_self->capsule = long_acados_create_capsule(); + + /* "acados_template/acados_ocp_solver_pyx.pyx":82 + * + * # create solver + * assert acados_solver.acados_create(self.capsule) == 0 # <<<<<<<<<<<<<< + * self.solver_created = True + * + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_3 = (long_acados_create(__pyx_v_self->capsule) == 0); + if (unlikely(!__pyx_t_3)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(0, 82, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(0, 82, __pyx_L1_error) + #endif + + /* "acados_template/acados_ocp_solver_pyx.pyx":83 + * # create solver + * assert acados_solver.acados_create(self.capsule) == 0 + * self.solver_created = True # <<<<<<<<<<<<<< + * + * # get pointers solver + */ + __pyx_v_self->solver_created = 1; + + /* "acados_template/acados_ocp_solver_pyx.pyx":86 + * + * # get pointers solver + * self.__get_pointers_solver() # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_AcadosOcpSolverCython__get_poin); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 86, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = NULL; + __pyx_t_1 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_4))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_4); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_4); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_4, function); + __pyx_t_1 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_5, NULL}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_1, 0+__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 86, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":70 + * cdef str nlp_solver_type + * + * def __cinit__(self, model_name, nlp_solver_type, N): # <<<<<<<<<<<<<< + * + * self.solver_created = False + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":89 + * + * + * def __get_pointers_solver(self): # <<<<<<<<<<<<<< + * """ + * Private function to get the pointers for solver + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_3_AcadosOcpSolverCython__get_pointers_solver(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_2__get_pointers_solver, "\n Private function to get the pointers for solver\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_3_AcadosOcpSolverCython__get_pointers_solver = {"_AcadosOcpSolverCython__get_pointers_solver", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_3_AcadosOcpSolverCython__get_pointers_solver, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_2__get_pointers_solver}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_3_AcadosOcpSolverCython__get_pointers_solver(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("_AcadosOcpSolverCython__get_pointers_solver (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("_AcadosOcpSolverCython__get_pointers_solver", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "_AcadosOcpSolverCython__get_pointers_solver", 0))) return NULL; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_2__get_pointers_solver(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_2__get_pointers_solver(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("_AcadosOcpSolverCython__get_pointers_solver", 1); + + /* "acados_template/acados_ocp_solver_pyx.pyx":94 + * """ + * # get pointers solver + * self.nlp_opts = acados_solver.acados_get_nlp_opts(self.capsule) # <<<<<<<<<<<<<< + * self.nlp_dims = acados_solver.acados_get_nlp_dims(self.capsule) + * self.nlp_config = acados_solver.acados_get_nlp_config(self.capsule) + */ + __pyx_v_self->nlp_opts = long_acados_get_nlp_opts(__pyx_v_self->capsule); + + /* "acados_template/acados_ocp_solver_pyx.pyx":95 + * # get pointers solver + * self.nlp_opts = acados_solver.acados_get_nlp_opts(self.capsule) + * self.nlp_dims = acados_solver.acados_get_nlp_dims(self.capsule) # <<<<<<<<<<<<<< + * self.nlp_config = acados_solver.acados_get_nlp_config(self.capsule) + * self.nlp_out = acados_solver.acados_get_nlp_out(self.capsule) + */ + __pyx_v_self->nlp_dims = long_acados_get_nlp_dims(__pyx_v_self->capsule); + + /* "acados_template/acados_ocp_solver_pyx.pyx":96 + * self.nlp_opts = acados_solver.acados_get_nlp_opts(self.capsule) + * self.nlp_dims = acados_solver.acados_get_nlp_dims(self.capsule) + * self.nlp_config = acados_solver.acados_get_nlp_config(self.capsule) # <<<<<<<<<<<<<< + * self.nlp_out = acados_solver.acados_get_nlp_out(self.capsule) + * self.sens_out = acados_solver.acados_get_sens_out(self.capsule) + */ + __pyx_v_self->nlp_config = long_acados_get_nlp_config(__pyx_v_self->capsule); + + /* "acados_template/acados_ocp_solver_pyx.pyx":97 + * self.nlp_dims = acados_solver.acados_get_nlp_dims(self.capsule) + * self.nlp_config = acados_solver.acados_get_nlp_config(self.capsule) + * self.nlp_out = acados_solver.acados_get_nlp_out(self.capsule) # <<<<<<<<<<<<<< + * self.sens_out = acados_solver.acados_get_sens_out(self.capsule) + * self.nlp_in = acados_solver.acados_get_nlp_in(self.capsule) + */ + __pyx_v_self->nlp_out = long_acados_get_nlp_out(__pyx_v_self->capsule); + + /* "acados_template/acados_ocp_solver_pyx.pyx":98 + * self.nlp_config = acados_solver.acados_get_nlp_config(self.capsule) + * self.nlp_out = acados_solver.acados_get_nlp_out(self.capsule) + * self.sens_out = acados_solver.acados_get_sens_out(self.capsule) # <<<<<<<<<<<<<< + * self.nlp_in = acados_solver.acados_get_nlp_in(self.capsule) + * self.nlp_solver = acados_solver.acados_get_nlp_solver(self.capsule) + */ + __pyx_v_self->sens_out = long_acados_get_sens_out(__pyx_v_self->capsule); + + /* "acados_template/acados_ocp_solver_pyx.pyx":99 + * self.nlp_out = acados_solver.acados_get_nlp_out(self.capsule) + * self.sens_out = acados_solver.acados_get_sens_out(self.capsule) + * self.nlp_in = acados_solver.acados_get_nlp_in(self.capsule) # <<<<<<<<<<<<<< + * self.nlp_solver = acados_solver.acados_get_nlp_solver(self.capsule) + * + */ + __pyx_v_self->nlp_in = long_acados_get_nlp_in(__pyx_v_self->capsule); + + /* "acados_template/acados_ocp_solver_pyx.pyx":100 + * self.sens_out = acados_solver.acados_get_sens_out(self.capsule) + * self.nlp_in = acados_solver.acados_get_nlp_in(self.capsule) + * self.nlp_solver = acados_solver.acados_get_nlp_solver(self.capsule) # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_self->nlp_solver = long_acados_get_nlp_solver(__pyx_v_self->capsule); + + /* "acados_template/acados_ocp_solver_pyx.pyx":89 + * + * + * def __get_pointers_solver(self): # <<<<<<<<<<<<<< + * """ + * Private function to get the pointers for solver + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":103 + * + * + * def solve_for_x0(self, x0_bar): # <<<<<<<<<<<<<< + * """ + * Wrapper around `solve()` which sets initial state constraint, solves the OCP, and returns u0. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve_for_x0(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve_for_x0, "\n Wrapper around `solve()` which sets initial state constraint, solves the OCP, and returns u0.\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve_for_x0 = {"solve_for_x0", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve_for_x0, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve_for_x0}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve_for_x0(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_x0_bar = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("solve_for_x0 (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_x0_bar,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_x0_bar)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 103, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "solve_for_x0") < 0)) __PYX_ERR(0, 103, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_x0_bar = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("solve_for_x0", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 103, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.solve_for_x0", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve_for_x0(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_x0_bar); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve_for_x0(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_x0_bar) { + PyObject *__pyx_v_status = NULL; + PyObject *__pyx_v_u0 = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("solve_for_x0", 1); + + /* "acados_template/acados_ocp_solver_pyx.pyx":107 + * Wrapper around `solve()` which sets initial state constraint, solves the OCP, and returns u0. + * """ + * self.set(0, "lbx", x0_bar) # <<<<<<<<<<<<<< + * self.set(0, "ubx", x0_bar) + * + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_set); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 107, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[4] = {__pyx_t_3, __pyx_int_0, __pyx_n_u_lbx, __pyx_v_x0_bar}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 3+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 107, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":108 + * """ + * self.set(0, "lbx", x0_bar) + * self.set(0, "ubx", x0_bar) # <<<<<<<<<<<<<< + * + * status = self.solve() + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_set); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 108, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[4] = {__pyx_t_3, __pyx_int_0, __pyx_n_u_ubx, __pyx_v_x0_bar}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 3+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 108, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":110 + * self.set(0, "ubx", x0_bar) + * + * status = self.solve() # <<<<<<<<<<<<<< + * + * if status == 2: + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_solve); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 110, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, NULL}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 0+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 110, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_v_status = __pyx_t_1; + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":112 + * status = self.solve() + * + * if status == 2: # <<<<<<<<<<<<<< + * print("Warning: acados_ocp_solver reached maximum iterations.") + * elif status != 0: + */ + __pyx_t_5 = (__Pyx_PyInt_BoolEqObjC(__pyx_v_status, __pyx_int_2, 2, 0)); if (unlikely((__pyx_t_5 < 0))) __PYX_ERR(0, 112, __pyx_L1_error) + if (__pyx_t_5) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":113 + * + * if status == 2: + * print("Warning: acados_ocp_solver reached maximum iterations.") # <<<<<<<<<<<<<< + * elif status != 0: + * raise Exception(f'acados acados_ocp_solver returned status {status}') + */ + __pyx_t_1 = __Pyx_PyObject_Call(__pyx_builtin_print, __pyx_tuple__11, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 113, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":112 + * status = self.solve() + * + * if status == 2: # <<<<<<<<<<<<<< + * print("Warning: acados_ocp_solver reached maximum iterations.") + * elif status != 0: + */ + goto __pyx_L3; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":114 + * if status == 2: + * print("Warning: acados_ocp_solver reached maximum iterations.") + * elif status != 0: # <<<<<<<<<<<<<< + * raise Exception(f'acados acados_ocp_solver returned status {status}') + * + */ + __pyx_t_5 = (__Pyx_PyInt_BoolNeObjC(__pyx_v_status, __pyx_int_0, 0, 0)); if (unlikely((__pyx_t_5 < 0))) __PYX_ERR(0, 114, __pyx_L1_error) + if (unlikely(__pyx_t_5)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":115 + * print("Warning: acados_ocp_solver reached maximum iterations.") + * elif status != 0: + * raise Exception(f'acados acados_ocp_solver returned status {status}') # <<<<<<<<<<<<<< + * + * u0 = self.get(0, "u") + */ + __pyx_t_1 = __Pyx_PyObject_FormatSimple(__pyx_v_status, __pyx_empty_unicode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 115, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyUnicode_Concat(__pyx_kp_u_acados_acados_ocp_solver_returne, __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 115, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 115, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 115, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":114 + * if status == 2: + * print("Warning: acados_ocp_solver reached maximum iterations.") + * elif status != 0: # <<<<<<<<<<<<<< + * raise Exception(f'acados acados_ocp_solver returned status {status}') + * + */ + } + __pyx_L3:; + + /* "acados_template/acados_ocp_solver_pyx.pyx":117 + * raise Exception(f'acados acados_ocp_solver returned status {status}') + * + * u0 = self.get(0, "u") # <<<<<<<<<<<<<< + * return u0 + * + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 117, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_Call(__pyx_t_1, __pyx_tuple__12, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 117, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_u0 = __pyx_t_2; + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":118 + * + * u0 = self.get(0, "u") + * return u0 # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_u0); + __pyx_r = __pyx_v_u0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":103 + * + * + * def solve_for_x0(self, x0_bar): # <<<<<<<<<<<<<< + * """ + * Wrapper around `solve()` which sets initial state constraint, solves the OCP, and returns u0. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.solve_for_x0", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_status); + __Pyx_XDECREF(__pyx_v_u0); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":121 + * + * + * def solve(self): # <<<<<<<<<<<<<< + * """ + * Solve the ocp with current input. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7solve(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6solve, "\n Solve the ocp with current input.\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7solve = {"solve", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7solve, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6solve}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7solve(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("solve (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("solve", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "solve", 0))) return NULL; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6solve(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6solve(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("solve", 1); + + /* "acados_template/acados_ocp_solver_pyx.pyx":125 + * Solve the ocp with current input. + * """ + * return acados_solver.acados_solve(self.capsule) # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_int(long_acados_solve(__pyx_v_self->capsule)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 125, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":121 + * + * + * def solve(self): # <<<<<<<<<<<<<< + * """ + * Solve the ocp with current input. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.solve", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":128 + * + * + * def reset(self, reset_qp_solver_mem=1): # <<<<<<<<<<<<<< + * """ + * Sets current iterate to all zeros. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9reset(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8reset, "\n Sets current iterate to all zeros.\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9reset = {"reset", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9reset, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8reset}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9reset(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_reset_qp_solver_mem = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("reset (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_reset_qp_solver_mem,0}; + values[0] = __Pyx_Arg_NewRef_FASTCALL(((PyObject *)__pyx_int_1)); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_reset_qp_solver_mem); + if (value) { values[0] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 128, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "reset") < 0)) __PYX_ERR(0, 128, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_reset_qp_solver_mem = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("reset", 0, 0, 1, __pyx_nargs); __PYX_ERR(0, 128, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.reset", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8reset(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_reset_qp_solver_mem); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8reset(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_reset_qp_solver_mem) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("reset", 1); + + /* "acados_template/acados_ocp_solver_pyx.pyx":132 + * Sets current iterate to all zeros. + * """ + * return acados_solver.acados_reset(self.capsule, reset_qp_solver_mem) # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_As_int(__pyx_v_reset_qp_solver_mem); if (unlikely((__pyx_t_1 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 132, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyInt_From_int(long_acados_reset(__pyx_v_self->capsule, __pyx_t_1)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 132, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":128 + * + * + * def reset(self, reset_qp_solver_mem=1): # <<<<<<<<<<<<<< + * """ + * Sets current iterate to all zeros. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.reset", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":135 + * + * + * def custom_update(self, data_): # <<<<<<<<<<<<<< + * """ + * A custom function that can be implemented by a user to be called between solver calls. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11custom_update(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10custom_update, "\n A custom function that can be implemented by a user to be called between solver calls.\n By default this does nothing.\n The idea is to have a convenient wrapper to do complex updates of parameters and numerical data efficiently in C,\n in a function that is compiled into the solver library and can be conveniently used in the Python environment.\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11custom_update = {"custom_update", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11custom_update, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10custom_update}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11custom_update(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_data_ = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("custom_update (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_data,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_data)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 135, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "custom_update") < 0)) __PYX_ERR(0, 135, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_data_ = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("custom_update", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 135, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.custom_update", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10custom_update(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_data_); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10custom_update(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_data_) { + Py_ssize_t __pyx_v_data_len; + PyArrayObject *__pyx_v_data = 0; + __Pyx_LocalBuf_ND __pyx_pybuffernd_data; + __Pyx_Buffer __pyx_pybuffer_data; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyArrayObject *__pyx_t_7 = NULL; + char *__pyx_t_8; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("custom_update", 1); + __pyx_pybuffer_data.pybuffer.buf = NULL; + __pyx_pybuffer_data.refcount = 0; + __pyx_pybuffernd_data.data = NULL; + __pyx_pybuffernd_data.rcbuffer = &__pyx_pybuffer_data; + + /* "acados_template/acados_ocp_solver_pyx.pyx":142 + * in a function that is compiled into the solver library and can be conveniently used in the Python environment. + * """ + * data_len = len(data_) # <<<<<<<<<<<<<< + * cdef cnp.ndarray[cnp.float64_t, ndim=1] data = np.ascontiguousarray(data_, dtype=np.float64) + * + */ + __pyx_t_1 = PyObject_Length(__pyx_v_data_); if (unlikely(__pyx_t_1 == ((Py_ssize_t)-1))) __PYX_ERR(0, 142, __pyx_L1_error) + __pyx_v_data_len = __pyx_t_1; + + /* "acados_template/acados_ocp_solver_pyx.pyx":143 + * """ + * data_len = len(data_) + * cdef cnp.ndarray[cnp.float64_t, ndim=1] data = np.ascontiguousarray(data_, dtype=np.float64) # <<<<<<<<<<<<<< + * + * return acados_solver.acados_custom_update(self.capsule, data.data, data_len) + */ + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_np); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = PyTuple_New(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_INCREF(__pyx_v_data_); + __Pyx_GIVEREF(__pyx_v_data_); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_v_data_)) __PYX_ERR(0, 143, __pyx_L1_error); + __pyx_t_4 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GetModuleGlobalName(__pyx_t_5, __pyx_n_s_np); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_float64); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (PyDict_SetItem(__pyx_t_4, __pyx_n_s_dtype, __pyx_t_6) < 0) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __pyx_t_6 = __Pyx_PyObject_Call(__pyx_t_3, __pyx_t_2, __pyx_t_4); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 143, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (!(likely(((__pyx_t_6) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_6, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 143, __pyx_L1_error) + __pyx_t_7 = ((PyArrayObject *)__pyx_t_6); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_data.rcbuffer->pybuffer, (PyObject*)__pyx_t_7, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 1, 0, __pyx_stack) == -1)) { + __pyx_v_data = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_data.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 143, __pyx_L1_error) + } else {__pyx_pybuffernd_data.diminfo[0].strides = __pyx_pybuffernd_data.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_data.diminfo[0].shape = __pyx_pybuffernd_data.rcbuffer->pybuffer.shape[0]; + } + } + __pyx_t_7 = 0; + __pyx_v_data = ((PyArrayObject *)__pyx_t_6); + __pyx_t_6 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":145 + * cdef cnp.ndarray[cnp.float64_t, ndim=1] data = np.ascontiguousarray(data_, dtype=np.float64) + * + * return acados_solver.acados_custom_update(self.capsule, data.data, data_len) # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_8 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_data)); if (unlikely(__pyx_t_8 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 145, __pyx_L1_error) + __pyx_t_6 = __Pyx_PyInt_From_int(long_acados_custom_update(__pyx_v_self->capsule, ((double *)__pyx_t_8), __pyx_v_data_len)); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 145, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_r = __pyx_t_6; + __pyx_t_6 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":135 + * + * + * def custom_update(self, data_): # <<<<<<<<<<<<<< + * """ + * A custom function that can be implemented by a user to be called between solver calls. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_data.rcbuffer->pybuffer); + __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.custom_update", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + goto __pyx_L2; + __pyx_L0:; + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_data.rcbuffer->pybuffer); + __pyx_L2:; + __Pyx_XDECREF((PyObject *)__pyx_v_data); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":148 + * + * + * def set_new_time_steps(self, new_time_steps): # <<<<<<<<<<<<<< + * """ + * Set new time steps. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13set_new_time_steps(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12set_new_time_steps, "\n Set new time steps.\n Recreates the solver if N changes.\n\n :param new_time_steps: 1 dimensional np array of new time steps for the solver\n\n .. note:: This allows for different use-cases: either set a new size of time-steps or a new distribution of\n the shooting nodes without changing the number, e.g., to reach a different final time. Both cases\n do not require a new code export and compilation.\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13set_new_time_steps = {"set_new_time_steps", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13set_new_time_steps, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12set_new_time_steps}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13set_new_time_steps(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v_new_time_steps = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("set_new_time_steps (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_new_time_steps,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_new_time_steps)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 148, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "set_new_time_steps") < 0)) __PYX_ERR(0, 148, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_new_time_steps = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("set_new_time_steps", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 148, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.set_new_time_steps", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12set_new_time_steps(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_new_time_steps); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12set_new_time_steps(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_new_time_steps) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("set_new_time_steps", 1); + + /* "acados_template/acados_ocp_solver_pyx.pyx":160 + * """ + * + * raise NotImplementedError("AcadosOcpSolverCython: does not support set_new_time_steps() since it is only a prototyping feature") # <<<<<<<<<<<<<< + * # # unlikely but still possible + * # if not self.solver_created: + */ + __pyx_t_1 = __Pyx_PyObject_Call(__pyx_builtin_NotImplementedError, __pyx_tuple__13, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 160, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 160, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":148 + * + * + * def set_new_time_steps(self, new_time_steps): # <<<<<<<<<<<<<< + * """ + * Set new time steps. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.set_new_time_steps", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":199 + * + * + * def update_qp_solver_cond_N(self, qp_solver_cond_N: int): # <<<<<<<<<<<<<< + * """ + * Recreate solver with new value `qp_solver_cond_N` with a partial condensing QP solver. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15update_qp_solver_cond_N(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14update_qp_solver_cond_N, "\n Recreate solver with new value `qp_solver_cond_N` with a partial condensing QP solver.\n This function is relevant for code reuse, i.e., if either `set_new_time_steps(...)` is used or\n the influence of a different `qp_solver_cond_N` is studied without code export and compilation.\n :param qp_solver_cond_N: new number of condensing stages for the solver\n\n .. note:: This function can only be used in combination with a partial condensing QP solver.\n\n .. note:: After `set_new_time_steps(...)` is used and depending on the new number of time steps it might be\n necessary to change `qp_solver_cond_N` as well (using this function), i.e., typically\n `qp_solver_cond_N < N`.\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15update_qp_solver_cond_N = {"update_qp_solver_cond_N", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15update_qp_solver_cond_N, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14update_qp_solver_cond_N}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15update_qp_solver_cond_N(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v_qp_solver_cond_N = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("update_qp_solver_cond_N (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_qp_solver_cond_N,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_qp_solver_cond_N)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 199, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "update_qp_solver_cond_N") < 0)) __PYX_ERR(0, 199, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_qp_solver_cond_N = ((PyObject*)values[0]); + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("update_qp_solver_cond_N", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 199, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.update_qp_solver_cond_N", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_qp_solver_cond_N), (&PyInt_Type), 0, "qp_solver_cond_N", 1))) __PYX_ERR(0, 199, __pyx_L1_error) + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14update_qp_solver_cond_N(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_qp_solver_cond_N); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = NULL; + __pyx_L0:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14update_qp_solver_cond_N(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v_qp_solver_cond_N) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("update_qp_solver_cond_N", 1); + + /* "acados_template/acados_ocp_solver_pyx.pyx":212 + * `qp_solver_cond_N < N`. + * """ + * raise NotImplementedError("AcadosOcpSolverCython: does not support update_qp_solver_cond_N() since it is only a prototyping feature") # <<<<<<<<<<<<<< + * + * # # unlikely but still possible + */ + __pyx_t_1 = __Pyx_PyObject_Call(__pyx_builtin_NotImplementedError, __pyx_tuple__14, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 212, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 212, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":199 + * + * + * def update_qp_solver_cond_N(self, qp_solver_cond_N: int): # <<<<<<<<<<<<<< + * """ + * Recreate solver with new value `qp_solver_cond_N` with a partial condensing QP solver. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.update_qp_solver_cond_N", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":233 + * + * + * def eval_param_sens(self, index, stage=0, field="ex"): # <<<<<<<<<<<<<< + * """ + * Calculate the sensitivity of the curent solution with respect to the initial state component of index + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17eval_param_sens(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16eval_param_sens, "\n Calculate the sensitivity of the curent solution with respect to the initial state component of index\n\n :param index: integer corresponding to initial state index in range(nx)\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17eval_param_sens = {"eval_param_sens", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17eval_param_sens, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16eval_param_sens}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17eval_param_sens(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_index = 0; + PyObject *__pyx_v_stage = 0; + PyObject *__pyx_v_field = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("eval_param_sens (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_index,&__pyx_n_s_stage,&__pyx_n_s_field,0}; + values[1] = __Pyx_Arg_NewRef_FASTCALL(((PyObject *)__pyx_int_0)); + values[2] = __Pyx_Arg_NewRef_FASTCALL(((PyObject *)__pyx_n_u_ex)); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_index)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 233, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stage); + if (value) { values[1] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 233, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field); + if (value) { values[2] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 233, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "eval_param_sens") < 0)) __PYX_ERR(0, 233, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_index = values[0]; + __pyx_v_stage = values[1]; + __pyx_v_field = values[2]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("eval_param_sens", 0, 1, 3, __pyx_nargs); __PYX_ERR(0, 233, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.eval_param_sens", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16eval_param_sens(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_index, __pyx_v_stage, __pyx_v_field); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16eval_param_sens(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_stage, PyObject *__pyx_v_field) { + PyObject *__pyx_v_field_ = NULL; + int __pyx_v_nx; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_t_5; + int __pyx_t_6; + char const *__pyx_t_7; + Py_ssize_t __pyx_t_8; + Py_UCS4 __pyx_t_9; + char *__pyx_t_10; + int __pyx_t_11; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("eval_param_sens", 0); + __Pyx_INCREF(__pyx_v_field); + + /* "acados_template/acados_ocp_solver_pyx.pyx":240 + * """ + * + * field_ = field # <<<<<<<<<<<<<< + * field = field_.encode('utf-8') + * + */ + __Pyx_INCREF(__pyx_v_field); + __pyx_v_field_ = __pyx_v_field; + + /* "acados_template/acados_ocp_solver_pyx.pyx":241 + * + * field_ = field + * field = field_.encode('utf-8') # <<<<<<<<<<<<<< + * + * # checks + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_field_, __pyx_n_s_encode); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 241, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_kp_u_utf_8}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 241, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __Pyx_DECREF_SET(__pyx_v_field, __pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":244 + * + * # checks + * if not isinstance(index, int): # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.eval_param_sens(): index must be Integer.') + * + */ + __pyx_t_5 = PyInt_Check(__pyx_v_index); + __pyx_t_6 = (!__pyx_t_5); + if (unlikely(__pyx_t_6)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":245 + * # checks + * if not isinstance(index, int): + * raise Exception('AcadosOcpSolverCython.eval_param_sens(): index must be Integer.') # <<<<<<<<<<<<<< + * + * cdef int nx = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, self.nlp_dims, self.nlp_out, 0, "x".encode('utf-8')) + */ + __pyx_t_1 = __Pyx_PyObject_Call(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_tuple__15, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 245, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 245, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":244 + * + * # checks + * if not isinstance(index, int): # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.eval_param_sens(): index must be Integer.') + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":247 + * raise Exception('AcadosOcpSolverCython.eval_param_sens(): index must be Integer.') + * + * cdef int nx = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, self.nlp_dims, self.nlp_out, 0, "x".encode('utf-8')) # <<<<<<<<<<<<<< + * + * if index < 0 or index > nx: + */ + __pyx_t_7 = __Pyx_PyBytes_AsString(__pyx_n_b_x); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 247, __pyx_L1_error) + __pyx_v_nx = ocp_nlp_dims_get_from_attr(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, 0, __pyx_t_7); + + /* "acados_template/acados_ocp_solver_pyx.pyx":249 + * cdef int nx = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, self.nlp_dims, self.nlp_out, 0, "x".encode('utf-8')) + * + * if index < 0 or index > nx: # <<<<<<<<<<<<<< + * raise Exception(f'AcadosOcpSolverCython.eval_param_sens(): index must be in [0, nx-1], got: {index}.') + * + */ + __pyx_t_1 = PyObject_RichCompare(__pyx_v_index, __pyx_int_0, Py_LT); __Pyx_XGOTREF(__pyx_t_1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 249, __pyx_L1_error) + __pyx_t_5 = __Pyx_PyObject_IsTrue(__pyx_t_1); if (unlikely((__pyx_t_5 < 0))) __PYX_ERR(0, 249, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (!__pyx_t_5) { + } else { + __pyx_t_6 = __pyx_t_5; + goto __pyx_L5_bool_binop_done; + } + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_nx); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = PyObject_RichCompare(__pyx_v_index, __pyx_t_1, Py_GT); __Pyx_XGOTREF(__pyx_t_2); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 249, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_5 = __Pyx_PyObject_IsTrue(__pyx_t_2); if (unlikely((__pyx_t_5 < 0))) __PYX_ERR(0, 249, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_6 = __pyx_t_5; + __pyx_L5_bool_binop_done:; + if (unlikely(__pyx_t_6)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":250 + * + * if index < 0 or index > nx: + * raise Exception(f'AcadosOcpSolverCython.eval_param_sens(): index must be in [0, nx-1], got: {index}.') # <<<<<<<<<<<<<< + * + * # actual eval_param + */ + __pyx_t_2 = PyTuple_New(3); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 250, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_8 = 0; + __pyx_t_9 = 127; + __Pyx_INCREF(__pyx_kp_u_AcadosOcpSolverCython_eval_param_2); + __pyx_t_8 += 74; + __Pyx_GIVEREF(__pyx_kp_u_AcadosOcpSolverCython_eval_param_2); + PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_kp_u_AcadosOcpSolverCython_eval_param_2); + __pyx_t_1 = __Pyx_PyObject_FormatSimple(__pyx_v_index, __pyx_empty_unicode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 250, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_9 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) > __pyx_t_9) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) : __pyx_t_9; + __pyx_t_8 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_2, 1, __pyx_t_1); + __pyx_t_1 = 0; + __Pyx_INCREF(__pyx_kp_u__2); + __pyx_t_8 += 1; + __Pyx_GIVEREF(__pyx_kp_u__2); + PyTuple_SET_ITEM(__pyx_t_2, 2, __pyx_kp_u__2); + __pyx_t_1 = __Pyx_PyUnicode_Join(__pyx_t_2, 3, __pyx_t_8, __pyx_t_9); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 250, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 250, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 250, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":249 + * cdef int nx = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, self.nlp_dims, self.nlp_out, 0, "x".encode('utf-8')) + * + * if index < 0 or index > nx: # <<<<<<<<<<<<<< + * raise Exception(f'AcadosOcpSolverCython.eval_param_sens(): index must be in [0, nx-1], got: {index}.') + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":253 + * + * # actual eval_param + * acados_solver_common.ocp_nlp_eval_param_sens(self.nlp_solver, field, stage, index, self.sens_out) # <<<<<<<<<<<<<< + * + * return + */ + __pyx_t_10 = __Pyx_PyObject_AsWritableString(__pyx_v_field); if (unlikely((!__pyx_t_10) && PyErr_Occurred())) __PYX_ERR(0, 253, __pyx_L1_error) + __pyx_t_4 = __Pyx_PyInt_As_int(__pyx_v_stage); if (unlikely((__pyx_t_4 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 253, __pyx_L1_error) + __pyx_t_11 = __Pyx_PyInt_As_int(__pyx_v_index); if (unlikely((__pyx_t_11 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 253, __pyx_L1_error) + ocp_nlp_eval_param_sens(__pyx_v_self->nlp_solver, __pyx_t_10, __pyx_t_4, __pyx_t_11, __pyx_v_self->sens_out); + + /* "acados_template/acados_ocp_solver_pyx.pyx":255 + * acados_solver_common.ocp_nlp_eval_param_sens(self.nlp_solver, field, stage, index, self.sens_out) + * + * return # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":233 + * + * + * def eval_param_sens(self, index, stage=0, field="ex"): # <<<<<<<<<<<<<< + * """ + * Calculate the sensitivity of the curent solution with respect to the initial state component of index + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.eval_param_sens", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_field_); + __Pyx_XDECREF(__pyx_v_field); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":258 + * + * + * def get(self, int stage, str field_): # <<<<<<<<<<<<<< + * """ + * Get the last solution of the solver: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19get(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18get, "\n Get the last solution of the solver:\n\n :param stage: integer corresponding to shooting node\n :param field: string in ['x', 'u', 'z', 'pi', 'lam', 't', 'sl', 'su',]\n\n .. note:: regarding lam, t: \n\n the inequalities are internally organized in the following order: \n\n [ lbu lbx lg lh lphi ubu ubx ug uh uphi; \n\n lsbu lsbx lsg lsh lsphi usbu usbx usg ush usphi]\n\n .. note:: pi: multipliers for dynamics equality constraints \n\n lam: multipliers for inequalities \n\n t: slack variables corresponding to evaluation of all inequalities (at the solution) \n\n sl: slack variables of soft lower inequality constraints \n\n su: slack variables of soft upper inequality constraints \n\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19get = {"get", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19get, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18get}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19get(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + int __pyx_v_stage; + PyObject *__pyx_v_field_ = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[2] = {0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("get (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_stage,&__pyx_n_s_field_2,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stage)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 258, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field_2)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 258, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("get", 1, 2, 2, 1); __PYX_ERR(0, 258, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "get") < 0)) __PYX_ERR(0, 258, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 2)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + } + __pyx_v_stage = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_stage == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 258, __pyx_L3_error) + __pyx_v_field_ = ((PyObject*)values[1]); + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("get", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 258, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.get", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 258, __pyx_L1_error) + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18get(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_stage, __pyx_v_field_); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = NULL; + __pyx_L0:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18get(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_) { + PyObject *__pyx_v_out_fields = NULL; + PyObject *__pyx_v_field = NULL; + int __pyx_v_dims; + PyArrayObject *__pyx_v_out = 0; + __Pyx_LocalBuf_ND __pyx_pybuffernd_out; + __Pyx_Buffer __pyx_pybuffer_out; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_t_5; + int __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + char const *__pyx_t_8; + PyArrayObject *__pyx_t_9 = NULL; + char const *__pyx_t_10; + char *__pyx_t_11; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get", 1); + __pyx_pybuffer_out.pybuffer.buf = NULL; + __pyx_pybuffer_out.refcount = 0; + __pyx_pybuffernd_out.data = NULL; + __pyx_pybuffernd_out.rcbuffer = &__pyx_pybuffer_out; + + /* "acados_template/acados_ocp_solver_pyx.pyx":277 + * """ + * + * out_fields = ['x', 'u', 'z', 'pi', 'lam', 't', 'sl', 'su'] # <<<<<<<<<<<<<< + * field = field_.encode('utf-8') + * + */ + __pyx_t_1 = PyList_New(8); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 277, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_u_x); + __Pyx_GIVEREF(__pyx_n_u_x); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_u_x)) __PYX_ERR(0, 277, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_u); + __Pyx_GIVEREF(__pyx_n_u_u); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 1, __pyx_n_u_u)) __PYX_ERR(0, 277, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_z); + __Pyx_GIVEREF(__pyx_n_u_z); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 2, __pyx_n_u_z)) __PYX_ERR(0, 277, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_pi); + __Pyx_GIVEREF(__pyx_n_u_pi); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 3, __pyx_n_u_pi)) __PYX_ERR(0, 277, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_lam); + __Pyx_GIVEREF(__pyx_n_u_lam); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 4, __pyx_n_u_lam)) __PYX_ERR(0, 277, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_t); + __Pyx_GIVEREF(__pyx_n_u_t); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 5, __pyx_n_u_t)) __PYX_ERR(0, 277, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_sl); + __Pyx_GIVEREF(__pyx_n_u_sl); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 6, __pyx_n_u_sl)) __PYX_ERR(0, 277, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_su); + __Pyx_GIVEREF(__pyx_n_u_su); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 7, __pyx_n_u_su)) __PYX_ERR(0, 277, __pyx_L1_error); + __pyx_v_out_fields = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":278 + * + * out_fields = ['x', 'u', 'z', 'pi', 'lam', 't', 'sl', 'su'] + * field = field_.encode('utf-8') # <<<<<<<<<<<<<< + * + * if field_ not in out_fields: + */ + if (unlikely(__pyx_v_field_ == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); + __PYX_ERR(0, 278, __pyx_L1_error) + } + __pyx_t_1 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 278, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_field = __pyx_t_1; + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":280 + * field = field_.encode('utf-8') + * + * if field_ not in out_fields: # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.get(): {} is an invalid argument.\ + * \n Possible values are {}.'.format(field_, out_fields)) + */ + __pyx_t_2 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_out_fields, Py_NE)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 280, __pyx_L1_error) + if (unlikely(__pyx_t_2)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":282 + * if field_ not in out_fields: + * raise Exception('AcadosOcpSolverCython.get(): {} is an invalid argument.\ + * \n Possible values are {}.'.format(field_, out_fields)) # <<<<<<<<<<<<<< + * + * if stage < 0 or stage > self.N: + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_get_is_an, __pyx_n_s_format); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 282, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = NULL; + __pyx_t_5 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_5 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_4, __pyx_v_field_, __pyx_v_out_fields}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_5, 2+__pyx_t_5); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 282, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":281 + * + * if field_ not in out_fields: + * raise Exception('AcadosOcpSolverCython.get(): {} is an invalid argument.\ # <<<<<<<<<<<<<< + * \n Possible values are {}.'.format(field_, out_fields)) + * + */ + __pyx_t_3 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 281, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_t_3, 0, 0, 0); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __PYX_ERR(0, 281, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":280 + * field = field_.encode('utf-8') + * + * if field_ not in out_fields: # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.get(): {} is an invalid argument.\ + * \n Possible values are {}.'.format(field_, out_fields)) + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":284 + * \n Possible values are {}.'.format(field_, out_fields)) + * + * if stage < 0 or stage > self.N: # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.get(): stage index must be in [0, N], got: {}.'.format(self.N)) + * + */ + __pyx_t_6 = (__pyx_v_stage < 0); + if (!__pyx_t_6) { + } else { + __pyx_t_2 = __pyx_t_6; + goto __pyx_L5_bool_binop_done; + } + __pyx_t_6 = (__pyx_v_stage > __pyx_v_self->N); + __pyx_t_2 = __pyx_t_6; + __pyx_L5_bool_binop_done:; + if (unlikely(__pyx_t_2)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":285 + * + * if stage < 0 or stage > self.N: + * raise Exception('AcadosOcpSolverCython.get(): stage index must be in [0, N], got: {}.'.format(self.N)) # <<<<<<<<<<<<<< + * + * if stage == self.N and field_ == 'pi': + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_get_stage, __pyx_n_s_format); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 285, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_4 = __Pyx_PyInt_From_int(__pyx_v_self->N); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 285, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_7 = NULL; + __pyx_t_5 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_5 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_7, __pyx_t_4}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_5, 1+__pyx_t_5); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 285, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 285, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 285, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":284 + * \n Possible values are {}.'.format(field_, out_fields)) + * + * if stage < 0 or stage > self.N: # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.get(): stage index must be in [0, N], got: {}.'.format(self.N)) + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":287 + * raise Exception('AcadosOcpSolverCython.get(): stage index must be in [0, N], got: {}.'.format(self.N)) + * + * if stage == self.N and field_ == 'pi': # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.get(): field {} does not exist at final stage {}.'\ + * .format(field_, stage)) + */ + __pyx_t_6 = (__pyx_v_stage == __pyx_v_self->N); + if (__pyx_t_6) { + } else { + __pyx_t_2 = __pyx_t_6; + goto __pyx_L8_bool_binop_done; + } + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_pi, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 287, __pyx_L1_error) + __pyx_t_2 = __pyx_t_6; + __pyx_L8_bool_binop_done:; + if (unlikely(__pyx_t_2)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":289 + * if stage == self.N and field_ == 'pi': + * raise Exception('AcadosOcpSolverCython.get(): field {} does not exist at final stage {}.'\ + * .format(field_, stage)) # <<<<<<<<<<<<<< + * + * cdef int dims = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_get_field, __pyx_n_s_format); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 289, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = __Pyx_PyInt_From_int(__pyx_v_stage); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 289, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_7 = NULL; + __pyx_t_5 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_5 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_7, __pyx_v_field_, __pyx_t_4}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_5, 2+__pyx_t_5); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 289, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":288 + * + * if stage == self.N and field_ == 'pi': + * raise Exception('AcadosOcpSolverCython.get(): field {} does not exist at final stage {}.'\ # <<<<<<<<<<<<<< + * .format(field_, stage)) + * + */ + __pyx_t_3 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 288, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_t_3, 0, 0, 0); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __PYX_ERR(0, 288, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":287 + * raise Exception('AcadosOcpSolverCython.get(): stage index must be in [0, N], got: {}.'.format(self.N)) + * + * if stage == self.N and field_ == 'pi': # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.get(): field {} does not exist at final stage {}.'\ + * .format(field_, stage)) + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":292 + * + * cdef int dims = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, + * self.nlp_dims, self.nlp_out, stage, field) # <<<<<<<<<<<<<< + * + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((dims,)) + */ + __pyx_t_8 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_8) && PyErr_Occurred())) __PYX_ERR(0, 292, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":291 + * .format(field_, stage)) + * + * cdef int dims = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, # <<<<<<<<<<<<<< + * self.nlp_dims, self.nlp_out, stage, field) + * + */ + __pyx_v_dims = ocp_nlp_dims_get_from_attr(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_8); + + /* "acados_template/acados_ocp_solver_pyx.pyx":294 + * self.nlp_dims, self.nlp_out, stage, field) + * + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((dims,)) # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_out_get(self.nlp_config, \ + * self.nlp_dims, self.nlp_out, stage, field, out.data) + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 294, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_zeros); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 294, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_dims); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 294, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = PyTuple_New(1); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 294, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_7, 0, __pyx_t_1)) __PYX_ERR(0, 294, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_1 = NULL; + __pyx_t_5 = 0; + #if CYTHON_UNPACK_METHODS + if (unlikely(PyMethod_Check(__pyx_t_4))) { + __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_4); + if (likely(__pyx_t_1)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_4); + __Pyx_INCREF(__pyx_t_1); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_4, function); + __pyx_t_5 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_1, __pyx_t_7}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_5, 1+__pyx_t_5); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 294, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + if (!(likely(((__pyx_t_3) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_3, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 294, __pyx_L1_error) + __pyx_t_9 = ((PyArrayObject *)__pyx_t_3); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_out.rcbuffer->pybuffer, (PyObject*)__pyx_t_9, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 1, 0, __pyx_stack) == -1)) { + __pyx_v_out = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_out.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 294, __pyx_L1_error) + } else {__pyx_pybuffernd_out.diminfo[0].strides = __pyx_pybuffernd_out.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_out.diminfo[0].shape = __pyx_pybuffernd_out.rcbuffer->pybuffer.shape[0]; + } + } + __pyx_t_9 = 0; + __pyx_v_out = ((PyArrayObject *)__pyx_t_3); + __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":296 + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((dims,)) + * acados_solver_common.ocp_nlp_out_get(self.nlp_config, \ + * self.nlp_dims, self.nlp_out, stage, field, out.data) # <<<<<<<<<<<<<< + * + * return out + */ + __pyx_t_10 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_10) && PyErr_Occurred())) __PYX_ERR(0, 296, __pyx_L1_error) + __pyx_t_11 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_out)); if (unlikely(__pyx_t_11 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 296, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":295 + * + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((dims,)) + * acados_solver_common.ocp_nlp_out_get(self.nlp_config, \ # <<<<<<<<<<<<<< + * self.nlp_dims, self.nlp_out, stage, field, out.data) + * + */ + ocp_nlp_out_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_10, ((void *)__pyx_t_11)); + + /* "acados_template/acados_ocp_solver_pyx.pyx":298 + * self.nlp_dims, self.nlp_out, stage, field, out.data) + * + * return out # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_out); + __pyx_r = ((PyObject *)__pyx_v_out); + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":258 + * + * + * def get(self, int stage, str field_): # <<<<<<<<<<<<<< + * """ + * Get the last solution of the solver: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_7); + { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_out.rcbuffer->pybuffer); + __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.get", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + goto __pyx_L2; + __pyx_L0:; + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_out.rcbuffer->pybuffer); + __pyx_L2:; + __Pyx_XDECREF(__pyx_v_out_fields); + __Pyx_XDECREF(__pyx_v_field); + __Pyx_XDECREF((PyObject *)__pyx_v_out); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":301 + * + * + * def print_statistics(self): # <<<<<<<<<<<<<< + * """ + * prints statistics of previous solver run as a table: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21print_statistics(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20print_statistics, "\n prints statistics of previous solver run as a table:\n - iter: iteration number\n - res_stat: stationarity residual\n - res_eq: residual wrt equality constraints (dynamics)\n - res_ineq: residual wrt inequality constraints (constraints)\n - res_comp: residual wrt complementarity conditions\n - qp_stat: status of QP solver\n - qp_iter: number of QP iterations\n - qp_res_stat: stationarity residual of the last QP solution\n - qp_res_eq: residual wrt equality constraints (dynamics) of the last QP solution\n - qp_res_ineq: residual wrt inequality constraints (constraints) of the last QP solution\n - qp_res_comp: residual wrt complementarity conditions of the last QP solution\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21print_statistics = {"print_statistics", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21print_statistics, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20print_statistics}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21print_statistics(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("print_statistics (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("print_statistics", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "print_statistics", 0))) return NULL; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20print_statistics(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20print_statistics(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("print_statistics", 1); + + /* "acados_template/acados_ocp_solver_pyx.pyx":316 + * - qp_res_comp: residual wrt complementarity conditions of the last QP solution + * """ + * acados_solver.acados_print_stats(self.capsule) # <<<<<<<<<<<<<< + * + * + */ + long_acados_print_stats(__pyx_v_self->capsule); + + /* "acados_template/acados_ocp_solver_pyx.pyx":301 + * + * + * def print_statistics(self): # <<<<<<<<<<<<<< + * """ + * prints statistics of previous solver run as a table: + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":319 + * + * + * def store_iterate(self, filename='', overwrite=False): # <<<<<<<<<<<<<< + * """ + * Stores the current iterate of the ocp solver in a json file. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23store_iterate(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22store_iterate, "\n Stores the current iterate of the ocp solver in a json file.\n\n :param filename: if not set, use model_name + timestamp + '.json'\n :param overwrite: if false and filename exists add timestamp to filename\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23store_iterate = {"store_iterate", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23store_iterate, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22store_iterate}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23store_iterate(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_filename = 0; + PyObject *__pyx_v_overwrite = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[2] = {0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("store_iterate (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_filename,&__pyx_n_s_overwrite,0}; + values[0] = __Pyx_Arg_NewRef_FASTCALL(((PyObject *)__pyx_kp_u__16)); + values[1] = __Pyx_Arg_NewRef_FASTCALL(((PyObject *)Py_False)); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_filename); + if (value) { values[0] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 319, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 1: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_overwrite); + if (value) { values[1] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 319, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "store_iterate") < 0)) __PYX_ERR(0, 319, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_filename = values[0]; + __pyx_v_overwrite = values[1]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("store_iterate", 0, 0, 2, __pyx_nargs); __PYX_ERR(0, 319, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.store_iterate", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22store_iterate(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_filename, __pyx_v_overwrite); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":358 + * # save + * with open(filename, 'w') as f: + * json.dump(solution, f, default=lambda x: x.tolist(), indent=4, sort_keys=True) # <<<<<<<<<<<<<< + * print("stored current iterate in ", os.path.join(os.getcwd(), filename)) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13store_iterate_lambda(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13store_iterate_lambda = {"lambda", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13store_iterate_lambda, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13store_iterate_lambda(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_x = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("lambda (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_x,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_x)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 358, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "lambda") < 0)) __PYX_ERR(0, 358, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_x = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("lambda", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 358, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.store_iterate.lambda", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_lambda_funcdef_lambda(__pyx_self, __pyx_v_x); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_lambda_funcdef_lambda(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_x) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("lambda", 1); + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_x, __pyx_n_s_tolist); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 358, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, NULL}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 0+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 358, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.store_iterate.lambda", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":319 + * + * + * def store_iterate(self, filename='', overwrite=False): # <<<<<<<<<<<<<< + * """ + * Stores the current iterate of the ocp solver in a json file. + */ + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22store_iterate(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_filename, PyObject *__pyx_v_overwrite) { + PyObject *__pyx_v_json = NULL; + PyObject *__pyx_v_solution = NULL; + Py_ssize_t __pyx_v_lN; + long __pyx_v_i; + PyObject *__pyx_v_i_string = NULL; + PyObject *__pyx_v_k = NULL; + PyObject *__pyx_v_f = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + Py_ssize_t __pyx_t_8; + long __pyx_t_9; + long __pyx_t_10; + long __pyx_t_11; + Py_UCS4 __pyx_t_12; + Py_ssize_t __pyx_t_13; + PyObject *__pyx_t_14 = NULL; + PyObject *__pyx_t_15 = NULL; + PyObject *__pyx_t_16 = NULL; + PyObject *__pyx_t_17 = NULL; + PyObject *__pyx_t_18 = NULL; + PyObject *__pyx_t_19 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("store_iterate", 0); + __Pyx_INCREF(__pyx_v_filename); + + /* "acados_template/acados_ocp_solver_pyx.pyx":326 + * :param overwrite: if false and filename exists add timestamp to filename + * """ + * import json # <<<<<<<<<<<<<< + * if filename == '': + * filename += self.model_name + '_' + 'iterate' + '.json' + */ + __pyx_t_1 = __Pyx_ImportDottedModule(__pyx_n_s_json, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 326, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_json = __pyx_t_1; + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":327 + * """ + * import json + * if filename == '': # <<<<<<<<<<<<<< + * filename += self.model_name + '_' + 'iterate' + '.json' + * + */ + __pyx_t_2 = (__Pyx_PyUnicode_Equals(__pyx_v_filename, __pyx_kp_u__16, Py_EQ)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 327, __pyx_L1_error) + if (__pyx_t_2) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":328 + * import json + * if filename == '': + * filename += self.model_name + '_' + 'iterate' + '.json' # <<<<<<<<<<<<<< + * + * if not overwrite: + */ + __pyx_t_1 = __Pyx_PyUnicode_ConcatSafe(__pyx_v_self->model_name, __pyx_n_u__17); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 328, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyUnicode_ConcatInPlace(__pyx_t_1, __pyx_n_u_iterate); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 328, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyUnicode_ConcatInPlace(__pyx_t_3, __pyx_kp_u_json_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 328, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = PyNumber_InPlaceAdd(__pyx_v_filename, __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 328, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF_SET(__pyx_v_filename, __pyx_t_3); + __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":327 + * """ + * import json + * if filename == '': # <<<<<<<<<<<<<< + * filename += self.model_name + '_' + 'iterate' + '.json' + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":330 + * filename += self.model_name + '_' + 'iterate' + '.json' + * + * if not overwrite: # <<<<<<<<<<<<<< + * # append timestamp + * if os.path.isfile(filename): + */ + __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_v_overwrite); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 330, __pyx_L1_error) + __pyx_t_4 = (!__pyx_t_2); + if (__pyx_t_4) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":332 + * if not overwrite: + * # append timestamp + * if os.path.isfile(filename): # <<<<<<<<<<<<<< + * filename = filename[:-5] + * filename += datetime.utcnow().strftime('%Y-%m-%d-%H:%M:%S.%f') + '.json' + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_os); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 332, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_path); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 332, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_isfile); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 332, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_5, __pyx_v_filename}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 1+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 332, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_t_3); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 332, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + if (__pyx_t_4) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":333 + * # append timestamp + * if os.path.isfile(filename): + * filename = filename[:-5] # <<<<<<<<<<<<<< + * filename += datetime.utcnow().strftime('%Y-%m-%d-%H:%M:%S.%f') + '.json' + * + */ + __pyx_t_3 = __Pyx_PyObject_GetSlice(__pyx_v_filename, 0, -5L, NULL, NULL, &__pyx_slice__18, 0, 1, 1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 333, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF_SET(__pyx_v_filename, __pyx_t_3); + __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":334 + * if os.path.isfile(filename): + * filename = filename[:-5] + * filename += datetime.utcnow().strftime('%Y-%m-%d-%H:%M:%S.%f') + '.json' # <<<<<<<<<<<<<< + * + * # get iterate: + */ + __Pyx_GetModuleGlobalName(__pyx_t_5, __pyx_n_s_datetime); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 334, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_utcnow); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 334, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (unlikely(PyMethod_Check(__pyx_t_7))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_7); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_7); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_7, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_5, NULL}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_7, __pyx_callargs+1-__pyx_t_6, 0+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 334, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + } + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_strftime); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 334, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_7))) { + __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_7); + if (likely(__pyx_t_1)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_7); + __Pyx_INCREF(__pyx_t_1); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_7, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_1, __pyx_kp_u_Y_m_d_H_M_S_f}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_7, __pyx_callargs+1-__pyx_t_6, 1+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 334, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + } + __pyx_t_7 = PyNumber_Add(__pyx_t_3, __pyx_kp_u_json_2); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 334, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = PyNumber_InPlaceAdd(__pyx_v_filename, __pyx_t_7); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 334, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF_SET(__pyx_v_filename, __pyx_t_3); + __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":332 + * if not overwrite: + * # append timestamp + * if os.path.isfile(filename): # <<<<<<<<<<<<<< + * filename = filename[:-5] + * filename += datetime.utcnow().strftime('%Y-%m-%d-%H:%M:%S.%f') + '.json' + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":330 + * filename += self.model_name + '_' + 'iterate' + '.json' + * + * if not overwrite: # <<<<<<<<<<<<<< + * # append timestamp + * if os.path.isfile(filename): + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":337 + * + * # get iterate: + * solution = dict() # <<<<<<<<<<<<<< + * + * lN = len(str(self.N+1)) + */ + __pyx_t_3 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 337, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_v_solution = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":339 + * solution = dict() + * + * lN = len(str(self.N+1)) # <<<<<<<<<<<<<< + * for i in range(self.N+1): + * i_string = f'{i:0{lN}d}' + */ + __pyx_t_3 = __Pyx_PyInt_From_long((__pyx_v_self->N + 1)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 339, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_7 = __Pyx_PyObject_Str(__pyx_t_3); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 339, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_8 = PyObject_Length(__pyx_t_7); if (unlikely(__pyx_t_8 == ((Py_ssize_t)-1))) __PYX_ERR(0, 339, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __pyx_v_lN = __pyx_t_8; + + /* "acados_template/acados_ocp_solver_pyx.pyx":340 + * + * lN = len(str(self.N+1)) + * for i in range(self.N+1): # <<<<<<<<<<<<<< + * i_string = f'{i:0{lN}d}' + * solution['x_'+i_string] = self.get(i,'x') + */ + __pyx_t_9 = (__pyx_v_self->N + 1); + __pyx_t_10 = __pyx_t_9; + for (__pyx_t_11 = 0; __pyx_t_11 < __pyx_t_10; __pyx_t_11+=1) { + __pyx_v_i = __pyx_t_11; + + /* "acados_template/acados_ocp_solver_pyx.pyx":341 + * lN = len(str(self.N+1)) + * for i in range(self.N+1): + * i_string = f'{i:0{lN}d}' # <<<<<<<<<<<<<< + * solution['x_'+i_string] = self.get(i,'x') + * solution['u_'+i_string] = self.get(i,'u') + */ + __pyx_t_7 = __Pyx_PyInt_From_long(__pyx_v_i); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 341, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 341, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_8 = 0; + __pyx_t_12 = 127; + __Pyx_INCREF(__pyx_kp_u_0); + __pyx_t_8 += 1; + __Pyx_GIVEREF(__pyx_kp_u_0); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_kp_u_0); + __pyx_t_1 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_lN, 0, ' ', 'd'); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 341, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_8 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1); + __pyx_t_1 = 0; + __Pyx_INCREF(__pyx_n_u_d); + __pyx_t_8 += 1; + __Pyx_GIVEREF(__pyx_n_u_d); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_n_u_d); + __pyx_t_1 = __Pyx_PyUnicode_Join(__pyx_t_3, 3, __pyx_t_8, __pyx_t_12); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 341, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PyObject_Format(__pyx_t_7, __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 341, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF_SET(__pyx_v_i_string, ((PyObject*)__pyx_t_3)); + __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":342 + * for i in range(self.N+1): + * i_string = f'{i:0{lN}d}' + * solution['x_'+i_string] = self.get(i,'x') # <<<<<<<<<<<<<< + * solution['u_'+i_string] = self.get(i,'u') + * solution['z_'+i_string] = self.get(i,'z') + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 342, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = __Pyx_PyInt_From_long(__pyx_v_i); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 342, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_t_7, __pyx_n_u_x}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 342, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyUnicode_Concat(__pyx_n_u_x_2, __pyx_v_i_string); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 342, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_3) < 0))) __PYX_ERR(0, 342, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":343 + * i_string = f'{i:0{lN}d}' + * solution['x_'+i_string] = self.get(i,'x') + * solution['u_'+i_string] = self.get(i,'u') # <<<<<<<<<<<<<< + * solution['z_'+i_string] = self.get(i,'z') + * solution['lam_'+i_string] = self.get(i,'lam') + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 343, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = __Pyx_PyInt_From_long(__pyx_v_i); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 343, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_t_7, __pyx_n_u_u}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 343, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyUnicode_Concat(__pyx_n_u_u_2, __pyx_v_i_string); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 343, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_3) < 0))) __PYX_ERR(0, 343, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":344 + * solution['x_'+i_string] = self.get(i,'x') + * solution['u_'+i_string] = self.get(i,'u') + * solution['z_'+i_string] = self.get(i,'z') # <<<<<<<<<<<<<< + * solution['lam_'+i_string] = self.get(i,'lam') + * solution['t_'+i_string] = self.get(i, 't') + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 344, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = __Pyx_PyInt_From_long(__pyx_v_i); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 344, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_t_7, __pyx_n_u_z}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 344, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyUnicode_Concat(__pyx_n_u_z_2, __pyx_v_i_string); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 344, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_3) < 0))) __PYX_ERR(0, 344, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":345 + * solution['u_'+i_string] = self.get(i,'u') + * solution['z_'+i_string] = self.get(i,'z') + * solution['lam_'+i_string] = self.get(i,'lam') # <<<<<<<<<<<<<< + * solution['t_'+i_string] = self.get(i, 't') + * solution['sl_'+i_string] = self.get(i, 'sl') + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 345, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = __Pyx_PyInt_From_long(__pyx_v_i); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 345, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_t_7, __pyx_n_u_lam}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 345, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyUnicode_Concat(__pyx_n_u_lam_2, __pyx_v_i_string); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 345, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_3) < 0))) __PYX_ERR(0, 345, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":346 + * solution['z_'+i_string] = self.get(i,'z') + * solution['lam_'+i_string] = self.get(i,'lam') + * solution['t_'+i_string] = self.get(i, 't') # <<<<<<<<<<<<<< + * solution['sl_'+i_string] = self.get(i, 'sl') + * solution['su_'+i_string] = self.get(i, 'su') + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 346, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = __Pyx_PyInt_From_long(__pyx_v_i); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 346, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_t_7, __pyx_n_u_t}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 346, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyUnicode_Concat(__pyx_n_u_t_2, __pyx_v_i_string); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 346, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_3) < 0))) __PYX_ERR(0, 346, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":347 + * solution['lam_'+i_string] = self.get(i,'lam') + * solution['t_'+i_string] = self.get(i, 't') + * solution['sl_'+i_string] = self.get(i, 'sl') # <<<<<<<<<<<<<< + * solution['su_'+i_string] = self.get(i, 'su') + * if i < self.N: + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 347, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = __Pyx_PyInt_From_long(__pyx_v_i); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 347, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_t_7, __pyx_n_u_sl}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 347, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyUnicode_Concat(__pyx_n_u_sl_2, __pyx_v_i_string); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 347, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_3) < 0))) __PYX_ERR(0, 347, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":348 + * solution['t_'+i_string] = self.get(i, 't') + * solution['sl_'+i_string] = self.get(i, 'sl') + * solution['su_'+i_string] = self.get(i, 'su') # <<<<<<<<<<<<<< + * if i < self.N: + * solution['pi_'+i_string] = self.get(i,'pi') + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 348, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = __Pyx_PyInt_From_long(__pyx_v_i); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 348, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_t_7, __pyx_n_u_su}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 348, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyUnicode_Concat(__pyx_n_u_su_2, __pyx_v_i_string); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 348, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_3) < 0))) __PYX_ERR(0, 348, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":349 + * solution['sl_'+i_string] = self.get(i, 'sl') + * solution['su_'+i_string] = self.get(i, 'su') + * if i < self.N: # <<<<<<<<<<<<<< + * solution['pi_'+i_string] = self.get(i,'pi') + * + */ + __pyx_t_4 = (__pyx_v_i < __pyx_v_self->N); + if (__pyx_t_4) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":350 + * solution['su_'+i_string] = self.get(i, 'su') + * if i < self.N: + * solution['pi_'+i_string] = self.get(i,'pi') # <<<<<<<<<<<<<< + * + * for k in list(solution.keys()): + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 350, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = __Pyx_PyInt_From_long(__pyx_v_i); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 350, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_t_7, __pyx_n_u_pi}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 350, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyUnicode_Concat(__pyx_n_u_pi_2, __pyx_v_i_string); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 350, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyDict_SetItem(__pyx_v_solution, __pyx_t_1, __pyx_t_3) < 0))) __PYX_ERR(0, 350, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":349 + * solution['sl_'+i_string] = self.get(i, 'sl') + * solution['su_'+i_string] = self.get(i, 'su') + * if i < self.N: # <<<<<<<<<<<<<< + * solution['pi_'+i_string] = self.get(i,'pi') + * + */ + } + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":352 + * solution['pi_'+i_string] = self.get(i,'pi') + * + * for k in list(solution.keys()): # <<<<<<<<<<<<<< + * if len(solution[k]) == 0: + * del solution[k] + */ + __pyx_t_3 = __Pyx_PyDict_Keys(__pyx_v_solution); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 352, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = __Pyx_PySequence_ListKeepNew(__pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 352, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __pyx_t_1; __Pyx_INCREF(__pyx_t_3); + __pyx_t_8 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + for (;;) { + { + Py_ssize_t __pyx_temp = __Pyx_PyList_GET_SIZE(__pyx_t_3); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 352, __pyx_L1_error) + #endif + if (__pyx_t_8 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_1 = PyList_GET_ITEM(__pyx_t_3, __pyx_t_8); __Pyx_INCREF(__pyx_t_1); __pyx_t_8++; if (unlikely((0 < 0))) __PYX_ERR(0, 352, __pyx_L1_error) + #else + __pyx_t_1 = __Pyx_PySequence_ITEM(__pyx_t_3, __pyx_t_8); __pyx_t_8++; if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 352, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + #endif + __Pyx_XDECREF_SET(__pyx_v_k, __pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":353 + * + * for k in list(solution.keys()): + * if len(solution[k]) == 0: # <<<<<<<<<<<<<< + * del solution[k] + * + */ + __pyx_t_1 = __Pyx_PyDict_GetItem(__pyx_v_solution, __pyx_v_k); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 353, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_13 = PyObject_Length(__pyx_t_1); if (unlikely(__pyx_t_13 == ((Py_ssize_t)-1))) __PYX_ERR(0, 353, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_4 = (__pyx_t_13 == 0); + if (__pyx_t_4) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":354 + * for k in list(solution.keys()): + * if len(solution[k]) == 0: + * del solution[k] # <<<<<<<<<<<<<< + * + * # save + */ + if (unlikely((PyDict_DelItem(__pyx_v_solution, __pyx_v_k) < 0))) __PYX_ERR(0, 354, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":353 + * + * for k in list(solution.keys()): + * if len(solution[k]) == 0: # <<<<<<<<<<<<<< + * del solution[k] + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":352 + * solution['pi_'+i_string] = self.get(i,'pi') + * + * for k in list(solution.keys()): # <<<<<<<<<<<<<< + * if len(solution[k]) == 0: + * del solution[k] + */ + } + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":357 + * + * # save + * with open(filename, 'w') as f: # <<<<<<<<<<<<<< + * json.dump(solution, f, default=lambda x: x.tolist(), indent=4, sort_keys=True) + * print("stored current iterate in ", os.path.join(os.getcwd(), filename)) + */ + /*with:*/ { + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 357, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_v_filename); + __Pyx_GIVEREF(__pyx_v_filename); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_v_filename)) __PYX_ERR(0, 357, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_w); + __Pyx_GIVEREF(__pyx_n_u_w); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_n_u_w)) __PYX_ERR(0, 357, __pyx_L1_error); + __pyx_t_1 = __Pyx_PyObject_Call(__pyx_builtin_open, __pyx_t_3, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 357, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_14 = __Pyx_PyObject_LookupSpecial(__pyx_t_1, __pyx_n_s_exit); if (unlikely(!__pyx_t_14)) __PYX_ERR(0, 357, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_14); + __pyx_t_7 = __Pyx_PyObject_LookupSpecial(__pyx_t_1, __pyx_n_s_enter); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 357, __pyx_L13_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_7))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_7); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_7); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_7, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_5, NULL}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_7, __pyx_callargs+1-__pyx_t_6, 0+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 357, __pyx_L13_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + } + __pyx_t_7 = __pyx_t_3; + __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + /*try:*/ { + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_15, &__pyx_t_16, &__pyx_t_17); + __Pyx_XGOTREF(__pyx_t_15); + __Pyx_XGOTREF(__pyx_t_16); + __Pyx_XGOTREF(__pyx_t_17); + /*try:*/ { + __pyx_v_f = __pyx_t_7; + __pyx_t_7 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":358 + * # save + * with open(filename, 'w') as f: + * json.dump(solution, f, default=lambda x: x.tolist(), indent=4, sort_keys=True) # <<<<<<<<<<<<<< + * print("stored current iterate in ", os.path.join(os.getcwd(), filename)) + * + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_v_json, __pyx_n_s_dump); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 358, __pyx_L17_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_1 = PyTuple_New(2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 358, __pyx_L17_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v_solution); + __Pyx_GIVEREF(__pyx_v_solution); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v_solution)) __PYX_ERR(0, 358, __pyx_L17_error); + __Pyx_INCREF(__pyx_v_f); + __Pyx_GIVEREF(__pyx_v_f); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_v_f)) __PYX_ERR(0, 358, __pyx_L17_error); + __pyx_t_3 = __Pyx_PyDict_NewPresized(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 358, __pyx_L17_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13store_iterate_lambda, 0, __pyx_n_s_store_iterate_locals_lambda, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, NULL); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 358, __pyx_L17_error) + __Pyx_GOTREF(__pyx_t_5); + if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_default, __pyx_t_5) < 0) __PYX_ERR(0, 358, __pyx_L17_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_indent, __pyx_int_4) < 0) __PYX_ERR(0, 358, __pyx_L17_error) + if (PyDict_SetItem(__pyx_t_3, __pyx_n_s_sort_keys, Py_True) < 0) __PYX_ERR(0, 358, __pyx_L17_error) + __pyx_t_5 = __Pyx_PyObject_Call(__pyx_t_7, __pyx_t_1, __pyx_t_3); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 358, __pyx_L17_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":357 + * + * # save + * with open(filename, 'w') as f: # <<<<<<<<<<<<<< + * json.dump(solution, f, default=lambda x: x.tolist(), indent=4, sort_keys=True) + * print("stored current iterate in ", os.path.join(os.getcwd(), filename)) + */ + } + __Pyx_XDECREF(__pyx_t_15); __pyx_t_15 = 0; + __Pyx_XDECREF(__pyx_t_16); __pyx_t_16 = 0; + __Pyx_XDECREF(__pyx_t_17); __pyx_t_17 = 0; + goto __pyx_L22_try_end; + __pyx_L17_error:; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + /*except:*/ { + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.store_iterate", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_3, &__pyx_t_1) < 0) __PYX_ERR(0, 357, __pyx_L19_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __pyx_t_7 = PyTuple_Pack(3, __pyx_t_5, __pyx_t_3, __pyx_t_1); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 357, __pyx_L19_except_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_18 = __Pyx_PyObject_Call(__pyx_t_14, __pyx_t_7, NULL); + __Pyx_DECREF(__pyx_t_14); __pyx_t_14 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_18)) __PYX_ERR(0, 357, __pyx_L19_except_error) + __Pyx_GOTREF(__pyx_t_18); + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_t_18); + __Pyx_DECREF(__pyx_t_18); __pyx_t_18 = 0; + if (__pyx_t_4 < 0) __PYX_ERR(0, 357, __pyx_L19_except_error) + __pyx_t_2 = (!__pyx_t_4); + if (unlikely(__pyx_t_2)) { + __Pyx_GIVEREF(__pyx_t_5); + __Pyx_GIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_ErrRestoreWithState(__pyx_t_5, __pyx_t_3, __pyx_t_1); + __pyx_t_5 = 0; __pyx_t_3 = 0; __pyx_t_1 = 0; + __PYX_ERR(0, 357, __pyx_L19_except_error) + } + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + goto __pyx_L18_exception_handled; + } + __pyx_L19_except_error:; + __Pyx_XGIVEREF(__pyx_t_15); + __Pyx_XGIVEREF(__pyx_t_16); + __Pyx_XGIVEREF(__pyx_t_17); + __Pyx_ExceptionReset(__pyx_t_15, __pyx_t_16, __pyx_t_17); + goto __pyx_L1_error; + __pyx_L18_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_15); + __Pyx_XGIVEREF(__pyx_t_16); + __Pyx_XGIVEREF(__pyx_t_17); + __Pyx_ExceptionReset(__pyx_t_15, __pyx_t_16, __pyx_t_17); + __pyx_L22_try_end:; + } + } + /*finally:*/ { + /*normal exit:*/{ + if (__pyx_t_14) { + __pyx_t_17 = __Pyx_PyObject_Call(__pyx_t_14, __pyx_tuple__19, NULL); + __Pyx_DECREF(__pyx_t_14); __pyx_t_14 = 0; + if (unlikely(!__pyx_t_17)) __PYX_ERR(0, 357, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_17); + __Pyx_DECREF(__pyx_t_17); __pyx_t_17 = 0; + } + goto __pyx_L16; + } + __pyx_L16:; + } + goto __pyx_L26; + __pyx_L13_error:; + __Pyx_DECREF(__pyx_t_14); __pyx_t_14 = 0; + goto __pyx_L1_error; + __pyx_L26:; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":359 + * with open(filename, 'w') as f: + * json.dump(solution, f, default=lambda x: x.tolist(), indent=4, sort_keys=True) + * print("stored current iterate in ", os.path.join(os.getcwd(), filename)) # <<<<<<<<<<<<<< + * + * + */ + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_os); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 359, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_path); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 359, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_join); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 359, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_GetModuleGlobalName(__pyx_t_7, __pyx_n_s_os); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 359, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_19 = __Pyx_PyObject_GetAttrStr(__pyx_t_7, __pyx_n_s_getcwd); if (unlikely(!__pyx_t_19)) __PYX_ERR(0, 359, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_19); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __pyx_t_7 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (unlikely(PyMethod_Check(__pyx_t_19))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_19); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_19); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_19, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_7, NULL}; + __pyx_t_5 = __Pyx_PyObject_FastCall(__pyx_t_19, __pyx_callargs+1-__pyx_t_6, 0+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 359, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_19); __pyx_t_19 = 0; + } + __pyx_t_19 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_19 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_19)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_19); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_19, __pyx_t_5, __pyx_v_filename}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_19); __pyx_t_19 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 359, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 359, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_kp_u_stored_current_iterate_in); + __Pyx_GIVEREF(__pyx_kp_u_stored_current_iterate_in); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_kp_u_stored_current_iterate_in)) __PYX_ERR(0, 359, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1)) __PYX_ERR(0, 359, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_Call(__pyx_builtin_print, __pyx_t_3, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 359, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":319 + * + * + * def store_iterate(self, filename='', overwrite=False): # <<<<<<<<<<<<<< + * """ + * Stores the current iterate of the ocp solver in a json file. + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_19); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.store_iterate", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_json); + __Pyx_XDECREF(__pyx_v_solution); + __Pyx_XDECREF(__pyx_v_i_string); + __Pyx_XDECREF(__pyx_v_k); + __Pyx_XDECREF(__pyx_v_f); + __Pyx_XDECREF(__pyx_v_filename); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":362 + * + * + * def load_iterate(self, filename): # <<<<<<<<<<<<<< + * """ + * Loads the iterate stored in json file with filename into the ocp solver. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25load_iterate(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_24load_iterate, "\n Loads the iterate stored in json file with filename into the ocp solver.\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25load_iterate = {"load_iterate", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25load_iterate, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_24load_iterate}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25load_iterate(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_filename = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("load_iterate (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_filename,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_filename)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 362, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "load_iterate") < 0)) __PYX_ERR(0, 362, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_filename = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("load_iterate", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 362, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.load_iterate", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_24load_iterate(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_filename); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_24load_iterate(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_filename) { + PyObject *__pyx_v_json = NULL; + PyObject *__pyx_v_f = NULL; + PyObject *__pyx_v_solution = NULL; + PyObject *__pyx_v_key = NULL; + PyObject *__pyx_v_field = NULL; + PyObject *__pyx_v_stage = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_t_5; + int __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + PyObject *__pyx_t_9 = NULL; + PyObject *__pyx_t_10 = NULL; + PyObject *__pyx_t_11 = NULL; + PyObject *__pyx_t_12 = NULL; + PyObject *__pyx_t_13 = NULL; + Py_ssize_t __pyx_t_14; + Py_ssize_t __pyx_t_15; + int __pyx_t_16; + PyObject *(*__pyx_t_17)(PyObject *); + PyObject *__pyx_t_18 = NULL; + PyObject *__pyx_t_19 = NULL; + PyObject *__pyx_t_20 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("load_iterate", 1); + + /* "acados_template/acados_ocp_solver_pyx.pyx":366 + * Loads the iterate stored in json file with filename into the ocp solver. + * """ + * import json # <<<<<<<<<<<<<< + * if not os.path.isfile(filename): + * raise Exception('load_iterate: failed, file does not exist: ' + os.path.join(os.getcwd(), filename)) + */ + __pyx_t_1 = __Pyx_ImportDottedModule(__pyx_n_s_json, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 366, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_json = __pyx_t_1; + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":367 + * """ + * import json + * if not os.path.isfile(filename): # <<<<<<<<<<<<<< + * raise Exception('load_iterate: failed, file does not exist: ' + os.path.join(os.getcwd(), filename)) + * + */ + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_os); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 367, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_path); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 367, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_isfile); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 367, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_filename}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 367, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_t_5 = __Pyx_PyObject_IsTrue(__pyx_t_1); if (unlikely((__pyx_t_5 < 0))) __PYX_ERR(0, 367, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_6 = (!__pyx_t_5); + if (unlikely(__pyx_t_6)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":368 + * import json + * if not os.path.isfile(filename): + * raise Exception('load_iterate: failed, file does not exist: ' + os.path.join(os.getcwd(), filename)) # <<<<<<<<<<<<<< + * + * with open(filename, 'r') as f: + */ + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_os); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 368, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_path); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 368, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_join); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 368, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_GetModuleGlobalName(__pyx_t_7, __pyx_n_s_os); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 368, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_t_7, __pyx_n_s_getcwd); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 368, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __pyx_t_7 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (unlikely(PyMethod_Check(__pyx_t_8))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_8); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_8); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_8, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_7, NULL}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_8, __pyx_callargs+1-__pyx_t_4, 0+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 368, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } + __pyx_t_8 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_8 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_8)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_8); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_8, __pyx_t_3, __pyx_v_filename}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 2+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 368, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_t_2 = PyNumber_Add(__pyx_kp_u_load_iterate_failed_file_does_no, __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 368, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 368, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 368, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":367 + * """ + * import json + * if not os.path.isfile(filename): # <<<<<<<<<<<<<< + * raise Exception('load_iterate: failed, file does not exist: ' + os.path.join(os.getcwd(), filename)) + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":370 + * raise Exception('load_iterate: failed, file does not exist: ' + os.path.join(os.getcwd(), filename)) + * + * with open(filename, 'r') as f: # <<<<<<<<<<<<<< + * solution = json.load(f) + * + */ + /*with:*/ { + __pyx_t_1 = PyTuple_New(2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 370, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v_filename); + __Pyx_GIVEREF(__pyx_v_filename); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v_filename)) __PYX_ERR(0, 370, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_r); + __Pyx_GIVEREF(__pyx_n_u_r); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_n_u_r)) __PYX_ERR(0, 370, __pyx_L1_error); + __pyx_t_2 = __Pyx_PyObject_Call(__pyx_builtin_open, __pyx_t_1, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 370, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_9 = __Pyx_PyObject_LookupSpecial(__pyx_t_2, __pyx_n_s_exit); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 370, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __pyx_t_3 = __Pyx_PyObject_LookupSpecial(__pyx_t_2, __pyx_n_s_enter); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 370, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_8 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_8 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_8)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_8); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_8, NULL}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_4, 0+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 370, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_t_3 = __pyx_t_1; + __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + /*try:*/ { + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_10, &__pyx_t_11, &__pyx_t_12); + __Pyx_XGOTREF(__pyx_t_10); + __Pyx_XGOTREF(__pyx_t_11); + __Pyx_XGOTREF(__pyx_t_12); + /*try:*/ { + __pyx_v_f = __pyx_t_3; + __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":371 + * + * with open(filename, 'r') as f: + * solution = json.load(f) # <<<<<<<<<<<<<< + * + * for key in solution.keys(): + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_json, __pyx_n_s_load); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 371, __pyx_L8_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_1 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_1)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_1); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_1, __pyx_v_f}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 371, __pyx_L8_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_v_solution = __pyx_t_3; + __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":370 + * raise Exception('load_iterate: failed, file does not exist: ' + os.path.join(os.getcwd(), filename)) + * + * with open(filename, 'r') as f: # <<<<<<<<<<<<<< + * solution = json.load(f) + * + */ + } + __Pyx_XDECREF(__pyx_t_10); __pyx_t_10 = 0; + __Pyx_XDECREF(__pyx_t_11); __pyx_t_11 = 0; + __Pyx_XDECREF(__pyx_t_12); __pyx_t_12 = 0; + goto __pyx_L13_try_end; + __pyx_L8_error:; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + /*except:*/ { + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.load_iterate", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_3, &__pyx_t_2, &__pyx_t_1) < 0) __PYX_ERR(0, 370, __pyx_L10_except_error) + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_1); + __pyx_t_8 = PyTuple_Pack(3, __pyx_t_3, __pyx_t_2, __pyx_t_1); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 370, __pyx_L10_except_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_13 = __Pyx_PyObject_Call(__pyx_t_9, __pyx_t_8, NULL); + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + if (unlikely(!__pyx_t_13)) __PYX_ERR(0, 370, __pyx_L10_except_error) + __Pyx_GOTREF(__pyx_t_13); + __pyx_t_6 = __Pyx_PyObject_IsTrue(__pyx_t_13); + __Pyx_DECREF(__pyx_t_13); __pyx_t_13 = 0; + if (__pyx_t_6 < 0) __PYX_ERR(0, 370, __pyx_L10_except_error) + __pyx_t_5 = (!__pyx_t_6); + if (unlikely(__pyx_t_5)) { + __Pyx_GIVEREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_ErrRestoreWithState(__pyx_t_3, __pyx_t_2, __pyx_t_1); + __pyx_t_3 = 0; __pyx_t_2 = 0; __pyx_t_1 = 0; + __PYX_ERR(0, 370, __pyx_L10_except_error) + } + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + goto __pyx_L9_exception_handled; + } + __pyx_L10_except_error:; + __Pyx_XGIVEREF(__pyx_t_10); + __Pyx_XGIVEREF(__pyx_t_11); + __Pyx_XGIVEREF(__pyx_t_12); + __Pyx_ExceptionReset(__pyx_t_10, __pyx_t_11, __pyx_t_12); + goto __pyx_L1_error; + __pyx_L9_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_10); + __Pyx_XGIVEREF(__pyx_t_11); + __Pyx_XGIVEREF(__pyx_t_12); + __Pyx_ExceptionReset(__pyx_t_10, __pyx_t_11, __pyx_t_12); + __pyx_L13_try_end:; + } + } + /*finally:*/ { + /*normal exit:*/{ + if (__pyx_t_9) { + __pyx_t_12 = __Pyx_PyObject_Call(__pyx_t_9, __pyx_tuple__19, NULL); + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + if (unlikely(!__pyx_t_12)) __PYX_ERR(0, 370, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_12); + __Pyx_DECREF(__pyx_t_12); __pyx_t_12 = 0; + } + goto __pyx_L7; + } + __pyx_L7:; + } + goto __pyx_L17; + __pyx_L4_error:; + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + goto __pyx_L1_error; + __pyx_L17:; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":373 + * solution = json.load(f) + * + * for key in solution.keys(): # <<<<<<<<<<<<<< + * (field, stage) = key.split('_') + * self.set(int(stage), field, np.array(solution[key])) + */ + __pyx_t_14 = 0; + if (unlikely(!__pyx_v_solution)) { __Pyx_RaiseUnboundLocalError("solution"); __PYX_ERR(0, 373, __pyx_L1_error) } + if (unlikely(__pyx_v_solution == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "keys"); + __PYX_ERR(0, 373, __pyx_L1_error) + } + __pyx_t_2 = __Pyx_dict_iterator(__pyx_v_solution, 0, __pyx_n_s_keys, (&__pyx_t_15), (&__pyx_t_4)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 373, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_1); + __pyx_t_1 = __pyx_t_2; + __pyx_t_2 = 0; + while (1) { + __pyx_t_16 = __Pyx_dict_iter_next(__pyx_t_1, __pyx_t_15, &__pyx_t_14, &__pyx_t_2, NULL, NULL, __pyx_t_4); + if (unlikely(__pyx_t_16 == 0)) break; + if (unlikely(__pyx_t_16 == -1)) __PYX_ERR(0, 373, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_XDECREF_SET(__pyx_v_key, __pyx_t_2); + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":374 + * + * for key in solution.keys(): + * (field, stage) = key.split('_') # <<<<<<<<<<<<<< + * self.set(int(stage), field, np.array(solution[key])) + * + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_v_key, __pyx_n_s_split); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 374, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_8 = NULL; + __pyx_t_16 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_8 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_8)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_8); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_16 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_8, __pyx_n_u__17}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_16, 1+__pyx_t_16); + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 374, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + if ((likely(PyTuple_CheckExact(__pyx_t_2))) || (PyList_CheckExact(__pyx_t_2))) { + PyObject* sequence = __pyx_t_2; + Py_ssize_t size = __Pyx_PySequence_SIZE(sequence); + if (unlikely(size != 2)) { + if (size > 2) __Pyx_RaiseTooManyValuesError(2); + else if (size >= 0) __Pyx_RaiseNeedMoreValuesError(size); + __PYX_ERR(0, 374, __pyx_L1_error) + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + if (likely(PyTuple_CheckExact(sequence))) { + __pyx_t_3 = PyTuple_GET_ITEM(sequence, 0); + __pyx_t_8 = PyTuple_GET_ITEM(sequence, 1); + } else { + __pyx_t_3 = PyList_GET_ITEM(sequence, 0); + __pyx_t_8 = PyList_GET_ITEM(sequence, 1); + } + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(__pyx_t_8); + #else + __pyx_t_3 = PySequence_ITEM(sequence, 0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 374, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_8 = PySequence_ITEM(sequence, 1); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 374, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + #endif + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } else { + Py_ssize_t index = -1; + __pyx_t_7 = PyObject_GetIter(__pyx_t_2); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 374, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_17 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_7); + index = 0; __pyx_t_3 = __pyx_t_17(__pyx_t_7); if (unlikely(!__pyx_t_3)) goto __pyx_L20_unpacking_failed; + __Pyx_GOTREF(__pyx_t_3); + index = 1; __pyx_t_8 = __pyx_t_17(__pyx_t_7); if (unlikely(!__pyx_t_8)) goto __pyx_L20_unpacking_failed; + __Pyx_GOTREF(__pyx_t_8); + if (__Pyx_IternextUnpackEndCheck(__pyx_t_17(__pyx_t_7), 2) < 0) __PYX_ERR(0, 374, __pyx_L1_error) + __pyx_t_17 = NULL; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + goto __pyx_L21_unpacking_done; + __pyx_L20_unpacking_failed:; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __pyx_t_17 = NULL; + if (__Pyx_IterFinish() == 0) __Pyx_RaiseNeedMoreValuesError(index); + __PYX_ERR(0, 374, __pyx_L1_error) + __pyx_L21_unpacking_done:; + } + __Pyx_XDECREF_SET(__pyx_v_field, __pyx_t_3); + __pyx_t_3 = 0; + __Pyx_XDECREF_SET(__pyx_v_stage, __pyx_t_8); + __pyx_t_8 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":375 + * for key in solution.keys(): + * (field, stage) = key.split('_') + * self.set(int(stage), field, np.array(solution[key])) # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_set); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 375, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_3 = __Pyx_PyNumber_Int(__pyx_v_stage); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 375, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GetModuleGlobalName(__pyx_t_18, __pyx_n_s_np); if (unlikely(!__pyx_t_18)) __PYX_ERR(0, 375, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_18); + __pyx_t_19 = __Pyx_PyObject_GetAttrStr(__pyx_t_18, __pyx_n_s_array); if (unlikely(!__pyx_t_19)) __PYX_ERR(0, 375, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_19); + __Pyx_DECREF(__pyx_t_18); __pyx_t_18 = 0; + if (unlikely(!__pyx_v_solution)) { __Pyx_RaiseUnboundLocalError("solution"); __PYX_ERR(0, 375, __pyx_L1_error) } + __pyx_t_18 = __Pyx_PyObject_GetItem(__pyx_v_solution, __pyx_v_key); if (unlikely(!__pyx_t_18)) __PYX_ERR(0, 375, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_18); + __pyx_t_20 = NULL; + __pyx_t_16 = 0; + #if CYTHON_UNPACK_METHODS + if (unlikely(PyMethod_Check(__pyx_t_19))) { + __pyx_t_20 = PyMethod_GET_SELF(__pyx_t_19); + if (likely(__pyx_t_20)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_19); + __Pyx_INCREF(__pyx_t_20); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_19, function); + __pyx_t_16 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_20, __pyx_t_18}; + __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_19, __pyx_callargs+1-__pyx_t_16, 1+__pyx_t_16); + __Pyx_XDECREF(__pyx_t_20); __pyx_t_20 = 0; + __Pyx_DECREF(__pyx_t_18); __pyx_t_18 = 0; + if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 375, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_19); __pyx_t_19 = 0; + } + __pyx_t_19 = NULL; + __pyx_t_16 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_8))) { + __pyx_t_19 = PyMethod_GET_SELF(__pyx_t_8); + if (likely(__pyx_t_19)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_8); + __Pyx_INCREF(__pyx_t_19); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_8, function); + __pyx_t_16 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[4] = {__pyx_t_19, __pyx_t_3, __pyx_v_field, __pyx_t_7}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_8, __pyx_callargs+1-__pyx_t_16, 3+__pyx_t_16); + __Pyx_XDECREF(__pyx_t_19); __pyx_t_19 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 375, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":362 + * + * + * def load_iterate(self, filename): # <<<<<<<<<<<<<< + * """ + * Loads the iterate stored in json file with filename into the ocp solver. + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_XDECREF(__pyx_t_18); + __Pyx_XDECREF(__pyx_t_19); + __Pyx_XDECREF(__pyx_t_20); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.load_iterate", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_json); + __Pyx_XDECREF(__pyx_v_f); + __Pyx_XDECREF(__pyx_v_solution); + __Pyx_XDECREF(__pyx_v_key); + __Pyx_XDECREF(__pyx_v_field); + __Pyx_XDECREF(__pyx_v_stage); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":378 + * + * + * def get_stats(self, field_): # <<<<<<<<<<<<<< + * """ + * Get the information of the last solver call. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27get_stats(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_26get_stats, "\n Get the information of the last solver call.\n\n :param field: string in ['statistics', 'time_tot', 'time_lin', 'time_sim', 'time_sim_ad', 'time_sim_la', 'time_qp', 'time_qp_solver_call', 'time_reg', 'sqp_iter']\n Available fileds:\n - time_tot: total CPU time previous call\n - time_lin: CPU time for linearization\n - time_sim: CPU time for integrator\n - time_sim_ad: CPU time for integrator contribution of external function calls\n - time_sim_la: CPU time for integrator contribution of linear algebra\n - time_qp: CPU time qp solution\n - time_qp_solver_call: CPU time inside qp solver (without converting the QP)\n - time_qp_xcond: time_glob: CPU time globalization\n - time_solution_sensitivities: CPU time for previous call to eval_param_sens\n - time_reg: CPU time regularization\n - sqp_iter: number of SQP iterations\n - qp_iter: vector of QP iterations for last SQP call\n - statistics: table with info about last iteration\n - stat_m: number of rows in statistics matrix\n - stat_n: number of columns in statistics matrix\n - residuals: residuals of last iterate\n - alpha: step sizes of SQP iterations\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27get_stats = {"get_stats", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27get_stats, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_26get_stats}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27get_stats(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_field_ = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("get_stats (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_field_2,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field_2)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 378, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "get_stats") < 0)) __PYX_ERR(0, 378, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_field_ = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("get_stats", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 378, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.get_stats", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_26get_stats(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_field_); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_26get_stats(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field_) { + PyObject *__pyx_v_double_fields = NULL; + CYTHON_UNUSED PyObject *__pyx_v_fields = NULL; + PyObject *__pyx_v_field = NULL; + PyObject *__pyx_v_sqp_iter = NULL; + PyObject *__pyx_v_stat_m = NULL; + PyObject *__pyx_v_stat_n = NULL; + PyObject *__pyx_v_min_size = NULL; + PyObject *__pyx_v_full_stats = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_t_5; + int __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_stats", 1); + + /* "acados_template/acados_ocp_solver_pyx.pyx":403 + * """ + * + * double_fields = ['time_tot', # <<<<<<<<<<<<<< + * 'time_lin', + * 'time_sim', + */ + __pyx_t_1 = PyList_New(11); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 403, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_u_time_tot); + __Pyx_GIVEREF(__pyx_n_u_time_tot); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_u_time_tot)) __PYX_ERR(0, 403, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_time_lin); + __Pyx_GIVEREF(__pyx_n_u_time_lin); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 1, __pyx_n_u_time_lin)) __PYX_ERR(0, 403, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_time_sim); + __Pyx_GIVEREF(__pyx_n_u_time_sim); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 2, __pyx_n_u_time_sim)) __PYX_ERR(0, 403, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_time_sim_ad); + __Pyx_GIVEREF(__pyx_n_u_time_sim_ad); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 3, __pyx_n_u_time_sim_ad)) __PYX_ERR(0, 403, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_time_sim_la); + __Pyx_GIVEREF(__pyx_n_u_time_sim_la); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 4, __pyx_n_u_time_sim_la)) __PYX_ERR(0, 403, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_time_qp); + __Pyx_GIVEREF(__pyx_n_u_time_qp); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 5, __pyx_n_u_time_qp)) __PYX_ERR(0, 403, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_time_qp_solver_call); + __Pyx_GIVEREF(__pyx_n_u_time_qp_solver_call); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 6, __pyx_n_u_time_qp_solver_call)) __PYX_ERR(0, 403, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_time_qp_xcond); + __Pyx_GIVEREF(__pyx_n_u_time_qp_xcond); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 7, __pyx_n_u_time_qp_xcond)) __PYX_ERR(0, 403, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_time_glob); + __Pyx_GIVEREF(__pyx_n_u_time_glob); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 8, __pyx_n_u_time_glob)) __PYX_ERR(0, 403, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_time_solution_sensitivities); + __Pyx_GIVEREF(__pyx_n_u_time_solution_sensitivities); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 9, __pyx_n_u_time_solution_sensitivities)) __PYX_ERR(0, 403, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_time_reg); + __Pyx_GIVEREF(__pyx_n_u_time_reg); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 10, __pyx_n_u_time_reg)) __PYX_ERR(0, 403, __pyx_L1_error); + __pyx_v_double_fields = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":415 + * 'time_reg' + * ] + * fields = double_fields + [ # <<<<<<<<<<<<<< + * 'sqp_iter', + * 'qp_iter', + */ + __pyx_t_1 = PyList_New(7); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 415, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_u_sqp_iter); + __Pyx_GIVEREF(__pyx_n_u_sqp_iter); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_u_sqp_iter)) __PYX_ERR(0, 415, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_qp_iter); + __Pyx_GIVEREF(__pyx_n_u_qp_iter); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 1, __pyx_n_u_qp_iter)) __PYX_ERR(0, 415, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_statistics); + __Pyx_GIVEREF(__pyx_n_u_statistics); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 2, __pyx_n_u_statistics)) __PYX_ERR(0, 415, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_stat_m); + __Pyx_GIVEREF(__pyx_n_u_stat_m); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 3, __pyx_n_u_stat_m)) __PYX_ERR(0, 415, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_stat_n); + __Pyx_GIVEREF(__pyx_n_u_stat_n); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 4, __pyx_n_u_stat_n)) __PYX_ERR(0, 415, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_residuals); + __Pyx_GIVEREF(__pyx_n_u_residuals); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 5, __pyx_n_u_residuals)) __PYX_ERR(0, 415, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_alpha); + __Pyx_GIVEREF(__pyx_n_u_alpha); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 6, __pyx_n_u_alpha)) __PYX_ERR(0, 415, __pyx_L1_error); + __pyx_t_2 = PyNumber_Add(__pyx_v_double_fields, __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 415, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_fields = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":424 + * 'alpha', + * ] + * field = field_.encode('utf-8') # <<<<<<<<<<<<<< + * + * if field_ in ['sqp_iter', 'stat_m', 'stat_n']: + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_field_, __pyx_n_s_encode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 424, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_kp_u_utf_8}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 424, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_v_field = __pyx_t_2; + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":426 + * field = field_.encode('utf-8') + * + * if field_ in ['sqp_iter', 'stat_m', 'stat_n']: # <<<<<<<<<<<<<< + * return self.__get_stat_int(field) + * + */ + __Pyx_INCREF(__pyx_v_field_); + __pyx_t_2 = __pyx_v_field_; + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_t_2, __pyx_n_u_sqp_iter, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 426, __pyx_L1_error) + if (!__pyx_t_6) { + } else { + __pyx_t_5 = __pyx_t_6; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_t_2, __pyx_n_u_stat_m, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 426, __pyx_L1_error) + if (!__pyx_t_6) { + } else { + __pyx_t_5 = __pyx_t_6; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_t_2, __pyx_n_u_stat_n, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 426, __pyx_L1_error) + __pyx_t_5 = __pyx_t_6; + __pyx_L4_bool_binop_done:; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_6 = __pyx_t_5; + if (__pyx_t_6) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":427 + * + * if field_ in ['sqp_iter', 'stat_m', 'stat_n']: + * return self.__get_stat_int(field) # <<<<<<<<<<<<<< + * + * elif field_ in double_fields: + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_AcadosOcpSolverCython__get_stat); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 427, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_field}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 427, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":426 + * field = field_.encode('utf-8') + * + * if field_ in ['sqp_iter', 'stat_m', 'stat_n']: # <<<<<<<<<<<<<< + * return self.__get_stat_int(field) + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":429 + * return self.__get_stat_int(field) + * + * elif field_ in double_fields: # <<<<<<<<<<<<<< + * return self.__get_stat_double(field) + * + */ + __pyx_t_6 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_double_fields, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 429, __pyx_L1_error) + if (__pyx_t_6) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":430 + * + * elif field_ in double_fields: + * return self.__get_stat_double(field) # <<<<<<<<<<<<<< + * + * elif field_ == 'statistics': + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_AcadosOcpSolverCython__get_stat_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 430, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_v_field}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 430, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":429 + * return self.__get_stat_int(field) + * + * elif field_ in double_fields: # <<<<<<<<<<<<<< + * return self.__get_stat_double(field) + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":432 + * return self.__get_stat_double(field) + * + * elif field_ == 'statistics': # <<<<<<<<<<<<<< + * sqp_iter = self.get_stats("sqp_iter") + * stat_m = self.get_stats("stat_m") + */ + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_statistics, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 432, __pyx_L1_error) + if (__pyx_t_6) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":433 + * + * elif field_ == 'statistics': + * sqp_iter = self.get_stats("sqp_iter") # <<<<<<<<<<<<<< + * stat_m = self.get_stats("stat_m") + * stat_n = self.get_stats("stat_n") + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_stats); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 433, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_n_u_sqp_iter}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 433, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_v_sqp_iter = __pyx_t_2; + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":434 + * elif field_ == 'statistics': + * sqp_iter = self.get_stats("sqp_iter") + * stat_m = self.get_stats("stat_m") # <<<<<<<<<<<<<< + * stat_n = self.get_stats("stat_n") + * min_size = min([stat_m, sqp_iter+1]) + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_stats); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 434, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_n_u_stat_m}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 434, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_v_stat_m = __pyx_t_2; + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":435 + * sqp_iter = self.get_stats("sqp_iter") + * stat_m = self.get_stats("stat_m") + * stat_n = self.get_stats("stat_n") # <<<<<<<<<<<<<< + * min_size = min([stat_m, sqp_iter+1]) + * return self.__get_stat_matrix(field, stat_n+1, min_size) + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_stats); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 435, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_3 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_3)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_3, __pyx_n_u_stat_n}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 435, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_v_stat_n = __pyx_t_2; + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":436 + * stat_m = self.get_stats("stat_m") + * stat_n = self.get_stats("stat_n") + * min_size = min([stat_m, sqp_iter+1]) # <<<<<<<<<<<<<< + * return self.__get_stat_matrix(field, stat_n+1, min_size) + * + */ + __pyx_t_2 = __Pyx_PyInt_AddObjC(__pyx_v_sqp_iter, __pyx_int_1, 1, 0, 0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 436, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_INCREF(__pyx_v_stat_m); + __pyx_t_1 = __pyx_v_stat_m; + __pyx_t_7 = PyObject_RichCompare(__pyx_t_2, __pyx_t_1, Py_LT); __Pyx_XGOTREF(__pyx_t_7); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 436, __pyx_L1_error) + __pyx_t_6 = __Pyx_PyObject_IsTrue(__pyx_t_7); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 436, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (__pyx_t_6) { + __Pyx_INCREF(__pyx_t_2); + __pyx_t_3 = __pyx_t_2; + } else { + __Pyx_INCREF(__pyx_t_1); + __pyx_t_3 = __pyx_t_1; + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __pyx_t_3; + __Pyx_INCREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_v_min_size = __pyx_t_2; + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":437 + * stat_n = self.get_stats("stat_n") + * min_size = min([stat_m, sqp_iter+1]) + * return self.__get_stat_matrix(field, stat_n+1, min_size) # <<<<<<<<<<<<<< + * + * elif field_ == 'qp_iter': + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_AcadosOcpSolverCython__get_stat_3); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 437, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = __Pyx_PyInt_AddObjC(__pyx_v_stat_n, __pyx_int_1, 1, 0, 0); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 437, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_7 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[4] = {__pyx_t_7, __pyx_v_field, __pyx_t_1, __pyx_v_min_size}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_4, 3+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 437, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":432 + * return self.__get_stat_double(field) + * + * elif field_ == 'statistics': # <<<<<<<<<<<<<< + * sqp_iter = self.get_stats("sqp_iter") + * stat_m = self.get_stats("stat_m") + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":439 + * return self.__get_stat_matrix(field, stat_n+1, min_size) + * + * elif field_ == 'qp_iter': # <<<<<<<<<<<<<< + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': + */ + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_qp_iter, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 439, __pyx_L1_error) + if (__pyx_t_6) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":440 + * + * elif field_ == 'qp_iter': + * full_stats = self.get_stats('statistics') # <<<<<<<<<<<<<< + * if self.nlp_solver_type == 'SQP': + * return full_stats[6, :] + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_stats); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 440, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_1)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_1); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_1, __pyx_n_u_statistics}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 440, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_v_full_stats = __pyx_t_2; + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":441 + * elif field_ == 'qp_iter': + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': # <<<<<<<<<<<<<< + * return full_stats[6, :] + * elif self.nlp_solver_type == 'SQP_RTI': + */ + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_self->nlp_solver_type, __pyx_n_u_SQP, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 441, __pyx_L1_error) + if (__pyx_t_6) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":442 + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': + * return full_stats[6, :] # <<<<<<<<<<<<<< + * elif self.nlp_solver_type == 'SQP_RTI': + * return full_stats[2, :] + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_v_full_stats, __pyx_tuple__20); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 442, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":441 + * elif field_ == 'qp_iter': + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': # <<<<<<<<<<<<<< + * return full_stats[6, :] + * elif self.nlp_solver_type == 'SQP_RTI': + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":443 + * if self.nlp_solver_type == 'SQP': + * return full_stats[6, :] + * elif self.nlp_solver_type == 'SQP_RTI': # <<<<<<<<<<<<<< + * return full_stats[2, :] + * + */ + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_self->nlp_solver_type, __pyx_n_u_SQP_RTI, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 443, __pyx_L1_error) + if (__pyx_t_6) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":444 + * return full_stats[6, :] + * elif self.nlp_solver_type == 'SQP_RTI': + * return full_stats[2, :] # <<<<<<<<<<<<<< + * + * elif field_ == 'alpha': + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_v_full_stats, __pyx_tuple__21); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 444, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":443 + * if self.nlp_solver_type == 'SQP': + * return full_stats[6, :] + * elif self.nlp_solver_type == 'SQP_RTI': # <<<<<<<<<<<<<< + * return full_stats[2, :] + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":439 + * return self.__get_stat_matrix(field, stat_n+1, min_size) + * + * elif field_ == 'qp_iter': # <<<<<<<<<<<<<< + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': + */ + goto __pyx_L3; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":446 + * return full_stats[2, :] + * + * elif field_ == 'alpha': # <<<<<<<<<<<<<< + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': + */ + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_alpha, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 446, __pyx_L1_error) + if (__pyx_t_6) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":447 + * + * elif field_ == 'alpha': + * full_stats = self.get_stats('statistics') # <<<<<<<<<<<<<< + * if self.nlp_solver_type == 'SQP': + * return full_stats[7, :] + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_stats); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 447, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_1)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_1); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_1, __pyx_n_u_statistics}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 447, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_v_full_stats = __pyx_t_2; + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":448 + * elif field_ == 'alpha': + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': # <<<<<<<<<<<<<< + * return full_stats[7, :] + * else: # self.nlp_solver_type == 'SQP_RTI': + */ + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_self->nlp_solver_type, __pyx_n_u_SQP, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 448, __pyx_L1_error) + if (likely(__pyx_t_6)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":449 + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': + * return full_stats[7, :] # <<<<<<<<<<<<<< + * else: # self.nlp_solver_type == 'SQP_RTI': + * raise Exception("alpha values are not available for SQP_RTI") + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_v_full_stats, __pyx_tuple__22); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 449, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":448 + * elif field_ == 'alpha': + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': # <<<<<<<<<<<<<< + * return full_stats[7, :] + * else: # self.nlp_solver_type == 'SQP_RTI': + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":451 + * return full_stats[7, :] + * else: # self.nlp_solver_type == 'SQP_RTI': + * raise Exception("alpha values are not available for SQP_RTI") # <<<<<<<<<<<<<< + * + * elif field_ == 'residuals': + */ + /*else*/ { + __pyx_t_2 = __Pyx_PyObject_Call(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_tuple__23, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 451, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 451, __pyx_L1_error) + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":446 + * return full_stats[2, :] + * + * elif field_ == 'alpha': # <<<<<<<<<<<<<< + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":453 + * raise Exception("alpha values are not available for SQP_RTI") + * + * elif field_ == 'residuals': # <<<<<<<<<<<<<< + * return self.get_residuals() + * + */ + __pyx_t_6 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_residuals, Py_EQ)); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 453, __pyx_L1_error) + if (likely(__pyx_t_6)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":454 + * + * elif field_ == 'residuals': + * return self.get_residuals() # <<<<<<<<<<<<<< + * + * else: + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_get_residuals); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 454, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_1 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_1)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_1); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_1, NULL}; + __pyx_t_2 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_4, 0+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 454, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":453 + * raise Exception("alpha values are not available for SQP_RTI") + * + * elif field_ == 'residuals': # <<<<<<<<<<<<<< + * return self.get_residuals() + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":457 + * + * else: + * raise NotImplementedError("TODO!") # <<<<<<<<<<<<<< + * + * + */ + /*else*/ { + __pyx_t_2 = __Pyx_PyObject_Call(__pyx_builtin_NotImplementedError, __pyx_tuple__24, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 457, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 457, __pyx_L1_error) + } + __pyx_L3:; + + /* "acados_template/acados_ocp_solver_pyx.pyx":378 + * + * + * def get_stats(self, field_): # <<<<<<<<<<<<<< + * """ + * Get the information of the last solver call. + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.get_stats", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_double_fields); + __Pyx_XDECREF(__pyx_v_fields); + __Pyx_XDECREF(__pyx_v_field); + __Pyx_XDECREF(__pyx_v_sqp_iter); + __Pyx_XDECREF(__pyx_v_stat_m); + __Pyx_XDECREF(__pyx_v_stat_n); + __Pyx_XDECREF(__pyx_v_min_size); + __Pyx_XDECREF(__pyx_v_full_stats); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":460 + * + * + * def __get_stat_int(self, field): # <<<<<<<<<<<<<< + * cdef int out + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &out) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_int(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_int = {"_AcadosOcpSolverCython__get_stat_int", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_int, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_int(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_field = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("_AcadosOcpSolverCython__get_stat_int (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_field,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 460, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "_AcadosOcpSolverCython__get_stat_int") < 0)) __PYX_ERR(0, 460, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_field = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("_AcadosOcpSolverCython__get_stat_int", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 460, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython._AcadosOcpSolverCython__get_stat_int", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_28__get_stat_int(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_field); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_28__get_stat_int(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field) { + int __pyx_v_out; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + char const *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("_AcadosOcpSolverCython__get_stat_int", 1); + + /* "acados_template/acados_ocp_solver_pyx.pyx":462 + * def __get_stat_int(self, field): + * cdef int out + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &out) # <<<<<<<<<<<<<< + * return out + * + */ + __pyx_t_1 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_1) && PyErr_Occurred())) __PYX_ERR(0, 462, __pyx_L1_error) + ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_t_1, ((void *)(&__pyx_v_out))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":463 + * cdef int out + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &out) + * return out # <<<<<<<<<<<<<< + * + * def __get_stat_double(self, field): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyInt_From_int(__pyx_v_out); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 463, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":460 + * + * + * def __get_stat_int(self, field): # <<<<<<<<<<<<<< + * cdef int out + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &out) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython._AcadosOcpSolverCython__get_stat_int", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":465 + * return out + * + * def __get_stat_double(self, field): # <<<<<<<<<<<<<< + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31_AcadosOcpSolverCython__get_stat_double(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31_AcadosOcpSolverCython__get_stat_double = {"_AcadosOcpSolverCython__get_stat_double", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31_AcadosOcpSolverCython__get_stat_double, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31_AcadosOcpSolverCython__get_stat_double(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_field = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("_AcadosOcpSolverCython__get_stat_double (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_field,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 465, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "_AcadosOcpSolverCython__get_stat_double") < 0)) __PYX_ERR(0, 465, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_field = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("_AcadosOcpSolverCython__get_stat_double", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 465, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython._AcadosOcpSolverCython__get_stat_double", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_30__get_stat_double(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_field); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_30__get_stat_double(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field) { + PyArrayObject *__pyx_v_out = 0; + __Pyx_LocalBuf_ND __pyx_pybuffernd_out; + __Pyx_Buffer __pyx_pybuffer_out; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + PyArrayObject *__pyx_t_5 = NULL; + char const *__pyx_t_6; + char *__pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("_AcadosOcpSolverCython__get_stat_double", 1); + __pyx_pybuffer_out.pybuffer.buf = NULL; + __pyx_pybuffer_out.refcount = 0; + __pyx_pybuffernd_out.data = NULL; + __pyx_pybuffernd_out.rcbuffer = &__pyx_pybuffer_out; + + /* "acados_template/acados_ocp_solver_pyx.pyx":466 + * + * def __get_stat_double(self, field): + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) + * return out + */ + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_np); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 466, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_zeros); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 466, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = NULL; + __pyx_t_4 = 0; + #if CYTHON_UNPACK_METHODS + if (unlikely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_2 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_2)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_2); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_4 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_2, __pyx_tuple__25}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_4, 1+__pyx_t_4); + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 466, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + if (!(likely(((__pyx_t_1) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_1, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 466, __pyx_L1_error) + __pyx_t_5 = ((PyArrayObject *)__pyx_t_1); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_out.rcbuffer->pybuffer, (PyObject*)__pyx_t_5, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 1, 0, __pyx_stack) == -1)) { + __pyx_v_out = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_out.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 466, __pyx_L1_error) + } else {__pyx_pybuffernd_out.diminfo[0].strides = __pyx_pybuffernd_out.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_out.diminfo[0].shape = __pyx_pybuffernd_out.rcbuffer->pybuffer.shape[0]; + } + } + __pyx_t_5 = 0; + __pyx_v_out = ((PyArrayObject *)__pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":467 + * def __get_stat_double(self, field): + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) # <<<<<<<<<<<<<< + * return out + * + */ + __pyx_t_6 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_6) && PyErr_Occurred())) __PYX_ERR(0, 467, __pyx_L1_error) + __pyx_t_7 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_out)); if (unlikely(__pyx_t_7 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 467, __pyx_L1_error) + ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_t_6, ((void *)__pyx_t_7)); + + /* "acados_template/acados_ocp_solver_pyx.pyx":468 + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) + * return out # <<<<<<<<<<<<<< + * + * def __get_stat_matrix(self, field, n, m): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_out); + __pyx_r = ((PyObject *)__pyx_v_out); + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":465 + * return out + * + * def __get_stat_double(self, field): # <<<<<<<<<<<<<< + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_out.rcbuffer->pybuffer); + __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython._AcadosOcpSolverCython__get_stat_double", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + goto __pyx_L2; + __pyx_L0:; + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_out.rcbuffer->pybuffer); + __pyx_L2:; + __Pyx_XDECREF((PyObject *)__pyx_v_out); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":470 + * return out + * + * def __get_stat_matrix(self, field, n, m): # <<<<<<<<<<<<<< + * cdef cnp.ndarray[cnp.float64_t, ndim=2] out_mat = np.ascontiguousarray(np.zeros((n, m)), dtype=np.float64) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_mat.data) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33_AcadosOcpSolverCython__get_stat_matrix(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33_AcadosOcpSolverCython__get_stat_matrix = {"_AcadosOcpSolverCython__get_stat_matrix", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33_AcadosOcpSolverCython__get_stat_matrix, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33_AcadosOcpSolverCython__get_stat_matrix(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_field = 0; + PyObject *__pyx_v_n = 0; + PyObject *__pyx_v_m = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("_AcadosOcpSolverCython__get_stat_matrix (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_field,&__pyx_n_s_n,&__pyx_n_s_m,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 470, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_n)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 470, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("_AcadosOcpSolverCython__get_stat_matrix", 1, 3, 3, 1); __PYX_ERR(0, 470, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_m)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 470, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("_AcadosOcpSolverCython__get_stat_matrix", 1, 3, 3, 2); __PYX_ERR(0, 470, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "_AcadosOcpSolverCython__get_stat_matrix") < 0)) __PYX_ERR(0, 470, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + } + __pyx_v_field = values[0]; + __pyx_v_n = values[1]; + __pyx_v_m = values[2]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("_AcadosOcpSolverCython__get_stat_matrix", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 470, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython._AcadosOcpSolverCython__get_stat_matrix", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_32__get_stat_matrix(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_field, __pyx_v_n, __pyx_v_m); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_32__get_stat_matrix(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field, PyObject *__pyx_v_n, PyObject *__pyx_v_m) { + PyArrayObject *__pyx_v_out_mat = 0; + __Pyx_LocalBuf_ND __pyx_pybuffernd_out_mat; + __Pyx_Buffer __pyx_pybuffer_out_mat; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + PyArrayObject *__pyx_t_7 = NULL; + char const *__pyx_t_8; + char *__pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("_AcadosOcpSolverCython__get_stat_matrix", 1); + __pyx_pybuffer_out_mat.pybuffer.buf = NULL; + __pyx_pybuffer_out_mat.refcount = 0; + __pyx_pybuffernd_out_mat.data = NULL; + __pyx_pybuffernd_out_mat.rcbuffer = &__pyx_pybuffer_out_mat; + + /* "acados_template/acados_ocp_solver_pyx.pyx":471 + * + * def __get_stat_matrix(self, field, n, m): + * cdef cnp.ndarray[cnp.float64_t, ndim=2] out_mat = np.ascontiguousarray(np.zeros((n, m)), dtype=np.float64) # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_mat.data) + * return out_mat + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 471, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 471, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_np); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 471, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_zeros); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 471, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 471, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_v_n); + __Pyx_GIVEREF(__pyx_v_n); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_v_n)) __PYX_ERR(0, 471, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_m); + __Pyx_GIVEREF(__pyx_v_m); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_v_m)) __PYX_ERR(0, 471, __pyx_L1_error); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (unlikely(PyMethod_Check(__pyx_t_4))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_4); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_4); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_4, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_5, __pyx_t_3}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_6, 1+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 471, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + __pyx_t_4 = PyTuple_New(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 471, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_1)) __PYX_ERR(0, 471, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 471, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_np); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 471, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_3, __pyx_n_s_float64); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 471, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + if (PyDict_SetItem(__pyx_t_1, __pyx_n_s_dtype, __pyx_t_5) < 0) __PYX_ERR(0, 471, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_5 = __Pyx_PyObject_Call(__pyx_t_2, __pyx_t_4, __pyx_t_1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 471, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (!(likely(((__pyx_t_5) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_5, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 471, __pyx_L1_error) + __pyx_t_7 = ((PyArrayObject *)__pyx_t_5); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_out_mat.rcbuffer->pybuffer, (PyObject*)__pyx_t_7, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 2, 0, __pyx_stack) == -1)) { + __pyx_v_out_mat = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_out_mat.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 471, __pyx_L1_error) + } else {__pyx_pybuffernd_out_mat.diminfo[0].strides = __pyx_pybuffernd_out_mat.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_out_mat.diminfo[0].shape = __pyx_pybuffernd_out_mat.rcbuffer->pybuffer.shape[0]; __pyx_pybuffernd_out_mat.diminfo[1].strides = __pyx_pybuffernd_out_mat.rcbuffer->pybuffer.strides[1]; __pyx_pybuffernd_out_mat.diminfo[1].shape = __pyx_pybuffernd_out_mat.rcbuffer->pybuffer.shape[1]; + } + } + __pyx_t_7 = 0; + __pyx_v_out_mat = ((PyArrayObject *)__pyx_t_5); + __pyx_t_5 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":472 + * def __get_stat_matrix(self, field, n, m): + * cdef cnp.ndarray[cnp.float64_t, ndim=2] out_mat = np.ascontiguousarray(np.zeros((n, m)), dtype=np.float64) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_mat.data) # <<<<<<<<<<<<<< + * return out_mat + * + */ + __pyx_t_8 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_8) && PyErr_Occurred())) __PYX_ERR(0, 472, __pyx_L1_error) + __pyx_t_9 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_out_mat)); if (unlikely(__pyx_t_9 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 472, __pyx_L1_error) + ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_t_8, ((void *)__pyx_t_9)); + + /* "acados_template/acados_ocp_solver_pyx.pyx":473 + * cdef cnp.ndarray[cnp.float64_t, ndim=2] out_mat = np.ascontiguousarray(np.zeros((n, m)), dtype=np.float64) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_mat.data) + * return out_mat # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_out_mat); + __pyx_r = ((PyObject *)__pyx_v_out_mat); + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":470 + * return out + * + * def __get_stat_matrix(self, field, n, m): # <<<<<<<<<<<<<< + * cdef cnp.ndarray[cnp.float64_t, ndim=2] out_mat = np.ascontiguousarray(np.zeros((n, m)), dtype=np.float64) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_mat.data) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_out_mat.rcbuffer->pybuffer); + __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython._AcadosOcpSolverCython__get_stat_matrix", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + goto __pyx_L2; + __pyx_L0:; + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_out_mat.rcbuffer->pybuffer); + __pyx_L2:; + __Pyx_XDECREF((PyObject *)__pyx_v_out_mat); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":476 + * + * + * def get_cost(self): # <<<<<<<<<<<<<< + * """ + * Returns the cost value of the current solution. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35get_cost(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34get_cost, "\n Returns the cost value of the current solution.\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35get_cost = {"get_cost", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35get_cost, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34get_cost}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35get_cost(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("get_cost (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("get_cost", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "get_cost", 0))) return NULL; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34get_cost(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34get_cost(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { + double __pyx_v_out; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_cost", 1); + + /* "acados_template/acados_ocp_solver_pyx.pyx":481 + * """ + * # compute cost internally + * acados_solver_common.ocp_nlp_eval_cost(self.nlp_solver, self.nlp_in, self.nlp_out) # <<<<<<<<<<<<<< + * + * # create output + */ + ocp_nlp_eval_cost(__pyx_v_self->nlp_solver, __pyx_v_self->nlp_in, __pyx_v_self->nlp_out); + + /* "acados_template/acados_ocp_solver_pyx.pyx":487 + * + * # call getter + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, "cost_value", &out) # <<<<<<<<<<<<<< + * + * return out + */ + ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, ((char const *)"cost_value"), ((void *)(&__pyx_v_out))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":489 + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, "cost_value", &out) + * + * return out # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyFloat_FromDouble(__pyx_v_out); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 489, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":476 + * + * + * def get_cost(self): # <<<<<<<<<<<<<< + * """ + * Returns the cost value of the current solution. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.get_cost", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":492 + * + * + * def get_residuals(self, recompute=False): # <<<<<<<<<<<<<< + * """ + * Returns an array of the form [res_stat, res_eq, res_ineq, res_comp]. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37get_residuals(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36get_residuals, "\n Returns an array of the form [res_stat, res_eq, res_ineq, res_comp].\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37get_residuals = {"get_residuals", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37get_residuals, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36get_residuals}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37get_residuals(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_recompute = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("get_residuals (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_recompute,0}; + values[0] = __Pyx_Arg_NewRef_FASTCALL(((PyObject *)Py_False)); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_recompute); + if (value) { values[0] = __Pyx_Arg_NewRef_FASTCALL(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 492, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "get_residuals") < 0)) __PYX_ERR(0, 492, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_recompute = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("get_residuals", 0, 0, 1, __pyx_nargs); __PYX_ERR(0, 492, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.get_residuals", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36get_residuals(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_recompute); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36get_residuals(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_recompute) { + PyArrayObject *__pyx_v_out = 0; + double __pyx_v_double_value; + PyObject *__pyx_v_field = NULL; + __Pyx_LocalBuf_ND __pyx_pybuffernd_out; + __Pyx_Buffer __pyx_pybuffer_out; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_t_9; + PyArrayObject *__pyx_t_10 = NULL; + char const *__pyx_t_11; + Py_ssize_t __pyx_t_12; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_residuals", 1); + __pyx_pybuffer_out.pybuffer.buf = NULL; + __pyx_pybuffer_out.refcount = 0; + __pyx_pybuffernd_out.data = NULL; + __pyx_pybuffernd_out.rcbuffer = &__pyx_pybuffer_out; + + /* "acados_template/acados_ocp_solver_pyx.pyx":497 + * """ + * # compute residuals if RTI + * if self.nlp_solver_type == 'SQP_RTI' or recompute: # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_eval_residuals(self.nlp_solver, self.nlp_in, self.nlp_out) + * + */ + __pyx_t_2 = (__Pyx_PyUnicode_Equals(__pyx_v_self->nlp_solver_type, __pyx_n_u_SQP_RTI, Py_EQ)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 497, __pyx_L1_error) + if (!__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_v_recompute); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 497, __pyx_L1_error) + __pyx_t_1 = __pyx_t_2; + __pyx_L4_bool_binop_done:; + if (__pyx_t_1) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":498 + * # compute residuals if RTI + * if self.nlp_solver_type == 'SQP_RTI' or recompute: + * acados_solver_common.ocp_nlp_eval_residuals(self.nlp_solver, self.nlp_in, self.nlp_out) # <<<<<<<<<<<<<< + * + * # create output array + */ + ocp_nlp_eval_residuals(__pyx_v_self->nlp_solver, __pyx_v_self->nlp_in, __pyx_v_self->nlp_out); + + /* "acados_template/acados_ocp_solver_pyx.pyx":497 + * """ + * # compute residuals if RTI + * if self.nlp_solver_type == 'SQP_RTI' or recompute: # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_eval_residuals(self.nlp_solver, self.nlp_in, self.nlp_out) + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":501 + * + * # create output array + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.ascontiguousarray(np.zeros((4,), dtype=np.float64)) # <<<<<<<<<<<<<< + * cdef double double_value + * + */ + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_np); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 501, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 501, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_np); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 501, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_zeros); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 501, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 501, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GetModuleGlobalName(__pyx_t_7, __pyx_n_s_np); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 501, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_t_7, __pyx_n_s_float64); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 501, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (PyDict_SetItem(__pyx_t_4, __pyx_n_s_dtype, __pyx_t_8) < 0) __PYX_ERR(0, 501, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_t_6, __pyx_tuple__27, __pyx_t_4); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 501, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = NULL; + __pyx_t_9 = 0; + #if CYTHON_UNPACK_METHODS + if (unlikely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_9 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_4, __pyx_t_8}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_9, 1+__pyx_t_9); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 501, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + if (!(likely(((__pyx_t_3) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_3, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 501, __pyx_L1_error) + __pyx_t_10 = ((PyArrayObject *)__pyx_t_3); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_out.rcbuffer->pybuffer, (PyObject*)__pyx_t_10, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES| PyBUF_WRITABLE, 1, 0, __pyx_stack) == -1)) { + __pyx_v_out = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_out.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 501, __pyx_L1_error) + } else {__pyx_pybuffernd_out.diminfo[0].strides = __pyx_pybuffernd_out.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_out.diminfo[0].shape = __pyx_pybuffernd_out.rcbuffer->pybuffer.shape[0]; + } + } + __pyx_t_10 = 0; + __pyx_v_out = ((PyArrayObject *)__pyx_t_3); + __pyx_t_3 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":504 + * cdef double double_value + * + * field = "res_stat".encode('utf-8') # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) + * out[0] = double_value + */ + __Pyx_INCREF(__pyx_n_b_res_stat); + __pyx_v_field = __pyx_n_b_res_stat; + + /* "acados_template/acados_ocp_solver_pyx.pyx":505 + * + * field = "res_stat".encode('utf-8') + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) # <<<<<<<<<<<<<< + * out[0] = double_value + * + */ + __pyx_t_11 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_11) && PyErr_Occurred())) __PYX_ERR(0, 505, __pyx_L1_error) + ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_t_11, ((void *)(&__pyx_v_double_value))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":506 + * field = "res_stat".encode('utf-8') + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) + * out[0] = double_value # <<<<<<<<<<<<<< + * + * field = "res_eq".encode('utf-8') + */ + __pyx_t_12 = 0; + __pyx_t_9 = -1; + if (__pyx_t_12 < 0) { + __pyx_t_12 += __pyx_pybuffernd_out.diminfo[0].shape; + if (unlikely(__pyx_t_12 < 0)) __pyx_t_9 = 0; + } else if (unlikely(__pyx_t_12 >= __pyx_pybuffernd_out.diminfo[0].shape)) __pyx_t_9 = 0; + if (unlikely(__pyx_t_9 != -1)) { + __Pyx_RaiseBufferIndexError(__pyx_t_9); + __PYX_ERR(0, 506, __pyx_L1_error) + } + *__Pyx_BufPtrStrided1d(__pyx_t_5numpy_float64_t *, __pyx_pybuffernd_out.rcbuffer->pybuffer.buf, __pyx_t_12, __pyx_pybuffernd_out.diminfo[0].strides) = __pyx_v_double_value; + + /* "acados_template/acados_ocp_solver_pyx.pyx":508 + * out[0] = double_value + * + * field = "res_eq".encode('utf-8') # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) + * out[1] = double_value + */ + __Pyx_INCREF(__pyx_n_b_res_eq); + __Pyx_DECREF_SET(__pyx_v_field, __pyx_n_b_res_eq); + + /* "acados_template/acados_ocp_solver_pyx.pyx":509 + * + * field = "res_eq".encode('utf-8') + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) # <<<<<<<<<<<<<< + * out[1] = double_value + * + */ + __pyx_t_11 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_11) && PyErr_Occurred())) __PYX_ERR(0, 509, __pyx_L1_error) + ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_t_11, ((void *)(&__pyx_v_double_value))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":510 + * field = "res_eq".encode('utf-8') + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) + * out[1] = double_value # <<<<<<<<<<<<<< + * + * field = "res_ineq".encode('utf-8') + */ + __pyx_t_12 = 1; + __pyx_t_9 = -1; + if (__pyx_t_12 < 0) { + __pyx_t_12 += __pyx_pybuffernd_out.diminfo[0].shape; + if (unlikely(__pyx_t_12 < 0)) __pyx_t_9 = 0; + } else if (unlikely(__pyx_t_12 >= __pyx_pybuffernd_out.diminfo[0].shape)) __pyx_t_9 = 0; + if (unlikely(__pyx_t_9 != -1)) { + __Pyx_RaiseBufferIndexError(__pyx_t_9); + __PYX_ERR(0, 510, __pyx_L1_error) + } + *__Pyx_BufPtrStrided1d(__pyx_t_5numpy_float64_t *, __pyx_pybuffernd_out.rcbuffer->pybuffer.buf, __pyx_t_12, __pyx_pybuffernd_out.diminfo[0].strides) = __pyx_v_double_value; + + /* "acados_template/acados_ocp_solver_pyx.pyx":512 + * out[1] = double_value + * + * field = "res_ineq".encode('utf-8') # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) + * out[2] = double_value + */ + __Pyx_INCREF(__pyx_n_b_res_ineq); + __Pyx_DECREF_SET(__pyx_v_field, __pyx_n_b_res_ineq); + + /* "acados_template/acados_ocp_solver_pyx.pyx":513 + * + * field = "res_ineq".encode('utf-8') + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) # <<<<<<<<<<<<<< + * out[2] = double_value + * + */ + __pyx_t_11 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_11) && PyErr_Occurred())) __PYX_ERR(0, 513, __pyx_L1_error) + ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_t_11, ((void *)(&__pyx_v_double_value))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":514 + * field = "res_ineq".encode('utf-8') + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) + * out[2] = double_value # <<<<<<<<<<<<<< + * + * field = "res_comp".encode('utf-8') + */ + __pyx_t_12 = 2; + __pyx_t_9 = -1; + if (__pyx_t_12 < 0) { + __pyx_t_12 += __pyx_pybuffernd_out.diminfo[0].shape; + if (unlikely(__pyx_t_12 < 0)) __pyx_t_9 = 0; + } else if (unlikely(__pyx_t_12 >= __pyx_pybuffernd_out.diminfo[0].shape)) __pyx_t_9 = 0; + if (unlikely(__pyx_t_9 != -1)) { + __Pyx_RaiseBufferIndexError(__pyx_t_9); + __PYX_ERR(0, 514, __pyx_L1_error) + } + *__Pyx_BufPtrStrided1d(__pyx_t_5numpy_float64_t *, __pyx_pybuffernd_out.rcbuffer->pybuffer.buf, __pyx_t_12, __pyx_pybuffernd_out.diminfo[0].strides) = __pyx_v_double_value; + + /* "acados_template/acados_ocp_solver_pyx.pyx":516 + * out[2] = double_value + * + * field = "res_comp".encode('utf-8') # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) + * out[3] = double_value + */ + __Pyx_INCREF(__pyx_n_b_res_comp); + __Pyx_DECREF_SET(__pyx_v_field, __pyx_n_b_res_comp); + + /* "acados_template/acados_ocp_solver_pyx.pyx":517 + * + * field = "res_comp".encode('utf-8') + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) # <<<<<<<<<<<<<< + * out[3] = double_value + * + */ + __pyx_t_11 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_11) && PyErr_Occurred())) __PYX_ERR(0, 517, __pyx_L1_error) + ocp_nlp_get(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_t_11, ((void *)(&__pyx_v_double_value))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":518 + * field = "res_comp".encode('utf-8') + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &double_value) + * out[3] = double_value # <<<<<<<<<<<<<< + * + * return out + */ + __pyx_t_12 = 3; + __pyx_t_9 = -1; + if (__pyx_t_12 < 0) { + __pyx_t_12 += __pyx_pybuffernd_out.diminfo[0].shape; + if (unlikely(__pyx_t_12 < 0)) __pyx_t_9 = 0; + } else if (unlikely(__pyx_t_12 >= __pyx_pybuffernd_out.diminfo[0].shape)) __pyx_t_9 = 0; + if (unlikely(__pyx_t_9 != -1)) { + __Pyx_RaiseBufferIndexError(__pyx_t_9); + __PYX_ERR(0, 518, __pyx_L1_error) + } + *__Pyx_BufPtrStrided1d(__pyx_t_5numpy_float64_t *, __pyx_pybuffernd_out.rcbuffer->pybuffer.buf, __pyx_t_12, __pyx_pybuffernd_out.diminfo[0].strides) = __pyx_v_double_value; + + /* "acados_template/acados_ocp_solver_pyx.pyx":520 + * out[3] = double_value + * + * return out # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_out); + __pyx_r = ((PyObject *)__pyx_v_out); + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":492 + * + * + * def get_residuals(self, recompute=False): # <<<<<<<<<<<<<< + * """ + * Returns an array of the form [res_stat, res_eq, res_ineq, res_comp]. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_out.rcbuffer->pybuffer); + __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.get_residuals", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + goto __pyx_L2; + __pyx_L0:; + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_out.rcbuffer->pybuffer); + __pyx_L2:; + __Pyx_XDECREF((PyObject *)__pyx_v_out); + __Pyx_XDECREF(__pyx_v_field); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":524 + * + * # Note: this function should not be used anymore, better use cost_set, constraints_set + * def set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * + * """ + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39set(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38set, "\n Set numerical data inside the solver.\n\n :param stage: integer corresponding to shooting node\n :param field: string in ['x', 'u', 'pi', 'lam', 't', 'p']\n\n .. note:: regarding lam, t: \n\n the inequalities are internally organized in the following order: \n\n [ lbu lbx lg lh lphi ubu ubx ug uh uphi; \n\n lsbu lsbx lsg lsh lsphi usbu usbx usg ush usphi]\n\n .. note:: pi: multipliers for dynamics equality constraints \n\n lam: multipliers for inequalities \n\n t: slack variables corresponding to evaluation of all inequalities (at the solution) \n\n sl: slack variables of soft lower inequality constraints \n\n su: slack variables of soft upper inequality constraints \n\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39set = {"set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38set}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39set(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + int __pyx_v_stage; + PyObject *__pyx_v_field_ = 0; + PyObject *__pyx_v_value_ = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("set (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_stage,&__pyx_n_s_field_2,&__pyx_n_s_value,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stage)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 524, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field_2)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 524, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("set", 1, 3, 3, 1); __PYX_ERR(0, 524, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_value)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 524, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("set", 1, 3, 3, 2); __PYX_ERR(0, 524, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "set") < 0)) __PYX_ERR(0, 524, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + } + __pyx_v_stage = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_stage == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 524, __pyx_L3_error) + __pyx_v_field_ = ((PyObject*)values[1]); + __pyx_v_value_ = values[2]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("set", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 524, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.set", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 524, __pyx_L1_error) + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38set(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_stage, __pyx_v_field_, __pyx_v_value_); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = NULL; + __pyx_L0:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_) { + PyObject *__pyx_v_cost_fields = NULL; + PyObject *__pyx_v_constraints_fields = NULL; + PyObject *__pyx_v_out_fields = NULL; + PyObject *__pyx_v_mem_fields = NULL; + PyObject *__pyx_v_field = NULL; + PyArrayObject *__pyx_v_value = 0; + PyObject *__pyx_v_dims = NULL; + PyObject *__pyx_v_msg = NULL; + __Pyx_LocalBuf_ND __pyx_pybuffernd_value; + __Pyx_Buffer __pyx_pybuffer_value; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_t_3; + int __pyx_t_4; + Py_ssize_t __pyx_t_5; + Py_UCS4 __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + PyObject *__pyx_t_9 = NULL; + PyArrayObject *__pyx_t_10 = NULL; + char *__pyx_t_11; + npy_intp *__pyx_t_12; + int __pyx_t_13; + char const *__pyx_t_14; + char const *__pyx_t_15; + char const *__pyx_t_16; + char const *__pyx_t_17; + char const *__pyx_t_18; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("set", 1); + __pyx_pybuffer_value.pybuffer.buf = NULL; + __pyx_pybuffer_value.refcount = 0; + __pyx_pybuffernd_value.data = NULL; + __pyx_pybuffernd_value.rcbuffer = &__pyx_pybuffer_value; + + /* "acados_template/acados_ocp_solver_pyx.pyx":543 + * su: slack variables of soft upper inequality constraints \n + * """ + * if not isinstance(value_, np.ndarray): # <<<<<<<<<<<<<< + * raise Exception(f"set: value must be numpy array, got {type(value_)}.") + * cost_fields = ['y_ref', 'yref'] + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 543, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_ndarray); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 543, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_3 = PyObject_IsInstance(__pyx_v_value_, __pyx_t_2); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(0, 543, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_4 = (!__pyx_t_3); + if (unlikely(__pyx_t_4)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":544 + * """ + * if not isinstance(value_, np.ndarray): + * raise Exception(f"set: value must be numpy array, got {type(value_)}.") # <<<<<<<<<<<<<< + * cost_fields = ['y_ref', 'yref'] + * constraints_fields = ['lbx', 'ubx', 'lbu', 'ubu'] + */ + __pyx_t_2 = PyTuple_New(3); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 544, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_5 = 0; + __pyx_t_6 = 127; + __Pyx_INCREF(__pyx_kp_u_set_value_must_be_numpy_array_go); + __pyx_t_5 += 36; + __Pyx_GIVEREF(__pyx_kp_u_set_value_must_be_numpy_array_go); + PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_kp_u_set_value_must_be_numpy_array_go); + __pyx_t_1 = __Pyx_PyObject_FormatSimple(((PyObject *)Py_TYPE(__pyx_v_value_)), __pyx_empty_unicode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 544, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_2, 1, __pyx_t_1); + __pyx_t_1 = 0; + __Pyx_INCREF(__pyx_kp_u__2); + __pyx_t_5 += 1; + __Pyx_GIVEREF(__pyx_kp_u__2); + PyTuple_SET_ITEM(__pyx_t_2, 2, __pyx_kp_u__2); + __pyx_t_1 = __Pyx_PyUnicode_Join(__pyx_t_2, 3, __pyx_t_5, __pyx_t_6); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 544, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 544, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 544, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":543 + * su: slack variables of soft upper inequality constraints \n + * """ + * if not isinstance(value_, np.ndarray): # <<<<<<<<<<<<<< + * raise Exception(f"set: value must be numpy array, got {type(value_)}.") + * cost_fields = ['y_ref', 'yref'] + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":545 + * if not isinstance(value_, np.ndarray): + * raise Exception(f"set: value must be numpy array, got {type(value_)}.") + * cost_fields = ['y_ref', 'yref'] # <<<<<<<<<<<<<< + * constraints_fields = ['lbx', 'ubx', 'lbu', 'ubu'] + * out_fields = ['x', 'u', 'pi', 'lam', 't', 'z', 'sl', 'su'] + */ + __pyx_t_2 = PyList_New(2); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 545, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_INCREF(__pyx_n_u_y_ref); + __Pyx_GIVEREF(__pyx_n_u_y_ref); + if (__Pyx_PyList_SET_ITEM(__pyx_t_2, 0, __pyx_n_u_y_ref)) __PYX_ERR(0, 545, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_yref); + __Pyx_GIVEREF(__pyx_n_u_yref); + if (__Pyx_PyList_SET_ITEM(__pyx_t_2, 1, __pyx_n_u_yref)) __PYX_ERR(0, 545, __pyx_L1_error); + __pyx_v_cost_fields = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":546 + * raise Exception(f"set: value must be numpy array, got {type(value_)}.") + * cost_fields = ['y_ref', 'yref'] + * constraints_fields = ['lbx', 'ubx', 'lbu', 'ubu'] # <<<<<<<<<<<<<< + * out_fields = ['x', 'u', 'pi', 'lam', 't', 'z', 'sl', 'su'] + * mem_fields = ['xdot_guess', 'z_guess'] + */ + __pyx_t_2 = PyList_New(4); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 546, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_INCREF(__pyx_n_u_lbx); + __Pyx_GIVEREF(__pyx_n_u_lbx); + if (__Pyx_PyList_SET_ITEM(__pyx_t_2, 0, __pyx_n_u_lbx)) __PYX_ERR(0, 546, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_ubx); + __Pyx_GIVEREF(__pyx_n_u_ubx); + if (__Pyx_PyList_SET_ITEM(__pyx_t_2, 1, __pyx_n_u_ubx)) __PYX_ERR(0, 546, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_lbu); + __Pyx_GIVEREF(__pyx_n_u_lbu); + if (__Pyx_PyList_SET_ITEM(__pyx_t_2, 2, __pyx_n_u_lbu)) __PYX_ERR(0, 546, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_ubu); + __Pyx_GIVEREF(__pyx_n_u_ubu); + if (__Pyx_PyList_SET_ITEM(__pyx_t_2, 3, __pyx_n_u_ubu)) __PYX_ERR(0, 546, __pyx_L1_error); + __pyx_v_constraints_fields = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":547 + * cost_fields = ['y_ref', 'yref'] + * constraints_fields = ['lbx', 'ubx', 'lbu', 'ubu'] + * out_fields = ['x', 'u', 'pi', 'lam', 't', 'z', 'sl', 'su'] # <<<<<<<<<<<<<< + * mem_fields = ['xdot_guess', 'z_guess'] + * + */ + __pyx_t_2 = PyList_New(8); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 547, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_INCREF(__pyx_n_u_x); + __Pyx_GIVEREF(__pyx_n_u_x); + if (__Pyx_PyList_SET_ITEM(__pyx_t_2, 0, __pyx_n_u_x)) __PYX_ERR(0, 547, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_u); + __Pyx_GIVEREF(__pyx_n_u_u); + if (__Pyx_PyList_SET_ITEM(__pyx_t_2, 1, __pyx_n_u_u)) __PYX_ERR(0, 547, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_pi); + __Pyx_GIVEREF(__pyx_n_u_pi); + if (__Pyx_PyList_SET_ITEM(__pyx_t_2, 2, __pyx_n_u_pi)) __PYX_ERR(0, 547, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_lam); + __Pyx_GIVEREF(__pyx_n_u_lam); + if (__Pyx_PyList_SET_ITEM(__pyx_t_2, 3, __pyx_n_u_lam)) __PYX_ERR(0, 547, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_t); + __Pyx_GIVEREF(__pyx_n_u_t); + if (__Pyx_PyList_SET_ITEM(__pyx_t_2, 4, __pyx_n_u_t)) __PYX_ERR(0, 547, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_z); + __Pyx_GIVEREF(__pyx_n_u_z); + if (__Pyx_PyList_SET_ITEM(__pyx_t_2, 5, __pyx_n_u_z)) __PYX_ERR(0, 547, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_sl); + __Pyx_GIVEREF(__pyx_n_u_sl); + if (__Pyx_PyList_SET_ITEM(__pyx_t_2, 6, __pyx_n_u_sl)) __PYX_ERR(0, 547, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_su); + __Pyx_GIVEREF(__pyx_n_u_su); + if (__Pyx_PyList_SET_ITEM(__pyx_t_2, 7, __pyx_n_u_su)) __PYX_ERR(0, 547, __pyx_L1_error); + __pyx_v_out_fields = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":548 + * constraints_fields = ['lbx', 'ubx', 'lbu', 'ubu'] + * out_fields = ['x', 'u', 'pi', 'lam', 't', 'z', 'sl', 'su'] + * mem_fields = ['xdot_guess', 'z_guess'] # <<<<<<<<<<<<<< + * + * field = field_.encode('utf-8') + */ + __pyx_t_2 = PyList_New(2); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 548, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_INCREF(__pyx_n_u_xdot_guess); + __Pyx_GIVEREF(__pyx_n_u_xdot_guess); + if (__Pyx_PyList_SET_ITEM(__pyx_t_2, 0, __pyx_n_u_xdot_guess)) __PYX_ERR(0, 548, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_z_guess); + __Pyx_GIVEREF(__pyx_n_u_z_guess); + if (__Pyx_PyList_SET_ITEM(__pyx_t_2, 1, __pyx_n_u_z_guess)) __PYX_ERR(0, 548, __pyx_L1_error); + __pyx_v_mem_fields = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":550 + * mem_fields = ['xdot_guess', 'z_guess'] + * + * field = field_.encode('utf-8') # <<<<<<<<<<<<<< + * + * cdef cnp.ndarray[cnp.float64_t, ndim=1] value = np.ascontiguousarray(value_, dtype=np.float64) + */ + if (unlikely(__pyx_v_field_ == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); + __PYX_ERR(0, 550, __pyx_L1_error) + } + __pyx_t_2 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 550, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_v_field = __pyx_t_2; + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":552 + * field = field_.encode('utf-8') + * + * cdef cnp.ndarray[cnp.float64_t, ndim=1] value = np.ascontiguousarray(value_, dtype=np.float64) # <<<<<<<<<<<<<< + * + * # treat parameters separately + */ + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_np); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 552, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 552, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = PyTuple_New(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 552, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_INCREF(__pyx_v_value_); + __Pyx_GIVEREF(__pyx_v_value_); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_v_value_)) __PYX_ERR(0, 552, __pyx_L1_error); + __pyx_t_7 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 552, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_GetModuleGlobalName(__pyx_t_8, __pyx_n_s_np); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 552, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_9 = __Pyx_PyObject_GetAttrStr(__pyx_t_8, __pyx_n_s_float64); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 552, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + if (PyDict_SetItem(__pyx_t_7, __pyx_n_s_dtype, __pyx_t_9) < 0) __PYX_ERR(0, 552, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + __pyx_t_9 = __Pyx_PyObject_Call(__pyx_t_1, __pyx_t_2, __pyx_t_7); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 552, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (!(likely(((__pyx_t_9) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_9, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 552, __pyx_L1_error) + __pyx_t_10 = ((PyArrayObject *)__pyx_t_9); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_value.rcbuffer->pybuffer, (PyObject*)__pyx_t_10, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 1, 0, __pyx_stack) == -1)) { + __pyx_v_value = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_value.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 552, __pyx_L1_error) + } else {__pyx_pybuffernd_value.diminfo[0].strides = __pyx_pybuffernd_value.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_value.diminfo[0].shape = __pyx_pybuffernd_value.rcbuffer->pybuffer.shape[0]; + } + } + __pyx_t_10 = 0; + __pyx_v_value = ((PyArrayObject *)__pyx_t_9); + __pyx_t_9 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":555 + * + * # treat parameters separately + * if field_ == 'p': # <<<<<<<<<<<<<< + * assert acados_solver.acados_update_params(self.capsule, stage, value.data, value.shape[0]) == 0 + * else: + */ + __pyx_t_4 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_p, Py_EQ)); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 555, __pyx_L1_error) + if (__pyx_t_4) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":556 + * # treat parameters separately + * if field_ == 'p': + * assert acados_solver.acados_update_params(self.capsule, stage, value.data, value.shape[0]) == 0 # <<<<<<<<<<<<<< + * else: + * if field_ not in constraints_fields + cost_fields + out_fields: + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_11 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_11 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 556, __pyx_L1_error) + __pyx_t_12 = __pyx_f_5numpy_7ndarray_5shape_shape(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_12 == ((npy_intp *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 556, __pyx_L1_error) + __pyx_t_4 = (long_acados_update_params(__pyx_v_self->capsule, __pyx_v_stage, ((double *)__pyx_t_11), (__pyx_t_12[0])) == 0); + if (unlikely(!__pyx_t_4)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(0, 556, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(0, 556, __pyx_L1_error) + #endif + + /* "acados_template/acados_ocp_solver_pyx.pyx":555 + * + * # treat parameters separately + * if field_ == 'p': # <<<<<<<<<<<<<< + * assert acados_solver.acados_update_params(self.capsule, stage, value.data, value.shape[0]) == 0 + * else: + */ + goto __pyx_L4; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":558 + * assert acados_solver.acados_update_params(self.capsule, stage, value.data, value.shape[0]) == 0 + * else: + * if field_ not in constraints_fields + cost_fields + out_fields: # <<<<<<<<<<<<<< + * raise Exception("AcadosOcpSolverCython.set(): {} is not a valid argument.\ + * \nPossible values are {}.".format(field, \ + */ + /*else*/ { + __pyx_t_9 = PyNumber_Add(__pyx_v_constraints_fields, __pyx_v_cost_fields); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 558, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __pyx_t_7 = PyNumber_Add(__pyx_t_9, __pyx_v_out_fields); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 558, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + __pyx_t_4 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_t_7, Py_NE)); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 558, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely(__pyx_t_4)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":560 + * if field_ not in constraints_fields + cost_fields + out_fields: + * raise Exception("AcadosOcpSolverCython.set(): {} is not a valid argument.\ + * \nPossible values are {}.".format(field, \ # <<<<<<<<<<<<<< + * constraints_fields + cost_fields + out_fields + ['p'])) + * + */ + __pyx_t_9 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_set_is_not, __pyx_n_s_format); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 560, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + + /* "acados_template/acados_ocp_solver_pyx.pyx":561 + * raise Exception("AcadosOcpSolverCython.set(): {} is not a valid argument.\ + * \nPossible values are {}.".format(field, \ + * constraints_fields + cost_fields + out_fields + ['p'])) # <<<<<<<<<<<<<< + * + * dims = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, + */ + __pyx_t_2 = PyNumber_Add(__pyx_v_constraints_fields, __pyx_v_cost_fields); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 561, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_1 = PyNumber_Add(__pyx_t_2, __pyx_v_out_fields); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 561, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = PyList_New(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 561, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_INCREF(__pyx_n_u_p); + __Pyx_GIVEREF(__pyx_n_u_p); + if (__Pyx_PyList_SET_ITEM(__pyx_t_2, 0, __pyx_n_u_p)) __PYX_ERR(0, 561, __pyx_L1_error); + __pyx_t_8 = PyNumber_Add(__pyx_t_1, __pyx_t_2); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 561, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = NULL; + __pyx_t_13 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_9))) { + __pyx_t_2 = PyMethod_GET_SELF(__pyx_t_9); + if (likely(__pyx_t_2)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_9); + __Pyx_INCREF(__pyx_t_2); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_9, function); + __pyx_t_13 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_2, __pyx_v_field, __pyx_t_8}; + __pyx_t_7 = __Pyx_PyObject_FastCall(__pyx_t_9, __pyx_callargs+1-__pyx_t_13, 2+__pyx_t_13); + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 560, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":559 + * else: + * if field_ not in constraints_fields + cost_fields + out_fields: + * raise Exception("AcadosOcpSolverCython.set(): {} is not a valid argument.\ # <<<<<<<<<<<<<< + * \nPossible values are {}.".format(field, \ + * constraints_fields + cost_fields + out_fields + ['p'])) + */ + __pyx_t_9 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_7); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 559, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_Raise(__pyx_t_9, 0, 0, 0); + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + __PYX_ERR(0, 559, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":558 + * assert acados_solver.acados_update_params(self.capsule, stage, value.data, value.shape[0]) == 0 + * else: + * if field_ not in constraints_fields + cost_fields + out_fields: # <<<<<<<<<<<<<< + * raise Exception("AcadosOcpSolverCython.set(): {} is not a valid argument.\ + * \nPossible values are {}.".format(field, \ + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":564 + * + * dims = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, + * self.nlp_dims, self.nlp_out, stage, field) # <<<<<<<<<<<<<< + * + * if value_.shape[0] != dims: + */ + __pyx_t_14 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_14) && PyErr_Occurred())) __PYX_ERR(0, 564, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":563 + * constraints_fields + cost_fields + out_fields + ['p'])) + * + * dims = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, # <<<<<<<<<<<<<< + * self.nlp_dims, self.nlp_out, stage, field) + * + */ + __pyx_t_9 = __Pyx_PyInt_From_int(ocp_nlp_dims_get_from_attr(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_14)); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 563, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __pyx_v_dims = __pyx_t_9; + __pyx_t_9 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":566 + * self.nlp_dims, self.nlp_out, stage, field) + * + * if value_.shape[0] != dims: # <<<<<<<<<<<<<< + * msg = 'AcadosOcpSolverCython.set(): mismatching dimension for field "{}" '.format(field_) + * msg += 'with dimension {} (you have {})'.format(dims, value_.shape[0]) + */ + __pyx_t_9 = __Pyx_PyObject_GetAttrStr(__pyx_v_value_, __pyx_n_s_shape); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 566, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __pyx_t_7 = __Pyx_GetItemInt(__pyx_t_9, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 566, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + __pyx_t_9 = PyObject_RichCompare(__pyx_t_7, __pyx_v_dims, Py_NE); __Pyx_XGOTREF(__pyx_t_9); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 566, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_t_9); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 566, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + if (unlikely(__pyx_t_4)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":567 + * + * if value_.shape[0] != dims: + * msg = 'AcadosOcpSolverCython.set(): mismatching dimension for field "{}" '.format(field_) # <<<<<<<<<<<<<< + * msg += 'with dimension {} (you have {})'.format(dims, value_.shape[0]) + * raise Exception(msg) + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_set_mismat, __pyx_n_s_format); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 567, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_8 = NULL; + __pyx_t_13 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_7))) { + __pyx_t_8 = PyMethod_GET_SELF(__pyx_t_7); + if (likely(__pyx_t_8)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_7); + __Pyx_INCREF(__pyx_t_8); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_7, function); + __pyx_t_13 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_8, __pyx_v_field_}; + __pyx_t_9 = __Pyx_PyObject_FastCall(__pyx_t_7, __pyx_callargs+1-__pyx_t_13, 1+__pyx_t_13); + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 567, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + } + __pyx_v_msg = __pyx_t_9; + __pyx_t_9 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":568 + * if value_.shape[0] != dims: + * msg = 'AcadosOcpSolverCython.set(): mismatching dimension for field "{}" '.format(field_) + * msg += 'with dimension {} (you have {})'.format(dims, value_.shape[0]) # <<<<<<<<<<<<<< + * raise Exception(msg) + * + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_with_dimension_you_have, __pyx_n_s_format); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 568, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_value_, __pyx_n_s_shape); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 568, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_2 = __Pyx_GetItemInt(__pyx_t_8, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 568, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_t_8 = NULL; + __pyx_t_13 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_7))) { + __pyx_t_8 = PyMethod_GET_SELF(__pyx_t_7); + if (likely(__pyx_t_8)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_7); + __Pyx_INCREF(__pyx_t_8); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_7, function); + __pyx_t_13 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_8, __pyx_v_dims, __pyx_t_2}; + __pyx_t_9 = __Pyx_PyObject_FastCall(__pyx_t_7, __pyx_callargs+1-__pyx_t_13, 2+__pyx_t_13); + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 568, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + } + __pyx_t_7 = PyNumber_InPlaceAdd(__pyx_v_msg, __pyx_t_9); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 568, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + __Pyx_DECREF_SET(__pyx_v_msg, __pyx_t_7); + __pyx_t_7 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":569 + * msg = 'AcadosOcpSolverCython.set(): mismatching dimension for field "{}" '.format(field_) + * msg += 'with dimension {} (you have {})'.format(dims, value_.shape[0]) + * raise Exception(msg) # <<<<<<<<<<<<<< + * + * if field_ in constraints_fields: + */ + __pyx_t_7 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_v_msg); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 569, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_Raise(__pyx_t_7, 0, 0, 0); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __PYX_ERR(0, 569, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":566 + * self.nlp_dims, self.nlp_out, stage, field) + * + * if value_.shape[0] != dims: # <<<<<<<<<<<<<< + * msg = 'AcadosOcpSolverCython.set(): mismatching dimension for field "{}" '.format(field_) + * msg += 'with dimension {} (you have {})'.format(dims, value_.shape[0]) + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":571 + * raise Exception(msg) + * + * if field_ in constraints_fields: # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, + * self.nlp_dims, self.nlp_in, stage, field, value.data) + */ + __pyx_t_4 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_constraints_fields, Py_EQ)); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 571, __pyx_L1_error) + if (__pyx_t_4) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":573 + * if field_ in constraints_fields: + * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, + * self.nlp_dims, self.nlp_in, stage, field, value.data) # <<<<<<<<<<<<<< + * elif field_ in cost_fields: + * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, + */ + __pyx_t_15 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_15) && PyErr_Occurred())) __PYX_ERR(0, 573, __pyx_L1_error) + __pyx_t_11 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_11 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 573, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":572 + * + * if field_ in constraints_fields: + * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, # <<<<<<<<<<<<<< + * self.nlp_dims, self.nlp_in, stage, field, value.data) + * elif field_ in cost_fields: + */ + (void)(ocp_nlp_constraints_model_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_in, __pyx_v_stage, __pyx_t_15, ((void *)__pyx_t_11))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":571 + * raise Exception(msg) + * + * if field_ in constraints_fields: # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, + * self.nlp_dims, self.nlp_in, stage, field, value.data) + */ + goto __pyx_L7; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":574 + * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, + * self.nlp_dims, self.nlp_in, stage, field, value.data) + * elif field_ in cost_fields: # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, + * self.nlp_dims, self.nlp_in, stage, field, value.data) + */ + __pyx_t_4 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_cost_fields, Py_EQ)); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 574, __pyx_L1_error) + if (__pyx_t_4) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":576 + * elif field_ in cost_fields: + * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, + * self.nlp_dims, self.nlp_in, stage, field, value.data) # <<<<<<<<<<<<<< + * elif field_ in out_fields: + * acados_solver_common.ocp_nlp_out_set(self.nlp_config, + */ + __pyx_t_16 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_16) && PyErr_Occurred())) __PYX_ERR(0, 576, __pyx_L1_error) + __pyx_t_11 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_11 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 576, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":575 + * self.nlp_dims, self.nlp_in, stage, field, value.data) + * elif field_ in cost_fields: + * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, # <<<<<<<<<<<<<< + * self.nlp_dims, self.nlp_in, stage, field, value.data) + * elif field_ in out_fields: + */ + (void)(ocp_nlp_cost_model_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_in, __pyx_v_stage, __pyx_t_16, ((void *)__pyx_t_11))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":574 + * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, + * self.nlp_dims, self.nlp_in, stage, field, value.data) + * elif field_ in cost_fields: # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, + * self.nlp_dims, self.nlp_in, stage, field, value.data) + */ + goto __pyx_L7; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":577 + * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, + * self.nlp_dims, self.nlp_in, stage, field, value.data) + * elif field_ in out_fields: # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_out_set(self.nlp_config, + * self.nlp_dims, self.nlp_out, stage, field, value.data) + */ + __pyx_t_4 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_out_fields, Py_EQ)); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 577, __pyx_L1_error) + if (__pyx_t_4) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":579 + * elif field_ in out_fields: + * acados_solver_common.ocp_nlp_out_set(self.nlp_config, + * self.nlp_dims, self.nlp_out, stage, field, value.data) # <<<<<<<<<<<<<< + * elif field_ in mem_fields: + * acados_solver_common.ocp_nlp_set(self.nlp_config, \ + */ + __pyx_t_17 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_17) && PyErr_Occurred())) __PYX_ERR(0, 579, __pyx_L1_error) + __pyx_t_11 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_11 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 579, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":578 + * self.nlp_dims, self.nlp_in, stage, field, value.data) + * elif field_ in out_fields: + * acados_solver_common.ocp_nlp_out_set(self.nlp_config, # <<<<<<<<<<<<<< + * self.nlp_dims, self.nlp_out, stage, field, value.data) + * elif field_ in mem_fields: + */ + ocp_nlp_out_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_17, ((void *)__pyx_t_11)); + + /* "acados_template/acados_ocp_solver_pyx.pyx":577 + * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, + * self.nlp_dims, self.nlp_in, stage, field, value.data) + * elif field_ in out_fields: # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_out_set(self.nlp_config, + * self.nlp_dims, self.nlp_out, stage, field, value.data) + */ + goto __pyx_L7; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":580 + * acados_solver_common.ocp_nlp_out_set(self.nlp_config, + * self.nlp_dims, self.nlp_out, stage, field, value.data) + * elif field_ in mem_fields: # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_set(self.nlp_config, \ + * self.nlp_solver, stage, field, value.data) + */ + __pyx_t_4 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_mem_fields, Py_EQ)); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 580, __pyx_L1_error) + if (__pyx_t_4) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":582 + * elif field_ in mem_fields: + * acados_solver_common.ocp_nlp_set(self.nlp_config, \ + * self.nlp_solver, stage, field, value.data) # <<<<<<<<<<<<<< + * + * if field_ == 'z': + */ + __pyx_t_18 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_18) && PyErr_Occurred())) __PYX_ERR(0, 582, __pyx_L1_error) + __pyx_t_11 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_11 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 582, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":581 + * self.nlp_dims, self.nlp_out, stage, field, value.data) + * elif field_ in mem_fields: + * acados_solver_common.ocp_nlp_set(self.nlp_config, \ # <<<<<<<<<<<<<< + * self.nlp_solver, stage, field, value.data) + * + */ + ocp_nlp_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_v_stage, __pyx_t_18, ((void *)__pyx_t_11)); + + /* "acados_template/acados_ocp_solver_pyx.pyx":580 + * acados_solver_common.ocp_nlp_out_set(self.nlp_config, + * self.nlp_dims, self.nlp_out, stage, field, value.data) + * elif field_ in mem_fields: # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_set(self.nlp_config, \ + * self.nlp_solver, stage, field, value.data) + */ + } + __pyx_L7:; + + /* "acados_template/acados_ocp_solver_pyx.pyx":584 + * self.nlp_solver, stage, field, value.data) + * + * if field_ == 'z': # <<<<<<<<<<<<<< + * field = 'z_guess'.encode('utf-8') + * acados_solver_common.ocp_nlp_set(self.nlp_config, \ + */ + __pyx_t_4 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_z, Py_EQ)); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 584, __pyx_L1_error) + if (__pyx_t_4) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":585 + * + * if field_ == 'z': + * field = 'z_guess'.encode('utf-8') # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_set(self.nlp_config, \ + * self.nlp_solver, stage, field, value.data) + */ + __Pyx_INCREF(__pyx_n_b_z_guess); + __Pyx_DECREF_SET(__pyx_v_field, __pyx_n_b_z_guess); + + /* "acados_template/acados_ocp_solver_pyx.pyx":587 + * field = 'z_guess'.encode('utf-8') + * acados_solver_common.ocp_nlp_set(self.nlp_config, \ + * self.nlp_solver, stage, field, value.data) # <<<<<<<<<<<<<< + * return + * + */ + __pyx_t_18 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_18) && PyErr_Occurred())) __PYX_ERR(0, 587, __pyx_L1_error) + __pyx_t_11 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_11 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 587, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":586 + * if field_ == 'z': + * field = 'z_guess'.encode('utf-8') + * acados_solver_common.ocp_nlp_set(self.nlp_config, \ # <<<<<<<<<<<<<< + * self.nlp_solver, stage, field, value.data) + * return + */ + ocp_nlp_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_solver, __pyx_v_stage, __pyx_t_18, ((void *)__pyx_t_11)); + + /* "acados_template/acados_ocp_solver_pyx.pyx":584 + * self.nlp_solver, stage, field, value.data) + * + * if field_ == 'z': # <<<<<<<<<<<<<< + * field = 'z_guess'.encode('utf-8') + * acados_solver_common.ocp_nlp_set(self.nlp_config, \ + */ + } + } + __pyx_L4:; + + /* "acados_template/acados_ocp_solver_pyx.pyx":588 + * acados_solver_common.ocp_nlp_set(self.nlp_config, \ + * self.nlp_solver, stage, field, value.data) + * return # <<<<<<<<<<<<<< + * + * def cost_set(self, int stage, str field_, value_): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":524 + * + * # Note: this function should not be used anymore, better use cost_set, constraints_set + * def set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * + * """ + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_XDECREF(__pyx_t_9); + { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_value.rcbuffer->pybuffer); + __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.set", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + goto __pyx_L2; + __pyx_L0:; + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_value.rcbuffer->pybuffer); + __pyx_L2:; + __Pyx_XDECREF(__pyx_v_cost_fields); + __Pyx_XDECREF(__pyx_v_constraints_fields); + __Pyx_XDECREF(__pyx_v_out_fields); + __Pyx_XDECREF(__pyx_v_mem_fields); + __Pyx_XDECREF(__pyx_v_field); + __Pyx_XDECREF((PyObject *)__pyx_v_value); + __Pyx_XDECREF(__pyx_v_dims); + __Pyx_XDECREF(__pyx_v_msg); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":590 + * return + * + * def cost_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set numerical data in the cost module of the solver. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41cost_set(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40cost_set, "\n Set numerical data in the cost module of the solver.\n\n :param stage: integer corresponding to shooting node\n :param field: string, e.g. 'yref', 'W', 'ext_cost_num_hess'\n :param value: of appropriate size\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41cost_set = {"cost_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41cost_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40cost_set}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41cost_set(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + int __pyx_v_stage; + PyObject *__pyx_v_field_ = 0; + PyObject *__pyx_v_value_ = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("cost_set (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_stage,&__pyx_n_s_field_2,&__pyx_n_s_value,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stage)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 590, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field_2)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 590, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("cost_set", 1, 3, 3, 1); __PYX_ERR(0, 590, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_value)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 590, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("cost_set", 1, 3, 3, 2); __PYX_ERR(0, 590, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "cost_set") < 0)) __PYX_ERR(0, 590, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + } + __pyx_v_stage = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_stage == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 590, __pyx_L3_error) + __pyx_v_field_ = ((PyObject*)values[1]); + __pyx_v_value_ = values[2]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("cost_set", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 590, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.cost_set", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 590, __pyx_L1_error) + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40cost_set(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_stage, __pyx_v_field_, __pyx_v_value_); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = NULL; + __pyx_L0:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40cost_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_) { + PyObject *__pyx_v_field = NULL; + int __pyx_v_dims[2]; + __Pyx_memviewslice __pyx_v_value = { 0, 0, { 0 }, { 0 }, { 0 } }; + PyObject *__pyx_v_value_shape = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_t_3; + int __pyx_t_4; + Py_ssize_t __pyx_t_5; + Py_UCS4 __pyx_t_6; + char const *__pyx_t_7; + PyObject *__pyx_t_8 = NULL; + PyObject *__pyx_t_9 = NULL; + int __pyx_t_10; + __Pyx_memviewslice __pyx_t_11 = { 0, 0, { 0 }, { 0 }, { 0 } }; + char const *__pyx_t_12; + Py_ssize_t __pyx_t_13; + Py_ssize_t __pyx_t_14; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("cost_set", 1); + + /* "acados_template/acados_ocp_solver_pyx.pyx":598 + * :param value: of appropriate size + * """ + * if not isinstance(value_, np.ndarray): # <<<<<<<<<<<<<< + * raise Exception(f"cost_set: value must be numpy array, got {type(value_)}.") + * field = field_.encode('utf-8') + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 598, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_ndarray); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 598, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_3 = PyObject_IsInstance(__pyx_v_value_, __pyx_t_2); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(0, 598, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_4 = (!__pyx_t_3); + if (unlikely(__pyx_t_4)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":599 + * """ + * if not isinstance(value_, np.ndarray): + * raise Exception(f"cost_set: value must be numpy array, got {type(value_)}.") # <<<<<<<<<<<<<< + * field = field_.encode('utf-8') + * + */ + __pyx_t_2 = PyTuple_New(3); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 599, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_5 = 0; + __pyx_t_6 = 127; + __Pyx_INCREF(__pyx_kp_u_cost_set_value_must_be_numpy_arr); + __pyx_t_5 += 41; + __Pyx_GIVEREF(__pyx_kp_u_cost_set_value_must_be_numpy_arr); + PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_kp_u_cost_set_value_must_be_numpy_arr); + __pyx_t_1 = __Pyx_PyObject_FormatSimple(((PyObject *)Py_TYPE(__pyx_v_value_)), __pyx_empty_unicode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 599, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_2, 1, __pyx_t_1); + __pyx_t_1 = 0; + __Pyx_INCREF(__pyx_kp_u__2); + __pyx_t_5 += 1; + __Pyx_GIVEREF(__pyx_kp_u__2); + PyTuple_SET_ITEM(__pyx_t_2, 2, __pyx_kp_u__2); + __pyx_t_1 = __Pyx_PyUnicode_Join(__pyx_t_2, 3, __pyx_t_5, __pyx_t_6); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 599, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 599, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 599, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":598 + * :param value: of appropriate size + * """ + * if not isinstance(value_, np.ndarray): # <<<<<<<<<<<<<< + * raise Exception(f"cost_set: value must be numpy array, got {type(value_)}.") + * field = field_.encode('utf-8') + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":600 + * if not isinstance(value_, np.ndarray): + * raise Exception(f"cost_set: value must be numpy array, got {type(value_)}.") + * field = field_.encode('utf-8') # <<<<<<<<<<<<<< + * + * cdef int dims[2] + */ + if (unlikely(__pyx_v_field_ == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); + __PYX_ERR(0, 600, __pyx_L1_error) + } + __pyx_t_2 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 600, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_v_field = __pyx_t_2; + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":604 + * cdef int dims[2] + * acados_solver_common.ocp_nlp_cost_dims_get_from_attr(self.nlp_config, \ + * self.nlp_dims, self.nlp_out, stage, field, &dims[0]) # <<<<<<<<<<<<<< + * + * cdef double[::1,:] value + */ + __pyx_t_7 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 604, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":603 + * + * cdef int dims[2] + * acados_solver_common.ocp_nlp_cost_dims_get_from_attr(self.nlp_config, \ # <<<<<<<<<<<<<< + * self.nlp_dims, self.nlp_out, stage, field, &dims[0]) + * + */ + ocp_nlp_cost_dims_get_from_attr(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_7, (&(__pyx_v_dims[0]))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":608 + * cdef double[::1,:] value + * + * value_shape = value_.shape # <<<<<<<<<<<<<< + * if len(value_shape) == 1: + * value_shape = (value_shape[0], 0) + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_value_, __pyx_n_s_shape); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 608, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_v_value_shape = __pyx_t_2; + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":609 + * + * value_shape = value_.shape + * if len(value_shape) == 1: # <<<<<<<<<<<<<< + * value_shape = (value_shape[0], 0) + * value = np.asfortranarray(value_[None,:]) + */ + __pyx_t_5 = PyObject_Length(__pyx_v_value_shape); if (unlikely(__pyx_t_5 == ((Py_ssize_t)-1))) __PYX_ERR(0, 609, __pyx_L1_error) + __pyx_t_4 = (__pyx_t_5 == 1); + if (__pyx_t_4) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":610 + * value_shape = value_.shape + * if len(value_shape) == 1: + * value_shape = (value_shape[0], 0) # <<<<<<<<<<<<<< + * value = np.asfortranarray(value_[None,:]) + * + */ + __pyx_t_2 = __Pyx_GetItemInt(__pyx_v_value_shape, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 610, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_1 = PyTuple_New(2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 610, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_t_2)) __PYX_ERR(0, 610, __pyx_L1_error); + __Pyx_INCREF(__pyx_int_0); + __Pyx_GIVEREF(__pyx_int_0); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_int_0)) __PYX_ERR(0, 610, __pyx_L1_error); + __pyx_t_2 = 0; + __Pyx_DECREF_SET(__pyx_v_value_shape, __pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":611 + * if len(value_shape) == 1: + * value_shape = (value_shape[0], 0) + * value = np.asfortranarray(value_[None,:]) # <<<<<<<<<<<<<< + * + * elif len(value_shape) == 2: + */ + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_np); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 611, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_asfortranarray); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 611, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_v_value_, __pyx_tuple__28); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 611, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_9 = NULL; + __pyx_t_10 = 0; + #if CYTHON_UNPACK_METHODS + if (unlikely(PyMethod_Check(__pyx_t_8))) { + __pyx_t_9 = PyMethod_GET_SELF(__pyx_t_8); + if (likely(__pyx_t_9)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_8); + __Pyx_INCREF(__pyx_t_9); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_8, function); + __pyx_t_10 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_9, __pyx_t_2}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_8, __pyx_callargs+1-__pyx_t_10, 1+__pyx_t_10); + __Pyx_XDECREF(__pyx_t_9); __pyx_t_9 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 611, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } + __pyx_t_11 = __Pyx_PyObject_to_MemoryviewSlice_dcd__double(__pyx_t_1, PyBUF_WRITABLE); if (unlikely(!__pyx_t_11.memview)) __PYX_ERR(0, 611, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_value = __pyx_t_11; + __pyx_t_11.memview = NULL; + __pyx_t_11.data = NULL; + + /* "acados_template/acados_ocp_solver_pyx.pyx":609 + * + * value_shape = value_.shape + * if len(value_shape) == 1: # <<<<<<<<<<<<<< + * value_shape = (value_shape[0], 0) + * value = np.asfortranarray(value_[None,:]) + */ + goto __pyx_L4; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":613 + * value = np.asfortranarray(value_[None,:]) + * + * elif len(value_shape) == 2: # <<<<<<<<<<<<<< + * # Get elements in column major order + * value = np.asfortranarray(value_) + */ + __pyx_t_5 = PyObject_Length(__pyx_v_value_shape); if (unlikely(__pyx_t_5 == ((Py_ssize_t)-1))) __PYX_ERR(0, 613, __pyx_L1_error) + __pyx_t_4 = (__pyx_t_5 == 2); + if (__pyx_t_4) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":615 + * elif len(value_shape) == 2: + * # Get elements in column major order + * value = np.asfortranarray(value_) # <<<<<<<<<<<<<< + * + * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: + */ + __Pyx_GetModuleGlobalName(__pyx_t_8, __pyx_n_s_np); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 615, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_8, __pyx_n_s_asfortranarray); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 615, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_t_8 = NULL; + __pyx_t_10 = 0; + #if CYTHON_UNPACK_METHODS + if (unlikely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_8 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_8)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_8); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_10 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_8, __pyx_v_value_}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_10, 1+__pyx_t_10); + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 615, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_t_11 = __Pyx_PyObject_to_MemoryviewSlice_dcd__double(__pyx_t_1, PyBUF_WRITABLE); if (unlikely(!__pyx_t_11.memview)) __PYX_ERR(0, 615, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_value = __pyx_t_11; + __pyx_t_11.memview = NULL; + __pyx_t_11.data = NULL; + + /* "acados_template/acados_ocp_solver_pyx.pyx":613 + * value = np.asfortranarray(value_[None,:]) + * + * elif len(value_shape) == 2: # <<<<<<<<<<<<<< + * # Get elements in column major order + * value = np.asfortranarray(value_) + */ + } + __pyx_L4:; + + /* "acados_template/acados_ocp_solver_pyx.pyx":617 + * value = np.asfortranarray(value_) + * + * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.cost_set(): mismatching dimension' + + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') + */ + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_value_shape, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyInt_From_int((__pyx_v_dims[0])); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_8 = PyObject_RichCompare(__pyx_t_1, __pyx_t_2, Py_NE); __Pyx_XGOTREF(__pyx_t_8); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_3 = __Pyx_PyObject_IsTrue(__pyx_t_8); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + if (!__pyx_t_3) { + } else { + __pyx_t_4 = __pyx_t_3; + goto __pyx_L6_bool_binop_done; + } + __pyx_t_8 = __Pyx_GetItemInt(__pyx_v_value_shape, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_2 = __Pyx_PyInt_From_int((__pyx_v_dims[1])); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_1 = PyObject_RichCompare(__pyx_t_8, __pyx_t_2, Py_NE); __Pyx_XGOTREF(__pyx_t_1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_3 = __Pyx_PyObject_IsTrue(__pyx_t_1); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_4 = __pyx_t_3; + __pyx_L6_bool_binop_done:; + if (unlikely(__pyx_t_4)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":619 + * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: + * raise Exception('AcadosOcpSolverCython.cost_set(): mismatching dimension' + + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') # <<<<<<<<<<<<<< + * + * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, \ + */ + __pyx_t_1 = PyTuple_New(9); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 619, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = 0; + __pyx_t_6 = 127; + __Pyx_INCREF(__pyx_kp_u_for_field); + __pyx_t_5 += 12; + __Pyx_GIVEREF(__pyx_kp_u_for_field); + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_kp_u_for_field); + __pyx_t_2 = __Pyx_PyUnicode_Unicode(__pyx_v_field_); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 619, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_t_2); + __pyx_t_2 = 0; + __Pyx_INCREF(__pyx_kp_u_at_stage); + __pyx_t_5 += 11; + __Pyx_GIVEREF(__pyx_kp_u_at_stage); + PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_kp_u_at_stage); + __pyx_t_2 = __Pyx_PyUnicode_From_int(__pyx_v_stage, 0, ' ', 'd'); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 619, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_1, 3, __pyx_t_2); + __pyx_t_2 = 0; + __Pyx_INCREF(__pyx_kp_u_with_dimension); + __pyx_t_5 += 16; + __Pyx_GIVEREF(__pyx_kp_u_with_dimension); + PyTuple_SET_ITEM(__pyx_t_1, 4, __pyx_kp_u_with_dimension); + __pyx_t_2 = __Pyx_carray_to_py_int(__pyx_v_dims, 2); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 619, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_8 = __Pyx_PySequence_Tuple(__pyx_t_2); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 619, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_FormatSimple(__pyx_t_8, __pyx_empty_unicode); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 619, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_1, 5, __pyx_t_2); + __pyx_t_2 = 0; + __Pyx_INCREF(__pyx_kp_u_you_have); + __pyx_t_5 += 11; + __Pyx_GIVEREF(__pyx_kp_u_you_have); + PyTuple_SET_ITEM(__pyx_t_1, 6, __pyx_kp_u_you_have); + __pyx_t_2 = __Pyx_PyObject_FormatSimple(__pyx_v_value_shape, __pyx_empty_unicode); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 619, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_1, 7, __pyx_t_2); + __pyx_t_2 = 0; + __Pyx_INCREF(__pyx_kp_u__7); + __pyx_t_5 += 1; + __Pyx_GIVEREF(__pyx_kp_u__7); + PyTuple_SET_ITEM(__pyx_t_1, 8, __pyx_kp_u__7); + __pyx_t_2 = __Pyx_PyUnicode_Join(__pyx_t_1, 9, __pyx_t_5, __pyx_t_6); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 619, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":618 + * + * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: + * raise Exception('AcadosOcpSolverCython.cost_set(): mismatching dimension' + # <<<<<<<<<<<<<< + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') + * + */ + __pyx_t_1 = __Pyx_PyUnicode_Concat(__pyx_kp_u_AcadosOcpSolverCython_cost_set_m, __pyx_t_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 618, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 618, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 618, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":617 + * value = np.asfortranarray(value_) + * + * if value_shape[0] != dims[0] or value_shape[1] != dims[1]: # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.cost_set(): mismatching dimension' + + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":622 + * + * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, \ + * self.nlp_dims, self.nlp_in, stage, field, &value[0][0]) # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_12 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_12) && PyErr_Occurred())) __PYX_ERR(0, 622, __pyx_L1_error) + if (unlikely(!__pyx_v_value.memview)) { __Pyx_RaiseUnboundLocalError("value"); __PYX_ERR(0, 622, __pyx_L1_error) } + __pyx_t_13 = 0; + __pyx_t_14 = 0; + __pyx_t_10 = -1; + if (__pyx_t_13 < 0) { + __pyx_t_13 += __pyx_v_value.shape[0]; + if (unlikely(__pyx_t_13 < 0)) __pyx_t_10 = 0; + } else if (unlikely(__pyx_t_13 >= __pyx_v_value.shape[0])) __pyx_t_10 = 0; + if (__pyx_t_14 < 0) { + __pyx_t_14 += __pyx_v_value.shape[1]; + if (unlikely(__pyx_t_14 < 0)) __pyx_t_10 = 1; + } else if (unlikely(__pyx_t_14 >= __pyx_v_value.shape[1])) __pyx_t_10 = 1; + if (unlikely(__pyx_t_10 != -1)) { + __Pyx_RaiseBufferIndexError(__pyx_t_10); + __PYX_ERR(0, 622, __pyx_L1_error) + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":621 + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') + * + * acados_solver_common.ocp_nlp_cost_model_set(self.nlp_config, \ # <<<<<<<<<<<<<< + * self.nlp_dims, self.nlp_in, stage, field, &value[0][0]) + * + */ + (void)(ocp_nlp_cost_model_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_in, __pyx_v_stage, __pyx_t_12, ((void *)(&(*((double *) ( /* dim=1 */ (( /* dim=0 */ ((char *) (((double *) __pyx_v_value.data) + __pyx_t_13)) ) + __pyx_t_14 * __pyx_v_value.strides[1]) ))))))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":590 + * return + * + * def cost_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set numerical data in the cost module of the solver. + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_XDECREF(__pyx_t_9); + __PYX_XCLEAR_MEMVIEW(&__pyx_t_11, 1); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.cost_set", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_field); + __PYX_XCLEAR_MEMVIEW(&__pyx_v_value, 1); + __Pyx_XDECREF(__pyx_v_value_shape); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":625 + * + * + * def constraints_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set numerical data in the constraint module of the solver. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43constraints_set(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42constraints_set, "\n Set numerical data in the constraint module of the solver.\n\n :param stage: integer corresponding to shooting node\n :param field: string in ['lbx', 'ubx', 'lbu', 'ubu', 'lg', 'ug', 'lh', 'uh', 'uphi', 'C', 'D']\n :param value: of appropriate size\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43constraints_set = {"constraints_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43constraints_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42constraints_set}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43constraints_set(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + int __pyx_v_stage; + PyObject *__pyx_v_field_ = 0; + PyObject *__pyx_v_value_ = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("constraints_set (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_stage,&__pyx_n_s_field_2,&__pyx_n_s_value,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stage)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 625, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field_2)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 625, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("constraints_set", 1, 3, 3, 1); __PYX_ERR(0, 625, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_value)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 625, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("constraints_set", 1, 3, 3, 2); __PYX_ERR(0, 625, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "constraints_set") < 0)) __PYX_ERR(0, 625, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + } + __pyx_v_stage = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_stage == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 625, __pyx_L3_error) + __pyx_v_field_ = ((PyObject*)values[1]); + __pyx_v_value_ = values[2]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("constraints_set", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 625, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.constraints_set", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 625, __pyx_L1_error) + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42constraints_set(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_stage, __pyx_v_field_, __pyx_v_value_); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = NULL; + __pyx_L0:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42constraints_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_) { + PyObject *__pyx_v_field = NULL; + int __pyx_v_dims[2]; + __Pyx_memviewslice __pyx_v_value = { 0, 0, { 0 }, { 0 }, { 0 } }; + PyObject *__pyx_v_value_shape = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_t_3; + int __pyx_t_4; + Py_ssize_t __pyx_t_5; + Py_UCS4 __pyx_t_6; + char const *__pyx_t_7; + PyObject *__pyx_t_8 = NULL; + PyObject *__pyx_t_9 = NULL; + int __pyx_t_10; + __Pyx_memviewslice __pyx_t_11 = { 0, 0, { 0 }, { 0 }, { 0 } }; + char const *__pyx_t_12; + Py_ssize_t __pyx_t_13; + Py_ssize_t __pyx_t_14; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("constraints_set", 1); + + /* "acados_template/acados_ocp_solver_pyx.pyx":633 + * :param value: of appropriate size + * """ + * if not isinstance(value_, np.ndarray): # <<<<<<<<<<<<<< + * raise Exception(f"constraints_set: value must be numpy array, got {type(value_)}.") + * + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 633, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_ndarray); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 633, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_3 = PyObject_IsInstance(__pyx_v_value_, __pyx_t_2); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(0, 633, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_4 = (!__pyx_t_3); + if (unlikely(__pyx_t_4)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":634 + * """ + * if not isinstance(value_, np.ndarray): + * raise Exception(f"constraints_set: value must be numpy array, got {type(value_)}.") # <<<<<<<<<<<<<< + * + * field = field_.encode('utf-8') + */ + __pyx_t_2 = PyTuple_New(3); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 634, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_5 = 0; + __pyx_t_6 = 127; + __Pyx_INCREF(__pyx_kp_u_constraints_set_value_must_be_nu); + __pyx_t_5 += 48; + __Pyx_GIVEREF(__pyx_kp_u_constraints_set_value_must_be_nu); + PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_kp_u_constraints_set_value_must_be_nu); + __pyx_t_1 = __Pyx_PyObject_FormatSimple(((PyObject *)Py_TYPE(__pyx_v_value_)), __pyx_empty_unicode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 634, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_1) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + PyTuple_SET_ITEM(__pyx_t_2, 1, __pyx_t_1); + __pyx_t_1 = 0; + __Pyx_INCREF(__pyx_kp_u__2); + __pyx_t_5 += 1; + __Pyx_GIVEREF(__pyx_kp_u__2); + PyTuple_SET_ITEM(__pyx_t_2, 2, __pyx_kp_u__2); + __pyx_t_1 = __Pyx_PyUnicode_Join(__pyx_t_2, 3, __pyx_t_5, __pyx_t_6); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 634, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 634, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 634, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":633 + * :param value: of appropriate size + * """ + * if not isinstance(value_, np.ndarray): # <<<<<<<<<<<<<< + * raise Exception(f"constraints_set: value must be numpy array, got {type(value_)}.") + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":636 + * raise Exception(f"constraints_set: value must be numpy array, got {type(value_)}.") + * + * field = field_.encode('utf-8') # <<<<<<<<<<<<<< + * + * cdef int dims[2] + */ + if (unlikely(__pyx_v_field_ == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); + __PYX_ERR(0, 636, __pyx_L1_error) + } + __pyx_t_2 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 636, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_v_field = __pyx_t_2; + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":640 + * cdef int dims[2] + * acados_solver_common.ocp_nlp_constraint_dims_get_from_attr(self.nlp_config, \ + * self.nlp_dims, self.nlp_out, stage, field, &dims[0]) # <<<<<<<<<<<<<< + * + * cdef double[::1,:] value + */ + __pyx_t_7 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 640, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":639 + * + * cdef int dims[2] + * acados_solver_common.ocp_nlp_constraint_dims_get_from_attr(self.nlp_config, \ # <<<<<<<<<<<<<< + * self.nlp_dims, self.nlp_out, stage, field, &dims[0]) + * + */ + ocp_nlp_constraint_dims_get_from_attr(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_7, (&(__pyx_v_dims[0]))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":644 + * cdef double[::1,:] value + * + * value_shape = value_.shape # <<<<<<<<<<<<<< + * if len(value_shape) == 1: + * value_shape = (value_shape[0], 0) + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_value_, __pyx_n_s_shape); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 644, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_v_value_shape = __pyx_t_2; + __pyx_t_2 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":645 + * + * value_shape = value_.shape + * if len(value_shape) == 1: # <<<<<<<<<<<<<< + * value_shape = (value_shape[0], 0) + * value = np.asfortranarray(value_[None,:]) + */ + __pyx_t_5 = PyObject_Length(__pyx_v_value_shape); if (unlikely(__pyx_t_5 == ((Py_ssize_t)-1))) __PYX_ERR(0, 645, __pyx_L1_error) + __pyx_t_4 = (__pyx_t_5 == 1); + if (__pyx_t_4) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":646 + * value_shape = value_.shape + * if len(value_shape) == 1: + * value_shape = (value_shape[0], 0) # <<<<<<<<<<<<<< + * value = np.asfortranarray(value_[None,:]) + * + */ + __pyx_t_2 = __Pyx_GetItemInt(__pyx_v_value_shape, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 646, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_1 = PyTuple_New(2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 646, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_t_2)) __PYX_ERR(0, 646, __pyx_L1_error); + __Pyx_INCREF(__pyx_int_0); + __Pyx_GIVEREF(__pyx_int_0); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_int_0)) __PYX_ERR(0, 646, __pyx_L1_error); + __pyx_t_2 = 0; + __Pyx_DECREF_SET(__pyx_v_value_shape, __pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":647 + * if len(value_shape) == 1: + * value_shape = (value_shape[0], 0) + * value = np.asfortranarray(value_[None,:]) # <<<<<<<<<<<<<< + * + * elif len(value_shape) == 2: + */ + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_np); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 647, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_asfortranarray); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 647, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_v_value_, __pyx_tuple__28); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 647, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_9 = NULL; + __pyx_t_10 = 0; + #if CYTHON_UNPACK_METHODS + if (unlikely(PyMethod_Check(__pyx_t_8))) { + __pyx_t_9 = PyMethod_GET_SELF(__pyx_t_8); + if (likely(__pyx_t_9)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_8); + __Pyx_INCREF(__pyx_t_9); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_8, function); + __pyx_t_10 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_9, __pyx_t_2}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_8, __pyx_callargs+1-__pyx_t_10, 1+__pyx_t_10); + __Pyx_XDECREF(__pyx_t_9); __pyx_t_9 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 647, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } + __pyx_t_11 = __Pyx_PyObject_to_MemoryviewSlice_dcd__double(__pyx_t_1, PyBUF_WRITABLE); if (unlikely(!__pyx_t_11.memview)) __PYX_ERR(0, 647, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_value = __pyx_t_11; + __pyx_t_11.memview = NULL; + __pyx_t_11.data = NULL; + + /* "acados_template/acados_ocp_solver_pyx.pyx":645 + * + * value_shape = value_.shape + * if len(value_shape) == 1: # <<<<<<<<<<<<<< + * value_shape = (value_shape[0], 0) + * value = np.asfortranarray(value_[None,:]) + */ + goto __pyx_L4; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":649 + * value = np.asfortranarray(value_[None,:]) + * + * elif len(value_shape) == 2: # <<<<<<<<<<<<<< + * # Get elements in column major order + * value = np.asfortranarray(value_) + */ + __pyx_t_5 = PyObject_Length(__pyx_v_value_shape); if (unlikely(__pyx_t_5 == ((Py_ssize_t)-1))) __PYX_ERR(0, 649, __pyx_L1_error) + __pyx_t_4 = (__pyx_t_5 == 2); + if (__pyx_t_4) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":651 + * elif len(value_shape) == 2: + * # Get elements in column major order + * value = np.asfortranarray(value_) # <<<<<<<<<<<<<< + * + * if value_shape != tuple(dims): + */ + __Pyx_GetModuleGlobalName(__pyx_t_8, __pyx_n_s_np); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 651, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_8, __pyx_n_s_asfortranarray); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 651, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_t_8 = NULL; + __pyx_t_10 = 0; + #if CYTHON_UNPACK_METHODS + if (unlikely(PyMethod_Check(__pyx_t_2))) { + __pyx_t_8 = PyMethod_GET_SELF(__pyx_t_2); + if (likely(__pyx_t_8)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_2); + __Pyx_INCREF(__pyx_t_8); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_2, function); + __pyx_t_10 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_8, __pyx_v_value_}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_2, __pyx_callargs+1-__pyx_t_10, 1+__pyx_t_10); + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 651, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } + __pyx_t_11 = __Pyx_PyObject_to_MemoryviewSlice_dcd__double(__pyx_t_1, PyBUF_WRITABLE); if (unlikely(!__pyx_t_11.memview)) __PYX_ERR(0, 651, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_v_value = __pyx_t_11; + __pyx_t_11.memview = NULL; + __pyx_t_11.data = NULL; + + /* "acados_template/acados_ocp_solver_pyx.pyx":649 + * value = np.asfortranarray(value_[None,:]) + * + * elif len(value_shape) == 2: # <<<<<<<<<<<<<< + * # Get elements in column major order + * value = np.asfortranarray(value_) + */ + } + __pyx_L4:; + + /* "acados_template/acados_ocp_solver_pyx.pyx":653 + * value = np.asfortranarray(value_) + * + * if value_shape != tuple(dims): # <<<<<<<<<<<<<< + * raise Exception(f'AcadosOcpSolverCython.constraints_set(): mismatching dimension' + + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') + */ + __pyx_t_1 = __Pyx_carray_to_py_int(__pyx_v_dims, 2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 653, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PySequence_Tuple(__pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 653, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = PyObject_RichCompare(__pyx_v_value_shape, __pyx_t_2, Py_NE); __Pyx_XGOTREF(__pyx_t_1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 653, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_t_1); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 653, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(__pyx_t_4)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":655 + * if value_shape != tuple(dims): + * raise Exception(f'AcadosOcpSolverCython.constraints_set(): mismatching dimension' + + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') # <<<<<<<<<<<<<< + * + * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, \ + */ + __pyx_t_1 = PyTuple_New(9); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 655, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = 0; + __pyx_t_6 = 127; + __Pyx_INCREF(__pyx_kp_u_for_field); + __pyx_t_5 += 12; + __Pyx_GIVEREF(__pyx_kp_u_for_field); + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_kp_u_for_field); + __pyx_t_2 = __Pyx_PyUnicode_Unicode(__pyx_v_field_); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 655, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_t_2); + __pyx_t_2 = 0; + __Pyx_INCREF(__pyx_kp_u_at_stage); + __pyx_t_5 += 11; + __Pyx_GIVEREF(__pyx_kp_u_at_stage); + PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_kp_u_at_stage); + __pyx_t_2 = __Pyx_PyUnicode_From_int(__pyx_v_stage, 0, ' ', 'd'); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 655, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_1, 3, __pyx_t_2); + __pyx_t_2 = 0; + __Pyx_INCREF(__pyx_kp_u_with_dimension); + __pyx_t_5 += 16; + __Pyx_GIVEREF(__pyx_kp_u_with_dimension); + PyTuple_SET_ITEM(__pyx_t_1, 4, __pyx_kp_u_with_dimension); + __pyx_t_2 = __Pyx_carray_to_py_int(__pyx_v_dims, 2); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 655, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_8 = __Pyx_PySequence_Tuple(__pyx_t_2); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 655, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_FormatSimple(__pyx_t_8, __pyx_empty_unicode); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 655, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_1, 5, __pyx_t_2); + __pyx_t_2 = 0; + __Pyx_INCREF(__pyx_kp_u_you_have); + __pyx_t_5 += 11; + __Pyx_GIVEREF(__pyx_kp_u_you_have); + PyTuple_SET_ITEM(__pyx_t_1, 6, __pyx_kp_u_you_have); + __pyx_t_2 = __Pyx_PyObject_FormatSimple(__pyx_v_value_shape, __pyx_empty_unicode); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 655, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_1, 7, __pyx_t_2); + __pyx_t_2 = 0; + __Pyx_INCREF(__pyx_kp_u__7); + __pyx_t_5 += 1; + __Pyx_GIVEREF(__pyx_kp_u__7); + PyTuple_SET_ITEM(__pyx_t_1, 8, __pyx_kp_u__7); + __pyx_t_2 = __Pyx_PyUnicode_Join(__pyx_t_1, 9, __pyx_t_5, __pyx_t_6); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 655, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":654 + * + * if value_shape != tuple(dims): + * raise Exception(f'AcadosOcpSolverCython.constraints_set(): mismatching dimension' + # <<<<<<<<<<<<<< + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') + * + */ + __pyx_t_1 = __Pyx_PyUnicode_Concat(__pyx_kp_u_AcadosOcpSolverCython_constraint, __pyx_t_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 654, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 654, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 654, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":653 + * value = np.asfortranarray(value_) + * + * if value_shape != tuple(dims): # <<<<<<<<<<<<<< + * raise Exception(f'AcadosOcpSolverCython.constraints_set(): mismatching dimension' + + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":658 + * + * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, \ + * self.nlp_dims, self.nlp_in, stage, field, &value[0][0]) # <<<<<<<<<<<<<< + * + * return + */ + __pyx_t_12 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_12) && PyErr_Occurred())) __PYX_ERR(0, 658, __pyx_L1_error) + if (unlikely(!__pyx_v_value.memview)) { __Pyx_RaiseUnboundLocalError("value"); __PYX_ERR(0, 658, __pyx_L1_error) } + __pyx_t_13 = 0; + __pyx_t_14 = 0; + __pyx_t_10 = -1; + if (__pyx_t_13 < 0) { + __pyx_t_13 += __pyx_v_value.shape[0]; + if (unlikely(__pyx_t_13 < 0)) __pyx_t_10 = 0; + } else if (unlikely(__pyx_t_13 >= __pyx_v_value.shape[0])) __pyx_t_10 = 0; + if (__pyx_t_14 < 0) { + __pyx_t_14 += __pyx_v_value.shape[1]; + if (unlikely(__pyx_t_14 < 0)) __pyx_t_10 = 1; + } else if (unlikely(__pyx_t_14 >= __pyx_v_value.shape[1])) __pyx_t_10 = 1; + if (unlikely(__pyx_t_10 != -1)) { + __Pyx_RaiseBufferIndexError(__pyx_t_10); + __PYX_ERR(0, 658, __pyx_L1_error) + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":657 + * f' for field "{field_}" at stage {stage} with dimension {tuple(dims)} (you have {value_shape})') + * + * acados_solver_common.ocp_nlp_constraints_model_set(self.nlp_config, \ # <<<<<<<<<<<<<< + * self.nlp_dims, self.nlp_in, stage, field, &value[0][0]) + * + */ + (void)(ocp_nlp_constraints_model_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_in, __pyx_v_stage, __pyx_t_12, ((void *)(&(*((double *) ( /* dim=1 */ (( /* dim=0 */ ((char *) (((double *) __pyx_v_value.data) + __pyx_t_13)) ) + __pyx_t_14 * __pyx_v_value.strides[1]) ))))))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":660 + * self.nlp_dims, self.nlp_in, stage, field, &value[0][0]) + * + * return # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":625 + * + * + * def constraints_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set numerical data in the constraint module of the solver. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_XDECREF(__pyx_t_9); + __PYX_XCLEAR_MEMVIEW(&__pyx_t_11, 1); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.constraints_set", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_field); + __PYX_XCLEAR_MEMVIEW(&__pyx_v_value, 1); + __Pyx_XDECREF(__pyx_v_value_shape); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":663 + * + * + * def get_from_qp_in(self, int stage, str field_): # <<<<<<<<<<<<<< + * """ + * Get numerical data from the dynamics module of the solver: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_45get_from_qp_in(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_44get_from_qp_in, "\n Get numerical data from the dynamics module of the solver:\n\n :param stage: integer corresponding to shooting node\n :param field: string, e.g. 'A'\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_45get_from_qp_in = {"get_from_qp_in", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_45get_from_qp_in, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_44get_from_qp_in}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_45get_from_qp_in(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + int __pyx_v_stage; + PyObject *__pyx_v_field_ = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[2] = {0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("get_from_qp_in (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_stage,&__pyx_n_s_field_2,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stage)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 663, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field_2)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 663, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("get_from_qp_in", 1, 2, 2, 1); __PYX_ERR(0, 663, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "get_from_qp_in") < 0)) __PYX_ERR(0, 663, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 2)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + } + __pyx_v_stage = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_stage == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 663, __pyx_L3_error) + __pyx_v_field_ = ((PyObject*)values[1]); + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("get_from_qp_in", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 663, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.get_from_qp_in", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 663, __pyx_L1_error) + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_44get_from_qp_in(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_stage, __pyx_v_field_); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = NULL; + __pyx_L0:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_44get_from_qp_in(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_field_) { + PyObject *__pyx_v_field = NULL; + int __pyx_v_dims[2]; + PyArrayObject *__pyx_v_out = 0; + __Pyx_LocalBuf_ND __pyx_pybuffernd_out; + __Pyx_Buffer __pyx_pybuffer_out; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + char const *__pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyArrayObject *__pyx_t_6 = NULL; + char const *__pyx_t_7; + char *__pyx_t_8; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_from_qp_in", 1); + __pyx_pybuffer_out.pybuffer.buf = NULL; + __pyx_pybuffer_out.refcount = 0; + __pyx_pybuffernd_out.data = NULL; + __pyx_pybuffernd_out.rcbuffer = &__pyx_pybuffer_out; + + /* "acados_template/acados_ocp_solver_pyx.pyx":670 + * :param field: string, e.g. 'A' + * """ + * field = field_.encode('utf-8') # <<<<<<<<<<<<<< + * + * # get dims + */ + if (unlikely(__pyx_v_field_ == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); + __PYX_ERR(0, 670, __pyx_L1_error) + } + __pyx_t_1 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 670, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_field = __pyx_t_1; + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":674 + * # get dims + * cdef int[2] dims + * acados_solver_common.ocp_nlp_qp_dims_get_from_attr(self.nlp_config, self.nlp_dims, self.nlp_out, stage, field, &dims[0]) # <<<<<<<<<<<<<< + * + * # create output data + */ + __pyx_t_2 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_2) && PyErr_Occurred())) __PYX_ERR(0, 674, __pyx_L1_error) + ocp_nlp_qp_dims_get_from_attr(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_out, __pyx_v_stage, __pyx_t_2, (&(__pyx_v_dims[0]))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":677 + * + * # create output data + * cdef cnp.ndarray[cnp.float64_t, ndim=2] out = np.zeros((dims[0], dims[1]), order='F') # <<<<<<<<<<<<<< + * + * # call getter + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 677, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_zeros); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 677, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyInt_From_int((__pyx_v_dims[0])); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 677, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_4 = __Pyx_PyInt_From_int((__pyx_v_dims[1])); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 677, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = PyTuple_New(2); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 677, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_t_1)) __PYX_ERR(0, 677, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_4); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_4)) __PYX_ERR(0, 677, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_4 = 0; + __pyx_t_4 = PyTuple_New(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 677, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_5); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_5)) __PYX_ERR(0, 677, __pyx_L1_error); + __pyx_t_5 = 0; + __pyx_t_5 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 677, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + if (PyDict_SetItem(__pyx_t_5, __pyx_n_s_order, __pyx_n_u_F) < 0) __PYX_ERR(0, 677, __pyx_L1_error) + __pyx_t_1 = __Pyx_PyObject_Call(__pyx_t_3, __pyx_t_4, __pyx_t_5); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 677, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (!(likely(((__pyx_t_1) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_1, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 677, __pyx_L1_error) + __pyx_t_6 = ((PyArrayObject *)__pyx_t_1); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_out.rcbuffer->pybuffer, (PyObject*)__pyx_t_6, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 2, 0, __pyx_stack) == -1)) { + __pyx_v_out = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_out.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 677, __pyx_L1_error) + } else {__pyx_pybuffernd_out.diminfo[0].strides = __pyx_pybuffernd_out.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_out.diminfo[0].shape = __pyx_pybuffernd_out.rcbuffer->pybuffer.shape[0]; __pyx_pybuffernd_out.diminfo[1].strides = __pyx_pybuffernd_out.rcbuffer->pybuffer.strides[1]; __pyx_pybuffernd_out.diminfo[1].shape = __pyx_pybuffernd_out.rcbuffer->pybuffer.shape[1]; + } + } + __pyx_t_6 = 0; + __pyx_v_out = ((PyArrayObject *)__pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":680 + * + * # call getter + * acados_solver_common.ocp_nlp_get_at_stage(self.nlp_config, self.nlp_dims, self.nlp_solver, stage, field, out.data) # <<<<<<<<<<<<<< + * + * return out + */ + __pyx_t_7 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 680, __pyx_L1_error) + __pyx_t_8 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_out)); if (unlikely(__pyx_t_8 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 680, __pyx_L1_error) + ocp_nlp_get_at_stage(__pyx_v_self->nlp_config, __pyx_v_self->nlp_dims, __pyx_v_self->nlp_solver, __pyx_v_stage, __pyx_t_7, ((void *)__pyx_t_8)); + + /* "acados_template/acados_ocp_solver_pyx.pyx":682 + * acados_solver_common.ocp_nlp_get_at_stage(self.nlp_config, self.nlp_dims, self.nlp_solver, stage, field, out.data) + * + * return out # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_out); + __pyx_r = ((PyObject *)__pyx_v_out); + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":663 + * + * + * def get_from_qp_in(self, int stage, str field_): # <<<<<<<<<<<<<< + * """ + * Get numerical data from the dynamics module of the solver: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_out.rcbuffer->pybuffer); + __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.get_from_qp_in", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + goto __pyx_L2; + __pyx_L0:; + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_out.rcbuffer->pybuffer); + __pyx_L2:; + __Pyx_XDECREF(__pyx_v_field); + __Pyx_XDECREF((PyObject *)__pyx_v_out); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":685 + * + * + * def options_set(self, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set options of the solver. + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47options_set(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_46options_set, "\n Set options of the solver.\n\n :param field: string, e.g. 'print_level', 'rti_phase', 'initialize_t_slacks', 'step_length', 'alpha_min', 'alpha_reduction', 'qp_warm_start', 'line_search_use_sufficient_descent', 'full_step_dual', 'globalization_use_SOC', 'qp_tol_stat', 'qp_tol_eq', 'qp_tol_ineq', 'qp_tol_comp', 'qp_tau_min', 'qp_mu0'\n\n :param value: of type int, float, string\n\n - qp_tol_stat: QP solver tolerance stationarity\n - qp_tol_eq: QP solver tolerance equalities\n - qp_tol_ineq: QP solver tolerance inequalities\n - qp_tol_comp: QP solver tolerance complementarity\n - qp_tau_min: for HPIPM QP solvers: minimum value of barrier parameter in HPIPM\n - qp_mu0: for HPIPM QP solvers: initial value for complementarity slackness\n - warm_start_first_qp: indicates if first QP in SQP is warm_started\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47options_set = {"options_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47options_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_46options_set}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47options_set(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_field_ = 0; + PyObject *__pyx_v_value_ = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[2] = {0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("options_set (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_field_2,&__pyx_n_s_value,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_field_2)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 685, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_value)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 685, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("options_set", 1, 2, 2, 1); __PYX_ERR(0, 685, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "options_set") < 0)) __PYX_ERR(0, 685, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 2)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + } + __pyx_v_field_ = ((PyObject*)values[0]); + __pyx_v_value_ = values[1]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("options_set", 1, 2, 2, __pyx_nargs); __PYX_ERR(0, 685, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.options_set", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_field_), (&PyUnicode_Type), 1, "field_", 1))) __PYX_ERR(0, 685, __pyx_L1_error) + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_46options_set(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_field_, __pyx_v_value_); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = NULL; + __pyx_L0:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_46options_set(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, PyObject *__pyx_v_field_, PyObject *__pyx_v_value_) { + PyObject *__pyx_v_int_fields = NULL; + PyObject *__pyx_v_double_fields = NULL; + PyObject *__pyx_v_string_fields = NULL; + PyObject *__pyx_v_field = NULL; + int __pyx_v_int_value; + double __pyx_v_double_value; + __Pyx_memviewslice __pyx_v_string_value = { 0, 0, { 0 }, { 0 }, { 0 } }; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + int __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + char const *__pyx_t_7; + double __pyx_t_8; + __Pyx_memviewslice __pyx_t_9 = { 0, 0, { 0 }, { 0 }, { 0 } }; + Py_ssize_t __pyx_t_10; + PyObject *__pyx_t_11 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("options_set", 1); + + /* "acados_template/acados_ocp_solver_pyx.pyx":701 + * - warm_start_first_qp: indicates if first QP in SQP is warm_started + * """ + * int_fields = ['print_level', 'rti_phase', 'initialize_t_slacks', 'qp_warm_start', 'line_search_use_sufficient_descent', 'full_step_dual', 'globalization_use_SOC', 'warm_start_first_qp'] # <<<<<<<<<<<<<< + * double_fields = ['step_length', 'tol_eq', 'tol_stat', 'tol_ineq', 'tol_comp', 'alpha_min', 'alpha_reduction', 'eps_sufficient_descent', + * 'qp_tol_stat', 'qp_tol_eq', 'qp_tol_ineq', 'qp_tol_comp', 'qp_tau_min', 'qp_mu0'] + */ + __pyx_t_1 = PyList_New(8); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 701, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_u_print_level); + __Pyx_GIVEREF(__pyx_n_u_print_level); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_u_print_level)) __PYX_ERR(0, 701, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_rti_phase); + __Pyx_GIVEREF(__pyx_n_u_rti_phase); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 1, __pyx_n_u_rti_phase)) __PYX_ERR(0, 701, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_initialize_t_slacks); + __Pyx_GIVEREF(__pyx_n_u_initialize_t_slacks); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 2, __pyx_n_u_initialize_t_slacks)) __PYX_ERR(0, 701, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_qp_warm_start); + __Pyx_GIVEREF(__pyx_n_u_qp_warm_start); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 3, __pyx_n_u_qp_warm_start)) __PYX_ERR(0, 701, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_line_search_use_sufficient_desce); + __Pyx_GIVEREF(__pyx_n_u_line_search_use_sufficient_desce); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 4, __pyx_n_u_line_search_use_sufficient_desce)) __PYX_ERR(0, 701, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_full_step_dual); + __Pyx_GIVEREF(__pyx_n_u_full_step_dual); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 5, __pyx_n_u_full_step_dual)) __PYX_ERR(0, 701, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_globalization_use_SOC); + __Pyx_GIVEREF(__pyx_n_u_globalization_use_SOC); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 6, __pyx_n_u_globalization_use_SOC)) __PYX_ERR(0, 701, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_warm_start_first_qp); + __Pyx_GIVEREF(__pyx_n_u_warm_start_first_qp); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 7, __pyx_n_u_warm_start_first_qp)) __PYX_ERR(0, 701, __pyx_L1_error); + __pyx_v_int_fields = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":702 + * """ + * int_fields = ['print_level', 'rti_phase', 'initialize_t_slacks', 'qp_warm_start', 'line_search_use_sufficient_descent', 'full_step_dual', 'globalization_use_SOC', 'warm_start_first_qp'] + * double_fields = ['step_length', 'tol_eq', 'tol_stat', 'tol_ineq', 'tol_comp', 'alpha_min', 'alpha_reduction', 'eps_sufficient_descent', # <<<<<<<<<<<<<< + * 'qp_tol_stat', 'qp_tol_eq', 'qp_tol_ineq', 'qp_tol_comp', 'qp_tau_min', 'qp_mu0'] + * string_fields = ['globalization'] + */ + __pyx_t_1 = PyList_New(14); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 702, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_u_step_length); + __Pyx_GIVEREF(__pyx_n_u_step_length); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_u_step_length)) __PYX_ERR(0, 702, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_tol_eq); + __Pyx_GIVEREF(__pyx_n_u_tol_eq); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 1, __pyx_n_u_tol_eq)) __PYX_ERR(0, 702, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_tol_stat); + __Pyx_GIVEREF(__pyx_n_u_tol_stat); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 2, __pyx_n_u_tol_stat)) __PYX_ERR(0, 702, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_tol_ineq); + __Pyx_GIVEREF(__pyx_n_u_tol_ineq); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 3, __pyx_n_u_tol_ineq)) __PYX_ERR(0, 702, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_tol_comp); + __Pyx_GIVEREF(__pyx_n_u_tol_comp); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 4, __pyx_n_u_tol_comp)) __PYX_ERR(0, 702, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_alpha_min); + __Pyx_GIVEREF(__pyx_n_u_alpha_min); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 5, __pyx_n_u_alpha_min)) __PYX_ERR(0, 702, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_alpha_reduction); + __Pyx_GIVEREF(__pyx_n_u_alpha_reduction); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 6, __pyx_n_u_alpha_reduction)) __PYX_ERR(0, 702, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_eps_sufficient_descent); + __Pyx_GIVEREF(__pyx_n_u_eps_sufficient_descent); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 7, __pyx_n_u_eps_sufficient_descent)) __PYX_ERR(0, 702, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_qp_tol_stat); + __Pyx_GIVEREF(__pyx_n_u_qp_tol_stat); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 8, __pyx_n_u_qp_tol_stat)) __PYX_ERR(0, 702, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_qp_tol_eq); + __Pyx_GIVEREF(__pyx_n_u_qp_tol_eq); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 9, __pyx_n_u_qp_tol_eq)) __PYX_ERR(0, 702, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_qp_tol_ineq); + __Pyx_GIVEREF(__pyx_n_u_qp_tol_ineq); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 10, __pyx_n_u_qp_tol_ineq)) __PYX_ERR(0, 702, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_qp_tol_comp); + __Pyx_GIVEREF(__pyx_n_u_qp_tol_comp); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 11, __pyx_n_u_qp_tol_comp)) __PYX_ERR(0, 702, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_qp_tau_min); + __Pyx_GIVEREF(__pyx_n_u_qp_tau_min); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 12, __pyx_n_u_qp_tau_min)) __PYX_ERR(0, 702, __pyx_L1_error); + __Pyx_INCREF(__pyx_n_u_qp_mu0); + __Pyx_GIVEREF(__pyx_n_u_qp_mu0); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 13, __pyx_n_u_qp_mu0)) __PYX_ERR(0, 702, __pyx_L1_error); + __pyx_v_double_fields = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":704 + * double_fields = ['step_length', 'tol_eq', 'tol_stat', 'tol_ineq', 'tol_comp', 'alpha_min', 'alpha_reduction', 'eps_sufficient_descent', + * 'qp_tol_stat', 'qp_tol_eq', 'qp_tol_ineq', 'qp_tol_comp', 'qp_tau_min', 'qp_mu0'] + * string_fields = ['globalization'] # <<<<<<<<<<<<<< + * + * # encode + */ + __pyx_t_1 = PyList_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 704, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_u_globalization); + __Pyx_GIVEREF(__pyx_n_u_globalization); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_u_globalization)) __PYX_ERR(0, 704, __pyx_L1_error); + __pyx_v_string_fields = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":707 + * + * # encode + * field = field_.encode('utf-8') # <<<<<<<<<<<<<< + * + * cdef int int_value + */ + if (unlikely(__pyx_v_field_ == Py_None)) { + PyErr_Format(PyExc_AttributeError, "'NoneType' object has no attribute '%.30s'", "encode"); + __PYX_ERR(0, 707, __pyx_L1_error) + } + __pyx_t_1 = PyUnicode_AsUTF8String(__pyx_v_field_); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 707, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_field = __pyx_t_1; + __pyx_t_1 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":714 + * + * # check field availability and type + * if field_ in int_fields: # <<<<<<<<<<<<<< + * if not isinstance(value_, int): + * raise Exception('solver option {} must be of type int. You have {}.'.format(field_, type(value_))) + */ + __pyx_t_2 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_int_fields, Py_EQ)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 714, __pyx_L1_error) + if (__pyx_t_2) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":715 + * # check field availability and type + * if field_ in int_fields: + * if not isinstance(value_, int): # <<<<<<<<<<<<<< + * raise Exception('solver option {} must be of type int. You have {}.'.format(field_, type(value_))) + * + */ + __pyx_t_2 = PyInt_Check(__pyx_v_value_); + __pyx_t_3 = (!__pyx_t_2); + if (unlikely(__pyx_t_3)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":716 + * if field_ in int_fields: + * if not isinstance(value_, int): + * raise Exception('solver option {} must be of type int. You have {}.'.format(field_, type(value_))) # <<<<<<<<<<<<<< + * + * if field_ == 'rti_phase': + */ + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_solver_option_must_be_of_type_in, __pyx_n_s_format); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 716, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_4))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_4); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_4); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_4, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_v_field_, ((PyObject *)Py_TYPE(__pyx_v_value_))}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 716, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + __pyx_t_4 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 716, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_t_4, 0, 0, 0); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __PYX_ERR(0, 716, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":715 + * # check field availability and type + * if field_ in int_fields: + * if not isinstance(value_, int): # <<<<<<<<<<<<<< + * raise Exception('solver option {} must be of type int. You have {}.'.format(field_, type(value_))) + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":718 + * raise Exception('solver option {} must be of type int. You have {}.'.format(field_, type(value_))) + * + * if field_ == 'rti_phase': # <<<<<<<<<<<<<< + * if value_ < 0 or value_ > 2: + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' + */ + __pyx_t_3 = (__Pyx_PyUnicode_Equals(__pyx_v_field_, __pyx_n_u_rti_phase, Py_EQ)); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(0, 718, __pyx_L1_error) + if (__pyx_t_3) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":719 + * + * if field_ == 'rti_phase': + * if value_ < 0 or value_ > 2: # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' + * 'take only values 0, 1, 2 for SQP-RTI-type solvers') + */ + __pyx_t_4 = PyObject_RichCompare(__pyx_v_value_, __pyx_int_0, Py_LT); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 719, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 719, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (!__pyx_t_2) { + } else { + __pyx_t_3 = __pyx_t_2; + goto __pyx_L7_bool_binop_done; + } + __pyx_t_4 = PyObject_RichCompare(__pyx_v_value_, __pyx_int_2, Py_GT); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 719, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 719, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_3 = __pyx_t_2; + __pyx_L7_bool_binop_done:; + if (unlikely(__pyx_t_3)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":720 + * if field_ == 'rti_phase': + * if value_ < 0 or value_ > 2: + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' # <<<<<<<<<<<<<< + * 'take only values 0, 1, 2 for SQP-RTI-type solvers') + * if self.nlp_solver_type != 'SQP_RTI' and value_ > 0: + */ + __pyx_t_4 = __Pyx_PyObject_Call(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_tuple__29, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 720, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_Raise(__pyx_t_4, 0, 0, 0); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __PYX_ERR(0, 720, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":719 + * + * if field_ == 'rti_phase': + * if value_ < 0 or value_ > 2: # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' + * 'take only values 0, 1, 2 for SQP-RTI-type solvers') + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":722 + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' + * 'take only values 0, 1, 2 for SQP-RTI-type solvers') + * if self.nlp_solver_type != 'SQP_RTI' and value_ > 0: # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' + * 'take only value 0 for SQP-type solvers') + */ + __pyx_t_2 = (__Pyx_PyUnicode_Equals(__pyx_v_self->nlp_solver_type, __pyx_n_u_SQP_RTI, Py_NE)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 722, __pyx_L1_error) + if (__pyx_t_2) { + } else { + __pyx_t_3 = __pyx_t_2; + goto __pyx_L10_bool_binop_done; + } + __pyx_t_4 = PyObject_RichCompare(__pyx_v_value_, __pyx_int_0, Py_GT); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 722, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 722, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_3 = __pyx_t_2; + __pyx_L10_bool_binop_done:; + if (unlikely(__pyx_t_3)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":723 + * 'take only values 0, 1, 2 for SQP-RTI-type solvers') + * if self.nlp_solver_type != 'SQP_RTI' and value_ > 0: + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' # <<<<<<<<<<<<<< + * 'take only value 0 for SQP-type solvers') + * + */ + __pyx_t_4 = __Pyx_PyObject_Call(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_tuple__30, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 723, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_Raise(__pyx_t_4, 0, 0, 0); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __PYX_ERR(0, 723, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":722 + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' + * 'take only values 0, 1, 2 for SQP-RTI-type solvers') + * if self.nlp_solver_type != 'SQP_RTI' and value_ > 0: # <<<<<<<<<<<<<< + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' + * 'take only value 0 for SQP-type solvers') + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":718 + * raise Exception('solver option {} must be of type int. You have {}.'.format(field_, type(value_))) + * + * if field_ == 'rti_phase': # <<<<<<<<<<<<<< + * if value_ < 0 or value_ > 2: + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":726 + * 'take only value 0 for SQP-type solvers') + * + * int_value = value_ # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &int_value) + * + */ + __pyx_t_6 = __Pyx_PyInt_As_int(__pyx_v_value_); if (unlikely((__pyx_t_6 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 726, __pyx_L1_error) + __pyx_v_int_value = __pyx_t_6; + + /* "acados_template/acados_ocp_solver_pyx.pyx":727 + * + * int_value = value_ + * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &int_value) # <<<<<<<<<<<<<< + * + * elif field_ in double_fields: + */ + __pyx_t_7 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 727, __pyx_L1_error) + ocp_nlp_solver_opts_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_opts, __pyx_t_7, ((void *)(&__pyx_v_int_value))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":714 + * + * # check field availability and type + * if field_ in int_fields: # <<<<<<<<<<<<<< + * if not isinstance(value_, int): + * raise Exception('solver option {} must be of type int. You have {}.'.format(field_, type(value_))) + */ + goto __pyx_L3; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":729 + * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &int_value) + * + * elif field_ in double_fields: # <<<<<<<<<<<<<< + * if not isinstance(value_, float): + * raise Exception('solver option {} must be of type float. You have {}.'.format(field_, type(value_))) + */ + __pyx_t_3 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_double_fields, Py_EQ)); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(0, 729, __pyx_L1_error) + if (__pyx_t_3) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":730 + * + * elif field_ in double_fields: + * if not isinstance(value_, float): # <<<<<<<<<<<<<< + * raise Exception('solver option {} must be of type float. You have {}.'.format(field_, type(value_))) + * + */ + __pyx_t_3 = PyFloat_Check(__pyx_v_value_); + __pyx_t_2 = (!__pyx_t_3); + if (unlikely(__pyx_t_2)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":731 + * elif field_ in double_fields: + * if not isinstance(value_, float): + * raise Exception('solver option {} must be of type float. You have {}.'.format(field_, type(value_))) # <<<<<<<<<<<<<< + * + * double_value = value_ + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_solver_option_must_be_of_type_fl, __pyx_n_s_format); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 731, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_v_field_, ((PyObject *)Py_TYPE(__pyx_v_value_))}; + __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 731, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_1 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_4); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 731, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 731, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":730 + * + * elif field_ in double_fields: + * if not isinstance(value_, float): # <<<<<<<<<<<<<< + * raise Exception('solver option {} must be of type float. You have {}.'.format(field_, type(value_))) + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":733 + * raise Exception('solver option {} must be of type float. You have {}.'.format(field_, type(value_))) + * + * double_value = value_ # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &double_value) + * + */ + __pyx_t_8 = __pyx_PyFloat_AsDouble(__pyx_v_value_); if (unlikely((__pyx_t_8 == (double)-1) && PyErr_Occurred())) __PYX_ERR(0, 733, __pyx_L1_error) + __pyx_v_double_value = __pyx_t_8; + + /* "acados_template/acados_ocp_solver_pyx.pyx":734 + * + * double_value = value_ + * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &double_value) # <<<<<<<<<<<<<< + * + * elif field_ in string_fields: + */ + __pyx_t_7 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 734, __pyx_L1_error) + ocp_nlp_solver_opts_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_opts, __pyx_t_7, ((void *)(&__pyx_v_double_value))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":729 + * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &int_value) + * + * elif field_ in double_fields: # <<<<<<<<<<<<<< + * if not isinstance(value_, float): + * raise Exception('solver option {} must be of type float. You have {}.'.format(field_, type(value_))) + */ + goto __pyx_L3; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":736 + * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &double_value) + * + * elif field_ in string_fields: # <<<<<<<<<<<<<< + * if not isinstance(value_, bytes): + * raise Exception('solver option {} must be of type str. You have {}.'.format(field_, type(value_))) + */ + __pyx_t_2 = (__Pyx_PySequence_ContainsTF(__pyx_v_field_, __pyx_v_string_fields, Py_EQ)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 736, __pyx_L1_error) + if (likely(__pyx_t_2)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":737 + * + * elif field_ in string_fields: + * if not isinstance(value_, bytes): # <<<<<<<<<<<<<< + * raise Exception('solver option {} must be of type str. You have {}.'.format(field_, type(value_))) + * + */ + __pyx_t_2 = PyBytes_Check(__pyx_v_value_); + __pyx_t_3 = (!__pyx_t_2); + if (unlikely(__pyx_t_3)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":738 + * elif field_ in string_fields: + * if not isinstance(value_, bytes): + * raise Exception('solver option {} must be of type str. You have {}.'.format(field_, type(value_))) # <<<<<<<<<<<<<< + * + * string_value = value_.encode('utf-8') + */ + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_solver_option_must_be_of_type_st, __pyx_n_s_format); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 738, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_4))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_4); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_4); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_4, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_5, __pyx_v_field_, ((PyObject *)Py_TYPE(__pyx_v_value_))}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_4, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 738, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + __pyx_t_4 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 738, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_t_4, 0, 0, 0); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __PYX_ERR(0, 738, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":737 + * + * elif field_ in string_fields: + * if not isinstance(value_, bytes): # <<<<<<<<<<<<<< + * raise Exception('solver option {} must be of type str. You have {}.'.format(field_, type(value_))) + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":740 + * raise Exception('solver option {} must be of type str. You have {}.'.format(field_, type(value_))) + * + * string_value = value_.encode('utf-8') # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &string_value[0]) + * + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_value_, __pyx_n_s_encode); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 740, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_5 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_5)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_5); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_5, __pyx_kp_u_utf_8}; + __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 1+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 740, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_t_9 = __Pyx_PyObject_to_MemoryviewSlice_dc_unsigned_char(__pyx_t_4, PyBUF_WRITABLE); if (unlikely(!__pyx_t_9.memview)) __PYX_ERR(0, 740, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_v_string_value = __pyx_t_9; + __pyx_t_9.memview = NULL; + __pyx_t_9.data = NULL; + + /* "acados_template/acados_ocp_solver_pyx.pyx":741 + * + * string_value = value_.encode('utf-8') + * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &string_value[0]) # <<<<<<<<<<<<<< + * + * else: + */ + __pyx_t_7 = __Pyx_PyObject_AsString(__pyx_v_field); if (unlikely((!__pyx_t_7) && PyErr_Occurred())) __PYX_ERR(0, 741, __pyx_L1_error) + __pyx_t_10 = 0; + __pyx_t_6 = -1; + if (__pyx_t_10 < 0) { + __pyx_t_10 += __pyx_v_string_value.shape[0]; + if (unlikely(__pyx_t_10 < 0)) __pyx_t_6 = 0; + } else if (unlikely(__pyx_t_10 >= __pyx_v_string_value.shape[0])) __pyx_t_6 = 0; + if (unlikely(__pyx_t_6 != -1)) { + __Pyx_RaiseBufferIndexError(__pyx_t_6); + __PYX_ERR(0, 741, __pyx_L1_error) + } + ocp_nlp_solver_opts_set(__pyx_v_self->nlp_config, __pyx_v_self->nlp_opts, __pyx_t_7, ((void *)(&(*((unsigned char *) ( /* dim=0 */ ((char *) (((unsigned char *) __pyx_v_string_value.data) + __pyx_t_10)) )))))); + + /* "acados_template/acados_ocp_solver_pyx.pyx":736 + * acados_solver_common.ocp_nlp_solver_opts_set(self.nlp_config, self.nlp_opts, field, &double_value) + * + * elif field_ in string_fields: # <<<<<<<<<<<<<< + * if not isinstance(value_, bytes): + * raise Exception('solver option {} must be of type str. You have {}.'.format(field_, type(value_))) + */ + goto __pyx_L3; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":744 + * + * else: + * raise Exception('AcadosOcpSolverCython.options_set() does not support field {}.'\ # <<<<<<<<<<<<<< + * '\n Possible values are {}.'.format(field_, ', '.join(int_fields + double_fields + string_fields))) + * + */ + /*else*/ { + + /* "acados_template/acados_ocp_solver_pyx.pyx":745 + * else: + * raise Exception('AcadosOcpSolverCython.options_set() does not support field {}.'\ + * '\n Possible values are {}.'.format(field_, ', '.join(int_fields + double_fields + string_fields))) # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_kp_u_AcadosOcpSolverCython_options_se, __pyx_n_s_format); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 745, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_5 = PyNumber_Add(__pyx_v_int_fields, __pyx_v_double_fields); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 745, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_11 = PyNumber_Add(__pyx_t_5, __pyx_v_string_fields); if (unlikely(!__pyx_t_11)) __PYX_ERR(0, 745, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_11); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_5 = PyUnicode_Join(__pyx_kp_u__31, __pyx_t_11); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 745, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; + __pyx_t_11 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_1))) { + __pyx_t_11 = PyMethod_GET_SELF(__pyx_t_1); + if (likely(__pyx_t_11)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_1); + __Pyx_INCREF(__pyx_t_11); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_1, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_11, __pyx_v_field_, __pyx_t_5}; + __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_1, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_11); __pyx_t_11 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 745, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":744 + * + * else: + * raise Exception('AcadosOcpSolverCython.options_set() does not support field {}.'\ # <<<<<<<<<<<<<< + * '\n Possible values are {}.'.format(field_, ', '.join(int_fields + double_fields + string_fields))) + * + */ + __pyx_t_1 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_4); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 744, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_Raise(__pyx_t_1, 0, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 744, __pyx_L1_error) + } + __pyx_L3:; + + /* "acados_template/acados_ocp_solver_pyx.pyx":685 + * + * + * def options_set(self, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set options of the solver. + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __PYX_XCLEAR_MEMVIEW(&__pyx_t_9, 1); + __Pyx_XDECREF(__pyx_t_11); + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.options_set", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_int_fields); + __Pyx_XDECREF(__pyx_v_double_fields); + __Pyx_XDECREF(__pyx_v_string_fields); + __Pyx_XDECREF(__pyx_v_field); + __PYX_XCLEAR_MEMVIEW(&__pyx_v_string_value, 1); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":748 + * + * + * def set_params_sparse(self, int stage, idx_values_, param_values_): # <<<<<<<<<<<<<< + * """ + * set parameters of the solvers external function partially: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49set_params_sparse(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +PyDoc_STRVAR(__pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_48set_params_sparse, "\n set parameters of the solvers external function partially:\n Pseudo: solver.param[idx_values_] = param_values_;\n Parameters:\n :param stage_: integer corresponding to shooting node\n :param idx_values_: 0 based integer array corresponding to parameter indices to be set\n :param param_values_: new parameter values as numpy array\n "); +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49set_params_sparse = {"set_params_sparse", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49set_params_sparse, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_48set_params_sparse}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49set_params_sparse(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + int __pyx_v_stage; + PyObject *__pyx_v_idx_values_ = 0; + PyObject *__pyx_v_param_values_ = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("set_params_sparse (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_stage,&__pyx_n_s_idx_values,&__pyx_n_s_param_values,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_stage)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 748, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_idx_values)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 748, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("set_params_sparse", 1, 3, 3, 1); __PYX_ERR(0, 748, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_param_values)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 748, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("set_params_sparse", 1, 3, 3, 2); __PYX_ERR(0, 748, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "set_params_sparse") < 0)) __PYX_ERR(0, 748, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + } + __pyx_v_stage = __Pyx_PyInt_As_int(values[0]); if (unlikely((__pyx_v_stage == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 748, __pyx_L3_error) + __pyx_v_idx_values_ = values[1]; + __pyx_v_param_values_ = values[2]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("set_params_sparse", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 748, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.set_params_sparse", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_48set_params_sparse(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v_stage, __pyx_v_idx_values_, __pyx_v_param_values_); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_48set_params_sparse(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, int __pyx_v_stage, PyObject *__pyx_v_idx_values_, PyObject *__pyx_v_param_values_) { + PyArrayObject *__pyx_v_value = 0; + PyArrayObject *__pyx_v_idx = 0; + int __pyx_v_n_update; + __Pyx_LocalBuf_ND __pyx_pybuffernd_idx; + __Pyx_Buffer __pyx_pybuffer_idx; + __Pyx_LocalBuf_ND __pyx_pybuffernd_value; + __Pyx_Buffer __pyx_pybuffer_value; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_t_3; + int __pyx_t_4; + Py_ssize_t __pyx_t_5; + PyObject *__pyx_t_6 = NULL; + Py_UCS4 __pyx_t_7; + Py_ssize_t __pyx_t_8; + PyObject *__pyx_t_9 = NULL; + PyObject *__pyx_t_10 = NULL; + PyArrayObject *__pyx_t_11 = NULL; + PyArrayObject *__pyx_t_12 = NULL; + npy_intp *__pyx_t_13; + char *__pyx_t_14; + char *__pyx_t_15; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("set_params_sparse", 1); + __pyx_pybuffer_value.pybuffer.buf = NULL; + __pyx_pybuffer_value.refcount = 0; + __pyx_pybuffernd_value.data = NULL; + __pyx_pybuffernd_value.rcbuffer = &__pyx_pybuffer_value; + __pyx_pybuffer_idx.pybuffer.buf = NULL; + __pyx_pybuffer_idx.refcount = 0; + __pyx_pybuffernd_idx.data = NULL; + __pyx_pybuffernd_idx.rcbuffer = &__pyx_pybuffer_idx; + + /* "acados_template/acados_ocp_solver_pyx.pyx":758 + * """ + * + * if not isinstance(param_values_, np.ndarray): # <<<<<<<<<<<<<< + * raise Exception('param_values_ must be np.array.') + * + */ + __Pyx_GetModuleGlobalName(__pyx_t_1, __pyx_n_s_np); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 758, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_ndarray); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 758, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_3 = PyObject_IsInstance(__pyx_v_param_values_, __pyx_t_2); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(0, 758, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_4 = (!__pyx_t_3); + if (unlikely(__pyx_t_4)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":759 + * + * if not isinstance(param_values_, np.ndarray): + * raise Exception('param_values_ must be np.array.') # <<<<<<<<<<<<<< + * + * if param_values_.shape[0] != len(idx_values_): + */ + __pyx_t_2 = __Pyx_PyObject_Call(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_tuple__32, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 759, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 759, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":758 + * """ + * + * if not isinstance(param_values_, np.ndarray): # <<<<<<<<<<<<<< + * raise Exception('param_values_ must be np.array.') + * + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":761 + * raise Exception('param_values_ must be np.array.') + * + * if param_values_.shape[0] != len(idx_values_): # <<<<<<<<<<<<<< + * raise Exception(f'param_values_ and idx_values_ must be of the same size.' + + * f' Got sizes idx {param_values_.shape[0]}, param_values {len(idx_values_)}.') + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_param_values_, __pyx_n_s_shape); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 761, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_1 = __Pyx_GetItemInt(__pyx_t_2, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 761, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_5 = PyObject_Length(__pyx_v_idx_values_); if (unlikely(__pyx_t_5 == ((Py_ssize_t)-1))) __PYX_ERR(0, 761, __pyx_L1_error) + __pyx_t_2 = PyInt_FromSsize_t(__pyx_t_5); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 761, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_6 = PyObject_RichCompare(__pyx_t_1, __pyx_t_2, Py_NE); __Pyx_XGOTREF(__pyx_t_6); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 761, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_t_6); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 761, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(__pyx_t_4)) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":763 + * if param_values_.shape[0] != len(idx_values_): + * raise Exception(f'param_values_ and idx_values_ must be of the same size.' + + * f' Got sizes idx {param_values_.shape[0]}, param_values {len(idx_values_)}.') # <<<<<<<<<<<<<< + * + * # n_update = c_int(len(param_values_)) + */ + __pyx_t_6 = PyTuple_New(5); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 763, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_5 = 0; + __pyx_t_7 = 127; + __Pyx_INCREF(__pyx_kp_u_Got_sizes_idx); + __pyx_t_5 += 15; + __Pyx_GIVEREF(__pyx_kp_u_Got_sizes_idx); + PyTuple_SET_ITEM(__pyx_t_6, 0, __pyx_kp_u_Got_sizes_idx); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_param_values_, __pyx_n_s_shape); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 763, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_1 = __Pyx_GetItemInt(__pyx_t_2, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 763, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_FormatSimple(__pyx_t_1, __pyx_empty_unicode); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 763, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_7 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) > __pyx_t_7) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_2) : __pyx_t_7; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_6, 1, __pyx_t_2); + __pyx_t_2 = 0; + __Pyx_INCREF(__pyx_kp_u_param_values_2); + __pyx_t_5 += 15; + __Pyx_GIVEREF(__pyx_kp_u_param_values_2); + PyTuple_SET_ITEM(__pyx_t_6, 2, __pyx_kp_u_param_values_2); + __pyx_t_8 = PyObject_Length(__pyx_v_idx_values_); if (unlikely(__pyx_t_8 == ((Py_ssize_t)-1))) __PYX_ERR(0, 763, __pyx_L1_error) + __pyx_t_2 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_t_8, 0, ' ', 'd'); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 763, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + PyTuple_SET_ITEM(__pyx_t_6, 3, __pyx_t_2); + __pyx_t_2 = 0; + __Pyx_INCREF(__pyx_kp_u__2); + __pyx_t_5 += 1; + __Pyx_GIVEREF(__pyx_kp_u__2); + PyTuple_SET_ITEM(__pyx_t_6, 4, __pyx_kp_u__2); + __pyx_t_2 = __Pyx_PyUnicode_Join(__pyx_t_6, 5, __pyx_t_5, __pyx_t_7); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 763, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":762 + * + * if param_values_.shape[0] != len(idx_values_): + * raise Exception(f'param_values_ and idx_values_ must be of the same size.' + # <<<<<<<<<<<<<< + * f' Got sizes idx {param_values_.shape[0]}, param_values {len(idx_values_)}.') + * + */ + __pyx_t_6 = __Pyx_PyUnicode_Concat(__pyx_kp_u_param_values__and_idx_values__mu, __pyx_t_2); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 762, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_CallOneArg(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0])), __pyx_t_6); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 762, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_Raise(__pyx_t_2, 0, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 762, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":761 + * raise Exception('param_values_ must be np.array.') + * + * if param_values_.shape[0] != len(idx_values_): # <<<<<<<<<<<<<< + * raise Exception(f'param_values_ and idx_values_ must be of the same size.' + + * f' Got sizes idx {param_values_.shape[0]}, param_values {len(idx_values_)}.') + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":777 + * # (self.capsule, stage, idx_data, param_data, n_update) + * + * cdef cnp.ndarray[cnp.float64_t, ndim=1] value = np.ascontiguousarray(param_values_, dtype=np.float64) # <<<<<<<<<<<<<< + * # cdef cnp.ndarray[cnp.intc, ndim=1] idx = np.ascontiguousarray(idx_values_, dtype=np.intc) + * + */ + __Pyx_GetModuleGlobalName(__pyx_t_2, __pyx_n_s_np); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 777, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 777, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = PyTuple_New(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 777, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_INCREF(__pyx_v_param_values_); + __Pyx_GIVEREF(__pyx_v_param_values_); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_v_param_values_)) __PYX_ERR(0, 777, __pyx_L1_error); + __pyx_t_1 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 777, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_GetModuleGlobalName(__pyx_t_9, __pyx_n_s_np); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 777, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __pyx_t_10 = __Pyx_PyObject_GetAttrStr(__pyx_t_9, __pyx_n_s_float64); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 777, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + if (PyDict_SetItem(__pyx_t_1, __pyx_n_s_dtype, __pyx_t_10) < 0) __PYX_ERR(0, 777, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + __pyx_t_10 = __Pyx_PyObject_Call(__pyx_t_6, __pyx_t_2, __pyx_t_1); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 777, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (!(likely(((__pyx_t_10) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_10, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 777, __pyx_L1_error) + __pyx_t_11 = ((PyArrayObject *)__pyx_t_10); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_value.rcbuffer->pybuffer, (PyObject*)__pyx_t_11, &__Pyx_TypeInfo_nn___pyx_t_5numpy_float64_t, PyBUF_FORMAT| PyBUF_STRIDES, 1, 0, __pyx_stack) == -1)) { + __pyx_v_value = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_value.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 777, __pyx_L1_error) + } else {__pyx_pybuffernd_value.diminfo[0].strides = __pyx_pybuffernd_value.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_value.diminfo[0].shape = __pyx_pybuffernd_value.rcbuffer->pybuffer.shape[0]; + } + } + __pyx_t_11 = 0; + __pyx_v_value = ((PyArrayObject *)__pyx_t_10); + __pyx_t_10 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":784 + * # cdef cnp.ndarray[cnp.int, ndim=1] idx = np.ascontiguousarray(idx_values_, dtype=np.intc) + * + * cdef cnp.ndarray[cnp.int32_t, ndim=1] idx = np.ascontiguousarray(idx_values_, dtype=np.int32) # <<<<<<<<<<<<<< + * cdef int n_update = value.shape[0] + * # print(f"in set_params_sparse Cython n_update {n_update}") + */ + __Pyx_GetModuleGlobalName(__pyx_t_10, __pyx_n_s_np); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 784, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_10, __pyx_n_s_ascontiguousarray); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 784, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + __pyx_t_10 = PyTuple_New(1); if (unlikely(!__pyx_t_10)) __PYX_ERR(0, 784, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_10); + __Pyx_INCREF(__pyx_v_idx_values_); + __Pyx_GIVEREF(__pyx_v_idx_values_); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_10, 0, __pyx_v_idx_values_)) __PYX_ERR(0, 784, __pyx_L1_error); + __pyx_t_2 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 784, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_GetModuleGlobalName(__pyx_t_6, __pyx_n_s_np); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 784, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_9 = __Pyx_PyObject_GetAttrStr(__pyx_t_6, __pyx_n_s_int32); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 784, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + if (PyDict_SetItem(__pyx_t_2, __pyx_n_s_dtype, __pyx_t_9) < 0) __PYX_ERR(0, 784, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + __pyx_t_9 = __Pyx_PyObject_Call(__pyx_t_1, __pyx_t_10, __pyx_t_2); if (unlikely(!__pyx_t_9)) __PYX_ERR(0, 784, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_10); __pyx_t_10 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + if (!(likely(((__pyx_t_9) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_9, __pyx_ptype_5numpy_ndarray))))) __PYX_ERR(0, 784, __pyx_L1_error) + __pyx_t_12 = ((PyArrayObject *)__pyx_t_9); + { + __Pyx_BufFmt_StackElem __pyx_stack[1]; + if (unlikely(__Pyx_GetBufferAndValidate(&__pyx_pybuffernd_idx.rcbuffer->pybuffer, (PyObject*)__pyx_t_12, &__Pyx_TypeInfo_nn___pyx_t_5numpy_int32_t, PyBUF_FORMAT| PyBUF_STRIDES, 1, 0, __pyx_stack) == -1)) { + __pyx_v_idx = ((PyArrayObject *)Py_None); __Pyx_INCREF(Py_None); __pyx_pybuffernd_idx.rcbuffer->pybuffer.buf = NULL; + __PYX_ERR(0, 784, __pyx_L1_error) + } else {__pyx_pybuffernd_idx.diminfo[0].strides = __pyx_pybuffernd_idx.rcbuffer->pybuffer.strides[0]; __pyx_pybuffernd_idx.diminfo[0].shape = __pyx_pybuffernd_idx.rcbuffer->pybuffer.shape[0]; + } + } + __pyx_t_12 = 0; + __pyx_v_idx = ((PyArrayObject *)__pyx_t_9); + __pyx_t_9 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":785 + * + * cdef cnp.ndarray[cnp.int32_t, ndim=1] idx = np.ascontiguousarray(idx_values_, dtype=np.int32) + * cdef int n_update = value.shape[0] # <<<<<<<<<<<<<< + * # print(f"in set_params_sparse Cython n_update {n_update}") + * + */ + __pyx_t_13 = __pyx_f_5numpy_7ndarray_5shape_shape(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_13 == ((npy_intp *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 785, __pyx_L1_error) + __pyx_v_n_update = (__pyx_t_13[0]); + + /* "acados_template/acados_ocp_solver_pyx.pyx":788 + * # print(f"in set_params_sparse Cython n_update {n_update}") + * + * assert acados_solver.acados_update_params_sparse(self.capsule, stage, idx.data, value.data, n_update) == 0 # <<<<<<<<<<<<<< + * return + * + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_14 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_idx)); if (unlikely(__pyx_t_14 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 788, __pyx_L1_error) + __pyx_t_15 = __pyx_f_5numpy_7ndarray_4data_data(((PyArrayObject *)__pyx_v_value)); if (unlikely(__pyx_t_15 == ((char *)NULL) && PyErr_Occurred())) __PYX_ERR(0, 788, __pyx_L1_error) + __pyx_t_4 = (long_acados_update_params_sparse(__pyx_v_self->capsule, __pyx_v_stage, ((int *)__pyx_t_14), ((double *)__pyx_t_15), __pyx_v_n_update) == 0); + if (unlikely(!__pyx_t_4)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(0, 788, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(0, 788, __pyx_L1_error) + #endif + + /* "acados_template/acados_ocp_solver_pyx.pyx":789 + * + * assert acados_solver.acados_update_params_sparse(self.capsule, stage, idx.data, value.data, n_update) == 0 + * return # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":748 + * + * + * def set_params_sparse(self, int stage, idx_values_, param_values_): # <<<<<<<<<<<<<< + * """ + * set parameters of the solvers external function partially: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_9); + __Pyx_XDECREF(__pyx_t_10); + { PyObject *__pyx_type, *__pyx_value, *__pyx_tb; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&__pyx_type, &__pyx_value, &__pyx_tb); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_idx.rcbuffer->pybuffer); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_value.rcbuffer->pybuffer); + __Pyx_ErrRestore(__pyx_type, __pyx_value, __pyx_tb);} + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.set_params_sparse", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + goto __pyx_L2; + __pyx_L0:; + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_idx.rcbuffer->pybuffer); + __Pyx_SafeReleaseBuffer(&__pyx_pybuffernd_value.rcbuffer->pybuffer); + __pyx_L2:; + __Pyx_XDECREF((PyObject *)__pyx_v_value); + __Pyx_XDECREF((PyObject *)__pyx_v_idx); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "acados_template/acados_ocp_solver_pyx.pyx":792 + * + * + * def __del__(self): # <<<<<<<<<<<<<< + * if self.solver_created: + * acados_solver.acados_free(self.capsule) + */ + +/* Python wrapper */ +static void __pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_51__del__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_51__del__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__del__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_50__del__(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_50__del__(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":793 + * + * def __del__(self): + * if self.solver_created: # <<<<<<<<<<<<<< + * acados_solver.acados_free(self.capsule) + * acados_solver.acados_free_capsule(self.capsule) + */ + if (__pyx_v_self->solver_created) { + + /* "acados_template/acados_ocp_solver_pyx.pyx":794 + * def __del__(self): + * if self.solver_created: + * acados_solver.acados_free(self.capsule) # <<<<<<<<<<<<<< + * acados_solver.acados_free_capsule(self.capsule) + */ + (void)(long_acados_free(__pyx_v_self->capsule)); + + /* "acados_template/acados_ocp_solver_pyx.pyx":795 + * if self.solver_created: + * acados_solver.acados_free(self.capsule) + * acados_solver.acados_free_capsule(self.capsule) # <<<<<<<<<<<<<< + */ + (void)(long_acados_free_capsule(__pyx_v_self->capsule)); + + /* "acados_template/acados_ocp_solver_pyx.pyx":793 + * + * def __del__(self): + * if self.solver_created: # <<<<<<<<<<<<<< + * acados_solver.acados_free(self.capsule) + * acados_solver.acados_free_capsule(self.capsule) + */ + } + + /* "acados_template/acados_ocp_solver_pyx.pyx":792 + * + * + * def __del__(self): # <<<<<<<<<<<<<< + * if self.solver_created: + * acados_solver.acados_free(self.capsule) + */ + + /* function exit code */ +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_53__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_53__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_53__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_53__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_52__reduce_cython__(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_52__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_55__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_55__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_55__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_55__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(1, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_54__setstate_cython__(((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_54__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(1, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_tp_new_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython(PyTypeObject *t, PyObject *a, PyObject *k) { + struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)o); + p->model_name = ((PyObject*)Py_None); Py_INCREF(Py_None); + p->nlp_solver_type = ((PyObject*)Py_None); Py_INCREF(Py_None); + if (unlikely(__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_1__cinit__(o, a, k) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +#if CYTHON_USE_TP_FINALIZE +static void __pyx_tp_finalize_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython(PyObject *o) { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_51__del__(o); + PyErr_Restore(etype, eval, etb); +} +#endif + +static void __pyx_tp_dealloc_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython(PyObject *o) { + struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *p = (struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + Py_CLEAR(p->model_name); + Py_CLEAR(p->nlp_solver_type); + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} + +static PyMethodDef __pyx_methods_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython[] = { + {"_AcadosOcpSolverCython__get_pointers_solver", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_3_AcadosOcpSolverCython__get_pointers_solver, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_2__get_pointers_solver}, + {"solve_for_x0", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve_for_x0, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_4solve_for_x0}, + {"solve", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7solve, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_6solve}, + {"reset", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9reset, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_8reset}, + {"custom_update", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11custom_update, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_10custom_update}, + {"set_new_time_steps", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13set_new_time_steps, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_12set_new_time_steps}, + {"update_qp_solver_cond_N", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15update_qp_solver_cond_N, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_14update_qp_solver_cond_N}, + {"eval_param_sens", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17eval_param_sens, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_16eval_param_sens}, + {"get", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19get, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_18get}, + {"print_statistics", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21print_statistics, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_20print_statistics}, + {"store_iterate", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23store_iterate, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_22store_iterate}, + {"load_iterate", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25load_iterate, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_24load_iterate}, + {"get_stats", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27get_stats, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_26get_stats}, + {"_AcadosOcpSolverCython__get_stat_int", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_int, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"_AcadosOcpSolverCython__get_stat_double", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31_AcadosOcpSolverCython__get_stat_double, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"_AcadosOcpSolverCython__get_stat_matrix", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33_AcadosOcpSolverCython__get_stat_matrix, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"get_cost", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35get_cost, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_34get_cost}, + {"get_residuals", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37get_residuals, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_36get_residuals}, + {"set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_38set}, + {"cost_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41cost_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_40cost_set}, + {"constraints_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43constraints_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_42constraints_set}, + {"get_from_qp_in", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_45get_from_qp_in, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_44get_from_qp_in}, + {"options_set", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47options_set, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_46options_set}, + {"set_params_sparse", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49set_params_sparse, __Pyx_METH_FASTCALL|METH_KEYWORDS, __pyx_doc_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_48set_params_sparse}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_53__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_55__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython}, + {Py_tp_doc, (void *)PyDoc_STR("\n Class to interact with the acados ocp solver C object.\n ")}, + {Py_tp_methods, (void *)__pyx_methods_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython}, + {Py_tp_new, (void *)__pyx_tp_new_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython}, + #if PY_VERSION_HEX >= 0x030400a1 + {Py_tp_finalize, (void *)__pyx_tp_finalize_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython}, + #endif + {0, 0}, +}; +static PyType_Spec __pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython_spec = { + "acados_template.acados_ocp_solver_pyx.AcadosOcpSolverCython", + sizeof(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_FINALIZE, + __pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython_slots, +}; +#else + +static PyTypeObject __pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython = { + PyVarObject_HEAD_INIT(0, 0) + "acados_template.acados_ocp_solver_pyx.""AcadosOcpSolverCython", /*tp_name*/ + sizeof(struct __pyx_obj_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_FINALIZE, /*tp_flags*/ + PyDoc_STR("\n Class to interact with the acados ocp solver C object.\n "), /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + __pyx_tp_finalize_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif +static struct __pyx_vtabstruct_array __pyx_vtable_array; + +static PyObject *__pyx_tp_new_array(PyTypeObject *t, PyObject *a, PyObject *k) { + struct __pyx_array_obj *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_array_obj *)o); + p->__pyx_vtab = __pyx_vtabptr_array; + p->mode = ((PyObject*)Py_None); Py_INCREF(Py_None); + p->_format = ((PyObject*)Py_None); Py_INCREF(Py_None); + if (unlikely(__pyx_array___cinit__(o, a, k) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static void __pyx_tp_dealloc_array(PyObject *o) { + struct __pyx_array_obj *p = (struct __pyx_array_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_array) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_array___dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + Py_CLEAR(p->mode); + Py_CLEAR(p->_format); + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} +static PyObject *__pyx_sq_item_array(PyObject *o, Py_ssize_t i) { + PyObject *r; + PyObject *x = PyInt_FromSsize_t(i); if(!x) return 0; + r = Py_TYPE(o)->tp_as_mapping->mp_subscript(o, x); + Py_DECREF(x); + return r; +} + +static int __pyx_mp_ass_subscript_array(PyObject *o, PyObject *i, PyObject *v) { + if (v) { + return __pyx_array___setitem__(o, i, v); + } + else { + __Pyx_TypeName o_type_name; + o_type_name = __Pyx_PyType_GetName(Py_TYPE(o)); + PyErr_Format(PyExc_NotImplementedError, + "Subscript deletion not supported by " __Pyx_FMT_TYPENAME, o_type_name); + __Pyx_DECREF_TypeName(o_type_name); + return -1; + } +} + +static PyObject *__pyx_tp_getattro_array(PyObject *o, PyObject *n) { + PyObject *v = __Pyx_PyObject_GenericGetAttr(o, n); + if (!v && PyErr_ExceptionMatches(PyExc_AttributeError)) { + PyErr_Clear(); + v = __pyx_array___getattr__(o, n); + } + return v; +} + +static PyObject *__pyx_getprop___pyx_array_memview(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_5array_7memview_1__get__(o); +} + +static PyMethodDef __pyx_methods_array[] = { + {"__getattr__", (PyCFunction)__pyx_array___getattr__, METH_O|METH_COEXIST, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_array_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_array_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; + +static struct PyGetSetDef __pyx_getsets_array[] = { + {(char *)"memview", __pyx_getprop___pyx_array_memview, 0, (char *)0, 0}, + {0, 0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +#if !CYTHON_COMPILING_IN_LIMITED_API + +static PyBufferProcs __pyx_tp_as_buffer_array = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_array_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; +#endif +static PyType_Slot __pyx_type___pyx_array_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_array}, + {Py_sq_length, (void *)__pyx_array___len__}, + {Py_sq_item, (void *)__pyx_sq_item_array}, + {Py_mp_length, (void *)__pyx_array___len__}, + {Py_mp_subscript, (void *)__pyx_array___getitem__}, + {Py_mp_ass_subscript, (void *)__pyx_mp_ass_subscript_array}, + {Py_tp_getattro, (void *)__pyx_tp_getattro_array}, + #if defined(Py_bf_getbuffer) + {Py_bf_getbuffer, (void *)__pyx_array_getbuffer}, + #endif + {Py_tp_methods, (void *)__pyx_methods_array}, + {Py_tp_getset, (void *)__pyx_getsets_array}, + {Py_tp_new, (void *)__pyx_tp_new_array}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_array_spec = { + "acados_template.acados_ocp_solver_pyx.array", + sizeof(struct __pyx_array_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_SEQUENCE, + __pyx_type___pyx_array_slots, +}; +#else + +static PySequenceMethods __pyx_tp_as_sequence_array = { + __pyx_array___len__, /*sq_length*/ + 0, /*sq_concat*/ + 0, /*sq_repeat*/ + __pyx_sq_item_array, /*sq_item*/ + 0, /*sq_slice*/ + 0, /*sq_ass_item*/ + 0, /*sq_ass_slice*/ + 0, /*sq_contains*/ + 0, /*sq_inplace_concat*/ + 0, /*sq_inplace_repeat*/ +}; + +static PyMappingMethods __pyx_tp_as_mapping_array = { + __pyx_array___len__, /*mp_length*/ + __pyx_array___getitem__, /*mp_subscript*/ + __pyx_mp_ass_subscript_array, /*mp_ass_subscript*/ +}; + +static PyBufferProcs __pyx_tp_as_buffer_array = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_array_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; + +static PyTypeObject __pyx_type___pyx_array = { + PyVarObject_HEAD_INIT(0, 0) + "acados_template.acados_ocp_solver_pyx.""array", /*tp_name*/ + sizeof(struct __pyx_array_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_array, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + &__pyx_tp_as_sequence_array, /*tp_as_sequence*/ + &__pyx_tp_as_mapping_array, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + __pyx_tp_getattro_array, /*tp_getattro*/ + 0, /*tp_setattro*/ + &__pyx_tp_as_buffer_array, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_SEQUENCE, /*tp_flags*/ + 0, /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_array, /*tp_methods*/ + 0, /*tp_members*/ + __pyx_getsets_array, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_array, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyObject *__pyx_tp_new_Enum(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { + struct __pyx_MemviewEnum_obj *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_MemviewEnum_obj *)o); + p->name = Py_None; Py_INCREF(Py_None); + return o; +} + +static void __pyx_tp_dealloc_Enum(PyObject *o) { + struct __pyx_MemviewEnum_obj *p = (struct __pyx_MemviewEnum_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_Enum) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + Py_CLEAR(p->name); + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} + +static int __pyx_tp_traverse_Enum(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_MemviewEnum_obj *p = (struct __pyx_MemviewEnum_obj *)o; + if (p->name) { + e = (*v)(p->name, a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear_Enum(PyObject *o) { + PyObject* tmp; + struct __pyx_MemviewEnum_obj *p = (struct __pyx_MemviewEnum_obj *)o; + tmp = ((PyObject*)p->name); + p->name = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + return 0; +} + +static PyObject *__pyx_specialmethod___pyx_MemviewEnum___repr__(PyObject *self, CYTHON_UNUSED PyObject *arg) { + return __pyx_MemviewEnum___repr__(self); +} + +static PyMethodDef __pyx_methods_Enum[] = { + {"__repr__", (PyCFunction)__pyx_specialmethod___pyx_MemviewEnum___repr__, METH_NOARGS|METH_COEXIST, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_MemviewEnum_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_MemviewEnum_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type___pyx_MemviewEnum_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_Enum}, + {Py_tp_repr, (void *)__pyx_MemviewEnum___repr__}, + {Py_tp_traverse, (void *)__pyx_tp_traverse_Enum}, + {Py_tp_clear, (void *)__pyx_tp_clear_Enum}, + {Py_tp_methods, (void *)__pyx_methods_Enum}, + {Py_tp_init, (void *)__pyx_MemviewEnum___init__}, + {Py_tp_new, (void *)__pyx_tp_new_Enum}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_MemviewEnum_spec = { + "acados_template.acados_ocp_solver_pyx.Enum", + sizeof(struct __pyx_MemviewEnum_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, + __pyx_type___pyx_MemviewEnum_slots, +}; +#else + +static PyTypeObject __pyx_type___pyx_MemviewEnum = { + PyVarObject_HEAD_INIT(0, 0) + "acados_template.acados_ocp_solver_pyx.""Enum", /*tp_name*/ + sizeof(struct __pyx_MemviewEnum_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_Enum, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + __pyx_MemviewEnum___repr__, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, /*tp_flags*/ + 0, /*tp_doc*/ + __pyx_tp_traverse_Enum, /*tp_traverse*/ + __pyx_tp_clear_Enum, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_Enum, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + __pyx_MemviewEnum___init__, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_Enum, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif +static struct __pyx_vtabstruct_memoryview __pyx_vtable_memoryview; + +static PyObject *__pyx_tp_new_memoryview(PyTypeObject *t, PyObject *a, PyObject *k) { + struct __pyx_memoryview_obj *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_memoryview_obj *)o); + p->__pyx_vtab = __pyx_vtabptr_memoryview; + p->obj = Py_None; Py_INCREF(Py_None); + p->_size = Py_None; Py_INCREF(Py_None); + p->_array_interface = Py_None; Py_INCREF(Py_None); + p->view.obj = NULL; + if (unlikely(__pyx_memoryview___cinit__(o, a, k) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static void __pyx_tp_dealloc_memoryview(PyObject *o) { + struct __pyx_memoryview_obj *p = (struct __pyx_memoryview_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_memoryview) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_memoryview___dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + Py_CLEAR(p->obj); + Py_CLEAR(p->_size); + Py_CLEAR(p->_array_interface); + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} + +static int __pyx_tp_traverse_memoryview(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_memoryview_obj *p = (struct __pyx_memoryview_obj *)o; + if (p->obj) { + e = (*v)(p->obj, a); if (e) return e; + } + if (p->_size) { + e = (*v)(p->_size, a); if (e) return e; + } + if (p->_array_interface) { + e = (*v)(p->_array_interface, a); if (e) return e; + } + if (p->view.obj) { + e = (*v)(p->view.obj, a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear_memoryview(PyObject *o) { + PyObject* tmp; + struct __pyx_memoryview_obj *p = (struct __pyx_memoryview_obj *)o; + tmp = ((PyObject*)p->obj); + p->obj = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + tmp = ((PyObject*)p->_size); + p->_size = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + tmp = ((PyObject*)p->_array_interface); + p->_array_interface = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + Py_CLEAR(p->view.obj); + return 0; +} +static PyObject *__pyx_sq_item_memoryview(PyObject *o, Py_ssize_t i) { + PyObject *r; + PyObject *x = PyInt_FromSsize_t(i); if(!x) return 0; + r = Py_TYPE(o)->tp_as_mapping->mp_subscript(o, x); + Py_DECREF(x); + return r; +} + +static int __pyx_mp_ass_subscript_memoryview(PyObject *o, PyObject *i, PyObject *v) { + if (v) { + return __pyx_memoryview___setitem__(o, i, v); + } + else { + __Pyx_TypeName o_type_name; + o_type_name = __Pyx_PyType_GetName(Py_TYPE(o)); + PyErr_Format(PyExc_NotImplementedError, + "Subscript deletion not supported by " __Pyx_FMT_TYPENAME, o_type_name); + __Pyx_DECREF_TypeName(o_type_name); + return -1; + } +} + +static PyObject *__pyx_getprop___pyx_memoryview_T(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_1T_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_base(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_4base_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_shape(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_5shape_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_strides(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_7strides_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_suboffsets(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_10suboffsets_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_ndim(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_4ndim_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_itemsize(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_8itemsize_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_nbytes(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_6nbytes_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_size(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_4size_1__get__(o); +} + +static PyObject *__pyx_specialmethod___pyx_memoryview___repr__(PyObject *self, CYTHON_UNUSED PyObject *arg) { + return __pyx_memoryview___repr__(self); +} + +static PyMethodDef __pyx_methods_memoryview[] = { + {"__repr__", (PyCFunction)__pyx_specialmethod___pyx_memoryview___repr__, METH_NOARGS|METH_COEXIST, 0}, + {"is_c_contig", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_is_c_contig, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"is_f_contig", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_is_f_contig, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"copy", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_copy, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"copy_fortran", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_copy_fortran, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryview_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryview_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; + +static struct PyGetSetDef __pyx_getsets_memoryview[] = { + {(char *)"T", __pyx_getprop___pyx_memoryview_T, 0, (char *)0, 0}, + {(char *)"base", __pyx_getprop___pyx_memoryview_base, 0, (char *)0, 0}, + {(char *)"shape", __pyx_getprop___pyx_memoryview_shape, 0, (char *)0, 0}, + {(char *)"strides", __pyx_getprop___pyx_memoryview_strides, 0, (char *)0, 0}, + {(char *)"suboffsets", __pyx_getprop___pyx_memoryview_suboffsets, 0, (char *)0, 0}, + {(char *)"ndim", __pyx_getprop___pyx_memoryview_ndim, 0, (char *)0, 0}, + {(char *)"itemsize", __pyx_getprop___pyx_memoryview_itemsize, 0, (char *)0, 0}, + {(char *)"nbytes", __pyx_getprop___pyx_memoryview_nbytes, 0, (char *)0, 0}, + {(char *)"size", __pyx_getprop___pyx_memoryview_size, 0, (char *)0, 0}, + {0, 0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +#if !CYTHON_COMPILING_IN_LIMITED_API + +static PyBufferProcs __pyx_tp_as_buffer_memoryview = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_memoryview_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; +#endif +static PyType_Slot __pyx_type___pyx_memoryview_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_memoryview}, + {Py_tp_repr, (void *)__pyx_memoryview___repr__}, + {Py_sq_length, (void *)__pyx_memoryview___len__}, + {Py_sq_item, (void *)__pyx_sq_item_memoryview}, + {Py_mp_length, (void *)__pyx_memoryview___len__}, + {Py_mp_subscript, (void *)__pyx_memoryview___getitem__}, + {Py_mp_ass_subscript, (void *)__pyx_mp_ass_subscript_memoryview}, + {Py_tp_str, (void *)__pyx_memoryview___str__}, + #if defined(Py_bf_getbuffer) + {Py_bf_getbuffer, (void *)__pyx_memoryview_getbuffer}, + #endif + {Py_tp_traverse, (void *)__pyx_tp_traverse_memoryview}, + {Py_tp_clear, (void *)__pyx_tp_clear_memoryview}, + {Py_tp_methods, (void *)__pyx_methods_memoryview}, + {Py_tp_getset, (void *)__pyx_getsets_memoryview}, + {Py_tp_new, (void *)__pyx_tp_new_memoryview}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_memoryview_spec = { + "acados_template.acados_ocp_solver_pyx.memoryview", + sizeof(struct __pyx_memoryview_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, + __pyx_type___pyx_memoryview_slots, +}; +#else + +static PySequenceMethods __pyx_tp_as_sequence_memoryview = { + __pyx_memoryview___len__, /*sq_length*/ + 0, /*sq_concat*/ + 0, /*sq_repeat*/ + __pyx_sq_item_memoryview, /*sq_item*/ + 0, /*sq_slice*/ + 0, /*sq_ass_item*/ + 0, /*sq_ass_slice*/ + 0, /*sq_contains*/ + 0, /*sq_inplace_concat*/ + 0, /*sq_inplace_repeat*/ +}; + +static PyMappingMethods __pyx_tp_as_mapping_memoryview = { + __pyx_memoryview___len__, /*mp_length*/ + __pyx_memoryview___getitem__, /*mp_subscript*/ + __pyx_mp_ass_subscript_memoryview, /*mp_ass_subscript*/ +}; + +static PyBufferProcs __pyx_tp_as_buffer_memoryview = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_memoryview_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; + +static PyTypeObject __pyx_type___pyx_memoryview = { + PyVarObject_HEAD_INIT(0, 0) + "acados_template.acados_ocp_solver_pyx.""memoryview", /*tp_name*/ + sizeof(struct __pyx_memoryview_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_memoryview, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + __pyx_memoryview___repr__, /*tp_repr*/ + 0, /*tp_as_number*/ + &__pyx_tp_as_sequence_memoryview, /*tp_as_sequence*/ + &__pyx_tp_as_mapping_memoryview, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + __pyx_memoryview___str__, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + &__pyx_tp_as_buffer_memoryview, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, /*tp_flags*/ + 0, /*tp_doc*/ + __pyx_tp_traverse_memoryview, /*tp_traverse*/ + __pyx_tp_clear_memoryview, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_memoryview, /*tp_methods*/ + 0, /*tp_members*/ + __pyx_getsets_memoryview, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_memoryview, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif +static struct __pyx_vtabstruct__memoryviewslice __pyx_vtable__memoryviewslice; + +static PyObject *__pyx_tp_new__memoryviewslice(PyTypeObject *t, PyObject *a, PyObject *k) { + struct __pyx_memoryviewslice_obj *p; + PyObject *o = __pyx_tp_new_memoryview(t, a, k); + if (unlikely(!o)) return 0; + p = ((struct __pyx_memoryviewslice_obj *)o); + p->__pyx_base.__pyx_vtab = (struct __pyx_vtabstruct_memoryview*)__pyx_vtabptr__memoryviewslice; + p->from_object = Py_None; Py_INCREF(Py_None); + p->from_slice.memview = NULL; + return o; +} + +static void __pyx_tp_dealloc__memoryviewslice(PyObject *o) { + struct __pyx_memoryviewslice_obj *p = (struct __pyx_memoryviewslice_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc__memoryviewslice) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_memoryviewslice___dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + Py_CLEAR(p->from_object); + PyObject_GC_Track(o); + __pyx_tp_dealloc_memoryview(o); +} + +static int __pyx_tp_traverse__memoryviewslice(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_memoryviewslice_obj *p = (struct __pyx_memoryviewslice_obj *)o; + e = __pyx_tp_traverse_memoryview(o, v, a); if (e) return e; + if (p->from_object) { + e = (*v)(p->from_object, a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear__memoryviewslice(PyObject *o) { + PyObject* tmp; + struct __pyx_memoryviewslice_obj *p = (struct __pyx_memoryviewslice_obj *)o; + __pyx_tp_clear_memoryview(o); + tmp = ((PyObject*)p->from_object); + p->from_object = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + __PYX_XCLEAR_MEMVIEW(&p->from_slice, 1); + return 0; +} + +static PyMethodDef __pyx_methods__memoryviewslice[] = { + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryviewslice_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryviewslice_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type___pyx_memoryviewslice_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc__memoryviewslice}, + {Py_tp_doc, (void *)PyDoc_STR("Internal class for passing memoryview slices to Python")}, + {Py_tp_traverse, (void *)__pyx_tp_traverse__memoryviewslice}, + {Py_tp_clear, (void *)__pyx_tp_clear__memoryviewslice}, + {Py_tp_methods, (void *)__pyx_methods__memoryviewslice}, + {Py_tp_new, (void *)__pyx_tp_new__memoryviewslice}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_memoryviewslice_spec = { + "acados_template.acados_ocp_solver_pyx._memoryviewslice", + sizeof(struct __pyx_memoryviewslice_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_SEQUENCE, + __pyx_type___pyx_memoryviewslice_slots, +}; +#else + +static PyTypeObject __pyx_type___pyx_memoryviewslice = { + PyVarObject_HEAD_INIT(0, 0) + "acados_template.acados_ocp_solver_pyx.""_memoryviewslice", /*tp_name*/ + sizeof(struct __pyx_memoryviewslice_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc__memoryviewslice, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + #if CYTHON_COMPILING_IN_PYPY || 0 + __pyx_memoryview___repr__, /*tp_repr*/ + #else + 0, /*tp_repr*/ + #endif + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + #if CYTHON_COMPILING_IN_PYPY || 0 + __pyx_memoryview___str__, /*tp_str*/ + #else + 0, /*tp_str*/ + #endif + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_SEQUENCE, /*tp_flags*/ + PyDoc_STR("Internal class for passing memoryview slices to Python"), /*tp_doc*/ + __pyx_tp_traverse__memoryviewslice, /*tp_traverse*/ + __pyx_tp_clear__memoryviewslice, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods__memoryviewslice, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new__memoryviewslice, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyMethodDef __pyx_methods[] = { + {0, 0, 0, 0} +}; +#ifndef CYTHON_SMALL_CODE +#if defined(__clang__) + #define CYTHON_SMALL_CODE +#elif defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 3)) + #define CYTHON_SMALL_CODE __attribute__((cold)) +#else + #define CYTHON_SMALL_CODE +#endif +#endif +/* #### Code section: pystring_table ### */ + +static int __Pyx_CreateStringTabAndInitStrings(void) { + __Pyx_StringTabEntry __pyx_string_tab[] = { + {&__pyx_kp_u_, __pyx_k_, sizeof(__pyx_k_), 0, 1, 0, 0}, + {&__pyx_kp_u_0, __pyx_k_0, sizeof(__pyx_k_0), 0, 1, 0, 0}, + {&__pyx_n_s_ASCII, __pyx_k_ASCII, sizeof(__pyx_k_ASCII), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython, __pyx_k_AcadosOcpSolverCython, sizeof(__pyx_k_AcadosOcpSolverCython), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython___get_poin, __pyx_k_AcadosOcpSolverCython___get_poin, sizeof(__pyx_k_AcadosOcpSolverCython___get_poin), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython___get_stat, __pyx_k_AcadosOcpSolverCython___get_stat, sizeof(__pyx_k_AcadosOcpSolverCython___get_stat), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython___get_stat_2, __pyx_k_AcadosOcpSolverCython___get_stat_2, sizeof(__pyx_k_AcadosOcpSolverCython___get_stat_2), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython___get_stat_3, __pyx_k_AcadosOcpSolverCython___get_stat_3, sizeof(__pyx_k_AcadosOcpSolverCython___get_stat_3), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython___reduce_c, __pyx_k_AcadosOcpSolverCython___reduce_c, sizeof(__pyx_k_AcadosOcpSolverCython___reduce_c), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython___setstate, __pyx_k_AcadosOcpSolverCython___setstate, sizeof(__pyx_k_AcadosOcpSolverCython___setstate), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython__get_poin, __pyx_k_AcadosOcpSolverCython__get_poin, sizeof(__pyx_k_AcadosOcpSolverCython__get_poin), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython__get_stat, __pyx_k_AcadosOcpSolverCython__get_stat, sizeof(__pyx_k_AcadosOcpSolverCython__get_stat), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython__get_stat_2, __pyx_k_AcadosOcpSolverCython__get_stat_2, sizeof(__pyx_k_AcadosOcpSolverCython__get_stat_2), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython__get_stat_3, __pyx_k_AcadosOcpSolverCython__get_stat_3, sizeof(__pyx_k_AcadosOcpSolverCython__get_stat_3), 0, 0, 1, 1}, + {&__pyx_kp_u_AcadosOcpSolverCython_constraint, __pyx_k_AcadosOcpSolverCython_constraint, sizeof(__pyx_k_AcadosOcpSolverCython_constraint), 0, 1, 0, 0}, + {&__pyx_n_s_AcadosOcpSolverCython_constraint_2, __pyx_k_AcadosOcpSolverCython_constraint_2, sizeof(__pyx_k_AcadosOcpSolverCython_constraint_2), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython_cost_set, __pyx_k_AcadosOcpSolverCython_cost_set, sizeof(__pyx_k_AcadosOcpSolverCython_cost_set), 0, 0, 1, 1}, + {&__pyx_kp_u_AcadosOcpSolverCython_cost_set_m, __pyx_k_AcadosOcpSolverCython_cost_set_m, sizeof(__pyx_k_AcadosOcpSolverCython_cost_set_m), 0, 1, 0, 0}, + {&__pyx_n_s_AcadosOcpSolverCython_custom_upd, __pyx_k_AcadosOcpSolverCython_custom_upd, sizeof(__pyx_k_AcadosOcpSolverCython_custom_upd), 0, 0, 1, 1}, + {&__pyx_kp_u_AcadosOcpSolverCython_does_not_s, __pyx_k_AcadosOcpSolverCython_does_not_s, sizeof(__pyx_k_AcadosOcpSolverCython_does_not_s), 0, 1, 0, 0}, + {&__pyx_kp_u_AcadosOcpSolverCython_does_not_s_2, __pyx_k_AcadosOcpSolverCython_does_not_s_2, sizeof(__pyx_k_AcadosOcpSolverCython_does_not_s_2), 0, 1, 0, 0}, + {&__pyx_kp_u_AcadosOcpSolverCython_eval_param, __pyx_k_AcadosOcpSolverCython_eval_param, sizeof(__pyx_k_AcadosOcpSolverCython_eval_param), 0, 1, 0, 0}, + {&__pyx_kp_u_AcadosOcpSolverCython_eval_param_2, __pyx_k_AcadosOcpSolverCython_eval_param_2, sizeof(__pyx_k_AcadosOcpSolverCython_eval_param_2), 0, 1, 0, 0}, + {&__pyx_n_s_AcadosOcpSolverCython_eval_param_3, __pyx_k_AcadosOcpSolverCython_eval_param_3, sizeof(__pyx_k_AcadosOcpSolverCython_eval_param_3), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython_get, __pyx_k_AcadosOcpSolverCython_get, sizeof(__pyx_k_AcadosOcpSolverCython_get), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython_get_cost, __pyx_k_AcadosOcpSolverCython_get_cost, sizeof(__pyx_k_AcadosOcpSolverCython_get_cost), 0, 0, 1, 1}, + {&__pyx_kp_u_AcadosOcpSolverCython_get_field, __pyx_k_AcadosOcpSolverCython_get_field, sizeof(__pyx_k_AcadosOcpSolverCython_get_field), 0, 1, 0, 0}, + {&__pyx_n_s_AcadosOcpSolverCython_get_from_q, __pyx_k_AcadosOcpSolverCython_get_from_q, sizeof(__pyx_k_AcadosOcpSolverCython_get_from_q), 0, 0, 1, 1}, + {&__pyx_kp_u_AcadosOcpSolverCython_get_is_an, __pyx_k_AcadosOcpSolverCython_get_is_an, sizeof(__pyx_k_AcadosOcpSolverCython_get_is_an), 0, 1, 0, 0}, + {&__pyx_n_s_AcadosOcpSolverCython_get_residu, __pyx_k_AcadosOcpSolverCython_get_residu, sizeof(__pyx_k_AcadosOcpSolverCython_get_residu), 0, 0, 1, 1}, + {&__pyx_kp_u_AcadosOcpSolverCython_get_stage, __pyx_k_AcadosOcpSolverCython_get_stage, sizeof(__pyx_k_AcadosOcpSolverCython_get_stage), 0, 1, 0, 0}, + {&__pyx_n_s_AcadosOcpSolverCython_get_stats, __pyx_k_AcadosOcpSolverCython_get_stats, sizeof(__pyx_k_AcadosOcpSolverCython_get_stats), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython_load_itera, __pyx_k_AcadosOcpSolverCython_load_itera, sizeof(__pyx_k_AcadosOcpSolverCython_load_itera), 0, 0, 1, 1}, + {&__pyx_kp_u_AcadosOcpSolverCython_options_se, __pyx_k_AcadosOcpSolverCython_options_se, sizeof(__pyx_k_AcadosOcpSolverCython_options_se), 0, 1, 0, 0}, + {&__pyx_n_s_AcadosOcpSolverCython_options_se_2, __pyx_k_AcadosOcpSolverCython_options_se_2, sizeof(__pyx_k_AcadosOcpSolverCython_options_se_2), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython_print_stat, __pyx_k_AcadosOcpSolverCython_print_stat, sizeof(__pyx_k_AcadosOcpSolverCython_print_stat), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython_reset, __pyx_k_AcadosOcpSolverCython_reset, sizeof(__pyx_k_AcadosOcpSolverCython_reset), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython_set, __pyx_k_AcadosOcpSolverCython_set, sizeof(__pyx_k_AcadosOcpSolverCython_set), 0, 0, 1, 1}, + {&__pyx_kp_u_AcadosOcpSolverCython_set_is_not, __pyx_k_AcadosOcpSolverCython_set_is_not, sizeof(__pyx_k_AcadosOcpSolverCython_set_is_not), 0, 1, 0, 0}, + {&__pyx_kp_u_AcadosOcpSolverCython_set_mismat, __pyx_k_AcadosOcpSolverCython_set_mismat, sizeof(__pyx_k_AcadosOcpSolverCython_set_mismat), 0, 1, 0, 0}, + {&__pyx_n_s_AcadosOcpSolverCython_set_new_ti, __pyx_k_AcadosOcpSolverCython_set_new_ti, sizeof(__pyx_k_AcadosOcpSolverCython_set_new_ti), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython_set_params, __pyx_k_AcadosOcpSolverCython_set_params, sizeof(__pyx_k_AcadosOcpSolverCython_set_params), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython_solve, __pyx_k_AcadosOcpSolverCython_solve, sizeof(__pyx_k_AcadosOcpSolverCython_solve), 0, 0, 1, 1}, + {&__pyx_kp_u_AcadosOcpSolverCython_solve_argu, __pyx_k_AcadosOcpSolverCython_solve_argu, sizeof(__pyx_k_AcadosOcpSolverCython_solve_argu), 0, 1, 0, 0}, + {&__pyx_kp_u_AcadosOcpSolverCython_solve_argu_2, __pyx_k_AcadosOcpSolverCython_solve_argu_2, sizeof(__pyx_k_AcadosOcpSolverCython_solve_argu_2), 0, 1, 0, 0}, + {&__pyx_n_s_AcadosOcpSolverCython_solve_for, __pyx_k_AcadosOcpSolverCython_solve_for, sizeof(__pyx_k_AcadosOcpSolverCython_solve_for), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython_store_iter, __pyx_k_AcadosOcpSolverCython_store_iter, sizeof(__pyx_k_AcadosOcpSolverCython_store_iter), 0, 0, 1, 1}, + {&__pyx_n_s_AcadosOcpSolverCython_update_qp, __pyx_k_AcadosOcpSolverCython_update_qp, sizeof(__pyx_k_AcadosOcpSolverCython_update_qp), 0, 0, 1, 1}, + {&__pyx_kp_s_All_dimensions_preceding_dimensi, __pyx_k_All_dimensions_preceding_dimensi, sizeof(__pyx_k_All_dimensions_preceding_dimensi), 0, 0, 1, 0}, + {&__pyx_n_s_AssertionError, __pyx_k_AssertionError, sizeof(__pyx_k_AssertionError), 0, 0, 1, 1}, + {&__pyx_kp_s_Buffer_view_does_not_expose_stri, __pyx_k_Buffer_view_does_not_expose_stri, sizeof(__pyx_k_Buffer_view_does_not_expose_stri), 0, 0, 1, 0}, + {&__pyx_kp_s_Can_only_create_a_buffer_that_is, __pyx_k_Can_only_create_a_buffer_that_is, sizeof(__pyx_k_Can_only_create_a_buffer_that_is), 0, 0, 1, 0}, + {&__pyx_kp_s_Cannot_assign_to_read_only_memor, __pyx_k_Cannot_assign_to_read_only_memor, sizeof(__pyx_k_Cannot_assign_to_read_only_memor), 0, 0, 1, 0}, + {&__pyx_kp_s_Cannot_create_writable_memory_vi, __pyx_k_Cannot_create_writable_memory_vi, sizeof(__pyx_k_Cannot_create_writable_memory_vi), 0, 0, 1, 0}, + {&__pyx_kp_u_Cannot_index_with_type, __pyx_k_Cannot_index_with_type, sizeof(__pyx_k_Cannot_index_with_type), 0, 1, 0, 0}, + {&__pyx_kp_s_Cannot_transpose_memoryview_with, __pyx_k_Cannot_transpose_memoryview_with, sizeof(__pyx_k_Cannot_transpose_memoryview_with), 0, 0, 1, 0}, + {&__pyx_kp_s_Dimension_d_is_not_direct, __pyx_k_Dimension_d_is_not_direct, sizeof(__pyx_k_Dimension_d_is_not_direct), 0, 0, 1, 0}, + {&__pyx_n_s_Ellipsis, __pyx_k_Ellipsis, sizeof(__pyx_k_Ellipsis), 0, 0, 1, 1}, + {&__pyx_kp_s_Empty_shape_tuple_for_cython_arr, __pyx_k_Empty_shape_tuple_for_cython_arr, sizeof(__pyx_k_Empty_shape_tuple_for_cython_arr), 0, 0, 1, 0}, + {&__pyx_n_u_F, __pyx_k_F, sizeof(__pyx_k_F), 0, 1, 0, 1}, + {&__pyx_kp_u_Got_sizes_idx, __pyx_k_Got_sizes_idx, sizeof(__pyx_k_Got_sizes_idx), 0, 1, 0, 0}, + {&__pyx_n_s_ImportError, __pyx_k_ImportError, sizeof(__pyx_k_ImportError), 0, 0, 1, 1}, + {&__pyx_kp_s_Incompatible_checksums_0x_x_vs_0, __pyx_k_Incompatible_checksums_0x_x_vs_0, sizeof(__pyx_k_Incompatible_checksums_0x_x_vs_0), 0, 0, 1, 0}, + {&__pyx_n_s_IndexError, __pyx_k_IndexError, sizeof(__pyx_k_IndexError), 0, 0, 1, 1}, + {&__pyx_kp_s_Index_out_of_bounds_axis_d, __pyx_k_Index_out_of_bounds_axis_d, sizeof(__pyx_k_Index_out_of_bounds_axis_d), 0, 0, 1, 0}, + {&__pyx_kp_s_Indirect_dimensions_not_supporte, __pyx_k_Indirect_dimensions_not_supporte, sizeof(__pyx_k_Indirect_dimensions_not_supporte), 0, 0, 1, 0}, + {&__pyx_kp_u_Invalid_mode_expected_c_or_fortr, __pyx_k_Invalid_mode_expected_c_or_fortr, sizeof(__pyx_k_Invalid_mode_expected_c_or_fortr), 0, 1, 0, 0}, + {&__pyx_kp_u_Invalid_shape_in_axis, __pyx_k_Invalid_shape_in_axis, sizeof(__pyx_k_Invalid_shape_in_axis), 0, 1, 0, 0}, + {&__pyx_n_s_MemoryError, __pyx_k_MemoryError, sizeof(__pyx_k_MemoryError), 0, 0, 1, 1}, + {&__pyx_kp_s_MemoryView_of_r_at_0x_x, __pyx_k_MemoryView_of_r_at_0x_x, sizeof(__pyx_k_MemoryView_of_r_at_0x_x), 0, 0, 1, 0}, + {&__pyx_kp_s_MemoryView_of_r_object, __pyx_k_MemoryView_of_r_object, sizeof(__pyx_k_MemoryView_of_r_object), 0, 0, 1, 0}, + {&__pyx_n_s_N, __pyx_k_N, sizeof(__pyx_k_N), 0, 0, 1, 1}, + {&__pyx_kp_u_None, __pyx_k_None, sizeof(__pyx_k_None), 0, 1, 0, 0}, + {&__pyx_n_s_NotImplementedError, __pyx_k_NotImplementedError, sizeof(__pyx_k_NotImplementedError), 0, 0, 1, 1}, + {&__pyx_n_b_O, __pyx_k_O, sizeof(__pyx_k_O), 0, 0, 0, 1}, + {&__pyx_kp_u_Out_of_bounds_on_buffer_access_a, __pyx_k_Out_of_bounds_on_buffer_access_a, sizeof(__pyx_k_Out_of_bounds_on_buffer_access_a), 0, 1, 0, 0}, + {&__pyx_n_s_PickleError, __pyx_k_PickleError, sizeof(__pyx_k_PickleError), 0, 0, 1, 1}, + {&__pyx_n_u_SQP, __pyx_k_SQP, sizeof(__pyx_k_SQP), 0, 1, 0, 1}, + {&__pyx_n_u_SQP_RTI, __pyx_k_SQP_RTI, sizeof(__pyx_k_SQP_RTI), 0, 1, 0, 1}, + {&__pyx_n_s_Sequence, __pyx_k_Sequence, sizeof(__pyx_k_Sequence), 0, 0, 1, 1}, + {&__pyx_kp_s_Step_may_not_be_zero_axis_d, __pyx_k_Step_may_not_be_zero_axis_d, sizeof(__pyx_k_Step_may_not_be_zero_axis_d), 0, 0, 1, 0}, + {&__pyx_kp_u_TODO, __pyx_k_TODO, sizeof(__pyx_k_TODO), 0, 1, 0, 0}, + {&__pyx_n_s_TypeError, __pyx_k_TypeError, sizeof(__pyx_k_TypeError), 0, 0, 1, 1}, + {&__pyx_kp_s_Unable_to_convert_item_to_object, __pyx_k_Unable_to_convert_item_to_object, sizeof(__pyx_k_Unable_to_convert_item_to_object), 0, 0, 1, 0}, + {&__pyx_n_s_ValueError, __pyx_k_ValueError, sizeof(__pyx_k_ValueError), 0, 0, 1, 1}, + {&__pyx_n_s_View_MemoryView, __pyx_k_View_MemoryView, sizeof(__pyx_k_View_MemoryView), 0, 0, 1, 1}, + {&__pyx_kp_u_Warning_acados_ocp_solver_reache, __pyx_k_Warning_acados_ocp_solver_reache, sizeof(__pyx_k_Warning_acados_ocp_solver_reache), 0, 1, 0, 0}, + {&__pyx_kp_u_Y_m_d_H_M_S_f, __pyx_k_Y_m_d_H_M_S_f, sizeof(__pyx_k_Y_m_d_H_M_S_f), 0, 1, 0, 0}, + {&__pyx_kp_u__16, __pyx_k__16, sizeof(__pyx_k__16), 0, 1, 0, 0}, + {&__pyx_n_u__17, __pyx_k__17, sizeof(__pyx_k__17), 0, 1, 0, 1}, + {&__pyx_kp_u__2, __pyx_k__2, sizeof(__pyx_k__2), 0, 1, 0, 0}, + {&__pyx_n_s__3, __pyx_k__3, sizeof(__pyx_k__3), 0, 0, 1, 1}, + {&__pyx_kp_u__31, __pyx_k__31, sizeof(__pyx_k__31), 0, 1, 0, 0}, + {&__pyx_kp_u__6, __pyx_k__6, sizeof(__pyx_k__6), 0, 1, 0, 0}, + {&__pyx_kp_u__7, __pyx_k__7, sizeof(__pyx_k__7), 0, 1, 0, 0}, + {&__pyx_n_s__94, __pyx_k__94, sizeof(__pyx_k__94), 0, 0, 1, 1}, + {&__pyx_n_s_abc, __pyx_k_abc, sizeof(__pyx_k_abc), 0, 0, 1, 1}, + {&__pyx_kp_u_acados_acados_ocp_solver_returne, __pyx_k_acados_acados_ocp_solver_returne, sizeof(__pyx_k_acados_acados_ocp_solver_returne), 0, 1, 0, 0}, + {&__pyx_n_s_acados_template_acados_ocp_solve, __pyx_k_acados_template_acados_ocp_solve, sizeof(__pyx_k_acados_template_acados_ocp_solve), 0, 0, 1, 1}, + {&__pyx_n_s_allocate_buffer, __pyx_k_allocate_buffer, sizeof(__pyx_k_allocate_buffer), 0, 0, 1, 1}, + {&__pyx_n_u_alpha, __pyx_k_alpha, sizeof(__pyx_k_alpha), 0, 1, 0, 1}, + {&__pyx_n_u_alpha_min, __pyx_k_alpha_min, sizeof(__pyx_k_alpha_min), 0, 1, 0, 1}, + {&__pyx_n_u_alpha_reduction, __pyx_k_alpha_reduction, sizeof(__pyx_k_alpha_reduction), 0, 1, 0, 1}, + {&__pyx_kp_u_alpha_values_are_not_available_f, __pyx_k_alpha_values_are_not_available_f, sizeof(__pyx_k_alpha_values_are_not_available_f), 0, 1, 0, 0}, + {&__pyx_kp_u_and, __pyx_k_and, sizeof(__pyx_k_and), 0, 1, 0, 0}, + {&__pyx_n_s_array, __pyx_k_array, sizeof(__pyx_k_array), 0, 0, 1, 1}, + {&__pyx_n_s_ascontiguousarray, __pyx_k_ascontiguousarray, sizeof(__pyx_k_ascontiguousarray), 0, 0, 1, 1}, + {&__pyx_n_s_asfortranarray, __pyx_k_asfortranarray, sizeof(__pyx_k_asfortranarray), 0, 0, 1, 1}, + {&__pyx_n_s_asyncio_coroutines, __pyx_k_asyncio_coroutines, sizeof(__pyx_k_asyncio_coroutines), 0, 0, 1, 1}, + {&__pyx_kp_u_at_stage, __pyx_k_at_stage, sizeof(__pyx_k_at_stage), 0, 1, 0, 0}, + {&__pyx_n_s_base, __pyx_k_base, sizeof(__pyx_k_base), 0, 0, 1, 1}, + {&__pyx_n_s_c, __pyx_k_c, sizeof(__pyx_k_c), 0, 0, 1, 1}, + {&__pyx_n_u_c, __pyx_k_c, sizeof(__pyx_k_c), 0, 1, 0, 1}, + {&__pyx_n_s_class, __pyx_k_class, sizeof(__pyx_k_class), 0, 0, 1, 1}, + {&__pyx_n_s_class_getitem, __pyx_k_class_getitem, sizeof(__pyx_k_class_getitem), 0, 0, 1, 1}, + {&__pyx_n_s_cline_in_traceback, __pyx_k_cline_in_traceback, sizeof(__pyx_k_cline_in_traceback), 0, 0, 1, 1}, + {&__pyx_n_s_collections, __pyx_k_collections, sizeof(__pyx_k_collections), 0, 0, 1, 1}, + {&__pyx_kp_s_collections_abc, __pyx_k_collections_abc, sizeof(__pyx_k_collections_abc), 0, 0, 1, 0}, + {&__pyx_n_s_constraints_fields, __pyx_k_constraints_fields, sizeof(__pyx_k_constraints_fields), 0, 0, 1, 1}, + {&__pyx_n_s_constraints_set, __pyx_k_constraints_set, sizeof(__pyx_k_constraints_set), 0, 0, 1, 1}, + {&__pyx_kp_u_constraints_set_value_must_be_nu, __pyx_k_constraints_set_value_must_be_nu, sizeof(__pyx_k_constraints_set_value_must_be_nu), 0, 1, 0, 0}, + {&__pyx_kp_s_contiguous_and_direct, __pyx_k_contiguous_and_direct, sizeof(__pyx_k_contiguous_and_direct), 0, 0, 1, 0}, + {&__pyx_kp_s_contiguous_and_indirect, __pyx_k_contiguous_and_indirect, sizeof(__pyx_k_contiguous_and_indirect), 0, 0, 1, 0}, + {&__pyx_n_s_cost_fields, __pyx_k_cost_fields, sizeof(__pyx_k_cost_fields), 0, 0, 1, 1}, + {&__pyx_n_s_cost_set, __pyx_k_cost_set, sizeof(__pyx_k_cost_set), 0, 0, 1, 1}, + {&__pyx_kp_u_cost_set_value_must_be_numpy_arr, __pyx_k_cost_set_value_must_be_numpy_arr, sizeof(__pyx_k_cost_set_value_must_be_numpy_arr), 0, 1, 0, 0}, + {&__pyx_n_s_count, __pyx_k_count, sizeof(__pyx_k_count), 0, 0, 1, 1}, + {&__pyx_n_s_custom_update, __pyx_k_custom_update, sizeof(__pyx_k_custom_update), 0, 0, 1, 1}, + {&__pyx_n_u_d, __pyx_k_d, sizeof(__pyx_k_d), 0, 1, 0, 1}, + {&__pyx_n_s_data, __pyx_k_data, sizeof(__pyx_k_data), 0, 0, 1, 1}, + {&__pyx_n_s_data_2, __pyx_k_data_2, sizeof(__pyx_k_data_2), 0, 0, 1, 1}, + {&__pyx_n_s_data_len, __pyx_k_data_len, sizeof(__pyx_k_data_len), 0, 0, 1, 1}, + {&__pyx_n_s_datetime, __pyx_k_datetime, sizeof(__pyx_k_datetime), 0, 0, 1, 1}, + {&__pyx_n_s_default, __pyx_k_default, sizeof(__pyx_k_default), 0, 0, 1, 1}, + {&__pyx_n_s_dict, __pyx_k_dict, sizeof(__pyx_k_dict), 0, 0, 1, 1}, + {&__pyx_n_s_dims, __pyx_k_dims, sizeof(__pyx_k_dims), 0, 0, 1, 1}, + {&__pyx_kp_u_disable, __pyx_k_disable, sizeof(__pyx_k_disable), 0, 1, 0, 0}, + {&__pyx_n_s_double_fields, __pyx_k_double_fields, sizeof(__pyx_k_double_fields), 0, 0, 1, 1}, + {&__pyx_n_s_double_value, __pyx_k_double_value, sizeof(__pyx_k_double_value), 0, 0, 1, 1}, + {&__pyx_n_s_dtype, __pyx_k_dtype, sizeof(__pyx_k_dtype), 0, 0, 1, 1}, + {&__pyx_n_s_dtype_is_object, __pyx_k_dtype_is_object, sizeof(__pyx_k_dtype_is_object), 0, 0, 1, 1}, + {&__pyx_n_s_dump, __pyx_k_dump, sizeof(__pyx_k_dump), 0, 0, 1, 1}, + {&__pyx_kp_u_enable, __pyx_k_enable, sizeof(__pyx_k_enable), 0, 1, 0, 0}, + {&__pyx_n_s_encode, __pyx_k_encode, sizeof(__pyx_k_encode), 0, 0, 1, 1}, + {&__pyx_n_s_enter, __pyx_k_enter, sizeof(__pyx_k_enter), 0, 0, 1, 1}, + {&__pyx_n_s_enumerate, __pyx_k_enumerate, sizeof(__pyx_k_enumerate), 0, 0, 1, 1}, + {&__pyx_n_u_eps_sufficient_descent, __pyx_k_eps_sufficient_descent, sizeof(__pyx_k_eps_sufficient_descent), 0, 1, 0, 1}, + {&__pyx_n_s_error, __pyx_k_error, sizeof(__pyx_k_error), 0, 0, 1, 1}, + {&__pyx_n_s_eval_param_sens, __pyx_k_eval_param_sens, sizeof(__pyx_k_eval_param_sens), 0, 0, 1, 1}, + {&__pyx_n_u_ex, __pyx_k_ex, sizeof(__pyx_k_ex), 0, 1, 0, 1}, + {&__pyx_n_s_exit, __pyx_k_exit, sizeof(__pyx_k_exit), 0, 0, 1, 1}, + {&__pyx_n_s_f, __pyx_k_f, sizeof(__pyx_k_f), 0, 0, 1, 1}, + {&__pyx_n_s_field, __pyx_k_field, sizeof(__pyx_k_field), 0, 0, 1, 1}, + {&__pyx_n_s_field_2, __pyx_k_field_2, sizeof(__pyx_k_field_2), 0, 0, 1, 1}, + {&__pyx_n_s_fields, __pyx_k_fields, sizeof(__pyx_k_fields), 0, 0, 1, 1}, + {&__pyx_n_s_filename, __pyx_k_filename, sizeof(__pyx_k_filename), 0, 0, 1, 1}, + {&__pyx_n_s_flags, __pyx_k_flags, sizeof(__pyx_k_flags), 0, 0, 1, 1}, + {&__pyx_n_s_float64, __pyx_k_float64, sizeof(__pyx_k_float64), 0, 0, 1, 1}, + {&__pyx_kp_u_for_field, __pyx_k_for_field, sizeof(__pyx_k_for_field), 0, 1, 0, 0}, + {&__pyx_n_s_format, __pyx_k_format, sizeof(__pyx_k_format), 0, 0, 1, 1}, + {&__pyx_n_s_fortran, __pyx_k_fortran, sizeof(__pyx_k_fortran), 0, 0, 1, 1}, + {&__pyx_n_u_fortran, __pyx_k_fortran, sizeof(__pyx_k_fortran), 0, 1, 0, 1}, + {&__pyx_n_s_full_stats, __pyx_k_full_stats, sizeof(__pyx_k_full_stats), 0, 0, 1, 1}, + {&__pyx_n_u_full_step_dual, __pyx_k_full_step_dual, sizeof(__pyx_k_full_step_dual), 0, 1, 0, 1}, + {&__pyx_kp_u_gc, __pyx_k_gc, sizeof(__pyx_k_gc), 0, 1, 0, 0}, + {&__pyx_n_s_get, __pyx_k_get, sizeof(__pyx_k_get), 0, 0, 1, 1}, + {&__pyx_n_s_get_cost, __pyx_k_get_cost, sizeof(__pyx_k_get_cost), 0, 0, 1, 1}, + {&__pyx_n_s_get_from_qp_in, __pyx_k_get_from_qp_in, sizeof(__pyx_k_get_from_qp_in), 0, 0, 1, 1}, + {&__pyx_n_s_get_pointers_solver, __pyx_k_get_pointers_solver, sizeof(__pyx_k_get_pointers_solver), 0, 0, 1, 1}, + {&__pyx_n_s_get_residuals, __pyx_k_get_residuals, sizeof(__pyx_k_get_residuals), 0, 0, 1, 1}, + {&__pyx_n_s_get_stat_double, __pyx_k_get_stat_double, sizeof(__pyx_k_get_stat_double), 0, 0, 1, 1}, + {&__pyx_n_s_get_stat_int, __pyx_k_get_stat_int, sizeof(__pyx_k_get_stat_int), 0, 0, 1, 1}, + {&__pyx_n_s_get_stat_matrix, __pyx_k_get_stat_matrix, sizeof(__pyx_k_get_stat_matrix), 0, 0, 1, 1}, + {&__pyx_n_s_get_stats, __pyx_k_get_stats, sizeof(__pyx_k_get_stats), 0, 0, 1, 1}, + {&__pyx_n_s_getcwd, __pyx_k_getcwd, sizeof(__pyx_k_getcwd), 0, 0, 1, 1}, + {&__pyx_n_s_getstate, __pyx_k_getstate, sizeof(__pyx_k_getstate), 0, 0, 1, 1}, + {&__pyx_n_u_globalization, __pyx_k_globalization, sizeof(__pyx_k_globalization), 0, 1, 0, 1}, + {&__pyx_n_u_globalization_use_SOC, __pyx_k_globalization_use_SOC, sizeof(__pyx_k_globalization_use_SOC), 0, 1, 0, 1}, + {&__pyx_kp_u_got, __pyx_k_got, sizeof(__pyx_k_got), 0, 1, 0, 0}, + {&__pyx_kp_u_got_differing_extents_in_dimensi, __pyx_k_got_differing_extents_in_dimensi, sizeof(__pyx_k_got_differing_extents_in_dimensi), 0, 1, 0, 0}, + {&__pyx_n_s_i, __pyx_k_i, sizeof(__pyx_k_i), 0, 0, 1, 1}, + {&__pyx_n_s_i_string, __pyx_k_i_string, sizeof(__pyx_k_i_string), 0, 0, 1, 1}, + {&__pyx_n_s_id, __pyx_k_id, sizeof(__pyx_k_id), 0, 0, 1, 1}, + {&__pyx_n_s_idx, __pyx_k_idx, sizeof(__pyx_k_idx), 0, 0, 1, 1}, + {&__pyx_n_s_idx_values, __pyx_k_idx_values, sizeof(__pyx_k_idx_values), 0, 0, 1, 1}, + {&__pyx_n_s_import, __pyx_k_import, sizeof(__pyx_k_import), 0, 0, 1, 1}, + {&__pyx_n_s_indent, __pyx_k_indent, sizeof(__pyx_k_indent), 0, 0, 1, 1}, + {&__pyx_n_s_index, __pyx_k_index, sizeof(__pyx_k_index), 0, 0, 1, 1}, + {&__pyx_n_u_initialize_t_slacks, __pyx_k_initialize_t_slacks, sizeof(__pyx_k_initialize_t_slacks), 0, 1, 0, 1}, + {&__pyx_n_s_initializing, __pyx_k_initializing, sizeof(__pyx_k_initializing), 0, 0, 1, 1}, + {&__pyx_n_s_int, __pyx_k_int, sizeof(__pyx_k_int), 0, 0, 1, 1}, + {&__pyx_n_s_int32, __pyx_k_int32, sizeof(__pyx_k_int32), 0, 0, 1, 1}, + {&__pyx_n_s_int_fields, __pyx_k_int_fields, sizeof(__pyx_k_int_fields), 0, 0, 1, 1}, + {&__pyx_n_s_int_value, __pyx_k_int_value, sizeof(__pyx_k_int_value), 0, 0, 1, 1}, + {&__pyx_n_s_is_coroutine, __pyx_k_is_coroutine, sizeof(__pyx_k_is_coroutine), 0, 0, 1, 1}, + {&__pyx_kp_u_isenabled, __pyx_k_isenabled, sizeof(__pyx_k_isenabled), 0, 1, 0, 0}, + {&__pyx_n_s_isfile, __pyx_k_isfile, sizeof(__pyx_k_isfile), 0, 0, 1, 1}, + {&__pyx_n_s_itemsize, __pyx_k_itemsize, sizeof(__pyx_k_itemsize), 0, 0, 1, 1}, + {&__pyx_kp_s_itemsize_0_for_cython_array, __pyx_k_itemsize_0_for_cython_array, sizeof(__pyx_k_itemsize_0_for_cython_array), 0, 0, 1, 0}, + {&__pyx_n_u_iterate, __pyx_k_iterate, sizeof(__pyx_k_iterate), 0, 1, 0, 1}, + {&__pyx_n_s_join, __pyx_k_join, sizeof(__pyx_k_join), 0, 0, 1, 1}, + {&__pyx_n_s_json, __pyx_k_json, sizeof(__pyx_k_json), 0, 0, 1, 1}, + {&__pyx_kp_u_json_2, __pyx_k_json_2, sizeof(__pyx_k_json_2), 0, 1, 0, 0}, + {&__pyx_n_s_k, __pyx_k_k, sizeof(__pyx_k_k), 0, 0, 1, 1}, + {&__pyx_n_s_key, __pyx_k_key, sizeof(__pyx_k_key), 0, 0, 1, 1}, + {&__pyx_n_s_keys, __pyx_k_keys, sizeof(__pyx_k_keys), 0, 0, 1, 1}, + {&__pyx_n_s_lN, __pyx_k_lN, sizeof(__pyx_k_lN), 0, 0, 1, 1}, + {&__pyx_n_u_lam, __pyx_k_lam, sizeof(__pyx_k_lam), 0, 1, 0, 1}, + {&__pyx_n_u_lam_2, __pyx_k_lam_2, sizeof(__pyx_k_lam_2), 0, 1, 0, 1}, + {&__pyx_n_u_lbu, __pyx_k_lbu, sizeof(__pyx_k_lbu), 0, 1, 0, 1}, + {&__pyx_n_u_lbx, __pyx_k_lbx, sizeof(__pyx_k_lbx), 0, 1, 0, 1}, + {&__pyx_n_u_line_search_use_sufficient_desce, __pyx_k_line_search_use_sufficient_desce, sizeof(__pyx_k_line_search_use_sufficient_desce), 0, 1, 0, 1}, + {&__pyx_n_s_load, __pyx_k_load, sizeof(__pyx_k_load), 0, 0, 1, 1}, + {&__pyx_n_s_load_iterate, __pyx_k_load_iterate, sizeof(__pyx_k_load_iterate), 0, 0, 1, 1}, + {&__pyx_kp_u_load_iterate_failed_file_does_no, __pyx_k_load_iterate_failed_file_does_no, sizeof(__pyx_k_load_iterate_failed_file_does_no), 0, 1, 0, 0}, + {&__pyx_n_s_m, __pyx_k_m, sizeof(__pyx_k_m), 0, 0, 1, 1}, + {&__pyx_n_s_main, __pyx_k_main, sizeof(__pyx_k_main), 0, 0, 1, 1}, + {&__pyx_n_s_mem_fields, __pyx_k_mem_fields, sizeof(__pyx_k_mem_fields), 0, 0, 1, 1}, + {&__pyx_n_s_memview, __pyx_k_memview, sizeof(__pyx_k_memview), 0, 0, 1, 1}, + {&__pyx_n_s_min_size, __pyx_k_min_size, sizeof(__pyx_k_min_size), 0, 0, 1, 1}, + {&__pyx_n_s_mode, __pyx_k_mode, sizeof(__pyx_k_mode), 0, 0, 1, 1}, + {&__pyx_n_s_model_name, __pyx_k_model_name, sizeof(__pyx_k_model_name), 0, 0, 1, 1}, + {&__pyx_n_s_msg, __pyx_k_msg, sizeof(__pyx_k_msg), 0, 0, 1, 1}, + {&__pyx_n_s_n, __pyx_k_n, sizeof(__pyx_k_n), 0, 0, 1, 1}, + {&__pyx_n_s_n_update, __pyx_k_n_update, sizeof(__pyx_k_n_update), 0, 0, 1, 1}, + {&__pyx_n_s_name, __pyx_k_name, sizeof(__pyx_k_name), 0, 0, 1, 1}, + {&__pyx_n_s_name_2, __pyx_k_name_2, sizeof(__pyx_k_name_2), 0, 0, 1, 1}, + {&__pyx_n_s_ndarray, __pyx_k_ndarray, sizeof(__pyx_k_ndarray), 0, 0, 1, 1}, + {&__pyx_n_s_ndim, __pyx_k_ndim, sizeof(__pyx_k_ndim), 0, 0, 1, 1}, + {&__pyx_n_s_new, __pyx_k_new, sizeof(__pyx_k_new), 0, 0, 1, 1}, + {&__pyx_n_s_new_time_steps, __pyx_k_new_time_steps, sizeof(__pyx_k_new_time_steps), 0, 0, 1, 1}, + {&__pyx_n_s_nlp_solver_type, __pyx_k_nlp_solver_type, sizeof(__pyx_k_nlp_solver_type), 0, 0, 1, 1}, + {&__pyx_kp_s_no_default___reduce___due_to_non, __pyx_k_no_default___reduce___due_to_non, sizeof(__pyx_k_no_default___reduce___due_to_non), 0, 0, 1, 0}, + {&__pyx_n_s_np, __pyx_k_np, sizeof(__pyx_k_np), 0, 0, 1, 1}, + {&__pyx_n_s_numpy, __pyx_k_numpy, sizeof(__pyx_k_numpy), 0, 0, 1, 1}, + {&__pyx_kp_u_numpy_core_multiarray_failed_to, __pyx_k_numpy_core_multiarray_failed_to, sizeof(__pyx_k_numpy_core_multiarray_failed_to), 0, 1, 0, 0}, + {&__pyx_kp_u_numpy_core_umath_failed_to_impor, __pyx_k_numpy_core_umath_failed_to_impor, sizeof(__pyx_k_numpy_core_umath_failed_to_impor), 0, 1, 0, 0}, + {&__pyx_n_s_nx, __pyx_k_nx, sizeof(__pyx_k_nx), 0, 0, 1, 1}, + {&__pyx_n_s_obj, __pyx_k_obj, sizeof(__pyx_k_obj), 0, 0, 1, 1}, + {&__pyx_n_s_open, __pyx_k_open, sizeof(__pyx_k_open), 0, 0, 1, 1}, + {&__pyx_n_s_options_set, __pyx_k_options_set, sizeof(__pyx_k_options_set), 0, 0, 1, 1}, + {&__pyx_n_s_order, __pyx_k_order, sizeof(__pyx_k_order), 0, 0, 1, 1}, + {&__pyx_n_s_os, __pyx_k_os, sizeof(__pyx_k_os), 0, 0, 1, 1}, + {&__pyx_n_s_out, __pyx_k_out, sizeof(__pyx_k_out), 0, 0, 1, 1}, + {&__pyx_n_s_out_fields, __pyx_k_out_fields, sizeof(__pyx_k_out_fields), 0, 0, 1, 1}, + {&__pyx_n_s_out_mat, __pyx_k_out_mat, sizeof(__pyx_k_out_mat), 0, 0, 1, 1}, + {&__pyx_n_s_overwrite, __pyx_k_overwrite, sizeof(__pyx_k_overwrite), 0, 0, 1, 1}, + {&__pyx_n_u_p, __pyx_k_p, sizeof(__pyx_k_p), 0, 1, 0, 1}, + {&__pyx_n_s_pack, __pyx_k_pack, sizeof(__pyx_k_pack), 0, 0, 1, 1}, + {&__pyx_n_s_param_values, __pyx_k_param_values, sizeof(__pyx_k_param_values), 0, 0, 1, 1}, + {&__pyx_kp_u_param_values_2, __pyx_k_param_values_2, sizeof(__pyx_k_param_values_2), 0, 1, 0, 0}, + {&__pyx_kp_u_param_values__and_idx_values__mu, __pyx_k_param_values__and_idx_values__mu, sizeof(__pyx_k_param_values__and_idx_values__mu), 0, 1, 0, 0}, + {&__pyx_kp_u_param_values__must_be_np_array, __pyx_k_param_values__must_be_np_array, sizeof(__pyx_k_param_values__must_be_np_array), 0, 1, 0, 0}, + {&__pyx_n_s_path, __pyx_k_path, sizeof(__pyx_k_path), 0, 0, 1, 1}, + {&__pyx_n_u_pi, __pyx_k_pi, sizeof(__pyx_k_pi), 0, 1, 0, 1}, + {&__pyx_n_u_pi_2, __pyx_k_pi_2, sizeof(__pyx_k_pi_2), 0, 1, 0, 1}, + {&__pyx_n_s_pickle, __pyx_k_pickle, sizeof(__pyx_k_pickle), 0, 0, 1, 1}, + {&__pyx_n_s_print, __pyx_k_print, sizeof(__pyx_k_print), 0, 0, 1, 1}, + {&__pyx_n_u_print_level, __pyx_k_print_level, sizeof(__pyx_k_print_level), 0, 1, 0, 1}, + {&__pyx_n_s_print_statistics, __pyx_k_print_statistics, sizeof(__pyx_k_print_statistics), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_PickleError, __pyx_k_pyx_PickleError, sizeof(__pyx_k_pyx_PickleError), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_checksum, __pyx_k_pyx_checksum, sizeof(__pyx_k_pyx_checksum), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_result, __pyx_k_pyx_result, sizeof(__pyx_k_pyx_result), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_state, __pyx_k_pyx_state, sizeof(__pyx_k_pyx_state), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_type, __pyx_k_pyx_type, sizeof(__pyx_k_pyx_type), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_unpickle_Enum, __pyx_k_pyx_unpickle_Enum, sizeof(__pyx_k_pyx_unpickle_Enum), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_vtable, __pyx_k_pyx_vtable, sizeof(__pyx_k_pyx_vtable), 0, 0, 1, 1}, + {&__pyx_n_u_qp_iter, __pyx_k_qp_iter, sizeof(__pyx_k_qp_iter), 0, 1, 0, 1}, + {&__pyx_n_u_qp_mu0, __pyx_k_qp_mu0, sizeof(__pyx_k_qp_mu0), 0, 1, 0, 1}, + {&__pyx_n_s_qp_solver_cond_N, __pyx_k_qp_solver_cond_N, sizeof(__pyx_k_qp_solver_cond_N), 0, 0, 1, 1}, + {&__pyx_n_u_qp_tau_min, __pyx_k_qp_tau_min, sizeof(__pyx_k_qp_tau_min), 0, 1, 0, 1}, + {&__pyx_n_u_qp_tol_comp, __pyx_k_qp_tol_comp, sizeof(__pyx_k_qp_tol_comp), 0, 1, 0, 1}, + {&__pyx_n_u_qp_tol_eq, __pyx_k_qp_tol_eq, sizeof(__pyx_k_qp_tol_eq), 0, 1, 0, 1}, + {&__pyx_n_u_qp_tol_ineq, __pyx_k_qp_tol_ineq, sizeof(__pyx_k_qp_tol_ineq), 0, 1, 0, 1}, + {&__pyx_n_u_qp_tol_stat, __pyx_k_qp_tol_stat, sizeof(__pyx_k_qp_tol_stat), 0, 1, 0, 1}, + {&__pyx_n_u_qp_warm_start, __pyx_k_qp_warm_start, sizeof(__pyx_k_qp_warm_start), 0, 1, 0, 1}, + {&__pyx_n_u_r, __pyx_k_r, sizeof(__pyx_k_r), 0, 1, 0, 1}, + {&__pyx_n_s_range, __pyx_k_range, sizeof(__pyx_k_range), 0, 0, 1, 1}, + {&__pyx_n_s_recompute, __pyx_k_recompute, sizeof(__pyx_k_recompute), 0, 0, 1, 1}, + {&__pyx_n_s_reduce, __pyx_k_reduce, sizeof(__pyx_k_reduce), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_cython, __pyx_k_reduce_cython, sizeof(__pyx_k_reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_ex, __pyx_k_reduce_ex, sizeof(__pyx_k_reduce_ex), 0, 0, 1, 1}, + {&__pyx_n_s_register, __pyx_k_register, sizeof(__pyx_k_register), 0, 0, 1, 1}, + {&__pyx_n_b_res_comp, __pyx_k_res_comp, sizeof(__pyx_k_res_comp), 0, 0, 0, 1}, + {&__pyx_n_b_res_eq, __pyx_k_res_eq, sizeof(__pyx_k_res_eq), 0, 0, 0, 1}, + {&__pyx_n_b_res_ineq, __pyx_k_res_ineq, sizeof(__pyx_k_res_ineq), 0, 0, 0, 1}, + {&__pyx_n_b_res_stat, __pyx_k_res_stat, sizeof(__pyx_k_res_stat), 0, 0, 0, 1}, + {&__pyx_n_s_reset, __pyx_k_reset, sizeof(__pyx_k_reset), 0, 0, 1, 1}, + {&__pyx_n_s_reset_qp_solver_mem, __pyx_k_reset_qp_solver_mem, sizeof(__pyx_k_reset_qp_solver_mem), 0, 0, 1, 1}, + {&__pyx_n_u_residuals, __pyx_k_residuals, sizeof(__pyx_k_residuals), 0, 1, 0, 1}, + {&__pyx_n_u_rti_phase, __pyx_k_rti_phase, sizeof(__pyx_k_rti_phase), 0, 1, 0, 1}, + {&__pyx_n_s_self, __pyx_k_self, sizeof(__pyx_k_self), 0, 0, 1, 1}, + {&__pyx_n_s_set, __pyx_k_set, sizeof(__pyx_k_set), 0, 0, 1, 1}, + {&__pyx_n_s_set_new_time_steps, __pyx_k_set_new_time_steps, sizeof(__pyx_k_set_new_time_steps), 0, 0, 1, 1}, + {&__pyx_n_s_set_params_sparse, __pyx_k_set_params_sparse, sizeof(__pyx_k_set_params_sparse), 0, 0, 1, 1}, + {&__pyx_kp_u_set_value_must_be_numpy_array_go, __pyx_k_set_value_must_be_numpy_array_go, sizeof(__pyx_k_set_value_must_be_numpy_array_go), 0, 1, 0, 0}, + {&__pyx_n_s_setstate, __pyx_k_setstate, sizeof(__pyx_k_setstate), 0, 0, 1, 1}, + {&__pyx_n_s_setstate_cython, __pyx_k_setstate_cython, sizeof(__pyx_k_setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_shape, __pyx_k_shape, sizeof(__pyx_k_shape), 0, 0, 1, 1}, + {&__pyx_n_s_size, __pyx_k_size, sizeof(__pyx_k_size), 0, 0, 1, 1}, + {&__pyx_n_u_sl, __pyx_k_sl, sizeof(__pyx_k_sl), 0, 1, 0, 1}, + {&__pyx_n_u_sl_2, __pyx_k_sl_2, sizeof(__pyx_k_sl_2), 0, 1, 0, 1}, + {&__pyx_n_s_solution, __pyx_k_solution, sizeof(__pyx_k_solution), 0, 0, 1, 1}, + {&__pyx_n_s_solve, __pyx_k_solve, sizeof(__pyx_k_solve), 0, 0, 1, 1}, + {&__pyx_n_s_solve_for_x0, __pyx_k_solve_for_x0, sizeof(__pyx_k_solve_for_x0), 0, 0, 1, 1}, + {&__pyx_kp_u_solver_option_must_be_of_type_fl, __pyx_k_solver_option_must_be_of_type_fl, sizeof(__pyx_k_solver_option_must_be_of_type_fl), 0, 1, 0, 0}, + {&__pyx_kp_u_solver_option_must_be_of_type_in, __pyx_k_solver_option_must_be_of_type_in, sizeof(__pyx_k_solver_option_must_be_of_type_in), 0, 1, 0, 0}, + {&__pyx_kp_u_solver_option_must_be_of_type_st, __pyx_k_solver_option_must_be_of_type_st, sizeof(__pyx_k_solver_option_must_be_of_type_st), 0, 1, 0, 0}, + {&__pyx_n_s_sort_keys, __pyx_k_sort_keys, sizeof(__pyx_k_sort_keys), 0, 0, 1, 1}, + {&__pyx_n_s_spec, __pyx_k_spec, sizeof(__pyx_k_spec), 0, 0, 1, 1}, + {&__pyx_n_s_split, __pyx_k_split, sizeof(__pyx_k_split), 0, 0, 1, 1}, + {&__pyx_n_s_sqp_iter, __pyx_k_sqp_iter, sizeof(__pyx_k_sqp_iter), 0, 0, 1, 1}, + {&__pyx_n_u_sqp_iter, __pyx_k_sqp_iter, sizeof(__pyx_k_sqp_iter), 0, 1, 0, 1}, + {&__pyx_n_s_stage, __pyx_k_stage, sizeof(__pyx_k_stage), 0, 0, 1, 1}, + {&__pyx_n_s_start, __pyx_k_start, sizeof(__pyx_k_start), 0, 0, 1, 1}, + {&__pyx_n_s_stat_m, __pyx_k_stat_m, sizeof(__pyx_k_stat_m), 0, 0, 1, 1}, + {&__pyx_n_u_stat_m, __pyx_k_stat_m, sizeof(__pyx_k_stat_m), 0, 1, 0, 1}, + {&__pyx_n_s_stat_n, __pyx_k_stat_n, sizeof(__pyx_k_stat_n), 0, 0, 1, 1}, + {&__pyx_n_u_stat_n, __pyx_k_stat_n, sizeof(__pyx_k_stat_n), 0, 1, 0, 1}, + {&__pyx_n_u_statistics, __pyx_k_statistics, sizeof(__pyx_k_statistics), 0, 1, 0, 1}, + {&__pyx_n_s_status, __pyx_k_status, sizeof(__pyx_k_status), 0, 0, 1, 1}, + {&__pyx_n_s_step, __pyx_k_step, sizeof(__pyx_k_step), 0, 0, 1, 1}, + {&__pyx_n_u_step_length, __pyx_k_step_length, sizeof(__pyx_k_step_length), 0, 1, 0, 1}, + {&__pyx_n_s_stop, __pyx_k_stop, sizeof(__pyx_k_stop), 0, 0, 1, 1}, + {&__pyx_n_s_store_iterate, __pyx_k_store_iterate, sizeof(__pyx_k_store_iterate), 0, 0, 1, 1}, + {&__pyx_n_s_store_iterate_locals_lambda, __pyx_k_store_iterate_locals_lambda, sizeof(__pyx_k_store_iterate_locals_lambda), 0, 0, 1, 1}, + {&__pyx_kp_u_stored_current_iterate_in, __pyx_k_stored_current_iterate_in, sizeof(__pyx_k_stored_current_iterate_in), 0, 1, 0, 0}, + {&__pyx_n_s_strftime, __pyx_k_strftime, sizeof(__pyx_k_strftime), 0, 0, 1, 1}, + {&__pyx_kp_s_strided_and_direct, __pyx_k_strided_and_direct, sizeof(__pyx_k_strided_and_direct), 0, 0, 1, 0}, + {&__pyx_kp_s_strided_and_direct_or_indirect, __pyx_k_strided_and_direct_or_indirect, sizeof(__pyx_k_strided_and_direct_or_indirect), 0, 0, 1, 0}, + {&__pyx_kp_s_strided_and_indirect, __pyx_k_strided_and_indirect, sizeof(__pyx_k_strided_and_indirect), 0, 0, 1, 0}, + {&__pyx_n_s_string_fields, __pyx_k_string_fields, sizeof(__pyx_k_string_fields), 0, 0, 1, 1}, + {&__pyx_n_s_string_value, __pyx_k_string_value, sizeof(__pyx_k_string_value), 0, 0, 1, 1}, + {&__pyx_kp_s_stringsource, __pyx_k_stringsource, sizeof(__pyx_k_stringsource), 0, 0, 1, 0}, + {&__pyx_n_s_struct, __pyx_k_struct, sizeof(__pyx_k_struct), 0, 0, 1, 1}, + {&__pyx_n_u_su, __pyx_k_su, sizeof(__pyx_k_su), 0, 1, 0, 1}, + {&__pyx_n_u_su_2, __pyx_k_su_2, sizeof(__pyx_k_su_2), 0, 1, 0, 1}, + {&__pyx_n_s_sys, __pyx_k_sys, sizeof(__pyx_k_sys), 0, 0, 1, 1}, + {&__pyx_n_u_t, __pyx_k_t, sizeof(__pyx_k_t), 0, 1, 0, 1}, + {&__pyx_n_u_t_2, __pyx_k_t_2, sizeof(__pyx_k_t_2), 0, 1, 0, 1}, + {&__pyx_n_s_test, __pyx_k_test, sizeof(__pyx_k_test), 0, 0, 1, 1}, + {&__pyx_kp_s_third_party_acados_acados_templa, __pyx_k_third_party_acados_acados_templa, sizeof(__pyx_k_third_party_acados_acados_templa), 0, 0, 1, 0}, + {&__pyx_n_u_time_glob, __pyx_k_time_glob, sizeof(__pyx_k_time_glob), 0, 1, 0, 1}, + {&__pyx_n_u_time_lin, __pyx_k_time_lin, sizeof(__pyx_k_time_lin), 0, 1, 0, 1}, + {&__pyx_n_u_time_qp, __pyx_k_time_qp, sizeof(__pyx_k_time_qp), 0, 1, 0, 1}, + {&__pyx_n_u_time_qp_solver_call, __pyx_k_time_qp_solver_call, sizeof(__pyx_k_time_qp_solver_call), 0, 1, 0, 1}, + {&__pyx_n_u_time_qp_xcond, __pyx_k_time_qp_xcond, sizeof(__pyx_k_time_qp_xcond), 0, 1, 0, 1}, + {&__pyx_n_u_time_reg, __pyx_k_time_reg, sizeof(__pyx_k_time_reg), 0, 1, 0, 1}, + {&__pyx_n_u_time_sim, __pyx_k_time_sim, sizeof(__pyx_k_time_sim), 0, 1, 0, 1}, + {&__pyx_n_u_time_sim_ad, __pyx_k_time_sim_ad, sizeof(__pyx_k_time_sim_ad), 0, 1, 0, 1}, + {&__pyx_n_u_time_sim_la, __pyx_k_time_sim_la, sizeof(__pyx_k_time_sim_la), 0, 1, 0, 1}, + {&__pyx_n_u_time_solution_sensitivities, __pyx_k_time_solution_sensitivities, sizeof(__pyx_k_time_solution_sensitivities), 0, 1, 0, 1}, + {&__pyx_n_u_time_tot, __pyx_k_time_tot, sizeof(__pyx_k_time_tot), 0, 1, 0, 1}, + {&__pyx_n_u_tol_comp, __pyx_k_tol_comp, sizeof(__pyx_k_tol_comp), 0, 1, 0, 1}, + {&__pyx_n_u_tol_eq, __pyx_k_tol_eq, sizeof(__pyx_k_tol_eq), 0, 1, 0, 1}, + {&__pyx_n_u_tol_ineq, __pyx_k_tol_ineq, sizeof(__pyx_k_tol_ineq), 0, 1, 0, 1}, + {&__pyx_n_u_tol_stat, __pyx_k_tol_stat, sizeof(__pyx_k_tol_stat), 0, 1, 0, 1}, + {&__pyx_n_s_tolist, __pyx_k_tolist, sizeof(__pyx_k_tolist), 0, 0, 1, 1}, + {&__pyx_n_u_u, __pyx_k_u, sizeof(__pyx_k_u), 0, 1, 0, 1}, + {&__pyx_n_s_u0, __pyx_k_u0, sizeof(__pyx_k_u0), 0, 0, 1, 1}, + {&__pyx_n_u_u_2, __pyx_k_u_2, sizeof(__pyx_k_u_2), 0, 1, 0, 1}, + {&__pyx_n_u_ubu, __pyx_k_ubu, sizeof(__pyx_k_ubu), 0, 1, 0, 1}, + {&__pyx_n_u_ubx, __pyx_k_ubx, sizeof(__pyx_k_ubx), 0, 1, 0, 1}, + {&__pyx_kp_s_unable_to_allocate_array_data, __pyx_k_unable_to_allocate_array_data, sizeof(__pyx_k_unable_to_allocate_array_data), 0, 0, 1, 0}, + {&__pyx_kp_s_unable_to_allocate_shape_and_str, __pyx_k_unable_to_allocate_shape_and_str, sizeof(__pyx_k_unable_to_allocate_shape_and_str), 0, 0, 1, 0}, + {&__pyx_n_s_unpack, __pyx_k_unpack, sizeof(__pyx_k_unpack), 0, 0, 1, 1}, + {&__pyx_n_s_update, __pyx_k_update, sizeof(__pyx_k_update), 0, 0, 1, 1}, + {&__pyx_n_s_update_qp_solver_cond_N, __pyx_k_update_qp_solver_cond_N, sizeof(__pyx_k_update_qp_solver_cond_N), 0, 0, 1, 1}, + {&__pyx_n_s_utcnow, __pyx_k_utcnow, sizeof(__pyx_k_utcnow), 0, 0, 1, 1}, + {&__pyx_kp_u_utf_8, __pyx_k_utf_8, sizeof(__pyx_k_utf_8), 0, 1, 0, 0}, + {&__pyx_n_s_value, __pyx_k_value, sizeof(__pyx_k_value), 0, 0, 1, 1}, + {&__pyx_n_s_value_2, __pyx_k_value_2, sizeof(__pyx_k_value_2), 0, 0, 1, 1}, + {&__pyx_n_s_value_shape, __pyx_k_value_shape, sizeof(__pyx_k_value_shape), 0, 0, 1, 1}, + {&__pyx_n_s_version_info, __pyx_k_version_info, sizeof(__pyx_k_version_info), 0, 0, 1, 1}, + {&__pyx_n_u_w, __pyx_k_w, sizeof(__pyx_k_w), 0, 1, 0, 1}, + {&__pyx_n_u_warm_start_first_qp, __pyx_k_warm_start_first_qp, sizeof(__pyx_k_warm_start_first_qp), 0, 1, 0, 1}, + {&__pyx_kp_u_with_dimension, __pyx_k_with_dimension, sizeof(__pyx_k_with_dimension), 0, 1, 0, 0}, + {&__pyx_kp_u_with_dimension_you_have, __pyx_k_with_dimension_you_have, sizeof(__pyx_k_with_dimension_you_have), 0, 1, 0, 0}, + {&__pyx_n_b_x, __pyx_k_x, sizeof(__pyx_k_x), 0, 0, 0, 1}, + {&__pyx_n_s_x, __pyx_k_x, sizeof(__pyx_k_x), 0, 0, 1, 1}, + {&__pyx_n_u_x, __pyx_k_x, sizeof(__pyx_k_x), 0, 1, 0, 1}, + {&__pyx_n_s_x0_bar, __pyx_k_x0_bar, sizeof(__pyx_k_x0_bar), 0, 0, 1, 1}, + {&__pyx_n_u_x_2, __pyx_k_x_2, sizeof(__pyx_k_x_2), 0, 1, 0, 1}, + {&__pyx_n_u_xdot_guess, __pyx_k_xdot_guess, sizeof(__pyx_k_xdot_guess), 0, 1, 0, 1}, + {&__pyx_n_u_y_ref, __pyx_k_y_ref, sizeof(__pyx_k_y_ref), 0, 1, 0, 1}, + {&__pyx_kp_u_you_have, __pyx_k_you_have, sizeof(__pyx_k_you_have), 0, 1, 0, 0}, + {&__pyx_n_u_yref, __pyx_k_yref, sizeof(__pyx_k_yref), 0, 1, 0, 1}, + {&__pyx_n_u_z, __pyx_k_z, sizeof(__pyx_k_z), 0, 1, 0, 1}, + {&__pyx_n_u_z_2, __pyx_k_z_2, sizeof(__pyx_k_z_2), 0, 1, 0, 1}, + {&__pyx_n_b_z_guess, __pyx_k_z_guess, sizeof(__pyx_k_z_guess), 0, 0, 0, 1}, + {&__pyx_n_u_z_guess, __pyx_k_z_guess, sizeof(__pyx_k_z_guess), 0, 1, 0, 1}, + {&__pyx_n_s_zeros, __pyx_k_zeros, sizeof(__pyx_k_zeros), 0, 0, 1, 1}, + {0, 0, 0, 0, 0, 0, 0} + }; + return __Pyx_InitStrings(__pyx_string_tab); +} +/* #### Code section: cached_builtins ### */ +static CYTHON_SMALL_CODE int __Pyx_InitCachedBuiltins(void) { + __pyx_builtin_AssertionError = __Pyx_GetBuiltinName(__pyx_n_s_AssertionError); if (!__pyx_builtin_AssertionError) __PYX_ERR(0, 82, __pyx_L1_error) + __pyx_builtin_print = __Pyx_GetBuiltinName(__pyx_n_s_print); if (!__pyx_builtin_print) __PYX_ERR(0, 113, __pyx_L1_error) + __pyx_builtin_NotImplementedError = __Pyx_GetBuiltinName(__pyx_n_s_NotImplementedError); if (!__pyx_builtin_NotImplementedError) __PYX_ERR(0, 160, __pyx_L1_error) + __pyx_builtin_range = __Pyx_GetBuiltinName(__pyx_n_s_range); if (!__pyx_builtin_range) __PYX_ERR(0, 340, __pyx_L1_error) + __pyx_builtin_open = __Pyx_GetBuiltinName(__pyx_n_s_open); if (!__pyx_builtin_open) __PYX_ERR(0, 357, __pyx_L1_error) + __pyx_builtin_TypeError = __Pyx_GetBuiltinName(__pyx_n_s_TypeError); if (!__pyx_builtin_TypeError) __PYX_ERR(1, 2, __pyx_L1_error) + __pyx_builtin___import__ = __Pyx_GetBuiltinName(__pyx_n_s_import); if (!__pyx_builtin___import__) __PYX_ERR(1, 100, __pyx_L1_error) + __pyx_builtin_ValueError = __Pyx_GetBuiltinName(__pyx_n_s_ValueError); if (!__pyx_builtin_ValueError) __PYX_ERR(1, 141, __pyx_L1_error) + __pyx_builtin_MemoryError = __Pyx_GetBuiltinName(__pyx_n_s_MemoryError); if (!__pyx_builtin_MemoryError) __PYX_ERR(1, 156, __pyx_L1_error) + __pyx_builtin_enumerate = __Pyx_GetBuiltinName(__pyx_n_s_enumerate); if (!__pyx_builtin_enumerate) __PYX_ERR(1, 159, __pyx_L1_error) + __pyx_builtin_Ellipsis = __Pyx_GetBuiltinName(__pyx_n_s_Ellipsis); if (!__pyx_builtin_Ellipsis) __PYX_ERR(1, 408, __pyx_L1_error) + __pyx_builtin_id = __Pyx_GetBuiltinName(__pyx_n_s_id); if (!__pyx_builtin_id) __PYX_ERR(1, 618, __pyx_L1_error) + __pyx_builtin_IndexError = __Pyx_GetBuiltinName(__pyx_n_s_IndexError); if (!__pyx_builtin_IndexError) __PYX_ERR(1, 914, __pyx_L1_error) + __pyx_builtin_ImportError = __Pyx_GetBuiltinName(__pyx_n_s_ImportError); if (!__pyx_builtin_ImportError) __PYX_ERR(2, 984, __pyx_L1_error) + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: cached_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_InitCachedConstants", 0); + + /* "View.MemoryView":582 + * def suboffsets(self): + * if self.view.suboffsets == NULL: + * return (-1,) * self.view.ndim # <<<<<<<<<<<<<< + * + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + */ + __pyx_tuple__4 = PyTuple_New(1); if (unlikely(!__pyx_tuple__4)) __PYX_ERR(1, 582, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__4); + __Pyx_INCREF(__pyx_int_neg_1); + __Pyx_GIVEREF(__pyx_int_neg_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_tuple__4, 0, __pyx_int_neg_1)) __PYX_ERR(1, 582, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_tuple__4); + + /* "View.MemoryView":679 + * tup = index if isinstance(index, tuple) else (index,) + * + * result = [slice(None)] * ndim # <<<<<<<<<<<<<< + * have_slices = False + * seen_ellipsis = False + */ + __pyx_slice__5 = PySlice_New(Py_None, Py_None, Py_None); if (unlikely(!__pyx_slice__5)) __PYX_ERR(1, 679, __pyx_L1_error) + __Pyx_GOTREF(__pyx_slice__5); + __Pyx_GIVEREF(__pyx_slice__5); + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + */ + __pyx_tuple__8 = PyTuple_Pack(3, __pyx_int_136983863, __pyx_int_112105877, __pyx_int_184977713); if (unlikely(!__pyx_tuple__8)) __PYX_ERR(1, 4, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__8); + __Pyx_GIVEREF(__pyx_tuple__8); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":984 + * __pyx_import_array() + * except Exception: + * raise ImportError("numpy.core.multiarray failed to import") # <<<<<<<<<<<<<< + * + * cdef inline int import_umath() except -1: + */ + __pyx_tuple__9 = PyTuple_Pack(1, __pyx_kp_u_numpy_core_multiarray_failed_to); if (unlikely(!__pyx_tuple__9)) __PYX_ERR(2, 984, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__9); + __Pyx_GIVEREF(__pyx_tuple__9); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":990 + * _import_umath() + * except Exception: + * raise ImportError("numpy.core.umath failed to import") # <<<<<<<<<<<<<< + * + * cdef inline int import_ufunc() except -1: + */ + __pyx_tuple__10 = PyTuple_Pack(1, __pyx_kp_u_numpy_core_umath_failed_to_impor); if (unlikely(!__pyx_tuple__10)) __PYX_ERR(2, 990, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__10); + __Pyx_GIVEREF(__pyx_tuple__10); + + /* "acados_template/acados_ocp_solver_pyx.pyx":113 + * + * if status == 2: + * print("Warning: acados_ocp_solver reached maximum iterations.") # <<<<<<<<<<<<<< + * elif status != 0: + * raise Exception(f'acados acados_ocp_solver returned status {status}') + */ + __pyx_tuple__11 = PyTuple_Pack(1, __pyx_kp_u_Warning_acados_ocp_solver_reache); if (unlikely(!__pyx_tuple__11)) __PYX_ERR(0, 113, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__11); + __Pyx_GIVEREF(__pyx_tuple__11); + + /* "acados_template/acados_ocp_solver_pyx.pyx":117 + * raise Exception(f'acados acados_ocp_solver returned status {status}') + * + * u0 = self.get(0, "u") # <<<<<<<<<<<<<< + * return u0 + * + */ + __pyx_tuple__12 = PyTuple_Pack(2, __pyx_int_0, __pyx_n_u_u); if (unlikely(!__pyx_tuple__12)) __PYX_ERR(0, 117, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__12); + __Pyx_GIVEREF(__pyx_tuple__12); + + /* "acados_template/acados_ocp_solver_pyx.pyx":160 + * """ + * + * raise NotImplementedError("AcadosOcpSolverCython: does not support set_new_time_steps() since it is only a prototyping feature") # <<<<<<<<<<<<<< + * # # unlikely but still possible + * # if not self.solver_created: + */ + __pyx_tuple__13 = PyTuple_Pack(1, __pyx_kp_u_AcadosOcpSolverCython_does_not_s); if (unlikely(!__pyx_tuple__13)) __PYX_ERR(0, 160, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__13); + __Pyx_GIVEREF(__pyx_tuple__13); + + /* "acados_template/acados_ocp_solver_pyx.pyx":212 + * `qp_solver_cond_N < N`. + * """ + * raise NotImplementedError("AcadosOcpSolverCython: does not support update_qp_solver_cond_N() since it is only a prototyping feature") # <<<<<<<<<<<<<< + * + * # # unlikely but still possible + */ + __pyx_tuple__14 = PyTuple_Pack(1, __pyx_kp_u_AcadosOcpSolverCython_does_not_s_2); if (unlikely(!__pyx_tuple__14)) __PYX_ERR(0, 212, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__14); + __Pyx_GIVEREF(__pyx_tuple__14); + + /* "acados_template/acados_ocp_solver_pyx.pyx":245 + * # checks + * if not isinstance(index, int): + * raise Exception('AcadosOcpSolverCython.eval_param_sens(): index must be Integer.') # <<<<<<<<<<<<<< + * + * cdef int nx = acados_solver_common.ocp_nlp_dims_get_from_attr(self.nlp_config, self.nlp_dims, self.nlp_out, 0, "x".encode('utf-8')) + */ + __pyx_tuple__15 = PyTuple_Pack(1, __pyx_kp_u_AcadosOcpSolverCython_eval_param); if (unlikely(!__pyx_tuple__15)) __PYX_ERR(0, 245, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__15); + __Pyx_GIVEREF(__pyx_tuple__15); + + /* "acados_template/acados_ocp_solver_pyx.pyx":333 + * # append timestamp + * if os.path.isfile(filename): + * filename = filename[:-5] # <<<<<<<<<<<<<< + * filename += datetime.utcnow().strftime('%Y-%m-%d-%H:%M:%S.%f') + '.json' + * + */ + __pyx_slice__18 = PySlice_New(Py_None, __pyx_int_neg_5, Py_None); if (unlikely(!__pyx_slice__18)) __PYX_ERR(0, 333, __pyx_L1_error) + __Pyx_GOTREF(__pyx_slice__18); + __Pyx_GIVEREF(__pyx_slice__18); + + /* "acados_template/acados_ocp_solver_pyx.pyx":357 + * + * # save + * with open(filename, 'w') as f: # <<<<<<<<<<<<<< + * json.dump(solution, f, default=lambda x: x.tolist(), indent=4, sort_keys=True) + * print("stored current iterate in ", os.path.join(os.getcwd(), filename)) + */ + __pyx_tuple__19 = PyTuple_Pack(3, Py_None, Py_None, Py_None); if (unlikely(!__pyx_tuple__19)) __PYX_ERR(0, 357, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__19); + __Pyx_GIVEREF(__pyx_tuple__19); + + /* "acados_template/acados_ocp_solver_pyx.pyx":442 + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': + * return full_stats[6, :] # <<<<<<<<<<<<<< + * elif self.nlp_solver_type == 'SQP_RTI': + * return full_stats[2, :] + */ + __pyx_tuple__20 = PyTuple_Pack(2, __pyx_int_6, __pyx_slice__5); if (unlikely(!__pyx_tuple__20)) __PYX_ERR(0, 442, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__20); + __Pyx_GIVEREF(__pyx_tuple__20); + + /* "acados_template/acados_ocp_solver_pyx.pyx":444 + * return full_stats[6, :] + * elif self.nlp_solver_type == 'SQP_RTI': + * return full_stats[2, :] # <<<<<<<<<<<<<< + * + * elif field_ == 'alpha': + */ + __pyx_tuple__21 = PyTuple_Pack(2, __pyx_int_2, __pyx_slice__5); if (unlikely(!__pyx_tuple__21)) __PYX_ERR(0, 444, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__21); + __Pyx_GIVEREF(__pyx_tuple__21); + + /* "acados_template/acados_ocp_solver_pyx.pyx":449 + * full_stats = self.get_stats('statistics') + * if self.nlp_solver_type == 'SQP': + * return full_stats[7, :] # <<<<<<<<<<<<<< + * else: # self.nlp_solver_type == 'SQP_RTI': + * raise Exception("alpha values are not available for SQP_RTI") + */ + __pyx_tuple__22 = PyTuple_Pack(2, __pyx_int_7, __pyx_slice__5); if (unlikely(!__pyx_tuple__22)) __PYX_ERR(0, 449, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__22); + __Pyx_GIVEREF(__pyx_tuple__22); + + /* "acados_template/acados_ocp_solver_pyx.pyx":451 + * return full_stats[7, :] + * else: # self.nlp_solver_type == 'SQP_RTI': + * raise Exception("alpha values are not available for SQP_RTI") # <<<<<<<<<<<<<< + * + * elif field_ == 'residuals': + */ + __pyx_tuple__23 = PyTuple_Pack(1, __pyx_kp_u_alpha_values_are_not_available_f); if (unlikely(!__pyx_tuple__23)) __PYX_ERR(0, 451, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__23); + __Pyx_GIVEREF(__pyx_tuple__23); + + /* "acados_template/acados_ocp_solver_pyx.pyx":457 + * + * else: + * raise NotImplementedError("TODO!") # <<<<<<<<<<<<<< + * + * + */ + __pyx_tuple__24 = PyTuple_Pack(1, __pyx_kp_u_TODO); if (unlikely(!__pyx_tuple__24)) __PYX_ERR(0, 457, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__24); + __Pyx_GIVEREF(__pyx_tuple__24); + + /* "acados_template/acados_ocp_solver_pyx.pyx":466 + * + * def __get_stat_double(self, field): + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) # <<<<<<<<<<<<<< + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) + * return out + */ + __pyx_tuple__25 = PyTuple_Pack(1, __pyx_int_1); if (unlikely(!__pyx_tuple__25)) __PYX_ERR(0, 466, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__25); + __Pyx_GIVEREF(__pyx_tuple__25); + + /* "acados_template/acados_ocp_solver_pyx.pyx":501 + * + * # create output array + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.ascontiguousarray(np.zeros((4,), dtype=np.float64)) # <<<<<<<<<<<<<< + * cdef double double_value + * + */ + __pyx_tuple__26 = PyTuple_Pack(1, __pyx_int_4); if (unlikely(!__pyx_tuple__26)) __PYX_ERR(0, 501, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__26); + __Pyx_GIVEREF(__pyx_tuple__26); + __pyx_tuple__27 = PyTuple_Pack(1, __pyx_tuple__26); if (unlikely(!__pyx_tuple__27)) __PYX_ERR(0, 501, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__27); + __Pyx_GIVEREF(__pyx_tuple__27); + + /* "acados_template/acados_ocp_solver_pyx.pyx":611 + * if len(value_shape) == 1: + * value_shape = (value_shape[0], 0) + * value = np.asfortranarray(value_[None,:]) # <<<<<<<<<<<<<< + * + * elif len(value_shape) == 2: + */ + __pyx_tuple__28 = PyTuple_Pack(2, Py_None, __pyx_slice__5); if (unlikely(!__pyx_tuple__28)) __PYX_ERR(0, 611, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__28); + __Pyx_GIVEREF(__pyx_tuple__28); + + /* "acados_template/acados_ocp_solver_pyx.pyx":720 + * if field_ == 'rti_phase': + * if value_ < 0 or value_ > 2: + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' # <<<<<<<<<<<<<< + * 'take only values 0, 1, 2 for SQP-RTI-type solvers') + * if self.nlp_solver_type != 'SQP_RTI' and value_ > 0: + */ + __pyx_tuple__29 = PyTuple_Pack(1, __pyx_kp_u_AcadosOcpSolverCython_solve_argu); if (unlikely(!__pyx_tuple__29)) __PYX_ERR(0, 720, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__29); + __Pyx_GIVEREF(__pyx_tuple__29); + + /* "acados_template/acados_ocp_solver_pyx.pyx":723 + * 'take only values 0, 1, 2 for SQP-RTI-type solvers') + * if self.nlp_solver_type != 'SQP_RTI' and value_ > 0: + * raise Exception('AcadosOcpSolverCython.solve(): argument \'rti_phase\' can ' # <<<<<<<<<<<<<< + * 'take only value 0 for SQP-type solvers') + * + */ + __pyx_tuple__30 = PyTuple_Pack(1, __pyx_kp_u_AcadosOcpSolverCython_solve_argu_2); if (unlikely(!__pyx_tuple__30)) __PYX_ERR(0, 723, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__30); + __Pyx_GIVEREF(__pyx_tuple__30); + + /* "acados_template/acados_ocp_solver_pyx.pyx":759 + * + * if not isinstance(param_values_, np.ndarray): + * raise Exception('param_values_ must be np.array.') # <<<<<<<<<<<<<< + * + * if param_values_.shape[0] != len(idx_values_): + */ + __pyx_tuple__32 = PyTuple_Pack(1, __pyx_kp_u_param_values__must_be_np_array); if (unlikely(!__pyx_tuple__32)) __PYX_ERR(0, 759, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__32); + __Pyx_GIVEREF(__pyx_tuple__32); + + /* "View.MemoryView":100 + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: + * if __import__("sys").version_info >= (3, 3): # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + */ + __pyx_tuple__33 = PyTuple_Pack(1, __pyx_n_s_sys); if (unlikely(!__pyx_tuple__33)) __PYX_ERR(1, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__33); + __Pyx_GIVEREF(__pyx_tuple__33); + __pyx_tuple__34 = PyTuple_Pack(2, __pyx_int_3, __pyx_int_3); if (unlikely(!__pyx_tuple__34)) __PYX_ERR(1, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__34); + __Pyx_GIVEREF(__pyx_tuple__34); + + /* "View.MemoryView":101 + * try: + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence # <<<<<<<<<<<<<< + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence + */ + __pyx_tuple__35 = PyTuple_Pack(1, __pyx_kp_s_collections_abc); if (unlikely(!__pyx_tuple__35)) __PYX_ERR(1, 101, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__35); + __Pyx_GIVEREF(__pyx_tuple__35); + + /* "View.MemoryView":103 + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence # <<<<<<<<<<<<<< + * except: + * + */ + __pyx_tuple__36 = PyTuple_Pack(1, __pyx_n_s_collections); if (unlikely(!__pyx_tuple__36)) __PYX_ERR(1, 103, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__36); + __Pyx_GIVEREF(__pyx_tuple__36); + + /* "View.MemoryView":309 + * return self.name + * + * cdef generic = Enum("") # <<<<<<<<<<<<<< + * cdef strided = Enum("") # default + * cdef indirect = Enum("") + */ + __pyx_tuple__37 = PyTuple_Pack(1, __pyx_kp_s_strided_and_direct_or_indirect); if (unlikely(!__pyx_tuple__37)) __PYX_ERR(1, 309, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__37); + __Pyx_GIVEREF(__pyx_tuple__37); + + /* "View.MemoryView":310 + * + * cdef generic = Enum("") + * cdef strided = Enum("") # default # <<<<<<<<<<<<<< + * cdef indirect = Enum("") + * + */ + __pyx_tuple__38 = PyTuple_Pack(1, __pyx_kp_s_strided_and_direct); if (unlikely(!__pyx_tuple__38)) __PYX_ERR(1, 310, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__38); + __Pyx_GIVEREF(__pyx_tuple__38); + + /* "View.MemoryView":311 + * cdef generic = Enum("") + * cdef strided = Enum("") # default + * cdef indirect = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_tuple__39 = PyTuple_Pack(1, __pyx_kp_s_strided_and_indirect); if (unlikely(!__pyx_tuple__39)) __PYX_ERR(1, 311, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__39); + __Pyx_GIVEREF(__pyx_tuple__39); + + /* "View.MemoryView":314 + * + * + * cdef contiguous = Enum("") # <<<<<<<<<<<<<< + * cdef indirect_contiguous = Enum("") + * + */ + __pyx_tuple__40 = PyTuple_Pack(1, __pyx_kp_s_contiguous_and_direct); if (unlikely(!__pyx_tuple__40)) __PYX_ERR(1, 314, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__40); + __Pyx_GIVEREF(__pyx_tuple__40); + + /* "View.MemoryView":315 + * + * cdef contiguous = Enum("") + * cdef indirect_contiguous = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_tuple__41 = PyTuple_Pack(1, __pyx_kp_s_contiguous_and_indirect); if (unlikely(!__pyx_tuple__41)) __PYX_ERR(1, 315, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__41); + __Pyx_GIVEREF(__pyx_tuple__41); + + /* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + __pyx_tuple__42 = PyTuple_Pack(5, __pyx_n_s_pyx_type, __pyx_n_s_pyx_checksum, __pyx_n_s_pyx_state, __pyx_n_s_pyx_PickleError, __pyx_n_s_pyx_result); if (unlikely(!__pyx_tuple__42)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__42); + __Pyx_GIVEREF(__pyx_tuple__42); + __pyx_codeobj__43 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__42, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_pyx_unpickle_Enum, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__43)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":89 + * + * + * def __get_pointers_solver(self): # <<<<<<<<<<<<<< + * """ + * Private function to get the pointers for solver + */ + __pyx_tuple__44 = PyTuple_Pack(1, __pyx_n_s_self); if (unlikely(!__pyx_tuple__44)) __PYX_ERR(0, 89, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__44); + __Pyx_GIVEREF(__pyx_tuple__44); + __pyx_codeobj__45 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__44, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_pointers_solver, 89, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__45)) __PYX_ERR(0, 89, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":103 + * + * + * def solve_for_x0(self, x0_bar): # <<<<<<<<<<<<<< + * """ + * Wrapper around `solve()` which sets initial state constraint, solves the OCP, and returns u0. + */ + __pyx_tuple__46 = PyTuple_Pack(4, __pyx_n_s_self, __pyx_n_s_x0_bar, __pyx_n_s_status, __pyx_n_s_u0); if (unlikely(!__pyx_tuple__46)) __PYX_ERR(0, 103, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__46); + __Pyx_GIVEREF(__pyx_tuple__46); + __pyx_codeobj__47 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 4, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__46, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_solve_for_x0, 103, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__47)) __PYX_ERR(0, 103, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":121 + * + * + * def solve(self): # <<<<<<<<<<<<<< + * """ + * Solve the ocp with current input. + */ + __pyx_codeobj__48 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__44, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_solve, 121, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__48)) __PYX_ERR(0, 121, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":128 + * + * + * def reset(self, reset_qp_solver_mem=1): # <<<<<<<<<<<<<< + * """ + * Sets current iterate to all zeros. + */ + __pyx_tuple__49 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_reset_qp_solver_mem); if (unlikely(!__pyx_tuple__49)) __PYX_ERR(0, 128, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__49); + __Pyx_GIVEREF(__pyx_tuple__49); + __pyx_codeobj__50 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__49, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_reset, 128, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__50)) __PYX_ERR(0, 128, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":135 + * + * + * def custom_update(self, data_): # <<<<<<<<<<<<<< + * """ + * A custom function that can be implemented by a user to be called between solver calls. + */ + __pyx_tuple__51 = PyTuple_Pack(4, __pyx_n_s_self, __pyx_n_s_data, __pyx_n_s_data_len, __pyx_n_s_data_2); if (unlikely(!__pyx_tuple__51)) __PYX_ERR(0, 135, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__51); + __Pyx_GIVEREF(__pyx_tuple__51); + __pyx_codeobj__52 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 4, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__51, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_custom_update, 135, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__52)) __PYX_ERR(0, 135, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":148 + * + * + * def set_new_time_steps(self, new_time_steps): # <<<<<<<<<<<<<< + * """ + * Set new time steps. + */ + __pyx_tuple__53 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_new_time_steps); if (unlikely(!__pyx_tuple__53)) __PYX_ERR(0, 148, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__53); + __Pyx_GIVEREF(__pyx_tuple__53); + __pyx_codeobj__54 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__53, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_set_new_time_steps, 148, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__54)) __PYX_ERR(0, 148, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":199 + * + * + * def update_qp_solver_cond_N(self, qp_solver_cond_N: int): # <<<<<<<<<<<<<< + * """ + * Recreate solver with new value `qp_solver_cond_N` with a partial condensing QP solver. + */ + __pyx_tuple__55 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_qp_solver_cond_N); if (unlikely(!__pyx_tuple__55)) __PYX_ERR(0, 199, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__55); + __Pyx_GIVEREF(__pyx_tuple__55); + __pyx_codeobj__56 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__55, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_update_qp_solver_cond_N, 199, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__56)) __PYX_ERR(0, 199, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":233 + * + * + * def eval_param_sens(self, index, stage=0, field="ex"): # <<<<<<<<<<<<<< + * """ + * Calculate the sensitivity of the curent solution with respect to the initial state component of index + */ + __pyx_tuple__57 = PyTuple_Pack(6, __pyx_n_s_self, __pyx_n_s_index, __pyx_n_s_stage, __pyx_n_s_field, __pyx_n_s_field_2, __pyx_n_s_nx); if (unlikely(!__pyx_tuple__57)) __PYX_ERR(0, 233, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__57); + __Pyx_GIVEREF(__pyx_tuple__57); + __pyx_codeobj__58 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 6, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__57, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_eval_param_sens, 233, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__58)) __PYX_ERR(0, 233, __pyx_L1_error) + __pyx_tuple__59 = PyTuple_Pack(2, __pyx_int_0, __pyx_n_u_ex); if (unlikely(!__pyx_tuple__59)) __PYX_ERR(0, 233, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__59); + __Pyx_GIVEREF(__pyx_tuple__59); + + /* "acados_template/acados_ocp_solver_pyx.pyx":258 + * + * + * def get(self, int stage, str field_): # <<<<<<<<<<<<<< + * """ + * Get the last solution of the solver: + */ + __pyx_tuple__60 = PyTuple_Pack(7, __pyx_n_s_self, __pyx_n_s_stage, __pyx_n_s_field_2, __pyx_n_s_out_fields, __pyx_n_s_field, __pyx_n_s_dims, __pyx_n_s_out); if (unlikely(!__pyx_tuple__60)) __PYX_ERR(0, 258, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__60); + __Pyx_GIVEREF(__pyx_tuple__60); + __pyx_codeobj__61 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 7, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__60, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get, 258, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__61)) __PYX_ERR(0, 258, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":301 + * + * + * def print_statistics(self): # <<<<<<<<<<<<<< + * """ + * prints statistics of previous solver run as a table: + */ + __pyx_codeobj__62 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__44, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_print_statistics, 301, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__62)) __PYX_ERR(0, 301, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":319 + * + * + * def store_iterate(self, filename='', overwrite=False): # <<<<<<<<<<<<<< + * """ + * Stores the current iterate of the ocp solver in a json file. + */ + __pyx_tuple__63 = PyTuple_Pack(10, __pyx_n_s_self, __pyx_n_s_filename, __pyx_n_s_overwrite, __pyx_n_s_json, __pyx_n_s_solution, __pyx_n_s_lN, __pyx_n_s_i, __pyx_n_s_i_string, __pyx_n_s_k, __pyx_n_s_f); if (unlikely(!__pyx_tuple__63)) __PYX_ERR(0, 319, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__63); + __Pyx_GIVEREF(__pyx_tuple__63); + __pyx_codeobj__64 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 10, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__63, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_store_iterate, 319, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__64)) __PYX_ERR(0, 319, __pyx_L1_error) + __pyx_tuple__65 = PyTuple_Pack(2, __pyx_kp_u__16, Py_False); if (unlikely(!__pyx_tuple__65)) __PYX_ERR(0, 319, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__65); + __Pyx_GIVEREF(__pyx_tuple__65); + + /* "acados_template/acados_ocp_solver_pyx.pyx":362 + * + * + * def load_iterate(self, filename): # <<<<<<<<<<<<<< + * """ + * Loads the iterate stored in json file with filename into the ocp solver. + */ + __pyx_tuple__66 = PyTuple_Pack(8, __pyx_n_s_self, __pyx_n_s_filename, __pyx_n_s_json, __pyx_n_s_f, __pyx_n_s_solution, __pyx_n_s_key, __pyx_n_s_field, __pyx_n_s_stage); if (unlikely(!__pyx_tuple__66)) __PYX_ERR(0, 362, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__66); + __Pyx_GIVEREF(__pyx_tuple__66); + __pyx_codeobj__67 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 8, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__66, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_load_iterate, 362, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__67)) __PYX_ERR(0, 362, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":378 + * + * + * def get_stats(self, field_): # <<<<<<<<<<<<<< + * """ + * Get the information of the last solver call. + */ + __pyx_tuple__68 = PyTuple_Pack(10, __pyx_n_s_self, __pyx_n_s_field_2, __pyx_n_s_double_fields, __pyx_n_s_fields, __pyx_n_s_field, __pyx_n_s_sqp_iter, __pyx_n_s_stat_m, __pyx_n_s_stat_n, __pyx_n_s_min_size, __pyx_n_s_full_stats); if (unlikely(!__pyx_tuple__68)) __PYX_ERR(0, 378, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__68); + __Pyx_GIVEREF(__pyx_tuple__68); + __pyx_codeobj__69 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 10, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__68, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_stats, 378, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__69)) __PYX_ERR(0, 378, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":460 + * + * + * def __get_stat_int(self, field): # <<<<<<<<<<<<<< + * cdef int out + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &out) + */ + __pyx_tuple__70 = PyTuple_Pack(3, __pyx_n_s_self, __pyx_n_s_field, __pyx_n_s_out); if (unlikely(!__pyx_tuple__70)) __PYX_ERR(0, 460, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__70); + __Pyx_GIVEREF(__pyx_tuple__70); + __pyx_codeobj__71 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__70, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_stat_int, 460, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__71)) __PYX_ERR(0, 460, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":465 + * return out + * + * def __get_stat_double(self, field): # <<<<<<<<<<<<<< + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) + */ + __pyx_codeobj__72 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__70, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_stat_double, 465, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__72)) __PYX_ERR(0, 465, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":470 + * return out + * + * def __get_stat_matrix(self, field, n, m): # <<<<<<<<<<<<<< + * cdef cnp.ndarray[cnp.float64_t, ndim=2] out_mat = np.ascontiguousarray(np.zeros((n, m)), dtype=np.float64) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_mat.data) + */ + __pyx_tuple__73 = PyTuple_Pack(5, __pyx_n_s_self, __pyx_n_s_field, __pyx_n_s_n, __pyx_n_s_m, __pyx_n_s_out_mat); if (unlikely(!__pyx_tuple__73)) __PYX_ERR(0, 470, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__73); + __Pyx_GIVEREF(__pyx_tuple__73); + __pyx_codeobj__74 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__73, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_stat_matrix, 470, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__74)) __PYX_ERR(0, 470, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":476 + * + * + * def get_cost(self): # <<<<<<<<<<<<<< + * """ + * Returns the cost value of the current solution. + */ + __pyx_tuple__75 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_out); if (unlikely(!__pyx_tuple__75)) __PYX_ERR(0, 476, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__75); + __Pyx_GIVEREF(__pyx_tuple__75); + __pyx_codeobj__76 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__75, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_cost, 476, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__76)) __PYX_ERR(0, 476, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":492 + * + * + * def get_residuals(self, recompute=False): # <<<<<<<<<<<<<< + * """ + * Returns an array of the form [res_stat, res_eq, res_ineq, res_comp]. + */ + __pyx_tuple__77 = PyTuple_Pack(5, __pyx_n_s_self, __pyx_n_s_recompute, __pyx_n_s_out, __pyx_n_s_double_value, __pyx_n_s_field); if (unlikely(!__pyx_tuple__77)) __PYX_ERR(0, 492, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__77); + __Pyx_GIVEREF(__pyx_tuple__77); + __pyx_codeobj__78 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__77, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_residuals, 492, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__78)) __PYX_ERR(0, 492, __pyx_L1_error) + __pyx_tuple__79 = PyTuple_Pack(1, Py_False); if (unlikely(!__pyx_tuple__79)) __PYX_ERR(0, 492, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__79); + __Pyx_GIVEREF(__pyx_tuple__79); + + /* "acados_template/acados_ocp_solver_pyx.pyx":524 + * + * # Note: this function should not be used anymore, better use cost_set, constraints_set + * def set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * + * """ + */ + __pyx_tuple__80 = PyTuple_Pack(12, __pyx_n_s_self, __pyx_n_s_stage, __pyx_n_s_field_2, __pyx_n_s_value, __pyx_n_s_cost_fields, __pyx_n_s_constraints_fields, __pyx_n_s_out_fields, __pyx_n_s_mem_fields, __pyx_n_s_field, __pyx_n_s_value_2, __pyx_n_s_dims, __pyx_n_s_msg); if (unlikely(!__pyx_tuple__80)) __PYX_ERR(0, 524, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__80); + __Pyx_GIVEREF(__pyx_tuple__80); + __pyx_codeobj__81 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 12, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__80, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_set, 524, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__81)) __PYX_ERR(0, 524, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":590 + * return + * + * def cost_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set numerical data in the cost module of the solver. + */ + __pyx_tuple__82 = PyTuple_Pack(8, __pyx_n_s_self, __pyx_n_s_stage, __pyx_n_s_field_2, __pyx_n_s_value, __pyx_n_s_field, __pyx_n_s_dims, __pyx_n_s_value_2, __pyx_n_s_value_shape); if (unlikely(!__pyx_tuple__82)) __PYX_ERR(0, 590, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__82); + __Pyx_GIVEREF(__pyx_tuple__82); + __pyx_codeobj__83 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 8, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__82, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_cost_set, 590, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__83)) __PYX_ERR(0, 590, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":625 + * + * + * def constraints_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set numerical data in the constraint module of the solver. + */ + __pyx_codeobj__84 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 8, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__82, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_constraints_set, 625, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__84)) __PYX_ERR(0, 625, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":663 + * + * + * def get_from_qp_in(self, int stage, str field_): # <<<<<<<<<<<<<< + * """ + * Get numerical data from the dynamics module of the solver: + */ + __pyx_tuple__85 = PyTuple_Pack(6, __pyx_n_s_self, __pyx_n_s_stage, __pyx_n_s_field_2, __pyx_n_s_field, __pyx_n_s_dims, __pyx_n_s_out); if (unlikely(!__pyx_tuple__85)) __PYX_ERR(0, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__85); + __Pyx_GIVEREF(__pyx_tuple__85); + __pyx_codeobj__86 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 6, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__85, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_get_from_qp_in, 663, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__86)) __PYX_ERR(0, 663, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":685 + * + * + * def options_set(self, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set options of the solver. + */ + __pyx_tuple__87 = PyTuple_Pack(10, __pyx_n_s_self, __pyx_n_s_field_2, __pyx_n_s_value, __pyx_n_s_int_fields, __pyx_n_s_double_fields, __pyx_n_s_string_fields, __pyx_n_s_field, __pyx_n_s_int_value, __pyx_n_s_double_value, __pyx_n_s_string_value); if (unlikely(!__pyx_tuple__87)) __PYX_ERR(0, 685, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__87); + __Pyx_GIVEREF(__pyx_tuple__87); + __pyx_codeobj__88 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 10, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__87, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_options_set, 685, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__88)) __PYX_ERR(0, 685, __pyx_L1_error) + + /* "acados_template/acados_ocp_solver_pyx.pyx":748 + * + * + * def set_params_sparse(self, int stage, idx_values_, param_values_): # <<<<<<<<<<<<<< + * """ + * set parameters of the solvers external function partially: + */ + __pyx_tuple__89 = PyTuple_Pack(7, __pyx_n_s_self, __pyx_n_s_stage, __pyx_n_s_idx_values, __pyx_n_s_param_values, __pyx_n_s_value_2, __pyx_n_s_idx, __pyx_n_s_n_update); if (unlikely(!__pyx_tuple__89)) __PYX_ERR(0, 748, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__89); + __Pyx_GIVEREF(__pyx_tuple__89); + __pyx_codeobj__90 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 7, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__89, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_third_party_acados_acados_templa, __pyx_n_s_set_params_sparse, 748, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__90)) __PYX_ERR(0, 748, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_codeobj__91 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__44, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__91)) __PYX_ERR(1, 1, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_tuple__92 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_pyx_state); if (unlikely(!__pyx_tuple__92)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__92); + __Pyx_GIVEREF(__pyx_tuple__92); + __pyx_codeobj__93 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__92, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__93)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_RefNannyFinishContext(); + return -1; +} +/* #### Code section: init_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitConstants(void) { + __pyx_umethod_PyDict_Type_keys.type = (PyObject*)&PyDict_Type; + __pyx_umethod_PyDict_Type_keys.method_name = &__pyx_n_s_keys; + if (__Pyx_CreateStringTabAndInitStrings() < 0) __PYX_ERR(0, 1, __pyx_L1_error); + __pyx_int_0 = PyInt_FromLong(0); if (unlikely(!__pyx_int_0)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_1 = PyInt_FromLong(1); if (unlikely(!__pyx_int_1)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_2 = PyInt_FromLong(2); if (unlikely(!__pyx_int_2)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_3 = PyInt_FromLong(3); if (unlikely(!__pyx_int_3)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_4 = PyInt_FromLong(4); if (unlikely(!__pyx_int_4)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_6 = PyInt_FromLong(6); if (unlikely(!__pyx_int_6)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_7 = PyInt_FromLong(7); if (unlikely(!__pyx_int_7)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_112105877 = PyInt_FromLong(112105877L); if (unlikely(!__pyx_int_112105877)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_136983863 = PyInt_FromLong(136983863L); if (unlikely(!__pyx_int_136983863)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_184977713 = PyInt_FromLong(184977713L); if (unlikely(!__pyx_int_184977713)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_neg_1 = PyInt_FromLong(-1); if (unlikely(!__pyx_int_neg_1)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_int_neg_5 = PyInt_FromLong(-5); if (unlikely(!__pyx_int_neg_5)) __PYX_ERR(0, 1, __pyx_L1_error) + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: init_globals ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitGlobals(void) { + /* AssertionsEnabled.init */ + if (likely(__Pyx_init_assertions_enabled() == 0)); else + +if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 1, __pyx_L1_error) + + /* NumpyImportArray.init */ + /* + * Cython has automatically inserted a call to _import_array since + * you didn't include one when you cimported numpy. To disable this + * add the line + * numpy._import_array + */ +#ifdef NPY_FEATURE_VERSION +#ifndef NO_IMPORT_ARRAY +if (unlikely(_import_array() == -1)) { + PyErr_SetString(PyExc_ImportError, "numpy.core.multiarray failed to import " + "(auto-generated because you didn't call 'numpy.import_array()' after cimporting numpy; " + "use 'numpy._import_array' to disable if you are certain you don't need it)."); +} +#endif +#endif + +if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 1, __pyx_L1_error) + + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: init_module ### */ + +static CYTHON_SMALL_CODE int __Pyx_modinit_global_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_import_code(void); /*proto*/ + +static int __Pyx_modinit_global_init_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_global_init_code", 0); + /*--- Global init code ---*/ + __pyx_collections_abc_Sequence = Py_None; Py_INCREF(Py_None); + generic = Py_None; Py_INCREF(Py_None); + strided = Py_None; Py_INCREF(Py_None); + indirect = Py_None; Py_INCREF(Py_None); + contiguous = Py_None; Py_INCREF(Py_None); + indirect_contiguous = Py_None; Py_INCREF(Py_None); + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_variable_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_export_code", 0); + /*--- Variable export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_export_code", 0); + /*--- Function export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_type_init_code(void) { + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_modinit_type_init_code", 0); + /*--- Type init code ---*/ + #if CYTHON_USE_TYPE_SPECS + __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython_spec, NULL); if (unlikely(!__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython)) __PYX_ERR(0, 49, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython_spec, __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython) < 0) __PYX_ERR(0, 49, __pyx_L1_error) + #else + __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython = &__pyx_type_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython) < 0) __PYX_ERR(0, 49, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_dictoffset && __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_AcadosOcpSolverCython, (PyObject *) __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython) < 0) __PYX_ERR(0, 49, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython) < 0) __PYX_ERR(0, 49, __pyx_L1_error) + #endif + __pyx_vtabptr_array = &__pyx_vtable_array; + __pyx_vtable_array.get_memview = (PyObject *(*)(struct __pyx_array_obj *))__pyx_array_get_memview; + #if CYTHON_USE_TYPE_SPECS + __pyx_array_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_array_spec, NULL); if (unlikely(!__pyx_array_type)) __PYX_ERR(1, 114, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + __pyx_array_type->tp_as_buffer = &__pyx_tp_as_buffer_array; + if (!__pyx_array_type->tp_as_buffer->bf_releasebuffer && __pyx_array_type->tp_base->tp_as_buffer && __pyx_array_type->tp_base->tp_as_buffer->bf_releasebuffer) { + __pyx_array_type->tp_as_buffer->bf_releasebuffer = __pyx_array_type->tp_base->tp_as_buffer->bf_releasebuffer; + } + #elif defined(Py_bf_getbuffer) && defined(Py_bf_releasebuffer) + /* PY_VERSION_HEX >= 0x03090000 || Py_LIMITED_API >= 0x030B0000 */ + #elif defined(_MSC_VER) + #pragma message ("The buffer protocol is not supported in the Limited C-API < 3.11.") + #else + #warning "The buffer protocol is not supported in the Limited C-API < 3.11." + #endif + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_array_spec, __pyx_array_type) < 0) __PYX_ERR(1, 114, __pyx_L1_error) + #else + __pyx_array_type = &__pyx_type___pyx_array; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_array_type) < 0) __PYX_ERR(1, 114, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_array_type->tp_print = 0; + #endif + if (__Pyx_SetVtable(__pyx_array_type, __pyx_vtabptr_array) < 0) __PYX_ERR(1, 114, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_array_type) < 0) __PYX_ERR(1, 114, __pyx_L1_error) + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_array_type) < 0) __PYX_ERR(1, 114, __pyx_L1_error) + #endif + #if CYTHON_USE_TYPE_SPECS + __pyx_MemviewEnum_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_MemviewEnum_spec, NULL); if (unlikely(!__pyx_MemviewEnum_type)) __PYX_ERR(1, 302, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_MemviewEnum_spec, __pyx_MemviewEnum_type) < 0) __PYX_ERR(1, 302, __pyx_L1_error) + #else + __pyx_MemviewEnum_type = &__pyx_type___pyx_MemviewEnum; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_MemviewEnum_type) < 0) __PYX_ERR(1, 302, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_MemviewEnum_type->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_MemviewEnum_type->tp_dictoffset && __pyx_MemviewEnum_type->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_MemviewEnum_type->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_MemviewEnum_type) < 0) __PYX_ERR(1, 302, __pyx_L1_error) + #endif + __pyx_vtabptr_memoryview = &__pyx_vtable_memoryview; + __pyx_vtable_memoryview.get_item_pointer = (char *(*)(struct __pyx_memoryview_obj *, PyObject *))__pyx_memoryview_get_item_pointer; + __pyx_vtable_memoryview.is_slice = (PyObject *(*)(struct __pyx_memoryview_obj *, PyObject *))__pyx_memoryview_is_slice; + __pyx_vtable_memoryview.setitem_slice_assignment = (PyObject *(*)(struct __pyx_memoryview_obj *, PyObject *, PyObject *))__pyx_memoryview_setitem_slice_assignment; + __pyx_vtable_memoryview.setitem_slice_assign_scalar = (PyObject *(*)(struct __pyx_memoryview_obj *, struct __pyx_memoryview_obj *, PyObject *))__pyx_memoryview_setitem_slice_assign_scalar; + __pyx_vtable_memoryview.setitem_indexed = (PyObject *(*)(struct __pyx_memoryview_obj *, PyObject *, PyObject *))__pyx_memoryview_setitem_indexed; + __pyx_vtable_memoryview.convert_item_to_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *))__pyx_memoryview_convert_item_to_object; + __pyx_vtable_memoryview.assign_item_from_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *, PyObject *))__pyx_memoryview_assign_item_from_object; + __pyx_vtable_memoryview._get_base = (PyObject *(*)(struct __pyx_memoryview_obj *))__pyx_memoryview__get_base; + #if CYTHON_USE_TYPE_SPECS + __pyx_memoryview_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_memoryview_spec, NULL); if (unlikely(!__pyx_memoryview_type)) __PYX_ERR(1, 337, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + __pyx_memoryview_type->tp_as_buffer = &__pyx_tp_as_buffer_memoryview; + if (!__pyx_memoryview_type->tp_as_buffer->bf_releasebuffer && __pyx_memoryview_type->tp_base->tp_as_buffer && __pyx_memoryview_type->tp_base->tp_as_buffer->bf_releasebuffer) { + __pyx_memoryview_type->tp_as_buffer->bf_releasebuffer = __pyx_memoryview_type->tp_base->tp_as_buffer->bf_releasebuffer; + } + #elif defined(Py_bf_getbuffer) && defined(Py_bf_releasebuffer) + /* PY_VERSION_HEX >= 0x03090000 || Py_LIMITED_API >= 0x030B0000 */ + #elif defined(_MSC_VER) + #pragma message ("The buffer protocol is not supported in the Limited C-API < 3.11.") + #else + #warning "The buffer protocol is not supported in the Limited C-API < 3.11." + #endif + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_memoryview_spec, __pyx_memoryview_type) < 0) __PYX_ERR(1, 337, __pyx_L1_error) + #else + __pyx_memoryview_type = &__pyx_type___pyx_memoryview; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_memoryview_type) < 0) __PYX_ERR(1, 337, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_memoryview_type->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_memoryview_type->tp_dictoffset && __pyx_memoryview_type->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_memoryview_type->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (__Pyx_SetVtable(__pyx_memoryview_type, __pyx_vtabptr_memoryview) < 0) __PYX_ERR(1, 337, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_memoryview_type) < 0) __PYX_ERR(1, 337, __pyx_L1_error) + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_memoryview_type) < 0) __PYX_ERR(1, 337, __pyx_L1_error) + #endif + __pyx_vtabptr__memoryviewslice = &__pyx_vtable__memoryviewslice; + __pyx_vtable__memoryviewslice.__pyx_base = *__pyx_vtabptr_memoryview; + __pyx_vtable__memoryviewslice.__pyx_base.convert_item_to_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *))__pyx_memoryviewslice_convert_item_to_object; + __pyx_vtable__memoryviewslice.__pyx_base.assign_item_from_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *, PyObject *))__pyx_memoryviewslice_assign_item_from_object; + __pyx_vtable__memoryviewslice.__pyx_base._get_base = (PyObject *(*)(struct __pyx_memoryview_obj *))__pyx_memoryviewslice__get_base; + #if CYTHON_USE_TYPE_SPECS + __pyx_t_1 = PyTuple_Pack(1, (PyObject *)__pyx_memoryview_type); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 952, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_memoryviewslice_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_memoryviewslice_spec, __pyx_t_1); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_memoryviewslice_type)) __PYX_ERR(1, 952, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_memoryviewslice_spec, __pyx_memoryviewslice_type) < 0) __PYX_ERR(1, 952, __pyx_L1_error) + #else + __pyx_memoryviewslice_type = &__pyx_type___pyx_memoryviewslice; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + __pyx_memoryviewslice_type->tp_base = __pyx_memoryview_type; + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_memoryviewslice_type) < 0) __PYX_ERR(1, 952, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_memoryviewslice_type->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_memoryviewslice_type->tp_dictoffset && __pyx_memoryviewslice_type->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_memoryviewslice_type->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (__Pyx_SetVtable(__pyx_memoryviewslice_type, __pyx_vtabptr__memoryviewslice) < 0) __PYX_ERR(1, 952, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_memoryviewslice_type) < 0) __PYX_ERR(1, 952, __pyx_L1_error) + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_memoryviewslice_type) < 0) __PYX_ERR(1, 952, __pyx_L1_error) + #endif + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_RefNannyFinishContext(); + return -1; +} + +static int __Pyx_modinit_type_import_code(void) { + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_modinit_type_import_code", 0); + /*--- Type import code ---*/ + __pyx_t_1 = PyImport_ImportModule(__Pyx_BUILTIN_MODULE_NAME); if (unlikely(!__pyx_t_1)) __PYX_ERR(3, 9, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_ptype_7cpython_4type_type = __Pyx_ImportType_3_0_8(__pyx_t_1, __Pyx_BUILTIN_MODULE_NAME, "type", + #if defined(PYPY_VERSION_NUM) && PYPY_VERSION_NUM < 0x050B0000 + sizeof(PyTypeObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyTypeObject), + #elif CYTHON_COMPILING_IN_LIMITED_API + sizeof(PyTypeObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyTypeObject), + #else + sizeof(PyHeapTypeObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyHeapTypeObject), + #endif + __Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_7cpython_4type_type) __PYX_ERR(3, 9, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = PyImport_ImportModule("numpy"); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 202, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_ptype_5numpy_dtype = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "dtype", sizeof(PyArray_Descr), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyArray_Descr),__Pyx_ImportType_CheckSize_Ignore_3_0_8); if (!__pyx_ptype_5numpy_dtype) __PYX_ERR(2, 202, __pyx_L1_error) + __pyx_ptype_5numpy_flatiter = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "flatiter", sizeof(PyArrayIterObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyArrayIterObject),__Pyx_ImportType_CheckSize_Ignore_3_0_8); if (!__pyx_ptype_5numpy_flatiter) __PYX_ERR(2, 225, __pyx_L1_error) + __pyx_ptype_5numpy_broadcast = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "broadcast", sizeof(PyArrayMultiIterObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyArrayMultiIterObject),__Pyx_ImportType_CheckSize_Ignore_3_0_8); if (!__pyx_ptype_5numpy_broadcast) __PYX_ERR(2, 229, __pyx_L1_error) + __pyx_ptype_5numpy_ndarray = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "ndarray", sizeof(PyArrayObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyArrayObject),__Pyx_ImportType_CheckSize_Ignore_3_0_8); if (!__pyx_ptype_5numpy_ndarray) __PYX_ERR(2, 238, __pyx_L1_error) + __pyx_ptype_5numpy_generic = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "generic", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_generic) __PYX_ERR(2, 809, __pyx_L1_error) + __pyx_ptype_5numpy_number = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "number", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_number) __PYX_ERR(2, 811, __pyx_L1_error) + __pyx_ptype_5numpy_integer = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "integer", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_integer) __PYX_ERR(2, 813, __pyx_L1_error) + __pyx_ptype_5numpy_signedinteger = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "signedinteger", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_signedinteger) __PYX_ERR(2, 815, __pyx_L1_error) + __pyx_ptype_5numpy_unsignedinteger = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "unsignedinteger", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_unsignedinteger) __PYX_ERR(2, 817, __pyx_L1_error) + __pyx_ptype_5numpy_inexact = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "inexact", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_inexact) __PYX_ERR(2, 819, __pyx_L1_error) + __pyx_ptype_5numpy_floating = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "floating", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_floating) __PYX_ERR(2, 821, __pyx_L1_error) + __pyx_ptype_5numpy_complexfloating = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "complexfloating", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_complexfloating) __PYX_ERR(2, 823, __pyx_L1_error) + __pyx_ptype_5numpy_flexible = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "flexible", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_flexible) __PYX_ERR(2, 825, __pyx_L1_error) + __pyx_ptype_5numpy_character = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "character", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_character) __PYX_ERR(2, 827, __pyx_L1_error) + __pyx_ptype_5numpy_ufunc = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "ufunc", sizeof(PyUFuncObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyUFuncObject),__Pyx_ImportType_CheckSize_Ignore_3_0_8); if (!__pyx_ptype_5numpy_ufunc) __PYX_ERR(2, 866, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_RefNannyFinishContext(); + return -1; +} + +static int __Pyx_modinit_variable_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_import_code", 0); + /*--- Variable import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_import_code", 0); + /*--- Function import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + + +#if PY_MAJOR_VERSION >= 3 +#if CYTHON_PEP489_MULTI_PHASE_INIT +static PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def); /*proto*/ +static int __pyx_pymod_exec_acados_ocp_solver_pyx(PyObject* module); /*proto*/ +static PyModuleDef_Slot __pyx_moduledef_slots[] = { + {Py_mod_create, (void*)__pyx_pymod_create}, + {Py_mod_exec, (void*)__pyx_pymod_exec_acados_ocp_solver_pyx}, + {0, NULL} +}; +#endif + +#ifdef __cplusplus +namespace { + struct PyModuleDef __pyx_moduledef = + #else + static struct PyModuleDef __pyx_moduledef = + #endif + { + PyModuleDef_HEAD_INIT, + "acados_ocp_solver_pyx", + 0, /* m_doc */ + #if CYTHON_PEP489_MULTI_PHASE_INIT + 0, /* m_size */ + #elif CYTHON_USE_MODULE_STATE + sizeof(__pyx_mstate), /* m_size */ + #else + -1, /* m_size */ + #endif + __pyx_methods /* m_methods */, + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_moduledef_slots, /* m_slots */ + #else + NULL, /* m_reload */ + #endif + #if CYTHON_USE_MODULE_STATE + __pyx_m_traverse, /* m_traverse */ + __pyx_m_clear, /* m_clear */ + NULL /* m_free */ + #else + NULL, /* m_traverse */ + NULL, /* m_clear */ + NULL /* m_free */ + #endif + }; + #ifdef __cplusplus +} /* anonymous namespace */ +#endif +#endif + +#ifndef CYTHON_NO_PYINIT_EXPORT +#define __Pyx_PyMODINIT_FUNC PyMODINIT_FUNC +#elif PY_MAJOR_VERSION < 3 +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" void +#else +#define __Pyx_PyMODINIT_FUNC void +#endif +#else +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" PyObject * +#else +#define __Pyx_PyMODINIT_FUNC PyObject * +#endif +#endif + + +#if PY_MAJOR_VERSION < 3 +__Pyx_PyMODINIT_FUNC initacados_ocp_solver_pyx(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC initacados_ocp_solver_pyx(void) +#else +__Pyx_PyMODINIT_FUNC PyInit_acados_ocp_solver_pyx(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC PyInit_acados_ocp_solver_pyx(void) +#if CYTHON_PEP489_MULTI_PHASE_INIT +{ + return PyModuleDef_Init(&__pyx_moduledef); +} +static CYTHON_SMALL_CODE int __Pyx_check_single_interpreter(void) { + #if PY_VERSION_HEX >= 0x030700A1 + static PY_INT64_T main_interpreter_id = -1; + PY_INT64_T current_id = PyInterpreterState_GetID(PyThreadState_Get()->interp); + if (main_interpreter_id == -1) { + main_interpreter_id = current_id; + return (unlikely(current_id == -1)) ? -1 : 0; + } else if (unlikely(main_interpreter_id != current_id)) + #else + static PyInterpreterState *main_interpreter = NULL; + PyInterpreterState *current_interpreter = PyThreadState_Get()->interp; + if (!main_interpreter) { + main_interpreter = current_interpreter; + } else if (unlikely(main_interpreter != current_interpreter)) + #endif + { + PyErr_SetString( + PyExc_ImportError, + "Interpreter change detected - this module can only be loaded into one interpreter per process."); + return -1; + } + return 0; +} +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *module, const char* from_name, const char* to_name, int allow_none) +#else +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *moddict, const char* from_name, const char* to_name, int allow_none) +#endif +{ + PyObject *value = PyObject_GetAttrString(spec, from_name); + int result = 0; + if (likely(value)) { + if (allow_none || value != Py_None) { +#if CYTHON_COMPILING_IN_LIMITED_API + result = PyModule_AddObject(module, to_name, value); +#else + result = PyDict_SetItemString(moddict, to_name, value); +#endif + } + Py_DECREF(value); + } else if (PyErr_ExceptionMatches(PyExc_AttributeError)) { + PyErr_Clear(); + } else { + result = -1; + } + return result; +} +static CYTHON_SMALL_CODE PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def) { + PyObject *module = NULL, *moddict, *modname; + CYTHON_UNUSED_VAR(def); + if (__Pyx_check_single_interpreter()) + return NULL; + if (__pyx_m) + return __Pyx_NewRef(__pyx_m); + modname = PyObject_GetAttrString(spec, "name"); + if (unlikely(!modname)) goto bad; + module = PyModule_NewObject(modname); + Py_DECREF(modname); + if (unlikely(!module)) goto bad; +#if CYTHON_COMPILING_IN_LIMITED_API + moddict = module; +#else + moddict = PyModule_GetDict(module); + if (unlikely(!moddict)) goto bad; +#endif + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "loader", "__loader__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "origin", "__file__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "parent", "__package__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "submodule_search_locations", "__path__", 0) < 0)) goto bad; + return module; +bad: + Py_XDECREF(module); + return NULL; +} + + +static CYTHON_SMALL_CODE int __pyx_pymod_exec_acados_ocp_solver_pyx(PyObject *__pyx_pyinit_module) +#endif +#endif +{ + int stringtab_initialized = 0; + #if CYTHON_USE_MODULE_STATE + int pystate_addmodule_run = 0; + #endif + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + static PyThread_type_lock __pyx_t_8[8]; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannyDeclarations + #if CYTHON_PEP489_MULTI_PHASE_INIT + if (__pyx_m) { + if (__pyx_m == __pyx_pyinit_module) return 0; + PyErr_SetString(PyExc_RuntimeError, "Module 'acados_ocp_solver_pyx' has already been imported. Re-initialisation is not supported."); + return -1; + } + #elif PY_MAJOR_VERSION >= 3 + if (__pyx_m) return __Pyx_NewRef(__pyx_m); + #endif + /*--- Module creation code ---*/ + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_m = __pyx_pyinit_module; + Py_INCREF(__pyx_m); + #else + #if PY_MAJOR_VERSION < 3 + __pyx_m = Py_InitModule4("acados_ocp_solver_pyx", __pyx_methods, 0, 0, PYTHON_API_VERSION); Py_XINCREF(__pyx_m); + if (unlikely(!__pyx_m)) __PYX_ERR(0, 1, __pyx_L1_error) + #elif CYTHON_USE_MODULE_STATE + __pyx_t_1 = PyModule_Create(&__pyx_moduledef); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 1, __pyx_L1_error) + { + int add_module_result = PyState_AddModule(__pyx_t_1, &__pyx_moduledef); + __pyx_t_1 = 0; /* transfer ownership from __pyx_t_1 to "acados_ocp_solver_pyx" pseudovariable */ + if (unlikely((add_module_result < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + pystate_addmodule_run = 1; + } + #else + __pyx_m = PyModule_Create(&__pyx_moduledef); + if (unlikely(!__pyx_m)) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #endif + CYTHON_UNUSED_VAR(__pyx_t_1); + __pyx_d = PyModule_GetDict(__pyx_m); if (unlikely(!__pyx_d)) __PYX_ERR(0, 1, __pyx_L1_error) + Py_INCREF(__pyx_d); + __pyx_b = __Pyx_PyImport_AddModuleRef(__Pyx_BUILTIN_MODULE_NAME); if (unlikely(!__pyx_b)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_cython_runtime = __Pyx_PyImport_AddModuleRef((const char *) "cython_runtime"); if (unlikely(!__pyx_cython_runtime)) __PYX_ERR(0, 1, __pyx_L1_error) + if (PyObject_SetAttrString(__pyx_m, "__builtins__", __pyx_b) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #if CYTHON_REFNANNY +__Pyx_RefNanny = __Pyx_RefNannyImportAPI("refnanny"); +if (!__Pyx_RefNanny) { + PyErr_Clear(); + __Pyx_RefNanny = __Pyx_RefNannyImportAPI("Cython.Runtime.refnanny"); + if (!__Pyx_RefNanny) + Py_FatalError("failed to import 'refnanny' module"); +} +#endif + __Pyx_RefNannySetupContext("__Pyx_PyMODINIT_FUNC PyInit_acados_ocp_solver_pyx(void)", 0); + if (__Pyx_check_binary_version(__PYX_LIMITED_VERSION_HEX, __Pyx_get_runtime_version(), CYTHON_COMPILING_IN_LIMITED_API) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #ifdef __Pxy_PyFrame_Initialize_Offsets + __Pxy_PyFrame_Initialize_Offsets(); + #endif + __pyx_empty_tuple = PyTuple_New(0); if (unlikely(!__pyx_empty_tuple)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_empty_bytes = PyBytes_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_bytes)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_empty_unicode = PyUnicode_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_unicode)) __PYX_ERR(0, 1, __pyx_L1_error) + #ifdef __Pyx_CyFunction_USED + if (__pyx_CyFunction_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_FusedFunction_USED + if (__pyx_FusedFunction_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Coroutine_USED + if (__pyx_Coroutine_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Generator_USED + if (__pyx_Generator_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_AsyncGen_USED + if (__pyx_AsyncGen_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_StopAsyncIteration_USED + if (__pyx_StopAsyncIteration_init(__pyx_m) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + /*--- Library function declarations ---*/ + /*--- Threads initialization code ---*/ + #if defined(WITH_THREAD) && PY_VERSION_HEX < 0x030700F0 && defined(__PYX_FORCE_INIT_THREADS) && __PYX_FORCE_INIT_THREADS + PyEval_InitThreads(); + #endif + /*--- Initialize various global constants etc. ---*/ + if (__Pyx_InitConstants() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + stringtab_initialized = 1; + if (__Pyx_InitGlobals() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #if PY_MAJOR_VERSION < 3 && (__PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT) + if (__Pyx_init_sys_getdefaultencoding_params() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + if (__pyx_module_is_main_acados_template__acados_ocp_solver_pyx) { + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_name_2, __pyx_n_s_main) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + } + #if PY_MAJOR_VERSION >= 3 + { + PyObject *modules = PyImport_GetModuleDict(); if (unlikely(!modules)) __PYX_ERR(0, 1, __pyx_L1_error) + if (!PyDict_GetItemString(modules, "acados_template.acados_ocp_solver_pyx")) { + if (unlikely((PyDict_SetItemString(modules, "acados_template.acados_ocp_solver_pyx", __pyx_m) < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + } + } + #endif + /*--- Builtin init code ---*/ + if (__Pyx_InitCachedBuiltins() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + /*--- Constants init code ---*/ + if (__Pyx_InitCachedConstants() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + /*--- Global type/function init code ---*/ + (void)__Pyx_modinit_global_init_code(); + (void)__Pyx_modinit_variable_export_code(); + (void)__Pyx_modinit_function_export_code(); + if (unlikely((__Pyx_modinit_type_init_code() < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + if (unlikely((__Pyx_modinit_type_import_code() < 0))) __PYX_ERR(0, 1, __pyx_L1_error) + (void)__Pyx_modinit_variable_import_code(); + (void)__Pyx_modinit_function_import_code(); + /*--- Execution code ---*/ + #if defined(__Pyx_Generator_USED) || defined(__Pyx_Coroutine_USED) + if (__Pyx_patch_abc() < 0) __PYX_ERR(0, 1, __pyx_L1_error) + #endif + + /* "View.MemoryView":99 + * + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: # <<<<<<<<<<<<<< + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "View.MemoryView":100 + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: + * if __import__("sys").version_info >= (3, 3): # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + */ + __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__33, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 100, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_version_info); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 100, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = PyObject_RichCompare(__pyx_t_5, __pyx_tuple__34, Py_GE); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 100, __pyx_L2_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_6 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(1, 100, __pyx_L2_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (__pyx_t_6) { + + /* "View.MemoryView":101 + * try: + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence # <<<<<<<<<<<<<< + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence + */ + __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__35, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 101, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_abc); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 101, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_Sequence); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 101, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XGOTREF(__pyx_collections_abc_Sequence); + __Pyx_DECREF_SET(__pyx_collections_abc_Sequence, __pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + __pyx_t_4 = 0; + + /* "View.MemoryView":100 + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: + * if __import__("sys").version_info >= (3, 3): # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + */ + goto __pyx_L8; + } + + /* "View.MemoryView":103 + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence # <<<<<<<<<<<<<< + * except: + * + */ + /*else*/ { + __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__36, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 103, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_Sequence); if (unlikely(!__pyx_t_5)) __PYX_ERR(1, 103, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XGOTREF(__pyx_collections_abc_Sequence); + __Pyx_DECREF_SET(__pyx_collections_abc_Sequence, __pyx_t_5); + __Pyx_GIVEREF(__pyx_t_5); + __pyx_t_5 = 0; + } + __pyx_L8:; + + /* "View.MemoryView":99 + * + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: # <<<<<<<<<<<<<< + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L7_try_end; + __pyx_L2_error:; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "View.MemoryView":104 + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence + * except: # <<<<<<<<<<<<<< + * + * __pyx_collections_abc_Sequence = None + */ + /*except:*/ { + __Pyx_AddTraceback("View.MemoryView", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_4, &__pyx_t_7) < 0) __PYX_ERR(1, 104, __pyx_L4_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_4); + __Pyx_XGOTREF(__pyx_t_7); + + /* "View.MemoryView":106 + * except: + * + * __pyx_collections_abc_Sequence = None # <<<<<<<<<<<<<< + * + * + */ + __Pyx_INCREF(Py_None); + __Pyx_XGOTREF(__pyx_collections_abc_Sequence); + __Pyx_DECREF_SET(__pyx_collections_abc_Sequence, Py_None); + __Pyx_GIVEREF(Py_None); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + goto __pyx_L3_exception_handled; + } + + /* "View.MemoryView":99 + * + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: # <<<<<<<<<<<<<< + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + */ + __pyx_L4_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + goto __pyx_L1_error; + __pyx_L3_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + __pyx_L7_try_end:; + } + + /* "View.MemoryView":241 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_3, &__pyx_t_2, &__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_1); + /*try:*/ { + + /* "View.MemoryView":242 + * + * try: + * count = __pyx_collections_abc_Sequence.count # <<<<<<<<<<<<<< + * index = __pyx_collections_abc_Sequence.index + * except: + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_count); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 242, __pyx_L11_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict(__pyx_array_type, __pyx_n_s_count, __pyx_t_7) < 0) __PYX_ERR(1, 242, __pyx_L11_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_array_type); + + /* "View.MemoryView":243 + * try: + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index # <<<<<<<<<<<<<< + * except: + * pass + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_index); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 243, __pyx_L11_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict(__pyx_array_type, __pyx_n_s_index, __pyx_t_7) < 0) __PYX_ERR(1, 243, __pyx_L11_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_array_type); + + /* "View.MemoryView":241 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + } + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + goto __pyx_L16_try_end; + __pyx_L11_error:; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":244 + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + * except: # <<<<<<<<<<<<<< + * pass + * + */ + /*except:*/ { + __Pyx_ErrRestore(0,0,0); + goto __pyx_L12_exception_handled; + } + __pyx_L12_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_2, __pyx_t_1); + __pyx_L16_try_end:; + } + + /* "View.MemoryView":309 + * return self.name + * + * cdef generic = Enum("") # <<<<<<<<<<<<<< + * cdef strided = Enum("") # default + * cdef indirect = Enum("") + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__37, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 309, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(generic); + __Pyx_DECREF_SET(generic, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":310 + * + * cdef generic = Enum("") + * cdef strided = Enum("") # default # <<<<<<<<<<<<<< + * cdef indirect = Enum("") + * + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__38, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 310, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(strided); + __Pyx_DECREF_SET(strided, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":311 + * cdef generic = Enum("") + * cdef strided = Enum("") # default + * cdef indirect = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__39, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 311, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(indirect); + __Pyx_DECREF_SET(indirect, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":314 + * + * + * cdef contiguous = Enum("") # <<<<<<<<<<<<<< + * cdef indirect_contiguous = Enum("") + * + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__40, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 314, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(contiguous); + __Pyx_DECREF_SET(contiguous, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":315 + * + * cdef contiguous = Enum("") + * cdef indirect_contiguous = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__41, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 315, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(indirect_contiguous); + __Pyx_DECREF_SET(indirect_contiguous, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":323 + * + * + * cdef int __pyx_memoryview_thread_locks_used = 0 # <<<<<<<<<<<<<< + * cdef PyThread_type_lock[8] __pyx_memoryview_thread_locks = [ + * PyThread_allocate_lock(), + */ + __pyx_memoryview_thread_locks_used = 0; + + /* "View.MemoryView":324 + * + * cdef int __pyx_memoryview_thread_locks_used = 0 + * cdef PyThread_type_lock[8] __pyx_memoryview_thread_locks = [ # <<<<<<<<<<<<<< + * PyThread_allocate_lock(), + * PyThread_allocate_lock(), + */ + __pyx_t_8[0] = PyThread_allocate_lock(); + __pyx_t_8[1] = PyThread_allocate_lock(); + __pyx_t_8[2] = PyThread_allocate_lock(); + __pyx_t_8[3] = PyThread_allocate_lock(); + __pyx_t_8[4] = PyThread_allocate_lock(); + __pyx_t_8[5] = PyThread_allocate_lock(); + __pyx_t_8[6] = PyThread_allocate_lock(); + __pyx_t_8[7] = PyThread_allocate_lock(); + memcpy(&(__pyx_memoryview_thread_locks[0]), __pyx_t_8, sizeof(__pyx_memoryview_thread_locks[0]) * (8)); + + /* "View.MemoryView":982 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "View.MemoryView":983 + * + * try: + * count = __pyx_collections_abc_Sequence.count # <<<<<<<<<<<<<< + * index = __pyx_collections_abc_Sequence.index + * except: + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_count); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 983, __pyx_L17_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict(__pyx_memoryviewslice_type, __pyx_n_s_count, __pyx_t_7) < 0) __PYX_ERR(1, 983, __pyx_L17_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_memoryviewslice_type); + + /* "View.MemoryView":984 + * try: + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index # <<<<<<<<<<<<<< + * except: + * pass + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_index); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 984, __pyx_L17_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict(__pyx_memoryviewslice_type, __pyx_n_s_index, __pyx_t_7) < 0) __PYX_ERR(1, 984, __pyx_L17_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_memoryviewslice_type); + + /* "View.MemoryView":982 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L22_try_end; + __pyx_L17_error:; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":985 + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + * except: # <<<<<<<<<<<<<< + * pass + * + */ + /*except:*/ { + __Pyx_ErrRestore(0,0,0); + goto __pyx_L18_exception_handled; + } + __pyx_L18_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + __pyx_L22_try_end:; + } + + /* "View.MemoryView":988 + * pass + * + * try: # <<<<<<<<<<<<<< + * if __pyx_collections_abc_Sequence: + * + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_3, &__pyx_t_2, &__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_1); + /*try:*/ { + + /* "View.MemoryView":989 + * + * try: + * if __pyx_collections_abc_Sequence: # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_6 = __Pyx_PyObject_IsTrue(__pyx_collections_abc_Sequence); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(1, 989, __pyx_L23_error) + if (__pyx_t_6) { + + /* "View.MemoryView":993 + * + * + * __pyx_collections_abc_Sequence.register(_memoryviewslice) # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence.register(array) + * except: + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_register); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 993, __pyx_L23_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_4 = __Pyx_PyObject_CallOneArg(__pyx_t_7, ((PyObject *)__pyx_memoryviewslice_type)); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 993, __pyx_L23_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "View.MemoryView":994 + * + * __pyx_collections_abc_Sequence.register(_memoryviewslice) + * __pyx_collections_abc_Sequence.register(array) # <<<<<<<<<<<<<< + * except: + * pass # ignore failure, it's a minor issue + */ + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_register); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 994, __pyx_L23_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_7 = __Pyx_PyObject_CallOneArg(__pyx_t_4, ((PyObject *)__pyx_array_type)); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 994, __pyx_L23_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":989 + * + * try: + * if __pyx_collections_abc_Sequence: # <<<<<<<<<<<<<< + * + * + */ + } + + /* "View.MemoryView":988 + * pass + * + * try: # <<<<<<<<<<<<<< + * if __pyx_collections_abc_Sequence: + * + */ + } + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + goto __pyx_L28_try_end; + __pyx_L23_error:; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":995 + * __pyx_collections_abc_Sequence.register(_memoryviewslice) + * __pyx_collections_abc_Sequence.register(array) + * except: # <<<<<<<<<<<<<< + * pass # ignore failure, it's a minor issue + * + */ + /*except:*/ { + __Pyx_ErrRestore(0,0,0); + goto __pyx_L24_exception_handled; + } + __pyx_L24_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_2, __pyx_t_1); + __pyx_L28_try_end:; + } + + /* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + __pyx_t_7 = PyCFunction_NewEx(&__pyx_mdef_15View_dot_MemoryView_1__pyx_unpickle_Enum, NULL, __pyx_n_s_View_MemoryView); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_pyx_unpickle_Enum, __pyx_t_7) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":44 + * cimport numpy as cnp + * + * import os # <<<<<<<<<<<<<< + * from datetime import datetime + * import numpy as np + */ + __pyx_t_7 = __Pyx_ImportDottedModule(__pyx_n_s_os, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 44, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_os, __pyx_t_7) < 0) __PYX_ERR(0, 44, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":45 + * + * import os + * from datetime import datetime # <<<<<<<<<<<<<< + * import numpy as np + * + */ + __pyx_t_7 = PyList_New(1); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 45, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_INCREF(__pyx_n_s_datetime); + __Pyx_GIVEREF(__pyx_n_s_datetime); + if (__Pyx_PyList_SET_ITEM(__pyx_t_7, 0, __pyx_n_s_datetime)) __PYX_ERR(0, 45, __pyx_L1_error); + __pyx_t_4 = __Pyx_Import(__pyx_n_s_datetime, __pyx_t_7, 0); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 45, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __pyx_t_7 = __Pyx_ImportFrom(__pyx_t_4, __pyx_n_s_datetime); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 45, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_datetime, __pyx_t_7) < 0) __PYX_ERR(0, 45, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":46 + * import os + * from datetime import datetime + * import numpy as np # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_4 = __Pyx_ImportDottedModule(__pyx_n_s_numpy, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 46, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_np, __pyx_t_4) < 0) __PYX_ERR(0, 46, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":89 + * + * + * def __get_pointers_solver(self): # <<<<<<<<<<<<<< + * """ + * Private function to get the pointers for solver + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_3_AcadosOcpSolverCython__get_pointers_solver, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___get_poin, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__45)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 89, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_AcadosOcpSolverCython__get_poin, __pyx_t_4) < 0) __PYX_ERR(0, 89, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":103 + * + * + * def solve_for_x0(self, x0_bar): # <<<<<<<<<<<<<< + * """ + * Wrapper around `solve()` which sets initial state constraint, solves the OCP, and returns u0. + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_5solve_for_x0, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_solve_for, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__47)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 103, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_solve_for_x0, __pyx_t_4) < 0) __PYX_ERR(0, 103, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":121 + * + * + * def solve(self): # <<<<<<<<<<<<<< + * """ + * Solve the ocp with current input. + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_7solve, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_solve, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__48)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 121, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_solve, __pyx_t_4) < 0) __PYX_ERR(0, 121, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":128 + * + * + * def reset(self, reset_qp_solver_mem=1): # <<<<<<<<<<<<<< + * """ + * Sets current iterate to all zeros. + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_9reset, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_reset, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__50)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 128, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_4, __pyx_tuple__25); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_reset, __pyx_t_4) < 0) __PYX_ERR(0, 128, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":135 + * + * + * def custom_update(self, data_): # <<<<<<<<<<<<<< + * """ + * A custom function that can be implemented by a user to be called between solver calls. + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_11custom_update, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_custom_upd, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__52)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 135, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_custom_update, __pyx_t_4) < 0) __PYX_ERR(0, 135, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":148 + * + * + * def set_new_time_steps(self, new_time_steps): # <<<<<<<<<<<<<< + * """ + * Set new time steps. + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_13set_new_time_steps, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_set_new_ti, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__54)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 148, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_set_new_time_steps, __pyx_t_4) < 0) __PYX_ERR(0, 148, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":199 + * + * + * def update_qp_solver_cond_N(self, qp_solver_cond_N: int): # <<<<<<<<<<<<<< + * """ + * Recreate solver with new value `qp_solver_cond_N` with a partial condensing QP solver. + */ + __pyx_t_4 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 199, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem(__pyx_t_4, __pyx_n_s_qp_solver_cond_N, __pyx_n_s_int) < 0) __PYX_ERR(0, 199, __pyx_L1_error) + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_15update_qp_solver_cond_N, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_update_qp, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__56)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 199, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_CyFunction_SetAnnotationsDict(__pyx_t_7, __pyx_t_4); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_update_qp_solver_cond_N, __pyx_t_7) < 0) __PYX_ERR(0, 199, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":233 + * + * + * def eval_param_sens(self, index, stage=0, field="ex"): # <<<<<<<<<<<<<< + * """ + * Calculate the sensitivity of the curent solution with respect to the initial state component of index + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_17eval_param_sens, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_eval_param_3, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__58)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 233, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_7, __pyx_tuple__59); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_eval_param_sens, __pyx_t_7) < 0) __PYX_ERR(0, 233, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":258 + * + * + * def get(self, int stage, str field_): # <<<<<<<<<<<<<< + * """ + * Get the last solution of the solver: + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_19get, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_get, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__61)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 258, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_get, __pyx_t_7) < 0) __PYX_ERR(0, 258, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":301 + * + * + * def print_statistics(self): # <<<<<<<<<<<<<< + * """ + * prints statistics of previous solver run as a table: + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_21print_statistics, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_print_stat, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__62)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 301, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_print_statistics, __pyx_t_7) < 0) __PYX_ERR(0, 301, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":319 + * + * + * def store_iterate(self, filename='', overwrite=False): # <<<<<<<<<<<<<< + * """ + * Stores the current iterate of the ocp solver in a json file. + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_23store_iterate, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_store_iter, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__64)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 319, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_7, __pyx_tuple__65); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_store_iterate, __pyx_t_7) < 0) __PYX_ERR(0, 319, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":362 + * + * + * def load_iterate(self, filename): # <<<<<<<<<<<<<< + * """ + * Loads the iterate stored in json file with filename into the ocp solver. + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_25load_iterate, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_load_itera, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__67)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 362, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_load_iterate, __pyx_t_7) < 0) __PYX_ERR(0, 362, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":378 + * + * + * def get_stats(self, field_): # <<<<<<<<<<<<<< + * """ + * Get the information of the last solver call. + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_27get_stats, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_get_stats, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__69)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 378, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_get_stats, __pyx_t_7) < 0) __PYX_ERR(0, 378, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":460 + * + * + * def __get_stat_int(self, field): # <<<<<<<<<<<<<< + * cdef int out + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, &out) + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_29_AcadosOcpSolverCython__get_stat_int, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___get_stat, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__71)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 460, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_AcadosOcpSolverCython__get_stat, __pyx_t_7) < 0) __PYX_ERR(0, 460, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":465 + * return out + * + * def __get_stat_double(self, field): # <<<<<<<<<<<<<< + * cdef cnp.ndarray[cnp.float64_t, ndim=1] out = np.zeros((1,)) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out.data) + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_31_AcadosOcpSolverCython__get_stat_double, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___get_stat_2, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__72)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 465, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_AcadosOcpSolverCython__get_stat_2, __pyx_t_7) < 0) __PYX_ERR(0, 465, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":470 + * return out + * + * def __get_stat_matrix(self, field, n, m): # <<<<<<<<<<<<<< + * cdef cnp.ndarray[cnp.float64_t, ndim=2] out_mat = np.ascontiguousarray(np.zeros((n, m)), dtype=np.float64) + * acados_solver_common.ocp_nlp_get(self.nlp_config, self.nlp_solver, field, out_mat.data) + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_33_AcadosOcpSolverCython__get_stat_matrix, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___get_stat_3, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__74)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 470, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_AcadosOcpSolverCython__get_stat_3, __pyx_t_7) < 0) __PYX_ERR(0, 470, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":476 + * + * + * def get_cost(self): # <<<<<<<<<<<<<< + * """ + * Returns the cost value of the current solution. + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_35get_cost, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_get_cost, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__76)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 476, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_get_cost, __pyx_t_7) < 0) __PYX_ERR(0, 476, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":492 + * + * + * def get_residuals(self, recompute=False): # <<<<<<<<<<<<<< + * """ + * Returns an array of the form [res_stat, res_eq, res_ineq, res_comp]. + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_37get_residuals, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_get_residu, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__78)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 492, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_CyFunction_SetDefaultsTuple(__pyx_t_7, __pyx_tuple__79); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_get_residuals, __pyx_t_7) < 0) __PYX_ERR(0, 492, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":524 + * + * # Note: this function should not be used anymore, better use cost_set, constraints_set + * def set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * + * """ + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_39set, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_set, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__81)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 524, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_set, __pyx_t_7) < 0) __PYX_ERR(0, 524, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":590 + * return + * + * def cost_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set numerical data in the cost module of the solver. + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_41cost_set, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_cost_set, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__83)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 590, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_cost_set, __pyx_t_7) < 0) __PYX_ERR(0, 590, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":625 + * + * + * def constraints_set(self, int stage, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set numerical data in the constraint module of the solver. + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_43constraints_set, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_constraint_2, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__84)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 625, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_constraints_set, __pyx_t_7) < 0) __PYX_ERR(0, 625, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":663 + * + * + * def get_from_qp_in(self, int stage, str field_): # <<<<<<<<<<<<<< + * """ + * Get numerical data from the dynamics module of the solver: + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_45get_from_qp_in, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_get_from_q, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__86)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_get_from_qp_in, __pyx_t_7) < 0) __PYX_ERR(0, 663, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":685 + * + * + * def options_set(self, str field_, value_): # <<<<<<<<<<<<<< + * """ + * Set options of the solver. + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_47options_set, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_options_se_2, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__88)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 685, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_options_set, __pyx_t_7) < 0) __PYX_ERR(0, 685, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "acados_template/acados_ocp_solver_pyx.pyx":748 + * + * + * def set_params_sparse(self, int stage, idx_values_, param_values_): # <<<<<<<<<<<<<< + * """ + * set parameters of the solvers external function partially: + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_49set_params_sparse, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython_set_params, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__90)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 748, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython, __pyx_n_s_set_params_sparse, __pyx_t_7) < 0) __PYX_ERR(0, 748, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_15acados_template_21acados_ocp_solver_pyx_AcadosOcpSolverCython); + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_53__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___reduce_c, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__91)); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_7) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_15acados_template_21acados_ocp_solver_pyx_21AcadosOcpSolverCython_55__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_AcadosOcpSolverCython___setstate, NULL, __pyx_n_s_acados_template_acados_ocp_solve, __pyx_d, ((PyObject *)__pyx_codeobj__93)); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_7) < 0) __PYX_ERR(1, 3, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "acados_template/acados_ocp_solver_pyx.pyx":1 + * # -*- coding: future_fstrings -*- # <<<<<<<<<<<<<< + * # + * # Copyright (c) The acados authors. + */ + __pyx_t_7 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_test, __pyx_t_7) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /*--- Wrapped vars code ---*/ + + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_7); + if (__pyx_m) { + if (__pyx_d && stringtab_initialized) { + __Pyx_AddTraceback("init acados_template.acados_ocp_solver_pyx", __pyx_clineno, __pyx_lineno, __pyx_filename); + } + #if !CYTHON_USE_MODULE_STATE + Py_CLEAR(__pyx_m); + #else + Py_DECREF(__pyx_m); + if (pystate_addmodule_run) { + PyObject *tp, *value, *tb; + PyErr_Fetch(&tp, &value, &tb); + PyState_RemoveModule(&__pyx_moduledef); + PyErr_Restore(tp, value, tb); + } + #endif + } else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_ImportError, "init acados_template.acados_ocp_solver_pyx"); + } + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + #if CYTHON_PEP489_MULTI_PHASE_INIT + return (__pyx_m != NULL) ? 0 : -1; + #elif PY_MAJOR_VERSION >= 3 + return __pyx_m; + #else + return; + #endif +} +/* #### Code section: cleanup_globals ### */ +/* #### Code section: cleanup_module ### */ +/* #### Code section: main_method ### */ +/* #### Code section: utility_code_pragmas ### */ +#ifdef _MSC_VER +#pragma warning( push ) +/* Warning 4127: conditional expression is constant + * Cython uses constant conditional expressions to allow in inline functions to be optimized at + * compile-time, so this warning is not useful + */ +#pragma warning( disable : 4127 ) +#endif + + + +/* #### Code section: utility_code_def ### */ + +/* --- Runtime support code --- */ +/* Refnanny */ +#if CYTHON_REFNANNY +static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname) { + PyObject *m = NULL, *p = NULL; + void *r = NULL; + m = PyImport_ImportModule(modname); + if (!m) goto end; + p = PyObject_GetAttrString(m, "RefNannyAPI"); + if (!p) goto end; + r = PyLong_AsVoidPtr(p); +end: + Py_XDECREF(p); + Py_XDECREF(m); + return (__Pyx_RefNannyAPIStruct *)r; +} +#endif + +/* PyErrExceptionMatches */ +#if CYTHON_FAST_THREAD_STATE +static int __Pyx_PyErr_ExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; i= 0x030C00A6 + PyObject *current_exception = tstate->current_exception; + if (unlikely(!current_exception)) return 0; + exc_type = (PyObject*) Py_TYPE(current_exception); + if (exc_type == err) return 1; +#else + exc_type = tstate->curexc_type; + if (exc_type == err) return 1; + if (unlikely(!exc_type)) return 0; +#endif + #if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(exc_type); + #endif + if (unlikely(PyTuple_Check(err))) { + result = __Pyx_PyErr_ExceptionMatchesTuple(exc_type, err); + } else { + result = __Pyx_PyErr_GivenExceptionMatches(exc_type, err); + } + #if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(exc_type); + #endif + return result; +} +#endif + +/* PyErrFetchRestore */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject *tmp_value; + assert(type == NULL || (value != NULL && type == (PyObject*) Py_TYPE(value))); + if (value) { + #if CYTHON_COMPILING_IN_CPYTHON + if (unlikely(((PyBaseExceptionObject*) value)->traceback != tb)) + #endif + PyException_SetTraceback(value, tb); + } + tmp_value = tstate->current_exception; + tstate->current_exception = value; + Py_XDECREF(tmp_value); + Py_XDECREF(type); + Py_XDECREF(tb); +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + tmp_type = tstate->curexc_type; + tmp_value = tstate->curexc_value; + tmp_tb = tstate->curexc_traceback; + tstate->curexc_type = type; + tstate->curexc_value = value; + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); +#endif +} +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject* exc_value; + exc_value = tstate->current_exception; + tstate->current_exception = 0; + *value = exc_value; + *type = NULL; + *tb = NULL; + if (exc_value) { + *type = (PyObject*) Py_TYPE(exc_value); + Py_INCREF(*type); + #if CYTHON_COMPILING_IN_CPYTHON + *tb = ((PyBaseExceptionObject*) exc_value)->traceback; + Py_XINCREF(*tb); + #else + *tb = PyException_GetTraceback(exc_value); + #endif + } +#else + *type = tstate->curexc_type; + *value = tstate->curexc_value; + *tb = tstate->curexc_traceback; + tstate->curexc_type = 0; + tstate->curexc_value = 0; + tstate->curexc_traceback = 0; +#endif +} +#endif + +/* PyObjectGetAttrStr */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name) { + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro)) + return tp->tp_getattro(obj, attr_name); +#if PY_MAJOR_VERSION < 3 + if (likely(tp->tp_getattr)) + return tp->tp_getattr(obj, PyString_AS_STRING(attr_name)); +#endif + return PyObject_GetAttr(obj, attr_name); +} +#endif + +/* PyObjectGetAttrStrNoError */ +#if __PYX_LIMITED_VERSION_HEX < 0x030d00A1 +static void __Pyx_PyObject_GetAttrStr_ClearAttributeError(void) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + if (likely(__Pyx_PyErr_ExceptionMatches(PyExc_AttributeError))) + __Pyx_PyErr_Clear(); +} +#endif +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name) { + PyObject *result; +#if __PYX_LIMITED_VERSION_HEX >= 0x030d00A1 + (void) PyObject_GetOptionalAttr(obj, attr_name, &result); + return result; +#else +#if CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_TYPE_SLOTS && PY_VERSION_HEX >= 0x030700B1 + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro == PyObject_GenericGetAttr)) { + return _PyObject_GenericGetAttrWithDict(obj, attr_name, NULL, 1); + } +#endif + result = __Pyx_PyObject_GetAttrStr(obj, attr_name); + if (unlikely(!result)) { + __Pyx_PyObject_GetAttrStr_ClearAttributeError(); + } + return result; +#endif +} + +/* GetBuiltinName */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name) { + PyObject* result = __Pyx_PyObject_GetAttrStrNoError(__pyx_b, name); + if (unlikely(!result) && !PyErr_Occurred()) { + PyErr_Format(PyExc_NameError, +#if PY_MAJOR_VERSION >= 3 + "name '%U' is not defined", name); +#else + "name '%.200s' is not defined", PyString_AS_STRING(name)); +#endif + } + return result; +} + +/* TupleAndListFromArray */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE void __Pyx_copy_object_array(PyObject *const *CYTHON_RESTRICT src, PyObject** CYTHON_RESTRICT dest, Py_ssize_t length) { + PyObject *v; + Py_ssize_t i; + for (i = 0; i < length; i++) { + v = dest[i] = src[i]; + Py_INCREF(v); + } +} +static CYTHON_INLINE PyObject * +__Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + Py_INCREF(__pyx_empty_tuple); + return __pyx_empty_tuple; + } + res = PyTuple_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyTupleObject*)res)->ob_item, n); + return res; +} +static CYTHON_INLINE PyObject * +__Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + return PyList_New(0); + } + res = PyList_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyListObject*)res)->ob_item, n); + return res; +} +#endif + +/* BytesEquals */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else + if (s1 == s2) { + return (equals == Py_EQ); + } else if (PyBytes_CheckExact(s1) & PyBytes_CheckExact(s2)) { + const char *ps1, *ps2; + Py_ssize_t length = PyBytes_GET_SIZE(s1); + if (length != PyBytes_GET_SIZE(s2)) + return (equals == Py_NE); + ps1 = PyBytes_AS_STRING(s1); + ps2 = PyBytes_AS_STRING(s2); + if (ps1[0] != ps2[0]) { + return (equals == Py_NE); + } else if (length == 1) { + return (equals == Py_EQ); + } else { + int result; +#if CYTHON_USE_UNICODE_INTERNALS && (PY_VERSION_HEX < 0x030B0000) + Py_hash_t hash1, hash2; + hash1 = ((PyBytesObject*)s1)->ob_shash; + hash2 = ((PyBytesObject*)s2)->ob_shash; + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + return (equals == Py_NE); + } +#endif + result = memcmp(ps1, ps2, (size_t)length); + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & PyBytes_CheckExact(s2)) { + return (equals == Py_NE); + } else if ((s2 == Py_None) & PyBytes_CheckExact(s1)) { + return (equals == Py_NE); + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +#endif +} + +/* UnicodeEquals */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else +#if PY_MAJOR_VERSION < 3 + PyObject* owned_ref = NULL; +#endif + int s1_is_unicode, s2_is_unicode; + if (s1 == s2) { + goto return_eq; + } + s1_is_unicode = PyUnicode_CheckExact(s1); + s2_is_unicode = PyUnicode_CheckExact(s2); +#if PY_MAJOR_VERSION < 3 + if ((s1_is_unicode & (!s2_is_unicode)) && PyString_CheckExact(s2)) { + owned_ref = PyUnicode_FromObject(s2); + if (unlikely(!owned_ref)) + return -1; + s2 = owned_ref; + s2_is_unicode = 1; + } else if ((s2_is_unicode & (!s1_is_unicode)) && PyString_CheckExact(s1)) { + owned_ref = PyUnicode_FromObject(s1); + if (unlikely(!owned_ref)) + return -1; + s1 = owned_ref; + s1_is_unicode = 1; + } else if (((!s2_is_unicode) & (!s1_is_unicode))) { + return __Pyx_PyBytes_Equals(s1, s2, equals); + } +#endif + if (s1_is_unicode & s2_is_unicode) { + Py_ssize_t length; + int kind; + void *data1, *data2; + if (unlikely(__Pyx_PyUnicode_READY(s1) < 0) || unlikely(__Pyx_PyUnicode_READY(s2) < 0)) + return -1; + length = __Pyx_PyUnicode_GET_LENGTH(s1); + if (length != __Pyx_PyUnicode_GET_LENGTH(s2)) { + goto return_ne; + } +#if CYTHON_USE_UNICODE_INTERNALS + { + Py_hash_t hash1, hash2; + #if CYTHON_PEP393_ENABLED + hash1 = ((PyASCIIObject*)s1)->hash; + hash2 = ((PyASCIIObject*)s2)->hash; + #else + hash1 = ((PyUnicodeObject*)s1)->hash; + hash2 = ((PyUnicodeObject*)s2)->hash; + #endif + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + goto return_ne; + } + } +#endif + kind = __Pyx_PyUnicode_KIND(s1); + if (kind != __Pyx_PyUnicode_KIND(s2)) { + goto return_ne; + } + data1 = __Pyx_PyUnicode_DATA(s1); + data2 = __Pyx_PyUnicode_DATA(s2); + if (__Pyx_PyUnicode_READ(kind, data1, 0) != __Pyx_PyUnicode_READ(kind, data2, 0)) { + goto return_ne; + } else if (length == 1) { + goto return_eq; + } else { + int result = memcmp(data1, data2, (size_t)(length * kind)); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & s2_is_unicode) { + goto return_ne; + } else if ((s2 == Py_None) & s1_is_unicode) { + goto return_ne; + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +return_eq: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ); +return_ne: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_NE); +#endif +} + +/* fastcall */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s) +{ + Py_ssize_t i, n = PyTuple_GET_SIZE(kwnames); + for (i = 0; i < n; i++) + { + if (s == PyTuple_GET_ITEM(kwnames, i)) return kwvalues[i]; + } + for (i = 0; i < n; i++) + { + int eq = __Pyx_PyUnicode_Equals(s, PyTuple_GET_ITEM(kwnames, i), Py_EQ); + if (unlikely(eq != 0)) { + if (unlikely(eq < 0)) return NULL; + return kwvalues[i]; + } + } + return NULL; +} +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 +CYTHON_UNUSED static PyObject *__Pyx_KwargsAsDict_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues) { + Py_ssize_t i, nkwargs = PyTuple_GET_SIZE(kwnames); + PyObject *dict; + dict = PyDict_New(); + if (unlikely(!dict)) + return NULL; + for (i=0; i= 3 + "%s() got multiple values for keyword argument '%U'", func_name, kw_name); + #else + "%s() got multiple values for keyword argument '%s'", func_name, + PyString_AsString(kw_name)); + #endif +} + +/* ParseKeywords */ +static int __Pyx_ParseOptionalKeywords( + PyObject *kwds, + PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, + PyObject *values[], + Py_ssize_t num_pos_args, + const char* function_name) +{ + PyObject *key = 0, *value = 0; + Py_ssize_t pos = 0; + PyObject*** name; + PyObject*** first_kw_arg = argnames + num_pos_args; + int kwds_is_tuple = CYTHON_METH_FASTCALL && likely(PyTuple_Check(kwds)); + while (1) { + Py_XDECREF(key); key = NULL; + Py_XDECREF(value); value = NULL; + if (kwds_is_tuple) { + Py_ssize_t size; +#if CYTHON_ASSUME_SAFE_MACROS + size = PyTuple_GET_SIZE(kwds); +#else + size = PyTuple_Size(kwds); + if (size < 0) goto bad; +#endif + if (pos >= size) break; +#if CYTHON_AVOID_BORROWED_REFS + key = __Pyx_PySequence_ITEM(kwds, pos); + if (!key) goto bad; +#elif CYTHON_ASSUME_SAFE_MACROS + key = PyTuple_GET_ITEM(kwds, pos); +#else + key = PyTuple_GetItem(kwds, pos); + if (!key) goto bad; +#endif + value = kwvalues[pos]; + pos++; + } + else + { + if (!PyDict_Next(kwds, &pos, &key, &value)) break; +#if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(key); +#endif + } + name = first_kw_arg; + while (*name && (**name != key)) name++; + if (*name) { + values[name-argnames] = value; +#if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(value); + Py_DECREF(key); +#endif + key = NULL; + value = NULL; + continue; + } +#if !CYTHON_AVOID_BORROWED_REFS + Py_INCREF(key); +#endif + Py_INCREF(value); + name = first_kw_arg; + #if PY_MAJOR_VERSION < 3 + if (likely(PyString_Check(key))) { + while (*name) { + if ((CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**name) == PyString_GET_SIZE(key)) + && _PyString_Eq(**name, key)) { + values[name-argnames] = value; +#if CYTHON_AVOID_BORROWED_REFS + value = NULL; +#endif + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + if ((**argname == key) || ( + (CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**argname) == PyString_GET_SIZE(key)) + && _PyString_Eq(**argname, key))) { + goto arg_passed_twice; + } + argname++; + } + } + } else + #endif + if (likely(PyUnicode_Check(key))) { + while (*name) { + int cmp = ( + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**name) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**name, key) + ); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) { + values[name-argnames] = value; +#if CYTHON_AVOID_BORROWED_REFS + value = NULL; +#endif + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + int cmp = (**argname == key) ? 0 : + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**argname) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**argname, key); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) goto arg_passed_twice; + argname++; + } + } + } else + goto invalid_keyword_type; + if (kwds2) { + if (unlikely(PyDict_SetItem(kwds2, key, value))) goto bad; + } else { + goto invalid_keyword; + } + } + Py_XDECREF(key); + Py_XDECREF(value); + return 0; +arg_passed_twice: + __Pyx_RaiseDoubleKeywordsError(function_name, key); + goto bad; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + goto bad; +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif +bad: + Py_XDECREF(key); + Py_XDECREF(value); + return -1; +} + +/* ArgTypeTest */ +static int __Pyx__ArgTypeTest(PyObject *obj, PyTypeObject *type, const char *name, int exact) +{ + __Pyx_TypeName type_name; + __Pyx_TypeName obj_type_name; + if (unlikely(!type)) { + PyErr_SetString(PyExc_SystemError, "Missing type object"); + return 0; + } + else if (exact) { + #if PY_MAJOR_VERSION == 2 + if ((type == &PyBaseString_Type) && likely(__Pyx_PyBaseString_CheckExact(obj))) return 1; + #endif + } + else { + if (likely(__Pyx_TypeCheck(obj, type))) return 1; + } + type_name = __Pyx_PyType_GetName(type); + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "Argument '%.200s' has incorrect type (expected " __Pyx_FMT_TYPENAME + ", got " __Pyx_FMT_TYPENAME ")", name, type_name, obj_type_name); + __Pyx_DECREF_TypeName(type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return 0; +} + +/* RaiseException */ +#if PY_MAJOR_VERSION < 3 +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + __Pyx_PyThreadState_declare + CYTHON_UNUSED_VAR(cause); + Py_XINCREF(type); + if (!value || value == Py_None) + value = NULL; + else + Py_INCREF(value); + if (!tb || tb == Py_None) + tb = NULL; + else { + Py_INCREF(tb); + if (!PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto raise_error; + } + } + if (PyType_Check(type)) { +#if CYTHON_COMPILING_IN_PYPY + if (!value) { + Py_INCREF(Py_None); + value = Py_None; + } +#endif + PyErr_NormalizeException(&type, &value, &tb); + } else { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto raise_error; + } + value = type; + type = (PyObject*) Py_TYPE(type); + Py_INCREF(type); + if (!PyType_IsSubtype((PyTypeObject *)type, (PyTypeObject *)PyExc_BaseException)) { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto raise_error; + } + } + __Pyx_PyThreadState_assign + __Pyx_ErrRestore(type, value, tb); + return; +raise_error: + Py_XDECREF(value); + Py_XDECREF(type); + Py_XDECREF(tb); + return; +} +#else +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + PyObject* owned_instance = NULL; + if (tb == Py_None) { + tb = 0; + } else if (tb && !PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto bad; + } + if (value == Py_None) + value = 0; + if (PyExceptionInstance_Check(type)) { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto bad; + } + value = type; + type = (PyObject*) Py_TYPE(value); + } else if (PyExceptionClass_Check(type)) { + PyObject *instance_class = NULL; + if (value && PyExceptionInstance_Check(value)) { + instance_class = (PyObject*) Py_TYPE(value); + if (instance_class != type) { + int is_subclass = PyObject_IsSubclass(instance_class, type); + if (!is_subclass) { + instance_class = NULL; + } else if (unlikely(is_subclass == -1)) { + goto bad; + } else { + type = instance_class; + } + } + } + if (!instance_class) { + PyObject *args; + if (!value) + args = PyTuple_New(0); + else if (PyTuple_Check(value)) { + Py_INCREF(value); + args = value; + } else + args = PyTuple_Pack(1, value); + if (!args) + goto bad; + owned_instance = PyObject_Call(type, args, NULL); + Py_DECREF(args); + if (!owned_instance) + goto bad; + value = owned_instance; + if (!PyExceptionInstance_Check(value)) { + PyErr_Format(PyExc_TypeError, + "calling %R should have returned an instance of " + "BaseException, not %R", + type, Py_TYPE(value)); + goto bad; + } + } + } else { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto bad; + } + if (cause) { + PyObject *fixed_cause; + if (cause == Py_None) { + fixed_cause = NULL; + } else if (PyExceptionClass_Check(cause)) { + fixed_cause = PyObject_CallObject(cause, NULL); + if (fixed_cause == NULL) + goto bad; + } else if (PyExceptionInstance_Check(cause)) { + fixed_cause = cause; + Py_INCREF(fixed_cause); + } else { + PyErr_SetString(PyExc_TypeError, + "exception causes must derive from " + "BaseException"); + goto bad; + } + PyException_SetCause(value, fixed_cause); + } + PyErr_SetObject(type, value); + if (tb) { + #if PY_VERSION_HEX >= 0x030C00A6 + PyException_SetTraceback(value, tb); + #elif CYTHON_FAST_THREAD_STATE + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject* tmp_tb = tstate->curexc_traceback; + if (tb != tmp_tb) { + Py_INCREF(tb); + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_tb); + } +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + PyErr_Fetch(&tmp_type, &tmp_value, &tmp_tb); + Py_INCREF(tb); + PyErr_Restore(tmp_type, tmp_value, tb); + Py_XDECREF(tmp_tb); +#endif + } +bad: + Py_XDECREF(owned_instance); + return; +} +#endif + +/* PyFunctionFastCall */ +#if CYTHON_FAST_PYCALL && !CYTHON_VECTORCALL +static PyObject* __Pyx_PyFunction_FastCallNoKw(PyCodeObject *co, PyObject **args, Py_ssize_t na, + PyObject *globals) { + PyFrameObject *f; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject **fastlocals; + Py_ssize_t i; + PyObject *result; + assert(globals != NULL); + /* XXX Perhaps we should create a specialized + PyFrame_New() that doesn't take locals, but does + take builtins without sanity checking them. + */ + assert(tstate != NULL); + f = PyFrame_New(tstate, co, globals, NULL); + if (f == NULL) { + return NULL; + } + fastlocals = __Pyx_PyFrame_GetLocalsplus(f); + for (i = 0; i < na; i++) { + Py_INCREF(*args); + fastlocals[i] = *args++; + } + result = PyEval_EvalFrameEx(f,0); + ++tstate->recursion_depth; + Py_DECREF(f); + --tstate->recursion_depth; + return result; +} +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs) { + PyCodeObject *co = (PyCodeObject *)PyFunction_GET_CODE(func); + PyObject *globals = PyFunction_GET_GLOBALS(func); + PyObject *argdefs = PyFunction_GET_DEFAULTS(func); + PyObject *closure; +#if PY_MAJOR_VERSION >= 3 + PyObject *kwdefs; +#endif + PyObject *kwtuple, **k; + PyObject **d; + Py_ssize_t nd; + Py_ssize_t nk; + PyObject *result; + assert(kwargs == NULL || PyDict_Check(kwargs)); + nk = kwargs ? PyDict_Size(kwargs) : 0; + #if PY_MAJOR_VERSION < 3 + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) { + return NULL; + } + #else + if (unlikely(Py_EnterRecursiveCall(" while calling a Python object"))) { + return NULL; + } + #endif + if ( +#if PY_MAJOR_VERSION >= 3 + co->co_kwonlyargcount == 0 && +#endif + likely(kwargs == NULL || nk == 0) && + co->co_flags == (CO_OPTIMIZED | CO_NEWLOCALS | CO_NOFREE)) { + if (argdefs == NULL && co->co_argcount == nargs) { + result = __Pyx_PyFunction_FastCallNoKw(co, args, nargs, globals); + goto done; + } + else if (nargs == 0 && argdefs != NULL + && co->co_argcount == Py_SIZE(argdefs)) { + /* function called with no arguments, but all parameters have + a default value: use default values as arguments .*/ + args = &PyTuple_GET_ITEM(argdefs, 0); + result =__Pyx_PyFunction_FastCallNoKw(co, args, Py_SIZE(argdefs), globals); + goto done; + } + } + if (kwargs != NULL) { + Py_ssize_t pos, i; + kwtuple = PyTuple_New(2 * nk); + if (kwtuple == NULL) { + result = NULL; + goto done; + } + k = &PyTuple_GET_ITEM(kwtuple, 0); + pos = i = 0; + while (PyDict_Next(kwargs, &pos, &k[i], &k[i+1])) { + Py_INCREF(k[i]); + Py_INCREF(k[i+1]); + i += 2; + } + nk = i / 2; + } + else { + kwtuple = NULL; + k = NULL; + } + closure = PyFunction_GET_CLOSURE(func); +#if PY_MAJOR_VERSION >= 3 + kwdefs = PyFunction_GET_KW_DEFAULTS(func); +#endif + if (argdefs != NULL) { + d = &PyTuple_GET_ITEM(argdefs, 0); + nd = Py_SIZE(argdefs); + } + else { + d = NULL; + nd = 0; + } +#if PY_MAJOR_VERSION >= 3 + result = PyEval_EvalCodeEx((PyObject*)co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, kwdefs, closure); +#else + result = PyEval_EvalCodeEx(co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, closure); +#endif + Py_XDECREF(kwtuple); +done: + Py_LeaveRecursiveCall(); + return result; +} +#endif + +/* PyObjectCall */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw) { + PyObject *result; + ternaryfunc call = Py_TYPE(func)->tp_call; + if (unlikely(!call)) + return PyObject_Call(func, arg, kw); + #if PY_MAJOR_VERSION < 3 + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + #else + if (unlikely(Py_EnterRecursiveCall(" while calling a Python object"))) + return NULL; + #endif + result = (*call)(func, arg, kw); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* PyObjectCallMethO */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg) { + PyObject *self, *result; + PyCFunction cfunc; + cfunc = __Pyx_CyOrPyCFunction_GET_FUNCTION(func); + self = __Pyx_CyOrPyCFunction_GET_SELF(func); + #if PY_MAJOR_VERSION < 3 + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + #else + if (unlikely(Py_EnterRecursiveCall(" while calling a Python object"))) + return NULL; + #endif + result = cfunc(self, arg); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* PyObjectFastCall */ +#if PY_VERSION_HEX < 0x03090000 || CYTHON_COMPILING_IN_LIMITED_API +static PyObject* __Pyx_PyObject_FastCall_fallback(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs) { + PyObject *argstuple; + PyObject *result = 0; + size_t i; + argstuple = PyTuple_New((Py_ssize_t)nargs); + if (unlikely(!argstuple)) return NULL; + for (i = 0; i < nargs; i++) { + Py_INCREF(args[i]); + if (__Pyx_PyTuple_SET_ITEM(argstuple, (Py_ssize_t)i, args[i]) < 0) goto bad; + } + result = __Pyx_PyObject_Call(func, argstuple, kwargs); + bad: + Py_DECREF(argstuple); + return result; +} +#endif +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t _nargs, PyObject *kwargs) { + Py_ssize_t nargs = __Pyx_PyVectorcall_NARGS(_nargs); +#if CYTHON_COMPILING_IN_CPYTHON + if (nargs == 0 && kwargs == NULL) { + if (__Pyx_CyOrPyCFunction_Check(func) && likely( __Pyx_CyOrPyCFunction_GET_FLAGS(func) & METH_NOARGS)) + return __Pyx_PyObject_CallMethO(func, NULL); + } + else if (nargs == 1 && kwargs == NULL) { + if (__Pyx_CyOrPyCFunction_Check(func) && likely( __Pyx_CyOrPyCFunction_GET_FLAGS(func) & METH_O)) + return __Pyx_PyObject_CallMethO(func, args[0]); + } +#endif + #if PY_VERSION_HEX < 0x030800B1 + #if CYTHON_FAST_PYCCALL + if (PyCFunction_Check(func)) { + if (kwargs) { + return _PyCFunction_FastCallDict(func, args, nargs, kwargs); + } else { + return _PyCFunction_FastCallKeywords(func, args, nargs, NULL); + } + } + #if PY_VERSION_HEX >= 0x030700A1 + if (!kwargs && __Pyx_IS_TYPE(func, &PyMethodDescr_Type)) { + return _PyMethodDescr_FastCallKeywords(func, args, nargs, NULL); + } + #endif + #endif + #if CYTHON_FAST_PYCALL + if (PyFunction_Check(func)) { + return __Pyx_PyFunction_FastCallDict(func, args, nargs, kwargs); + } + #endif + #endif + if (kwargs == NULL) { + #if CYTHON_VECTORCALL + #if PY_VERSION_HEX < 0x03090000 + vectorcallfunc f = _PyVectorcall_Function(func); + #else + vectorcallfunc f = PyVectorcall_Function(func); + #endif + if (f) { + return f(func, args, (size_t)nargs, NULL); + } + #elif defined(__Pyx_CyFunction_USED) && CYTHON_BACKPORT_VECTORCALL + if (__Pyx_CyFunction_CheckExact(func)) { + __pyx_vectorcallfunc f = __Pyx_CyFunction_func_vectorcall(func); + if (f) return f(func, args, (size_t)nargs, NULL); + } + #endif + } + if (nargs == 0) { + return __Pyx_PyObject_Call(func, __pyx_empty_tuple, kwargs); + } + #if PY_VERSION_HEX >= 0x03090000 && !CYTHON_COMPILING_IN_LIMITED_API + return PyObject_VectorcallDict(func, args, (size_t)nargs, kwargs); + #else + return __Pyx_PyObject_FastCall_fallback(func, args, (size_t)nargs, kwargs); + #endif +} + +/* RaiseUnexpectedTypeError */ +static int +__Pyx_RaiseUnexpectedTypeError(const char *expected, PyObject *obj) +{ + __Pyx_TypeName obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, "Expected %s, got " __Pyx_FMT_TYPENAME, + expected, obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return 0; +} + +/* CIntToDigits */ +static const char DIGIT_PAIRS_10[2*10*10+1] = { + "00010203040506070809" + "10111213141516171819" + "20212223242526272829" + "30313233343536373839" + "40414243444546474849" + "50515253545556575859" + "60616263646566676869" + "70717273747576777879" + "80818283848586878889" + "90919293949596979899" +}; +static const char DIGIT_PAIRS_8[2*8*8+1] = { + "0001020304050607" + "1011121314151617" + "2021222324252627" + "3031323334353637" + "4041424344454647" + "5051525354555657" + "6061626364656667" + "7071727374757677" +}; +static const char DIGITS_HEX[2*16+1] = { + "0123456789abcdef" + "0123456789ABCDEF" +}; + +/* BuildPyUnicode */ +static PyObject* __Pyx_PyUnicode_BuildFromAscii(Py_ssize_t ulength, char* chars, int clength, + int prepend_sign, char padding_char) { + PyObject *uval; + Py_ssize_t uoffset = ulength - clength; +#if CYTHON_USE_UNICODE_INTERNALS + Py_ssize_t i; +#if CYTHON_PEP393_ENABLED + void *udata; + uval = PyUnicode_New(ulength, 127); + if (unlikely(!uval)) return NULL; + udata = PyUnicode_DATA(uval); +#else + Py_UNICODE *udata; + uval = PyUnicode_FromUnicode(NULL, ulength); + if (unlikely(!uval)) return NULL; + udata = PyUnicode_AS_UNICODE(uval); +#endif + if (uoffset > 0) { + i = 0; + if (prepend_sign) { + __Pyx_PyUnicode_WRITE(PyUnicode_1BYTE_KIND, udata, 0, '-'); + i++; + } + for (; i < uoffset; i++) { + __Pyx_PyUnicode_WRITE(PyUnicode_1BYTE_KIND, udata, i, padding_char); + } + } + for (i=0; i < clength; i++) { + __Pyx_PyUnicode_WRITE(PyUnicode_1BYTE_KIND, udata, uoffset+i, chars[i]); + } +#else + { + PyObject *sign = NULL, *padding = NULL; + uval = NULL; + if (uoffset > 0) { + prepend_sign = !!prepend_sign; + if (uoffset > prepend_sign) { + padding = PyUnicode_FromOrdinal(padding_char); + if (likely(padding) && uoffset > prepend_sign + 1) { + PyObject *tmp; + PyObject *repeat = PyInt_FromSsize_t(uoffset - prepend_sign); + if (unlikely(!repeat)) goto done_or_error; + tmp = PyNumber_Multiply(padding, repeat); + Py_DECREF(repeat); + Py_DECREF(padding); + padding = tmp; + } + if (unlikely(!padding)) goto done_or_error; + } + if (prepend_sign) { + sign = PyUnicode_FromOrdinal('-'); + if (unlikely(!sign)) goto done_or_error; + } + } + uval = PyUnicode_DecodeASCII(chars, clength, NULL); + if (likely(uval) && padding) { + PyObject *tmp = PyNumber_Add(padding, uval); + Py_DECREF(uval); + uval = tmp; + } + if (likely(uval) && sign) { + PyObject *tmp = PyNumber_Add(sign, uval); + Py_DECREF(uval); + uval = tmp; + } +done_or_error: + Py_XDECREF(padding); + Py_XDECREF(sign); + } +#endif + return uval; +} + +/* CIntToPyUnicode */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_int(int value, Py_ssize_t width, char padding_char, char format_char) { + char digits[sizeof(int)*3+2]; + char *dpos, *end = digits + sizeof(int)*3+2; + const char *hex_digits = DIGITS_HEX; + Py_ssize_t length, ulength; + int prepend_sign, last_one_off; + int remaining; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (format_char == 'X') { + hex_digits += 16; + format_char = 'x'; + } + remaining = value; + last_one_off = 0; + dpos = end; + do { + int digit_pos; + switch (format_char) { + case 'o': + digit_pos = abs((int)(remaining % (8*8))); + remaining = (int) (remaining / (8*8)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_8 + digit_pos * 2, 2); + last_one_off = (digit_pos < 8); + break; + case 'd': + digit_pos = abs((int)(remaining % (10*10))); + remaining = (int) (remaining / (10*10)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_10 + digit_pos * 2, 2); + last_one_off = (digit_pos < 10); + break; + case 'x': + *(--dpos) = hex_digits[abs((int)(remaining % 16))]; + remaining = (int) (remaining / 16); + break; + default: + assert(0); + break; + } + } while (unlikely(remaining != 0)); + assert(!last_one_off || *dpos == '0'); + dpos += last_one_off; + length = end - dpos; + ulength = length; + prepend_sign = 0; + if (!is_unsigned && value <= neg_one) { + if (padding_char == ' ' || width <= length + 1) { + *(--dpos) = '-'; + ++length; + } else { + prepend_sign = 1; + } + ++ulength; + } + if (width > ulength) { + ulength = width; + } + if (ulength == 1) { + return PyUnicode_FromOrdinal(*dpos); + } + return __Pyx_PyUnicode_BuildFromAscii(ulength, dpos, (int) length, prepend_sign, padding_char); +} + +/* CIntToPyUnicode */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_Py_ssize_t(Py_ssize_t value, Py_ssize_t width, char padding_char, char format_char) { + char digits[sizeof(Py_ssize_t)*3+2]; + char *dpos, *end = digits + sizeof(Py_ssize_t)*3+2; + const char *hex_digits = DIGITS_HEX; + Py_ssize_t length, ulength; + int prepend_sign, last_one_off; + Py_ssize_t remaining; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const Py_ssize_t neg_one = (Py_ssize_t) -1, const_zero = (Py_ssize_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (format_char == 'X') { + hex_digits += 16; + format_char = 'x'; + } + remaining = value; + last_one_off = 0; + dpos = end; + do { + int digit_pos; + switch (format_char) { + case 'o': + digit_pos = abs((int)(remaining % (8*8))); + remaining = (Py_ssize_t) (remaining / (8*8)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_8 + digit_pos * 2, 2); + last_one_off = (digit_pos < 8); + break; + case 'd': + digit_pos = abs((int)(remaining % (10*10))); + remaining = (Py_ssize_t) (remaining / (10*10)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_10 + digit_pos * 2, 2); + last_one_off = (digit_pos < 10); + break; + case 'x': + *(--dpos) = hex_digits[abs((int)(remaining % 16))]; + remaining = (Py_ssize_t) (remaining / 16); + break; + default: + assert(0); + break; + } + } while (unlikely(remaining != 0)); + assert(!last_one_off || *dpos == '0'); + dpos += last_one_off; + length = end - dpos; + ulength = length; + prepend_sign = 0; + if (!is_unsigned && value <= neg_one) { + if (padding_char == ' ' || width <= length + 1) { + *(--dpos) = '-'; + ++length; + } else { + prepend_sign = 1; + } + ++ulength; + } + if (width > ulength) { + ulength = width; + } + if (ulength == 1) { + return PyUnicode_FromOrdinal(*dpos); + } + return __Pyx_PyUnicode_BuildFromAscii(ulength, dpos, (int) length, prepend_sign, padding_char); +} + +/* JoinPyUnicode */ +static PyObject* __Pyx_PyUnicode_Join(PyObject* value_tuple, Py_ssize_t value_count, Py_ssize_t result_ulength, + Py_UCS4 max_char) { +#if CYTHON_USE_UNICODE_INTERNALS && CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + PyObject *result_uval; + int result_ukind, kind_shift; + Py_ssize_t i, char_pos; + void *result_udata; + CYTHON_MAYBE_UNUSED_VAR(max_char); +#if CYTHON_PEP393_ENABLED + result_uval = PyUnicode_New(result_ulength, max_char); + if (unlikely(!result_uval)) return NULL; + result_ukind = (max_char <= 255) ? PyUnicode_1BYTE_KIND : (max_char <= 65535) ? PyUnicode_2BYTE_KIND : PyUnicode_4BYTE_KIND; + kind_shift = (result_ukind == PyUnicode_4BYTE_KIND) ? 2 : result_ukind - 1; + result_udata = PyUnicode_DATA(result_uval); +#else + result_uval = PyUnicode_FromUnicode(NULL, result_ulength); + if (unlikely(!result_uval)) return NULL; + result_ukind = sizeof(Py_UNICODE); + kind_shift = (result_ukind == 4) ? 2 : result_ukind - 1; + result_udata = PyUnicode_AS_UNICODE(result_uval); +#endif + assert(kind_shift == 2 || kind_shift == 1 || kind_shift == 0); + char_pos = 0; + for (i=0; i < value_count; i++) { + int ukind; + Py_ssize_t ulength; + void *udata; + PyObject *uval = PyTuple_GET_ITEM(value_tuple, i); + if (unlikely(__Pyx_PyUnicode_READY(uval))) + goto bad; + ulength = __Pyx_PyUnicode_GET_LENGTH(uval); + if (unlikely(!ulength)) + continue; + if (unlikely((PY_SSIZE_T_MAX >> kind_shift) - ulength < char_pos)) + goto overflow; + ukind = __Pyx_PyUnicode_KIND(uval); + udata = __Pyx_PyUnicode_DATA(uval); + if (!CYTHON_PEP393_ENABLED || ukind == result_ukind) { + memcpy((char *)result_udata + (char_pos << kind_shift), udata, (size_t) (ulength << kind_shift)); + } else { + #if PY_VERSION_HEX >= 0x030d0000 + if (unlikely(PyUnicode_CopyCharacters(result_uval, char_pos, uval, 0, ulength) < 0)) goto bad; + #elif CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030300F0 || defined(_PyUnicode_FastCopyCharacters) + _PyUnicode_FastCopyCharacters(result_uval, char_pos, uval, 0, ulength); + #else + Py_ssize_t j; + for (j=0; j < ulength; j++) { + Py_UCS4 uchar = __Pyx_PyUnicode_READ(ukind, udata, j); + __Pyx_PyUnicode_WRITE(result_ukind, result_udata, char_pos+j, uchar); + } + #endif + } + char_pos += ulength; + } + return result_uval; +overflow: + PyErr_SetString(PyExc_OverflowError, "join() result is too long for a Python string"); +bad: + Py_DECREF(result_uval); + return NULL; +#else + CYTHON_UNUSED_VAR(max_char); + CYTHON_UNUSED_VAR(result_ulength); + CYTHON_UNUSED_VAR(value_count); + return PyUnicode_Join(__pyx_empty_unicode, value_tuple); +#endif +} + +/* GetAttr */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr(PyObject *o, PyObject *n) { +#if CYTHON_USE_TYPE_SLOTS +#if PY_MAJOR_VERSION >= 3 + if (likely(PyUnicode_Check(n))) +#else + if (likely(PyString_Check(n))) +#endif + return __Pyx_PyObject_GetAttrStr(o, n); +#endif + return PyObject_GetAttr(o, n); +} + +/* GetItemInt */ +static PyObject *__Pyx_GetItemInt_Generic(PyObject *o, PyObject* j) { + PyObject *r; + if (unlikely(!j)) return NULL; + r = PyObject_GetItem(o, j); + Py_DECREF(j); + return r; +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_List_Fast(PyObject *o, Py_ssize_t i, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + Py_ssize_t wrapped_i = i; + if (wraparound & unlikely(i < 0)) { + wrapped_i += PyList_GET_SIZE(o); + } + if ((!boundscheck) || likely(__Pyx_is_valid_index(wrapped_i, PyList_GET_SIZE(o)))) { + PyObject *r = PyList_GET_ITEM(o, wrapped_i); + Py_INCREF(r); + return r; + } + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +#else + return PySequence_GetItem(o, i); +#endif +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Tuple_Fast(PyObject *o, Py_ssize_t i, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + Py_ssize_t wrapped_i = i; + if (wraparound & unlikely(i < 0)) { + wrapped_i += PyTuple_GET_SIZE(o); + } + if ((!boundscheck) || likely(__Pyx_is_valid_index(wrapped_i, PyTuple_GET_SIZE(o)))) { + PyObject *r = PyTuple_GET_ITEM(o, wrapped_i); + Py_INCREF(r); + return r; + } + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +#else + return PySequence_GetItem(o, i); +#endif +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Fast(PyObject *o, Py_ssize_t i, int is_list, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS && CYTHON_USE_TYPE_SLOTS + if (is_list || PyList_CheckExact(o)) { + Py_ssize_t n = ((!wraparound) | likely(i >= 0)) ? i : i + PyList_GET_SIZE(o); + if ((!boundscheck) || (likely(__Pyx_is_valid_index(n, PyList_GET_SIZE(o))))) { + PyObject *r = PyList_GET_ITEM(o, n); + Py_INCREF(r); + return r; + } + } + else if (PyTuple_CheckExact(o)) { + Py_ssize_t n = ((!wraparound) | likely(i >= 0)) ? i : i + PyTuple_GET_SIZE(o); + if ((!boundscheck) || likely(__Pyx_is_valid_index(n, PyTuple_GET_SIZE(o)))) { + PyObject *r = PyTuple_GET_ITEM(o, n); + Py_INCREF(r); + return r; + } + } else { + PyMappingMethods *mm = Py_TYPE(o)->tp_as_mapping; + PySequenceMethods *sm = Py_TYPE(o)->tp_as_sequence; + if (mm && mm->mp_subscript) { + PyObject *r, *key = PyInt_FromSsize_t(i); + if (unlikely(!key)) return NULL; + r = mm->mp_subscript(o, key); + Py_DECREF(key); + return r; + } + if (likely(sm && sm->sq_item)) { + if (wraparound && unlikely(i < 0) && likely(sm->sq_length)) { + Py_ssize_t l = sm->sq_length(o); + if (likely(l >= 0)) { + i += l; + } else { + if (!PyErr_ExceptionMatches(PyExc_OverflowError)) + return NULL; + PyErr_Clear(); + } + } + return sm->sq_item(o, i); + } + } +#else + if (is_list || !PyMapping_Check(o)) { + return PySequence_GetItem(o, i); + } +#endif + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +} + +/* PyObjectCallOneArg */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg) { + PyObject *args[2] = {NULL, arg}; + return __Pyx_PyObject_FastCall(func, args+1, 1 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* ObjectGetItem */ +#if CYTHON_USE_TYPE_SLOTS +static PyObject *__Pyx_PyObject_GetIndex(PyObject *obj, PyObject *index) { + PyObject *runerr = NULL; + Py_ssize_t key_value; + key_value = __Pyx_PyIndex_AsSsize_t(index); + if (likely(key_value != -1 || !(runerr = PyErr_Occurred()))) { + return __Pyx_GetItemInt_Fast(obj, key_value, 0, 1, 1); + } + if (PyErr_GivenExceptionMatches(runerr, PyExc_OverflowError)) { + __Pyx_TypeName index_type_name = __Pyx_PyType_GetName(Py_TYPE(index)); + PyErr_Clear(); + PyErr_Format(PyExc_IndexError, + "cannot fit '" __Pyx_FMT_TYPENAME "' into an index-sized integer", index_type_name); + __Pyx_DECREF_TypeName(index_type_name); + } + return NULL; +} +static PyObject *__Pyx_PyObject_GetItem_Slow(PyObject *obj, PyObject *key) { + __Pyx_TypeName obj_type_name; + if (likely(PyType_Check(obj))) { + PyObject *meth = __Pyx_PyObject_GetAttrStrNoError(obj, __pyx_n_s_class_getitem); + if (!meth) { + PyErr_Clear(); + } else { + PyObject *result = __Pyx_PyObject_CallOneArg(meth, key); + Py_DECREF(meth); + return result; + } + } + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "'" __Pyx_FMT_TYPENAME "' object is not subscriptable", obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return NULL; +} +static PyObject *__Pyx_PyObject_GetItem(PyObject *obj, PyObject *key) { + PyTypeObject *tp = Py_TYPE(obj); + PyMappingMethods *mm = tp->tp_as_mapping; + PySequenceMethods *sm = tp->tp_as_sequence; + if (likely(mm && mm->mp_subscript)) { + return mm->mp_subscript(obj, key); + } + if (likely(sm && sm->sq_item)) { + return __Pyx_PyObject_GetIndex(obj, key); + } + return __Pyx_PyObject_GetItem_Slow(obj, key); +} +#endif + +/* KeywordStringCheck */ +static int __Pyx_CheckKeywordStrings( + PyObject *kw, + const char* function_name, + int kw_allowed) +{ + PyObject* key = 0; + Py_ssize_t pos = 0; +#if CYTHON_COMPILING_IN_PYPY + if (!kw_allowed && PyDict_Next(kw, &pos, &key, 0)) + goto invalid_keyword; + return 1; +#else + if (CYTHON_METH_FASTCALL && likely(PyTuple_Check(kw))) { + Py_ssize_t kwsize; +#if CYTHON_ASSUME_SAFE_MACROS + kwsize = PyTuple_GET_SIZE(kw); +#else + kwsize = PyTuple_Size(kw); + if (kwsize < 0) return 0; +#endif + if (unlikely(kwsize == 0)) + return 1; + if (!kw_allowed) { +#if CYTHON_ASSUME_SAFE_MACROS + key = PyTuple_GET_ITEM(kw, 0); +#else + key = PyTuple_GetItem(kw, pos); + if (!key) return 0; +#endif + goto invalid_keyword; + } +#if PY_VERSION_HEX < 0x03090000 + for (pos = 0; pos < kwsize; pos++) { +#if CYTHON_ASSUME_SAFE_MACROS + key = PyTuple_GET_ITEM(kw, pos); +#else + key = PyTuple_GetItem(kw, pos); + if (!key) return 0; +#endif + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } +#endif + return 1; + } + while (PyDict_Next(kw, &pos, &key, 0)) { + #if PY_MAJOR_VERSION < 3 + if (unlikely(!PyString_Check(key))) + #endif + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } + if (!kw_allowed && unlikely(key)) + goto invalid_keyword; + return 1; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + return 0; +#endif +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif + return 0; +} + +/* DivInt[Py_ssize_t] */ +static CYTHON_INLINE Py_ssize_t __Pyx_div_Py_ssize_t(Py_ssize_t a, Py_ssize_t b) { + Py_ssize_t q = a / b; + Py_ssize_t r = a - q*b; + q -= ((r != 0) & ((r ^ b) < 0)); + return q; +} + +/* GetAttr3 */ +#if __PYX_LIMITED_VERSION_HEX < 0x030d00A1 +static PyObject *__Pyx_GetAttr3Default(PyObject *d) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + if (unlikely(!__Pyx_PyErr_ExceptionMatches(PyExc_AttributeError))) + return NULL; + __Pyx_PyErr_Clear(); + Py_INCREF(d); + return d; +} +#endif +static CYTHON_INLINE PyObject *__Pyx_GetAttr3(PyObject *o, PyObject *n, PyObject *d) { + PyObject *r; +#if __PYX_LIMITED_VERSION_HEX >= 0x030d00A1 + int res = PyObject_GetOptionalAttr(o, n, &r); + return (res != 0) ? r : __Pyx_NewRef(d); +#else + #if CYTHON_USE_TYPE_SLOTS + if (likely(PyString_Check(n))) { + r = __Pyx_PyObject_GetAttrStrNoError(o, n); + if (unlikely(!r) && likely(!PyErr_Occurred())) { + r = __Pyx_NewRef(d); + } + return r; + } + #endif + r = PyObject_GetAttr(o, n); + return (likely(r)) ? r : __Pyx_GetAttr3Default(d); +#endif +} + +/* PyDictVersioning */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + return likely(dict) ? __PYX_GET_DICT_VERSION(dict) : 0; +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj) { + PyObject **dictptr = NULL; + Py_ssize_t offset = Py_TYPE(obj)->tp_dictoffset; + if (offset) { +#if CYTHON_COMPILING_IN_CPYTHON + dictptr = (likely(offset > 0)) ? (PyObject **) ((char *)obj + offset) : _PyObject_GetDictPtr(obj); +#else + dictptr = _PyObject_GetDictPtr(obj); +#endif + } + return (dictptr && *dictptr) ? __PYX_GET_DICT_VERSION(*dictptr) : 0; +} +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + if (unlikely(!dict) || unlikely(tp_dict_version != __PYX_GET_DICT_VERSION(dict))) + return 0; + return obj_dict_version == __Pyx_get_object_dict_version(obj); +} +#endif + +/* GetModuleGlobalName */ +#if CYTHON_USE_DICT_VERSIONS +static PyObject *__Pyx__GetModuleGlobalName(PyObject *name, PY_UINT64_T *dict_version, PyObject **dict_cached_value) +#else +static CYTHON_INLINE PyObject *__Pyx__GetModuleGlobalName(PyObject *name) +#endif +{ + PyObject *result; +#if !CYTHON_AVOID_BORROWED_REFS +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030500A1 && PY_VERSION_HEX < 0x030d0000 + result = _PyDict_GetItem_KnownHash(__pyx_d, name, ((PyASCIIObject *) name)->hash); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } else if (unlikely(PyErr_Occurred())) { + return NULL; + } +#elif CYTHON_COMPILING_IN_LIMITED_API + if (unlikely(!__pyx_m)) { + return NULL; + } + result = PyObject_GetAttr(__pyx_m, name); + if (likely(result)) { + return result; + } +#else + result = PyDict_GetItem(__pyx_d, name); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } +#endif +#else + result = PyObject_GetItem(__pyx_d, name); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } + PyErr_Clear(); +#endif + return __Pyx_GetBuiltinName(name); +} + +/* RaiseTooManyValuesToUnpack */ +static CYTHON_INLINE void __Pyx_RaiseTooManyValuesError(Py_ssize_t expected) { + PyErr_Format(PyExc_ValueError, + "too many values to unpack (expected %" CYTHON_FORMAT_SSIZE_T "d)", expected); +} + +/* RaiseNeedMoreValuesToUnpack */ +static CYTHON_INLINE void __Pyx_RaiseNeedMoreValuesError(Py_ssize_t index) { + PyErr_Format(PyExc_ValueError, + "need more than %" CYTHON_FORMAT_SSIZE_T "d value%.1s to unpack", + index, (index == 1) ? "" : "s"); +} + +/* RaiseNoneIterError */ +static CYTHON_INLINE void __Pyx_RaiseNoneNotIterableError(void) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not iterable"); +} + +/* ExtTypeTest */ +static CYTHON_INLINE int __Pyx_TypeTest(PyObject *obj, PyTypeObject *type) { + __Pyx_TypeName obj_type_name; + __Pyx_TypeName type_name; + if (unlikely(!type)) { + PyErr_SetString(PyExc_SystemError, "Missing type object"); + return 0; + } + if (likely(__Pyx_TypeCheck(obj, type))) + return 1; + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + type_name = __Pyx_PyType_GetName(type); + PyErr_Format(PyExc_TypeError, + "Cannot convert " __Pyx_FMT_TYPENAME " to " __Pyx_FMT_TYPENAME, + obj_type_name, type_name); + __Pyx_DECREF_TypeName(obj_type_name); + __Pyx_DECREF_TypeName(type_name); + return 0; +} + +/* GetTopmostException */ +#if CYTHON_USE_EXC_INFO_STACK && CYTHON_FAST_THREAD_STATE +static _PyErr_StackItem * +__Pyx_PyErr_GetTopmostException(PyThreadState *tstate) +{ + _PyErr_StackItem *exc_info = tstate->exc_info; + while ((exc_info->exc_value == NULL || exc_info->exc_value == Py_None) && + exc_info->previous_item != NULL) + { + exc_info = exc_info->previous_item; + } + return exc_info; +} +#endif + +/* SaveResetException */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx__ExceptionSave(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { + #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 + _PyErr_StackItem *exc_info = __Pyx_PyErr_GetTopmostException(tstate); + PyObject *exc_value = exc_info->exc_value; + if (exc_value == NULL || exc_value == Py_None) { + *value = NULL; + *type = NULL; + *tb = NULL; + } else { + *value = exc_value; + Py_INCREF(*value); + *type = (PyObject*) Py_TYPE(exc_value); + Py_INCREF(*type); + *tb = PyException_GetTraceback(exc_value); + } + #elif CYTHON_USE_EXC_INFO_STACK + _PyErr_StackItem *exc_info = __Pyx_PyErr_GetTopmostException(tstate); + *type = exc_info->exc_type; + *value = exc_info->exc_value; + *tb = exc_info->exc_traceback; + Py_XINCREF(*type); + Py_XINCREF(*value); + Py_XINCREF(*tb); + #else + *type = tstate->exc_type; + *value = tstate->exc_value; + *tb = tstate->exc_traceback; + Py_XINCREF(*type); + Py_XINCREF(*value); + Py_XINCREF(*tb); + #endif +} +static CYTHON_INLINE void __Pyx__ExceptionReset(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb) { + #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 + _PyErr_StackItem *exc_info = tstate->exc_info; + PyObject *tmp_value = exc_info->exc_value; + exc_info->exc_value = value; + Py_XDECREF(tmp_value); + Py_XDECREF(type); + Py_XDECREF(tb); + #else + PyObject *tmp_type, *tmp_value, *tmp_tb; + #if CYTHON_USE_EXC_INFO_STACK + _PyErr_StackItem *exc_info = tstate->exc_info; + tmp_type = exc_info->exc_type; + tmp_value = exc_info->exc_value; + tmp_tb = exc_info->exc_traceback; + exc_info->exc_type = type; + exc_info->exc_value = value; + exc_info->exc_traceback = tb; + #else + tmp_type = tstate->exc_type; + tmp_value = tstate->exc_value; + tmp_tb = tstate->exc_traceback; + tstate->exc_type = type; + tstate->exc_value = value; + tstate->exc_traceback = tb; + #endif + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); + #endif +} +#endif + +/* GetException */ +#if CYTHON_FAST_THREAD_STATE +static int __Pyx__GetException(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) +#else +static int __Pyx_GetException(PyObject **type, PyObject **value, PyObject **tb) +#endif +{ + PyObject *local_type = NULL, *local_value, *local_tb = NULL; +#if CYTHON_FAST_THREAD_STATE + PyObject *tmp_type, *tmp_value, *tmp_tb; + #if PY_VERSION_HEX >= 0x030C00A6 + local_value = tstate->current_exception; + tstate->current_exception = 0; + if (likely(local_value)) { + local_type = (PyObject*) Py_TYPE(local_value); + Py_INCREF(local_type); + local_tb = PyException_GetTraceback(local_value); + } + #else + local_type = tstate->curexc_type; + local_value = tstate->curexc_value; + local_tb = tstate->curexc_traceback; + tstate->curexc_type = 0; + tstate->curexc_value = 0; + tstate->curexc_traceback = 0; + #endif +#else + PyErr_Fetch(&local_type, &local_value, &local_tb); +#endif + PyErr_NormalizeException(&local_type, &local_value, &local_tb); +#if CYTHON_FAST_THREAD_STATE && PY_VERSION_HEX >= 0x030C00A6 + if (unlikely(tstate->current_exception)) +#elif CYTHON_FAST_THREAD_STATE + if (unlikely(tstate->curexc_type)) +#else + if (unlikely(PyErr_Occurred())) +#endif + goto bad; + #if PY_MAJOR_VERSION >= 3 + if (local_tb) { + if (unlikely(PyException_SetTraceback(local_value, local_tb) < 0)) + goto bad; + } + #endif + Py_XINCREF(local_tb); + Py_XINCREF(local_type); + Py_XINCREF(local_value); + *type = local_type; + *value = local_value; + *tb = local_tb; +#if CYTHON_FAST_THREAD_STATE + #if CYTHON_USE_EXC_INFO_STACK + { + _PyErr_StackItem *exc_info = tstate->exc_info; + #if PY_VERSION_HEX >= 0x030B00a4 + tmp_value = exc_info->exc_value; + exc_info->exc_value = local_value; + tmp_type = NULL; + tmp_tb = NULL; + Py_XDECREF(local_type); + Py_XDECREF(local_tb); + #else + tmp_type = exc_info->exc_type; + tmp_value = exc_info->exc_value; + tmp_tb = exc_info->exc_traceback; + exc_info->exc_type = local_type; + exc_info->exc_value = local_value; + exc_info->exc_traceback = local_tb; + #endif + } + #else + tmp_type = tstate->exc_type; + tmp_value = tstate->exc_value; + tmp_tb = tstate->exc_traceback; + tstate->exc_type = local_type; + tstate->exc_value = local_value; + tstate->exc_traceback = local_tb; + #endif + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); +#else + PyErr_SetExcInfo(local_type, local_value, local_tb); +#endif + return 0; +bad: + *type = 0; + *value = 0; + *tb = 0; + Py_XDECREF(local_type); + Py_XDECREF(local_value); + Py_XDECREF(local_tb); + return -1; +} + +/* SwapException */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx__ExceptionSwap(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { + PyObject *tmp_type, *tmp_value, *tmp_tb; + #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 + _PyErr_StackItem *exc_info = tstate->exc_info; + tmp_value = exc_info->exc_value; + exc_info->exc_value = *value; + if (tmp_value == NULL || tmp_value == Py_None) { + Py_XDECREF(tmp_value); + tmp_value = NULL; + tmp_type = NULL; + tmp_tb = NULL; + } else { + tmp_type = (PyObject*) Py_TYPE(tmp_value); + Py_INCREF(tmp_type); + #if CYTHON_COMPILING_IN_CPYTHON + tmp_tb = ((PyBaseExceptionObject*) tmp_value)->traceback; + Py_XINCREF(tmp_tb); + #else + tmp_tb = PyException_GetTraceback(tmp_value); + #endif + } + #elif CYTHON_USE_EXC_INFO_STACK + _PyErr_StackItem *exc_info = tstate->exc_info; + tmp_type = exc_info->exc_type; + tmp_value = exc_info->exc_value; + tmp_tb = exc_info->exc_traceback; + exc_info->exc_type = *type; + exc_info->exc_value = *value; + exc_info->exc_traceback = *tb; + #else + tmp_type = tstate->exc_type; + tmp_value = tstate->exc_value; + tmp_tb = tstate->exc_traceback; + tstate->exc_type = *type; + tstate->exc_value = *value; + tstate->exc_traceback = *tb; + #endif + *type = tmp_type; + *value = tmp_value; + *tb = tmp_tb; +} +#else +static CYTHON_INLINE void __Pyx_ExceptionSwap(PyObject **type, PyObject **value, PyObject **tb) { + PyObject *tmp_type, *tmp_value, *tmp_tb; + PyErr_GetExcInfo(&tmp_type, &tmp_value, &tmp_tb); + PyErr_SetExcInfo(*type, *value, *tb); + *type = tmp_type; + *value = tmp_value; + *tb = tmp_tb; +} +#endif + +/* Import */ +static PyObject *__Pyx_Import(PyObject *name, PyObject *from_list, int level) { + PyObject *module = 0; + PyObject *empty_dict = 0; + PyObject *empty_list = 0; + #if PY_MAJOR_VERSION < 3 + PyObject *py_import; + py_import = __Pyx_PyObject_GetAttrStr(__pyx_b, __pyx_n_s_import); + if (unlikely(!py_import)) + goto bad; + if (!from_list) { + empty_list = PyList_New(0); + if (unlikely(!empty_list)) + goto bad; + from_list = empty_list; + } + #endif + empty_dict = PyDict_New(); + if (unlikely(!empty_dict)) + goto bad; + { + #if PY_MAJOR_VERSION >= 3 + if (level == -1) { + if (strchr(__Pyx_MODULE_NAME, '.') != NULL) { + module = PyImport_ImportModuleLevelObject( + name, __pyx_d, empty_dict, from_list, 1); + if (unlikely(!module)) { + if (unlikely(!PyErr_ExceptionMatches(PyExc_ImportError))) + goto bad; + PyErr_Clear(); + } + } + level = 0; + } + #endif + if (!module) { + #if PY_MAJOR_VERSION < 3 + PyObject *py_level = PyInt_FromLong(level); + if (unlikely(!py_level)) + goto bad; + module = PyObject_CallFunctionObjArgs(py_import, + name, __pyx_d, empty_dict, from_list, py_level, (PyObject *)NULL); + Py_DECREF(py_level); + #else + module = PyImport_ImportModuleLevelObject( + name, __pyx_d, empty_dict, from_list, level); + #endif + } + } +bad: + Py_XDECREF(empty_dict); + Py_XDECREF(empty_list); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_import); + #endif + return module; +} + +/* ImportDottedModule */ +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx__ImportDottedModule_Error(PyObject *name, PyObject *parts_tuple, Py_ssize_t count) { + PyObject *partial_name = NULL, *slice = NULL, *sep = NULL; + if (unlikely(PyErr_Occurred())) { + PyErr_Clear(); + } + if (likely(PyTuple_GET_SIZE(parts_tuple) == count)) { + partial_name = name; + } else { + slice = PySequence_GetSlice(parts_tuple, 0, count); + if (unlikely(!slice)) + goto bad; + sep = PyUnicode_FromStringAndSize(".", 1); + if (unlikely(!sep)) + goto bad; + partial_name = PyUnicode_Join(sep, slice); + } + PyErr_Format( +#if PY_MAJOR_VERSION < 3 + PyExc_ImportError, + "No module named '%s'", PyString_AS_STRING(partial_name)); +#else +#if PY_VERSION_HEX >= 0x030600B1 + PyExc_ModuleNotFoundError, +#else + PyExc_ImportError, +#endif + "No module named '%U'", partial_name); +#endif +bad: + Py_XDECREF(sep); + Py_XDECREF(slice); + Py_XDECREF(partial_name); + return NULL; +} +#endif +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx__ImportDottedModule_Lookup(PyObject *name) { + PyObject *imported_module; +#if PY_VERSION_HEX < 0x030700A1 || (CYTHON_COMPILING_IN_PYPY && PYPY_VERSION_NUM < 0x07030400) + PyObject *modules = PyImport_GetModuleDict(); + if (unlikely(!modules)) + return NULL; + imported_module = __Pyx_PyDict_GetItemStr(modules, name); + Py_XINCREF(imported_module); +#else + imported_module = PyImport_GetModule(name); +#endif + return imported_module; +} +#endif +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_ImportDottedModule_WalkParts(PyObject *module, PyObject *name, PyObject *parts_tuple) { + Py_ssize_t i, nparts; + nparts = PyTuple_GET_SIZE(parts_tuple); + for (i=1; i < nparts && module; i++) { + PyObject *part, *submodule; +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + part = PyTuple_GET_ITEM(parts_tuple, i); +#else + part = PySequence_ITEM(parts_tuple, i); +#endif + submodule = __Pyx_PyObject_GetAttrStrNoError(module, part); +#if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(part); +#endif + Py_DECREF(module); + module = submodule; + } + if (unlikely(!module)) { + return __Pyx__ImportDottedModule_Error(name, parts_tuple, i); + } + return module; +} +#endif +static PyObject *__Pyx__ImportDottedModule(PyObject *name, PyObject *parts_tuple) { +#if PY_MAJOR_VERSION < 3 + PyObject *module, *from_list, *star = __pyx_n_s__3; + CYTHON_UNUSED_VAR(parts_tuple); + from_list = PyList_New(1); + if (unlikely(!from_list)) + return NULL; + Py_INCREF(star); + PyList_SET_ITEM(from_list, 0, star); + module = __Pyx_Import(name, from_list, 0); + Py_DECREF(from_list); + return module; +#else + PyObject *imported_module; + PyObject *module = __Pyx_Import(name, NULL, 0); + if (!parts_tuple || unlikely(!module)) + return module; + imported_module = __Pyx__ImportDottedModule_Lookup(name); + if (likely(imported_module)) { + Py_DECREF(module); + return imported_module; + } + PyErr_Clear(); + return __Pyx_ImportDottedModule_WalkParts(module, name, parts_tuple); +#endif +} +static PyObject *__Pyx_ImportDottedModule(PyObject *name, PyObject *parts_tuple) { +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030400B1 + PyObject *module = __Pyx__ImportDottedModule_Lookup(name); + if (likely(module)) { + PyObject *spec = __Pyx_PyObject_GetAttrStrNoError(module, __pyx_n_s_spec); + if (likely(spec)) { + PyObject *unsafe = __Pyx_PyObject_GetAttrStrNoError(spec, __pyx_n_s_initializing); + if (likely(!unsafe || !__Pyx_PyObject_IsTrue(unsafe))) { + Py_DECREF(spec); + spec = NULL; + } + Py_XDECREF(unsafe); + } + if (likely(!spec)) { + PyErr_Clear(); + return module; + } + Py_DECREF(spec); + Py_DECREF(module); + } else if (PyErr_Occurred()) { + PyErr_Clear(); + } +#endif + return __Pyx__ImportDottedModule(name, parts_tuple); +} + +/* FastTypeChecks */ +#if CYTHON_COMPILING_IN_CPYTHON +static int __Pyx_InBases(PyTypeObject *a, PyTypeObject *b) { + while (a) { + a = __Pyx_PyType_GetSlot(a, tp_base, PyTypeObject*); + if (a == b) + return 1; + } + return b == &PyBaseObject_Type; +} +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (a == b) return 1; + mro = a->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + if (PyTuple_GET_ITEM(mro, i) == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(a, b); +} +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (cls == a || cls == b) return 1; + mro = cls->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + PyObject *base = PyTuple_GET_ITEM(mro, i); + if (base == (PyObject *)a || base == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(cls, a) || __Pyx_InBases(cls, b); +} +#if PY_MAJOR_VERSION == 2 +static int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject* exc_type2) { + PyObject *exception, *value, *tb; + int res; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&exception, &value, &tb); + res = exc_type1 ? PyObject_IsSubclass(err, exc_type1) : 0; + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + if (!res) { + res = PyObject_IsSubclass(err, exc_type2); + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + } + __Pyx_ErrRestore(exception, value, tb); + return res; +} +#else +static CYTHON_INLINE int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject *exc_type2) { + if (exc_type1) { + return __Pyx_IsAnySubtype2((PyTypeObject*)err, (PyTypeObject*)exc_type1, (PyTypeObject*)exc_type2); + } else { + return __Pyx_IsSubtype((PyTypeObject*)err, (PyTypeObject*)exc_type2); + } +} +#endif +static int __Pyx_PyErr_GivenExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + assert(PyExceptionClass_Check(exc_type)); + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; itp_as_sequence && type->tp_as_sequence->sq_repeat)) { + return type->tp_as_sequence->sq_repeat(seq, mul); + } else +#endif + { + return __Pyx_PySequence_Multiply_Generic(seq, mul); + } +} + +/* SetItemInt */ +static int __Pyx_SetItemInt_Generic(PyObject *o, PyObject *j, PyObject *v) { + int r; + if (unlikely(!j)) return -1; + r = PyObject_SetItem(o, j, v); + Py_DECREF(j); + return r; +} +static CYTHON_INLINE int __Pyx_SetItemInt_Fast(PyObject *o, Py_ssize_t i, PyObject *v, int is_list, + CYTHON_NCP_UNUSED int wraparound, CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS && CYTHON_USE_TYPE_SLOTS + if (is_list || PyList_CheckExact(o)) { + Py_ssize_t n = (!wraparound) ? i : ((likely(i >= 0)) ? i : i + PyList_GET_SIZE(o)); + if ((!boundscheck) || likely(__Pyx_is_valid_index(n, PyList_GET_SIZE(o)))) { + PyObject* old = PyList_GET_ITEM(o, n); + Py_INCREF(v); + PyList_SET_ITEM(o, n, v); + Py_DECREF(old); + return 1; + } + } else { + PyMappingMethods *mm = Py_TYPE(o)->tp_as_mapping; + PySequenceMethods *sm = Py_TYPE(o)->tp_as_sequence; + if (mm && mm->mp_ass_subscript) { + int r; + PyObject *key = PyInt_FromSsize_t(i); + if (unlikely(!key)) return -1; + r = mm->mp_ass_subscript(o, key, v); + Py_DECREF(key); + return r; + } + if (likely(sm && sm->sq_ass_item)) { + if (wraparound && unlikely(i < 0) && likely(sm->sq_length)) { + Py_ssize_t l = sm->sq_length(o); + if (likely(l >= 0)) { + i += l; + } else { + if (!PyErr_ExceptionMatches(PyExc_OverflowError)) + return -1; + PyErr_Clear(); + } + } + return sm->sq_ass_item(o, i, v); + } + } +#else + if (is_list || !PyMapping_Check(o)) + { + return PySequence_SetItem(o, i, v); + } +#endif + return __Pyx_SetItemInt_Generic(o, PyInt_FromSsize_t(i), v); +} + +/* RaiseUnboundLocalError */ +static CYTHON_INLINE void __Pyx_RaiseUnboundLocalError(const char *varname) { + PyErr_Format(PyExc_UnboundLocalError, "local variable '%s' referenced before assignment", varname); +} + +/* DivInt[long] */ +static CYTHON_INLINE long __Pyx_div_long(long a, long b) { + long q = a / b; + long r = a - q*b; + q -= ((r != 0) & ((r ^ b) < 0)); + return q; +} + +/* ImportFrom */ +static PyObject* __Pyx_ImportFrom(PyObject* module, PyObject* name) { + PyObject* value = __Pyx_PyObject_GetAttrStr(module, name); + if (unlikely(!value) && PyErr_ExceptionMatches(PyExc_AttributeError)) { + const char* module_name_str = 0; + PyObject* module_name = 0; + PyObject* module_dot = 0; + PyObject* full_name = 0; + PyErr_Clear(); + module_name_str = PyModule_GetName(module); + if (unlikely(!module_name_str)) { goto modbad; } + module_name = PyUnicode_FromString(module_name_str); + if (unlikely(!module_name)) { goto modbad; } + module_dot = PyUnicode_Concat(module_name, __pyx_kp_u__2); + if (unlikely(!module_dot)) { goto modbad; } + full_name = PyUnicode_Concat(module_dot, name); + if (unlikely(!full_name)) { goto modbad; } + #if PY_VERSION_HEX < 0x030700A1 || (CYTHON_COMPILING_IN_PYPY && PYPY_VERSION_NUM < 0x07030400) + { + PyObject *modules = PyImport_GetModuleDict(); + if (unlikely(!modules)) + goto modbad; + value = PyObject_GetItem(modules, full_name); + } + #else + value = PyImport_GetModule(full_name); + #endif + modbad: + Py_XDECREF(full_name); + Py_XDECREF(module_dot); + Py_XDECREF(module_name); + } + if (unlikely(!value)) { + PyErr_Format(PyExc_ImportError, + #if PY_MAJOR_VERSION < 3 + "cannot import name %.230s", PyString_AS_STRING(name)); + #else + "cannot import name %S", name); + #endif + } + return value; +} + +/* HasAttr */ +#if __PYX_LIMITED_VERSION_HEX < 0x030d00A1 +static CYTHON_INLINE int __Pyx_HasAttr(PyObject *o, PyObject *n) { + PyObject *r; + if (unlikely(!__Pyx_PyBaseString_Check(n))) { + PyErr_SetString(PyExc_TypeError, + "hasattr(): attribute name must be string"); + return -1; + } + r = __Pyx_GetAttr(o, n); + if (!r) { + PyErr_Clear(); + return 0; + } else { + Py_DECREF(r); + return 1; + } +} +#endif + +/* PyIntCompare */ +static CYTHON_INLINE int __Pyx_PyInt_BoolEqObjC(PyObject *op1, PyObject *op2, long intval, long inplace) { + CYTHON_MAYBE_UNUSED_VAR(intval); + CYTHON_UNUSED_VAR(inplace); + if (op1 == op2) { + return 1; + } + #if PY_MAJOR_VERSION < 3 + if (likely(PyInt_CheckExact(op1))) { + const long b = intval; + long a = PyInt_AS_LONG(op1); + return (a == b); + } + #endif + #if CYTHON_USE_PYLONG_INTERNALS + if (likely(PyLong_CheckExact(op1))) { + int unequal; + unsigned long uintval; + Py_ssize_t size = __Pyx_PyLong_DigitCount(op1); + const digit* digits = __Pyx_PyLong_Digits(op1); + if (intval == 0) { + return (__Pyx_PyLong_IsZero(op1) == 1); + } else if (intval < 0) { + if (__Pyx_PyLong_IsNonNeg(op1)) + return 0; + intval = -intval; + } else { + if (__Pyx_PyLong_IsNeg(op1)) + return 0; + } + uintval = (unsigned long) intval; +#if PyLong_SHIFT * 4 < SIZEOF_LONG*8 + if (uintval >> (PyLong_SHIFT * 4)) { + unequal = (size != 5) || (digits[0] != (uintval & (unsigned long) PyLong_MASK)) + | (digits[1] != ((uintval >> (1 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[2] != ((uintval >> (2 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[3] != ((uintval >> (3 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[4] != ((uintval >> (4 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)); + } else +#endif +#if PyLong_SHIFT * 3 < SIZEOF_LONG*8 + if (uintval >> (PyLong_SHIFT * 3)) { + unequal = (size != 4) || (digits[0] != (uintval & (unsigned long) PyLong_MASK)) + | (digits[1] != ((uintval >> (1 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[2] != ((uintval >> (2 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[3] != ((uintval >> (3 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)); + } else +#endif +#if PyLong_SHIFT * 2 < SIZEOF_LONG*8 + if (uintval >> (PyLong_SHIFT * 2)) { + unequal = (size != 3) || (digits[0] != (uintval & (unsigned long) PyLong_MASK)) + | (digits[1] != ((uintval >> (1 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[2] != ((uintval >> (2 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)); + } else +#endif +#if PyLong_SHIFT * 1 < SIZEOF_LONG*8 + if (uintval >> (PyLong_SHIFT * 1)) { + unequal = (size != 2) || (digits[0] != (uintval & (unsigned long) PyLong_MASK)) + | (digits[1] != ((uintval >> (1 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)); + } else +#endif + unequal = (size != 1) || (((unsigned long) digits[0]) != (uintval & (unsigned long) PyLong_MASK)); + return (unequal == 0); + } + #endif + if (PyFloat_CheckExact(op1)) { + const long b = intval; +#if CYTHON_COMPILING_IN_LIMITED_API + double a = __pyx_PyFloat_AsDouble(op1); +#else + double a = PyFloat_AS_DOUBLE(op1); +#endif + return ((double)a == (double)b); + } + return __Pyx_PyObject_IsTrueAndDecref( + PyObject_RichCompare(op1, op2, Py_EQ)); +} + +/* PyIntCompare */ +static CYTHON_INLINE int __Pyx_PyInt_BoolNeObjC(PyObject *op1, PyObject *op2, long intval, long inplace) { + CYTHON_MAYBE_UNUSED_VAR(intval); + CYTHON_UNUSED_VAR(inplace); + if (op1 == op2) { + return 0; + } + #if PY_MAJOR_VERSION < 3 + if (likely(PyInt_CheckExact(op1))) { + const long b = intval; + long a = PyInt_AS_LONG(op1); + return (a != b); + } + #endif + #if CYTHON_USE_PYLONG_INTERNALS + if (likely(PyLong_CheckExact(op1))) { + int unequal; + unsigned long uintval; + Py_ssize_t size = __Pyx_PyLong_DigitCount(op1); + const digit* digits = __Pyx_PyLong_Digits(op1); + if (intval == 0) { + return (__Pyx_PyLong_IsZero(op1) != 1); + } else if (intval < 0) { + if (__Pyx_PyLong_IsNonNeg(op1)) + return 1; + intval = -intval; + } else { + if (__Pyx_PyLong_IsNeg(op1)) + return 1; + } + uintval = (unsigned long) intval; +#if PyLong_SHIFT * 4 < SIZEOF_LONG*8 + if (uintval >> (PyLong_SHIFT * 4)) { + unequal = (size != 5) || (digits[0] != (uintval & (unsigned long) PyLong_MASK)) + | (digits[1] != ((uintval >> (1 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[2] != ((uintval >> (2 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[3] != ((uintval >> (3 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[4] != ((uintval >> (4 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)); + } else +#endif +#if PyLong_SHIFT * 3 < SIZEOF_LONG*8 + if (uintval >> (PyLong_SHIFT * 3)) { + unequal = (size != 4) || (digits[0] != (uintval & (unsigned long) PyLong_MASK)) + | (digits[1] != ((uintval >> (1 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[2] != ((uintval >> (2 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[3] != ((uintval >> (3 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)); + } else +#endif +#if PyLong_SHIFT * 2 < SIZEOF_LONG*8 + if (uintval >> (PyLong_SHIFT * 2)) { + unequal = (size != 3) || (digits[0] != (uintval & (unsigned long) PyLong_MASK)) + | (digits[1] != ((uintval >> (1 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)) | (digits[2] != ((uintval >> (2 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)); + } else +#endif +#if PyLong_SHIFT * 1 < SIZEOF_LONG*8 + if (uintval >> (PyLong_SHIFT * 1)) { + unequal = (size != 2) || (digits[0] != (uintval & (unsigned long) PyLong_MASK)) + | (digits[1] != ((uintval >> (1 * PyLong_SHIFT)) & (unsigned long) PyLong_MASK)); + } else +#endif + unequal = (size != 1) || (((unsigned long) digits[0]) != (uintval & (unsigned long) PyLong_MASK)); + return (unequal != 0); + } + #endif + if (PyFloat_CheckExact(op1)) { + const long b = intval; +#if CYTHON_COMPILING_IN_LIMITED_API + double a = __pyx_PyFloat_AsDouble(op1); +#else + double a = PyFloat_AS_DOUBLE(op1); +#endif + return ((double)a != (double)b); + } + return __Pyx_PyObject_IsTrueAndDecref( + PyObject_RichCompare(op1, op2, Py_NE)); +} + +/* IsLittleEndian */ +static CYTHON_INLINE int __Pyx_Is_Little_Endian(void) +{ + union { + uint32_t u32; + uint8_t u8[4]; + } S; + S.u32 = 0x01020304; + return S.u8[0] == 4; +} + +/* BufferFormatCheck */ +static void __Pyx_BufFmt_Init(__Pyx_BufFmt_Context* ctx, + __Pyx_BufFmt_StackElem* stack, + __Pyx_TypeInfo* type) { + stack[0].field = &ctx->root; + stack[0].parent_offset = 0; + ctx->root.type = type; + ctx->root.name = "buffer dtype"; + ctx->root.offset = 0; + ctx->head = stack; + ctx->head->field = &ctx->root; + ctx->fmt_offset = 0; + ctx->head->parent_offset = 0; + ctx->new_packmode = '@'; + ctx->enc_packmode = '@'; + ctx->new_count = 1; + ctx->enc_count = 0; + ctx->enc_type = 0; + ctx->is_complex = 0; + ctx->is_valid_array = 0; + ctx->struct_alignment = 0; + while (type->typegroup == 'S') { + ++ctx->head; + ctx->head->field = type->fields; + ctx->head->parent_offset = 0; + type = type->fields->type; + } +} +static int __Pyx_BufFmt_ParseNumber(const char** ts) { + int count; + const char* t = *ts; + if (*t < '0' || *t > '9') { + return -1; + } else { + count = *t++ - '0'; + while (*t >= '0' && *t <= '9') { + count *= 10; + count += *t++ - '0'; + } + } + *ts = t; + return count; +} +static int __Pyx_BufFmt_ExpectNumber(const char **ts) { + int number = __Pyx_BufFmt_ParseNumber(ts); + if (number == -1) + PyErr_Format(PyExc_ValueError,\ + "Does not understand character buffer dtype format string ('%c')", **ts); + return number; +} +static void __Pyx_BufFmt_RaiseUnexpectedChar(char ch) { + PyErr_Format(PyExc_ValueError, + "Unexpected format string character: '%c'", ch); +} +static const char* __Pyx_BufFmt_DescribeTypeChar(char ch, int is_complex) { + switch (ch) { + case '?': return "'bool'"; + case 'c': return "'char'"; + case 'b': return "'signed char'"; + case 'B': return "'unsigned char'"; + case 'h': return "'short'"; + case 'H': return "'unsigned short'"; + case 'i': return "'int'"; + case 'I': return "'unsigned int'"; + case 'l': return "'long'"; + case 'L': return "'unsigned long'"; + case 'q': return "'long long'"; + case 'Q': return "'unsigned long long'"; + case 'f': return (is_complex ? "'complex float'" : "'float'"); + case 'd': return (is_complex ? "'complex double'" : "'double'"); + case 'g': return (is_complex ? "'complex long double'" : "'long double'"); + case 'T': return "a struct"; + case 'O': return "Python object"; + case 'P': return "a pointer"; + case 's': case 'p': return "a string"; + case 0: return "end"; + default: return "unparsable format string"; + } +} +static size_t __Pyx_BufFmt_TypeCharToStandardSize(char ch, int is_complex) { + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return 2; + case 'i': case 'I': case 'l': case 'L': return 4; + case 'q': case 'Q': return 8; + case 'f': return (is_complex ? 8 : 4); + case 'd': return (is_complex ? 16 : 8); + case 'g': { + PyErr_SetString(PyExc_ValueError, "Python does not define a standard format string size for long double ('g').."); + return 0; + } + case 'O': case 'P': return sizeof(void*); + default: + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } +} +static size_t __Pyx_BufFmt_TypeCharToNativeSize(char ch, int is_complex) { + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return sizeof(short); + case 'i': case 'I': return sizeof(int); + case 'l': case 'L': return sizeof(long); + #ifdef HAVE_LONG_LONG + case 'q': case 'Q': return sizeof(PY_LONG_LONG); + #endif + case 'f': return sizeof(float) * (is_complex ? 2 : 1); + case 'd': return sizeof(double) * (is_complex ? 2 : 1); + case 'g': return sizeof(long double) * (is_complex ? 2 : 1); + case 'O': case 'P': return sizeof(void*); + default: { + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } + } +} +typedef struct { char c; short x; } __Pyx_st_short; +typedef struct { char c; int x; } __Pyx_st_int; +typedef struct { char c; long x; } __Pyx_st_long; +typedef struct { char c; float x; } __Pyx_st_float; +typedef struct { char c; double x; } __Pyx_st_double; +typedef struct { char c; long double x; } __Pyx_st_longdouble; +typedef struct { char c; void *x; } __Pyx_st_void_p; +#ifdef HAVE_LONG_LONG +typedef struct { char c; PY_LONG_LONG x; } __Pyx_st_longlong; +#endif +static size_t __Pyx_BufFmt_TypeCharToAlignment(char ch, int is_complex) { + CYTHON_UNUSED_VAR(is_complex); + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return sizeof(__Pyx_st_short) - sizeof(short); + case 'i': case 'I': return sizeof(__Pyx_st_int) - sizeof(int); + case 'l': case 'L': return sizeof(__Pyx_st_long) - sizeof(long); +#ifdef HAVE_LONG_LONG + case 'q': case 'Q': return sizeof(__Pyx_st_longlong) - sizeof(PY_LONG_LONG); +#endif + case 'f': return sizeof(__Pyx_st_float) - sizeof(float); + case 'd': return sizeof(__Pyx_st_double) - sizeof(double); + case 'g': return sizeof(__Pyx_st_longdouble) - sizeof(long double); + case 'P': case 'O': return sizeof(__Pyx_st_void_p) - sizeof(void*); + default: + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } +} +/* These are for computing the padding at the end of the struct to align + on the first member of the struct. This will probably the same as above, + but we don't have any guarantees. + */ +typedef struct { short x; char c; } __Pyx_pad_short; +typedef struct { int x; char c; } __Pyx_pad_int; +typedef struct { long x; char c; } __Pyx_pad_long; +typedef struct { float x; char c; } __Pyx_pad_float; +typedef struct { double x; char c; } __Pyx_pad_double; +typedef struct { long double x; char c; } __Pyx_pad_longdouble; +typedef struct { void *x; char c; } __Pyx_pad_void_p; +#ifdef HAVE_LONG_LONG +typedef struct { PY_LONG_LONG x; char c; } __Pyx_pad_longlong; +#endif +static size_t __Pyx_BufFmt_TypeCharToPadding(char ch, int is_complex) { + CYTHON_UNUSED_VAR(is_complex); + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return sizeof(__Pyx_pad_short) - sizeof(short); + case 'i': case 'I': return sizeof(__Pyx_pad_int) - sizeof(int); + case 'l': case 'L': return sizeof(__Pyx_pad_long) - sizeof(long); +#ifdef HAVE_LONG_LONG + case 'q': case 'Q': return sizeof(__Pyx_pad_longlong) - sizeof(PY_LONG_LONG); +#endif + case 'f': return sizeof(__Pyx_pad_float) - sizeof(float); + case 'd': return sizeof(__Pyx_pad_double) - sizeof(double); + case 'g': return sizeof(__Pyx_pad_longdouble) - sizeof(long double); + case 'P': case 'O': return sizeof(__Pyx_pad_void_p) - sizeof(void*); + default: + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } +} +static char __Pyx_BufFmt_TypeCharToGroup(char ch, int is_complex) { + switch (ch) { + case 'c': + return 'H'; + case 'b': case 'h': case 'i': + case 'l': case 'q': case 's': case 'p': + return 'I'; + case '?': case 'B': case 'H': case 'I': case 'L': case 'Q': + return 'U'; + case 'f': case 'd': case 'g': + return (is_complex ? 'C' : 'R'); + case 'O': + return 'O'; + case 'P': + return 'P'; + default: { + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } + } +} +static void __Pyx_BufFmt_RaiseExpected(__Pyx_BufFmt_Context* ctx) { + if (ctx->head == NULL || ctx->head->field == &ctx->root) { + const char* expected; + const char* quote; + if (ctx->head == NULL) { + expected = "end"; + quote = ""; + } else { + expected = ctx->head->field->type->name; + quote = "'"; + } + PyErr_Format(PyExc_ValueError, + "Buffer dtype mismatch, expected %s%s%s but got %s", + quote, expected, quote, + __Pyx_BufFmt_DescribeTypeChar(ctx->enc_type, ctx->is_complex)); + } else { + __Pyx_StructField* field = ctx->head->field; + __Pyx_StructField* parent = (ctx->head - 1)->field; + PyErr_Format(PyExc_ValueError, + "Buffer dtype mismatch, expected '%s' but got %s in '%s.%s'", + field->type->name, __Pyx_BufFmt_DescribeTypeChar(ctx->enc_type, ctx->is_complex), + parent->type->name, field->name); + } +} +static int __Pyx_BufFmt_ProcessTypeChunk(__Pyx_BufFmt_Context* ctx) { + char group; + size_t size, offset, arraysize = 1; + if (ctx->enc_type == 0) return 0; + if (ctx->head->field->type->arraysize[0]) { + int i, ndim = 0; + if (ctx->enc_type == 's' || ctx->enc_type == 'p') { + ctx->is_valid_array = ctx->head->field->type->ndim == 1; + ndim = 1; + if (ctx->enc_count != ctx->head->field->type->arraysize[0]) { + PyErr_Format(PyExc_ValueError, + "Expected a dimension of size %zu, got %zu", + ctx->head->field->type->arraysize[0], ctx->enc_count); + return -1; + } + } + if (!ctx->is_valid_array) { + PyErr_Format(PyExc_ValueError, "Expected %d dimensions, got %d", + ctx->head->field->type->ndim, ndim); + return -1; + } + for (i = 0; i < ctx->head->field->type->ndim; i++) { + arraysize *= ctx->head->field->type->arraysize[i]; + } + ctx->is_valid_array = 0; + ctx->enc_count = 1; + } + group = __Pyx_BufFmt_TypeCharToGroup(ctx->enc_type, ctx->is_complex); + do { + __Pyx_StructField* field = ctx->head->field; + __Pyx_TypeInfo* type = field->type; + if (ctx->enc_packmode == '@' || ctx->enc_packmode == '^') { + size = __Pyx_BufFmt_TypeCharToNativeSize(ctx->enc_type, ctx->is_complex); + } else { + size = __Pyx_BufFmt_TypeCharToStandardSize(ctx->enc_type, ctx->is_complex); + } + if (ctx->enc_packmode == '@') { + size_t align_at = __Pyx_BufFmt_TypeCharToAlignment(ctx->enc_type, ctx->is_complex); + size_t align_mod_offset; + if (align_at == 0) return -1; + align_mod_offset = ctx->fmt_offset % align_at; + if (align_mod_offset > 0) ctx->fmt_offset += align_at - align_mod_offset; + if (ctx->struct_alignment == 0) + ctx->struct_alignment = __Pyx_BufFmt_TypeCharToPadding(ctx->enc_type, + ctx->is_complex); + } + if (type->size != size || type->typegroup != group) { + if (type->typegroup == 'C' && type->fields != NULL) { + size_t parent_offset = ctx->head->parent_offset + field->offset; + ++ctx->head; + ctx->head->field = type->fields; + ctx->head->parent_offset = parent_offset; + continue; + } + if ((type->typegroup == 'H' || group == 'H') && type->size == size) { + } else { + __Pyx_BufFmt_RaiseExpected(ctx); + return -1; + } + } + offset = ctx->head->parent_offset + field->offset; + if (ctx->fmt_offset != offset) { + PyErr_Format(PyExc_ValueError, + "Buffer dtype mismatch; next field is at offset %" CYTHON_FORMAT_SSIZE_T "d but %" CYTHON_FORMAT_SSIZE_T "d expected", + (Py_ssize_t)ctx->fmt_offset, (Py_ssize_t)offset); + return -1; + } + ctx->fmt_offset += size; + if (arraysize) + ctx->fmt_offset += (arraysize - 1) * size; + --ctx->enc_count; + while (1) { + if (field == &ctx->root) { + ctx->head = NULL; + if (ctx->enc_count != 0) { + __Pyx_BufFmt_RaiseExpected(ctx); + return -1; + } + break; + } + ctx->head->field = ++field; + if (field->type == NULL) { + --ctx->head; + field = ctx->head->field; + continue; + } else if (field->type->typegroup == 'S') { + size_t parent_offset = ctx->head->parent_offset + field->offset; + if (field->type->fields->type == NULL) continue; + field = field->type->fields; + ++ctx->head; + ctx->head->field = field; + ctx->head->parent_offset = parent_offset; + break; + } else { + break; + } + } + } while (ctx->enc_count); + ctx->enc_type = 0; + ctx->is_complex = 0; + return 0; +} +static int +__pyx_buffmt_parse_array(__Pyx_BufFmt_Context* ctx, const char** tsp) +{ + const char *ts = *tsp; + int i = 0, number, ndim; + ++ts; + if (ctx->new_count != 1) { + PyErr_SetString(PyExc_ValueError, + "Cannot handle repeated arrays in format string"); + return -1; + } + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return -1; + ndim = ctx->head->field->type->ndim; + while (*ts && *ts != ')') { + switch (*ts) { + case ' ': case '\f': case '\r': case '\n': case '\t': case '\v': continue; + default: break; + } + number = __Pyx_BufFmt_ExpectNumber(&ts); + if (number == -1) return -1; + if (i < ndim && (size_t) number != ctx->head->field->type->arraysize[i]) { + PyErr_Format(PyExc_ValueError, + "Expected a dimension of size %zu, got %d", + ctx->head->field->type->arraysize[i], number); + return -1; + } + if (*ts != ',' && *ts != ')') { + PyErr_Format(PyExc_ValueError, + "Expected a comma in format string, got '%c'", *ts); + return -1; + } + if (*ts == ',') ts++; + i++; + } + if (i != ndim) { + PyErr_Format(PyExc_ValueError, "Expected %d dimension(s), got %d", + ctx->head->field->type->ndim, i); + return -1; + } + if (!*ts) { + PyErr_SetString(PyExc_ValueError, + "Unexpected end of format string, expected ')'"); + return -1; + } + ctx->is_valid_array = 1; + ctx->new_count = 1; + *tsp = ++ts; + return 0; +} +static const char* __Pyx_BufFmt_CheckString(__Pyx_BufFmt_Context* ctx, const char* ts) { + int got_Z = 0; + while (1) { + switch(*ts) { + case 0: + if (ctx->enc_type != 0 && ctx->head == NULL) { + __Pyx_BufFmt_RaiseExpected(ctx); + return NULL; + } + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + if (ctx->head != NULL) { + __Pyx_BufFmt_RaiseExpected(ctx); + return NULL; + } + return ts; + case ' ': + case '\r': + case '\n': + ++ts; + break; + case '<': + if (!__Pyx_Is_Little_Endian()) { + PyErr_SetString(PyExc_ValueError, "Little-endian buffer not supported on big-endian compiler"); + return NULL; + } + ctx->new_packmode = '='; + ++ts; + break; + case '>': + case '!': + if (__Pyx_Is_Little_Endian()) { + PyErr_SetString(PyExc_ValueError, "Big-endian buffer not supported on little-endian compiler"); + return NULL; + } + ctx->new_packmode = '='; + ++ts; + break; + case '=': + case '@': + case '^': + ctx->new_packmode = *ts++; + break; + case 'T': + { + const char* ts_after_sub; + size_t i, struct_count = ctx->new_count; + size_t struct_alignment = ctx->struct_alignment; + ctx->new_count = 1; + ++ts; + if (*ts != '{') { + PyErr_SetString(PyExc_ValueError, "Buffer acquisition: Expected '{' after 'T'"); + return NULL; + } + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->enc_type = 0; + ctx->enc_count = 0; + ctx->struct_alignment = 0; + ++ts; + ts_after_sub = ts; + for (i = 0; i != struct_count; ++i) { + ts_after_sub = __Pyx_BufFmt_CheckString(ctx, ts); + if (!ts_after_sub) return NULL; + } + ts = ts_after_sub; + if (struct_alignment) ctx->struct_alignment = struct_alignment; + } + break; + case '}': + { + size_t alignment = ctx->struct_alignment; + ++ts; + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->enc_type = 0; + if (alignment && ctx->fmt_offset % alignment) { + ctx->fmt_offset += alignment - (ctx->fmt_offset % alignment); + } + } + return ts; + case 'x': + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->fmt_offset += ctx->new_count; + ctx->new_count = 1; + ctx->enc_count = 0; + ctx->enc_type = 0; + ctx->enc_packmode = ctx->new_packmode; + ++ts; + break; + case 'Z': + got_Z = 1; + ++ts; + if (*ts != 'f' && *ts != 'd' && *ts != 'g') { + __Pyx_BufFmt_RaiseUnexpectedChar('Z'); + return NULL; + } + CYTHON_FALLTHROUGH; + case '?': case 'c': case 'b': case 'B': case 'h': case 'H': case 'i': case 'I': + case 'l': case 'L': case 'q': case 'Q': + case 'f': case 'd': case 'g': + case 'O': case 'p': + if ((ctx->enc_type == *ts) && (got_Z == ctx->is_complex) && + (ctx->enc_packmode == ctx->new_packmode) && (!ctx->is_valid_array)) { + ctx->enc_count += ctx->new_count; + ctx->new_count = 1; + got_Z = 0; + ++ts; + break; + } + CYTHON_FALLTHROUGH; + case 's': + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->enc_count = ctx->new_count; + ctx->enc_packmode = ctx->new_packmode; + ctx->enc_type = *ts; + ctx->is_complex = got_Z; + ++ts; + ctx->new_count = 1; + got_Z = 0; + break; + case ':': + ++ts; + while(*ts != ':') ++ts; + ++ts; + break; + case '(': + if (__pyx_buffmt_parse_array(ctx, &ts) < 0) return NULL; + break; + default: + { + int number = __Pyx_BufFmt_ExpectNumber(&ts); + if (number == -1) return NULL; + ctx->new_count = (size_t)number; + } + } + } +} + +/* BufferGetAndValidate */ + static CYTHON_INLINE void __Pyx_SafeReleaseBuffer(Py_buffer* info) { + if (unlikely(info->buf == NULL)) return; + if (info->suboffsets == __Pyx_minusones) info->suboffsets = NULL; + __Pyx_ReleaseBuffer(info); +} +static void __Pyx_ZeroBuffer(Py_buffer* buf) { + buf->buf = NULL; + buf->obj = NULL; + buf->strides = __Pyx_zeros; + buf->shape = __Pyx_zeros; + buf->suboffsets = __Pyx_minusones; +} +static int __Pyx__GetBufferAndValidate( + Py_buffer* buf, PyObject* obj, __Pyx_TypeInfo* dtype, int flags, + int nd, int cast, __Pyx_BufFmt_StackElem* stack) +{ + buf->buf = NULL; + if (unlikely(__Pyx_GetBuffer(obj, buf, flags) == -1)) { + __Pyx_ZeroBuffer(buf); + return -1; + } + if (unlikely(buf->ndim != nd)) { + PyErr_Format(PyExc_ValueError, + "Buffer has wrong number of dimensions (expected %d, got %d)", + nd, buf->ndim); + goto fail; + } + if (!cast) { + __Pyx_BufFmt_Context ctx; + __Pyx_BufFmt_Init(&ctx, stack, dtype); + if (!__Pyx_BufFmt_CheckString(&ctx, buf->format)) goto fail; + } + if (unlikely((size_t)buf->itemsize != dtype->size)) { + PyErr_Format(PyExc_ValueError, + "Item size of buffer (%" CYTHON_FORMAT_SSIZE_T "d byte%s) does not match size of '%s' (%" CYTHON_FORMAT_SSIZE_T "d byte%s)", + buf->itemsize, (buf->itemsize > 1) ? "s" : "", + dtype->name, (Py_ssize_t)dtype->size, (dtype->size > 1) ? "s" : ""); + goto fail; + } + if (buf->suboffsets == NULL) buf->suboffsets = __Pyx_minusones; + return 0; +fail:; + __Pyx_SafeReleaseBuffer(buf); + return -1; +} + +/* UnicodeConcatInPlace */ + # if CYTHON_COMPILING_IN_CPYTHON && PY_MAJOR_VERSION >= 3 +static int +__Pyx_unicode_modifiable(PyObject *unicode) +{ + if (Py_REFCNT(unicode) != 1) + return 0; + if (!PyUnicode_CheckExact(unicode)) + return 0; + if (PyUnicode_CHECK_INTERNED(unicode)) + return 0; + return 1; +} +static CYTHON_INLINE PyObject *__Pyx_PyUnicode_ConcatInPlaceImpl(PyObject **p_left, PyObject *right + #if CYTHON_REFNANNY + , void* __pyx_refnanny + #endif + ) { + PyObject *left = *p_left; + Py_ssize_t left_len, right_len, new_len; + if (unlikely(__Pyx_PyUnicode_READY(left) == -1)) + return NULL; + if (unlikely(__Pyx_PyUnicode_READY(right) == -1)) + return NULL; + left_len = PyUnicode_GET_LENGTH(left); + if (left_len == 0) { + Py_INCREF(right); + return right; + } + right_len = PyUnicode_GET_LENGTH(right); + if (right_len == 0) { + Py_INCREF(left); + return left; + } + if (unlikely(left_len > PY_SSIZE_T_MAX - right_len)) { + PyErr_SetString(PyExc_OverflowError, + "strings are too large to concat"); + return NULL; + } + new_len = left_len + right_len; + if (__Pyx_unicode_modifiable(left) + && PyUnicode_CheckExact(right) + && PyUnicode_KIND(right) <= PyUnicode_KIND(left) + && !(PyUnicode_IS_ASCII(left) && !PyUnicode_IS_ASCII(right))) { + int ret; + __Pyx_GIVEREF(*p_left); + ret = PyUnicode_Resize(p_left, new_len); + __Pyx_GOTREF(*p_left); + if (unlikely(ret != 0)) + return NULL; + #if PY_VERSION_HEX >= 0x030d0000 + if (unlikely(PyUnicode_CopyCharacters(*p_left, left_len, right, 0, right_len) < 0)) return NULL; + #else + _PyUnicode_FastCopyCharacters(*p_left, left_len, right, 0, right_len); + #endif + __Pyx_INCREF(*p_left); + __Pyx_GIVEREF(*p_left); + return *p_left; + } else { + return __Pyx_PyUnicode_Concat(left, right); + } + } +#endif + +/* SliceObject */ + static CYTHON_INLINE PyObject* __Pyx_PyObject_GetSlice(PyObject* obj, + Py_ssize_t cstart, Py_ssize_t cstop, + PyObject** _py_start, PyObject** _py_stop, PyObject** _py_slice, + int has_cstart, int has_cstop, int wraparound) { + __Pyx_TypeName obj_type_name; +#if CYTHON_USE_TYPE_SLOTS + PyMappingMethods* mp; +#if PY_MAJOR_VERSION < 3 + PySequenceMethods* ms = Py_TYPE(obj)->tp_as_sequence; + if (likely(ms && ms->sq_slice)) { + if (!has_cstart) { + if (_py_start && (*_py_start != Py_None)) { + cstart = __Pyx_PyIndex_AsSsize_t(*_py_start); + if ((cstart == (Py_ssize_t)-1) && PyErr_Occurred()) goto bad; + } else + cstart = 0; + } + if (!has_cstop) { + if (_py_stop && (*_py_stop != Py_None)) { + cstop = __Pyx_PyIndex_AsSsize_t(*_py_stop); + if ((cstop == (Py_ssize_t)-1) && PyErr_Occurred()) goto bad; + } else + cstop = PY_SSIZE_T_MAX; + } + if (wraparound && unlikely((cstart < 0) | (cstop < 0)) && likely(ms->sq_length)) { + Py_ssize_t l = ms->sq_length(obj); + if (likely(l >= 0)) { + if (cstop < 0) { + cstop += l; + if (cstop < 0) cstop = 0; + } + if (cstart < 0) { + cstart += l; + if (cstart < 0) cstart = 0; + } + } else { + if (!PyErr_ExceptionMatches(PyExc_OverflowError)) + goto bad; + PyErr_Clear(); + } + } + return ms->sq_slice(obj, cstart, cstop); + } +#else + CYTHON_UNUSED_VAR(wraparound); +#endif + mp = Py_TYPE(obj)->tp_as_mapping; + if (likely(mp && mp->mp_subscript)) +#else + CYTHON_UNUSED_VAR(wraparound); +#endif + { + PyObject* result; + PyObject *py_slice, *py_start, *py_stop; + if (_py_slice) { + py_slice = *_py_slice; + } else { + PyObject* owned_start = NULL; + PyObject* owned_stop = NULL; + if (_py_start) { + py_start = *_py_start; + } else { + if (has_cstart) { + owned_start = py_start = PyInt_FromSsize_t(cstart); + if (unlikely(!py_start)) goto bad; + } else + py_start = Py_None; + } + if (_py_stop) { + py_stop = *_py_stop; + } else { + if (has_cstop) { + owned_stop = py_stop = PyInt_FromSsize_t(cstop); + if (unlikely(!py_stop)) { + Py_XDECREF(owned_start); + goto bad; + } + } else + py_stop = Py_None; + } + py_slice = PySlice_New(py_start, py_stop, Py_None); + Py_XDECREF(owned_start); + Py_XDECREF(owned_stop); + if (unlikely(!py_slice)) goto bad; + } +#if CYTHON_USE_TYPE_SLOTS + result = mp->mp_subscript(obj, py_slice); +#else + result = PyObject_GetItem(obj, py_slice); +#endif + if (!_py_slice) { + Py_DECREF(py_slice); + } + return result; + } + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "'" __Pyx_FMT_TYPENAME "' object is unsliceable", obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); +bad: + return NULL; +} + +/* PyObjectFormat */ + #if CYTHON_USE_UNICODE_WRITER +static PyObject* __Pyx_PyObject_Format(PyObject* obj, PyObject* format_spec) { + int ret; + _PyUnicodeWriter writer; + if (likely(PyFloat_CheckExact(obj))) { +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x03040000 + _PyUnicodeWriter_Init(&writer, 0); +#else + _PyUnicodeWriter_Init(&writer); +#endif + ret = _PyFloat_FormatAdvancedWriter( + &writer, + obj, + format_spec, 0, PyUnicode_GET_LENGTH(format_spec)); + } else if (likely(PyLong_CheckExact(obj))) { +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x03040000 + _PyUnicodeWriter_Init(&writer, 0); +#else + _PyUnicodeWriter_Init(&writer); +#endif + ret = _PyLong_FormatAdvancedWriter( + &writer, + obj, + format_spec, 0, PyUnicode_GET_LENGTH(format_spec)); + } else { + return PyObject_Format(obj, format_spec); + } + if (unlikely(ret == -1)) { + _PyUnicodeWriter_Dealloc(&writer); + return NULL; + } + return _PyUnicodeWriter_Finish(&writer); +} +#endif + +/* UnpackUnboundCMethod */ + static PyObject *__Pyx_SelflessCall(PyObject *method, PyObject *args, PyObject *kwargs) { + PyObject *result; + PyObject *selfless_args = PyTuple_GetSlice(args, 1, PyTuple_Size(args)); + if (unlikely(!selfless_args)) return NULL; + result = PyObject_Call(method, selfless_args, kwargs); + Py_DECREF(selfless_args); + return result; +} +static PyMethodDef __Pyx_UnboundCMethod_Def = { + "CythonUnboundCMethod", + __PYX_REINTERPRET_FUNCION(PyCFunction, __Pyx_SelflessCall), + METH_VARARGS | METH_KEYWORDS, + NULL +}; +static int __Pyx_TryUnpackUnboundCMethod(__Pyx_CachedCFunction* target) { + PyObject *method; + method = __Pyx_PyObject_GetAttrStr(target->type, *target->method_name); + if (unlikely(!method)) + return -1; + target->method = method; +#if CYTHON_COMPILING_IN_CPYTHON + #if PY_MAJOR_VERSION >= 3 + if (likely(__Pyx_TypeCheck(method, &PyMethodDescr_Type))) + #else + if (likely(!__Pyx_CyOrPyCFunction_Check(method))) + #endif + { + PyMethodDescrObject *descr = (PyMethodDescrObject*) method; + target->func = descr->d_method->ml_meth; + target->flag = descr->d_method->ml_flags & ~(METH_CLASS | METH_STATIC | METH_COEXIST | METH_STACKLESS); + } else +#endif +#if CYTHON_COMPILING_IN_PYPY +#else + if (PyCFunction_Check(method)) +#endif + { + PyObject *self; + int self_found; +#if CYTHON_COMPILING_IN_LIMITED_API || CYTHON_COMPILING_IN_PYPY + self = PyObject_GetAttrString(method, "__self__"); + if (!self) { + PyErr_Clear(); + } +#else + self = PyCFunction_GET_SELF(method); +#endif + self_found = (self && self != Py_None); +#if CYTHON_COMPILING_IN_LIMITED_API || CYTHON_COMPILING_IN_PYPY + Py_XDECREF(self); +#endif + if (self_found) { + PyObject *unbound_method = PyCFunction_New(&__Pyx_UnboundCMethod_Def, method); + if (unlikely(!unbound_method)) return -1; + Py_DECREF(method); + target->method = unbound_method; + } + } + return 0; +} + +/* CallUnboundCMethod0 */ + static PyObject* __Pyx__CallUnboundCMethod0(__Pyx_CachedCFunction* cfunc, PyObject* self) { + PyObject *args, *result = NULL; + if (unlikely(!cfunc->method) && unlikely(__Pyx_TryUnpackUnboundCMethod(cfunc) < 0)) return NULL; +#if CYTHON_ASSUME_SAFE_MACROS + args = PyTuple_New(1); + if (unlikely(!args)) goto bad; + Py_INCREF(self); + PyTuple_SET_ITEM(args, 0, self); +#else + args = PyTuple_Pack(1, self); + if (unlikely(!args)) goto bad; +#endif + result = __Pyx_PyObject_Call(cfunc->method, args, NULL); + Py_DECREF(args); +bad: + return result; +} + +/* py_dict_keys */ + static CYTHON_INLINE PyObject* __Pyx_PyDict_Keys(PyObject* d) { + if (PY_MAJOR_VERSION >= 3) + return __Pyx_CallUnboundCMethod0(&__pyx_umethod_PyDict_Type_keys, d); + else + return PyDict_Keys(d); +} + +/* DictGetItem */ + #if PY_MAJOR_VERSION >= 3 && !CYTHON_COMPILING_IN_PYPY +static PyObject *__Pyx_PyDict_GetItem(PyObject *d, PyObject* key) { + PyObject *value; + value = PyDict_GetItemWithError(d, key); + if (unlikely(!value)) { + if (!PyErr_Occurred()) { + if (unlikely(PyTuple_Check(key))) { + PyObject* args = PyTuple_Pack(1, key); + if (likely(args)) { + PyErr_SetObject(PyExc_KeyError, args); + Py_DECREF(args); + } + } else { + PyErr_SetObject(PyExc_KeyError, key); + } + } + return NULL; + } + Py_INCREF(value); + return value; +} +#endif + +/* PyObjectLookupSpecial */ + #if CYTHON_USE_PYTYPE_LOOKUP && CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx__PyObject_LookupSpecial(PyObject* obj, PyObject* attr_name, int with_error) { + PyObject *res; + PyTypeObject *tp = Py_TYPE(obj); +#if PY_MAJOR_VERSION < 3 + if (unlikely(PyInstance_Check(obj))) + return with_error ? __Pyx_PyObject_GetAttrStr(obj, attr_name) : __Pyx_PyObject_GetAttrStrNoError(obj, attr_name); +#endif + res = _PyType_Lookup(tp, attr_name); + if (likely(res)) { + descrgetfunc f = Py_TYPE(res)->tp_descr_get; + if (!f) { + Py_INCREF(res); + } else { + res = f(res, obj, (PyObject *)tp); + } + } else if (with_error) { + PyErr_SetObject(PyExc_AttributeError, attr_name); + } + return res; +} +#endif + +/* FixUpExtensionType */ + #if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type) { +#if PY_VERSION_HEX > 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + CYTHON_UNUSED_VAR(spec); + CYTHON_UNUSED_VAR(type); +#else + const PyType_Slot *slot = spec->slots; + while (slot && slot->slot && slot->slot != Py_tp_members) + slot++; + if (slot && slot->slot == Py_tp_members) { + int changed = 0; +#if !(PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON) + const +#endif + PyMemberDef *memb = (PyMemberDef*) slot->pfunc; + while (memb && memb->name) { + if (memb->name[0] == '_' && memb->name[1] == '_') { +#if PY_VERSION_HEX < 0x030900b1 + if (strcmp(memb->name, "__weaklistoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_weaklistoffset = memb->offset; + changed = 1; + } + else if (strcmp(memb->name, "__dictoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_dictoffset = memb->offset; + changed = 1; + } +#if CYTHON_METH_FASTCALL + else if (strcmp(memb->name, "__vectorcalloffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); +#if PY_VERSION_HEX >= 0x030800b4 + type->tp_vectorcall_offset = memb->offset; +#else + type->tp_print = (printfunc) memb->offset; +#endif + changed = 1; + } +#endif +#else + if ((0)); +#endif +#if PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON + else if (strcmp(memb->name, "__module__") == 0) { + PyObject *descr; + assert(memb->type == T_OBJECT); + assert(memb->flags == 0 || memb->flags == READONLY); + descr = PyDescr_NewMember(type, memb); + if (unlikely(!descr)) + return -1; + if (unlikely(PyDict_SetItem(type->tp_dict, PyDescr_NAME(descr), descr) < 0)) { + Py_DECREF(descr); + return -1; + } + Py_DECREF(descr); + changed = 1; + } +#endif + } + memb++; + } + if (changed) + PyType_Modified(type); + } +#endif + return 0; +} +#endif + +/* FetchSharedCythonModule */ + static PyObject *__Pyx_FetchSharedCythonABIModule(void) { + return __Pyx_PyImport_AddModuleRef((char*) __PYX_ABI_MODULE_NAME); +} + +/* FetchCommonType */ + static int __Pyx_VerifyCachedType(PyObject *cached_type, + const char *name, + Py_ssize_t basicsize, + Py_ssize_t expected_basicsize) { + if (!PyType_Check(cached_type)) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s is not a type object", name); + return -1; + } + if (basicsize != expected_basicsize) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s has the wrong size, try recompiling", + name); + return -1; + } + return 0; +} +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type) { + PyObject* abi_module; + const char* object_name; + PyTypeObject *cached_type = NULL; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + object_name = strrchr(type->tp_name, '.'); + object_name = object_name ? object_name+1 : type->tp_name; + cached_type = (PyTypeObject*) PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + if (__Pyx_VerifyCachedType( + (PyObject *)cached_type, + object_name, + cached_type->tp_basicsize, + type->tp_basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + if (PyType_Ready(type) < 0) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, (PyObject *)type) < 0) + goto bad; + Py_INCREF(type); + cached_type = type; +done: + Py_DECREF(abi_module); + return cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#else +static PyTypeObject *__Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases) { + PyObject *abi_module, *cached_type = NULL; + const char* object_name = strrchr(spec->name, '.'); + object_name = object_name ? object_name+1 : spec->name; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + cached_type = PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + Py_ssize_t basicsize; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *py_basicsize; + py_basicsize = PyObject_GetAttrString(cached_type, "__basicsize__"); + if (unlikely(!py_basicsize)) goto bad; + basicsize = PyLong_AsSsize_t(py_basicsize); + Py_DECREF(py_basicsize); + py_basicsize = 0; + if (unlikely(basicsize == (Py_ssize_t)-1) && PyErr_Occurred()) goto bad; +#else + basicsize = likely(PyType_Check(cached_type)) ? ((PyTypeObject*) cached_type)->tp_basicsize : -1; +#endif + if (__Pyx_VerifyCachedType( + cached_type, + object_name, + basicsize, + spec->basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + CYTHON_UNUSED_VAR(module); + cached_type = __Pyx_PyType_FromModuleAndSpec(abi_module, spec, bases); + if (unlikely(!cached_type)) goto bad; + if (unlikely(__Pyx_fix_up_extension_type_from_spec(spec, (PyTypeObject *) cached_type) < 0)) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, cached_type) < 0) goto bad; +done: + Py_DECREF(abi_module); + assert(cached_type == NULL || PyType_Check(cached_type)); + return (PyTypeObject *) cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#endif + +/* PyVectorcallFastCallDict */ + #if CYTHON_METH_FASTCALL +static PyObject *__Pyx_PyVectorcall_FastCallDict_kw(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + PyObject *res = NULL; + PyObject *kwnames; + PyObject **newargs; + PyObject **kwvalues; + Py_ssize_t i, pos; + size_t j; + PyObject *key, *value; + unsigned long keys_are_strings; + Py_ssize_t nkw = PyDict_GET_SIZE(kw); + newargs = (PyObject **)PyMem_Malloc((nargs + (size_t)nkw) * sizeof(args[0])); + if (unlikely(newargs == NULL)) { + PyErr_NoMemory(); + return NULL; + } + for (j = 0; j < nargs; j++) newargs[j] = args[j]; + kwnames = PyTuple_New(nkw); + if (unlikely(kwnames == NULL)) { + PyMem_Free(newargs); + return NULL; + } + kwvalues = newargs + nargs; + pos = i = 0; + keys_are_strings = Py_TPFLAGS_UNICODE_SUBCLASS; + while (PyDict_Next(kw, &pos, &key, &value)) { + keys_are_strings &= Py_TYPE(key)->tp_flags; + Py_INCREF(key); + Py_INCREF(value); + PyTuple_SET_ITEM(kwnames, i, key); + kwvalues[i] = value; + i++; + } + if (unlikely(!keys_are_strings)) { + PyErr_SetString(PyExc_TypeError, "keywords must be strings"); + goto cleanup; + } + res = vc(func, newargs, nargs, kwnames); +cleanup: + Py_DECREF(kwnames); + for (i = 0; i < nkw; i++) + Py_DECREF(kwvalues[i]); + PyMem_Free(newargs); + return res; +} +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + if (likely(kw == NULL) || PyDict_GET_SIZE(kw) == 0) { + return vc(func, args, nargs, NULL); + } + return __Pyx_PyVectorcall_FastCallDict_kw(func, vc, args, nargs, kw); +} +#endif + +/* CythonFunctionShared */ + #if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc) { + if (__Pyx_CyFunction_Check(func)) { + return PyCFunction_GetFunction(((__pyx_CyFunctionObject*)func)->func) == (PyCFunction) cfunc; + } else if (PyCFunction_Check(func)) { + return PyCFunction_GetFunction(func) == (PyCFunction) cfunc; + } + return 0; +} +#else +static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc) { + return __Pyx_CyOrPyCFunction_Check(func) && __Pyx_CyOrPyCFunction_GET_FUNCTION(func) == (PyCFunction) cfunc; +} +#endif +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj) { +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + __Pyx_Py_XDECREF_SET( + __Pyx_CyFunction_GetClassObj(f), + ((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#else + __Pyx_Py_XDECREF_SET( + ((PyCMethodObject *) (f))->mm_class, + (PyTypeObject*)((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#endif +} +static PyObject * +__Pyx_CyFunction_get_doc(__pyx_CyFunctionObject *op, void *closure) +{ + CYTHON_UNUSED_VAR(closure); + if (unlikely(op->func_doc == NULL)) { +#if CYTHON_COMPILING_IN_LIMITED_API + op->func_doc = PyObject_GetAttrString(op->func, "__doc__"); + if (unlikely(!op->func_doc)) return NULL; +#else + if (((PyCFunctionObject*)op)->m_ml->ml_doc) { +#if PY_MAJOR_VERSION >= 3 + op->func_doc = PyUnicode_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#else + op->func_doc = PyString_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#endif + if (unlikely(op->func_doc == NULL)) + return NULL; + } else { + Py_INCREF(Py_None); + return Py_None; + } +#endif + } + Py_INCREF(op->func_doc); + return op->func_doc; +} +static int +__Pyx_CyFunction_set_doc(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (value == NULL) { + value = Py_None; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_doc, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_name(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_name == NULL)) { +#if CYTHON_COMPILING_IN_LIMITED_API + op->func_name = PyObject_GetAttrString(op->func, "__name__"); +#elif PY_MAJOR_VERSION >= 3 + op->func_name = PyUnicode_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#else + op->func_name = PyString_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#endif + if (unlikely(op->func_name == NULL)) + return NULL; + } + Py_INCREF(op->func_name); + return op->func_name; +} +static int +__Pyx_CyFunction_set_name(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__name__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_name, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_qualname(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_qualname); + return op->func_qualname; +} +static int +__Pyx_CyFunction_set_qualname(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__qualname__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_qualname, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_dict(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_dict == NULL)) { + op->func_dict = PyDict_New(); + if (unlikely(op->func_dict == NULL)) + return NULL; + } + Py_INCREF(op->func_dict); + return op->func_dict; +} +static int +__Pyx_CyFunction_set_dict(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(value == NULL)) { + PyErr_SetString(PyExc_TypeError, + "function's dictionary may not be deleted"); + return -1; + } + if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "setting function's dictionary to a non-dict"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_dict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_globals(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_globals); + return op->func_globals; +} +static PyObject * +__Pyx_CyFunction_get_closure(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(op); + CYTHON_UNUSED_VAR(context); + Py_INCREF(Py_None); + return Py_None; +} +static PyObject * +__Pyx_CyFunction_get_code(__pyx_CyFunctionObject *op, void *context) +{ + PyObject* result = (op->func_code) ? op->func_code : Py_None; + CYTHON_UNUSED_VAR(context); + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_init_defaults(__pyx_CyFunctionObject *op) { + int result = 0; + PyObject *res = op->defaults_getter((PyObject *) op); + if (unlikely(!res)) + return -1; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + op->defaults_tuple = PyTuple_GET_ITEM(res, 0); + Py_INCREF(op->defaults_tuple); + op->defaults_kwdict = PyTuple_GET_ITEM(res, 1); + Py_INCREF(op->defaults_kwdict); + #else + op->defaults_tuple = __Pyx_PySequence_ITEM(res, 0); + if (unlikely(!op->defaults_tuple)) result = -1; + else { + op->defaults_kwdict = __Pyx_PySequence_ITEM(res, 1); + if (unlikely(!op->defaults_kwdict)) result = -1; + } + #endif + Py_DECREF(res); + return result; +} +static int +__Pyx_CyFunction_set_defaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyTuple_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__defaults__ must be set to a tuple object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__defaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_tuple, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_defaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_tuple; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_tuple; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_kwdefaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__kwdefaults__ must be set to a dict object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__kwdefaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_kwdict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_kwdefaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_kwdict; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_kwdict; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_annotations(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value || value == Py_None) { + value = NULL; + } else if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__annotations__ must be set to a dict object"); + return -1; + } + Py_XINCREF(value); + __Pyx_Py_XDECREF_SET(op->func_annotations, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_annotations(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->func_annotations; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + result = PyDict_New(); + if (unlikely(!result)) return NULL; + op->func_annotations = result; + } + Py_INCREF(result); + return result; +} +static PyObject * +__Pyx_CyFunction_get_is_coroutine(__pyx_CyFunctionObject *op, void *context) { + int is_coroutine; + CYTHON_UNUSED_VAR(context); + if (op->func_is_coroutine) { + return __Pyx_NewRef(op->func_is_coroutine); + } + is_coroutine = op->flags & __Pyx_CYFUNCTION_COROUTINE; +#if PY_VERSION_HEX >= 0x03050000 + if (is_coroutine) { + PyObject *module, *fromlist, *marker = __pyx_n_s_is_coroutine; + fromlist = PyList_New(1); + if (unlikely(!fromlist)) return NULL; + Py_INCREF(marker); +#if CYTHON_ASSUME_SAFE_MACROS + PyList_SET_ITEM(fromlist, 0, marker); +#else + if (unlikely(PyList_SetItem(fromlist, 0, marker) < 0)) { + Py_DECREF(marker); + Py_DECREF(fromlist); + return NULL; + } +#endif + module = PyImport_ImportModuleLevelObject(__pyx_n_s_asyncio_coroutines, NULL, NULL, fromlist, 0); + Py_DECREF(fromlist); + if (unlikely(!module)) goto ignore; + op->func_is_coroutine = __Pyx_PyObject_GetAttrStr(module, marker); + Py_DECREF(module); + if (likely(op->func_is_coroutine)) { + return __Pyx_NewRef(op->func_is_coroutine); + } +ignore: + PyErr_Clear(); + } +#endif + op->func_is_coroutine = __Pyx_PyBool_FromLong(is_coroutine); + return __Pyx_NewRef(op->func_is_coroutine); +} +#if CYTHON_COMPILING_IN_LIMITED_API +static PyObject * +__Pyx_CyFunction_get_module(__pyx_CyFunctionObject *op, void *context) { + CYTHON_UNUSED_VAR(context); + return PyObject_GetAttrString(op->func, "__module__"); +} +static int +__Pyx_CyFunction_set_module(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + return PyObject_SetAttrString(op->func, "__module__", value); +} +#endif +static PyGetSetDef __pyx_CyFunction_getsets[] = { + {(char *) "func_doc", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "__doc__", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "func_name", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__name__", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__qualname__", (getter)__Pyx_CyFunction_get_qualname, (setter)__Pyx_CyFunction_set_qualname, 0, 0}, + {(char *) "func_dict", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "__dict__", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "func_globals", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "__globals__", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "func_closure", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "__closure__", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "func_code", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "__code__", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "func_defaults", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__defaults__", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__kwdefaults__", (getter)__Pyx_CyFunction_get_kwdefaults, (setter)__Pyx_CyFunction_set_kwdefaults, 0, 0}, + {(char *) "__annotations__", (getter)__Pyx_CyFunction_get_annotations, (setter)__Pyx_CyFunction_set_annotations, 0, 0}, + {(char *) "_is_coroutine", (getter)__Pyx_CyFunction_get_is_coroutine, 0, 0, 0}, +#if CYTHON_COMPILING_IN_LIMITED_API + {"__module__", (getter)__Pyx_CyFunction_get_module, (setter)__Pyx_CyFunction_set_module, 0, 0}, +#endif + {0, 0, 0, 0, 0} +}; +static PyMemberDef __pyx_CyFunction_members[] = { +#if !CYTHON_COMPILING_IN_LIMITED_API + {(char *) "__module__", T_OBJECT, offsetof(PyCFunctionObject, m_module), 0, 0}, +#endif +#if CYTHON_USE_TYPE_SPECS + {(char *) "__dictoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_dict), READONLY, 0}, +#if CYTHON_METH_FASTCALL +#if CYTHON_BACKPORT_VECTORCALL + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_vectorcall), READONLY, 0}, +#else +#if !CYTHON_COMPILING_IN_LIMITED_API + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(PyCFunctionObject, vectorcall), READONLY, 0}, +#endif +#endif +#endif +#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_weakreflist), READONLY, 0}, +#else + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(PyCFunctionObject, m_weakreflist), READONLY, 0}, +#endif +#endif + {0, 0, 0, 0, 0} +}; +static PyObject * +__Pyx_CyFunction_reduce(__pyx_CyFunctionObject *m, PyObject *args) +{ + CYTHON_UNUSED_VAR(args); +#if PY_MAJOR_VERSION >= 3 + Py_INCREF(m->func_qualname); + return m->func_qualname; +#else + return PyString_FromString(((PyCFunctionObject*)m)->m_ml->ml_name); +#endif +} +static PyMethodDef __pyx_CyFunction_methods[] = { + {"__reduce__", (PyCFunction)__Pyx_CyFunction_reduce, METH_VARARGS, 0}, + {0, 0, 0, 0} +}; +#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API +#define __Pyx_CyFunction_weakreflist(cyfunc) ((cyfunc)->func_weakreflist) +#else +#define __Pyx_CyFunction_weakreflist(cyfunc) (((PyCFunctionObject*)cyfunc)->m_weakreflist) +#endif +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject *op, PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { +#if !CYTHON_COMPILING_IN_LIMITED_API + PyCFunctionObject *cf = (PyCFunctionObject*) op; +#endif + if (unlikely(op == NULL)) + return NULL; +#if CYTHON_COMPILING_IN_LIMITED_API + op->func = PyCFunction_NewEx(ml, (PyObject*)op, module); + if (unlikely(!op->func)) return NULL; +#endif + op->flags = flags; + __Pyx_CyFunction_weakreflist(op) = NULL; +#if !CYTHON_COMPILING_IN_LIMITED_API + cf->m_ml = ml; + cf->m_self = (PyObject *) op; +#endif + Py_XINCREF(closure); + op->func_closure = closure; +#if !CYTHON_COMPILING_IN_LIMITED_API + Py_XINCREF(module); + cf->m_module = module; +#endif + op->func_dict = NULL; + op->func_name = NULL; + Py_INCREF(qualname); + op->func_qualname = qualname; + op->func_doc = NULL; +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + op->func_classobj = NULL; +#else + ((PyCMethodObject*)op)->mm_class = NULL; +#endif + op->func_globals = globals; + Py_INCREF(op->func_globals); + Py_XINCREF(code); + op->func_code = code; + op->defaults_pyobjects = 0; + op->defaults_size = 0; + op->defaults = NULL; + op->defaults_tuple = NULL; + op->defaults_kwdict = NULL; + op->defaults_getter = NULL; + op->func_annotations = NULL; + op->func_is_coroutine = NULL; +#if CYTHON_METH_FASTCALL + switch (ml->ml_flags & (METH_VARARGS | METH_FASTCALL | METH_NOARGS | METH_O | METH_KEYWORDS | METH_METHOD)) { + case METH_NOARGS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_NOARGS; + break; + case METH_O: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_O; + break; + case METH_METHOD | METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD; + break; + case METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS; + break; + case METH_VARARGS | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = NULL; + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + Py_DECREF(op); + return NULL; + } +#endif + return (PyObject *) op; +} +static int +__Pyx_CyFunction_clear(__pyx_CyFunctionObject *m) +{ + Py_CLEAR(m->func_closure); +#if CYTHON_COMPILING_IN_LIMITED_API + Py_CLEAR(m->func); +#else + Py_CLEAR(((PyCFunctionObject*)m)->m_module); +#endif + Py_CLEAR(m->func_dict); + Py_CLEAR(m->func_name); + Py_CLEAR(m->func_qualname); + Py_CLEAR(m->func_doc); + Py_CLEAR(m->func_globals); + Py_CLEAR(m->func_code); +#if !CYTHON_COMPILING_IN_LIMITED_API +#if PY_VERSION_HEX < 0x030900B1 + Py_CLEAR(__Pyx_CyFunction_GetClassObj(m)); +#else + { + PyObject *cls = (PyObject*) ((PyCMethodObject *) (m))->mm_class; + ((PyCMethodObject *) (m))->mm_class = NULL; + Py_XDECREF(cls); + } +#endif +#endif + Py_CLEAR(m->defaults_tuple); + Py_CLEAR(m->defaults_kwdict); + Py_CLEAR(m->func_annotations); + Py_CLEAR(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_XDECREF(pydefaults[i]); + PyObject_Free(m->defaults); + m->defaults = NULL; + } + return 0; +} +static void __Pyx__CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + if (__Pyx_CyFunction_weakreflist(m) != NULL) + PyObject_ClearWeakRefs((PyObject *) m); + __Pyx_CyFunction_clear(m); + __Pyx_PyHeapTypeObject_GC_Del(m); +} +static void __Pyx_CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + PyObject_GC_UnTrack(m); + __Pyx__CyFunction_dealloc(m); +} +static int __Pyx_CyFunction_traverse(__pyx_CyFunctionObject *m, visitproc visit, void *arg) +{ + Py_VISIT(m->func_closure); +#if CYTHON_COMPILING_IN_LIMITED_API + Py_VISIT(m->func); +#else + Py_VISIT(((PyCFunctionObject*)m)->m_module); +#endif + Py_VISIT(m->func_dict); + Py_VISIT(m->func_name); + Py_VISIT(m->func_qualname); + Py_VISIT(m->func_doc); + Py_VISIT(m->func_globals); + Py_VISIT(m->func_code); +#if !CYTHON_COMPILING_IN_LIMITED_API + Py_VISIT(__Pyx_CyFunction_GetClassObj(m)); +#endif + Py_VISIT(m->defaults_tuple); + Py_VISIT(m->defaults_kwdict); + Py_VISIT(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_VISIT(pydefaults[i]); + } + return 0; +} +static PyObject* +__Pyx_CyFunction_repr(__pyx_CyFunctionObject *op) +{ +#if PY_MAJOR_VERSION >= 3 + return PyUnicode_FromFormat("", + op->func_qualname, (void *)op); +#else + return PyString_FromFormat("", + PyString_AsString(op->func_qualname), (void *)op); +#endif +} +static PyObject * __Pyx_CyFunction_CallMethod(PyObject *func, PyObject *self, PyObject *arg, PyObject *kw) { +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *f = ((__pyx_CyFunctionObject*)func)->func; + PyObject *py_name = NULL; + PyCFunction meth; + int flags; + meth = PyCFunction_GetFunction(f); + if (unlikely(!meth)) return NULL; + flags = PyCFunction_GetFlags(f); + if (unlikely(flags < 0)) return NULL; +#else + PyCFunctionObject* f = (PyCFunctionObject*)func; + PyCFunction meth = f->m_ml->ml_meth; + int flags = f->m_ml->ml_flags; +#endif + Py_ssize_t size; + switch (flags & (METH_VARARGS | METH_KEYWORDS | METH_NOARGS | METH_O)) { + case METH_VARARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) + return (*meth)(self, arg); + break; + case METH_VARARGS | METH_KEYWORDS: + return (*(PyCFunctionWithKeywords)(void*)meth)(self, arg, kw); + case METH_NOARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { +#if CYTHON_ASSUME_SAFE_MACROS + size = PyTuple_GET_SIZE(arg); +#else + size = PyTuple_Size(arg); + if (unlikely(size < 0)) return NULL; +#endif + if (likely(size == 0)) + return (*meth)(self, NULL); +#if CYTHON_COMPILING_IN_LIMITED_API + py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); + if (!py_name) return NULL; + PyErr_Format(PyExc_TypeError, + "%.200S() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + py_name, size); + Py_DECREF(py_name); +#else + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); +#endif + return NULL; + } + break; + case METH_O: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { +#if CYTHON_ASSUME_SAFE_MACROS + size = PyTuple_GET_SIZE(arg); +#else + size = PyTuple_Size(arg); + if (unlikely(size < 0)) return NULL; +#endif + if (likely(size == 1)) { + PyObject *result, *arg0; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + arg0 = PyTuple_GET_ITEM(arg, 0); + #else + arg0 = __Pyx_PySequence_ITEM(arg, 0); if (unlikely(!arg0)) return NULL; + #endif + result = (*meth)(self, arg0); + #if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(arg0); + #endif + return result; + } +#if CYTHON_COMPILING_IN_LIMITED_API + py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); + if (!py_name) return NULL; + PyErr_Format(PyExc_TypeError, + "%.200S() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + py_name, size); + Py_DECREF(py_name); +#else + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); +#endif + return NULL; + } + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + return NULL; + } +#if CYTHON_COMPILING_IN_LIMITED_API + py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); + if (!py_name) return NULL; + PyErr_Format(PyExc_TypeError, "%.200S() takes no keyword arguments", + py_name); + Py_DECREF(py_name); +#else + PyErr_Format(PyExc_TypeError, "%.200s() takes no keyword arguments", + f->m_ml->ml_name); +#endif + return NULL; +} +static CYTHON_INLINE PyObject *__Pyx_CyFunction_Call(PyObject *func, PyObject *arg, PyObject *kw) { + PyObject *self, *result; +#if CYTHON_COMPILING_IN_LIMITED_API + self = PyCFunction_GetSelf(((__pyx_CyFunctionObject*)func)->func); + if (unlikely(!self) && PyErr_Occurred()) return NULL; +#else + self = ((PyCFunctionObject*)func)->m_self; +#endif + result = __Pyx_CyFunction_CallMethod(func, self, arg, kw); + return result; +} +static PyObject *__Pyx_CyFunction_CallAsMethod(PyObject *func, PyObject *args, PyObject *kw) { + PyObject *result; + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *) func; +#if CYTHON_METH_FASTCALL + __pyx_vectorcallfunc vc = __Pyx_CyFunction_func_vectorcall(cyfunc); + if (vc) { +#if CYTHON_ASSUME_SAFE_MACROS + return __Pyx_PyVectorcall_FastCallDict(func, vc, &PyTuple_GET_ITEM(args, 0), (size_t)PyTuple_GET_SIZE(args), kw); +#else + (void) &__Pyx_PyVectorcall_FastCallDict; + return PyVectorcall_Call(func, args, kw); +#endif + } +#endif + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + Py_ssize_t argc; + PyObject *new_args; + PyObject *self; +#if CYTHON_ASSUME_SAFE_MACROS + argc = PyTuple_GET_SIZE(args); +#else + argc = PyTuple_Size(args); + if (unlikely(!argc) < 0) return NULL; +#endif + new_args = PyTuple_GetSlice(args, 1, argc); + if (unlikely(!new_args)) + return NULL; + self = PyTuple_GetItem(args, 0); + if (unlikely(!self)) { + Py_DECREF(new_args); +#if PY_MAJOR_VERSION > 2 + PyErr_Format(PyExc_TypeError, + "unbound method %.200S() needs an argument", + cyfunc->func_qualname); +#else + PyErr_SetString(PyExc_TypeError, + "unbound method needs an argument"); +#endif + return NULL; + } + result = __Pyx_CyFunction_CallMethod(func, self, new_args, kw); + Py_DECREF(new_args); + } else { + result = __Pyx_CyFunction_Call(func, args, kw); + } + return result; +} +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE int __Pyx_CyFunction_Vectorcall_CheckArgs(__pyx_CyFunctionObject *cyfunc, Py_ssize_t nargs, PyObject *kwnames) +{ + int ret = 0; + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + if (unlikely(nargs < 1)) { + PyErr_Format(PyExc_TypeError, "%.200s() needs an argument", + ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + ret = 1; + } + if (unlikely(kwnames) && unlikely(PyTuple_GET_SIZE(kwnames))) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no keyword arguments", ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + return ret; +} +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 0)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, NULL); +} +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 1)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, args[0]); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((_PyCFunctionFastWithKeywords)(void(*)(void))def->ml_meth)(self, args, nargs, kwnames); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; + PyTypeObject *cls = (PyTypeObject *) __Pyx_CyFunction_GetClassObj(cyfunc); +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((__Pyx_PyCMethod)(void(*)(void))def->ml_meth)(self, cls, args, (size_t)nargs, kwnames); +} +#endif +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_CyFunctionType_slots[] = { + {Py_tp_dealloc, (void *)__Pyx_CyFunction_dealloc}, + {Py_tp_repr, (void *)__Pyx_CyFunction_repr}, + {Py_tp_call, (void *)__Pyx_CyFunction_CallAsMethod}, + {Py_tp_traverse, (void *)__Pyx_CyFunction_traverse}, + {Py_tp_clear, (void *)__Pyx_CyFunction_clear}, + {Py_tp_methods, (void *)__pyx_CyFunction_methods}, + {Py_tp_members, (void *)__pyx_CyFunction_members}, + {Py_tp_getset, (void *)__pyx_CyFunction_getsets}, + {Py_tp_descr_get, (void *)__Pyx_PyMethod_New}, + {0, 0}, +}; +static PyType_Spec __pyx_CyFunctionType_spec = { + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#if (defined(_Py_TPFLAGS_HAVE_VECTORCALL) && CYTHON_METH_FASTCALL) + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + __pyx_CyFunctionType_slots +}; +#else +static PyTypeObject __pyx_CyFunctionType_type = { + PyVarObject_HEAD_INIT(0, 0) + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, + (destructor) __Pyx_CyFunction_dealloc, +#if !CYTHON_METH_FASTCALL + 0, +#elif CYTHON_BACKPORT_VECTORCALL + (printfunc)offsetof(__pyx_CyFunctionObject, func_vectorcall), +#else + offsetof(PyCFunctionObject, vectorcall), +#endif + 0, + 0, +#if PY_MAJOR_VERSION < 3 + 0, +#else + 0, +#endif + (reprfunc) __Pyx_CyFunction_repr, + 0, + 0, + 0, + 0, + __Pyx_CyFunction_CallAsMethod, + 0, + 0, + 0, + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#if defined(_Py_TPFLAGS_HAVE_VECTORCALL) && CYTHON_METH_FASTCALL + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + 0, + (traverseproc) __Pyx_CyFunction_traverse, + (inquiry) __Pyx_CyFunction_clear, + 0, +#if PY_VERSION_HEX < 0x030500A0 + offsetof(__pyx_CyFunctionObject, func_weakreflist), +#else + offsetof(PyCFunctionObject, m_weakreflist), +#endif + 0, + 0, + __pyx_CyFunction_methods, + __pyx_CyFunction_members, + __pyx_CyFunction_getsets, + 0, + 0, + __Pyx_PyMethod_New, + 0, + offsetof(__pyx_CyFunctionObject, func_dict), + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, +#if PY_VERSION_HEX >= 0x030400a1 + 0, +#endif +#if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, +#endif +#if __PYX_NEED_TP_PRINT_SLOT + 0, +#endif +#if PY_VERSION_HEX >= 0x030C0000 + 0, +#endif +#if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, +#endif +}; +#endif +static int __pyx_CyFunction_init(PyObject *module) { +#if CYTHON_USE_TYPE_SPECS + __pyx_CyFunctionType = __Pyx_FetchCommonTypeFromSpec(module, &__pyx_CyFunctionType_spec, NULL); +#else + CYTHON_UNUSED_VAR(module); + __pyx_CyFunctionType = __Pyx_FetchCommonType(&__pyx_CyFunctionType_type); +#endif + if (unlikely(__pyx_CyFunctionType == NULL)) { + return -1; + } + return 0; +} +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *func, size_t size, int pyobjects) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults = PyObject_Malloc(size); + if (unlikely(!m->defaults)) + return PyErr_NoMemory(); + memset(m->defaults, 0, size); + m->defaults_pyobjects = pyobjects; + m->defaults_size = size; + return m->defaults; +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *func, PyObject *tuple) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_tuple = tuple; + Py_INCREF(tuple); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_kwdict = dict; + Py_INCREF(dict); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->func_annotations = dict; + Py_INCREF(dict); +} + +/* CythonFunction */ + static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { + PyObject *op = __Pyx_CyFunction_Init( + PyObject_GC_New(__pyx_CyFunctionObject, __pyx_CyFunctionType), + ml, flags, qualname, closure, module, globals, code + ); + if (likely(op)) { + PyObject_GC_Track(op); + } + return op; +} + +/* IterFinish */ + static CYTHON_INLINE int __Pyx_IterFinish(void) { + PyObject* exc_type; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + exc_type = __Pyx_PyErr_CurrentExceptionType(); + if (unlikely(exc_type)) { + if (unlikely(!__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) + return -1; + __Pyx_PyErr_Clear(); + return 0; + } + return 0; +} + +/* PyObjectCallNoArg */ + static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func) { + PyObject *arg[2] = {NULL, NULL}; + return __Pyx_PyObject_FastCall(func, arg + 1, 0 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* PyObjectGetMethod */ + static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method) { + PyObject *attr; +#if CYTHON_UNPACK_METHODS && CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_PYTYPE_LOOKUP + __Pyx_TypeName type_name; + PyTypeObject *tp = Py_TYPE(obj); + PyObject *descr; + descrgetfunc f = NULL; + PyObject **dictptr, *dict; + int meth_found = 0; + assert (*method == NULL); + if (unlikely(tp->tp_getattro != PyObject_GenericGetAttr)) { + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; + } + if (unlikely(tp->tp_dict == NULL) && unlikely(PyType_Ready(tp) < 0)) { + return 0; + } + descr = _PyType_Lookup(tp, name); + if (likely(descr != NULL)) { + Py_INCREF(descr); +#if defined(Py_TPFLAGS_METHOD_DESCRIPTOR) && Py_TPFLAGS_METHOD_DESCRIPTOR + if (__Pyx_PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_METHOD_DESCRIPTOR)) +#elif PY_MAJOR_VERSION >= 3 + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type))) + #endif +#else + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr))) + #endif +#endif + { + meth_found = 1; + } else { + f = Py_TYPE(descr)->tp_descr_get; + if (f != NULL && PyDescr_IsData(descr)) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + } + } + dictptr = _PyObject_GetDictPtr(obj); + if (dictptr != NULL && (dict = *dictptr) != NULL) { + Py_INCREF(dict); + attr = __Pyx_PyDict_GetItemStr(dict, name); + if (attr != NULL) { + Py_INCREF(attr); + Py_DECREF(dict); + Py_XDECREF(descr); + goto try_unpack; + } + Py_DECREF(dict); + } + if (meth_found) { + *method = descr; + return 1; + } + if (f != NULL) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + if (likely(descr != NULL)) { + *method = descr; + return 0; + } + type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return 0; +#else + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; +#endif +try_unpack: +#if CYTHON_UNPACK_METHODS + if (likely(attr) && PyMethod_Check(attr) && likely(PyMethod_GET_SELF(attr) == obj)) { + PyObject *function = PyMethod_GET_FUNCTION(attr); + Py_INCREF(function); + Py_DECREF(attr); + *method = function; + return 1; + } +#endif + *method = attr; + return 0; +} + +/* PyObjectCallMethod0 */ + static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name) { + PyObject *method = NULL, *result = NULL; + int is_method = __Pyx_PyObject_GetMethod(obj, method_name, &method); + if (likely(is_method)) { + result = __Pyx_PyObject_CallOneArg(method, obj); + Py_DECREF(method); + return result; + } + if (unlikely(!method)) goto bad; + result = __Pyx_PyObject_CallNoArg(method); + Py_DECREF(method); +bad: + return result; +} + +/* UnpackItemEndCheck */ + static int __Pyx_IternextUnpackEndCheck(PyObject *retval, Py_ssize_t expected) { + if (unlikely(retval)) { + Py_DECREF(retval); + __Pyx_RaiseTooManyValuesError(expected); + return -1; + } + return __Pyx_IterFinish(); +} + +/* UnpackTupleError */ + static void __Pyx_UnpackTupleError(PyObject *t, Py_ssize_t index) { + if (t == Py_None) { + __Pyx_RaiseNoneNotIterableError(); + } else if (PyTuple_GET_SIZE(t) < index) { + __Pyx_RaiseNeedMoreValuesError(PyTuple_GET_SIZE(t)); + } else { + __Pyx_RaiseTooManyValuesError(index); + } +} + +/* UnpackTuple2 */ + static CYTHON_INLINE int __Pyx_unpack_tuple2_exact( + PyObject* tuple, PyObject** pvalue1, PyObject** pvalue2, int decref_tuple) { + PyObject *value1 = NULL, *value2 = NULL; +#if CYTHON_COMPILING_IN_PYPY + value1 = PySequence_ITEM(tuple, 0); if (unlikely(!value1)) goto bad; + value2 = PySequence_ITEM(tuple, 1); if (unlikely(!value2)) goto bad; +#else + value1 = PyTuple_GET_ITEM(tuple, 0); Py_INCREF(value1); + value2 = PyTuple_GET_ITEM(tuple, 1); Py_INCREF(value2); +#endif + if (decref_tuple) { + Py_DECREF(tuple); + } + *pvalue1 = value1; + *pvalue2 = value2; + return 0; +#if CYTHON_COMPILING_IN_PYPY +bad: + Py_XDECREF(value1); + Py_XDECREF(value2); + if (decref_tuple) { Py_XDECREF(tuple); } + return -1; +#endif +} +static int __Pyx_unpack_tuple2_generic(PyObject* tuple, PyObject** pvalue1, PyObject** pvalue2, + int has_known_size, int decref_tuple) { + Py_ssize_t index; + PyObject *value1 = NULL, *value2 = NULL, *iter = NULL; + iternextfunc iternext; + iter = PyObject_GetIter(tuple); + if (unlikely(!iter)) goto bad; + if (decref_tuple) { Py_DECREF(tuple); tuple = NULL; } + iternext = __Pyx_PyObject_GetIterNextFunc(iter); + value1 = iternext(iter); if (unlikely(!value1)) { index = 0; goto unpacking_failed; } + value2 = iternext(iter); if (unlikely(!value2)) { index = 1; goto unpacking_failed; } + if (!has_known_size && unlikely(__Pyx_IternextUnpackEndCheck(iternext(iter), 2))) goto bad; + Py_DECREF(iter); + *pvalue1 = value1; + *pvalue2 = value2; + return 0; +unpacking_failed: + if (!has_known_size && __Pyx_IterFinish() == 0) + __Pyx_RaiseNeedMoreValuesError(index); +bad: + Py_XDECREF(iter); + Py_XDECREF(value1); + Py_XDECREF(value2); + if (decref_tuple) { Py_XDECREF(tuple); } + return -1; +} + +/* dict_iter */ + #if CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 +#include +#endif +static CYTHON_INLINE PyObject* __Pyx_dict_iterator(PyObject* iterable, int is_dict, PyObject* method_name, + Py_ssize_t* p_orig_length, int* p_source_is_dict) { + is_dict = is_dict || likely(PyDict_CheckExact(iterable)); + *p_source_is_dict = is_dict; + if (is_dict) { +#if !CYTHON_COMPILING_IN_PYPY + *p_orig_length = PyDict_Size(iterable); + Py_INCREF(iterable); + return iterable; +#elif PY_MAJOR_VERSION >= 3 + static PyObject *py_items = NULL, *py_keys = NULL, *py_values = NULL; + PyObject **pp = NULL; + if (method_name) { + const char *name = PyUnicode_AsUTF8(method_name); + if (strcmp(name, "iteritems") == 0) pp = &py_items; + else if (strcmp(name, "iterkeys") == 0) pp = &py_keys; + else if (strcmp(name, "itervalues") == 0) pp = &py_values; + if (pp) { + if (!*pp) { + *pp = PyUnicode_FromString(name + 4); + if (!*pp) + return NULL; + } + method_name = *pp; + } + } +#endif + } + *p_orig_length = 0; + if (method_name) { + PyObject* iter; + iterable = __Pyx_PyObject_CallMethod0(iterable, method_name); + if (!iterable) + return NULL; +#if !CYTHON_COMPILING_IN_PYPY + if (PyTuple_CheckExact(iterable) || PyList_CheckExact(iterable)) + return iterable; +#endif + iter = PyObject_GetIter(iterable); + Py_DECREF(iterable); + return iter; + } + return PyObject_GetIter(iterable); +} +static CYTHON_INLINE int __Pyx_dict_iter_next( + PyObject* iter_obj, CYTHON_NCP_UNUSED Py_ssize_t orig_length, CYTHON_NCP_UNUSED Py_ssize_t* ppos, + PyObject** pkey, PyObject** pvalue, PyObject** pitem, int source_is_dict) { + PyObject* next_item; +#if !CYTHON_COMPILING_IN_PYPY + if (source_is_dict) { + PyObject *key, *value; + if (unlikely(orig_length != PyDict_Size(iter_obj))) { + PyErr_SetString(PyExc_RuntimeError, "dictionary changed size during iteration"); + return -1; + } + if (unlikely(!PyDict_Next(iter_obj, ppos, &key, &value))) { + return 0; + } + if (pitem) { + PyObject* tuple = PyTuple_New(2); + if (unlikely(!tuple)) { + return -1; + } + Py_INCREF(key); + Py_INCREF(value); + PyTuple_SET_ITEM(tuple, 0, key); + PyTuple_SET_ITEM(tuple, 1, value); + *pitem = tuple; + } else { + if (pkey) { + Py_INCREF(key); + *pkey = key; + } + if (pvalue) { + Py_INCREF(value); + *pvalue = value; + } + } + return 1; + } else if (PyTuple_CheckExact(iter_obj)) { + Py_ssize_t pos = *ppos; + if (unlikely(pos >= PyTuple_GET_SIZE(iter_obj))) return 0; + *ppos = pos + 1; + next_item = PyTuple_GET_ITEM(iter_obj, pos); + Py_INCREF(next_item); + } else if (PyList_CheckExact(iter_obj)) { + Py_ssize_t pos = *ppos; + if (unlikely(pos >= PyList_GET_SIZE(iter_obj))) return 0; + *ppos = pos + 1; + next_item = PyList_GET_ITEM(iter_obj, pos); + Py_INCREF(next_item); + } else +#endif + { + next_item = PyIter_Next(iter_obj); + if (unlikely(!next_item)) { + return __Pyx_IterFinish(); + } + } + if (pitem) { + *pitem = next_item; + } else if (pkey && pvalue) { + if (__Pyx_unpack_tuple2(next_item, pkey, pvalue, source_is_dict, source_is_dict, 1)) + return -1; + } else if (pkey) { + *pkey = next_item; + } else { + *pvalue = next_item; + } + return 1; +} + +/* PyIntBinop */ + #if !CYTHON_COMPILING_IN_PYPY +static PyObject* __Pyx_PyInt_AddObjC(PyObject *op1, PyObject *op2, long intval, int inplace, int zerodivision_check) { + CYTHON_MAYBE_UNUSED_VAR(intval); + CYTHON_MAYBE_UNUSED_VAR(inplace); + CYTHON_UNUSED_VAR(zerodivision_check); + #if PY_MAJOR_VERSION < 3 + if (likely(PyInt_CheckExact(op1))) { + const long b = intval; + long x; + long a = PyInt_AS_LONG(op1); + + x = (long)((unsigned long)a + (unsigned long)b); + if (likely((x^a) >= 0 || (x^b) >= 0)) + return PyInt_FromLong(x); + return PyLong_Type.tp_as_number->nb_add(op1, op2); + } + #endif + #if CYTHON_USE_PYLONG_INTERNALS + if (likely(PyLong_CheckExact(op1))) { + const long b = intval; + long a, x; +#ifdef HAVE_LONG_LONG + const PY_LONG_LONG llb = intval; + PY_LONG_LONG lla, llx; +#endif + if (unlikely(__Pyx_PyLong_IsZero(op1))) { + return __Pyx_NewRef(op2); + } + if (likely(__Pyx_PyLong_IsCompact(op1))) { + a = __Pyx_PyLong_CompactValue(op1); + } else { + const digit* digits = __Pyx_PyLong_Digits(op1); + const Py_ssize_t size = __Pyx_PyLong_SignedDigitCount(op1); + switch (size) { + case -2: + if (8 * sizeof(long) - 1 > 2 * PyLong_SHIFT) { + a = -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0])); + break; + #ifdef HAVE_LONG_LONG + } else if (8 * sizeof(PY_LONG_LONG) - 1 > 2 * PyLong_SHIFT) { + lla = -(PY_LONG_LONG) (((((unsigned PY_LONG_LONG)digits[1]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[0])); + goto long_long; + #endif + } + CYTHON_FALLTHROUGH; + case 2: + if (8 * sizeof(long) - 1 > 2 * PyLong_SHIFT) { + a = (long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0])); + break; + #ifdef HAVE_LONG_LONG + } else if (8 * sizeof(PY_LONG_LONG) - 1 > 2 * PyLong_SHIFT) { + lla = (PY_LONG_LONG) (((((unsigned PY_LONG_LONG)digits[1]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[0])); + goto long_long; + #endif + } + CYTHON_FALLTHROUGH; + case -3: + if (8 * sizeof(long) - 1 > 3 * PyLong_SHIFT) { + a = -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0])); + break; + #ifdef HAVE_LONG_LONG + } else if (8 * sizeof(PY_LONG_LONG) - 1 > 3 * PyLong_SHIFT) { + lla = -(PY_LONG_LONG) (((((((unsigned PY_LONG_LONG)digits[2]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[1]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[0])); + goto long_long; + #endif + } + CYTHON_FALLTHROUGH; + case 3: + if (8 * sizeof(long) - 1 > 3 * PyLong_SHIFT) { + a = (long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0])); + break; + #ifdef HAVE_LONG_LONG + } else if (8 * sizeof(PY_LONG_LONG) - 1 > 3 * PyLong_SHIFT) { + lla = (PY_LONG_LONG) (((((((unsigned PY_LONG_LONG)digits[2]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[1]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[0])); + goto long_long; + #endif + } + CYTHON_FALLTHROUGH; + case -4: + if (8 * sizeof(long) - 1 > 4 * PyLong_SHIFT) { + a = -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0])); + break; + #ifdef HAVE_LONG_LONG + } else if (8 * sizeof(PY_LONG_LONG) - 1 > 4 * PyLong_SHIFT) { + lla = -(PY_LONG_LONG) (((((((((unsigned PY_LONG_LONG)digits[3]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[2]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[1]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[0])); + goto long_long; + #endif + } + CYTHON_FALLTHROUGH; + case 4: + if (8 * sizeof(long) - 1 > 4 * PyLong_SHIFT) { + a = (long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0])); + break; + #ifdef HAVE_LONG_LONG + } else if (8 * sizeof(PY_LONG_LONG) - 1 > 4 * PyLong_SHIFT) { + lla = (PY_LONG_LONG) (((((((((unsigned PY_LONG_LONG)digits[3]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[2]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[1]) << PyLong_SHIFT) | (unsigned PY_LONG_LONG)digits[0])); + goto long_long; + #endif + } + CYTHON_FALLTHROUGH; + default: return PyLong_Type.tp_as_number->nb_add(op1, op2); + } + } + x = a + b; + return PyLong_FromLong(x); +#ifdef HAVE_LONG_LONG + long_long: + llx = lla + llb; + return PyLong_FromLongLong(llx); +#endif + + + } + #endif + if (PyFloat_CheckExact(op1)) { + const long b = intval; +#if CYTHON_COMPILING_IN_LIMITED_API + double a = __pyx_PyFloat_AsDouble(op1); +#else + double a = PyFloat_AS_DOUBLE(op1); +#endif + double result; + + PyFPE_START_PROTECT("add", return NULL) + result = ((double)a) + (double)b; + PyFPE_END_PROTECT(result) + return PyFloat_FromDouble(result); + } + return (inplace ? PyNumber_InPlaceAdd : PyNumber_Add)(op1, op2); +} +#endif + +/* BufferIndexError */ + static void __Pyx_RaiseBufferIndexError(int axis) { + PyErr_Format(PyExc_IndexError, + "Out of bounds on buffer access (axis %d)", axis); +} + +/* PyUnicode_Unicode */ + static CYTHON_INLINE PyObject* __Pyx_PyUnicode_Unicode(PyObject *obj) { + if (unlikely(obj == Py_None)) + obj = __pyx_kp_u_None; + return __Pyx_NewRef(obj); +} + +/* PyObject_GenericGetAttrNoDict */ + #if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject *__Pyx_RaiseGenericGetAttributeError(PyTypeObject *tp, PyObject *attr_name) { + __Pyx_TypeName type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, attr_name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(attr_name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name) { + PyObject *descr; + PyTypeObject *tp = Py_TYPE(obj); + if (unlikely(!PyString_Check(attr_name))) { + return PyObject_GenericGetAttr(obj, attr_name); + } + assert(!tp->tp_dictoffset); + descr = _PyType_Lookup(tp, attr_name); + if (unlikely(!descr)) { + return __Pyx_RaiseGenericGetAttributeError(tp, attr_name); + } + Py_INCREF(descr); + #if PY_MAJOR_VERSION < 3 + if (likely(PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_HAVE_CLASS))) + #endif + { + descrgetfunc f = Py_TYPE(descr)->tp_descr_get; + if (unlikely(f)) { + PyObject *res = f(descr, obj, (PyObject *)tp); + Py_DECREF(descr); + return res; + } + } + return descr; +} +#endif + +/* PyObject_GenericGetAttr */ + #if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name) { + if (unlikely(Py_TYPE(obj)->tp_dictoffset)) { + return PyObject_GenericGetAttr(obj, attr_name); + } + return __Pyx_PyObject_GenericGetAttrNoDict(obj, attr_name); +} +#endif + +/* ValidateBasesTuple */ + #if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases) { + Py_ssize_t i, n; +#if CYTHON_ASSUME_SAFE_MACROS + n = PyTuple_GET_SIZE(bases); +#else + n = PyTuple_Size(bases); + if (n < 0) return -1; +#endif + for (i = 1; i < n; i++) + { +#if CYTHON_AVOID_BORROWED_REFS + PyObject *b0 = PySequence_GetItem(bases, i); + if (!b0) return -1; +#elif CYTHON_ASSUME_SAFE_MACROS + PyObject *b0 = PyTuple_GET_ITEM(bases, i); +#else + PyObject *b0 = PyTuple_GetItem(bases, i); + if (!b0) return -1; +#endif + PyTypeObject *b; +#if PY_MAJOR_VERSION < 3 + if (PyClass_Check(b0)) + { + PyErr_Format(PyExc_TypeError, "base class '%.200s' is an old-style class", + PyString_AS_STRING(((PyClassObject*)b0)->cl_name)); +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + return -1; + } +#endif + b = (PyTypeObject*) b0; + if (!__Pyx_PyType_HasFeature(b, Py_TPFLAGS_HEAPTYPE)) + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "base class '" __Pyx_FMT_TYPENAME "' is not a heap type", b_name); + __Pyx_DECREF_TypeName(b_name); +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + return -1; + } + if (dictoffset == 0) + { + Py_ssize_t b_dictoffset = 0; +#if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + b_dictoffset = b->tp_dictoffset; +#else + PyObject *py_b_dictoffset = PyObject_GetAttrString((PyObject*)b, "__dictoffset__"); + if (!py_b_dictoffset) goto dictoffset_return; + b_dictoffset = PyLong_AsSsize_t(py_b_dictoffset); + Py_DECREF(py_b_dictoffset); + if (b_dictoffset == -1 && PyErr_Occurred()) goto dictoffset_return; +#endif + if (b_dictoffset) { + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "extension type '%.200s' has no __dict__ slot, " + "but base type '" __Pyx_FMT_TYPENAME "' has: " + "either add 'cdef dict __dict__' to the extension type " + "or add '__slots__ = [...]' to the base type", + type_name, b_name); + __Pyx_DECREF_TypeName(b_name); + } +#if !(CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY) + dictoffset_return: +#endif +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + return -1; + } + } +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + } + return 0; +} +#endif + +/* PyType_Ready */ + static int __Pyx_PyType_Ready(PyTypeObject *t) { +#if CYTHON_USE_TYPE_SPECS || !(CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API) || defined(PYSTON_MAJOR_VERSION) + (void)__Pyx_PyObject_CallMethod0; +#if CYTHON_USE_TYPE_SPECS + (void)__Pyx_validate_bases_tuple; +#endif + return PyType_Ready(t); +#else + int r; + PyObject *bases = __Pyx_PyType_GetSlot(t, tp_bases, PyObject*); + if (bases && unlikely(__Pyx_validate_bases_tuple(t->tp_name, t->tp_dictoffset, bases) == -1)) + return -1; +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + { + int gc_was_enabled; + #if PY_VERSION_HEX >= 0x030A00b1 + gc_was_enabled = PyGC_Disable(); + (void)__Pyx_PyObject_CallMethod0; + #else + PyObject *ret, *py_status; + PyObject *gc = NULL; + #if PY_VERSION_HEX >= 0x030700a1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM+0 >= 0x07030400) + gc = PyImport_GetModule(__pyx_kp_u_gc); + #endif + if (unlikely(!gc)) gc = PyImport_Import(__pyx_kp_u_gc); + if (unlikely(!gc)) return -1; + py_status = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_isenabled); + if (unlikely(!py_status)) { + Py_DECREF(gc); + return -1; + } + gc_was_enabled = __Pyx_PyObject_IsTrue(py_status); + Py_DECREF(py_status); + if (gc_was_enabled > 0) { + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_disable); + if (unlikely(!ret)) { + Py_DECREF(gc); + return -1; + } + Py_DECREF(ret); + } else if (unlikely(gc_was_enabled == -1)) { + Py_DECREF(gc); + return -1; + } + #endif + t->tp_flags |= Py_TPFLAGS_HEAPTYPE; +#if PY_VERSION_HEX >= 0x030A0000 + t->tp_flags |= Py_TPFLAGS_IMMUTABLETYPE; +#endif +#else + (void)__Pyx_PyObject_CallMethod0; +#endif + r = PyType_Ready(t); +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + t->tp_flags &= ~Py_TPFLAGS_HEAPTYPE; + #if PY_VERSION_HEX >= 0x030A00b1 + if (gc_was_enabled) + PyGC_Enable(); + #else + if (gc_was_enabled) { + PyObject *tp, *v, *tb; + PyErr_Fetch(&tp, &v, &tb); + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_enable); + if (likely(ret || r == -1)) { + Py_XDECREF(ret); + PyErr_Restore(tp, v, tb); + } else { + Py_XDECREF(tp); + Py_XDECREF(v); + Py_XDECREF(tb); + r = -1; + } + } + Py_DECREF(gc); + #endif + } +#endif + return r; +#endif +} + +/* SetupReduce */ + #if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce_is_named(PyObject* meth, PyObject* name) { + int ret; + PyObject *name_attr; + name_attr = __Pyx_PyObject_GetAttrStrNoError(meth, __pyx_n_s_name_2); + if (likely(name_attr)) { + ret = PyObject_RichCompareBool(name_attr, name, Py_EQ); + } else { + ret = -1; + } + if (unlikely(ret < 0)) { + PyErr_Clear(); + ret = 0; + } + Py_XDECREF(name_attr); + return ret; +} +static int __Pyx_setup_reduce(PyObject* type_obj) { + int ret = 0; + PyObject *object_reduce = NULL; + PyObject *object_getstate = NULL; + PyObject *object_reduce_ex = NULL; + PyObject *reduce = NULL; + PyObject *reduce_ex = NULL; + PyObject *reduce_cython = NULL; + PyObject *setstate = NULL; + PyObject *setstate_cython = NULL; + PyObject *getstate = NULL; +#if CYTHON_USE_PYTYPE_LOOKUP + getstate = _PyType_Lookup((PyTypeObject*)type_obj, __pyx_n_s_getstate); +#else + getstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_getstate); + if (!getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (getstate) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_getstate = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_getstate); +#else + object_getstate = __Pyx_PyObject_GetAttrStrNoError((PyObject*)&PyBaseObject_Type, __pyx_n_s_getstate); + if (!object_getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (object_getstate != getstate) { + goto __PYX_GOOD; + } + } +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce_ex = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#else + object_reduce_ex = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#endif + reduce_ex = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce_ex); if (unlikely(!reduce_ex)) goto __PYX_BAD; + if (reduce_ex == object_reduce_ex) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#else + object_reduce = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#endif + reduce = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce); if (unlikely(!reduce)) goto __PYX_BAD; + if (reduce == object_reduce || __Pyx_setup_reduce_is_named(reduce, __pyx_n_s_reduce_cython)) { + reduce_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_reduce_cython); + if (likely(reduce_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce, reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (reduce == object_reduce || PyErr_Occurred()) { + goto __PYX_BAD; + } + setstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate); + if (!setstate) PyErr_Clear(); + if (!setstate || __Pyx_setup_reduce_is_named(setstate, __pyx_n_s_setstate_cython)) { + setstate_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate_cython); + if (likely(setstate_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate, setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (!setstate || PyErr_Occurred()) { + goto __PYX_BAD; + } + } + PyType_Modified((PyTypeObject*)type_obj); + } + } + goto __PYX_GOOD; +__PYX_BAD: + if (!PyErr_Occurred()) { + __Pyx_TypeName type_obj_name = + __Pyx_PyType_GetName((PyTypeObject*)type_obj); + PyErr_Format(PyExc_RuntimeError, + "Unable to initialize pickling for " __Pyx_FMT_TYPENAME, type_obj_name); + __Pyx_DECREF_TypeName(type_obj_name); + } + ret = -1; +__PYX_GOOD: +#if !CYTHON_USE_PYTYPE_LOOKUP + Py_XDECREF(object_reduce); + Py_XDECREF(object_reduce_ex); + Py_XDECREF(object_getstate); + Py_XDECREF(getstate); +#endif + Py_XDECREF(reduce); + Py_XDECREF(reduce_ex); + Py_XDECREF(reduce_cython); + Py_XDECREF(setstate); + Py_XDECREF(setstate_cython); + return ret; +} +#endif + +/* SetVTable */ + static int __Pyx_SetVtable(PyTypeObject *type, void *vtable) { + PyObject *ob = PyCapsule_New(vtable, 0, 0); + if (unlikely(!ob)) + goto bad; +#if CYTHON_COMPILING_IN_LIMITED_API + if (unlikely(PyObject_SetAttr((PyObject *) type, __pyx_n_s_pyx_vtable, ob) < 0)) +#else + if (unlikely(PyDict_SetItem(type->tp_dict, __pyx_n_s_pyx_vtable, ob) < 0)) +#endif + goto bad; + Py_DECREF(ob); + return 0; +bad: + Py_XDECREF(ob); + return -1; +} + +/* GetVTable */ + static void* __Pyx_GetVtable(PyTypeObject *type) { + void* ptr; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *ob = PyObject_GetAttr((PyObject *)type, __pyx_n_s_pyx_vtable); +#else + PyObject *ob = PyObject_GetItem(type->tp_dict, __pyx_n_s_pyx_vtable); +#endif + if (!ob) + goto bad; + ptr = PyCapsule_GetPointer(ob, 0); + if (!ptr && !PyErr_Occurred()) + PyErr_SetString(PyExc_RuntimeError, "invalid vtable found for imported type"); + Py_DECREF(ob); + return ptr; +bad: + Py_XDECREF(ob); + return NULL; +} + +/* MergeVTables */ + #if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_MergeVtables(PyTypeObject *type) { + int i; + void** base_vtables; + __Pyx_TypeName tp_base_name; + __Pyx_TypeName base_name; + void* unknown = (void*)-1; + PyObject* bases = type->tp_bases; + int base_depth = 0; + { + PyTypeObject* base = type->tp_base; + while (base) { + base_depth += 1; + base = base->tp_base; + } + } + base_vtables = (void**) malloc(sizeof(void*) * (size_t)(base_depth + 1)); + base_vtables[0] = unknown; + for (i = 1; i < PyTuple_GET_SIZE(bases); i++) { + void* base_vtable = __Pyx_GetVtable(((PyTypeObject*)PyTuple_GET_ITEM(bases, i))); + if (base_vtable != NULL) { + int j; + PyTypeObject* base = type->tp_base; + for (j = 0; j < base_depth; j++) { + if (base_vtables[j] == unknown) { + base_vtables[j] = __Pyx_GetVtable(base); + base_vtables[j + 1] = unknown; + } + if (base_vtables[j] == base_vtable) { + break; + } else if (base_vtables[j] == NULL) { + goto bad; + } + base = base->tp_base; + } + } + } + PyErr_Clear(); + free(base_vtables); + return 0; +bad: + tp_base_name = __Pyx_PyType_GetName(type->tp_base); + base_name = __Pyx_PyType_GetName((PyTypeObject*)PyTuple_GET_ITEM(bases, i)); + PyErr_Format(PyExc_TypeError, + "multiple bases have vtable conflict: '" __Pyx_FMT_TYPENAME "' and '" __Pyx_FMT_TYPENAME "'", tp_base_name, base_name); + __Pyx_DECREF_TypeName(tp_base_name); + __Pyx_DECREF_TypeName(base_name); + free(base_vtables); + return -1; +} +#endif + +/* TypeImport */ + #ifndef __PYX_HAVE_RT_ImportType_3_0_8 +#define __PYX_HAVE_RT_ImportType_3_0_8 +static PyTypeObject *__Pyx_ImportType_3_0_8(PyObject *module, const char *module_name, const char *class_name, + size_t size, size_t alignment, enum __Pyx_ImportType_CheckSize_3_0_8 check_size) +{ + PyObject *result = 0; + char warning[200]; + Py_ssize_t basicsize; + Py_ssize_t itemsize; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *py_basicsize; + PyObject *py_itemsize; +#endif + result = PyObject_GetAttrString(module, class_name); + if (!result) + goto bad; + if (!PyType_Check(result)) { + PyErr_Format(PyExc_TypeError, + "%.200s.%.200s is not a type object", + module_name, class_name); + goto bad; + } +#if !CYTHON_COMPILING_IN_LIMITED_API + basicsize = ((PyTypeObject *)result)->tp_basicsize; + itemsize = ((PyTypeObject *)result)->tp_itemsize; +#else + py_basicsize = PyObject_GetAttrString(result, "__basicsize__"); + if (!py_basicsize) + goto bad; + basicsize = PyLong_AsSsize_t(py_basicsize); + Py_DECREF(py_basicsize); + py_basicsize = 0; + if (basicsize == (Py_ssize_t)-1 && PyErr_Occurred()) + goto bad; + py_itemsize = PyObject_GetAttrString(result, "__itemsize__"); + if (!py_itemsize) + goto bad; + itemsize = PyLong_AsSsize_t(py_itemsize); + Py_DECREF(py_itemsize); + py_itemsize = 0; + if (itemsize == (Py_ssize_t)-1 && PyErr_Occurred()) + goto bad; +#endif + if (itemsize) { + if (size % alignment) { + alignment = size % alignment; + } + if (itemsize < (Py_ssize_t)alignment) + itemsize = (Py_ssize_t)alignment; + } + if ((size_t)(basicsize + itemsize) < size) { + PyErr_Format(PyExc_ValueError, + "%.200s.%.200s size changed, may indicate binary incompatibility. " + "Expected %zd from C header, got %zd from PyObject", + module_name, class_name, size, basicsize+itemsize); + goto bad; + } + if (check_size == __Pyx_ImportType_CheckSize_Error_3_0_8 && + ((size_t)basicsize > size || (size_t)(basicsize + itemsize) < size)) { + PyErr_Format(PyExc_ValueError, + "%.200s.%.200s size changed, may indicate binary incompatibility. " + "Expected %zd from C header, got %zd-%zd from PyObject", + module_name, class_name, size, basicsize, basicsize+itemsize); + goto bad; + } + else if (check_size == __Pyx_ImportType_CheckSize_Warn_3_0_8 && (size_t)basicsize > size) { + PyOS_snprintf(warning, sizeof(warning), + "%s.%s size changed, may indicate binary incompatibility. " + "Expected %zd from C header, got %zd from PyObject", + module_name, class_name, size, basicsize); + if (PyErr_WarnEx(NULL, warning, 0) < 0) goto bad; + } + return (PyTypeObject *)result; +bad: + Py_XDECREF(result); + return NULL; +} +#endif + +/* CLineInTraceback */ + #ifndef CYTHON_CLINE_IN_TRACEBACK +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line) { + PyObject *use_cline; + PyObject *ptype, *pvalue, *ptraceback; +#if CYTHON_COMPILING_IN_CPYTHON + PyObject **cython_runtime_dict; +#endif + CYTHON_MAYBE_UNUSED_VAR(tstate); + if (unlikely(!__pyx_cython_runtime)) { + return c_line; + } + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); +#if CYTHON_COMPILING_IN_CPYTHON + cython_runtime_dict = _PyObject_GetDictPtr(__pyx_cython_runtime); + if (likely(cython_runtime_dict)) { + __PYX_PY_DICT_LOOKUP_IF_MODIFIED( + use_cline, *cython_runtime_dict, + __Pyx_PyDict_GetItemStr(*cython_runtime_dict, __pyx_n_s_cline_in_traceback)) + } else +#endif + { + PyObject *use_cline_obj = __Pyx_PyObject_GetAttrStrNoError(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback); + if (use_cline_obj) { + use_cline = PyObject_Not(use_cline_obj) ? Py_False : Py_True; + Py_DECREF(use_cline_obj); + } else { + PyErr_Clear(); + use_cline = NULL; + } + } + if (!use_cline) { + c_line = 0; + (void) PyObject_SetAttr(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback, Py_False); + } + else if (use_cline == Py_False || (use_cline != Py_True && PyObject_Not(use_cline) != 0)) { + c_line = 0; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + return c_line; +} +#endif + +/* CodeObjectCache */ + #if !CYTHON_COMPILING_IN_LIMITED_API +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line) { + int start = 0, mid = 0, end = count - 1; + if (end >= 0 && code_line > entries[end].code_line) { + return count; + } + while (start < end) { + mid = start + (end - start) / 2; + if (code_line < entries[mid].code_line) { + end = mid; + } else if (code_line > entries[mid].code_line) { + start = mid + 1; + } else { + return mid; + } + } + if (code_line <= entries[mid].code_line) { + return mid; + } else { + return mid + 1; + } +} +static PyCodeObject *__pyx_find_code_object(int code_line) { + PyCodeObject* code_object; + int pos; + if (unlikely(!code_line) || unlikely(!__pyx_code_cache.entries)) { + return NULL; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if (unlikely(pos >= __pyx_code_cache.count) || unlikely(__pyx_code_cache.entries[pos].code_line != code_line)) { + return NULL; + } + code_object = __pyx_code_cache.entries[pos].code_object; + Py_INCREF(code_object); + return code_object; +} +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object) { + int pos, i; + __Pyx_CodeObjectCacheEntry* entries = __pyx_code_cache.entries; + if (unlikely(!code_line)) { + return; + } + if (unlikely(!entries)) { + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Malloc(64*sizeof(__Pyx_CodeObjectCacheEntry)); + if (likely(entries)) { + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = 64; + __pyx_code_cache.count = 1; + entries[0].code_line = code_line; + entries[0].code_object = code_object; + Py_INCREF(code_object); + } + return; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if ((pos < __pyx_code_cache.count) && unlikely(__pyx_code_cache.entries[pos].code_line == code_line)) { + PyCodeObject* tmp = entries[pos].code_object; + entries[pos].code_object = code_object; + Py_DECREF(tmp); + return; + } + if (__pyx_code_cache.count == __pyx_code_cache.max_count) { + int new_max = __pyx_code_cache.max_count + 64; + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Realloc( + __pyx_code_cache.entries, ((size_t)new_max) * sizeof(__Pyx_CodeObjectCacheEntry)); + if (unlikely(!entries)) { + return; + } + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = new_max; + } + for (i=__pyx_code_cache.count; i>pos; i--) { + entries[i] = entries[i-1]; + } + entries[pos].code_line = code_line; + entries[pos].code_object = code_object; + __pyx_code_cache.count++; + Py_INCREF(code_object); +} +#endif + +/* AddTraceback */ + #include "compile.h" +#include "frameobject.h" +#include "traceback.h" +#if PY_VERSION_HEX >= 0x030b00a6 && !CYTHON_COMPILING_IN_LIMITED_API + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static PyObject *__Pyx_PyCode_Replace_For_AddTraceback(PyObject *code, PyObject *scratch_dict, + PyObject *firstlineno, PyObject *name) { + PyObject *replace = NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "co_firstlineno", firstlineno))) return NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "co_name", name))) return NULL; + replace = PyObject_GetAttrString(code, "replace"); + if (likely(replace)) { + PyObject *result; + result = PyObject_Call(replace, __pyx_empty_tuple, scratch_dict); + Py_DECREF(replace); + return result; + } + PyErr_Clear(); + #if __PYX_LIMITED_VERSION_HEX < 0x030780000 + { + PyObject *compiled = NULL, *result = NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "code", code))) return NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "type", (PyObject*)(&PyType_Type)))) return NULL; + compiled = Py_CompileString( + "out = type(code)(\n" + " code.co_argcount, code.co_kwonlyargcount, code.co_nlocals, code.co_stacksize,\n" + " code.co_flags, code.co_code, code.co_consts, code.co_names,\n" + " code.co_varnames, code.co_filename, co_name, co_firstlineno,\n" + " code.co_lnotab)\n", "", Py_file_input); + if (!compiled) return NULL; + result = PyEval_EvalCode(compiled, scratch_dict, scratch_dict); + Py_DECREF(compiled); + if (!result) PyErr_Print(); + Py_DECREF(result); + result = PyDict_GetItemString(scratch_dict, "out"); + if (result) Py_INCREF(result); + return result; + } + #else + return NULL; + #endif +} +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + PyObject *code_object = NULL, *py_py_line = NULL, *py_funcname = NULL, *dict = NULL; + PyObject *replace = NULL, *getframe = NULL, *frame = NULL; + PyObject *exc_type, *exc_value, *exc_traceback; + int success = 0; + if (c_line) { + (void) __pyx_cfilenm; + (void) __Pyx_CLineForTraceback(__Pyx_PyThreadState_Current, c_line); + } + PyErr_Fetch(&exc_type, &exc_value, &exc_traceback); + code_object = Py_CompileString("_getframe()", filename, Py_eval_input); + if (unlikely(!code_object)) goto bad; + py_py_line = PyLong_FromLong(py_line); + if (unlikely(!py_py_line)) goto bad; + py_funcname = PyUnicode_FromString(funcname); + if (unlikely(!py_funcname)) goto bad; + dict = PyDict_New(); + if (unlikely(!dict)) goto bad; + { + PyObject *old_code_object = code_object; + code_object = __Pyx_PyCode_Replace_For_AddTraceback(code_object, dict, py_py_line, py_funcname); + Py_DECREF(old_code_object); + } + if (unlikely(!code_object)) goto bad; + getframe = PySys_GetObject("_getframe"); + if (unlikely(!getframe)) goto bad; + if (unlikely(PyDict_SetItemString(dict, "_getframe", getframe))) goto bad; + frame = PyEval_EvalCode(code_object, dict, dict); + if (unlikely(!frame) || frame == Py_None) goto bad; + success = 1; + bad: + PyErr_Restore(exc_type, exc_value, exc_traceback); + Py_XDECREF(code_object); + Py_XDECREF(py_py_line); + Py_XDECREF(py_funcname); + Py_XDECREF(dict); + Py_XDECREF(replace); + if (success) { + PyTraceBack_Here( + (struct _frame*)frame); + } + Py_XDECREF(frame); +} +#else +static PyCodeObject* __Pyx_CreateCodeObjectForTraceback( + const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = NULL; + PyObject *py_funcname = NULL; + #if PY_MAJOR_VERSION < 3 + PyObject *py_srcfile = NULL; + py_srcfile = PyString_FromString(filename); + if (!py_srcfile) goto bad; + #endif + if (c_line) { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + #else + py_funcname = PyUnicode_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + funcname = PyUnicode_AsUTF8(py_funcname); + if (!funcname) goto bad; + #endif + } + else { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromString(funcname); + if (!py_funcname) goto bad; + #endif + } + #if PY_MAJOR_VERSION < 3 + py_code = __Pyx_PyCode_New( + 0, + 0, + 0, + 0, + 0, + 0, + __pyx_empty_bytes, /*PyObject *code,*/ + __pyx_empty_tuple, /*PyObject *consts,*/ + __pyx_empty_tuple, /*PyObject *names,*/ + __pyx_empty_tuple, /*PyObject *varnames,*/ + __pyx_empty_tuple, /*PyObject *freevars,*/ + __pyx_empty_tuple, /*PyObject *cellvars,*/ + py_srcfile, /*PyObject *filename,*/ + py_funcname, /*PyObject *name,*/ + py_line, + __pyx_empty_bytes /*PyObject *lnotab*/ + ); + Py_DECREF(py_srcfile); + #else + py_code = PyCode_NewEmpty(filename, funcname, py_line); + #endif + Py_XDECREF(py_funcname); + return py_code; +bad: + Py_XDECREF(py_funcname); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_srcfile); + #endif + return NULL; +} +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = 0; + PyFrameObject *py_frame = 0; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject *ptype, *pvalue, *ptraceback; + if (c_line) { + c_line = __Pyx_CLineForTraceback(tstate, c_line); + } + py_code = __pyx_find_code_object(c_line ? -c_line : py_line); + if (!py_code) { + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); + py_code = __Pyx_CreateCodeObjectForTraceback( + funcname, c_line, py_line, filename); + if (!py_code) { + /* If the code object creation fails, then we should clear the + fetched exception references and propagate the new exception */ + Py_XDECREF(ptype); + Py_XDECREF(pvalue); + Py_XDECREF(ptraceback); + goto bad; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + __pyx_insert_code_object(c_line ? -c_line : py_line, py_code); + } + py_frame = PyFrame_New( + tstate, /*PyThreadState *tstate,*/ + py_code, /*PyCodeObject *code,*/ + __pyx_d, /*PyObject *globals,*/ + 0 /*PyObject *locals*/ + ); + if (!py_frame) goto bad; + __Pyx_PyFrame_SetLineNumber(py_frame, py_line); + PyTraceBack_Here(py_frame); +bad: + Py_XDECREF(py_code); + Py_XDECREF(py_frame); +} +#endif + +#if PY_MAJOR_VERSION < 3 +static int __Pyx_GetBuffer(PyObject *obj, Py_buffer *view, int flags) { + __Pyx_TypeName obj_type_name; + if (PyObject_CheckBuffer(obj)) return PyObject_GetBuffer(obj, view, flags); + if (__Pyx_TypeCheck(obj, __pyx_array_type)) return __pyx_array_getbuffer(obj, view, flags); + if (__Pyx_TypeCheck(obj, __pyx_memoryview_type)) return __pyx_memoryview_getbuffer(obj, view, flags); + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "'" __Pyx_FMT_TYPENAME "' does not have the buffer interface", + obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return -1; +} +static void __Pyx_ReleaseBuffer(Py_buffer *view) { + PyObject *obj = view->obj; + if (!obj) return; + if (PyObject_CheckBuffer(obj)) { + PyBuffer_Release(view); + return; + } + if ((0)) {} + view->obj = NULL; + Py_DECREF(obj); +} +#endif + + + /* MemviewSliceIsContig */ + static int +__pyx_memviewslice_is_contig(const __Pyx_memviewslice mvs, char order, int ndim) +{ + int i, index, step, start; + Py_ssize_t itemsize = mvs.memview->view.itemsize; + if (order == 'F') { + step = 1; + start = 0; + } else { + step = -1; + start = ndim - 1; + } + for (i = 0; i < ndim; i++) { + index = start + step * i; + if (mvs.suboffsets[index] >= 0 || mvs.strides[index] != itemsize) + return 0; + itemsize *= mvs.shape[index]; + } + return 1; +} + +/* OverlappingSlices */ + static void +__pyx_get_array_memory_extents(__Pyx_memviewslice *slice, + void **out_start, void **out_end, + int ndim, size_t itemsize) +{ + char *start, *end; + int i; + start = end = slice->data; + for (i = 0; i < ndim; i++) { + Py_ssize_t stride = slice->strides[i]; + Py_ssize_t extent = slice->shape[i]; + if (extent == 0) { + *out_start = *out_end = start; + return; + } else { + if (stride > 0) + end += stride * (extent - 1); + else + start += stride * (extent - 1); + } + } + *out_start = start; + *out_end = end + itemsize; +} +static int +__pyx_slices_overlap(__Pyx_memviewslice *slice1, + __Pyx_memviewslice *slice2, + int ndim, size_t itemsize) +{ + void *start1, *end1, *start2, *end2; + __pyx_get_array_memory_extents(slice1, &start1, &end1, ndim, itemsize); + __pyx_get_array_memory_extents(slice2, &start2, &end2, ndim, itemsize); + return (start1 < end2) && (start2 < end1); +} + +/* CIntFromPyVerify */ + #define __PYX_VERIFY_RETURN_INT(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 0) +#define __PYX_VERIFY_RETURN_INT_EXC(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 1) +#define __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, exc)\ + {\ + func_type value = func_value;\ + if (sizeof(target_type) < sizeof(func_type)) {\ + if (unlikely(value != (func_type) (target_type) value)) {\ + func_type zero = 0;\ + if (exc && unlikely(value == (func_type)-1 && PyErr_Occurred()))\ + return (target_type) -1;\ + if (is_unsigned && unlikely(value < zero))\ + goto raise_neg_overflow;\ + else\ + goto raise_overflow;\ + }\ + }\ + return (target_type) value;\ + } + +/* TypeInfoCompare */ + static int +__pyx_typeinfo_cmp(__Pyx_TypeInfo *a, __Pyx_TypeInfo *b) +{ + int i; + if (!a || !b) + return 0; + if (a == b) + return 1; + if (a->size != b->size || a->typegroup != b->typegroup || + a->is_unsigned != b->is_unsigned || a->ndim != b->ndim) { + if (a->typegroup == 'H' || b->typegroup == 'H') { + return a->size == b->size; + } else { + return 0; + } + } + if (a->ndim) { + for (i = 0; i < a->ndim; i++) + if (a->arraysize[i] != b->arraysize[i]) + return 0; + } + if (a->typegroup == 'S') { + if (a->flags != b->flags) + return 0; + if (a->fields || b->fields) { + if (!(a->fields && b->fields)) + return 0; + for (i = 0; a->fields[i].type && b->fields[i].type; i++) { + __Pyx_StructField *field_a = a->fields + i; + __Pyx_StructField *field_b = b->fields + i; + if (field_a->offset != field_b->offset || + !__pyx_typeinfo_cmp(field_a->type, field_b->type)) + return 0; + } + return !a->fields[i].type && !b->fields[i].type; + } + } + return 1; +} + +/* MemviewSliceValidateAndInit */ + static int +__pyx_check_strides(Py_buffer *buf, int dim, int ndim, int spec) +{ + if (buf->shape[dim] <= 1) + return 1; + if (buf->strides) { + if (spec & __Pyx_MEMVIEW_CONTIG) { + if (spec & (__Pyx_MEMVIEW_PTR|__Pyx_MEMVIEW_FULL)) { + if (unlikely(buf->strides[dim] != sizeof(void *))) { + PyErr_Format(PyExc_ValueError, + "Buffer is not indirectly contiguous " + "in dimension %d.", dim); + goto fail; + } + } else if (unlikely(buf->strides[dim] != buf->itemsize)) { + PyErr_SetString(PyExc_ValueError, + "Buffer and memoryview are not contiguous " + "in the same dimension."); + goto fail; + } + } + if (spec & __Pyx_MEMVIEW_FOLLOW) { + Py_ssize_t stride = buf->strides[dim]; + if (stride < 0) + stride = -stride; + if (unlikely(stride < buf->itemsize)) { + PyErr_SetString(PyExc_ValueError, + "Buffer and memoryview are not contiguous " + "in the same dimension."); + goto fail; + } + } + } else { + if (unlikely(spec & __Pyx_MEMVIEW_CONTIG && dim != ndim - 1)) { + PyErr_Format(PyExc_ValueError, + "C-contiguous buffer is not contiguous in " + "dimension %d", dim); + goto fail; + } else if (unlikely(spec & (__Pyx_MEMVIEW_PTR))) { + PyErr_Format(PyExc_ValueError, + "C-contiguous buffer is not indirect in " + "dimension %d", dim); + goto fail; + } else if (unlikely(buf->suboffsets)) { + PyErr_SetString(PyExc_ValueError, + "Buffer exposes suboffsets but no strides"); + goto fail; + } + } + return 1; +fail: + return 0; +} +static int +__pyx_check_suboffsets(Py_buffer *buf, int dim, int ndim, int spec) +{ + CYTHON_UNUSED_VAR(ndim); + if (spec & __Pyx_MEMVIEW_DIRECT) { + if (unlikely(buf->suboffsets && buf->suboffsets[dim] >= 0)) { + PyErr_Format(PyExc_ValueError, + "Buffer not compatible with direct access " + "in dimension %d.", dim); + goto fail; + } + } + if (spec & __Pyx_MEMVIEW_PTR) { + if (unlikely(!buf->suboffsets || (buf->suboffsets[dim] < 0))) { + PyErr_Format(PyExc_ValueError, + "Buffer is not indirectly accessible " + "in dimension %d.", dim); + goto fail; + } + } + return 1; +fail: + return 0; +} +static int +__pyx_verify_contig(Py_buffer *buf, int ndim, int c_or_f_flag) +{ + int i; + if (c_or_f_flag & __Pyx_IS_F_CONTIG) { + Py_ssize_t stride = 1; + for (i = 0; i < ndim; i++) { + if (unlikely(stride * buf->itemsize != buf->strides[i] && buf->shape[i] > 1)) { + PyErr_SetString(PyExc_ValueError, + "Buffer not fortran contiguous."); + goto fail; + } + stride = stride * buf->shape[i]; + } + } else if (c_or_f_flag & __Pyx_IS_C_CONTIG) { + Py_ssize_t stride = 1; + for (i = ndim - 1; i >- 1; i--) { + if (unlikely(stride * buf->itemsize != buf->strides[i] && buf->shape[i] > 1)) { + PyErr_SetString(PyExc_ValueError, + "Buffer not C contiguous."); + goto fail; + } + stride = stride * buf->shape[i]; + } + } + return 1; +fail: + return 0; +} +static int __Pyx_ValidateAndInit_memviewslice( + int *axes_specs, + int c_or_f_flag, + int buf_flags, + int ndim, + __Pyx_TypeInfo *dtype, + __Pyx_BufFmt_StackElem stack[], + __Pyx_memviewslice *memviewslice, + PyObject *original_obj) +{ + struct __pyx_memoryview_obj *memview, *new_memview; + __Pyx_RefNannyDeclarations + Py_buffer *buf; + int i, spec = 0, retval = -1; + __Pyx_BufFmt_Context ctx; + int from_memoryview = __pyx_memoryview_check(original_obj); + __Pyx_RefNannySetupContext("ValidateAndInit_memviewslice", 0); + if (from_memoryview && __pyx_typeinfo_cmp(dtype, ((struct __pyx_memoryview_obj *) + original_obj)->typeinfo)) { + memview = (struct __pyx_memoryview_obj *) original_obj; + new_memview = NULL; + } else { + memview = (struct __pyx_memoryview_obj *) __pyx_memoryview_new( + original_obj, buf_flags, 0, dtype); + new_memview = memview; + if (unlikely(!memview)) + goto fail; + } + buf = &memview->view; + if (unlikely(buf->ndim != ndim)) { + PyErr_Format(PyExc_ValueError, + "Buffer has wrong number of dimensions (expected %d, got %d)", + ndim, buf->ndim); + goto fail; + } + if (new_memview) { + __Pyx_BufFmt_Init(&ctx, stack, dtype); + if (unlikely(!__Pyx_BufFmt_CheckString(&ctx, buf->format))) goto fail; + } + if (unlikely((unsigned) buf->itemsize != dtype->size)) { + PyErr_Format(PyExc_ValueError, + "Item size of buffer (%" CYTHON_FORMAT_SSIZE_T "u byte%s) " + "does not match size of '%s' (%" CYTHON_FORMAT_SSIZE_T "u byte%s)", + buf->itemsize, + (buf->itemsize > 1) ? "s" : "", + dtype->name, + dtype->size, + (dtype->size > 1) ? "s" : ""); + goto fail; + } + if (buf->len > 0) { + for (i = 0; i < ndim; i++) { + spec = axes_specs[i]; + if (unlikely(!__pyx_check_strides(buf, i, ndim, spec))) + goto fail; + if (unlikely(!__pyx_check_suboffsets(buf, i, ndim, spec))) + goto fail; + } + if (unlikely(buf->strides && !__pyx_verify_contig(buf, ndim, c_or_f_flag))) + goto fail; + } + if (unlikely(__Pyx_init_memviewslice(memview, ndim, memviewslice, + new_memview != NULL) == -1)) { + goto fail; + } + retval = 0; + goto no_fail; +fail: + Py_XDECREF(new_memview); + retval = -1; +no_fail: + __Pyx_RefNannyFinishContext(); + return retval; +} + +/* ObjectToMemviewSlice */ + static CYTHON_INLINE __Pyx_memviewslice __Pyx_PyObject_to_MemoryviewSlice_dcd__double(PyObject *obj, int writable_flag) { + __Pyx_memviewslice result = { 0, 0, { 0 }, { 0 }, { 0 } }; + __Pyx_BufFmt_StackElem stack[1]; + int axes_specs[] = { (__Pyx_MEMVIEW_DIRECT | __Pyx_MEMVIEW_CONTIG), (__Pyx_MEMVIEW_DIRECT | __Pyx_MEMVIEW_FOLLOW) }; + int retcode; + if (obj == Py_None) { + result.memview = (struct __pyx_memoryview_obj *) Py_None; + return result; + } + retcode = __Pyx_ValidateAndInit_memviewslice(axes_specs, __Pyx_IS_F_CONTIG, + (PyBUF_F_CONTIGUOUS | PyBUF_FORMAT) | writable_flag, 2, + &__Pyx_TypeInfo_double, stack, + &result, obj); + if (unlikely(retcode == -1)) + goto __pyx_fail; + return result; +__pyx_fail: + result.memview = NULL; + result.data = NULL; + return result; +} + +/* ObjectToMemviewSlice */ + static CYTHON_INLINE __Pyx_memviewslice __Pyx_PyObject_to_MemoryviewSlice_dc_unsigned_char(PyObject *obj, int writable_flag) { + __Pyx_memviewslice result = { 0, 0, { 0 }, { 0 }, { 0 } }; + __Pyx_BufFmt_StackElem stack[1]; + int axes_specs[] = { (__Pyx_MEMVIEW_DIRECT | __Pyx_MEMVIEW_CONTIG) }; + int retcode; + if (obj == Py_None) { + result.memview = (struct __pyx_memoryview_obj *) Py_None; + return result; + } + retcode = __Pyx_ValidateAndInit_memviewslice(axes_specs, __Pyx_IS_C_CONTIG, + (PyBUF_C_CONTIGUOUS | PyBUF_FORMAT) | writable_flag, 1, + &__Pyx_TypeInfo_unsigned_char, stack, + &result, obj); + if (unlikely(retcode == -1)) + goto __pyx_fail; + return result; +__pyx_fail: + result.memview = NULL; + result.data = NULL; + return result; +} + +/* Declarations */ + #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #ifdef __cplusplus + static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float x, float y) { + return ::std::complex< float >(x, y); + } + #else + static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float x, float y) { + return x + y*(__pyx_t_float_complex)_Complex_I; + } + #endif +#else + static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float x, float y) { + __pyx_t_float_complex z; + z.real = x; + z.imag = y; + return z; + } +#endif + +/* Arithmetic */ + #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) +#else + static CYTHON_INLINE int __Pyx_c_eq_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + return (a.real == b.real) && (a.imag == b.imag); + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_sum_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + __pyx_t_float_complex z; + z.real = a.real + b.real; + z.imag = a.imag + b.imag; + return z; + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_diff_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + __pyx_t_float_complex z; + z.real = a.real - b.real; + z.imag = a.imag - b.imag; + return z; + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_prod_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + __pyx_t_float_complex z; + z.real = a.real * b.real - a.imag * b.imag; + z.imag = a.real * b.imag + a.imag * b.real; + return z; + } + #if 1 + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_quot_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + if (b.imag == 0) { + return __pyx_t_float_complex_from_parts(a.real / b.real, a.imag / b.real); + } else if (fabsf(b.real) >= fabsf(b.imag)) { + if (b.real == 0 && b.imag == 0) { + return __pyx_t_float_complex_from_parts(a.real / b.real, a.imag / b.imag); + } else { + float r = b.imag / b.real; + float s = (float)(1.0) / (b.real + b.imag * r); + return __pyx_t_float_complex_from_parts( + (a.real + a.imag * r) * s, (a.imag - a.real * r) * s); + } + } else { + float r = b.real / b.imag; + float s = (float)(1.0) / (b.imag + b.real * r); + return __pyx_t_float_complex_from_parts( + (a.real * r + a.imag) * s, (a.imag * r - a.real) * s); + } + } + #else + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_quot_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + if (b.imag == 0) { + return __pyx_t_float_complex_from_parts(a.real / b.real, a.imag / b.real); + } else { + float denom = b.real * b.real + b.imag * b.imag; + return __pyx_t_float_complex_from_parts( + (a.real * b.real + a.imag * b.imag) / denom, + (a.imag * b.real - a.real * b.imag) / denom); + } + } + #endif + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_neg_float(__pyx_t_float_complex a) { + __pyx_t_float_complex z; + z.real = -a.real; + z.imag = -a.imag; + return z; + } + static CYTHON_INLINE int __Pyx_c_is_zero_float(__pyx_t_float_complex a) { + return (a.real == 0) && (a.imag == 0); + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_conj_float(__pyx_t_float_complex a) { + __pyx_t_float_complex z; + z.real = a.real; + z.imag = -a.imag; + return z; + } + #if 1 + static CYTHON_INLINE float __Pyx_c_abs_float(__pyx_t_float_complex z) { + #if !defined(HAVE_HYPOT) || defined(_MSC_VER) + return sqrtf(z.real*z.real + z.imag*z.imag); + #else + return hypotf(z.real, z.imag); + #endif + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_pow_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + __pyx_t_float_complex z; + float r, lnr, theta, z_r, z_theta; + if (b.imag == 0 && b.real == (int)b.real) { + if (b.real < 0) { + float denom = a.real * a.real + a.imag * a.imag; + a.real = a.real / denom; + a.imag = -a.imag / denom; + b.real = -b.real; + } + switch ((int)b.real) { + case 0: + z.real = 1; + z.imag = 0; + return z; + case 1: + return a; + case 2: + return __Pyx_c_prod_float(a, a); + case 3: + z = __Pyx_c_prod_float(a, a); + return __Pyx_c_prod_float(z, a); + case 4: + z = __Pyx_c_prod_float(a, a); + return __Pyx_c_prod_float(z, z); + } + } + if (a.imag == 0) { + if (a.real == 0) { + return a; + } else if ((b.imag == 0) && (a.real >= 0)) { + z.real = powf(a.real, b.real); + z.imag = 0; + return z; + } else if (a.real > 0) { + r = a.real; + theta = 0; + } else { + r = -a.real; + theta = atan2f(0.0, -1.0); + } + } else { + r = __Pyx_c_abs_float(a); + theta = atan2f(a.imag, a.real); + } + lnr = logf(r); + z_r = expf(lnr * b.real - theta * b.imag); + z_theta = theta * b.real + lnr * b.imag; + z.real = z_r * cosf(z_theta); + z.imag = z_r * sinf(z_theta); + return z; + } + #endif +#endif + +/* Declarations */ + #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #ifdef __cplusplus + static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double x, double y) { + return ::std::complex< double >(x, y); + } + #else + static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double x, double y) { + return x + y*(__pyx_t_double_complex)_Complex_I; + } + #endif +#else + static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double x, double y) { + __pyx_t_double_complex z; + z.real = x; + z.imag = y; + return z; + } +#endif + +/* Arithmetic */ + #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) +#else + static CYTHON_INLINE int __Pyx_c_eq_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + return (a.real == b.real) && (a.imag == b.imag); + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_sum_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + __pyx_t_double_complex z; + z.real = a.real + b.real; + z.imag = a.imag + b.imag; + return z; + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_diff_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + __pyx_t_double_complex z; + z.real = a.real - b.real; + z.imag = a.imag - b.imag; + return z; + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_prod_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + __pyx_t_double_complex z; + z.real = a.real * b.real - a.imag * b.imag; + z.imag = a.real * b.imag + a.imag * b.real; + return z; + } + #if 1 + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_quot_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + if (b.imag == 0) { + return __pyx_t_double_complex_from_parts(a.real / b.real, a.imag / b.real); + } else if (fabs(b.real) >= fabs(b.imag)) { + if (b.real == 0 && b.imag == 0) { + return __pyx_t_double_complex_from_parts(a.real / b.real, a.imag / b.imag); + } else { + double r = b.imag / b.real; + double s = (double)(1.0) / (b.real + b.imag * r); + return __pyx_t_double_complex_from_parts( + (a.real + a.imag * r) * s, (a.imag - a.real * r) * s); + } + } else { + double r = b.real / b.imag; + double s = (double)(1.0) / (b.imag + b.real * r); + return __pyx_t_double_complex_from_parts( + (a.real * r + a.imag) * s, (a.imag * r - a.real) * s); + } + } + #else + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_quot_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + if (b.imag == 0) { + return __pyx_t_double_complex_from_parts(a.real / b.real, a.imag / b.real); + } else { + double denom = b.real * b.real + b.imag * b.imag; + return __pyx_t_double_complex_from_parts( + (a.real * b.real + a.imag * b.imag) / denom, + (a.imag * b.real - a.real * b.imag) / denom); + } + } + #endif + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_neg_double(__pyx_t_double_complex a) { + __pyx_t_double_complex z; + z.real = -a.real; + z.imag = -a.imag; + return z; + } + static CYTHON_INLINE int __Pyx_c_is_zero_double(__pyx_t_double_complex a) { + return (a.real == 0) && (a.imag == 0); + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_conj_double(__pyx_t_double_complex a) { + __pyx_t_double_complex z; + z.real = a.real; + z.imag = -a.imag; + return z; + } + #if 1 + static CYTHON_INLINE double __Pyx_c_abs_double(__pyx_t_double_complex z) { + #if !defined(HAVE_HYPOT) || defined(_MSC_VER) + return sqrt(z.real*z.real + z.imag*z.imag); + #else + return hypot(z.real, z.imag); + #endif + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_pow_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + __pyx_t_double_complex z; + double r, lnr, theta, z_r, z_theta; + if (b.imag == 0 && b.real == (int)b.real) { + if (b.real < 0) { + double denom = a.real * a.real + a.imag * a.imag; + a.real = a.real / denom; + a.imag = -a.imag / denom; + b.real = -b.real; + } + switch ((int)b.real) { + case 0: + z.real = 1; + z.imag = 0; + return z; + case 1: + return a; + case 2: + return __Pyx_c_prod_double(a, a); + case 3: + z = __Pyx_c_prod_double(a, a); + return __Pyx_c_prod_double(z, a); + case 4: + z = __Pyx_c_prod_double(a, a); + return __Pyx_c_prod_double(z, z); + } + } + if (a.imag == 0) { + if (a.real == 0) { + return a; + } else if ((b.imag == 0) && (a.real >= 0)) { + z.real = pow(a.real, b.real); + z.imag = 0; + return z; + } else if (a.real > 0) { + r = a.real; + theta = 0; + } else { + r = -a.real; + theta = atan2(0.0, -1.0); + } + } else { + r = __Pyx_c_abs_double(a); + theta = atan2(a.imag, a.real); + } + lnr = log(r); + z_r = exp(lnr * b.real - theta * b.imag); + z_theta = theta * b.real + lnr * b.imag; + z.real = z_r * cos(z_theta); + z.imag = z_r * sin(z_theta); + return z; + } + #endif +#endif + +/* MemviewSliceCopyTemplate */ + static __Pyx_memviewslice +__pyx_memoryview_copy_new_contig(const __Pyx_memviewslice *from_mvs, + const char *mode, int ndim, + size_t sizeof_dtype, int contig_flag, + int dtype_is_object) +{ + __Pyx_RefNannyDeclarations + int i; + __Pyx_memviewslice new_mvs = { 0, 0, { 0 }, { 0 }, { 0 } }; + struct __pyx_memoryview_obj *from_memview = from_mvs->memview; + Py_buffer *buf = &from_memview->view; + PyObject *shape_tuple = NULL; + PyObject *temp_int = NULL; + struct __pyx_array_obj *array_obj = NULL; + struct __pyx_memoryview_obj *memview_obj = NULL; + __Pyx_RefNannySetupContext("__pyx_memoryview_copy_new_contig", 0); + for (i = 0; i < ndim; i++) { + if (unlikely(from_mvs->suboffsets[i] >= 0)) { + PyErr_Format(PyExc_ValueError, "Cannot copy memoryview slice with " + "indirect dimensions (axis %d)", i); + goto fail; + } + } + shape_tuple = PyTuple_New(ndim); + if (unlikely(!shape_tuple)) { + goto fail; + } + __Pyx_GOTREF(shape_tuple); + for(i = 0; i < ndim; i++) { + temp_int = PyInt_FromSsize_t(from_mvs->shape[i]); + if(unlikely(!temp_int)) { + goto fail; + } else { + PyTuple_SET_ITEM(shape_tuple, i, temp_int); + temp_int = NULL; + } + } + array_obj = __pyx_array_new(shape_tuple, sizeof_dtype, buf->format, (char *) mode, NULL); + if (unlikely(!array_obj)) { + goto fail; + } + __Pyx_GOTREF(array_obj); + memview_obj = (struct __pyx_memoryview_obj *) __pyx_memoryview_new( + (PyObject *) array_obj, contig_flag, + dtype_is_object, + from_mvs->memview->typeinfo); + if (unlikely(!memview_obj)) + goto fail; + if (unlikely(__Pyx_init_memviewslice(memview_obj, ndim, &new_mvs, 1) < 0)) + goto fail; + if (unlikely(__pyx_memoryview_copy_contents(*from_mvs, new_mvs, ndim, ndim, + dtype_is_object) < 0)) + goto fail; + goto no_fail; +fail: + __Pyx_XDECREF(new_mvs.memview); + new_mvs.memview = NULL; + new_mvs.data = NULL; +no_fail: + __Pyx_XDECREF(shape_tuple); + __Pyx_XDECREF(temp_int); + __Pyx_XDECREF(array_obj); + __Pyx_RefNannyFinishContext(); + return new_mvs; +} + +/* MemviewSliceInit */ + static int +__Pyx_init_memviewslice(struct __pyx_memoryview_obj *memview, + int ndim, + __Pyx_memviewslice *memviewslice, + int memview_is_new_reference) +{ + __Pyx_RefNannyDeclarations + int i, retval=-1; + Py_buffer *buf = &memview->view; + __Pyx_RefNannySetupContext("init_memviewslice", 0); + if (unlikely(memviewslice->memview || memviewslice->data)) { + PyErr_SetString(PyExc_ValueError, + "memviewslice is already initialized!"); + goto fail; + } + if (buf->strides) { + for (i = 0; i < ndim; i++) { + memviewslice->strides[i] = buf->strides[i]; + } + } else { + Py_ssize_t stride = buf->itemsize; + for (i = ndim - 1; i >= 0; i--) { + memviewslice->strides[i] = stride; + stride *= buf->shape[i]; + } + } + for (i = 0; i < ndim; i++) { + memviewslice->shape[i] = buf->shape[i]; + if (buf->suboffsets) { + memviewslice->suboffsets[i] = buf->suboffsets[i]; + } else { + memviewslice->suboffsets[i] = -1; + } + } + memviewslice->memview = memview; + memviewslice->data = (char *)buf->buf; + if (__pyx_add_acquisition_count(memview) == 0 && !memview_is_new_reference) { + Py_INCREF(memview); + } + retval = 0; + goto no_fail; +fail: + memviewslice->memview = 0; + memviewslice->data = 0; + retval = -1; +no_fail: + __Pyx_RefNannyFinishContext(); + return retval; +} +#ifndef Py_NO_RETURN +#define Py_NO_RETURN +#endif +static void __pyx_fatalerror(const char *fmt, ...) Py_NO_RETURN { + va_list vargs; + char msg[200]; +#if PY_VERSION_HEX >= 0x030A0000 || defined(HAVE_STDARG_PROTOTYPES) + va_start(vargs, fmt); +#else + va_start(vargs); +#endif + vsnprintf(msg, 200, fmt, vargs); + va_end(vargs); + Py_FatalError(msg); +} +static CYTHON_INLINE int +__pyx_add_acquisition_count_locked(__pyx_atomic_int_type *acquisition_count, + PyThread_type_lock lock) +{ + int result; + PyThread_acquire_lock(lock, 1); + result = (*acquisition_count)++; + PyThread_release_lock(lock); + return result; +} +static CYTHON_INLINE int +__pyx_sub_acquisition_count_locked(__pyx_atomic_int_type *acquisition_count, + PyThread_type_lock lock) +{ + int result; + PyThread_acquire_lock(lock, 1); + result = (*acquisition_count)--; + PyThread_release_lock(lock); + return result; +} +static CYTHON_INLINE void +__Pyx_INC_MEMVIEW(__Pyx_memviewslice *memslice, int have_gil, int lineno) +{ + __pyx_nonatomic_int_type old_acquisition_count; + struct __pyx_memoryview_obj *memview = memslice->memview; + if (unlikely(!memview || (PyObject *) memview == Py_None)) { + return; + } + old_acquisition_count = __pyx_add_acquisition_count(memview); + if (unlikely(old_acquisition_count <= 0)) { + if (likely(old_acquisition_count == 0)) { + if (have_gil) { + Py_INCREF((PyObject *) memview); + } else { + PyGILState_STATE _gilstate = PyGILState_Ensure(); + Py_INCREF((PyObject *) memview); + PyGILState_Release(_gilstate); + } + } else { + __pyx_fatalerror("Acquisition count is %d (line %d)", + old_acquisition_count+1, lineno); + } + } +} +static CYTHON_INLINE void __Pyx_XCLEAR_MEMVIEW(__Pyx_memviewslice *memslice, + int have_gil, int lineno) { + __pyx_nonatomic_int_type old_acquisition_count; + struct __pyx_memoryview_obj *memview = memslice->memview; + if (unlikely(!memview || (PyObject *) memview == Py_None)) { + memslice->memview = NULL; + return; + } + old_acquisition_count = __pyx_sub_acquisition_count(memview); + memslice->data = NULL; + if (likely(old_acquisition_count > 1)) { + memslice->memview = NULL; + } else if (likely(old_acquisition_count == 1)) { + if (have_gil) { + Py_CLEAR(memslice->memview); + } else { + PyGILState_STATE _gilstate = PyGILState_Ensure(); + Py_CLEAR(memslice->memview); + PyGILState_Release(_gilstate); + } + } else { + __pyx_fatalerror("Acquisition count is %d (line %d)", + old_acquisition_count-1, lineno); + } +} + +/* CIntFromPy */ + static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(int) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(int, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (int) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 2 * PyLong_SHIFT)) { + return (int) (((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 3 * PyLong_SHIFT)) { + return (int) (((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 4 * PyLong_SHIFT)) { + return (int) (((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(int) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(int) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) ((((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) ((((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) ((((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(int) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + int val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (int) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (int) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (int) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (int) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(int) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(int) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((int) 1) << (sizeof(int) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (int) -1; + } + } else { + int val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (int) -1; + val = __Pyx_PyInt_As_int(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to int"); + return (int) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to int"); + return (int) -1; +} + +/* CIntToPy */ + static CYTHON_INLINE PyObject* __Pyx_PyInt_From_int(int value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(int) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(int) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(int) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(int) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(int) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; +#if !CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030d0000 + return _PyLong_FromByteArray(bytes, sizeof(int), + little, !is_unsigned); +#else + PyObject *from_bytes, *result = NULL; + PyObject *py_bytes = NULL, *arg_tuple = NULL, *kwds = NULL, *order_str = NULL; + from_bytes = PyObject_GetAttrString((PyObject*)&PyLong_Type, "from_bytes"); + if (!from_bytes) return NULL; + py_bytes = PyBytes_FromStringAndSize((char*)bytes, sizeof(int)); + if (!py_bytes) goto limited_bad; + order_str = PyUnicode_FromString(little ? "little" : "big"); + if (!order_str) goto limited_bad; + arg_tuple = PyTuple_Pack(2, py_bytes, order_str); + if (!arg_tuple) goto limited_bad; + if (!is_unsigned) { + kwds = PyDict_New(); + if (!kwds) goto limited_bad; + if (PyDict_SetItemString(kwds, "signed", __Pyx_NewRef(Py_True))) goto limited_bad; + } + result = PyObject_Call(from_bytes, arg_tuple, kwds); + limited_bad: + Py_XDECREF(kwds); + Py_XDECREF(arg_tuple); + Py_XDECREF(order_str); + Py_XDECREF(py_bytes); + Py_XDECREF(from_bytes); + return result; +#endif + } +} + +/* CIntFromPy */ + static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(long) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(long, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (long) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 2 * PyLong_SHIFT)) { + return (long) (((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 3 * PyLong_SHIFT)) { + return (long) (((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 4 * PyLong_SHIFT)) { + return (long) (((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(long) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(long) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) ((((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) ((((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) ((((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(long) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + long val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (long) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (long) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (long) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (long) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(long) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(long) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((long) 1) << (sizeof(long) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (long) -1; + } + } else { + long val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (long) -1; + val = __Pyx_PyInt_As_long(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to long"); + return (long) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to long"); + return (long) -1; +} + +/* CIntToPy */ + static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(long) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(long) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(long) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; +#if !CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030d0000 + return _PyLong_FromByteArray(bytes, sizeof(long), + little, !is_unsigned); +#else + PyObject *from_bytes, *result = NULL; + PyObject *py_bytes = NULL, *arg_tuple = NULL, *kwds = NULL, *order_str = NULL; + from_bytes = PyObject_GetAttrString((PyObject*)&PyLong_Type, "from_bytes"); + if (!from_bytes) return NULL; + py_bytes = PyBytes_FromStringAndSize((char*)bytes, sizeof(long)); + if (!py_bytes) goto limited_bad; + order_str = PyUnicode_FromString(little ? "little" : "big"); + if (!order_str) goto limited_bad; + arg_tuple = PyTuple_Pack(2, py_bytes, order_str); + if (!arg_tuple) goto limited_bad; + if (!is_unsigned) { + kwds = PyDict_New(); + if (!kwds) goto limited_bad; + if (PyDict_SetItemString(kwds, "signed", __Pyx_NewRef(Py_True))) goto limited_bad; + } + result = PyObject_Call(from_bytes, arg_tuple, kwds); + limited_bad: + Py_XDECREF(kwds); + Py_XDECREF(arg_tuple); + Py_XDECREF(order_str); + Py_XDECREF(py_bytes); + Py_XDECREF(from_bytes); + return result; +#endif + } +} + +/* CIntFromPy */ + static CYTHON_INLINE size_t __Pyx_PyInt_As_size_t(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const size_t neg_one = (size_t) -1, const_zero = (size_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(size_t) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(size_t, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (size_t) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(size_t, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(size_t) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) >= 2 * PyLong_SHIFT)) { + return (size_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(size_t) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) >= 3 * PyLong_SHIFT)) { + return (size_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(size_t) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) >= 4 * PyLong_SHIFT)) { + return (size_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (size_t) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(size_t) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(size_t) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(size_t, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(size_t) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 2 * PyLong_SHIFT)) { + return (size_t) (((size_t)-1)*(((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(size_t) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 2 * PyLong_SHIFT)) { + return (size_t) ((((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(size_t) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 3 * PyLong_SHIFT)) { + return (size_t) (((size_t)-1)*(((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(size_t) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 3 * PyLong_SHIFT)) { + return (size_t) ((((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(size_t) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 4 * PyLong_SHIFT)) { + return (size_t) (((size_t)-1)*(((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(size_t) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(size_t, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(size_t) - 1 > 4 * PyLong_SHIFT)) { + return (size_t) ((((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(size_t) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(size_t) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(size_t, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + size_t val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (size_t) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (size_t) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (size_t) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (size_t) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (size_t) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(size_t) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((size_t) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(size_t) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((size_t) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((size_t) 1) << (sizeof(size_t) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (size_t) -1; + } + } else { + size_t val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (size_t) -1; + val = __Pyx_PyInt_As_size_t(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to size_t"); + return (size_t) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to size_t"); + return (size_t) -1; +} + +/* CIntFromPy */ + static CYTHON_INLINE char __Pyx_PyInt_As_char(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const char neg_one = (char) -1, const_zero = (char) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(char) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(char, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (char) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(char, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(char) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) >= 2 * PyLong_SHIFT)) { + return (char) (((((char)digits[1]) << PyLong_SHIFT) | (char)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(char) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) >= 3 * PyLong_SHIFT)) { + return (char) (((((((char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(char) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) >= 4 * PyLong_SHIFT)) { + return (char) (((((((((char)digits[3]) << PyLong_SHIFT) | (char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (char) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(char) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(char, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(char) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(char, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(char, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(char) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 2 * PyLong_SHIFT)) { + return (char) (((char)-1)*(((((char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(char) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 2 * PyLong_SHIFT)) { + return (char) ((((((char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(char) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 3 * PyLong_SHIFT)) { + return (char) (((char)-1)*(((((((char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(char) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 3 * PyLong_SHIFT)) { + return (char) ((((((((char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(char) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 4 * PyLong_SHIFT)) { + return (char) (((char)-1)*(((((((((char)digits[3]) << PyLong_SHIFT) | (char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(char) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 4 * PyLong_SHIFT)) { + return (char) ((((((((((char)digits[3]) << PyLong_SHIFT) | (char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(char) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(char, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(char) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(char, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + char val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (char) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (char) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (char) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (char) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (char) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(char) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((char) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(char) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((char) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((char) 1) << (sizeof(char) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (char) -1; + } + } else { + char val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (char) -1; + val = __Pyx_PyInt_As_char(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to char"); + return (char) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to char"); + return (char) -1; +} + +/* FormatTypeName */ + #if CYTHON_COMPILING_IN_LIMITED_API +static __Pyx_TypeName +__Pyx_PyType_GetName(PyTypeObject* tp) +{ + PyObject *name = __Pyx_PyObject_GetAttrStr((PyObject *)tp, + __pyx_n_s_name_2); + if (unlikely(name == NULL) || unlikely(!PyUnicode_Check(name))) { + PyErr_Clear(); + Py_XDECREF(name); + name = __Pyx_NewRef(__pyx_n_s__94); + } + return name; +} +#endif + +/* CheckBinaryVersion */ + static unsigned long __Pyx_get_runtime_version(void) { +#if __PYX_LIMITED_VERSION_HEX >= 0x030B00A4 + return Py_Version & ~0xFFUL; +#else + const char* rt_version = Py_GetVersion(); + unsigned long version = 0; + unsigned long factor = 0x01000000UL; + unsigned int digit = 0; + int i = 0; + while (factor) { + while ('0' <= rt_version[i] && rt_version[i] <= '9') { + digit = digit * 10 + (unsigned int) (rt_version[i] - '0'); + ++i; + } + version += factor * digit; + if (rt_version[i] != '.') + break; + digit = 0; + factor >>= 8; + ++i; + } + return version; +#endif +} +static int __Pyx_check_binary_version(unsigned long ct_version, unsigned long rt_version, int allow_newer) { + const unsigned long MAJOR_MINOR = 0xFFFF0000UL; + if ((rt_version & MAJOR_MINOR) == (ct_version & MAJOR_MINOR)) + return 0; + if (likely(allow_newer && (rt_version & MAJOR_MINOR) > (ct_version & MAJOR_MINOR))) + return 1; + { + char message[200]; + PyOS_snprintf(message, sizeof(message), + "compile time Python version %d.%d " + "of module '%.100s' " + "%s " + "runtime version %d.%d", + (int) (ct_version >> 24), (int) ((ct_version >> 16) & 0xFF), + __Pyx_MODULE_NAME, + (allow_newer) ? "was newer than" : "does not match", + (int) (rt_version >> 24), (int) ((rt_version >> 16) & 0xFF) + ); + return PyErr_WarnEx(NULL, message, 1); + } +} + +/* InitStrings */ + #if PY_MAJOR_VERSION >= 3 +static int __Pyx_InitString(__Pyx_StringTabEntry t, PyObject **str) { + if (t.is_unicode | t.is_str) { + if (t.intern) { + *str = PyUnicode_InternFromString(t.s); + } else if (t.encoding) { + *str = PyUnicode_Decode(t.s, t.n - 1, t.encoding, NULL); + } else { + *str = PyUnicode_FromStringAndSize(t.s, t.n - 1); + } + } else { + *str = PyBytes_FromStringAndSize(t.s, t.n - 1); + } + if (!*str) + return -1; + if (PyObject_Hash(*str) == -1) + return -1; + return 0; +} +#endif +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t) { + while (t->p) { + #if PY_MAJOR_VERSION >= 3 + __Pyx_InitString(*t, t->p); + #else + if (t->is_unicode) { + *t->p = PyUnicode_DecodeUTF8(t->s, t->n - 1, NULL); + } else if (t->intern) { + *t->p = PyString_InternFromString(t->s); + } else { + *t->p = PyString_FromStringAndSize(t->s, t->n - 1); + } + if (!*t->p) + return -1; + if (PyObject_Hash(*t->p) == -1) + return -1; + #endif + ++t; + } + return 0; +} + +#include +static CYTHON_INLINE Py_ssize_t __Pyx_ssize_strlen(const char *s) { + size_t len = strlen(s); + if (unlikely(len > (size_t) PY_SSIZE_T_MAX)) { + PyErr_SetString(PyExc_OverflowError, "byte string is too long"); + return -1; + } + return (Py_ssize_t) len; +} +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char* c_str) { + Py_ssize_t len = __Pyx_ssize_strlen(c_str); + if (unlikely(len < 0)) return NULL; + return __Pyx_PyUnicode_FromStringAndSize(c_str, len); +} +static CYTHON_INLINE PyObject* __Pyx_PyByteArray_FromString(const char* c_str) { + Py_ssize_t len = __Pyx_ssize_strlen(c_str); + if (unlikely(len < 0)) return NULL; + return PyByteArray_FromStringAndSize(c_str, len); +} +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject* o) { + Py_ssize_t ignore; + return __Pyx_PyObject_AsStringAndSize(o, &ignore); +} +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +#if !CYTHON_PEP393_ENABLED +static const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + char* defenc_c; + PyObject* defenc = _PyUnicode_AsDefaultEncodedString(o, NULL); + if (!defenc) return NULL; + defenc_c = PyBytes_AS_STRING(defenc); +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + { + char* end = defenc_c + PyBytes_GET_SIZE(defenc); + char* c; + for (c = defenc_c; c < end; c++) { + if ((unsigned char) (*c) >= 128) { + PyUnicode_AsASCIIString(o); + return NULL; + } + } + } +#endif + *length = PyBytes_GET_SIZE(defenc); + return defenc_c; +} +#else +static CYTHON_INLINE const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + if (unlikely(__Pyx_PyUnicode_READY(o) == -1)) return NULL; +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + if (likely(PyUnicode_IS_ASCII(o))) { + *length = PyUnicode_GET_LENGTH(o); + return PyUnicode_AsUTF8(o); + } else { + PyUnicode_AsASCIIString(o); + return NULL; + } +#else + return PyUnicode_AsUTF8AndSize(o, length); +#endif +} +#endif +#endif +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject* o, Py_ssize_t *length) { +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT + if ( +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + __Pyx_sys_getdefaultencoding_not_ascii && +#endif + PyUnicode_Check(o)) { + return __Pyx_PyUnicode_AsStringAndSize(o, length); + } else +#endif +#if (!CYTHON_COMPILING_IN_PYPY && !CYTHON_COMPILING_IN_LIMITED_API) || (defined(PyByteArray_AS_STRING) && defined(PyByteArray_GET_SIZE)) + if (PyByteArray_Check(o)) { + *length = PyByteArray_GET_SIZE(o); + return PyByteArray_AS_STRING(o); + } else +#endif + { + char* result; + int r = PyBytes_AsStringAndSize(o, &result, length); + if (unlikely(r < 0)) { + return NULL; + } else { + return result; + } + } +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject* x) { + int is_true = x == Py_True; + if (is_true | (x == Py_False) | (x == Py_None)) return is_true; + else return PyObject_IsTrue(x); +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject* x) { + int retval; + if (unlikely(!x)) return -1; + retval = __Pyx_PyObject_IsTrue(x); + Py_DECREF(x); + return retval; +} +static PyObject* __Pyx_PyNumber_IntOrLongWrongResultType(PyObject* result, const char* type_name) { + __Pyx_TypeName result_type_name = __Pyx_PyType_GetName(Py_TYPE(result)); +#if PY_MAJOR_VERSION >= 3 + if (PyLong_Check(result)) { + if (PyErr_WarnFormat(PyExc_DeprecationWarning, 1, + "__int__ returned non-int (type " __Pyx_FMT_TYPENAME "). " + "The ability to return an instance of a strict subclass of int is deprecated, " + "and may be removed in a future version of Python.", + result_type_name)) { + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; + } + __Pyx_DECREF_TypeName(result_type_name); + return result; + } +#endif + PyErr_Format(PyExc_TypeError, + "__%.4s__ returned non-%.4s (type " __Pyx_FMT_TYPENAME ")", + type_name, type_name, result_type_name); + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x) { +#if CYTHON_USE_TYPE_SLOTS + PyNumberMethods *m; +#endif + const char *name = NULL; + PyObject *res = NULL; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x) || PyLong_Check(x))) +#else + if (likely(PyLong_Check(x))) +#endif + return __Pyx_NewRef(x); +#if CYTHON_USE_TYPE_SLOTS + m = Py_TYPE(x)->tp_as_number; + #if PY_MAJOR_VERSION < 3 + if (m && m->nb_int) { + name = "int"; + res = m->nb_int(x); + } + else if (m && m->nb_long) { + name = "long"; + res = m->nb_long(x); + } + #else + if (likely(m && m->nb_int)) { + name = "int"; + res = m->nb_int(x); + } + #endif +#else + if (!PyBytes_CheckExact(x) && !PyUnicode_CheckExact(x)) { + res = PyNumber_Int(x); + } +#endif + if (likely(res)) { +#if PY_MAJOR_VERSION < 3 + if (unlikely(!PyInt_Check(res) && !PyLong_Check(res))) { +#else + if (unlikely(!PyLong_CheckExact(res))) { +#endif + return __Pyx_PyNumber_IntOrLongWrongResultType(res, name); + } + } + else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_TypeError, + "an integer is required"); + } + return res; +} +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject* b) { + Py_ssize_t ival; + PyObject *x; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_CheckExact(b))) { + if (sizeof(Py_ssize_t) >= sizeof(long)) + return PyInt_AS_LONG(b); + else + return PyInt_AsSsize_t(b); + } +#endif + if (likely(PyLong_CheckExact(b))) { + #if CYTHON_USE_PYLONG_INTERNALS + if (likely(__Pyx_PyLong_IsCompact(b))) { + return __Pyx_PyLong_CompactValue(b); + } else { + const digit* digits = __Pyx_PyLong_Digits(b); + const Py_ssize_t size = __Pyx_PyLong_SignedDigitCount(b); + switch (size) { + case 2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return (Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + } + } + #endif + return PyLong_AsSsize_t(b); + } + x = PyNumber_Index(b); + if (!x) return -1; + ival = PyInt_AsSsize_t(x); + Py_DECREF(x); + return ival; +} +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject* o) { + if (sizeof(Py_hash_t) == sizeof(Py_ssize_t)) { + return (Py_hash_t) __Pyx_PyIndex_AsSsize_t(o); +#if PY_MAJOR_VERSION < 3 + } else if (likely(PyInt_CheckExact(o))) { + return PyInt_AS_LONG(o); +#endif + } else { + Py_ssize_t ival; + PyObject *x; + x = PyNumber_Index(o); + if (!x) return -1; + ival = PyInt_AsLong(x); + Py_DECREF(x); + return ival; + } +} +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b) { + return b ? __Pyx_NewRef(Py_True) : __Pyx_NewRef(Py_False); +} +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t ival) { + return PyInt_FromSize_t(ival); +} + + +/* #### Code section: utility_code_pragmas_end ### */ +#ifdef _MSC_VER +#pragma warning( pop ) +#endif + + + +/* #### Code section: end ### */ +#endif /* Py_PYTHON_H */ diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_ocp_solver_pyx.so b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_ocp_solver_pyx.so new file mode 100755 index 0000000..848eaef Binary files /dev/null and b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_ocp_solver_pyx.so differ diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_sim_solver_long.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_sim_solver_long.c new file mode 100644 index 0000000..d451c56 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_sim_solver_long.c @@ -0,0 +1,294 @@ +/* + * Copyright (c) The acados authors. + * + * This file is part of acados. + * + * The 2-Clause BSD License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE.; + */ +// standard +#include +#include + +// acados +#include "acados_c/external_function_interface.h" +#include "acados_c/sim_interface.h" +#include "acados_c/external_function_interface.h" + +#include "acados/sim/sim_common.h" +#include "acados/utils/external_function_generic.h" +#include "acados/utils/print.h" + + +// example specific +#include "long_model/long_model.h" +#include "acados_sim_solver_long.h" + + +// ** solver data ** + +sim_solver_capsule * long_acados_sim_solver_create_capsule() +{ + void* capsule_mem = malloc(sizeof(sim_solver_capsule)); + sim_solver_capsule *capsule = (sim_solver_capsule *) capsule_mem; + + return capsule; +} + + +int long_acados_sim_solver_free_capsule(sim_solver_capsule * capsule) +{ + free(capsule); + return 0; +} + + +int long_acados_sim_create(sim_solver_capsule * capsule) +{ + // initialize + const int nx = LONG_NX; + const int nu = LONG_NU; + const int nz = LONG_NZ; + const int np = LONG_NP; + bool tmp_bool; + + + double Tsim = 0.06944444444444445; + + + // explicit ode + capsule->sim_forw_vde_casadi = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)); + capsule->sim_vde_adj_casadi = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)); + capsule->sim_expl_ode_fun_casadi = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)); + + capsule->sim_forw_vde_casadi->casadi_fun = &long_expl_vde_forw; + capsule->sim_forw_vde_casadi->casadi_n_in = &long_expl_vde_forw_n_in; + capsule->sim_forw_vde_casadi->casadi_n_out = &long_expl_vde_forw_n_out; + capsule->sim_forw_vde_casadi->casadi_sparsity_in = &long_expl_vde_forw_sparsity_in; + capsule->sim_forw_vde_casadi->casadi_sparsity_out = &long_expl_vde_forw_sparsity_out; + capsule->sim_forw_vde_casadi->casadi_work = &long_expl_vde_forw_work; + external_function_param_casadi_create(capsule->sim_forw_vde_casadi, np); + + capsule->sim_vde_adj_casadi->casadi_fun = &long_expl_vde_adj; + capsule->sim_vde_adj_casadi->casadi_n_in = &long_expl_vde_adj_n_in; + capsule->sim_vde_adj_casadi->casadi_n_out = &long_expl_vde_adj_n_out; + capsule->sim_vde_adj_casadi->casadi_sparsity_in = &long_expl_vde_adj_sparsity_in; + capsule->sim_vde_adj_casadi->casadi_sparsity_out = &long_expl_vde_adj_sparsity_out; + capsule->sim_vde_adj_casadi->casadi_work = &long_expl_vde_adj_work; + external_function_param_casadi_create(capsule->sim_vde_adj_casadi, np); + + capsule->sim_expl_ode_fun_casadi->casadi_fun = &long_expl_ode_fun; + capsule->sim_expl_ode_fun_casadi->casadi_n_in = &long_expl_ode_fun_n_in; + capsule->sim_expl_ode_fun_casadi->casadi_n_out = &long_expl_ode_fun_n_out; + capsule->sim_expl_ode_fun_casadi->casadi_sparsity_in = &long_expl_ode_fun_sparsity_in; + capsule->sim_expl_ode_fun_casadi->casadi_sparsity_out = &long_expl_ode_fun_sparsity_out; + capsule->sim_expl_ode_fun_casadi->casadi_work = &long_expl_ode_fun_work; + external_function_param_casadi_create(capsule->sim_expl_ode_fun_casadi, np); + + + + // sim plan & config + sim_solver_plan_t plan; + plan.sim_solver = ERK; + + // create correct config based on plan + sim_config * long_sim_config = sim_config_create(plan); + capsule->acados_sim_config = long_sim_config; + + // sim dims + void *long_sim_dims = sim_dims_create(long_sim_config); + capsule->acados_sim_dims = long_sim_dims; + sim_dims_set(long_sim_config, long_sim_dims, "nx", &nx); + sim_dims_set(long_sim_config, long_sim_dims, "nu", &nu); + sim_dims_set(long_sim_config, long_sim_dims, "nz", &nz); + + + // sim opts + sim_opts *long_sim_opts = sim_opts_create(long_sim_config, long_sim_dims); + capsule->acados_sim_opts = long_sim_opts; + int tmp_int = 3; + sim_opts_set(long_sim_config, long_sim_opts, "newton_iter", &tmp_int); + double tmp_double = 0.0; + sim_opts_set(long_sim_config, long_sim_opts, "newton_tol", &tmp_double); + sim_collocation_type collocation_type = GAUSS_LEGENDRE; + sim_opts_set(long_sim_config, long_sim_opts, "collocation_type", &collocation_type); + + + tmp_int = 4; + sim_opts_set(long_sim_config, long_sim_opts, "num_stages", &tmp_int); + tmp_int = 1; + sim_opts_set(long_sim_config, long_sim_opts, "num_steps", &tmp_int); + tmp_bool = 0; + sim_opts_set(long_sim_config, long_sim_opts, "jac_reuse", &tmp_bool); + + + // sim in / out + sim_in *long_sim_in = sim_in_create(long_sim_config, long_sim_dims); + capsule->acados_sim_in = long_sim_in; + sim_out *long_sim_out = sim_out_create(long_sim_config, long_sim_dims); + capsule->acados_sim_out = long_sim_out; + + sim_in_set(long_sim_config, long_sim_dims, + long_sim_in, "T", &Tsim); + + // model functions + long_sim_config->model_set(long_sim_in->model, + "expl_vde_forw", capsule->sim_forw_vde_casadi); + long_sim_config->model_set(long_sim_in->model, + "expl_vde_adj", capsule->sim_vde_adj_casadi); + long_sim_config->model_set(long_sim_in->model, + "expl_ode_fun", capsule->sim_expl_ode_fun_casadi); + + // sim solver + sim_solver *long_sim_solver = sim_solver_create(long_sim_config, + long_sim_dims, long_sim_opts); + capsule->acados_sim_solver = long_sim_solver; + + + /* initialize parameter values */ + double* p = calloc(np, sizeof(double)); + + p[0] = -1.2; + p[1] = 1.2; + p[4] = 1.45; + p[5] = 0.75; + + long_acados_sim_update_params(capsule, p, np); + free(p); + + + /* initialize input */ + // x + double x0[3]; + for (int ii = 0; ii < 3; ii++) + x0[ii] = 0.0; + + sim_in_set(long_sim_config, long_sim_dims, + long_sim_in, "x", x0); + + + // u + double u0[1]; + for (int ii = 0; ii < 1; ii++) + u0[ii] = 0.0; + + sim_in_set(long_sim_config, long_sim_dims, + long_sim_in, "u", u0); + + // S_forw + double S_forw[12]; + for (int ii = 0; ii < 12; ii++) + S_forw[ii] = 0.0; + for (int ii = 0; ii < 3; ii++) + S_forw[ii + ii * 3 ] = 1.0; + + + sim_in_set(long_sim_config, long_sim_dims, + long_sim_in, "S_forw", S_forw); + + int status = sim_precompute(long_sim_solver, long_sim_in, long_sim_out); + + return status; +} + + +int long_acados_sim_solve(sim_solver_capsule *capsule) +{ + // integrate dynamics using acados sim_solver + int status = sim_solve(capsule->acados_sim_solver, + capsule->acados_sim_in, capsule->acados_sim_out); + if (status != 0) + printf("error in long_acados_sim_solve()! Exiting.\n"); + + return status; +} + + +int long_acados_sim_free(sim_solver_capsule *capsule) +{ + // free memory + sim_solver_destroy(capsule->acados_sim_solver); + sim_in_destroy(capsule->acados_sim_in); + sim_out_destroy(capsule->acados_sim_out); + sim_opts_destroy(capsule->acados_sim_opts); + sim_dims_destroy(capsule->acados_sim_dims); + sim_config_destroy(capsule->acados_sim_config); + + // free external function + external_function_param_casadi_free(capsule->sim_forw_vde_casadi); + external_function_param_casadi_free(capsule->sim_vde_adj_casadi); + external_function_param_casadi_free(capsule->sim_expl_ode_fun_casadi); + + return 0; +} + + +int long_acados_sim_update_params(sim_solver_capsule *capsule, double *p, int np) +{ + int status = 0; + int casadi_np = LONG_NP; + + if (casadi_np != np) { + printf("long_acados_sim_update_params: trying to set %i parameters for external functions." + " External function has %i parameters. Exiting.\n", np, casadi_np); + exit(1); + } + capsule->sim_forw_vde_casadi[0].set_param(capsule->sim_forw_vde_casadi, p); + capsule->sim_vde_adj_casadi[0].set_param(capsule->sim_vde_adj_casadi, p); + capsule->sim_expl_ode_fun_casadi[0].set_param(capsule->sim_expl_ode_fun_casadi, p); + + return status; +} + +/* getters pointers to C objects*/ +sim_config * long_acados_get_sim_config(sim_solver_capsule *capsule) +{ + return capsule->acados_sim_config; +}; + +sim_in * long_acados_get_sim_in(sim_solver_capsule *capsule) +{ + return capsule->acados_sim_in; +}; + +sim_out * long_acados_get_sim_out(sim_solver_capsule *capsule) +{ + return capsule->acados_sim_out; +}; + +void * long_acados_get_sim_dims(sim_solver_capsule *capsule) +{ + return capsule->acados_sim_dims; +}; + +sim_opts * long_acados_get_sim_opts(sim_solver_capsule *capsule) +{ + return capsule->acados_sim_opts; +}; + +sim_solver * long_acados_get_sim_solver(sim_solver_capsule *capsule) +{ + return capsule->acados_sim_solver; +}; + diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_solver.pxd b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_solver.pxd new file mode 100644 index 0000000..c04a1b2 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_solver.pxd @@ -0,0 +1,62 @@ +# +# Copyright (c) The acados authors. +# +# This file is part of acados. +# +# The 2-Clause BSD License +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are met: +# +# 1. Redistributions of source code must retain the above copyright notice, +# this list of conditions and the following disclaimer. +# +# 2. Redistributions in binary form must reproduce the above copyright notice, +# this list of conditions and the following disclaimer in the documentation +# and/or other materials provided with the distribution. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE +# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE.; +# + +cimport acados_solver_common + +cdef extern from "acados_solver_long.h": + ctypedef struct nlp_solver_capsule "long_solver_capsule": + pass + + nlp_solver_capsule * acados_create_capsule "long_acados_create_capsule"() + int acados_free_capsule "long_acados_free_capsule"(nlp_solver_capsule *capsule) + + int acados_create "long_acados_create"(nlp_solver_capsule * capsule) + + int acados_create_with_discretization "long_acados_create_with_discretization"(nlp_solver_capsule * capsule, int n_time_steps, double* new_time_steps) + int acados_update_time_steps "long_acados_update_time_steps"(nlp_solver_capsule * capsule, int N, double* new_time_steps) + int acados_update_qp_solver_cond_N "long_acados_update_qp_solver_cond_N"(nlp_solver_capsule * capsule, int qp_solver_cond_N) + + int acados_update_params "long_acados_update_params"(nlp_solver_capsule * capsule, int stage, double *value, int np_) + int acados_update_params_sparse "long_acados_update_params_sparse"(nlp_solver_capsule * capsule, int stage, int *idx, double *p, int n_update) + int acados_solve "long_acados_solve"(nlp_solver_capsule * capsule) + int acados_reset "long_acados_reset"(nlp_solver_capsule * capsule, int reset_qp_solver_mem) + int acados_free "long_acados_free"(nlp_solver_capsule * capsule) + void acados_print_stats "long_acados_print_stats"(nlp_solver_capsule * capsule) + + int acados_custom_update "long_acados_custom_update"(nlp_solver_capsule* capsule, double * data, int data_len) + + acados_solver_common.ocp_nlp_in *acados_get_nlp_in "long_acados_get_nlp_in"(nlp_solver_capsule * capsule) + acados_solver_common.ocp_nlp_out *acados_get_nlp_out "long_acados_get_nlp_out"(nlp_solver_capsule * capsule) + acados_solver_common.ocp_nlp_out *acados_get_sens_out "long_acados_get_sens_out"(nlp_solver_capsule * capsule) + acados_solver_common.ocp_nlp_solver *acados_get_nlp_solver "long_acados_get_nlp_solver"(nlp_solver_capsule * capsule) + acados_solver_common.ocp_nlp_config *acados_get_nlp_config "long_acados_get_nlp_config"(nlp_solver_capsule * capsule) + void *acados_get_nlp_opts "long_acados_get_nlp_opts"(nlp_solver_capsule * capsule) + acados_solver_common.ocp_nlp_dims *acados_get_nlp_dims "long_acados_get_nlp_dims"(nlp_solver_capsule * capsule) + acados_solver_common.ocp_nlp_plan *acados_get_nlp_plan "long_acados_get_nlp_plan"(nlp_solver_capsule * capsule) diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_solver_long.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_solver_long.c new file mode 100644 index 0000000..bdeec91 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/acados_solver_long.c @@ -0,0 +1,1087 @@ +/* + * Copyright (c) The acados authors. + * + * This file is part of acados. + * + * The 2-Clause BSD License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE.; + */ + +// standard +#include +#include +#include +// acados +// #include "acados/utils/print.h" +#include "acados_c/ocp_nlp_interface.h" +#include "acados_c/external_function_interface.h" + +// example specific +#include "long_model/long_model.h" +#include "long_constraints/long_constraints.h" +#include "long_cost/long_cost.h" + + + + +#include "acados_solver_long.h" + +#define NX LONG_NX +#define NZ LONG_NZ +#define NU LONG_NU +#define NP LONG_NP +#define NBX LONG_NBX +#define NBX0 LONG_NBX0 +#define NBU LONG_NBU +#define NSBX LONG_NSBX +#define NSBU LONG_NSBU +#define NSH LONG_NSH +#define NSG LONG_NSG +#define NSPHI LONG_NSPHI +#define NSHN LONG_NSHN +#define NSGN LONG_NSGN +#define NSPHIN LONG_NSPHIN +#define NSBXN LONG_NSBXN +#define NS LONG_NS +#define NSN LONG_NSN +#define NG LONG_NG +#define NBXN LONG_NBXN +#define NGN LONG_NGN +#define NY0 LONG_NY0 +#define NY LONG_NY +#define NYN LONG_NYN +// #define N LONG_N +#define NH LONG_NH +#define NPHI LONG_NPHI +#define NHN LONG_NHN +#define NPHIN LONG_NPHIN +#define NR LONG_NR + + +// ** solver data ** + +long_solver_capsule * long_acados_create_capsule(void) +{ + void* capsule_mem = malloc(sizeof(long_solver_capsule)); + long_solver_capsule *capsule = (long_solver_capsule *) capsule_mem; + + return capsule; +} + + +int long_acados_free_capsule(long_solver_capsule *capsule) +{ + free(capsule); + return 0; +} + + +int long_acados_create(long_solver_capsule* capsule) +{ + int N_shooting_intervals = LONG_N; + double* new_time_steps = NULL; // NULL -> don't alter the code generated time-steps + return long_acados_create_with_discretization(capsule, N_shooting_intervals, new_time_steps); +} + + +int long_acados_update_time_steps(long_solver_capsule* capsule, int N, double* new_time_steps) +{ + if (N != capsule->nlp_solver_plan->N) { + fprintf(stderr, "long_acados_update_time_steps: given number of time steps (= %d) " \ + "differs from the currently allocated number of " \ + "time steps (= %d)!\n" \ + "Please recreate with new discretization and provide a new vector of time_stamps!\n", + N, capsule->nlp_solver_plan->N); + return 1; + } + + ocp_nlp_config * nlp_config = capsule->nlp_config; + ocp_nlp_dims * nlp_dims = capsule->nlp_dims; + ocp_nlp_in * nlp_in = capsule->nlp_in; + + for (int i = 0; i < N; i++) + { + ocp_nlp_in_set(nlp_config, nlp_dims, nlp_in, i, "Ts", &new_time_steps[i]); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "scaling", &new_time_steps[i]); + } + return 0; +} + +/** + * Internal function for long_acados_create: step 1 + */ +void long_acados_create_1_set_plan(ocp_nlp_plan_t* nlp_solver_plan, const int N) +{ + assert(N == nlp_solver_plan->N); + + /************************************************ + * plan + ************************************************/ + nlp_solver_plan->nlp_solver = SQP_RTI; + + nlp_solver_plan->ocp_qp_solver_plan.qp_solver = PARTIAL_CONDENSING_HPIPM; + + nlp_solver_plan->nlp_cost[0] = NONLINEAR_LS; + for (int i = 1; i < N; i++) + nlp_solver_plan->nlp_cost[i] = NONLINEAR_LS; + + nlp_solver_plan->nlp_cost[N] = NONLINEAR_LS; + + for (int i = 0; i < N; i++) + { + nlp_solver_plan->nlp_dynamics[i] = CONTINUOUS_MODEL; + nlp_solver_plan->sim_solver_plan[i].sim_solver = ERK; + } + + for (int i = 0; i < N; i++) + {nlp_solver_plan->nlp_constraints[i] = BGH; + } + nlp_solver_plan->nlp_constraints[N] = BGH; +} + + +/** + * Internal function for long_acados_create: step 2 + */ +ocp_nlp_dims* long_acados_create_2_create_and_set_dimensions(long_solver_capsule* capsule) +{ + ocp_nlp_plan_t* nlp_solver_plan = capsule->nlp_solver_plan; + const int N = nlp_solver_plan->N; + ocp_nlp_config* nlp_config = capsule->nlp_config; + + /************************************************ + * dimensions + ************************************************/ + #define NINTNP1MEMS 17 + int* intNp1mem = (int*)malloc( (N+1)*sizeof(int)*NINTNP1MEMS ); + + int* nx = intNp1mem + (N+1)*0; + int* nu = intNp1mem + (N+1)*1; + int* nbx = intNp1mem + (N+1)*2; + int* nbu = intNp1mem + (N+1)*3; + int* nsbx = intNp1mem + (N+1)*4; + int* nsbu = intNp1mem + (N+1)*5; + int* nsg = intNp1mem + (N+1)*6; + int* nsh = intNp1mem + (N+1)*7; + int* nsphi = intNp1mem + (N+1)*8; + int* ns = intNp1mem + (N+1)*9; + int* ng = intNp1mem + (N+1)*10; + int* nh = intNp1mem + (N+1)*11; + int* nphi = intNp1mem + (N+1)*12; + int* nz = intNp1mem + (N+1)*13; + int* ny = intNp1mem + (N+1)*14; + int* nr = intNp1mem + (N+1)*15; + int* nbxe = intNp1mem + (N+1)*16; + + for (int i = 0; i < N+1; i++) + { + // common + nx[i] = NX; + nu[i] = NU; + nz[i] = NZ; + ns[i] = NS; + // cost + ny[i] = NY; + // constraints + nbx[i] = NBX; + nbu[i] = NBU; + nsbx[i] = NSBX; + nsbu[i] = NSBU; + nsg[i] = NSG; + nsh[i] = NSH; + nsphi[i] = NSPHI; + ng[i] = NG; + nh[i] = NH; + nphi[i] = NPHI; + nr[i] = NR; + nbxe[i] = 0; + } + + // for initial state + nbx[0] = NBX0; + nsbx[0] = 0; + ns[0] = NS - NSBX; + nbxe[0] = 3; + ny[0] = NY0; + + // terminal - common + nu[N] = 0; + nz[N] = 0; + ns[N] = NSN; + // cost + ny[N] = NYN; + // constraint + nbx[N] = NBXN; + nbu[N] = 0; + ng[N] = NGN; + nh[N] = NHN; + nphi[N] = NPHIN; + nr[N] = 0; + + nsbx[N] = NSBXN; + nsbu[N] = 0; + nsg[N] = NSGN; + nsh[N] = NSHN; + nsphi[N] = NSPHIN; + + /* create and set ocp_nlp_dims */ + ocp_nlp_dims * nlp_dims = ocp_nlp_dims_create(nlp_config); + + ocp_nlp_dims_set_opt_vars(nlp_config, nlp_dims, "nx", nx); + ocp_nlp_dims_set_opt_vars(nlp_config, nlp_dims, "nu", nu); + ocp_nlp_dims_set_opt_vars(nlp_config, nlp_dims, "nz", nz); + ocp_nlp_dims_set_opt_vars(nlp_config, nlp_dims, "ns", ns); + + for (int i = 0; i <= N; i++) + { + ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "nbx", &nbx[i]); + ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "nbu", &nbu[i]); + ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "nsbx", &nsbx[i]); + ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "nsbu", &nsbu[i]); + ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "ng", &ng[i]); + ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "nsg", &nsg[i]); + ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "nbxe", &nbxe[i]); + } + ocp_nlp_dims_set_cost(nlp_config, nlp_dims, 0, "ny", &ny[0]); + for (int i = 1; i < N; i++) + ocp_nlp_dims_set_cost(nlp_config, nlp_dims, i, "ny", &ny[i]); + + for (int i = 0; i < N; i++) + { + ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "nh", &nh[i]); + ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, i, "nsh", &nsh[i]); + } + ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, N, "nh", &nh[N]); + ocp_nlp_dims_set_constraints(nlp_config, nlp_dims, N, "nsh", &nsh[N]); + ocp_nlp_dims_set_cost(nlp_config, nlp_dims, N, "ny", &ny[N]); + free(intNp1mem); +return nlp_dims; +} + + +/** + * Internal function for long_acados_create: step 3 + */ +void long_acados_create_3_create_and_set_functions(long_solver_capsule* capsule) +{ + const int N = capsule->nlp_solver_plan->N; + + /************************************************ + * external functions + ************************************************/ + +#define MAP_CASADI_FNC(__CAPSULE_FNC__, __MODEL_BASE_FNC__) do{ \ + capsule->__CAPSULE_FNC__.casadi_fun = & __MODEL_BASE_FNC__ ;\ + capsule->__CAPSULE_FNC__.casadi_n_in = & __MODEL_BASE_FNC__ ## _n_in; \ + capsule->__CAPSULE_FNC__.casadi_n_out = & __MODEL_BASE_FNC__ ## _n_out; \ + capsule->__CAPSULE_FNC__.casadi_sparsity_in = & __MODEL_BASE_FNC__ ## _sparsity_in; \ + capsule->__CAPSULE_FNC__.casadi_sparsity_out = & __MODEL_BASE_FNC__ ## _sparsity_out; \ + capsule->__CAPSULE_FNC__.casadi_work = & __MODEL_BASE_FNC__ ## _work; \ + external_function_param_casadi_create(&capsule->__CAPSULE_FNC__ , 6); \ + }while(false) + + + // constraints.constr_type == "BGH" and dims.nh > 0 + capsule->nl_constr_h_fun_jac = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); + for (int i = 0; i < N; i++) { + MAP_CASADI_FNC(nl_constr_h_fun_jac[i], long_constr_h_fun_jac_uxt_zt); + } + capsule->nl_constr_h_fun = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); + for (int i = 0; i < N; i++) { + MAP_CASADI_FNC(nl_constr_h_fun[i], long_constr_h_fun); + } + + + + + // explicit ode + capsule->forw_vde_casadi = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); + for (int i = 0; i < N; i++) { + MAP_CASADI_FNC(forw_vde_casadi[i], long_expl_vde_forw); + } + + capsule->expl_ode_fun = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); + for (int i = 0; i < N; i++) { + MAP_CASADI_FNC(expl_ode_fun[i], long_expl_ode_fun); + } + + + // nonlinear least squares function + MAP_CASADI_FNC(cost_y_0_fun, long_cost_y_0_fun); + MAP_CASADI_FNC(cost_y_0_fun_jac_ut_xt, long_cost_y_0_fun_jac_ut_xt); + MAP_CASADI_FNC(cost_y_0_hess, long_cost_y_0_hess); + // nonlinear least squares cost + capsule->cost_y_fun = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); + for (int i = 0; i < N-1; i++) + { + MAP_CASADI_FNC(cost_y_fun[i], long_cost_y_fun); + } + + capsule->cost_y_fun_jac_ut_xt = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); + for (int i = 0; i < N-1; i++) + { + MAP_CASADI_FNC(cost_y_fun_jac_ut_xt[i], long_cost_y_fun_jac_ut_xt); + } + + capsule->cost_y_hess = (external_function_param_casadi *) malloc(sizeof(external_function_param_casadi)*N); + for (int i = 0; i < N-1; i++) + { + MAP_CASADI_FNC(cost_y_hess[i], long_cost_y_hess); + } + // nonlinear least square function + MAP_CASADI_FNC(cost_y_e_fun, long_cost_y_e_fun); + MAP_CASADI_FNC(cost_y_e_fun_jac_ut_xt, long_cost_y_e_fun_jac_ut_xt); + MAP_CASADI_FNC(cost_y_e_hess, long_cost_y_e_hess); + +#undef MAP_CASADI_FNC +} + + +/** + * Internal function for long_acados_create: step 4 + */ +void long_acados_create_4_set_default_parameters(long_solver_capsule* capsule) { + const int N = capsule->nlp_solver_plan->N; + // initialize parameters to nominal value + double* p = calloc(NP, sizeof(double)); + p[0] = -1.2; + p[1] = 1.2; + p[4] = 1.45; + p[5] = 0.75; + + for (int i = 0; i <= N; i++) { + long_acados_update_params(capsule, i, p, NP); + } + free(p); +} + + +/** + * Internal function for long_acados_create: step 5 + */ +void long_acados_create_5_set_nlp_in(long_solver_capsule* capsule, const int N, double* new_time_steps) +{ + assert(N == capsule->nlp_solver_plan->N); + ocp_nlp_config* nlp_config = capsule->nlp_config; + ocp_nlp_dims* nlp_dims = capsule->nlp_dims; + + /************************************************ + * nlp_in + ************************************************/ +// ocp_nlp_in * nlp_in = ocp_nlp_in_create(nlp_config, nlp_dims); +// capsule->nlp_in = nlp_in; + ocp_nlp_in * nlp_in = capsule->nlp_in; + + // set up time_steps + + + if (new_time_steps) { + long_acados_update_time_steps(capsule, N, new_time_steps); + } else {// time_steps are different + double* time_steps = malloc(N*sizeof(double)); + time_steps[0] = 0.06944444444444445; + time_steps[1] = 0.20833333333333337; + time_steps[2] = 0.3472222222222222; + time_steps[3] = 0.4861111111111112; + time_steps[4] = 0.6250000000000002; + time_steps[5] = 0.7638888888888886; + time_steps[6] = 0.9027777777777786; + time_steps[7] = 1.041666666666666; + time_steps[8] = 1.1805555555555554; + time_steps[9] = 1.3194444444444455; + time_steps[10] = 1.4583333333333313; + time_steps[11] = 1.5972222222222232; + long_acados_update_time_steps(capsule, N, time_steps); + free(time_steps); + } + + /**** Dynamics ****/ + for (int i = 0; i < N; i++) + { + ocp_nlp_dynamics_model_set(nlp_config, nlp_dims, nlp_in, i, "expl_vde_forw", &capsule->forw_vde_casadi[i]); + ocp_nlp_dynamics_model_set(nlp_config, nlp_dims, nlp_in, i, "expl_ode_fun", &capsule->expl_ode_fun[i]); + + } + + /**** Cost ****/ + double* yref_0 = calloc(NY0, sizeof(double)); + // change only the non-zero elements: + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "yref", yref_0); + free(yref_0); + double* yref = calloc(NY, sizeof(double)); + // change only the non-zero elements: + + for (int i = 1; i < N; i++) + { + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "yref", yref); + } + free(yref); + double* yref_e = calloc(NYN, sizeof(double)); + // change only the non-zero elements: + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "yref", yref_e); + free(yref_e); + double* W_0 = calloc(NY0*NY0, sizeof(double)); + // change only the non-zero elements: + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "W", W_0); + free(W_0); + double* W = calloc(NY*NY, sizeof(double)); + // change only the non-zero elements: + + for (int i = 1; i < N; i++) + { + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "W", W); + } + free(W); + double* W_e = calloc(NYN*NYN, sizeof(double)); + // change only the non-zero elements: + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "W", W_e); + free(W_e); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "nls_y_fun", &capsule->cost_y_0_fun); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "nls_y_fun_jac", &capsule->cost_y_0_fun_jac_ut_xt); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, 0, "nls_y_hess", &capsule->cost_y_0_hess); + for (int i = 1; i < N; i++) + { + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "nls_y_fun", &capsule->cost_y_fun[i-1]); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "nls_y_fun_jac", &capsule->cost_y_fun_jac_ut_xt[i-1]); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "nls_y_hess", &capsule->cost_y_hess[i-1]); + } + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "nls_y_fun", &capsule->cost_y_e_fun); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "nls_y_fun_jac", &capsule->cost_y_e_fun_jac_ut_xt); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, N, "nls_y_hess", &capsule->cost_y_e_hess); + // slacks + double* zlumem = calloc(4*NS, sizeof(double)); + double* Zl = zlumem+NS*0; + double* Zu = zlumem+NS*1; + double* zl = zlumem+NS*2; + double* zu = zlumem+NS*3; + // change only the non-zero elements: + + for (int i = 0; i < N; i++) + { + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "Zl", Zl); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "Zu", Zu); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "zl", zl); + ocp_nlp_cost_model_set(nlp_config, nlp_dims, nlp_in, i, "zu", zu); + } + free(zlumem); + + + + /**** Constraints ****/ + + // bounds for initial stage + // x0 + int* idxbx0 = malloc(NBX0 * sizeof(int)); + idxbx0[0] = 0; + idxbx0[1] = 1; + idxbx0[2] = 2; + + double* lubx0 = calloc(2*NBX0, sizeof(double)); + double* lbx0 = lubx0; + double* ubx0 = lubx0 + NBX0; + // change only the non-zero elements: + + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "idxbx", idxbx0); + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "lbx", lbx0); + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "ubx", ubx0); + free(idxbx0); + free(lubx0); + // idxbxe_0 + int* idxbxe_0 = malloc(3 * sizeof(int)); + + idxbxe_0[0] = 0; + idxbxe_0[1] = 1; + idxbxe_0[2] = 2; + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "idxbxe", idxbxe_0); + free(idxbxe_0); + + /* constraints that are the same for initial and intermediate */ + + + + + // set up soft bounds for nonlinear constraints + int* idxsh = malloc(NSH * sizeof(int)); + + idxsh[0] = 0; + idxsh[1] = 1; + idxsh[2] = 2; + idxsh[3] = 3; + double* lush = calloc(2*NSH, sizeof(double)); + double* lsh = lush; + double* ush = lush + NSH; + + + for (int i = 0; i < N; i++) + { + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "idxsh", idxsh); + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "lsh", lsh); + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "ush", ush); + } + free(idxsh); + free(lush); + + + + + + + + + // set up nonlinear constraints for stage 0 to N-1 + double* luh = calloc(2*NH, sizeof(double)); + double* lh = luh; + double* uh = luh + NH; + + + + + uh[0] = 10000.0; + uh[1] = 10000.0; + uh[2] = 10000.0; + uh[3] = 10000.0; + + for (int i = 0; i < N; i++) + { + // nonlinear constraints for stages 0 to N-1 + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "nl_constr_h_fun_jac", + &capsule->nl_constr_h_fun_jac[i]); + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "nl_constr_h_fun", + &capsule->nl_constr_h_fun[i]); + + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "lh", lh); + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, i, "uh", uh); + } + free(luh); + + + + /* terminal constraints */ + + + + + + + + + + + + + + + +} + + +/** + * Internal function for long_acados_create: step 6 + */ +void long_acados_create_6_set_opts(long_solver_capsule* capsule) +{ + const int N = capsule->nlp_solver_plan->N; + ocp_nlp_config* nlp_config = capsule->nlp_config; + void *nlp_opts = capsule->nlp_opts; + + /************************************************ + * opts + ************************************************/ + + + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "globalization", "fixed_step");int full_step_dual = 0; + ocp_nlp_solver_opts_set(nlp_config, capsule->nlp_opts, "full_step_dual", &full_step_dual); + + // set collocation type (relevant for implicit integrators) + sim_collocation_type collocation_type = GAUSS_LEGENDRE; + for (int i = 0; i < N; i++) + ocp_nlp_solver_opts_set_at_stage(nlp_config, nlp_opts, i, "dynamics_collocation_type", &collocation_type); + + // set up sim_method_num_steps + // all sim_method_num_steps are identical + int sim_method_num_steps = 1; + for (int i = 0; i < N; i++) + ocp_nlp_solver_opts_set_at_stage(nlp_config, nlp_opts, i, "dynamics_num_steps", &sim_method_num_steps); + + // set up sim_method_num_stages + // all sim_method_num_stages are identical + int sim_method_num_stages = 4; + for (int i = 0; i < N; i++) + ocp_nlp_solver_opts_set_at_stage(nlp_config, nlp_opts, i, "dynamics_num_stages", &sim_method_num_stages); + + int newton_iter_val = 3; + for (int i = 0; i < N; i++) + ocp_nlp_solver_opts_set_at_stage(nlp_config, nlp_opts, i, "dynamics_newton_iter", &newton_iter_val); + + + // set up sim_method_jac_reuse + bool tmp_bool = (bool) 0; + for (int i = 0; i < N; i++) + ocp_nlp_solver_opts_set_at_stage(nlp_config, nlp_opts, i, "dynamics_jac_reuse", &tmp_bool); + + double nlp_solver_step_length = 1.0; + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "step_length", &nlp_solver_step_length); + + double levenberg_marquardt = 0.0; + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "levenberg_marquardt", &levenberg_marquardt); + + /* options QP solver */ + int qp_solver_cond_N; + + const int qp_solver_cond_N_ori = 1; + qp_solver_cond_N = N < qp_solver_cond_N_ori ? N : qp_solver_cond_N_ori; // use the minimum value here + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_cond_N", &qp_solver_cond_N); + + int nlp_solver_ext_qp_res = 0; + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "ext_qp_res", &nlp_solver_ext_qp_res); + // set HPIPM mode: should be done before setting other QP solver options + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_hpipm_mode", "BALANCE"); + + + + int qp_solver_iter_max = 10; + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_iter_max", &qp_solver_iter_max); + + + double qp_solver_tol_stat = 0.001; + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_tol_stat", &qp_solver_tol_stat); + double qp_solver_tol_eq = 0.001; + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_tol_eq", &qp_solver_tol_eq); + double qp_solver_tol_ineq = 0.001; + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_tol_ineq", &qp_solver_tol_ineq); + double qp_solver_tol_comp = 0.001; + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_tol_comp", &qp_solver_tol_comp);int print_level = 0; + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "print_level", &print_level); + int qp_solver_cond_ric_alg = 1; + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_cond_ric_alg", &qp_solver_cond_ric_alg); + + int qp_solver_ric_alg = 1; + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "qp_ric_alg", &qp_solver_ric_alg); + + + int ext_cost_num_hess = 0; +} + + +/** + * Internal function for long_acados_create: step 7 + */ +void long_acados_create_7_set_nlp_out(long_solver_capsule* capsule) +{ + const int N = capsule->nlp_solver_plan->N; + ocp_nlp_config* nlp_config = capsule->nlp_config; + ocp_nlp_dims* nlp_dims = capsule->nlp_dims; + ocp_nlp_out* nlp_out = capsule->nlp_out; + + // initialize primal solution + double* xu0 = calloc(NX+NU, sizeof(double)); + double* x0 = xu0; + + // initialize with x0 + + + + double* u0 = xu0 + NX; + + for (int i = 0; i < N; i++) + { + // x0 + ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, i, "x", x0); + // u0 + ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, i, "u", u0); + } + ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, N, "x", x0); + free(xu0); +} + + +/** + * Internal function for long_acados_create: step 8 + */ +//void long_acados_create_8_create_solver(long_solver_capsule* capsule) +//{ +// capsule->nlp_solver = ocp_nlp_solver_create(capsule->nlp_config, capsule->nlp_dims, capsule->nlp_opts); +//} + +/** + * Internal function for long_acados_create: step 9 + */ +int long_acados_create_9_precompute(long_solver_capsule* capsule) { + int status = ocp_nlp_precompute(capsule->nlp_solver, capsule->nlp_in, capsule->nlp_out); + + if (status != ACADOS_SUCCESS) { + printf("\nocp_nlp_precompute failed!\n\n"); + exit(1); + } + + return status; +} + + +int long_acados_create_with_discretization(long_solver_capsule* capsule, int N, double* new_time_steps) +{ + // If N does not match the number of shooting intervals used for code generation, new_time_steps must be given. + if (N != LONG_N && !new_time_steps) { + fprintf(stderr, "long_acados_create_with_discretization: new_time_steps is NULL " \ + "but the number of shooting intervals (= %d) differs from the number of " \ + "shooting intervals (= %d) during code generation! Please provide a new vector of time_stamps!\n", \ + N, LONG_N); + return 1; + } + + // number of expected runtime parameters + capsule->nlp_np = NP; + + // 1) create and set nlp_solver_plan; create nlp_config + capsule->nlp_solver_plan = ocp_nlp_plan_create(N); + long_acados_create_1_set_plan(capsule->nlp_solver_plan, N); + capsule->nlp_config = ocp_nlp_config_create(*capsule->nlp_solver_plan); + + // 3) create and set dimensions + capsule->nlp_dims = long_acados_create_2_create_and_set_dimensions(capsule); + long_acados_create_3_create_and_set_functions(capsule); + + // 4) set default parameters in functions + long_acados_create_4_set_default_parameters(capsule); + + // 5) create and set nlp_in + capsule->nlp_in = ocp_nlp_in_create(capsule->nlp_config, capsule->nlp_dims); + long_acados_create_5_set_nlp_in(capsule, N, new_time_steps); + + // 6) create and set nlp_opts + capsule->nlp_opts = ocp_nlp_solver_opts_create(capsule->nlp_config, capsule->nlp_dims); + long_acados_create_6_set_opts(capsule); + + // 7) create and set nlp_out + // 7.1) nlp_out + capsule->nlp_out = ocp_nlp_out_create(capsule->nlp_config, capsule->nlp_dims); + // 7.2) sens_out + capsule->sens_out = ocp_nlp_out_create(capsule->nlp_config, capsule->nlp_dims); + long_acados_create_7_set_nlp_out(capsule); + + // 8) create solver + capsule->nlp_solver = ocp_nlp_solver_create(capsule->nlp_config, capsule->nlp_dims, capsule->nlp_opts); + //long_acados_create_8_create_solver(capsule); + + // 9) do precomputations + int status = long_acados_create_9_precompute(capsule); + + return status; +} + +/** + * This function is for updating an already initialized solver with a different number of qp_cond_N. It is useful for code reuse after code export. + */ +int long_acados_update_qp_solver_cond_N(long_solver_capsule* capsule, int qp_solver_cond_N) +{ + // 1) destroy solver + ocp_nlp_solver_destroy(capsule->nlp_solver); + + // 2) set new value for "qp_cond_N" + const int N = capsule->nlp_solver_plan->N; + if(qp_solver_cond_N > N) + printf("Warning: qp_solver_cond_N = %d > N = %d\n", qp_solver_cond_N, N); + ocp_nlp_solver_opts_set(capsule->nlp_config, capsule->nlp_opts, "qp_cond_N", &qp_solver_cond_N); + + // 3) continue with the remaining steps from long_acados_create_with_discretization(...): + // -> 8) create solver + capsule->nlp_solver = ocp_nlp_solver_create(capsule->nlp_config, capsule->nlp_dims, capsule->nlp_opts); + + // -> 9) do precomputations + int status = long_acados_create_9_precompute(capsule); + return status; +} + + +int long_acados_reset(long_solver_capsule* capsule, int reset_qp_solver_mem) +{ + + // set initialization to all zeros + + const int N = capsule->nlp_solver_plan->N; + ocp_nlp_config* nlp_config = capsule->nlp_config; + ocp_nlp_dims* nlp_dims = capsule->nlp_dims; + ocp_nlp_out* nlp_out = capsule->nlp_out; + ocp_nlp_in* nlp_in = capsule->nlp_in; + ocp_nlp_solver* nlp_solver = capsule->nlp_solver; + + double* buffer = calloc(NX+NU+NZ+2*NS+2*NSN+NBX+NBU+NG+NH+NPHI+NBX0+NBXN+NHN+NPHIN+NGN, sizeof(double)); + + for(int i=0; i reset memory + int qp_status; + ocp_nlp_get(capsule->nlp_config, capsule->nlp_solver, "qp_status", &qp_status); + if (reset_qp_solver_mem || (qp_status == 3)) + { + // printf("\nin reset qp_status %d -> resetting QP memory\n", qp_status); + ocp_nlp_solver_reset_qp_memory(nlp_solver, nlp_in, nlp_out); + } + + free(buffer); + return 0; +} + + + + +int long_acados_update_params(long_solver_capsule* capsule, int stage, double *p, int np) +{ + int solver_status = 0; + + int casadi_np = 6; + if (casadi_np != np) { + printf("acados_update_params: trying to set %i parameters for external functions." + " External function has %i parameters. Exiting.\n", np, casadi_np); + exit(1); + } + + const int N = capsule->nlp_solver_plan->N; + if (stage < N && stage >= 0) + { + capsule->forw_vde_casadi[stage].set_param(capsule->forw_vde_casadi+stage, p); + capsule->expl_ode_fun[stage].set_param(capsule->expl_ode_fun+stage, p); + + + // constraints + + capsule->nl_constr_h_fun_jac[stage].set_param(capsule->nl_constr_h_fun_jac+stage, p); + capsule->nl_constr_h_fun[stage].set_param(capsule->nl_constr_h_fun+stage, p); + + // cost + if (stage == 0) + { + capsule->cost_y_0_fun.set_param(&capsule->cost_y_0_fun, p); + capsule->cost_y_0_fun_jac_ut_xt.set_param(&capsule->cost_y_0_fun_jac_ut_xt, p); + capsule->cost_y_0_hess.set_param(&capsule->cost_y_0_hess, p); + } + else // 0 < stage < N + { + capsule->cost_y_fun[stage-1].set_param(capsule->cost_y_fun+stage-1, p); + capsule->cost_y_fun_jac_ut_xt[stage-1].set_param(capsule->cost_y_fun_jac_ut_xt+stage-1, p); + capsule->cost_y_hess[stage-1].set_param(capsule->cost_y_hess+stage-1, p); + } + } + + else // stage == N + { + // terminal shooting node has no dynamics + // cost + capsule->cost_y_e_fun.set_param(&capsule->cost_y_e_fun, p); + capsule->cost_y_e_fun_jac_ut_xt.set_param(&capsule->cost_y_e_fun_jac_ut_xt, p); + capsule->cost_y_e_hess.set_param(&capsule->cost_y_e_hess, p); + // constraints + + } + + return solver_status; +} + + +int long_acados_update_params_sparse(long_solver_capsule * capsule, int stage, int *idx, double *p, int n_update) +{ + int solver_status = 0; + + int casadi_np = 6; + if (casadi_np < n_update) { + printf("long_acados_update_params_sparse: trying to set %d parameters for external functions." + " External function has %d parameters. Exiting.\n", n_update, casadi_np); + exit(1); + } + // for (int i = 0; i < n_update; i++) + // { + // if (idx[i] > casadi_np) { + // printf("long_acados_update_params_sparse: attempt to set parameters with index %d, while" + // " external functions only has %d parameters. Exiting.\n", idx[i], casadi_np); + // exit(1); + // } + // printf("param %d value %e\n", idx[i], p[i]); + // } + const int N = capsule->nlp_solver_plan->N; + if (stage < N && stage >= 0) + { + capsule->forw_vde_casadi[stage].set_param_sparse(capsule->forw_vde_casadi+stage, n_update, idx, p); + capsule->expl_ode_fun[stage].set_param_sparse(capsule->expl_ode_fun+stage, n_update, idx, p); + + + // constraints + + capsule->nl_constr_h_fun_jac[stage].set_param_sparse(capsule->nl_constr_h_fun_jac+stage, n_update, idx, p); + capsule->nl_constr_h_fun[stage].set_param_sparse(capsule->nl_constr_h_fun+stage, n_update, idx, p); + + // cost + if (stage == 0) + { + capsule->cost_y_0_fun.set_param_sparse(&capsule->cost_y_0_fun, n_update, idx, p); + capsule->cost_y_0_fun_jac_ut_xt.set_param_sparse(&capsule->cost_y_0_fun_jac_ut_xt, n_update, idx, p); + capsule->cost_y_0_hess.set_param_sparse(&capsule->cost_y_0_hess, n_update, idx, p); + } + else // 0 < stage < N + { + capsule->cost_y_fun[stage-1].set_param_sparse(capsule->cost_y_fun+stage-1, n_update, idx, p); + capsule->cost_y_fun_jac_ut_xt[stage-1].set_param_sparse(capsule->cost_y_fun_jac_ut_xt+stage-1, n_update, idx, p); + capsule->cost_y_hess[stage-1].set_param_sparse(capsule->cost_y_hess+stage-1, n_update, idx, p); + } + } + + else // stage == N + { + // terminal shooting node has no dynamics + // cost + capsule->cost_y_e_fun.set_param_sparse(&capsule->cost_y_e_fun, n_update, idx, p); + capsule->cost_y_e_fun_jac_ut_xt.set_param_sparse(&capsule->cost_y_e_fun_jac_ut_xt, n_update, idx, p); + capsule->cost_y_e_hess.set_param_sparse(&capsule->cost_y_e_hess, n_update, idx, p); + // constraints + + } + + + return solver_status; +} + +int long_acados_solve(long_solver_capsule* capsule) +{ + // solve NLP + int solver_status = ocp_nlp_solve(capsule->nlp_solver, capsule->nlp_in, capsule->nlp_out); + + return solver_status; +} + + +int long_acados_free(long_solver_capsule* capsule) +{ + // before destroying, keep some info + const int N = capsule->nlp_solver_plan->N; + // free memory + ocp_nlp_solver_opts_destroy(capsule->nlp_opts); + ocp_nlp_in_destroy(capsule->nlp_in); + ocp_nlp_out_destroy(capsule->nlp_out); + ocp_nlp_out_destroy(capsule->sens_out); + ocp_nlp_solver_destroy(capsule->nlp_solver); + ocp_nlp_dims_destroy(capsule->nlp_dims); + ocp_nlp_config_destroy(capsule->nlp_config); + ocp_nlp_plan_destroy(capsule->nlp_solver_plan); + + /* free external function */ + // dynamics + for (int i = 0; i < N; i++) + { + external_function_param_casadi_free(&capsule->forw_vde_casadi[i]); + external_function_param_casadi_free(&capsule->expl_ode_fun[i]); + } + free(capsule->forw_vde_casadi); + free(capsule->expl_ode_fun); + + // cost + external_function_param_casadi_free(&capsule->cost_y_0_fun); + external_function_param_casadi_free(&capsule->cost_y_0_fun_jac_ut_xt); + external_function_param_casadi_free(&capsule->cost_y_0_hess); + for (int i = 0; i < N - 1; i++) + { + external_function_param_casadi_free(&capsule->cost_y_fun[i]); + external_function_param_casadi_free(&capsule->cost_y_fun_jac_ut_xt[i]); + external_function_param_casadi_free(&capsule->cost_y_hess[i]); + } + free(capsule->cost_y_fun); + free(capsule->cost_y_fun_jac_ut_xt); + free(capsule->cost_y_hess); + external_function_param_casadi_free(&capsule->cost_y_e_fun); + external_function_param_casadi_free(&capsule->cost_y_e_fun_jac_ut_xt); + external_function_param_casadi_free(&capsule->cost_y_e_hess); + + // constraints + for (int i = 0; i < N; i++) + { + external_function_param_casadi_free(&capsule->nl_constr_h_fun_jac[i]); + external_function_param_casadi_free(&capsule->nl_constr_h_fun[i]); + } + free(capsule->nl_constr_h_fun_jac); + free(capsule->nl_constr_h_fun); + + return 0; +} + + +void long_acados_print_stats(long_solver_capsule* capsule) +{ + int sqp_iter, stat_m, stat_n, tmp_int; + ocp_nlp_get(capsule->nlp_config, capsule->nlp_solver, "sqp_iter", &sqp_iter); + ocp_nlp_get(capsule->nlp_config, capsule->nlp_solver, "stat_n", &stat_n); + ocp_nlp_get(capsule->nlp_config, capsule->nlp_solver, "stat_m", &stat_m); + + + double stat[1200]; + ocp_nlp_get(capsule->nlp_config, capsule->nlp_solver, "statistics", stat); + + int nrow = sqp_iter+1 < stat_m ? sqp_iter+1 : stat_m; + + printf("iter\tres_stat\tres_eq\t\tres_ineq\tres_comp\tqp_stat\tqp_iter\talpha"); + if (stat_n > 8) + printf("\t\tqp_res_stat\tqp_res_eq\tqp_res_ineq\tqp_res_comp"); + printf("\n"); + printf("iter\tqp_stat\tqp_iter\n"); + for (int i = 0; i < nrow; i++) + { + for (int j = 0; j < stat_n + 1; j++) + { + tmp_int = (int) stat[i + j * nrow]; + printf("%d\t", tmp_int); + } + printf("\n"); + } +} + +int long_acados_custom_update(long_solver_capsule* capsule, double* data, int data_len) +{ + (void)capsule; + (void)data; + (void)data_len; + printf("\ndummy function that can be called in between solver calls to update parameters or numerical data efficiently in C.\n"); + printf("nothing set yet..\n"); + return 1; + +} + + + +ocp_nlp_in *long_acados_get_nlp_in(long_solver_capsule* capsule) { return capsule->nlp_in; } +ocp_nlp_out *long_acados_get_nlp_out(long_solver_capsule* capsule) { return capsule->nlp_out; } +ocp_nlp_out *long_acados_get_sens_out(long_solver_capsule* capsule) { return capsule->sens_out; } +ocp_nlp_solver *long_acados_get_nlp_solver(long_solver_capsule* capsule) { return capsule->nlp_solver; } +ocp_nlp_config *long_acados_get_nlp_config(long_solver_capsule* capsule) { return capsule->nlp_config; } +void *long_acados_get_nlp_opts(long_solver_capsule* capsule) { return capsule->nlp_opts; } +ocp_nlp_dims *long_acados_get_nlp_dims(long_solver_capsule* capsule) { return capsule->nlp_dims; } +ocp_nlp_plan_t *long_acados_get_nlp_plan(long_solver_capsule* capsule) { return capsule->nlp_solver_plan; } diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/libacados_ocp_solver_long.so b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/libacados_ocp_solver_long.so new file mode 100755 index 0000000..00e02a4 Binary files /dev/null and b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/libacados_ocp_solver_long.so differ diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_constraints/long_constr_h_fun.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_constraints/long_constr_h_fun.c new file mode 100644 index 0000000..be006b8 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_constraints/long_constr_h_fun.c @@ -0,0 +1,179 @@ +/* This file was automatically generated by CasADi 3.6.4. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) long_constr_h_fun_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) +#define casadi_s4 CASADI_PREFIX(s4) +#define casadi_sq CASADI_PREFIX(sq) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +casadi_real casadi_sq(casadi_real x) { return x*x;} + +static const casadi_int casadi_s0[7] = {3, 1, 0, 3, 0, 1, 2}; +static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; +static const casadi_int casadi_s2[3] = {0, 0, 0}; +static const casadi_int casadi_s3[10] = {6, 1, 0, 6, 0, 1, 2, 3, 4, 5}; +static const casadi_int casadi_s4[8] = {4, 1, 0, 4, 0, 1, 2, 3}; + +/* long_constr_h_fun:(i0[3],i1,i2[],i3[6])->(o0[4]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a2, a3, a4; + a0=arg[0]? arg[0][1] : 0; + if (res[0]!=0) res[0][0]=a0; + a1=arg[0]? arg[0][2] : 0; + a2=arg[3]? arg[3][0] : 0; + a2=(a1-a2); + if (res[0]!=0) res[0][1]=a2; + a2=arg[3]? arg[3][1] : 0; + a2=(a2-a1); + if (res[0]!=0) res[0][2]=a2; + a2=arg[3]? arg[3][2] : 0; + a1=arg[0]? arg[0][0] : 0; + a2=(a2-a1); + a1=arg[3]? arg[3][5] : 0; + a3=casadi_sq(a0); + a4=5.; + a3=(a3/a4); + a4=arg[3]? arg[3][4] : 0; + a4=(a4*a0); + a3=(a3+a4); + a4=6.; + a3=(a3+a4); + a1=(a1*a3); + a2=(a2-a1); + a1=10.; + a0=(a0+a1); + a2=(a2/a0); + if (res[0]!=0) res[0][3]=a2; + return 0; +} + +CASADI_SYMBOL_EXPORT int long_constr_h_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int long_constr_h_fun_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int long_constr_h_fun_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_constr_h_fun_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int long_constr_h_fun_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_constr_h_fun_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void long_constr_h_fun_incref(void) { +} + +CASADI_SYMBOL_EXPORT void long_constr_h_fun_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int long_constr_h_fun_n_in(void) { return 4;} + +CASADI_SYMBOL_EXPORT casadi_int long_constr_h_fun_n_out(void) { return 1;} + +CASADI_SYMBOL_EXPORT casadi_real long_constr_h_fun_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_constr_h_fun_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_constr_h_fun_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_constr_h_fun_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + case 3: return casadi_s3; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_constr_h_fun_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s4; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int long_constr_h_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 4; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_constraints/long_constr_h_fun_jac_uxt_zt.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_constraints/long_constr_h_fun_jac_uxt_zt.c new file mode 100644 index 0000000..7f78a87 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_constraints/long_constr_h_fun_jac_uxt_zt.c @@ -0,0 +1,205 @@ +/* This file was automatically generated by CasADi 3.6.4. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) long_constr_h_fun_jac_uxt_zt_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) +#define casadi_s4 CASADI_PREFIX(s4) +#define casadi_s5 CASADI_PREFIX(s5) +#define casadi_s6 CASADI_PREFIX(s6) +#define casadi_sq CASADI_PREFIX(sq) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +casadi_real casadi_sq(casadi_real x) { return x*x;} + +static const casadi_int casadi_s0[7] = {3, 1, 0, 3, 0, 1, 2}; +static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; +static const casadi_int casadi_s2[3] = {0, 0, 0}; +static const casadi_int casadi_s3[10] = {6, 1, 0, 6, 0, 1, 2, 3, 4, 5}; +static const casadi_int casadi_s4[8] = {4, 1, 0, 4, 0, 1, 2, 3}; +static const casadi_int casadi_s5[12] = {4, 4, 0, 1, 2, 3, 5, 2, 3, 3, 1, 2}; +static const casadi_int casadi_s6[3] = {4, 0, 0}; + +/* long_constr_h_fun_jac_uxt_zt:(i0[3],i1,i2[],i3[6])->(o0[4],o1[4x4,5nz],o2[4x0]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a2, a3, a4, a5; + a0=arg[0]? arg[0][1] : 0; + if (res[0]!=0) res[0][0]=a0; + a1=arg[0]? arg[0][2] : 0; + a2=arg[3]? arg[3][0] : 0; + a2=(a1-a2); + if (res[0]!=0) res[0][1]=a2; + a2=arg[3]? arg[3][1] : 0; + a2=(a2-a1); + if (res[0]!=0) res[0][2]=a2; + a2=arg[3]? arg[3][2] : 0; + a1=arg[0]? arg[0][0] : 0; + a2=(a2-a1); + a1=arg[3]? arg[3][5] : 0; + a3=casadi_sq(a0); + a4=5.; + a3=(a3/a4); + a4=arg[3]? arg[3][4] : 0; + a5=(a4*a0); + a3=(a3+a5); + a5=6.; + a3=(a3+a5); + a3=(a1*a3); + a2=(a2-a3); + a3=10.; + a3=(a0+a3); + a2=(a2/a3); + if (res[0]!=0) res[0][3]=a2; + a5=1.; + if (res[1]!=0) res[1][0]=a5; + if (res[1]!=0) res[1][1]=a5; + a5=-1.; + if (res[1]!=0) res[1][2]=a5; + a5=(1./a3); + a5=(-a5); + if (res[1]!=0) res[1][3]=a5; + a5=2.0000000000000001e-01; + a0=(a0+a0); + a5=(a5*a0); + a5=(a5+a4); + a1=(a1*a5); + a1=(a1/a3); + a2=(a2/a3); + a1=(a1+a2); + a1=(-a1); + if (res[1]!=0) res[1][4]=a1; + return 0; +} + +CASADI_SYMBOL_EXPORT int long_constr_h_fun_jac_uxt_zt(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int long_constr_h_fun_jac_uxt_zt_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int long_constr_h_fun_jac_uxt_zt_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_constr_h_fun_jac_uxt_zt_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int long_constr_h_fun_jac_uxt_zt_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_constr_h_fun_jac_uxt_zt_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void long_constr_h_fun_jac_uxt_zt_incref(void) { +} + +CASADI_SYMBOL_EXPORT void long_constr_h_fun_jac_uxt_zt_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int long_constr_h_fun_jac_uxt_zt_n_in(void) { return 4;} + +CASADI_SYMBOL_EXPORT casadi_int long_constr_h_fun_jac_uxt_zt_n_out(void) { return 3;} + +CASADI_SYMBOL_EXPORT casadi_real long_constr_h_fun_jac_uxt_zt_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_constr_h_fun_jac_uxt_zt_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_constr_h_fun_jac_uxt_zt_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + case 1: return "o1"; + case 2: return "o2"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_constr_h_fun_jac_uxt_zt_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + case 3: return casadi_s3; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_constr_h_fun_jac_uxt_zt_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s4; + case 1: return casadi_s5; + case 2: return casadi_s6; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int long_constr_h_fun_jac_uxt_zt_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 4; + if (sz_res) *sz_res = 3; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_0_fun.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_0_fun.c new file mode 100644 index 0000000..1189293 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_0_fun.c @@ -0,0 +1,176 @@ +/* This file was automatically generated by CasADi 3.6.4. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) long_cost_y_0_fun_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) +#define casadi_sq CASADI_PREFIX(sq) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +casadi_real casadi_sq(casadi_real x) { return x*x;} + +static const casadi_int casadi_s0[7] = {3, 1, 0, 3, 0, 1, 2}; +static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; +static const casadi_int casadi_s2[3] = {0, 0, 0}; +static const casadi_int casadi_s3[10] = {6, 1, 0, 6, 0, 1, 2, 3, 4, 5}; + +/* long_cost_y_0_fun:(i0[3],i1,i2[],i3[6])->(o0[6]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a2, a3, a4; + a0=arg[3]? arg[3][2] : 0; + a1=arg[0]? arg[0][0] : 0; + a0=(a0-a1); + a2=arg[0]? arg[0][1] : 0; + a3=casadi_sq(a2); + a4=5.; + a3=(a3/a4); + a4=arg[3]? arg[3][4] : 0; + a4=(a4*a2); + a3=(a3+a4); + a4=6.; + a3=(a3+a4); + a0=(a0-a3); + a3=10.; + a3=(a2+a3); + a0=(a0/a3); + if (res[0]!=0) res[0][0]=a0; + if (res[0]!=0) res[0][1]=a1; + if (res[0]!=0) res[0][2]=a2; + a2=arg[0]? arg[0][2] : 0; + if (res[0]!=0) res[0][3]=a2; + a1=arg[3]? arg[3][3] : 0; + a2=(a2-a1); + if (res[0]!=0) res[0][4]=a2; + a2=arg[1]? arg[1][0] : 0; + if (res[0]!=0) res[0][5]=a2; + return 0; +} + +CASADI_SYMBOL_EXPORT int long_cost_y_0_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int long_cost_y_0_fun_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int long_cost_y_0_fun_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_cost_y_0_fun_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int long_cost_y_0_fun_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_cost_y_0_fun_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void long_cost_y_0_fun_incref(void) { +} + +CASADI_SYMBOL_EXPORT void long_cost_y_0_fun_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_0_fun_n_in(void) { return 4;} + +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_0_fun_n_out(void) { return 1;} + +CASADI_SYMBOL_EXPORT casadi_real long_cost_y_0_fun_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_cost_y_0_fun_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_cost_y_0_fun_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_0_fun_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + case 3: return casadi_s3; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_0_fun_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s3; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int long_cost_y_0_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 4; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_0_fun_jac_ut_xt.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_0_fun_jac_ut_xt.c new file mode 100644 index 0000000..7227e03 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_0_fun_jac_ut_xt.c @@ -0,0 +1,202 @@ +/* This file was automatically generated by CasADi 3.6.4. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) long_cost_y_0_fun_jac_ut_xt_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) +#define casadi_s4 CASADI_PREFIX(s4) +#define casadi_s5 CASADI_PREFIX(s5) +#define casadi_sq CASADI_PREFIX(sq) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +casadi_real casadi_sq(casadi_real x) { return x*x;} + +static const casadi_int casadi_s0[7] = {3, 1, 0, 3, 0, 1, 2}; +static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; +static const casadi_int casadi_s2[3] = {0, 0, 0}; +static const casadi_int casadi_s3[10] = {6, 1, 0, 6, 0, 1, 2, 3, 4, 5}; +static const casadi_int casadi_s4[16] = {4, 6, 0, 2, 3, 4, 5, 6, 7, 1, 2, 1, 2, 3, 3, 0}; +static const casadi_int casadi_s5[3] = {6, 0, 0}; + +/* long_cost_y_0_fun_jac_ut_xt:(i0[3],i1,i2[],i3[6])->(o0[6],o1[4x6,7nz],o2[6x0]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a2, a3, a4, a5; + a0=arg[3]? arg[3][2] : 0; + a1=arg[0]? arg[0][0] : 0; + a0=(a0-a1); + a2=arg[0]? arg[0][1] : 0; + a3=casadi_sq(a2); + a4=5.; + a3=(a3/a4); + a4=arg[3]? arg[3][4] : 0; + a5=(a4*a2); + a3=(a3+a5); + a5=6.; + a3=(a3+a5); + a0=(a0-a3); + a3=10.; + a3=(a2+a3); + a0=(a0/a3); + if (res[0]!=0) res[0][0]=a0; + if (res[0]!=0) res[0][1]=a1; + if (res[0]!=0) res[0][2]=a2; + a1=arg[0]? arg[0][2] : 0; + if (res[0]!=0) res[0][3]=a1; + a5=arg[3]? arg[3][3] : 0; + a1=(a1-a5); + if (res[0]!=0) res[0][4]=a1; + a1=arg[1]? arg[1][0] : 0; + if (res[0]!=0) res[0][5]=a1; + a1=(1./a3); + a1=(-a1); + if (res[1]!=0) res[1][0]=a1; + a1=2.0000000000000001e-01; + a2=(a2+a2); + a1=(a1*a2); + a1=(a1+a4); + a1=(a1/a3); + a0=(a0/a3); + a1=(a1+a0); + a1=(-a1); + if (res[1]!=0) res[1][1]=a1; + a1=1.; + if (res[1]!=0) res[1][2]=a1; + if (res[1]!=0) res[1][3]=a1; + if (res[1]!=0) res[1][4]=a1; + if (res[1]!=0) res[1][5]=a1; + if (res[1]!=0) res[1][6]=a1; + return 0; +} + +CASADI_SYMBOL_EXPORT int long_cost_y_0_fun_jac_ut_xt(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int long_cost_y_0_fun_jac_ut_xt_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int long_cost_y_0_fun_jac_ut_xt_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_cost_y_0_fun_jac_ut_xt_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int long_cost_y_0_fun_jac_ut_xt_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_cost_y_0_fun_jac_ut_xt_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void long_cost_y_0_fun_jac_ut_xt_incref(void) { +} + +CASADI_SYMBOL_EXPORT void long_cost_y_0_fun_jac_ut_xt_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_0_fun_jac_ut_xt_n_in(void) { return 4;} + +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_0_fun_jac_ut_xt_n_out(void) { return 3;} + +CASADI_SYMBOL_EXPORT casadi_real long_cost_y_0_fun_jac_ut_xt_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_cost_y_0_fun_jac_ut_xt_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_cost_y_0_fun_jac_ut_xt_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + case 1: return "o1"; + case 2: return "o2"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_0_fun_jac_ut_xt_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + case 3: return casadi_s3; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_0_fun_jac_ut_xt_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s3; + case 1: return casadi_s4; + case 2: return casadi_s5; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int long_cost_y_0_fun_jac_ut_xt_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 4; + if (sz_res) *sz_res = 3; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_0_hess.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_0_hess.c new file mode 100644 index 0000000..74eec0d --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_0_hess.c @@ -0,0 +1,201 @@ +/* This file was automatically generated by CasADi 3.6.4. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) long_cost_y_0_hess_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) +#define casadi_s4 CASADI_PREFIX(s4) +#define casadi_sq CASADI_PREFIX(sq) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +casadi_real casadi_sq(casadi_real x) { return x*x;} + +static const casadi_int casadi_s0[7] = {3, 1, 0, 3, 0, 1, 2}; +static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; +static const casadi_int casadi_s2[3] = {0, 0, 0}; +static const casadi_int casadi_s3[10] = {6, 1, 0, 6, 0, 1, 2, 3, 4, 5}; +static const casadi_int casadi_s4[10] = {4, 4, 0, 0, 1, 3, 3, 2, 1, 2}; + +/* long_cost_y_0_hess:(i0[3],i1,i2[],i3[6],i4[6])->(o0[4x4,3nz]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a10, a2, a3, a4, a5, a6, a7, a8, a9; + a0=arg[3]? arg[3][0] : 0; + a1=arg[0]? arg[0][1] : 0; + a2=10.; + a2=(a1+a2); + a3=(1./a2); + a3=(a3/a2); + a3=(a0*a3); + if (res[0]!=0) res[0][0]=a3; + a3=(a0/a2); + a4=(a3/a2); + if (res[0]!=0) res[0][1]=a4; + a5=2.0000000000000001e-01; + a6=(a1+a1); + a6=(a5*a6); + a7=arg[4]? arg[4][4] : 0; + a6=(a6+a7); + a6=(a6/a2); + a8=arg[4]? arg[4][2] : 0; + a9=arg[0]? arg[0][0] : 0; + a8=(a8-a9); + a9=casadi_sq(a1); + a10=5.; + a9=(a9/a10); + a10=(a7*a1); + a9=(a9+a10); + a10=6.; + a9=(a9+a10); + a8=(a8-a9); + a8=(a8/a2); + a9=(a8/a2); + a6=(a6+a9); + a6=(a6/a2); + a8=(a8/a2); + a8=(a8/a2); + a6=(a6+a8); + a0=(a0*a6); + a7=(a7*a4); + a0=(a0+a7); + a7=2.; + a3=(a5*a3); + a7=(a7*a3); + a1=(a1+a1); + a5=(a5*a4); + a1=(a1*a5); + a7=(a7-a1); + a0=(a0-a7); + if (res[0]!=0) res[0][2]=a0; + return 0; +} + +CASADI_SYMBOL_EXPORT int long_cost_y_0_hess(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int long_cost_y_0_hess_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int long_cost_y_0_hess_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_cost_y_0_hess_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int long_cost_y_0_hess_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_cost_y_0_hess_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void long_cost_y_0_hess_incref(void) { +} + +CASADI_SYMBOL_EXPORT void long_cost_y_0_hess_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_0_hess_n_in(void) { return 5;} + +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_0_hess_n_out(void) { return 1;} + +CASADI_SYMBOL_EXPORT casadi_real long_cost_y_0_hess_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_cost_y_0_hess_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + case 4: return "i4"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_cost_y_0_hess_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_0_hess_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + case 3: return casadi_s3; + case 4: return casadi_s3; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_0_hess_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s4; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int long_cost_y_0_hess_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 5; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_e_fun.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_e_fun.c new file mode 100644 index 0000000..92dcef2 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_e_fun.c @@ -0,0 +1,174 @@ +/* This file was automatically generated by CasADi 3.6.4. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) long_cost_y_e_fun_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) +#define casadi_sq CASADI_PREFIX(sq) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +casadi_real casadi_sq(casadi_real x) { return x*x;} + +static const casadi_int casadi_s0[7] = {3, 1, 0, 3, 0, 1, 2}; +static const casadi_int casadi_s1[3] = {0, 0, 0}; +static const casadi_int casadi_s2[10] = {6, 1, 0, 6, 0, 1, 2, 3, 4, 5}; +static const casadi_int casadi_s3[9] = {5, 1, 0, 5, 0, 1, 2, 3, 4}; + +/* long_cost_y_e_fun:(i0[3],i1[],i2[],i3[6])->(o0[5]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a2, a3, a4; + a0=arg[3]? arg[3][2] : 0; + a1=arg[0]? arg[0][0] : 0; + a0=(a0-a1); + a2=arg[0]? arg[0][1] : 0; + a3=casadi_sq(a2); + a4=5.; + a3=(a3/a4); + a4=arg[3]? arg[3][4] : 0; + a4=(a4*a2); + a3=(a3+a4); + a4=6.; + a3=(a3+a4); + a0=(a0-a3); + a3=10.; + a3=(a2+a3); + a0=(a0/a3); + if (res[0]!=0) res[0][0]=a0; + if (res[0]!=0) res[0][1]=a1; + if (res[0]!=0) res[0][2]=a2; + a2=arg[0]? arg[0][2] : 0; + if (res[0]!=0) res[0][3]=a2; + a1=arg[3]? arg[3][3] : 0; + a2=(a2-a1); + if (res[0]!=0) res[0][4]=a2; + return 0; +} + +CASADI_SYMBOL_EXPORT int long_cost_y_e_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int long_cost_y_e_fun_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int long_cost_y_e_fun_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_cost_y_e_fun_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int long_cost_y_e_fun_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_cost_y_e_fun_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void long_cost_y_e_fun_incref(void) { +} + +CASADI_SYMBOL_EXPORT void long_cost_y_e_fun_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_e_fun_n_in(void) { return 4;} + +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_e_fun_n_out(void) { return 1;} + +CASADI_SYMBOL_EXPORT casadi_real long_cost_y_e_fun_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_cost_y_e_fun_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_cost_y_e_fun_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_e_fun_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s1; + case 3: return casadi_s2; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_e_fun_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s3; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int long_cost_y_e_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 4; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_e_fun_jac_ut_xt.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_e_fun_jac_ut_xt.c new file mode 100644 index 0000000..3cef9bb --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_e_fun_jac_ut_xt.c @@ -0,0 +1,199 @@ +/* This file was automatically generated by CasADi 3.6.4. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) long_cost_y_e_fun_jac_ut_xt_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) +#define casadi_s4 CASADI_PREFIX(s4) +#define casadi_s5 CASADI_PREFIX(s5) +#define casadi_sq CASADI_PREFIX(sq) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +casadi_real casadi_sq(casadi_real x) { return x*x;} + +static const casadi_int casadi_s0[7] = {3, 1, 0, 3, 0, 1, 2}; +static const casadi_int casadi_s1[3] = {0, 0, 0}; +static const casadi_int casadi_s2[10] = {6, 1, 0, 6, 0, 1, 2, 3, 4, 5}; +static const casadi_int casadi_s3[9] = {5, 1, 0, 5, 0, 1, 2, 3, 4}; +static const casadi_int casadi_s4[14] = {3, 5, 0, 2, 3, 4, 5, 6, 0, 1, 0, 1, 2, 2}; +static const casadi_int casadi_s5[3] = {5, 0, 0}; + +/* long_cost_y_e_fun_jac_ut_xt:(i0[3],i1[],i2[],i3[6])->(o0[5],o1[3x5,6nz],o2[5x0]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a2, a3, a4, a5; + a0=arg[3]? arg[3][2] : 0; + a1=arg[0]? arg[0][0] : 0; + a0=(a0-a1); + a2=arg[0]? arg[0][1] : 0; + a3=casadi_sq(a2); + a4=5.; + a3=(a3/a4); + a4=arg[3]? arg[3][4] : 0; + a5=(a4*a2); + a3=(a3+a5); + a5=6.; + a3=(a3+a5); + a0=(a0-a3); + a3=10.; + a3=(a2+a3); + a0=(a0/a3); + if (res[0]!=0) res[0][0]=a0; + if (res[0]!=0) res[0][1]=a1; + if (res[0]!=0) res[0][2]=a2; + a1=arg[0]? arg[0][2] : 0; + if (res[0]!=0) res[0][3]=a1; + a5=arg[3]? arg[3][3] : 0; + a1=(a1-a5); + if (res[0]!=0) res[0][4]=a1; + a1=(1./a3); + a1=(-a1); + if (res[1]!=0) res[1][0]=a1; + a1=2.0000000000000001e-01; + a2=(a2+a2); + a1=(a1*a2); + a1=(a1+a4); + a1=(a1/a3); + a0=(a0/a3); + a1=(a1+a0); + a1=(-a1); + if (res[1]!=0) res[1][1]=a1; + a1=1.; + if (res[1]!=0) res[1][2]=a1; + if (res[1]!=0) res[1][3]=a1; + if (res[1]!=0) res[1][4]=a1; + if (res[1]!=0) res[1][5]=a1; + return 0; +} + +CASADI_SYMBOL_EXPORT int long_cost_y_e_fun_jac_ut_xt(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int long_cost_y_e_fun_jac_ut_xt_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int long_cost_y_e_fun_jac_ut_xt_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_cost_y_e_fun_jac_ut_xt_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int long_cost_y_e_fun_jac_ut_xt_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_cost_y_e_fun_jac_ut_xt_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void long_cost_y_e_fun_jac_ut_xt_incref(void) { +} + +CASADI_SYMBOL_EXPORT void long_cost_y_e_fun_jac_ut_xt_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_e_fun_jac_ut_xt_n_in(void) { return 4;} + +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_e_fun_jac_ut_xt_n_out(void) { return 3;} + +CASADI_SYMBOL_EXPORT casadi_real long_cost_y_e_fun_jac_ut_xt_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_cost_y_e_fun_jac_ut_xt_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_cost_y_e_fun_jac_ut_xt_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + case 1: return "o1"; + case 2: return "o2"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_e_fun_jac_ut_xt_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s1; + case 3: return casadi_s2; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_e_fun_jac_ut_xt_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s3; + case 1: return casadi_s4; + case 2: return casadi_s5; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int long_cost_y_e_fun_jac_ut_xt_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 4; + if (sz_res) *sz_res = 3; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_e_hess.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_e_hess.c new file mode 100644 index 0000000..b14ef57 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_e_hess.c @@ -0,0 +1,201 @@ +/* This file was automatically generated by CasADi 3.6.4. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) long_cost_y_e_hess_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) +#define casadi_s4 CASADI_PREFIX(s4) +#define casadi_sq CASADI_PREFIX(sq) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +casadi_real casadi_sq(casadi_real x) { return x*x;} + +static const casadi_int casadi_s0[7] = {3, 1, 0, 3, 0, 1, 2}; +static const casadi_int casadi_s1[3] = {0, 0, 0}; +static const casadi_int casadi_s2[9] = {5, 1, 0, 5, 0, 1, 2, 3, 4}; +static const casadi_int casadi_s3[10] = {6, 1, 0, 6, 0, 1, 2, 3, 4, 5}; +static const casadi_int casadi_s4[9] = {3, 3, 0, 1, 3, 3, 1, 0, 1}; + +/* long_cost_y_e_hess:(i0[3],i1[],i2[],i3[5],i4[6])->(o0[3x3,3nz]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a10, a2, a3, a4, a5, a6, a7, a8, a9; + a0=arg[3]? arg[3][0] : 0; + a1=arg[0]? arg[0][1] : 0; + a2=10.; + a2=(a1+a2); + a3=(1./a2); + a3=(a3/a2); + a3=(a0*a3); + if (res[0]!=0) res[0][0]=a3; + a3=(a0/a2); + a4=(a3/a2); + if (res[0]!=0) res[0][1]=a4; + a5=2.0000000000000001e-01; + a6=(a1+a1); + a6=(a5*a6); + a7=arg[4]? arg[4][4] : 0; + a6=(a6+a7); + a6=(a6/a2); + a8=arg[4]? arg[4][2] : 0; + a9=arg[0]? arg[0][0] : 0; + a8=(a8-a9); + a9=casadi_sq(a1); + a10=5.; + a9=(a9/a10); + a10=(a7*a1); + a9=(a9+a10); + a10=6.; + a9=(a9+a10); + a8=(a8-a9); + a8=(a8/a2); + a9=(a8/a2); + a6=(a6+a9); + a6=(a6/a2); + a8=(a8/a2); + a8=(a8/a2); + a6=(a6+a8); + a0=(a0*a6); + a7=(a7*a4); + a0=(a0+a7); + a7=2.; + a3=(a5*a3); + a7=(a7*a3); + a1=(a1+a1); + a5=(a5*a4); + a1=(a1*a5); + a7=(a7-a1); + a0=(a0-a7); + if (res[0]!=0) res[0][2]=a0; + return 0; +} + +CASADI_SYMBOL_EXPORT int long_cost_y_e_hess(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int long_cost_y_e_hess_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int long_cost_y_e_hess_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_cost_y_e_hess_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int long_cost_y_e_hess_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_cost_y_e_hess_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void long_cost_y_e_hess_incref(void) { +} + +CASADI_SYMBOL_EXPORT void long_cost_y_e_hess_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_e_hess_n_in(void) { return 5;} + +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_e_hess_n_out(void) { return 1;} + +CASADI_SYMBOL_EXPORT casadi_real long_cost_y_e_hess_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_cost_y_e_hess_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + case 4: return "i4"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_cost_y_e_hess_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_e_hess_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s1; + case 3: return casadi_s2; + case 4: return casadi_s3; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_e_hess_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s4; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int long_cost_y_e_hess_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 5; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_fun.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_fun.c new file mode 100644 index 0000000..2c5e7d6 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_fun.c @@ -0,0 +1,176 @@ +/* This file was automatically generated by CasADi 3.6.4. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) long_cost_y_fun_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) +#define casadi_sq CASADI_PREFIX(sq) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +casadi_real casadi_sq(casadi_real x) { return x*x;} + +static const casadi_int casadi_s0[7] = {3, 1, 0, 3, 0, 1, 2}; +static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; +static const casadi_int casadi_s2[3] = {0, 0, 0}; +static const casadi_int casadi_s3[10] = {6, 1, 0, 6, 0, 1, 2, 3, 4, 5}; + +/* long_cost_y_fun:(i0[3],i1,i2[],i3[6])->(o0[6]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a2, a3, a4; + a0=arg[3]? arg[3][2] : 0; + a1=arg[0]? arg[0][0] : 0; + a0=(a0-a1); + a2=arg[0]? arg[0][1] : 0; + a3=casadi_sq(a2); + a4=5.; + a3=(a3/a4); + a4=arg[3]? arg[3][4] : 0; + a4=(a4*a2); + a3=(a3+a4); + a4=6.; + a3=(a3+a4); + a0=(a0-a3); + a3=10.; + a3=(a2+a3); + a0=(a0/a3); + if (res[0]!=0) res[0][0]=a0; + if (res[0]!=0) res[0][1]=a1; + if (res[0]!=0) res[0][2]=a2; + a2=arg[0]? arg[0][2] : 0; + if (res[0]!=0) res[0][3]=a2; + a1=arg[3]? arg[3][3] : 0; + a2=(a2-a1); + if (res[0]!=0) res[0][4]=a2; + a2=arg[1]? arg[1][0] : 0; + if (res[0]!=0) res[0][5]=a2; + return 0; +} + +CASADI_SYMBOL_EXPORT int long_cost_y_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int long_cost_y_fun_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int long_cost_y_fun_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_cost_y_fun_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int long_cost_y_fun_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_cost_y_fun_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void long_cost_y_fun_incref(void) { +} + +CASADI_SYMBOL_EXPORT void long_cost_y_fun_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_fun_n_in(void) { return 4;} + +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_fun_n_out(void) { return 1;} + +CASADI_SYMBOL_EXPORT casadi_real long_cost_y_fun_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_cost_y_fun_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_cost_y_fun_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_fun_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + case 3: return casadi_s3; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_fun_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s3; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int long_cost_y_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 4; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_fun_jac_ut_xt.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_fun_jac_ut_xt.c new file mode 100644 index 0000000..6d1e496 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_fun_jac_ut_xt.c @@ -0,0 +1,202 @@ +/* This file was automatically generated by CasADi 3.6.4. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) long_cost_y_fun_jac_ut_xt_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) +#define casadi_s4 CASADI_PREFIX(s4) +#define casadi_s5 CASADI_PREFIX(s5) +#define casadi_sq CASADI_PREFIX(sq) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +casadi_real casadi_sq(casadi_real x) { return x*x;} + +static const casadi_int casadi_s0[7] = {3, 1, 0, 3, 0, 1, 2}; +static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; +static const casadi_int casadi_s2[3] = {0, 0, 0}; +static const casadi_int casadi_s3[10] = {6, 1, 0, 6, 0, 1, 2, 3, 4, 5}; +static const casadi_int casadi_s4[16] = {4, 6, 0, 2, 3, 4, 5, 6, 7, 1, 2, 1, 2, 3, 3, 0}; +static const casadi_int casadi_s5[3] = {6, 0, 0}; + +/* long_cost_y_fun_jac_ut_xt:(i0[3],i1,i2[],i3[6])->(o0[6],o1[4x6,7nz],o2[6x0]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a2, a3, a4, a5; + a0=arg[3]? arg[3][2] : 0; + a1=arg[0]? arg[0][0] : 0; + a0=(a0-a1); + a2=arg[0]? arg[0][1] : 0; + a3=casadi_sq(a2); + a4=5.; + a3=(a3/a4); + a4=arg[3]? arg[3][4] : 0; + a5=(a4*a2); + a3=(a3+a5); + a5=6.; + a3=(a3+a5); + a0=(a0-a3); + a3=10.; + a3=(a2+a3); + a0=(a0/a3); + if (res[0]!=0) res[0][0]=a0; + if (res[0]!=0) res[0][1]=a1; + if (res[0]!=0) res[0][2]=a2; + a1=arg[0]? arg[0][2] : 0; + if (res[0]!=0) res[0][3]=a1; + a5=arg[3]? arg[3][3] : 0; + a1=(a1-a5); + if (res[0]!=0) res[0][4]=a1; + a1=arg[1]? arg[1][0] : 0; + if (res[0]!=0) res[0][5]=a1; + a1=(1./a3); + a1=(-a1); + if (res[1]!=0) res[1][0]=a1; + a1=2.0000000000000001e-01; + a2=(a2+a2); + a1=(a1*a2); + a1=(a1+a4); + a1=(a1/a3); + a0=(a0/a3); + a1=(a1+a0); + a1=(-a1); + if (res[1]!=0) res[1][1]=a1; + a1=1.; + if (res[1]!=0) res[1][2]=a1; + if (res[1]!=0) res[1][3]=a1; + if (res[1]!=0) res[1][4]=a1; + if (res[1]!=0) res[1][5]=a1; + if (res[1]!=0) res[1][6]=a1; + return 0; +} + +CASADI_SYMBOL_EXPORT int long_cost_y_fun_jac_ut_xt(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int long_cost_y_fun_jac_ut_xt_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int long_cost_y_fun_jac_ut_xt_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_cost_y_fun_jac_ut_xt_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int long_cost_y_fun_jac_ut_xt_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_cost_y_fun_jac_ut_xt_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void long_cost_y_fun_jac_ut_xt_incref(void) { +} + +CASADI_SYMBOL_EXPORT void long_cost_y_fun_jac_ut_xt_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_fun_jac_ut_xt_n_in(void) { return 4;} + +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_fun_jac_ut_xt_n_out(void) { return 3;} + +CASADI_SYMBOL_EXPORT casadi_real long_cost_y_fun_jac_ut_xt_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_cost_y_fun_jac_ut_xt_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_cost_y_fun_jac_ut_xt_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + case 1: return "o1"; + case 2: return "o2"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_fun_jac_ut_xt_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + case 3: return casadi_s3; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_fun_jac_ut_xt_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s3; + case 1: return casadi_s4; + case 2: return casadi_s5; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int long_cost_y_fun_jac_ut_xt_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 4; + if (sz_res) *sz_res = 3; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_hess.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_hess.c new file mode 100644 index 0000000..fc43b07 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_cost/long_cost_y_hess.c @@ -0,0 +1,201 @@ +/* This file was automatically generated by CasADi 3.6.4. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) long_cost_y_hess_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) +#define casadi_s4 CASADI_PREFIX(s4) +#define casadi_sq CASADI_PREFIX(sq) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +casadi_real casadi_sq(casadi_real x) { return x*x;} + +static const casadi_int casadi_s0[7] = {3, 1, 0, 3, 0, 1, 2}; +static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; +static const casadi_int casadi_s2[3] = {0, 0, 0}; +static const casadi_int casadi_s3[10] = {6, 1, 0, 6, 0, 1, 2, 3, 4, 5}; +static const casadi_int casadi_s4[10] = {4, 4, 0, 0, 1, 3, 3, 2, 1, 2}; + +/* long_cost_y_hess:(i0[3],i1,i2[],i3[6],i4[6])->(o0[4x4,3nz]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a10, a2, a3, a4, a5, a6, a7, a8, a9; + a0=arg[3]? arg[3][0] : 0; + a1=arg[0]? arg[0][1] : 0; + a2=10.; + a2=(a1+a2); + a3=(1./a2); + a3=(a3/a2); + a3=(a0*a3); + if (res[0]!=0) res[0][0]=a3; + a3=(a0/a2); + a4=(a3/a2); + if (res[0]!=0) res[0][1]=a4; + a5=2.0000000000000001e-01; + a6=(a1+a1); + a6=(a5*a6); + a7=arg[4]? arg[4][4] : 0; + a6=(a6+a7); + a6=(a6/a2); + a8=arg[4]? arg[4][2] : 0; + a9=arg[0]? arg[0][0] : 0; + a8=(a8-a9); + a9=casadi_sq(a1); + a10=5.; + a9=(a9/a10); + a10=(a7*a1); + a9=(a9+a10); + a10=6.; + a9=(a9+a10); + a8=(a8-a9); + a8=(a8/a2); + a9=(a8/a2); + a6=(a6+a9); + a6=(a6/a2); + a8=(a8/a2); + a8=(a8/a2); + a6=(a6+a8); + a0=(a0*a6); + a7=(a7*a4); + a0=(a0+a7); + a7=2.; + a3=(a5*a3); + a7=(a7*a3); + a1=(a1+a1); + a5=(a5*a4); + a1=(a1*a5); + a7=(a7-a1); + a0=(a0-a7); + if (res[0]!=0) res[0][2]=a0; + return 0; +} + +CASADI_SYMBOL_EXPORT int long_cost_y_hess(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int long_cost_y_hess_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int long_cost_y_hess_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_cost_y_hess_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int long_cost_y_hess_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_cost_y_hess_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void long_cost_y_hess_incref(void) { +} + +CASADI_SYMBOL_EXPORT void long_cost_y_hess_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_hess_n_in(void) { return 5;} + +CASADI_SYMBOL_EXPORT casadi_int long_cost_y_hess_n_out(void) { return 1;} + +CASADI_SYMBOL_EXPORT casadi_real long_cost_y_hess_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_cost_y_hess_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + case 4: return "i4"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_cost_y_hess_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_hess_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + case 3: return casadi_s3; + case 4: return casadi_s3; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_cost_y_hess_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s4; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int long_cost_y_hess_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 5; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_model/long_expl_ode_fun.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_model/long_expl_ode_fun.c new file mode 100644 index 0000000..29598d6 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_model/long_expl_ode_fun.c @@ -0,0 +1,149 @@ +/* This file was automatically generated by CasADi 3.6.4. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) long_expl_ode_fun_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +static const casadi_int casadi_s0[7] = {3, 1, 0, 3, 0, 1, 2}; +static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; +static const casadi_int casadi_s2[10] = {6, 1, 0, 6, 0, 1, 2, 3, 4, 5}; + +/* long_expl_ode_fun:(i0[3],i1,i2[6])->(o0[3]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0; + a0=arg[0]? arg[0][1] : 0; + if (res[0]!=0) res[0][0]=a0; + a0=arg[0]? arg[0][2] : 0; + if (res[0]!=0) res[0][1]=a0; + a0=arg[1]? arg[1][0] : 0; + if (res[0]!=0) res[0][2]=a0; + return 0; +} + +CASADI_SYMBOL_EXPORT int long_expl_ode_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int long_expl_ode_fun_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int long_expl_ode_fun_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_expl_ode_fun_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int long_expl_ode_fun_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_expl_ode_fun_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void long_expl_ode_fun_incref(void) { +} + +CASADI_SYMBOL_EXPORT void long_expl_ode_fun_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int long_expl_ode_fun_n_in(void) { return 3;} + +CASADI_SYMBOL_EXPORT casadi_int long_expl_ode_fun_n_out(void) { return 1;} + +CASADI_SYMBOL_EXPORT casadi_real long_expl_ode_fun_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_expl_ode_fun_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_expl_ode_fun_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_expl_ode_fun_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_expl_ode_fun_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int long_expl_ode_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 3; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_model/long_expl_vde_adj.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_model/long_expl_vde_adj.c new file mode 100644 index 0000000..d8bd4d0 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_model/long_expl_vde_adj.c @@ -0,0 +1,155 @@ +/* This file was automatically generated by CasADi 3.6.4. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) long_expl_vde_adj_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +static const casadi_int casadi_s0[7] = {3, 1, 0, 3, 0, 1, 2}; +static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; +static const casadi_int casadi_s2[10] = {6, 1, 0, 6, 0, 1, 2, 3, 4, 5}; +static const casadi_int casadi_s3[8] = {4, 1, 0, 4, 0, 1, 2, 3}; + +/* long_expl_vde_adj:(i0[3],i1[3],i2,i3[6])->(o0[4]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0; + a0=0.; + if (res[0]!=0) res[0][0]=a0; + a0=arg[1]? arg[1][0] : 0; + if (res[0]!=0) res[0][1]=a0; + a0=arg[1]? arg[1][1] : 0; + if (res[0]!=0) res[0][2]=a0; + a0=arg[1]? arg[1][2] : 0; + if (res[0]!=0) res[0][3]=a0; + return 0; +} + +CASADI_SYMBOL_EXPORT int long_expl_vde_adj(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int long_expl_vde_adj_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int long_expl_vde_adj_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_expl_vde_adj_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int long_expl_vde_adj_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_expl_vde_adj_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void long_expl_vde_adj_incref(void) { +} + +CASADI_SYMBOL_EXPORT void long_expl_vde_adj_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int long_expl_vde_adj_n_in(void) { return 4;} + +CASADI_SYMBOL_EXPORT casadi_int long_expl_vde_adj_n_out(void) { return 1;} + +CASADI_SYMBOL_EXPORT casadi_real long_expl_vde_adj_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_expl_vde_adj_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_expl_vde_adj_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_expl_vde_adj_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s0; + case 2: return casadi_s1; + case 3: return casadi_s2; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_expl_vde_adj_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s3; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int long_expl_vde_adj_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 4; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_model/long_expl_vde_forw.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_model/long_expl_vde_forw.c new file mode 100644 index 0000000..ecde7cc --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/long_model/long_expl_vde_forw.c @@ -0,0 +1,181 @@ +/* This file was automatically generated by CasADi 3.6.4. + * It consists of: + * 1) content generated by CasADi runtime: not copyrighted + * 2) template code copied from CasADi source: permissively licensed (MIT-0) + * 3) user code: owned by the user + * + */ +#ifdef __cplusplus +extern "C" { +#endif + +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) long_expl_vde_forw_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +static const casadi_int casadi_s0[7] = {3, 1, 0, 3, 0, 1, 2}; +static const casadi_int casadi_s1[15] = {3, 3, 0, 3, 6, 9, 0, 1, 2, 0, 1, 2, 0, 1, 2}; +static const casadi_int casadi_s2[5] = {1, 1, 0, 1, 0}; +static const casadi_int casadi_s3[10] = {6, 1, 0, 6, 0, 1, 2, 3, 4, 5}; + +/* long_expl_vde_forw:(i0[3],i1[3x3],i2[3],i3,i4[6])->(o0[3],o1[3x3],o2[3]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1; + a0=arg[0]? arg[0][1] : 0; + if (res[0]!=0) res[0][0]=a0; + a0=arg[0]? arg[0][2] : 0; + if (res[0]!=0) res[0][1]=a0; + a0=arg[3]? arg[3][0] : 0; + if (res[0]!=0) res[0][2]=a0; + a0=arg[1]? arg[1][1] : 0; + if (res[1]!=0) res[1][0]=a0; + a0=arg[1]? arg[1][2] : 0; + if (res[1]!=0) res[1][1]=a0; + a0=0.; + if (res[1]!=0) res[1][2]=a0; + a1=arg[1]? arg[1][4] : 0; + if (res[1]!=0) res[1][3]=a1; + a1=arg[1]? arg[1][5] : 0; + if (res[1]!=0) res[1][4]=a1; + if (res[1]!=0) res[1][5]=a0; + a1=arg[1]? arg[1][7] : 0; + if (res[1]!=0) res[1][6]=a1; + a1=arg[1]? arg[1][8] : 0; + if (res[1]!=0) res[1][7]=a1; + if (res[1]!=0) res[1][8]=a0; + a0=arg[2]? arg[2][1] : 0; + if (res[2]!=0) res[2][0]=a0; + a0=arg[2]? arg[2][2] : 0; + if (res[2]!=0) res[2][1]=a0; + a0=1.; + if (res[2]!=0) res[2][2]=a0; + return 0; +} + +CASADI_SYMBOL_EXPORT int long_expl_vde_forw(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +CASADI_SYMBOL_EXPORT int long_expl_vde_forw_alloc_mem(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT int long_expl_vde_forw_init_mem(int mem) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_expl_vde_forw_free_mem(int mem) { +} + +CASADI_SYMBOL_EXPORT int long_expl_vde_forw_checkout(void) { + return 0; +} + +CASADI_SYMBOL_EXPORT void long_expl_vde_forw_release(int mem) { +} + +CASADI_SYMBOL_EXPORT void long_expl_vde_forw_incref(void) { +} + +CASADI_SYMBOL_EXPORT void long_expl_vde_forw_decref(void) { +} + +CASADI_SYMBOL_EXPORT casadi_int long_expl_vde_forw_n_in(void) { return 5;} + +CASADI_SYMBOL_EXPORT casadi_int long_expl_vde_forw_n_out(void) { return 3;} + +CASADI_SYMBOL_EXPORT casadi_real long_expl_vde_forw_default_in(casadi_int i) { + switch (i) { + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_expl_vde_forw_name_in(casadi_int i) { + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + case 4: return "i4"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const char* long_expl_vde_forw_name_out(casadi_int i) { + switch (i) { + case 0: return "o0"; + case 1: return "o1"; + case 2: return "o2"; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_expl_vde_forw_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s0; + case 3: return casadi_s2; + case 4: return casadi_s3; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT const casadi_int* long_expl_vde_forw_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s0; + default: return 0; + } +} + +CASADI_SYMBOL_EXPORT int long_expl_vde_forw_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 5; + if (sz_res) *sz_res = 3; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + +#ifdef __cplusplus +} /* extern "C" */ +#endif diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/main_long.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/main_long.c new file mode 100644 index 0000000..94ff7c1 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/main_long.c @@ -0,0 +1,216 @@ +/* + * Copyright (c) The acados authors. + * + * This file is part of acados. + * + * The 2-Clause BSD License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE.; + */ + + +// standard +#include +#include +// acados +#include "acados/utils/print.h" +#include "acados/utils/math.h" +#include "acados_c/ocp_nlp_interface.h" +#include "acados_c/external_function_interface.h" +#include "acados_solver_long.h" + +// blasfeo +#include "blasfeo/include/blasfeo_d_aux_ext_dep.h" + +#define NX LONG_NX +#define NZ LONG_NZ +#define NU LONG_NU +#define NP LONG_NP +#define NBX LONG_NBX +#define NBX0 LONG_NBX0 +#define NBU LONG_NBU +#define NSBX LONG_NSBX +#define NSBU LONG_NSBU +#define NSH LONG_NSH +#define NSG LONG_NSG +#define NSPHI LONG_NSPHI +#define NSHN LONG_NSHN +#define NSGN LONG_NSGN +#define NSPHIN LONG_NSPHIN +#define NSBXN LONG_NSBXN +#define NS LONG_NS +#define NSN LONG_NSN +#define NG LONG_NG +#define NBXN LONG_NBXN +#define NGN LONG_NGN +#define NY0 LONG_NY0 +#define NY LONG_NY +#define NYN LONG_NYN +#define NH LONG_NH +#define NPHI LONG_NPHI +#define NHN LONG_NHN +#define NPHIN LONG_NPHIN +#define NR LONG_NR + + +int main() +{ + + long_solver_capsule *acados_ocp_capsule = long_acados_create_capsule(); + // there is an opportunity to change the number of shooting intervals in C without new code generation + int N = LONG_N; + // allocate the array and fill it accordingly + double* new_time_steps = NULL; + int status = long_acados_create_with_discretization(acados_ocp_capsule, N, new_time_steps); + + if (status) + { + printf("long_acados_create() returned status %d. Exiting.\n", status); + exit(1); + } + + ocp_nlp_config *nlp_config = long_acados_get_nlp_config(acados_ocp_capsule); + ocp_nlp_dims *nlp_dims = long_acados_get_nlp_dims(acados_ocp_capsule); + ocp_nlp_in *nlp_in = long_acados_get_nlp_in(acados_ocp_capsule); + ocp_nlp_out *nlp_out = long_acados_get_nlp_out(acados_ocp_capsule); + ocp_nlp_solver *nlp_solver = long_acados_get_nlp_solver(acados_ocp_capsule); + void *nlp_opts = long_acados_get_nlp_opts(acados_ocp_capsule); + + // initial condition + int idxbx0[NBX0]; + idxbx0[0] = 0; + idxbx0[1] = 1; + idxbx0[2] = 2; + + double lbx0[NBX0]; + double ubx0[NBX0]; + lbx0[0] = 0.0; + ubx0[0] = 0.0; + lbx0[1] = 0.0; + ubx0[1] = 0.0; + lbx0[2] = 0.0; + ubx0[2] = 0.0; + + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "idxbx", idxbx0); + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "lbx", lbx0); + ocp_nlp_constraints_model_set(nlp_config, nlp_dims, nlp_in, 0, "ubx", ubx0); + + // initialization for state values + double x_init[NX]; + x_init[0] = 0.0; + x_init[1] = 0.0; + x_init[2] = 0.0; + + // initial value for control input + double u0[NU]; + u0[0] = 0.0; + // set parameters + double p[NP]; + p[0] = -1.2; + p[1] = 1.2; + p[2] = 0.0; + p[3] = 0.0; + p[4] = 1.45; + p[5] = 0.75; + + for (int ii = 0; ii <= N; ii++) + { + long_acados_update_params(acados_ocp_capsule, ii, p, NP); + } + + + // prepare evaluation + int NTIMINGS = 1; + double min_time = 1e12; + double kkt_norm_inf; + double elapsed_time; + int sqp_iter; + + double xtraj[NX * (N+1)]; + double utraj[NU * N]; + + + // solve ocp in loop + int rti_phase = 0; + + for (int ii = 0; ii < NTIMINGS; ii++) + { + // initialize solution + for (int i = 0; i < N; i++) + { + ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, i, "x", x_init); + ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, i, "u", u0); + } + ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, N, "x", x_init); + ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "rti_phase", &rti_phase); + status = long_acados_solve(acados_ocp_capsule); + ocp_nlp_get(nlp_config, nlp_solver, "time_tot", &elapsed_time); + min_time = MIN(elapsed_time, min_time); + } + + /* print solution and statistics */ + for (int ii = 0; ii <= nlp_dims->N; ii++) + ocp_nlp_out_get(nlp_config, nlp_dims, nlp_out, ii, "x", &xtraj[ii*NX]); + for (int ii = 0; ii < nlp_dims->N; ii++) + ocp_nlp_out_get(nlp_config, nlp_dims, nlp_out, ii, "u", &utraj[ii*NU]); + + printf("\n--- xtraj ---\n"); + d_print_exp_tran_mat( NX, N+1, xtraj, NX); + printf("\n--- utraj ---\n"); + d_print_exp_tran_mat( NU, N, utraj, NU ); + // ocp_nlp_out_print(nlp_solver->dims, nlp_out); + + printf("\nsolved ocp %d times, solution printed above\n\n", NTIMINGS); + + if (status == ACADOS_SUCCESS) + { + printf("long_acados_solve(): SUCCESS!\n"); + } + else + { + printf("long_acados_solve() failed with status %d.\n", status); + } + + // get solution + ocp_nlp_out_get(nlp_config, nlp_dims, nlp_out, 0, "kkt_norm_inf", &kkt_norm_inf); + ocp_nlp_get(nlp_config, nlp_solver, "sqp_iter", &sqp_iter); + + long_acados_print_stats(acados_ocp_capsule); + + printf("\nSolver info:\n"); + printf(" SQP iterations %2d\n minimum time for %d solve %f [ms]\n KKT %e\n", + sqp_iter, NTIMINGS, min_time*1000, kkt_norm_inf); + + // free solver + status = long_acados_free(acados_ocp_capsule); + if (status) { + printf("long_acados_free() returned status %d. \n", status); + } + // free solver capsule + status = long_acados_free_capsule(acados_ocp_capsule); + if (status) { + printf("long_acados_free_capsule() returned status %d. \n", status); + } + + return status; +} diff --git a/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/main_sim_long.c b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/main_sim_long.c new file mode 100644 index 0000000..67fa560 --- /dev/null +++ b/selfdrive/controls/lib/longitudinal_mpc_lib/c_generated_code/main_sim_long.c @@ -0,0 +1,127 @@ +/* + * Copyright (c) The acados authors. + * + * This file is part of acados. + * + * The 2-Clause BSD License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE.; + */ + + +// standard +#include +#include +// acados +#include "acados/utils/print.h" +#include "acados/utils/math.h" +#include "acados_c/sim_interface.h" +#include "acados_sim_solver_long.h" + +#define NX LONG_NX +#define NZ LONG_NZ +#define NU LONG_NU +#define NP LONG_NP + + +int main() +{ + int status = 0; + sim_solver_capsule *capsule = long_acados_sim_solver_create_capsule(); + status = long_acados_sim_create(capsule); + + if (status) + { + printf("acados_create() returned status %d. Exiting.\n", status); + exit(1); + } + + sim_config *acados_sim_config = long_acados_get_sim_config(capsule); + sim_in *acados_sim_in = long_acados_get_sim_in(capsule); + sim_out *acados_sim_out = long_acados_get_sim_out(capsule); + void *acados_sim_dims = long_acados_get_sim_dims(capsule); + + // initial condition + double x_current[NX]; + x_current[0] = 0.0; + x_current[1] = 0.0; + x_current[2] = 0.0; + + + x_current[0] = 0.0; + x_current[1] = 0.0; + x_current[2] = 0.0; + + + + + // initial value for control input + double u0[NU]; + u0[0] = 0.0; + // set parameters + double p[NP]; + p[0] = -1.2; + p[1] = 1.2; + p[2] = 0.0; + p[3] = 0.0; + p[4] = 1.45; + p[5] = 0.75; + + long_acados_sim_update_params(capsule, p, NP); + + + int n_sim_steps = 3; + // solve ocp in loop + for (int ii = 0; ii < n_sim_steps; ii++) + { + sim_in_set(acados_sim_config, acados_sim_dims, + acados_sim_in, "x", x_current); + status = long_acados_sim_solve(capsule); + + if (status != ACADOS_SUCCESS) + { + printf("acados_solve() failed with status %d.\n", status); + } + + sim_out_get(acados_sim_config, acados_sim_dims, + acados_sim_out, "x", x_current); + + printf("\nx_current, %d\n", ii); + for (int jj = 0; jj < NX; jj++) + { + printf("%e\n", x_current[jj]); + } + } + + printf("\nPerformed %d simulation steps with acados integrator successfully.\n\n", n_sim_steps); + + // free solver + status = long_acados_sim_free(capsule); + if (status) { + printf("long_acados_sim_free() returned status %d. \n", status); + } + + long_acados_sim_solver_free_capsule(capsule); + + return status; +} diff --git a/selfdrive/controls/tests/__init__.py b/selfdrive/controls/tests/__init__.py deleted file mode 100644 index e69de29..0000000 diff --git a/selfdrive/controls/tests/test_alerts.py b/selfdrive/controls/tests/test_alerts.py deleted file mode 100644 index 7b4fba0..0000000 --- a/selfdrive/controls/tests/test_alerts.py +++ /dev/null @@ -1,135 +0,0 @@ -#!/usr/bin/env python3 -import copy -import json -import os -import unittest -import random -from PIL import Image, ImageDraw, ImageFont - -from cereal import log, car -from cereal.messaging import SubMaster -from openpilot.common.basedir import BASEDIR -from openpilot.common.params import Params -from openpilot.selfdrive.controls.lib.events import Alert, EVENTS, ET -from openpilot.selfdrive.controls.lib.alertmanager import set_offroad_alert -from openpilot.selfdrive.test.process_replay.process_replay import CONFIGS - -AlertSize = log.ControlsState.AlertSize - -OFFROAD_ALERTS_PATH = os.path.join(BASEDIR, "selfdrive/controls/lib/alerts_offroad.json") - -# TODO: add callback alerts -ALERTS = [] -for event_types in EVENTS.values(): - for alert in event_types.values(): - ALERTS.append(alert) - - -class TestAlerts(unittest.TestCase): - - @classmethod - def setUpClass(cls): - with open(OFFROAD_ALERTS_PATH) as f: - cls.offroad_alerts = json.loads(f.read()) - - # Create fake objects for callback - cls.CS = car.CarState.new_message() - cls.CP = car.CarParams.new_message() - cfg = [c for c in CONFIGS if c.proc_name == 'controlsd'][0] - cls.sm = SubMaster(cfg.pubs) - - def test_events_defined(self): - # Ensure all events in capnp schema are defined in events.py - events = car.CarEvent.EventName.schema.enumerants - - for name, e in events.items(): - if not name.endswith("DEPRECATED"): - fail_msg = "%s @%d not in EVENTS" % (name, e) - self.assertTrue(e in EVENTS.keys(), msg=fail_msg) - - # ensure alert text doesn't exceed allowed width - def test_alert_text_length(self): - font_path = os.path.join(BASEDIR, "selfdrive/assets/fonts") - regular_font_path = os.path.join(font_path, "Inter-SemiBold.ttf") - bold_font_path = os.path.join(font_path, "Inter-Bold.ttf") - semibold_font_path = os.path.join(font_path, "Inter-SemiBold.ttf") - - max_text_width = 2160 - 300 # full screen width is usable, minus sidebar - draw = ImageDraw.Draw(Image.new('RGB', (0, 0))) - - fonts = { - AlertSize.small: [ImageFont.truetype(semibold_font_path, 74)], - AlertSize.mid: [ImageFont.truetype(bold_font_path, 88), - ImageFont.truetype(regular_font_path, 66)], - } - - for alert in ALERTS: - if not isinstance(alert, Alert): - alert = alert(self.CP, self.CS, self.sm, metric=False, soft_disable_time=100) - - # for full size alerts, both text fields wrap the text, - # so it's unlikely that they would go past the max width - if alert.alert_size in (AlertSize.none, AlertSize.full): - continue - - for i, txt in enumerate([alert.alert_text_1, alert.alert_text_2]): - if i >= len(fonts[alert.alert_size]): - break - - font = fonts[alert.alert_size][i] - left, _, right, _ = draw.textbbox((0, 0), txt, font) - width = right - left - msg = f"type: {alert.alert_type} msg: {txt}" - self.assertLessEqual(width, max_text_width, msg=msg) - - def test_alert_sanity_check(self): - for event_types in EVENTS.values(): - for event_type, a in event_types.items(): - # TODO: add callback alerts - if not isinstance(a, Alert): - continue - - if a.alert_size == AlertSize.none: - self.assertEqual(len(a.alert_text_1), 0) - self.assertEqual(len(a.alert_text_2), 0) - elif a.alert_size == AlertSize.small: - self.assertGreater(len(a.alert_text_1), 0) - self.assertEqual(len(a.alert_text_2), 0) - elif a.alert_size == AlertSize.mid: - self.assertGreater(len(a.alert_text_1), 0) - self.assertGreater(len(a.alert_text_2), 0) - else: - self.assertGreater(len(a.alert_text_1), 0) - - self.assertGreaterEqual(a.duration, 0.) - - if event_type not in (ET.WARNING, ET.PERMANENT, ET.PRE_ENABLE): - self.assertEqual(a.creation_delay, 0.) - - def test_offroad_alerts(self): - params = Params() - for a in self.offroad_alerts: - # set the alert - alert = copy.copy(self.offroad_alerts[a]) - set_offroad_alert(a, True) - alert['extra'] = '' - self.assertTrue(json.dumps(alert) == params.get(a, encoding='utf8')) - - # then delete it - set_offroad_alert(a, False) - self.assertTrue(params.get(a) is None) - - def test_offroad_alerts_extra_text(self): - params = Params() - for i in range(50): - # set the alert - a = random.choice(list(self.offroad_alerts)) - alert = self.offroad_alerts[a] - set_offroad_alert(a, True, extra_text="a"*i) - - written_alert = json.loads(params.get(a, encoding='utf8')) - self.assertTrue("a"*i == written_alert['extra']) - self.assertTrue(alert["text"] == written_alert['text']) - -if __name__ == "__main__": - unittest.main() diff --git a/selfdrive/controls/tests/test_cruise_speed.py b/selfdrive/controls/tests/test_cruise_speed.py deleted file mode 100644 index 76a2222..0000000 --- a/selfdrive/controls/tests/test_cruise_speed.py +++ /dev/null @@ -1,158 +0,0 @@ -#!/usr/bin/env python3 -import itertools -import numpy as np -import unittest - -from parameterized import parameterized_class -from cereal import log -from openpilot.common.params import Params -from openpilot.selfdrive.controls.lib.drive_helpers import VCruiseHelper, V_CRUISE_MIN, V_CRUISE_MAX, V_CRUISE_INITIAL, IMPERIAL_INCREMENT -from cereal import car -from openpilot.common.conversions import Conversions as CV -from openpilot.selfdrive.test.longitudinal_maneuvers.maneuver import Maneuver - -ButtonEvent = car.CarState.ButtonEvent -ButtonType = car.CarState.ButtonEvent.Type - - -def run_cruise_simulation(cruise, e2e, t_end=20.): - man = Maneuver( - '', - duration=t_end, - initial_speed=max(cruise - 1., 0.0), - lead_relevancy=True, - initial_distance_lead=100, - cruise_values=[cruise], - prob_lead_values=[0.0], - breakpoints=[0.], - e2e=e2e, - ) - valid, output = man.evaluate() - assert valid - return output[-1, 3] - - -@parameterized_class(("e2e", "personality", "speed"), itertools.product( - [True, False], # e2e - log.LongitudinalPersonality.schema.enumerants, # personality - [5,35])) # speed -class TestCruiseSpeed(unittest.TestCase): - def test_cruise_speed(self): - params = Params() - params.put("LongitudinalPersonality", str(self.personality)) - print(f'Testing {self.speed} m/s') - cruise_speed = float(self.speed) - - simulation_steady_state = run_cruise_simulation(cruise_speed, self.e2e) - self.assertAlmostEqual(simulation_steady_state, cruise_speed, delta=.01, msg=f'Did not reach {self.speed} m/s') - - -# TODO: test pcmCruise -@parameterized_class(('pcm_cruise',), [(False,)]) -class TestVCruiseHelper(unittest.TestCase): - def setUp(self): - self.CP = car.CarParams(pcmCruise=self.pcm_cruise) - self.v_cruise_helper = VCruiseHelper(self.CP) - self.reset_cruise_speed_state() - - def reset_cruise_speed_state(self): - # Two resets previous cruise speed - for _ in range(2): - self.v_cruise_helper.update_v_cruise(car.CarState(cruiseState={"available": False}), enabled=False, is_metric=False) - - def enable(self, v_ego, experimental_mode): - # Simulates user pressing set with a current speed - self.v_cruise_helper.initialize_v_cruise(car.CarState(vEgo=v_ego), experimental_mode) - - def test_adjust_speed(self): - """ - Asserts speed changes on falling edges of buttons. - """ - - self.enable(V_CRUISE_INITIAL * CV.KPH_TO_MS, False) - - for btn in (ButtonType.accelCruise, ButtonType.decelCruise): - for pressed in (True, False): - CS = car.CarState(cruiseState={"available": True}) - CS.buttonEvents = [ButtonEvent(type=btn, pressed=pressed)] - - self.v_cruise_helper.update_v_cruise(CS, enabled=True, is_metric=False) - self.assertEqual(pressed, self.v_cruise_helper.v_cruise_kph == self.v_cruise_helper.v_cruise_kph_last) - - def test_rising_edge_enable(self): - """ - Some car interfaces may enable on rising edge of a button, - ensure we don't adjust speed if enabled changes mid-press. - """ - - # NOTE: enabled is always one frame behind the result from button press in controlsd - for enabled, pressed in ((False, False), - (False, True), - (True, False)): - CS = car.CarState(cruiseState={"available": True}) - CS.buttonEvents = [ButtonEvent(type=ButtonType.decelCruise, pressed=pressed)] - self.v_cruise_helper.update_v_cruise(CS, enabled=enabled, is_metric=False) - if pressed: - self.enable(V_CRUISE_INITIAL * CV.KPH_TO_MS, False) - - # Expected diff on enabling. Speed should not change on falling edge of pressed - self.assertEqual(not pressed, self.v_cruise_helper.v_cruise_kph == self.v_cruise_helper.v_cruise_kph_last) - - def test_resume_in_standstill(self): - """ - Asserts we don't increment set speed if user presses resume/accel to exit cruise standstill. - """ - - self.enable(0, False) - - for standstill in (True, False): - for pressed in (True, False): - CS = car.CarState(cruiseState={"available": True, "standstill": standstill}) - CS.buttonEvents = [ButtonEvent(type=ButtonType.accelCruise, pressed=pressed)] - self.v_cruise_helper.update_v_cruise(CS, enabled=True, is_metric=False) - - # speed should only update if not at standstill and button falling edge - should_equal = standstill or pressed - self.assertEqual(should_equal, self.v_cruise_helper.v_cruise_kph == self.v_cruise_helper.v_cruise_kph_last) - - def test_set_gas_pressed(self): - """ - Asserts pressing set while enabled with gas pressed sets - the speed to the maximum of vEgo and current cruise speed. - """ - - for v_ego in np.linspace(0, 100, 101): - self.reset_cruise_speed_state() - self.enable(V_CRUISE_INITIAL * CV.KPH_TO_MS, False) - - # first decrement speed, then perform gas pressed logic - expected_v_cruise_kph = self.v_cruise_helper.v_cruise_kph - IMPERIAL_INCREMENT - expected_v_cruise_kph = max(expected_v_cruise_kph, v_ego * CV.MS_TO_KPH) # clip to min of vEgo - expected_v_cruise_kph = float(np.clip(round(expected_v_cruise_kph, 1), V_CRUISE_MIN, V_CRUISE_MAX)) - - CS = car.CarState(vEgo=float(v_ego), gasPressed=True, cruiseState={"available": True}) - CS.buttonEvents = [ButtonEvent(type=ButtonType.decelCruise, pressed=False)] - self.v_cruise_helper.update_v_cruise(CS, enabled=True, is_metric=False) - - # TODO: fix skipping first run due to enabled on rising edge exception - if v_ego == 0.0: - continue - self.assertEqual(expected_v_cruise_kph, self.v_cruise_helper.v_cruise_kph) - - def test_initialize_v_cruise(self): - """ - Asserts allowed cruise speeds on enabling with SET. - """ - - for experimental_mode in (True, False): - for v_ego in np.linspace(0, 100, 101): - self.reset_cruise_speed_state() - self.assertFalse(self.v_cruise_helper.v_cruise_initialized) - - self.enable(float(v_ego), experimental_mode) - self.assertTrue(V_CRUISE_INITIAL <= self.v_cruise_helper.v_cruise_kph <= V_CRUISE_MAX) - self.assertTrue(self.v_cruise_helper.v_cruise_initialized) - - -if __name__ == "__main__": - unittest.main() diff --git a/selfdrive/controls/tests/test_following_distance.py b/selfdrive/controls/tests/test_following_distance.py deleted file mode 100644 index 3b31632..0000000 --- a/selfdrive/controls/tests/test_following_distance.py +++ /dev/null @@ -1,47 +0,0 @@ -#!/usr/bin/env python3 -import unittest -import itertools -from parameterized import parameterized_class - -from openpilot.common.params import Params -from cereal import log - -from openpilot.selfdrive.controls.lib.longitudinal_mpc_lib.long_mpc import desired_follow_distance, get_T_FOLLOW -from openpilot.selfdrive.test.longitudinal_maneuvers.maneuver import Maneuver - - -def run_following_distance_simulation(v_lead, t_end=100.0, e2e=False): - man = Maneuver( - '', - duration=t_end, - initial_speed=float(v_lead), - lead_relevancy=True, - initial_distance_lead=100, - speed_lead_values=[v_lead], - breakpoints=[0.], - e2e=e2e, - ) - valid, output = man.evaluate() - assert valid - return output[-1,2] - output[-1,1] - - -@parameterized_class(("e2e", "personality", "speed"), itertools.product( - [True, False], # e2e - [log.LongitudinalPersonality.relaxed, # personality - log.LongitudinalPersonality.standard, - log.LongitudinalPersonality.aggressive], - [0,10,35])) # speed -class TestFollowingDistance(unittest.TestCase): - def test_following_distance(self): - params = Params() - params.put("LongitudinalPersonality", str(self.personality)) - v_lead = float(self.speed) - simulation_steady_state = run_following_distance_simulation(v_lead, e2e=self.e2e) - correct_steady_state = desired_follow_distance(v_lead, v_lead, get_T_FOLLOW(self.personality)) - err_ratio = 0.2 if self.e2e else 0.1 - self.assertAlmostEqual(simulation_steady_state, correct_steady_state, delta=(err_ratio * correct_steady_state + .5)) - - -if __name__ == "__main__": - unittest.main() diff --git a/selfdrive/controls/tests/test_lateral_mpc.py b/selfdrive/controls/tests/test_lateral_mpc.py deleted file mode 100644 index 8c09f46..0000000 --- a/selfdrive/controls/tests/test_lateral_mpc.py +++ /dev/null @@ -1,89 +0,0 @@ -import unittest -import numpy as np -from openpilot.selfdrive.controls.lib.lateral_mpc_lib.lat_mpc import LateralMpc -from openpilot.selfdrive.controls.lib.drive_helpers import CAR_ROTATION_RADIUS -from openpilot.selfdrive.controls.lib.lateral_mpc_lib.lat_mpc import N as LAT_MPC_N - - -def run_mpc(lat_mpc=None, v_ref=30., x_init=0., y_init=0., psi_init=0., curvature_init=0., - lane_width=3.6, poly_shift=0.): - - if lat_mpc is None: - lat_mpc = LateralMpc() - lat_mpc.set_weights(1., .1, 0.0, .05, 800) - - y_pts = poly_shift * np.ones(LAT_MPC_N + 1) - heading_pts = np.zeros(LAT_MPC_N + 1) - curv_rate_pts = np.zeros(LAT_MPC_N + 1) - - x0 = np.array([x_init, y_init, psi_init, curvature_init]) - p = np.column_stack([v_ref * np.ones(LAT_MPC_N + 1), - CAR_ROTATION_RADIUS * np.ones(LAT_MPC_N + 1)]) - - # converge in no more than 10 iterations - for _ in range(10): - lat_mpc.run(x0, p, - y_pts, heading_pts, curv_rate_pts) - return lat_mpc.x_sol - - -class TestLateralMpc(unittest.TestCase): - - def _assert_null(self, sol, curvature=1e-6): - for i in range(len(sol)): - self.assertAlmostEqual(sol[0,i,1], 0., delta=curvature) - self.assertAlmostEqual(sol[0,i,2], 0., delta=curvature) - self.assertAlmostEqual(sol[0,i,3], 0., delta=curvature) - - def _assert_simmetry(self, sol, curvature=1e-6): - for i in range(len(sol)): - self.assertAlmostEqual(sol[0,i,1], -sol[1,i,1], delta=curvature) - self.assertAlmostEqual(sol[0,i,2], -sol[1,i,2], delta=curvature) - self.assertAlmostEqual(sol[0,i,3], -sol[1,i,3], delta=curvature) - self.assertAlmostEqual(sol[0,i,0], sol[1,i,0], delta=curvature) - - def test_straight(self): - sol = run_mpc() - self._assert_null(np.array([sol])) - - def test_y_symmetry(self): - sol = [] - for y_init in [-0.5, 0.5]: - sol.append(run_mpc(y_init=y_init)) - self._assert_simmetry(np.array(sol)) - - def test_poly_symmetry(self): - sol = [] - for poly_shift in [-1., 1.]: - sol.append(run_mpc(poly_shift=poly_shift)) - self._assert_simmetry(np.array(sol)) - - def test_curvature_symmetry(self): - sol = [] - for curvature_init in [-0.1, 0.1]: - sol.append(run_mpc(curvature_init=curvature_init)) - self._assert_simmetry(np.array(sol)) - - def test_psi_symmetry(self): - sol = [] - for psi_init in [-0.1, 0.1]: - sol.append(run_mpc(psi_init=psi_init)) - self._assert_simmetry(np.array(sol)) - - def test_no_overshoot(self): - y_init = 1. - sol = run_mpc(y_init=y_init) - for y in list(sol[:,1]): - self.assertGreaterEqual(y_init, abs(y)) - - def test_switch_convergence(self): - lat_mpc = LateralMpc() - sol = run_mpc(lat_mpc=lat_mpc, poly_shift=3.0, v_ref=7.0) - right_psi_deg = np.degrees(sol[:,2]) - sol = run_mpc(lat_mpc=lat_mpc, poly_shift=-3.0, v_ref=7.0) - left_psi_deg = np.degrees(sol[:,2]) - np.testing.assert_almost_equal(right_psi_deg, -left_psi_deg, decimal=3) - - -if __name__ == "__main__": - unittest.main() diff --git a/selfdrive/controls/tests/test_leads.py b/selfdrive/controls/tests/test_leads.py deleted file mode 100644 index 268d9c4..0000000 --- a/selfdrive/controls/tests/test_leads.py +++ /dev/null @@ -1,36 +0,0 @@ -#!/usr/bin/env python3 -import unittest - -import cereal.messaging as messaging - -from openpilot.selfdrive.test.process_replay import replay_process_with_name -from openpilot.selfdrive.car.toyota.values import CAR as TOYOTA - - -class TestLeads(unittest.TestCase): - def test_radar_fault(self): - # if there's no radar-related can traffic, radard should either not respond or respond with an error - # this is tightly coupled with underlying car radar_interface implementation, but it's a good sanity check - def single_iter_pkg(): - # single iter package, with meaningless cans and empty carState/modelV2 - msgs = [] - for _ in range(5): - can = messaging.new_message("can", 1) - cs = messaging.new_message("carState") - msgs.append(can.as_reader()) - msgs.append(cs.as_reader()) - model = messaging.new_message("modelV2") - msgs.append(model.as_reader()) - - return msgs - - msgs = [m for _ in range(3) for m in single_iter_pkg()] - out = replay_process_with_name("radard", msgs, fingerprint=TOYOTA.COROLLA_TSS2) - states = [m for m in out if m.which() == "radarState"] - failures = [not state.valid and len(state.radarState.radarErrors) for state in states] - - self.assertTrue(len(states) == 0 or all(failures)) - - -if __name__ == "__main__": - unittest.main() diff --git a/selfdrive/controls/tests/test_startup.py b/selfdrive/controls/tests/test_startup.py deleted file mode 100644 index 34d14fb..0000000 --- a/selfdrive/controls/tests/test_startup.py +++ /dev/null @@ -1,120 +0,0 @@ -import os -from parameterized import parameterized - -from cereal import log, car -import cereal.messaging as messaging -from openpilot.common.params import Params -from openpilot.selfdrive.boardd.boardd_api_impl import can_list_to_can_capnp -from openpilot.selfdrive.car.fingerprints import _FINGERPRINTS -from openpilot.selfdrive.car.toyota.values import CAR as TOYOTA -from openpilot.selfdrive.car.mazda.values import CAR as MAZDA -from openpilot.selfdrive.controls.lib.events import EVENT_NAME -from openpilot.selfdrive.manager.process_config import managed_processes - -EventName = car.CarEvent.EventName -Ecu = car.CarParams.Ecu - -COROLLA_FW_VERSIONS = [ - (Ecu.engine, 0x7e0, None, b'\x0230ZC2000\x00\x00\x00\x00\x00\x00\x00\x0050212000\x00\x00\x00\x00\x00\x00\x00\x00'), - (Ecu.abs, 0x7b0, None, b'F152602190\x00\x00\x00\x00\x00\x00'), - (Ecu.eps, 0x7a1, None, b'8965B02181\x00\x00\x00\x00\x00\x00'), - (Ecu.fwdRadar, 0x750, 0xf, b'8821F4702100\x00\x00\x00\x00'), - (Ecu.fwdCamera, 0x750, 0x6d, b'8646F0201101\x00\x00\x00\x00'), - (Ecu.dsu, 0x791, None, b'881510201100\x00\x00\x00\x00'), -] -COROLLA_FW_VERSIONS_FUZZY = COROLLA_FW_VERSIONS[:-1] + [(Ecu.dsu, 0x791, None, b'xxxxxx')] -COROLLA_FW_VERSIONS_NO_DSU = COROLLA_FW_VERSIONS[:-1] - -CX5_FW_VERSIONS = [ - (Ecu.engine, 0x7e0, None, b'PYNF-188K2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00'), - (Ecu.abs, 0x760, None, b'K123-437K2-E\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00'), - (Ecu.eps, 0x730, None, b'KJ01-3210X-G-00\x00\x00\x00\x00\x00\x00\x00\x00\x00'), - (Ecu.fwdRadar, 0x764, None, b'K123-67XK2-F\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00'), - (Ecu.fwdCamera, 0x706, None, b'B61L-67XK2-T\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00'), - (Ecu.transmission, 0x7e1, None, b'PYNC-21PS1-B\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00'), -] - - -@parameterized.expand([ - # TODO: test EventName.startup for release branches - - # officially supported car - (EventName.startupMaster, TOYOTA.COROLLA, COROLLA_FW_VERSIONS, "toyota"), - (EventName.startupMaster, TOYOTA.COROLLA, COROLLA_FW_VERSIONS, "toyota"), - - # dashcamOnly car - (EventName.startupNoControl, MAZDA.CX5, CX5_FW_VERSIONS, "mazda"), - (EventName.startupNoControl, MAZDA.CX5, CX5_FW_VERSIONS, "mazda"), - - # unrecognized car with no fw - (EventName.startupNoFw, None, None, ""), - (EventName.startupNoFw, None, None, ""), - - # unrecognized car - (EventName.startupNoCar, None, COROLLA_FW_VERSIONS[:1], "toyota"), - (EventName.startupNoCar, None, COROLLA_FW_VERSIONS[:1], "toyota"), - - # fuzzy match - (EventName.startupMaster, TOYOTA.COROLLA, COROLLA_FW_VERSIONS_FUZZY, "toyota"), - (EventName.startupMaster, TOYOTA.COROLLA, COROLLA_FW_VERSIONS_FUZZY, "toyota"), -]) -def test_startup_alert(expected_event, car_model, fw_versions, brand): - controls_sock = messaging.sub_sock("controlsState") - pm = messaging.PubMaster(['can', 'pandaStates']) - - params = Params() - params.put_bool("OpenpilotEnabledToggle", True) - - # Build capnn version of FW array - if fw_versions is not None: - car_fw = [] - cp = car.CarParams.new_message() - for ecu, addr, subaddress, version in fw_versions: - f = car.CarParams.CarFw.new_message() - f.ecu = ecu - f.address = addr - f.fwVersion = version - f.brand = brand - - if subaddress is not None: - f.subAddress = subaddress - - car_fw.append(f) - cp.carVin = "1" * 17 - cp.carFw = car_fw - params.put("CarParamsCache", cp.to_bytes()) - else: - os.environ['SKIP_FW_QUERY'] = '1' - - managed_processes['controlsd'].start() - - assert pm.wait_for_readers_to_update('can', 5) - pm.send('can', can_list_to_can_capnp([[0, 0, b"", 0]])) - - assert pm.wait_for_readers_to_update('pandaStates', 5) - msg = messaging.new_message('pandaStates', 1) - msg.pandaStates[0].pandaType = log.PandaState.PandaType.uno - pm.send('pandaStates', msg) - - # fingerprint - if (car_model is None) or (fw_versions is not None): - finger = {addr: 1 for addr in range(1, 100)} - else: - finger = _FINGERPRINTS[car_model][0] - - msgs = [[addr, 0, b'\x00'*length, 0] for addr, length in finger.items()] - for _ in range(1000): - # controlsd waits for boardd to echo back that it has changed the multiplexing mode - if not params.get_bool("ObdMultiplexingChanged"): - params.put_bool("ObdMultiplexingChanged", True) - - pm.send('can', can_list_to_can_capnp(msgs)) - assert pm.wait_for_readers_to_update('can', 5, dt=0.001), f"step: {_}" - - ctrls = messaging.drain_sock(controls_sock) - if len(ctrls): - event_name = ctrls[0].controlsState.alertType.split("/")[0] - assert EVENT_NAME[expected_event] == event_name, f"expected {EVENT_NAME[expected_event]} for '{car_model}', got {event_name}" - break - else: - raise Exception(f"failed to fingerprint {car_model}") diff --git a/selfdrive/controls/tests/test_state_machine.py b/selfdrive/controls/tests/test_state_machine.py deleted file mode 100644 index d491117..0000000 --- a/selfdrive/controls/tests/test_state_machine.py +++ /dev/null @@ -1,109 +0,0 @@ -#!/usr/bin/env python3 -import unittest - -from cereal import car, log -from openpilot.common.realtime import DT_CTRL -from openpilot.selfdrive.car.car_helpers import interfaces -from openpilot.selfdrive.controls.controlsd import Controls, SOFT_DISABLE_TIME -from openpilot.selfdrive.controls.lib.events import Events, ET, Alert, Priority, AlertSize, AlertStatus, VisualAlert, \ - AudibleAlert, EVENTS -from openpilot.selfdrive.car.mock.values import CAR as MOCK - -State = log.ControlsState.OpenpilotState - -# The event types that maintain the current state -MAINTAIN_STATES = {State.enabled: (None,), State.disabled: (None,), State.softDisabling: (ET.SOFT_DISABLE,), - State.preEnabled: (ET.PRE_ENABLE,), State.overriding: (ET.OVERRIDE_LATERAL, ET.OVERRIDE_LONGITUDINAL)} -ALL_STATES = tuple(State.schema.enumerants.values()) -# The event types checked in DISABLED section of state machine -ENABLE_EVENT_TYPES = (ET.ENABLE, ET.PRE_ENABLE, ET.OVERRIDE_LATERAL, ET.OVERRIDE_LONGITUDINAL) - - -def make_event(event_types): - event = {} - for ev in event_types: - event[ev] = Alert("", "", AlertStatus.normal, AlertSize.small, Priority.LOW, - VisualAlert.none, AudibleAlert.none, 1.) - EVENTS[0] = event - return 0 - - -class TestStateMachine(unittest.TestCase): - - def setUp(self): - CarInterface, CarController, CarState = interfaces[MOCK.MOCK] - CP = CarInterface.get_non_essential_params(MOCK.MOCK) - CI = CarInterface(CP, CarController, CarState) - - self.controlsd = Controls(CI=CI) - self.controlsd.events = Events() - self.controlsd.soft_disable_timer = int(SOFT_DISABLE_TIME / DT_CTRL) - self.CS = car.CarState() - - def test_immediate_disable(self): - for state in ALL_STATES: - for et in MAINTAIN_STATES[state]: - self.controlsd.events.add(make_event([et, ET.IMMEDIATE_DISABLE])) - self.controlsd.state = state - self.controlsd.state_transition(self.CS) - self.assertEqual(State.disabled, self.controlsd.state) - self.controlsd.events.clear() - - def test_user_disable(self): - for state in ALL_STATES: - for et in MAINTAIN_STATES[state]: - self.controlsd.events.add(make_event([et, ET.USER_DISABLE])) - self.controlsd.state = state - self.controlsd.state_transition(self.CS) - self.assertEqual(State.disabled, self.controlsd.state) - self.controlsd.events.clear() - - def test_soft_disable(self): - for state in ALL_STATES: - if state == State.preEnabled: # preEnabled considers NO_ENTRY instead - continue - for et in MAINTAIN_STATES[state]: - self.controlsd.events.add(make_event([et, ET.SOFT_DISABLE])) - self.controlsd.state = state - self.controlsd.state_transition(self.CS) - self.assertEqual(self.controlsd.state, State.disabled if state == State.disabled else State.softDisabling) - self.controlsd.events.clear() - - def test_soft_disable_timer(self): - self.controlsd.state = State.enabled - self.controlsd.events.add(make_event([ET.SOFT_DISABLE])) - self.controlsd.state_transition(self.CS) - for _ in range(int(SOFT_DISABLE_TIME / DT_CTRL)): - self.assertEqual(self.controlsd.state, State.softDisabling) - self.controlsd.state_transition(self.CS) - - self.assertEqual(self.controlsd.state, State.disabled) - - def test_no_entry(self): - # Make sure noEntry keeps us disabled - for et in ENABLE_EVENT_TYPES: - self.controlsd.events.add(make_event([ET.NO_ENTRY, et])) - self.controlsd.state_transition(self.CS) - self.assertEqual(self.controlsd.state, State.disabled) - self.controlsd.events.clear() - - def test_no_entry_pre_enable(self): - # preEnabled with noEntry event - self.controlsd.state = State.preEnabled - self.controlsd.events.add(make_event([ET.NO_ENTRY, ET.PRE_ENABLE])) - self.controlsd.state_transition(self.CS) - self.assertEqual(self.controlsd.state, State.preEnabled) - - def test_maintain_states(self): - # Given current state's event type, we should maintain state - for state in ALL_STATES: - for et in MAINTAIN_STATES[state]: - self.controlsd.state = state - self.controlsd.events.add(make_event([et])) - self.controlsd.state_transition(self.CS) - self.assertEqual(self.controlsd.state, state) - self.controlsd.events.clear() - - -if __name__ == "__main__": - unittest.main() diff --git a/selfdrive/debug/can_printer.py b/selfdrive/debug/can_printer.py deleted file mode 100755 index 2200089..0000000 --- a/selfdrive/debug/can_printer.py +++ /dev/null @@ -1,45 +0,0 @@ -#!/usr/bin/env python3 -import argparse -import binascii -import time -from collections import defaultdict - -import cereal.messaging as messaging - - -def can_printer(bus, max_msg, addr, ascii_decode): - logcan = messaging.sub_sock('can', addr=addr) - - start = time.monotonic() - lp = time.monotonic() - msgs = defaultdict(list) - while 1: - can_recv = messaging.drain_sock(logcan, wait_for_one=True) - for x in can_recv: - for y in x.can: - if y.src == bus: - msgs[y.address].append(y.dat) - - if time.monotonic() - lp > 0.1: - dd = chr(27) + "[2J" - dd += f"{time.monotonic() - start:5.2f}\n" - for addr in sorted(msgs.keys()): - a = f"\"{msgs[addr][-1].decode('ascii', 'backslashreplace')}\"" if ascii_decode else "" - x = binascii.hexlify(msgs[addr][-1]).decode('ascii') - freq = len(msgs[addr]) / (time.monotonic() - start) - if max_msg is None or addr < max_msg: - dd += "%04X(%4d)(%6d)(%3dHz) %s %s\n" % (addr, addr, len(msgs[addr]), freq, x.ljust(20), a) - print(dd) - lp = time.monotonic() - -if __name__ == "__main__": - parser = argparse.ArgumentParser(description="simple CAN data viewer", - formatter_class=argparse.ArgumentDefaultsHelpFormatter) - - parser.add_argument("--bus", type=int, help="CAN bus to print out", default=0) - parser.add_argument("--max_msg", type=int, help="max addr") - parser.add_argument("--ascii", action='store_true', help="decode as ascii") - parser.add_argument("--addr", default="127.0.0.1") - - args = parser.parse_args() - can_printer(args.bus, args.max_msg, args.addr, args.ascii) diff --git a/selfdrive/debug/check_freq.py b/selfdrive/debug/check_freq.py deleted file mode 100755 index 7e7b05e..0000000 --- a/selfdrive/debug/check_freq.py +++ /dev/null @@ -1,50 +0,0 @@ -#!/usr/bin/env python3 -import argparse -import numpy as np -import time -from collections import defaultdict, deque -from typing import DefaultDict, Deque, MutableSequence - -import cereal.messaging as messaging - - -if __name__ == "__main__": - context = messaging.Context() - poller = messaging.Poller() - - parser = argparse.ArgumentParser() - parser.add_argument("socket", type=str, nargs='*', help="socket name") - args = parser.parse_args() - - socket_names = args.socket - sockets = {} - - rcv_times: DefaultDict[str, MutableSequence[float]] = defaultdict(lambda: deque(maxlen=100)) - valids: DefaultDict[str, Deque[bool]] = defaultdict(lambda: deque(maxlen=100)) - - t = time.monotonic() - for name in socket_names: - sock = messaging.sub_sock(name, poller=poller) - sockets[sock] = name - - prev_print = t - while True: - for socket in poller.poll(100): - msg = messaging.recv_one(socket) - if msg is None: - continue - - name = msg.which() - - t = time.monotonic() - rcv_times[name].append(msg.logMonoTime / 1e9) - valids[name].append(msg.valid) - - if t - prev_print > 1: - print() - for name in socket_names: - dts = np.diff(rcv_times[name]) - mean = np.mean(dts) - print(f"{name}: Freq {1.0 / mean:.2f} Hz, Min {np.min(dts) / mean * 100:.2f}%, Max {np.max(dts) / mean * 100:.2f}%, valid ", all(valids[name])) - - prev_print = t diff --git a/selfdrive/debug/dump.py b/selfdrive/debug/dump.py deleted file mode 100755 index 787e9bc..0000000 --- a/selfdrive/debug/dump.py +++ /dev/null @@ -1,63 +0,0 @@ -#!/usr/bin/env python3 -import sys -import argparse -import json -import codecs - -from hexdump import hexdump -from cereal import log -from cereal.services import SERVICE_LIST -from openpilot.tools.lib.live_logreader import raw_live_logreader - - -codecs.register_error("strict", codecs.backslashreplace_errors) - -if __name__ == "__main__": - - parser = argparse.ArgumentParser(description='Dump communication sockets. See cereal/services.py for a complete list of available sockets.') - parser.add_argument('--pipe', action='store_true') - parser.add_argument('--raw', action='store_true') - parser.add_argument('--json', action='store_true') - parser.add_argument('--dump-json', action='store_true') - parser.add_argument('--no-print', action='store_true') - parser.add_argument('--addr', default='127.0.0.1') - parser.add_argument('--values', help='values to monitor (instead of entire event)') - parser.add_argument("socket", type=str, nargs='*', default=list(SERVICE_LIST.keys()), help="socket names to dump. defaults to all services defined in cereal") - args = parser.parse_args() - - lr = raw_live_logreader(args.socket, args.addr) - - values = None - if args.values: - values = [s.strip().split(".") for s in args.values.split(",")] - - for msg in lr: - with log.Event.from_bytes(msg) as evt: - if not args.no_print: - if args.pipe: - sys.stdout.write(str(msg)) - sys.stdout.flush() - elif args.raw: - hexdump(msg) - elif args.json: - print(json.loads(msg)) - elif args.dump_json: - print(json.dumps(evt.to_dict())) - elif values: - print(f"logMonotime = {evt.logMonoTime}") - for value in values: - if hasattr(evt, value[0]): - item = evt - for key in value: - item = getattr(item, key) - print(f"{'.'.join(value)} = {item}") - print("") - else: - try: - print(evt) - except UnicodeDecodeError: - w = evt.which() - s = f"( logMonoTime {evt.logMonoTime} \n {w} = " - s += str(evt.__getattr__(w)) - s += f"\n valid = {evt.valid} )" - print(s) diff --git a/selfdrive/debug/filter_log_message.py b/selfdrive/debug/filter_log_message.py deleted file mode 100755 index 9cbab0b..0000000 --- a/selfdrive/debug/filter_log_message.py +++ /dev/null @@ -1,79 +0,0 @@ -#!/usr/bin/env python3 -import argparse -import json - -import cereal.messaging as messaging -from openpilot.tools.lib.logreader import LogReader - -LEVELS = { - "DEBUG": 10, - "INFO": 20, - "WARNING": 30, - "ERROR": 40, - "CRITICAL": 50, -} - -ANDROID_LOG_SOURCE = { - 0: "MAIN", - 1: "RADIO", - 2: "EVENTS", - 3: "SYSTEM", - 4: "CRASH", - 5: "KERNEL", -} - - -def print_logmessage(t, msg, min_level): - try: - log = json.loads(msg) - if log['levelnum'] >= min_level: - print(f"[{t / 1e9:.6f}] {log['filename']}:{log.get('lineno', '')} - {log.get('funcname', '')}: {log['msg']}") - if 'exc_info' in log: - print(log['exc_info']) - except json.decoder.JSONDecodeError: - print(f"[{t / 1e9:.6f}] decode error: {msg}") - - -def print_androidlog(t, msg): - source = ANDROID_LOG_SOURCE[msg.id] - try: - m = json.loads(msg.message)['MESSAGE'] - except Exception: - m = msg.message - - print(f"[{t / 1e9:.6f}] {source} {msg.pid} {msg.tag} - {m}") - - -if __name__ == "__main__": - parser = argparse.ArgumentParser() - parser.add_argument('--absolute', action='store_true') - parser.add_argument('--level', default='DEBUG') - parser.add_argument('--addr', default='127.0.0.1') - parser.add_argument("route", type=str, nargs='*', help="route name + segment number for offline usage") - args = parser.parse_args() - - min_level = LEVELS[args.level] - - if args.route: - st = None if not args.absolute else 0 - for route in args.route: - lr = LogReader(route, sort_by_time=True) - for m in lr: - if st is None: - st = m.logMonoTime - if m.which() == 'logMessage': - print_logmessage(m.logMonoTime-st, m.logMessage, min_level) - elif m.which() == 'errorLogMessage': - print_logmessage(m.logMonoTime-st, m.errorLogMessage, min_level) - elif m.which() == 'androidLog': - print_androidlog(m.logMonoTime-st, m.androidLog) - else: - sm = messaging.SubMaster(['logMessage', 'androidLog'], addr=args.addr) - while True: - sm.update() - - if sm.updated['logMessage']: - print_logmessage(sm.logMonoTime['logMessage'], sm['logMessage'], min_level) - - if sm.updated['androidLog']: - print_androidlog(sm.logMonoTime['androidLog'], sm['androidLog']) diff --git a/selfdrive/debug/format_fingerprints.py b/selfdrive/debug/format_fingerprints.py deleted file mode 100755 index bd58227..0000000 --- a/selfdrive/debug/format_fingerprints.py +++ /dev/null @@ -1,81 +0,0 @@ -#!/usr/bin/env python3 -import jinja2 -import os - -from cereal import car -from openpilot.common.basedir import BASEDIR -from openpilot.selfdrive.car.interfaces import get_interface_attr - -Ecu = car.CarParams.Ecu - -CARS = get_interface_attr('CAR') -FW_VERSIONS = get_interface_attr('FW_VERSIONS') -FINGERPRINTS = get_interface_attr('FINGERPRINTS') -ECU_NAME = {v: k for k, v in Ecu.schema.enumerants.items()} - -FINGERPRINTS_PY_TEMPLATE = jinja2.Template(""" -{%- if FINGERPRINTS[brand] %} -# ruff: noqa: E501 -{% endif %} -{% if FW_VERSIONS[brand] %} -from cereal import car -{% endif %} -from openpilot.selfdrive.car.{{brand}}.values import CAR -{% if FW_VERSIONS[brand] %} - -Ecu = car.CarParams.Ecu -{% endif %} -{% if comments +%} -{{ comments | join() }} -{% endif %} -{% if FINGERPRINTS[brand] %} - -FINGERPRINTS = { -{% for car, fingerprints in FINGERPRINTS[brand].items() %} - CAR.{{car.name}}: [{ -{% for fingerprint in fingerprints %} -{% if not loop.first %} - {{ "{" }} -{% endif %} - {% for key, value in fingerprint.items() %}{{key}}: {{value}}{% if not loop.last %}, {% endif %}{% endfor %} - - }{% if loop.last %}]{% endif %}, -{% endfor %} -{% endfor %} -} -{% endif %} - -FW_VERSIONS{% if not FW_VERSIONS[brand] %}: dict[str, dict[tuple, list[bytes]]]{% endif %} = { -{% for car, _ in FW_VERSIONS[brand].items() %} - CAR.{{car.name}}: { -{% for key, fw_versions in FW_VERSIONS[brand][car].items() %} - (Ecu.{{ECU_NAME[key[0]]}}, 0x{{"%0x" | format(key[1] | int)}}, \ -{% if key[2] %}0x{{"%0x" | format(key[2] | int)}}{% else %}{{key[2]}}{% endif %}): [ - {% for fw_version in (fw_versions + extra_fw_versions.get(car, {}).get(key, [])) | unique | sort %} - {{fw_version}}, - {% endfor %} - ], -{% endfor %} - }, -{% endfor %} -} - -""", trim_blocks=True) - - -def format_brand_fw_versions(brand, extra_fw_versions: None | dict[str, dict[tuple, list[bytes]]] = None): - extra_fw_versions = extra_fw_versions or {} - - fingerprints_file = os.path.join(BASEDIR, f"selfdrive/car/{brand}/fingerprints.py") - with open(fingerprints_file, "r") as f: - comments = [line for line in f.readlines() if line.startswith("#") and "noqa" not in line] - - with open(fingerprints_file, "w") as f: - f.write(FINGERPRINTS_PY_TEMPLATE.render(brand=brand, comments=comments, ECU_NAME=ECU_NAME, - FINGERPRINTS=FINGERPRINTS, FW_VERSIONS=FW_VERSIONS, - extra_fw_versions=extra_fw_versions)) - - -if __name__ == "__main__": - for brand in FW_VERSIONS.keys(): - format_brand_fw_versions(brand) diff --git a/selfdrive/debug/get_fingerprint.py b/selfdrive/debug/get_fingerprint.py deleted file mode 100755 index f7f7a16..0000000 --- a/selfdrive/debug/get_fingerprint.py +++ /dev/null @@ -1,31 +0,0 @@ -#!/usr/bin/env python3 - -# simple script to get a vehicle fingerprint. - -# Instructions: -# - connect to a Panda -# - run selfdrive/boardd/boardd -# - launching this script -# Note: it's very important that the car is in stock mode, in order to collect a complete fingerprint -# - since some messages are published at low frequency, keep this script running for at least 30s, -# until all messages are received at least once - -import cereal.messaging as messaging - -logcan = messaging.sub_sock('can') -msgs = {} -while True: - lc = messaging.recv_sock(logcan, True) - if lc is None: - continue - - for c in lc.can: - # read also msgs sent by EON on CAN bus 0x80 and filter out the - # addr with more than 11 bits - if c.src % 0x80 == 0 and c.address < 0x800 and c.address not in (0x7df, 0x7e0, 0x7e8): - msgs[c.address] = len(c.dat) - - fingerprint = ', '.join("%d: %d" % v for v in sorted(msgs.items())) - - print(f"number of messages {len(msgs)}:") - print(f"fingerprint {fingerprint}") diff --git a/selfdrive/debug/hyundai_enable_radar_points.py b/selfdrive/debug/hyundai_enable_radar_points.py deleted file mode 100755 index 7735391..0000000 --- a/selfdrive/debug/hyundai_enable_radar_points.py +++ /dev/null @@ -1,128 +0,0 @@ -#!/usr/bin/env python3 -"""Some Hyundai radars can be reconfigured to output (debug) radar points on bus 1. -Reconfiguration is done over UDS by reading/writing to 0x0142 using the Read/Write Data By Identifier -endpoints (0x22 & 0x2E). This script checks your radar firmware version against a list of known -firmware versions. If you want to try on a new radar make sure to note the default config value -in case it's different from the other radars and you need to revert the changes. - -After changing the config the car should not show any faults when openpilot is not running. -These config changes are persistent across car reboots. You need to run this script again -to go back to the default values. - -USE AT YOUR OWN RISK! Safety features, like AEB and FCW, might be affected by these changes.""" - -import sys -import argparse -from typing import NamedTuple -from subprocess import check_output, CalledProcessError - -from panda.python import Panda -from panda.python.uds import UdsClient, SESSION_TYPE, DATA_IDENTIFIER_TYPE - -class ConfigValues(NamedTuple): - default_config: bytes - tracks_enabled: bytes - -# If your radar supports changing data identifier 0x0142 as well make a PR to -# this file to add your firmware version. Make sure to post a drive as proof! -# NOTE: these firmware versions do not match what openpilot uses -# because this script uses a different diagnostic session type -SUPPORTED_FW_VERSIONS = { - # 2020 SONATA - b"DN8_ SCC FHCUP 1.00 1.00 99110-L0000\x19\x08)\x15T ": ConfigValues( - default_config=b"\x00\x00\x00\x01\x00\x00", - tracks_enabled=b"\x00\x00\x00\x01\x00\x01"), - b"DN8_ SCC F-CUP 1.00 1.00 99110-L0000\x19\x08)\x15T ": ConfigValues( - default_config=b"\x00\x00\x00\x01\x00\x00", - tracks_enabled=b"\x00\x00\x00\x01\x00\x01"), - # 2021 SONATA HYBRID - b"DNhe SCC FHCUP 1.00 1.02 99110-L5000 \x01#\x15# ": ConfigValues( - default_config=b"\x00\x00\x00\x01\x00\x00", - tracks_enabled=b"\x00\x00\x00\x01\x00\x01"), - # 2020 PALISADE - b"LX2_ SCC FHCUP 1.00 1.04 99110-S8100\x19\x05\x02\x16V ": ConfigValues( - default_config=b"\x00\x00\x00\x01\x00\x00", - tracks_enabled=b"\x00\x00\x00\x01\x00\x01"), - # 2022 PALISADE - b"LX2_ SCC FHCUP 1.00 1.00 99110-S8110!\x04\x05\x17\x01 ": ConfigValues( - default_config=b"\x00\x00\x00\x01\x00\x00", - tracks_enabled=b"\x00\x00\x00\x01\x00\x01"), - # 2020 SANTA FE - b"TM__ SCC F-CUP 1.00 1.03 99110-S2000\x19\x050\x13' ": ConfigValues( - default_config=b"\x00\x00\x00\x01\x00\x00", - tracks_enabled=b"\x00\x00\x00\x01\x00\x01"), - # 2020 GENESIS G70 - b'IK__ SCC F-CUP 1.00 1.02 96400-G9100\x18\x07\x06\x17\x12 ': ConfigValues( - default_config=b"\x00\x00\x00\x01\x00\x00", - tracks_enabled=b"\x00\x00\x00\x01\x00\x01"), - # 2019 SANTA FE - b"TM__ SCC F-CUP 1.00 1.00 99110-S1210\x19\x01%\x168 ": ConfigValues( - default_config=b"\x00\x00\x00\x01\x00\x00", - tracks_enabled=b"\x00\x00\x00\x01\x00\x01"), - b"TM__ SCC F-CUP 1.00 1.02 99110-S2000\x18\x07\x08\x18W ": ConfigValues( - default_config=b"\x00\x00\x00\x01\x00\x00", - tracks_enabled=b"\x00\x00\x00\x01\x00\x01"), - # 2021 K5 HEV - b"DLhe SCC FHCUP 1.00 1.02 99110-L7000 \x01 \x102 ": ConfigValues( - default_config=b"\x00\x00\x00\x01\x00\x00", - tracks_enabled=b"\x00\x00\x00\x01\x00\x01"), -} - -if __name__ == "__main__": - parser = argparse.ArgumentParser(description='configure radar to output points (or reset to default)') - parser.add_argument('--default', action="store_true", default=False, help='reset to default configuration (default: false)') - parser.add_argument('--debug', action="store_true", default=False, help='enable debug output (default: false)') - parser.add_argument('--bus', type=int, default=0, help='can bus to use (default: 0)') - args = parser.parse_args() - - try: - check_output(["pidof", "boardd"]) - print("boardd is running, please kill openpilot before running this script! (aborted)") - sys.exit(1) - except CalledProcessError as e: - if e.returncode != 1: # 1 == no process found (boardd not running) - raise e - - confirm = input("power on the vehicle keeping the engine off (press start button twice) then type OK to continue: ").upper().strip() - if confirm != "OK": - print("\nyou didn't type 'OK! (aborted)") - sys.exit(0) - - panda = Panda() - panda.set_safety_mode(Panda.SAFETY_ELM327) - uds_client = UdsClient(panda, 0x7D0, bus=args.bus, debug=args.debug) - - print("\n[START DIAGNOSTIC SESSION]") - session_type : SESSION_TYPE = 0x07 # type: ignore - uds_client.diagnostic_session_control(session_type) - - print("[HARDWARE/SOFTWARE VERSION]") - fw_version_data_id : DATA_IDENTIFIER_TYPE = 0xf100 # type: ignore - fw_version = uds_client.read_data_by_identifier(fw_version_data_id) - print(fw_version) - if fw_version not in SUPPORTED_FW_VERSIONS.keys(): - print("radar not supported! (aborted)") - sys.exit(1) - - print("[GET CONFIGURATION]") - config_data_id : DATA_IDENTIFIER_TYPE = 0x0142 # type: ignore - current_config = uds_client.read_data_by_identifier(config_data_id) - config_values = SUPPORTED_FW_VERSIONS[fw_version] - new_config = config_values.default_config if args.default else config_values.tracks_enabled - print(f"current config: 0x{current_config.hex()}") - if current_config != new_config: - print("[CHANGE CONFIGURATION]") - print(f"new config: 0x{new_config.hex()}") - uds_client.write_data_by_identifier(config_data_id, new_config) - if not args.default and current_config != SUPPORTED_FW_VERSIONS[fw_version].default_config: - print("\ncurrent config does not match expected default! (aborted)") - sys.exit(1) - - print("[DONE]") - print("\nrestart your vehicle and ensure there are no faults") - if not args.default: - print("you can run this script again with --default to go back to the original (factory) settings") - else: - print("[DONE]") - print("\ncurrent config is already the desired configuration") - sys.exit(0) diff --git a/selfdrive/debug/uiview.py b/selfdrive/debug/uiview.py deleted file mode 100755 index f4440a9..0000000 --- a/selfdrive/debug/uiview.py +++ /dev/null @@ -1,33 +0,0 @@ -#!/usr/bin/env python3 -import time - -from cereal import car, log, messaging -from openpilot.common.params import Params -from openpilot.selfdrive.manager.process_config import managed_processes - -if __name__ == "__main__": - CP = car.CarParams(notCar=True) - Params().put("CarParams", CP.to_bytes()) - - procs = ['camerad', 'ui', 'modeld', 'calibrationd'] - for p in procs: - managed_processes[p].start() - - pm = messaging.PubMaster(['controlsState', 'deviceState', 'pandaStates', 'carParams']) - - msgs = {s: messaging.new_message(s) for s in ['controlsState', 'deviceState', 'carParams']} - msgs['deviceState'].deviceState.started = True - msgs['carParams'].carParams.openpilotLongitudinalControl = True - - msgs['pandaStates'] = messaging.new_message('pandaStates', 1) - msgs['pandaStates'].pandaStates[0].ignitionLine = True - msgs['pandaStates'].pandaStates[0].pandaType = log.PandaState.PandaType.uno - - try: - while True: - time.sleep(1 / 100) # continually send, rate doesn't matter - for s in msgs: - pm.send(s, msgs[s]) - except KeyboardInterrupt: - for p in procs: - managed_processes[p].stop() diff --git a/selfdrive/debug/vw_mqb_config.py b/selfdrive/debug/vw_mqb_config.py deleted file mode 100755 index 75409e3..0000000 --- a/selfdrive/debug/vw_mqb_config.py +++ /dev/null @@ -1,157 +0,0 @@ -#!/usr/bin/env python3 - -import argparse -import struct -from enum import IntEnum -from panda import Panda -from panda.python.uds import UdsClient, MessageTimeoutError, NegativeResponseError, SESSION_TYPE,\ - DATA_IDENTIFIER_TYPE, ACCESS_TYPE - -# TODO: extend UDS library to allow custom/vendor-defined data identifiers without ignoring type checks -class VOLKSWAGEN_DATA_IDENTIFIER_TYPE(IntEnum): - CODING = 0x0600 - -# TODO: extend UDS library security_access() to take an access level offset per ISO 14229-1:2020 10.4 and remove this -class ACCESS_TYPE_LEVEL_1(IntEnum): - REQUEST_SEED = ACCESS_TYPE.REQUEST_SEED + 2 - SEND_KEY = ACCESS_TYPE.SEND_KEY + 2 - -MQB_EPS_CAN_ADDR = 0x712 -RX_OFFSET = 0x6a - -if __name__ == "__main__": - desc_text = "Shows Volkswagen EPS software and coding info, and enables or disables Heading Control Assist " + \ - "(Lane Assist). Useful for enabling HCA on cars without factory Lane Assist that want to use " + \ - "openpilot integrated at the CAN gateway (J533)." - epilog_text = "This tool is meant to run directly on a vehicle-installed comma three, with the " + \ - "openpilot/tmux processes stopped. It should also work on a separate PC with a USB-attached comma " + \ - "panda. Vehicle ignition must be on. Recommend engine not be running when making changes. Must " + \ - "turn ignition off and on again for any changes to take effect." - parser = argparse.ArgumentParser(description=desc_text, epilog=epilog_text) - parser.add_argument("--debug", action="store_true", help="enable ISO-TP/UDS stack debugging output") - parser.add_argument("action", choices={"show", "enable", "disable"}, help="show or modify current EPS HCA config") - args = parser.parse_args() - - panda = Panda() - panda.set_safety_mode(Panda.SAFETY_ELM327) - bus = 1 if panda.has_obd() else 0 - uds_client = UdsClient(panda, MQB_EPS_CAN_ADDR, MQB_EPS_CAN_ADDR + RX_OFFSET, bus, timeout=0.2, debug=args.debug) - - try: - uds_client.diagnostic_session_control(SESSION_TYPE.EXTENDED_DIAGNOSTIC) - except MessageTimeoutError: - print("Timeout opening session with EPS") - quit() - - odx_file, current_coding = None, None - try: - hw_pn = uds_client.read_data_by_identifier(DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_ECU_HARDWARE_NUMBER).decode("utf-8") - sw_pn = uds_client.read_data_by_identifier(DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_SPARE_PART_NUMBER).decode("utf-8") - sw_ver = uds_client.read_data_by_identifier(DATA_IDENTIFIER_TYPE.VEHICLE_MANUFACTURER_ECU_SOFTWARE_VERSION_NUMBER).decode("utf-8") - component = uds_client.read_data_by_identifier(DATA_IDENTIFIER_TYPE.SYSTEM_NAME_OR_ENGINE_TYPE).decode("utf-8") - odx_file = uds_client.read_data_by_identifier(DATA_IDENTIFIER_TYPE.ODX_FILE).decode("utf-8").rstrip('\x00') - current_coding = uds_client.read_data_by_identifier(VOLKSWAGEN_DATA_IDENTIFIER_TYPE.CODING) # type: ignore - coding_text = current_coding.hex() - - print("\nEPS diagnostic data\n") - print(f" Part No HW: {hw_pn}") - print(f" Part No SW: {sw_pn}") - print(f" SW Version: {sw_ver}") - print(f" Component: {component}") - print(f" Coding: {coding_text}") - print(f" ASAM Dataset: {odx_file}") - except NegativeResponseError: - print("Error fetching data from EPS") - quit() - except MessageTimeoutError: - print("Timeout fetching data from EPS") - quit() - - coding_variant, current_coding_array, coding_byte, coding_bit = None, None, 0, 0 - coding_length = len(current_coding) - - # EPS_MQB_ZFLS - if odx_file in ("EV_SteerAssisMQB", "EV_SteerAssisMNB"): - coding_variant = "ZFLS" - coding_byte = 0 - coding_bit = 4 - - # MQB_PP_APA, MQB_VWBS_GEN2 - elif odx_file in ("EV_SteerAssisVWBSMQBA", "EV_SteerAssisVWBSMQBGen2"): - coding_variant = "APA" - coding_byte = 3 - coding_bit = 0 - - else: - print("Configuration changes not yet supported on this EPS!") - quit() - - current_coding_array = struct.unpack(f"!{coding_length}B", current_coding) - hca_enabled = (current_coding_array[coding_byte] & (1 << coding_bit) != 0) - hca_text = ("DISABLED", "ENABLED")[hca_enabled] - print(f" Lane Assist: {hca_text}") - - try: - params = uds_client.read_data_by_identifier(DATA_IDENTIFIER_TYPE.APPLICATION_DATA_IDENTIFICATION).decode("utf-8") - param_version_system_params = params[1:3] - param_vehicle_type = params[3:5] - param_index_char_curve = params[5:7] - param_version_char_values = params[7:9] - param_version_memory_map = params[9:11] - print("\nEPS parameterization (per-vehicle calibration) data\n") - print(f" Version of system parameters: {param_version_system_params}") - print(f" Vehicle type: {param_vehicle_type}") - print(f" Index of characteristic curve: {param_index_char_curve}") - print(f" Version of characteristic values: {param_version_char_values}") - print(f" Version of memory map: {param_version_memory_map}") - except (NegativeResponseError, MessageTimeoutError): - print("Error fetching parameterization data from EPS!") - quit() - - if args.action in ["enable", "disable"]: - print("\nAttempting configuration update") - - assert(coding_variant in ("ZFLS", "APA")) - # ZFLS EPS config coding length can be anywhere from 1 to 4 bytes, but the - # bit we care about is always in the same place in the first byte - if args.action == "enable": - new_byte = current_coding_array[coding_byte] | (1 << coding_bit) - else: - new_byte = current_coding_array[coding_byte] & ~(1 << coding_bit) - new_coding = current_coding[0:coding_byte] + new_byte.to_bytes(1, "little") + current_coding[coding_byte+1:] - - try: - seed = uds_client.security_access(ACCESS_TYPE_LEVEL_1.REQUEST_SEED) # type: ignore - key = struct.unpack("!I", seed)[0] + 28183 # yeah, it's like that - uds_client.security_access(ACCESS_TYPE_LEVEL_1.SEND_KEY, struct.pack("!I", key)) # type: ignore - except (NegativeResponseError, MessageTimeoutError): - print("Security access failed!") - print("Open the hood and retry (disables the \"diagnostic firewall\" on newer vehicles)") - quit() - - try: - # Programming date and tester number must be written before making - # a change, or write to CODING will fail with request sequence error - # Encoding on tester is unclear, it contains the workshop code in the - # last two bytes, but not the VZ/importer or tester serial number - # Can't seem to read it back, but we can read the calibration tester, - # so fib a little and say that same tester did the programming - # TODO: encode the actual current date - prog_date = b'\x22\x02\x08' - uds_client.write_data_by_identifier(DATA_IDENTIFIER_TYPE.PROGRAMMING_DATE, prog_date) - tester_num = uds_client.read_data_by_identifier(DATA_IDENTIFIER_TYPE.CALIBRATION_REPAIR_SHOP_CODE_OR_CALIBRATION_EQUIPMENT_SERIAL_NUMBER) - uds_client.write_data_by_identifier(DATA_IDENTIFIER_TYPE.REPAIR_SHOP_CODE_OR_TESTER_SERIAL_NUMBER, tester_num) - uds_client.write_data_by_identifier(VOLKSWAGEN_DATA_IDENTIFIER_TYPE.CODING, new_coding) # type: ignore - except (NegativeResponseError, MessageTimeoutError): - print("Writing new configuration failed!") - print("Make sure the comma processes are stopped: tmux kill-session -t comma") - quit() - - try: - # Read back result just to make 100% sure everything worked - current_coding_text = uds_client.read_data_by_identifier(VOLKSWAGEN_DATA_IDENTIFIER_TYPE.CODING).hex() # type: ignore - print(f" New coding: {current_coding_text}") - except (NegativeResponseError, MessageTimeoutError): - print("Reading back updated coding failed!") - quit() - print("EPS configuration successfully updated") diff --git a/selfdrive/frogpilot/navigation/ui/navigation_functions.h b/selfdrive/frogpilot/navigation/ui/navigation_functions.h deleted file mode 100644 index b4db3bc..0000000 --- a/selfdrive/frogpilot/navigation/ui/navigation_functions.h +++ /dev/null @@ -1,311 +0,0 @@ -#pragma once - -#include -#include -#include -#include -#include -#include -#include -#include - -#include "selfdrive/ui/qt/offroad/settings.h" -#include "selfdrive/ui/qt/widgets/controls.h" -#include "selfdrive/ui/ui.h" - -QMap northeastMap = { - {"CT", "Connecticut"}, {"DE", "Delaware"}, {"MA", "Massachusetts"}, - {"MD", "Maryland"}, {"ME", "Maine"}, {"NH", "New Hampshire"}, - {"NJ", "New Jersey"}, {"NY", "New York"}, {"PA", "Pennsylvania"}, - {"RI", "Rhode Island"}, {"VT", "Vermont"} -}; - -QMap midwestMap = { - {"IA", "Iowa"}, {"IL", "Illinois"}, {"IN", "Indiana"}, - {"KS", "Kansas"}, {"MI", "Michigan"}, {"MN", "Minnesota"}, - {"MO", "Missouri"}, {"ND", "North Dakota"}, {"NE", "Nebraska"}, - {"OH", "Ohio"}, {"SD", "South Dakota"}, {"WI", "Wisconsin"} -}; - -QMap southMap = { - {"AL", "Alabama"}, {"AR", "Arkansas"}, {"FL", "Florida"}, - {"GA", "Georgia"}, {"KY", "Kentucky"}, {"LA", "Louisiana"}, - {"MS", "Mississippi"}, {"NC", "North Carolina"}, {"OK", "Oklahoma"}, - {"SC", "South Carolina"}, {"TN", "Tennessee"}, {"TX", "Texas"}, - {"VA", "Virginia"}, {"WV", "West Virginia"} -}; - -QMap westMap = { - {"AK", "Alaska"}, {"AZ", "Arizona"}, {"CA", "California"}, - {"CO", "Colorado"}, {"HI", "Hawaii"}, {"ID", "Idaho"}, - {"MT", "Montana"}, {"NM", "New Mexico"}, {"NV", "Nevada"}, - {"OR", "Oregon"}, {"UT", "Utah"}, {"WA", "Washington"}, - {"WY", "Wyoming"} -}; - -QMap territoriesMap = { - {"AS", "American Samoa"}, {"DC", "District of Columbia"}, - {"GM", "Guam"}, {"MP", "North Mariana Islands"}, - {"PR", "Puerto Rico"}, {"VI", "Virgin Islands"} -}; - -QMap africaMap = { - {"DZ", "Algeria"}, {"AO", "Angola"}, {"BJ", "Benin"}, {"BW", "Botswana"}, - {"BF", "Burkina Faso"}, {"BI", "Burundi"}, {"CM", "Cameroon"}, {"CV", "Cape Verde"}, - {"CF", "Central African Republic"}, {"TD", "Chad"}, {"KM", "Comoros"}, {"CG", "Congo (Brazzaville)"}, - {"CD", "Congo (Kinshasa)"}, {"CI", "Ivory Coast"}, {"DJ", "Djibouti"}, {"EG", "Egypt"}, - {"GQ", "Equatorial Guinea"}, {"ER", "Eritrea"}, {"SZ", "Eswatini"}, {"ET", "Ethiopia"}, - {"GA", "Gabon"}, {"GM", "Gambia"}, {"GH", "Ghana"}, {"GN", "Guinea"}, - {"GW", "Guinea-Bissau"}, {"KE", "Kenya"}, {"LS", "Lesotho"}, {"LR", "Liberia"}, - {"LY", "Libya"}, {"MG", "Madagascar"}, {"MW", "Malawi"}, {"ML", "Mali"}, - {"MR", "Mauritania"}, {"MU", "Mauritius"}, {"MA", "Morocco"}, {"MZ", "Mozambique"}, - {"NA", "Namibia"}, {"NE", "Niger"}, {"NG", "Nigeria"}, {"RW", "Rwanda"}, - {"ST", "Sao Tome and Principe"}, {"SN", "Senegal"}, {"SC", "Seychelles"}, {"SL", "Sierra Leone"}, - {"SO", "Somalia"}, {"ZA", "South Africa"}, {"SS", "South Sudan"}, {"SD", "Sudan"}, - {"TZ", "Tanzania"}, {"TG", "Togo"}, {"TN", "Tunisia"}, {"UG", "Uganda"}, - {"EH", "Western Sahara"}, {"ZM", "Zambia"}, {"ZW", "Zimbabwe"} -}; - -QMap antarcticaMap = { - {"AQ", "Antarctica"} -}; - -QMap asiaMap = { - {"AF", "Afghanistan"}, {"AM", "Armenia"}, {"AZ", "Azerbaijan"}, {"BH", "Bahrain"}, - {"BD", "Bangladesh"}, {"BT", "Bhutan"}, {"BN", "Brunei"}, {"KH", "Cambodia"}, - {"CN", "China"}, {"CY", "Cyprus"}, {"GE", "Georgia"}, {"IN", "India"}, - {"ID", "Indonesia"}, {"IR", "Iran"}, {"IQ", "Iraq"}, {"IL", "Israel"}, - {"JP", "Japan"}, {"JO", "Jordan"}, {"KZ", "Kazakhstan"}, {"KP", "North Korea"}, - {"KR", "South Korea"}, {"KW", "Kuwait"}, {"KG", "Kyrgyzstan"}, {"LA", "Laos"}, - {"LB", "Lebanon"}, {"MY", "Malaysia"}, {"MV", "Maldives"}, {"MN", "Mongolia"}, - {"MM", "Myanmar"}, {"NP", "Nepal"}, {"OM", "Oman"}, {"PK", "Pakistan"}, - {"PS", "Palestine"}, {"PH", "Philippines"}, {"QA", "Qatar"}, {"SA", "Saudi Arabia"}, - {"SG", "Singapore"}, {"LK", "Sri Lanka"}, {"SY", "Syria"}, {"TW", "Taiwan"}, - {"TJ", "Tajikistan"}, {"TH", "Thailand"}, {"TL", "Timor-Leste"}, {"TR", "Turkey"}, - {"TM", "Turkmenistan"}, {"AE", "United Arab Emirates"}, {"UZ", "Uzbekistan"}, {"VN", "Vietnam"}, - {"YE", "Yemen"} -}; - -QMap europeMap = { - {"AL", "Albania"}, {"AD", "Andorra"}, {"AT", "Austria"}, {"BY", "Belarus"}, - {"BE", "Belgium"}, {"BA", "Bosnia and Herzegovina"}, {"BG", "Bulgaria"}, {"HR", "Croatia"}, - {"CY", "Cyprus"}, {"CZ", "Czech Republic"}, {"DK", "Denmark"}, {"EE", "Estonia"}, - {"FI", "Finland"}, {"FR", "France"}, {"DE", "Germany"}, {"GR", "Greece"}, - {"HU", "Hungary"}, {"IS", "Iceland"}, {"IE", "Ireland"}, {"IT", "Italy"}, - {"LV", "Latvia"}, {"LI", "Liechtenstein"}, {"LT", "Lithuania"}, {"LU", "Luxembourg"}, - {"MT", "Malta"}, {"MD", "Moldova"}, {"MC", "Monaco"}, {"ME", "Montenegro"}, - {"NL", "Netherlands"}, {"MK", "North Macedonia"}, {"NO", "Norway"}, {"PL", "Poland"}, - {"PT", "Portugal"}, {"RO", "Romania"}, {"RU", "Russia"}, {"SM", "San Marino"}, - {"RS", "Serbia"}, {"SK", "Slovakia"}, {"SI", "Slovenia"}, {"ES", "Spain"}, - {"SE", "Sweden"}, {"CH", "Switzerland"}, {"TR", "Turkey"}, {"UA", "Ukraine"}, - {"GB", "United Kingdom"}, {"VA", "Vatican City"} -}; - -QMap northAmericaMap = { - {"AG", "Antigua and Barbuda"}, {"BS", "Bahamas"}, {"BB", "Barbados"}, {"BZ", "Belize"}, - {"CA", "Canada"}, {"CR", "Costa Rica"}, {"CU", "Cuba"}, {"DM", "Dominica"}, - {"DO", "Dominican Republic"}, {"SV", "El Salvador"}, {"GD", "Grenada"}, {"GT", "Guatemala"}, - {"HT", "Haiti"}, {"HN", "Honduras"}, {"JM", "Jamaica"}, {"MX", "Mexico"}, - {"NI", "Nicaragua"}, {"PA", "Panama"}, {"KN", "Saint Kitts and Nevis"}, {"LC", "Saint Lucia"}, - {"VC", "Saint Vincent and the Grenadines"}, {"TT", "Trinidad and Tobago"}, {"US", "United States"} -}; - -QMap oceaniaMap = { - {"AU", "Australia"}, {"FJ", "Fiji"}, {"KI", "Kiribati"}, {"MH", "Marshall Islands"}, - {"FM", "Micronesia"}, {"NR", "Nauru"}, {"NZ", "New Zealand"}, {"PW", "Palau"}, - {"PG", "Papua New Guinea"}, {"WS", "Samoa"}, {"SB", "Solomon Islands"}, {"TO", "Tonga"}, - {"TV", "Tuvalu"}, {"VU", "Vanuatu"} -}; - -QMap southAmericaMap = { - {"AR", "Argentina"}, {"BO", "Bolivia"}, {"BR", "Brazil"}, {"CL", "Chile"}, - {"CO", "Colombia"}, {"EC", "Ecuador"}, {"GY", "Guyana"}, {"PY", "Paraguay"}, - {"PE", "Peru"}, {"SR", "Suriname"}, {"TT", "Trinidad and Tobago"}, {"UY", "Uruguay"}, - {"VE", "Venezuela"} -}; - -class ButtonSelectionControl : public QWidget { -public: - static QString selectedStates; - static QString selectedCountries; - - explicit ButtonSelectionControl(const QString &id, const QString &title, const QString &description, - const QMap &map, bool isCountry, QWidget *parent = nullptr) - : QWidget(parent), country(isCountry) { - QVBoxLayout *layout = new QVBoxLayout(this); - layout->setAlignment(Qt::AlignTop); - layout->setSpacing(10); - - QHBoxLayout *buttonsLayout = new QHBoxLayout(); - buttonsLayout->setSpacing(10); - layout->addLayout(buttonsLayout); - - int count = 0; - int max = country ? 3 : 4; - - QJsonObject mapsSelected = QJsonDocument::fromJson(QString::fromStdString(Params().get("MapsSelected")).toUtf8()).object(); - - for (const QString &stateCode : map.keys()) { - if (count % max == 0 && count != 0) { - buttonsLayout = new QHBoxLayout(); - buttonsLayout->setSpacing(10); - layout->addLayout(buttonsLayout); - } - - QPushButton *button = createButton(buttonsLayout, map[stateCode], stateCode); - - QString key = country ? "nations" : "states"; - if (mapsSelected.contains(key)) { - QJsonArray selectedItems = mapsSelected.value(key).toArray(); - button->setChecked(selectedItems.contains(stateCode)); - } - - count++; - } - - adjustButtonWidths(buttonsLayout); - } - -private: - bool country; - - const QString buttonStyle = R"( - QPushButton { - border-radius: 50px; font-size: 40px; font-weight: 500; - height: 100px; padding: 0 25 0 25; color: #E4E4E4; - background-color: #393939; - } - QPushButton:pressed, QPushButton:checked { - background-color: #4a4a4a; - } - QPushButton:checked:enabled { - background-color: #33Ab4C; - } - QPushButton:disabled { - color: #33E4E4E4; - } - )"; - - QPushButton *createButton(QHBoxLayout *layout, const QString &label, const QString &stateCode) { - QPushButton *button = new QPushButton(label, this); - button->setCheckable(true); - button->setStyleSheet(buttonStyle); - connect(button, &QPushButton::clicked, this, [this, button, stateCode] { updateState(stateCode, button); }); - layout->addWidget(button); - return button; - } - - void adjustButtonWidths(QHBoxLayout *layout) { - if (!layout || layout->count() == (country ? 3 : 4)) return; - - for (int i = 0; i < layout->count(); ++i) { - QWidget *widget = layout->itemAt(i)->widget(); - QPushButton *button = qobject_cast(widget); - if (button) { - button->setMinimumWidth(button->sizeHint().width()); - } - } - } - - void updateState(const QString &newState, QPushButton *button) { - QString &selectedList = country ? selectedCountries : selectedStates; - QStringList tempList = selectedList.split(','); - - if (button->isChecked()) { - if (!selectedList.isEmpty()) selectedList += ","; - selectedList += newState; - } else { - tempList.removeAll(newState); - selectedList = tempList.join(','); - } - - Params("/dev/shm/params").remove("OSMDownloadLocations"); - } -}; - -QString ButtonSelectionControl::selectedStates = ""; -QString ButtonSelectionControl::selectedCountries = ""; - -namespace { - template - T extractFromJson(const std::string &jsonData, const std::string &key, T defaultValue = 0) { - std::string::size_type pos = jsonData.find(key); - return pos != std::string::npos ? std::stol(jsonData.substr(pos + key.length())) : defaultValue; - } -} - -QString formatTime(long timeInSeconds) { - long minutes = timeInSeconds / 60; - long seconds = timeInSeconds % 60; - QString formattedTime = (minutes > 0) ? QString::number(minutes) + "m " : ""; - formattedTime += QString::number(seconds) + "s"; - return formattedTime; -} - -QString formatDateTime(const std::chrono::time_point &timePoint) { - return QDateTime::fromTime_t(std::chrono::system_clock::to_time_t(timePoint)).toString("h:mm ap"); -} - -QString calculateElapsedTime(int totalFiles, int downloadedFiles, const std::chrono::steady_clock::time_point &startTime) { - using namespace std::chrono; - if (totalFiles <= 0 || downloadedFiles >= totalFiles) return "Calculating..."; - - long elapsed = duration_cast(steady_clock::now() - startTime).count(); - return formatTime(elapsed); -} - -QString calculateETA(int totalFiles, int downloadedFiles, const std::chrono::steady_clock::time_point &startTime) { - using namespace std::chrono; - if (totalFiles <= 0 || downloadedFiles >= totalFiles) return "Calculating..."; - - long elapsed = duration_cast(steady_clock::now() - startTime).count(); - - if (downloadedFiles == 0 || elapsed <= 0) { - return "Calculating..."; - } - - double averageTimePerFile = static_cast(elapsed) / downloadedFiles; - int remainingFiles = totalFiles - downloadedFiles; - long estimatedTimeRemaining = static_cast(averageTimePerFile * remainingFiles); - - std::chrono::time_point estimatedCompletionTime = system_clock::now() + seconds(estimatedTimeRemaining); - QString estimatedTimeStr = formatDateTime(estimatedCompletionTime); - - return formatTime(estimatedTimeRemaining) + " (" + estimatedTimeStr + ")"; - -} - -QString formatDownloadStatus(int totalFiles, int downloadedFiles) { - if (totalFiles <= 0) return "Calculating..."; - if (downloadedFiles >= totalFiles) return "Downloaded"; - - int percentage = static_cast(100 * downloadedFiles / totalFiles); - return QString::asprintf("Downloading: %d/%d (%d%%)", downloadedFiles, totalFiles, percentage); -} - -quint64 calculateDirectorySize(const QString &path) { - quint64 totalSize = 0; - QDirIterator it(path, QDir::Files, QDirIterator::Subdirectories); - while (it.hasNext()) { - it.next(); - QFileInfo fileInfo(it.filePath()); - if (fileInfo.isFile()) { - totalSize += fileInfo.size(); - } - } - return totalSize; -} - -QString formatSize(qint64 size) { - const qint64 kb = 1024; - const qint64 mb = 1024 * kb; - const qint64 gb = 1024 * mb; - - if (size < gb) { - double sizeMB = size / static_cast(mb); - return QString::number(sizeMB, 'f', 2) + " MB"; - } else { - double sizeGB = size / static_cast(gb); - return QString::number(sizeGB, 'f', 2) + " GB"; - } -} diff --git a/selfdrive/frogpilot/navigation/ui/navigation_settings.cc b/selfdrive/frogpilot/navigation/ui/navigation_settings.cc deleted file mode 100644 index df04ead..0000000 --- a/selfdrive/frogpilot/navigation/ui/navigation_settings.cc +++ /dev/null @@ -1,574 +0,0 @@ -#include - -#include "selfdrive/frogpilot/navigation/ui/navigation_functions.h" -#include "selfdrive/frogpilot/navigation/ui/navigation_settings.h" - -FrogPilotNavigationPanel::FrogPilotNavigationPanel(QWidget *parent) : QFrame(parent), scene(uiState()->scene) { - mainLayout = new QStackedLayout(this); - - navigationWidget = new QWidget(); - QVBoxLayout *navigationLayout = new QVBoxLayout(navigationWidget); - navigationLayout->setMargin(40); - - FrogPilotListWidget *list = new FrogPilotListWidget(navigationWidget); - - Primeless *primelessPanel = new Primeless(this); - mainLayout->addWidget(primelessPanel); - - ButtonControl *manageNOOButton = new ButtonControl(tr("Manage Primeless Navigation Settings"), tr("MANAGE"), tr("Manage primeless navigate on openpilot settings.")); - QObject::connect(manageNOOButton, &ButtonControl::clicked, [=]() { mainLayout->setCurrentWidget(primelessPanel); }); - QObject::connect(primelessPanel, &Primeless::backPress, [=]() { mainLayout->setCurrentWidget(navigationWidget); }); - list->addItem(manageNOOButton); - manageNOOButton->setVisible(!uiState()->hasPrime()); - - std::vector scheduleOptions{tr("Manually"), tr("Weekly"), tr("Monthly")}; - ButtonParamControl *preferredSchedule = new ButtonParamControl("PreferredSchedule", tr("Maps Scheduler"), - tr("Choose the frequency for updating maps with the latest OpenStreetMap (OSM) changes. " - "Weekly updates begin at midnight every Sunday, while monthly updates start at midnight on the 1st of each month. " - "If your device is off or not connected to WiFi during a scheduled update, the download will be conducted the next " - "time you're offroad with a WiFi connection."), - "", - scheduleOptions); - schedule = params.getInt("PreferredSchedule"); - schedulePending = params.getBool("SchedulePending"); - list->addItem(preferredSchedule); - - list->addItem(offlineMapsSize = new LabelControl(tr("Offline Maps Size"), formatSize(calculateDirectorySize(offlineFolderPath)))); - offlineMapsSize->setVisible(true); - list->addItem(lastMapsDownload = new LabelControl(tr("Last Download"), "")); - lastMapsDownload->setVisible(!params.get("LastMapsUpdate").empty()); - lastMapsDownload->setText(QString::fromStdString(params.get("LastMapsUpdate"))); - list->addItem(offlineMapsStatus = new LabelControl(tr("Offline Maps Status"), "")); - offlineMapsStatus->setVisible(false); - list->addItem(offlineMapsETA = new LabelControl(tr("Offline Maps ETA"), "")); - offlineMapsETA->setVisible(false); - list->addItem(offlineMapsElapsed = new LabelControl(tr("Time Elapsed"), "")); - offlineMapsElapsed->setVisible(false); - - cancelDownloadButton = new ButtonControl(tr("Cancel Download"), tr("CANCEL"), tr("Cancel your current download.")); - QObject::connect(cancelDownloadButton, &ButtonControl::clicked, [this] { cancelDownload(this); }); - list->addItem(cancelDownloadButton); - cancelDownloadButton->setVisible(false); - - downloadOfflineMapsButton = new ButtonControl(tr("Download Offline Maps"), tr("DOWNLOAD"), tr("Download your selected offline maps to use with openpilot.")); - QObject::connect(downloadOfflineMapsButton, &ButtonControl::clicked, [this] { downloadMaps(); }); - list->addItem(downloadOfflineMapsButton); - downloadOfflineMapsButton->setVisible(!params.get("MapsSelected").empty()); - - SelectMaps *mapsPanel = new SelectMaps(this); - mainLayout->addWidget(mapsPanel); - - QObject::connect(mapsPanel, &SelectMaps::setMaps, [=]() { setMaps(); }); - - ButtonControl *selectMapsButton = new ButtonControl(tr("Select Offline Maps"), tr("SELECT"), tr("Select your maps to use with OSM.")); - QObject::connect(selectMapsButton, &ButtonControl::clicked, [=]() { mainLayout->setCurrentWidget(mapsPanel); }); - QObject::connect(mapsPanel, &SelectMaps::backPress, [=]() { mainLayout->setCurrentWidget(navigationWidget); }); - list->addItem(selectMapsButton); - - removeOfflineMapsButton = new ButtonControl(tr("Remove Offline Maps"), tr("REMOVE"), tr("Remove your downloaded offline maps to clear up storage space.")); - QObject::connect(removeOfflineMapsButton, &ButtonControl::clicked, [this] { removeMaps(this); }); - list->addItem(removeOfflineMapsButton); - removeOfflineMapsButton->setVisible(QDir(offlineFolderPath).exists()); - - navigationLayout->addWidget(new ScrollView(list, navigationWidget)); - navigationWidget->setLayout(navigationLayout); - mainLayout->addWidget(navigationWidget); - mainLayout->setCurrentWidget(navigationWidget); - - QObject::connect(uiState(), &UIState::uiUpdate, this, &FrogPilotNavigationPanel::updateState); - - checkIfUpdateMissed(); -} - -void FrogPilotNavigationPanel::hideEvent(QHideEvent *event) { - QWidget::hideEvent(event); - mainLayout->setCurrentWidget(navigationWidget); -} - -void FrogPilotNavigationPanel::updateState() { - if (!isVisible() && downloadActive) updateVisibility(downloadActive); - if (downloadActive) updateStatuses(); - if (schedule) downloadSchedule(); -} - -void FrogPilotNavigationPanel::updateStatuses() { - static std::chrono::steady_clock::time_point startTime = std::chrono::steady_clock::now(); - osmDownloadProgress = params.get("OSMDownloadProgress"); - - const int totalFiles = extractFromJson(osmDownloadProgress, "\"total_files\":"); - const int downloadedFiles = extractFromJson(osmDownloadProgress, "\"downloaded_files\":"); - - if (paramsMemory.get("OSMDownloadLocations").empty()) { - downloadActive = false; - updateDownloadedLabel(); - qint64 fileSize = calculateDirectorySize(offlineFolderPath); - offlineMapsSize->setText(formatSize(fileSize)); - previousOSMDownloadProgress = osmDownloadProgress; - } - - if (osmDownloadProgress != previousOSMDownloadProgress && isVisible()) { - qint64 fileSize = calculateDirectorySize(offlineFolderPath); - offlineMapsSize->setText(formatSize(fileSize)); - previousOSMDownloadProgress = osmDownloadProgress; - } - - elapsedTime = calculateElapsedTime(totalFiles, downloadedFiles, startTime); - - offlineMapsElapsed->setText(elapsedTime); - offlineMapsETA->setText(calculateETA(totalFiles, downloadedFiles, startTime)); - offlineMapsStatus->setText(formatDownloadStatus(totalFiles, downloadedFiles)); - - if (downloadActive != previousDownloadActive) { - startTime = !downloadActive ? std::chrono::steady_clock::now() : startTime; - updateVisibility(downloadActive); - previousDownloadActive = downloadActive; - } -} - -void FrogPilotNavigationPanel::updateVisibility(bool visibility) { - cancelDownloadButton->setVisible(visibility); - offlineMapsElapsed->setVisible(visibility); - offlineMapsETA->setVisible(visibility); - offlineMapsStatus->setVisible(visibility); - downloadOfflineMapsButton->setVisible(!visibility); - lastMapsDownload->setVisible(QDir(offlineFolderPath).exists() && !downloadActive); - removeOfflineMapsButton->setVisible(QDir(offlineFolderPath).exists() && !downloadActive); - update(); -} - -void FrogPilotNavigationPanel::checkIfUpdateMissed() { - std::string lastMapsUpdate = params.get("LastMapsUpdate"); - - if (lastMapsUpdate.empty() || schedule == 0) { - return; - } - - std::time_t currentTime = std::time(nullptr); - std::tm *now = std::localtime(¤tTime); - - std::tm lastUpdate = {}; - sscanf(lastMapsUpdate.c_str(), "%d-%d-%d", &lastUpdate.tm_year, &lastUpdate.tm_mon, &lastUpdate.tm_mday); - lastUpdate.tm_year -= 1900; - lastUpdate.tm_mon -= 1; - - std::time_t lastUpdateTime = std::mktime(&lastUpdate); - std::tm *lastUpdateDay = std::localtime(&lastUpdateTime); - - if (schedule == 1) { - schedulePending = (now->tm_wday == 0 && lastUpdateDay->tm_wday != 0) || (now->tm_wday > lastUpdateDay->tm_wday); - } else if (schedule == 2) { - schedulePending = (now->tm_mday == 1 && lastUpdate.tm_mday != 1) || (now->tm_mon != lastUpdate.tm_mon); - } -} - -void FrogPilotNavigationPanel::updateDownloadedLabel() { - std::time_t t = std::time(nullptr); - std::tm now = *std::localtime(&t); - char dateBuffer[11]; - std::strftime(dateBuffer, sizeof(dateBuffer), "%Y-%m-%d", &now); - QDate date = QDate::fromString(dateBuffer, "yyyy-MM-dd"); - - int day = date.day(); - std::string suffix = (day == 1 || day == 21 || day == 31) ? "st" : - (day == 2 || day == 22) ? "nd" : - (day == 3 || day == 23) ? "rd" : "th"; - std::string lastMapsUpdate = date.toString("MMMM d").toStdString() + suffix + date.toString(", yyyy").toStdString(); - lastMapsDownload->setText(QString::fromStdString(lastMapsUpdate)); - params.put("LastMapsUpdate", lastMapsUpdate); -} - -void FrogPilotNavigationPanel::downloadSchedule() { - const bool wifi = (*uiState()->sm)["deviceState"].getDeviceState().getNetworkType() == cereal::DeviceState::NetworkType::WIFI; - - const std::time_t t = std::time(nullptr); - const std::tm *now = std::localtime(&t); - - const bool isScheduleTime = (schedule == 1 && now->tm_wday == 0) || (schedule == 2 && now->tm_mday == 1); - - if ((isScheduleTime || schedulePending) && !(scene.started || scheduleCompleted) && wifi) { - downloadMaps(); - scheduleCompleted = true; - - if (schedulePending) { - schedulePending = false; - params.putBool("SchedulePending", false); - } - } else if (!isScheduleTime) { - scheduleCompleted = false; - } else { - if (!schedulePending) { - params.putBool("SchedulePending", true); - } - schedulePending = true; - } -} - -void FrogPilotNavigationPanel::cancelDownload(QWidget *parent) { - if (FrogPilotConfirmationDialog::yesorno("Are you sure you want to cancel the download?", parent)) { - std::thread([&] { - std::system("pkill mapd"); - }).detach(); - if (FrogPilotConfirmationDialog::toggle("Reboot required to re-enable map downloads", "Reboot Now", parent)) { - Hardware::soft_reboot(); - } - downloadActive = false; - updateVisibility(downloadActive); - downloadOfflineMapsButton->setVisible(downloadActive); - } -} - -void FrogPilotNavigationPanel::downloadMaps() { - params.remove("OSMDownloadProgress"); - paramsMemory.put("OSMDownloadLocations", params.get("MapsSelected")); - removeOfflineMapsButton->setVisible(true); - downloadActive = true; -} - -void FrogPilotNavigationPanel::removeMaps(QWidget *parent) { - if (FrogPilotConfirmationDialog::yesorno("Are you sure you want to delete all of your downloaded maps?", parent)) { - std::thread([&] { - lastMapsDownload->setVisible(false); - removeOfflineMapsButton->setVisible(false); - offlineMapsSize->setText(formatSize(0)); - params.remove("LastMapsUpdate"); - std::system("rm -rf /data/media/0/osm/offline"); - }).detach(); - } -} - -void FrogPilotNavigationPanel::setMaps() { - std::thread([&] { - QStringList states = ButtonSelectionControl::selectedStates.split(',', QString::SkipEmptyParts); - QStringList countries = ButtonSelectionControl::selectedCountries.split(',', QString::SkipEmptyParts); - - QJsonObject json; - json.insert("states", QJsonArray::fromStringList(states)); - json.insert("nations", QJsonArray::fromStringList(countries)); - - params.put("MapsSelected", QJsonDocument(json).toJson(QJsonDocument::Compact).toStdString()); - - if (!states.isEmpty() || !countries.isEmpty()) { - downloadOfflineMapsButton->setVisible(true); - update(); - } else { - params.remove("MapsSelected"); - } - }).detach(); -} - -SelectMaps::SelectMaps(QWidget *parent) : QWidget(parent) { - QVBoxLayout *mainLayout = new QVBoxLayout(this); - - QHBoxLayout *buttonsLayout = new QHBoxLayout(); - buttonsLayout->setContentsMargins(20, 40, 20, 0); - - backButton = new QPushButton(tr("Back"), this); - statesButton = new QPushButton(tr("States"), this); - countriesButton = new QPushButton(tr("Countries"), this); - - backButton->setFixedSize(400, 100); - statesButton->setFixedSize(400, 100); - countriesButton->setFixedSize(400, 100); - - buttonsLayout->addWidget(backButton); - buttonsLayout->addStretch(); - buttonsLayout->addWidget(statesButton); - buttonsLayout->addStretch(); - buttonsLayout->addWidget(countriesButton); - mainLayout->addLayout(buttonsLayout); - - mainLayout->addWidget(horizontalLine()); - mainLayout->setSpacing(20); - - mapsLayout = new QStackedLayout(); - mapsLayout->setMargin(40); - mapsLayout->setSpacing(20); - mainLayout->addLayout(mapsLayout); - - QObject::connect(backButton, &QPushButton::clicked, this, [this]() { emit backPress(), emit setMaps(); }); - - FrogPilotListWidget *statesList = new FrogPilotListWidget(); - - LabelControl *northeastLabel = new LabelControl(tr("United States - Northeast"), ""); - statesList->addItem(northeastLabel); - - ButtonSelectionControl *northeastControl = new ButtonSelectionControl("", tr(""), tr(""), northeastMap, false); - statesList->addItem(northeastControl); - - LabelControl *midwestLabel = new LabelControl(tr("United States - Midwest"), ""); - statesList->addItem(midwestLabel); - - ButtonSelectionControl *midwestControl = new ButtonSelectionControl("", tr(""), tr(""), midwestMap, false); - statesList->addItem(midwestControl); - - LabelControl *southLabel = new LabelControl(tr("United States - South"), ""); - statesList->addItem(southLabel); - - ButtonSelectionControl *southControl = new ButtonSelectionControl("", tr(""), tr(""), southMap, false); - statesList->addItem(southControl); - - LabelControl *westLabel = new LabelControl(tr("United States - West"), ""); - statesList->addItem(westLabel); - - ButtonSelectionControl *westControl = new ButtonSelectionControl("", tr(""), tr(""), westMap, false); - statesList->addItem(westControl); - - LabelControl *territoriesLabel = new LabelControl(tr("United States - Territories"), ""); - statesList->addItem(territoriesLabel); - - ButtonSelectionControl *territoriesControl = new ButtonSelectionControl("", tr(""), tr(""), territoriesMap, false); - statesList->addItem(territoriesControl); - - statesScrollView = new ScrollView(statesList); - mapsLayout->addWidget(statesScrollView); - - QObject::connect(statesButton, &QPushButton::clicked, this, [this]() { - mapsLayout->setCurrentWidget(statesScrollView); - statesButton->setStyleSheet(activeButtonStyle); - countriesButton->setStyleSheet(normalButtonStyle); - }); - - FrogPilotListWidget *countriesList = new FrogPilotListWidget(); - - LabelControl *africaLabel = new LabelControl(tr("Africa"), ""); - countriesList->addItem(africaLabel); - - ButtonSelectionControl *africaControl = new ButtonSelectionControl("", tr(""), tr(""), africaMap, true); - countriesList->addItem(africaControl); - - LabelControl *antarcticaLabel = new LabelControl(tr("Antarctica"), ""); - countriesList->addItem(antarcticaLabel); - - ButtonSelectionControl *antarcticaControl = new ButtonSelectionControl("", tr(""), tr(""), antarcticaMap, true); - countriesList->addItem(antarcticaControl); - - LabelControl *asiaLabel = new LabelControl(tr("Asia"), ""); - countriesList->addItem(asiaLabel); - - ButtonSelectionControl *asiaControl = new ButtonSelectionControl("", tr(""), tr(""), asiaMap, true); - countriesList->addItem(asiaControl); - - LabelControl *europeLabel = new LabelControl(tr("Europe"), ""); - countriesList->addItem(europeLabel); - - ButtonSelectionControl *europeControl = new ButtonSelectionControl("", tr(""), tr(""), europeMap, true); - countriesList->addItem(europeControl); - - LabelControl *northAmericaLabel = new LabelControl(tr("North America"), ""); - countriesList->addItem(northAmericaLabel); - - ButtonSelectionControl *northAmericaControl = new ButtonSelectionControl("", tr(""), tr(""), northAmericaMap, true); - countriesList->addItem(northAmericaControl); - - LabelControl *oceaniaLabel = new LabelControl(tr("Oceania"), ""); - countriesList->addItem(oceaniaLabel); - - ButtonSelectionControl *oceaniaControl = new ButtonSelectionControl("", tr(""), tr(""), oceaniaMap, true); - countriesList->addItem(oceaniaControl); - - LabelControl *southAmericaLabel = new LabelControl(tr("South America"), ""); - countriesList->addItem(southAmericaLabel); - - ButtonSelectionControl *southAmericaControl = new ButtonSelectionControl("", tr(""), tr(""), southAmericaMap, true); - countriesList->addItem(southAmericaControl); - - countriesScrollView = new ScrollView(countriesList); - mapsLayout->addWidget(countriesScrollView); - - QObject::connect(countriesButton, &QPushButton::clicked, this, [this]() { - mapsLayout->setCurrentWidget(countriesScrollView); - statesButton->setStyleSheet(normalButtonStyle); - countriesButton->setStyleSheet(activeButtonStyle); - }); - - mapsLayout->setCurrentWidget(statesScrollView); - statesButton->setStyleSheet(activeButtonStyle); - - setStyleSheet(R"( - QPushButton { - font-size: 50px; - margin: 0px; - padding: 15px; - border-width: 0; - border-radius: 30px; - color: #dddddd; - background-color: #393939; - } - QPushButton:pressed { - background-color: #4a4a4a; - } - )"); -} - -QString SelectMaps::activeButtonStyle = R"( - font-size: 50px; - margin: 0px; - padding: 15px; - border-width: 0; - border-radius: 30px; - color: #dddddd; - background-color: #33Ab4C; -)"; - -QString SelectMaps::normalButtonStyle = R"( - font-size: 50px; - margin: 0px; - padding: 15px; - border-width: 0; - border-radius: 30px; - color: #dddddd; - background-color: #393939; -)"; - -QFrame *SelectMaps::horizontalLine(QWidget *parent) const { - QFrame *line = new QFrame(parent); - - line->setFrameShape(QFrame::StyledPanel); - line->setStyleSheet(R"( - border-width: 2px; - border-bottom-style: solid; - border-color: gray; - )"); - line->setFixedHeight(2); - - return line; -} - -void SelectMaps::hideEvent(QHideEvent *event) { - QWidget::hideEvent(event); - emit setMaps(); -} - -Primeless::Primeless(QWidget *parent) : QWidget(parent) { - QStackedLayout *primelessLayout = new QStackedLayout(this); - - QWidget *mainWidget = new QWidget(); - mainLayout = new QVBoxLayout(mainWidget); - mainLayout->setMargin(40); - - backButton = new QPushButton(tr("Back"), this); - backButton->setObjectName("backButton"); - backButton->setFixedSize(400, 100); - QObject::connect(backButton, &QPushButton::clicked, this, [this]() { emit backPress(); }); - mainLayout->addWidget(backButton, 0, Qt::AlignLeft); - - list = new FrogPilotListWidget(mainWidget); - - wifi = new WifiManager(this); - ipLabel = new LabelControl(tr("Manage Your Settings At"), QString("%1:8082").arg(wifi->getIp4Address())); - list->addItem(ipLabel); - - std::vector searchOptions{tr("MapBox"), tr("Amap"), tr("Google")}; - ButtonParamControl *searchInput = new ButtonParamControl("SearchInput", tr("Destination Search Provider"), - tr("Select a search provider for destination queries in Navigate on Openpilot. Options include MapBox (recommended), Amap, and Google Maps."), - "", searchOptions); - list->addItem(searchInput); - - createMapboxKeyControl(publicMapboxKeyControl, tr("Public Mapbox Key"), "MapboxPublicKey", "pk."); - createMapboxKeyControl(secretMapboxKeyControl, tr("Secret Mapbox Key"), "MapboxSecretKey", "sk."); - - mapboxPublicKeySet = !params.get("MapboxPublicKey").empty(); - mapboxSecretKeySet = !params.get("MapboxSecretKey").empty(); - setupCompleted = mapboxPublicKeySet && mapboxSecretKeySet; - - QHBoxLayout *setupLayout = new QHBoxLayout(); - setupLayout->setMargin(0); - - imageLabel = new QLabel(this); - pixmap.load(currentStep); - imageLabel->setPixmap(pixmap.scaledToWidth(1500, Qt::SmoothTransformation)); - setupLayout->addWidget(imageLabel, 0, Qt::AlignCenter); - imageLabel->hide(); - - ButtonControl *setupButton = new ButtonControl(tr("Mapbox Setup Instructions"), tr("VIEW"), tr("View the instructions to set up MapBox for Primeless Navigation."), this); - QObject::connect(setupButton, &ButtonControl::clicked, this, [this]() { - updateStep(); - backButton->hide(); - list->setVisible(false); - imageLabel->show(); - }); - list->addItem(setupButton); - - QObject::connect(uiState(), &UIState::uiUpdate, this, &Primeless::updateState); - - mainLayout->addLayout(setupLayout); - mainLayout->addWidget(new ScrollView(list, mainWidget)); - mainWidget->setLayout(mainLayout); - primelessLayout->addWidget(mainWidget); - - setLayout(primelessLayout); - - setStyleSheet(R"( - QPushButton { - font-size: 50px; - margin: 0px; - padding: 15px; - border-width: 0; - border-radius: 30px; - color: #dddddd; - background-color: #393939; - } - QPushButton:pressed { - background-color: #4a4a4a; - } - )"); -} - -void Primeless::hideEvent(QHideEvent *event) { - QWidget::hideEvent(event); - backButton->show(); - list->setVisible(true); - imageLabel->hide(); -} - -void Primeless::mousePressEvent(QMouseEvent *event) { - backButton->show(); - list->setVisible(true); - imageLabel->hide(); -} - -void Primeless::updateState() { - if (!isVisible()) return; - - QString ipAddress = wifi->getIp4Address(); - ipLabel->setText(ipAddress.isEmpty() ? tr("Device Offline") : QString("%1:8082").arg(ipAddress)); - - mapboxPublicKeySet = !params.get("MapboxPublicKey").empty(); - mapboxSecretKeySet = !params.get("MapboxSecretKey").empty(); - setupCompleted = mapboxPublicKeySet && mapboxSecretKeySet && setupCompleted; - - publicMapboxKeyControl->setText(mapboxPublicKeySet ? tr("REMOVE") : tr("ADD")); - secretMapboxKeyControl->setText(mapboxSecretKeySet ? tr("REMOVE") : tr("ADD")); - - if (imageLabel->isVisible()) { - updateStep(); - } -} - -void Primeless::createMapboxKeyControl(ButtonControl *&control, const QString &label, const std::string ¶mKey, const QString &prefix) { - control = new ButtonControl(label, "", tr("Manage your %1."), this); - QObject::connect(control, &ButtonControl::clicked, this, [this, control, label, paramKey, prefix] { - if (control->text() == tr("ADD")) { - QString key = InputDialog::getText(tr("Enter your %1").arg(label), this); - if (!key.startsWith(prefix)) { - key = prefix + key; - } - if (key.length() >= 80) { - params.put(paramKey, key.toStdString()); - } - } else { - params.remove(paramKey); - } - }); - list->addItem(control); - control->setText(params.get(paramKey).empty() ? tr("ADD") : tr("REMOVE")); -} - -void Primeless::updateStep() { - currentStep = setupCompleted ? "../frogpilot/navigation/navigation_training/setup_completed.png" : - (mapboxPublicKeySet && mapboxSecretKeySet) ? "../frogpilot/navigation/navigation_training/both_keys_set.png" : - mapboxPublicKeySet ? "../frogpilot/navigation/navigation_training/public_key_set.png" : "../frogpilot/navigation/navigation_training/no_keys_set.png"; - - pixmap.load(currentStep); - imageLabel->setPixmap(pixmap.scaledToWidth(1500, Qt::SmoothTransformation)); -} diff --git a/selfdrive/frogpilot/navigation/ui/navigation_settings.h b/selfdrive/frogpilot/navigation/ui/navigation_settings.h deleted file mode 100644 index a27c292..0000000 --- a/selfdrive/frogpilot/navigation/ui/navigation_settings.h +++ /dev/null @@ -1,121 +0,0 @@ -#pragma once - -#include "selfdrive/frogpilot/ui/frogpilot_ui_functions.h" -#include "selfdrive/ui/qt/network/wifi_manager.h" -#include "selfdrive/ui/qt/offroad/settings.h" -#include "selfdrive/ui/qt/widgets/scrollview.h" -#include "selfdrive/ui/ui.h" - -class Primeless : public QWidget { - Q_OBJECT - -public: - explicit Primeless(QWidget *parent = nullptr); - -protected: - void mousePressEvent(QMouseEvent *event) override; - void hideEvent(QHideEvent *event) override; - -private: - void createMapboxKeyControl(ButtonControl *&control, const QString &label, const std::string ¶mKey, const QString &prefix); - void updateState(); - void updateStep(); - - QVBoxLayout *mainLayout; - FrogPilotListWidget *list; - - QPushButton *backButton; - QLabel *imageLabel; - - ButtonControl *publicMapboxKeyControl; - ButtonControl *secretMapboxKeyControl; - LabelControl *ipLabel; - - WifiManager *wifi; - - bool mapboxPublicKeySet; - bool mapboxSecretKeySet; - bool setupCompleted; - QPixmap pixmap; - QString currentStep = "../assets/images/setup_completed.png"; - - Params params; - -signals: - void backPress(); -}; - -class SelectMaps : public QWidget { - Q_OBJECT - -public: - explicit SelectMaps(QWidget *parent = nullptr); - - QFrame *horizontalLine(QWidget *parent = nullptr) const; - -private: - void hideEvent(QHideEvent *event); - - ScrollView *countriesScrollView; - ScrollView *statesScrollView; - QStackedLayout *mapsLayout; - - QPushButton *backButton; - QPushButton *statesButton; - QPushButton *countriesButton; - - static QString activeButtonStyle; - static QString normalButtonStyle; - -signals: - void backPress(); - void setMaps(); -}; - -class FrogPilotNavigationPanel : public QFrame { - Q_OBJECT - -public: - explicit FrogPilotNavigationPanel(QWidget *parent = 0); - -private: - void cancelDownload(QWidget *parent); - void checkIfUpdateMissed(); - void downloadMaps(); - void downloadSchedule(); - void hideEvent(QHideEvent *event); - void removeMaps(QWidget *parent); - void setMaps(); - void updateDownloadedLabel(); - void updateState(); - void updateStatuses(); - void updateVisibility(bool visibility); - - QStackedLayout *mainLayout; - QWidget *navigationWidget; - - ButtonControl *cancelDownloadButton; - ButtonControl *downloadOfflineMapsButton; - ButtonControl *redownloadOfflineMapsButton; - ButtonControl *removeOfflineMapsButton; - - LabelControl *lastMapsDownload; - LabelControl *offlineMapsSize; - LabelControl *offlineMapsStatus; - LabelControl *offlineMapsETA; - LabelControl *offlineMapsElapsed; - - bool downloadActive; - bool previousDownloadActive; - bool scheduleCompleted; - bool schedulePending; - int schedule; - QString elapsedTime; - QString offlineFolderPath = "/data/media/0/osm/offline"; - std::string osmDownloadProgress; - std::string previousOSMDownloadProgress; - - Params params; - Params paramsMemory{"/dev/shm/params"}; - UIScene &scene; -}; diff --git a/selfdrive/frogpilot/screenrecorder/blocking_queue.h b/selfdrive/frogpilot/screenrecorder/blocking_queue.h deleted file mode 100644 index 0bf9c2d..0000000 --- a/selfdrive/frogpilot/screenrecorder/blocking_queue.h +++ /dev/null @@ -1,89 +0,0 @@ -#pragma once -#include -#include -#include - -template -class BlockingQueue -{ -public: - std::deque content; - size_t capacity; - - std::mutex mutex; - std::condition_variable not_empty; - std::condition_variable not_full; - - BlockingQueue(const BlockingQueue &) = delete; - BlockingQueue(BlockingQueue &&) = delete; - BlockingQueue &operator = (const BlockingQueue &) = delete; - BlockingQueue &operator = (BlockingQueue &&) = delete; - - public: - BlockingQueue(size_t capacity): capacity(capacity) {} - - void clear() { - { - std::unique_lock lk(mutex); - content.clear(); - } - not_full.notify_one(); - } - - void push(T &&item) { - { - std::unique_lock lk(mutex); - not_full.wait(lk, [this]() { return content.size() < capacity; }); - content.push_back(std::move(item)); - } - not_empty.notify_one(); - } - - bool try_push(T &&item) { - { - std::unique_lock lk(mutex); - if (content.size() == capacity) - return false; - content.push_back(std::move(item)); - } - not_empty.notify_one(); - return true; - } - - void pop(T &item) { - { - std::unique_lock lk(mutex); - not_empty.wait(lk, [this]() { return !content.empty(); }); - item = std::move(content.front()); - content.pop_front(); - } - not_full.notify_one(); - } - - bool pop_wait_for(T &item, std::chrono::milliseconds duration) { - { - std::unique_lock lk(mutex); - if(not_empty.wait_for(lk, duration, [this]() { return !content.empty(); })) { - item = std::move(content.front()); - content.pop_front(); - } - else { - return false; - } - } - not_full.notify_one(); - return true; - } - - bool try_pop(T &item) { - { - std::unique_lock lk(mutex); - if (content.empty()) - return false; - item = std::move(content.front()); - content.pop_front(); - } - not_full.notify_one(); - return true; - } -}; diff --git a/selfdrive/frogpilot/screenrecorder/omx_encoder.cc b/selfdrive/frogpilot/screenrecorder/omx_encoder.cc deleted file mode 100644 index 332e541..0000000 --- a/selfdrive/frogpilot/screenrecorder/omx_encoder.cc +++ /dev/null @@ -1,697 +0,0 @@ -#pragma clang diagnostic ignored "-Wdeprecated-declarations" - -#include "selfdrive/frogpilot/screenrecorder/omx_encoder.h" - -#include -#include -#include - -#include -#include -#include - -#include -#include -#include -#include -#include "libyuv.h" -#include "msm_media_info.h" -#include "common/swaglog.h" -#include "common/util.h" - - -using namespace libyuv; - -LIBYUV_API -int ABGRToNV12(const uint8_t* src_abgr, - int src_stride_abgr, - uint8_t* dst_y, - int dst_stride_y, - uint8_t* dst_uv, - int dst_stride_uv, - int width, - int height) { - int y; - int halfwidth = (width + 1) >> 1; - void (*ABGRToUVRow)(const uint8_t* src_abgr0, int src_stride_abgr, - uint8_t* dst_u, uint8_t* dst_v, int width) = - ABGRToUVRow_C; - void (*ABGRToYRow)(const uint8_t* src_abgr, uint8_t* dst_y, int width) = - ABGRToYRow_C; - void (*MergeUVRow_)(const uint8_t* src_u, const uint8_t* src_v, uint8_t* dst_uv, int width) = MergeUVRow_C; - if (!src_abgr || !dst_y || !dst_uv || width <= 0 || height == 0) { - return -1; - } -if (height < 0) { // Negative height means invert the image. - height = -height; - src_abgr = src_abgr + (height - 1) * src_stride_abgr; - src_stride_abgr = -src_stride_abgr; -} -#if defined(HAS_ABGRTOYROW_SSSE3) && defined(HAS_ABGRTOUVROW_SSSE3) - if (TestCpuFlag(kCpuHasSSSE3)) { - ABGRToUVRow = ABGRToUVRow_Any_SSSE3; - ABGRToYRow = ABGRToYRow_Any_SSSE3; - if (IS_ALIGNED(width, 16)) { - ABGRToUVRow = ABGRToUVRow_SSSE3; - ABGRToYRow = ABGRToYRow_SSSE3; - } - } -#endif -#if defined(HAS_ABGRTOYROW_AVX2) && defined(HAS_ABGRTOUVROW_AVX2) - if (TestCpuFlag(kCpuHasAVX2)) { - ABGRToUVRow = ABGRToUVRow_Any_AVX2; - ABGRToYRow = ABGRToYRow_Any_AVX2; - if (IS_ALIGNED(width, 32)) { - ABGRToUVRow = ABGRToUVRow_AVX2; - ABGRToYRow = ABGRToYRow_AVX2; - } - } -#endif -#if defined(HAS_ABGRTOYROW_NEON) - if (TestCpuFlag(kCpuHasNEON)) { - ABGRToYRow = ABGRToYRow_Any_NEON; - if (IS_ALIGNED(width, 8)) { - ABGRToYRow = ABGRToYRow_NEON; - } - } -#endif -#if defined(HAS_ABGRTOUVROW_NEON) - if (TestCpuFlag(kCpuHasNEON)) { - ABGRToUVRow = ABGRToUVRow_Any_NEON; - if (IS_ALIGNED(width, 16)) { - ABGRToUVRow = ABGRToUVRow_NEON; - } - } -#endif -#if defined(HAS_ABGRTOYROW_MMI) && defined(HAS_ABGRTOUVROW_MMI) - if (TestCpuFlag(kCpuHasMMI)) { - ABGRToYRow = ABGRToYRow_Any_MMI; - ABGRToUVRow = ABGRToUVRow_Any_MMI; - if (IS_ALIGNED(width, 8)) { - ABGRToYRow = ABGRToYRow_MMI; - } - if (IS_ALIGNED(width, 16)) { - ABGRToUVRow = ABGRToUVRow_MMI; - } - } -#endif -#if defined(HAS_ABGRTOYROW_MSA) && defined(HAS_ABGRTOUVROW_MSA) - if (TestCpuFlag(kCpuHasMSA)) { - ABGRToYRow = ABGRToYRow_Any_MSA; - ABGRToUVRow = ABGRToUVRow_Any_MSA; - if (IS_ALIGNED(width, 16)) { - ABGRToYRow = ABGRToYRow_MSA; - } - if (IS_ALIGNED(width, 32)) { - ABGRToUVRow = ABGRToUVRow_MSA; - } - } -#endif -#if defined(HAS_MERGEUVROW_SSE2) - if (TestCpuFlag(kCpuHasSSE2)) { - MergeUVRow_ = MergeUVRow_Any_SSE2; - if (IS_ALIGNED(halfwidth, 16)) { - MergeUVRow_ = MergeUVRow_SSE2; - } - } -#endif -#if defined(HAS_MERGEUVROW_AVX2) - if (TestCpuFlag(kCpuHasAVX2)) { - MergeUVRow_ = MergeUVRow_Any_AVX2; - if (IS_ALIGNED(halfwidth, 32)) { - MergeUVRow_ = MergeUVRow_AVX2; - } - } -#endif -#if defined(HAS_MERGEUVROW_NEON) - if (TestCpuFlag(kCpuHasNEON)) { - MergeUVRow_ = MergeUVRow_Any_NEON; - if (IS_ALIGNED(halfwidth, 16)) { - MergeUVRow_ = MergeUVRow_NEON; - } - } -#endif -#if defined(HAS_MERGEUVROW_MMI) - if (TestCpuFlag(kCpuHasMMI)) { - MergeUVRow_ = MergeUVRow_Any_MMI; - if (IS_ALIGNED(halfwidth, 8)) { - MergeUVRow_ = MergeUVRow_MMI; - } - } -#endif -#if defined(HAS_MERGEUVROW_MSA) - if (TestCpuFlag(kCpuHasMSA)) { - MergeUVRow_ = MergeUVRow_Any_MSA; - if (IS_ALIGNED(halfwidth, 16)) { - MergeUVRow_ = MergeUVRow_MSA; - } - } -#endif - { - // Allocate a rows of uv. - align_buffer_64(row_u, ((halfwidth + 31) & ~31) * 2); - uint8_t* row_v = row_u + ((halfwidth + 31) & ~31); - - for (y = 0; y < height - 1; y += 2) { - ABGRToUVRow(src_abgr, src_stride_abgr, row_u, row_v, width); - MergeUVRow_(row_u, row_v, dst_uv, halfwidth); - ABGRToYRow(src_abgr, dst_y, width); - ABGRToYRow(src_abgr + src_stride_abgr, dst_y + dst_stride_y, width); - src_abgr += src_stride_abgr * 2; - dst_y += dst_stride_y * 2; - dst_uv += dst_stride_uv; - } - if (height & 1) { - ABGRToUVRow(src_abgr, 0, row_u, row_v, width); - MergeUVRow_(row_u, row_v, dst_uv, halfwidth); - ABGRToYRow(src_abgr, dst_y, width); - } - free_aligned_buffer_64(row_u); - } - return 0; -} - -// Check the OMX error code and assert if an error occurred. -#define OMX_CHECK(_expr) \ - do { \ - assert(OMX_ErrorNone == (_expr)); \ - } while (0) - -extern ExitHandler do_exit; - -// ***** OMX callback functions ***** - -void OmxEncoder::wait_for_state(OMX_STATETYPE state_) { - std::unique_lock lk(this->state_lock); - while (this->state != state_) { - this->state_cv.wait(lk); - } -} - -static OMX_CALLBACKTYPE omx_callbacks = { - .EventHandler = OmxEncoder::event_handler, - .EmptyBufferDone = OmxEncoder::empty_buffer_done, - .FillBufferDone = OmxEncoder::fill_buffer_done, -}; - -OMX_ERRORTYPE OmxEncoder::event_handler(OMX_HANDLETYPE component, OMX_PTR app_data, OMX_EVENTTYPE event, - OMX_U32 data1, OMX_U32 data2, OMX_PTR event_data) { - OmxEncoder *e = (OmxEncoder*)app_data; - if (event == OMX_EventCmdComplete) { - assert(data1 == OMX_CommandStateSet); - LOG("set state event 0x%x", data2); - { - std::unique_lock lk(e->state_lock); - e->state = (OMX_STATETYPE)data2; - } - e->state_cv.notify_all(); - } else if (event == OMX_EventError) { - LOGE("OMX error 0x%08x", data1); - } else { - LOGE("OMX unhandled event %d", event); - assert(false); - } - - return OMX_ErrorNone; -} - -OMX_ERRORTYPE OmxEncoder::empty_buffer_done(OMX_HANDLETYPE component, OMX_PTR app_data, - OMX_BUFFERHEADERTYPE *buffer) { - OmxEncoder *e = (OmxEncoder*)app_data; - e->free_in.push(buffer); - return OMX_ErrorNone; -} - -OMX_ERRORTYPE OmxEncoder::fill_buffer_done(OMX_HANDLETYPE component, OMX_PTR app_data, - OMX_BUFFERHEADERTYPE *buffer) { - OmxEncoder *e = (OmxEncoder*)app_data; - e->done_out.push(buffer); - return OMX_ErrorNone; -} - -#define PORT_INDEX_IN 0 -#define PORT_INDEX_OUT 1 - -static const char* omx_color_fomat_name(uint32_t format) __attribute__((unused)); -static const char* omx_color_fomat_name(uint32_t format) { - switch (format) { - case OMX_COLOR_FormatUnused: return "OMX_COLOR_FormatUnused"; - case OMX_COLOR_FormatMonochrome: return "OMX_COLOR_FormatMonochrome"; - case OMX_COLOR_Format8bitRGB332: return "OMX_COLOR_Format8bitRGB332"; - case OMX_COLOR_Format12bitRGB444: return "OMX_COLOR_Format12bitRGB444"; - case OMX_COLOR_Format16bitARGB4444: return "OMX_COLOR_Format16bitARGB4444"; - case OMX_COLOR_Format16bitARGB1555: return "OMX_COLOR_Format16bitARGB1555"; - case OMX_COLOR_Format16bitRGB565: return "OMX_COLOR_Format16bitRGB565"; - case OMX_COLOR_Format16bitBGR565: return "OMX_COLOR_Format16bitBGR565"; - case OMX_COLOR_Format18bitRGB666: return "OMX_COLOR_Format18bitRGB666"; - case OMX_COLOR_Format18bitARGB1665: return "OMX_COLOR_Format18bitARGB1665"; - case OMX_COLOR_Format19bitARGB1666: return "OMX_COLOR_Format19bitARGB1666"; - case OMX_COLOR_Format24bitRGB888: return "OMX_COLOR_Format24bitRGB888"; - case OMX_COLOR_Format24bitBGR888: return "OMX_COLOR_Format24bitBGR888"; - case OMX_COLOR_Format24bitARGB1887: return "OMX_COLOR_Format24bitARGB1887"; - case OMX_COLOR_Format25bitARGB1888: return "OMX_COLOR_Format25bitARGB1888"; - case OMX_COLOR_Format32bitBGRA8888: return "OMX_COLOR_Format32bitBGRA8888"; - case OMX_COLOR_Format32bitARGB8888: return "OMX_COLOR_Format32bitARGB8888"; - case OMX_COLOR_FormatYUV411Planar: return "OMX_COLOR_FormatYUV411Planar"; - case OMX_COLOR_FormatYUV411PackedPlanar: return "OMX_COLOR_FormatYUV411PackedPlanar"; - case OMX_COLOR_FormatYUV420Planar: return "OMX_COLOR_FormatYUV420Planar"; - case OMX_COLOR_FormatYUV420PackedPlanar: return "OMX_COLOR_FormatYUV420PackedPlanar"; - case OMX_COLOR_FormatYUV420SemiPlanar: return "OMX_COLOR_FormatYUV420SemiPlanar"; - case OMX_COLOR_FormatYUV422Planar: return "OMX_COLOR_FormatYUV422Planar"; - case OMX_COLOR_FormatYUV422PackedPlanar: return "OMX_COLOR_FormatYUV422PackedPlanar"; - case OMX_COLOR_FormatYUV422SemiPlanar: return "OMX_COLOR_FormatYUV422SemiPlanar"; - case OMX_COLOR_FormatYCbYCr: return "OMX_COLOR_FormatYCbYCr"; - case OMX_COLOR_FormatYCrYCb: return "OMX_COLOR_FormatYCrYCb"; - case OMX_COLOR_FormatCbYCrY: return "OMX_COLOR_FormatCbYCrY"; - case OMX_COLOR_FormatCrYCbY: return "OMX_COLOR_FormatCrYCbY"; - case OMX_COLOR_FormatYUV444Interleaved: return "OMX_COLOR_FormatYUV444Interleaved"; - case OMX_COLOR_FormatRawBayer8bit: return "OMX_COLOR_FormatRawBayer8bit"; - case OMX_COLOR_FormatRawBayer10bit: return "OMX_COLOR_FormatRawBayer10bit"; - case OMX_COLOR_FormatRawBayer8bitcompressed: return "OMX_COLOR_FormatRawBayer8bitcompressed"; - case OMX_COLOR_FormatL2: return "OMX_COLOR_FormatL2"; - case OMX_COLOR_FormatL4: return "OMX_COLOR_FormatL4"; - case OMX_COLOR_FormatL8: return "OMX_COLOR_FormatL8"; - case OMX_COLOR_FormatL16: return "OMX_COLOR_FormatL16"; - case OMX_COLOR_FormatL24: return "OMX_COLOR_FormatL24"; - case OMX_COLOR_FormatL32: return "OMX_COLOR_FormatL32"; - case OMX_COLOR_FormatYUV420PackedSemiPlanar: return "OMX_COLOR_FormatYUV420PackedSemiPlanar"; - case OMX_COLOR_FormatYUV422PackedSemiPlanar: return "OMX_COLOR_FormatYUV422PackedSemiPlanar"; - case OMX_COLOR_Format18BitBGR666: return "OMX_COLOR_Format18BitBGR666"; - case OMX_COLOR_Format24BitARGB6666: return "OMX_COLOR_Format24BitARGB6666"; - case OMX_COLOR_Format24BitABGR6666: return "OMX_COLOR_Format24BitABGR6666"; - - case OMX_COLOR_FormatAndroidOpaque: return "OMX_COLOR_FormatAndroidOpaque"; - case OMX_TI_COLOR_FormatYUV420PackedSemiPlanar: return "OMX_TI_COLOR_FormatYUV420PackedSemiPlanar"; - case OMX_QCOM_COLOR_FormatYVU420SemiPlanar: return "OMX_QCOM_COLOR_FormatYVU420SemiPlanar"; - case OMX_QCOM_COLOR_FormatYUV420PackedSemiPlanar64x32Tile2m8ka: return "OMX_QCOM_COLOR_FormatYUV420PackedSemiPlanar64x32Tile2m8ka"; - case OMX_SEC_COLOR_FormatNV12Tiled: return "OMX_SEC_COLOR_FormatNV12Tiled"; - case OMX_QCOM_COLOR_FormatYUV420PackedSemiPlanar32m: return "OMX_QCOM_COLOR_FormatYUV420PackedSemiPlanar32m"; - - case QOMX_COLOR_FormatYVU420PackedSemiPlanar32m4ka: return "QOMX_COLOR_FormatYVU420PackedSemiPlanar32m4ka"; - case QOMX_COLOR_FormatYUV420PackedSemiPlanar16m2ka: return "QOMX_COLOR_FormatYUV420PackedSemiPlanar16m2ka"; - case QOMX_COLOR_FORMATYUV420PackedSemiPlanar32mMultiView: return "QOMX_COLOR_FORMATYUV420PackedSemiPlanar32mMultiView"; - case QOMX_COLOR_FORMATYUV420PackedSemiPlanar32mCompressed: return "QOMX_COLOR_FORMATYUV420PackedSemiPlanar32mCompressed"; - case QOMX_COLOR_Format32bitRGBA8888: return "QOMX_COLOR_Format32bitRGBA8888"; - case QOMX_COLOR_Format32bitRGBA8888Compressed: return "QOMX_COLOR_Format32bitRGBA8888Compressed"; - - default: - return "unkn"; - } -} - - -// ***** encoder functions ***** - -OmxEncoder::OmxEncoder(const char* path, int width, int height, int fps, int bitrate, bool h265, bool downscale) { - this->path = path; - this->width = width; - this->height = height; - this->fps = fps; - this->remuxing = !h265; - - this->downscale = downscale; - if (this->downscale) { - this->y_ptr2 = (uint8_t *)malloc(this->width*this->height); - this->u_ptr2 = (uint8_t *)malloc(this->width*this->height/4); - this->v_ptr2 = (uint8_t *)malloc(this->width*this->height/4); - } - - auto component = (OMX_STRING)(h265 ? "OMX.qcom.video.encoder.hevc" : "OMX.qcom.video.encoder.avc"); - int err = OMX_GetHandle(&this->handle, component, this, &omx_callbacks); - if (err != OMX_ErrorNone) { - LOGE("error getting codec: %x", err); - } - - // setup input port - - OMX_PARAM_PORTDEFINITIONTYPE in_port = {0}; - in_port.nSize = sizeof(in_port); - in_port.nPortIndex = (OMX_U32) PORT_INDEX_IN; - OMX_CHECK(OMX_GetParameter(this->handle, OMX_IndexParamPortDefinition, (OMX_PTR) &in_port)); - - in_port.format.video.nFrameWidth = this->width; - in_port.format.video.nFrameHeight = this->height; - in_port.format.video.nStride = VENUS_Y_STRIDE(COLOR_FMT_NV12, this->width); - in_port.format.video.nSliceHeight = this->height; - in_port.nBufferSize = VENUS_BUFFER_SIZE(COLOR_FMT_NV12, this->width, this->height); - in_port.format.video.xFramerate = (this->fps * 65536); - in_port.format.video.eCompressionFormat = OMX_VIDEO_CodingUnused; - in_port.format.video.eColorFormat = (OMX_COLOR_FORMATTYPE)QOMX_COLOR_FORMATYUV420PackedSemiPlanar32m; - - OMX_CHECK(OMX_SetParameter(this->handle, OMX_IndexParamPortDefinition, (OMX_PTR) &in_port)); - OMX_CHECK(OMX_GetParameter(this->handle, OMX_IndexParamPortDefinition, (OMX_PTR) &in_port)); - this->in_buf_headers.resize(in_port.nBufferCountActual); - - // setup output port - - OMX_PARAM_PORTDEFINITIONTYPE out_port = {0}; - out_port.nSize = sizeof(out_port); - out_port.nPortIndex = (OMX_U32) PORT_INDEX_OUT; - OMX_CHECK(OMX_GetParameter(this->handle, OMX_IndexParamPortDefinition, (OMX_PTR)&out_port)); - out_port.format.video.nFrameWidth = this->width; - out_port.format.video.nFrameHeight = this->height; - out_port.format.video.xFramerate = 0; - out_port.format.video.nBitrate = bitrate; - if (h265) { - out_port.format.video.eCompressionFormat = OMX_VIDEO_CodingHEVC; - } else { - out_port.format.video.eCompressionFormat = OMX_VIDEO_CodingAVC; - } - out_port.format.video.eColorFormat = OMX_COLOR_FormatUnused; - - OMX_CHECK(OMX_SetParameter(this->handle, OMX_IndexParamPortDefinition, (OMX_PTR) &out_port)); - - OMX_CHECK(OMX_GetParameter(this->handle, OMX_IndexParamPortDefinition, (OMX_PTR) &out_port)); - this->out_buf_headers.resize(out_port.nBufferCountActual); - - OMX_VIDEO_PARAM_BITRATETYPE bitrate_type = {0}; - bitrate_type.nSize = sizeof(bitrate_type); - bitrate_type.nPortIndex = (OMX_U32) PORT_INDEX_OUT; - OMX_CHECK(OMX_GetParameter(this->handle, OMX_IndexParamVideoBitrate, (OMX_PTR) &bitrate_type)); - bitrate_type.eControlRate = OMX_Video_ControlRateVariable; - bitrate_type.nTargetBitrate = bitrate; - - OMX_CHECK(OMX_SetParameter(this->handle, OMX_IndexParamVideoBitrate, (OMX_PTR) &bitrate_type)); - - if (h265) { - // setup HEVC - #ifndef QCOM2 - OMX_VIDEO_PARAM_HEVCTYPE hevc_type = {0}; - OMX_INDEXTYPE index_type = (OMX_INDEXTYPE) OMX_IndexParamVideoHevc; - #else - OMX_VIDEO_PARAM_PROFILELEVELTYPE hevc_type = {0}; - OMX_INDEXTYPE index_type = OMX_IndexParamVideoProfileLevelCurrent; - #endif - hevc_type.nSize = sizeof(hevc_type); - hevc_type.nPortIndex = (OMX_U32) PORT_INDEX_OUT; - OMX_CHECK(OMX_GetParameter(this->handle, index_type, (OMX_PTR) &hevc_type)); - - hevc_type.eProfile = OMX_VIDEO_HEVCProfileMain; - hevc_type.eLevel = OMX_VIDEO_HEVCHighTierLevel5; - - OMX_CHECK(OMX_SetParameter(this->handle, index_type, (OMX_PTR) &hevc_type)); - } else { - // setup h264 - OMX_VIDEO_PARAM_AVCTYPE avc = { 0 }; - avc.nSize = sizeof(avc); - avc.nPortIndex = (OMX_U32) PORT_INDEX_OUT; - OMX_CHECK(OMX_GetParameter(this->handle, OMX_IndexParamVideoAvc, &avc)); - - avc.nBFrames = 0; - avc.nPFrames = 15; - - avc.eProfile = OMX_VIDEO_AVCProfileHigh; - avc.eLevel = OMX_VIDEO_AVCLevel31; - - avc.nAllowedPictureTypes |= OMX_VIDEO_PictureTypeB; - avc.eLoopFilterMode = OMX_VIDEO_AVCLoopFilterEnable; - - avc.nRefFrames = 1; - avc.bUseHadamard = OMX_TRUE; - avc.bEntropyCodingCABAC = OMX_TRUE; - avc.bWeightedPPrediction = OMX_TRUE; - avc.bconstIpred = OMX_TRUE; - - OMX_CHECK(OMX_SetParameter(this->handle, OMX_IndexParamVideoAvc, &avc)); - } - - OMX_CHECK(OMX_SendCommand(this->handle, OMX_CommandStateSet, OMX_StateIdle, NULL)); - - for (auto &buf : this->in_buf_headers) { - OMX_CHECK(OMX_AllocateBuffer(this->handle, &buf, PORT_INDEX_IN, this, - in_port.nBufferSize)); - } - - for (auto &buf : this->out_buf_headers) { - OMX_CHECK(OMX_AllocateBuffer(this->handle, &buf, PORT_INDEX_OUT, this, - out_port.nBufferSize)); - } - - wait_for_state(OMX_StateIdle); - - OMX_CHECK(OMX_SendCommand(this->handle, OMX_CommandStateSet, OMX_StateExecuting, NULL)); - - wait_for_state(OMX_StateExecuting); - - // give omx all the output buffers - for (auto &buf : this->out_buf_headers) { - OMX_CHECK(OMX_FillThisBuffer(this->handle, buf)); - } - - // fill the input free queue - for (auto &buf : this->in_buf_headers) { - this->free_in.push(buf); - } -} - -void OmxEncoder::handle_out_buf(OmxEncoder *e, OMX_BUFFERHEADERTYPE *out_buf) { - int err; - uint8_t *buf_data = out_buf->pBuffer + out_buf->nOffset; - - if (out_buf->nFlags & OMX_BUFFERFLAG_CODECCONFIG) { - if (e->codec_config_len < out_buf->nFilledLen) { - e->codec_config = (uint8_t *)realloc(e->codec_config, out_buf->nFilledLen); - } - e->codec_config_len = out_buf->nFilledLen; - memcpy(e->codec_config, buf_data, out_buf->nFilledLen); -#ifdef QCOM2 - out_buf->nTimeStamp = 0; -#endif - } - - if (e->of) { - fwrite(buf_data, out_buf->nFilledLen, 1, e->of); - } - - if (e->remuxing) { - if (!e->wrote_codec_config && e->codec_config_len > 0) { - // extradata will be freed by av_free() in avcodec_free_context() - e->codec_ctx->extradata = (uint8_t*)av_mallocz(e->codec_config_len + AV_INPUT_BUFFER_PADDING_SIZE); - e->codec_ctx->extradata_size = e->codec_config_len; - memcpy(e->codec_ctx->extradata, e->codec_config, e->codec_config_len); - - err = avcodec_parameters_from_context(e->out_stream->codecpar, e->codec_ctx); - assert(err >= 0); - err = avformat_write_header(e->ofmt_ctx, NULL); - assert(err >= 0); - - e->wrote_codec_config = true; - } - - if (out_buf->nTimeStamp > 0) { - // input timestamps are in microseconds - AVRational in_timebase = {1, 1000000}; - - AVPacket pkt; - av_init_packet(&pkt); - pkt.data = buf_data; - pkt.size = out_buf->nFilledLen; - - enum AVRounding rnd = static_cast(AV_ROUND_NEAR_INF|AV_ROUND_PASS_MINMAX); - pkt.pts = pkt.dts = av_rescale_q_rnd(out_buf->nTimeStamp, in_timebase, e->ofmt_ctx->streams[0]->time_base, rnd); - pkt.duration = av_rescale_q(50*1000, in_timebase, e->ofmt_ctx->streams[0]->time_base); - - if (out_buf->nFlags & OMX_BUFFERFLAG_SYNCFRAME) { - pkt.flags |= AV_PKT_FLAG_KEY; - } - - err = av_write_frame(e->ofmt_ctx, &pkt); - if (err < 0) { LOGW("ts encoder write issue"); } - - av_free_packet(&pkt); - } - } - - // give omx back the buffer -#ifdef QCOM2 - if (out_buf->nFlags & OMX_BUFFERFLAG_EOS) { - out_buf->nTimeStamp = 0; - } -#endif - OMX_CHECK(OMX_FillThisBuffer(e->handle, out_buf)); -} - -int OmxEncoder::encode_frame_rgba(const uint8_t *ptr, int in_width, int in_height, uint64_t ts) { - int err; - if (!this->is_open) { - return -1; - } - - // this sometimes freezes... put it outside the encoder lock so we can still trigger rotates... - // THIS IS A REALLY BAD IDEA, but apparently the race has to happen 30 times to trigger this - OMX_BUFFERHEADERTYPE* in_buf = nullptr; - while (!this->free_in.try_pop(in_buf, 20)) { - if (do_exit) { - return -1; - } - } - - int ret = this->counter; - - uint8_t *in_buf_ptr = in_buf->pBuffer; - - uint8_t *in_y_ptr = in_buf_ptr; - int in_y_stride = VENUS_Y_STRIDE(COLOR_FMT_NV12, this->width); - int in_uv_stride = VENUS_UV_STRIDE(COLOR_FMT_NV12, this->width); - uint8_t *in_uv_ptr = in_buf_ptr + (in_y_stride * VENUS_Y_SCANLINES(COLOR_FMT_NV12, this->height)); - - err = ABGRToNV12(ptr, this->width*4, - in_y_ptr, in_y_stride, - in_uv_ptr, in_uv_stride, - this->width, this->height); - assert(err == 0); - - in_buf->nFilledLen = VENUS_BUFFER_SIZE(COLOR_FMT_NV12, this->width, this->height); - in_buf->nFlags = OMX_BUFFERFLAG_ENDOFFRAME; - in_buf->nOffset = 0; - in_buf->nTimeStamp = ts/1000LL; // OMX_TICKS, in microseconds - this->last_t = in_buf->nTimeStamp; - - OMX_CHECK(OMX_EmptyThisBuffer(this->handle, in_buf)); - - // pump output - while (true) { - OMX_BUFFERHEADERTYPE *out_buf; - if (!this->done_out.try_pop(out_buf)) { - break; - } - handle_out_buf(this, out_buf); - } - - this->dirty = true; - - this->counter++; - - return ret; -} - -void OmxEncoder::encoder_open(const char* filename) { - int err; - - struct stat st = {0}; - if (stat(this->path.c_str(), &st) == -1) { - mkdir(this->path.c_str(), 0755); - } - - snprintf(this->vid_path, sizeof(this->vid_path), "%s/%s", this->path.c_str(), filename); - printf("encoder_open %s remuxing:%d\n", this->vid_path, this->remuxing); - - if (this->remuxing) { - avformat_alloc_output_context2(&this->ofmt_ctx, NULL, NULL, this->vid_path); - assert(this->ofmt_ctx); - - this->out_stream = avformat_new_stream(this->ofmt_ctx, NULL); - assert(this->out_stream); - - // set codec correctly - av_register_all(); - - AVCodec *codec = NULL; - codec = avcodec_find_encoder(AV_CODEC_ID_H264); - assert(codec); - - this->codec_ctx = avcodec_alloc_context3(codec); - assert(this->codec_ctx); - this->codec_ctx->width = this->width; - this->codec_ctx->height = this->height; - this->codec_ctx->pix_fmt = AV_PIX_FMT_YUV420P; - this->codec_ctx->time_base = (AVRational){ 1, this->fps }; - - err = avio_open(&this->ofmt_ctx->pb, this->vid_path, AVIO_FLAG_WRITE); - assert(err >= 0); - - this->wrote_codec_config = false; - } else { - this->of = fopen(this->vid_path, "wb"); - assert(this->of); -#ifndef QCOM2 - if (this->codec_config_len > 0) { - fwrite(this->codec_config, this->codec_config_len, 1, this->of); - } -#endif - } - - // create camera lock file - snprintf(this->lock_path, sizeof(this->lock_path), "%s/%s.lock", this->path.c_str(), filename); - int lock_fd = HANDLE_EINTR(open(this->lock_path, O_RDWR | O_CREAT, 0664)); - assert(lock_fd >= 0); - close(lock_fd); - - this->is_open = true; - this->counter = 0; -} - -void OmxEncoder::encoder_close() { - if (this->is_open) { - if (this->dirty) { - // drain output only if there could be frames in the encoder - - OMX_BUFFERHEADERTYPE* in_buf = this->free_in.pop(); - in_buf->nFilledLen = 0; - in_buf->nOffset = 0; - in_buf->nFlags = OMX_BUFFERFLAG_EOS; - in_buf->nTimeStamp = this->last_t + 1000000LL/this->fps; - - OMX_CHECK(OMX_EmptyThisBuffer(this->handle, in_buf)); - - while (true) { - OMX_BUFFERHEADERTYPE *out_buf = this->done_out.pop(); - - handle_out_buf(this, out_buf); - - if (out_buf->nFlags & OMX_BUFFERFLAG_EOS) { - break; - } - } - this->dirty = false; - } - - if (this->remuxing) { - av_write_trailer(this->ofmt_ctx); - avcodec_free_context(&this->codec_ctx); - avio_closep(&this->ofmt_ctx->pb); - avformat_free_context(this->ofmt_ctx); - } else { - fclose(this->of); - this->of = nullptr; - } - unlink(this->lock_path); - } - this->is_open = false; -} - -OmxEncoder::~OmxEncoder() { - assert(!this->is_open); - - OMX_CHECK(OMX_SendCommand(this->handle, OMX_CommandStateSet, OMX_StateIdle, NULL)); - - wait_for_state(OMX_StateIdle); - - OMX_CHECK(OMX_SendCommand(this->handle, OMX_CommandStateSet, OMX_StateLoaded, NULL)); - - for (auto &buf : this->in_buf_headers) { - OMX_CHECK(OMX_FreeBuffer(this->handle, PORT_INDEX_IN, buf)); - } - - for (auto &buf : this->out_buf_headers) { - OMX_CHECK(OMX_FreeBuffer(this->handle, PORT_INDEX_OUT, buf)); - } - - wait_for_state(OMX_StateLoaded); - - OMX_CHECK(OMX_FreeHandle(this->handle)); - - OMX_BUFFERHEADERTYPE *out_buf; - while (this->free_in.try_pop(out_buf)); - while (this->done_out.try_pop(out_buf)); - - if (this->codec_config) { - free(this->codec_config); - } - - if (this->downscale) { - free(this->y_ptr2); - free(this->u_ptr2); - free(this->v_ptr2); - } -} diff --git a/selfdrive/frogpilot/screenrecorder/omx_encoder.h b/selfdrive/frogpilot/screenrecorder/omx_encoder.h deleted file mode 100644 index 5cb630c..0000000 --- a/selfdrive/frogpilot/screenrecorder/omx_encoder.h +++ /dev/null @@ -1,72 +0,0 @@ -#pragma once - -#include -#include -#include -#include - -#include -extern "C" { -#include -} - -#include "common/queue.h" - -// OmxEncoder, lossey codec using hardware hevc -class OmxEncoder { -public: - OmxEncoder(const char* path, int width, int height, int fps, int bitrate, bool h265, bool downscale); - ~OmxEncoder(); - - int encode_frame_rgba(const uint8_t *ptr, int in_width, int in_height, uint64_t ts); - void encoder_open(const char* filename); - void encoder_close(); - - // OMX callbacks - static OMX_ERRORTYPE event_handler(OMX_HANDLETYPE component, OMX_PTR app_data, OMX_EVENTTYPE event, - OMX_U32 data1, OMX_U32 data2, OMX_PTR event_data); - static OMX_ERRORTYPE empty_buffer_done(OMX_HANDLETYPE component, OMX_PTR app_data, - OMX_BUFFERHEADERTYPE *buffer); - static OMX_ERRORTYPE fill_buffer_done(OMX_HANDLETYPE component, OMX_PTR app_data, - OMX_BUFFERHEADERTYPE *buffer); - -private: - void wait_for_state(OMX_STATETYPE state); - static void handle_out_buf(OmxEncoder *e, OMX_BUFFERHEADERTYPE *out_buf); - - int width, height, fps; - char vid_path[1024]; - char lock_path[1024]; - bool is_open = false; - bool dirty = false; - int counter = 0; - - std::string path; - FILE *of; - - size_t codec_config_len; - uint8_t *codec_config = NULL; - bool wrote_codec_config; - - std::mutex state_lock; - std::condition_variable state_cv; - OMX_STATETYPE state = OMX_StateLoaded; - - OMX_HANDLETYPE handle; - - std::vector in_buf_headers; - std::vector out_buf_headers; - - uint64_t last_t; - - SafeQueue free_in; - SafeQueue done_out; - - AVFormatContext *ofmt_ctx; - AVCodecContext *codec_ctx; - AVStream *out_stream; - bool remuxing; - - bool downscale; - uint8_t *y_ptr2, *u_ptr2, *v_ptr2; -}; diff --git a/selfdrive/frogpilot/screenrecorder/openmax/include/OMX_Audio.h b/selfdrive/frogpilot/screenrecorder/openmax/include/OMX_Audio.h deleted file mode 100644 index 0d45576..0000000 --- a/selfdrive/frogpilot/screenrecorder/openmax/include/OMX_Audio.h +++ /dev/null @@ -1,1312 +0,0 @@ -/* - * Copyright (c) 2008 The Khronos Group Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining - * a copy of this software and associated documentation files (the - * "Software"), to deal in the Software without restriction, including - * without limitation the rights to use, copy, modify, merge, publish, - * distribute, sublicense, and/or sell copies of the Software, and to - * permit persons to whom the Software is furnished to do so, subject - * to the following conditions: - * The above copyright notice and this permission notice shall be included - * in all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS - * OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. - * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY - * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, - * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE - * SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - * - */ - -/** @file OMX_Audio.h - OpenMax IL version 1.1.2 - * The structures needed by Audio components to exchange - * parameters and configuration data with the componenmilts. - */ - -#ifndef OMX_Audio_h -#define OMX_Audio_h - -#ifdef __cplusplus -extern "C" { -#endif /* __cplusplus */ - - -/* Each OMX header must include all required header files to allow the - * header to compile without errors. The includes below are required - * for this header file to compile successfully - */ - -#include - -/** @defgroup midi MIDI - * @ingroup audio - */ - -/** @defgroup effects Audio effects - * @ingroup audio - */ - -/** @defgroup audio OpenMAX IL Audio Domain - * Structures for OpenMAX IL Audio domain - * @{ - */ - -/** Enumeration used to define the possible audio codings. - * If "OMX_AUDIO_CodingUnused" is selected, the coding selection must - * be done in a vendor specific way. Since this is for an audio - * processing element this enum is relevant. However, for another - * type of component other enums would be in this area. - */ -typedef enum OMX_AUDIO_CODINGTYPE { - OMX_AUDIO_CodingUnused = 0, /**< Placeholder value when coding is N/A */ - OMX_AUDIO_CodingAutoDetect, /**< auto detection of audio format */ - OMX_AUDIO_CodingPCM, /**< Any variant of PCM coding */ - OMX_AUDIO_CodingADPCM, /**< Any variant of ADPCM encoded data */ - OMX_AUDIO_CodingAMR, /**< Any variant of AMR encoded data */ - OMX_AUDIO_CodingGSMFR, /**< Any variant of GSM fullrate (i.e. GSM610) */ - OMX_AUDIO_CodingGSMEFR, /**< Any variant of GSM Enhanced Fullrate encoded data*/ - OMX_AUDIO_CodingGSMHR, /**< Any variant of GSM Halfrate encoded data */ - OMX_AUDIO_CodingPDCFR, /**< Any variant of PDC Fullrate encoded data */ - OMX_AUDIO_CodingPDCEFR, /**< Any variant of PDC Enhanced Fullrate encoded data */ - OMX_AUDIO_CodingPDCHR, /**< Any variant of PDC Halfrate encoded data */ - OMX_AUDIO_CodingTDMAFR, /**< Any variant of TDMA Fullrate encoded data (TIA/EIA-136-420) */ - OMX_AUDIO_CodingTDMAEFR, /**< Any variant of TDMA Enhanced Fullrate encoded data (TIA/EIA-136-410) */ - OMX_AUDIO_CodingQCELP8, /**< Any variant of QCELP 8kbps encoded data */ - OMX_AUDIO_CodingQCELP13, /**< Any variant of QCELP 13kbps encoded data */ - OMX_AUDIO_CodingEVRC, /**< Any variant of EVRC encoded data */ - OMX_AUDIO_CodingSMV, /**< Any variant of SMV encoded data */ - OMX_AUDIO_CodingG711, /**< Any variant of G.711 encoded data */ - OMX_AUDIO_CodingG723, /**< Any variant of G.723 dot 1 encoded data */ - OMX_AUDIO_CodingG726, /**< Any variant of G.726 encoded data */ - OMX_AUDIO_CodingG729, /**< Any variant of G.729 encoded data */ - OMX_AUDIO_CodingAAC, /**< Any variant of AAC encoded data */ - OMX_AUDIO_CodingMP3, /**< Any variant of MP3 encoded data */ - OMX_AUDIO_CodingSBC, /**< Any variant of SBC encoded data */ - OMX_AUDIO_CodingVORBIS, /**< Any variant of VORBIS encoded data */ - OMX_AUDIO_CodingWMA, /**< Any variant of WMA encoded data */ - OMX_AUDIO_CodingRA, /**< Any variant of RA encoded data */ - OMX_AUDIO_CodingMIDI, /**< Any variant of MIDI encoded data */ - OMX_AUDIO_CodingAC3, /**< Any variant of AC3 encoded data */ - OMX_AUDIO_CodingKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_CodingVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_CodingMax = 0x7FFFFFFF -} OMX_AUDIO_CODINGTYPE; - - -/** The PortDefinition structure is used to define all of the parameters - * necessary for the compliant component to setup an input or an output audio - * path. If additional information is needed to define the parameters of the - * port (such as frequency), additional structures must be sent such as the - * OMX_AUDIO_PARAM_PCMMODETYPE structure to supply the extra parameters for the port. - */ -typedef struct OMX_AUDIO_PORTDEFINITIONTYPE { - OMX_STRING cMIMEType; /**< MIME type of data for the port */ - OMX_NATIVE_DEVICETYPE pNativeRender; /** < platform specific reference - for an output device, - otherwise this field is 0 */ - OMX_BOOL bFlagErrorConcealment; /**< Turns on error concealment if it is - supported by the OMX component */ - OMX_AUDIO_CODINGTYPE eEncoding; /**< Type of data expected for this - port (e.g. PCM, AMR, MP3, etc) */ -} OMX_AUDIO_PORTDEFINITIONTYPE; - - -/** Port format parameter. This structure is used to enumerate - * the various data input/output format supported by the port. - */ -typedef struct OMX_AUDIO_PARAM_PORTFORMATTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< Indicates which port to set */ - OMX_U32 nIndex; /**< Indicates the enumeration index for the format from 0x0 to N-1 */ - OMX_AUDIO_CODINGTYPE eEncoding; /**< Type of data expected for this port (e.g. PCM, AMR, MP3, etc) */ -} OMX_AUDIO_PARAM_PORTFORMATTYPE; - - -/** PCM mode type */ -typedef enum OMX_AUDIO_PCMMODETYPE { - OMX_AUDIO_PCMModeLinear = 0, /**< Linear PCM encoded data */ - OMX_AUDIO_PCMModeALaw, /**< A law PCM encoded data (G.711) */ - OMX_AUDIO_PCMModeMULaw, /**< Mu law PCM encoded data (G.711) */ - OMX_AUDIO_PCMModeKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_PCMModeVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_PCMModeMax = 0x7FFFFFFF -} OMX_AUDIO_PCMMODETYPE; - - -typedef enum OMX_AUDIO_CHANNELTYPE { - OMX_AUDIO_ChannelNone = 0x0, /**< Unused or empty */ - OMX_AUDIO_ChannelLF = 0x1, /**< Left front */ - OMX_AUDIO_ChannelRF = 0x2, /**< Right front */ - OMX_AUDIO_ChannelCF = 0x3, /**< Center front */ - OMX_AUDIO_ChannelLS = 0x4, /**< Left surround */ - OMX_AUDIO_ChannelRS = 0x5, /**< Right surround */ - OMX_AUDIO_ChannelLFE = 0x6, /**< Low frequency effects */ - OMX_AUDIO_ChannelCS = 0x7, /**< Back surround */ - OMX_AUDIO_ChannelLR = 0x8, /**< Left rear. */ - OMX_AUDIO_ChannelRR = 0x9, /**< Right rear. */ - OMX_AUDIO_ChannelKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_ChannelVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_ChannelMax = 0x7FFFFFFF -} OMX_AUDIO_CHANNELTYPE; - -#define OMX_AUDIO_MAXCHANNELS 16 /**< maximum number distinct audio channels that a buffer may contain */ -#define OMX_MIN_PCMPAYLOAD_MSEC 5 /**< Minimum audio buffer payload size for uncompressed (PCM) audio */ - -/** PCM format description */ -typedef struct OMX_AUDIO_PARAM_PCMMODETYPE { - OMX_U32 nSize; /**< Size of this structure, in Bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels (e.g. 2 for stereo) */ - OMX_NUMERICALDATATYPE eNumData; /**< indicates PCM data as signed or unsigned */ - OMX_ENDIANTYPE eEndian; /**< indicates PCM data as little or big endian */ - OMX_BOOL bInterleaved; /**< True for normal interleaved data; false for - non-interleaved data (e.g. block data) */ - OMX_U32 nBitPerSample; /**< Bit per sample */ - OMX_U32 nSamplingRate; /**< Sampling rate of the source data. Use 0 for - variable or unknown sampling rate. */ - OMX_AUDIO_PCMMODETYPE ePCMMode; /**< PCM mode enumeration */ - OMX_AUDIO_CHANNELTYPE eChannelMapping[OMX_AUDIO_MAXCHANNELS]; /**< Slot i contains channel defined by eChannelMap[i] */ - -} OMX_AUDIO_PARAM_PCMMODETYPE; - - -/** Audio channel mode. This is used by both AAC and MP3, although the names are more appropriate - * for the MP3. For example, JointStereo for MP3 is CouplingChannels for AAC. - */ -typedef enum OMX_AUDIO_CHANNELMODETYPE { - OMX_AUDIO_ChannelModeStereo = 0, /**< 2 channels, the bitrate allocation between those - two channels changes accordingly to each channel information */ - OMX_AUDIO_ChannelModeJointStereo, /**< mode that takes advantage of what is common between - 2 channels for higher compression gain */ - OMX_AUDIO_ChannelModeDual, /**< 2 mono-channels, each channel is encoded with half - the bitrate of the overall bitrate */ - OMX_AUDIO_ChannelModeMono, /**< Mono channel mode */ - OMX_AUDIO_ChannelModeKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_ChannelModeVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_ChannelModeMax = 0x7FFFFFFF -} OMX_AUDIO_CHANNELMODETYPE; - - -typedef enum OMX_AUDIO_MP3STREAMFORMATTYPE { - OMX_AUDIO_MP3StreamFormatMP1Layer3 = 0, /**< MP3 Audio MPEG 1 Layer 3 Stream format */ - OMX_AUDIO_MP3StreamFormatMP2Layer3, /**< MP3 Audio MPEG 2 Layer 3 Stream format */ - OMX_AUDIO_MP3StreamFormatMP2_5Layer3, /**< MP3 Audio MPEG2.5 Layer 3 Stream format */ - OMX_AUDIO_MP3StreamFormatKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_MP3StreamFormatVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_MP3StreamFormatMax = 0x7FFFFFFF -} OMX_AUDIO_MP3STREAMFORMATTYPE; - -/** MP3 params */ -typedef struct OMX_AUDIO_PARAM_MP3TYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels */ - OMX_U32 nBitRate; /**< Bit rate of the input data. Use 0 for variable - rate or unknown bit rates */ - OMX_U32 nSampleRate; /**< Sampling rate of the source data. Use 0 for - variable or unknown sampling rate. */ - OMX_U32 nAudioBandWidth; /**< Audio band width (in Hz) to which an encoder should - limit the audio signal. Use 0 to let encoder decide */ - OMX_AUDIO_CHANNELMODETYPE eChannelMode; /**< Channel mode enumeration */ - OMX_AUDIO_MP3STREAMFORMATTYPE eFormat; /**< MP3 stream format */ -} OMX_AUDIO_PARAM_MP3TYPE; - - -typedef enum OMX_AUDIO_AACSTREAMFORMATTYPE { - OMX_AUDIO_AACStreamFormatMP2ADTS = 0, /**< AAC Audio Data Transport Stream 2 format */ - OMX_AUDIO_AACStreamFormatMP4ADTS, /**< AAC Audio Data Transport Stream 4 format */ - OMX_AUDIO_AACStreamFormatMP4LOAS, /**< AAC Low Overhead Audio Stream format */ - OMX_AUDIO_AACStreamFormatMP4LATM, /**< AAC Low overhead Audio Transport Multiplex */ - OMX_AUDIO_AACStreamFormatADIF, /**< AAC Audio Data Interchange Format */ - OMX_AUDIO_AACStreamFormatMP4FF, /**< AAC inside MPEG-4/ISO File Format */ - OMX_AUDIO_AACStreamFormatRAW, /**< AAC Raw Format */ - OMX_AUDIO_AACStreamFormatKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_AACStreamFormatVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_AACStreamFormatMax = 0x7FFFFFFF -} OMX_AUDIO_AACSTREAMFORMATTYPE; - - -/** AAC mode type. Note that the term profile is used with the MPEG-2 - * standard and the term object type and profile is used with MPEG-4 */ -typedef enum OMX_AUDIO_AACPROFILETYPE{ - OMX_AUDIO_AACObjectNull = 0, /**< Null, not used */ - OMX_AUDIO_AACObjectMain = 1, /**< AAC Main object */ - OMX_AUDIO_AACObjectLC, /**< AAC Low Complexity object (AAC profile) */ - OMX_AUDIO_AACObjectSSR, /**< AAC Scalable Sample Rate object */ - OMX_AUDIO_AACObjectLTP, /**< AAC Long Term Prediction object */ - OMX_AUDIO_AACObjectHE, /**< AAC High Efficiency (object type SBR, HE-AAC profile) */ - OMX_AUDIO_AACObjectScalable, /**< AAC Scalable object */ - OMX_AUDIO_AACObjectERLC = 17, /**< ER AAC Low Complexity object (Error Resilient AAC-LC) */ - OMX_AUDIO_AACObjectLD = 23, /**< AAC Low Delay object (Error Resilient) */ - OMX_AUDIO_AACObjectHE_PS = 29, /**< AAC High Efficiency with Parametric Stereo coding (HE-AAC v2, object type PS) */ - OMX_AUDIO_AACObjectKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_AACObjectVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_AACObjectMax = 0x7FFFFFFF -} OMX_AUDIO_AACPROFILETYPE; - - -/** AAC tool usage (for nAACtools in OMX_AUDIO_PARAM_AACPROFILETYPE). - * Required for encoder configuration and optional as decoder info output. - * For MP3, OMX_AUDIO_CHANNELMODETYPE is sufficient. */ -#define OMX_AUDIO_AACToolNone 0x00000000 /**< no AAC tools allowed (encoder config) or active (decoder info output) */ -#define OMX_AUDIO_AACToolMS 0x00000001 /**< MS: Mid/side joint coding tool allowed or active */ -#define OMX_AUDIO_AACToolIS 0x00000002 /**< IS: Intensity stereo tool allowed or active */ -#define OMX_AUDIO_AACToolTNS 0x00000004 /**< TNS: Temporal Noise Shaping tool allowed or active */ -#define OMX_AUDIO_AACToolPNS 0x00000008 /**< PNS: MPEG-4 Perceptual Noise substitution tool allowed or active */ -#define OMX_AUDIO_AACToolLTP 0x00000010 /**< LTP: MPEG-4 Long Term Prediction tool allowed or active */ -#define OMX_AUDIO_AACToolAll 0x7FFFFFFF /**< all AAC tools allowed or active (*/ - -/** MPEG-4 AAC error resilience (ER) tool usage (for nAACERtools in OMX_AUDIO_PARAM_AACPROFILETYPE). - * Required for ER encoder configuration and optional as decoder info output */ -#define OMX_AUDIO_AACERNone 0x00000000 /**< no AAC ER tools allowed/used */ -#define OMX_AUDIO_AACERVCB11 0x00000001 /**< VCB11: Virtual Code Books for AAC section data */ -#define OMX_AUDIO_AACERRVLC 0x00000002 /**< RVLC: Reversible Variable Length Coding */ -#define OMX_AUDIO_AACERHCR 0x00000004 /**< HCR: Huffman Codeword Reordering */ -#define OMX_AUDIO_AACERAll 0x7FFFFFFF /**< all AAC ER tools allowed/used */ - - -/** AAC params */ -typedef struct OMX_AUDIO_PARAM_AACPROFILETYPE { - OMX_U32 nSize; /**< Size of this structure, in Bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< Port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels */ - OMX_U32 nSampleRate; /**< Sampling rate of the source data. Use 0 for - variable or unknown sampling rate. */ - OMX_U32 nBitRate; /**< Bit rate of the input data. Use 0 for variable - rate or unknown bit rates */ - OMX_U32 nAudioBandWidth; /**< Audio band width (in Hz) to which an encoder should - limit the audio signal. Use 0 to let encoder decide */ - OMX_U32 nFrameLength; /**< Frame length (in audio samples per channel) of the codec. - Can be 1024 or 960 (AAC-LC), 2048 (HE-AAC), 480 or 512 (AAC-LD). - Use 0 to let encoder decide */ - OMX_U32 nAACtools; /**< AAC tool usage */ - OMX_U32 nAACERtools; /**< MPEG-4 AAC error resilience tool usage */ - OMX_AUDIO_AACPROFILETYPE eAACProfile; /**< AAC profile enumeration */ - OMX_AUDIO_AACSTREAMFORMATTYPE eAACStreamFormat; /**< AAC stream format enumeration */ - OMX_AUDIO_CHANNELMODETYPE eChannelMode; /**< Channel mode enumeration */ -} OMX_AUDIO_PARAM_AACPROFILETYPE; - - -/** VORBIS params */ -typedef struct OMX_AUDIO_PARAM_VORBISTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels */ - OMX_U32 nBitRate; /**< Bit rate of the encoded data data. Use 0 for variable - rate or unknown bit rates. Encoding is set to the - bitrate closest to specified value (in bps) */ - OMX_U32 nMinBitRate; /**< Sets minimum bitrate (in bps). */ - OMX_U32 nMaxBitRate; /**< Sets maximum bitrate (in bps). */ - - OMX_U32 nSampleRate; /**< Sampling rate of the source data. Use 0 for - variable or unknown sampling rate. */ - OMX_U32 nAudioBandWidth; /**< Audio band width (in Hz) to which an encoder should - limit the audio signal. Use 0 to let encoder decide */ - OMX_S32 nQuality; /**< Sets encoding quality to n, between -1 (low) and 10 (high). - In the default mode of operation, teh quality level is 3. - Normal quality range is 0 - 10. */ - OMX_BOOL bManaged; /**< Set bitrate management mode. This turns off the - normal VBR encoding, but allows hard or soft bitrate - constraints to be enforced by the encoder. This mode can - be slower, and may also be lower quality. It is - primarily useful for streaming. */ - OMX_BOOL bDownmix; /**< Downmix input from stereo to mono (has no effect on - non-stereo streams). Useful for lower-bitrate encoding. */ -} OMX_AUDIO_PARAM_VORBISTYPE; - - -/** WMA Version */ -typedef enum OMX_AUDIO_WMAFORMATTYPE { - OMX_AUDIO_WMAFormatUnused = 0, /**< format unused or unknown */ - OMX_AUDIO_WMAFormat7, /**< Windows Media Audio format 7 */ - OMX_AUDIO_WMAFormat8, /**< Windows Media Audio format 8 */ - OMX_AUDIO_WMAFormat9, /**< Windows Media Audio format 9 */ - OMX_AUDIO_WMAFormatKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_WMAFormatVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_WMAFormatMax = 0x7FFFFFFF -} OMX_AUDIO_WMAFORMATTYPE; - - -/** WMA Profile */ -typedef enum OMX_AUDIO_WMAPROFILETYPE { - OMX_AUDIO_WMAProfileUnused = 0, /**< profile unused or unknown */ - OMX_AUDIO_WMAProfileL1, /**< Windows Media audio version 9 profile L1 */ - OMX_AUDIO_WMAProfileL2, /**< Windows Media audio version 9 profile L2 */ - OMX_AUDIO_WMAProfileL3, /**< Windows Media audio version 9 profile L3 */ - OMX_AUDIO_WMAProfileKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_WMAProfileVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_WMAProfileMax = 0x7FFFFFFF -} OMX_AUDIO_WMAPROFILETYPE; - - -/** WMA params */ -typedef struct OMX_AUDIO_PARAM_WMATYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U16 nChannels; /**< Number of channels */ - OMX_U32 nBitRate; /**< Bit rate of the input data. Use 0 for variable - rate or unknown bit rates */ - OMX_AUDIO_WMAFORMATTYPE eFormat; /**< Version of WMA stream / data */ - OMX_AUDIO_WMAPROFILETYPE eProfile; /**< Profile of WMA stream / data */ - OMX_U32 nSamplingRate; /**< Sampling rate of the source data */ - OMX_U16 nBlockAlign; /**< is the block alignment, or block size, in bytes of the audio codec */ - OMX_U16 nEncodeOptions; /**< WMA Type-specific data */ - OMX_U32 nSuperBlockAlign; /**< WMA Type-specific data */ -} OMX_AUDIO_PARAM_WMATYPE; - -/** - * RealAudio format - */ -typedef enum OMX_AUDIO_RAFORMATTYPE { - OMX_AUDIO_RAFormatUnused = 0, /**< Format unused or unknown */ - OMX_AUDIO_RA8, /**< RealAudio 8 codec */ - OMX_AUDIO_RA9, /**< RealAudio 9 codec */ - OMX_AUDIO_RA10_AAC, /**< MPEG-4 AAC codec for bitrates of more than 128kbps */ - OMX_AUDIO_RA10_CODEC, /**< RealAudio codec for bitrates less than 128 kbps */ - OMX_AUDIO_RA10_LOSSLESS, /**< RealAudio Lossless */ - OMX_AUDIO_RA10_MULTICHANNEL, /**< RealAudio Multichannel */ - OMX_AUDIO_RA10_VOICE, /**< RealAudio Voice for bitrates below 15 kbps */ - OMX_AUDIO_RAFormatKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_RAFormatVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_RAFormatMax = 0x7FFFFFFF -} OMX_AUDIO_RAFORMATTYPE; - -/** RA (Real Audio) params */ -typedef struct OMX_AUDIO_PARAM_RATYPE { - OMX_U32 nSize; /**< Size of this structure, in Bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< Port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels */ - OMX_U32 nSamplingRate; /**< is the sampling rate of the source data */ - OMX_U32 nBitsPerFrame; /**< is the value for bits per frame */ - OMX_U32 nSamplePerFrame; /**< is the value for samples per frame */ - OMX_U32 nCouplingQuantBits; /**< is the number of coupling quantization bits in the stream */ - OMX_U32 nCouplingStartRegion; /**< is the coupling start region in the stream */ - OMX_U32 nNumRegions; /**< is the number of regions value */ - OMX_AUDIO_RAFORMATTYPE eFormat; /**< is the RealAudio audio format */ -} OMX_AUDIO_PARAM_RATYPE; - - -/** SBC Allocation Method Type */ -typedef enum OMX_AUDIO_SBCALLOCMETHODTYPE { - OMX_AUDIO_SBCAllocMethodLoudness, /**< Loudness allocation method */ - OMX_AUDIO_SBCAllocMethodSNR, /**< SNR allocation method */ - OMX_AUDIO_SBCAllocMethodKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_SBCAllocMethodVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_SBCAllocMethodMax = 0x7FFFFFFF -} OMX_AUDIO_SBCALLOCMETHODTYPE; - - -/** SBC params */ -typedef struct OMX_AUDIO_PARAM_SBCTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels */ - OMX_U32 nBitRate; /**< Bit rate of the input data. Use 0 for variable - rate or unknown bit rates */ - OMX_U32 nSampleRate; /**< Sampling rate of the source data. Use 0 for - variable or unknown sampling rate. */ - OMX_U32 nBlocks; /**< Number of blocks */ - OMX_U32 nSubbands; /**< Number of subbands */ - OMX_U32 nBitPool; /**< Bitpool value */ - OMX_BOOL bEnableBitrate; /**< Use bitrate value instead of bitpool */ - OMX_AUDIO_CHANNELMODETYPE eChannelMode; /**< Channel mode enumeration */ - OMX_AUDIO_SBCALLOCMETHODTYPE eSBCAllocType; /**< SBC Allocation method type */ -} OMX_AUDIO_PARAM_SBCTYPE; - - -/** ADPCM stream format parameters */ -typedef struct OMX_AUDIO_PARAM_ADPCMTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels in the data stream (not - necessarily the same as the number of channels - to be rendered. */ - OMX_U32 nBitsPerSample; /**< Number of bits in each sample */ - OMX_U32 nSampleRate; /**< Sampling rate of the source data. Use 0 for - variable or unknown sampling rate. */ -} OMX_AUDIO_PARAM_ADPCMTYPE; - - -/** G723 rate */ -typedef enum OMX_AUDIO_G723RATE { - OMX_AUDIO_G723ModeUnused = 0, /**< AMRNB Mode unused / unknown */ - OMX_AUDIO_G723ModeLow, /**< 5300 bps */ - OMX_AUDIO_G723ModeHigh, /**< 6300 bps */ - OMX_AUDIO_G723ModeKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_G723ModeVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_G723ModeMax = 0x7FFFFFFF -} OMX_AUDIO_G723RATE; - - -/** G723 - Sample rate must be 8 KHz */ -typedef struct OMX_AUDIO_PARAM_G723TYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels in the data stream (not - necessarily the same as the number of channels - to be rendered. */ - OMX_BOOL bDTX; /**< Enable Discontinuous Transmisssion */ - OMX_AUDIO_G723RATE eBitRate; /**< todo: Should this be moved to a config? */ - OMX_BOOL bHiPassFilter; /**< Enable High Pass Filter */ - OMX_BOOL bPostFilter; /**< Enable Post Filter */ -} OMX_AUDIO_PARAM_G723TYPE; - - -/** ITU G726 (ADPCM) rate */ -typedef enum OMX_AUDIO_G726MODE { - OMX_AUDIO_G726ModeUnused = 0, /**< G726 Mode unused / unknown */ - OMX_AUDIO_G726Mode16, /**< 16 kbps */ - OMX_AUDIO_G726Mode24, /**< 24 kbps */ - OMX_AUDIO_G726Mode32, /**< 32 kbps, most common rate, also G721 */ - OMX_AUDIO_G726Mode40, /**< 40 kbps */ - OMX_AUDIO_G726ModeKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_G726ModeVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_G726ModeMax = 0x7FFFFFFF -} OMX_AUDIO_G726MODE; - - -/** G.726 stream format parameters - must be at 8KHz */ -typedef struct OMX_AUDIO_PARAM_G726TYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels in the data stream (not - necessarily the same as the number of channels - to be rendered. */ - OMX_AUDIO_G726MODE eG726Mode; -} OMX_AUDIO_PARAM_G726TYPE; - - -/** G729 coder type */ -typedef enum OMX_AUDIO_G729TYPE { - OMX_AUDIO_G729 = 0, /**< ITU G.729 encoded data */ - OMX_AUDIO_G729A, /**< ITU G.729 annex A encoded data */ - OMX_AUDIO_G729B, /**< ITU G.729 with annex B encoded data */ - OMX_AUDIO_G729AB, /**< ITU G.729 annexes A and B encoded data */ - OMX_AUDIO_G729KhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_G729VendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_G729Max = 0x7FFFFFFF -} OMX_AUDIO_G729TYPE; - - -/** G729 stream format parameters - fixed 6KHz sample rate */ -typedef struct OMX_AUDIO_PARAM_G729TYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels in the data stream (not - necessarily the same as the number of channels - to be rendered. */ - OMX_BOOL bDTX; /**< Enable Discontinuous Transmisssion */ - OMX_AUDIO_G729TYPE eBitType; -} OMX_AUDIO_PARAM_G729TYPE; - - -/** AMR Frame format */ -typedef enum OMX_AUDIO_AMRFRAMEFORMATTYPE { - OMX_AUDIO_AMRFrameFormatConformance = 0, /**< Frame Format is AMR Conformance - (Standard) Format */ - OMX_AUDIO_AMRFrameFormatIF1, /**< Frame Format is AMR Interface - Format 1 */ - OMX_AUDIO_AMRFrameFormatIF2, /**< Frame Format is AMR Interface - Format 2*/ - OMX_AUDIO_AMRFrameFormatFSF, /**< Frame Format is AMR File Storage - Format */ - OMX_AUDIO_AMRFrameFormatRTPPayload, /**< Frame Format is AMR Real-Time - Transport Protocol Payload Format */ - OMX_AUDIO_AMRFrameFormatITU, /**< Frame Format is ITU Format (added at Motorola request) */ - OMX_AUDIO_AMRFrameFormatKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_AMRFrameFormatVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_AMRFrameFormatMax = 0x7FFFFFFF -} OMX_AUDIO_AMRFRAMEFORMATTYPE; - - -/** AMR band mode */ -typedef enum OMX_AUDIO_AMRBANDMODETYPE { - OMX_AUDIO_AMRBandModeUnused = 0, /**< AMRNB Mode unused / unknown */ - OMX_AUDIO_AMRBandModeNB0, /**< AMRNB Mode 0 = 4750 bps */ - OMX_AUDIO_AMRBandModeNB1, /**< AMRNB Mode 1 = 5150 bps */ - OMX_AUDIO_AMRBandModeNB2, /**< AMRNB Mode 2 = 5900 bps */ - OMX_AUDIO_AMRBandModeNB3, /**< AMRNB Mode 3 = 6700 bps */ - OMX_AUDIO_AMRBandModeNB4, /**< AMRNB Mode 4 = 7400 bps */ - OMX_AUDIO_AMRBandModeNB5, /**< AMRNB Mode 5 = 7950 bps */ - OMX_AUDIO_AMRBandModeNB6, /**< AMRNB Mode 6 = 10200 bps */ - OMX_AUDIO_AMRBandModeNB7, /**< AMRNB Mode 7 = 12200 bps */ - OMX_AUDIO_AMRBandModeWB0, /**< AMRWB Mode 0 = 6600 bps */ - OMX_AUDIO_AMRBandModeWB1, /**< AMRWB Mode 1 = 8850 bps */ - OMX_AUDIO_AMRBandModeWB2, /**< AMRWB Mode 2 = 12650 bps */ - OMX_AUDIO_AMRBandModeWB3, /**< AMRWB Mode 3 = 14250 bps */ - OMX_AUDIO_AMRBandModeWB4, /**< AMRWB Mode 4 = 15850 bps */ - OMX_AUDIO_AMRBandModeWB5, /**< AMRWB Mode 5 = 18250 bps */ - OMX_AUDIO_AMRBandModeWB6, /**< AMRWB Mode 6 = 19850 bps */ - OMX_AUDIO_AMRBandModeWB7, /**< AMRWB Mode 7 = 23050 bps */ - OMX_AUDIO_AMRBandModeWB8, /**< AMRWB Mode 8 = 23850 bps */ - OMX_AUDIO_AMRBandModeKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_AMRBandModeVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_AMRBandModeMax = 0x7FFFFFFF -} OMX_AUDIO_AMRBANDMODETYPE; - - -/** AMR Discontinuous Transmission mode */ -typedef enum OMX_AUDIO_AMRDTXMODETYPE { - OMX_AUDIO_AMRDTXModeOff = 0, /**< AMR Discontinuous Transmission Mode is disabled */ - OMX_AUDIO_AMRDTXModeOnVAD1, /**< AMR Discontinuous Transmission Mode using - Voice Activity Detector 1 (VAD1) is enabled */ - OMX_AUDIO_AMRDTXModeOnVAD2, /**< AMR Discontinuous Transmission Mode using - Voice Activity Detector 2 (VAD2) is enabled */ - OMX_AUDIO_AMRDTXModeOnAuto, /**< The codec will automatically select between - Off, VAD1 or VAD2 modes */ - - OMX_AUDIO_AMRDTXasEFR, /**< DTX as EFR instead of AMR standard (3GPP 26.101, frame type =8,9,10) */ - - OMX_AUDIO_AMRDTXModeKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_AMRDTXModeVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_AMRDTXModeMax = 0x7FFFFFFF -} OMX_AUDIO_AMRDTXMODETYPE; - - -/** AMR params */ -typedef struct OMX_AUDIO_PARAM_AMRTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels */ - OMX_U32 nBitRate; /**< Bit rate read only field */ - OMX_AUDIO_AMRBANDMODETYPE eAMRBandMode; /**< AMR Band Mode enumeration */ - OMX_AUDIO_AMRDTXMODETYPE eAMRDTXMode; /**< AMR DTX Mode enumeration */ - OMX_AUDIO_AMRFRAMEFORMATTYPE eAMRFrameFormat; /**< AMR frame format enumeration */ -} OMX_AUDIO_PARAM_AMRTYPE; - - -/** GSM_FR (ETSI 06.10, 3GPP 46.010) stream format parameters */ -typedef struct OMX_AUDIO_PARAM_GSMFRTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_BOOL bDTX; /**< Enable Discontinuous Transmisssion */ - OMX_BOOL bHiPassFilter; /**< Enable High Pass Filter */ -} OMX_AUDIO_PARAM_GSMFRTYPE; - - -/** GSM-HR (ETSI 06.20, 3GPP 46.020) stream format parameters */ -typedef struct OMX_AUDIO_PARAM_GSMHRTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_BOOL bDTX; /**< Enable Discontinuous Transmisssion */ - OMX_BOOL bHiPassFilter; /**< Enable High Pass Filter */ -} OMX_AUDIO_PARAM_GSMHRTYPE; - - -/** GSM-EFR (ETSI 06.60, 3GPP 46.060) stream format parameters */ -typedef struct OMX_AUDIO_PARAM_GSMEFRTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_BOOL bDTX; /**< Enable Discontinuous Transmisssion */ - OMX_BOOL bHiPassFilter; /**< Enable High Pass Filter */ -} OMX_AUDIO_PARAM_GSMEFRTYPE; - - -/** TDMA FR (TIA/EIA-136-420, VSELP 7.95kbps coder) stream format parameters */ -typedef struct OMX_AUDIO_PARAM_TDMAFRTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels in the data stream (not - necessarily the same as the number of channels - to be rendered. */ - OMX_BOOL bDTX; /**< Enable Discontinuous Transmisssion */ - OMX_BOOL bHiPassFilter; /**< Enable High Pass Filter */ -} OMX_AUDIO_PARAM_TDMAFRTYPE; - - -/** TDMA EFR (TIA/EIA-136-410, ACELP 7.4kbps coder) stream format parameters */ -typedef struct OMX_AUDIO_PARAM_TDMAEFRTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels in the data stream (not - necessarily the same as the number of channels - to be rendered. */ - OMX_BOOL bDTX; /**< Enable Discontinuous Transmisssion */ - OMX_BOOL bHiPassFilter; /**< Enable High Pass Filter */ -} OMX_AUDIO_PARAM_TDMAEFRTYPE; - - -/** PDC FR ( RCR-27, VSELP 6.7kbps coder) stream format parameters */ -typedef struct OMX_AUDIO_PARAM_PDCFRTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels in the data stream (not - necessarily the same as the number of channels - to be rendered. */ - OMX_BOOL bDTX; /**< Enable Discontinuous Transmisssion */ - OMX_BOOL bHiPassFilter; /**< Enable High Pass Filter */ -} OMX_AUDIO_PARAM_PDCFRTYPE; - - -/** PDC EFR ( RCR-27, ACELP 6.7kbps coder) stream format parameters */ -typedef struct OMX_AUDIO_PARAM_PDCEFRTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels in the data stream (not - necessarily the same as the number of channels - to be rendered. */ - OMX_BOOL bDTX; /**< Enable Discontinuous Transmisssion */ - OMX_BOOL bHiPassFilter; /**< Enable High Pass Filter */ -} OMX_AUDIO_PARAM_PDCEFRTYPE; - -/** PDC HR ( RCR-27, PSI-CELP 3.45kbps coder) stream format parameters */ -typedef struct OMX_AUDIO_PARAM_PDCHRTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels in the data stream (not - necessarily the same as the number of channels - to be rendered. */ - OMX_BOOL bDTX; /**< Enable Discontinuous Transmisssion */ - OMX_BOOL bHiPassFilter; /**< Enable High Pass Filter */ -} OMX_AUDIO_PARAM_PDCHRTYPE; - - -/** CDMA Rate types */ -typedef enum OMX_AUDIO_CDMARATETYPE { - OMX_AUDIO_CDMARateBlank = 0, /**< CDMA encoded frame is blank */ - OMX_AUDIO_CDMARateFull, /**< CDMA encoded frame in full rate */ - OMX_AUDIO_CDMARateHalf, /**< CDMA encoded frame in half rate */ - OMX_AUDIO_CDMARateQuarter, /**< CDMA encoded frame in quarter rate */ - OMX_AUDIO_CDMARateEighth, /**< CDMA encoded frame in eighth rate (DTX)*/ - OMX_AUDIO_CDMARateErasure, /**< CDMA erasure frame */ - OMX_AUDIO_CDMARateKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_CDMARateVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_CDMARateMax = 0x7FFFFFFF -} OMX_AUDIO_CDMARATETYPE; - - -/** QCELP8 (TIA/EIA-96, up to 8kbps coder) stream format parameters */ -typedef struct OMX_AUDIO_PARAM_QCELP8TYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels in the data stream (not - necessarily the same as the number of channels - to be rendered. */ - OMX_U32 nBitRate; /**< Bit rate of the input data. Use 0 for variable - rate or unknown bit rates */ - OMX_AUDIO_CDMARATETYPE eCDMARate; /**< Frame rate */ - OMX_U32 nMinBitRate; /**< minmal rate for the encoder = 1,2,3,4, default = 1 */ - OMX_U32 nMaxBitRate; /**< maximal rate for the encoder = 1,2,3,4, default = 4 */ -} OMX_AUDIO_PARAM_QCELP8TYPE; - - -/** QCELP13 ( CDMA, EIA/TIA-733, 13.3kbps coder) stream format parameters */ -typedef struct OMX_AUDIO_PARAM_QCELP13TYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels in the data stream (not - necessarily the same as the number of channels - to be rendered. */ - OMX_AUDIO_CDMARATETYPE eCDMARate; /**< Frame rate */ - OMX_U32 nMinBitRate; /**< minmal rate for the encoder = 1,2,3,4, default = 1 */ - OMX_U32 nMaxBitRate; /**< maximal rate for the encoder = 1,2,3,4, default = 4 */ -} OMX_AUDIO_PARAM_QCELP13TYPE; - - -/** EVRC ( CDMA, EIA/TIA-127, RCELP up to 8.55kbps coder) stream format parameters */ -typedef struct OMX_AUDIO_PARAM_EVRCTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels in the data stream (not - necessarily the same as the number of channels - to be rendered. */ - OMX_AUDIO_CDMARATETYPE eCDMARate; /**< actual Frame rate */ - OMX_BOOL bRATE_REDUCon; /**< RATE_REDUCtion is requested for this frame */ - OMX_U32 nMinBitRate; /**< minmal rate for the encoder = 1,2,3,4, default = 1 */ - OMX_U32 nMaxBitRate; /**< maximal rate for the encoder = 1,2,3,4, default = 4 */ - OMX_BOOL bHiPassFilter; /**< Enable encoder's High Pass Filter */ - OMX_BOOL bNoiseSuppressor; /**< Enable encoder's noise suppressor pre-processing */ - OMX_BOOL bPostFilter; /**< Enable decoder's post Filter */ -} OMX_AUDIO_PARAM_EVRCTYPE; - - -/** SMV ( up to 8.55kbps coder) stream format parameters */ -typedef struct OMX_AUDIO_PARAM_SMVTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannels; /**< Number of channels in the data stream (not - necessarily the same as the number of channels - to be rendered. */ - OMX_AUDIO_CDMARATETYPE eCDMARate; /**< Frame rate */ - OMX_BOOL bRATE_REDUCon; /**< RATE_REDUCtion is requested for this frame */ - OMX_U32 nMinBitRate; /**< minmal rate for the encoder = 1,2,3,4, default = 1 ??*/ - OMX_U32 nMaxBitRate; /**< maximal rate for the encoder = 1,2,3,4, default = 4 ??*/ - OMX_BOOL bHiPassFilter; /**< Enable encoder's High Pass Filter ??*/ - OMX_BOOL bNoiseSuppressor; /**< Enable encoder's noise suppressor pre-processing */ - OMX_BOOL bPostFilter; /**< Enable decoder's post Filter ??*/ -} OMX_AUDIO_PARAM_SMVTYPE; - - -/** MIDI Format - * @ingroup midi - */ -typedef enum OMX_AUDIO_MIDIFORMATTYPE -{ - OMX_AUDIO_MIDIFormatUnknown = 0, /**< MIDI Format unknown or don't care */ - OMX_AUDIO_MIDIFormatSMF0, /**< Standard MIDI File Type 0 */ - OMX_AUDIO_MIDIFormatSMF1, /**< Standard MIDI File Type 1 */ - OMX_AUDIO_MIDIFormatSMF2, /**< Standard MIDI File Type 2 */ - OMX_AUDIO_MIDIFormatSPMIDI, /**< SP-MIDI */ - OMX_AUDIO_MIDIFormatXMF0, /**< eXtensible Music Format type 0 */ - OMX_AUDIO_MIDIFormatXMF1, /**< eXtensible Music Format type 1 */ - OMX_AUDIO_MIDIFormatMobileXMF, /**< Mobile XMF (eXtensible Music Format type 2) */ - OMX_AUDIO_MIDIFormatKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_MIDIFormatVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_MIDIFormatMax = 0x7FFFFFFF -} OMX_AUDIO_MIDIFORMATTYPE; - - -/** MIDI params - * @ingroup midi - */ -typedef struct OMX_AUDIO_PARAM_MIDITYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nFileSize; /**< size of the MIDI file in bytes, where the entire - MIDI file passed in, otherwise if 0x0, the MIDI data - is merged and streamed (instead of passed as an - entire MIDI file) */ - OMX_BU32 sMaxPolyphony; /**< Specifies the maximum simultaneous polyphonic - voices. A value of zero indicates that the default - polyphony of the device is used */ - OMX_BOOL bLoadDefaultSound; /**< Whether to load default sound - bank at initialization */ - OMX_AUDIO_MIDIFORMATTYPE eMidiFormat; /**< Version of the MIDI file */ -} OMX_AUDIO_PARAM_MIDITYPE; - - -/** Type of the MIDI sound bank - * @ingroup midi - */ -typedef enum OMX_AUDIO_MIDISOUNDBANKTYPE { - OMX_AUDIO_MIDISoundBankUnused = 0, /**< unused/unknown soundbank type */ - OMX_AUDIO_MIDISoundBankDLS1, /**< DLS version 1 */ - OMX_AUDIO_MIDISoundBankDLS2, /**< DLS version 2 */ - OMX_AUDIO_MIDISoundBankMobileDLSBase, /**< Mobile DLS, using the base functionality */ - OMX_AUDIO_MIDISoundBankMobileDLSPlusOptions, /**< Mobile DLS, using the specification-defined optional feature set */ - OMX_AUDIO_MIDISoundBankKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_MIDISoundBankVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_MIDISoundBankMax = 0x7FFFFFFF -} OMX_AUDIO_MIDISOUNDBANKTYPE; - - -/** Bank Layout describes how bank MSB & LSB are used in the DLS instrument definitions sound bank - * @ingroup midi - */ -typedef enum OMX_AUDIO_MIDISOUNDBANKLAYOUTTYPE { - OMX_AUDIO_MIDISoundBankLayoutUnused = 0, /**< unused/unknown soundbank type */ - OMX_AUDIO_MIDISoundBankLayoutGM, /**< GS layout (based on bank MSB 0x00) */ - OMX_AUDIO_MIDISoundBankLayoutGM2, /**< General MIDI 2 layout (using MSB 0x78/0x79, LSB 0x00) */ - OMX_AUDIO_MIDISoundBankLayoutUser, /**< Does not conform to any bank numbering standards */ - OMX_AUDIO_MIDISoundBankLayoutKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_MIDISoundBankLayoutVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_MIDISoundBankLayoutMax = 0x7FFFFFFF -} OMX_AUDIO_MIDISOUNDBANKLAYOUTTYPE; - - -/** MIDI params to load/unload user soundbank - * @ingroup midi - */ -typedef struct OMX_AUDIO_PARAM_MIDILOADUSERSOUNDTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nDLSIndex; /**< DLS file index to be loaded */ - OMX_U32 nDLSSize; /**< Size in bytes */ - OMX_PTR pDLSData; /**< Pointer to DLS file data */ - OMX_AUDIO_MIDISOUNDBANKTYPE eMidiSoundBank; /**< Midi sound bank type enumeration */ - OMX_AUDIO_MIDISOUNDBANKLAYOUTTYPE eMidiSoundBankLayout; /**< Midi sound bank layout enumeration */ -} OMX_AUDIO_PARAM_MIDILOADUSERSOUNDTYPE; - - -/** Structure for Live MIDI events and MIP messages. - * (MIP = Maximum Instantaneous Polyphony; part of the SP-MIDI standard.) - * @ingroup midi - */ -typedef struct OMX_AUDIO_CONFIG_MIDIIMMEDIATEEVENTTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< Port that this structure applies to */ - OMX_U32 nMidiEventSize; /**< Size of immediate MIDI events or MIP message in bytes */ - OMX_U8 nMidiEvents[1]; /**< MIDI event array to be rendered immediately, or an - array for the MIP message buffer, where the size is - indicated by nMidiEventSize */ -} OMX_AUDIO_CONFIG_MIDIIMMEDIATEEVENTTYPE; - - -/** MIDI sound bank/ program pair in a given channel - * @ingroup midi - */ -typedef struct OMX_AUDIO_CONFIG_MIDISOUNDBANKPROGRAMTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< Port that this structure applies to */ - OMX_U32 nChannel; /**< Valid channel values range from 1 to 16 */ - OMX_U16 nIDProgram; /**< Valid program ID range is 1 to 128 */ - OMX_U16 nIDSoundBank; /**< Sound bank ID */ - OMX_U32 nUserSoundBankIndex;/**< User soundbank index, easier to access soundbanks - by index if multiple banks are present */ -} OMX_AUDIO_CONFIG_MIDISOUNDBANKPROGRAMTYPE; - - -/** MIDI control - * @ingroup midi - */ -typedef struct OMX_AUDIO_CONFIG_MIDICONTROLTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_BS32 sPitchTransposition; /**< Pitch transposition in semitones, stored as Q22.10 - format based on JAVA MMAPI (JSR-135) requirement */ - OMX_BU32 sPlayBackRate; /**< Relative playback rate, stored as Q14.17 fixed-point - number based on JSR-135 requirement */ - OMX_BU32 sTempo ; /**< Tempo in beats per minute (BPM), stored as Q22.10 - fixed-point number based on JSR-135 requirement */ - OMX_U32 nMaxPolyphony; /**< Specifies the maximum simultaneous polyphonic - voices. A value of zero indicates that the default - polyphony of the device is used */ - OMX_U32 nNumRepeat; /**< Number of times to repeat playback */ - OMX_U32 nStopTime; /**< Time in milliseconds to indicate when playback - will stop automatically. Set to zero if not used */ - OMX_U16 nChannelMuteMask; /**< 16 bit mask for channel mute status */ - OMX_U16 nChannelSoloMask; /**< 16 bit mask for channel solo status */ - OMX_U32 nTrack0031MuteMask; /**< 32 bit mask for track mute status. Note: This is for tracks 0-31 */ - OMX_U32 nTrack3263MuteMask; /**< 32 bit mask for track mute status. Note: This is for tracks 32-63 */ - OMX_U32 nTrack0031SoloMask; /**< 32 bit mask for track solo status. Note: This is for tracks 0-31 */ - OMX_U32 nTrack3263SoloMask; /**< 32 bit mask for track solo status. Note: This is for tracks 32-63 */ - -} OMX_AUDIO_CONFIG_MIDICONTROLTYPE; - - -/** MIDI Playback States - * @ingroup midi - */ -typedef enum OMX_AUDIO_MIDIPLAYBACKSTATETYPE { - OMX_AUDIO_MIDIPlayBackStateUnknown = 0, /**< Unknown state or state does not map to - other defined states */ - OMX_AUDIO_MIDIPlayBackStateClosedEngaged, /**< No MIDI resource is currently open. - The MIDI engine is currently processing - MIDI events. */ - OMX_AUDIO_MIDIPlayBackStateParsing, /**< A MIDI resource is open and is being - primed. The MIDI engine is currently - processing MIDI events. */ - OMX_AUDIO_MIDIPlayBackStateOpenEngaged, /**< A MIDI resource is open and primed but - not playing. The MIDI engine is currently - processing MIDI events. The transition to - this state is only possible from the - OMX_AUDIO_MIDIPlayBackStatePlaying state, - when the 'playback head' reaches the end - of media data or the playback stops due - to stop time set.*/ - OMX_AUDIO_MIDIPlayBackStatePlaying, /**< A MIDI resource is open and currently - playing. The MIDI engine is currently - processing MIDI events.*/ - OMX_AUDIO_MIDIPlayBackStatePlayingPartially, /**< Best-effort playback due to SP-MIDI/DLS - resource constraints */ - OMX_AUDIO_MIDIPlayBackStatePlayingSilently, /**< Due to system resource constraints and - SP-MIDI content constraints, there is - no audible MIDI content during playback - currently. The situation may change if - resources are freed later.*/ - OMX_AUDIO_MIDIPlayBackStateKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_MIDIPlayBackStateVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_MIDIPlayBackStateMax = 0x7FFFFFFF -} OMX_AUDIO_MIDIPLAYBACKSTATETYPE; - - -/** MIDI status - * @ingroup midi - */ -typedef struct OMX_AUDIO_CONFIG_MIDISTATUSTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U16 nNumTracks; /**< Number of MIDI tracks in the file, read only field. - NOTE: May not return a meaningful value until the entire - file is parsed and buffered. */ - OMX_U32 nDuration; /**< The length of the currently open MIDI resource - in milliseconds. NOTE: May not return a meaningful value - until the entire file is parsed and buffered. */ - OMX_U32 nPosition; /**< Current Position of the MIDI resource being played - in milliseconds */ - OMX_BOOL bVibra; /**< Does Vibra track exist? NOTE: May not return a meaningful - value until the entire file is parsed and buffered. */ - OMX_U32 nNumMetaEvents; /**< Total number of MIDI Meta Events in the currently - open MIDI resource. NOTE: May not return a meaningful value - until the entire file is parsed and buffered. */ - OMX_U32 nNumActiveVoices; /**< Number of active voices in the currently playing - MIDI resource. NOTE: May not return a meaningful value until - the entire file is parsed and buffered. */ - OMX_AUDIO_MIDIPLAYBACKSTATETYPE eMIDIPlayBackState; /**< MIDI playback state enumeration, read only field */ -} OMX_AUDIO_CONFIG_MIDISTATUSTYPE; - - -/** MIDI Meta Event structure one per Meta Event. - * MIDI Meta Events are like audio metadata, except that they are interspersed - * with the MIDI content throughout the file and are not localized in the header. - * As such, it is necessary to retrieve information about these Meta Events from - * the engine, as it encounters these Meta Events within the MIDI content. - * For example, SMF files can have up to 14 types of MIDI Meta Events (copyright, - * author, default tempo, etc.) scattered throughout the file. - * @ingroup midi - */ -typedef struct OMX_AUDIO_CONFIG_MIDIMETAEVENTTYPE{ - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nIndex; /**< Index of Meta Event */ - OMX_U8 nMetaEventType; /**< Meta Event Type, 7bits (i.e. 0 - 127) */ - OMX_U32 nMetaEventSize; /**< size of the Meta Event in bytes */ - OMX_U32 nTrack; /**< track number for the meta event */ - OMX_U32 nPosition; /**< Position of the meta-event in milliseconds */ -} OMX_AUDIO_CONFIG_MIDIMETAEVENTTYPE; - - -/** MIDI Meta Event Data structure - one per Meta Event. - * @ingroup midi - */ -typedef struct OMX_AUDIO_CONFIG_MIDIMETAEVENTDATATYPE{ - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nIndex; /**< Index of Meta Event */ - OMX_U32 nMetaEventSize; /**< size of the Meta Event in bytes */ - OMX_U8 nData[1]; /**< array of one or more bytes of meta data - as indicated by the nMetaEventSize field */ -} OMX_AUDIO_CONFIG__MIDIMETAEVENTDATATYPE; - - -/** Audio Volume adjustment for a port */ -typedef struct OMX_AUDIO_CONFIG_VOLUMETYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< Port index indicating which port to - set. Select the input port to set - just that port's volume. Select the - output port to adjust the master - volume. */ - OMX_BOOL bLinear; /**< Is the volume to be set in linear (0.100) - or logarithmic scale (mB) */ - OMX_BS32 sVolume; /**< Volume linear setting in the 0..100 range, OR - Volume logarithmic setting for this port. The values - for volume are in mB (millibels = 1/100 dB) relative - to a gain of 1 (e.g. the output is the same as the - input level). Values are in mB from nMax - (maximum volume) to nMin mB (typically negative). - Since the volume is "voltage" - and not a "power", it takes a setting of - -600 mB to decrease the volume by 1/2. If - a component cannot accurately set the - volume to the requested value, it must - set the volume to the closest value BELOW - the requested value. When getting the - volume setting, the current actual volume - must be returned. */ -} OMX_AUDIO_CONFIG_VOLUMETYPE; - - -/** Audio Volume adjustment for a channel */ -typedef struct OMX_AUDIO_CONFIG_CHANNELVOLUMETYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< Port index indicating which port to - set. Select the input port to set - just that port's volume. Select the - output port to adjust the master - volume. */ - OMX_U32 nChannel; /**< channel to select from 0 to N-1, - using OMX_ALL to apply volume settings - to all channels */ - OMX_BOOL bLinear; /**< Is the volume to be set in linear (0.100) or - logarithmic scale (mB) */ - OMX_BS32 sVolume; /**< Volume linear setting in the 0..100 range, OR - Volume logarithmic setting for this port. - The values for volume are in mB - (millibels = 1/100 dB) relative to a gain - of 1 (e.g. the output is the same as the - input level). Values are in mB from nMax - (maximum volume) to nMin mB (typically negative). - Since the volume is "voltage" - and not a "power", it takes a setting of - -600 mB to decrease the volume by 1/2. If - a component cannot accurately set the - volume to the requested value, it must - set the volume to the closest value BELOW - the requested value. When getting the - volume setting, the current actual volume - must be returned. */ - OMX_BOOL bIsMIDI; /**< TRUE if nChannel refers to a MIDI channel, - FALSE otherwise */ -} OMX_AUDIO_CONFIG_CHANNELVOLUMETYPE; - - -/** Audio balance setting */ -typedef struct OMX_AUDIO_CONFIG_BALANCETYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< Port index indicating which port to - set. Select the input port to set - just that port's balance. Select the - output port to adjust the master - balance. */ - OMX_S32 nBalance; /**< balance setting for this port - (-100 to 100, where -100 indicates - all left, and no right */ -} OMX_AUDIO_CONFIG_BALANCETYPE; - - -/** Audio Port mute */ -typedef struct OMX_AUDIO_CONFIG_MUTETYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< Port index indicating which port to - set. Select the input port to set - just that port's mute. Select the - output port to adjust the master - mute. */ - OMX_BOOL bMute; /**< Mute setting for this port */ -} OMX_AUDIO_CONFIG_MUTETYPE; - - -/** Audio Channel mute */ -typedef struct OMX_AUDIO_CONFIG_CHANNELMUTETYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nChannel; /**< channel to select from 0 to N-1, - using OMX_ALL to apply mute settings - to all channels */ - OMX_BOOL bMute; /**< Mute setting for this channel */ - OMX_BOOL bIsMIDI; /**< TRUE if nChannel refers to a MIDI channel, - FALSE otherwise */ -} OMX_AUDIO_CONFIG_CHANNELMUTETYPE; - - - -/** Enable / Disable for loudness control, which boosts bass and to a - * smaller extent high end frequencies to compensate for hearing - * ability at the extreme ends of the audio spectrum - */ -typedef struct OMX_AUDIO_CONFIG_LOUDNESSTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_BOOL bLoudness; /**< Enable/disable for loudness */ -} OMX_AUDIO_CONFIG_LOUDNESSTYPE; - - -/** Enable / Disable for bass, which controls low frequencies - */ -typedef struct OMX_AUDIO_CONFIG_BASSTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_BOOL bEnable; /**< Enable/disable for bass control */ - OMX_S32 nBass; /**< bass setting for the port, as a - continuous value from -100 to 100 - (0 means no change in bass level)*/ -} OMX_AUDIO_CONFIG_BASSTYPE; - - -/** Enable / Disable for treble, which controls high frequencies tones - */ -typedef struct OMX_AUDIO_CONFIG_TREBLETYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_BOOL bEnable; /**< Enable/disable for treble control */ - OMX_S32 nTreble; /**< treble setting for the port, as a - continuous value from -100 to 100 - (0 means no change in treble level) */ -} OMX_AUDIO_CONFIG_TREBLETYPE; - - -/** An equalizer is typically used for two reasons: to compensate for an - * sub-optimal frequency response of a system to make it sound more natural - * or to create intentionally some unnatural coloring to the sound to create - * an effect. - * @ingroup effects - */ -typedef struct OMX_AUDIO_CONFIG_EQUALIZERTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_BOOL bEnable; /**< Enable/disable for equalizer */ - OMX_BU32 sBandIndex; /**< Band number to be set. Upper Limit is - N-1, where N is the number of bands, lower limit is 0 */ - OMX_BU32 sCenterFreq; /**< Center frequecies in Hz. This is a - read only element and is used to determine - the lower, center and upper frequency of - this band. */ - OMX_BS32 sBandLevel; /**< band level in millibels */ -} OMX_AUDIO_CONFIG_EQUALIZERTYPE; - - -/** Stereo widening mode type - * @ingroup effects - */ -typedef enum OMX_AUDIO_STEREOWIDENINGTYPE { - OMX_AUDIO_StereoWideningHeadphones, /**< Stereo widening for loudspeakers */ - OMX_AUDIO_StereoWideningLoudspeakers, /**< Stereo widening for closely spaced loudspeakers */ - OMX_AUDIO_StereoWideningKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_StereoWideningVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_StereoWideningMax = 0x7FFFFFFF -} OMX_AUDIO_STEREOWIDENINGTYPE; - - -/** Control for stereo widening, which is a special 2-channel - * case of the audio virtualizer effect. For example, for 5.1-channel - * output, it translates to virtual surround sound. - * @ingroup effects - */ -typedef struct OMX_AUDIO_CONFIG_STEREOWIDENINGTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_BOOL bEnable; /**< Enable/disable for stereo widening control */ - OMX_AUDIO_STEREOWIDENINGTYPE eWideningType; /**< Stereo widening algorithm type */ - OMX_U32 nStereoWidening; /**< stereo widening setting for the port, - as a continuous value from 0 to 100 */ -} OMX_AUDIO_CONFIG_STEREOWIDENINGTYPE; - - -/** The chorus effect (or ``choralizer'') is any signal processor which makes - * one sound source (such as a voice) sound like many such sources singing - * (or playing) in unison. Since performance in unison is never exact, chorus - * effects simulate this by making independently modified copies of the input - * signal. Modifications may include (1) delay, (2) frequency shift, and - * (3) amplitude modulation. - * @ingroup effects - */ -typedef struct OMX_AUDIO_CONFIG_CHORUSTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_BOOL bEnable; /**< Enable/disable for chorus */ - OMX_BU32 sDelay; /**< average delay in milliseconds */ - OMX_BU32 sModulationRate; /**< rate of modulation in millihertz */ - OMX_U32 nModulationDepth; /**< depth of modulation as a percentage of - delay (i.e. 0 to 100) */ - OMX_BU32 nFeedback; /**< Feedback from chorus output to input in percentage */ -} OMX_AUDIO_CONFIG_CHORUSTYPE; - - -/** Reverberation is part of the reflected sound that follows the early - * reflections. In a typical room, this consists of a dense succession of - * echoes whose energy decays exponentially. The reverberation effect structure - * as defined here includes both (early) reflections as well as (late) reverberations. - * @ingroup effects - */ -typedef struct OMX_AUDIO_CONFIG_REVERBERATIONTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_BOOL bEnable; /**< Enable/disable for reverberation control */ - OMX_BS32 sRoomLevel; /**< Intensity level for the whole room effect - (i.e. both early reflections and late - reverberation) in millibels */ - OMX_BS32 sRoomHighFreqLevel; /**< Attenuation at high frequencies - relative to the intensity at low - frequencies in millibels */ - OMX_BS32 sReflectionsLevel; /**< Intensity level of early reflections - (relative to room value), in millibels */ - OMX_BU32 sReflectionsDelay; /**< Delay time of the first reflection relative - to the direct path, in milliseconds */ - OMX_BS32 sReverbLevel; /**< Intensity level of late reverberation - relative to room level, in millibels */ - OMX_BU32 sReverbDelay; /**< Time delay from the first early reflection - to the beginning of the late reverberation - section, in milliseconds */ - OMX_BU32 sDecayTime; /**< Late reverberation decay time at low - frequencies, in milliseconds */ - OMX_BU32 nDecayHighFreqRatio; /**< Ratio of high frequency decay time relative - to low frequency decay time in percent */ - OMX_U32 nDensity; /**< Modal density in the late reverberation decay, - in percent (i.e. 0 - 100) */ - OMX_U32 nDiffusion; /**< Echo density in the late reverberation decay, - in percent (i.e. 0 - 100) */ - OMX_BU32 sReferenceHighFreq; /**< Reference high frequency in Hertz. This is - the frequency used as the reference for all - the high-frequency settings above */ - -} OMX_AUDIO_CONFIG_REVERBERATIONTYPE; - - -/** Possible settings for the Echo Cancelation structure to use - * @ingroup effects - */ -typedef enum OMX_AUDIO_ECHOCANTYPE { - OMX_AUDIO_EchoCanOff = 0, /**< Echo Cancellation is disabled */ - OMX_AUDIO_EchoCanNormal, /**< Echo Cancellation normal operation - - echo from plastics and face */ - OMX_AUDIO_EchoCanHFree, /**< Echo Cancellation optimized for - Hands Free operation */ - OMX_AUDIO_EchoCanCarKit, /**< Echo Cancellation optimized for - Car Kit (longer echo) */ - OMX_AUDIO_EchoCanKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_AUDIO_EchoCanVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_AUDIO_EchoCanMax = 0x7FFFFFFF -} OMX_AUDIO_ECHOCANTYPE; - - -/** Enable / Disable for echo cancelation, which removes undesired echo's - * from the audio - * @ingroup effects - */ -typedef struct OMX_AUDIO_CONFIG_ECHOCANCELATIONTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_AUDIO_ECHOCANTYPE eEchoCancelation; /**< Echo cancelation settings */ -} OMX_AUDIO_CONFIG_ECHOCANCELATIONTYPE; - - -/** Enable / Disable for noise reduction, which undesired noise from - * the audio - * @ingroup effects - */ -typedef struct OMX_AUDIO_CONFIG_NOISEREDUCTIONTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_BOOL bNoiseReduction; /**< Enable/disable for noise reduction */ -} OMX_AUDIO_CONFIG_NOISEREDUCTIONTYPE; - -/** @} */ - -#ifdef __cplusplus -} -#endif /* __cplusplus */ - -#endif -/* File EOF */ - diff --git a/selfdrive/frogpilot/screenrecorder/openmax/include/OMX_Component.h b/selfdrive/frogpilot/screenrecorder/openmax/include/OMX_Component.h deleted file mode 100644 index d595640..0000000 --- a/selfdrive/frogpilot/screenrecorder/openmax/include/OMX_Component.h +++ /dev/null @@ -1,579 +0,0 @@ -/* - * Copyright (c) 2008 The Khronos Group Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining - * a copy of this software and associated documentation files (the - * "Software"), to deal in the Software without restriction, including - * without limitation the rights to use, copy, modify, merge, publish, - * distribute, sublicense, and/or sell copies of the Software, and to - * permit persons to whom the Software is furnished to do so, subject - * to the following conditions: - * The above copyright notice and this permission notice shall be included - * in all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS - * OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. - * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY - * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, - * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE - * SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - * - */ - -/** OMX_Component.h - OpenMax IL version 1.1.2 - * The OMX_Component header file contains the definitions used to define - * the public interface of a component. This header file is intended to - * be used by both the application and the component. - */ - -#ifndef OMX_Component_h -#define OMX_Component_h - -#ifdef __cplusplus -extern "C" { -#endif /* __cplusplus */ - - - -/* Each OMX header must include all required header files to allow the - * header to compile without errors. The includes below are required - * for this header file to compile successfully - */ - -#include -#include -#include -#include - -/** @ingroup comp */ -typedef enum OMX_PORTDOMAINTYPE { - OMX_PortDomainAudio, - OMX_PortDomainVideo, - OMX_PortDomainImage, - OMX_PortDomainOther, - OMX_PortDomainKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_PortDomainVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_PortDomainMax = 0x7ffffff -} OMX_PORTDOMAINTYPE; - -/** @ingroup comp */ -typedef struct OMX_PARAM_PORTDEFINITIONTYPE { - OMX_U32 nSize; /**< Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< Port number the structure applies to */ - OMX_DIRTYPE eDir; /**< Direction (input or output) of this port */ - OMX_U32 nBufferCountActual; /**< The actual number of buffers allocated on this port */ - OMX_U32 nBufferCountMin; /**< The minimum number of buffers this port requires */ - OMX_U32 nBufferSize; /**< Size, in bytes, for buffers to be used for this channel */ - OMX_BOOL bEnabled; /**< Ports default to enabled and are enabled/disabled by - OMX_CommandPortEnable/OMX_CommandPortDisable. - When disabled a port is unpopulated. A disabled port - is not populated with buffers on a transition to IDLE. */ - OMX_BOOL bPopulated; /**< Port is populated with all of its buffers as indicated by - nBufferCountActual. A disabled port is always unpopulated. - An enabled port is populated on a transition to OMX_StateIdle - and unpopulated on a transition to loaded. */ - OMX_PORTDOMAINTYPE eDomain; /**< Domain of the port. Determines the contents of metadata below. */ - union { - OMX_AUDIO_PORTDEFINITIONTYPE audio; - OMX_VIDEO_PORTDEFINITIONTYPE video; - OMX_IMAGE_PORTDEFINITIONTYPE image; - OMX_OTHER_PORTDEFINITIONTYPE other; - } format; - OMX_BOOL bBuffersContiguous; - OMX_U32 nBufferAlignment; -} OMX_PARAM_PORTDEFINITIONTYPE; - -/** @ingroup comp */ -typedef struct OMX_PARAM_U32TYPE { - OMX_U32 nSize; /**< Size of this structure, in Bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_U32 nU32; /**< U32 value */ -} OMX_PARAM_U32TYPE; - -/** @ingroup rpm */ -typedef enum OMX_SUSPENSIONPOLICYTYPE { - OMX_SuspensionDisabled, /**< No suspension; v1.0 behavior */ - OMX_SuspensionEnabled, /**< Suspension allowed */ - OMX_SuspensionPolicyKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_SuspensionPolicyStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_SuspensionPolicyMax = 0x7fffffff -} OMX_SUSPENSIONPOLICYTYPE; - -/** @ingroup rpm */ -typedef struct OMX_PARAM_SUSPENSIONPOLICYTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_SUSPENSIONPOLICYTYPE ePolicy; -} OMX_PARAM_SUSPENSIONPOLICYTYPE; - -/** @ingroup rpm */ -typedef enum OMX_SUSPENSIONTYPE { - OMX_NotSuspended, /**< component is not suspended */ - OMX_Suspended, /**< component is suspended */ - OMX_SuspensionKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_SuspensionVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_SuspendMax = 0x7FFFFFFF -} OMX_SUSPENSIONTYPE; - -/** @ingroup rpm */ -typedef struct OMX_PARAM_SUSPENSIONTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_SUSPENSIONTYPE eType; -} OMX_PARAM_SUSPENSIONTYPE ; - -typedef struct OMX_CONFIG_BOOLEANTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_BOOL bEnabled; -} OMX_CONFIG_BOOLEANTYPE; - -/* Parameter specifying the content uri to use. */ -/** @ingroup cp */ -typedef struct OMX_PARAM_CONTENTURITYPE -{ - OMX_U32 nSize; /**< size of the structure in bytes, including - actual URI name */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U8 contentURI[1]; /**< The URI name */ -} OMX_PARAM_CONTENTURITYPE; - -/* Parameter specifying the pipe to use. */ -/** @ingroup cp */ -typedef struct OMX_PARAM_CONTENTPIPETYPE -{ - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_HANDLETYPE hPipe; /**< The pipe handle*/ -} OMX_PARAM_CONTENTPIPETYPE; - -/** @ingroup rpm */ -typedef struct OMX_RESOURCECONCEALMENTTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_BOOL bResourceConcealmentForbidden; /**< disallow the use of resource concealment - methods (like degrading algorithm quality to - lower resource consumption or functional bypass) - on a component as a resolution to resource conflicts. */ -} OMX_RESOURCECONCEALMENTTYPE; - - -/** @ingroup metadata */ -typedef enum OMX_METADATACHARSETTYPE { - OMX_MetadataCharsetUnknown = 0, - OMX_MetadataCharsetASCII, - OMX_MetadataCharsetBinary, - OMX_MetadataCharsetCodePage1252, - OMX_MetadataCharsetUTF8, - OMX_MetadataCharsetJavaConformantUTF8, - OMX_MetadataCharsetUTF7, - OMX_MetadataCharsetImapUTF7, - OMX_MetadataCharsetUTF16LE, - OMX_MetadataCharsetUTF16BE, - OMX_MetadataCharsetGB12345, - OMX_MetadataCharsetHZGB2312, - OMX_MetadataCharsetGB2312, - OMX_MetadataCharsetGB18030, - OMX_MetadataCharsetGBK, - OMX_MetadataCharsetBig5, - OMX_MetadataCharsetISO88591, - OMX_MetadataCharsetISO88592, - OMX_MetadataCharsetISO88593, - OMX_MetadataCharsetISO88594, - OMX_MetadataCharsetISO88595, - OMX_MetadataCharsetISO88596, - OMX_MetadataCharsetISO88597, - OMX_MetadataCharsetISO88598, - OMX_MetadataCharsetISO88599, - OMX_MetadataCharsetISO885910, - OMX_MetadataCharsetISO885913, - OMX_MetadataCharsetISO885914, - OMX_MetadataCharsetISO885915, - OMX_MetadataCharsetShiftJIS, - OMX_MetadataCharsetISO2022JP, - OMX_MetadataCharsetISO2022JP1, - OMX_MetadataCharsetISOEUCJP, - OMX_MetadataCharsetSMS7Bit, - OMX_MetadataCharsetKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_MetadataCharsetVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_MetadataCharsetTypeMax= 0x7FFFFFFF -} OMX_METADATACHARSETTYPE; - -/** @ingroup metadata */ -typedef enum OMX_METADATASCOPETYPE -{ - OMX_MetadataScopeAllLevels, - OMX_MetadataScopeTopLevel, - OMX_MetadataScopePortLevel, - OMX_MetadataScopeNodeLevel, - OMX_MetadataScopeKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_MetadataScopeVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_MetadataScopeTypeMax = 0x7fffffff -} OMX_METADATASCOPETYPE; - -/** @ingroup metadata */ -typedef enum OMX_METADATASEARCHMODETYPE -{ - OMX_MetadataSearchValueSizeByIndex, - OMX_MetadataSearchItemByIndex, - OMX_MetadataSearchNextItemByKey, - OMX_MetadataSearchKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_MetadataSearchVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_MetadataSearchTypeMax = 0x7fffffff -} OMX_METADATASEARCHMODETYPE; -/** @ingroup metadata */ -typedef struct OMX_CONFIG_METADATAITEMCOUNTTYPE -{ - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_METADATASCOPETYPE eScopeMode; - OMX_U32 nScopeSpecifier; - OMX_U32 nMetadataItemCount; -} OMX_CONFIG_METADATAITEMCOUNTTYPE; - -/** @ingroup metadata */ -typedef struct OMX_CONFIG_METADATAITEMTYPE -{ - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_METADATASCOPETYPE eScopeMode; - OMX_U32 nScopeSpecifier; - OMX_U32 nMetadataItemIndex; - OMX_METADATASEARCHMODETYPE eSearchMode; - OMX_METADATACHARSETTYPE eKeyCharset; - OMX_U8 nKeySizeUsed; - OMX_U8 nKey[128]; - OMX_METADATACHARSETTYPE eValueCharset; - OMX_STRING sLanguageCountry; - OMX_U32 nValueMaxSize; - OMX_U32 nValueSizeUsed; - OMX_U8 nValue[1]; -} OMX_CONFIG_METADATAITEMTYPE; - -/* @ingroup metadata */ -typedef struct OMX_CONFIG_CONTAINERNODECOUNTTYPE -{ - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_BOOL bAllKeys; - OMX_U32 nParentNodeID; - OMX_U32 nNumNodes; -} OMX_CONFIG_CONTAINERNODECOUNTTYPE; - -/** @ingroup metadata */ -typedef struct OMX_CONFIG_CONTAINERNODEIDTYPE -{ - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_BOOL bAllKeys; - OMX_U32 nParentNodeID; - OMX_U32 nNodeIndex; - OMX_U32 nNodeID; - OMX_STRING cNodeName; - OMX_BOOL bIsLeafType; -} OMX_CONFIG_CONTAINERNODEIDTYPE; - -/** @ingroup metadata */ -typedef struct OMX_PARAM_METADATAFILTERTYPE -{ - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_BOOL bAllKeys; /* if true then this structure refers to all keys and - * the three key fields below are ignored */ - OMX_METADATACHARSETTYPE eKeyCharset; - OMX_U32 nKeySizeUsed; - OMX_U8 nKey [128]; - OMX_U32 nLanguageCountrySizeUsed; - OMX_U8 nLanguageCountry[128]; - OMX_BOOL bEnabled; /* if true then key is part of filter (e.g. - * retained for query later). If false then - * key is not part of filter */ -} OMX_PARAM_METADATAFILTERTYPE; - -/** The OMX_HANDLETYPE structure defines the component handle. The component - * handle is used to access all of the component's public methods and also - * contains pointers to the component's private data area. The component - * handle is initialized by the OMX core (with help from the component) - * during the process of loading the component. After the component is - * successfully loaded, the application can safely access any of the - * component's public functions (although some may return an error because - * the state is inappropriate for the access). - * - * @ingroup comp - */ -typedef struct OMX_COMPONENTTYPE -{ - /** The size of this structure, in bytes. It is the responsibility - of the allocator of this structure to fill in this value. Since - this structure is allocated by the GetHandle function, this - function will fill in this value. */ - OMX_U32 nSize; - - /** nVersion is the version of the OMX specification that the structure - is built against. It is the responsibility of the creator of this - structure to initialize this value and every user of this structure - should verify that it knows how to use the exact version of - this structure found herein. */ - OMX_VERSIONTYPE nVersion; - - /** pComponentPrivate is a pointer to the component private data area. - This member is allocated and initialized by the component when the - component is first loaded. The application should not access this - data area. */ - OMX_PTR pComponentPrivate; - - /** pApplicationPrivate is a pointer that is a parameter to the - OMX_GetHandle method, and contains an application private value - provided by the IL client. This application private data is - returned to the IL Client by OMX in all callbacks */ - OMX_PTR pApplicationPrivate; - - /** refer to OMX_GetComponentVersion in OMX_core.h or the OMX IL - specification for details on the GetComponentVersion method. - */ - OMX_ERRORTYPE (*GetComponentVersion)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_OUT OMX_STRING pComponentName, - OMX_OUT OMX_VERSIONTYPE* pComponentVersion, - OMX_OUT OMX_VERSIONTYPE* pSpecVersion, - OMX_OUT OMX_UUIDTYPE* pComponentUUID); - - /** refer to OMX_SendCommand in OMX_core.h or the OMX IL - specification for details on the SendCommand method. - */ - OMX_ERRORTYPE (*SendCommand)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_IN OMX_COMMANDTYPE Cmd, - OMX_IN OMX_U32 nParam1, - OMX_IN OMX_PTR pCmdData); - - /** refer to OMX_GetParameter in OMX_core.h or the OMX IL - specification for details on the GetParameter method. - */ - OMX_ERRORTYPE (*GetParameter)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_IN OMX_INDEXTYPE nParamIndex, - OMX_INOUT OMX_PTR pComponentParameterStructure); - - - /** refer to OMX_SetParameter in OMX_core.h or the OMX IL - specification for details on the SetParameter method. - */ - OMX_ERRORTYPE (*SetParameter)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_IN OMX_INDEXTYPE nIndex, - OMX_IN OMX_PTR pComponentParameterStructure); - - - /** refer to OMX_GetConfig in OMX_core.h or the OMX IL - specification for details on the GetConfig method. - */ - OMX_ERRORTYPE (*GetConfig)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_IN OMX_INDEXTYPE nIndex, - OMX_INOUT OMX_PTR pComponentConfigStructure); - - - /** refer to OMX_SetConfig in OMX_core.h or the OMX IL - specification for details on the SetConfig method. - */ - OMX_ERRORTYPE (*SetConfig)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_IN OMX_INDEXTYPE nIndex, - OMX_IN OMX_PTR pComponentConfigStructure); - - - /** refer to OMX_GetExtensionIndex in OMX_core.h or the OMX IL - specification for details on the GetExtensionIndex method. - */ - OMX_ERRORTYPE (*GetExtensionIndex)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_IN OMX_STRING cParameterName, - OMX_OUT OMX_INDEXTYPE* pIndexType); - - - /** refer to OMX_GetState in OMX_core.h or the OMX IL - specification for details on the GetState method. - */ - OMX_ERRORTYPE (*GetState)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_OUT OMX_STATETYPE* pState); - - - /** The ComponentTunnelRequest method will interact with another OMX - component to determine if tunneling is possible and to setup the - tunneling. The return codes for this method can be used to - determine if tunneling is not possible, or if tunneling is not - supported. - - Base profile components (i.e. non-interop) do not support this - method and should return OMX_ErrorNotImplemented - - The interop profile component MUST support tunneling to another - interop profile component with a compatible port parameters. - A component may also support proprietary communication. - - If proprietary communication is supported the negotiation of - proprietary communication is done outside of OMX in a vendor - specific way. It is only required that the proper result be - returned and the details of how the setup is done is left - to the component implementation. - - When this method is invoked when nPort in an output port, the - component will: - 1. Populate the pTunnelSetup structure with the output port's - requirements and constraints for the tunnel. - - When this method is invoked when nPort in an input port, the - component will: - 1. Query the necessary parameters from the output port to - determine if the ports are compatible for tunneling - 2. If the ports are compatible, the component should store - the tunnel step provided by the output port - 3. Determine which port (either input or output) is the buffer - supplier, and call OMX_SetParameter on the output port to - indicate this selection. - - The component will return from this call within 5 msec. - - @param [in] hComp - Handle of the component to be accessed. This is the component - handle returned by the call to the OMX_GetHandle method. - @param [in] nPort - nPort is used to select the port on the component to be used - for tunneling. - @param [in] hTunneledComp - Handle of the component to tunnel with. This is the component - handle returned by the call to the OMX_GetHandle method. When - this parameter is 0x0 the component should setup the port for - communication with the application / IL Client. - @param [in] nPortOutput - nPortOutput is used indicate the port the component should - tunnel with. - @param [in] pTunnelSetup - Pointer to the tunnel setup structure. When nPort is an output port - the component should populate the fields of this structure. When - When nPort is an input port the component should review the setup - provided by the component with the output port. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup tun - */ - - OMX_ERRORTYPE (*ComponentTunnelRequest)( - OMX_IN OMX_HANDLETYPE hComp, - OMX_IN OMX_U32 nPort, - OMX_IN OMX_HANDLETYPE hTunneledComp, - OMX_IN OMX_U32 nTunneledPort, - OMX_INOUT OMX_TUNNELSETUPTYPE* pTunnelSetup); - - /** refer to OMX_UseBuffer in OMX_core.h or the OMX IL - specification for details on the UseBuffer method. - @ingroup buf - */ - OMX_ERRORTYPE (*UseBuffer)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_INOUT OMX_BUFFERHEADERTYPE** ppBufferHdr, - OMX_IN OMX_U32 nPortIndex, - OMX_IN OMX_PTR pAppPrivate, - OMX_IN OMX_U32 nSizeBytes, - OMX_IN OMX_U8* pBuffer); - - /** refer to OMX_AllocateBuffer in OMX_core.h or the OMX IL - specification for details on the AllocateBuffer method. - @ingroup buf - */ - OMX_ERRORTYPE (*AllocateBuffer)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_INOUT OMX_BUFFERHEADERTYPE** ppBuffer, - OMX_IN OMX_U32 nPortIndex, - OMX_IN OMX_PTR pAppPrivate, - OMX_IN OMX_U32 nSizeBytes); - - /** refer to OMX_FreeBuffer in OMX_core.h or the OMX IL - specification for details on the FreeBuffer method. - @ingroup buf - */ - OMX_ERRORTYPE (*FreeBuffer)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_IN OMX_U32 nPortIndex, - OMX_IN OMX_BUFFERHEADERTYPE* pBuffer); - - /** refer to OMX_EmptyThisBuffer in OMX_core.h or the OMX IL - specification for details on the EmptyThisBuffer method. - @ingroup buf - */ - OMX_ERRORTYPE (*EmptyThisBuffer)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_IN OMX_BUFFERHEADERTYPE* pBuffer); - - /** refer to OMX_FillThisBuffer in OMX_core.h or the OMX IL - specification for details on the FillThisBuffer method. - @ingroup buf - */ - OMX_ERRORTYPE (*FillThisBuffer)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_IN OMX_BUFFERHEADERTYPE* pBuffer); - - /** The SetCallbacks method is used by the core to specify the callback - structure from the application to the component. This is a blocking - call. The component will return from this call within 5 msec. - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the GetHandle function. - @param [in] pCallbacks - pointer to an OMX_CALLBACKTYPE structure used to provide the - callback information to the component - @param [in] pAppData - pointer to an application defined value. It is anticipated that - the application will pass a pointer to a data structure or a "this - pointer" in this area to allow the callback (in the application) - to determine the context of the call - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - */ - OMX_ERRORTYPE (*SetCallbacks)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_IN OMX_CALLBACKTYPE* pCallbacks, - OMX_IN OMX_PTR pAppData); - - /** ComponentDeInit method is used to deinitialize the component - providing a means to free any resources allocated at component - initialization. NOTE: After this call the component handle is - not valid for further use. - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the GetHandle function. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - */ - OMX_ERRORTYPE (*ComponentDeInit)( - OMX_IN OMX_HANDLETYPE hComponent); - - /** @ingroup buf */ - OMX_ERRORTYPE (*UseEGLImage)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_INOUT OMX_BUFFERHEADERTYPE** ppBufferHdr, - OMX_IN OMX_U32 nPortIndex, - OMX_IN OMX_PTR pAppPrivate, - OMX_IN void* eglImage); - - OMX_ERRORTYPE (*ComponentRoleEnum)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_OUT OMX_U8 *cRole, - OMX_IN OMX_U32 nIndex); - -} OMX_COMPONENTTYPE; - -#ifdef __cplusplus -} -#endif /* __cplusplus */ - -#endif -/* File EOF */ diff --git a/selfdrive/frogpilot/screenrecorder/openmax/include/OMX_ContentPipe.h b/selfdrive/frogpilot/screenrecorder/openmax/include/OMX_ContentPipe.h deleted file mode 100644 index 5f6310c..0000000 --- a/selfdrive/frogpilot/screenrecorder/openmax/include/OMX_ContentPipe.h +++ /dev/null @@ -1,195 +0,0 @@ -/* - * Copyright (c) 2008 The Khronos Group Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining - * a copy of this software and associated documentation files (the - * "Software"), to deal in the Software without restriction, including - * without limitation the rights to use, copy, modify, merge, publish, - * distribute, sublicense, and/or sell copies of the Software, and to - * permit persons to whom the Software is furnished to do so, subject - * to the following conditions: - * The above copyright notice and this permission notice shall be included - * in all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS - * OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. - * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY - * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, - * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE - * SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - * - */ - -/** OMX_ContentPipe.h - OpenMax IL version 1.1.2 - * The OMX_ContentPipe header file contains the definitions used to define - * the public interface for content piples. This header file is intended to - * be used by the component. - */ - -#ifndef OMX_CONTENTPIPE_H -#define OMX_CONTENTPIPE_H - -#ifndef KD_EACCES -/* OpenKODE error codes. CPResult values may be zero (indicating success - or one of the following values) */ -#define KD_EACCES (1) -#define KD_EADDRINUSE (2) -#define KD_EAGAIN (5) -#define KD_EBADF (7) -#define KD_EBUSY (8) -#define KD_ECONNREFUSED (9) -#define KD_ECONNRESET (10) -#define KD_EDEADLK (11) -#define KD_EDESTADDRREQ (12) -#define KD_ERANGE (35) -#define KD_EEXIST (13) -#define KD_EFBIG (14) -#define KD_EHOSTUNREACH (15) -#define KD_EINVAL (17) -#define KD_EIO (18) -#define KD_EISCONN (20) -#define KD_EISDIR (21) -#define KD_EMFILE (22) -#define KD_ENAMETOOLONG (23) -#define KD_ENOENT (24) -#define KD_ENOMEM (25) -#define KD_ENOSPC (26) -#define KD_ENOSYS (27) -#define KD_ENOTCONN (28) -#define KD_EPERM (33) -#define KD_ETIMEDOUT (36) -#define KD_EILSEQ (19) -#endif - -/** Map types from OMX standard types only here so interface is as generic as possible. */ -typedef OMX_U32 CPresult; -typedef char * CPstring; -typedef void * CPhandle; -typedef OMX_U32 CPuint; -typedef OMX_S32 CPint; -typedef char CPbyte; -typedef OMX_BOOL CPbool; - -/** enumeration of origin types used in the CP_PIPETYPE's Seek function - * @ingroup cp - */ -typedef enum CP_ORIGINTYPE { - CP_OriginBegin, - CP_OriginCur, - CP_OriginEnd, - CP_OriginKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - CP_OriginVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - CP_OriginMax = 0X7FFFFFFF -} CP_ORIGINTYPE; - -/** enumeration of contact access types used in the CP_PIPETYPE's Open function - * @ingroup cp - */ -typedef enum CP_ACCESSTYPE { - CP_AccessRead, - CP_AccessWrite, - CP_AccessReadWrite , - CP_AccessKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - CP_AccessVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - CP_AccessMax = 0X7FFFFFFF -} CP_ACCESSTYPE; - -/** enumeration of results returned by the CP_PIPETYPE's CheckAvailableBytes function - * @ingroup cp - */ -typedef enum CP_CHECKBYTESRESULTTYPE -{ - CP_CheckBytesOk, /**< There are at least the request number - of bytes available */ - CP_CheckBytesNotReady, /**< The pipe is still retrieving bytes - and presently lacks sufficient bytes. - Client will be called when they are - sufficient bytes are available. */ - CP_CheckBytesInsufficientBytes , /**< The pipe has retrieved all bytes - but those available are less than those - requested */ - CP_CheckBytesAtEndOfStream, /**< The pipe has reached the end of stream - and no more bytes are available. */ - CP_CheckBytesOutOfBuffers, /**< All read/write buffers are currently in use. */ - CP_CheckBytesKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - CP_CheckBytesVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - CP_CheckBytesMax = 0X7FFFFFFF -} CP_CHECKBYTESRESULTTYPE; - -/** enumeration of content pipe events sent to the client callback. - * @ingroup cp - */ -typedef enum CP_EVENTTYPE{ - CP_BytesAvailable, /** bytes requested in a CheckAvailableBytes call are now available*/ - CP_Overflow, /** enumeration of content pipe events sent to the client callback*/ - CP_PipeDisconnected , /** enumeration of content pipe events sent to the client callback*/ - CP_EventKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - CP_EventVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - CP_EventMax = 0X7FFFFFFF -} CP_EVENTTYPE; - -/** content pipe definition - * @ingroup cp - */ -typedef struct CP_PIPETYPE -{ - /** Open a content stream for reading or writing. */ - CPresult (*Open)( CPhandle* hContent, CPstring szURI, CP_ACCESSTYPE eAccess ); - - /** Close a content stream. */ - CPresult (*Close)( CPhandle hContent ); - - /** Create a content source and open it for writing. */ - CPresult (*Create)( CPhandle *hContent, CPstring szURI ); - - /** Check the that specified number of bytes are available for reading or writing (depending on access type).*/ - CPresult (*CheckAvailableBytes)( CPhandle hContent, CPuint nBytesRequested, CP_CHECKBYTESRESULTTYPE *eResult ); - - /** Seek to certain position in the content relative to the specified origin. */ - CPresult (*SetPosition)( CPhandle hContent, CPint nOffset, CP_ORIGINTYPE eOrigin); - - /** Retrieve the current position relative to the start of the content. */ - CPresult (*GetPosition)( CPhandle hContent, CPuint *pPosition); - - /** Retrieve data of the specified size from the content stream (advance content pointer by size of data). - Note: pipe client provides pointer. This function is appropriate for small high frequency reads. */ - CPresult (*Read)( CPhandle hContent, CPbyte *pData, CPuint nSize); - - /** Retrieve a buffer allocated by the pipe that contains the requested number of bytes. - Buffer contains the next block of bytes, as specified by nSize, of the content. nSize also - returns the size of the block actually read. Content pointer advances the by the returned size. - Note: pipe provides pointer. This function is appropriate for large reads. The client must call - ReleaseReadBuffer when done with buffer. - - In some cases the requested block may not reside in contiguous memory within the - pipe implementation. For instance if the pipe leverages a circular buffer then the requested - block may straddle the boundary of the circular buffer. By default a pipe implementation - performs a copy in this case to provide the block to the pipe client in one contiguous buffer. - If, however, the client sets bForbidCopy, then the pipe returns only those bytes preceding the memory - boundary. Here the client may retrieve the data in segments over successive calls. */ - CPresult (*ReadBuffer)( CPhandle hContent, CPbyte **ppBuffer, CPuint *nSize, CPbool bForbidCopy); - - /** Release a buffer obtained by ReadBuffer back to the pipe. */ - CPresult (*ReleaseReadBuffer)(CPhandle hContent, CPbyte *pBuffer); - - /** Write data of the specified size to the content (advance content pointer by size of data). - Note: pipe client provides pointer. This function is appropriate for small high frequency writes. */ - CPresult (*Write)( CPhandle hContent, CPbyte *data, CPuint nSize); - - /** Retrieve a buffer allocated by the pipe used to write data to the content. - Client will fill buffer with output data. Note: pipe provides pointer. This function is appropriate - for large writes. The client must call WriteBuffer when done it has filled the buffer with data.*/ - CPresult (*GetWriteBuffer)( CPhandle hContent, CPbyte **ppBuffer, CPuint nSize); - - /** Deliver a buffer obtained via GetWriteBuffer to the pipe. Pipe will write the - the contents of the buffer to content and advance content pointer by the size of the buffer */ - CPresult (*WriteBuffer)( CPhandle hContent, CPbyte *pBuffer, CPuint nFilledSize); - - /** Register a per-handle client callback with the content pipe. */ - CPresult (*RegisterCallback)( CPhandle hContent, CPresult (*ClientCallback)(CP_EVENTTYPE eEvent, CPuint iParam)); - -} CP_PIPETYPE; - -#endif - diff --git a/selfdrive/frogpilot/screenrecorder/openmax/include/OMX_Core.h b/selfdrive/frogpilot/screenrecorder/openmax/include/OMX_Core.h deleted file mode 100644 index 52d211f..0000000 --- a/selfdrive/frogpilot/screenrecorder/openmax/include/OMX_Core.h +++ /dev/null @@ -1,1440 +0,0 @@ -/* - * Copyright (c) 2008 The Khronos Group Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining - * a copy of this software and associated documentation files (the - * "Software"), to deal in the Software without restriction, including - * without limitation the rights to use, copy, modify, merge, publish, - * distribute, sublicense, and/or sell copies of the Software, and to - * permit persons to whom the Software is furnished to do so, subject - * to the following conditions: - * The above copyright notice and this permission notice shall be included - * in all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS - * OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. - * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY - * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, - * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE - * SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - * - */ - -/** OMX_Core.h - OpenMax IL version 1.1.2 - * The OMX_Core header file contains the definitions used by both the - * application and the component to access common items. - */ - -#ifndef OMX_Core_h -#define OMX_Core_h - -#ifdef __cplusplus -extern "C" { -#endif /* __cplusplus */ - - -/* Each OMX header shall include all required header files to allow the - * header to compile without errors. The includes below are required - * for this header file to compile successfully - */ - -#include - - -/** The OMX_COMMANDTYPE enumeration is used to specify the action in the - * OMX_SendCommand macro. - * @ingroup core - */ -typedef enum OMX_COMMANDTYPE -{ - OMX_CommandStateSet, /**< Change the component state */ - OMX_CommandFlush, /**< Flush the data queue(s) of a component */ - OMX_CommandPortDisable, /**< Disable a port on a component. */ - OMX_CommandPortEnable, /**< Enable a port on a component. */ - OMX_CommandMarkBuffer, /**< Mark a component/buffer for observation */ - OMX_CommandKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_CommandVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_CommandMax = 0X7FFFFFFF -} OMX_COMMANDTYPE; - - - -/** The OMX_STATETYPE enumeration is used to indicate or change the component - * state. This enumeration reflects the current state of the component when - * used with the OMX_GetState macro or becomes the parameter in a state change - * command when used with the OMX_SendCommand macro. - * - * The component will be in the Loaded state after the component is initially - * loaded into memory. In the Loaded state, the component is not allowed to - * allocate or hold resources other than to build it's internal parameter - * and configuration tables. The application will send one or more - * SetParameters/GetParameters and SetConfig/GetConfig commands to the - * component and the component will record each of these parameter and - * configuration changes for use later. When the application sends the - * Idle command, the component will acquire the resources needed for the - * specified configuration and will transition to the idle state if the - * allocation is successful. If the component cannot successfully - * transition to the idle state for any reason, the state of the component - * shall be fully rolled back to the Loaded state (e.g. all allocated - * resources shall be released). When the component receives the command - * to go to the Executing state, it shall begin processing buffers by - * sending all input buffers it holds to the application. While - * the component is in the Idle state, the application may also send the - * Pause command. If the component receives the pause command while in the - * Idle state, the component shall send all input buffers it holds to the - * application, but shall not begin processing buffers. This will allow the - * application to prefill buffers. - * - * @ingroup comp - */ - -typedef enum OMX_STATETYPE -{ - OMX_StateInvalid, /**< component has detected that it's internal data - structures are corrupted to the point that - it cannot determine it's state properly */ - OMX_StateLoaded, /**< component has been loaded but has not completed - initialization. The OMX_SetParameter macro - and the OMX_GetParameter macro are the only - valid macros allowed to be sent to the - component in this state. */ - OMX_StateIdle, /**< component initialization has been completed - successfully and the component is ready to - to start. */ - OMX_StateExecuting, /**< component has accepted the start command and - is processing data (if data is available) */ - OMX_StatePause, /**< component has received pause command */ - OMX_StateWaitForResources, /**< component is waiting for resources, either after - preemption or before it gets the resources requested. - See specification for complete details. */ - OMX_StateKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_StateVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_StateMax = 0X7FFFFFFF -} OMX_STATETYPE; - -/** The OMX_ERRORTYPE enumeration defines the standard OMX Errors. These - * errors should cover most of the common failure cases. However, - * vendors are free to add additional error messages of their own as - * long as they follow these rules: - * 1. Vendor error messages shall be in the range of 0x90000000 to - * 0x9000FFFF. - * 2. Vendor error messages shall be defined in a header file provided - * with the component. No error messages are allowed that are - * not defined. - */ -typedef enum OMX_ERRORTYPE -{ - OMX_ErrorNone = 0, - - /** There were insufficient resources to perform the requested operation */ - OMX_ErrorInsufficientResources = (OMX_S32) 0x80001000, - - /** There was an error, but the cause of the error could not be determined */ - OMX_ErrorUndefined = (OMX_S32) 0x80001001, - - /** The component name string was not valid */ - OMX_ErrorInvalidComponentName = (OMX_S32) 0x80001002, - - /** No component with the specified name string was found */ - OMX_ErrorComponentNotFound = (OMX_S32) 0x80001003, - - /** The component specified did not have a "OMX_ComponentInit" or - "OMX_ComponentDeInit entry point */ - OMX_ErrorInvalidComponent = (OMX_S32) 0x80001004, - - /** One or more parameters were not valid */ - OMX_ErrorBadParameter = (OMX_S32) 0x80001005, - - /** The requested function is not implemented */ - OMX_ErrorNotImplemented = (OMX_S32) 0x80001006, - - /** The buffer was emptied before the next buffer was ready */ - OMX_ErrorUnderflow = (OMX_S32) 0x80001007, - - /** The buffer was not available when it was needed */ - OMX_ErrorOverflow = (OMX_S32) 0x80001008, - - /** The hardware failed to respond as expected */ - OMX_ErrorHardware = (OMX_S32) 0x80001009, - - /** The component is in the state OMX_StateInvalid */ - OMX_ErrorInvalidState = (OMX_S32) 0x8000100A, - - /** Stream is found to be corrupt */ - OMX_ErrorStreamCorrupt = (OMX_S32) 0x8000100B, - - /** Ports being connected are not compatible */ - OMX_ErrorPortsNotCompatible = (OMX_S32) 0x8000100C, - - /** Resources allocated to an idle component have been - lost resulting in the component returning to the loaded state */ - OMX_ErrorResourcesLost = (OMX_S32) 0x8000100D, - - /** No more indicies can be enumerated */ - OMX_ErrorNoMore = (OMX_S32) 0x8000100E, - - /** The component detected a version mismatch */ - OMX_ErrorVersionMismatch = (OMX_S32) 0x8000100F, - - /** The component is not ready to return data at this time */ - OMX_ErrorNotReady = (OMX_S32) 0x80001010, - - /** There was a timeout that occurred */ - OMX_ErrorTimeout = (OMX_S32) 0x80001011, - - /** This error occurs when trying to transition into the state you are already in */ - OMX_ErrorSameState = (OMX_S32) 0x80001012, - - /** Resources allocated to an executing or paused component have been - preempted, causing the component to return to the idle state */ - OMX_ErrorResourcesPreempted = (OMX_S32) 0x80001013, - - /** A non-supplier port sends this error to the IL client (via the EventHandler callback) - during the allocation of buffers (on a transition from the LOADED to the IDLE state or - on a port restart) when it deems that it has waited an unusually long time for the supplier - to send it an allocated buffer via a UseBuffer call. */ - OMX_ErrorPortUnresponsiveDuringAllocation = (OMX_S32) 0x80001014, - - /** A non-supplier port sends this error to the IL client (via the EventHandler callback) - during the deallocation of buffers (on a transition from the IDLE to LOADED state or - on a port stop) when it deems that it has waited an unusually long time for the supplier - to request the deallocation of a buffer header via a FreeBuffer call. */ - OMX_ErrorPortUnresponsiveDuringDeallocation = (OMX_S32) 0x80001015, - - /** A supplier port sends this error to the IL client (via the EventHandler callback) - during the stopping of a port (either on a transition from the IDLE to LOADED - state or a port stop) when it deems that it has waited an unusually long time for - the non-supplier to return a buffer via an EmptyThisBuffer or FillThisBuffer call. */ - OMX_ErrorPortUnresponsiveDuringStop = (OMX_S32) 0x80001016, - - /** Attempting a state transtion that is not allowed */ - OMX_ErrorIncorrectStateTransition = (OMX_S32) 0x80001017, - - /* Attempting a command that is not allowed during the present state. */ - OMX_ErrorIncorrectStateOperation = (OMX_S32) 0x80001018, - - /** The values encapsulated in the parameter or config structure are not supported. */ - OMX_ErrorUnsupportedSetting = (OMX_S32) 0x80001019, - - /** The parameter or config indicated by the given index is not supported. */ - OMX_ErrorUnsupportedIndex = (OMX_S32) 0x8000101A, - - /** The port index supplied is incorrect. */ - OMX_ErrorBadPortIndex = (OMX_S32) 0x8000101B, - - /** The port has lost one or more of its buffers and it thus unpopulated. */ - OMX_ErrorPortUnpopulated = (OMX_S32) 0x8000101C, - - /** Component suspended due to temporary loss of resources */ - OMX_ErrorComponentSuspended = (OMX_S32) 0x8000101D, - - /** Component suspended due to an inability to acquire dynamic resources */ - OMX_ErrorDynamicResourcesUnavailable = (OMX_S32) 0x8000101E, - - /** When the macroblock error reporting is enabled the component returns new error - for every frame that has errors */ - OMX_ErrorMbErrorsInFrame = (OMX_S32) 0x8000101F, - - /** A component reports this error when it cannot parse or determine the format of an input stream. */ - OMX_ErrorFormatNotDetected = (OMX_S32) 0x80001020, - - /** The content open operation failed. */ - OMX_ErrorContentPipeOpenFailed = (OMX_S32) 0x80001021, - - /** The content creation operation failed. */ - OMX_ErrorContentPipeCreationFailed = (OMX_S32) 0x80001022, - - /** Separate table information is being used */ - OMX_ErrorSeperateTablesUsed = (OMX_S32) 0x80001023, - - /** Tunneling is unsupported by the component*/ - OMX_ErrorTunnelingUnsupported = (OMX_S32) 0x80001024, - - OMX_ErrorKhronosExtensions = (OMX_S32)0x8F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_ErrorVendorStartUnused = (OMX_S32)0x90000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_ErrorMax = 0x7FFFFFFF -} OMX_ERRORTYPE; - -/** @ingroup core */ -typedef OMX_ERRORTYPE (* OMX_COMPONENTINITTYPE)(OMX_IN OMX_HANDLETYPE hComponent); - -/** @ingroup core */ -typedef struct OMX_COMPONENTREGISTERTYPE -{ - const char * pName; /* Component name, 128 byte limit (including '\0') applies */ - OMX_COMPONENTINITTYPE pInitialize; /* Component instance initialization function */ -} OMX_COMPONENTREGISTERTYPE; - -/** @ingroup core */ -extern OMX_COMPONENTREGISTERTYPE OMX_ComponentRegistered[]; - -/** @ingroup rpm */ -typedef struct OMX_PRIORITYMGMTTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nGroupPriority; /**< Priority of the component group */ - OMX_U32 nGroupID; /**< ID of the component group */ -} OMX_PRIORITYMGMTTYPE; - -/* Component name and Role names are limited to 128 characters including the terminating '\0'. */ -#define OMX_MAX_STRINGNAME_SIZE 128 - -/** @ingroup comp */ -typedef struct OMX_PARAM_COMPONENTROLETYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U8 cRole[OMX_MAX_STRINGNAME_SIZE]; /**< name of standard component which defines component role */ -} OMX_PARAM_COMPONENTROLETYPE; - -/** End of Stream Buffer Flag: - * - * A component sets EOS when it has no more data to emit on a particular - * output port. Thus an output port shall set EOS on the last buffer it - * emits. A component's determination of when an output port should - * cease sending data is implemenation specific. - * @ingroup buf - */ - -#define OMX_BUFFERFLAG_EOS 0x00000001 - -/** Start Time Buffer Flag: - * - * The source of a stream (e.g. a demux component) sets the STARTTIME - * flag on the buffer that contains the starting timestamp for the - * stream. The starting timestamp corresponds to the first data that - * should be displayed at startup or after a seek. - * The first timestamp of the stream is not necessarily the start time. - * For instance, in the case of a seek to a particular video frame, - * the target frame may be an interframe. Thus the first buffer of - * the stream will be the intra-frame preceding the target frame and - * the starttime will occur with the target frame (with any other - * required frames required to reconstruct the target intervening). - * - * The STARTTIME flag is directly associated with the buffer's - * timestamp ' thus its association to buffer data and its - * propagation is identical to the timestamp's. - * - * When a Sync Component client receives a buffer with the - * STARTTIME flag it shall perform a SetConfig on its sync port - * using OMX_ConfigTimeClientStartTime and passing the buffer's - * timestamp. - * - * @ingroup buf - */ - -#define OMX_BUFFERFLAG_STARTTIME 0x00000002 - - - -/** Decode Only Buffer Flag: - * - * The source of a stream (e.g. a demux component) sets the DECODEONLY - * flag on any buffer that should shall be decoded but should not be - * displayed. This flag is used, for instance, when a source seeks to - * a target interframe that requires the decode of frames preceding the - * target to facilitate the target's reconstruction. In this case the - * source would emit the frames preceding the target downstream - * but mark them as decode only. - * - * The DECODEONLY is associated with buffer data and propagated in a - * manner identical to the buffer timestamp. - * - * A component that renders data should ignore all buffers with - * the DECODEONLY flag set. - * - * @ingroup buf - */ - -#define OMX_BUFFERFLAG_DECODEONLY 0x00000004 - - -/* Data Corrupt Flag: This flag is set when the IL client believes the data in the associated buffer is corrupt - * @ingroup buf - */ - -#define OMX_BUFFERFLAG_DATACORRUPT 0x00000008 - -/* End of Frame: The buffer contains exactly one end of frame and no data - * occurs after the end of frame. This flag is an optional hint. The absence - * of this flag does not imply the absence of an end of frame within the buffer. - * @ingroup buf -*/ -#define OMX_BUFFERFLAG_ENDOFFRAME 0x00000010 - -/* Sync Frame Flag: This flag is set when the buffer content contains a coded sync frame ' - * a frame that has no dependency on any other frame information - * @ingroup buf - */ -#define OMX_BUFFERFLAG_SYNCFRAME 0x00000020 - -/* Extra data present flag: there is extra data appended to the data stream - * residing in the buffer - * @ingroup buf - */ -#define OMX_BUFFERFLAG_EXTRADATA 0x00000040 - -/** Codec Config Buffer Flag: -* OMX_BUFFERFLAG_CODECCONFIG is an optional flag that is set by an -* output port when all bytes in the buffer form part or all of a set of -* codec specific configuration data. Examples include SPS/PPS nal units -* for OMX_VIDEO_CodingAVC or AudioSpecificConfig data for -* OMX_AUDIO_CodingAAC. Any component that for a given stream sets -* OMX_BUFFERFLAG_CODECCONFIG shall not mix codec configuration bytes -* with frame data in the same buffer, and shall send all buffers -* containing codec configuration bytes before any buffers containing -* frame data that those configurations bytes describe. -* If the stream format for a particular codec has a frame specific -* header at the start of each frame, for example OMX_AUDIO_CodingMP3 or -* OMX_AUDIO_CodingAAC in ADTS mode, then these shall be presented as -* normal without setting OMX_BUFFERFLAG_CODECCONFIG. - * @ingroup buf - */ -#define OMX_BUFFERFLAG_CODECCONFIG 0x00000080 - -/* -* OMX_BUFFERFLAG_READONLY: This flag is set when a component emitting the -* buffer on an output port or the IL client wishes to identify the buffer -* payload contents to be read-only. An IL client or an input port -* shall not alter the contents of the buffer. This flag shall only be -* cleared by the originator of the buffer when the buffer is returned. -* For tunneled ports, the usage of this flag shall be allowed only if the -* components negotiated a read-only tunnel -*/ -#define OMX_BUFFERFLAG_READONLY 0x00000200 - -/** @ingroup buf */ -typedef struct OMX_BUFFERHEADERTYPE -{ - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U8* pBuffer; /**< Pointer to actual block of memory - that is acting as the buffer */ - OMX_U32 nAllocLen; /**< size of the buffer allocated, in bytes */ - OMX_U32 nFilledLen; /**< number of bytes currently in the - buffer */ - OMX_U32 nOffset; /**< start offset of valid data in bytes from - the start of the buffer */ - OMX_PTR pAppPrivate; /**< pointer to any data the application - wants to associate with this buffer */ - OMX_PTR pPlatformPrivate; /**< pointer to any data the platform - wants to associate with this buffer */ - OMX_PTR pInputPortPrivate; /**< pointer to any data the input port - wants to associate with this buffer */ - OMX_PTR pOutputPortPrivate; /**< pointer to any data the output port - wants to associate with this buffer */ - OMX_HANDLETYPE hMarkTargetComponent; /**< The component that will generate a - mark event upon processing this buffer. */ - OMX_PTR pMarkData; /**< Application specific data associated with - the mark sent on a mark event to disambiguate - this mark from others. */ - OMX_U32 nTickCount; /**< Optional entry that the component and - application can update with a tick count - when they access the component. This - value should be in microseconds. Since - this is a value relative to an arbitrary - starting point, this value cannot be used - to determine absolute time. This is an - optional entry and not all components - will update it.*/ - OMX_TICKS nTimeStamp; /**< Timestamp corresponding to the sample - starting at the first logical sample - boundary in the buffer. Timestamps of - successive samples within the buffer may - be inferred by adding the duration of the - of the preceding buffer to the timestamp - of the preceding buffer.*/ - OMX_U32 nFlags; /**< buffer specific flags */ - OMX_U32 nOutputPortIndex; /**< The index of the output port (if any) using - this buffer */ - OMX_U32 nInputPortIndex; /**< The index of the input port (if any) using - this buffer */ -} OMX_BUFFERHEADERTYPE; - -/** The OMX_EXTRADATATYPE enumeration is used to define the - * possible extra data payload types. - * NB: this enum is binary backwards compatible with the previous - * OMX_EXTRADATA_QUANT define. This should be replaced with - * OMX_ExtraDataQuantization. - */ -typedef enum OMX_EXTRADATATYPE -{ - OMX_ExtraDataNone = 0, /**< Indicates that no more extra data sections follow */ - OMX_ExtraDataQuantization, /**< The data payload contains quantization data */ - OMX_ExtraDataKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_ExtraDataVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_ExtraDataMax = 0x7FFFFFFF -} OMX_EXTRADATATYPE; - - -typedef struct OMX_OTHER_EXTRADATATYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_EXTRADATATYPE eType; /* Extra Data type */ - OMX_U32 nDataSize; /* Size of the supporting data to follow */ - OMX_U8 data[1]; /* Supporting data hint */ -} OMX_OTHER_EXTRADATATYPE; - -/** @ingroup comp */ -typedef struct OMX_PORT_PARAM_TYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPorts; /**< The number of ports for this component */ - OMX_U32 nStartPortNumber; /** first port number for this type of port */ -} OMX_PORT_PARAM_TYPE; - -/** @ingroup comp */ -typedef enum OMX_EVENTTYPE -{ - OMX_EventCmdComplete, /**< component has sucessfully completed a command */ - OMX_EventError, /**< component has detected an error condition */ - OMX_EventMark, /**< component has detected a buffer mark */ - OMX_EventPortSettingsChanged, /**< component is reported a port settings change */ - OMX_EventBufferFlag, /**< component has detected an EOS */ - OMX_EventResourcesAcquired, /**< component has been granted resources and is - automatically starting the state change from - OMX_StateWaitForResources to OMX_StateIdle. */ - OMX_EventComponentResumed, /**< Component resumed due to reacquisition of resources */ - OMX_EventDynamicResourcesAvailable, /**< Component has acquired previously unavailable dynamic resources */ - OMX_EventPortFormatDetected, /**< Component has detected a supported format. */ - OMX_EventKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_EventVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_EventMax = 0x7FFFFFFF -} OMX_EVENTTYPE; - -typedef struct OMX_CALLBACKTYPE -{ - /** The EventHandler method is used to notify the application when an - event of interest occurs. Events are defined in the OMX_EVENTTYPE - enumeration. Please see that enumeration for details of what will - be returned for each type of event. Callbacks should not return - an error to the component, so if an error occurs, the application - shall handle it internally. This is a blocking call. - - The application should return from this call within 5 msec to avoid - blocking the component for an excessively long period of time. - - @param hComponent - handle of the component to access. This is the component - handle returned by the call to the GetHandle function. - @param pAppData - pointer to an application defined value that was provided in the - pAppData parameter to the OMX_GetHandle method for the component. - This application defined value is provided so that the application - can have a component specific context when receiving the callback. - @param eEvent - Event that the component wants to notify the application about. - @param nData1 - nData will be the OMX_ERRORTYPE for an error event and will be - an OMX_COMMANDTYPE for a command complete event and OMX_INDEXTYPE for a OMX_PortSettingsChanged event. - @param nData2 - nData2 will hold further information related to the event. Can be OMX_STATETYPE for - a OMX_CommandStateSet command or port index for a OMX_PortSettingsChanged event. - Default value is 0 if not used. ) - @param pEventData - Pointer to additional event-specific data (see spec for meaning). - */ - - OMX_ERRORTYPE (*EventHandler)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_IN OMX_PTR pAppData, - OMX_IN OMX_EVENTTYPE eEvent, - OMX_IN OMX_U32 nData1, - OMX_IN OMX_U32 nData2, - OMX_IN OMX_PTR pEventData); - - /** The EmptyBufferDone method is used to return emptied buffers from an - input port back to the application for reuse. This is a blocking call - so the application should not attempt to refill the buffers during this - call, but should queue them and refill them in another thread. There - is no error return, so the application shall handle any errors generated - internally. - - The application should return from this call within 5 msec. - - @param hComponent - handle of the component to access. This is the component - handle returned by the call to the GetHandle function. - @param pAppData - pointer to an application defined value that was provided in the - pAppData parameter to the OMX_GetHandle method for the component. - This application defined value is provided so that the application - can have a component specific context when receiving the callback. - @param pBuffer - pointer to an OMX_BUFFERHEADERTYPE structure allocated with UseBuffer - or AllocateBuffer indicating the buffer that was emptied. - @ingroup buf - */ - OMX_ERRORTYPE (*EmptyBufferDone)( - OMX_IN OMX_HANDLETYPE hComponent, - OMX_IN OMX_PTR pAppData, - OMX_IN OMX_BUFFERHEADERTYPE* pBuffer); - - /** The FillBufferDone method is used to return filled buffers from an - output port back to the application for emptying and then reuse. - This is a blocking call so the application should not attempt to - empty the buffers during this call, but should queue the buffers - and empty them in another thread. There is no error return, so - the application shall handle any errors generated internally. The - application shall also update the buffer header to indicate the - number of bytes placed into the buffer. - - The application should return from this call within 5 msec. - - @param hComponent - handle of the component to access. This is the component - handle returned by the call to the GetHandle function. - @param pAppData - pointer to an application defined value that was provided in the - pAppData parameter to the OMX_GetHandle method for the component. - This application defined value is provided so that the application - can have a component specific context when receiving the callback. - @param pBuffer - pointer to an OMX_BUFFERHEADERTYPE structure allocated with UseBuffer - or AllocateBuffer indicating the buffer that was filled. - @ingroup buf - */ - OMX_ERRORTYPE (*FillBufferDone)( - OMX_OUT OMX_HANDLETYPE hComponent, - OMX_OUT OMX_PTR pAppData, - OMX_OUT OMX_BUFFERHEADERTYPE* pBuffer); - -} OMX_CALLBACKTYPE; - -/** The OMX_BUFFERSUPPLIERTYPE enumeration is used to dictate port supplier - preference when tunneling between two ports. - @ingroup tun buf -*/ -typedef enum OMX_BUFFERSUPPLIERTYPE -{ - OMX_BufferSupplyUnspecified = 0x0, /**< port supplying the buffers is unspecified, - or don't care */ - OMX_BufferSupplyInput, /**< input port supplies the buffers */ - OMX_BufferSupplyOutput, /**< output port supplies the buffers */ - OMX_BufferSupplyKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_BufferSupplyVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_BufferSupplyMax = 0x7FFFFFFF -} OMX_BUFFERSUPPLIERTYPE; - - -/** buffer supplier parameter - * @ingroup tun - */ -typedef struct OMX_PARAM_BUFFERSUPPLIERTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_BUFFERSUPPLIERTYPE eBufferSupplier; /**< buffer supplier */ -} OMX_PARAM_BUFFERSUPPLIERTYPE; - - -/**< indicates that buffers received by an input port of a tunnel - may not modify the data in the buffers - @ingroup tun - */ -#define OMX_PORTTUNNELFLAG_READONLY 0x00000001 - - -/** The OMX_TUNNELSETUPTYPE structure is used to pass data from an output - port to an input port as part the two ComponentTunnelRequest calls - resulting from a OMX_SetupTunnel call from the IL Client. - @ingroup tun - */ -typedef struct OMX_TUNNELSETUPTYPE -{ - OMX_U32 nTunnelFlags; /**< bit flags for tunneling */ - OMX_BUFFERSUPPLIERTYPE eSupplier; /**< supplier preference */ -} OMX_TUNNELSETUPTYPE; - -/* OMX Component headers is included to enable the core to use - macros for functions into the component for OMX release 1.0. - Developers should not access any structures or data from within - the component header directly */ -/* TO BE REMOVED - #include */ - -/** GetComponentVersion will return information about the component. - This is a blocking call. This macro will go directly from the - application to the component (via a core macro). The - component will return from this call within 5 msec. - @param [in] hComponent - handle of component to execute the command - @param [out] pComponentName - pointer to an empty string of length 128 bytes. The component - will write its name into this string. The name will be - terminated by a single zero byte. The name of a component will - be 127 bytes or less to leave room for the trailing zero byte. - An example of a valid component name is "OMX.ABC.ChannelMixer\0". - @param [out] pComponentVersion - pointer to an OMX Version structure that the component will fill - in. The component will fill in a value that indicates the - component version. NOTE: the component version is NOT the same - as the OMX Specification version (found in all structures). The - component version is defined by the vendor of the component and - its value is entirely up to the component vendor. - @param [out] pSpecVersion - pointer to an OMX Version structure that the component will fill - in. The SpecVersion is the version of the specification that the - component was built against. Please note that this value may or - may not match the structure's version. For example, if the - component was built against the 2.0 specification, but the - application (which creates the structure is built against the - 1.0 specification the versions would be different. - @param [out] pComponentUUID - pointer to the UUID of the component which will be filled in by - the component. The UUID is a unique identifier that is set at - RUN time for the component and is unique to each instantion of - the component. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup comp - */ -#define OMX_GetComponentVersion( \ - hComponent, \ - pComponentName, \ - pComponentVersion, \ - pSpecVersion, \ - pComponentUUID) \ - ((OMX_COMPONENTTYPE*)hComponent)->GetComponentVersion( \ - hComponent, \ - pComponentName, \ - pComponentVersion, \ - pSpecVersion, \ - pComponentUUID) /* Macro End */ - - -/** Send a command to the component. This call is a non-blocking call. - The component should check the parameters and then queue the command - to the component thread to be executed. The component thread shall - send the EventHandler() callback at the conclusion of the command. - This macro will go directly from the application to the component (via - a core macro). The component will return from this call within 5 msec. - - When the command is "OMX_CommandStateSet" the component will queue a - state transition to the new state idenfied in nParam. - - When the command is "OMX_CommandFlush", to flush a port's buffer queues, - the command will force the component to return all buffers NOT CURRENTLY - BEING PROCESSED to the application, in the order in which the buffers - were received. - - When the command is "OMX_CommandPortDisable" or - "OMX_CommandPortEnable", the component's port (given by the value of - nParam) will be stopped or restarted. - - When the command "OMX_CommandMarkBuffer" is used to mark a buffer, the - pCmdData will point to a OMX_MARKTYPE structure containing the component - handle of the component to examine the buffer chain for the mark. nParam1 - contains the index of the port on which the buffer mark is applied. - - Specification text for more details. - - @param [in] hComponent - handle of component to execute the command - @param [in] Cmd - Command for the component to execute - @param [in] nParam - Parameter for the command to be executed. When Cmd has the value - OMX_CommandStateSet, value is a member of OMX_STATETYPE. When Cmd has - the value OMX_CommandFlush, value of nParam indicates which port(s) - to flush. -1 is used to flush all ports a single port index will - only flush that port. When Cmd has the value "OMX_CommandPortDisable" - or "OMX_CommandPortEnable", the component's port is given by - the value of nParam. When Cmd has the value "OMX_CommandMarkBuffer" - the components pot is given by the value of nParam. - @param [in] pCmdData - Parameter pointing to the OMX_MARKTYPE structure when Cmd has the value - "OMX_CommandMarkBuffer". - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup comp - */ -#define OMX_SendCommand( \ - hComponent, \ - Cmd, \ - nParam, \ - pCmdData) \ - ((OMX_COMPONENTTYPE*)hComponent)->SendCommand( \ - hComponent, \ - Cmd, \ - nParam, \ - pCmdData) /* Macro End */ - - -/** The OMX_GetParameter macro will get one of the current parameter - settings from the component. This macro cannot only be invoked when - the component is in the OMX_StateInvalid state. The nParamIndex - parameter is used to indicate which structure is being requested from - the component. The application shall allocate the correct structure - and shall fill in the structure size and version information before - invoking this macro. When the parameter applies to a port, the - caller shall fill in the appropriate nPortIndex value indicating the - port on which the parameter applies. If the component has not had - any settings changed, then the component should return a set of - valid DEFAULT parameters for the component. This is a blocking - call. - - The component should return from this call within 20 msec. - - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the OMX_GetHandle function. - @param [in] nParamIndex - Index of the structure to be filled. This value is from the - OMX_INDEXTYPE enumeration. - @param [in,out] pComponentParameterStructure - Pointer to application allocated structure to be filled by the - component. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup comp - */ -#define OMX_GetParameter( \ - hComponent, \ - nParamIndex, \ - pComponentParameterStructure) \ - ((OMX_COMPONENTTYPE*)hComponent)->GetParameter( \ - hComponent, \ - nParamIndex, \ - pComponentParameterStructure) /* Macro End */ - - -/** The OMX_SetParameter macro will send an initialization parameter - structure to a component. Each structure shall be sent one at a time, - in a separate invocation of the macro. This macro can only be - invoked when the component is in the OMX_StateLoaded state, or the - port is disabled (when the parameter applies to a port). The - nParamIndex parameter is used to indicate which structure is being - passed to the component. The application shall allocate the - correct structure and shall fill in the structure size and version - information (as well as the actual data) before invoking this macro. - The application is free to dispose of this structure after the call - as the component is required to copy any data it shall retain. This - is a blocking call. - - The component should return from this call within 20 msec. - - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the OMX_GetHandle function. - @param [in] nIndex - Index of the structure to be sent. This value is from the - OMX_INDEXTYPE enumeration. - @param [in] pComponentParameterStructure - pointer to application allocated structure to be used for - initialization by the component. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup comp - */ -#define OMX_SetParameter( \ - hComponent, \ - nParamIndex, \ - pComponentParameterStructure) \ - ((OMX_COMPONENTTYPE*)hComponent)->SetParameter( \ - hComponent, \ - nParamIndex, \ - pComponentParameterStructure) /* Macro End */ - - -/** The OMX_GetConfig macro will get one of the configuration structures - from a component. This macro can be invoked anytime after the - component has been loaded. The nParamIndex call parameter is used to - indicate which structure is being requested from the component. The - application shall allocate the correct structure and shall fill in the - structure size and version information before invoking this macro. - If the component has not had this configuration parameter sent before, - then the component should return a set of valid DEFAULT values for the - component. This is a blocking call. - - The component should return from this call within 5 msec. - - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the OMX_GetHandle function. - @param [in] nIndex - Index of the structure to be filled. This value is from the - OMX_INDEXTYPE enumeration. - @param [in,out] pComponentConfigStructure - pointer to application allocated structure to be filled by the - component. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup comp -*/ -#define OMX_GetConfig( \ - hComponent, \ - nConfigIndex, \ - pComponentConfigStructure) \ - ((OMX_COMPONENTTYPE*)hComponent)->GetConfig( \ - hComponent, \ - nConfigIndex, \ - pComponentConfigStructure) /* Macro End */ - - -/** The OMX_SetConfig macro will send one of the configuration - structures to a component. Each structure shall be sent one at a time, - each in a separate invocation of the macro. This macro can be invoked - anytime after the component has been loaded. The application shall - allocate the correct structure and shall fill in the structure size - and version information (as well as the actual data) before invoking - this macro. The application is free to dispose of this structure after - the call as the component is required to copy any data it shall retain. - This is a blocking call. - - The component should return from this call within 5 msec. - - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the OMX_GetHandle function. - @param [in] nConfigIndex - Index of the structure to be sent. This value is from the - OMX_INDEXTYPE enumeration above. - @param [in] pComponentConfigStructure - pointer to application allocated structure to be used for - initialization by the component. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup comp - */ -#define OMX_SetConfig( \ - hComponent, \ - nConfigIndex, \ - pComponentConfigStructure) \ - ((OMX_COMPONENTTYPE*)hComponent)->SetConfig( \ - hComponent, \ - nConfigIndex, \ - pComponentConfigStructure) /* Macro End */ - - -/** The OMX_GetExtensionIndex macro will invoke a component to translate - a vendor specific configuration or parameter string into an OMX - structure index. There is no requirement for the vendor to support - this command for the indexes already found in the OMX_INDEXTYPE - enumeration (this is done to save space in small components). The - component shall support all vendor supplied extension indexes not found - in the master OMX_INDEXTYPE enumeration. This is a blocking call. - - The component should return from this call within 5 msec. - - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the GetHandle function. - @param [in] cParameterName - OMX_STRING that shall be less than 128 characters long including - the trailing null byte. This is the string that will get - translated by the component into a configuration index. - @param [out] pIndexType - a pointer to a OMX_INDEXTYPE to receive the index value. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup comp - */ -#define OMX_GetExtensionIndex( \ - hComponent, \ - cParameterName, \ - pIndexType) \ - ((OMX_COMPONENTTYPE*)hComponent)->GetExtensionIndex( \ - hComponent, \ - cParameterName, \ - pIndexType) /* Macro End */ - - -/** The OMX_GetState macro will invoke the component to get the current - state of the component and place the state value into the location - pointed to by pState. - - The component should return from this call within 5 msec. - - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the OMX_GetHandle function. - @param [out] pState - pointer to the location to receive the state. The value returned - is one of the OMX_STATETYPE members - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup comp - */ -#define OMX_GetState( \ - hComponent, \ - pState) \ - ((OMX_COMPONENTTYPE*)hComponent)->GetState( \ - hComponent, \ - pState) /* Macro End */ - - -/** The OMX_UseBuffer macro will request that the component use - a buffer (and allocate its own buffer header) already allocated - by another component, or by the IL Client. This is a blocking - call. - - The component should return from this call within 20 msec. - - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the OMX_GetHandle function. - @param [out] ppBuffer - pointer to an OMX_BUFFERHEADERTYPE structure used to receive the - pointer to the buffer header - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup comp buf - */ - -#define OMX_UseBuffer( \ - hComponent, \ - ppBufferHdr, \ - nPortIndex, \ - pAppPrivate, \ - nSizeBytes, \ - pBuffer) \ - ((OMX_COMPONENTTYPE*)hComponent)->UseBuffer( \ - hComponent, \ - ppBufferHdr, \ - nPortIndex, \ - pAppPrivate, \ - nSizeBytes, \ - pBuffer) - - -/** The OMX_AllocateBuffer macro will request that the component allocate - a new buffer and buffer header. The component will allocate the - buffer and the buffer header and return a pointer to the buffer - header. This is a blocking call. - - The component should return from this call within 5 msec. - - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the OMX_GetHandle function. - @param [out] ppBuffer - pointer to an OMX_BUFFERHEADERTYPE structure used to receive - the pointer to the buffer header - @param [in] nPortIndex - nPortIndex is used to select the port on the component the buffer will - be used with. The port can be found by using the nPortIndex - value as an index into the Port Definition array of the component. - @param [in] pAppPrivate - pAppPrivate is used to initialize the pAppPrivate member of the - buffer header structure. - @param [in] nSizeBytes - size of the buffer to allocate. Used when bAllocateNew is true. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup comp buf - */ -#define OMX_AllocateBuffer( \ - hComponent, \ - ppBuffer, \ - nPortIndex, \ - pAppPrivate, \ - nSizeBytes) \ - ((OMX_COMPONENTTYPE*)hComponent)->AllocateBuffer( \ - hComponent, \ - ppBuffer, \ - nPortIndex, \ - pAppPrivate, \ - nSizeBytes) /* Macro End */ - - -/** The OMX_FreeBuffer macro will release a buffer header from the component - which was allocated using either OMX_AllocateBuffer or OMX_UseBuffer. If - the component allocated the buffer (see the OMX_UseBuffer macro) then - the component shall free the buffer and buffer header. This is a - blocking call. - - The component should return from this call within 20 msec. - - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the OMX_GetHandle function. - @param [in] nPortIndex - nPortIndex is used to select the port on the component the buffer will - be used with. - @param [in] pBuffer - pointer to an OMX_BUFFERHEADERTYPE structure allocated with UseBuffer - or AllocateBuffer. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup comp buf - */ -#define OMX_FreeBuffer( \ - hComponent, \ - nPortIndex, \ - pBuffer) \ - ((OMX_COMPONENTTYPE*)hComponent)->FreeBuffer( \ - hComponent, \ - nPortIndex, \ - pBuffer) /* Macro End */ - - -/** The OMX_EmptyThisBuffer macro will send a buffer full of data to an - input port of a component. The buffer will be emptied by the component - and returned to the application via the EmptyBufferDone call back. - This is a non-blocking call in that the component will record the buffer - and return immediately and then empty the buffer, later, at the proper - time. As expected, this macro may be invoked only while the component - is in the OMX_StateExecuting. If nPortIndex does not specify an input - port, the component shall return an error. - - The component should return from this call within 5 msec. - - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the OMX_GetHandle function. - @param [in] pBuffer - pointer to an OMX_BUFFERHEADERTYPE structure allocated with UseBuffer - or AllocateBuffer. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup comp buf - */ -#define OMX_EmptyThisBuffer( \ - hComponent, \ - pBuffer) \ - ((OMX_COMPONENTTYPE*)hComponent)->EmptyThisBuffer( \ - hComponent, \ - pBuffer) /* Macro End */ - - -/** The OMX_FillThisBuffer macro will send an empty buffer to an - output port of a component. The buffer will be filled by the component - and returned to the application via the FillBufferDone call back. - This is a non-blocking call in that the component will record the buffer - and return immediately and then fill the buffer, later, at the proper - time. As expected, this macro may be invoked only while the component - is in the OMX_ExecutingState. If nPortIndex does not specify an output - port, the component shall return an error. - - The component should return from this call within 5 msec. - - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the OMX_GetHandle function. - @param [in] pBuffer - pointer to an OMX_BUFFERHEADERTYPE structure allocated with UseBuffer - or AllocateBuffer. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup comp buf - */ -#define OMX_FillThisBuffer( \ - hComponent, \ - pBuffer) \ - ((OMX_COMPONENTTYPE*)hComponent)->FillThisBuffer( \ - hComponent, \ - pBuffer) /* Macro End */ - - - -/** The OMX_UseEGLImage macro will request that the component use - a EGLImage provided by EGL (and allocate its own buffer header) - This is a blocking call. - - The component should return from this call within 20 msec. - - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the OMX_GetHandle function. - @param [out] ppBuffer - pointer to an OMX_BUFFERHEADERTYPE structure used to receive the - pointer to the buffer header. Note that the memory location used - for this buffer is NOT visible to the IL Client. - @param [in] nPortIndex - nPortIndex is used to select the port on the component the buffer will - be used with. The port can be found by using the nPortIndex - value as an index into the Port Definition array of the component. - @param [in] pAppPrivate - pAppPrivate is used to initialize the pAppPrivate member of the - buffer header structure. - @param [in] eglImage - eglImage contains the handle of the EGLImage to use as a buffer on the - specified port. The component is expected to validate properties of - the EGLImage against the configuration of the port to ensure the component - can use the EGLImage as a buffer. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup comp buf - */ -#define OMX_UseEGLImage( \ - hComponent, \ - ppBufferHdr, \ - nPortIndex, \ - pAppPrivate, \ - eglImage) \ - ((OMX_COMPONENTTYPE*)hComponent)->UseEGLImage( \ - hComponent, \ - ppBufferHdr, \ - nPortIndex, \ - pAppPrivate, \ - eglImage) - -/** The OMX_Init method is used to initialize the OMX core. It shall be the - first call made into OMX and it should only be executed one time without - an interviening OMX_Deinit call. - - The core should return from this call within 20 msec. - - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup core - */ -OMX_API OMX_ERRORTYPE OMX_APIENTRY OMX_Init(void); - - -/** The OMX_Deinit method is used to deinitialize the OMX core. It shall be - the last call made into OMX. In the event that the core determines that - thare are components loaded when this call is made, the core may return - with an error rather than try to unload the components. - - The core should return from this call within 20 msec. - - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup core - */ -OMX_API OMX_ERRORTYPE OMX_APIENTRY OMX_Deinit(void); - - -/** The OMX_ComponentNameEnum method will enumerate through all the names of - recognised valid components in the system. This function is provided - as a means to detect all the components in the system run-time. There is - no strict ordering to the enumeration order of component names, although - each name will only be enumerated once. If the OMX core supports run-time - installation of new components, it is only requried to detect newly - installed components when the first call to enumerate component names - is made (i.e. when nIndex is 0x0). - - The core should return from this call in 20 msec. - - @param [out] cComponentName - pointer to a null terminated string with the component name. The - names of the components are strings less than 127 bytes in length - plus the trailing null for a maximum size of 128 bytes. An example - of a valid component name is "OMX.TI.AUDIO.DSP.MIXER\0". Names are - assigned by the vendor, but shall start with "OMX." and then have - the Vendor designation next. - @param [in] nNameLength - number of characters in the cComponentName string. With all - component name strings restricted to less than 128 characters - (including the trailing null) it is recomended that the caller - provide a input string for the cComponentName of 128 characters. - @param [in] nIndex - number containing the enumeration index for the component. - Multiple calls to OMX_ComponentNameEnum with increasing values - of nIndex will enumerate through the component names in the - system until OMX_ErrorNoMore is returned. The value of nIndex - is 0 to (N-1), where N is the number of valid installed components - in the system. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. When the value of nIndex exceeds the number of - components in the system minus 1, OMX_ErrorNoMore will be - returned. Otherwise the appropriate OMX error will be returned. - @ingroup core - */ -OMX_API OMX_ERRORTYPE OMX_APIENTRY OMX_ComponentNameEnum( - OMX_OUT OMX_STRING cComponentName, - OMX_IN OMX_U32 nNameLength, - OMX_IN OMX_U32 nIndex); - - -/** The OMX_GetHandle method will locate the component specified by the - component name given, load that component into memory and then invoke - the component's methods to create an instance of the component. - - The core should return from this call within 20 msec. - - @param [out] pHandle - pointer to an OMX_HANDLETYPE pointer to be filled in by this method. - @param [in] cComponentName - pointer to a null terminated string with the component name. The - names of the components are strings less than 127 bytes in length - plus the trailing null for a maximum size of 128 bytes. An example - of a valid component name is "OMX.TI.AUDIO.DSP.MIXER\0". Names are - assigned by the vendor, but shall start with "OMX." and then have - the Vendor designation next. - @param [in] pAppData - pointer to an application defined value that will be returned - during callbacks so that the application can identify the source - of the callback. - @param [in] pCallBacks - pointer to a OMX_CALLBACKTYPE structure that will be passed to the - component to initialize it with. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup core - */ -OMX_API OMX_ERRORTYPE OMX_APIENTRY OMX_GetHandle( - OMX_OUT OMX_HANDLETYPE* pHandle, - OMX_IN OMX_STRING cComponentName, - OMX_IN OMX_PTR pAppData, - OMX_IN OMX_CALLBACKTYPE* pCallBacks); - - -/** The OMX_FreeHandle method will free a handle allocated by the OMX_GetHandle - method. If the component reference count goes to zero, the component will - be unloaded from memory. - - The core should return from this call within 20 msec when the component is - in the OMX_StateLoaded state. - - @param [in] hComponent - Handle of the component to be accessed. This is the component - handle returned by the call to the GetHandle function. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - @ingroup core - */ -OMX_API OMX_ERRORTYPE OMX_APIENTRY OMX_FreeHandle( - OMX_IN OMX_HANDLETYPE hComponent); - - - -/** The OMX_SetupTunnel method will handle the necessary calls to the components - to setup the specified tunnel the two components. NOTE: This is - an actual method (not a #define macro). This method will make calls into - the component ComponentTunnelRequest method to do the actual tunnel - connection. - - The ComponentTunnelRequest method on both components will be called. - This method shall not be called unless the component is in the - OMX_StateLoaded state except when the ports used for the tunnel are - disabled. In this case, the component may be in the OMX_StateExecuting, - OMX_StatePause, or OMX_StateIdle states. - - The core should return from this call within 20 msec. - - @param [in] hOutput - Handle of the component to be accessed. Also this is the handle - of the component whose port, specified in the nPortOutput parameter - will be used the source for the tunnel. This is the component handle - returned by the call to the OMX_GetHandle function. There is a - requirement that hOutput be the source for the data when - tunelling (i.e. nPortOutput is an output port). If 0x0, the component - specified in hInput will have it's port specified in nPortInput - setup for communication with the application / IL client. - @param [in] nPortOutput - nPortOutput is used to select the source port on component to be - used in the tunnel. - @param [in] hInput - This is the component to setup the tunnel with. This is the handle - of the component whose port, specified in the nPortInput parameter - will be used the destination for the tunnel. This is the component handle - returned by the call to the OMX_GetHandle function. There is a - requirement that hInput be the destination for the data when - tunelling (i.e. nPortInut is an input port). If 0x0, the component - specified in hOutput will have it's port specified in nPortPOutput - setup for communication with the application / IL client. - @param [in] nPortInput - nPortInput is used to select the destination port on component to be - used in the tunnel. - @return OMX_ERRORTYPE - If the command successfully executes, the return code will be - OMX_ErrorNone. Otherwise the appropriate OMX error will be returned. - When OMX_ErrorNotImplemented is returned, one or both components is - a non-interop component and does not support tunneling. - - On failure, the ports of both components are setup for communication - with the application / IL Client. - @ingroup core tun - */ -OMX_API OMX_ERRORTYPE OMX_APIENTRY OMX_SetupTunnel( - OMX_IN OMX_HANDLETYPE hOutput, - OMX_IN OMX_U32 nPortOutput, - OMX_IN OMX_HANDLETYPE hInput, - OMX_IN OMX_U32 nPortInput); - -/** @ingroup cp */ -OMX_API OMX_ERRORTYPE OMX_GetContentPipe( - OMX_OUT OMX_HANDLETYPE *hPipe, - OMX_IN OMX_STRING szURI); - -/** The OMX_GetComponentsOfRole method will return the number of components that support the given - role and (if the compNames field is non-NULL) the names of those components. The call will fail if - an insufficiently sized array of names is supplied. To ensure the array is sufficiently sized the - client should: - * first call this function with the compNames field NULL to determine the number of component names - * second call this function with the compNames field pointing to an array of names allocated - according to the number returned by the first call. - - The core should return from this call within 5 msec. - - @param [in] role - This is generic standard component name consisting only of component class - name and the type within that class (e.g. 'audio_decoder.aac'). - @param [inout] pNumComps - This is used both as input and output. - - If compNames is NULL, the input is ignored and the output specifies how many components support - the given role. - - If compNames is not NULL, on input it bounds the size of the input structure and - on output, it specifies the number of components string names listed within the compNames parameter. - @param [inout] compNames - If NULL this field is ignored. If non-NULL this points to an array of 128-byte strings which accepts - a list of the names of all physical components that implement the specified standard component name. - Each name is NULL terminated. numComps indicates the number of names. - @ingroup core - */ -OMX_API OMX_ERRORTYPE OMX_GetComponentsOfRole ( - OMX_IN OMX_STRING role, - OMX_INOUT OMX_U32 *pNumComps, - OMX_INOUT OMX_U8 **compNames); - -/** The OMX_GetRolesOfComponent method will return the number of roles supported by the given - component and (if the roles field is non-NULL) the names of those roles. The call will fail if - an insufficiently sized array of names is supplied. To ensure the array is sufficiently sized the - client should: - * first call this function with the roles field NULL to determine the number of role names - * second call this function with the roles field pointing to an array of names allocated - according to the number returned by the first call. - - The core should return from this call within 5 msec. - - @param [in] compName - This is the name of the component being queried about. - @param [inout] pNumRoles - This is used both as input and output. - - If roles is NULL, the input is ignored and the output specifies how many roles the component supports. - - If compNames is not NULL, on input it bounds the size of the input structure and - on output, it specifies the number of roles string names listed within the roles parameter. - @param [out] roles - If NULL this field is ignored. If non-NULL this points to an array of 128-byte strings - which accepts a list of the names of all standard components roles implemented on the - specified component name. numComps indicates the number of names. - @ingroup core - */ -OMX_API OMX_ERRORTYPE OMX_GetRolesOfComponent ( - OMX_IN OMX_STRING compName, - OMX_INOUT OMX_U32 *pNumRoles, - OMX_OUT OMX_U8 **roles); - -#ifdef __cplusplus -} -#endif /* __cplusplus */ - -#endif -/* File EOF */ - diff --git a/selfdrive/frogpilot/screenrecorder/openmax/include/OMX_CoreExt.h b/selfdrive/frogpilot/screenrecorder/openmax/include/OMX_CoreExt.h deleted file mode 100644 index 3ec14b0..0000000 --- a/selfdrive/frogpilot/screenrecorder/openmax/include/OMX_CoreExt.h +++ /dev/null @@ -1,66 +0,0 @@ -/* - * Copyright (c) 2009 The Khronos Group Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining - * a copy of this software and associated documentation files (the - * "Software"), to deal in the Software without restriction, including - * without limitation the rights to use, copy, modify, merge, publish, - * distribute, sublicense, and/or sell copies of the Software, and to - * permit persons to whom the Software is furnished to do so, subject - * to the following conditions: - * The above copyright notice and this permission notice shall be included - * in all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS - * OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. - * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY - * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, - * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE - * SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - * - */ - -/** OMX_CoreExt.h - OpenMax IL version 1.1.2 - * The OMX_CoreExt header file contains extensions to the definitions used - * by both the application and the component to access common items. - */ - -#ifndef OMX_CoreExt_h -#define OMX_CoreExt_h - -#ifdef __cplusplus -extern "C" { -#endif /* __cplusplus */ - -/* Each OMX header shall include all required header files to allow the - * header to compile without errors. The includes below are required - * for this header file to compile successfully - */ -#include - - -/** Event type extensions. */ -typedef enum OMX_EVENTEXTTYPE -{ - OMX_EventIndexSettingChanged = OMX_EventKhronosExtensions, /**< component signals the IL client of a change - in a param, config, or extension */ - OMX_EventExtMax = 0x7FFFFFFF -} OMX_EVENTEXTTYPE; - - -/** Enable or disable a callback event. */ -typedef struct OMX_CONFIG_CALLBACKREQUESTTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_INDEXTYPE nIndex; /**< the index the callback is requested for */ - OMX_BOOL bEnable; /**< enable (OMX_TRUE) or disable (OMX_FALSE) the callback */ -} OMX_CONFIG_CALLBACKREQUESTTYPE; - -#ifdef __cplusplus -} -#endif /* __cplusplus */ - -#endif /* OMX_CoreExt_h */ -/* File EOF */ diff --git a/selfdrive/frogpilot/screenrecorder/openmax/include/OMX_IVCommon.h b/selfdrive/frogpilot/screenrecorder/openmax/include/OMX_IVCommon.h deleted file mode 100644 index ec71756..0000000 --- a/selfdrive/frogpilot/screenrecorder/openmax/include/OMX_IVCommon.h +++ /dev/null @@ -1,933 +0,0 @@ -/** - * Copyright (c) 2008 The Khronos Group Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining - * a copy of this software and associated documentation files (the - * "Software"), to deal in the Software without restriction, including - * without limitation the rights to use, copy, modify, merge, publish, - * distribute, sublicense, and/or sell copies of the Software, and to - * permit persons to whom the Software is furnished to do so, subject - * to the following conditions: - * The above copyright notice and this permission notice shall be included - * in all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS - * OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. - * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY - * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, - * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE - * SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - * - */ - -/** - * @file OMX_IVCommon.h - OpenMax IL version 1.1.2 - * The structures needed by Video and Image components to exchange - * parameters and configuration data with the components. - */ -#ifndef OMX_IVCommon_h -#define OMX_IVCommon_h - -#ifdef __cplusplus -extern "C" { -#endif /* __cplusplus */ - -/** - * Each OMX header must include all required header files to allow the header - * to compile without errors. The includes below are required for this header - * file to compile successfully - */ - -#include - -/** @defgroup iv OpenMAX IL Imaging and Video Domain - * Common structures for OpenMAX IL Imaging and Video domains - * @{ - */ - - -/** - * Enumeration defining possible uncompressed image/video formats. - * - * ENUMS: - * Unused : Placeholder value when format is N/A - * Monochrome : black and white - * 8bitRGB332 : Red 7:5, Green 4:2, Blue 1:0 - * 12bitRGB444 : Red 11:8, Green 7:4, Blue 3:0 - * 16bitARGB4444 : Alpha 15:12, Red 11:8, Green 7:4, Blue 3:0 - * 16bitARGB1555 : Alpha 15, Red 14:10, Green 9:5, Blue 4:0 - * 16bitRGB565 : Red 15:11, Green 10:5, Blue 4:0 - * 16bitBGR565 : Blue 15:11, Green 10:5, Red 4:0 - * 18bitRGB666 : Red 17:12, Green 11:6, Blue 5:0 - * 18bitARGB1665 : Alpha 17, Red 16:11, Green 10:5, Blue 4:0 - * 19bitARGB1666 : Alpha 18, Red 17:12, Green 11:6, Blue 5:0 - * 24bitRGB888 : Red 24:16, Green 15:8, Blue 7:0 - * 24bitBGR888 : Blue 24:16, Green 15:8, Red 7:0 - * 24bitARGB1887 : Alpha 23, Red 22:15, Green 14:7, Blue 6:0 - * 25bitARGB1888 : Alpha 24, Red 23:16, Green 15:8, Blue 7:0 - * 32bitBGRA8888 : Blue 31:24, Green 23:16, Red 15:8, Alpha 7:0 - * 32bitARGB8888 : Alpha 31:24, Red 23:16, Green 15:8, Blue 7:0 - * YUV411Planar : U,Y are subsampled by a factor of 4 horizontally - * YUV411PackedPlanar : packed per payload in planar slices - * YUV420Planar : Three arrays Y,U,V. - * YUV420PackedPlanar : packed per payload in planar slices - * YUV420SemiPlanar : Two arrays, one is all Y, the other is U and V - * YUV422Planar : Three arrays Y,U,V. - * YUV422PackedPlanar : packed per payload in planar slices - * YUV422SemiPlanar : Two arrays, one is all Y, the other is U and V - * YCbYCr : Organized as 16bit YUYV (i.e. YCbYCr) - * YCrYCb : Organized as 16bit YVYU (i.e. YCrYCb) - * CbYCrY : Organized as 16bit UYVY (i.e. CbYCrY) - * CrYCbY : Organized as 16bit VYUY (i.e. CrYCbY) - * YUV444Interleaved : Each pixel contains equal parts YUV - * RawBayer8bit : SMIA camera output format - * RawBayer10bit : SMIA camera output format - * RawBayer8bitcompressed : SMIA camera output format - */ -typedef enum OMX_COLOR_FORMATTYPE { - OMX_COLOR_FormatUnused, - OMX_COLOR_FormatMonochrome, - OMX_COLOR_Format8bitRGB332, - OMX_COLOR_Format12bitRGB444, - OMX_COLOR_Format16bitARGB4444, - OMX_COLOR_Format16bitARGB1555, - OMX_COLOR_Format16bitRGB565, - OMX_COLOR_Format16bitBGR565, - OMX_COLOR_Format18bitRGB666, - OMX_COLOR_Format18bitARGB1665, - OMX_COLOR_Format19bitARGB1666, - OMX_COLOR_Format24bitRGB888, - OMX_COLOR_Format24bitBGR888, - OMX_COLOR_Format24bitARGB1887, - OMX_COLOR_Format25bitARGB1888, - OMX_COLOR_Format32bitBGRA8888, - OMX_COLOR_Format32bitARGB8888, - OMX_COLOR_FormatYUV411Planar, - OMX_COLOR_FormatYUV411PackedPlanar, - OMX_COLOR_FormatYUV420Planar, - OMX_COLOR_FormatYUV420PackedPlanar, - OMX_COLOR_FormatYUV420SemiPlanar, - OMX_COLOR_FormatYUV422Planar, - OMX_COLOR_FormatYUV422PackedPlanar, - OMX_COLOR_FormatYUV422SemiPlanar, - OMX_COLOR_FormatYCbYCr, - OMX_COLOR_FormatYCrYCb, - OMX_COLOR_FormatCbYCrY, - OMX_COLOR_FormatCrYCbY, - OMX_COLOR_FormatYUV444Interleaved, - OMX_COLOR_FormatRawBayer8bit, - OMX_COLOR_FormatRawBayer10bit, - OMX_COLOR_FormatRawBayer8bitcompressed, - OMX_COLOR_FormatL2, - OMX_COLOR_FormatL4, - OMX_COLOR_FormatL8, - OMX_COLOR_FormatL16, - OMX_COLOR_FormatL24, - OMX_COLOR_FormatL32, - OMX_COLOR_FormatYUV420PackedSemiPlanar, - OMX_COLOR_FormatYUV422PackedSemiPlanar, - OMX_COLOR_Format18BitBGR666, - OMX_COLOR_Format24BitARGB6666, - OMX_COLOR_Format24BitABGR6666, - OMX_COLOR_FormatKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_COLOR_FormatVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - /** - -/** @defgroup imaging OpenMAX IL Imaging Domain - * @ingroup iv - * Structures for OpenMAX IL Imaging domain - * @{ - */ - -/** - * Enumeration used to define the possible image compression coding. - */ -typedef enum OMX_IMAGE_CODINGTYPE { - OMX_IMAGE_CodingUnused, /**< Value when format is N/A */ - OMX_IMAGE_CodingAutoDetect, /**< Auto detection of image format */ - OMX_IMAGE_CodingJPEG, /**< JPEG/JFIF image format */ - OMX_IMAGE_CodingJPEG2K, /**< JPEG 2000 image format */ - OMX_IMAGE_CodingEXIF, /**< EXIF image format */ - OMX_IMAGE_CodingTIFF, /**< TIFF image format */ - OMX_IMAGE_CodingGIF, /**< Graphics image format */ - OMX_IMAGE_CodingPNG, /**< PNG image format */ - OMX_IMAGE_CodingLZW, /**< LZW image format */ - OMX_IMAGE_CodingBMP, /**< Windows Bitmap format */ - OMX_IMAGE_CodingKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_IMAGE_CodingVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_IMAGE_CodingMax = 0x7FFFFFFF -} OMX_IMAGE_CODINGTYPE; - - -/** - * Data structure used to define an image path. The number of image paths - * for input and output will vary by type of the image component. - * - * Input (aka Source) : Zero Inputs, one Output, - * Splitter : One Input, 2 or more Outputs, - * Processing Element : One Input, one output, - * Mixer : 2 or more inputs, one output, - * Output (aka Sink) : One Input, zero outputs. - * - * The PortDefinition structure is used to define all of the parameters - * necessary for the compliant component to setup an input or an output - * image path. If additional vendor specific data is required, it should - * be transmitted to the component using the CustomCommand function. - * Compliant components will prepopulate this structure with optimal - * values during the OMX_GetParameter() command. - * - * STRUCT MEMBERS: - * cMIMEType : MIME type of data for the port - * pNativeRender : Platform specific reference for a display if a - * sync, otherwise this field is 0 - * nFrameWidth : Width of frame to be used on port if - * uncompressed format is used. Use 0 for - * unknown, don't care or variable - * nFrameHeight : Height of frame to be used on port if - * uncompressed format is used. Use 0 for - * unknown, don't care or variable - * nStride : Number of bytes per span of an image (i.e. - * indicates the number of bytes to get from - * span N to span N+1, where negative stride - * indicates the image is bottom up - * nSliceHeight : Height used when encoding in slices - * bFlagErrorConcealment : Turns on error concealment if it is supported by - * the OMX component - * eCompressionFormat : Compression format used in this instance of - * the component. When OMX_IMAGE_CodingUnused is - * specified, eColorFormat is valid - * eColorFormat : Decompressed format used by this component - * pNativeWindow : Platform specific reference for a window object if a - * display sink , otherwise this field is 0x0. - */ -typedef struct OMX_IMAGE_PORTDEFINITIONTYPE { - OMX_STRING cMIMEType; - OMX_NATIVE_DEVICETYPE pNativeRender; - OMX_U32 nFrameWidth; - OMX_U32 nFrameHeight; - OMX_S32 nStride; - OMX_U32 nSliceHeight; - OMX_BOOL bFlagErrorConcealment; - OMX_IMAGE_CODINGTYPE eCompressionFormat; - OMX_COLOR_FORMATTYPE eColorFormat; - OMX_NATIVE_WINDOWTYPE pNativeWindow; -} OMX_IMAGE_PORTDEFINITIONTYPE; - - -/** - * Port format parameter. This structure is used to enumerate the various - * data input/output format supported by the port. - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Indicates which port to set - * nIndex : Indicates the enumeration index for the format from - * 0x0 to N-1 - * eCompressionFormat : Compression format used in this instance of the - * component. When OMX_IMAGE_CodingUnused is specified, - * eColorFormat is valid - * eColorFormat : Decompressed format used by this component - */ -typedef struct OMX_IMAGE_PARAM_PORTFORMATTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nIndex; - OMX_IMAGE_CODINGTYPE eCompressionFormat; - OMX_COLOR_FORMATTYPE eColorFormat; -} OMX_IMAGE_PARAM_PORTFORMATTYPE; - - -/** - * Flash control type - * - * ENUMS - * Torch : Flash forced constantly on - */ -typedef enum OMX_IMAGE_FLASHCONTROLTYPE { - OMX_IMAGE_FlashControlOn = 0, - OMX_IMAGE_FlashControlOff, - OMX_IMAGE_FlashControlAuto, - OMX_IMAGE_FlashControlRedEyeReduction, - OMX_IMAGE_FlashControlFillin, - OMX_IMAGE_FlashControlTorch, - OMX_IMAGE_FlashControlKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_IMAGE_FlashControlVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_IMAGE_FlashControlMax = 0x7FFFFFFF -} OMX_IMAGE_FLASHCONTROLTYPE; - - -/** - * Flash control configuration - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * eFlashControl : Flash control type - */ -typedef struct OMX_IMAGE_PARAM_FLASHCONTROLTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_IMAGE_FLASHCONTROLTYPE eFlashControl; -} OMX_IMAGE_PARAM_FLASHCONTROLTYPE; - - -/** - * Focus control type - */ -typedef enum OMX_IMAGE_FOCUSCONTROLTYPE { - OMX_IMAGE_FocusControlOn = 0, - OMX_IMAGE_FocusControlOff, - OMX_IMAGE_FocusControlAuto, - OMX_IMAGE_FocusControlAutoLock, - OMX_IMAGE_FocusControlKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_IMAGE_FocusControlVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_IMAGE_FocusControlMax = 0x7FFFFFFF -} OMX_IMAGE_FOCUSCONTROLTYPE; - - -/** - * Focus control configuration - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * eFocusControl : Focus control - * nFocusSteps : Focus can take on values from 0 mm to infinity. - * Interest is only in number of steps over this range. - * nFocusStepIndex : Current focus step index - */ -typedef struct OMX_IMAGE_CONFIG_FOCUSCONTROLTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_IMAGE_FOCUSCONTROLTYPE eFocusControl; - OMX_U32 nFocusSteps; - OMX_U32 nFocusStepIndex; -} OMX_IMAGE_CONFIG_FOCUSCONTROLTYPE; - - -/** - * Q Factor for JPEG compression, which controls the tradeoff between image - * quality and size. Q Factor provides a more simple means of controlling - * JPEG compression quality, without directly programming Quantization - * tables for chroma and luma - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * nQFactor : JPEG Q factor value in the range of 1-100. A factor of 1 - * produces the smallest, worst quality images, and a factor - * of 100 produces the largest, best quality images. A - * typical default is 75 for small good quality images - */ -typedef struct OMX_IMAGE_PARAM_QFACTORTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nQFactor; -} OMX_IMAGE_PARAM_QFACTORTYPE; - -/** - * Quantization table type - */ - -typedef enum OMX_IMAGE_QUANTIZATIONTABLETYPE { - OMX_IMAGE_QuantizationTableLuma = 0, - OMX_IMAGE_QuantizationTableChroma, - OMX_IMAGE_QuantizationTableChromaCb, - OMX_IMAGE_QuantizationTableChromaCr, - OMX_IMAGE_QuantizationTableKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_IMAGE_QuantizationTableVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_IMAGE_QuantizationTableMax = 0x7FFFFFFF -} OMX_IMAGE_QUANTIZATIONTABLETYPE; - -/** - * JPEG quantization tables are used to determine DCT compression for - * YUV data, as an alternative to specifying Q factor, providing exact - * control of compression - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * eQuantizationTable : Quantization table type - * nQuantizationMatrix[64] : JPEG quantization table of coefficients stored - * in increasing columns then by rows of data (i.e. - * row 1, ... row 8). Quantization values are in - * the range 0-255 and stored in linear order - * (i.e. the component will zig-zag the - * quantization table data if required internally) - */ -typedef struct OMX_IMAGE_PARAM_QUANTIZATIONTABLETYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_IMAGE_QUANTIZATIONTABLETYPE eQuantizationTable; - OMX_U8 nQuantizationMatrix[64]; -} OMX_IMAGE_PARAM_QUANTIZATIONTABLETYPE; - - -/** - * Huffman table type, the same Huffman table is applied for chroma and - * luma component - */ -typedef enum OMX_IMAGE_HUFFMANTABLETYPE { - OMX_IMAGE_HuffmanTableAC = 0, - OMX_IMAGE_HuffmanTableDC, - OMX_IMAGE_HuffmanTableACLuma, - OMX_IMAGE_HuffmanTableACChroma, - OMX_IMAGE_HuffmanTableDCLuma, - OMX_IMAGE_HuffmanTableDCChroma, - OMX_IMAGE_HuffmanTableKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_IMAGE_HuffmanTableVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_IMAGE_HuffmanTableMax = 0x7FFFFFFF -} OMX_IMAGE_HUFFMANTABLETYPE; - -/** - * JPEG Huffman table - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * eHuffmanTable : Huffman table type - * nNumberOfHuffmanCodeOfLength[16] : 0-16, number of Huffman codes of each - * possible length - * nHuffmanTable[256] : 0-255, the size used for AC and DC - * HuffmanTable are 16 and 162 - */ -typedef struct OMX_IMAGE_PARAM_HUFFMANTTABLETYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_IMAGE_HUFFMANTABLETYPE eHuffmanTable; - OMX_U8 nNumberOfHuffmanCodeOfLength[16]; - OMX_U8 nHuffmanTable[256]; -}OMX_IMAGE_PARAM_HUFFMANTTABLETYPE; - -/** @} */ -#ifdef __cplusplus -} -#endif /* __cplusplus */ - -#endif -/* File EOF */ diff --git a/selfdrive/frogpilot/screenrecorder/openmax/include/OMX_Index.h b/selfdrive/frogpilot/screenrecorder/openmax/include/OMX_Index.h deleted file mode 100644 index a1f1748..0000000 --- a/selfdrive/frogpilot/screenrecorder/openmax/include/OMX_Index.h +++ /dev/null @@ -1,259 +0,0 @@ -/* - * Copyright (c) 2008 The Khronos Group Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining - * a copy of this software and associated documentation files (the - * "Software"), to deal in the Software without restriction, including - * without limitation the rights to use, copy, modify, merge, publish, - * distribute, sublicense, and/or sell copies of the Software, and to - * permit persons to whom the Software is furnished to do so, subject - * to the following conditions: - * The above copyright notice and this permission notice shall be included - * in all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS - * OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. - * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY - * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, - * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE - * SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - * - */ - -/** @file OMX_Index.h - OpenMax IL version 1.1.2 - * The OMX_Index header file contains the definitions for both applications - * and components . - */ - - -#ifndef OMX_Index_h -#define OMX_Index_h - -#ifdef __cplusplus -extern "C" { -#endif /* __cplusplus */ - - -/* Each OMX header must include all required header files to allow the - * header to compile without errors. The includes below are required - * for this header file to compile successfully - */ -#include - - -/** The OMX_INDEXTYPE enumeration is used to select a structure when either - * getting or setting parameters and/or configuration data. Each entry in - * this enumeration maps to an OMX specified structure. When the - * OMX_GetParameter, OMX_SetParameter, OMX_GetConfig or OMX_SetConfig methods - * are used, the second parameter will always be an entry from this enumeration - * and the third entry will be the structure shown in the comments for the entry. - * For example, if the application is initializing a cropping function, the - * OMX_SetConfig command would have OMX_IndexConfigCommonInputCrop as the second parameter - * and would send a pointer to an initialized OMX_RECTTYPE structure as the - * third parameter. - * - * The enumeration entries named with the OMX_Config prefix are sent using - * the OMX_SetConfig command and the enumeration entries named with the - * OMX_PARAM_ prefix are sent using the OMX_SetParameter command. - */ -typedef enum OMX_INDEXTYPE { - - OMX_IndexComponentStartUnused = 0x01000000, - OMX_IndexParamPriorityMgmt, /**< reference: OMX_PRIORITYMGMTTYPE */ - OMX_IndexParamAudioInit, /**< reference: OMX_PORT_PARAM_TYPE */ - OMX_IndexParamImageInit, /**< reference: OMX_PORT_PARAM_TYPE */ - OMX_IndexParamVideoInit, /**< reference: OMX_PORT_PARAM_TYPE */ - OMX_IndexParamOtherInit, /**< reference: OMX_PORT_PARAM_TYPE */ - OMX_IndexParamNumAvailableStreams, /**< reference: OMX_PARAM_U32TYPE */ - OMX_IndexParamActiveStream, /**< reference: OMX_PARAM_U32TYPE */ - OMX_IndexParamSuspensionPolicy, /**< reference: OMX_PARAM_SUSPENSIONPOLICYTYPE */ - OMX_IndexParamComponentSuspended, /**< reference: OMX_PARAM_SUSPENSIONTYPE */ - OMX_IndexConfigCapturing, /**< reference: OMX_CONFIG_BOOLEANTYPE */ - OMX_IndexConfigCaptureMode, /**< reference: OMX_CONFIG_CAPTUREMODETYPE */ - OMX_IndexAutoPauseAfterCapture, /**< reference: OMX_CONFIG_BOOLEANTYPE */ - OMX_IndexParamContentURI, /**< reference: OMX_PARAM_CONTENTURITYPE */ - OMX_IndexParamCustomContentPipe, /**< reference: OMX_PARAM_CONTENTPIPETYPE */ - OMX_IndexParamDisableResourceConcealment, /**< reference: OMX_RESOURCECONCEALMENTTYPE */ - OMX_IndexConfigMetadataItemCount, /**< reference: OMX_CONFIG_METADATAITEMCOUNTTYPE */ - OMX_IndexConfigContainerNodeCount, /**< reference: OMX_CONFIG_CONTAINERNODECOUNTTYPE */ - OMX_IndexConfigMetadataItem, /**< reference: OMX_CONFIG_METADATAITEMTYPE */ - OMX_IndexConfigCounterNodeID, /**< reference: OMX_CONFIG_CONTAINERNODEIDTYPE */ - OMX_IndexParamMetadataFilterType, /**< reference: OMX_PARAM_METADATAFILTERTYPE */ - OMX_IndexParamMetadataKeyFilter, /**< reference: OMX_PARAM_METADATAFILTERTYPE */ - OMX_IndexConfigPriorityMgmt, /**< reference: OMX_PRIORITYMGMTTYPE */ - OMX_IndexParamStandardComponentRole, /**< reference: OMX_PARAM_COMPONENTROLETYPE */ - - OMX_IndexPortStartUnused = 0x02000000, - OMX_IndexParamPortDefinition, /**< reference: OMX_PARAM_PORTDEFINITIONTYPE */ - OMX_IndexParamCompBufferSupplier, /**< reference: OMX_PARAM_BUFFERSUPPLIERTYPE */ - OMX_IndexReservedStartUnused = 0x03000000, - - /* Audio parameters and configurations */ - OMX_IndexAudioStartUnused = 0x04000000, - OMX_IndexParamAudioPortFormat, /**< reference: OMX_AUDIO_PARAM_PORTFORMATTYPE */ - OMX_IndexParamAudioPcm, /**< reference: OMX_AUDIO_PARAM_PCMMODETYPE */ - OMX_IndexParamAudioAac, /**< reference: OMX_AUDIO_PARAM_AACPROFILETYPE */ - OMX_IndexParamAudioRa, /**< reference: OMX_AUDIO_PARAM_RATYPE */ - OMX_IndexParamAudioMp3, /**< reference: OMX_AUDIO_PARAM_MP3TYPE */ - OMX_IndexParamAudioAdpcm, /**< reference: OMX_AUDIO_PARAM_ADPCMTYPE */ - OMX_IndexParamAudioG723, /**< reference: OMX_AUDIO_PARAM_G723TYPE */ - OMX_IndexParamAudioG729, /**< reference: OMX_AUDIO_PARAM_G729TYPE */ - OMX_IndexParamAudioAmr, /**< reference: OMX_AUDIO_PARAM_AMRTYPE */ - OMX_IndexParamAudioWma, /**< reference: OMX_AUDIO_PARAM_WMATYPE */ - OMX_IndexParamAudioSbc, /**< reference: OMX_AUDIO_PARAM_SBCTYPE */ - OMX_IndexParamAudioMidi, /**< reference: OMX_AUDIO_PARAM_MIDITYPE */ - OMX_IndexParamAudioGsm_FR, /**< reference: OMX_AUDIO_PARAM_GSMFRTYPE */ - OMX_IndexParamAudioMidiLoadUserSound, /**< reference: OMX_AUDIO_PARAM_MIDILOADUSERSOUNDTYPE */ - OMX_IndexParamAudioG726, /**< reference: OMX_AUDIO_PARAM_G726TYPE */ - OMX_IndexParamAudioGsm_EFR, /**< reference: OMX_AUDIO_PARAM_GSMEFRTYPE */ - OMX_IndexParamAudioGsm_HR, /**< reference: OMX_AUDIO_PARAM_GSMHRTYPE */ - OMX_IndexParamAudioPdc_FR, /**< reference: OMX_AUDIO_PARAM_PDCFRTYPE */ - OMX_IndexParamAudioPdc_EFR, /**< reference: OMX_AUDIO_PARAM_PDCEFRTYPE */ - OMX_IndexParamAudioPdc_HR, /**< reference: OMX_AUDIO_PARAM_PDCHRTYPE */ - OMX_IndexParamAudioTdma_FR, /**< reference: OMX_AUDIO_PARAM_TDMAFRTYPE */ - OMX_IndexParamAudioTdma_EFR, /**< reference: OMX_AUDIO_PARAM_TDMAEFRTYPE */ - OMX_IndexParamAudioQcelp8, /**< reference: OMX_AUDIO_PARAM_QCELP8TYPE */ - OMX_IndexParamAudioQcelp13, /**< reference: OMX_AUDIO_PARAM_QCELP13TYPE */ - OMX_IndexParamAudioEvrc, /**< reference: OMX_AUDIO_PARAM_EVRCTYPE */ - OMX_IndexParamAudioSmv, /**< reference: OMX_AUDIO_PARAM_SMVTYPE */ - OMX_IndexParamAudioVorbis, /**< reference: OMX_AUDIO_PARAM_VORBISTYPE */ - - OMX_IndexConfigAudioMidiImmediateEvent, /**< reference: OMX_AUDIO_CONFIG_MIDIIMMEDIATEEVENTTYPE */ - OMX_IndexConfigAudioMidiControl, /**< reference: OMX_AUDIO_CONFIG_MIDICONTROLTYPE */ - OMX_IndexConfigAudioMidiSoundBankProgram, /**< reference: OMX_AUDIO_CONFIG_MIDISOUNDBANKPROGRAMTYPE */ - OMX_IndexConfigAudioMidiStatus, /**< reference: OMX_AUDIO_CONFIG_MIDISTATUSTYPE */ - OMX_IndexConfigAudioMidiMetaEvent, /**< reference: OMX_AUDIO_CONFIG_MIDIMETAEVENTTYPE */ - OMX_IndexConfigAudioMidiMetaEventData, /**< reference: OMX_AUDIO_CONFIG_MIDIMETAEVENTDATATYPE */ - OMX_IndexConfigAudioVolume, /**< reference: OMX_AUDIO_CONFIG_VOLUMETYPE */ - OMX_IndexConfigAudioBalance, /**< reference: OMX_AUDIO_CONFIG_BALANCETYPE */ - OMX_IndexConfigAudioChannelMute, /**< reference: OMX_AUDIO_CONFIG_CHANNELMUTETYPE */ - OMX_IndexConfigAudioMute, /**< reference: OMX_AUDIO_CONFIG_MUTETYPE */ - OMX_IndexConfigAudioLoudness, /**< reference: OMX_AUDIO_CONFIG_LOUDNESSTYPE */ - OMX_IndexConfigAudioEchoCancelation, /**< reference: OMX_AUDIO_CONFIG_ECHOCANCELATIONTYPE */ - OMX_IndexConfigAudioNoiseReduction, /**< reference: OMX_AUDIO_CONFIG_NOISEREDUCTIONTYPE */ - OMX_IndexConfigAudioBass, /**< reference: OMX_AUDIO_CONFIG_BASSTYPE */ - OMX_IndexConfigAudioTreble, /**< reference: OMX_AUDIO_CONFIG_TREBLETYPE */ - OMX_IndexConfigAudioStereoWidening, /**< reference: OMX_AUDIO_CONFIG_STEREOWIDENINGTYPE */ - OMX_IndexConfigAudioChorus, /**< reference: OMX_AUDIO_CONFIG_CHORUSTYPE */ - OMX_IndexConfigAudioEqualizer, /**< reference: OMX_AUDIO_CONFIG_EQUALIZERTYPE */ - OMX_IndexConfigAudioReverberation, /**< reference: OMX_AUDIO_CONFIG_REVERBERATIONTYPE */ - OMX_IndexConfigAudioChannelVolume, /**< reference: OMX_AUDIO_CONFIG_CHANNELVOLUMETYPE */ - - /* Image specific parameters and configurations */ - OMX_IndexImageStartUnused = 0x05000000, - OMX_IndexParamImagePortFormat, /**< reference: OMX_IMAGE_PARAM_PORTFORMATTYPE */ - OMX_IndexParamFlashControl, /**< reference: OMX_IMAGE_PARAM_FLASHCONTROLTYPE */ - OMX_IndexConfigFocusControl, /**< reference: OMX_IMAGE_CONFIG_FOCUSCONTROLTYPE */ - OMX_IndexParamQFactor, /**< reference: OMX_IMAGE_PARAM_QFACTORTYPE */ - OMX_IndexParamQuantizationTable, /**< reference: OMX_IMAGE_PARAM_QUANTIZATIONTABLETYPE */ - OMX_IndexParamHuffmanTable, /**< reference: OMX_IMAGE_PARAM_HUFFMANTTABLETYPE */ - OMX_IndexConfigFlashControl, /**< reference: OMX_IMAGE_PARAM_FLASHCONTROLTYPE */ - - /* Video specific parameters and configurations */ - OMX_IndexVideoStartUnused = 0x06000000, - OMX_IndexParamVideoPortFormat, /**< reference: OMX_VIDEO_PARAM_PORTFORMATTYPE */ - OMX_IndexParamVideoQuantization, /**< reference: OMX_VIDEO_PARAM_QUANTIZATIONTYPE */ - OMX_IndexParamVideoFastUpdate, /**< reference: OMX_VIDEO_PARAM_VIDEOFASTUPDATETYPE */ - OMX_IndexParamVideoBitrate, /**< reference: OMX_VIDEO_PARAM_BITRATETYPE */ - OMX_IndexParamVideoMotionVector, /**< reference: OMX_VIDEO_PARAM_MOTIONVECTORTYPE */ - OMX_IndexParamVideoIntraRefresh, /**< reference: OMX_VIDEO_PARAM_INTRAREFRESHTYPE */ - OMX_IndexParamVideoErrorCorrection, /**< reference: OMX_VIDEO_PARAM_ERRORCORRECTIONTYPE */ - OMX_IndexParamVideoVBSMC, /**< reference: OMX_VIDEO_PARAM_VBSMCTYPE */ - OMX_IndexParamVideoMpeg2, /**< reference: OMX_VIDEO_PARAM_MPEG2TYPE */ - OMX_IndexParamVideoMpeg4, /**< reference: OMX_VIDEO_PARAM_MPEG4TYPE */ - OMX_IndexParamVideoWmv, /**< reference: OMX_VIDEO_PARAM_WMVTYPE */ - OMX_IndexParamVideoRv, /**< reference: OMX_VIDEO_PARAM_RVTYPE */ - OMX_IndexParamVideoAvc, /**< reference: OMX_VIDEO_PARAM_AVCTYPE */ - OMX_IndexParamVideoH263, /**< reference: OMX_VIDEO_PARAM_H263TYPE */ - OMX_IndexParamVideoProfileLevelQuerySupported, /**< reference: OMX_VIDEO_PARAM_PROFILELEVELTYPE */ - OMX_IndexParamVideoProfileLevelCurrent, /**< reference: OMX_VIDEO_PARAM_PROFILELEVELTYPE */ - OMX_IndexConfigVideoBitrate, /**< reference: OMX_VIDEO_CONFIG_BITRATETYPE */ - OMX_IndexConfigVideoFramerate, /**< reference: OMX_CONFIG_FRAMERATETYPE */ - OMX_IndexConfigVideoIntraVOPRefresh, /**< reference: OMX_CONFIG_INTRAREFRESHVOPTYPE */ - OMX_IndexConfigVideoIntraMBRefresh, /**< reference: OMX_CONFIG_MACROBLOCKERRORMAPTYPE */ - OMX_IndexConfigVideoMBErrorReporting, /**< reference: OMX_CONFIG_MBERRORREPORTINGTYPE */ - OMX_IndexParamVideoMacroblocksPerFrame, /**< reference: OMX_PARAM_MACROBLOCKSTYPE */ - OMX_IndexConfigVideoMacroBlockErrorMap, /**< reference: OMX_CONFIG_MACROBLOCKERRORMAPTYPE */ - OMX_IndexParamVideoSliceFMO, /**< reference: OMX_VIDEO_PARAM_AVCSLICEFMO */ - OMX_IndexConfigVideoAVCIntraPeriod, /**< reference: OMX_VIDEO_CONFIG_AVCINTRAPERIOD */ - OMX_IndexConfigVideoNalSize, /**< reference: OMX_VIDEO_CONFIG_NALSIZE */ - OMX_IndexConfigCommonDeinterlace, /**< reference: OMX_VIDEO_CONFIG_DEINTERLACE */ - - /* Image & Video common Configurations */ - OMX_IndexCommonStartUnused = 0x07000000, - OMX_IndexParamCommonDeblocking, /**< reference: OMX_PARAM_DEBLOCKINGTYPE */ - OMX_IndexParamCommonSensorMode, /**< reference: OMX_PARAM_SENSORMODETYPE */ - OMX_IndexParamCommonInterleave, /**< reference: OMX_PARAM_INTERLEAVETYPE */ - OMX_IndexConfigCommonColorFormatConversion, /**< reference: OMX_CONFIG_COLORCONVERSIONTYPE */ - OMX_IndexConfigCommonScale, /**< reference: OMX_CONFIG_SCALEFACTORTYPE */ - OMX_IndexConfigCommonImageFilter, /**< reference: OMX_CONFIG_IMAGEFILTERTYPE */ - OMX_IndexConfigCommonColorEnhancement, /**< reference: OMX_CONFIG_COLORENHANCEMENTTYPE */ - OMX_IndexConfigCommonColorKey, /**< reference: OMX_CONFIG_COLORKEYTYPE */ - OMX_IndexConfigCommonColorBlend, /**< reference: OMX_CONFIG_COLORBLENDTYPE */ - OMX_IndexConfigCommonFrameStabilisation,/**< reference: OMX_CONFIG_FRAMESTABTYPE */ - OMX_IndexConfigCommonRotate, /**< reference: OMX_CONFIG_ROTATIONTYPE */ - OMX_IndexConfigCommonMirror, /**< reference: OMX_CONFIG_MIRRORTYPE */ - OMX_IndexConfigCommonOutputPosition, /**< reference: OMX_CONFIG_POINTTYPE */ - OMX_IndexConfigCommonInputCrop, /**< reference: OMX_CONFIG_RECTTYPE */ - OMX_IndexConfigCommonOutputCrop, /**< reference: OMX_CONFIG_RECTTYPE */ - OMX_IndexConfigCommonDigitalZoom, /**< reference: OMX_CONFIG_SCALEFACTORTYPE */ - OMX_IndexConfigCommonOpticalZoom, /**< reference: OMX_CONFIG_SCALEFACTORTYPE*/ - OMX_IndexConfigCommonWhiteBalance, /**< reference: OMX_CONFIG_WHITEBALCONTROLTYPE */ - OMX_IndexConfigCommonExposure, /**< reference: OMX_CONFIG_EXPOSURECONTROLTYPE */ - OMX_IndexConfigCommonContrast, /**< reference: OMX_CONFIG_CONTRASTTYPE */ - OMX_IndexConfigCommonBrightness, /**< reference: OMX_CONFIG_BRIGHTNESSTYPE */ - OMX_IndexConfigCommonBacklight, /**< reference: OMX_CONFIG_BACKLIGHTTYPE */ - OMX_IndexConfigCommonGamma, /**< reference: OMX_CONFIG_GAMMATYPE */ - OMX_IndexConfigCommonSaturation, /**< reference: OMX_CONFIG_SATURATIONTYPE */ - OMX_IndexConfigCommonLightness, /**< reference: OMX_CONFIG_LIGHTNESSTYPE */ - OMX_IndexConfigCommonExclusionRect, /**< reference: OMX_CONFIG_RECTTYPE */ - OMX_IndexConfigCommonDithering, /**< reference: OMX_CONFIG_DITHERTYPE */ - OMX_IndexConfigCommonPlaneBlend, /**< reference: OMX_CONFIG_PLANEBLENDTYPE */ - OMX_IndexConfigCommonExposureValue, /**< reference: OMX_CONFIG_EXPOSUREVALUETYPE */ - OMX_IndexConfigCommonOutputSize, /**< reference: OMX_FRAMESIZETYPE */ - OMX_IndexParamCommonExtraQuantData, /**< reference: OMX_OTHER_EXTRADATATYPE */ - OMX_IndexConfigCommonFocusRegion, /**< reference: OMX_CONFIG_FOCUSREGIONTYPE */ - OMX_IndexConfigCommonFocusStatus, /**< reference: OMX_PARAM_FOCUSSTATUSTYPE */ - OMX_IndexConfigCommonTransitionEffect, /**< reference: OMX_CONFIG_TRANSITIONEFFECTTYPE */ - - /* Reserved Configuration range */ - OMX_IndexOtherStartUnused = 0x08000000, - OMX_IndexParamOtherPortFormat, /**< reference: OMX_OTHER_PARAM_PORTFORMATTYPE */ - OMX_IndexConfigOtherPower, /**< reference: OMX_OTHER_CONFIG_POWERTYPE */ - OMX_IndexConfigOtherStats, /**< reference: OMX_OTHER_CONFIG_STATSTYPE */ - - - /* Reserved Time range */ - OMX_IndexTimeStartUnused = 0x09000000, - OMX_IndexConfigTimeScale, /**< reference: OMX_TIME_CONFIG_SCALETYPE */ - OMX_IndexConfigTimeClockState, /**< reference: OMX_TIME_CONFIG_CLOCKSTATETYPE */ - OMX_IndexConfigTimeActiveRefClock, /**< reference: OMX_TIME_CONFIG_ACTIVEREFCLOCKTYPE */ - OMX_IndexConfigTimeCurrentMediaTime, /**< reference: OMX_TIME_CONFIG_TIMESTAMPTYPE (read only) */ - OMX_IndexConfigTimeCurrentWallTime, /**< reference: OMX_TIME_CONFIG_TIMESTAMPTYPE (read only) */ - OMX_IndexConfigTimeCurrentAudioReference, /**< reference: OMX_TIME_CONFIG_TIMESTAMPTYPE (write only) */ - OMX_IndexConfigTimeCurrentVideoReference, /**< reference: OMX_TIME_CONFIG_TIMESTAMPTYPE (write only) */ - OMX_IndexConfigTimeMediaTimeRequest, /**< reference: OMX_TIME_CONFIG_MEDIATIMEREQUESTTYPE (write only) */ - OMX_IndexConfigTimeClientStartTime, /** - - -/** Khronos standard extension indices. - -This enum lists the current Khronos extension indices to OpenMAX IL. -*/ -typedef enum OMX_INDEXEXTTYPE { - - /* Component parameters and configurations */ - OMX_IndexExtComponentStartUnused = OMX_IndexKhronosExtensions + 0x00100000, - OMX_IndexConfigCallbackRequest, /**< reference: OMX_CONFIG_CALLBACKREQUESTTYPE */ - OMX_IndexConfigCommitMode, /**< reference: OMX_CONFIG_COMMITMODETYPE */ - OMX_IndexConfigCommit, /**< reference: OMX_CONFIG_COMMITTYPE */ - - /* Port parameters and configurations */ - OMX_IndexExtPortStartUnused = OMX_IndexKhronosExtensions + 0x00200000, - - /* Audio parameters and configurations */ - OMX_IndexExtAudioStartUnused = OMX_IndexKhronosExtensions + 0x00400000, - - /* Image parameters and configurations */ - OMX_IndexExtImageStartUnused = OMX_IndexKhronosExtensions + 0x00500000, - - /* Video parameters and configurations */ - OMX_IndexExtVideoStartUnused = OMX_IndexKhronosExtensions + 0x00600000, - OMX_IndexParamNalStreamFormatSupported, /**< reference: OMX_NALSTREAMFORMATTYPE */ - OMX_IndexParamNalStreamFormat, /**< reference: OMX_NALSTREAMFORMATTYPE */ - OMX_IndexParamNalStreamFormatSelect, /**< reference: OMX_NALSTREAMFORMATTYPE */ - OMX_IndexParamVideoVp8, /**< reference: OMX_VIDEO_PARAM_VP8TYPE */ - OMX_IndexConfigVideoVp8ReferenceFrame, /**< reference: OMX_VIDEO_VP8REFERENCEFRAMETYPE */ - OMX_IndexConfigVideoVp8ReferenceFrameType, /**< reference: OMX_VIDEO_VP8REFERENCEFRAMEINFOTYPE */ - OMX_IndexParamVideoReserved, /**< Reserved for future index */ - OMX_IndexParamVideoHevc, /**< reference: OMX_VIDEO_PARAM_HEVCTYPE */ - - /* Image & Video common configurations */ - OMX_IndexExtCommonStartUnused = OMX_IndexKhronosExtensions + 0x00700000, - - /* Other configurations */ - OMX_IndexExtOtherStartUnused = OMX_IndexKhronosExtensions + 0x00800000, - OMX_IndexConfigAutoFramerateConversion, /**< reference: OMX_CONFIG_BOOLEANTYPE */ - OMX_IndexConfigPriority, /**< reference: OMX_PARAM_U32TYPE */ - OMX_IndexConfigOperatingRate, /**< reference: OMX_PARAM_U32TYPE in Q16 format for video and in Hz for audio */ - - /* Time configurations */ - OMX_IndexExtTimeStartUnused = OMX_IndexKhronosExtensions + 0x00900000, - - OMX_IndexExtMax = 0x7FFFFFFF -} OMX_INDEXEXTTYPE; - -#ifdef __cplusplus -} -#endif /* __cplusplus */ - -#endif /* OMX_IndexExt_h */ -/* File EOF */ diff --git a/selfdrive/frogpilot/screenrecorder/openmax/include/OMX_Other.h b/selfdrive/frogpilot/screenrecorder/openmax/include/OMX_Other.h deleted file mode 100644 index caf7f38..0000000 --- a/selfdrive/frogpilot/screenrecorder/openmax/include/OMX_Other.h +++ /dev/null @@ -1,337 +0,0 @@ -/* - * Copyright (c) 2008 The Khronos Group Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining - * a copy of this software and associated documentation files (the - * "Software"), to deal in the Software without restriction, including - * without limitation the rights to use, copy, modify, merge, publish, - * distribute, sublicense, and/or sell copies of the Software, and to - * permit persons to whom the Software is furnished to do so, subject - * to the following conditions: - * The above copyright notice and this permission notice shall be included - * in all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS - * OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. - * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY - * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, - * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE - * SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - * - */ - -/** @file OMX_Other.h - OpenMax IL version 1.1.2 - * The structures needed by Other components to exchange - * parameters and configuration data with the components. - */ - -#ifndef OMX_Other_h -#define OMX_Other_h - -#ifdef __cplusplus -extern "C" { -#endif /* __cplusplus */ - - -/* Each OMX header must include all required header files to allow the - * header to compile without errors. The includes below are required - * for this header file to compile successfully - */ - -#include - - -/** - * Enumeration of possible data types which match to multiple domains or no - * domain at all. For types which are vendor specific, a value above - * OMX_OTHER_VENDORTSTART should be used. - */ -typedef enum OMX_OTHER_FORMATTYPE { - OMX_OTHER_FormatTime = 0, /**< Transmission of various timestamps, elapsed time, - time deltas, etc */ - OMX_OTHER_FormatPower, /**< Perhaps used for enabling/disabling power - management, setting clocks? */ - OMX_OTHER_FormatStats, /**< Could be things such as frame rate, frames - dropped, etc */ - OMX_OTHER_FormatBinary, /**< Arbitrary binary data */ - OMX_OTHER_FormatVendorReserved = 1000, /**< Starting value for vendor specific - formats */ - - OMX_OTHER_FormatKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_OTHER_FormatVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_OTHER_FormatMax = 0x7FFFFFFF -} OMX_OTHER_FORMATTYPE; - -/** - * Enumeration of seek modes. - */ -typedef enum OMX_TIME_SEEKMODETYPE { - OMX_TIME_SeekModeFast = 0, /**< Prefer seeking to an approximation - * of the requested seek position over - * the actual seek position if it - * results in a faster seek. */ - OMX_TIME_SeekModeAccurate, /**< Prefer seeking to the actual seek - * position over an approximation - * of the requested seek position even - * if it results in a slower seek. */ - OMX_TIME_SeekModeKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_TIME_SeekModeVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_TIME_SeekModeMax = 0x7FFFFFFF -} OMX_TIME_SEEKMODETYPE; - -/* Structure representing the seekmode of the component */ -typedef struct OMX_TIME_CONFIG_SEEKMODETYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_TIME_SEEKMODETYPE eType; /**< The seek mode */ -} OMX_TIME_CONFIG_SEEKMODETYPE; - -/** Structure representing a time stamp used with the following configs - * on the Clock Component (CC): - * - * OMX_IndexConfigTimeCurrentWallTime: query of the CCs current wall - * time - * OMX_IndexConfigTimeCurrentMediaTime: query of the CCs current media - * time - * OMX_IndexConfigTimeCurrentAudioReference and - * OMX_IndexConfigTimeCurrentVideoReference: audio/video reference - * clock sending SC its reference time - * OMX_IndexConfigTimeClientStartTime: a Clock Component client sends - * this structure to the Clock Component via a SetConfig on its - * client port when it receives a buffer with - * OMX_BUFFERFLAG_STARTTIME set. It must use the timestamp - * specified by that buffer for nStartTimestamp. - * - * Its also used with the following config on components in general: - * - * OMX_IndexConfigTimePosition: IL client querying component position - * (GetConfig) or commanding a component to seek to the given location - * (SetConfig) - */ -typedef struct OMX_TIME_CONFIG_TIMESTAMPTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version - * information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_TICKS nTimestamp; /**< timestamp .*/ -} OMX_TIME_CONFIG_TIMESTAMPTYPE; - -/** Enumeration of possible reference clocks to the media time. */ -typedef enum OMX_TIME_UPDATETYPE { - OMX_TIME_UpdateRequestFulfillment, /**< Update is the fulfillment of a media time request. */ - OMX_TIME_UpdateScaleChanged, /**< Update was generated because the scale chagned. */ - OMX_TIME_UpdateClockStateChanged, /**< Update was generated because the clock state changed. */ - OMX_TIME_UpdateKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_TIME_UpdateVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_TIME_UpdateMax = 0x7FFFFFFF -} OMX_TIME_UPDATETYPE; - -/** Enumeration of possible reference clocks to the media time. */ -typedef enum OMX_TIME_REFCLOCKTYPE { - OMX_TIME_RefClockNone, /**< Use no references. */ - OMX_TIME_RefClockAudio, /**< Use references sent through OMX_IndexConfigTimeCurrentAudioReference */ - OMX_TIME_RefClockVideo, /**< Use references sent through OMX_IndexConfigTimeCurrentVideoReference */ - OMX_TIME_RefClockKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_TIME_RefClockVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_TIME_RefClockMax = 0x7FFFFFFF -} OMX_TIME_REFCLOCKTYPE; - -/** Enumeration of clock states. */ -typedef enum OMX_TIME_CLOCKSTATE { - OMX_TIME_ClockStateRunning, /**< Clock running. */ - OMX_TIME_ClockStateWaitingForStartTime, /**< Clock waiting until the - * prescribed clients emit their - * start time. */ - OMX_TIME_ClockStateStopped, /**< Clock stopped. */ - OMX_TIME_ClockStateKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_TIME_ClockStateVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_TIME_ClockStateMax = 0x7FFFFFFF -} OMX_TIME_CLOCKSTATE; - -/** Structure representing a media time request to the clock component. - * - * A client component sends this structure to the Clock Component via a SetConfig - * on its client port to specify a media timestamp the Clock Component - * should emit. The Clock Component should fulfill the request by sending a - * OMX_TIME_MEDIATIMETYPE when its media clock matches the requested - * timestamp. - * - * The client may require a media time request be fulfilled slightly - * earlier than the media time specified. In this case the client specifies - * an offset which is equal to the difference between wall time corresponding - * to the requested media time and the wall time when it will be - * fulfilled. - * - * A client component may uses these requests and the OMX_TIME_MEDIATIMETYPE to - * time events according to timestamps. If a client must perform an operation O at - * a time T (e.g. deliver a video frame at its corresponding timestamp), it makes a - * media time request at T (perhaps specifying an offset to ensure the request fulfillment - * is a little early). When the clock component passes the resulting OMX_TIME_MEDIATIMETYPE - * structure back to the client component, the client may perform operation O (perhaps having - * to wait a slight amount more time itself as specified by the return values). - */ - -typedef struct OMX_TIME_CONFIG_MEDIATIMEREQUESTTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< port that this structure applies to */ - OMX_PTR pClientPrivate; /**< Client private data to disabiguate this media time - * from others (e.g. the number of the frame to deliver). - * Duplicated in the media time structure that fulfills - * this request. A value of zero is reserved for time scale - * updates. */ - OMX_TICKS nMediaTimestamp; /**< Media timestamp requested.*/ - OMX_TICKS nOffset; /**< Amount of wall clock time by which this - * request should be fulfilled early */ -} OMX_TIME_CONFIG_MEDIATIMEREQUESTTYPE; - -/**< Structure sent from the clock component client either when fulfilling - * a media time request or when the time scale has changed. - * - * In the former case the Clock Component fills this structure and times its emission - * to a client component (via the client port) according to the corresponding media - * time request sent by the client. The Clock Component should time the emission to occur - * when the requested timestamp matches the Clock Component's media time but also the - * prescribed offset early. - * - * Upon scale changes the clock component clears the nClientPrivate data, sends the current - * media time and sets the nScale to the new scale via the client port. It emits a - * OMX_TIME_MEDIATIMETYPE to all clients independent of any requests. This allows clients to - * alter processing to accomodate scaling. For instance a video component might skip inter-frames - * in the case of extreme fastforward. Likewise an audio component might add or remove samples - * from an audio frame to scale audio data. - * - * It is expected that some clock components may not be able to fulfill requests - * at exactly the prescribed time. This is acceptable so long as the request is - * fulfilled at least as early as described and not later. This structure provides - * fields the client may use to wait for the remaining time. - * - * The client may use either the nOffset or nWallTimeAtMedia fields to determine the - * wall time until the nMediaTimestamp actually occurs. In the latter case the - * client can get a more accurate value for offset by getting the current wall - * from the cloc component and subtracting it from nWallTimeAtMedia. - */ - -typedef struct OMX_TIME_MEDIATIMETYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nClientPrivate; /**< Client private data to disabiguate this media time - * from others. Copied from the media time request. - * A value of zero is reserved for time scale updates. */ - OMX_TIME_UPDATETYPE eUpdateType; /**< Reason for the update */ - OMX_TICKS nMediaTimestamp; /**< Media time requested. If no media time was - * requested then this is the current media time. */ - OMX_TICKS nOffset; /**< Amount of wall clock time by which this - * request was actually fulfilled early */ - - OMX_TICKS nWallTimeAtMediaTime; /**< Wall time corresponding to nMediaTimeStamp. - * A client may compare this value to current - * media time obtained from the Clock Component to determine - * the wall time until the media timestamp is really - * current. */ - OMX_S32 xScale; /**< Current media time scale in Q16 format. */ - OMX_TIME_CLOCKSTATE eState; /* Seeking Change. Added 7/12.*/ - /**< State of the media time. */ -} OMX_TIME_MEDIATIMETYPE; - -/** Structure representing the current media time scale factor. Applicable only to clock - * component, other components see scale changes via OMX_TIME_MEDIATIMETYPE buffers sent via - * the clock component client ports. Upon recieving this config the clock component changes - * the rate by which the media time increases or decreases effectively implementing trick modes. - */ -typedef struct OMX_TIME_CONFIG_SCALETYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_S32 xScale; /**< This is a value in Q16 format which is used for - * scaling the media time */ -} OMX_TIME_CONFIG_SCALETYPE; - -/** Bits used to identify a clock port. Used in OMX_TIME_CONFIG_CLOCKSTATETYPEs nWaitMask field */ -#define OMX_CLOCKPORT0 0x00000001 -#define OMX_CLOCKPORT1 0x00000002 -#define OMX_CLOCKPORT2 0x00000004 -#define OMX_CLOCKPORT3 0x00000008 -#define OMX_CLOCKPORT4 0x00000010 -#define OMX_CLOCKPORT5 0x00000020 -#define OMX_CLOCKPORT6 0x00000040 -#define OMX_CLOCKPORT7 0x00000080 - -/** Structure representing the current mode of the media clock. - * IL Client uses this config to change or query the mode of the - * media clock of the clock component. Applicable only to clock - * component. - * - * On a SetConfig if eState is OMX_TIME_ClockStateRunning media time - * starts immediately at the prescribed start time. If - * OMX_TIME_ClockStateWaitingForStartTime the Clock Component ignores - * the given nStartTime and waits for all clients specified in the - * nWaitMask to send starttimes (via - * OMX_IndexConfigTimeClientStartTime). The Clock Component then starts - * the media clock using the earliest start time supplied. */ -typedef struct OMX_TIME_CONFIG_CLOCKSTATETYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version - * information */ - OMX_TIME_CLOCKSTATE eState; /**< State of the media time. */ - OMX_TICKS nStartTime; /**< Start time of the media time. */ - OMX_TICKS nOffset; /**< Time to offset the media time by - * (e.g. preroll). Media time will be - * reported to be nOffset ticks earlier. - */ - OMX_U32 nWaitMask; /**< Mask of OMX_CLOCKPORT values. */ -} OMX_TIME_CONFIG_CLOCKSTATETYPE; - -/** Structure representing the reference clock currently being used to - * compute media time. IL client uses this config to change or query the - * clock component's active reference clock */ -typedef struct OMX_TIME_CONFIG_ACTIVEREFCLOCKTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_TIME_REFCLOCKTYPE eClock; /**< Reference clock used to compute media time */ -} OMX_TIME_CONFIG_ACTIVEREFCLOCKTYPE; - -/** Descriptor for setting specifics of power type. - * Note: this structure is listed for backwards compatibility. */ -typedef struct OMX_OTHER_CONFIG_POWERTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_BOOL bEnablePM; /**< Flag to enable Power Management */ -} OMX_OTHER_CONFIG_POWERTYPE; - - -/** Descriptor for setting specifics of stats type. - * Note: this structure is listed for backwards compatibility. */ -typedef struct OMX_OTHER_CONFIG_STATSTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - /* what goes here */ -} OMX_OTHER_CONFIG_STATSTYPE; - - -/** - * The PortDefinition structure is used to define all of the parameters - * necessary for the compliant component to setup an input or an output other - * path. - */ -typedef struct OMX_OTHER_PORTDEFINITIONTYPE { - OMX_OTHER_FORMATTYPE eFormat; /**< Type of data expected for this channel */ -} OMX_OTHER_PORTDEFINITIONTYPE; - -/** Port format parameter. This structure is used to enumerate - * the various data input/output format supported by the port. - */ -typedef struct OMX_OTHER_PARAM_PORTFORMATTYPE { - OMX_U32 nSize; /**< size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< Indicates which port to set */ - OMX_U32 nIndex; /**< Indicates the enumeration index for the format from 0x0 to N-1 */ - OMX_OTHER_FORMATTYPE eFormat; /**< Type of data expected for this channel */ -} OMX_OTHER_PARAM_PORTFORMATTYPE; - -#ifdef __cplusplus -} -#endif /* __cplusplus */ - -#endif -/* File EOF */ diff --git a/selfdrive/frogpilot/screenrecorder/openmax/include/OMX_QCOMExtns.h b/selfdrive/frogpilot/screenrecorder/openmax/include/OMX_QCOMExtns.h deleted file mode 100644 index 2091793..0000000 --- a/selfdrive/frogpilot/screenrecorder/openmax/include/OMX_QCOMExtns.h +++ /dev/null @@ -1,1888 +0,0 @@ -/*-------------------------------------------------------------------------- -Copyright (c) 2009-2015, The Linux Foundation. All rights reserved. - -Redistribution and use in source and binary forms, with or without -modification, are permitted provided that the following conditions are met: - * Redistributions of source code must retain the above copyright - notice, this list of conditions and the following disclaimer. - * Redistributions in binary form must reproduce the above copyright - notice, this list of conditions and the following disclaimer in the - documentation and/or other materials provided with the distribution. - * Neither the name of The Linux Foundation nor - the names of its contributors may be used to endorse or promote - products derived from this software without specific prior written - permission. - -THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND -NON-INFRINGEMENT ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR -CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, -EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, -PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; -OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, -WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR -OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF -ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. ---------------------------------------------------------------------------*/ -#ifndef __OMX_QCOM_EXTENSIONS_H__ -#define __OMX_QCOM_EXTENSIONS_H__ - -#ifdef __cplusplus -extern "C" { -#endif /* __cplusplus */ - -/*============================================================================ -*//** @file OMX_QCOMExtns.h - This header contains constants and type definitions that specify the - extensions added to the OpenMAX Vendor specific APIs. - -*//*========================================================================*/ - - -/////////////////////////////////////////////////////////////////////////////// -// Include Files -/////////////////////////////////////////////////////////////////////////////// -#include "OMX_Core.h" -#include "OMX_Video.h" - -#define OMX_VIDEO_MAX_HP_LAYERS 6 -/** - * This extension is used to register mapping of a virtual - * address to a physical address. This extension is a parameter - * which can be set using the OMX_SetParameter macro. The data - * pointer corresponding to this extension is - * OMX_QCOM_MemMapEntry. This parameter is a 'write only' - * parameter (Current value cannot be queried using - * OMX_GetParameter macro). - */ -#define OMX_QCOM_EXTN_REGISTER_MMAP "OMX.QCOM.index.param.register_mmap" - -/** - * This structure describes the data pointer corresponding to - * the OMX_QCOM_MMAP_REGISTER_EXTN extension. This parameter - * must be set only 'after' populating a port with a buffer - * using OMX_UseBuffer, wherein the data pointer of the buffer - * corresponds to the virtual address as specified in this - * structure. - */ -struct OMX_QCOM_PARAM_MEMMAPENTRYTYPE -{ - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /**< OMX specification version information */ - OMX_U32 nPortIndex; /**< Port number the structure applies to */ - - /** - * The virtual address of memory block - */ - OMX_U64 nVirtualAddress; - - /** - * The physical address corresponding to the virtual address. The physical - * address is contiguous for the entire valid range of the virtual - * address. - */ - OMX_U64 nPhysicalAddress; -}; - -#define QOMX_VIDEO_IntraRefreshRandom (OMX_VIDEO_IntraRefreshVendorStartUnused + 0) - -/* This error event is used for H.264 long-term reference (LTR) encoding. - * When IL client specifies an LTR frame with its identifier via - * OMX_QCOM_INDEX_CONFIG_VIDEO_LTRUSE to the encoder, if the specified - * LTR frame can not be located by the encoder in its LTR list, the encoder - * issues this error event to IL client to notify the failure of LTRUse config. - */ -#define QOMX_ErrorLTRUseFailed (OMX_ErrorVendorStartUnused + 1) - -#define QOMX_VIDEO_BUFFERFLAG_BFRAME 0x00100000 - -#define QOMX_VIDEO_BUFFERFLAG_EOSEQ 0x00200000 - -#define QOMX_VIDEO_BUFFERFLAG_MBAFF 0x00400000 - -#define QOMX_VIDEO_BUFFERFLAG_CANCEL 0x00800000 - -#define OMX_QCOM_PORTDEFN_EXTN "OMX.QCOM.index.param.portdefn" -/* Allowed APIs on the above Index: OMX_GetParameter() and OMX_SetParameter() */ - -typedef enum OMX_QCOMMemoryRegion -{ - OMX_QCOM_MemRegionInvalid, - OMX_QCOM_MemRegionEBI1, - OMX_QCOM_MemRegionSMI, - OMX_QCOM_MemRegionMax = 0X7FFFFFFF -} OMX_QCOMMemoryRegion; - -typedef enum OMX_QCOMCacheAttr -{ - OMX_QCOM_CacheAttrNone, - OMX_QCOM_CacheAttrWriteBack, - OMX_QCOM_CacheAttrWriteThrough, - OMX_QCOM_CacheAttrMAX = 0X7FFFFFFF -} OMX_QCOMCacheAttr; - -typedef struct OMX_QCOMRectangle -{ - OMX_S32 x; - OMX_S32 y; - OMX_S32 dx; - OMX_S32 dy; -} OMX_QCOMRectangle; - -/** OMX_QCOMFramePackingFormat - * Input or output buffer format - */ -typedef enum OMX_QCOMFramePackingFormat -{ - /* 0 - unspecified - */ - OMX_QCOM_FramePacking_Unspecified, - - /* 1 - Partial frames may be present OMX IL 1.1.1 Figure 2-10: - * Case 1??Each Buffer Filled In Whole or In Part - */ - OMX_QCOM_FramePacking_Arbitrary, - - /* 2 - Multiple complete frames per buffer (integer number) - * OMX IL 1.1.1 Figure 2-11: Case 2Each Buffer Filled with - * Only Complete Frames of Data - */ - OMX_QCOM_FramePacking_CompleteFrames, - - /* 3 - Only one complete frame per buffer, no partial frame - * OMX IL 1.1.1 Figure 2-12: Case 3Each Buffer Filled with - * Only One Frame of Compressed Data. Usually at least one - * complete unit of data will be delivered in a buffer for - * uncompressed data formats. - */ - OMX_QCOM_FramePacking_OnlyOneCompleteFrame, - - /* 4 - Only one complete subframe per buffer, no partial subframe - * Example: In H264, one complete NAL per buffer, where one frame - * can contatin multiple NAL - */ - OMX_QCOM_FramePacking_OnlyOneCompleteSubFrame, - - OMX_QCOM_FramePacking_MAX = 0X7FFFFFFF -} OMX_QCOMFramePackingFormat; - -typedef struct OMX_QCOM_PARAM_PORTDEFINITIONTYPE { - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion;/** OMX specification version information */ - OMX_U32 nPortIndex; /** Portindex which is extended by this structure */ - - /** Platform specific memory region EBI1, SMI, etc.,*/ - OMX_QCOMMemoryRegion nMemRegion; - - OMX_QCOMCacheAttr nCacheAttr; /** Cache attributes */ - - /** Input or output buffer format */ - OMX_U32 nFramePackingFormat; - -} OMX_QCOM_PARAM_PORTDEFINITIONTYPE; - -typedef struct OMX_QCOM_VIDEO_PARAM_QPRANGETYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 minQP; - OMX_U32 maxQP; -} OMX_QCOM_VIDEO_PARAM_QPRANGETYPE; - -#define OMX_QCOM_PLATFORMPVT_EXTN "OMX.QCOM.index.param.platformprivate" -/** Allowed APIs on the above Index: OMX_SetParameter() */ - -typedef enum OMX_QCOM_PLATFORM_PRIVATE_ENTRY_TYPE -{ - /** Enum for PMEM information */ - OMX_QCOM_PLATFORM_PRIVATE_PMEM = 0x1 -} OMX_QCOM_PLATFORM_PRIVATE_ENTRY_TYPE; - -/** IL client will set the following structure. A failure - * code will be returned if component does not support the - * value provided for 'type'. - */ -struct OMX_QCOM_PLATFORMPRIVATE_EXTN -{ - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /** OMX spec version information */ - OMX_U32 nPortIndex; /** Port number on which usebuffer extn is applied */ - - /** Type of extensions should match an entry from - OMX_QCOM_PLATFORM_PRIVATE_ENTRY_TYPE - */ - OMX_QCOM_PLATFORM_PRIVATE_ENTRY_TYPE type; -}; - -typedef struct OMX_QCOM_PLATFORM_PRIVATE_PMEM_INFO -{ - /** pmem file descriptor */ - unsigned long pmem_fd; - /** Offset from pmem device base address */ - OMX_U32 offset; - OMX_U32 size; - OMX_U32 mapped_size; - OMX_PTR buffer; -}OMX_QCOM_PLATFORM_PRIVATE_PMEM_INFO; - -typedef struct OMX_QCOM_PLATFORM_PRIVATE_ENTRY -{ - /** Entry type */ - OMX_QCOM_PLATFORM_PRIVATE_ENTRY_TYPE type; - - /** Pointer to platform specific entry */ - OMX_PTR entry; -}OMX_QCOM_PLATFORM_PRIVATE_ENTRY; - -typedef struct OMX_QCOM_PLATFORM_PRIVATE_LIST -{ - /** Number of entries */ - OMX_U32 nEntries; - - /** Pointer to array of platform specific entries * - * Contiguous block of OMX_QCOM_PLATFORM_PRIVATE_ENTRY element - */ - OMX_QCOM_PLATFORM_PRIVATE_ENTRY* entryList; -}OMX_QCOM_PLATFORM_PRIVATE_LIST; - -#define OMX_QCOM_FRAME_PACKING_FORMAT "OMX.QCOM.index.param.framepackfmt" -/* Allowed API call: OMX_GetParameter() */ -/* IL client can use this index to rerieve the list of frame formats * - * supported by the component */ - -typedef struct OMX_QCOM_FRAME_PACKINGFORMAT_TYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nIndex; - OMX_QCOMFramePackingFormat eframePackingFormat; -} OMX_QCOM_FRAME_PACKINGFORMAT_TYPE; - - -/** - * Following is the enum for color formats supported on Qualcomm - * MSMs YVU420SemiPlanar color format is not defined in OpenMAX - * 1.1.1 and prior versions of OpenMAX specification. - */ - -enum OMX_QCOM_COLOR_FORMATTYPE -{ - -/** YVU420SemiPlanar: YVU planar format, organized with a first - * plane containing Y pixels, and a second plane containing - * interleaved V and U pixels. V and U pixels are sub-sampled - * by a factor of two both horizontally and vertically. - */ - QOMX_COLOR_FormatYVU420SemiPlanar = 0x7FA30C00, - QOMX_COLOR_FormatYVU420PackedSemiPlanar32m4ka, - QOMX_COLOR_FormatYUV420PackedSemiPlanar16m2ka, - QOMX_COLOR_FormatYUV420PackedSemiPlanar64x32Tile2m8ka, - QOMX_COLOR_FORMATYUV420PackedSemiPlanar32m, - QOMX_COLOR_FORMATYUV420PackedSemiPlanar32mMultiView, - QOMX_COLOR_FORMATYUV420PackedSemiPlanar32mCompressed, - QOMX_COLOR_Format32bitRGBA8888, - QOMX_COLOR_Format32bitRGBA8888Compressed, - QOMX_COLOR_FormatAndroidOpaque = (OMX_COLOR_FORMATTYPE) OMX_COLOR_FormatVendorStartUnused + 0x789, -}; - -enum OMX_QCOM_VIDEO_CODINGTYPE -{ -/** Codecs support by qualcomm which are not listed in OMX 1.1.x - * spec - * */ - OMX_QCOM_VIDEO_CodingVC1 = 0x7FA30C00 , - OMX_QCOM_VIDEO_CodingWMV9 = 0x7FA30C01, - QOMX_VIDEO_CodingDivx = 0x7FA30C02, /**< Value when coding is Divx */ - QOMX_VIDEO_CodingSpark = 0x7FA30C03, /**< Value when coding is Sorenson Spark */ - QOMX_VIDEO_CodingVp = 0x7FA30C04, - QOMX_VIDEO_CodingVp8 = OMX_VIDEO_CodingVP8, /**< keeping old enum for backwards compatibility*/ - QOMX_VIDEO_CodingHevc = OMX_VIDEO_CodingHEVC, /**< keeping old enum for backwards compatibility*/ - QOMX_VIDEO_CodingMVC = 0x7FA30C07, - QOMX_VIDEO_CodingVp9 = OMX_VIDEO_CodingVP9, /**< keeping old enum for backwards compatibility*/ -}; - -enum OMX_QCOM_EXTN_INDEXTYPE -{ - /** Qcom proprietary extension index list */ - - /* "OMX.QCOM.index.param.register_mmap" */ - OMX_QcomIndexRegmmap = 0x7F000000, - - /* "OMX.QCOM.index.param.platformprivate" */ - OMX_QcomIndexPlatformPvt = 0x7F000001, - - /* "OMX.QCOM.index.param.portdefn" */ - OMX_QcomIndexPortDefn = 0x7F000002, - - /* "OMX.QCOM.index.param.framepackingformat" */ - OMX_QcomIndexPortFramePackFmt = 0x7F000003, - - /*"OMX.QCOM.index.param.Interlaced */ - OMX_QcomIndexParamInterlaced = 0x7F000004, - - /*"OMX.QCOM.index.config.interlaceformat */ - OMX_QcomIndexConfigInterlaced = 0x7F000005, - - /*"OMX.QCOM.index.param.syntaxhdr" */ - QOMX_IndexParamVideoSyntaxHdr = 0x7F000006, - - /*"OMX.QCOM.index.config.intraperiod" */ - QOMX_IndexConfigVideoIntraperiod = 0x7F000007, - - /*"OMX.QCOM.index.config.randomIntrarefresh" */ - QOMX_IndexConfigVideoIntraRefresh = 0x7F000008, - - /*"OMX.QCOM.index.config.video.TemporalSpatialTradeOff" */ - QOMX_IndexConfigVideoTemporalSpatialTradeOff = 0x7F000009, - - /*"OMX.QCOM.index.param.video.EncoderMode" */ - QOMX_IndexParamVideoEncoderMode = 0x7F00000A, - - /*"OMX.QCOM.index.param.Divxtype */ - OMX_QcomIndexParamVideoDivx = 0x7F00000B, - - /*"OMX.QCOM.index.param.Sparktype */ - OMX_QcomIndexParamVideoSpark = 0x7F00000C, - - /*"OMX.QCOM.index.param.Vptype */ - OMX_QcomIndexParamVideoVp = 0x7F00000D, - - OMX_QcomIndexQueryNumberOfVideoDecInstance = 0x7F00000E, - - OMX_QcomIndexParamVideoSyncFrameDecodingMode = 0x7F00000F, - - OMX_QcomIndexParamVideoDecoderPictureOrder = 0x7F000010, - - /* "OMX.QCOM.index.config.video.FramePackingInfo" */ - OMX_QcomIndexConfigVideoFramePackingArrangement = 0x7F000011, - - OMX_QcomIndexParamConcealMBMapExtraData = 0x7F000012, - - OMX_QcomIndexParamFrameInfoExtraData = 0x7F000013, - - OMX_QcomIndexParamInterlaceExtraData = 0x7F000014, - - OMX_QcomIndexParamH264TimeInfo = 0x7F000015, - - OMX_QcomIndexParamIndexExtraDataType = 0x7F000016, - - OMX_GoogleAndroidIndexEnableAndroidNativeBuffers = 0x7F000017, - - OMX_GoogleAndroidIndexUseAndroidNativeBuffer = 0x7F000018, - - OMX_GoogleAndroidIndexGetAndroidNativeBufferUsage = 0x7F000019, - - /*"OMX.QCOM.index.config.video.QPRange" */ - OMX_QcomIndexConfigVideoQPRange = 0x7F00001A, - - /*"OMX.QCOM.index.param.EnableTimeStampReoder"*/ - OMX_QcomIndexParamEnableTimeStampReorder = 0x7F00001B, - - /*"OMX.google.android.index.storeMetaDataInBuffers"*/ - OMX_QcomIndexParamVideoMetaBufferMode = 0x7F00001C, - - /*"OMX.google.android.index.useAndroidNativeBuffer2"*/ - OMX_GoogleAndroidIndexUseAndroidNativeBuffer2 = 0x7F00001D, - - /*"OMX.QCOM.index.param.VideoMaxAllowedBitrateCheck"*/ - OMX_QcomIndexParamVideoMaxAllowedBitrateCheck = 0x7F00001E, - - OMX_QcomIndexEnableSliceDeliveryMode = 0x7F00001F, - - /* "OMX.QCOM.index.param.video.ExtnUserExtraData" */ - OMX_QcomIndexEnableExtnUserData = 0x7F000020, - - /*"OMX.QCOM.index.param.video.EnableSmoothStreaming"*/ - OMX_QcomIndexParamEnableSmoothStreaming = 0x7F000021, - - /*"OMX.QCOM.index.param.video.QPRange" */ - OMX_QcomIndexParamVideoQPRange = 0x7F000022, - - OMX_QcomIndexEnableH263PlusPType = 0x7F000023, - - /*"OMX.QCOM.index.param.video.LTRCountRangeSupported"*/ - QOMX_IndexParamVideoLTRCountRangeSupported = 0x7F000024, - - /*"OMX.QCOM.index.param.video.LTRMode"*/ - QOMX_IndexParamVideoLTRMode = 0x7F000025, - - /*"OMX.QCOM.index.param.video.LTRCount"*/ - QOMX_IndexParamVideoLTRCount = 0x7F000026, - - /*"OMX.QCOM.index.config.video.LTRPeriod"*/ - QOMX_IndexConfigVideoLTRPeriod = 0x7F000027, - - /*"OMX.QCOM.index.config.video.LTRUse"*/ - QOMX_IndexConfigVideoLTRUse = 0x7F000028, - - /*"OMX.QCOM.index.config.video.LTRMark"*/ - QOMX_IndexConfigVideoLTRMark = 0x7F000029, - - /* OMX.google.android.index.prependSPSPPSToIDRFrames */ - OMX_QcomIndexParamSequenceHeaderWithIDR = 0x7F00002A, - - OMX_QcomIndexParamH264AUDelimiter = 0x7F00002B, - - OMX_QcomIndexParamVideoDownScalar = 0x7F00002C, - - /* "OMX.QCOM.index.param.video.FramePackingExtradata" */ - OMX_QcomIndexParamVideoFramePackingExtradata = 0x7F00002D, - - /* "OMX.QCOM.index.config.activeregiondetection" */ - OMX_QcomIndexConfigActiveRegionDetection = 0x7F00002E, - - /* "OMX.QCOM.index.config.activeregiondetectionstatus" */ - OMX_QcomIndexConfigActiveRegionDetectionStatus = 0x7F00002F, - - /* "OMX.QCOM.index.config.scalingmode" */ - OMX_QcomIndexConfigScalingMode = 0x7F000030, - - /* "OMX.QCOM.index.config.noisereduction" */ - OMX_QcomIndexConfigNoiseReduction = 0x7F000031, - - /* "OMX.QCOM.index.config.imageenhancement" */ - OMX_QcomIndexConfigImageEnhancement = 0x7F000032, - - /* google smooth-streaming support */ - OMX_QcomIndexParamVideoAdaptivePlaybackMode = 0x7F000033, - - /* H.264 MVC codec index */ - QOMX_IndexParamVideoMvc = 0x7F000034, - - /* "OMX.QCOM.index.param.video.QPExtradata" */ - OMX_QcomIndexParamVideoQPExtraData = 0x7F000035, - - /* "OMX.QCOM.index.param.video.InputBitsInfoExtradata" */ - OMX_QcomIndexParamVideoInputBitsInfoExtraData = 0x7F000036, - - /* VP8 Hierarchical P support */ - OMX_QcomIndexHierarchicalStructure = 0x7F000037, - - OMX_QcomIndexParamPerfLevel = 0x7F000038, - - OMX_QcomIndexParamH264VUITimingInfo = 0x7F000039, - - OMX_QcomIndexParamPeakBitrate = 0x7F00003A, - - /* Enable InitialQP index */ - QOMX_IndexParamVideoInitialQp = 0x7F00003B, - - OMX_QcomIndexParamSetMVSearchrange = 0x7F00003C, - - OMX_QcomIndexConfigPerfLevel = 0x7F00003D, - - /*"OMX.QCOM.index.param.video.LTRCount"*/ - OMX_QcomIndexParamVideoLTRCount = QOMX_IndexParamVideoLTRCount, - - /*"OMX.QCOM.index.config.video.LTRUse"*/ - OMX_QcomIndexConfigVideoLTRUse = QOMX_IndexConfigVideoLTRUse, - - /*"OMX.QCOM.index.config.video.LTRMark"*/ - OMX_QcomIndexConfigVideoLTRMark = QOMX_IndexConfigVideoLTRMark, - - /*"OMX.QCOM.index.param.video.CustomBufferSize"*/ - OMX_QcomIndexParamVideoCustomBufferSize = 0x7F00003E, - - /* Max Hierarchical P layers */ - OMX_QcomIndexMaxHierarchicallayers = 0x7F000041, - - /* Set Encoder Performance Index */ - OMX_QcomIndexConfigVideoVencPerfMode = 0x7F000042, - - /* Set Hybrid Hier-p layers */ - OMX_QcomIndexParamVideoHybridHierpMode = 0x7F000043, - - OMX_QcomIndexFlexibleYUVDescription = 0x7F000044, - - /* Vpp Hqv Control Type */ - OMX_QcomIndexParamVppHqvControl = 0x7F000045, - - /* Enable VPP */ - OMX_QcomIndexParamEnableVpp = 0x7F000046, - - /* MBI statistics mode */ - OMX_QcomIndexParamMBIStatisticsMode = 0x7F000047, - - /* Set PictureTypeDecode */ - OMX_QcomIndexConfigPictureTypeDecode = 0x7F000048, - - OMX_QcomIndexConfigH264EntropyCodingCabac = 0x7F000049, - - /* "OMX.QCOM.index.param.video.InputBatch" */ - OMX_QcomIndexParamBatchSize = 0x7F00004A, - - OMX_QcomIndexConfigNumHierPLayers = 0x7F00004B, - - OMX_QcomIndexConfigRectType = 0x7F00004C, - - OMX_QcomIndexConfigBaseLayerId = 0x7F00004E, - - OMX_QcomIndexParamDriverVersion = 0x7F00004F, - - OMX_QcomIndexConfigQp = 0x7F000050, - - OMX_QcomIndexParamVencAspectRatio = 0x7F000051, - - OMX_QTIIndexParamVQZipSEIExtraData = 0x7F000052, - - /* Enable VQZIP SEI NAL type */ - OMX_QTIIndexParamVQZIPSEIType = 0x7F000053, - - OMX_QTIIndexParamPassInputBufferFd = 0x7F000054, - - /* Set Prefer-adaptive playback*/ - /* "OMX.QTI.index.param.video.PreferAdaptivePlayback" */ - OMX_QTIIndexParamVideoPreferAdaptivePlayback = 0x7F000055, - - /* Set time params */ - OMX_QTIIndexConfigSetTimeData = 0x7F000056, - /* Force Compressed format for DPB when resolution <=1080p - * and OPB is cpu_access */ - /* OMX.QTI.index.param.video.ForceCompressedForDPB */ - OMX_QTIIndexParamForceCompressedForDPB = 0x7F000057, - - /* Enable ROI info */ - OMX_QTIIndexParamVideoEnableRoiInfo = 0x7F000058, - - /* Configure ROI info */ - OMX_QTIIndexConfigVideoRoiInfo = 0x7F000059, - - /* Set Low Latency Mode */ - OMX_QTIIndexParamLowLatencyMode = 0x7F00005A, - - /* Force OPB to UnCompressed mode */ - OMX_QTIIndexParamForceUnCompressedForOPB = 0x7F00005B, - -}; - -/** -* This is custom extension to configure Low Latency Mode. -* -* STRUCT MEMBERS -* -* nSize : Size of Structure in bytes -* nVersion : OpenMAX IL specification version information -* bLowLatencyMode : Enable/Disable Low Latency mode -*/ - -typedef struct QOMX_EXTNINDEX_VIDEO_VENC_LOW_LATENCY_MODE -{ - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_BOOL bLowLatencyMode; -} QOMX_EXTNINDEX_VIDEO_VENC_LOW_LATENCY_MODE; - -/** -* This is custom extension to configure Encoder Aspect Ratio. -* -* STRUCT MEMBERS -* -* nSize : Size of Structure in bytes -* nVersion : OpenMAX IL specification version information -* nSARWidth : Horizontal aspect size -* nSARHeight : Vertical aspect size -*/ - -typedef struct QOMX_EXTNINDEX_VIDEO_VENC_SAR -{ - OMX_U32 nSize; - OMX_U32 nVersion; - OMX_U32 nSARWidth; - OMX_U32 nSARHeight; -} QOMX_EXTNINDEX_VIDEO_VENC_SAR; - -/** -* This is custom extension to configure Hier-p layers. -* This mode configures Hier-p layers dynamically. -* -* STRUCT MEMBERS -* -* nSize : Size of Structure in bytes -* nVersion : OpenMAX IL specification version information -* nNumHierLayers: Set the number of Hier-p layers for the session -* - This should be less than the MAX Hier-P -* layers set for the session. -*/ - -typedef struct QOMX_EXTNINDEX_VIDEO_HIER_P_LAYERS { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nNumHierLayers; -} QOMX_EXTNINDEX_VIDEO_HIER_P_LAYERS; - - -/** -* This is custom extension to configure Hybrid Hier-p settings. -* This mode is different from enabling Hier-p mode. This -* property enables Hier-p encoding with LTR referencing in each -* sub-GOP. -* -* STRUCT MEMBERS -* -* nSize : Size of Structure in bytes -* nVersion : OpenMAX IL specification version information -* nKeyFrameInterval : Indicates the I frame interval -* nHpLayers : Set the number of Hier-p layers for the session -* - This should be <= 6. (1 Base layer + -* 5 Enhancement layers) -* nTemporalLayerBitrateRatio[OMX_VIDEO_MAX_HP_LAYERS] : Bitrate to -* be set for each enhancement layer -* nMinQuantizer : minimum session QP -* nMaxQuantizer : Maximun session QP -*/ - -typedef struct QOMX_EXTNINDEX_VIDEO_HYBRID_HP_MODE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nKeyFrameInterval; - OMX_U32 nTemporalLayerBitrateRatio[OMX_VIDEO_MAX_HP_LAYERS]; - OMX_U32 nMinQuantizer; - OMX_U32 nMaxQuantizer; - OMX_U32 nHpLayers; -} QOMX_EXTNINDEX_VIDEO_HYBRID_HP_MODE; - -/** - * Encoder Performance Mode. This structure is used to set - * performance mode or power save mode when encoding. The search - * range is modified to save power or improve quality. - * - * STRUCT MEMBERS: - * OMX_U32 nPerfMode : Performance mode: - * 1: MAX_QUALITY - * 2: POWER_SAVE - */ - -typedef struct QOMX_EXTNINDEX_VIDEO_PERFMODE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPerfMode; -} QOMX_EXTNINDEX_VIDEO_PERFMODE; - -/** - * Initial QP parameter. This structure is used to enable - * vendor specific extension to let client enable setting - * initial QP values to I P B Frames - * - * STRUCT MEMBERS: - * nSize : Size of Structure in bytes - * nVersion : OpenMAX IL specification version information - * nPortIndex : Index of the port to which this structure applies - * OMX_U32 nQpI : First Iframe QP - * OMX_U32 nQpP : First Pframe QP - * OMX_U32 nQpB : First Bframe QP - * OMX_U32 bEnableInitQp : Bit field indicating which frame type(s) shall - * use the specified initial QP. - * Bit 0: Enable initial QP for I/IDR - * and use value specified in nInitQpI - * Bit 1: Enable initial QP for P - * and use value specified in nInitQpP - * Bit 2: Enable initial QP for B - * and use value specified in nInitQpB - */ - -typedef struct QOMX_EXTNINDEX_VIDEO_INITIALQP { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nQpI; - OMX_U32 nQpP; - OMX_U32 nQpB; - OMX_U32 bEnableInitQp; -} QOMX_EXTNINDEX_VIDEO_INITIALQP; - -/** - * Extension index parameter. This structure is used to enable - * vendor specific extension on input/output port and - * to pass the required flags and data, if any. - * The format of flags and data being passed is known to - * the client and component apriori. - * - * STRUCT MEMBERS: - * nSize : Size of Structure plus pData size - * nVersion : OMX specification version information - * nPortIndex : Indicates which port to set - * bEnable : Extension index enable (1) or disable (0) - * nFlags : Extension index flags, if any - * nDataSize : Size of the extension index data to follow - * pData : Extension index data, if present. - */ -typedef struct QOMX_EXTNINDEX_PARAMTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bEnable; - OMX_U32 nFlags; - OMX_U32 nDataSize; - OMX_PTR pData; -} QOMX_EXTNINDEX_PARAMTYPE; - -/** - * Range index parameter. This structure is used to enable - * vendor specific extension on input/output port and - * to pass the required minimum and maximum values - * - * STRUCT MEMBERS: - * nSize : Size of Structure in bytes - * nVersion : OpenMAX IL specification version information - * nPortIndex : Index of the port to which this structure applies - * nMin : Minimum value - * nMax : Maximum value - * nSteSize : Step size - */ -typedef struct QOMX_EXTNINDEX_RANGETYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_S32 nMin; - OMX_S32 nMax; - OMX_S32 nStepSize; -} QOMX_EXTNINDEX_RANGETYPE; - -/** - * Specifies LTR mode types. - */ -typedef enum QOMX_VIDEO_LTRMODETYPE -{ - QOMX_VIDEO_LTRMode_Disable = 0x0, /**< LTR encoding is disabled */ - QOMX_VIDEO_LTRMode_Manual = 0x1, /**< In this mode, IL client configures - ** the encoder the LTR count and manually - ** controls the marking and use of LTR - ** frames during video encoding. - */ - QOMX_VIDEO_LTRMode_Auto = 0x2, /**< In this mode, IL client configures - ** the encoder the LTR count and LTR - ** period. The encoder marks LTR frames - ** automatically based on the LTR period - ** during video encoding. IL client controls - ** the use of LTR frames. - */ - QOMX_VIDEO_LTRMode_MAX = 0x7FFFFFFF /** Maximum LTR Mode type */ -} QOMX_VIDEO_LTRMODETYPE; - -/** - * LTR mode index parameter. This structure is used - * to enable vendor specific extension on output port - * to pass the LTR mode information. - * - * STRUCT MEMBERS: - * nSize : Size of Structure in bytes - * nVersion : OpenMAX IL specification version information - * nPortIndex : Index of the port to which this structure applies - * eLTRMode : Specifies the LTR mode used in encoder - */ -typedef struct QOMX_VIDEO_PARAM_LTRMODE_TYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - QOMX_VIDEO_LTRMODETYPE eLTRMode; -} QOMX_VIDEO_PARAM_LTRMODE_TYPE; - -/** - * LTR count index parameter. This structure is used - * to enable vendor specific extension on output port - * to pass the LTR count information. - * - * STRUCT MEMBERS: - * nSize : Size of Structure in bytes - * nVersion : OpenMAX IL specification version information - * nPortIndex : Index of the port to which this structure applies - * nCount : Specifies the number of LTR frames stored in the - * encoder component - */ -typedef struct QOMX_VIDEO_PARAM_LTRCOUNT_TYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nCount; -} QOMX_VIDEO_PARAM_LTRCOUNT_TYPE; - - -/** - * This should be used with OMX_QcomIndexParamVideoLTRCount extension. - */ -typedef QOMX_VIDEO_PARAM_LTRCOUNT_TYPE OMX_QCOM_VIDEO_PARAM_LTRCOUNT_TYPE; - -/** - * LTR period index parameter. This structure is used - * to enable vendor specific extension on output port - * to pass the LTR period information. - * - * STRUCT MEMBERS: - * nSize : Size of Structure in bytes - * nVersion : OpenMAX IL specification version information - * nPortIndex : Index of the port to which this structure applies - * nFrames : Specifies the number of frames between two consecutive - * LTR frames. - */ -typedef struct QOMX_VIDEO_CONFIG_LTRPERIOD_TYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nFrames; -} QOMX_VIDEO_CONFIG_LTRPERIOD_TYPE; - -/** - * Marks the next encoded frame as an LTR frame. - * STRUCT MEMBERS: - * nSize : Size of Structure in bytes - * nVersion : OpenMAX IL specification version information - * nPortIndex : Index of the port to which this structure applies - * nID : Specifies the identifier of the LTR frame to be marked - * as reference frame for encoding subsequent frames. - */ -typedef struct QOMX_VIDEO_CONFIG_LTRMARK_TYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nID; -} QOMX_VIDEO_CONFIG_LTRMARK_TYPE; - -/** - * This should be used with OMX_QcomIndexConfigVideoLTRMark extension. - */ -typedef QOMX_VIDEO_CONFIG_LTRMARK_TYPE OMX_QCOM_VIDEO_CONFIG_LTRMARK_TYPE; - -/** - * Specifies an LTR frame to encode subsequent frames. - * STRUCT MEMBERS: - * nSize : Size of Structure in bytes - * nVersion : OpenMAX IL specification version information - * nPortIndex : Index of the port to which this structure applies - * nID : Specifies the identifier of the LTR frame to be used - as reference frame for encoding subsequent frames. - * nFrames : Specifies the number of subsequent frames to be - encoded using the LTR frame with its identifier - nID as reference frame. Short-term reference frames - will be used thereafter. The value of 0xFFFFFFFF - indicates that all subsequent frames will be - encodedusing this LTR frame as reference frame. - */ -typedef struct QOMX_VIDEO_CONFIG_LTRUSE_TYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nID; - OMX_U32 nFrames; -} QOMX_VIDEO_CONFIG_LTRUSE_TYPE; - -/** - * This should be used with OMX_QcomIndexConfigVideoLTRUse extension. - */ -typedef QOMX_VIDEO_CONFIG_LTRUSE_TYPE OMX_QCOM_VIDEO_CONFIG_LTRUSE_TYPE; - -/** - * Enumeration used to define the video encoder modes - * - * ENUMS: - * EncoderModeDefault : Default video recording mode. - * All encoder settings made through - * OMX_SetParameter/OMX_SetConfig are applied. No - * parameter is overridden. - * EncoderModeMMS : Video recording mode for MMS (Multimedia Messaging - * Service). This mode is similar to EncoderModeDefault - * except that here the Rate control mode is overridden - * internally and set as a variant of variable bitrate with - * variable frame rate. After this mode is set if the IL - * client tries to set OMX_VIDEO_CONTROLRATETYPE via - * OMX_IndexParamVideoBitrate that would be rejected. For - * this, client should set mode back to EncoderModeDefault - * first and then change OMX_VIDEO_CONTROLRATETYPE. - */ -typedef enum QOMX_VIDEO_ENCODERMODETYPE -{ - QOMX_VIDEO_EncoderModeDefault = 0x00, - QOMX_VIDEO_EncoderModeMMS = 0x01, - QOMX_VIDEO_EncoderModeMax = 0x7FFFFFFF -} QOMX_VIDEO_ENCODERMODETYPE; - -/** - * This structure is used to set the video encoder mode. - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version info - * nPortIndex : Port that this structure applies to - * nMode : defines the video encoder mode - */ -typedef struct QOMX_VIDEO_PARAM_ENCODERMODETYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - QOMX_VIDEO_ENCODERMODETYPE nMode; -} QOMX_VIDEO_PARAM_ENCODERMODETYPE; - -/** - * This structure describes the parameters corresponding to the - * QOMX_VIDEO_SYNTAXHDRTYPE extension. This parameter can be queried - * during the loaded state. - */ - -typedef struct QOMX_VIDEO_SYNTAXHDRTYPE -{ - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion;/** OMX specification version information */ - OMX_U32 nPortIndex; /** Portindex which is extended by this structure */ - OMX_U32 nBytes; /** The number of bytes filled in to the buffer */ - OMX_U8 data[1]; /** Buffer to store the header information */ -} QOMX_VIDEO_SYNTAXHDRTYPE; - -/** - * This structure describes the parameters corresponding to the - * QOMX_VIDEO_TEMPORALSPATIALTYPE extension. This parameter can be set - * dynamically during any state except the state invalid. This is primarily - * used for setting MaxQP from the application. This is set on the out port. - */ - -typedef struct QOMX_VIDEO_TEMPORALSPATIALTYPE -{ - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion;/** OMX specification version information */ - OMX_U32 nPortIndex; /** Portindex which is extended by this structure */ - OMX_U32 nTSFactor; /** Temoral spatial tradeoff factor value in 0-100 */ -} QOMX_VIDEO_TEMPORALSPATIALTYPE; - -/** - * This structure describes the parameters corresponding to the - * OMX_QCOM_VIDEO_CONFIG_INTRAPERIODTYPE extension. This parameter can be set - * dynamically during any state except the state invalid. This is set on the out port. - */ - -typedef struct QOMX_VIDEO_INTRAPERIODTYPE -{ - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion;/** OMX specification version information */ - OMX_U32 nPortIndex; /** Portindex which is extended by this structure */ - OMX_U32 nIDRPeriod; /** This specifies coding a frame as IDR after every nPFrames - of intra frames. If this parameter is set to 0, only the - first frame of the encode session is an IDR frame. This - field is ignored for non-AVC codecs and is used only for - codecs that support IDR Period */ - OMX_U32 nPFrames; /** The number of "P" frames between two "I" frames */ - OMX_U32 nBFrames; /** The number of "B" frames between two "I" frames */ -} QOMX_VIDEO_INTRAPERIODTYPE; - -/** - * This structure describes the parameters corresponding to the - * OMX_QCOM_VIDEO_CONFIG_ULBUFFEROCCUPANCYTYPE extension. This parameter can be set - * dynamically during any state except the state invalid. This is used for the buffer negotiation - * with other clients. This is set on the out port. - */ -typedef struct OMX_QCOM_VIDEO_CONFIG_ULBUFFEROCCUPANCYTYPE -{ - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /** OMX specification version information */ - OMX_U32 nPortIndex; /** Portindex which is extended by this structure */ - OMX_U32 nBufferOccupancy; /** The number of bytes to be set for the buffer occupancy */ -} OMX_QCOM_VIDEO_CONFIG_ULBUFFEROCCUPANCYTYPE; - -/** - * This structure describes the parameters corresponding to the - * OMX_QCOM_VIDEO_CONFIG_RANDOMINTRAREFRESHTYPE extension. This parameter can be set - * dynamically during any state except the state invalid. This is primarily used for the dynamic/random - * intrarefresh. This is set on the out port. - */ -typedef struct OMX_QCOM_VIDEO_CONFIG_RANDOMINTRAREFRESHTYPE -{ - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion;/** OMX specification version information */ - OMX_U32 nPortIndex; /** Portindex which is extended by this structure */ - OMX_U32 nRirMBs; /** The number of MBs to be set for intrarefresh */ -} OMX_QCOM_VIDEO_CONFIG_RANDOMINTRAREFRESHTYPE; - - -/** - * This structure describes the parameters corresponding to the - * OMX_QCOM_VIDEO_CONFIG_QPRANGE extension. This parameter can be set - * dynamically during any state except the state invalid. This is primarily - * used for the min/max QP to be set from the application. This - * is set on the out port. - */ -typedef struct OMX_QCOM_VIDEO_CONFIG_QPRANGE -{ - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion;/** OMX specification version information */ - OMX_U32 nPortIndex; /** Portindex which is extended by this structure */ - OMX_U32 nMinQP; /** The number for minimum quantization parameter */ - OMX_U32 nMaxQP; /** The number for maximum quantization parameter */ -} OMX_QCOM_VIDEO_CONFIG_QPRANGE; - -/** - * This structure describes the parameters for the - * OMX_QcomIndexParamH264AUDelimiter extension. It enables/disables - * the AU delimiters in the H264 stream, which is used by WFD. - */ -typedef struct OMX_QCOM_VIDEO_CONFIG_H264_AUD -{ - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion;/** OMX specification version information */ - OMX_BOOL bEnable; /** Enable/disable the setting */ -} OMX_QCOM_VIDEO_CONFIG_H264_AUD; - -typedef enum QOMX_VIDEO_PERF_LEVEL -{ - OMX_QCOM_PerfLevelNominal, - OMX_QCOM_PerfLevelTurbo -} QOMX_VIDEO_PERF_LEVEL; - -/** - * This structure describes the parameters corresponding - * to OMX_QcomIndexParamPerfLevel extension. It will set - * the performance mode specified as QOMX_VIDEO_PERF_LEVEL. - */ -typedef struct OMX_QCOM_VIDEO_PARAM_PERF_LEVEL { - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /** OMX specification version information */ - QOMX_VIDEO_PERF_LEVEL ePerfLevel; /** Performance level */ -} OMX_QCOM_VIDEO_PARAM_PERF_LEVEL; - -/** - * This structure describes the parameters corresponding - * to OMX_QcomIndexConfigPerfLevel extension. It will set - * the performance mode specified as QOMX_VIDEO_PERF_LEVEL. - */ -typedef struct OMX_QCOM_VIDEO_CONFIG_PERF_LEVEL { - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /** OMX specification version information */ - QOMX_VIDEO_PERF_LEVEL ePerfLevel; /** Performance level */ -} OMX_QCOM_VIDEO_CONFIG_PERF_LEVEL; - -typedef enum QOMX_VIDEO_PICTURE_TYPE_DECODE -{ - OMX_QCOM_PictypeDecode_IPB, - OMX_QCOM_PictypeDecode_I -} QOMX_VIDEO_PICTURE_TYPE_DECODE; - -/** - * This structure describes the parameters corresponding - * to OMX_QcomIndexConfigPictureTypeDecode extension. It - * will set the picture type decode specified by eDecodeType. - */ -typedef struct OMX_QCOM_VIDEO_CONFIG_PICTURE_TYPE_DECODE { - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /** OMX specification version information */ - QOMX_VIDEO_PICTURE_TYPE_DECODE eDecodeType; /** Decode type */ -} OMX_QCOM_VIDEO_CONFIG_PICTURE_TYPE_DECODE; - -/** - * This structure describes the parameters corresponding - * to OMX_QcomIndexParamH264VUITimingInfo extension. It - * will enable/disable the VUI timing info. - */ -typedef struct OMX_QCOM_VIDEO_PARAM_VUI_TIMING_INFO { - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /** OMX specification version information */ - OMX_BOOL bEnable; /** Enable/disable the setting */ -} OMX_QCOM_VIDEO_PARAM_VUI_TIMING_INFO; - -/** - * This structure describes the parameters corresponding - * to OMX_QcomIndexParamVQZIPSEIType extension. It - * will enable/disable the VQZIP SEI info. - */ -typedef struct OMX_QTI_VIDEO_PARAM_VQZIP_SEI_TYPE { - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /** OMX specification version information */ - OMX_BOOL bEnable; /** Enable/disable the setting */ -} OMX_QTI_VIDEO_PARAM_VQZIP_SEI_TYPE; - -/** - * This structure describes the parameters corresponding - * to OMX_QcomIndexParamPeakBitrate extension. It will - * set the peak bitrate specified by nPeakBitrate. - */ -typedef struct OMX_QCOM_VIDEO_PARAM_PEAK_BITRATE { - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /** OMX specification version information */ - OMX_U32 nPeakBitrate; /** Peak bitrate value */ -} OMX_QCOM_VIDEO_PARAM_PEAK_BITRATE; - -/** - * This structure describes the parameters corresponding - * to OMX_QTIIndexParamForceCompressedForDPB extension. Enabling - * this extension will force the split mode DPB(compressed)/OPB(Linear) - * for all resolutions.On some chipsets preferred mode would be combined - * Linear for both DPB/OPB to save memory. For example on 8996 preferred mode - * would be combined linear for resolutions <= 1080p . - * Enabling this might save power but with the cost - * of increased memory i.e almost double the number on output YUV buffers. - */ -typedef struct OMX_QTI_VIDEO_PARAM_FORCE_COMPRESSED_FOR_DPB_TYPE { - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion; /** OMX specification version information */ - OMX_BOOL bEnable; /** Enable/disable the setting */ -} OMX_QTI_VIDEO_PARAM_FORCE_COMPRESSED_FOR_DPB_TYPE; - -/** - * This structure describes the parameters corresponding - * to OMX_QTIIndexParamForceUnCompressedForOPB extension. Enabling this - * extension will force the OPB to be linear for the current video session. - * If this property is not set, then the OPB will be set to linear or compressed - * based on resolution selected and/or if cpu access is requested on the - * OPB buffer. - */ -typedef struct OMX_QTI_VIDEO_PARAM_FORCE_UNCOMPRESSED_FOR_OPB_TYPE { - OMX_U32 nSize; /** Sizeo f the structure in bytes */ - OMX_VERSIONTYPE nVersion; /** OMX specification version information */ - OMX_BOOL bEnable; /** Enable/disable the setting */ -} OMX_QTI_VIDEO_PARAM_FORCE_UNCOMPRESSED_FOR_OPB_TYPE; - -typedef struct OMX_VENDOR_EXTRADATATYPE { - OMX_U32 nPortIndex; - OMX_U32 nDataSize; - OMX_U8 *pData; // cdata (codec_data/extradata) -} OMX_VENDOR_EXTRADATATYPE; - -/** - * This structure describes the parameters corresponding to the - * OMX_VENDOR_VIDEOFRAMERATE extension. This parameter can be set - * dynamically during any state except the state invalid. This is - * used for frame rate to be set from the application. This - * is set on the in port. - */ -typedef struct OMX_VENDOR_VIDEOFRAMERATE { - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion;/** OMX specification version information */ - OMX_U32 nPortIndex; /** Portindex which is extended by this structure */ - OMX_U32 nFps; /** Frame rate value */ - OMX_BOOL bEnabled; /** Flag to enable or disable client's frame rate value */ -} OMX_VENDOR_VIDEOFRAMERATE; - -typedef enum OMX_INDEXVENDORTYPE { - OMX_IndexVendorFileReadInputFilename = 0xFF000001, - OMX_IndexVendorParser3gpInputFilename = 0xFF000002, - OMX_IndexVendorVideoExtraData = 0xFF000003, - OMX_IndexVendorAudioExtraData = 0xFF000004, - OMX_IndexVendorVideoFrameRate = 0xFF000005, -} OMX_INDEXVENDORTYPE; - -typedef enum OMX_QCOM_VC1RESOLUTIONTYPE -{ - OMX_QCOM_VC1_PICTURE_RES_1x1, - OMX_QCOM_VC1_PICTURE_RES_2x1, - OMX_QCOM_VC1_PICTURE_RES_1x2, - OMX_QCOM_VC1_PICTURE_RES_2x2 -} OMX_QCOM_VC1RESOLUTIONTYPE; - -typedef enum OMX_QCOM_INTERLACETYPE -{ - OMX_QCOM_InterlaceFrameProgressive, - OMX_QCOM_InterlaceInterleaveFrameTopFieldFirst, - OMX_QCOM_InterlaceInterleaveFrameBottomFieldFirst, - OMX_QCOM_InterlaceFrameTopFieldFirst, - OMX_QCOM_InterlaceFrameBottomFieldFirst, - OMX_QCOM_InterlaceFieldTop, - OMX_QCOM_InterlaceFieldBottom -}OMX_QCOM_INTERLACETYPE; - -typedef struct OMX_QCOM_PARAM_VIDEO_INTERLACETYPE -{ - OMX_U32 nSize; /** Size of the structure in bytes */ - OMX_VERSIONTYPE nVersion;/** OMX specification version information */ - OMX_U32 nPortIndex; /** Portindex which is extended by this structure */ - OMX_BOOL bInterlace; /** Interlace content **/ -}OMX_QCOM_PARAM_VIDEO_INTERLACETYPE; - -typedef struct OMX_QCOM_CONFIG_INTERLACETYPE -{ - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nIndex; - OMX_QCOM_INTERLACETYPE eInterlaceType; -}OMX_QCOM_CONFIG_INTERLACETYPE; - -#define MAX_PAN_SCAN_WINDOWS 4 - -typedef struct OMX_QCOM_PANSCAN -{ - OMX_U32 numWindows; - OMX_QCOMRectangle window[MAX_PAN_SCAN_WINDOWS]; -} OMX_QCOM_PANSCAN; - -typedef struct OMX_QCOM_ASPECT_RATIO -{ - OMX_U32 aspectRatioX; - OMX_U32 aspectRatioY; -} OMX_QCOM_ASPECT_RATIO; - -typedef struct OMX_QCOM_DISPLAY_ASPECT_RATIO -{ - OMX_U32 displayVerticalSize; - OMX_U32 displayHorizontalSize; -} OMX_QCOM_DISPLAY_ASPECT_RATIO; - -typedef struct OMX_QCOM_FRAME_PACK_ARRANGEMENT -{ - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 id; - OMX_U32 cancel_flag; - OMX_U32 type; - OMX_U32 quincunx_sampling_flag; - OMX_U32 content_interpretation_type; - OMX_U32 spatial_flipping_flag; - OMX_U32 frame0_flipped_flag; - OMX_U32 field_views_flag; - OMX_U32 current_frame_is_frame0_flag; - OMX_U32 frame0_self_contained_flag; - OMX_U32 frame1_self_contained_flag; - OMX_U32 frame0_grid_position_x; - OMX_U32 frame0_grid_position_y; - OMX_U32 frame1_grid_position_x; - OMX_U32 frame1_grid_position_y; - OMX_U32 reserved_byte; - OMX_U32 repetition_period; - OMX_U32 extension_flag; -} OMX_QCOM_FRAME_PACK_ARRANGEMENT; - -typedef struct OMX_QCOM_EXTRADATA_QP -{ - OMX_U32 nQP; -} OMX_QCOM_EXTRADATA_QP; - -typedef struct OMX_QCOM_EXTRADATA_BITS_INFO -{ - OMX_U32 header_bits; - OMX_U32 frame_bits; -} OMX_QCOM_EXTRADATA_BITS_INFO; - -typedef struct OMX_QCOM_EXTRADATA_USERDATA { - OMX_U32 type; - OMX_U32 data[1]; -} OMX_QCOM_EXTRADATA_USERDATA; - -typedef struct OMX_QCOM_EXTRADATA_FRAMEINFO -{ - // common frame meta data. interlace related info removed - OMX_VIDEO_PICTURETYPE ePicType; - OMX_QCOM_INTERLACETYPE interlaceType; - OMX_QCOM_PANSCAN panScan; - OMX_QCOM_ASPECT_RATIO aspectRatio; - OMX_QCOM_DISPLAY_ASPECT_RATIO displayAspectRatio; - OMX_U32 nConcealedMacroblocks; - OMX_U32 nFrameRate; - OMX_TICKS nTimeStamp; -} OMX_QCOM_EXTRADATA_FRAMEINFO; - -typedef struct OMX_QCOM_EXTRADATA_FRAMEDIMENSION -{ - /** Frame Dimensions added to each YUV buffer */ - OMX_U32 nDecWidth; /** Width rounded to multiple of 16 */ - OMX_U32 nDecHeight; /** Height rounded to multiple of 16 */ - OMX_U32 nActualWidth; /** Actual Frame Width */ - OMX_U32 nActualHeight; /** Actual Frame Height */ - -} OMX_QCOM_EXTRADATA_FRAMEDIMENSION; - -typedef struct OMX_QCOM_H264EXTRADATA -{ - OMX_U64 seiTimeStamp; -} OMX_QCOM_H264EXTRADATA; - -typedef struct OMX_QCOM_VC1EXTRADATA -{ - OMX_U32 nVC1RangeY; - OMX_U32 nVC1RangeUV; - OMX_QCOM_VC1RESOLUTIONTYPE eVC1PicResolution; -} OMX_QCOM_VC1EXTRADATA; - -typedef union OMX_QCOM_EXTRADATA_CODEC_DATA -{ - OMX_QCOM_H264EXTRADATA h264ExtraData; - OMX_QCOM_VC1EXTRADATA vc1ExtraData; -} OMX_QCOM_EXTRADATA_CODEC_DATA; - -typedef struct OMX_QCOM_EXTRADATA_MBINFO -{ - OMX_U32 nFormat; - OMX_U32 nDataSize; - OMX_U8 data[0]; -} OMX_QCOM_EXTRADATA_MBINFO; - -typedef struct OMX_QCOM_EXTRADATA_VQZIPSEI { - OMX_U32 nSize; - OMX_U8 data[0]; -} OMX_QCOM_EXTRADATA_VQZIPSEI; - -typedef struct OMX_QTI_VIDEO_PARAM_ENABLE_ROIINFO { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bEnableRoiInfo; -} OMX_QTI_VIDEO_PARAM_ENABLE_ROIINFO; - -typedef struct OMX_QTI_VIDEO_CONFIG_ROIINFO { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_S32 nUpperQpOffset; - OMX_S32 nLowerQpOffset; - OMX_BOOL bUseRoiInfo; - OMX_S32 nRoiMBInfoSize; - OMX_PTR pRoiMBInfo; -} OMX_QTI_VIDEO_CONFIG_ROIINFO; - -typedef enum OMX_QCOM_EXTRADATATYPE -{ - OMX_ExtraDataFrameInfo = 0x7F000001, - OMX_ExtraDataH264 = 0x7F000002, - OMX_ExtraDataVC1 = 0x7F000003, - OMX_ExtraDataFrameDimension = 0x7F000004, - OMX_ExtraDataVideoEncoderSliceInfo = 0x7F000005, - OMX_ExtraDataConcealMB = 0x7F000006, - OMX_ExtraDataInterlaceFormat = 0x7F000007, - OMX_ExtraDataPortDef = 0x7F000008, - OMX_ExtraDataMP2ExtnData = 0x7F000009, - OMX_ExtraDataMP2UserData = 0x7F00000a, - OMX_ExtraDataVideoLTRInfo = 0x7F00000b, - OMX_ExtraDataFramePackingArrangement = 0x7F00000c, - OMX_ExtraDataQP = 0x7F00000d, - OMX_ExtraDataInputBitsInfo = 0x7F00000e, - OMX_ExtraDataVideoEncoderMBInfo = 0x7F00000f, - OMX_ExtraDataVQZipSEI = 0x7F000010, -} OMX_QCOM_EXTRADATATYPE; - -typedef struct OMX_STREAMINTERLACEFORMATTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bInterlaceFormat; - OMX_U32 nInterlaceFormats; -} OMX_STREAMINTERLACEFORMAT; - -typedef enum OMX_INTERLACETYPE -{ - OMX_InterlaceFrameProgressive, - OMX_InterlaceInterleaveFrameTopFieldFirst, - OMX_InterlaceInterleaveFrameBottomFieldFirst, - OMX_InterlaceFrameTopFieldFirst, - OMX_InterlaceFrameBottomFieldFirst -} OMX_INTERLACES; - - -#define OMX_EXTRADATA_HEADER_SIZE 20 - -/** - * AVC profile types, each profile indicates support for various - * performance bounds and different annexes. - */ -typedef enum QOMX_VIDEO_AVCPROFILETYPE { - QOMX_VIDEO_AVCProfileBaseline = OMX_VIDEO_AVCProfileBaseline, - QOMX_VIDEO_AVCProfileMain = OMX_VIDEO_AVCProfileMain, - QOMX_VIDEO_AVCProfileExtended = OMX_VIDEO_AVCProfileExtended, - QOMX_VIDEO_AVCProfileHigh = OMX_VIDEO_AVCProfileHigh, - QOMX_VIDEO_AVCProfileHigh10 = OMX_VIDEO_AVCProfileHigh10, - QOMX_VIDEO_AVCProfileHigh422 = OMX_VIDEO_AVCProfileHigh422, - QOMX_VIDEO_AVCProfileHigh444 = OMX_VIDEO_AVCProfileHigh444, - /* QCom specific profile indexes */ - QOMX_VIDEO_AVCProfileConstrained = OMX_VIDEO_AVCProfileVendorStartUnused, - QOMX_VIDEO_AVCProfileConstrainedBaseline, - QOMX_VIDEO_AVCProfileConstrainedHigh, -} QOMX_VIDEO_AVCPROFILETYPE; - - -/** - * H.264 MVC Profiles - */ -typedef enum QOMX_VIDEO_MVCPROFILETYPE { - QOMX_VIDEO_MVCProfileStereoHigh = 0x1, - QOMX_VIDEO_MVCProfileMultiViewHigh = 0x2, - QOMX_VIDEO_MVCProfileKhronosExtensions = 0x6F000000, - QOMX_VIDEO_MVCProfileVendorStartUnused = 0x7F000000, - QOMX_VIDEO_MVCProfileMax = 0x7FFFFFFF -} QOMX_VIDEO_MVCPROFILETYPE; - -/** - * H.264 MVC Levels - */ -typedef enum QOMX_VIDEO_MVCLEVELTYPE { - QOMX_VIDEO_MVCLevel1 = 0x01, /**< Level 1 */ - QOMX_VIDEO_MVCLevel1b = 0x02, /**< Level 1b */ - QOMX_VIDEO_MVCLevel11 = 0x04, /**< Level 1.1 */ - QOMX_VIDEO_MVCLevel12 = 0x08, /**< Level 1.2 */ - QOMX_VIDEO_MVCLevel13 = 0x10, /**< Level 1.3 */ - QOMX_VIDEO_MVCLevel2 = 0x20, /**< Level 2 */ - QOMX_VIDEO_MVCLevel21 = 0x40, /**< Level 2.1 */ - QOMX_VIDEO_MVCLevel22 = 0x80, /**< Level 2.2 */ - QOMX_VIDEO_MVCLevel3 = 0x100, /**< Level 3 */ - QOMX_VIDEO_MVCLevel31 = 0x200, /**< Level 3.1 */ - QOMX_VIDEO_MVCLevel32 = 0x400, /**< Level 3.2 */ - QOMX_VIDEO_MVCLevel4 = 0x800, /**< Level 4 */ - QOMX_VIDEO_MVCLevel41 = 0x1000, /**< Level 4.1 */ - QOMX_VIDEO_MVCLevel42 = 0x2000, /**< Level 4.2 */ - QOMX_VIDEO_MVCLevel5 = 0x4000, /**< Level 5 */ - QOMX_VIDEO_MVCLevel51 = 0x8000, /**< Level 5.1 */ - QOMX_VIDEO_MVCLevelKhronosExtensions = 0x6F000000, - QOMX_VIDEO_MVCLevelVendorStartUnused = 0x7F000000, - QOMX_VIDEO_MVCLevelMax = 0x7FFFFFFF -} QOMX_VIDEO_MVCLEVELTYPE; - -/** - * DivX Versions - */ -typedef enum QOMX_VIDEO_DIVXFORMATTYPE { - QOMX_VIDEO_DIVXFormatUnused = 0x01, /**< Format unused or unknown */ - QOMX_VIDEO_DIVXFormat311 = 0x02, /**< DivX 3.11 */ - QOMX_VIDEO_DIVXFormat4 = 0x04, /**< DivX 4 */ - QOMX_VIDEO_DIVXFormat5 = 0x08, /**< DivX 5 */ - QOMX_VIDEO_DIVXFormat6 = 0x10, /**< DivX 6 */ - QOMX_VIDEO_DIVXFormatKhronosExtensions = 0x6F000000, - QOMX_VIDEO_DIVXFormatVendorStartUnused = 0x7F000000, - QOMX_VIDEO_DIVXFormatMax = 0x7FFFFFFF -} QOMX_VIDEO_DIVXFORMATTYPE; - -/** - * DivX profile types, each profile indicates support for - * various performance bounds. - */ -typedef enum QOMX_VIDEO_DIVXPROFILETYPE { - QOMX_VIDEO_DivXProfileqMobile = 0x01, /**< qMobile Profile */ - QOMX_VIDEO_DivXProfileMobile = 0x02, /**< Mobile Profile */ - QOMX_VIDEO_DivXProfileMT = 0x04, /**< Mobile Theatre Profile */ - QOMX_VIDEO_DivXProfileHT = 0x08, /**< Home Theatre Profile */ - QOMX_VIDEO_DivXProfileHD = 0x10, /**< High Definition Profile */ - QOMX_VIDEO_DIVXProfileKhronosExtensions = 0x6F000000, - QOMX_VIDEO_DIVXProfileVendorStartUnused = 0x7F000000, - QOMX_VIDEO_DIVXProfileMax = 0x7FFFFFFF -} QOMX_VIDEO_DIVXPROFILETYPE; - -/** - * DivX Video Params - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * eFormat : Version of DivX stream / data - * eProfile : Profile of DivX stream / data - */ -typedef struct QOMX_VIDEO_PARAM_DIVXTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - QOMX_VIDEO_DIVXFORMATTYPE eFormat; - QOMX_VIDEO_DIVXPROFILETYPE eProfile; -} QOMX_VIDEO_PARAM_DIVXTYPE; - - - -/** - * VP Versions - */ -typedef enum QOMX_VIDEO_VPFORMATTYPE { - QOMX_VIDEO_VPFormatUnused = 0x01, /**< Format unused or unknown */ - QOMX_VIDEO_VPFormat6 = 0x02, /**< VP6 Video Format */ - QOMX_VIDEO_VPFormat7 = 0x04, /**< VP7 Video Format */ - QOMX_VIDEO_VPFormat8 = 0x08, /**< VP8 Video Format */ - QOMX_VIDEO_VPFormat9 = 0x10, /**< VP9 Video Format */ - QOMX_VIDEO_VPFormatKhronosExtensions = 0x6F000000, - QOMX_VIDEO_VPFormatVendorStartUnused = 0x7F000000, - QOMX_VIDEO_VPFormatMax = 0x7FFFFFFF -} QOMX_VIDEO_VPFORMATTYPE; - -/** - * VP profile types, each profile indicates support for various - * encoding tools. - */ -typedef enum QOMX_VIDEO_VPPROFILETYPE { - QOMX_VIDEO_VPProfileSimple = 0x01, /**< Simple Profile, applies to VP6 only */ - QOMX_VIDEO_VPProfileAdvanced = 0x02, /**< Advanced Profile, applies to VP6 only */ - QOMX_VIDEO_VPProfileVersion0 = 0x04, /**< Version 0, applies to VP7 and VP8 */ - QOMX_VIDEO_VPProfileVersion1 = 0x08, /**< Version 1, applies to VP7 and VP8 */ - QOMX_VIDEO_VPProfileVersion2 = 0x10, /**< Version 2, applies to VP8 only */ - QOMX_VIDEO_VPProfileVersion3 = 0x20, /**< Version 3, applies to VP8 only */ - QOMX_VIDEO_VPProfileKhronosExtensions = 0x6F000000, - QOMX_VIDEO_VPProfileVendorStartUnused = 0x7F000000, - QOMX_VIDEO_VPProfileMax = 0x7FFFFFFF -} QOMX_VIDEO_VPPROFILETYPE; - -/** - * VP Video Params - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * eFormat : Format of VP stream / data - * eProfile : Profile or Version of VP stream / data - */ -typedef struct QOMX_VIDEO_PARAM_VPTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - QOMX_VIDEO_VPFORMATTYPE eFormat; - QOMX_VIDEO_VPPROFILETYPE eProfile; -} QOMX_VIDEO_PARAM_VPTYPE; - -/** - * Spark Versions - */ -typedef enum QOMX_VIDEO_SPARKFORMATTYPE { - QOMX_VIDEO_SparkFormatUnused = 0x01, /**< Format unused or unknown */ - QOMX_VIDEO_SparkFormat0 = 0x02, /**< Video Format Version 0 */ - QOMX_VIDEO_SparkFormat1 = 0x04, /**< Video Format Version 1 */ - QOMX_VIDEO_SparkFormatKhronosExtensions = 0x6F000000, - QOMX_VIDEO_SparkFormatVendorStartUnused = 0x7F000000, - QOMX_VIDEO_SparkFormatMax = 0x7FFFFFFF -} QOMX_VIDEO_SPARKFORMATTYPE; - -/** - * Spark Video Params - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * eFormat : Version of Spark stream / data - */ -typedef struct QOMX_VIDEO_PARAM_SPARKTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - QOMX_VIDEO_SPARKFORMATTYPE eFormat; -} QOMX_VIDEO_PARAM_SPARKTYPE; - - -typedef struct QOMX_VIDEO_QUERY_DECODER_INSTANCES { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nNumOfInstances; -} QOMX_VIDEO_QUERY_DECODER_INSTANCES; - -typedef struct QOMX_ENABLETYPE { - OMX_BOOL bEnable; -} QOMX_ENABLETYPE; - -typedef enum QOMX_VIDEO_EVENTS { - OMX_EventIndexsettingChanged = OMX_EventVendorStartUnused -} QOMX_VIDEO_EVENTS; - -typedef enum QOMX_VIDEO_PICTURE_ORDER { - QOMX_VIDEO_DISPLAY_ORDER = 0x1, - QOMX_VIDEO_DECODE_ORDER = 0x2 -} QOMX_VIDEO_PICTURE_ORDER; - -typedef struct QOMX_VIDEO_DECODER_PICTURE_ORDER { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - QOMX_VIDEO_PICTURE_ORDER eOutputPictureOrder; -} QOMX_VIDEO_DECODER_PICTURE_ORDER; - -typedef struct QOMX_INDEXEXTRADATATYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bEnabled; - OMX_INDEXTYPE nIndex; -} QOMX_INDEXEXTRADATATYPE; - -typedef struct QOMX_INDEXTIMESTAMPREORDER { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bEnable; -} QOMX_INDEXTIMESTAMPREORDER; - -typedef struct QOMX_INDEXDOWNSCALAR { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bEnable; -} QOMX_INDEXDOWNSCALAR; - -typedef struct QOMX_VIDEO_CUSTOM_BUFFERSIZE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nBufferSize; -} QOMX_VIDEO_CUSTOM_BUFFERSIZE; - -#define OMX_QCOM_INDEX_PARAM_VIDEO_SYNCFRAMEDECODINGMODE "OMX.QCOM.index.param.video.SyncFrameDecodingMode" -#define OMX_QCOM_INDEX_PARAM_INDEXEXTRADATA "OMX.QCOM.index.param.IndexExtraData" -#define OMX_QCOM_INDEX_PARAM_VIDEO_SLICEDELIVERYMODE "OMX.QCOM.index.param.SliceDeliveryMode" -#define OMX_QCOM_INDEX_PARAM_VIDEO_FRAMEPACKING_EXTRADATA "OMX.QCOM.index.param.video.FramePackingExtradata" -#define OMX_QCOM_INDEX_PARAM_VIDEO_QP_EXTRADATA "OMX.QCOM.index.param.video.QPExtradata" -#define OMX_QCOM_INDEX_PARAM_VIDEO_INPUTBITSINFO_EXTRADATA "OMX.QCOM.index.param.video.InputBitsInfoExtradata" -#define OMX_QCOM_INDEX_PARAM_VIDEO_EXTNUSER_EXTRADATA "OMX.QCOM.index.param.video.ExtnUserExtraData" -#define OMX_QCOM_INDEX_CONFIG_VIDEO_FRAMEPACKING_INFO "OMX.QCOM.index.config.video.FramePackingInfo" -#define OMX_QCOM_INDEX_PARAM_VIDEO_MPEG2SEQDISP_EXTRADATA "OMX.QCOM.index.param.video.Mpeg2SeqDispExtraData" - -#define OMX_QCOM_INDEX_PARAM_VIDEO_HIERSTRUCTURE "OMX.QCOM.index.param.video.HierStructure" -#define OMX_QCOM_INDEX_PARAM_VIDEO_LTRCOUNT "OMX.QCOM.index.param.video.LTRCount" -#define OMX_QCOM_INDEX_PARAM_VIDEO_LTRPERIOD "OMX.QCOM.index.param.video.LTRPeriod" -#define OMX_QCOM_INDEX_CONFIG_VIDEO_LTRUSE "OMX.QCOM.index.config.video.LTRUse" -#define OMX_QCOM_INDEX_CONFIG_VIDEO_LTRMARK "OMX.QCOM.index.config.video.LTRMark" -#define OMX_QCOM_INDEX_CONFIG_VIDEO_HIER_P_LAYERS "OMX.QCOM.index.config.video.hierplayers" -#define OMX_QCOM_INDEX_CONFIG_RECTANGLE_TYPE "OMX.QCOM.index.config.video.rectangle" -#define OMX_QCOM_INDEX_PARAM_VIDEO_BASE_LAYER_ID "OMX.QCOM.index.param.video.baselayerid" -#define OMX_QCOM_INDEX_CONFIG_VIDEO_QP "OMX.QCOM.index.config.video.qp" -#define OMX_QCOM_INDEX_PARAM_VIDEO_SAR "OMX.QCOM.index.param.video.sar" -#define OMX_QTI_INDEX_PARAM_VIDEO_LOW_LATENCY "OMX.QTI.index.param.video.LowLatency" - -#define OMX_QCOM_INDEX_PARAM_VIDEO_PASSINPUTBUFFERFD "OMX.QCOM.index.param.video.PassInputBufferFd" -#define OMX_QTI_INDEX_PARAM_VIDEO_PREFER_ADAPTIVE_PLAYBACK "OMX.QTI.index.param.video.PreferAdaptivePlayback" -#define OMX_QTI_INDEX_CONFIG_VIDEO_SETTIMEDATA "OMX.QTI.index.config.video.settimedata" -#define OMX_QTI_INDEX_PARAM_VIDEO_FORCE_COMPRESSED_FOR_DPB "OMX.QTI.index.param.video.ForceCompressedForDPB" -#define OMX_QTI_INDEX_PARAM_VIDEO_ENABLE_ROIINFO "OMX.QTI.index.param.enableRoiInfo" -#define OMX_QTI_INDEX_CONFIG_VIDEO_ROIINFO "OMX.QTI.index.config.RoiInfo" - -typedef enum { - QOMX_VIDEO_FRAME_PACKING_CHECKERBOARD = 0, - QOMX_VIDEO_FRAME_PACKING_COLUMN_INTERLEAVE = 1, - QOMX_VIDEO_FRAME_PACKING_ROW_INTERLEAVE = 2, - QOMX_VIDEO_FRAME_PACKING_SIDE_BY_SIDE = 3, - QOMX_VIDEO_FRAME_PACKING_TOP_BOTTOM = 4, - QOMX_VIDEO_FRAME_PACKING_TEMPORAL = 5, -} QOMX_VIDEO_FRAME_PACKING_ARRANGEMENT; - -typedef enum { - QOMX_VIDEO_CONTENT_UNSPECIFIED = 0, - QOMX_VIDEO_CONTENT_LR_VIEW = 1, - QOMX_VIDEO_CONTENT_RL_VIEW = 2, -} QOMX_VIDEO_CONTENT_INTERPRETATION; - -/** - * Specifies the extended picture types. These values should be - * OR'd along with the types defined in OMX_VIDEO_PICTURETYPE to - * signal all pictures types which are allowed. - * - * ENUMS: - * H.264 Specific Picture Types: IDR - */ -typedef enum QOMX_VIDEO_PICTURETYPE { - QOMX_VIDEO_PictureTypeIDR = OMX_VIDEO_PictureTypeVendorStartUnused + 0x1000 -} QOMX_VIDEO_PICTURETYPE; - -#define OMX_QCOM_INDEX_CONFIG_ACTIVE_REGION_DETECTION "OMX.QCOM.index.config.activeregiondetection" -#define OMX_QCOM_INDEX_CONFIG_ACTIVE_REGION_DETECTION_STATUS "OMX.QCOM.index.config.activeregiondetectionstatus" -#define OMX_QCOM_INDEX_CONFIG_SCALING_MODE "OMX.QCOM.index.config.scalingmode" -#define OMX_QCOM_INDEX_CONFIG_NOISEREDUCTION "OMX.QCOM.index.config.noisereduction" -#define OMX_QCOM_INDEX_CONFIG_IMAGEENHANCEMENT "OMX.QCOM.index.config.imageenhancement" -#define OMX_QCOM_INDEX_PARAM_HELDBUFFERCOUNT "OMX.QCOM.index.param.HeldBufferCount" /**< reference: QOMX_HELDBUFFERCOUNTTYPE */ - - -typedef struct QOMX_RECTTYPE { - OMX_S32 nLeft; - OMX_S32 nTop; - OMX_U32 nWidth; - OMX_U32 nHeight; -} QOMX_RECTTYPE; - -typedef struct QOMX_ACTIVEREGIONDETECTIONTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bEnable; - QOMX_RECTTYPE sROI; - OMX_U32 nNumExclusionRegions; - QOMX_RECTTYPE sExclusionRegions[1]; -} QOMX_ACTIVEREGIONDETECTIONTYPE; - -typedef struct QOMX_ACTIVEREGIONDETECTION_STATUSTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bDetected; - QOMX_RECTTYPE sDetectedRegion; -} QOMX_ACTIVEREGIONDETECTION_STATUSTYPE; - -typedef enum QOMX_SCALE_MODETYPE { - QOMX_SCALE_MODE_Normal, - QOMX_SCALE_MODE_Anamorphic, - QOMX_SCALE_MODE_Max = 0x7FFFFFFF -} QOMX_SCALE_MODETYPE; - -typedef struct QOMX_SCALINGMODETYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - QOMX_SCALE_MODETYPE eScaleMode; -} QOMX_SCALINGMODETYPE; - -typedef struct QOMX_NOISEREDUCTIONTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bEnable; - OMX_BOOL bAutoMode; - OMX_S32 nNoiseReduction; -} QOMX_NOISEREDUCTIONTYPE; - -typedef struct QOMX_IMAGEENHANCEMENTTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bEnable; - OMX_BOOL bAutoMode; - OMX_S32 nImageEnhancement; -} QOMX_IMAGEENHANCEMENTTYPE; - -/* - * these are part of OMX1.2 but JB MR2 branch doesn't have them defined - * OMX_IndexParamInterlaceFormat - * OMX_INTERLACEFORMATTYPE - */ -#ifndef OMX_IndexParamInterlaceFormat -#define OMX_IndexParamInterlaceFormat (0x7FF00000) -typedef struct OMX_INTERLACEFORMATTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nFormat; - OMX_TICKS nTimeStamp; -} OMX_INTERLACEFORMATTYPE; -#endif - -/** - * This structure is used to indicate the maximum number of buffers - * that a port will hold during data flow. - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version info - * nPortIndex : Port that this structure applies to - * nHeldBufferCount : Read-only, maximum number of buffers that will be held - */ -typedef struct QOMX_HELDBUFFERCOUNTTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nHeldBufferCount; -} QOMX_HELDBUFFERCOUNTTYPE; - -typedef enum QOMX_VIDEO_HIERARCHICALCODINGTYPE { - QOMX_HIERARCHICALCODING_P = 0x01, - QOMX_HIERARCHICALCODING_B = 0x02, -} QOMX_VIDEO_HIERARCHICALCODINGTYPE; - -typedef struct QOMX_VIDEO_HIERARCHICALLAYERS { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nNumLayers; - QOMX_VIDEO_HIERARCHICALCODINGTYPE eHierarchicalCodingType; -} QOMX_VIDEO_HIERARCHICALLAYERS; - -typedef struct QOMX_VIDEO_H264ENTROPYCODINGTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_BOOL bCabac; - OMX_U32 nCabacInitIdc; -} QOMX_VIDEO_H264ENTROPYCODINGTYPE; - - -/* VIDEO POSTPROCESSING CTRLS AND ENUMS */ -#define QOMX_VPP_HQV_CUSTOMPAYLOAD_SZ 256 -#define VPP_HQV_CONTROL_GLOBAL_START (VPP_HQV_CONTROL_CUST + 1) - -typedef enum QOMX_VPP_HQV_MODE { - VPP_HQV_MODE_OFF, - VPP_HQV_MODE_AUTO, - VPP_HQV_MODE_MANUAL, - VPP_HQV_MODE_MAX -} QOMX_VPP_HQV_MODE; - -typedef enum QOMX_VPP_HQVCONTROLTYPE { - VPP_HQV_CONTROL_CADE = 0x1, - VPP_HQV_CONTROL_CNR = 0x04, - VPP_HQV_CONTROL_AIE = 0x05, - VPP_HQV_CONTROL_FRC = 0x06, - VPP_HQV_CONTROL_CUST = 0x07, - VPP_HQV_CONTROL_GLOBAL_DEMO = VPP_HQV_CONTROL_GLOBAL_START, - VPP_HQV_CONTROL_MAX, -} QOMX_VPP_HQVCONTROLTYPE; - -typedef enum QOMX_VPP_HQV_HUE_MODE { - VPP_HQV_HUE_MODE_OFF, - VPP_HQV_HUE_MODE_ON, - VPP_HQV_HUE_MODE_MAX, -} QOMX_VPP_HQV_HUE_MODE; - -typedef enum QOMX_VPP_HQV_FRC_MODE { - VPP_HQV_FRC_MODE_OFF, - VPP_HQV_FRC_MODE_LOW, - VPP_HQV_FRC_MODE_MED, - VPP_HQV_FRC_MODE_HIGH, - VPP_HQV_FRC_MODE_MAX, -} QOMX_VPP_HQV_FRC_MODE; - - -typedef struct QOMX_VPP_HQVCTRL_CADE { - QOMX_VPP_HQV_MODE mode; - OMX_U32 level; - OMX_S32 contrast; - OMX_S32 saturation; -} QOMX_VPP_HQVCTRL_CADE; - -typedef struct QOMX_VPP_HQVCTRL_CNR { - QOMX_VPP_HQV_MODE mode; - OMX_U32 level; -} QOMX_VPP_HQVCTRL_CNR; - -typedef struct QOMX_VPP_HQVCTRL_AIE { - QOMX_VPP_HQV_MODE mode; - QOMX_VPP_HQV_HUE_MODE hue_mode; - OMX_U32 cade_level; - OMX_U32 ltm_level; -} QOMX_VPP_HQVCTRL_AIE; - -typedef struct QOMX_VPP_HQVCTRL_CUSTOM { - OMX_U32 id; - OMX_U32 len; - OMX_U8 data[QOMX_VPP_HQV_CUSTOMPAYLOAD_SZ]; -} QOMX_VPP_HQVCTRL_CUSTOM; - -typedef struct QOMX_VPP_HQVCTRL_GLOBAL_DEMO { - OMX_U32 process_percent; -} QOMX_VPP_HQVCTRL_GLOBAL_DEMO; - -typedef struct QOMX_VPP_HQVCTRL_FRC { - QOMX_VPP_HQV_FRC_MODE mode; -} QOMX_VPP_HQVCTRL_FRC; - -typedef struct QOMX_VPP_HQVCONTROL { - QOMX_VPP_HQV_MODE mode; - QOMX_VPP_HQVCONTROLTYPE ctrl_type; - union { - QOMX_VPP_HQVCTRL_CADE cade; - QOMX_VPP_HQVCTRL_CNR cnr; - QOMX_VPP_HQVCTRL_AIE aie; - QOMX_VPP_HQVCTRL_CUSTOM custom; - QOMX_VPP_HQVCTRL_GLOBAL_DEMO global_demo; - QOMX_VPP_HQVCTRL_FRC frc; - }; -} QOMX_VPP_HQVCONTROL; - -/* STRUCTURE TO TURN VPP ON */ -typedef struct QOMX_VPP_ENABLE { - OMX_BOOL enable_vpp; -} QOMX_VPP_ENABLE; - -typedef enum OMX_QOMX_VIDEO_MBISTATISTICSTYPE { - QOMX_MBI_STATISTICS_MODE_DEFAULT = 0, - QOMX_MBI_STATISTICS_MODE_1 = 0x01, - QOMX_MBI_STATISTICS_MODE_2 = 0x02, -} OMX_QOMX_VIDEO_MBISTATISTICSTYPE; - -typedef struct OMX_QOMX_VIDEO_MBI_STATISTICS { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_QOMX_VIDEO_MBISTATISTICSTYPE eMBIStatisticsType; -} OMX_QOMX_VIDEO_MBI_STATISTICS; - -typedef struct QOMX_VIDEO_BATCHSIZETYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nBatchSize; -} QOMX_VIDEO_BATCHSIZETYPE; - -#ifdef __cplusplus -} -#endif /* __cplusplus */ - -#endif /* __OMX_QCOM_EXTENSIONS_H__ */ diff --git a/selfdrive/frogpilot/screenrecorder/openmax/include/OMX_Skype_VideoExtensions.h b/selfdrive/frogpilot/screenrecorder/openmax/include/OMX_Skype_VideoExtensions.h deleted file mode 100644 index 5cc8329..0000000 --- a/selfdrive/frogpilot/screenrecorder/openmax/include/OMX_Skype_VideoExtensions.h +++ /dev/null @@ -1,155 +0,0 @@ -/*@@@+++@@@@****************************************************************** - - Microsoft Skype Engineering - Copyright (C) 2014 Microsoft Corporation. - -MIT License - -Permission is hereby granted, free of charge, to any person obtaining a copy - of this software and associated documentation files (the "Software"), to deal - in the Software without restriction, including without limitation the rights - to use, copy, modify, merge, publish, distribute, sublicense, and/or sell - copies of the Software, and to permit persons to whom the Software is - furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in - all copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR - IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, - FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE - AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER - LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN - THE SOFTWARE. - -*@@@---@@@@******************************************************************/ - - -#ifndef __OMX_SKYPE_VIDEOEXTENSIONS_H__ -#define __OMX_SKYPE_VIDEOEXTENSIONS_H__ - -#ifdef __cplusplus -extern "C" -{ -#endif - -#include - -#pragma pack(push, 1) - - -typedef enum OMX_SKYPE_VIDEO_SliceControlMode -{ - OMX_SKYPE_VIDEO_SliceControlModeNone = 0, - OMX_SKYPE_VIDEO_SliceControlModeMB = 1, - OMX_SKYPE_VIDEO_SliceControlModeByte = 2, - OMX_SKYPE_VIDEO_SliceControlModMBRow = 3, -} OMX_SKYPE_VIDEO_SliceControlMode; - - -typedef enum OMX_SKYPE_VIDEO_HierarType -{ - OMX_SKYPE_VIDEO_HierarType_P = 0x01, - OMX_SKYPE_VIDEO_HierarType_B = 0x02, -} OMX_SKYPE_VIDEO_HIERAR_HierarType; - -typedef enum OMX_VIDEO_EXTENSION_AVCPROFILETYPE -{ - OMX_VIDEO_EXT_AVCProfileConstrainedBaseline = 0x01, - OMX_VIDEO_EXT_AVCProfileConstrainedHigh = 0x02, -} OMX_VIDEO_EXTENSION_AVCPROFILETYPE; - -typedef struct OMX_SKYPE_VIDEO_ENCODERPARAMS { - OMX_BOOL bLowLatency; - OMX_BOOL bUseExtendedProfile; - OMX_BOOL bSequenceHeaderWithIDR; - OMX_VIDEO_EXTENSION_AVCPROFILETYPE eProfile; - OMX_U32 nLTRFrames; - OMX_SKYPE_VIDEO_HierarType eHierarType; - OMX_U32 nMaxTemporalLayerCount; - OMX_SKYPE_VIDEO_SliceControlMode eSliceControlMode; - OMX_U32 nSarIndex; - OMX_U32 nSarWidth; - OMX_U32 nSarHeight; -} OMX_SKYPE_VIDEO_ENCODERPARAMS; - -typedef struct OMX_SKYPE_VIDEO_PARAM_ENCODERSETTING { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_SKYPE_VIDEO_ENCODERPARAMS stEncParam; -} OMX_SKYPE_VIDEO_PARAM_ENCODESETTING; - -typedef struct OMX_SKYPE_VIDEO_ENCODERCAP { - OMX_BOOL bLowLatency; - OMX_U32 nMaxFrameWidth; - OMX_U32 nMaxFrameHeight; - OMX_U32 nMaxInstances; - OMX_U32 nMaxTemporaLayerCount; - OMX_U32 nMaxRefFrames; - OMX_U32 nMaxLTRFrames; - OMX_VIDEO_AVCLEVELTYPE nMaxLevel; - OMX_U32 nSliceControlModesBM; - OMX_U32 nMaxMacroblockProcessingRate; - OMX_U32 xMinScaleFactor; -} OMX_SKYPE_VIDEO_ENCODERCAP; - -typedef struct OMX_SKYPE_VIDEO_PARAM_ENCODERCAP { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_SKYPE_VIDEO_ENCODERCAP stEncCap; -} OMX_SKYPE_VIDEO_PARAM_ENCODERCAP; - -typedef struct OMX_SKYPE_VIDEO_DECODERCAP { - OMX_BOOL bLowLatency; - OMX_U32 nMaxFrameWidth; - OMX_U32 nMaxFrameHeight; - OMX_U32 nMaxInstances; - OMX_VIDEO_AVCLEVELTYPE nMaxLevel; - OMX_U32 nMaxMacroblockProcessingRate; -} OMX_SKYPE_VIDEO_DECODERCAP; - -typedef struct OMX_SKYPE_VIDEO_PARAM_DECODERCAP { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_SKYPE_VIDEO_DECODERCAP stDecoderCap; -} OMX_SKYPE_VIDEO_PARAM_DECODERCAP; - -typedef struct OMX_SKYPE_VIDEO_CONFIG_QP { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nQP; -} OMX_SKYPE_VIDEO_CONFIG_QP; - -typedef struct OMX_SKYPE_VIDEO_CONFIG_BASELAYERPID{ - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nPID; -} OMX_SKYPE_VIDEO_CONFIG_BASELAYERPID; - -typedef struct OMX_SKYPE_VIDEO_PARAM_DRIVERVER { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U64 nDriverVersion; -} OMX_SKYPE_VIDEO_PARAM_DRIVERVER; - -typedef enum OMX_SKYPE_VIDEO_DownScaleFactor -{ - OMX_SKYPE_VIDEO_DownScaleFactor_1_1 = 0, - OMX_SKYPE_VIDEO_DownScaleFactor_Equal_AR = 1, - OMX_SKYPE_VIDEO_DownScaleFactor_Any = 2, -} OMX_SKYPE_VIDEO_DownScaleFactor; - -#pragma pack(pop) - -#ifdef __cplusplus -} -#endif - -#endif diff --git a/selfdrive/frogpilot/screenrecorder/openmax/include/OMX_Types.h b/selfdrive/frogpilot/screenrecorder/openmax/include/OMX_Types.h deleted file mode 100644 index 3b9fab4..0000000 --- a/selfdrive/frogpilot/screenrecorder/openmax/include/OMX_Types.h +++ /dev/null @@ -1,359 +0,0 @@ -/* - * Copyright (c) 2008 The Khronos Group Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining - * a copy of this software and associated documentation files (the - * "Software"), to deal in the Software without restriction, including - * without limitation the rights to use, copy, modify, merge, publish, - * distribute, sublicense, and/or sell copies of the Software, and to - * permit persons to whom the Software is furnished to do so, subject - * to the following conditions: - * The above copyright notice and this permission notice shall be included - * in all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS - * OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. - * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY - * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, - * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE - * SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - * - */ - -/** OMX_Types.h - OpenMax IL version 1.1.2 - * The OMX_Types header file contains the primitive type definitions used by - * the core, the application and the component. This file may need to be - * modified to be used on systems that do not have "char" set to 8 bits, - * "short" set to 16 bits and "long" set to 32 bits. - */ - -#ifndef OMX_Types_h -#define OMX_Types_h - -#ifdef __cplusplus -extern "C" { -#endif /* __cplusplus */ - -/** The OMX_API and OMX_APIENTRY are platform specific definitions used - * to declare OMX function prototypes. They are modified to meet the - * requirements for a particular platform */ -#ifdef __SYMBIAN32__ -# ifdef __OMX_EXPORTS -# define OMX_API __declspec(dllexport) -# else -# ifdef _WIN32 -# define OMX_API __declspec(dllexport) -# else -# define OMX_API __declspec(dllimport) -# endif -# endif -#else -# ifdef _WIN32 -# ifdef __OMX_EXPORTS -# define OMX_API __declspec(dllexport) -# else -# define OMX_API __declspec(dllimport) -# endif -# else -# ifdef __OMX_EXPORTS -# define OMX_API -# else -# define OMX_API extern -# endif -# endif -#endif - -#ifndef OMX_APIENTRY -#define OMX_APIENTRY -#endif - -/** OMX_IN is used to identify inputs to an OMX function. This designation - will also be used in the case of a pointer that points to a parameter - that is used as an output. */ -#ifndef OMX_IN -#define OMX_IN -#endif - -/** OMX_OUT is used to identify outputs from an OMX function. This - designation will also be used in the case of a pointer that points - to a parameter that is used as an input. */ -#ifndef OMX_OUT -#define OMX_OUT -#endif - - -/** OMX_INOUT is used to identify parameters that may be either inputs or - outputs from an OMX function at the same time. This designation will - also be used in the case of a pointer that points to a parameter that - is used both as an input and an output. */ -#ifndef OMX_INOUT -#define OMX_INOUT -#endif - -/** OMX_ALL is used to as a wildcard to select all entities of the same type - * when specifying the index, or referring to a object by an index. (i.e. - * use OMX_ALL to indicate all N channels). When used as a port index - * for a config or parameter this OMX_ALL denotes that the config or - * parameter applies to the entire component not just one port. */ -#define OMX_ALL 0xFFFFFFFF - -/** In the following we define groups that help building doxygen documentation */ - -/** @defgroup core OpenMAX IL core - * Functions and structure related to the OMX IL core - */ - - /** @defgroup comp OpenMAX IL component - * Functions and structure related to the OMX IL component - */ - -/** @defgroup rpm Resource and Policy Management - * Structures for resource and policy management of components - */ - -/** @defgroup buf Buffer Management - * Buffer handling functions and structures - */ - -/** @defgroup tun Tunneling - * @ingroup core comp - * Structures and functions to manage tunnels among component ports - */ - -/** @defgroup cp Content Pipes - * @ingroup core - */ - - /** @defgroup metadata Metadata handling - * - */ - -/** OMX_U8 is an 8 bit unsigned quantity that is byte aligned */ -typedef unsigned char OMX_U8; - -/** OMX_S8 is an 8 bit signed quantity that is byte aligned */ -typedef signed char OMX_S8; - -/** OMX_U16 is a 16 bit unsigned quantity that is 16 bit word aligned */ -typedef unsigned short OMX_U16; - -/** OMX_S16 is a 16 bit signed quantity that is 16 bit word aligned */ -typedef signed short OMX_S16; - -/** OMX_U32 is a 32 bit unsigned quantity that is 32 bit word aligned */ -typedef unsigned int OMX_U32; - -/** OMX_S32 is a 32 bit signed quantity that is 32 bit word aligned */ -typedef signed int OMX_S32; - - -/* Users with compilers that cannot accept the "long long" designation should - define the OMX_SKIP64BIT macro. It should be noted that this may cause - some components to fail to compile if the component was written to require - 64 bit integral types. However, these components would NOT compile anyway - since the compiler does not support the way the component was written. -*/ -#ifndef OMX_SKIP64BIT -#ifdef __SYMBIAN32__ -/** OMX_U64 is a 64 bit unsigned quantity that is 64 bit word aligned */ -typedef unsigned long long OMX_U64; - -/** OMX_S64 is a 64 bit signed quantity that is 64 bit word aligned */ -typedef signed long long OMX_S64; - -#elif defined(WIN32) - -/** OMX_U64 is a 64 bit unsigned quantity that is 64 bit word aligned */ -typedef unsigned __int64 OMX_U64; - -/** OMX_S64 is a 64 bit signed quantity that is 64 bit word aligned */ -typedef signed __int64 OMX_S64; - -#else /* WIN32 */ - -/** OMX_U64 is a 64 bit unsigned quantity that is 64 bit word aligned */ -typedef unsigned long long OMX_U64; - -/** OMX_S64 is a 64 bit signed quantity that is 64 bit word aligned */ -typedef signed long long OMX_S64; - -#endif /* WIN32 */ -#endif - - -/** The OMX_BOOL type is intended to be used to represent a true or a false - value when passing parameters to and from the OMX core and components. The - OMX_BOOL is a 32 bit quantity and is aligned on a 32 bit word boundary. - */ -typedef enum OMX_BOOL { - OMX_FALSE = 0, - OMX_TRUE = !OMX_FALSE, - OMX_BOOL_MAX = 0x7FFFFFFF -} OMX_BOOL; - -#ifdef OMX_ANDROID_COMPILE_AS_32BIT_ON_64BIT_PLATFORMS - -typedef OMX_U32 OMX_PTR; -typedef OMX_PTR OMX_STRING; -typedef OMX_PTR OMX_BYTE; - -#else - -/** The OMX_PTR type is intended to be used to pass pointers between the OMX - applications and the OMX Core and components. This is a 32 bit pointer and - is aligned on a 32 bit boundary. - */ -typedef void* OMX_PTR; - -/** The OMX_STRING type is intended to be used to pass "C" type strings between - the application and the core and component. The OMX_STRING type is a 32 - bit pointer to a zero terminated string. The pointer is word aligned and - the string is byte aligned. - */ -typedef char* OMX_STRING; - -/** The OMX_BYTE type is intended to be used to pass arrays of bytes such as - buffers between the application and the component and core. The OMX_BYTE - type is a 32 bit pointer to a zero terminated string. The pointer is word - aligned and the string is byte aligned. - */ -typedef unsigned char* OMX_BYTE; - -/** OMX_UUIDTYPE is a very long unique identifier to uniquely identify - at runtime. This identifier should be generated by a component in a way - that guarantees that every instance of the identifier running on the system - is unique. */ - - -#endif - -typedef unsigned char OMX_UUIDTYPE[128]; - -/** The OMX_DIRTYPE enumeration is used to indicate if a port is an input or - an output port. This enumeration is common across all component types. - */ -typedef enum OMX_DIRTYPE -{ - OMX_DirInput, /**< Port is an input port */ - OMX_DirOutput, /**< Port is an output port */ - OMX_DirMax = 0x7FFFFFFF -} OMX_DIRTYPE; - -/** The OMX_ENDIANTYPE enumeration is used to indicate the bit ordering - for numerical data (i.e. big endian, or little endian). - */ -typedef enum OMX_ENDIANTYPE -{ - OMX_EndianBig, /**< big endian */ - OMX_EndianLittle, /**< little endian */ - OMX_EndianMax = 0x7FFFFFFF -} OMX_ENDIANTYPE; - - -/** The OMX_NUMERICALDATATYPE enumeration is used to indicate if data - is signed or unsigned - */ -typedef enum OMX_NUMERICALDATATYPE -{ - OMX_NumericalDataSigned, /**< signed data */ - OMX_NumericalDataUnsigned, /**< unsigned data */ - OMX_NumercialDataMax = 0x7FFFFFFF -} OMX_NUMERICALDATATYPE; - - -/** Unsigned bounded value type */ -typedef struct OMX_BU32 { - OMX_U32 nValue; /**< actual value */ - OMX_U32 nMin; /**< minimum for value (i.e. nValue >= nMin) */ - OMX_U32 nMax; /**< maximum for value (i.e. nValue <= nMax) */ -} OMX_BU32; - - -/** Signed bounded value type */ -typedef struct OMX_BS32 { - OMX_S32 nValue; /**< actual value */ - OMX_S32 nMin; /**< minimum for value (i.e. nValue >= nMin) */ - OMX_S32 nMax; /**< maximum for value (i.e. nValue <= nMax) */ -} OMX_BS32; - - -/** Structure representing some time or duration in microseconds. This structure - * must be interpreted as a signed 64 bit value. The quantity is signed to accommodate - * negative deltas and preroll scenarios. The quantity is represented in microseconds - * to accomodate high resolution timestamps (e.g. DVD presentation timestamps based - * on a 90kHz clock) and to allow more accurate and synchronized delivery (e.g. - * individual audio samples delivered at 192 kHz). The quantity is 64 bit to - * accommodate a large dynamic range (signed 32 bit values would allow only for plus - * or minus 35 minutes). - * - * Implementations with limited precision may convert the signed 64 bit value to - * a signed 32 bit value internally but risk loss of precision. - */ -#ifndef OMX_SKIP64BIT -typedef OMX_S64 OMX_TICKS; -#else -typedef struct OMX_TICKS -{ - OMX_U32 nLowPart; /** low bits of the signed 64 bit tick value */ - OMX_U32 nHighPart; /** high bits of the signed 64 bit tick value */ -} OMX_TICKS; -#endif -#define OMX_TICKS_PER_SECOND 1000000 - -/** Define the public interface for the OMX Handle. The core will not use - this value internally, but the application should only use this value. - */ -typedef void* OMX_HANDLETYPE; - -typedef struct OMX_MARKTYPE -{ - OMX_HANDLETYPE hMarkTargetComponent; /**< The component that will - generate a mark event upon - processing the mark. */ - OMX_PTR pMarkData; /**< Application specific data associated with - the mark sent on a mark event to disambiguate - this mark from others. */ -} OMX_MARKTYPE; - - -/** OMX_NATIVE_DEVICETYPE is used to map a OMX video port to the - * platform & operating specific object used to reference the display - * or can be used by a audio port for native audio rendering */ -typedef void* OMX_NATIVE_DEVICETYPE; - -/** OMX_NATIVE_WINDOWTYPE is used to map a OMX video port to the - * platform & operating specific object used to reference the window */ -typedef void* OMX_NATIVE_WINDOWTYPE; - -/** The OMX_VERSIONTYPE union is used to specify the version for - a structure or component. For a component, the version is entirely - specified by the component vendor. Components doing the same function - from different vendors may or may not have the same version. For - structures, the version shall be set by the entity that allocates the - structure. For structures specified in the OMX 1.1 specification, the - value of the version shall be set to 1.1.0.0 in all cases. Access to the - OMX_VERSIONTYPE can be by a single 32 bit access (e.g. by nVersion) or - by accessing one of the structure elements to, for example, check only - the Major revision. - */ -typedef union OMX_VERSIONTYPE -{ - struct - { - OMX_U8 nVersionMajor; /**< Major version accessor element */ - OMX_U8 nVersionMinor; /**< Minor version accessor element */ - OMX_U8 nRevision; /**< Revision version accessor element */ - OMX_U8 nStep; /**< Step version accessor element */ - } s; - OMX_U32 nVersion; /**< 32 bit value to make accessing the - version easily done in a single word - size copy/compare operation */ -} OMX_VERSIONTYPE; - -#ifdef __cplusplus -} -#endif /* __cplusplus */ - -#endif -/* File EOF */ diff --git a/selfdrive/frogpilot/screenrecorder/openmax/include/OMX_Video.h b/selfdrive/frogpilot/screenrecorder/openmax/include/OMX_Video.h deleted file mode 100644 index 64dbe87..0000000 --- a/selfdrive/frogpilot/screenrecorder/openmax/include/OMX_Video.h +++ /dev/null @@ -1,1082 +0,0 @@ -/** - * Copyright (c) 2008 The Khronos Group Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining - * a copy of this software and associated documentation files (the - * "Software"), to deal in the Software without restriction, including - * without limitation the rights to use, copy, modify, merge, publish, - * distribute, sublicense, and/or sell copies of the Software, and to - * permit persons to whom the Software is furnished to do so, subject - * to the following conditions: - * The above copyright notice and this permission notice shall be included - * in all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS - * OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. - * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY - * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, - * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE - * SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - * - */ - -/** - * @file OMX_Video.h - OpenMax IL version 1.1.2 - * The structures is needed by Video components to exchange parameters - * and configuration data with OMX components. - */ -#ifndef OMX_Video_h -#define OMX_Video_h - -/** @defgroup video OpenMAX IL Video Domain - * @ingroup iv - * Structures for OpenMAX IL Video domain - * @{ - */ - -#ifdef __cplusplus -extern "C" { -#endif /* __cplusplus */ - - -/** - * Each OMX header must include all required header files to allow the - * header to compile without errors. The includes below are required - * for this header file to compile successfully - */ - -#include - - -/** - * Enumeration used to define the possible video compression codings. - * NOTE: This essentially refers to file extensions. If the coding is - * being used to specify the ENCODE type, then additional work - * must be done to configure the exact flavor of the compression - * to be used. For decode cases where the user application can - * not differentiate between MPEG-4 and H.264 bit streams, it is - * up to the codec to handle this. - */ -typedef enum OMX_VIDEO_CODINGTYPE { - OMX_VIDEO_CodingUnused, /**< Value when coding is N/A */ - OMX_VIDEO_CodingAutoDetect, /**< Autodetection of coding type */ - OMX_VIDEO_CodingMPEG2, /**< AKA: H.262 */ - OMX_VIDEO_CodingH263, /**< H.263 */ - OMX_VIDEO_CodingMPEG4, /**< MPEG-4 */ - OMX_VIDEO_CodingWMV, /**< all versions of Windows Media Video */ - OMX_VIDEO_CodingRV, /**< all versions of Real Video */ - OMX_VIDEO_CodingAVC, /**< H.264/AVC */ - OMX_VIDEO_CodingMJPEG, /**< Motion JPEG */ - OMX_VIDEO_CodingVP8, /**< Google VP8, formerly known as On2 VP8 */ - OMX_VIDEO_CodingVP9, /**< Google VP9 */ - OMX_VIDEO_CodingHEVC, /**< HEVC */ - OMX_VIDEO_CodingKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_CodingVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_CodingMax = 0x7FFFFFFF -} OMX_VIDEO_CODINGTYPE; - - -/** - * Data structure used to define a video path. The number of Video paths for - * input and output will vary by type of the Video component. - * - * Input (aka Source) : zero Inputs, one Output, - * Splitter : one Input, 2 or more Outputs, - * Processing Element : one Input, one output, - * Mixer : 2 or more inputs, one output, - * Output (aka Sink) : one Input, zero outputs. - * - * The PortDefinition structure is used to define all of the parameters - * necessary for the compliant component to setup an input or an output video - * path. If additional vendor specific data is required, it should be - * transmitted to the component using the CustomCommand function. Compliant - * components will prepopulate this structure with optimal values during the - * GetDefaultInitParams command. - * - * STRUCT MEMBERS: - * cMIMEType : MIME type of data for the port - * pNativeRender : Platform specific reference for a display if a - * sync, otherwise this field is 0 - * nFrameWidth : Width of frame to be used on channel if - * uncompressed format is used. Use 0 for unknown, - * don't care or variable - * nFrameHeight : Height of frame to be used on channel if - * uncompressed format is used. Use 0 for unknown, - * don't care or variable - * nStride : Number of bytes per span of an image - * (i.e. indicates the number of bytes to get - * from span N to span N+1, where negative stride - * indicates the image is bottom up - * nSliceHeight : Height used when encoding in slices - * nBitrate : Bit rate of frame to be used on channel if - * compressed format is used. Use 0 for unknown, - * don't care or variable - * xFramerate : Frame rate to be used on channel if uncompressed - * format is used. Use 0 for unknown, don't care or - * variable. Units are Q16 frames per second. - * bFlagErrorConcealment : Turns on error concealment if it is supported by - * the OMX component - * eCompressionFormat : Compression format used in this instance of the - * component. When OMX_VIDEO_CodingUnused is - * specified, eColorFormat is used - * eColorFormat : Decompressed format used by this component - * pNativeWindow : Platform specific reference for a window object if a - * display sink , otherwise this field is 0x0. - */ -typedef struct OMX_VIDEO_PORTDEFINITIONTYPE { - OMX_STRING cMIMEType; - OMX_NATIVE_DEVICETYPE pNativeRender; - OMX_U32 nFrameWidth; - OMX_U32 nFrameHeight; - OMX_S32 nStride; - OMX_U32 nSliceHeight; - OMX_U32 nBitrate; - OMX_U32 xFramerate; - OMX_BOOL bFlagErrorConcealment; - OMX_VIDEO_CODINGTYPE eCompressionFormat; - OMX_COLOR_FORMATTYPE eColorFormat; - OMX_NATIVE_WINDOWTYPE pNativeWindow; -} OMX_VIDEO_PORTDEFINITIONTYPE; - -/** - * Port format parameter. This structure is used to enumerate the various - * data input/output format supported by the port. - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Indicates which port to set - * nIndex : Indicates the enumeration index for the format from - * 0x0 to N-1 - * eCompressionFormat : Compression format used in this instance of the - * component. When OMX_VIDEO_CodingUnused is specified, - * eColorFormat is used - * eColorFormat : Decompressed format used by this component - * xFrameRate : Indicates the video frame rate in Q16 format - */ -typedef struct OMX_VIDEO_PARAM_PORTFORMATTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nIndex; - OMX_VIDEO_CODINGTYPE eCompressionFormat; - OMX_COLOR_FORMATTYPE eColorFormat; - OMX_U32 xFramerate; -} OMX_VIDEO_PARAM_PORTFORMATTYPE; - - -/** - * This is a structure for configuring video compression quantization - * parameter values. Codecs may support different QP values for different - * frame types. - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version info - * nPortIndex : Port that this structure applies to - * nQpI : QP value to use for index frames - * nQpP : QP value to use for P frames - * nQpB : QP values to use for bidirectional frames - */ -typedef struct OMX_VIDEO_PARAM_QUANTIZATIONTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nQpI; - OMX_U32 nQpP; - OMX_U32 nQpB; -} OMX_VIDEO_PARAM_QUANTIZATIONTYPE; - - -/** - * Structure for configuration of video fast update parameters. - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version info - * nPortIndex : Port that this structure applies to - * bEnableVFU : Enable/Disable video fast update - * nFirstGOB : Specifies the number of the first macroblock row - * nFirstMB : specifies the first MB relative to the specified first GOB - * nNumMBs : Specifies the number of MBs to be refreshed from nFirstGOB - * and nFirstMB - */ -typedef struct OMX_VIDEO_PARAM_VIDEOFASTUPDATETYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bEnableVFU; - OMX_U32 nFirstGOB; - OMX_U32 nFirstMB; - OMX_U32 nNumMBs; -} OMX_VIDEO_PARAM_VIDEOFASTUPDATETYPE; - - -/** - * Enumeration of possible bitrate control types - */ -typedef enum OMX_VIDEO_CONTROLRATETYPE { - OMX_Video_ControlRateDisable, - OMX_Video_ControlRateVariable, - OMX_Video_ControlRateConstant, - OMX_Video_ControlRateVariableSkipFrames, - OMX_Video_ControlRateConstantSkipFrames, - OMX_Video_ControlRateKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_Video_ControlRateVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_Video_ControlRateMax = 0x7FFFFFFF -} OMX_VIDEO_CONTROLRATETYPE; - - -/** - * Structure for configuring bitrate mode of a codec. - * - * STRUCT MEMBERS: - * nSize : Size of the struct in bytes - * nVersion : OMX spec version info - * nPortIndex : Port that this struct applies to - * eControlRate : Control rate type enum - * nTargetBitrate : Target bitrate to encode with - */ -typedef struct OMX_VIDEO_PARAM_BITRATETYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_VIDEO_CONTROLRATETYPE eControlRate; - OMX_U32 nTargetBitrate; -} OMX_VIDEO_PARAM_BITRATETYPE; - - -/** - * Enumeration of possible motion vector (MV) types - */ -typedef enum OMX_VIDEO_MOTIONVECTORTYPE { - OMX_Video_MotionVectorPixel, - OMX_Video_MotionVectorHalfPel, - OMX_Video_MotionVectorQuarterPel, - OMX_Video_MotionVectorEighthPel, - OMX_Video_MotionVectorKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_Video_MotionVectorVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_Video_MotionVectorMax = 0x7FFFFFFF -} OMX_VIDEO_MOTIONVECTORTYPE; - - -/** - * Structure for configuring the number of motion vectors used as well - * as their accuracy. - * - * STRUCT MEMBERS: - * nSize : Size of the struct in bytes - * nVersion : OMX spec version info - * nPortIndex : port that this structure applies to - * eAccuracy : Enumerated MV accuracy - * bUnrestrictedMVs : Allow unrestricted MVs - * bFourMV : Allow use of 4 MVs - * sXSearchRange : Search range in horizontal direction for MVs - * sYSearchRange : Search range in vertical direction for MVs - */ -typedef struct OMX_VIDEO_PARAM_MOTIONVECTORTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_VIDEO_MOTIONVECTORTYPE eAccuracy; - OMX_BOOL bUnrestrictedMVs; - OMX_BOOL bFourMV; - OMX_S32 sXSearchRange; - OMX_S32 sYSearchRange; -} OMX_VIDEO_PARAM_MOTIONVECTORTYPE; - - -/** - * Enumeration of possible methods to use for Intra Refresh - */ -typedef enum OMX_VIDEO_INTRAREFRESHTYPE { - OMX_VIDEO_IntraRefreshCyclic, - OMX_VIDEO_IntraRefreshAdaptive, - OMX_VIDEO_IntraRefreshBoth, - OMX_VIDEO_IntraRefreshKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_IntraRefreshVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_IntraRefreshRandom, - OMX_VIDEO_IntraRefreshMax = 0x7FFFFFFF -} OMX_VIDEO_INTRAREFRESHTYPE; - - -/** - * Structure for configuring intra refresh mode - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * eRefreshMode : Cyclic, Adaptive, or Both - * nAirMBs : Number of intra macroblocks to refresh in a frame when - * AIR is enabled - * nAirRef : Number of times a motion marked macroblock has to be - * intra coded - * nCirMBs : Number of consecutive macroblocks to be coded as "intra" - * when CIR is enabled - */ -typedef struct OMX_VIDEO_PARAM_INTRAREFRESHTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_VIDEO_INTRAREFRESHTYPE eRefreshMode; - OMX_U32 nAirMBs; - OMX_U32 nAirRef; - OMX_U32 nCirMBs; -} OMX_VIDEO_PARAM_INTRAREFRESHTYPE; - - -/** - * Structure for enabling various error correction methods for video - * compression. - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * bEnableHEC : Enable/disable header extension codes (HEC) - * bEnableResync : Enable/disable resynchronization markers - * nResynchMarkerSpacing : Resynch markers interval (in bits) to be - * applied in the stream - * bEnableDataPartitioning : Enable/disable data partitioning - * bEnableRVLC : Enable/disable reversible variable length - * coding - */ -typedef struct OMX_VIDEO_PARAM_ERRORCORRECTIONTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bEnableHEC; - OMX_BOOL bEnableResync; - OMX_U32 nResynchMarkerSpacing; - OMX_BOOL bEnableDataPartitioning; - OMX_BOOL bEnableRVLC; -} OMX_VIDEO_PARAM_ERRORCORRECTIONTYPE; - - -/** - * Configuration of variable block-size motion compensation (VBSMC) - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * b16x16 : Enable inter block search 16x16 - * b16x8 : Enable inter block search 16x8 - * b8x16 : Enable inter block search 8x16 - * b8x8 : Enable inter block search 8x8 - * b8x4 : Enable inter block search 8x4 - * b4x8 : Enable inter block search 4x8 - * b4x4 : Enable inter block search 4x4 - */ -typedef struct OMX_VIDEO_PARAM_VBSMCTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL b16x16; - OMX_BOOL b16x8; - OMX_BOOL b8x16; - OMX_BOOL b8x8; - OMX_BOOL b8x4; - OMX_BOOL b4x8; - OMX_BOOL b4x4; -} OMX_VIDEO_PARAM_VBSMCTYPE; - - -/** - * H.263 profile types, each profile indicates support for various - * performance bounds and different annexes. - * - * ENUMS: - * Baseline : Baseline Profile: H.263 (V1), no optional modes - * H320 Coding : H.320 Coding Efficiency Backward Compatibility - * Profile: H.263+ (V2), includes annexes I, J, L.4 - * and T - * BackwardCompatible : Backward Compatibility Profile: H.263 (V1), - * includes annex F - * ISWV2 : Interactive Streaming Wireless Profile: H.263+ - * (V2), includes annexes I, J, K and T - * ISWV3 : Interactive Streaming Wireless Profile: H.263++ - * (V3), includes profile 3 and annexes V and W.6.3.8 - * HighCompression : Conversational High Compression Profile: H.263++ - * (V3), includes profiles 1 & 2 and annexes D and U - * Internet : Conversational Internet Profile: H.263++ (V3), - * includes profile 5 and annex K - * Interlace : Conversational Interlace Profile: H.263++ (V3), - * includes profile 5 and annex W.6.3.11 - * HighLatency : High Latency Profile: H.263++ (V3), includes - * profile 6 and annexes O.1 and P.5 - */ -typedef enum OMX_VIDEO_H263PROFILETYPE { - OMX_VIDEO_H263ProfileBaseline = 0x01, - OMX_VIDEO_H263ProfileH320Coding = 0x02, - OMX_VIDEO_H263ProfileBackwardCompatible = 0x04, - OMX_VIDEO_H263ProfileISWV2 = 0x08, - OMX_VIDEO_H263ProfileISWV3 = 0x10, - OMX_VIDEO_H263ProfileHighCompression = 0x20, - OMX_VIDEO_H263ProfileInternet = 0x40, - OMX_VIDEO_H263ProfileInterlace = 0x80, - OMX_VIDEO_H263ProfileHighLatency = 0x100, - OMX_VIDEO_H263ProfileKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_H263ProfileVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_H263ProfileMax = 0x7FFFFFFF -} OMX_VIDEO_H263PROFILETYPE; - - -/** - * H.263 level types, each level indicates support for various frame sizes, - * bit rates, decoder frame rates. - */ -typedef enum OMX_VIDEO_H263LEVELTYPE { - OMX_VIDEO_H263Level10 = 0x01, - OMX_VIDEO_H263Level20 = 0x02, - OMX_VIDEO_H263Level30 = 0x04, - OMX_VIDEO_H263Level40 = 0x08, - OMX_VIDEO_H263Level45 = 0x10, - OMX_VIDEO_H263Level50 = 0x20, - OMX_VIDEO_H263Level60 = 0x40, - OMX_VIDEO_H263Level70 = 0x80, - OMX_VIDEO_H263LevelKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_H263LevelVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_H263LevelMax = 0x7FFFFFFF -} OMX_VIDEO_H263LEVELTYPE; - - -/** - * Specifies the picture type. These values should be OR'd to signal all - * pictures types which are allowed. - * - * ENUMS: - * Generic Picture Types: I, P and B - * H.263 Specific Picture Types: SI and SP - * H.264 Specific Picture Types: EI and EP - * MPEG-4 Specific Picture Types: S - */ -typedef enum OMX_VIDEO_PICTURETYPE { - OMX_VIDEO_PictureTypeI = 0x01, - OMX_VIDEO_PictureTypeP = 0x02, - OMX_VIDEO_PictureTypeB = 0x04, - OMX_VIDEO_PictureTypeSI = 0x08, - OMX_VIDEO_PictureTypeSP = 0x10, - OMX_VIDEO_PictureTypeEI = 0x11, - OMX_VIDEO_PictureTypeEP = 0x12, - OMX_VIDEO_PictureTypeS = 0x14, - OMX_VIDEO_PictureTypeKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_PictureTypeVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_PictureTypeMax = 0x7FFFFFFF -} OMX_VIDEO_PICTURETYPE; - - -/** - * H.263 Params - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * nPFrames : Number of P frames between each I frame - * nBFrames : Number of B frames between each I frame - * eProfile : H.263 profile(s) to use - * eLevel : H.263 level(s) to use - * bPLUSPTYPEAllowed : Indicating that it is allowed to use PLUSPTYPE - * (specified in the 1998 version of H.263) to - * indicate custom picture sizes or clock - * frequencies - * nAllowedPictureTypes : Specifies the picture types allowed in the - * bitstream - * bForceRoundingTypeToZero : value of the RTYPE bit (bit 6 of MPPTYPE) is - * not constrained. It is recommended to change - * the value of the RTYPE bit for each reference - * picture in error-free communication - * nPictureHeaderRepetition : Specifies the frequency of picture header - * repetition - * nGOBHeaderInterval : Specifies the interval of non-empty GOB - * headers in units of GOBs - */ -typedef struct OMX_VIDEO_PARAM_H263TYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nPFrames; - OMX_U32 nBFrames; - OMX_VIDEO_H263PROFILETYPE eProfile; - OMX_VIDEO_H263LEVELTYPE eLevel; - OMX_BOOL bPLUSPTYPEAllowed; - OMX_U32 nAllowedPictureTypes; - OMX_BOOL bForceRoundingTypeToZero; - OMX_U32 nPictureHeaderRepetition; - OMX_U32 nGOBHeaderInterval; -} OMX_VIDEO_PARAM_H263TYPE; - - -/** - * MPEG-2 profile types, each profile indicates support for various - * performance bounds and different annexes. - */ -typedef enum OMX_VIDEO_MPEG2PROFILETYPE { - OMX_VIDEO_MPEG2ProfileSimple = 0, /**< Simple Profile */ - OMX_VIDEO_MPEG2ProfileMain, /**< Main Profile */ - OMX_VIDEO_MPEG2Profile422, /**< 4:2:2 Profile */ - OMX_VIDEO_MPEG2ProfileSNR, /**< SNR Profile */ - OMX_VIDEO_MPEG2ProfileSpatial, /**< Spatial Profile */ - OMX_VIDEO_MPEG2ProfileHigh, /**< High Profile */ - OMX_VIDEO_MPEG2ProfileKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_MPEG2ProfileVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_MPEG2ProfileMax = 0x7FFFFFFF -} OMX_VIDEO_MPEG2PROFILETYPE; - - -/** - * MPEG-2 level types, each level indicates support for various frame - * sizes, bit rates, decoder frame rates. No need - */ -typedef enum OMX_VIDEO_MPEG2LEVELTYPE { - OMX_VIDEO_MPEG2LevelLL = 0, /**< Low Level */ - OMX_VIDEO_MPEG2LevelML, /**< Main Level */ - OMX_VIDEO_MPEG2LevelH14, /**< High 1440 */ - OMX_VIDEO_MPEG2LevelHL, /**< High Level */ - OMX_VIDEO_MPEG2LevelKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_MPEG2LevelVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_MPEG2LevelMax = 0x7FFFFFFF -} OMX_VIDEO_MPEG2LEVELTYPE; - - -/** - * MPEG-2 params - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * nPFrames : Number of P frames between each I frame - * nBFrames : Number of B frames between each I frame - * eProfile : MPEG-2 profile(s) to use - * eLevel : MPEG-2 levels(s) to use - */ -typedef struct OMX_VIDEO_PARAM_MPEG2TYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nPFrames; - OMX_U32 nBFrames; - OMX_VIDEO_MPEG2PROFILETYPE eProfile; - OMX_VIDEO_MPEG2LEVELTYPE eLevel; -} OMX_VIDEO_PARAM_MPEG2TYPE; - - -/** - * MPEG-4 profile types, each profile indicates support for various - * performance bounds and different annexes. - * - * ENUMS: - * - Simple Profile, Levels 1-3 - * - Simple Scalable Profile, Levels 1-2 - * - Core Profile, Levels 1-2 - * - Main Profile, Levels 2-4 - * - N-bit Profile, Level 2 - * - Scalable Texture Profile, Level 1 - * - Simple Face Animation Profile, Levels 1-2 - * - Simple Face and Body Animation (FBA) Profile, Levels 1-2 - * - Basic Animated Texture Profile, Levels 1-2 - * - Hybrid Profile, Levels 1-2 - * - Advanced Real Time Simple Profiles, Levels 1-4 - * - Core Scalable Profile, Levels 1-3 - * - Advanced Coding Efficiency Profile, Levels 1-4 - * - Advanced Core Profile, Levels 1-2 - * - Advanced Scalable Texture, Levels 2-3 - */ -typedef enum OMX_VIDEO_MPEG4PROFILETYPE { - OMX_VIDEO_MPEG4ProfileSimple = 0x01, - OMX_VIDEO_MPEG4ProfileSimpleScalable = 0x02, - OMX_VIDEO_MPEG4ProfileCore = 0x04, - OMX_VIDEO_MPEG4ProfileMain = 0x08, - OMX_VIDEO_MPEG4ProfileNbit = 0x10, - OMX_VIDEO_MPEG4ProfileScalableTexture = 0x20, - OMX_VIDEO_MPEG4ProfileSimpleFace = 0x40, - OMX_VIDEO_MPEG4ProfileSimpleFBA = 0x80, - OMX_VIDEO_MPEG4ProfileBasicAnimated = 0x100, - OMX_VIDEO_MPEG4ProfileHybrid = 0x200, - OMX_VIDEO_MPEG4ProfileAdvancedRealTime = 0x400, - OMX_VIDEO_MPEG4ProfileCoreScalable = 0x800, - OMX_VIDEO_MPEG4ProfileAdvancedCoding = 0x1000, - OMX_VIDEO_MPEG4ProfileAdvancedCore = 0x2000, - OMX_VIDEO_MPEG4ProfileAdvancedScalable = 0x4000, - OMX_VIDEO_MPEG4ProfileAdvancedSimple = 0x8000, - OMX_VIDEO_MPEG4ProfileKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_MPEG4ProfileVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_MPEG4ProfileMax = 0x7FFFFFFF -} OMX_VIDEO_MPEG4PROFILETYPE; - - -/** - * MPEG-4 level types, each level indicates support for various frame - * sizes, bit rates, decoder frame rates. No need - */ -typedef enum OMX_VIDEO_MPEG4LEVELTYPE { - OMX_VIDEO_MPEG4Level0 = 0x01, /**< Level 0 */ - OMX_VIDEO_MPEG4Level0b = 0x02, /**< Level 0b */ - OMX_VIDEO_MPEG4Level1 = 0x04, /**< Level 1 */ - OMX_VIDEO_MPEG4Level2 = 0x08, /**< Level 2 */ - OMX_VIDEO_MPEG4Level3 = 0x10, /**< Level 3 */ - OMX_VIDEO_MPEG4Level4 = 0x20, /**< Level 4 */ - OMX_VIDEO_MPEG4Level4a = 0x40, /**< Level 4a */ - OMX_VIDEO_MPEG4Level5 = 0x80, /**< Level 5 */ - OMX_VIDEO_MPEG4LevelKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_MPEG4LevelVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_MPEG4LevelMax = 0x7FFFFFFF -} OMX_VIDEO_MPEG4LEVELTYPE; - - -/** - * MPEG-4 configuration. This structure handles configuration options - * which are specific to MPEG4 algorithms - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * nSliceHeaderSpacing : Number of macroblocks between slice header (H263+ - * Annex K). Put zero if not used - * bSVH : Enable Short Video Header mode - * bGov : Flag to enable GOV - * nPFrames : Number of P frames between each I frame (also called - * GOV period) - * nBFrames : Number of B frames between each I frame - * nIDCVLCThreshold : Value of intra DC VLC threshold - * bACPred : Flag to use ac prediction - * nMaxPacketSize : Maximum size of packet in bytes. - * nTimeIncRes : Used to pass VOP time increment resolution for MPEG4. - * Interpreted as described in MPEG4 standard. - * eProfile : MPEG-4 profile(s) to use. - * eLevel : MPEG-4 level(s) to use. - * nAllowedPictureTypes : Specifies the picture types allowed in the bitstream - * nHeaderExtension : Specifies the number of consecutive video packet - * headers within a VOP - * bReversibleVLC : Specifies whether reversible variable length coding - * is in use - */ -typedef struct OMX_VIDEO_PARAM_MPEG4TYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nSliceHeaderSpacing; - OMX_BOOL bSVH; - OMX_BOOL bGov; - OMX_U32 nPFrames; - OMX_U32 nBFrames; - OMX_U32 nIDCVLCThreshold; - OMX_BOOL bACPred; - OMX_U32 nMaxPacketSize; - OMX_U32 nTimeIncRes; - OMX_VIDEO_MPEG4PROFILETYPE eProfile; - OMX_VIDEO_MPEG4LEVELTYPE eLevel; - OMX_U32 nAllowedPictureTypes; - OMX_U32 nHeaderExtension; - OMX_BOOL bReversibleVLC; -} OMX_VIDEO_PARAM_MPEG4TYPE; - - -/** - * WMV Versions - */ -typedef enum OMX_VIDEO_WMVFORMATTYPE { - OMX_VIDEO_WMVFormatUnused = 0x01, /**< Format unused or unknown */ - OMX_VIDEO_WMVFormat7 = 0x02, /**< Windows Media Video format 7 */ - OMX_VIDEO_WMVFormat8 = 0x04, /**< Windows Media Video format 8 */ - OMX_VIDEO_WMVFormat9 = 0x08, /**< Windows Media Video format 9 */ - OMX_VIDEO_WMFFormatKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_WMFFormatVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_WMVFormatMax = 0x7FFFFFFF -} OMX_VIDEO_WMVFORMATTYPE; - - -/** - * WMV Params - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * eFormat : Version of WMV stream / data - */ -typedef struct OMX_VIDEO_PARAM_WMVTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_VIDEO_WMVFORMATTYPE eFormat; -} OMX_VIDEO_PARAM_WMVTYPE; - - -/** - * Real Video Version - */ -typedef enum OMX_VIDEO_RVFORMATTYPE { - OMX_VIDEO_RVFormatUnused = 0, /**< Format unused or unknown */ - OMX_VIDEO_RVFormat8, /**< Real Video format 8 */ - OMX_VIDEO_RVFormat9, /**< Real Video format 9 */ - OMX_VIDEO_RVFormatG2, /**< Real Video Format G2 */ - OMX_VIDEO_RVFormatKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_RVFormatVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_RVFormatMax = 0x7FFFFFFF -} OMX_VIDEO_RVFORMATTYPE; - - -/** - * Real Video Params - * - * STUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * eFormat : Version of RV stream / data - * nBitsPerPixel : Bits per pixel coded in the frame - * nPaddedWidth : Padded width in pixel of a video frame - * nPaddedHeight : Padded Height in pixels of a video frame - * nFrameRate : Rate of video in frames per second - * nBitstreamFlags : Flags which internal information about the bitstream - * nBitstreamVersion : Bitstream version - * nMaxEncodeFrameSize: Max encoded frame size - * bEnablePostFilter : Turn on/off post filter - * bEnableTemporalInterpolation : Turn on/off temporal interpolation - * bEnableLatencyMode : When enabled, the decoder does not display a decoded - * frame until it has detected that no enhancement layer - * frames or dependent B frames will be coming. This - * detection usually occurs when a subsequent non-B - * frame is encountered - */ -typedef struct OMX_VIDEO_PARAM_RVTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_VIDEO_RVFORMATTYPE eFormat; - OMX_U16 nBitsPerPixel; - OMX_U16 nPaddedWidth; - OMX_U16 nPaddedHeight; - OMX_U32 nFrameRate; - OMX_U32 nBitstreamFlags; - OMX_U32 nBitstreamVersion; - OMX_U32 nMaxEncodeFrameSize; - OMX_BOOL bEnablePostFilter; - OMX_BOOL bEnableTemporalInterpolation; - OMX_BOOL bEnableLatencyMode; -} OMX_VIDEO_PARAM_RVTYPE; - - -/** - * AVC profile types, each profile indicates support for various - * performance bounds and different annexes. - */ -typedef enum OMX_VIDEO_AVCPROFILETYPE { - OMX_VIDEO_AVCProfileBaseline = 0x01, /**< Baseline profile */ - OMX_VIDEO_AVCProfileMain = 0x02, /**< Main profile */ - OMX_VIDEO_AVCProfileExtended = 0x04, /**< Extended profile */ - OMX_VIDEO_AVCProfileHigh = 0x08, /**< High profile */ - OMX_VIDEO_AVCProfileHigh10 = 0x10, /**< High 10 profile */ - OMX_VIDEO_AVCProfileHigh422 = 0x20, /**< High 4:2:2 profile */ - OMX_VIDEO_AVCProfileHigh444 = 0x40, /**< High 4:4:4 profile */ - OMX_VIDEO_AVCProfileKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_AVCProfileVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_AVCProfileMax = 0x7FFFFFFF -} OMX_VIDEO_AVCPROFILETYPE; - - -/** - * AVC level types, each level indicates support for various frame sizes, - * bit rates, decoder frame rates. No need - */ -typedef enum OMX_VIDEO_AVCLEVELTYPE { - OMX_VIDEO_AVCLevel1 = 0x01, /**< Level 1 */ - OMX_VIDEO_AVCLevel1b = 0x02, /**< Level 1b */ - OMX_VIDEO_AVCLevel11 = 0x04, /**< Level 1.1 */ - OMX_VIDEO_AVCLevel12 = 0x08, /**< Level 1.2 */ - OMX_VIDEO_AVCLevel13 = 0x10, /**< Level 1.3 */ - OMX_VIDEO_AVCLevel2 = 0x20, /**< Level 2 */ - OMX_VIDEO_AVCLevel21 = 0x40, /**< Level 2.1 */ - OMX_VIDEO_AVCLevel22 = 0x80, /**< Level 2.2 */ - OMX_VIDEO_AVCLevel3 = 0x100, /**< Level 3 */ - OMX_VIDEO_AVCLevel31 = 0x200, /**< Level 3.1 */ - OMX_VIDEO_AVCLevel32 = 0x400, /**< Level 3.2 */ - OMX_VIDEO_AVCLevel4 = 0x800, /**< Level 4 */ - OMX_VIDEO_AVCLevel41 = 0x1000, /**< Level 4.1 */ - OMX_VIDEO_AVCLevel42 = 0x2000, /**< Level 4.2 */ - OMX_VIDEO_AVCLevel5 = 0x4000, /**< Level 5 */ - OMX_VIDEO_AVCLevel51 = 0x8000, /**< Level 5.1 */ - OMX_VIDEO_AVCLevel52 = 0x10000, /**< Level 5.2 */ - OMX_VIDEO_AVCLevelKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_AVCLevelVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_AVCLevelMax = 0x7FFFFFFF -} OMX_VIDEO_AVCLEVELTYPE; - - -/** - * AVC loop filter modes - * - * OMX_VIDEO_AVCLoopFilterEnable : Enable - * OMX_VIDEO_AVCLoopFilterDisable : Disable - * OMX_VIDEO_AVCLoopFilterDisableSliceBoundary : Disabled on slice boundaries - */ -typedef enum OMX_VIDEO_AVCLOOPFILTERTYPE { - OMX_VIDEO_AVCLoopFilterEnable = 0, - OMX_VIDEO_AVCLoopFilterDisable, - OMX_VIDEO_AVCLoopFilterDisableSliceBoundary, - OMX_VIDEO_AVCLoopFilterKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_AVCLoopFilterVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_AVCLoopFilterMax = 0x7FFFFFFF -} OMX_VIDEO_AVCLOOPFILTERTYPE; - - -/** - * AVC params - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * nSliceHeaderSpacing : Number of macroblocks between slice header, put - * zero if not used - * nPFrames : Number of P frames between each I frame - * nBFrames : Number of B frames between each I frame - * bUseHadamard : Enable/disable Hadamard transform - * nRefFrames : Max number of reference frames to use for inter - * motion search (1-16) - * nRefIdxTrailing : Pic param set ref frame index (index into ref - * frame buffer of trailing frames list), B frame - * support - * nRefIdxForward : Pic param set ref frame index (index into ref - * frame buffer of forward frames list), B frame - * support - * bEnableUEP : Enable/disable unequal error protection. This - * is only valid of data partitioning is enabled. - * bEnableFMO : Enable/disable flexible macroblock ordering - * bEnableASO : Enable/disable arbitrary slice ordering - * bEnableRS : Enable/disable sending of redundant slices - * eProfile : AVC profile(s) to use - * eLevel : AVC level(s) to use - * nAllowedPictureTypes : Specifies the picture types allowed in the - * bitstream - * bFrameMBsOnly : specifies that every coded picture of the - * coded video sequence is a coded frame - * containing only frame macroblocks - * bMBAFF : Enable/disable switching between frame and - * field macroblocks within a picture - * bEntropyCodingCABAC : Entropy decoding method to be applied for the - * syntax elements for which two descriptors appear - * in the syntax tables - * bWeightedPPrediction : Enable/disable weighted prediction shall not - * be applied to P and SP slices - * nWeightedBipredicitonMode : Default weighted prediction is applied to B - * slices - * bconstIpred : Enable/disable intra prediction - * bDirect8x8Inference : Specifies the method used in the derivation - * process for luma motion vectors for B_Skip, - * B_Direct_16x16 and B_Direct_8x8 as specified - * in subclause 8.4.1.2 of the AVC spec - * bDirectSpatialTemporal : Flag indicating spatial or temporal direct - * mode used in B slice coding (related to - * bDirect8x8Inference) . Spatial direct mode is - * more common and should be the default. - * nCabacInitIdx : Index used to init CABAC contexts - * eLoopFilterMode : Enable/disable loop filter - */ -typedef struct OMX_VIDEO_PARAM_AVCTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nSliceHeaderSpacing; - OMX_U32 nPFrames; - OMX_U32 nBFrames; - OMX_BOOL bUseHadamard; - OMX_U32 nRefFrames; - OMX_U32 nRefIdx10ActiveMinus1; - OMX_U32 nRefIdx11ActiveMinus1; - OMX_BOOL bEnableUEP; - OMX_BOOL bEnableFMO; - OMX_BOOL bEnableASO; - OMX_BOOL bEnableRS; - OMX_VIDEO_AVCPROFILETYPE eProfile; - OMX_VIDEO_AVCLEVELTYPE eLevel; - OMX_U32 nAllowedPictureTypes; - OMX_BOOL bFrameMBsOnly; - OMX_BOOL bMBAFF; - OMX_BOOL bEntropyCodingCABAC; - OMX_BOOL bWeightedPPrediction; - OMX_U32 nWeightedBipredicitonMode; - OMX_BOOL bconstIpred ; - OMX_BOOL bDirect8x8Inference; - OMX_BOOL bDirectSpatialTemporal; - OMX_U32 nCabacInitIdc; - OMX_VIDEO_AVCLOOPFILTERTYPE eLoopFilterMode; -} OMX_VIDEO_PARAM_AVCTYPE; - -typedef struct OMX_VIDEO_PARAM_PROFILELEVELTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 eProfile; /**< type is OMX_VIDEO_AVCPROFILETYPE, OMX_VIDEO_H263PROFILETYPE, - or OMX_VIDEO_MPEG4PROFILETYPE depending on context */ - OMX_U32 eLevel; /**< type is OMX_VIDEO_AVCLEVELTYPE, OMX_VIDEO_H263LEVELTYPE, - or OMX_VIDEO_MPEG4PROFILETYPE depending on context */ - OMX_U32 nProfileIndex; /**< Used to query for individual profile support information, - This parameter is valid only for - OMX_IndexParamVideoProfileLevelQuerySupported index, - For all other indices this parameter is to be ignored. */ -} OMX_VIDEO_PARAM_PROFILELEVELTYPE; - -/** - * Structure for dynamically configuring bitrate mode of a codec. - * - * STRUCT MEMBERS: - * nSize : Size of the struct in bytes - * nVersion : OMX spec version info - * nPortIndex : Port that this struct applies to - * nEncodeBitrate : Target average bitrate to be generated in bps - */ -typedef struct OMX_VIDEO_CONFIG_BITRATETYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nEncodeBitrate; -} OMX_VIDEO_CONFIG_BITRATETYPE; - -/** - * Defines Encoder Frame Rate setting - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * xEncodeFramerate : Encoding framerate represented in Q16 format - */ -typedef struct OMX_CONFIG_FRAMERATETYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 xEncodeFramerate; /* Q16 format */ -} OMX_CONFIG_FRAMERATETYPE; - -typedef struct OMX_CONFIG_INTRAREFRESHVOPTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL IntraRefreshVOP; -} OMX_CONFIG_INTRAREFRESHVOPTYPE; - -typedef struct OMX_CONFIG_MACROBLOCKERRORMAPTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nErrMapSize; /* Size of the Error Map in bytes */ - OMX_U8 ErrMap[1]; /* Error map hint */ -} OMX_CONFIG_MACROBLOCKERRORMAPTYPE; - -typedef struct OMX_CONFIG_MBERRORREPORTINGTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bEnabled; -} OMX_CONFIG_MBERRORREPORTINGTYPE; - -typedef struct OMX_PARAM_MACROBLOCKSTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nMacroblocks; -} OMX_PARAM_MACROBLOCKSTYPE; - -/** - * AVC Slice Mode modes - * - * OMX_VIDEO_SLICEMODE_AVCDefault : Normal frame encoding, one slice per frame - * OMX_VIDEO_SLICEMODE_AVCMBSlice : NAL mode, number of MBs per frame - * OMX_VIDEO_SLICEMODE_AVCByteSlice : NAL mode, number of bytes per frame - */ -typedef enum OMX_VIDEO_AVCSLICEMODETYPE { - OMX_VIDEO_SLICEMODE_AVCDefault = 0, - OMX_VIDEO_SLICEMODE_AVCMBSlice, - OMX_VIDEO_SLICEMODE_AVCByteSlice, - OMX_VIDEO_SLICEMODE_AVCKhronosExtensions = 0x6F000000, /**< Reserved region for introducing Khronos Standard Extensions */ - OMX_VIDEO_SLICEMODE_AVCVendorStartUnused = 0x7F000000, /**< Reserved region for introducing Vendor Extensions */ - OMX_VIDEO_SLICEMODE_AVCLevelMax = 0x7FFFFFFF -} OMX_VIDEO_AVCSLICEMODETYPE; - -/** - * AVC FMO Slice Mode Params - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * nNumSliceGroups : Specifies the number of slice groups - * nSliceGroupMapType : Specifies the type of slice groups - * eSliceMode : Specifies the type of slice - */ -typedef struct OMX_VIDEO_PARAM_AVCSLICEFMO { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U8 nNumSliceGroups; - OMX_U8 nSliceGroupMapType; - OMX_VIDEO_AVCSLICEMODETYPE eSliceMode; -} OMX_VIDEO_PARAM_AVCSLICEFMO; - -/** - * AVC IDR Period Configs - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * nIDRPeriod : Specifies periodicity of IDR frames - * nPFrames : Specifies internal of coding Intra frames - */ -typedef struct OMX_VIDEO_CONFIG_AVCINTRAPERIOD { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nIDRPeriod; - OMX_U32 nPFrames; -} OMX_VIDEO_CONFIG_AVCINTRAPERIOD; - -/** - * AVC NAL Size Configs - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * nNaluBytes : Specifies the NAL unit size - */ -typedef struct OMX_VIDEO_CONFIG_NALSIZE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nNaluBytes; -} OMX_VIDEO_CONFIG_NALSIZE; - - -/** - * Deinterlace Config - * - * STRUCT MEMBERS: - * nSize : Size of the structure in bytes - * nVersion : OMX specification version information - * nPortIndex : Port that this structure applies to - * nEnable : Specifies to enable deinterlace - */ -typedef struct OMX_VIDEO_CONFIG_DEINTERLACE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_U32 nEnable; -} OMX_VIDEO_CONFIG_DEINTERLACE; - -/** @} */ - -#ifdef __cplusplus -} -#endif /* __cplusplus */ - -#endif -/* File EOF */ - diff --git a/selfdrive/frogpilot/screenrecorder/openmax/include/OMX_VideoExt.h b/selfdrive/frogpilot/screenrecorder/openmax/include/OMX_VideoExt.h deleted file mode 100644 index 5bf6fd4..0000000 --- a/selfdrive/frogpilot/screenrecorder/openmax/include/OMX_VideoExt.h +++ /dev/null @@ -1,166 +0,0 @@ -/* - * Copyright (c) 2010 The Khronos Group Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining - * a copy of this software and associated documentation files (the - * "Software"), to deal in the Software without restriction, including - * without limitation the rights to use, copy, modify, merge, publish, - * distribute, sublicense, and/or sell copies of the Software, and to - * permit persons to whom the Software is furnished to do so, subject - * to the following conditions: - * The above copyright notice and this permission notice shall be included - * in all copies or substantial portions of the Software. - * - * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS - * OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. - * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY - * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, - * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE - * SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - * - */ - -/** OMX_VideoExt.h - OpenMax IL version 1.1.2 - * The OMX_VideoExt header file contains extensions to the - * definitions used by both the application and the component to - * access video items. - */ - -#ifndef OMX_VideoExt_h -#define OMX_VideoExt_h - -#ifdef __cplusplus -extern "C" { -#endif /* __cplusplus */ - -/* Each OMX header shall include all required header files to allow the - * header to compile without errors. The includes below are required - * for this header file to compile successfully - */ -#include - -/** NALU Formats */ -typedef enum OMX_NALUFORMATSTYPE { - OMX_NaluFormatStartCodes = 1, - OMX_NaluFormatOneNaluPerBuffer = 2, - OMX_NaluFormatOneByteInterleaveLength = 4, - OMX_NaluFormatTwoByteInterleaveLength = 8, - OMX_NaluFormatFourByteInterleaveLength = 16, - OMX_NaluFormatCodingMax = 0x7FFFFFFF -} OMX_NALUFORMATSTYPE; - -/** NAL Stream Format */ -typedef struct OMX_NALSTREAMFORMATTYPE{ - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_NALUFORMATSTYPE eNaluFormat; -} OMX_NALSTREAMFORMATTYPE; - -/** VP8 profiles */ -typedef enum OMX_VIDEO_VP8PROFILETYPE { - OMX_VIDEO_VP8ProfileMain = 0x01, - OMX_VIDEO_VP8ProfileUnknown = 0x6EFFFFFF, - OMX_VIDEO_VP8ProfileMax = 0x7FFFFFFF -} OMX_VIDEO_VP8PROFILETYPE; - -/** VP8 levels */ -typedef enum OMX_VIDEO_VP8LEVELTYPE { - OMX_VIDEO_VP8Level_Version0 = 0x01, - OMX_VIDEO_VP8Level_Version1 = 0x02, - OMX_VIDEO_VP8Level_Version2 = 0x04, - OMX_VIDEO_VP8Level_Version3 = 0x08, - OMX_VIDEO_VP8LevelUnknown = 0x6EFFFFFF, - OMX_VIDEO_VP8LevelMax = 0x7FFFFFFF -} OMX_VIDEO_VP8LEVELTYPE; - -/** VP8 Param */ -typedef struct OMX_VIDEO_PARAM_VP8TYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_VIDEO_VP8PROFILETYPE eProfile; - OMX_VIDEO_VP8LEVELTYPE eLevel; - OMX_U32 nDCTPartitions; - OMX_BOOL bErrorResilientMode; -} OMX_VIDEO_PARAM_VP8TYPE; - -/** Structure for configuring VP8 reference frames */ -typedef struct OMX_VIDEO_VP8REFERENCEFRAMETYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bPreviousFrameRefresh; - OMX_BOOL bGoldenFrameRefresh; - OMX_BOOL bAlternateFrameRefresh; - OMX_BOOL bUsePreviousFrame; - OMX_BOOL bUseGoldenFrame; - OMX_BOOL bUseAlternateFrame; -} OMX_VIDEO_VP8REFERENCEFRAMETYPE; - -/** Structure for querying VP8 reference frame type */ -typedef struct OMX_VIDEO_VP8REFERENCEFRAMEINFOTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_BOOL bIsIntraFrame; - OMX_BOOL bIsGoldenOrAlternateFrame; -} OMX_VIDEO_VP8REFERENCEFRAMEINFOTYPE; - -/** HEVC Profiles */ -typedef enum OMX_VIDEO_HEVCPROFILETYPE { - OMX_VIDEO_HEVCProfileMain = 0x01, - OMX_VIDEO_HEVCProfileMain10 = 0x02, - OMX_VIDEO_HEVCProfileUnknown = 0x6EFFFFFF, - OMX_VIDEO_HEVCProfileMax = 0x7FFFFFFF -} OMX_VIDEO_HEVCPROFILETYPE; - -/** HEVC levels */ -typedef enum OMX_VIDEO_HEVCLEVELTYPE { - OMX_VIDEO_HEVCLevel_Version0 = 0x0, - OMX_VIDEO_HEVCMainTierLevel1 = 0x1, - OMX_VIDEO_HEVCHighTierLevel1 = 0x2, - OMX_VIDEO_HEVCMainTierLevel2 = 0x4, - OMX_VIDEO_HEVCHighTierLevel2 = 0x8, - OMX_VIDEO_HEVCMainTierLevel21 = 0x10, - OMX_VIDEO_HEVCHighTierLevel21 = 0x20, - OMX_VIDEO_HEVCMainTierLevel3 = 0x40, - OMX_VIDEO_HEVCHighTierLevel3 = 0x80, - OMX_VIDEO_HEVCMainTierLevel31 = 0x100, - OMX_VIDEO_HEVCHighTierLevel31 = 0x200, - OMX_VIDEO_HEVCMainTierLevel4 = 0x400, - OMX_VIDEO_HEVCHighTierLevel4 = 0x800, - OMX_VIDEO_HEVCMainTierLevel41 = 0x1000, - OMX_VIDEO_HEVCHighTierLevel41 = 0x2000, - OMX_VIDEO_HEVCMainTierLevel5 = 0x4000, - OMX_VIDEO_HEVCHighTierLevel5 = 0x8000, - OMX_VIDEO_HEVCMainTierLevel51 = 0x10000, - OMX_VIDEO_HEVCHighTierLevel51 = 0x20000, - OMX_VIDEO_HEVCMainTierLevel52 = 0x40000, - OMX_VIDEO_HEVCHighTierLevel52 = 0x80000, - OMX_VIDEO_HEVCMainTierLevel6 = 0x100000, - OMX_VIDEO_HEVCHighTierLevel6 = 0x200000, - OMX_VIDEO_HEVCMainTierLevel61 = 0x400000, - OMX_VIDEO_HEVCHighTierLevel61 = 0x800000, - OMX_VIDEO_HEVCMainTierLevel62 = 0x1000000, - OMX_VIDEO_HEVCLevelUnknown = 0x6EFFFFFF, - OMX_VIDEO_HEVCLevelMax = 0x7FFFFFFF -} OMX_VIDEO_HEVCLEVELTYPE; - -/** HEVC Param */ -typedef struct OMX_VIDEO_PARAM_HEVCTYPE { - OMX_U32 nSize; - OMX_VERSIONTYPE nVersion; - OMX_U32 nPortIndex; - OMX_VIDEO_HEVCPROFILETYPE eProfile; - OMX_VIDEO_HEVCLEVELTYPE eLevel; -} OMX_VIDEO_PARAM_HEVCTYPE; - - -#ifdef __cplusplus -} -#endif /* __cplusplus */ - -#endif /* OMX_VideoExt_h */ -/* File EOF */ diff --git a/selfdrive/frogpilot/screenrecorder/screenrecorder.cc b/selfdrive/frogpilot/screenrecorder/screenrecorder.cc deleted file mode 100644 index 21f3265..0000000 --- a/selfdrive/frogpilot/screenrecorder/screenrecorder.cc +++ /dev/null @@ -1,155 +0,0 @@ -#include "libyuv.h" - -#include "selfdrive/frogpilot/screenrecorder/screenrecorder.h" -#include "selfdrive/ui/qt/util.h" - -static long long milliseconds() { - struct timespec t; - clock_gettime(CLOCK_REALTIME, &t); - return static_cast(t.tv_sec * 1000.0 + t.tv_nsec * 1e-6); -} - -ScreenRecorder::ScreenRecorder(QWidget *parent) : QPushButton(parent), image_queue(30), recording(false), started(0), frame(0) { - setFixedSize(192 / 2 + 25, 192 / 2); - setFocusPolicy(Qt::NoFocus); - - screen_height = 1080; - screen_width = 2160; - recording_height = 720; - recording_width = (screen_width * recording_height) / screen_height + (recording_width % 2); - - rgb_scale_buffer = std::make_unique(recording_width * recording_height * 4); - - connect(this, &QPushButton::released, this, &ScreenRecorder::toggle); - - initializeEncoder(); -} - -void ScreenRecorder::initializeEncoder() { - const std::string path = "/data/media/0/videos"; - encoder = std::make_unique(path.c_str(), recording_width, recording_height, 60, 2 * 1024 * 1024, false, false); -} - -ScreenRecorder::~ScreenRecorder() { - stop(); -} - -void ScreenRecorder::applyColor() { - if (frame % (UI_FREQ / 2) == 0) { - recording_color = (frame % UI_FREQ < (UI_FREQ / 2)) ? QColor::fromRgbF(1, 1, 1, 1) : QColor::fromRgbF(0, 0, 0, 1); - update(); - } -} - -void ScreenRecorder::paintEvent(QPaintEvent *event) { - QPainter p(this); - p.setRenderHint(QPainter::Antialiasing); - - QRect fullRect(0, 0, 192 / 2, 192 / 2); - QColor outerColor = recording ? recording_color : QColor::fromRgbF(1, 1, 1, 1); - int outerRedWidth = fullRect.width() * 0.05; - - QRect outerRect = fullRect; - p.setBrush(outerColor); - p.setPen(Qt::NoPen); - p.drawEllipse(outerRect); - - QRect middleRect = fullRect.marginsRemoved(QMargins(outerRedWidth, outerRedWidth, outerRedWidth, outerRedWidth)); - p.setBrush(QColor::fromRgbF(1, 0, 0, 1)); - p.drawEllipse(middleRect); -} - -void ScreenRecorder::openEncoder(const char *filename) { - encoder->encoder_open(filename); -} - -void ScreenRecorder::closeEncoder() { - if (encoder) { - encoder->encoder_close(); - } -} - -void ScreenRecorder::toggle() { - if (!recording) { - start(); - } else { - stop(); - } -} - -void ScreenRecorder::start() { - if (recording) return; - - char filename[64]; - const time_t t = time(NULL); - const struct tm tm = *localtime(&t); - snprintf(filename, sizeof(filename), "%04d%02d%02d-%02d%02d%02d.mp4", - tm.tm_year + 1900, tm.tm_mon + 1, tm.tm_mday, - tm.tm_hour, tm.tm_min, tm.tm_sec); - - recording = true; - frame = 0; - QWidget *widget = this; - while (widget->parentWidget() != nullptr) { - widget = widget->parentWidget(); - } - rootWidget = widget; - openEncoder(filename); - encoding_thread = std::thread(&ScreenRecorder::encoding_thread_func, this); - - update(); - started = milliseconds(); -} - -void ScreenRecorder::encoding_thread_func() { - const uint64_t start_time = nanos_since_boot(); - while (recording && encoder) { - QImage popImage; - if (image_queue.pop_wait_for(popImage, std::chrono::milliseconds(10))) { - const QImage image = popImage.convertToFormat(QImage::Format_RGBA8888); - libyuv::ARGBScale(image.bits(), image.width() * 4, - image.width(), image.height(), - rgb_scale_buffer.get(), recording_width * 4, - recording_width, recording_height, - libyuv::kFilterLinear); - encoder->encode_frame_rgba(rgb_scale_buffer.get(), recording_width, recording_height, - static_cast(nanos_since_boot() - start_time)); - } - } -} - -void ScreenRecorder::stop() { - if (!recording) return; - - recording = false; - update(); - - if (encoding_thread.joinable()) { - encoding_thread.join(); - } - closeEncoder(); - image_queue.clear(); -} - -void ScreenRecorder::update_screen() { - if (!uiState()->scene.started) { - if (recording) { - stop(); - } - return; - } - if (!recording) return; - - if (milliseconds() - started > 1000 * 60 * 3) { - stop(); - start(); - return; - } - - applyColor(); - if (rootWidget != nullptr) { - const QPixmap pixmap = rootWidget->grab(); - image_queue.push(pixmap.toImage()); - } - frame++; -} diff --git a/selfdrive/frogpilot/screenrecorder/screenrecorder.h b/selfdrive/frogpilot/screenrecorder/screenrecorder.h deleted file mode 100644 index b7f89c1..0000000 --- a/selfdrive/frogpilot/screenrecorder/screenrecorder.h +++ /dev/null @@ -1,55 +0,0 @@ -#pragma once - -#include - -#include "omx_encoder.h" -#include "blocking_queue.h" -#include "selfdrive/ui/ui.h" - -class ScreenRecorder : public QPushButton { -#ifdef NO_SR - public: - explicit ScreenRecorder(QWidget *parent = nullptr){} - ~ScreenRecorder() override{} - - void update_screen(){} - void toggle(){} -#else - Q_OBJECT - -public: - explicit ScreenRecorder(QWidget *parent = nullptr); - ~ScreenRecorder() override; - - void update_screen(); - void toggle(); - -protected: - void paintEvent(QPaintEvent *event) override; - -private: - void applyColor(); - void closeEncoder(); - void encoding_thread_func(); - void initializeEncoder(); - void openEncoder(const char *filename); - void start(); - void stop(); - - bool recording; - int frame; - int recording_height; - int recording_width; - int screen_height; - int screen_width; - long long started = 0; - - std::unique_ptr encoder; - std::unique_ptr rgb_scale_buffer; - std::thread encoding_thread; - - BlockingQueue image_queue; - QColor recording_color; - QWidget *rootWidget; -#endif //NO_SR -}; diff --git a/selfdrive/frogpilot/ui/control_settings.cc b/selfdrive/frogpilot/ui/control_settings.cc deleted file mode 100644 index 284f69d..0000000 --- a/selfdrive/frogpilot/ui/control_settings.cc +++ /dev/null @@ -1,729 +0,0 @@ -#include "selfdrive/frogpilot/ui/control_settings.h" - -FrogPilotControlsPanel::FrogPilotControlsPanel(SettingsWindow *parent) : FrogPilotListWidget(parent) { - const std::vector> controlToggles { - {"AdjustablePersonalities", "Adjustable Personalities", "Use the 'Distance' button on the steering wheel or the onroad UI to switch between openpilot's driving personalities.\n\n1 bar = Aggressive\n2 bars = Standard\n3 bars = Relaxed", "../frogpilot/assets/toggle_icons/icon_distance.png"}, - - {"AlwaysOnLateral", "Always on Lateral", "Maintain openpilot lateral control when the brake or gas pedals are used.\n\nDeactivation occurs only through the 'Cruise Control' button.", "../frogpilot/assets/toggle_icons/icon_always_on_lateral.png"}, - {"AlwaysOnLateralMain", "Enable On Cruise Main", "Enable 'Always On Lateral' by simply turning on 'Cruise Control'.", ""}, - {"HideAOLStatusBar", "Hide the Status Bar", "Don't use the status bar for 'Always On Lateral'.", ""}, - - {"ConditionalExperimental", "Conditional Experimental Mode", "Automatically switches to 'Experimental Mode' under predefined conditions.", "../frogpilot/assets/toggle_icons/icon_conditional.png"}, - {"CECurves", "Curve Detected Ahead", "Switch to 'Experimental Mode' when a curve is detected.", ""}, - {"CENavigation", "Navigation Based", "Switch to 'Experimental Mode' based on navigation data. (i.e. Intersections, stop signs, etc.)", ""}, - {"CESlowerLead", "Slower Lead Detected Ahead", "Switch to 'Experimental Mode' when a slower lead vehicle is detected ahead.", ""}, - {"CEStopLights", "Stop Lights and Stop Signs", "Switch to 'Experimental Mode' when a stop light or stop sign is detected.", ""}, - {"CESignal", "Turn Signal When Below Highway Speeds", "Switch to 'Experimental Mode' when using turn signals below highway speeds to help assit with turns.", ""}, - {"HideCEMStatusBar", "Hide the Status Bar", "Don't use the status bar for 'Conditional Experimental Mode'.", ""}, - - {"CustomPersonalities", "Custom Driving Personalities", "Customize the driving personality profiles to your driving style.", "../frogpilot/assets/toggle_icons/icon_custom.png"}, - {"DeviceShutdown", "Device Shutdown Timer", "Configure the timer for automatic device shutdown when offroad conserving energy and preventing battery drain.", "../frogpilot/assets/toggle_icons/icon_time.png"}, - - {"ExperimentalModeActivation", "Experimental Mode Activation", "Toggle Experimental Mode with either buttons on ethe steering wheel or the screen.\n\nOverrides 'Conditional Experimental Mode'.", "../assets/img_experimental_white.svg"}, - {"ExperimentalModeViaLKAS", "Double Clicking the LKAS Button", "Enable/disable 'Experimental Mode' by double clicking the 'LKAS' button on your steering wheel.", ""}, - {"ExperimentalModeViaScreen", "Double Taping the Onroad UI", "Enable/disable 'Experimental Mode' by double taping the onroad UI within a 0.5 second time frame.", ""}, - {"ExperimentalModeViaDistance", "Long Pressing the Distance Button", "Enable/disable 'Experimental Mode' by holding down the 'distance' button on your steering wheel for 0.5 seconds.", ""}, - - {"FireTheBabysitter", "Fire the Babysitter", "Deactivate some of openpilot's 'Babysitter' protocols for more user autonomy.", "../frogpilot/assets/toggle_icons/icon_babysitter.png"}, - {"MuteOverheated", "Bypass Thermal Safety Limits", "Allow the device to run at any temperature even above comma's recommended thermal limits.", ""}, - {"NoLogging", "Disable Logging", "Turn off all data tracking to enhance privacy or reduce thermal load.\n\nWARNING: This action will prevent drive recording and data cannot be recovered!", ""}, - {"NoUploads", "Disable Uploads", "Turn off all data uploads to comma's servers.\n\nWARNING: This action will prevent your drives from appearing on comma connect which may impact debugging and support!", ""}, - {"OfflineMode", "Offline Mode", "Allow the device to be offline indefinitely.", ""}, - - {"LateralTune", "Lateral Tuning", "Modify openpilot's steering behavior.", "../frogpilot/assets/toggle_icons/icon_lateral_tune.png"}, - {"ForceAutoTune", "Force Auto Tune", "Forces comma's auto lateral tuning for unsupported vehicles.", ""}, - {"NNFF", "NNFF - Neural Network Feedforward", "Use Twilsonco's Neural Network Feedforward for enhanced precision in lateral control.", ""}, - {"SteerRatio", steerRatioStock != 0 ? QString("Steer Ratio (Default: %1)").arg(steerRatioStock, 0, 'f', 2) : "Steer Ratio", "Set a custom steer ratio for your vehicle controls.", ""}, - {"UseLateralJerk", "Use Lateral Jerk", "Include steer torque necessary to achieve desired steer rate (lateral jerk).", ""}, - - {"LongitudinalTune", "Longitudinal Tuning", "Modify openpilot's acceleration and braking behavior.", "../frogpilot/assets/toggle_icons/icon_longitudinal_tune.png"}, - {"AccelerationProfile", "Acceleration Profile", "Change the acceleration rate to be either sporty or eco-friendly.", ""}, - {"DecelerationProfile", "Deceleration Profile", "Change the deceleration rate to be either sporty or eco-friendly.", ""}, - {"AggressiveAcceleration", "Aggressive Acceleration With Lead", "Increase acceleration aggressiveness when following a lead vehicle from a stop.", ""}, - {"StoppingDistance", "Increase Stop Distance Behind Lead", "Increase the stopping distance for a more comfortable stop from lead vehicles.", ""}, - {"LeadDetectionThreshold", "Lead Detection Threshold", "Increase or decrease the lead detection threshold to either detect leads sooner, or increase model confidence.", ""}, - {"SmoothBraking", "Smoother Braking Behind Lead", "Smoothen out the braking behavior when approaching slower vehicles.", ""}, - {"TrafficMode", "Traffic Mode", "Hold down the 'distance' button for 2.5 seconds to enable more aggressive driving behavior catered towards stop and go traffic.", ""}, - - {"Model", "Model Selector", "Choose your preferred openpilot model.", "../assets/offroad/icon_calibration.png"}, - - {"MTSCEnabled", "Map Turn Speed Control", "Slow down for anticipated curves detected by your downloaded maps.", "../frogpilot/assets/toggle_icons/icon_speed_map.png"}, - {"DisableMTSCSmoothing", "Disable MTSC UI Smoothing", "Disables the smoothing for the requested speed in the onroad UI.", ""}, - {"MTSCCurvatureCheck", "Model Curvature Detection Failsafe", "Only trigger MTSC when the model detects a curve in the road. Purely used as a failsafe to prevent false positives. Leave this off if you never experience false positives.", ""}, - {"MTSCLimit", "Speed Change Hard Cap", "Set a hard cap for MTSC. If MTSC requests a speed decrease greater than this value, it ignores the requested speed from MTSC. Purely used as a failsafe to prevent false positives. Leave this off if you never experience false positives.", ""}, - {"MTSCAggressiveness", "Turn Speed Aggressiveness", "Set turn speed aggressiveness. Higher values result in faster turns, lower values yield gentler turns.\n\nA change of +- 1% results in the velocity being raised or lowered by about 1 mph.", ""}, - - {"NudgelessLaneChange", "Nudgeless Lane Change", "Enable lane changes without manual steering input.", "../frogpilot/assets/toggle_icons/icon_lane.png"}, - {"LaneChangeTime", "Lane Change Timer", "Specify a delay before executing a nudgeless lane change.", ""}, - {"LaneDetection", "Lane Detection", "Block nudgeless lane changes when a lane isn't detected.", ""}, - {"LaneDetectionWidth", "Lane Detection Threshold", "Set the required lane width to be qualified as a lane.", ""}, - {"OneLaneChange", "One Lane Change Per Signal", "Limit to one nudgeless lane change per turn signal activation.", ""}, - - {"QOLControls", "Quality of Life", "Miscellaneous quality of life changes to improve your overall openpilot experience.", "../frogpilot/assets/toggle_icons/quality_of_life.png"}, - {"DisableOnroadUploads", "Disable Onroad Uploads", "Prevent large data uploads when onroad.", ""}, - {"HigherBitrate", "Higher Bitrate Recording", "Increases the quality of the footage uploaded to comma connect.", ""}, - {"NavChill", "Navigate on Chill Mode", "Allows cars without longitudinal support to navigate. Allows navigation without experimental mode.", ""}, - {"PauseLateralOnSignal", "Pause Lateral On Turn Signal Below", "Temporarily disable lateral control during turn signal use below the set speed.", ""}, - {"ReverseCruise", "Reverse Cruise Increase", "Reverses the 'long press' functionality when increasing the max set speed. Useful to increase the max speed quickly.", ""}, - {"SetSpeedOffset", "Set Speed Offset", "Set an offset for your desired set speed.", ""}, - - {"SpeedLimitController", "Speed Limit Controller", "Automatically adjust vehicle speed to match speed limits using 'Open Street Map's, 'Navigate On openpilot', or your car's dashboard (TSS2 Toyotas only).", "../assets/offroad/icon_speed_limit.png"}, - {"SLCControls", "Controls Settings", "Manage settings for the controls.", ""}, - {"Offset1", "Speed Limit Offset (0-34 mph)", "Speed limit offset for speed limits between 0-34 mph.", ""}, - {"Offset2", "Speed Limit Offset (35-54 mph)", "Speed limit offset for speed limits between 35-54 mph.", ""}, - {"Offset3", "Speed Limit Offset (55-64 mph)", "Speed limit offset for speed limits between 55-64 mph.", ""}, - {"Offset4", "Speed Limit Offset (65-99 mph)", "Speed limit offset for speed limits between 65-99 mph.", ""}, - {"SLCFallback", "Fallback Method", "Choose your fallback method for when there are no speed limits currently being obtained from Navigation, OSM, and the car's dashboard.", ""}, - {"SLCOverride", "Override Method", "Choose your preferred method to override the current speed limit.", ""}, - {"SLCPriority", "Priority Order", "Determine the priority order for what speed limits to use.", ""}, - {"SLCQOL", "Quality of Life Settings", "Manage quality of life settings.", ""}, - {"SLCConfirmation", "Confirm New Speed Limits", "Don't automatically start using the new speed limit until it's been manually confirmed first.", ""}, - {"ForceMPHDashboard", "Force MPH From Dashboard Readings", "Force MPH readings from the dashboard. Only use this if you live in an area where the speed limits from your dashboard are in KPH but you use MPH.", ""}, - {"SetSpeedLimit", "Use Current Speed Limit As Set Speed", "Sets your max speed to the current speed limit if one is populated when you initially enable openpilot.", ""}, - {"SLCVisuals", "Visuals Settings", "Manage visual settings.", ""}, - {"ShowSLCOffset", "Show Speed Limit Offset", "Show the speed limit offset seperated from the speed limit in the onroad UI when using 'Speed Limit Controller'.", ""}, - {"UseVienna", "Use Vienna Speed Limit Signs", "Use the Vienna (EU) speed limit style signs as opposed to MUTCD (US).", ""}, - - {"TurnDesires", "Use Turn Desires", "Use turn desires for enhanced precision in turns below the minimum lane change speed.", "../assets/navigation/direction_continue_right.png"}, - - {"VisionTurnControl", "Vision Turn Speed Controller", "Slow down for detected road curvature for smoother curve handling.", "../frogpilot/assets/toggle_icons/icon_vtc.png"}, - {"DisableVTSCSmoothing", "Disable VTSC UI Smoothing", "Disables the smoothing for the requested speed in the onroad UI.", ""}, - {"CurveSensitivity", "Curve Detection Sensitivity", "Set curve detection sensitivity. Higher values prompt earlier responses, lower values lead to smoother but later reactions.", ""}, - {"TurnAggressiveness", "Turn Speed Aggressiveness", "Set turn speed aggressiveness. Higher values result in faster turns, lower values yield gentler turns.", ""}, - }; - - for (const auto &[param, title, desc, icon] : controlToggles) { - ParamControl *toggle; - - if (param == "AdjustablePersonalities") { - std::vector adjustablePersonalitiesToggles{"PersonalitiesViaWheel", "PersonalitiesViaScreen"}; - std::vector adjustablePersonalitiesNames{tr("Distance Button"), tr("Screen")}; - toggle = new FrogPilotParamToggleControl(param, title, desc, icon, adjustablePersonalitiesToggles, adjustablePersonalitiesNames); - - } else if (param == "AlwaysOnLateral") { - FrogPilotParamManageControl *aolToggle = new FrogPilotParamManageControl(param, title, desc, icon, this); - QObject::connect(aolToggle, &FrogPilotParamManageControl::manageButtonClicked, this, [this]() { - parentToggleClicked(); - for (auto &[key, toggle] : toggles) { - toggle->setVisible(aolKeys.find(key.c_str()) != aolKeys.end()); - } - }); - toggle = aolToggle; - - } else if (param == "ConditionalExperimental") { - FrogPilotParamManageControl *conditionalExperimentalToggle = new FrogPilotParamManageControl(param, title, desc, icon, this); - QObject::connect(conditionalExperimentalToggle, &FrogPilotParamManageControl::manageButtonClicked, this, [this]() { - parentToggleClicked(); - conditionalSpeedsImperial->setVisible(!isMetric); - conditionalSpeedsMetric->setVisible(isMetric); - for (auto &[key, toggle] : toggles) { - toggle->setVisible(conditionalExperimentalKeys.find(key.c_str()) != conditionalExperimentalKeys.end()); - } - }); - toggle = conditionalExperimentalToggle; - } else if (param == "CECurves") { - FrogPilotParamValueControl *CESpeedImperial = new FrogPilotParamValueControl("CESpeed", "Below", "Switch to 'Experimental Mode' below this speed in absence of a lead vehicle.", "", 0, 99, - std::map(), this, false, " mph"); - FrogPilotParamValueControl *CESpeedLeadImperial = new FrogPilotParamValueControl("CESpeedLead", " w/Lead", "Switch to 'Experimental Mode' below this speed when following a lead vehicle.", "", 0, 99, - std::map(), this, false, " mph"); - conditionalSpeedsImperial = new FrogPilotDualParamControl(CESpeedImperial, CESpeedLeadImperial, this); - addItem(conditionalSpeedsImperial); - - FrogPilotParamValueControl *CESpeedMetric = new FrogPilotParamValueControl("CESpeed", "Below", "Switch to 'Experimental Mode' below this speed in absence of a lead vehicle.", "", 0, 150, - std::map(), this, false, " kph"); - FrogPilotParamValueControl *CESpeedLeadMetric = new FrogPilotParamValueControl("CESpeedLead", " w/Lead", "Switch to 'Experimental Mode' below this speed when following a lead vehicle.", "", 0, 150, - std::map(), this, false, " kph"); - conditionalSpeedsMetric = new FrogPilotDualParamControl(CESpeedMetric, CESpeedLeadMetric, this); - addItem(conditionalSpeedsMetric); - - std::vector curveToggles{"CECurvesLead"}; - std::vector curveToggleNames{tr("With Lead")}; - toggle = new FrogPilotParamToggleControl(param, title, desc, icon, curveToggles, curveToggleNames); - } else if (param == "CENavigation") { - std::vector navigationToggles{"CENavigationIntersections", "CENavigationTurns", "CENavigationLead"}; - std::vector navigationToggleNames{tr("Intersections"), tr("Turns"), tr("With Lead")}; - toggle = new FrogPilotParamToggleControl(param, title, desc, icon, navigationToggles, navigationToggleNames); - } else if (param == "CEStopLights") { - std::vector stopLightToggles{"CEStopLightsLead"}; - std::vector stopLightToggleNames{tr("With Lead")}; - toggle = new FrogPilotParamToggleControl(param, title, desc, icon, stopLightToggles, stopLightToggleNames); - - } else if (param == "CustomPersonalities") { - FrogPilotParamManageControl *customPersonalitiesToggle = new FrogPilotParamManageControl(param, title, desc, icon, this); - QObject::connect(customPersonalitiesToggle, &FrogPilotParamManageControl::manageButtonClicked, this, [this]() { - parentToggleClicked(); - for (auto &[key, toggle] : toggles) { - toggle->setVisible(false); - } - aggressiveProfile->setVisible(true); - standardProfile->setVisible(true); - relaxedProfile->setVisible(true); - }); - toggle = customPersonalitiesToggle; - - FrogPilotParamValueControl *aggressiveFollow = new FrogPilotParamValueControl("AggressiveFollow", "Follow", - "Set the 'Aggressive' personality' following distance. " - "Represents seconds to follow behind the lead vehicle.\n\nStock: 1.25 seconds.", - "../frogpilot/assets/other_images/aggressive.png", - 1, 5, std::map(), this, false, " sec", 1, 0.01); - FrogPilotParamValueControl *aggressiveJerk = new FrogPilotParamValueControl("AggressiveJerk", " Jerk", - "Configure brake/gas pedal responsiveness for the 'Aggressive' personality. " - "Higher jerk value = smoother rides.\nLower jerk value = faster response.\n\nStock: 0.5.", - "", - 0.01, 5, std::map(), this, false, "", 1, 0.01); - aggressiveProfile = new FrogPilotDualParamControl(aggressiveFollow, aggressiveJerk, this, true); - addItem(aggressiveProfile); - - FrogPilotParamValueControl *standardFollow = new FrogPilotParamValueControl("StandardFollow", "Follow", - "Set the 'Standard' personality following distance. " - "Represents seconds to follow behind the lead vehicle.\n\nStock: 1.45 seconds.", - "../frogpilot/assets/other_images/standard.png", - 1, 5, std::map(), this, false, " sec", 1, 0.01); - FrogPilotParamValueControl *standardJerk = new FrogPilotParamValueControl("StandardJerk", " Jerk", - "Adjust brake/gas pedal responsiveness for the 'Standard' personality. " - "Higher jerk value = smoother rides.\nLower jerk value = faster response.\n\nStock: 1.0.", - "", - 0.01, 5, std::map(), this, false, "", 1, 0.01); - standardProfile = new FrogPilotDualParamControl(standardFollow, standardJerk, this, true); - addItem(standardProfile); - - FrogPilotParamValueControl *relaxedFollow = new FrogPilotParamValueControl("RelaxedFollow", "Follow", - "Set the 'Relaxed' personality following distance. " - "Represents seconds to follow behind the lead vehicle.\n\nStock: 1.75 seconds.", - "../frogpilot/assets/other_images/relaxed.png", - 1, 5, std::map(), this, false, " sec", 1, 0.01); - FrogPilotParamValueControl *relaxedJerk = new FrogPilotParamValueControl("RelaxedJerk", " Jerk", - "Set brake/gas pedal responsiveness for the 'Relaxed' personality. " - "Higher jerk value = smoother rides.\nLower jerk value = faster response.\n\nStock: 1.0.", - "", - 0.01, 5, std::map(), this, false, "", 1, 0.01); - relaxedProfile = new FrogPilotDualParamControl(relaxedFollow, relaxedJerk, this, true); - addItem(relaxedProfile); - - } else if (param == "DeviceShutdown") { - std::map shutdownLabels; - for (int i = 0; i <= 33; ++i) { - shutdownLabels[i] = i == 0 ? "Instant" : i <= 3 ? QString::number(i * 15) + " mins" : QString::number(i - 3) + (i == 4 ? " hour" : " hours"); - } - toggle = new FrogPilotParamValueControl(param, title, desc, icon, 0, 33, shutdownLabels, this, false); - - } else if (param == "ExperimentalModeActivation") { - FrogPilotParamManageControl *experimentalModeActivationToggle = new FrogPilotParamManageControl(param, title, desc, icon, this); - QObject::connect(experimentalModeActivationToggle, &FrogPilotParamManageControl::manageButtonClicked, this, [this]() { - parentToggleClicked(); - for (auto &[key, toggle] : toggles) { - toggle->setVisible(experimentalModeActivationKeys.find(key.c_str()) != experimentalModeActivationKeys.end()); - } - }); - toggle = experimentalModeActivationToggle; - - } else if (param == "FireTheBabysitter") { - FrogPilotParamManageControl *fireTheBabysitterToggle = new FrogPilotParamManageControl(param, title, desc, icon, this); - QObject::connect(fireTheBabysitterToggle, &FrogPilotParamManageControl::manageButtonClicked, this, [this]() { - parentToggleClicked(); - for (auto &[key, toggle] : toggles) { - toggle->setVisible(fireTheBabysitterKeys.find(key.c_str()) != fireTheBabysitterKeys.end()); - } - }); - toggle = fireTheBabysitterToggle; - - } else if (param == "LateralTune") { - FrogPilotParamManageControl *lateralTuneToggle = new FrogPilotParamManageControl(param, title, desc, icon, this); - QObject::connect(lateralTuneToggle, &FrogPilotParamManageControl::manageButtonClicked, this, [this]() { - parentToggleClicked(); - for (auto &[key, toggle] : toggles) { - toggle->setVisible(lateralTuneKeys.find(key.c_str()) != lateralTuneKeys.end()); - } - }); - toggle = lateralTuneToggle; - } else if (param == "SteerRatio") { - toggle = new FrogPilotParamValueControl(param, title, desc, icon, steerRatioStock * 0.75, steerRatioStock * 1.25, std::map(), this, false, "", 1, 0.01); - - } else if (param == "LongitudinalTune") { - FrogPilotParamManageControl *longitudinalTuneToggle = new FrogPilotParamManageControl(param, title, desc, icon, this); - QObject::connect(longitudinalTuneToggle, &FrogPilotParamManageControl::manageButtonClicked, this, [this]() { - parentToggleClicked(); - for (auto &[key, toggle] : toggles) { - toggle->setVisible(longitudinalTuneKeys.find(key.c_str()) != longitudinalTuneKeys.end()); - } - }); - toggle = longitudinalTuneToggle; - } else if (param == "AccelerationProfile") { - std::vector profileOptions{tr("Standard"), tr("Eco"), tr("Sport"), tr("Sport+")}; - FrogPilotButtonParamControl *profileSelection = new FrogPilotButtonParamControl(param, title, desc, icon, profileOptions); - toggle = profileSelection; - - QObject::connect(static_cast(toggle), &FrogPilotButtonParamControl::buttonClicked, [this](int id) { - if (id == 3) { - FrogPilotConfirmationDialog::toggleAlert("WARNING: This maxes out openpilot's acceleration from 2.0 m/s to 4.0 m/s and may cause oscillations when accelerating!", - "I understand the risks.", this); - } - }); - } else if (param == "DecelerationProfile") { - std::vector profileOptions{tr("Standard"), tr("Eco"), tr("Sport")}; - FrogPilotButtonParamControl *profileSelection = new FrogPilotButtonParamControl(param, title, desc, icon, profileOptions); - toggle = profileSelection; - } else if (param == "StoppingDistance") { - toggle = new FrogPilotParamValueControl(param, title, desc, icon, 0, 10, std::map(), this, false, " feet"); - } else if (param == "LeadDetectionThreshold") { - toggle = new FrogPilotParamValueControl(param, title, desc, icon, 1, 100, std::map(), this, false, "%"); - - } else if (param == "Model") { - modelSelectorButton = new FrogPilotButtonIconControl(title, tr("SELECT"), desc, icon); - QStringList models = {"los-angeles", "certified-herbalist", "duck-amigo", "recertified-herbalist"}; - QStringList modelLabels = {"Los Angeles (Default)", "Certified Herbalist", "Duck Amigo", "Recertified Herbalist"}; - QObject::connect(modelSelectorButton, &FrogPilotButtonIconControl::clicked, this, [this, models, modelLabels]() { - QString selection = MultiOptionDialog::getSelection(tr("Select a driving model"), modelLabels, "", this); - - if (!selection.isEmpty()) { - int selectedModelIndex = modelLabels.indexOf(selection); - QString selectedModelValue = models[selectedModelIndex]; - params.put("Model", selectedModelValue.toStdString()); - modelSelectorButton->setValue(selection); - if (FrogPilotConfirmationDialog::yesorno("Do you want to start with a fresh calibration for the newly selected model?", this)) { - params.remove("CalibrationParams"); - params.remove("LiveTorqueParameters"); - } - if (started) { - if (FrogPilotConfirmationDialog::toggle("Reboot required to take effect.", "Reboot Now", this)) { - Hardware::soft_reboot(); - } - } - } - }); - int initialModelIndex = models.indexOf(QString::fromStdString(params.get("Model"))); - QString initialModelLabel = modelLabels[initialModelIndex]; - modelSelectorButton->setValue(initialModelLabel); - addItem(modelSelectorButton); - - } else if (param == "MTSCEnabled") { - FrogPilotParamManageControl *mtscToggle = new FrogPilotParamManageControl(param, title, desc, icon, this); - QObject::connect(mtscToggle, &FrogPilotParamManageControl::manageButtonClicked, this, [this]() { - parentToggleClicked(); - for (auto &[key, toggle] : toggles) { - toggle->setVisible(mtscKeys.find(key.c_str()) != mtscKeys.end()); - } - }); - toggle = mtscToggle; - } else if (param == "MTSCAggressiveness") { - toggle = new FrogPilotParamValueControl(param, title, desc, icon, 1, 200, std::map(), this, false, "%"); - } else if (param == "MTSCLimit") { - toggle = new FrogPilotParamValueControl(param, title, desc, icon, 0, 99, std::map(), this, false, " mph"); - - } else if (param == "QOLControls") { - FrogPilotParamManageControl *qolToggle = new FrogPilotParamManageControl(param, title, desc, icon, this); - QObject::connect(qolToggle, &FrogPilotParamManageControl::manageButtonClicked, this, [this]() { - parentToggleClicked(); - for (auto &[key, toggle] : toggles) { - toggle->setVisible(qolKeys.find(key.c_str()) != qolKeys.end()); - } - }); - toggle = qolToggle; - } else if (param == "PauseLateralOnSignal") { - toggle = new FrogPilotParamValueControl(param, title, desc, icon, 0, 99, std::map(), this, false, " mph"); - } else if (param == "ReverseCruise") { - std::vector reverseCruiseToggles{"ReverseCruiseUI"}; - std::vector reverseCruiseNames{tr("Control Via UI")}; - toggle = new FrogPilotParamToggleControl(param, title, desc, icon, reverseCruiseToggles, reverseCruiseNames); - } else if (param == "SetSpeedOffset") { - toggle = new FrogPilotParamValueControl(param, title, desc, icon, 0, 99, std::map(), this, false, " mph"); - - } else if (param == "NudgelessLaneChange") { - FrogPilotParamManageControl *laneChangeToggle = new FrogPilotParamManageControl(param, title, desc, icon, this); - QObject::connect(laneChangeToggle, &FrogPilotParamManageControl::manageButtonClicked, this, [this]() { - parentToggleClicked(); - for (auto &[key, toggle] : toggles) { - toggle->setVisible(laneChangeKeys.find(key.c_str()) != laneChangeKeys.end()); - } - }); - toggle = laneChangeToggle; - } else if (param == "LaneChangeTime") { - std::map laneChangeTimeLabels; - for (int i = 0; i <= 10; ++i) { - laneChangeTimeLabels[i] = i == 0 ? "Instant" : QString::number(i / 2.0) + " seconds"; - } - toggle = new FrogPilotParamValueControl(param, title, desc, icon, 0, 10, laneChangeTimeLabels, this, false); - } else if (param == "LaneDetectionWidth") { - toggle = new FrogPilotParamValueControl(param, title, desc, icon, 0, 100, std::map(), this, false, " feet", 10); - - } else if (param == "SpeedLimitController") { - FrogPilotParamManageControl *speedLimitControllerToggle = new FrogPilotParamManageControl(param, title, desc, icon, this); - QObject::connect(speedLimitControllerToggle, &FrogPilotParamManageControl::manageButtonClicked, this, [this]() { - parentToggleClicked(); - for (auto &[key, toggle] : toggles) { - toggle->setVisible(speedLimitControllerKeys.find(key.c_str()) != speedLimitControllerKeys.end()); - } - }); - toggle = speedLimitControllerToggle; - } else if (param == "SLCControls") { - FrogPilotParamManageControl *manageSLCControlsToggle = new FrogPilotParamManageControl(param, title, desc, icon, this, true); - QObject::connect(manageSLCControlsToggle, &FrogPilotParamManageControl::manageButtonClicked, this, [this]() { - parentToggleClicked(); - for (auto &[key, toggle] : toggles) { - toggle->setVisible(speedLimitControllerControlsKeys.find(key.c_str()) != speedLimitControllerControlsKeys.end()); - subParentToggleClicked(); - } - slcPriorityButton->setVisible(true); - }); - toggle = manageSLCControlsToggle; - } else if (param == "SLCQOL") { - FrogPilotParamManageControl *manageSLCQOLToggle = new FrogPilotParamManageControl(param, title, desc, icon, this, true); - QObject::connect(manageSLCQOLToggle, &FrogPilotParamManageControl::manageButtonClicked, this, [this]() { - parentToggleClicked(); - for (auto &[key, toggle] : toggles) { - toggle->setVisible(speedLimitControllerQOLKeys.find(key.c_str()) != speedLimitControllerQOLKeys.end()); - subParentToggleClicked(); - } - }); - toggle = manageSLCQOLToggle; - } else if (param == "SLCConfirmation") { - std::vector slcConfirmationToggles{"SLCConfirmationLower", "SLCConfirmationHigher"}; - std::vector slcConfirmationNames{tr("Lower Limits"), tr("Higher Limits")}; - toggle = new FrogPilotParamToggleControl(param, title, desc, icon, slcConfirmationToggles, slcConfirmationNames); - } else if (param == "SLCVisuals") { - FrogPilotParamManageControl *manageSLCVisualsToggle = new FrogPilotParamManageControl(param, title, desc, icon, this, true); - QObject::connect(manageSLCVisualsToggle, &FrogPilotParamManageControl::manageButtonClicked, this, [this]() { - parentToggleClicked(); - for (auto &[key, toggle] : toggles) { - toggle->setVisible(speedLimitControllerVisualsKeys.find(key.c_str()) != speedLimitControllerVisualsKeys.end()); - subParentToggleClicked(); - } - }); - toggle = manageSLCVisualsToggle; - } else if (param == "Offset1" || param == "Offset2" || param == "Offset3" || param == "Offset4") { - toggle = new FrogPilotParamValueControl(param, title, desc, icon, -99, 99, std::map(), this, false, " mph"); - } else if (param == "ShowSLCOffset") { - std::vector slcOffsetToggles{"ShowSLCOffsetUI"}; - std::vector slcOffsetToggleNames{tr("Control Via UI")}; - toggle = new FrogPilotParamToggleControl(param, title, desc, icon, slcOffsetToggles, slcOffsetToggleNames); - } else if (param == "SLCFallback") { - std::vector fallbackOptions{tr("Set Speed"), tr("Experimental Mode"), tr("Previous Limit")}; - FrogPilotButtonParamControl *fallbackSelection = new FrogPilotButtonParamControl(param, title, desc, icon, fallbackOptions); - toggle = fallbackSelection; - } else if (param == "SLCOverride") { - std::vector overrideOptions{tr("None"), tr("Manual Set Speed"), tr("Set Speed")}; - FrogPilotButtonParamControl *overrideSelection = new FrogPilotButtonParamControl(param, title, desc, icon, overrideOptions); - toggle = overrideSelection; - } else if (param == "SLCPriority") { - slcPriorityButton = new ButtonControl(title, tr("SELECT"), desc); - QStringList primaryPriorities = {"None", "Dashboard", "Navigation", "Offline Maps", "Highest", "Lowest"}; - QStringList secondaryTertiaryPriorities = {"None", "Dashboard", "Navigation", "Offline Maps"}; - QStringList priorityPrompts = {tr("Select your primary priority"), tr("Select your secondary priority"), tr("Select your tertiary priority")}; - - QObject::connect(slcPriorityButton, &ButtonControl::clicked, this, [this, primaryPriorities, secondaryTertiaryPriorities, priorityPrompts]() { - QStringList availablePriorities = primaryPriorities; - QStringList selectedPriorities; - for (int i = 1; i <= 3; ++i) { - QStringList currentPriorities = (i == 1) ? availablePriorities : secondaryTertiaryPriorities; - - for (const QString &selectedPriority : selectedPriorities) { - currentPriorities.removeAll(selectedPriority); - } - - QString priorityKey = QString("SLCPriority%1").arg(i); - QString selection = MultiOptionDialog::getSelection(priorityPrompts[i - 1], currentPriorities, "", this); - if (!selection.isEmpty()) { - params.put(priorityKey.toStdString(), selection.toStdString()); - selectedPriorities.append(selection); - - if (i == 1 && (selection == "Highest" || selection == "Lowest" || selection == "None")) { - for (int j = i + 1; j <= 3; ++j) { - QString remainingPriorityKeys = QString("SLCPriority%1").arg(j); - params.putInt(remainingPriorityKeys.toStdString(), 0); - } - break; - } - - updateToggles(); - } else { - break; - } - } - - selectedPriorities.removeAll("None"); - slcPriorityButton->setValue(selectedPriorities.join(", ")); - }); - - QStringList initialPriorities; - for (int i = 1; i <= 3; ++i) { - QString priorityKey = QString("SLCPriority%1").arg(i); - std::string priorityValue = params.get(priorityKey.toStdString()); - QString priorityString = QString::fromStdString(priorityValue); - if (!priorityString.isEmpty() && primaryPriorities.contains(priorityString) && priorityString != "None") { - initialPriorities.append(priorityString); - } - } - slcPriorityButton->setValue(initialPriorities.join(", ")); - addItem(slcPriorityButton); - - } else if (param == "VisionTurnControl") { - FrogPilotParamManageControl *visionTurnControlToggle = new FrogPilotParamManageControl(param, title, desc, icon, this); - QObject::connect(visionTurnControlToggle, &FrogPilotParamManageControl::manageButtonClicked, this, [this]() { - parentToggleClicked(); - for (auto &[key, toggle] : toggles) { - toggle->setVisible(visionTurnControlKeys.find(key.c_str()) != visionTurnControlKeys.end()); - } - }); - toggle = visionTurnControlToggle; - } else if (param == "CurveSensitivity" || param == "TurnAggressiveness") { - toggle = new FrogPilotParamValueControl(param, title, desc, icon, 1, 200, std::map(), this, false, "%"); - - } else { - toggle = new ParamControl(param, title, desc, icon, this); - } - - addItem(toggle); - toggles[param.toStdString()] = toggle; - - QObject::connect(toggle, &ToggleControl::toggleFlipped, [this]() { - updateToggles(); - }); - - QObject::connect(static_cast(toggle), &FrogPilotButtonParamControl::buttonClicked, [this]() { - updateToggles(); - }); - - QObject::connect(static_cast(toggle), &FrogPilotParamValueControl::valueChanged, [this]() { - updateToggles(); - }); - - QObject::connect(toggle, &AbstractControl::showDescriptionEvent, [this]() { - update(); - }); - - QObject::connect(static_cast(toggle), &FrogPilotParamManageControl::manageButtonClicked, this, [this]() { - update(); - }); - } - - QObject::connect(toggles["AlwaysOnLateralMain"], &ToggleControl::toggleFlipped, [this]() { - if (params.getBool("AlwaysOnLateralMain")) { - FrogPilotConfirmationDialog::toggleAlert( - "WARNING: This isn't guaranteed to work, so if you run into any issues, please report it in the FrogPilot Discord!", - "I understand the risks.", this); - } - }); - - QObject::connect(toggles["MuteOverheated"], &ToggleControl::toggleFlipped, [this]() { - if (params.getBool("MuteOverheated")) { - FrogPilotConfirmationDialog::toggleAlert( - "WARNING: This MAY cause premature wear or damage by running the device over comma's recommended temperature limits!", - "I understand the risks.", this); - } - }); - - std::set rebootKeys = {"AlwaysOnLateral", "HigherBitrate", "NNFF", "UseLateralJerk"}; - for (const std::string &key : rebootKeys) { - QObject::connect(toggles[key], &ToggleControl::toggleFlipped, [this, key]() { - if (started) { - if (FrogPilotConfirmationDialog::toggle("Reboot required to take effect.", "Reboot Now", this)) { - Hardware::soft_reboot(); - } - } - }); - } - - QObject::connect(device(), &Device::interactiveTimeout, this, &FrogPilotControlsPanel::hideSubToggles); - QObject::connect(parent, &SettingsWindow::closeParentToggle, this, &FrogPilotControlsPanel::hideSubToggles); - QObject::connect(parent, &SettingsWindow::closeSubParentToggle, this, &FrogPilotControlsPanel::hideSubSubToggles); - QObject::connect(parent, &SettingsWindow::updateMetric, this, &FrogPilotControlsPanel::updateMetric); - QObject::connect(uiState(), &UIState::offroadTransition, this, &FrogPilotControlsPanel::updateCarToggles); - QObject::connect(uiState(), &UIState::uiUpdate, this, &FrogPilotControlsPanel::updateState); - - hideSubToggles(); - updateMetric(); -} - -void FrogPilotControlsPanel::updateState(const UIState &s) { - started = s.scene.started; -} - -void FrogPilotControlsPanel::updateToggles() { - std::thread([this]() { - paramsMemory.putBool("FrogPilotTogglesUpdated", true); - std::this_thread::sleep_for(std::chrono::seconds(1)); - paramsMemory.putBool("FrogPilotTogglesUpdated", false); - }).detach(); -} - -void FrogPilotControlsPanel::updateCarToggles() { - steerRatioStock = params.getFloat("SteerRatioStock"); - - if (steerRatioStock == 0.0) { - QTimer *timer = new QTimer(this); - timer->setInterval(1000); - connect(timer, &QTimer::timeout, this, [this, timer]() { - steerRatioStock = params.getFloat("SteerRatioStock"); - if (steerRatioStock != 0.0) { - timer->stop(); - timer->deleteLater(); - - FrogPilotParamValueControl *steerRatioToggle = static_cast(toggles["SteerRatio"]); - steerRatioToggle->setTitle(QString("Steer Ratio (Default: %1)").arg(steerRatioStock, 0, 'f', 2)); - steerRatioToggle->updateControl(steerRatioStock * 0.75, steerRatioStock * 1.25, "", 0.01); - steerRatioToggle->refresh(); - } - }); - timer->start(); - } else { - FrogPilotParamValueControl *steerRatioToggle = static_cast(toggles["SteerRatio"]); - steerRatioToggle->setTitle(QString("Steer Ratio (Default: %1)").arg(steerRatioStock, 0, 'f', 2)); - steerRatioToggle->updateControl(steerRatioStock * 0.75, steerRatioStock * 1.25, "", 0.01); - steerRatioToggle->refresh(); - } -} - -void FrogPilotControlsPanel::updateMetric() { - bool previousIsMetric = isMetric; - isMetric = params.getBool("IsMetric"); - - if (isMetric != previousIsMetric) { - double distanceConversion = isMetric ? FOOT_TO_METER : METER_TO_FOOT; - double speedConversion = isMetric ? MILE_TO_KM : KM_TO_MILE; - params.putIntNonBlocking("CESpeed", std::nearbyint(params.getInt("CESpeed") * speedConversion)); - params.putIntNonBlocking("CESpeedLead", std::nearbyint(params.getInt("CESpeedLead") * speedConversion)); - params.putIntNonBlocking("LaneDetectionWidth", std::nearbyint(params.getInt("LaneDetectionWidth") * distanceConversion)); - params.putIntNonBlocking("MTSCLimit", std::nearbyint(params.getInt("MTSCLimit") * speedConversion)); - params.putIntNonBlocking("Offset1", std::nearbyint(params.getInt("Offset1") * speedConversion)); - params.putIntNonBlocking("Offset2", std::nearbyint(params.getInt("Offset2") * speedConversion)); - params.putIntNonBlocking("Offset3", std::nearbyint(params.getInt("Offset3") * speedConversion)); - params.putIntNonBlocking("Offset4", std::nearbyint(params.getInt("Offset4") * speedConversion)); - params.putIntNonBlocking("PauseLateralOnSignal", std::nearbyint(params.getInt("PauseLateralOnSignal") * speedConversion)); - params.putIntNonBlocking("SetSpeedOffset", std::nearbyint(params.getInt("SetSpeedOffset") * speedConversion)); - params.putIntNonBlocking("StoppingDistance", std::nearbyint(params.getInt("StoppingDistance") * distanceConversion)); - } - - FrogPilotParamValueControl *laneWidthToggle = static_cast(toggles["LaneDetectionWidth"]); - FrogPilotParamValueControl *mtscLimitToggle = static_cast(toggles["MTSCLimit"]); - FrogPilotParamValueControl *offset1Toggle = static_cast(toggles["Offset1"]); - FrogPilotParamValueControl *offset2Toggle = static_cast(toggles["Offset2"]); - FrogPilotParamValueControl *offset3Toggle = static_cast(toggles["Offset3"]); - FrogPilotParamValueControl *offset4Toggle = static_cast(toggles["Offset4"]); - FrogPilotParamValueControl *pauseLateralToggle = static_cast(toggles["PauseLateralOnSignal"]); - FrogPilotParamValueControl *setSpeedOffsetToggle = static_cast(toggles["SetSpeedOffset"]); - FrogPilotParamValueControl *stoppingDistanceToggle = static_cast(toggles["StoppingDistance"]); - - if (isMetric) { - offset1Toggle->setTitle("Speed Limit Offset (0-34 kph)"); - offset2Toggle->setTitle("Speed Limit Offset (35-54 kph)"); - offset3Toggle->setTitle("Speed Limit Offset (55-64 kph)"); - offset4Toggle->setTitle("Speed Limit Offset (65-99 kph)"); - - offset1Toggle->setDescription("Set speed limit offset for limits between 0-34 kph."); - offset2Toggle->setDescription("Set speed limit offset for limits between 35-54 kph."); - offset3Toggle->setDescription("Set speed limit offset for limits between 55-64 kph."); - offset4Toggle->setDescription("Set speed limit offset for limits between 65-99 kph."); - - laneWidthToggle->updateControl(0, 30, " meters", 10); - - mtscLimitToggle->updateControl(0, 99, " kph"); - - offset1Toggle->updateControl(-99, 99, " kph"); - offset2Toggle->updateControl(-99, 99, " kph"); - offset3Toggle->updateControl(-99, 99, " kph"); - offset4Toggle->updateControl(-99, 99, " kph"); - - pauseLateralToggle->updateControl(0, 150, " kph"); - setSpeedOffsetToggle->updateControl(0, 150, " kph"); - - stoppingDistanceToggle->updateControl(0, 5, " meters"); - } else { - offset1Toggle->setTitle("Speed Limit Offset (0-34 mph)"); - offset2Toggle->setTitle("Speed Limit Offset (35-54 mph)"); - offset3Toggle->setTitle("Speed Limit Offset (55-64 mph)"); - offset4Toggle->setTitle("Speed Limit Offset (65-99 mph)"); - - offset1Toggle->setDescription("Set speed limit offset for limits between 0-34 mph."); - offset2Toggle->setDescription("Set speed limit offset for limits between 35-54 mph."); - offset3Toggle->setDescription("Set speed limit offset for limits between 55-64 mph."); - offset4Toggle->setDescription("Set speed limit offset for limits between 65-99 mph."); - - laneWidthToggle->updateControl(0, 100, " feet", 10); - - mtscLimitToggle->updateControl(0, 99, " mph"); - - offset1Toggle->updateControl(-99, 99, " mph"); - offset2Toggle->updateControl(-99, 99, " mph"); - offset3Toggle->updateControl(-99, 99, " mph"); - offset4Toggle->updateControl(-99, 99, " mph"); - - pauseLateralToggle->updateControl(0, 99, " mph"); - setSpeedOffsetToggle->updateControl(0, 99, " mph"); - - stoppingDistanceToggle->updateControl(0, 10, " feet"); - } - - laneWidthToggle->refresh(); - mtscLimitToggle->refresh(); - offset1Toggle->refresh(); - offset2Toggle->refresh(); - offset3Toggle->refresh(); - offset4Toggle->refresh(); - pauseLateralToggle->refresh(); - setSpeedOffsetToggle->refresh(); - stoppingDistanceToggle->refresh(); - - previousIsMetric = isMetric; -} - -void FrogPilotControlsPanel::parentToggleClicked() { - aggressiveProfile->setVisible(false); - conditionalSpeedsImperial->setVisible(false); - conditionalSpeedsMetric->setVisible(false); - modelSelectorButton->setVisible(false); - slcPriorityButton->setVisible(false); - standardProfile->setVisible(false); - relaxedProfile->setVisible(false); - - openParentToggle(); -} - -void FrogPilotControlsPanel::subParentToggleClicked() { - openSubParentToggle(); -} - -void FrogPilotControlsPanel::hideSubToggles() { - aggressiveProfile->setVisible(false); - conditionalSpeedsImperial->setVisible(false); - conditionalSpeedsMetric->setVisible(false); - modelSelectorButton->setVisible(true); - slcPriorityButton->setVisible(false); - standardProfile->setVisible(false); - relaxedProfile->setVisible(false); - - for (auto &[key, toggle] : toggles) { - bool subToggles = aolKeys.find(key.c_str()) != aolKeys.end() || - conditionalExperimentalKeys.find(key.c_str()) != conditionalExperimentalKeys.end() || - experimentalModeActivationKeys.find(key.c_str()) != experimentalModeActivationKeys.end() || - fireTheBabysitterKeys.find(key.c_str()) != fireTheBabysitterKeys.end() || - laneChangeKeys.find(key.c_str()) != laneChangeKeys.end() || - lateralTuneKeys.find(key.c_str()) != lateralTuneKeys.end() || - longitudinalTuneKeys.find(key.c_str()) != longitudinalTuneKeys.end() || - mtscKeys.find(key.c_str()) != mtscKeys.end() || - qolKeys.find(key.c_str()) != qolKeys.end() || - speedLimitControllerKeys.find(key.c_str()) != speedLimitControllerKeys.end() || - speedLimitControllerControlsKeys.find(key.c_str()) != speedLimitControllerControlsKeys.end() || - speedLimitControllerQOLKeys.find(key.c_str()) != speedLimitControllerQOLKeys.end() || - speedLimitControllerVisualsKeys.find(key.c_str()) != speedLimitControllerVisualsKeys.end() || - visionTurnControlKeys.find(key.c_str()) != visionTurnControlKeys.end(); - toggle->setVisible(!subToggles); - } - - closeParentToggle(); -} - -void FrogPilotControlsPanel::hideSubSubToggles() { - slcPriorityButton->setVisible(false); - - for (auto &[key, toggle] : toggles) { - bool isVisible = speedLimitControllerKeys.find(key.c_str()) != speedLimitControllerKeys.end(); - toggle->setVisible(isVisible); - } - - closeSubParentToggle(); - update(); -} - -void FrogPilotControlsPanel::hideEvent(QHideEvent *event) { - hideSubToggles(); -} diff --git a/selfdrive/frogpilot/ui/control_settings.h b/selfdrive/frogpilot/ui/control_settings.h deleted file mode 100644 index 19d9162..0000000 --- a/selfdrive/frogpilot/ui/control_settings.h +++ /dev/null @@ -1,66 +0,0 @@ -#pragma once - -#include - -#include "selfdrive/frogpilot/ui/frogpilot_ui_functions.h" -#include "selfdrive/ui/qt/offroad/settings.h" -#include "selfdrive/ui/ui.h" - -class FrogPilotControlsPanel : public FrogPilotListWidget { - Q_OBJECT - -public: - explicit FrogPilotControlsPanel(SettingsWindow *parent); - -signals: - void closeParentToggle(); - void closeSubParentToggle(); - void openParentToggle(); - void openSubParentToggle(); - -private: - void hideEvent(QHideEvent *event); - void hideSubSubToggles(); - void hideSubToggles(); - void parentToggleClicked(); - void subParentToggleClicked(); - void updateCarToggles(); - void updateMetric(); - void updateState(const UIState &s); - void updateToggles(); - - ButtonControl *slcPriorityButton; - - FrogPilotButtonIconControl *modelSelectorButton; - - FrogPilotDualParamControl *aggressiveProfile; - FrogPilotDualParamControl *conditionalSpeedsImperial; - FrogPilotDualParamControl *conditionalSpeedsMetric; - FrogPilotDualParamControl *standardProfile; - FrogPilotDualParamControl *relaxedProfile; - - std::set aolKeys = {"AlwaysOnLateralMain", "HideAOLStatusBar"}; - std::set conditionalExperimentalKeys = {"CECurves", "CECurvesLead", "CESlowerLead", "CENavigation", "CEStopLights", "CESignal", "HideCEMStatusBar"}; - std::set experimentalModeActivationKeys = {"ExperimentalModeViaDistance", "ExperimentalModeViaLKAS", "ExperimentalModeViaScreen"}; - std::set fireTheBabysitterKeys = {"NoLogging", "MuteOverheated", "NoUploads", "OfflineMode"}; - std::set laneChangeKeys = {"LaneChangeTime", "LaneDetection", "LaneDetectionWidth", "OneLaneChange"}; - std::set lateralTuneKeys = {"ForceAutoTune", "NNFF", "SteerRatio", "UseLateralJerk"}; - std::set longitudinalTuneKeys = {"AccelerationProfile", "DecelerationProfile", "AggressiveAcceleration", "LeadDetectionThreshold", "SmoothBraking", "StoppingDistance", "TrafficMode"}; - std::set mtscKeys = {"DisableMTSCSmoothing", "MTSCAggressiveness", "MTSCCurvatureCheck", "MTSCLimit"}; - std::set qolKeys = {"DisableOnroadUploads", "HigherBitrate", "NavChill", "PauseLateralOnSignal", "ReverseCruise", "SetSpeedOffset"}; - std::set speedLimitControllerKeys = {"SLCControls", "SLCQOL", "SLCVisuals"}; - std::set speedLimitControllerControlsKeys = {"Offset1", "Offset2", "Offset3", "Offset4", "SLCFallback", "SLCOverride", "SLCPriority"}; - std::set speedLimitControllerQOLKeys = {"SLCConfirmation", "ForceMPHDashboard", "SetSpeedLimit"}; - std::set speedLimitControllerVisualsKeys = {"ShowSLCOffset", "UseVienna"}; - std::set visionTurnControlKeys = {"DisableVTSCSmoothing", "CurveSensitivity", "TurnAggressiveness"}; - - std::map toggles; - - Params params; - Params paramsMemory{"/dev/shm/params"}; - - bool isMetric = params.getBool("IsMetric"); - bool started = false; - - float steerRatioStock = params.getFloat("SteerRatioStock"); -}; diff --git a/selfdrive/frogpilot/ui/frogpilot_ui_functions.cc b/selfdrive/frogpilot/ui/frogpilot_ui_functions.cc deleted file mode 100644 index 7bd6c3b..0000000 --- a/selfdrive/frogpilot/ui/frogpilot_ui_functions.cc +++ /dev/null @@ -1,42 +0,0 @@ -#include - -#include "selfdrive/frogpilot/ui/frogpilot_ui_functions.h" -#include "selfdrive/ui/ui.h" - -bool FrogPilotConfirmationDialog::toggle(const QString &prompt_text, const QString &confirm_text, QWidget *parent) { - ConfirmationDialog d = ConfirmationDialog(prompt_text, confirm_text, tr("Reboot Later"), false, parent); - return d.exec(); -} - -bool FrogPilotConfirmationDialog::toggleAlert(const QString &prompt_text, const QString &button_text, QWidget *parent) { - ConfirmationDialog d = ConfirmationDialog(prompt_text, button_text, "", false, parent); - return d.exec(); -} - -bool FrogPilotConfirmationDialog::yesorno(const QString &prompt_text, QWidget *parent) { - ConfirmationDialog d = ConfirmationDialog(prompt_text, tr("Yes"), tr("No"), false, parent); - return d.exec(); -} - -FrogPilotButtonIconControl::FrogPilotButtonIconControl(const QString &title, const QString &text, const QString &desc, const QString &icon, QWidget *parent) : AbstractControl(title, desc, icon, parent) { - btn.setText(text); - btn.setStyleSheet(R"( - QPushButton { - padding: 0; - border-radius: 50px; - font-size: 35px; - font-weight: 500; - color: #E4E4E4; - background-color: #393939; - } - QPushButton:pressed { - background-color: #4a4a4a; - } - QPushButton:disabled { - color: #33E4E4E4; - } - )"); - btn.setFixedSize(250, 100); - QObject::connect(&btn, &QPushButton::clicked, this, &FrogPilotButtonIconControl::clicked); - hlayout->addWidget(&btn); -} diff --git a/selfdrive/frogpilot/ui/frogpilot_ui_functions.h b/selfdrive/frogpilot/ui/frogpilot_ui_functions.h deleted file mode 100644 index 3785b1c..0000000 --- a/selfdrive/frogpilot/ui/frogpilot_ui_functions.h +++ /dev/null @@ -1,745 +0,0 @@ -#pragma once - -#include - -#include - -#include "selfdrive/ui/qt/widgets/controls.h" - -class FrogPilotConfirmationDialog : public ConfirmationDialog { - Q_OBJECT - -public: - explicit FrogPilotConfirmationDialog(const QString &prompt_text, const QString &confirm_text, - const QString &cancel_text, const bool rich, QWidget* parent); - static bool toggle(const QString &prompt_text, const QString &confirm_text, QWidget *parent); - static bool toggleAlert(const QString &prompt_text, const QString &button_text, QWidget *parent); - static bool yesorno(const QString &prompt_text, QWidget *parent); -}; - -class FrogPilotListWidget : public QWidget { - Q_OBJECT -public: - explicit FrogPilotListWidget(QWidget *parent = 0) : QWidget(parent), outer_layout(this) { - outer_layout.setMargin(0); - outer_layout.setSpacing(0); - outer_layout.addLayout(&inner_layout); - inner_layout.setMargin(0); - inner_layout.setSpacing(25); // default spacing is 25 - outer_layout.addStretch(); - } - inline void addItem(QWidget *w) { inner_layout.addWidget(w); } - inline void addItem(QLayout *layout) { inner_layout.addLayout(layout); } - inline void setSpacing(int spacing) { inner_layout.setSpacing(spacing); } - -private: - void paintEvent(QPaintEvent *) override { - QPainter p(this); - p.setPen(Qt::gray); - - int visibleWidgetCount = 0; - std::vector visibleRects; - - for (int i = 0; i < inner_layout.count(); ++i) { - QWidget *widget = inner_layout.itemAt(i)->widget(); - if (widget && widget->isVisible()) { - visibleWidgetCount++; - visibleRects.push_back(inner_layout.itemAt(i)->geometry()); - } - } - - for (int i = 0; i < visibleWidgetCount - 1; ++i) { - int bottom = visibleRects[i].bottom() + inner_layout.spacing() / 2; - p.drawLine(visibleRects[i].left() + 40, bottom, visibleRects[i].right() - 40, bottom); - } - } - QVBoxLayout outer_layout; - QVBoxLayout inner_layout; -}; - -class FrogPilotDualParamControl : public QFrame { - Q_OBJECT - -public: - FrogPilotDualParamControl(ParamControl *control1, ParamControl *control2, QWidget *parent = nullptr, bool split=false) - : QFrame(parent) { - QHBoxLayout *hlayout = new QHBoxLayout(this); - - control1->setSizePolicy(QSizePolicy::Minimum, QSizePolicy::Preferred); - control1->setMaximumWidth(split ? 850 : 700); - - control2->setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Preferred); - control2->setMaximumWidth(split ? 700 : 850); - - hlayout->addWidget(control1); - hlayout->addWidget(control2); - } -}; - -class FrogPilotButtonControl : public AbstractControl { - Q_OBJECT - -public: - FrogPilotButtonControl(const QString &title, const QString &text, const QString &desc = "", QWidget *parent = nullptr); - inline void setText(const QString &text) { btn.setText(text); } - inline QString text() const { return btn.text(); } - -signals: - void clicked(); - -public slots: - void setEnabled(bool enabled) { btn.setEnabled(enabled); } - -private: - QPushButton btn; -}; - -class FrogPilotButtonIconControl : public AbstractControl { - Q_OBJECT - -public: - FrogPilotButtonIconControl(const QString &title, const QString &text, const QString &desc = "", const QString &icon = "", QWidget *parent = nullptr); - inline void setText(const QString &text) { btn.setText(text); } - inline QString text() const { return btn.text(); } - -signals: - void clicked(); - -public slots: - void setEnabled(bool enabled) { btn.setEnabled(enabled); } - -private: - QPushButton btn; -}; - -class FrogPilotButtonParamControl : public ParamControl { - Q_OBJECT -public: - FrogPilotButtonParamControl(const QString ¶m, const QString &title, const QString &desc, const QString &icon, - const std::vector &button_texts, const int minimum_button_width = 225) - : ParamControl(param, title, desc, icon) { - const QString style = R"( - QPushButton { - border-radius: 50px; - font-size: 40px; - font-weight: 500; - height:100px; - padding: 0 25 0 25; - color: #E4E4E4; - background-color: #393939; - } - QPushButton:pressed { - background-color: #4a4a4a; - } - QPushButton:checked:enabled { - background-color: #33Ab4C; - } - QPushButton:disabled { - color: #33E4E4E4; - } - )"; - - key = param.toStdString(); - int value = atoi(params.get(key).c_str()); - - button_group = new QButtonGroup(this); - button_group->setExclusive(true); - for (size_t i = 0; i < button_texts.size(); i++) { - QPushButton *button = new QPushButton(button_texts[i], this); - button->setCheckable(true); - button->setChecked(i == value); - button->setStyleSheet(style); - button->setMinimumWidth(minimum_button_width); - hlayout->addWidget(button); - button_group->addButton(button, i); - } - - QObject::connect(button_group, QOverload::of(&QButtonGroup::buttonToggled), [=](int id, bool checked) { - if (checked) { - params.put(key, std::to_string(id)); - refresh(); - emit buttonClicked(id); - } - }); - - toggle.hide(); - } - - void setEnabled(bool enable) { - for (auto btn : button_group->buttons()) { - btn->setEnabled(enable); - } - } - -signals: - void buttonClicked(int id); - -private: - std::string key; - Params params; - QButtonGroup *button_group; -}; - -class FrogPilotButtonsControl : public ParamControl { - Q_OBJECT -public: - FrogPilotButtonsControl(const QString &title, const QString &desc, const QString &icon, - const std::vector &button_texts, const int minimum_button_width = 225) - : ParamControl("", title, desc, icon) { - const QString style = R"( - QPushButton { - border-radius: 50px; - font-size: 40px; - font-weight: 500; - height: 100px; - padding: 0 25px 0 25px; - color: #E4E4E4; - background-color: #393939; - } - QPushButton:pressed { - background-color: #33Ab4C; - } - QPushButton:disabled { - color: #33E4E4E4; - } - )"; - - button_group = new QButtonGroup(this); - - for (size_t i = 0; i < button_texts.size(); i++) { - QPushButton *button = new QPushButton(button_texts[i], this); - button->setStyleSheet(style); - button->setMinimumWidth(minimum_button_width); - hlayout->addWidget(button); - button_group->addButton(button, static_cast(i)); - - connect(button, &QPushButton::clicked, this, [this, i]() { - emit buttonClicked(static_cast(i)); - }); - } - - toggle.hide(); - } - -signals: - void buttonClicked(int id); - -private: - QButtonGroup *button_group; -}; - -class FrogPilotButtonsParamControl : public ParamControl { - Q_OBJECT -public: - FrogPilotButtonsParamControl(const QString ¶m, const QString &title, const QString &desc, const QString &icon, - const std::vector> &button_params) - : ParamControl(param, title, desc, icon) { - const QString style = R"( - QPushButton { - border-radius: 50px; - font-size: 40px; - font-weight: 500; - height:100px; - padding: 0 25 0 25; - color: #E4E4E4; - background-color: #393939; - } - QPushButton:pressed { - background-color: #4a4a4a; - } - QPushButton:checked:enabled { - background-color: #33Ab4C; - } - QPushButton:disabled { - color: #33E4E4E4; - } - )"; - - button_group = new QButtonGroup(this); - button_group->setExclusive(true); - - for (const auto ¶m_pair : button_params) { - const QString ¶m_toggle = param_pair.first; - const QString &button_text = param_pair.second; - - QPushButton *button = new QPushButton(button_text, this); - button->setCheckable(true); - - bool value = params.getBool(param_toggle.toStdString()); - button->setChecked(value); - button->setStyleSheet(style); - button->setMinimumWidth(225); - hlayout->addWidget(button); - - QObject::connect(button, &QPushButton::toggled, this, [=](bool checked) { - if (checked) { - for (const auto &inner_param_pair : button_params) { - const QString &inner_param = inner_param_pair.first; - params.putBool(inner_param.toStdString(), inner_param == param_toggle); - } - refresh(); - emit buttonClicked(); - } - }); - - button_group->addButton(button); - } - - toggle.hide(); - } - - void setEnabled(bool enable) { - for (auto btn : button_group->buttons()) { - btn->setEnabled(enable); - } - } - -signals: - void buttonClicked(); - -private: - Params params; - QButtonGroup *button_group; -}; - -class FrogPilotParamManageControl : public ParamControl { - Q_OBJECT - -public: - FrogPilotParamManageControl(const QString ¶m, const QString &title, const QString &desc, const QString &icon, QWidget *parent = nullptr, bool hideToggle = false) - : ParamControl(param, title, desc, icon, parent), - hideToggle(hideToggle), - key(param.toStdString()), - manageButton(new ButtonControl(tr(""), tr("MANAGE"), tr(""))) { - hlayout->insertWidget(hlayout->indexOf(&toggle) - 1, manageButton); - - connect(this, &ToggleControl::toggleFlipped, this, [this](bool state) { - refresh(); - }); - - connect(manageButton, &ButtonControl::clicked, this, &FrogPilotParamManageControl::manageButtonClicked); - - if (hideToggle) { - toggle.hide(); - } - } - - void refresh() { - ParamControl::refresh(); - manageButton->setVisible(params.getBool(key) || hideToggle); - } - - void showEvent(QShowEvent *event) override { - ParamControl::showEvent(event); - refresh(); - } - -signals: - void manageButtonClicked(); - -private: - bool hideToggle; - std::string key; - Params params; - ButtonControl *manageButton; -}; - -class FrogPilotParamToggleControl : public ParamControl { - Q_OBJECT -public: - FrogPilotParamToggleControl(const QString ¶m, const QString &title, const QString &desc, - const QString &icon, const std::vector &button_params, - const std::vector &button_texts, QWidget *parent = nullptr, - const int minimum_button_width = 225) - : ParamControl(param, title, desc, icon, parent) { - - key = param.toStdString(); - - connect(this, &ToggleControl::toggleFlipped, this, [this](bool state) { - refreshButtons(state); - }); - - const QString style = R"( - QPushButton { - border-radius: 50px; - font-size: 40px; - font-weight: 500; - height:100px; - padding: 0 25 0 25; - color: #E4E4E4; - background-color: #393939; - } - QPushButton:pressed { - background-color: #4a4a4a; - } - QPushButton:checked:enabled { - background-color: #33Ab4C; - } - QPushButton:disabled { - color: #33E4E4E4; - } - )"; - - button_group = new QButtonGroup(this); - button_group->setExclusive(false); - this->button_params = button_params; - - for (int i = 0; i < button_texts.size(); ++i) { - QPushButton *button = new QPushButton(button_texts[i], this); - button->setCheckable(true); - button->setStyleSheet(style); - button->setMinimumWidth(minimum_button_width); - button_group->addButton(button, i); - - connect(button, &QPushButton::clicked, [this, i](bool checked) { - params.putBool(this->button_params[i].toStdString(), checked); - button_group->button(i)->setChecked(checked); - emit buttonClicked(checked); - }); - - hlayout->insertWidget(hlayout->indexOf(&toggle) - 1, button); - } - } - - void refresh() { - bool state = params.getBool(key); - if (state != toggle.on) { - toggle.togglePosition(); - } - - refreshButtons(state); - updateButtonStates(); - } - - void refreshButtons(bool state) { - for (QAbstractButton *button : button_group->buttons()) { - button->setVisible(state); - } - } - - void updateButtonStates() { - for (int i = 0; i < button_group->buttons().size(); ++i) { - bool checked = params.getBool(button_params[i].toStdString()); - QAbstractButton *button = button_group->button(i); - if (button) { - button->setChecked(checked); - } - } - } - - void showEvent(QShowEvent *event) override { - refresh(); - QWidget::showEvent(event); - } - -signals: - void buttonClicked(const bool checked); - -private: - std::string key; - Params params; - QButtonGroup *button_group; - std::vector button_params; -}; - -class FrogPilotParamValueControl : public ParamControl { - Q_OBJECT - -public: - FrogPilotParamValueControl(const QString ¶m, const QString &title, const QString &desc, const QString &icon, - const float &minValue, const float &maxValue, const std::map &valueLabels, - QWidget *parent = nullptr, const bool &loop = true, const QString &label = "", - const float &division = 1.0f, const float &intervals = 1.0f) - : ParamControl(param, title, desc, icon, parent), - minValue(minValue), maxValue(maxValue), valueLabelMappings(valueLabels), loop(loop), labelText(label), - division(division), previousValue(0.0f), value(0.0f) { - key = param.toStdString(); - - valueLabel = new QLabel(this); - hlayout->addWidget(valueLabel); - - QPushButton *decrementButton = createButton("-", this); - QPushButton *incrementButton = createButton("+", this); - - hlayout->addWidget(decrementButton); - hlayout->addWidget(incrementButton); - - countdownTimer = new QTimer(this); - countdownTimer->setInterval(150); - countdownTimer->setSingleShot(true); - - connect(countdownTimer, &QTimer::timeout, this, &FrogPilotParamValueControl::handleTimeout); - - connect(decrementButton, &QPushButton::pressed, this, [=]() { updateValue(-intervals); }); - connect(incrementButton, &QPushButton::pressed, this, [=]() { updateValue(intervals); }); - - connect(decrementButton, &QPushButton::released, this, &FrogPilotParamValueControl::restartTimer); - connect(incrementButton, &QPushButton::released, this, &FrogPilotParamValueControl::restartTimer); - - toggle.hide(); - } - - void restartTimer() { - countdownTimer->stop(); - countdownTimer->start(); - } - - void handleTimeout() { - previousValue = value; - } - - void updateValue(float increment) { - if (std::fabs(previousValue - value) > 5.0f && std::fmod(value, 5.0f) == 0.0f) { - increment *= 5; - } - value += increment; - - if (loop) { - if (value < minValue) value = maxValue; - else if (value > maxValue) value = minValue; - } else { - value = std::max(minValue, std::min(maxValue, value)); - } - - params.putFloat(key, value); - refresh(); - emit valueChanged(value); - } - - void refresh() { - value = params.getFloat(key); - - QString text; - auto it = valueLabelMappings.find(value); - - if (division > 1.0f) { - text = QString::number(value / division, 'g', division >= 10.0f ? 4 : 3); - } else { - if (it != valueLabelMappings.end()) { - text = it->second; - } else { - text = QString::number(value, 'g', 4); - } - } - - if (!labelText.isEmpty()) { - text += labelText; - } - - valueLabel->setText(text); - valueLabel->setStyleSheet("QLabel { color: #E0E879; }"); - } - - void updateControl(float newMinValue, float newMaxValue, const QString &newLabel, float newDivision = 1.0f) { - minValue = newMinValue; - maxValue = newMaxValue; - labelText = newLabel; - division = newDivision; - } - - void showEvent(QShowEvent *event) override { - refresh(); - previousValue = value; - } - -signals: - void valueChanged(float value); - -private: - bool loop; - float division; - float maxValue; - float minValue; - float previousValue; - float value; - QLabel *valueLabel; - QString labelText; - std::map valueLabelMappings; - std::string key; - Params params; - QTimer *countdownTimer; - - QPushButton *createButton(const QString &text, QWidget *parent) { - QPushButton *button = new QPushButton(text, parent); - button->setFixedSize(150, 100); - button->setAutoRepeat(true); - button->setAutoRepeatInterval(150); - button->setAutoRepeatDelay(500); - button->setStyleSheet(R"( - QPushButton { - border-radius: 50px; - font-size: 50px; - font-weight: 500; - height: 100px; - padding: 0 25 0 25; - color: #E4E4E4; - background-color: #393939; - } - QPushButton:pressed { - background-color: #4a4a4a; - } - )"); - return button; - } -}; - -class FrogPilotParamValueToggleControl : public ParamControl { - Q_OBJECT - -public: - FrogPilotParamValueToggleControl(const QString ¶m, const QString &title, const QString &desc, const QString &icon, - const int &minValue, const int &maxValue, const std::map &valueLabels, - QWidget *parent = nullptr, const bool &loop = true, const QString &label = "", const int &division = 1, - const std::vector &button_params = std::vector(), const std::vector &button_texts = std::vector(), - const int minimum_button_width = 225) - : ParamControl(param, title, desc, icon, parent), - minValue(minValue), maxValue(maxValue), valueLabelMappings(valueLabels), loop(loop), labelText(label), division(division) { - key = param.toStdString(); - - const QString style = R"( - QPushButton { - border-radius: 50px; - font-size: 40px; - font-weight: 500; - height:100px; - padding: 0 25 0 25; - color: #E4E4E4; - background-color: #393939; - } - QPushButton:pressed { - background-color: #4a4a4a; - } - QPushButton:checked:enabled { - background-color: #33Ab4C; - } - QPushButton:disabled { - color: #33E4E4E4; - } - )"; - - button_group = new QButtonGroup(this); - button_group->setExclusive(false); - - std::map paramState; - for (const QString &button_param : button_params) { - paramState[button_param] = params.getBool(button_param.toStdString()); - } - - for (int i = 0; i < button_texts.size(); ++i) { - QPushButton *button = new QPushButton(button_texts[i], this); - button->setCheckable(true); - button->setChecked(paramState[button_params[i]]); - button->setStyleSheet(style); - button->setMinimumWidth(minimum_button_width); - button_group->addButton(button, i); - - connect(button, &QPushButton::clicked, [this, button_params, i](bool checked) { - params.putBool(button_params[i].toStdString(), checked); - button_group->button(i)->setChecked(checked); - }); - - hlayout->addWidget(button); - } - - valueLabel = new QLabel(this); - hlayout->addWidget(valueLabel); - - QPushButton *decrementButton = createButton("-", this); - QPushButton *incrementButton = createButton("+", this); - - hlayout->addWidget(decrementButton); - hlayout->addWidget(incrementButton); - - connect(decrementButton, &QPushButton::clicked, this, [=]() { - updateValue(-1); - }); - - connect(incrementButton, &QPushButton::clicked, this, [=]() { - updateValue(1); - }); - - toggle.hide(); - } - - void updateValue(int increment) { - value = value + increment; - - if (loop) { - if (value < minValue) value = maxValue; - else if (value > maxValue) value = minValue; - } else { - value = std::max(minValue, std::min(maxValue, value)); - } - - params.putInt(key, value); - refresh(); - emit valueChanged(value); - } - - void refresh() { - value = params.getInt(key); - - QString text; - auto it = valueLabelMappings.find(value); - if (division > 1) { - text = QString::number(value / (division * 1.0), 'g'); - } else { - text = it != valueLabelMappings.end() ? it->second : QString::number(value); - } - if (!labelText.isEmpty()) { - text += labelText; - } - valueLabel->setText(text); - valueLabel->setStyleSheet("QLabel { color: #E0E879; }"); - } - - void updateControl(int newMinValue, int newMaxValue, const QString &newLabel, int newDivision) { - minValue = newMinValue; - maxValue = newMaxValue; - labelText = newLabel; - division = newDivision; - } - - void showEvent(QShowEvent *event) override { - refresh(); - } - -signals: - void valueChanged(int value); - -private: - bool loop; - int division; - int maxValue; - int minValue; - int value; - QButtonGroup *button_group; - QLabel *valueLabel; - QString labelText; - std::map valueLabelMappings; - std::string key; - Params params; - - QPushButton *createButton(const QString &text, QWidget *parent) { - QPushButton *button = new QPushButton(text, parent); - button->setFixedSize(150, 100); - button->setAutoRepeat(true); - button->setAutoRepeatInterval(150); - button->setAutoRepeatDelay(350); - button->setStyleSheet(R"( - QPushButton { - border-radius: 50px; - font-size: 50px; - font-weight: 500; - height: 100px; - padding: 0 25 0 25; - color: #E4E4E4; - background-color: #393939; - } - QPushButton:pressed { - background-color: #4a4a4a; - } - )"); - return button; - } -}; diff --git a/selfdrive/frogpilot/ui/vehicle_settings.cc b/selfdrive/frogpilot/ui/vehicle_settings.cc deleted file mode 100644 index 83e1cd4..0000000 --- a/selfdrive/frogpilot/ui/vehicle_settings.cc +++ /dev/null @@ -1,233 +0,0 @@ -#include -#include -#include - -#include "selfdrive/frogpilot/ui/vehicle_settings.h" - -QStringList getCarNames(const QString &carMake) { - QMap makeMap; - makeMap["acura"] = "honda"; - makeMap["audi"] = "volkswagen"; - makeMap["buick"] = "gm"; - makeMap["cadillac"] = "gm"; - makeMap["chevrolet"] = "gm"; - makeMap["chrysler"] = "chrysler"; - makeMap["dodge"] = "chrysler"; - makeMap["ford"] = "ford"; - makeMap["gm"] = "gm"; - makeMap["gmc"] = "gm"; - makeMap["genesis"] = "hyundai"; - makeMap["honda"] = "honda"; - makeMap["hyundai"] = "hyundai"; - makeMap["infiniti"] = "nissan"; - makeMap["jeep"] = "chrysler"; - makeMap["kia"] = "hyundai"; - makeMap["lexus"] = "toyota"; - makeMap["lincoln"] = "ford"; - makeMap["man"] = "volkswagen"; - makeMap["mazda"] = "mazda"; - makeMap["nissan"] = "nissan"; - makeMap["ram"] = "chrysler"; - makeMap["seat"] = "volkswagen"; - makeMap["subaru"] = "subaru"; - makeMap["tesla"] = "tesla"; - makeMap["toyota"] = "toyota"; - makeMap["volkswagen"] = "volkswagen"; - makeMap["skoda"] = "volkswagen"; - - QString dirPath = "../../selfdrive/car"; - QDir dir(dirPath); - QString targetFolder = makeMap.value(carMake, carMake); - QStringList names; - - foreach (const QString &folder, dir.entryList(QDir::Dirs | QDir::NoDotAndDotDot)) { - if (folder == targetFolder) { - QFile file(dirPath + "/" + folder + "/values.py"); - if (file.open(QIODevice::ReadOnly | QIODevice::Text)) { - QRegularExpression regex("class CAR\\(StrEnum\\):([\\s\\S]*?)(?=^\\w)", QRegularExpression::MultilineOption); - QRegularExpressionMatch match = regex.match(QTextStream(&file).readAll()); - file.close(); - - if (match.hasMatch()) { - QRegularExpression nameRegex("=\\s*\"([^\"]+)\""); - QRegularExpressionMatchIterator it = nameRegex.globalMatch(match.captured(1)); - while (it.hasNext()) { - names << it.next().captured(1); - } - } - } - } - } - - std::sort(names.begin(), names.end()); - return names; -} - -FrogPilotVehiclesPanel::FrogPilotVehiclesPanel(SettingsWindow *parent) : FrogPilotListWidget(parent) { - selectMakeButton = new ButtonControl(tr("Select Make"), tr("SELECT")); - QObject::connect(selectMakeButton, &ButtonControl::clicked, [this]() { - QStringList makes = { - "Acura", "Audi", "BMW", "Buick", "Cadillac", "Chevrolet", "Chrysler", "Dodge", "Ford", "GM", "GMC", - "Genesis", "Honda", "Hyundai", "Infiniti", "Jeep", "Kia", "Lexus", "Lincoln", "MAN", "Mazda", - "Mercedes", "Nissan", "Ram", "SEAT", "Subaru", "Tesla", "Toyota", "Volkswagen", "Volvo", "Škoda", - }; - - QString newMakeSelection = MultiOptionDialog::getSelection(tr("Select a Make"), makes, "", this); - if (!newMakeSelection.isEmpty()) { - carMake = newMakeSelection; - params.putNonBlocking("CarMake", carMake.toStdString()); - selectMakeButton->setValue(newMakeSelection); - setModels(); - } - }); - addItem(selectMakeButton); - - selectModelButton = new ButtonControl(tr("Select Model"), tr("SELECT")); - QString modelSelection = QString::fromStdString(params.get("CarModel")); - QObject::connect(selectModelButton, &ButtonControl::clicked, [this]() { - QString newModelSelection = MultiOptionDialog::getSelection(tr("Select a Model"), models, "", this); - if (!newModelSelection.isEmpty()) { - params.putNonBlocking("CarModel", newModelSelection.toStdString()); - selectModelButton->setValue(newModelSelection); - } - }); - selectModelButton->setValue(modelSelection); - addItem(selectModelButton); - selectModelButton->setVisible(false); - - ParamControl *forceFingerprint = new ParamControl("ForceFingerprint", "Disable Automatic Fingerprint Detection", "Forces the selected fingerprint and prevents it from ever changing.", "", this); - addItem(forceFingerprint); - - ParamControl *disableOpenpilotLong = new ParamControl("DisableOpenpilotLongitudinal", "Disable Openpilot Longitudinal Control", "Disables openpilot longitudinal control to use stock ACC.", "", this); - addItem(disableOpenpilotLong); - - QObject::connect(disableOpenpilotLong, &ToggleControl::toggleFlipped, [=]() { - if (started) { - if (FrogPilotConfirmationDialog::toggle("Reboot required to take effect.", "Reboot Now", this)) { - Hardware::reboot(); - } - } - }); - - std::vector> vehicleToggles { - {"EVTable", "EV Lookup Tables", "Smoothen out the gas and brake controls for EV vehicles.", ""}, - {"GasRegenCmd", "GM Truck Gas Tune", "Increase acceleration and smoothen brake to stop. For use on Silverado/Sierra only.", ""}, - {"LongPitch", "Long Pitch Compensation", "Reduce speed and acceleration error for greater passenger comfort and improved vehicle efficiency.", ""}, - {"LowerVolt", "Lower Volt Enable Speed", "Lower the Volt's minimum enable speed to enable openpilot at any speed.", ""}, - - {"CrosstrekTorque", "Subaru Crosstrek Torque Increase", "Increases the maximum allowed torque for the Subaru Crosstrek.", ""}, - - {"LockDoors", "Lock Doors In Drive", "Automatically lock the doors when in drive and unlock when in park.", ""}, - {"LongitudinalTune", "Longitudinal Tune", "Use a custom Toyota longitudinal tune.\n\nCydia = More focused on TSS-P vehicles but works for all Toyotas\n\nDragonPilot = Focused on TSS2 vehicles\n\nFrogPilot = Takes the best of both worlds with some personal tweaks focused around my 2019 Lexus ES 350", ""}, - {"SNGHack", "Stop and Go Hack", "Enable the 'Stop and Go' hack for vehicles without stock stop and go functionality.", ""}, - }; - - for (const auto &[param, title, desc, icon] : vehicleToggles) { - ParamControl *toggle; - - if (param == "LongitudinalTune") { - std::vector> tuneOptions{ - {"StockTune", tr("Stock")}, - {"CydiaTune", tr("Cydia's")}, - {"DragonPilotTune", tr("DragonPilot's")}, - {"FrogsGoMooTune", tr("FrogPilot's")}, - }; - toggle = new FrogPilotButtonsParamControl(param, title, desc, icon, tuneOptions); - - QObject::connect(static_cast(toggle), &FrogPilotButtonsParamControl::buttonClicked, [this]() { - if (started) { - if (FrogPilotConfirmationDialog::toggle("Reboot required to take effect.", "Reboot Now", this)) { - Hardware::soft_reboot(); - } - } - }); - - } else { - toggle = new ParamControl(param, title, desc, icon, this); - } - - toggle->setVisible(false); - addItem(toggle); - toggles[param.toStdString()] = toggle; - - QObject::connect(toggle, &ToggleControl::toggleFlipped, [this]() { - updateToggles(); - }); - - QObject::connect(toggle, &AbstractControl::showDescriptionEvent, [this]() { - update(); - }); - } - - std::set rebootKeys = {"CrosstrekTorque", "GasRegenCmd", "LowerVolt"}; - for (const std::string &key : rebootKeys) { - QObject::connect(toggles[key], &ToggleControl::toggleFlipped, [this]() { - if (started) { - if (FrogPilotConfirmationDialog::toggle("Reboot required to take effect.", "Reboot Now", this)) { - Hardware::soft_reboot(); - } - } - }); - } - - QObject::connect(uiState(), &UIState::offroadTransition, this, [this](bool offroad) { - if (!offroad) { - std::thread([this]() { - while (carMake.isEmpty()) { - std::this_thread::sleep_for(std::chrono::seconds(1)); - carMake = QString::fromStdString(params.get("CarMake")); - } - setModels(); - }).detach(); - } - }); - - QObject::connect(uiState(), &UIState::uiUpdate, this, &FrogPilotVehiclesPanel::updateState); - - carMake = QString::fromStdString(params.get("CarMake")); - if (!carMake.isEmpty()) { - setModels(); - } -} - -void FrogPilotVehiclesPanel::updateState(const UIState &s) { - started = s.scene.started; -} - -void FrogPilotVehiclesPanel::updateToggles() { - std::thread([this]() { - paramsMemory.putBool("FrogPilotTogglesUpdated", true); - std::this_thread::sleep_for(std::chrono::seconds(1)); - paramsMemory.putBool("FrogPilotTogglesUpdated", false); - }).detach(); -} - -void FrogPilotVehiclesPanel::setModels() { - models = getCarNames(carMake.toLower()); - setToggles(); -} - -void FrogPilotVehiclesPanel::setToggles() { - selectMakeButton->setValue(carMake); - selectModelButton->setVisible(!carMake.isEmpty()); - - bool gm = carMake == "Buick" || carMake == "Cadillac" || carMake == "Chevrolet" || carMake == "GM" || carMake == "GMC"; - bool subaru = carMake == "Subaru"; - bool toyota = carMake == "Lexus" || carMake == "Toyota"; - - for (auto &[key, toggle] : toggles) { - if (toggle) { - toggle->setVisible(false); - - if (gm) { - toggle->setVisible(gmKeys.find(key.c_str()) != gmKeys.end()); - } else if (subaru) { - toggle->setVisible(subaruKeys.find(key.c_str()) != subaruKeys.end()); - } else if (toyota) { - toggle->setVisible(toyotaKeys.find(key.c_str()) != toyotaKeys.end()); - } - } - } - - update(); -} diff --git a/selfdrive/frogpilot/ui/vehicle_settings.h b/selfdrive/frogpilot/ui/vehicle_settings.h deleted file mode 100644 index 42320e1..0000000 --- a/selfdrive/frogpilot/ui/vehicle_settings.h +++ /dev/null @@ -1,39 +0,0 @@ -#pragma once - -#include - -#include - -#include "selfdrive/frogpilot/ui/frogpilot_ui_functions.h" -#include "selfdrive/ui/qt/offroad/settings.h" -#include "selfdrive/ui/ui.h" - -class FrogPilotVehiclesPanel : public FrogPilotListWidget { - Q_OBJECT - -public: - explicit FrogPilotVehiclesPanel(SettingsWindow *parent); - -private: - void setModels(); - void setToggles(); - void updateState(const UIState &s); - void updateToggles(); - - ButtonControl *selectMakeButton; - ButtonControl *selectModelButton; - - QString carMake; - QStringList models; - - std::map toggles; - - std::set gmKeys = {"EVTable", "GasRegenCmd", "LongPitch", "LowerVolt"}; - std::set subaruKeys = {"CrosstrekTorque"}; - std::set toyotaKeys = {"LockDoors", "LongitudinalTune", "SNGHack"}; - - Params params; - Params paramsMemory{"/dev/shm/params"}; - - bool started = false; -}; diff --git a/selfdrive/frogpilot/ui/visual_settings.cc b/selfdrive/frogpilot/ui/visual_settings.cc deleted file mode 100644 index 95e2aef..0000000 --- a/selfdrive/frogpilot/ui/visual_settings.cc +++ /dev/null @@ -1,388 +0,0 @@ -#include "selfdrive/frogpilot/ui/visual_settings.h" - -FrogPilotVisualsPanel::FrogPilotVisualsPanel(SettingsWindow *parent) : FrogPilotListWidget(parent) { - const std::vector> visualToggles { - {"CustomTheme", "Custom Themes", "Enable the ability to use custom themes.", "../frogpilot/assets/wheel_images/frog.png"}, - {"HolidayThemes", "Holiday Themes", "The openpilot theme changes according to the current/upcoming holiday. Minor holidays last a day, major holidays (Easter, Christmas, Halloween, etc.) last a week.", ""}, - {"CustomColors", "Color Theme", "Switch out the standard openpilot color scheme with a custom color scheme.\n\nWant to submit your own color scheme? Post it in the 'feature-request' channel in the FrogPilot Discord!", ""}, - {"CustomIcons", "Icon Pack", "Switch out the standard openpilot icons with a set of custom icons.\n\nWant to submit your own icon pack? Post it in the 'feature-request' channel in the FrogPilot Discord!", ""}, - {"CustomSignals", "Turn Signals", "Add custom animations for your turn signals for a personal touch!\n\nWant to submit your own turn signal animation? Post it in the 'feature-request' channel in the FrogPilot Discord!", ""}, - {"CustomSounds", "Sound Pack", "Switch out the standard openpilot sounds with a set of custom sounds.\n\nWant to submit your own sound pack? Post it in the 'feature-request' channel in the FrogPilot Discord!", ""}, - - {"AlertVolumeControl", "Alert Volume Control", "Control the volume level for each individual sound in openpilot.", "../frogpilot/assets/toggle_icons/icon_mute.png"}, - {"DisengageVolume", "Disengage Volume", "Related alerts:\n\nAdaptive Cruise Disabled\nParking Brake Engaged\nPedal Pressed\nSpeed too Low", ""}, - {"EngageVolume", "Engage Volume", "Related alerts:\n\nNNFF Torque Controller loaded", ""}, - {"PromptVolume", "Prompt Volume", "Related alerts:\n\nCar Detected in Blindspot\nLight turned green\nSpeed too Low\nSteer Unavailable Below 'X'\nTake Control, Turn Exceeds Steering Limit", ""}, - {"PromptDistractedVolume", "Prompt Distracted Volume", "Related alerts:\n\nPay Attention, Driver Distracted\nTouch Steering Wheel, Driver Unresponsive", ""}, - {"RefuseVolume", "Refuse Volume", "Related alerts:\n\nopenpilot Unavailable", ""}, - {"WarningSoftVolume", "Warning Soft Volume", "Related alerts:\n\nBRAKE!, Risk of Collision\nTAKE CONTROL IMMEDIATELY", ""}, - {"WarningImmediateVolume", "Warning Immediate Volume", "Related alerts:\n\nDISENGAGE IMMEDIATELY, Driver Distracted\nDISENGAGE IMMEDIATELY, Driver Unresponsive", ""}, - - {"CameraView", "Camera View", "Choose your preferred camera view for the onroad UI. This is a visual change only and doesn't impact openpilot.", "../frogpilot/assets/toggle_icons/icon_camera.png"}, - {"Compass", "Compass", "Add a compass to your onroad UI.", "../frogpilot/assets/toggle_icons/icon_compass.png"}, - - {"CustomAlerts", "Custom Alerts", "Enable custom alerts for various logic or situational changes.", "../frogpilot/assets/toggle_icons/icon_green_light.png"}, - {"GreenLightAlert", "Green Light Alert", "Get an alert when a traffic light changes from red to green.", ""}, - {"LeadDepartingAlert", "Lead Departing Alert", "Get an alert when your lead vehicle starts departing when you're at a standstill.", ""}, - {"LoudBlindspotAlert", "Loud Blindspot Alert", "Enable a louder alert for when a vehicle is detected in your blindspot when attempting to change lanes.", ""}, - {"SpeedLimitChangedAlert", "Speed Limit Changed Alert", "Trigger an alert whenever the current speed limit changes.", ""}, - - {"CustomUI", "Custom Onroad UI", "Customize the Onroad UI with some additional visual functions.", "../assets/offroad/icon_road.png"}, - {"AccelerationPath", "Acceleration Path", "Visualize the car's intended acceleration or deceleration with a color-coded path.", ""}, - {"AdjacentPath", "Adjacent Paths", "Display paths to the left and right of your car, visualizing where the model detects lanes.", ""}, - {"BlindSpotPath", "Blind Spot Path", "Visualize your blind spots with a red path when another vehicle is detected nearby.", ""}, - {"FPSCounter", "FPS Counter", "Display the Frames Per Second (FPS) of your onroad UI for monitoring system performance.", ""}, - {"LeadInfo", "Lead Info and Logics", "Get detailed information about the vehicle ahead, including speed and distance, and the logic behind your following distance.", ""}, - {"PedalsOnUI", "Pedals Being Pressed", "Display which pedals are being pressed on the onroad UI below the steering wheel icon.", ""}, - {"RoadNameUI", "Road Name", "See the name of the road you're on at the bottom of your screen. Sourced from OpenStreetMap.", ""}, - - {"DriverCamera", "Driver Camera On Reverse", "Show the driver's camera feed when you shift to reverse.", "../assets/img_driver_face_static.png"}, - - {"ModelUI", "Model UI", "Personalize how the model's visualizations appear on your screen.", "../assets/offroad/icon_calibration.png"}, - {"DynamicPathWidth", "Dynamic Path Width", "Have the path width dynamically adjust based on the current engagement state of openpilot.", ""}, - {"HideLeadMarker", "Hide Lead Marker", "Hide the lead marker from the onroad UI.", ""}, - {"LaneLinesWidth", "Lane Lines", "Adjust the visual thickness of lane lines on your display.\n\nDefault matches the MUTCD average of 4 inches.", ""}, - {"PathEdgeWidth", "Path Edges", "Adjust the width of the path edges shown on your UI to represent different driving modes and statuses.\n\nDefault is 20% of the total path.\n\nBlue = Navigation\nLight Blue = Always On Lateral\nGreen = Default with 'FrogPilot Colors'\nLight Green = Default with stock colors\nOrange = Experimental Mode Active\nYellow = Conditional Overriden", ""}, - {"PathWidth", "Path Width", "Customize the width of the driving path shown on your UI.\n\nDefault matches the width of a 2019 Lexus ES 350.", ""}, - {"RoadEdgesWidth", "Road Edges", "Adjust the visual thickness of road edges on your display.\n\nDefault is 1/2 of the MUTCD average lane line width of 4 inches.", ""}, - {"UnlimitedLength", "'Unlimited' Road UI Length", "Extend the display of the path, lane lines, and road edges as far as the system can detect, providing a more expansive view of the road ahead.", ""}, - - {"NumericalTemp", "Numerical Temperature Gauge", "Replace the 'GOOD', 'OK', and 'HIGH' temperature statuses with a numerical temperature gauge based on the highest temperature between the memory, CPU, and GPU.", "../frogpilot/assets/toggle_icons/icon_temperature.png"}, - - {"QOLVisuals", "Quality of Life", "Miscellaneous quality of life changes to improve your overall openpilot experience.", "../frogpilot/assets/toggle_icons/quality_of_life.png"}, - {"DriveStats", "Drive Stats In Home Screen", "Display your device's drive stats in the home screen.", ""}, - {"FullMap", "Full Sized Map", "Maximize the size of the map in the onroad UI.", ""}, - {"HideSpeed", "Hide Speed", "Hide the speed indicator in the onroad UI. Additional toggle allows it to be hidden/shown via tapping the speed itself.", ""}, - {"MapStyle", "Map Style", "Use a custom map style to be used for 'Navigate on openpilot'.", ""}, - {"WheelSpeed", "Use Wheel Speed", "Use the wheel speed metric as opposed to the artificial speed.", ""}, - - {"RandomEvents", "Random Events", "Enjoy a bit of unpredictability with random events that can occur during certain driving conditions.", "../frogpilot/assets/toggle_icons/icon_random.png"}, - - {"ScreenManagement", "Screen Management", "Manage your screen's brightness, timeout settings, and hide specific onroad UI elements.", "../frogpilot/assets/toggle_icons/icon_light.png"}, - {"HideUIElements", "Hide UI Elements", "Hide the selected UI elements from the onroad screen.", ""}, - {"ScreenBrightness", "Screen Brightness", "Customize your screen brightness when offroad.", ""}, - {"ScreenBrightnessOnroad", "Screen Brightness (Onroad)", "Customize your screen brightness when onroad.", ""}, - {"ScreenRecorder", "Screen Recorder", "Enable the screen recorder button to record the screen.", ""}, - {"ScreenTimeout", "Screen Timeout", "Customize how long it takes for your screen to turn off.", ""}, - {"ScreenTimeoutOnroad", "Screen Timeout (Onroad)", "Customize how long it takes for your screen to turn off after going onroad.", ""}, - {"StandbyMode", "Standby Mode", "Turn the screen off after your screen times out when onroad but wake it back up when engagement state changes or important alerts are triggered.", ""}, - - {"WheelIcon", "Steering Wheel Icon", "Replace the default steering wheel icon with a custom design, adding a unique touch to your interface.", "../assets/offroad/icon_openpilot.png"}, - }; - - for (const auto &[param, title, desc, icon] : visualToggles) { - ParamControl *toggle; - - if (param == "AlertVolumeControl") { - FrogPilotParamManageControl *alertVolumeControlToggle = new FrogPilotParamManageControl(param, title, desc, icon, this); - QObject::connect(alertVolumeControlToggle, &FrogPilotParamManageControl::manageButtonClicked, this, [this]() { - parentToggleClicked(); - for (auto &[key, toggle] : toggles) { - toggle->setVisible(alertVolumeControlKeys.find(key.c_str()) != alertVolumeControlKeys.end()); - } - }); - toggle = alertVolumeControlToggle; - } else if (alertVolumeControlKeys.find(param) != alertVolumeControlKeys.end()) { - if (param == "WarningImmediateVolume") { - toggle = new FrogPilotParamValueControl(param, title, desc, icon, 25, 100, std::map(), this, false, "%"); - } else { - toggle = new FrogPilotParamValueControl(param, title, desc, icon, 0, 100, std::map(), this, false, "%"); - } - - } else if (param == "CameraView") { - std::vector cameraOptions{tr("Auto"), tr("Standard"), tr("Wide"), tr("Driver")}; - FrogPilotButtonParamControl *preferredCamera = new FrogPilotButtonParamControl(param, title, desc, icon, cameraOptions); - toggle = preferredCamera; - - } else if (param == "CustomAlerts") { - FrogPilotParamManageControl *customAlertsToggle = new FrogPilotParamManageControl(param, title, desc, icon, this); - QObject::connect(customAlertsToggle, &FrogPilotParamManageControl::manageButtonClicked, this, [this]() { - parentToggleClicked(); - for (auto &[key, toggle] : toggles) { - toggle->setVisible(customAlertsKeys .find(key.c_str()) != customAlertsKeys .end()); - } - }); - toggle = customAlertsToggle; - - } else if (param == "CustomTheme") { - FrogPilotParamManageControl *customThemeToggle = new FrogPilotParamManageControl(param, title, desc, icon, this); - QObject::connect(customThemeToggle, &FrogPilotParamManageControl::manageButtonClicked, this, [this]() { - parentToggleClicked(); - for (auto &[key, toggle] : toggles) { - toggle->setVisible(customThemeKeys.find(key.c_str()) != customThemeKeys.end()); - } - }); - toggle = customThemeToggle; - } else if (customThemeKeys.find(param) != customThemeKeys.end() && param != "HolidayThemes") { - std::vector themeOptions{tr("Stock"), tr("Frog"), tr("Tesla"), tr("Stalin")}; - FrogPilotButtonParamControl *themeSelection = new FrogPilotButtonParamControl(param, title, desc, icon, themeOptions); - toggle = themeSelection; - - if (param == "CustomSounds") { - QObject::connect(static_cast(toggle), &FrogPilotButtonParamControl::buttonClicked, [this](int id) { - if (id == 1) { - if (FrogPilotConfirmationDialog::yesorno("Do you want to enable the bonus 'Goat' sound effect?", this)) { - params.putBoolNonBlocking("GoatScream", true); - } else { - params.putBoolNonBlocking("GoatScream", false); - } - } - }); - } - - } else if (param == "CustomUI") { - FrogPilotParamManageControl *customUIToggle = new FrogPilotParamManageControl(param, title, desc, icon, this); - QObject::connect(customUIToggle, &FrogPilotParamManageControl::manageButtonClicked, this, [this]() { - parentToggleClicked(); - for (auto &[key, toggle] : toggles) { - toggle->setVisible(customOnroadUIKeys.find(key.c_str()) != customOnroadUIKeys.end()); - } - }); - toggle = customUIToggle; - } else if (param == "LeadInfo") { - std::vector leadInfoToggles{"UseSI"}; - std::vector leadInfoToggleNames{tr("Use SI Values")}; - toggle = new FrogPilotParamToggleControl(param, title, desc, icon, leadInfoToggles, leadInfoToggleNames); - } else if (param == "AdjacentPath") { - std::vector adjacentPathToggles{"AdjacentPathMetrics"}; - std::vector adjacentPathToggleNames{tr("Display Metrics")}; - toggle = new FrogPilotParamToggleControl(param, title, desc, icon, adjacentPathToggles, adjacentPathToggleNames); - - } else if (param == "ModelUI") { - FrogPilotParamManageControl *modelUIToggle = new FrogPilotParamManageControl(param, title, desc, icon, this); - QObject::connect(modelUIToggle, &FrogPilotParamManageControl::manageButtonClicked, this, [this]() { - parentToggleClicked(); - for (auto &[key, toggle] : toggles) { - toggle->setVisible(modelUIKeys.find(key.c_str()) != modelUIKeys.end()); - } - }); - toggle = modelUIToggle; - } else if (param == "LaneLinesWidth" || param == "RoadEdgesWidth") { - toggle = new FrogPilotParamValueControl(param, title, desc, icon, 0, 24, std::map(), this, false, " inches"); - } else if (param == "PathEdgeWidth") { - toggle = new FrogPilotParamValueControl(param, title, desc, icon, 0, 100, std::map(), this, false, "%"); - } else if (param == "PathWidth") { - toggle = new FrogPilotParamValueControl(param, title, desc, icon, 0, 100, std::map(), this, false, " feet", 10); - - } else if (param == "NumericalTemp") { - std::vector temperatureToggles{"Fahrenheit"}; - std::vector temperatureToggleNames{tr("Fahrenheit")}; - toggle = new FrogPilotParamToggleControl(param, title, desc, icon, temperatureToggles, temperatureToggleNames); - - } else if (param == "QOLVisuals") { - FrogPilotParamManageControl *qolToggle = new FrogPilotParamManageControl(param, title, desc, icon, this); - QObject::connect(qolToggle, &FrogPilotParamManageControl::manageButtonClicked, this, [this]() { - parentToggleClicked(); - for (auto &[key, toggle] : toggles) { - toggle->setVisible(qolKeys.find(key.c_str()) != qolKeys.end()); - } - mapStyleButton->setVisible(true); - }); - toggle = qolToggle; - } else if (param == "HideSpeed") { - std::vector hideSpeedToggles{"HideSpeedUI"}; - std::vector hideSpeedToggleNames{tr("Control Via UI")}; - toggle = new FrogPilotParamToggleControl(param, title, desc, icon, hideSpeedToggles, hideSpeedToggleNames); - } else if (param == "MapStyle") { - QMap styleMap = { - {0, tr("Stock openpilot")}, - {1, tr("Mapbox Streets")}, - {2, tr("Mapbox Outdoors")}, - {3, tr("Mapbox Light")}, - {4, tr("Mapbox Dark")}, - {5, tr("Mapbox Satellite")}, - {6, tr("Mapbox Satellite Streets")}, - {7, tr("Mapbox Navigation Day")}, - {8, tr("Mapbox Navigation Night")}, - {9, tr("Mapbox Traffic Night")}, - {10, tr("mike854's (Satellite hybrid)")}, - }; - - QStringList styles = styleMap.values(); - - mapStyleButton = new ButtonControl(title, tr("SELECT"), desc); - QObject::connect(mapStyleButton, &ButtonControl::clicked, this, [this, styleMap]() { - QStringList styles = styleMap.values(); - QString selection = MultiOptionDialog::getSelection(tr("Select a map style"), styles, "", this); - if (!selection.isEmpty()) { - int selectedStyle = styleMap.key(selection); - params.putInt("MapStyle", selectedStyle); - mapStyleButton->setValue(selection); - updateToggles(); - } - }); - - int currentStyle = params.getInt("MapStyle"); - mapStyleButton->setValue(styleMap[currentStyle]); - - addItem(mapStyleButton); - - } else if (param == "ScreenManagement") { - FrogPilotParamManageControl *screenToggle = new FrogPilotParamManageControl(param, title, desc, icon, this); - QObject::connect(screenToggle, &FrogPilotParamManageControl::manageButtonClicked, this, [this]() { - parentToggleClicked(); - for (auto &[key, toggle] : toggles) { - toggle->setVisible(screenKeys.find(key.c_str()) != screenKeys.end()); - } - }); - toggle = screenToggle; - } else if (param == "HideUIElements") { - std::vector uiElementsToggles{"HideAlerts", "HideMapIcon", "HideMaxSpeed"}; - std::vector uiElementsToggleNames{tr("Alerts"), tr("Map Icon"), tr("Max Speed")}; - toggle = new FrogPilotParamToggleControl(param, title, desc, icon, uiElementsToggles, uiElementsToggleNames); - } else if (param == "ScreenBrightness" || param == "ScreenBrightnessOnroad") { - std::map brightnessLabels; - for (int i = 0; i <= 101; ++i) { - brightnessLabels[i] = i == 0 ? "Screen Off" : i == 101 ? "Auto" : QString::number(i) + "%"; - } - toggle = new FrogPilotParamValueControl(param, title, desc, icon, 0, 101, brightnessLabels, this, false); - } else if (param == "ScreenTimeout" || param == "ScreenTimeoutOnroad") { - toggle = new FrogPilotParamValueControl(param, title, desc, icon, 5, 60, std::map(), this, false, " seconds"); - - } else if (param == "WheelIcon") { - std::vector wheelToggles{"RotatingWheel"}; - std::vector wheelToggleNames{tr("Rotating")}; - std::map steeringWheelLabels = {{-1, "None"}, {0, "Stock"}, {1, "Lexus"}, {2, "Toyota"}, {3, "Frog"}, {4, "Rocket"}, {5, "Hyundai"}, {6, "Stalin"}}; - toggle = new FrogPilotParamValueToggleControl(param, title, desc, icon, -1, 6, steeringWheelLabels, this, true, "", 1, wheelToggles, wheelToggleNames); - - } else { - toggle = new ParamControl(param, title, desc, icon, this); - } - - addItem(toggle); - toggles[param.toStdString()] = toggle; - - QObject::connect(toggle, &ToggleControl::toggleFlipped, [this]() { - updateToggles(); - }); - - QObject::connect(static_cast(toggle), &FrogPilotButtonParamControl::buttonClicked, [this]() { - updateToggles(); - }); - - QObject::connect(static_cast(toggle), &FrogPilotParamValueControl::valueChanged, [this]() { - updateToggles(); - }); - - QObject::connect(toggle, &AbstractControl::showDescriptionEvent, [this]() { - update(); - }); - - QObject::connect(static_cast(toggle), &FrogPilotParamManageControl::manageButtonClicked, [this]() { - update(); - }); - } - - std::set rebootKeys = {"DriveStats"}; - for (const std::string &key : rebootKeys) { - QObject::connect(toggles[key], &ToggleControl::toggleFlipped, [this, key]() { - if (started || key == "DriveStats") { - if (FrogPilotConfirmationDialog::toggle("Reboot required to take effect.", "Reboot Now", this)) { - Hardware::soft_reboot(); - } - } - }); - } - - QObject::connect(device(), &Device::interactiveTimeout, this, &FrogPilotVisualsPanel::hideSubToggles); - QObject::connect(parent, &SettingsWindow::closeParentToggle, this, &FrogPilotVisualsPanel::hideSubToggles); - QObject::connect(parent, &SettingsWindow::closeSubParentToggle, this, &FrogPilotVisualsPanel::hideSubSubToggles); - QObject::connect(parent, &SettingsWindow::updateMetric, this, &FrogPilotVisualsPanel::updateMetric); - QObject::connect(uiState(), &UIState::uiUpdate, this, &FrogPilotVisualsPanel::updateState); - - hideSubToggles(); - updateMetric(); -} - -void FrogPilotVisualsPanel::updateState(const UIState &s) { - started = s.scene.started; -} - -void FrogPilotVisualsPanel::updateToggles() { - std::thread([this]() { - paramsMemory.putBool("FrogPilotTogglesUpdated", true); - std::this_thread::sleep_for(std::chrono::seconds(1)); - paramsMemory.putBool("FrogPilotTogglesUpdated", false); - }).detach(); -} - -void FrogPilotVisualsPanel::updateMetric() { - bool previousIsMetric = isMetric; - isMetric = params.getBool("IsMetric"); - - if (isMetric != previousIsMetric) { - double distanceConversion = isMetric ? INCH_TO_CM : CM_TO_INCH; - double speedConversion = isMetric ? FOOT_TO_METER : METER_TO_FOOT; - params.putIntNonBlocking("LaneLinesWidth", std::nearbyint(params.getInt("LaneLinesWidth") * distanceConversion)); - params.putIntNonBlocking("RoadEdgesWidth", std::nearbyint(params.getInt("RoadEdgesWidth") * distanceConversion)); - params.putIntNonBlocking("PathWidth", std::nearbyint(params.getInt("PathWidth") * speedConversion)); - } - - FrogPilotParamValueControl *laneLinesWidthToggle = static_cast(toggles["LaneLinesWidth"]); - FrogPilotParamValueControl *roadEdgesWidthToggle = static_cast(toggles["RoadEdgesWidth"]); - FrogPilotParamValueControl *pathWidthToggle = static_cast(toggles["PathWidth"]); - - if (isMetric) { - laneLinesWidthToggle->setDescription("Customize the lane line width.\n\nDefault matches the Vienna average of 10 centimeters."); - roadEdgesWidthToggle->setDescription("Customize the road edges width.\n\nDefault is 1/2 of the Vienna average lane line width of 10 centimeters."); - - laneLinesWidthToggle->updateControl(0, 60, " centimeters"); - roadEdgesWidthToggle->updateControl(0, 60, " centimeters"); - pathWidthToggle->updateControl(0, 30, " meters", 10); - } else { - laneLinesWidthToggle->setDescription("Customize the lane line width.\n\nDefault matches the MUTCD average of 4 inches."); - roadEdgesWidthToggle->setDescription("Customize the road edges width.\n\nDefault is 1/2 of the MUTCD average lane line width of 4 inches."); - - laneLinesWidthToggle->updateControl(0, 24, " inches"); - roadEdgesWidthToggle->updateControl(0, 24, " inches"); - pathWidthToggle->updateControl(0, 100, " feet", 10); - } - - laneLinesWidthToggle->refresh(); - roadEdgesWidthToggle->refresh(); - - previousIsMetric = isMetric; -} - -void FrogPilotVisualsPanel::parentToggleClicked() { - mapStyleButton->setVisible(false); - - openParentToggle(); -} - -void FrogPilotVisualsPanel::subParentToggleClicked() { - mapStyleButton->setVisible(false); - - openSubParentToggle(); -} - -void FrogPilotVisualsPanel::hideSubToggles() { - mapStyleButton->setVisible(false); - - for (auto &[key, toggle] : toggles) { - bool subToggles = alertVolumeControlKeys.find(key.c_str()) != alertVolumeControlKeys.end() || - customAlertsKeys.find(key.c_str()) != customAlertsKeys.end() || - customOnroadUIKeys.find(key.c_str()) != customOnroadUIKeys.end() || - customThemeKeys.find(key.c_str()) != customThemeKeys.end() || - modelUIKeys.find(key.c_str()) != modelUIKeys.end() || - qolKeys.find(key.c_str()) != qolKeys.end() || - screenKeys.find(key.c_str()) != screenKeys.end(); - toggle->setVisible(!subToggles); - } - - closeParentToggle(); -} - -void FrogPilotVisualsPanel::hideSubSubToggles() { - for (auto &[key, toggle] : toggles) { - bool isVisible = false; - toggle->setVisible(isVisible); - } - - closeSubParentToggle(); - update(); -} - -void FrogPilotVisualsPanel::hideEvent(QHideEvent *event) { - hideSubToggles(); -} diff --git a/selfdrive/frogpilot/ui/visual_settings.h b/selfdrive/frogpilot/ui/visual_settings.h deleted file mode 100644 index 61e58d6..0000000 --- a/selfdrive/frogpilot/ui/visual_settings.h +++ /dev/null @@ -1,48 +0,0 @@ -#pragma once - -#include - -#include "selfdrive/frogpilot/ui/frogpilot_ui_functions.h" -#include "selfdrive/ui/qt/offroad/settings.h" -#include "selfdrive/ui/ui.h" - -class FrogPilotVisualsPanel : public FrogPilotListWidget { - Q_OBJECT - -public: - explicit FrogPilotVisualsPanel(SettingsWindow *parent); - -signals: - void closeParentToggle(); - void closeSubParentToggle(); - void openParentToggle(); - void openSubParentToggle(); - -private: - void hideEvent(QHideEvent *event); - void hideSubToggles(); - void hideSubSubToggles(); - void parentToggleClicked(); - void subParentToggleClicked(); - void updateMetric(); - void updateState(const UIState &s); - void updateToggles(); - - ButtonControl *mapStyleButton; - - std::set alertVolumeControlKeys = {"EngageVolume", "DisengageVolume", "RefuseVolume", "PromptVolume", "PromptDistractedVolume", "WarningSoftVolume", "WarningImmediateVolume"}; - std::set customAlertsKeys = {"GreenLightAlert", "LeadDepartingAlert", "LoudBlindspotAlert", "SpeedLimitChangedAlert"}; - std::set customOnroadUIKeys = {"AccelerationPath", "AdjacentPath", "BlindSpotPath", "FPSCounter", "LeadInfo", "PedalsOnUI", "RoadNameUI"}; - std::set customThemeKeys = {"HolidayThemes", "CustomColors", "CustomIcons", "CustomSignals", "CustomSounds"}; - std::set modelUIKeys = {"DynamicPathWidth", "HideLeadMarker", "LaneLinesWidth", "PathEdgeWidth", "PathWidth", "RoadEdgesWidth", "UnlimitedLength"}; - std::set qolKeys = {"DriveStats", "FullMap", "HideSpeed", "MapStyle", "WheelSpeed"}; - std::set screenKeys = {"HideUIElements", "ScreenBrightness", "ScreenBrightnessOnroad", "ScreenRecorder", "ScreenTimeout", "ScreenTimeoutOnroad", "StandbyMode"}; - - std::map toggles; - - Params params; - Params paramsMemory{"/dev/shm/params"}; - - bool isMetric = params.getBool("IsMetric"); - bool started = false; -}; diff --git a/selfdrive/locationd/SConscript b/selfdrive/locationd/SConscript deleted file mode 100644 index 07555a6..0000000 --- a/selfdrive/locationd/SConscript +++ /dev/null @@ -1,37 +0,0 @@ -Import('env', 'arch', 'common', 'cereal', 'messaging', 'rednose', 'transformations') - -loc_libs = [cereal, messaging, 'zmq', common, 'capnp', 'kj', 'pthread', 'dl'] - -# build ekf models -rednose_gen_dir = 'models/generated' -rednose_gen_deps = [ - "models/constants.py", -] -live_ekf = env.RednoseCompileFilter( - target='live', - filter_gen_script='models/live_kf.py', - output_dir=rednose_gen_dir, - extra_gen_artifacts=['live_kf_constants.h'], - gen_script_deps=rednose_gen_deps, -) -car_ekf = env.RednoseCompileFilter( - target='car', - filter_gen_script='models/car_kf.py', - output_dir=rednose_gen_dir, - extra_gen_artifacts=[], - gen_script_deps=rednose_gen_deps, -) - -# locationd build -locationd_sources = ["locationd.cc", "models/live_kf.cc"] - -lenv = env.Clone() -# ekf filter libraries need to be linked, even if no symbols are used -if arch != "Darwin": - lenv["LINKFLAGS"] += ["-Wl,--no-as-needed"] - -lenv["LIBPATH"].append(Dir(rednose_gen_dir).abspath) -lenv["RPATH"].append(Dir(rednose_gen_dir).abspath) -locationd = lenv.Program("locationd", locationd_sources, LIBS=["live", "ekf_sym"] + loc_libs + transformations) -lenv.Depends(locationd, rednose) -lenv.Depends(locationd, live_ekf) diff --git a/third_party/snpe/x86_64/libHtpPrepare.so b/selfdrive/locationd/locationd old mode 100644 new mode 100755 similarity index 50% rename from third_party/snpe/x86_64/libHtpPrepare.so rename to selfdrive/locationd/locationd index 0b0657d..b4ab23a Binary files a/third_party/snpe/x86_64/libHtpPrepare.so and b/selfdrive/locationd/locationd differ diff --git a/selfdrive/locationd/locationd.cc b/selfdrive/locationd/locationd.cc deleted file mode 100644 index 1050d68..0000000 --- a/selfdrive/locationd/locationd.cc +++ /dev/null @@ -1,752 +0,0 @@ -#include "selfdrive/locationd/locationd.h" - -#include -#include - -#include -#include -#include - -using namespace EKFS; -using namespace Eigen; - -ExitHandler do_exit; -const double ACCEL_SANITY_CHECK = 100.0; // m/s^2 -const double ROTATION_SANITY_CHECK = 10.0; // rad/s -const double TRANS_SANITY_CHECK = 200.0; // m/s -const double CALIB_RPY_SANITY_CHECK = 0.5; // rad (+- 30 deg) -const double ALTITUDE_SANITY_CHECK = 10000; // m -const double MIN_STD_SANITY_CHECK = 1e-5; // m or rad -const double VALID_TIME_SINCE_RESET = 1.0; // s -const double VALID_POS_STD = 50.0; // m -const double MAX_RESET_TRACKER = 5.0; -const double SANE_GPS_UNCERTAINTY = 1500.0; // m -const double INPUT_INVALID_THRESHOLD = 0.5; // same as reset tracker -const double RESET_TRACKER_DECAY = 0.99995; -const double DECAY = 0.9993; // ~10 secs to resume after a bad input -const double MAX_FILTER_REWIND_TIME = 0.8; // s -const double YAWRATE_CROSS_ERR_CHECK_FACTOR = 30; - -// TODO: GPS sensor time offsets are empirically calculated -// They should be replaced with synced time from a real clock -const double GPS_QUECTEL_SENSOR_TIME_OFFSET = 0.630; // s -const double GPS_UBLOX_SENSOR_TIME_OFFSET = 0.095; // s -const float GPS_POS_STD_THRESHOLD = 50.0; -const float GPS_VEL_STD_THRESHOLD = 5.0; -const float GPS_POS_ERROR_RESET_THRESHOLD = 300.0; -const float GPS_POS_STD_RESET_THRESHOLD = 2.0; -const float GPS_VEL_STD_RESET_THRESHOLD = 0.5; -const float GPS_ORIENTATION_ERROR_RESET_THRESHOLD = 1.0; -const int GPS_ORIENTATION_ERROR_RESET_CNT = 3; - -const bool DEBUG = getenv("DEBUG") != nullptr && std::string(getenv("DEBUG")) != "0"; - -static VectorXd floatlist2vector(const capnp::List::Reader& floatlist) { - VectorXd res(floatlist.size()); - for (int i = 0; i < floatlist.size(); i++) { - res[i] = floatlist[i]; - } - return res; -} - -static Vector4d quat2vector(const Quaterniond& quat) { - return Vector4d(quat.w(), quat.x(), quat.y(), quat.z()); -} - -static Quaterniond vector2quat(const VectorXd& vec) { - return Quaterniond(vec(0), vec(1), vec(2), vec(3)); -} - -static void init_measurement(cereal::LiveLocationKalman::Measurement::Builder meas, const VectorXd& val, const VectorXd& std, bool valid) { - meas.setValue(kj::arrayPtr(val.data(), val.size())); - meas.setStd(kj::arrayPtr(std.data(), std.size())); - meas.setValid(valid); -} - - -static MatrixXdr rotate_cov(const MatrixXdr& rot_matrix, const MatrixXdr& cov_in) { - // To rotate a covariance matrix, the cov matrix needs to multiplied left and right by the transform matrix - return ((rot_matrix * cov_in) * rot_matrix.transpose()); -} - -static VectorXd rotate_std(const MatrixXdr& rot_matrix, const VectorXd& std_in) { - // Stds cannot be rotated like values, only covariances can be rotated - return rotate_cov(rot_matrix, std_in.array().square().matrix().asDiagonal()).diagonal().array().sqrt(); -} - -Localizer::Localizer(LocalizerGnssSource gnss_source) { - this->kf = std::make_unique(); - this->reset_kalman(); - - this->calib = Vector3d(0.0, 0.0, 0.0); - this->device_from_calib = MatrixXdr::Identity(3, 3); - this->calib_from_device = MatrixXdr::Identity(3, 3); - - for (int i = 0; i < POSENET_STD_HIST_HALF * 2; i++) { - this->posenet_stds.push_back(10.0); - } - - VectorXd ecef_pos = this->kf->get_x().segment(STATE_ECEF_POS_START); - this->converter = std::make_unique((ECEF) { .x = ecef_pos[0], .y = ecef_pos[1], .z = ecef_pos[2] }); - this->configure_gnss_source(gnss_source); -} - -void Localizer::build_live_location(cereal::LiveLocationKalman::Builder& fix) { - VectorXd predicted_state = this->kf->get_x(); - MatrixXdr predicted_cov = this->kf->get_P(); - VectorXd predicted_std = predicted_cov.diagonal().array().sqrt(); - - VectorXd fix_ecef = predicted_state.segment(STATE_ECEF_POS_START); - ECEF fix_ecef_ecef = { .x = fix_ecef(0), .y = fix_ecef(1), .z = fix_ecef(2) }; - VectorXd fix_ecef_std = predicted_std.segment(STATE_ECEF_POS_ERR_START); - VectorXd vel_ecef = predicted_state.segment(STATE_ECEF_VELOCITY_START); - VectorXd vel_ecef_std = predicted_std.segment(STATE_ECEF_VELOCITY_ERR_START); - VectorXd fix_pos_geo_vec = this->get_position_geodetic(); - VectorXd orientation_ecef = quat2euler(vector2quat(predicted_state.segment(STATE_ECEF_ORIENTATION_START))); - VectorXd orientation_ecef_std = predicted_std.segment(STATE_ECEF_ORIENTATION_ERR_START); - MatrixXdr orientation_ecef_cov = predicted_cov.block(STATE_ECEF_ORIENTATION_ERR_START, STATE_ECEF_ORIENTATION_ERR_START); - MatrixXdr device_from_ecef = euler2rot(orientation_ecef).transpose(); - VectorXd calibrated_orientation_ecef = rot2euler((this->calib_from_device * device_from_ecef).transpose()); - - VectorXd acc_calib = this->calib_from_device * predicted_state.segment(STATE_ACCELERATION_START); - MatrixXdr acc_calib_cov = predicted_cov.block(STATE_ACCELERATION_ERR_START, STATE_ACCELERATION_ERR_START); - VectorXd acc_calib_std = rotate_cov(this->calib_from_device, acc_calib_cov).diagonal().array().sqrt(); - VectorXd ang_vel_calib = this->calib_from_device * predicted_state.segment(STATE_ANGULAR_VELOCITY_START); - - MatrixXdr vel_angular_cov = predicted_cov.block(STATE_ANGULAR_VELOCITY_ERR_START, STATE_ANGULAR_VELOCITY_ERR_START); - VectorXd ang_vel_calib_std = rotate_cov(this->calib_from_device, vel_angular_cov).diagonal().array().sqrt(); - - VectorXd vel_device = device_from_ecef * vel_ecef; - VectorXd device_from_ecef_eul = quat2euler(vector2quat(predicted_state.segment(STATE_ECEF_ORIENTATION_START))).transpose(); - MatrixXdr condensed_cov(STATE_ECEF_ORIENTATION_ERR_LEN + STATE_ECEF_VELOCITY_ERR_LEN, STATE_ECEF_ORIENTATION_ERR_LEN + STATE_ECEF_VELOCITY_ERR_LEN); - condensed_cov.topLeftCorner() = - predicted_cov.block(STATE_ECEF_ORIENTATION_ERR_START, STATE_ECEF_ORIENTATION_ERR_START); - condensed_cov.topRightCorner() = - predicted_cov.block(STATE_ECEF_ORIENTATION_ERR_START, STATE_ECEF_VELOCITY_ERR_START); - condensed_cov.bottomRightCorner() = - predicted_cov.block(STATE_ECEF_VELOCITY_ERR_START, STATE_ECEF_VELOCITY_ERR_START); - condensed_cov.bottomLeftCorner() = - predicted_cov.block(STATE_ECEF_VELOCITY_ERR_START, STATE_ECEF_ORIENTATION_ERR_START); - VectorXd H_input(device_from_ecef_eul.size() + vel_ecef.size()); - H_input << device_from_ecef_eul, vel_ecef; - MatrixXdr HH = this->kf->H(H_input); - MatrixXdr vel_device_cov = (HH * condensed_cov) * HH.transpose(); - VectorXd vel_device_std = vel_device_cov.diagonal().array().sqrt(); - - VectorXd vel_calib = this->calib_from_device * vel_device; - VectorXd vel_calib_std = rotate_cov(this->calib_from_device, vel_device_cov).diagonal().array().sqrt(); - - VectorXd orientation_ned = ned_euler_from_ecef(fix_ecef_ecef, orientation_ecef); - VectorXd orientation_ned_std = rotate_cov(this->converter->ecef2ned_matrix, orientation_ecef_cov).diagonal().array().sqrt(); - VectorXd calibrated_orientation_ned = ned_euler_from_ecef(fix_ecef_ecef, calibrated_orientation_ecef); - VectorXd nextfix_ecef = fix_ecef + vel_ecef; - VectorXd ned_vel = this->converter->ecef2ned((ECEF) { .x = nextfix_ecef(0), .y = nextfix_ecef(1), .z = nextfix_ecef(2) }).to_vector() - converter->ecef2ned(fix_ecef_ecef).to_vector(); - - VectorXd accDevice = predicted_state.segment(STATE_ACCELERATION_START); - VectorXd accDeviceErr = predicted_std.segment(STATE_ACCELERATION_ERR_START); - - VectorXd angVelocityDevice = predicted_state.segment(STATE_ANGULAR_VELOCITY_START); - VectorXd angVelocityDeviceErr = predicted_std.segment(STATE_ANGULAR_VELOCITY_ERR_START); - - Vector3d nans = Vector3d(NAN, NAN, NAN); - - // TODO fill in NED and Calibrated stds - // write measurements to msg - init_measurement(fix.initPositionGeodetic(), fix_pos_geo_vec, nans, this->gps_mode); - init_measurement(fix.initPositionECEF(), fix_ecef, fix_ecef_std, this->gps_mode); - init_measurement(fix.initVelocityECEF(), vel_ecef, vel_ecef_std, this->gps_mode); - init_measurement(fix.initVelocityNED(), ned_vel, nans, this->gps_mode); - init_measurement(fix.initVelocityDevice(), vel_device, vel_device_std, true); - init_measurement(fix.initAccelerationDevice(), accDevice, accDeviceErr, true); - init_measurement(fix.initOrientationECEF(), orientation_ecef, orientation_ecef_std, this->gps_mode); - init_measurement(fix.initCalibratedOrientationECEF(), calibrated_orientation_ecef, nans, this->calibrated && this->gps_mode); - init_measurement(fix.initOrientationNED(), orientation_ned, orientation_ned_std, this->gps_mode); - init_measurement(fix.initCalibratedOrientationNED(), calibrated_orientation_ned, nans, this->calibrated && this->gps_mode); - init_measurement(fix.initAngularVelocityDevice(), angVelocityDevice, angVelocityDeviceErr, true); - init_measurement(fix.initVelocityCalibrated(), vel_calib, vel_calib_std, this->calibrated); - init_measurement(fix.initAngularVelocityCalibrated(), ang_vel_calib, ang_vel_calib_std, this->calibrated); - init_measurement(fix.initAccelerationCalibrated(), acc_calib, acc_calib_std, this->calibrated); - if (DEBUG) { - init_measurement(fix.initFilterState(), predicted_state, predicted_std, true); - } - - double old_mean = 0.0, new_mean = 0.0; - int i = 0; - for (double x : this->posenet_stds) { - if (i < POSENET_STD_HIST_HALF) { - old_mean += x; - } else { - new_mean += x; - } - i++; - } - old_mean /= POSENET_STD_HIST_HALF; - new_mean /= POSENET_STD_HIST_HALF; - // experimentally found these values, no false positives in 20k minutes of driving - bool std_spike = (new_mean / old_mean > 4.0 && new_mean > 7.0); - - fix.setPosenetOK(!(std_spike && this->car_speed > 5.0)); - fix.setDeviceStable(!this->device_fell); - fix.setExcessiveResets(this->reset_tracker > MAX_RESET_TRACKER); - fix.setTimeToFirstFix(std::isnan(this->ttff) ? -1. : this->ttff); - this->device_fell = false; - - //fix.setGpsWeek(this->time.week); - //fix.setGpsTimeOfWeek(this->time.tow); - fix.setUnixTimestampMillis(this->unix_timestamp_millis); - - double time_since_reset = this->kf->get_filter_time() - this->last_reset_time; - fix.setTimeSinceReset(time_since_reset); - if (fix_ecef_std.norm() < VALID_POS_STD && this->calibrated && time_since_reset > VALID_TIME_SINCE_RESET) { - fix.setStatus(cereal::LiveLocationKalman::Status::VALID); - } else if (fix_ecef_std.norm() < VALID_POS_STD && time_since_reset > VALID_TIME_SINCE_RESET) { - fix.setStatus(cereal::LiveLocationKalman::Status::UNCALIBRATED); - } else { - fix.setStatus(cereal::LiveLocationKalman::Status::UNINITIALIZED); - } -} - -VectorXd Localizer::get_position_geodetic() { - VectorXd fix_ecef = this->kf->get_x().segment(STATE_ECEF_POS_START); - ECEF fix_ecef_ecef = { .x = fix_ecef(0), .y = fix_ecef(1), .z = fix_ecef(2) }; - Geodetic fix_pos_geo = ecef2geodetic(fix_ecef_ecef); - return Vector3d(fix_pos_geo.lat, fix_pos_geo.lon, fix_pos_geo.alt); -} - -VectorXd Localizer::get_state() { - return this->kf->get_x(); -} - -VectorXd Localizer::get_stdev() { - return this->kf->get_P().diagonal().array().sqrt(); -} - -bool Localizer::are_inputs_ok() { - return this->critical_services_valid(this->observation_values_invalid) && !this->observation_timings_invalid; -} - -void Localizer::observation_timings_invalid_reset(){ - this->observation_timings_invalid = false; -} - -void Localizer::handle_sensor(double current_time, const cereal::SensorEventData::Reader& log) { - // TODO does not yet account for double sensor readings in the log - - // Ignore empty readings (e.g. in case the magnetometer had no data ready) - if (log.getTimestamp() == 0) { - return; - } - - double sensor_time = 1e-9 * log.getTimestamp(); - - // sensor time and log time should be close - if (std::abs(current_time - sensor_time) > 0.1) { - LOGE("Sensor reading ignored, sensor timestamp more than 100ms off from log time"); - this->observation_timings_invalid = true; - return; - } else if (!this->is_timestamp_valid(sensor_time)) { - this->observation_timings_invalid = true; - return; - } - - // TODO: handle messages from two IMUs at the same time - if (log.getSource() == cereal::SensorEventData::SensorSource::BMX055) { - return; - } - - // Gyro Uncalibrated - if (log.getSensor() == SENSOR_GYRO_UNCALIBRATED && log.getType() == SENSOR_TYPE_GYROSCOPE_UNCALIBRATED) { - auto v = log.getGyroUncalibrated().getV(); - auto meas = Vector3d(-v[2], -v[1], -v[0]); - - VectorXd gyro_bias = this->kf->get_x().segment(STATE_GYRO_BIAS_START); - float gyro_camodo_yawrate_err = std::abs((meas[2] - gyro_bias[2]) - this->camodo_yawrate_distribution[0]); - float gyro_camodo_yawrate_err_threshold = YAWRATE_CROSS_ERR_CHECK_FACTOR * this->camodo_yawrate_distribution[1]; - bool gyro_valid = gyro_camodo_yawrate_err < gyro_camodo_yawrate_err_threshold; - - if ((meas.norm() < ROTATION_SANITY_CHECK) && gyro_valid) { - this->kf->predict_and_observe(sensor_time, OBSERVATION_PHONE_GYRO, { meas }); - this->observation_values_invalid["gyroscope"] *= DECAY; - } else { - this->observation_values_invalid["gyroscope"] += 1.0; - } - } - - // Accelerometer - if (log.getSensor() == SENSOR_ACCELEROMETER && log.getType() == SENSOR_TYPE_ACCELEROMETER) { - auto v = log.getAcceleration().getV(); - - // TODO: reduce false positives and re-enable this check - // check if device fell, estimate 10 for g - // 40m/s**2 is a good filter for falling detection, no false positives in 20k minutes of driving - // this->device_fell |= (floatlist2vector(v) - Vector3d(10.0, 0.0, 0.0)).norm() > 40.0; - - auto meas = Vector3d(-v[2], -v[1], -v[0]); - if (meas.norm() < ACCEL_SANITY_CHECK) { - this->kf->predict_and_observe(sensor_time, OBSERVATION_PHONE_ACCEL, { meas }); - this->observation_values_invalid["accelerometer"] *= DECAY; - } else { - this->observation_values_invalid["accelerometer"] += 1.0; - } - } -} - -void Localizer::input_fake_gps_observations(double current_time) { - // This is done to make sure that the error estimate of the position does not blow up - // when the filter is in no-gps mode - // Steps : first predict -> observe current obs with reasonable STD - this->kf->predict(current_time); - - VectorXd current_x = this->kf->get_x(); - VectorXd ecef_pos = current_x.segment(STATE_ECEF_POS_START); - VectorXd ecef_vel = current_x.segment(STATE_ECEF_VELOCITY_START); - const MatrixXdr &ecef_pos_R = this->kf->get_fake_gps_pos_cov(); - const MatrixXdr &ecef_vel_R = this->kf->get_fake_gps_vel_cov(); - - this->kf->predict_and_observe(current_time, OBSERVATION_ECEF_POS, { ecef_pos }, { ecef_pos_R }); - this->kf->predict_and_observe(current_time, OBSERVATION_ECEF_VEL, { ecef_vel }, { ecef_vel_R }); -} - -void Localizer::handle_gps(double current_time, const cereal::GpsLocationData::Reader& log, const double sensor_time_offset) { - // ignore the message if the fix is invalid - bool gps_invalid_flag = (log.getFlags() % 2 == 0); - bool gps_unreasonable = (Vector2d(log.getAccuracy(), log.getVerticalAccuracy()).norm() >= SANE_GPS_UNCERTAINTY); - bool gps_accuracy_insane = ((log.getVerticalAccuracy() <= 0) || (log.getSpeedAccuracy() <= 0) || (log.getBearingAccuracyDeg() <= 0)); - bool gps_lat_lng_alt_insane = ((std::abs(log.getLatitude()) > 90) || (std::abs(log.getLongitude()) > 180) || (std::abs(log.getAltitude()) > ALTITUDE_SANITY_CHECK)); - bool gps_vel_insane = (floatlist2vector(log.getVNED()).norm() > TRANS_SANITY_CHECK); - - if (gps_invalid_flag || gps_unreasonable || gps_accuracy_insane || gps_lat_lng_alt_insane || gps_vel_insane) { - //this->gps_valid = false; - this->determine_gps_mode(current_time); - return; - } - - double sensor_time = current_time - sensor_time_offset; - - // Process message - //this->gps_valid = true; - this->gps_mode = true; - Geodetic geodetic = { log.getLatitude(), log.getLongitude(), log.getAltitude() }; - this->converter = std::make_unique(geodetic); - - VectorXd ecef_pos = this->converter->ned2ecef({ 0.0, 0.0, 0.0 }).to_vector(); - VectorXd ecef_vel = this->converter->ned2ecef({ log.getVNED()[0], log.getVNED()[1], log.getVNED()[2] }).to_vector() - ecef_pos; - float ecef_pos_std = std::sqrt(this->gps_variance_factor * std::pow(log.getAccuracy(), 2) + this->gps_vertical_variance_factor * std::pow(log.getVerticalAccuracy(), 2)); - MatrixXdr ecef_pos_R = Vector3d::Constant(std::pow(this->gps_std_factor * ecef_pos_std, 2)).asDiagonal(); - MatrixXdr ecef_vel_R = Vector3d::Constant(std::pow(this->gps_std_factor * log.getSpeedAccuracy(), 2)).asDiagonal(); - - this->unix_timestamp_millis = log.getUnixTimestampMillis(); - double gps_est_error = (this->kf->get_x().segment(STATE_ECEF_POS_START) - ecef_pos).norm(); - - VectorXd orientation_ecef = quat2euler(vector2quat(this->kf->get_x().segment(STATE_ECEF_ORIENTATION_START))); - VectorXd orientation_ned = ned_euler_from_ecef({ ecef_pos(0), ecef_pos(1), ecef_pos(2) }, orientation_ecef); - VectorXd orientation_ned_gps = Vector3d(0.0, 0.0, DEG2RAD(log.getBearingDeg())); - VectorXd orientation_error = (orientation_ned - orientation_ned_gps).array() - M_PI; - for (int i = 0; i < orientation_error.size(); i++) { - orientation_error(i) = std::fmod(orientation_error(i), 2.0 * M_PI); - if (orientation_error(i) < 0.0) { - orientation_error(i) += 2.0 * M_PI; - } - orientation_error(i) -= M_PI; - } - VectorXd initial_pose_ecef_quat = quat2vector(euler2quat(ecef_euler_from_ned({ ecef_pos(0), ecef_pos(1), ecef_pos(2) }, orientation_ned_gps))); - - if (ecef_vel.norm() > 5.0 && orientation_error.norm() > 1.0) { - LOGE("Locationd vs ubloxLocation orientation difference too large, kalman reset"); - this->reset_kalman(NAN, initial_pose_ecef_quat, ecef_pos, ecef_vel, ecef_pos_R, ecef_vel_R); - this->kf->predict_and_observe(sensor_time, OBSERVATION_ECEF_ORIENTATION_FROM_GPS, { initial_pose_ecef_quat }); - } else if (gps_est_error > 100.0) { - LOGE("Locationd vs ubloxLocation position difference too large, kalman reset"); - this->reset_kalman(NAN, initial_pose_ecef_quat, ecef_pos, ecef_vel, ecef_pos_R, ecef_vel_R); - } - - this->last_gps_msg = sensor_time; - this->kf->predict_and_observe(sensor_time, OBSERVATION_ECEF_POS, { ecef_pos }, { ecef_pos_R }); - this->kf->predict_and_observe(sensor_time, OBSERVATION_ECEF_VEL, { ecef_vel }, { ecef_vel_R }); -} - -void Localizer::handle_gnss(double current_time, const cereal::GnssMeasurements::Reader& log) { - - if (!log.getPositionECEF().getValid() || !log.getVelocityECEF().getValid()) { - this->determine_gps_mode(current_time); - return; - } - - double sensor_time = log.getMeasTime() * 1e-9; - sensor_time -= this->gps_time_offset; - - auto ecef_pos_v = log.getPositionECEF().getValue(); - VectorXd ecef_pos = Vector3d(ecef_pos_v[0], ecef_pos_v[1], ecef_pos_v[2]); - - // indexed at 0 cause all std values are the same MAE - auto ecef_pos_std = log.getPositionECEF().getStd()[0]; - MatrixXdr ecef_pos_R = Vector3d::Constant(pow(this->gps_std_factor*ecef_pos_std, 2)).asDiagonal(); - - auto ecef_vel_v = log.getVelocityECEF().getValue(); - VectorXd ecef_vel = Vector3d(ecef_vel_v[0], ecef_vel_v[1], ecef_vel_v[2]); - - // indexed at 0 cause all std values are the same MAE - auto ecef_vel_std = log.getVelocityECEF().getStd()[0]; - MatrixXdr ecef_vel_R = Vector3d::Constant(pow(this->gps_std_factor*ecef_vel_std, 2)).asDiagonal(); - - double gps_est_error = (this->kf->get_x().segment(STATE_ECEF_POS_START) - ecef_pos).norm(); - - VectorXd orientation_ecef = quat2euler(vector2quat(this->kf->get_x().segment(STATE_ECEF_ORIENTATION_START))); - VectorXd orientation_ned = ned_euler_from_ecef({ ecef_pos[0], ecef_pos[1], ecef_pos[2] }, orientation_ecef); - - LocalCoord convs((ECEF){ .x = ecef_pos[0], .y = ecef_pos[1], .z = ecef_pos[2] }); - ECEF next_ecef = {.x = ecef_pos[0] + ecef_vel[0], .y = ecef_pos[1] + ecef_vel[1], .z = ecef_pos[2] + ecef_vel[2]}; - VectorXd ned_vel = convs.ecef2ned(next_ecef).to_vector(); - double bearing_rad = atan2(ned_vel[1], ned_vel[0]); - - VectorXd orientation_ned_gps = Vector3d(0.0, 0.0, bearing_rad); - VectorXd orientation_error = (orientation_ned - orientation_ned_gps).array() - M_PI; - for (int i = 0; i < orientation_error.size(); i++) { - orientation_error(i) = std::fmod(orientation_error(i), 2.0 * M_PI); - if (orientation_error(i) < 0.0) { - orientation_error(i) += 2.0 * M_PI; - } - orientation_error(i) -= M_PI; - } - VectorXd initial_pose_ecef_quat = quat2vector(euler2quat(ecef_euler_from_ned({ ecef_pos(0), ecef_pos(1), ecef_pos(2) }, orientation_ned_gps))); - - if (ecef_pos_std > GPS_POS_STD_THRESHOLD || ecef_vel_std > GPS_VEL_STD_THRESHOLD) { - this->determine_gps_mode(current_time); - return; - } - - // prevent jumping gnss measurements (covered lots, standstill...) - bool orientation_reset = ecef_vel_std < GPS_VEL_STD_RESET_THRESHOLD; - orientation_reset &= orientation_error.norm() > GPS_ORIENTATION_ERROR_RESET_THRESHOLD; - orientation_reset &= !this->standstill; - if (orientation_reset) { - this->orientation_reset_count++; - } else { - this->orientation_reset_count = 0; - } - - if ((gps_est_error > GPS_POS_ERROR_RESET_THRESHOLD && ecef_pos_std < GPS_POS_STD_RESET_THRESHOLD) || this->last_gps_msg == 0) { - // always reset on first gps message and if the location is off but the accuracy is high - LOGE("Locationd vs gnssMeasurement position difference too large, kalman reset"); - this->reset_kalman(NAN, initial_pose_ecef_quat, ecef_pos, ecef_vel, ecef_pos_R, ecef_vel_R); - } else if (orientation_reset_count > GPS_ORIENTATION_ERROR_RESET_CNT) { - LOGE("Locationd vs gnssMeasurement orientation difference too large, kalman reset"); - this->reset_kalman(NAN, initial_pose_ecef_quat, ecef_pos, ecef_vel, ecef_pos_R, ecef_vel_R); - this->kf->predict_and_observe(sensor_time, OBSERVATION_ECEF_ORIENTATION_FROM_GPS, { initial_pose_ecef_quat }); - this->orientation_reset_count = 0; - } - - this->gps_mode = true; - this->last_gps_msg = sensor_time; - this->kf->predict_and_observe(sensor_time, OBSERVATION_ECEF_POS, { ecef_pos }, { ecef_pos_R }); - this->kf->predict_and_observe(sensor_time, OBSERVATION_ECEF_VEL, { ecef_vel }, { ecef_vel_R }); -} - -void Localizer::handle_car_state(double current_time, const cereal::CarState::Reader& log) { - this->car_speed = std::abs(log.getVEgo()); - this->standstill = log.getStandstill(); - if (this->standstill) { - this->kf->predict_and_observe(current_time, OBSERVATION_NO_ROT, { Vector3d(0.0, 0.0, 0.0) }); - this->kf->predict_and_observe(current_time, OBSERVATION_NO_ACCEL, { Vector3d(0.0, 0.0, 0.0) }); - } -} - -void Localizer::handle_cam_odo(double current_time, const cereal::CameraOdometry::Reader& log) { - VectorXd rot_device = this->device_from_calib * floatlist2vector(log.getRot()); - VectorXd trans_device = this->device_from_calib * floatlist2vector(log.getTrans()); - - if (!this->is_timestamp_valid(current_time)) { - this->observation_timings_invalid = true; - return; - } - - if ((rot_device.norm() > ROTATION_SANITY_CHECK) || (trans_device.norm() > TRANS_SANITY_CHECK)) { - this->observation_values_invalid["cameraOdometry"] += 1.0; - return; - } - - VectorXd rot_calib_std = floatlist2vector(log.getRotStd()); - VectorXd trans_calib_std = floatlist2vector(log.getTransStd()); - - if ((rot_calib_std.minCoeff() <= MIN_STD_SANITY_CHECK) || (trans_calib_std.minCoeff() <= MIN_STD_SANITY_CHECK)) { - this->observation_values_invalid["cameraOdometry"] += 1.0; - return; - } - - if ((rot_calib_std.norm() > 10 * ROTATION_SANITY_CHECK) || (trans_calib_std.norm() > 10 * TRANS_SANITY_CHECK)) { - this->observation_values_invalid["cameraOdometry"] += 1.0; - return; - } - - this->posenet_stds.pop_front(); - this->posenet_stds.push_back(trans_calib_std[0]); - - // Multiply by 10 to avoid to high certainty in kalman filter because of temporally correlated noise - trans_calib_std *= 10.0; - rot_calib_std *= 10.0; - MatrixXdr rot_device_cov = rotate_std(this->device_from_calib, rot_calib_std).array().square().matrix().asDiagonal(); - MatrixXdr trans_device_cov = rotate_std(this->device_from_calib, trans_calib_std).array().square().matrix().asDiagonal(); - this->kf->predict_and_observe(current_time, OBSERVATION_CAMERA_ODO_ROTATION, - { rot_device }, { rot_device_cov }); - this->kf->predict_and_observe(current_time, OBSERVATION_CAMERA_ODO_TRANSLATION, - { trans_device }, { trans_device_cov }); - this->observation_values_invalid["cameraOdometry"] *= DECAY; - this->camodo_yawrate_distribution = Vector2d(rot_device[2], rotate_std(this->device_from_calib, rot_calib_std)[2]); -} - -void Localizer::handle_live_calib(double current_time, const cereal::LiveCalibrationData::Reader& log) { - if (!this->is_timestamp_valid(current_time)) { - this->observation_timings_invalid = true; - return; - } - - if (log.getRpyCalib().size() > 0) { - auto live_calib = floatlist2vector(log.getRpyCalib()); - if ((live_calib.minCoeff() < -CALIB_RPY_SANITY_CHECK) || (live_calib.maxCoeff() > CALIB_RPY_SANITY_CHECK)) { - this->observation_values_invalid["liveCalibration"] += 1.0; - return; - } - - this->calib = live_calib; - this->device_from_calib = euler2rot(this->calib); - this->calib_from_device = this->device_from_calib.transpose(); - this->calibrated = log.getCalStatus() == cereal::LiveCalibrationData::Status::CALIBRATED; - this->observation_values_invalid["liveCalibration"] *= DECAY; - } -} - -void Localizer::reset_kalman(double current_time) { - const VectorXd &init_x = this->kf->get_initial_x(); - const MatrixXdr &init_P = this->kf->get_initial_P(); - this->reset_kalman(current_time, init_x, init_P); -} - -void Localizer::finite_check(double current_time) { - bool all_finite = this->kf->get_x().array().isFinite().all() or this->kf->get_P().array().isFinite().all(); - if (!all_finite) { - LOGE("Non-finite values detected, kalman reset"); - this->reset_kalman(current_time); - } -} - -void Localizer::time_check(double current_time) { - if (std::isnan(this->last_reset_time)) { - this->last_reset_time = current_time; - } - if (std::isnan(this->first_valid_log_time)) { - this->first_valid_log_time = current_time; - } - double filter_time = this->kf->get_filter_time(); - bool big_time_gap = !std::isnan(filter_time) && (current_time - filter_time > 10); - if (big_time_gap) { - LOGE("Time gap of over 10s detected, kalman reset"); - this->reset_kalman(current_time); - } -} - -void Localizer::update_reset_tracker() { - // reset tracker is tuned to trigger when over 1reset/10s over 2min period - if (this->is_gps_ok()) { - this->reset_tracker *= RESET_TRACKER_DECAY; - } else { - this->reset_tracker = 0.0; - } -} - -void Localizer::reset_kalman(double current_time, const VectorXd &init_orient, const VectorXd &init_pos, const VectorXd &init_vel, const MatrixXdr &init_pos_R, const MatrixXdr &init_vel_R) { - // too nonlinear to init on completely wrong - VectorXd current_x = this->kf->get_x(); - MatrixXdr current_P = this->kf->get_P(); - MatrixXdr init_P = this->kf->get_initial_P(); - const MatrixXdr &reset_orientation_P = this->kf->get_reset_orientation_P(); - int non_ecef_state_err_len = init_P.rows() - (STATE_ECEF_POS_ERR_LEN + STATE_ECEF_ORIENTATION_ERR_LEN + STATE_ECEF_VELOCITY_ERR_LEN); - - current_x.segment(STATE_ECEF_ORIENTATION_START) = init_orient; - current_x.segment(STATE_ECEF_VELOCITY_START) = init_vel; - current_x.segment(STATE_ECEF_POS_START) = init_pos; - - init_P.block(STATE_ECEF_POS_ERR_START, STATE_ECEF_POS_ERR_START).diagonal() = init_pos_R.diagonal(); - init_P.block(STATE_ECEF_ORIENTATION_ERR_START, STATE_ECEF_ORIENTATION_ERR_START).diagonal() = reset_orientation_P.diagonal(); - init_P.block(STATE_ECEF_VELOCITY_ERR_START, STATE_ECEF_VELOCITY_ERR_START).diagonal() = init_vel_R.diagonal(); - init_P.block(STATE_ANGULAR_VELOCITY_ERR_START, STATE_ANGULAR_VELOCITY_ERR_START, non_ecef_state_err_len, non_ecef_state_err_len).diagonal() = current_P.block(STATE_ANGULAR_VELOCITY_ERR_START, - STATE_ANGULAR_VELOCITY_ERR_START, non_ecef_state_err_len, non_ecef_state_err_len).diagonal(); - - this->reset_kalman(current_time, current_x, init_P); -} - -void Localizer::reset_kalman(double current_time, const VectorXd &init_x, const MatrixXdr &init_P) { - this->kf->init_state(init_x, init_P, current_time); - this->last_reset_time = current_time; - this->reset_tracker += 1.0; -} - -void Localizer::handle_msg_bytes(const char *data, const size_t size) { - AlignedBuffer aligned_buf; - - capnp::FlatArrayMessageReader cmsg(aligned_buf.align(data, size)); - cereal::Event::Reader event = cmsg.getRoot(); - - this->handle_msg(event); -} - -void Localizer::handle_msg(const cereal::Event::Reader& log) { - double t = log.getLogMonoTime() * 1e-9; - this->time_check(t); - if (log.isAccelerometer()) { - this->handle_sensor(t, log.getAccelerometer()); - } else if (log.isGyroscope()) { - this->handle_sensor(t, log.getGyroscope()); - } else if (log.isGpsLocation()) { - this->handle_gps(t, log.getGpsLocation(), GPS_QUECTEL_SENSOR_TIME_OFFSET); - } else if (log.isGpsLocationExternal()) { - this->handle_gps(t, log.getGpsLocationExternal(), GPS_UBLOX_SENSOR_TIME_OFFSET); - //} else if (log.isGnssMeasurements()) { - // this->handle_gnss(t, log.getGnssMeasurements()); - } else if (log.isCarState()) { - this->handle_car_state(t, log.getCarState()); - } else if (log.isCameraOdometry()) { - this->handle_cam_odo(t, log.getCameraOdometry()); - } else if (log.isLiveCalibration()) { - this->handle_live_calib(t, log.getLiveCalibration()); - } - this->finite_check(); - this->update_reset_tracker(); -} - -kj::ArrayPtr Localizer::get_message_bytes(MessageBuilder& msg_builder, bool inputsOK, - bool sensorsOK, bool gpsOK, bool msgValid) { - cereal::Event::Builder evt = msg_builder.initEvent(); - evt.setValid(msgValid); - cereal::LiveLocationKalman::Builder liveLoc = evt.initLiveLocationKalman(); - this->build_live_location(liveLoc); - liveLoc.setSensorsOK(sensorsOK); - liveLoc.setGpsOK(gpsOK); - liveLoc.setInputsOK(inputsOK); - return msg_builder.toBytes(); -} - -bool Localizer::is_gps_ok() { - return (this->kf->get_filter_time() - this->last_gps_msg) < 2.0; -} - -bool Localizer::critical_services_valid(const std::map &critical_services) { - for (auto &kv : critical_services){ - if (kv.second >= INPUT_INVALID_THRESHOLD){ - return false; - } - } - return true; -} - -bool Localizer::is_timestamp_valid(double current_time) { - double filter_time = this->kf->get_filter_time(); - if (!std::isnan(filter_time) && ((filter_time - current_time) > MAX_FILTER_REWIND_TIME)) { - LOGE("Observation timestamp is older than the max rewind threshold of the filter"); - return false; - } - return true; -} - -void Localizer::determine_gps_mode(double current_time) { - // 1. If the pos_std is greater than what's not acceptable and localizer is in gps-mode, reset to no-gps-mode - // 2. If the pos_std is greater than what's not acceptable and localizer is in no-gps-mode, fake obs - // 3. If the pos_std is smaller than what's not acceptable, let gps-mode be whatever it is - VectorXd current_pos_std = this->kf->get_P().block(STATE_ECEF_POS_ERR_START, STATE_ECEF_POS_ERR_START).diagonal().array().sqrt(); - if (current_pos_std.norm() > SANE_GPS_UNCERTAINTY){ - if (this->gps_mode){ - this->gps_mode = false; - this->reset_kalman(current_time); - } else { - this->input_fake_gps_observations(current_time); - } - } -} - -void Localizer::configure_gnss_source(const LocalizerGnssSource &source) { - this->gnss_source = source; - if (source == LocalizerGnssSource::UBLOX) { - this->gps_std_factor = 10.0; - this->gps_variance_factor = 1.0; - this->gps_vertical_variance_factor = 1.0; - this->gps_time_offset = GPS_UBLOX_SENSOR_TIME_OFFSET; - } else { - this->gps_std_factor = 2.0; - this->gps_variance_factor = 0.0; - this->gps_vertical_variance_factor = 3.0; - this->gps_time_offset = GPS_QUECTEL_SENSOR_TIME_OFFSET; - } -} - -int Localizer::locationd_thread() { - Params params; - LocalizerGnssSource source; - const char* gps_location_socket; - if (params.getBool("UbloxAvailable")) { - source = LocalizerGnssSource::UBLOX; - gps_location_socket = "gpsLocationExternal"; - } else { - source = LocalizerGnssSource::QCOM; - gps_location_socket = "gpsLocation"; - } - - this->configure_gnss_source(source); - const std::initializer_list service_list = {gps_location_socket, "cameraOdometry", "liveCalibration", - "carState", "accelerometer", "gyroscope"}; - - SubMaster sm(service_list, {}, nullptr, {gps_location_socket}); - PubMaster pm({"liveLocationKalman"}); - - uint64_t cnt = 0; - bool filterInitialized = false; - const std::vector critical_input_services = {"cameraOdometry", "liveCalibration", "accelerometer", "gyroscope"}; - for (std::string service : critical_input_services) { - this->observation_values_invalid.insert({service, 0.0}); - } - - while (!do_exit) { - sm.update(); - if (filterInitialized){ - this->observation_timings_invalid_reset(); - for (const char* service : service_list) { - if (sm.updated(service) && sm.valid(service)){ - const cereal::Event::Reader log = sm[service]; - this->handle_msg(log); - } - } - } else { - filterInitialized = sm.allAliveAndValid(); - } - - const char* trigger_msg = "cameraOdometry"; - if (sm.updated(trigger_msg)) { - bool inputsOK = sm.allValid() && this->are_inputs_ok(); - bool gpsOK = this->is_gps_ok(); - bool sensorsOK = sm.allAliveAndValid({"accelerometer", "gyroscope"}); - - // Log time to first fix - if (gpsOK && std::isnan(this->ttff) && !std::isnan(this->first_valid_log_time)) { - this->ttff = std::max(1e-3, (sm[trigger_msg].getLogMonoTime() * 1e-9) - this->first_valid_log_time); - } - - MessageBuilder msg_builder; - kj::ArrayPtr bytes = this->get_message_bytes(msg_builder, inputsOK, sensorsOK, gpsOK, filterInitialized); - pm.send("liveLocationKalman", bytes.begin(), bytes.size()); - - if (cnt % 1200 == 0 && gpsOK) { // once a minute - VectorXd posGeo = this->get_position_geodetic(); - std::string lastGPSPosJSON = util::string_format( - "{\"latitude\": %.15f, \"longitude\": %.15f, \"altitude\": %.15f}", posGeo(0), posGeo(1), posGeo(2)); - params.putNonBlocking("LastGPSPosition", lastGPSPosJSON); - } - cnt++; - } - } - return 0; -} - -int main() { - util::set_realtime_priority(5); - - Localizer localizer; - return localizer.locationd_thread(); -} diff --git a/selfdrive/locationd/locationd.h b/selfdrive/locationd/locationd.h deleted file mode 100644 index 47c8bf5..0000000 --- a/selfdrive/locationd/locationd.h +++ /dev/null @@ -1,100 +0,0 @@ -#pragma once - -#include -#include -#include -#include -#include -#include - -#include "cereal/messaging/messaging.h" -#include "common/transformations/coordinates.hpp" -#include "common/transformations/orientation.hpp" -#include "common/params.h" -#include "common/swaglog.h" -#include "common/timing.h" -#include "common/util.h" - -#include "system/sensord/sensors/constants.h" -#define VISION_DECIMATION 2 -#define SENSOR_DECIMATION 10 -#include "selfdrive/locationd/models/live_kf.h" - -#define POSENET_STD_HIST_HALF 20 - -enum LocalizerGnssSource { - UBLOX, QCOM -}; - -class Localizer { -public: - Localizer(LocalizerGnssSource gnss_source = LocalizerGnssSource::UBLOX); - - int locationd_thread(); - - void reset_kalman(double current_time = NAN); - void reset_kalman(double current_time, const Eigen::VectorXd &init_orient, const Eigen::VectorXd &init_pos, const Eigen::VectorXd &init_vel, const MatrixXdr &init_pos_R, const MatrixXdr &init_vel_R); - void reset_kalman(double current_time, const Eigen::VectorXd &init_x, const MatrixXdr &init_P); - void finite_check(double current_time = NAN); - void time_check(double current_time = NAN); - void update_reset_tracker(); - bool is_gps_ok(); - bool critical_services_valid(const std::map &critical_services); - bool is_timestamp_valid(double current_time); - void determine_gps_mode(double current_time); - bool are_inputs_ok(); - void observation_timings_invalid_reset(); - - kj::ArrayPtr get_message_bytes(MessageBuilder& msg_builder, - bool inputsOK, bool sensorsOK, bool gpsOK, bool msgValid); - void build_live_location(cereal::LiveLocationKalman::Builder& fix); - - Eigen::VectorXd get_position_geodetic(); - Eigen::VectorXd get_state(); - Eigen::VectorXd get_stdev(); - - void handle_msg_bytes(const char *data, const size_t size); - void handle_msg(const cereal::Event::Reader& log); - void handle_sensor(double current_time, const cereal::SensorEventData::Reader& log); - void handle_gps(double current_time, const cereal::GpsLocationData::Reader& log, const double sensor_time_offset); - void handle_gnss(double current_time, const cereal::GnssMeasurements::Reader& log); - void handle_car_state(double current_time, const cereal::CarState::Reader& log); - void handle_cam_odo(double current_time, const cereal::CameraOdometry::Reader& log); - void handle_live_calib(double current_time, const cereal::LiveCalibrationData::Reader& log); - - void input_fake_gps_observations(double current_time); - -private: - std::unique_ptr kf; - - Eigen::VectorXd calib; - MatrixXdr device_from_calib; - MatrixXdr calib_from_device; - bool calibrated = false; - - double car_speed = 0.0; - double last_reset_time = NAN; - std::deque posenet_stds; - - std::unique_ptr converter; - - int64_t unix_timestamp_millis = 0; - double reset_tracker = 0.0; - bool device_fell = false; - bool gps_mode = false; - double first_valid_log_time = NAN; - double ttff = NAN; - double last_gps_msg = 0; - LocalizerGnssSource gnss_source; - bool observation_timings_invalid = false; - std::map observation_values_invalid; - bool standstill = true; - int32_t orientation_reset_count = 0; - float gps_std_factor; - float gps_variance_factor; - float gps_vertical_variance_factor; - double gps_time_offset; - Eigen::VectorXd camodo_yawrate_distribution = Eigen::Vector2d(0.0, 10.0); // mean, std - - void configure_gnss_source(const LocalizerGnssSource &source); -}; diff --git a/selfdrive/locationd/models/generated/car.cpp b/selfdrive/locationd/models/generated/car.cpp new file mode 100644 index 0000000..68b6df3 --- /dev/null +++ b/selfdrive/locationd/models/generated/car.cpp @@ -0,0 +1,661 @@ +#include "car.h" + +namespace { +#define DIM 9 +#define EDIM 9 +#define MEDIM 9 +typedef void (*Hfun)(double *, double *, double *); + +double mass; + +void set_mass(double x){ mass = x;} + +double rotational_inertia; + +void set_rotational_inertia(double x){ rotational_inertia = x;} + +double center_to_front; + +void set_center_to_front(double x){ center_to_front = x;} + +double center_to_rear; + +void set_center_to_rear(double x){ center_to_rear = x;} + +double stiffness_front; + +void set_stiffness_front(double x){ stiffness_front = x;} + +double stiffness_rear; + +void set_stiffness_rear(double x){ stiffness_rear = x;} +const static double MAHA_THRESH_25 = 3.8414588206941227; +const static double MAHA_THRESH_24 = 5.991464547107981; +const static double MAHA_THRESH_30 = 3.8414588206941227; +const static double MAHA_THRESH_26 = 3.8414588206941227; +const static double MAHA_THRESH_27 = 3.8414588206941227; +const static double MAHA_THRESH_29 = 3.8414588206941227; +const static double MAHA_THRESH_28 = 3.8414588206941227; +const static double MAHA_THRESH_31 = 3.8414588206941227; + +/****************************************************************************** + * Code generated with SymPy 1.12 * + * * + * See http://www.sympy.org/ for more information. * + * * + * This file is part of 'ekf' * + ******************************************************************************/ +void err_fun(double *nom_x, double *delta_x, double *out_7718808222430479447) { + out_7718808222430479447[0] = delta_x[0] + nom_x[0]; + out_7718808222430479447[1] = delta_x[1] + nom_x[1]; + out_7718808222430479447[2] = delta_x[2] + nom_x[2]; + out_7718808222430479447[3] = delta_x[3] + nom_x[3]; + out_7718808222430479447[4] = delta_x[4] + nom_x[4]; + out_7718808222430479447[5] = delta_x[5] + nom_x[5]; + out_7718808222430479447[6] = delta_x[6] + nom_x[6]; + out_7718808222430479447[7] = delta_x[7] + nom_x[7]; + out_7718808222430479447[8] = delta_x[8] + nom_x[8]; +} +void inv_err_fun(double *nom_x, double *true_x, double *out_1034114423937537934) { + out_1034114423937537934[0] = -nom_x[0] + true_x[0]; + out_1034114423937537934[1] = -nom_x[1] + true_x[1]; + out_1034114423937537934[2] = -nom_x[2] + true_x[2]; + out_1034114423937537934[3] = -nom_x[3] + true_x[3]; + out_1034114423937537934[4] = -nom_x[4] + true_x[4]; + out_1034114423937537934[5] = -nom_x[5] + true_x[5]; + out_1034114423937537934[6] = -nom_x[6] + true_x[6]; + out_1034114423937537934[7] = -nom_x[7] + true_x[7]; + out_1034114423937537934[8] = -nom_x[8] + true_x[8]; +} +void H_mod_fun(double *state, double *out_7225960904852606817) { + out_7225960904852606817[0] = 1.0; + out_7225960904852606817[1] = 0; + out_7225960904852606817[2] = 0; + out_7225960904852606817[3] = 0; + out_7225960904852606817[4] = 0; + out_7225960904852606817[5] = 0; + out_7225960904852606817[6] = 0; + out_7225960904852606817[7] = 0; + out_7225960904852606817[8] = 0; + out_7225960904852606817[9] = 0; + out_7225960904852606817[10] = 1.0; + out_7225960904852606817[11] = 0; + out_7225960904852606817[12] = 0; + out_7225960904852606817[13] = 0; + out_7225960904852606817[14] = 0; + out_7225960904852606817[15] = 0; + out_7225960904852606817[16] = 0; + out_7225960904852606817[17] = 0; + out_7225960904852606817[18] = 0; + out_7225960904852606817[19] = 0; + out_7225960904852606817[20] = 1.0; + out_7225960904852606817[21] = 0; + out_7225960904852606817[22] = 0; + out_7225960904852606817[23] = 0; + out_7225960904852606817[24] = 0; + out_7225960904852606817[25] = 0; + out_7225960904852606817[26] = 0; + out_7225960904852606817[27] = 0; + out_7225960904852606817[28] = 0; + out_7225960904852606817[29] = 0; + out_7225960904852606817[30] = 1.0; + out_7225960904852606817[31] = 0; + out_7225960904852606817[32] = 0; + out_7225960904852606817[33] = 0; + out_7225960904852606817[34] = 0; + out_7225960904852606817[35] = 0; + out_7225960904852606817[36] = 0; + out_7225960904852606817[37] = 0; + out_7225960904852606817[38] = 0; + out_7225960904852606817[39] = 0; + out_7225960904852606817[40] = 1.0; + out_7225960904852606817[41] = 0; + out_7225960904852606817[42] = 0; + out_7225960904852606817[43] = 0; + out_7225960904852606817[44] = 0; + out_7225960904852606817[45] = 0; + out_7225960904852606817[46] = 0; + out_7225960904852606817[47] = 0; + out_7225960904852606817[48] = 0; + out_7225960904852606817[49] = 0; + out_7225960904852606817[50] = 1.0; + out_7225960904852606817[51] = 0; + out_7225960904852606817[52] = 0; + out_7225960904852606817[53] = 0; + out_7225960904852606817[54] = 0; + out_7225960904852606817[55] = 0; + out_7225960904852606817[56] = 0; + out_7225960904852606817[57] = 0; + out_7225960904852606817[58] = 0; + out_7225960904852606817[59] = 0; + out_7225960904852606817[60] = 1.0; + out_7225960904852606817[61] = 0; + out_7225960904852606817[62] = 0; + out_7225960904852606817[63] = 0; + out_7225960904852606817[64] = 0; + out_7225960904852606817[65] = 0; + out_7225960904852606817[66] = 0; + out_7225960904852606817[67] = 0; + out_7225960904852606817[68] = 0; + out_7225960904852606817[69] = 0; + out_7225960904852606817[70] = 1.0; + out_7225960904852606817[71] = 0; + out_7225960904852606817[72] = 0; + out_7225960904852606817[73] = 0; + out_7225960904852606817[74] = 0; + out_7225960904852606817[75] = 0; + out_7225960904852606817[76] = 0; + out_7225960904852606817[77] = 0; + out_7225960904852606817[78] = 0; + out_7225960904852606817[79] = 0; + out_7225960904852606817[80] = 1.0; +} +void f_fun(double *state, double dt, double *out_5925834804962007644) { + out_5925834804962007644[0] = state[0]; + out_5925834804962007644[1] = state[1]; + out_5925834804962007644[2] = state[2]; + out_5925834804962007644[3] = state[3]; + out_5925834804962007644[4] = state[4]; + out_5925834804962007644[5] = dt*((-state[4] + (-center_to_front*stiffness_front*state[0] + center_to_rear*stiffness_rear*state[0])/(mass*state[4]))*state[6] - 9.8000000000000007*state[8] + stiffness_front*(-state[2] - state[3] + state[7])*state[0]/(mass*state[1]) + (-stiffness_front*state[0] - stiffness_rear*state[0])*state[5]/(mass*state[4])) + state[5]; + out_5925834804962007644[6] = dt*(center_to_front*stiffness_front*(-state[2] - state[3] + state[7])*state[0]/(rotational_inertia*state[1]) + (-center_to_front*stiffness_front*state[0] + center_to_rear*stiffness_rear*state[0])*state[5]/(rotational_inertia*state[4]) + (-pow(center_to_front, 2)*stiffness_front*state[0] - pow(center_to_rear, 2)*stiffness_rear*state[0])*state[6]/(rotational_inertia*state[4])) + state[6]; + out_5925834804962007644[7] = state[7]; + out_5925834804962007644[8] = state[8]; +} +void F_fun(double *state, double dt, double *out_1594563891292900416) { + out_1594563891292900416[0] = 1; + out_1594563891292900416[1] = 0; + out_1594563891292900416[2] = 0; + out_1594563891292900416[3] = 0; + out_1594563891292900416[4] = 0; + out_1594563891292900416[5] = 0; + out_1594563891292900416[6] = 0; + out_1594563891292900416[7] = 0; + out_1594563891292900416[8] = 0; + out_1594563891292900416[9] = 0; + out_1594563891292900416[10] = 1; + out_1594563891292900416[11] = 0; + out_1594563891292900416[12] = 0; + out_1594563891292900416[13] = 0; + out_1594563891292900416[14] = 0; + out_1594563891292900416[15] = 0; + out_1594563891292900416[16] = 0; + out_1594563891292900416[17] = 0; + out_1594563891292900416[18] = 0; + out_1594563891292900416[19] = 0; + out_1594563891292900416[20] = 1; + out_1594563891292900416[21] = 0; + out_1594563891292900416[22] = 0; + out_1594563891292900416[23] = 0; + out_1594563891292900416[24] = 0; + out_1594563891292900416[25] = 0; + out_1594563891292900416[26] = 0; + out_1594563891292900416[27] = 0; + out_1594563891292900416[28] = 0; + out_1594563891292900416[29] = 0; + out_1594563891292900416[30] = 1; + out_1594563891292900416[31] = 0; + out_1594563891292900416[32] = 0; + out_1594563891292900416[33] = 0; + out_1594563891292900416[34] = 0; + out_1594563891292900416[35] = 0; + out_1594563891292900416[36] = 0; + out_1594563891292900416[37] = 0; + out_1594563891292900416[38] = 0; + out_1594563891292900416[39] = 0; + out_1594563891292900416[40] = 1; + out_1594563891292900416[41] = 0; + out_1594563891292900416[42] = 0; + out_1594563891292900416[43] = 0; + out_1594563891292900416[44] = 0; + out_1594563891292900416[45] = dt*(stiffness_front*(-state[2] - state[3] + state[7])/(mass*state[1]) + (-stiffness_front - stiffness_rear)*state[5]/(mass*state[4]) + (-center_to_front*stiffness_front + center_to_rear*stiffness_rear)*state[6]/(mass*state[4])); + out_1594563891292900416[46] = -dt*stiffness_front*(-state[2] - state[3] + state[7])*state[0]/(mass*pow(state[1], 2)); + out_1594563891292900416[47] = -dt*stiffness_front*state[0]/(mass*state[1]); + out_1594563891292900416[48] = -dt*stiffness_front*state[0]/(mass*state[1]); + out_1594563891292900416[49] = dt*((-1 - (-center_to_front*stiffness_front*state[0] + center_to_rear*stiffness_rear*state[0])/(mass*pow(state[4], 2)))*state[6] - (-stiffness_front*state[0] - stiffness_rear*state[0])*state[5]/(mass*pow(state[4], 2))); + out_1594563891292900416[50] = dt*(-stiffness_front*state[0] - stiffness_rear*state[0])/(mass*state[4]) + 1; + out_1594563891292900416[51] = dt*(-state[4] + (-center_to_front*stiffness_front*state[0] + center_to_rear*stiffness_rear*state[0])/(mass*state[4])); + out_1594563891292900416[52] = dt*stiffness_front*state[0]/(mass*state[1]); + out_1594563891292900416[53] = -9.8000000000000007*dt; + out_1594563891292900416[54] = dt*(center_to_front*stiffness_front*(-state[2] - state[3] + state[7])/(rotational_inertia*state[1]) + (-center_to_front*stiffness_front + center_to_rear*stiffness_rear)*state[5]/(rotational_inertia*state[4]) + (-pow(center_to_front, 2)*stiffness_front - pow(center_to_rear, 2)*stiffness_rear)*state[6]/(rotational_inertia*state[4])); + out_1594563891292900416[55] = -center_to_front*dt*stiffness_front*(-state[2] - state[3] + state[7])*state[0]/(rotational_inertia*pow(state[1], 2)); + out_1594563891292900416[56] = -center_to_front*dt*stiffness_front*state[0]/(rotational_inertia*state[1]); + out_1594563891292900416[57] = -center_to_front*dt*stiffness_front*state[0]/(rotational_inertia*state[1]); + out_1594563891292900416[58] = dt*(-(-center_to_front*stiffness_front*state[0] + center_to_rear*stiffness_rear*state[0])*state[5]/(rotational_inertia*pow(state[4], 2)) - (-pow(center_to_front, 2)*stiffness_front*state[0] - pow(center_to_rear, 2)*stiffness_rear*state[0])*state[6]/(rotational_inertia*pow(state[4], 2))); + out_1594563891292900416[59] = dt*(-center_to_front*stiffness_front*state[0] + center_to_rear*stiffness_rear*state[0])/(rotational_inertia*state[4]); + out_1594563891292900416[60] = dt*(-pow(center_to_front, 2)*stiffness_front*state[0] - pow(center_to_rear, 2)*stiffness_rear*state[0])/(rotational_inertia*state[4]) + 1; + out_1594563891292900416[61] = center_to_front*dt*stiffness_front*state[0]/(rotational_inertia*state[1]); + out_1594563891292900416[62] = 0; + out_1594563891292900416[63] = 0; + out_1594563891292900416[64] = 0; + out_1594563891292900416[65] = 0; + out_1594563891292900416[66] = 0; + out_1594563891292900416[67] = 0; + out_1594563891292900416[68] = 0; + out_1594563891292900416[69] = 0; + out_1594563891292900416[70] = 1; + out_1594563891292900416[71] = 0; + out_1594563891292900416[72] = 0; + out_1594563891292900416[73] = 0; + out_1594563891292900416[74] = 0; + out_1594563891292900416[75] = 0; + out_1594563891292900416[76] = 0; + out_1594563891292900416[77] = 0; + out_1594563891292900416[78] = 0; + out_1594563891292900416[79] = 0; + out_1594563891292900416[80] = 1; +} +void h_25(double *state, double *unused, double *out_4446559038823907444) { + out_4446559038823907444[0] = state[6]; +} +void H_25(double *state, double *unused, double *out_2291888026643029333) { + out_2291888026643029333[0] = 0; + out_2291888026643029333[1] = 0; + out_2291888026643029333[2] = 0; + out_2291888026643029333[3] = 0; + out_2291888026643029333[4] = 0; + out_2291888026643029333[5] = 0; + out_2291888026643029333[6] = 1; + out_2291888026643029333[7] = 0; + out_2291888026643029333[8] = 0; +} +void h_24(double *state, double *unused, double *out_5489680431960231161) { + out_5489680431960231161[0] = state[4]; + out_5489680431960231161[1] = state[5]; +} +void H_24(double *state, double *unused, double *out_1895242722289169838) { + out_1895242722289169838[0] = 0; + out_1895242722289169838[1] = 0; + out_1895242722289169838[2] = 0; + out_1895242722289169838[3] = 0; + out_1895242722289169838[4] = 1; + out_1895242722289169838[5] = 0; + out_1895242722289169838[6] = 0; + out_1895242722289169838[7] = 0; + out_1895242722289169838[8] = 0; + out_1895242722289169838[9] = 0; + out_1895242722289169838[10] = 0; + out_1895242722289169838[11] = 0; + out_1895242722289169838[12] = 0; + out_1895242722289169838[13] = 0; + out_1895242722289169838[14] = 1; + out_1895242722289169838[15] = 0; + out_1895242722289169838[16] = 0; + out_1895242722289169838[17] = 0; +} +void h_30(double *state, double *unused, double *out_8308242515252409096) { + out_8308242515252409096[0] = state[4]; +} +void H_30(double *state, double *unused, double *out_9208578368134646088) { + out_9208578368134646088[0] = 0; + out_9208578368134646088[1] = 0; + out_9208578368134646088[2] = 0; + out_9208578368134646088[3] = 0; + out_9208578368134646088[4] = 1; + out_9208578368134646088[5] = 0; + out_9208578368134646088[6] = 0; + out_9208578368134646088[7] = 0; + out_9208578368134646088[8] = 0; +} +void h_26(double *state, double *unused, double *out_2392611761518546760) { + out_2392611761518546760[0] = state[7]; +} +void H_26(double *state, double *unused, double *out_1449615292231026891) { + out_1449615292231026891[0] = 0; + out_1449615292231026891[1] = 0; + out_1449615292231026891[2] = 0; + out_1449615292231026891[3] = 0; + out_1449615292231026891[4] = 0; + out_1449615292231026891[5] = 0; + out_1449615292231026891[6] = 0; + out_1449615292231026891[7] = 1; + out_1449615292231026891[8] = 0; +} +void h_27(double *state, double *unused, double *out_5428643132159205556) { + out_5428643132159205556[0] = state[3]; +} +void H_27(double *state, double *unused, double *out_7033815056334221177) { + out_7033815056334221177[0] = 0; + out_7033815056334221177[1] = 0; + out_7033815056334221177[2] = 0; + out_7033815056334221177[3] = 1; + out_7033815056334221177[4] = 0; + out_7033815056334221177[5] = 0; + out_7033815056334221177[6] = 0; + out_7033815056334221177[7] = 0; + out_7033815056334221177[8] = 0; +} +void h_29(double *state, double *unused, double *out_5703837194443711445) { + out_5703837194443711445[0] = state[1]; +} +void H_29(double *state, double *unused, double *out_5320452329464670144) { + out_5320452329464670144[0] = 0; + out_5320452329464670144[1] = 1; + out_5320452329464670144[2] = 0; + out_5320452329464670144[3] = 0; + out_5320452329464670144[4] = 0; + out_5320452329464670144[5] = 0; + out_5320452329464670144[6] = 0; + out_5320452329464670144[7] = 0; + out_5320452329464670144[8] = 0; +} +void h_28(double *state, double *unused, double *out_6908571236733552516) { + out_6908571236733552516[0] = state[0]; +} +void H_28(double *state, double *unused, double *out_238053312395139570) { + out_238053312395139570[0] = 1; + out_238053312395139570[1] = 0; + out_238053312395139570[2] = 0; + out_238053312395139570[3] = 0; + out_238053312395139570[4] = 0; + out_238053312395139570[5] = 0; + out_238053312395139570[6] = 0; + out_238053312395139570[7] = 0; + out_238053312395139570[8] = 0; +} +void h_31(double *state, double *unused, double *out_3210479663755662439) { + out_3210479663755662439[0] = state[8]; +} +void H_31(double *state, double *unused, double *out_2322533988519989761) { + out_2322533988519989761[0] = 0; + out_2322533988519989761[1] = 0; + out_2322533988519989761[2] = 0; + out_2322533988519989761[3] = 0; + out_2322533988519989761[4] = 0; + out_2322533988519989761[5] = 0; + out_2322533988519989761[6] = 0; + out_2322533988519989761[7] = 0; + out_2322533988519989761[8] = 1; +} +#include +#include + +typedef Eigen::Matrix DDM; +typedef Eigen::Matrix EEM; +typedef Eigen::Matrix DEM; + +void predict(double *in_x, double *in_P, double *in_Q, double dt) { + typedef Eigen::Matrix RRM; + + double nx[DIM] = {0}; + double in_F[EDIM*EDIM] = {0}; + + // functions from sympy + f_fun(in_x, dt, nx); + F_fun(in_x, dt, in_F); + + + EEM F(in_F); + EEM P(in_P); + EEM Q(in_Q); + + RRM F_main = F.topLeftCorner(MEDIM, MEDIM); + P.topLeftCorner(MEDIM, MEDIM) = (F_main * P.topLeftCorner(MEDIM, MEDIM)) * F_main.transpose(); + P.topRightCorner(MEDIM, EDIM - MEDIM) = F_main * P.topRightCorner(MEDIM, EDIM - MEDIM); + P.bottomLeftCorner(EDIM - MEDIM, MEDIM) = P.bottomLeftCorner(EDIM - MEDIM, MEDIM) * F_main.transpose(); + + P = P + dt*Q; + + // copy out state + memcpy(in_x, nx, DIM * sizeof(double)); + memcpy(in_P, P.data(), EDIM * EDIM * sizeof(double)); +} + +// note: extra_args dim only correct when null space projecting +// otherwise 1 +template +void update(double *in_x, double *in_P, Hfun h_fun, Hfun H_fun, Hfun Hea_fun, double *in_z, double *in_R, double *in_ea, double MAHA_THRESHOLD) { + typedef Eigen::Matrix ZZM; + typedef Eigen::Matrix ZDM; + typedef Eigen::Matrix XEM; + //typedef Eigen::Matrix EZM; + typedef Eigen::Matrix X1M; + typedef Eigen::Matrix XXM; + + double in_hx[ZDIM] = {0}; + double in_H[ZDIM * DIM] = {0}; + double in_H_mod[EDIM * DIM] = {0}; + double delta_x[EDIM] = {0}; + double x_new[DIM] = {0}; + + + // state x, P + Eigen::Matrix z(in_z); + EEM P(in_P); + ZZM pre_R(in_R); + + // functions from sympy + h_fun(in_x, in_ea, in_hx); + H_fun(in_x, in_ea, in_H); + ZDM pre_H(in_H); + + // get y (y = z - hx) + Eigen::Matrix pre_y(in_hx); pre_y = z - pre_y; + X1M y; XXM H; XXM R; + if (Hea_fun){ + typedef Eigen::Matrix ZAM; + double in_Hea[ZDIM * EADIM] = {0}; + Hea_fun(in_x, in_ea, in_Hea); + ZAM Hea(in_Hea); + XXM A = Hea.transpose().fullPivLu().kernel(); + + + y = A.transpose() * pre_y; + H = A.transpose() * pre_H; + R = A.transpose() * pre_R * A; + } else { + y = pre_y; + H = pre_H; + R = pre_R; + } + // get modified H + H_mod_fun(in_x, in_H_mod); + DEM H_mod(in_H_mod); + XEM H_err = H * H_mod; + + // Do mahalobis distance test + if (MAHA_TEST){ + XXM a = (H_err * P * H_err.transpose() + R).inverse(); + double maha_dist = y.transpose() * a * y; + if (maha_dist > MAHA_THRESHOLD){ + R = 1.0e16 * R; + } + } + + // Outlier resilient weighting + double weight = 1;//(1.5)/(1 + y.squaredNorm()/R.sum()); + + // kalman gains and I_KH + XXM S = ((H_err * P) * H_err.transpose()) + R/weight; + XEM KT = S.fullPivLu().solve(H_err * P.transpose()); + //EZM K = KT.transpose(); TODO: WHY DOES THIS NOT COMPILE? + //EZM K = S.fullPivLu().solve(H_err * P.transpose()).transpose(); + //std::cout << "Here is the matrix rot:\n" << K << std::endl; + EEM I_KH = Eigen::Matrix::Identity() - (KT.transpose() * H_err); + + // update state by injecting dx + Eigen::Matrix dx(delta_x); + dx = (KT.transpose() * y); + memcpy(delta_x, dx.data(), EDIM * sizeof(double)); + err_fun(in_x, delta_x, x_new); + Eigen::Matrix x(x_new); + + // update cov + P = ((I_KH * P) * I_KH.transpose()) + ((KT.transpose() * R) * KT); + + // copy out state + memcpy(in_x, x.data(), DIM * sizeof(double)); + memcpy(in_P, P.data(), EDIM * EDIM * sizeof(double)); + memcpy(in_z, y.data(), y.rows() * sizeof(double)); +} + + + + +} +extern "C" { + +void car_update_25(double *in_x, double *in_P, double *in_z, double *in_R, double *in_ea) { + update<1, 3, 0>(in_x, in_P, h_25, H_25, NULL, in_z, in_R, in_ea, MAHA_THRESH_25); +} +void car_update_24(double *in_x, double *in_P, double *in_z, double *in_R, double *in_ea) { + update<2, 3, 0>(in_x, in_P, h_24, H_24, NULL, in_z, in_R, in_ea, MAHA_THRESH_24); +} +void car_update_30(double *in_x, double *in_P, double *in_z, double *in_R, double *in_ea) { + update<1, 3, 0>(in_x, in_P, h_30, H_30, NULL, in_z, in_R, in_ea, MAHA_THRESH_30); +} +void car_update_26(double *in_x, double *in_P, double *in_z, double *in_R, double *in_ea) { + update<1, 3, 0>(in_x, in_P, h_26, H_26, NULL, in_z, in_R, in_ea, MAHA_THRESH_26); +} +void car_update_27(double *in_x, double *in_P, double *in_z, double *in_R, double *in_ea) { + update<1, 3, 0>(in_x, in_P, h_27, H_27, NULL, in_z, in_R, in_ea, MAHA_THRESH_27); +} +void car_update_29(double *in_x, double *in_P, double *in_z, double *in_R, double *in_ea) { + update<1, 3, 0>(in_x, in_P, h_29, H_29, NULL, in_z, in_R, in_ea, MAHA_THRESH_29); +} +void car_update_28(double *in_x, double *in_P, double *in_z, double *in_R, double *in_ea) { + update<1, 3, 0>(in_x, in_P, h_28, H_28, NULL, in_z, in_R, in_ea, MAHA_THRESH_28); +} +void car_update_31(double *in_x, double *in_P, double *in_z, double *in_R, double *in_ea) { + update<1, 3, 0>(in_x, in_P, h_31, H_31, NULL, in_z, in_R, in_ea, MAHA_THRESH_31); +} +void car_err_fun(double *nom_x, double *delta_x, double *out_7718808222430479447) { + err_fun(nom_x, delta_x, out_7718808222430479447); +} +void car_inv_err_fun(double *nom_x, double *true_x, double *out_1034114423937537934) { + inv_err_fun(nom_x, true_x, out_1034114423937537934); +} +void car_H_mod_fun(double *state, double *out_7225960904852606817) { + H_mod_fun(state, out_7225960904852606817); +} +void car_f_fun(double *state, double dt, double *out_5925834804962007644) { + f_fun(state, dt, out_5925834804962007644); +} +void car_F_fun(double *state, double dt, double *out_1594563891292900416) { + F_fun(state, dt, out_1594563891292900416); +} +void car_h_25(double *state, double *unused, double *out_4446559038823907444) { + h_25(state, unused, out_4446559038823907444); +} +void car_H_25(double *state, double *unused, double *out_2291888026643029333) { + H_25(state, unused, out_2291888026643029333); +} +void car_h_24(double *state, double *unused, double *out_5489680431960231161) { + h_24(state, unused, out_5489680431960231161); +} +void car_H_24(double *state, double *unused, double *out_1895242722289169838) { + H_24(state, unused, out_1895242722289169838); +} +void car_h_30(double *state, double *unused, double *out_8308242515252409096) { + h_30(state, unused, out_8308242515252409096); +} +void car_H_30(double *state, double *unused, double *out_9208578368134646088) { + H_30(state, unused, out_9208578368134646088); +} +void car_h_26(double *state, double *unused, double *out_2392611761518546760) { + h_26(state, unused, out_2392611761518546760); +} +void car_H_26(double *state, double *unused, double *out_1449615292231026891) { + H_26(state, unused, out_1449615292231026891); +} +void car_h_27(double *state, double *unused, double *out_5428643132159205556) { + h_27(state, unused, out_5428643132159205556); +} +void car_H_27(double *state, double *unused, double *out_7033815056334221177) { + H_27(state, unused, out_7033815056334221177); +} +void car_h_29(double *state, double *unused, double *out_5703837194443711445) { + h_29(state, unused, out_5703837194443711445); +} +void car_H_29(double *state, double *unused, double *out_5320452329464670144) { + H_29(state, unused, out_5320452329464670144); +} +void car_h_28(double *state, double *unused, double *out_6908571236733552516) { + h_28(state, unused, out_6908571236733552516); +} +void car_H_28(double *state, double *unused, double *out_238053312395139570) { + H_28(state, unused, out_238053312395139570); +} +void car_h_31(double *state, double *unused, double *out_3210479663755662439) { + h_31(state, unused, out_3210479663755662439); +} +void car_H_31(double *state, double *unused, double *out_2322533988519989761) { + H_31(state, unused, out_2322533988519989761); +} +void car_predict(double *in_x, double *in_P, double *in_Q, double dt) { + predict(in_x, in_P, in_Q, dt); +} +void car_set_mass(double x) { + set_mass(x); +} +void car_set_rotational_inertia(double x) { + set_rotational_inertia(x); +} +void car_set_center_to_front(double x) { + set_center_to_front(x); +} +void car_set_center_to_rear(double x) { + set_center_to_rear(x); +} +void car_set_stiffness_front(double x) { + set_stiffness_front(x); +} +void car_set_stiffness_rear(double x) { + set_stiffness_rear(x); +} +} + +const EKF car = { + .name = "car", + .kinds = { 25, 24, 30, 26, 27, 29, 28, 31 }, + .feature_kinds = { }, + .f_fun = car_f_fun, + .F_fun = car_F_fun, + .err_fun = car_err_fun, + .inv_err_fun = car_inv_err_fun, + .H_mod_fun = car_H_mod_fun, + .predict = car_predict, + .hs = { + { 25, car_h_25 }, + { 24, car_h_24 }, + { 30, car_h_30 }, + { 26, car_h_26 }, + { 27, car_h_27 }, + { 29, car_h_29 }, + { 28, car_h_28 }, + { 31, car_h_31 }, + }, + .Hs = { + { 25, car_H_25 }, + { 24, car_H_24 }, + { 30, car_H_30 }, + { 26, car_H_26 }, + { 27, car_H_27 }, + { 29, car_H_29 }, + { 28, car_H_28 }, + { 31, car_H_31 }, + }, + .updates = { + { 25, car_update_25 }, + { 24, car_update_24 }, + { 30, car_update_30 }, + { 26, car_update_26 }, + { 27, car_update_27 }, + { 29, car_update_29 }, + { 28, car_update_28 }, + { 31, car_update_31 }, + }, + .Hes = { + }, + .sets = { + { "mass", car_set_mass }, + { "rotational_inertia", car_set_rotational_inertia }, + { "center_to_front", car_set_center_to_front }, + { "center_to_rear", car_set_center_to_rear }, + { "stiffness_front", car_set_stiffness_front }, + { "stiffness_rear", car_set_stiffness_rear }, + }, + .extra_routines = { + }, +}; + +ekf_lib_init(car) diff --git a/selfdrive/locationd/models/generated/libcar.so b/selfdrive/locationd/models/generated/libcar.so new file mode 100755 index 0000000..0f65107 Binary files /dev/null and b/selfdrive/locationd/models/generated/libcar.so differ diff --git a/selfdrive/locationd/models/generated/liblive.so b/selfdrive/locationd/models/generated/liblive.so new file mode 100755 index 0000000..1d02431 Binary files /dev/null and b/selfdrive/locationd/models/generated/liblive.so differ diff --git a/selfdrive/locationd/models/generated/live.cpp b/selfdrive/locationd/models/generated/live.cpp new file mode 100644 index 0000000..06ba1bb --- /dev/null +++ b/selfdrive/locationd/models/generated/live.cpp @@ -0,0 +1,1987 @@ +#include "live.h" + +namespace { +#define DIM 22 +#define EDIM 21 +#define MEDIM 21 +typedef void (*Hfun)(double *, double *, double *); +const static double MAHA_THRESH_4 = 7.814727903251177; +const static double MAHA_THRESH_9 = 7.814727903251177; +const static double MAHA_THRESH_10 = 7.814727903251177; +const static double MAHA_THRESH_12 = 7.814727903251177; +const static double MAHA_THRESH_35 = 7.814727903251177; +const static double MAHA_THRESH_32 = 9.487729036781154; +const static double MAHA_THRESH_13 = 7.814727903251177; +const static double MAHA_THRESH_14 = 7.814727903251177; +const static double MAHA_THRESH_33 = 7.814727903251177; + +/****************************************************************************** + * Code generated with SymPy 1.12 * + * * + * See http://www.sympy.org/ for more information. * + * * + * This file is part of 'ekf' * + ******************************************************************************/ +void H(double *in_vec, double *out_3655759921532451903) { + out_3655759921532451903[0] = 0; + out_3655759921532451903[1] = -sin(in_vec[1])*sin(in_vec[2])*in_vec[4] - sin(in_vec[1])*cos(in_vec[2])*in_vec[3] - cos(in_vec[1])*in_vec[5]; + out_3655759921532451903[2] = -sin(in_vec[2])*cos(in_vec[1])*in_vec[3] + cos(in_vec[1])*cos(in_vec[2])*in_vec[4]; + out_3655759921532451903[3] = cos(in_vec[1])*cos(in_vec[2]); + out_3655759921532451903[4] = sin(in_vec[2])*cos(in_vec[1]); + out_3655759921532451903[5] = -sin(in_vec[1]); + out_3655759921532451903[6] = (sin(in_vec[0])*sin(in_vec[2]) + sin(in_vec[1])*cos(in_vec[0])*cos(in_vec[2]))*in_vec[3] + (-sin(in_vec[0])*cos(in_vec[2]) + sin(in_vec[1])*sin(in_vec[2])*cos(in_vec[0]))*in_vec[4] + cos(in_vec[0])*cos(in_vec[1])*in_vec[5]; + out_3655759921532451903[7] = -sin(in_vec[0])*sin(in_vec[1])*in_vec[5] + sin(in_vec[0])*sin(in_vec[2])*cos(in_vec[1])*in_vec[4] + sin(in_vec[0])*cos(in_vec[1])*cos(in_vec[2])*in_vec[3]; + out_3655759921532451903[8] = (-sin(in_vec[0])*sin(in_vec[1])*sin(in_vec[2]) - cos(in_vec[0])*cos(in_vec[2]))*in_vec[3] + (sin(in_vec[0])*sin(in_vec[1])*cos(in_vec[2]) - sin(in_vec[2])*cos(in_vec[0]))*in_vec[4]; + out_3655759921532451903[9] = sin(in_vec[0])*sin(in_vec[1])*cos(in_vec[2]) - sin(in_vec[2])*cos(in_vec[0]); + out_3655759921532451903[10] = sin(in_vec[0])*sin(in_vec[1])*sin(in_vec[2]) + cos(in_vec[0])*cos(in_vec[2]); + out_3655759921532451903[11] = sin(in_vec[0])*cos(in_vec[1]); + out_3655759921532451903[12] = (-sin(in_vec[0])*sin(in_vec[1])*sin(in_vec[2]) - cos(in_vec[0])*cos(in_vec[2]))*in_vec[4] + (-sin(in_vec[0])*sin(in_vec[1])*cos(in_vec[2]) + sin(in_vec[2])*cos(in_vec[0]))*in_vec[3] - sin(in_vec[0])*cos(in_vec[1])*in_vec[5]; + out_3655759921532451903[13] = -sin(in_vec[1])*cos(in_vec[0])*in_vec[5] + sin(in_vec[2])*cos(in_vec[0])*cos(in_vec[1])*in_vec[4] + cos(in_vec[0])*cos(in_vec[1])*cos(in_vec[2])*in_vec[3]; + out_3655759921532451903[14] = (sin(in_vec[0])*sin(in_vec[2]) + sin(in_vec[1])*cos(in_vec[0])*cos(in_vec[2]))*in_vec[4] + (sin(in_vec[0])*cos(in_vec[2]) - sin(in_vec[1])*sin(in_vec[2])*cos(in_vec[0]))*in_vec[3]; + out_3655759921532451903[15] = sin(in_vec[0])*sin(in_vec[2]) + sin(in_vec[1])*cos(in_vec[0])*cos(in_vec[2]); + out_3655759921532451903[16] = -sin(in_vec[0])*cos(in_vec[2]) + sin(in_vec[1])*sin(in_vec[2])*cos(in_vec[0]); + out_3655759921532451903[17] = cos(in_vec[0])*cos(in_vec[1]); +} +void err_fun(double *nom_x, double *delta_x, double *out_6606438496319011893) { + out_6606438496319011893[0] = delta_x[0] + nom_x[0]; + out_6606438496319011893[1] = delta_x[1] + nom_x[1]; + out_6606438496319011893[2] = delta_x[2] + nom_x[2]; + out_6606438496319011893[3] = -0.5*delta_x[3]*nom_x[4] - 0.5*delta_x[4]*nom_x[5] - 0.5*delta_x[5]*nom_x[6] + 1.0*nom_x[3]; + out_6606438496319011893[4] = 0.5*delta_x[3]*nom_x[3] + 0.5*delta_x[4]*nom_x[6] - 0.5*delta_x[5]*nom_x[5] + 1.0*nom_x[4]; + out_6606438496319011893[5] = -0.5*delta_x[3]*nom_x[6] + 0.5*delta_x[4]*nom_x[3] + 0.5*delta_x[5]*nom_x[4] + 1.0*nom_x[5]; + out_6606438496319011893[6] = 0.5*delta_x[3]*nom_x[5] - 0.5*delta_x[4]*nom_x[4] + 0.5*delta_x[5]*nom_x[3] + 1.0*nom_x[6]; + out_6606438496319011893[7] = delta_x[6] + nom_x[7]; + out_6606438496319011893[8] = delta_x[7] + nom_x[8]; + out_6606438496319011893[9] = delta_x[8] + nom_x[9]; + out_6606438496319011893[10] = delta_x[9] + nom_x[10]; + out_6606438496319011893[11] = delta_x[10] + nom_x[11]; + out_6606438496319011893[12] = delta_x[11] + nom_x[12]; + out_6606438496319011893[13] = delta_x[12] + nom_x[13]; + out_6606438496319011893[14] = delta_x[13] + nom_x[14]; + out_6606438496319011893[15] = delta_x[14] + nom_x[15]; + out_6606438496319011893[16] = delta_x[15] + nom_x[16]; + out_6606438496319011893[17] = delta_x[16] + nom_x[17]; + out_6606438496319011893[18] = delta_x[17] + nom_x[18]; + out_6606438496319011893[19] = delta_x[18] + nom_x[19]; + out_6606438496319011893[20] = delta_x[19] + nom_x[20]; + out_6606438496319011893[21] = delta_x[20] + nom_x[21]; +} +void inv_err_fun(double *nom_x, double *true_x, double *out_1892773414432101423) { + out_1892773414432101423[0] = -nom_x[0] + true_x[0]; + out_1892773414432101423[1] = -nom_x[1] + true_x[1]; + out_1892773414432101423[2] = -nom_x[2] + true_x[2]; + out_1892773414432101423[3] = 2*nom_x[3]*true_x[4] - 2*nom_x[4]*true_x[3] + 2*nom_x[5]*true_x[6] - 2*nom_x[6]*true_x[5]; + out_1892773414432101423[4] = 2*nom_x[3]*true_x[5] - 2*nom_x[4]*true_x[6] - 2*nom_x[5]*true_x[3] + 2*nom_x[6]*true_x[4]; + out_1892773414432101423[5] = 2*nom_x[3]*true_x[6] + 2*nom_x[4]*true_x[5] - 2*nom_x[5]*true_x[4] - 2*nom_x[6]*true_x[3]; + out_1892773414432101423[6] = -nom_x[7] + true_x[7]; + out_1892773414432101423[7] = -nom_x[8] + true_x[8]; + out_1892773414432101423[8] = -nom_x[9] + true_x[9]; + out_1892773414432101423[9] = -nom_x[10] + true_x[10]; + out_1892773414432101423[10] = -nom_x[11] + true_x[11]; + out_1892773414432101423[11] = -nom_x[12] + true_x[12]; + out_1892773414432101423[12] = -nom_x[13] + true_x[13]; + out_1892773414432101423[13] = -nom_x[14] + true_x[14]; + out_1892773414432101423[14] = -nom_x[15] + true_x[15]; + out_1892773414432101423[15] = -nom_x[16] + true_x[16]; + out_1892773414432101423[16] = -nom_x[17] + true_x[17]; + out_1892773414432101423[17] = -nom_x[18] + true_x[18]; + out_1892773414432101423[18] = -nom_x[19] + true_x[19]; + out_1892773414432101423[19] = -nom_x[20] + true_x[20]; + out_1892773414432101423[20] = -nom_x[21] + true_x[21]; +} +void H_mod_fun(double *state, double *out_31505903139368806) { + out_31505903139368806[0] = 1.0; + out_31505903139368806[1] = 0; + out_31505903139368806[2] = 0; + out_31505903139368806[3] = 0; + out_31505903139368806[4] = 0; + out_31505903139368806[5] = 0; + out_31505903139368806[6] = 0; + out_31505903139368806[7] = 0; + out_31505903139368806[8] = 0; + out_31505903139368806[9] = 0; + out_31505903139368806[10] = 0; + out_31505903139368806[11] = 0; + out_31505903139368806[12] = 0; + out_31505903139368806[13] = 0; + out_31505903139368806[14] = 0; + out_31505903139368806[15] = 0; + out_31505903139368806[16] = 0; + out_31505903139368806[17] = 0; + out_31505903139368806[18] = 0; + out_31505903139368806[19] = 0; + out_31505903139368806[20] = 0; + out_31505903139368806[21] = 0; + out_31505903139368806[22] = 1.0; + out_31505903139368806[23] = 0; + out_31505903139368806[24] = 0; + out_31505903139368806[25] = 0; + out_31505903139368806[26] = 0; + out_31505903139368806[27] = 0; + out_31505903139368806[28] = 0; + out_31505903139368806[29] = 0; + out_31505903139368806[30] = 0; + out_31505903139368806[31] = 0; + out_31505903139368806[32] = 0; + out_31505903139368806[33] = 0; + out_31505903139368806[34] = 0; + out_31505903139368806[35] = 0; + out_31505903139368806[36] = 0; + out_31505903139368806[37] = 0; + out_31505903139368806[38] = 0; + out_31505903139368806[39] = 0; + out_31505903139368806[40] = 0; + out_31505903139368806[41] = 0; + out_31505903139368806[42] = 0; + out_31505903139368806[43] = 0; + out_31505903139368806[44] = 1.0; + out_31505903139368806[45] = 0; + out_31505903139368806[46] = 0; + out_31505903139368806[47] = 0; + out_31505903139368806[48] = 0; + out_31505903139368806[49] = 0; + out_31505903139368806[50] = 0; + out_31505903139368806[51] = 0; + out_31505903139368806[52] = 0; + out_31505903139368806[53] = 0; + out_31505903139368806[54] = 0; + out_31505903139368806[55] = 0; + out_31505903139368806[56] = 0; + out_31505903139368806[57] = 0; + out_31505903139368806[58] = 0; + out_31505903139368806[59] = 0; + out_31505903139368806[60] = 0; + out_31505903139368806[61] = 0; + out_31505903139368806[62] = 0; + out_31505903139368806[63] = 0; + out_31505903139368806[64] = 0; + out_31505903139368806[65] = 0; + out_31505903139368806[66] = -0.5*state[4]; + out_31505903139368806[67] = -0.5*state[5]; + out_31505903139368806[68] = -0.5*state[6]; + out_31505903139368806[69] = 0; + out_31505903139368806[70] = 0; + out_31505903139368806[71] = 0; + out_31505903139368806[72] = 0; + out_31505903139368806[73] = 0; + out_31505903139368806[74] = 0; + out_31505903139368806[75] = 0; + out_31505903139368806[76] = 0; + out_31505903139368806[77] = 0; + out_31505903139368806[78] = 0; + out_31505903139368806[79] = 0; + out_31505903139368806[80] = 0; + out_31505903139368806[81] = 0; + out_31505903139368806[82] = 0; + out_31505903139368806[83] = 0; + out_31505903139368806[84] = 0; + out_31505903139368806[85] = 0; + out_31505903139368806[86] = 0; + out_31505903139368806[87] = 0.5*state[3]; + out_31505903139368806[88] = 0.5*state[6]; + out_31505903139368806[89] = -0.5*state[5]; + out_31505903139368806[90] = 0; + out_31505903139368806[91] = 0; + out_31505903139368806[92] = 0; + out_31505903139368806[93] = 0; + out_31505903139368806[94] = 0; + out_31505903139368806[95] = 0; + out_31505903139368806[96] = 0; + out_31505903139368806[97] = 0; + out_31505903139368806[98] = 0; + out_31505903139368806[99] = 0; + out_31505903139368806[100] = 0; + out_31505903139368806[101] = 0; + out_31505903139368806[102] = 0; + out_31505903139368806[103] = 0; + out_31505903139368806[104] = 0; + out_31505903139368806[105] = 0; + out_31505903139368806[106] = 0; + out_31505903139368806[107] = 0; + out_31505903139368806[108] = -0.5*state[6]; + out_31505903139368806[109] = 0.5*state[3]; + out_31505903139368806[110] = 0.5*state[4]; + out_31505903139368806[111] = 0; + out_31505903139368806[112] = 0; + out_31505903139368806[113] = 0; + out_31505903139368806[114] = 0; + out_31505903139368806[115] = 0; + out_31505903139368806[116] = 0; + out_31505903139368806[117] = 0; + out_31505903139368806[118] = 0; + out_31505903139368806[119] = 0; + out_31505903139368806[120] = 0; + out_31505903139368806[121] = 0; + out_31505903139368806[122] = 0; + out_31505903139368806[123] = 0; + out_31505903139368806[124] = 0; + out_31505903139368806[125] = 0; + out_31505903139368806[126] = 0; + out_31505903139368806[127] = 0; + out_31505903139368806[128] = 0; + out_31505903139368806[129] = 0.5*state[5]; + out_31505903139368806[130] = -0.5*state[4]; + out_31505903139368806[131] = 0.5*state[3]; + out_31505903139368806[132] = 0; + out_31505903139368806[133] = 0; + out_31505903139368806[134] = 0; + out_31505903139368806[135] = 0; + out_31505903139368806[136] = 0; + out_31505903139368806[137] = 0; + out_31505903139368806[138] = 0; + out_31505903139368806[139] = 0; + out_31505903139368806[140] = 0; + out_31505903139368806[141] = 0; + out_31505903139368806[142] = 0; + out_31505903139368806[143] = 0; + out_31505903139368806[144] = 0; + out_31505903139368806[145] = 0; + out_31505903139368806[146] = 0; + out_31505903139368806[147] = 0; + out_31505903139368806[148] = 0; + out_31505903139368806[149] = 0; + out_31505903139368806[150] = 0; + out_31505903139368806[151] = 0; + out_31505903139368806[152] = 0; + out_31505903139368806[153] = 1.0; + out_31505903139368806[154] = 0; + out_31505903139368806[155] = 0; + out_31505903139368806[156] = 0; + out_31505903139368806[157] = 0; + out_31505903139368806[158] = 0; + out_31505903139368806[159] = 0; + out_31505903139368806[160] = 0; + out_31505903139368806[161] = 0; + out_31505903139368806[162] = 0; + out_31505903139368806[163] = 0; + out_31505903139368806[164] = 0; + out_31505903139368806[165] = 0; + out_31505903139368806[166] = 0; + out_31505903139368806[167] = 0; + out_31505903139368806[168] = 0; + out_31505903139368806[169] = 0; + out_31505903139368806[170] = 0; + out_31505903139368806[171] = 0; + out_31505903139368806[172] = 0; + out_31505903139368806[173] = 0; + out_31505903139368806[174] = 0; + out_31505903139368806[175] = 1.0; + out_31505903139368806[176] = 0; + out_31505903139368806[177] = 0; + out_31505903139368806[178] = 0; + out_31505903139368806[179] = 0; + out_31505903139368806[180] = 0; + out_31505903139368806[181] = 0; + out_31505903139368806[182] = 0; + out_31505903139368806[183] = 0; + out_31505903139368806[184] = 0; + out_31505903139368806[185] = 0; + out_31505903139368806[186] = 0; + out_31505903139368806[187] = 0; + out_31505903139368806[188] = 0; + out_31505903139368806[189] = 0; + out_31505903139368806[190] = 0; + out_31505903139368806[191] = 0; + out_31505903139368806[192] = 0; + out_31505903139368806[193] = 0; + out_31505903139368806[194] = 0; + out_31505903139368806[195] = 0; + out_31505903139368806[196] = 0; + out_31505903139368806[197] = 1.0; + out_31505903139368806[198] = 0; + out_31505903139368806[199] = 0; + out_31505903139368806[200] = 0; + out_31505903139368806[201] = 0; + out_31505903139368806[202] = 0; + out_31505903139368806[203] = 0; + out_31505903139368806[204] = 0; + out_31505903139368806[205] = 0; + out_31505903139368806[206] = 0; + out_31505903139368806[207] = 0; + out_31505903139368806[208] = 0; + out_31505903139368806[209] = 0; + out_31505903139368806[210] = 0; + out_31505903139368806[211] = 0; + out_31505903139368806[212] = 0; + out_31505903139368806[213] = 0; + out_31505903139368806[214] = 0; + out_31505903139368806[215] = 0; + out_31505903139368806[216] = 0; + out_31505903139368806[217] = 0; + out_31505903139368806[218] = 0; + out_31505903139368806[219] = 1.0; + out_31505903139368806[220] = 0; + out_31505903139368806[221] = 0; + out_31505903139368806[222] = 0; + out_31505903139368806[223] = 0; + out_31505903139368806[224] = 0; + out_31505903139368806[225] = 0; + out_31505903139368806[226] = 0; + out_31505903139368806[227] = 0; + out_31505903139368806[228] = 0; + out_31505903139368806[229] = 0; + out_31505903139368806[230] = 0; + out_31505903139368806[231] = 0; + out_31505903139368806[232] = 0; + out_31505903139368806[233] = 0; + out_31505903139368806[234] = 0; + out_31505903139368806[235] = 0; + out_31505903139368806[236] = 0; + out_31505903139368806[237] = 0; + out_31505903139368806[238] = 0; + out_31505903139368806[239] = 0; + out_31505903139368806[240] = 0; + out_31505903139368806[241] = 1.0; + out_31505903139368806[242] = 0; + out_31505903139368806[243] = 0; + out_31505903139368806[244] = 0; + out_31505903139368806[245] = 0; + out_31505903139368806[246] = 0; + out_31505903139368806[247] = 0; + out_31505903139368806[248] = 0; + out_31505903139368806[249] = 0; + out_31505903139368806[250] = 0; + out_31505903139368806[251] = 0; + out_31505903139368806[252] = 0; + out_31505903139368806[253] = 0; + out_31505903139368806[254] = 0; + out_31505903139368806[255] = 0; + out_31505903139368806[256] = 0; + out_31505903139368806[257] = 0; + out_31505903139368806[258] = 0; + out_31505903139368806[259] = 0; + out_31505903139368806[260] = 0; + out_31505903139368806[261] = 0; + out_31505903139368806[262] = 0; + out_31505903139368806[263] = 1.0; + out_31505903139368806[264] = 0; + out_31505903139368806[265] = 0; + out_31505903139368806[266] = 0; + out_31505903139368806[267] = 0; + out_31505903139368806[268] = 0; + out_31505903139368806[269] = 0; + out_31505903139368806[270] = 0; + out_31505903139368806[271] = 0; + out_31505903139368806[272] = 0; + out_31505903139368806[273] = 0; + out_31505903139368806[274] = 0; + out_31505903139368806[275] = 0; + out_31505903139368806[276] = 0; + out_31505903139368806[277] = 0; + out_31505903139368806[278] = 0; + out_31505903139368806[279] = 0; + out_31505903139368806[280] = 0; + out_31505903139368806[281] = 0; + out_31505903139368806[282] = 0; + out_31505903139368806[283] = 0; + out_31505903139368806[284] = 0; + out_31505903139368806[285] = 1.0; + out_31505903139368806[286] = 0; + out_31505903139368806[287] = 0; + out_31505903139368806[288] = 0; + out_31505903139368806[289] = 0; + out_31505903139368806[290] = 0; + out_31505903139368806[291] = 0; + out_31505903139368806[292] = 0; + out_31505903139368806[293] = 0; + out_31505903139368806[294] = 0; + out_31505903139368806[295] = 0; + out_31505903139368806[296] = 0; + out_31505903139368806[297] = 0; + out_31505903139368806[298] = 0; + out_31505903139368806[299] = 0; + out_31505903139368806[300] = 0; + out_31505903139368806[301] = 0; + out_31505903139368806[302] = 0; + out_31505903139368806[303] = 0; + out_31505903139368806[304] = 0; + out_31505903139368806[305] = 0; + out_31505903139368806[306] = 0; + out_31505903139368806[307] = 1.0; + out_31505903139368806[308] = 0; + out_31505903139368806[309] = 0; + out_31505903139368806[310] = 0; + out_31505903139368806[311] = 0; + out_31505903139368806[312] = 0; + out_31505903139368806[313] = 0; + out_31505903139368806[314] = 0; + out_31505903139368806[315] = 0; + out_31505903139368806[316] = 0; + out_31505903139368806[317] = 0; + out_31505903139368806[318] = 0; + out_31505903139368806[319] = 0; + out_31505903139368806[320] = 0; + out_31505903139368806[321] = 0; + out_31505903139368806[322] = 0; + out_31505903139368806[323] = 0; + out_31505903139368806[324] = 0; + out_31505903139368806[325] = 0; + out_31505903139368806[326] = 0; + out_31505903139368806[327] = 0; + out_31505903139368806[328] = 0; + out_31505903139368806[329] = 1.0; + out_31505903139368806[330] = 0; + out_31505903139368806[331] = 0; + out_31505903139368806[332] = 0; + out_31505903139368806[333] = 0; + out_31505903139368806[334] = 0; + out_31505903139368806[335] = 0; + out_31505903139368806[336] = 0; + out_31505903139368806[337] = 0; + out_31505903139368806[338] = 0; + out_31505903139368806[339] = 0; + out_31505903139368806[340] = 0; + out_31505903139368806[341] = 0; + out_31505903139368806[342] = 0; + out_31505903139368806[343] = 0; + out_31505903139368806[344] = 0; + out_31505903139368806[345] = 0; + out_31505903139368806[346] = 0; + out_31505903139368806[347] = 0; + out_31505903139368806[348] = 0; + out_31505903139368806[349] = 0; + out_31505903139368806[350] = 0; + out_31505903139368806[351] = 1.0; + out_31505903139368806[352] = 0; + out_31505903139368806[353] = 0; + out_31505903139368806[354] = 0; + out_31505903139368806[355] = 0; + out_31505903139368806[356] = 0; + out_31505903139368806[357] = 0; + out_31505903139368806[358] = 0; + out_31505903139368806[359] = 0; + out_31505903139368806[360] = 0; + out_31505903139368806[361] = 0; + out_31505903139368806[362] = 0; + out_31505903139368806[363] = 0; + out_31505903139368806[364] = 0; + out_31505903139368806[365] = 0; + out_31505903139368806[366] = 0; + out_31505903139368806[367] = 0; + out_31505903139368806[368] = 0; + out_31505903139368806[369] = 0; + out_31505903139368806[370] = 0; + out_31505903139368806[371] = 0; + out_31505903139368806[372] = 0; + out_31505903139368806[373] = 1.0; + out_31505903139368806[374] = 0; + out_31505903139368806[375] = 0; + out_31505903139368806[376] = 0; + out_31505903139368806[377] = 0; + out_31505903139368806[378] = 0; + out_31505903139368806[379] = 0; + out_31505903139368806[380] = 0; + out_31505903139368806[381] = 0; + out_31505903139368806[382] = 0; + out_31505903139368806[383] = 0; + out_31505903139368806[384] = 0; + out_31505903139368806[385] = 0; + out_31505903139368806[386] = 0; + out_31505903139368806[387] = 0; + out_31505903139368806[388] = 0; + out_31505903139368806[389] = 0; + out_31505903139368806[390] = 0; + out_31505903139368806[391] = 0; + out_31505903139368806[392] = 0; + out_31505903139368806[393] = 0; + out_31505903139368806[394] = 0; + out_31505903139368806[395] = 1.0; + out_31505903139368806[396] = 0; + out_31505903139368806[397] = 0; + out_31505903139368806[398] = 0; + out_31505903139368806[399] = 0; + out_31505903139368806[400] = 0; + out_31505903139368806[401] = 0; + out_31505903139368806[402] = 0; + out_31505903139368806[403] = 0; + out_31505903139368806[404] = 0; + out_31505903139368806[405] = 0; + out_31505903139368806[406] = 0; + out_31505903139368806[407] = 0; + out_31505903139368806[408] = 0; + out_31505903139368806[409] = 0; + out_31505903139368806[410] = 0; + out_31505903139368806[411] = 0; + out_31505903139368806[412] = 0; + out_31505903139368806[413] = 0; + out_31505903139368806[414] = 0; + out_31505903139368806[415] = 0; + out_31505903139368806[416] = 0; + out_31505903139368806[417] = 1.0; + out_31505903139368806[418] = 0; + out_31505903139368806[419] = 0; + out_31505903139368806[420] = 0; + out_31505903139368806[421] = 0; + out_31505903139368806[422] = 0; + out_31505903139368806[423] = 0; + out_31505903139368806[424] = 0; + out_31505903139368806[425] = 0; + out_31505903139368806[426] = 0; + out_31505903139368806[427] = 0; + out_31505903139368806[428] = 0; + out_31505903139368806[429] = 0; + out_31505903139368806[430] = 0; + out_31505903139368806[431] = 0; + out_31505903139368806[432] = 0; + out_31505903139368806[433] = 0; + out_31505903139368806[434] = 0; + out_31505903139368806[435] = 0; + out_31505903139368806[436] = 0; + out_31505903139368806[437] = 0; + out_31505903139368806[438] = 0; + out_31505903139368806[439] = 1.0; + out_31505903139368806[440] = 0; + out_31505903139368806[441] = 0; + out_31505903139368806[442] = 0; + out_31505903139368806[443] = 0; + out_31505903139368806[444] = 0; + out_31505903139368806[445] = 0; + out_31505903139368806[446] = 0; + out_31505903139368806[447] = 0; + out_31505903139368806[448] = 0; + out_31505903139368806[449] = 0; + out_31505903139368806[450] = 0; + out_31505903139368806[451] = 0; + out_31505903139368806[452] = 0; + out_31505903139368806[453] = 0; + out_31505903139368806[454] = 0; + out_31505903139368806[455] = 0; + out_31505903139368806[456] = 0; + out_31505903139368806[457] = 0; + out_31505903139368806[458] = 0; + out_31505903139368806[459] = 0; + out_31505903139368806[460] = 0; + out_31505903139368806[461] = 1.0; +} +void f_fun(double *state, double dt, double *out_4984514158829912596) { + out_4984514158829912596[0] = dt*state[7] + state[0]; + out_4984514158829912596[1] = dt*state[8] + state[1]; + out_4984514158829912596[2] = dt*state[9] + state[2]; + out_4984514158829912596[3] = dt*(-0.5*state[4]*state[10] - 0.5*state[5]*state[11] - 0.5*state[6]*state[12]) + state[3]; + out_4984514158829912596[4] = dt*(0.5*state[3]*state[10] + 0.5*state[5]*state[12] - 0.5*state[6]*state[11]) + state[4]; + out_4984514158829912596[5] = dt*(0.5*state[3]*state[11] - 0.5*state[4]*state[12] + 0.5*state[6]*state[10]) + state[5]; + out_4984514158829912596[6] = dt*(0.5*state[3]*state[12] + 0.5*state[4]*state[11] - 0.5*state[5]*state[10]) + state[6]; + out_4984514158829912596[7] = dt*((2*state[3]*state[5] + 2*state[4]*state[6])*state[18] + (-2*state[3]*state[6] + 2*state[4]*state[5])*state[17] + (pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2))*state[16]) + state[7]; + out_4984514158829912596[8] = dt*((-2*state[3]*state[4] + 2*state[5]*state[6])*state[18] + (2*state[3]*state[6] + 2*state[4]*state[5])*state[16] + (pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2))*state[17]) + state[8]; + out_4984514158829912596[9] = dt*((2*state[3]*state[4] + 2*state[5]*state[6])*state[17] + (-2*state[3]*state[5] + 2*state[4]*state[6])*state[16] + (pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[18]) + state[9]; + out_4984514158829912596[10] = state[10]; + out_4984514158829912596[11] = state[11]; + out_4984514158829912596[12] = state[12]; + out_4984514158829912596[13] = state[13]; + out_4984514158829912596[14] = state[14]; + out_4984514158829912596[15] = state[15]; + out_4984514158829912596[16] = state[16]; + out_4984514158829912596[17] = state[17]; + out_4984514158829912596[18] = state[18]; + out_4984514158829912596[19] = state[19]; + out_4984514158829912596[20] = state[20]; + out_4984514158829912596[21] = state[21]; +} +void F_fun(double *state, double dt, double *out_495900107318952904) { + out_495900107318952904[0] = 1; + out_495900107318952904[1] = 0; + out_495900107318952904[2] = 0; + out_495900107318952904[3] = 0; + out_495900107318952904[4] = 0; + out_495900107318952904[5] = 0; + out_495900107318952904[6] = dt; + out_495900107318952904[7] = 0; + out_495900107318952904[8] = 0; + out_495900107318952904[9] = 0; + out_495900107318952904[10] = 0; + out_495900107318952904[11] = 0; + out_495900107318952904[12] = 0; + out_495900107318952904[13] = 0; + out_495900107318952904[14] = 0; + out_495900107318952904[15] = 0; + out_495900107318952904[16] = 0; + out_495900107318952904[17] = 0; + out_495900107318952904[18] = 0; + out_495900107318952904[19] = 0; + out_495900107318952904[20] = 0; + out_495900107318952904[21] = 0; + out_495900107318952904[22] = 1; + out_495900107318952904[23] = 0; + out_495900107318952904[24] = 0; + out_495900107318952904[25] = 0; + out_495900107318952904[26] = 0; + out_495900107318952904[27] = 0; + out_495900107318952904[28] = dt; + out_495900107318952904[29] = 0; + out_495900107318952904[30] = 0; + out_495900107318952904[31] = 0; + out_495900107318952904[32] = 0; + out_495900107318952904[33] = 0; + out_495900107318952904[34] = 0; + out_495900107318952904[35] = 0; + out_495900107318952904[36] = 0; + out_495900107318952904[37] = 0; + out_495900107318952904[38] = 0; + out_495900107318952904[39] = 0; + out_495900107318952904[40] = 0; + out_495900107318952904[41] = 0; + out_495900107318952904[42] = 0; + out_495900107318952904[43] = 0; + out_495900107318952904[44] = 1; + out_495900107318952904[45] = 0; + out_495900107318952904[46] = 0; + out_495900107318952904[47] = 0; + out_495900107318952904[48] = 0; + out_495900107318952904[49] = 0; + out_495900107318952904[50] = dt; + out_495900107318952904[51] = 0; + out_495900107318952904[52] = 0; + out_495900107318952904[53] = 0; + out_495900107318952904[54] = 0; + out_495900107318952904[55] = 0; + out_495900107318952904[56] = 0; + out_495900107318952904[57] = 0; + out_495900107318952904[58] = 0; + out_495900107318952904[59] = 0; + out_495900107318952904[60] = 0; + out_495900107318952904[61] = 0; + out_495900107318952904[62] = 0; + out_495900107318952904[63] = 0; + out_495900107318952904[64] = 0; + out_495900107318952904[65] = 0; + out_495900107318952904[66] = 1; + out_495900107318952904[67] = dt*((2*state[3]*state[4] + 2*state[5]*state[6])*state[11] + (-2*state[3]*state[5] + 2*state[4]*state[6])*state[10] + (pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[12]); + out_495900107318952904[68] = dt*((2*state[3]*state[4] - 2*state[5]*state[6])*state[12] + (-2*state[3]*state[6] - 2*state[4]*state[5])*state[10] + (-pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[11]); + out_495900107318952904[69] = 0; + out_495900107318952904[70] = 0; + out_495900107318952904[71] = 0; + out_495900107318952904[72] = dt*(pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2)); + out_495900107318952904[73] = dt*(-2*state[3]*state[6] + 2*state[4]*state[5]); + out_495900107318952904[74] = dt*(2*state[3]*state[5] + 2*state[4]*state[6]); + out_495900107318952904[75] = 0; + out_495900107318952904[76] = 0; + out_495900107318952904[77] = 0; + out_495900107318952904[78] = 0; + out_495900107318952904[79] = 0; + out_495900107318952904[80] = 0; + out_495900107318952904[81] = 0; + out_495900107318952904[82] = 0; + out_495900107318952904[83] = 0; + out_495900107318952904[84] = 0; + out_495900107318952904[85] = 0; + out_495900107318952904[86] = 0; + out_495900107318952904[87] = dt*(-(2*state[3]*state[4] + 2*state[5]*state[6])*state[11] - (-2*state[3]*state[5] + 2*state[4]*state[6])*state[10] - (pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[12]); + out_495900107318952904[88] = 1; + out_495900107318952904[89] = dt*((2*state[3]*state[5] + 2*state[4]*state[6])*state[12] + (-2*state[3]*state[6] + 2*state[4]*state[5])*state[11] + (pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2))*state[10]); + out_495900107318952904[90] = 0; + out_495900107318952904[91] = 0; + out_495900107318952904[92] = 0; + out_495900107318952904[93] = dt*(2*state[3]*state[6] + 2*state[4]*state[5]); + out_495900107318952904[94] = dt*(pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2)); + out_495900107318952904[95] = dt*(-2*state[3]*state[4] + 2*state[5]*state[6]); + out_495900107318952904[96] = 0; + out_495900107318952904[97] = 0; + out_495900107318952904[98] = 0; + out_495900107318952904[99] = 0; + out_495900107318952904[100] = 0; + out_495900107318952904[101] = 0; + out_495900107318952904[102] = 0; + out_495900107318952904[103] = 0; + out_495900107318952904[104] = 0; + out_495900107318952904[105] = 0; + out_495900107318952904[106] = 0; + out_495900107318952904[107] = 0; + out_495900107318952904[108] = dt*((-2*state[3]*state[4] + 2*state[5]*state[6])*state[12] + (2*state[3]*state[6] + 2*state[4]*state[5])*state[10] + (pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2))*state[11]); + out_495900107318952904[109] = dt*((-2*state[3]*state[5] - 2*state[4]*state[6])*state[12] + (2*state[3]*state[6] - 2*state[4]*state[5])*state[11] + (-pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) + pow(state[6], 2))*state[10]); + out_495900107318952904[110] = 1; + out_495900107318952904[111] = 0; + out_495900107318952904[112] = 0; + out_495900107318952904[113] = 0; + out_495900107318952904[114] = dt*(-2*state[3]*state[5] + 2*state[4]*state[6]); + out_495900107318952904[115] = dt*(2*state[3]*state[4] + 2*state[5]*state[6]); + out_495900107318952904[116] = dt*(pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2)); + out_495900107318952904[117] = 0; + out_495900107318952904[118] = 0; + out_495900107318952904[119] = 0; + out_495900107318952904[120] = 0; + out_495900107318952904[121] = 0; + out_495900107318952904[122] = 0; + out_495900107318952904[123] = 0; + out_495900107318952904[124] = 0; + out_495900107318952904[125] = 0; + out_495900107318952904[126] = 0; + out_495900107318952904[127] = 0; + out_495900107318952904[128] = 0; + out_495900107318952904[129] = 0; + out_495900107318952904[130] = dt*((2*state[3]*state[4] + 2*state[5]*state[6])*state[17] + (-2*state[3]*state[5] + 2*state[4]*state[6])*state[16] + (pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[18]); + out_495900107318952904[131] = dt*((2*state[3]*state[4] - 2*state[5]*state[6])*state[18] + (-2*state[3]*state[6] - 2*state[4]*state[5])*state[16] + (-pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[17]); + out_495900107318952904[132] = 1; + out_495900107318952904[133] = 0; + out_495900107318952904[134] = 0; + out_495900107318952904[135] = 0; + out_495900107318952904[136] = 0; + out_495900107318952904[137] = 0; + out_495900107318952904[138] = 0; + out_495900107318952904[139] = 0; + out_495900107318952904[140] = 0; + out_495900107318952904[141] = dt*(pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2)); + out_495900107318952904[142] = dt*(-2*state[3]*state[6] + 2*state[4]*state[5]); + out_495900107318952904[143] = dt*(2*state[3]*state[5] + 2*state[4]*state[6]); + out_495900107318952904[144] = 0; + out_495900107318952904[145] = 0; + out_495900107318952904[146] = 0; + out_495900107318952904[147] = 0; + out_495900107318952904[148] = 0; + out_495900107318952904[149] = 0; + out_495900107318952904[150] = dt*(-(2*state[3]*state[4] + 2*state[5]*state[6])*state[17] - (-2*state[3]*state[5] + 2*state[4]*state[6])*state[16] - (pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[18]); + out_495900107318952904[151] = 0; + out_495900107318952904[152] = dt*((2*state[3]*state[5] + 2*state[4]*state[6])*state[18] + (-2*state[3]*state[6] + 2*state[4]*state[5])*state[17] + (pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2))*state[16]); + out_495900107318952904[153] = 0; + out_495900107318952904[154] = 1; + out_495900107318952904[155] = 0; + out_495900107318952904[156] = 0; + out_495900107318952904[157] = 0; + out_495900107318952904[158] = 0; + out_495900107318952904[159] = 0; + out_495900107318952904[160] = 0; + out_495900107318952904[161] = 0; + out_495900107318952904[162] = dt*(2*state[3]*state[6] + 2*state[4]*state[5]); + out_495900107318952904[163] = dt*(pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2)); + out_495900107318952904[164] = dt*(-2*state[3]*state[4] + 2*state[5]*state[6]); + out_495900107318952904[165] = 0; + out_495900107318952904[166] = 0; + out_495900107318952904[167] = 0; + out_495900107318952904[168] = 0; + out_495900107318952904[169] = 0; + out_495900107318952904[170] = 0; + out_495900107318952904[171] = dt*((-2*state[3]*state[4] + 2*state[5]*state[6])*state[18] + (2*state[3]*state[6] + 2*state[4]*state[5])*state[16] + (pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2))*state[17]); + out_495900107318952904[172] = dt*((-2*state[3]*state[5] - 2*state[4]*state[6])*state[18] + (2*state[3]*state[6] - 2*state[4]*state[5])*state[17] + (-pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) + pow(state[6], 2))*state[16]); + out_495900107318952904[173] = 0; + out_495900107318952904[174] = 0; + out_495900107318952904[175] = 0; + out_495900107318952904[176] = 1; + out_495900107318952904[177] = 0; + out_495900107318952904[178] = 0; + out_495900107318952904[179] = 0; + out_495900107318952904[180] = 0; + out_495900107318952904[181] = 0; + out_495900107318952904[182] = 0; + out_495900107318952904[183] = dt*(-2*state[3]*state[5] + 2*state[4]*state[6]); + out_495900107318952904[184] = dt*(2*state[3]*state[4] + 2*state[5]*state[6]); + out_495900107318952904[185] = dt*(pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2)); + out_495900107318952904[186] = 0; + out_495900107318952904[187] = 0; + out_495900107318952904[188] = 0; + out_495900107318952904[189] = 0; + out_495900107318952904[190] = 0; + out_495900107318952904[191] = 0; + out_495900107318952904[192] = 0; + out_495900107318952904[193] = 0; + out_495900107318952904[194] = 0; + out_495900107318952904[195] = 0; + out_495900107318952904[196] = 0; + out_495900107318952904[197] = 0; + out_495900107318952904[198] = 1; + out_495900107318952904[199] = 0; + out_495900107318952904[200] = 0; + out_495900107318952904[201] = 0; + out_495900107318952904[202] = 0; + out_495900107318952904[203] = 0; + out_495900107318952904[204] = 0; + out_495900107318952904[205] = 0; + out_495900107318952904[206] = 0; + out_495900107318952904[207] = 0; + out_495900107318952904[208] = 0; + out_495900107318952904[209] = 0; + out_495900107318952904[210] = 0; + out_495900107318952904[211] = 0; + out_495900107318952904[212] = 0; + out_495900107318952904[213] = 0; + out_495900107318952904[214] = 0; + out_495900107318952904[215] = 0; + out_495900107318952904[216] = 0; + out_495900107318952904[217] = 0; + out_495900107318952904[218] = 0; + out_495900107318952904[219] = 0; + out_495900107318952904[220] = 1; + out_495900107318952904[221] = 0; + out_495900107318952904[222] = 0; + out_495900107318952904[223] = 0; + out_495900107318952904[224] = 0; + out_495900107318952904[225] = 0; + out_495900107318952904[226] = 0; + out_495900107318952904[227] = 0; + out_495900107318952904[228] = 0; + out_495900107318952904[229] = 0; + out_495900107318952904[230] = 0; + out_495900107318952904[231] = 0; + out_495900107318952904[232] = 0; + out_495900107318952904[233] = 0; + out_495900107318952904[234] = 0; + out_495900107318952904[235] = 0; + out_495900107318952904[236] = 0; + out_495900107318952904[237] = 0; + out_495900107318952904[238] = 0; + out_495900107318952904[239] = 0; + out_495900107318952904[240] = 0; + out_495900107318952904[241] = 0; + out_495900107318952904[242] = 1; + out_495900107318952904[243] = 0; + out_495900107318952904[244] = 0; + out_495900107318952904[245] = 0; + out_495900107318952904[246] = 0; + out_495900107318952904[247] = 0; + out_495900107318952904[248] = 0; + out_495900107318952904[249] = 0; + out_495900107318952904[250] = 0; + out_495900107318952904[251] = 0; + out_495900107318952904[252] = 0; + out_495900107318952904[253] = 0; + out_495900107318952904[254] = 0; + out_495900107318952904[255] = 0; + out_495900107318952904[256] = 0; + out_495900107318952904[257] = 0; + out_495900107318952904[258] = 0; + out_495900107318952904[259] = 0; + out_495900107318952904[260] = 0; + out_495900107318952904[261] = 0; + out_495900107318952904[262] = 0; + out_495900107318952904[263] = 0; + out_495900107318952904[264] = 1; + out_495900107318952904[265] = 0; + out_495900107318952904[266] = 0; + out_495900107318952904[267] = 0; + out_495900107318952904[268] = 0; + out_495900107318952904[269] = 0; + out_495900107318952904[270] = 0; + out_495900107318952904[271] = 0; + out_495900107318952904[272] = 0; + out_495900107318952904[273] = 0; + out_495900107318952904[274] = 0; + out_495900107318952904[275] = 0; + out_495900107318952904[276] = 0; + out_495900107318952904[277] = 0; + out_495900107318952904[278] = 0; + out_495900107318952904[279] = 0; + out_495900107318952904[280] = 0; + out_495900107318952904[281] = 0; + out_495900107318952904[282] = 0; + out_495900107318952904[283] = 0; + out_495900107318952904[284] = 0; + out_495900107318952904[285] = 0; + out_495900107318952904[286] = 1; + out_495900107318952904[287] = 0; + out_495900107318952904[288] = 0; + out_495900107318952904[289] = 0; + out_495900107318952904[290] = 0; + out_495900107318952904[291] = 0; + out_495900107318952904[292] = 0; + out_495900107318952904[293] = 0; + out_495900107318952904[294] = 0; + out_495900107318952904[295] = 0; + out_495900107318952904[296] = 0; + out_495900107318952904[297] = 0; + out_495900107318952904[298] = 0; + out_495900107318952904[299] = 0; + out_495900107318952904[300] = 0; + out_495900107318952904[301] = 0; + out_495900107318952904[302] = 0; + out_495900107318952904[303] = 0; + out_495900107318952904[304] = 0; + out_495900107318952904[305] = 0; + out_495900107318952904[306] = 0; + out_495900107318952904[307] = 0; + out_495900107318952904[308] = 1; + out_495900107318952904[309] = 0; + out_495900107318952904[310] = 0; + out_495900107318952904[311] = 0; + out_495900107318952904[312] = 0; + out_495900107318952904[313] = 0; + out_495900107318952904[314] = 0; + out_495900107318952904[315] = 0; + out_495900107318952904[316] = 0; + out_495900107318952904[317] = 0; + out_495900107318952904[318] = 0; + out_495900107318952904[319] = 0; + out_495900107318952904[320] = 0; + out_495900107318952904[321] = 0; + out_495900107318952904[322] = 0; + out_495900107318952904[323] = 0; + out_495900107318952904[324] = 0; + out_495900107318952904[325] = 0; + out_495900107318952904[326] = 0; + out_495900107318952904[327] = 0; + out_495900107318952904[328] = 0; + out_495900107318952904[329] = 0; + out_495900107318952904[330] = 1; + out_495900107318952904[331] = 0; + out_495900107318952904[332] = 0; + out_495900107318952904[333] = 0; + out_495900107318952904[334] = 0; + out_495900107318952904[335] = 0; + out_495900107318952904[336] = 0; + out_495900107318952904[337] = 0; + out_495900107318952904[338] = 0; + out_495900107318952904[339] = 0; + out_495900107318952904[340] = 0; + out_495900107318952904[341] = 0; + out_495900107318952904[342] = 0; + out_495900107318952904[343] = 0; + out_495900107318952904[344] = 0; + out_495900107318952904[345] = 0; + out_495900107318952904[346] = 0; + out_495900107318952904[347] = 0; + out_495900107318952904[348] = 0; + out_495900107318952904[349] = 0; + out_495900107318952904[350] = 0; + out_495900107318952904[351] = 0; + out_495900107318952904[352] = 1; + out_495900107318952904[353] = 0; + out_495900107318952904[354] = 0; + out_495900107318952904[355] = 0; + out_495900107318952904[356] = 0; + out_495900107318952904[357] = 0; + out_495900107318952904[358] = 0; + out_495900107318952904[359] = 0; + out_495900107318952904[360] = 0; + out_495900107318952904[361] = 0; + out_495900107318952904[362] = 0; + out_495900107318952904[363] = 0; + out_495900107318952904[364] = 0; + out_495900107318952904[365] = 0; + out_495900107318952904[366] = 0; + out_495900107318952904[367] = 0; + out_495900107318952904[368] = 0; + out_495900107318952904[369] = 0; + out_495900107318952904[370] = 0; + out_495900107318952904[371] = 0; + out_495900107318952904[372] = 0; + out_495900107318952904[373] = 0; + out_495900107318952904[374] = 1; + out_495900107318952904[375] = 0; + out_495900107318952904[376] = 0; + out_495900107318952904[377] = 0; + out_495900107318952904[378] = 0; + out_495900107318952904[379] = 0; + out_495900107318952904[380] = 0; + out_495900107318952904[381] = 0; + out_495900107318952904[382] = 0; + out_495900107318952904[383] = 0; + out_495900107318952904[384] = 0; + out_495900107318952904[385] = 0; + out_495900107318952904[386] = 0; + out_495900107318952904[387] = 0; + out_495900107318952904[388] = 0; + out_495900107318952904[389] = 0; + out_495900107318952904[390] = 0; + out_495900107318952904[391] = 0; + out_495900107318952904[392] = 0; + out_495900107318952904[393] = 0; + out_495900107318952904[394] = 0; + out_495900107318952904[395] = 0; + out_495900107318952904[396] = 1; + out_495900107318952904[397] = 0; + out_495900107318952904[398] = 0; + out_495900107318952904[399] = 0; + out_495900107318952904[400] = 0; + out_495900107318952904[401] = 0; + out_495900107318952904[402] = 0; + out_495900107318952904[403] = 0; + out_495900107318952904[404] = 0; + out_495900107318952904[405] = 0; + out_495900107318952904[406] = 0; + out_495900107318952904[407] = 0; + out_495900107318952904[408] = 0; + out_495900107318952904[409] = 0; + out_495900107318952904[410] = 0; + out_495900107318952904[411] = 0; + out_495900107318952904[412] = 0; + out_495900107318952904[413] = 0; + out_495900107318952904[414] = 0; + out_495900107318952904[415] = 0; + out_495900107318952904[416] = 0; + out_495900107318952904[417] = 0; + out_495900107318952904[418] = 1; + out_495900107318952904[419] = 0; + out_495900107318952904[420] = 0; + out_495900107318952904[421] = 0; + out_495900107318952904[422] = 0; + out_495900107318952904[423] = 0; + out_495900107318952904[424] = 0; + out_495900107318952904[425] = 0; + out_495900107318952904[426] = 0; + out_495900107318952904[427] = 0; + out_495900107318952904[428] = 0; + out_495900107318952904[429] = 0; + out_495900107318952904[430] = 0; + out_495900107318952904[431] = 0; + out_495900107318952904[432] = 0; + out_495900107318952904[433] = 0; + out_495900107318952904[434] = 0; + out_495900107318952904[435] = 0; + out_495900107318952904[436] = 0; + out_495900107318952904[437] = 0; + out_495900107318952904[438] = 0; + out_495900107318952904[439] = 0; + out_495900107318952904[440] = 1; +} +void h_4(double *state, double *unused, double *out_4218409302925889705) { + out_4218409302925889705[0] = state[10] + state[13]; + out_4218409302925889705[1] = state[11] + state[14]; + out_4218409302925889705[2] = state[12] + state[15]; +} +void H_4(double *state, double *unused, double *out_2064362458237902773) { + out_2064362458237902773[0] = 0; + out_2064362458237902773[1] = 0; + out_2064362458237902773[2] = 0; + out_2064362458237902773[3] = 0; + out_2064362458237902773[4] = 0; + out_2064362458237902773[5] = 0; + out_2064362458237902773[6] = 0; + out_2064362458237902773[7] = 0; + out_2064362458237902773[8] = 0; + out_2064362458237902773[9] = 0; + out_2064362458237902773[10] = 1; + out_2064362458237902773[11] = 0; + out_2064362458237902773[12] = 0; + out_2064362458237902773[13] = 1; + out_2064362458237902773[14] = 0; + out_2064362458237902773[15] = 0; + out_2064362458237902773[16] = 0; + out_2064362458237902773[17] = 0; + out_2064362458237902773[18] = 0; + out_2064362458237902773[19] = 0; + out_2064362458237902773[20] = 0; + out_2064362458237902773[21] = 0; + out_2064362458237902773[22] = 0; + out_2064362458237902773[23] = 0; + out_2064362458237902773[24] = 0; + out_2064362458237902773[25] = 0; + out_2064362458237902773[26] = 0; + out_2064362458237902773[27] = 0; + out_2064362458237902773[28] = 0; + out_2064362458237902773[29] = 0; + out_2064362458237902773[30] = 0; + out_2064362458237902773[31] = 0; + out_2064362458237902773[32] = 0; + out_2064362458237902773[33] = 1; + out_2064362458237902773[34] = 0; + out_2064362458237902773[35] = 0; + out_2064362458237902773[36] = 1; + out_2064362458237902773[37] = 0; + out_2064362458237902773[38] = 0; + out_2064362458237902773[39] = 0; + out_2064362458237902773[40] = 0; + out_2064362458237902773[41] = 0; + out_2064362458237902773[42] = 0; + out_2064362458237902773[43] = 0; + out_2064362458237902773[44] = 0; + out_2064362458237902773[45] = 0; + out_2064362458237902773[46] = 0; + out_2064362458237902773[47] = 0; + out_2064362458237902773[48] = 0; + out_2064362458237902773[49] = 0; + out_2064362458237902773[50] = 0; + out_2064362458237902773[51] = 0; + out_2064362458237902773[52] = 0; + out_2064362458237902773[53] = 0; + out_2064362458237902773[54] = 0; + out_2064362458237902773[55] = 0; + out_2064362458237902773[56] = 1; + out_2064362458237902773[57] = 0; + out_2064362458237902773[58] = 0; + out_2064362458237902773[59] = 1; + out_2064362458237902773[60] = 0; + out_2064362458237902773[61] = 0; + out_2064362458237902773[62] = 0; + out_2064362458237902773[63] = 0; + out_2064362458237902773[64] = 0; + out_2064362458237902773[65] = 0; +} +void h_9(double *state, double *unused, double *out_4201404494137813277) { + out_4201404494137813277[0] = state[10]; + out_4201404494137813277[1] = state[11]; + out_4201404494137813277[2] = state[12]; +} +void H_9(double *state, double *unused, double *out_1823172811608312128) { + out_1823172811608312128[0] = 0; + out_1823172811608312128[1] = 0; + out_1823172811608312128[2] = 0; + out_1823172811608312128[3] = 0; + out_1823172811608312128[4] = 0; + out_1823172811608312128[5] = 0; + out_1823172811608312128[6] = 0; + out_1823172811608312128[7] = 0; + out_1823172811608312128[8] = 0; + out_1823172811608312128[9] = 0; + out_1823172811608312128[10] = 1; + out_1823172811608312128[11] = 0; + out_1823172811608312128[12] = 0; + out_1823172811608312128[13] = 0; + out_1823172811608312128[14] = 0; + out_1823172811608312128[15] = 0; + out_1823172811608312128[16] = 0; + out_1823172811608312128[17] = 0; + out_1823172811608312128[18] = 0; + out_1823172811608312128[19] = 0; + out_1823172811608312128[20] = 0; + out_1823172811608312128[21] = 0; + out_1823172811608312128[22] = 0; + out_1823172811608312128[23] = 0; + out_1823172811608312128[24] = 0; + out_1823172811608312128[25] = 0; + out_1823172811608312128[26] = 0; + out_1823172811608312128[27] = 0; + out_1823172811608312128[28] = 0; + out_1823172811608312128[29] = 0; + out_1823172811608312128[30] = 0; + out_1823172811608312128[31] = 0; + out_1823172811608312128[32] = 0; + out_1823172811608312128[33] = 1; + out_1823172811608312128[34] = 0; + out_1823172811608312128[35] = 0; + out_1823172811608312128[36] = 0; + out_1823172811608312128[37] = 0; + out_1823172811608312128[38] = 0; + out_1823172811608312128[39] = 0; + out_1823172811608312128[40] = 0; + out_1823172811608312128[41] = 0; + out_1823172811608312128[42] = 0; + out_1823172811608312128[43] = 0; + out_1823172811608312128[44] = 0; + out_1823172811608312128[45] = 0; + out_1823172811608312128[46] = 0; + out_1823172811608312128[47] = 0; + out_1823172811608312128[48] = 0; + out_1823172811608312128[49] = 0; + out_1823172811608312128[50] = 0; + out_1823172811608312128[51] = 0; + out_1823172811608312128[52] = 0; + out_1823172811608312128[53] = 0; + out_1823172811608312128[54] = 0; + out_1823172811608312128[55] = 0; + out_1823172811608312128[56] = 1; + out_1823172811608312128[57] = 0; + out_1823172811608312128[58] = 0; + out_1823172811608312128[59] = 0; + out_1823172811608312128[60] = 0; + out_1823172811608312128[61] = 0; + out_1823172811608312128[62] = 0; + out_1823172811608312128[63] = 0; + out_1823172811608312128[64] = 0; + out_1823172811608312128[65] = 0; +} +void h_10(double *state, double *unused, double *out_4904878276509257913) { + out_4904878276509257913[0] = 398600500000000.0*(-2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2] + 398600500000000.0*(2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1] + 398600500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*(pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2))*state[0] + state[16] + state[19]; + out_4904878276509257913[1] = 398600500000000.0*(2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2] + 398600500000000.0*(-2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0] + 398600500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*(pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2))*state[1] + state[17] + state[20]; + out_4904878276509257913[2] = 398600500000000.0*(-2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1] + 398600500000000.0*(2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0] + 398600500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*(pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[2] + state[18] + state[21]; +} +void H_10(double *state, double *unused, double *out_7361770315712994123) { + out_7361770315712994123[0] = -1195801500000000.0*(-2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[0]*state[2] - 1195801500000000.0*(2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[0]*state[1] - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2))*pow(state[0], 2) + 398600500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*(pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2)); + out_7361770315712994123[1] = -1195801500000000.0*(-2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[1]*state[2] - 1195801500000000.0*(2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*pow(state[1], 2) + 398600500000000.0*(2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5) - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2))*state[0]*state[1]; + out_7361770315712994123[2] = -1195801500000000.0*(-2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*pow(state[2], 2) + 398600500000000.0*(-2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5) - 1195801500000000.0*(2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[1]*state[2] - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2))*state[0]*state[2]; + out_7361770315712994123[3] = 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[3] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[6] - 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[5]; + out_7361770315712994123[4] = 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[4] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[5] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[6]; + out_7361770315712994123[5] = -797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[5] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[4] - 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[3]; + out_7361770315712994123[6] = -797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[6] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[3] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[4]; + out_7361770315712994123[7] = 0; + out_7361770315712994123[8] = 0; + out_7361770315712994123[9] = 0; + out_7361770315712994123[10] = 0; + out_7361770315712994123[11] = 0; + out_7361770315712994123[12] = 0; + out_7361770315712994123[13] = 0; + out_7361770315712994123[14] = 0; + out_7361770315712994123[15] = 0; + out_7361770315712994123[16] = 1; + out_7361770315712994123[17] = 0; + out_7361770315712994123[18] = 0; + out_7361770315712994123[19] = 1; + out_7361770315712994123[20] = 0; + out_7361770315712994123[21] = 0; + out_7361770315712994123[22] = -1195801500000000.0*(2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[0]*state[2] - 1195801500000000.0*(-2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*pow(state[0], 2) + 398600500000000.0*(-2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5) - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2))*state[0]*state[1]; + out_7361770315712994123[23] = -1195801500000000.0*(2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[1]*state[2] - 1195801500000000.0*(-2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[0]*state[1] - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2))*pow(state[1], 2) + 398600500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*(pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2)); + out_7361770315712994123[24] = -1195801500000000.0*(2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*pow(state[2], 2) + 398600500000000.0*(2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5) - 1195801500000000.0*(-2*state[3]*state[6] + 2*state[4]*state[5])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[0]*state[2] - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2))*state[1]*state[2]; + out_7361770315712994123[25] = -797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[6] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[3] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[4]; + out_7361770315712994123[26] = 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[5] - 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[4] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[3]; + out_7361770315712994123[27] = 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[4] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[5] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[6]; + out_7361770315712994123[28] = -797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[3] - 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[6] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[5]; + out_7361770315712994123[29] = 0; + out_7361770315712994123[30] = 0; + out_7361770315712994123[31] = 0; + out_7361770315712994123[32] = 0; + out_7361770315712994123[33] = 0; + out_7361770315712994123[34] = 0; + out_7361770315712994123[35] = 0; + out_7361770315712994123[36] = 0; + out_7361770315712994123[37] = 0; + out_7361770315712994123[38] = 0; + out_7361770315712994123[39] = 1; + out_7361770315712994123[40] = 0; + out_7361770315712994123[41] = 0; + out_7361770315712994123[42] = 1; + out_7361770315712994123[43] = 0; + out_7361770315712994123[44] = -1195801500000000.0*(-2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[0]*state[1] - 1195801500000000.0*(2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*pow(state[0], 2) + 398600500000000.0*(2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5) - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[0]*state[2]; + out_7361770315712994123[45] = -1195801500000000.0*(-2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*pow(state[1], 2) + 398600500000000.0*(-2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5) - 1195801500000000.0*(2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[0]*state[1] - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[1]*state[2]; + out_7361770315712994123[46] = -1195801500000000.0*(-2*state[3]*state[4] + 2*state[5]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[1]*state[2] - 1195801500000000.0*(2*state[3]*state[5] + 2*state[4]*state[6])*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*state[0]*state[2] - 1195801500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -2.5)*(pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*pow(state[2], 2) + 398600500000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*(pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2)); + out_7361770315712994123[47] = 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[5] - 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[4] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[3]; + out_7361770315712994123[48] = 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[6] - 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[3] - 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[4]; + out_7361770315712994123[49] = 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[3] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[6] - 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[5]; + out_7361770315712994123[50] = 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[0]*state[4] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[1]*state[5] + 797201000000000.0*pow(pow(state[0], 2) + pow(state[1], 2) + pow(state[2], 2), -1.5)*state[2]*state[6]; + out_7361770315712994123[51] = 0; + out_7361770315712994123[52] = 0; + out_7361770315712994123[53] = 0; + out_7361770315712994123[54] = 0; + out_7361770315712994123[55] = 0; + out_7361770315712994123[56] = 0; + out_7361770315712994123[57] = 0; + out_7361770315712994123[58] = 0; + out_7361770315712994123[59] = 0; + out_7361770315712994123[60] = 0; + out_7361770315712994123[61] = 0; + out_7361770315712994123[62] = 1; + out_7361770315712994123[63] = 0; + out_7361770315712994123[64] = 0; + out_7361770315712994123[65] = 1; +} +void h_12(double *state, double *unused, double *out_3237267128515768115) { + out_3237267128515768115[0] = state[0]; + out_3237267128515768115[1] = state[1]; + out_3237267128515768115[2] = state[2]; +} +void H_12(double *state, double *unused, double *out_2955093949794059022) { + out_2955093949794059022[0] = 1; + out_2955093949794059022[1] = 0; + out_2955093949794059022[2] = 0; + out_2955093949794059022[3] = 0; + out_2955093949794059022[4] = 0; + out_2955093949794059022[5] = 0; + out_2955093949794059022[6] = 0; + out_2955093949794059022[7] = 0; + out_2955093949794059022[8] = 0; + out_2955093949794059022[9] = 0; + out_2955093949794059022[10] = 0; + out_2955093949794059022[11] = 0; + out_2955093949794059022[12] = 0; + out_2955093949794059022[13] = 0; + out_2955093949794059022[14] = 0; + out_2955093949794059022[15] = 0; + out_2955093949794059022[16] = 0; + out_2955093949794059022[17] = 0; + out_2955093949794059022[18] = 0; + out_2955093949794059022[19] = 0; + out_2955093949794059022[20] = 0; + out_2955093949794059022[21] = 0; + out_2955093949794059022[22] = 0; + out_2955093949794059022[23] = 1; + out_2955093949794059022[24] = 0; + out_2955093949794059022[25] = 0; + out_2955093949794059022[26] = 0; + out_2955093949794059022[27] = 0; + out_2955093949794059022[28] = 0; + out_2955093949794059022[29] = 0; + out_2955093949794059022[30] = 0; + out_2955093949794059022[31] = 0; + out_2955093949794059022[32] = 0; + out_2955093949794059022[33] = 0; + out_2955093949794059022[34] = 0; + out_2955093949794059022[35] = 0; + out_2955093949794059022[36] = 0; + out_2955093949794059022[37] = 0; + out_2955093949794059022[38] = 0; + out_2955093949794059022[39] = 0; + out_2955093949794059022[40] = 0; + out_2955093949794059022[41] = 0; + out_2955093949794059022[42] = 0; + out_2955093949794059022[43] = 0; + out_2955093949794059022[44] = 0; + out_2955093949794059022[45] = 0; + out_2955093949794059022[46] = 1; + out_2955093949794059022[47] = 0; + out_2955093949794059022[48] = 0; + out_2955093949794059022[49] = 0; + out_2955093949794059022[50] = 0; + out_2955093949794059022[51] = 0; + out_2955093949794059022[52] = 0; + out_2955093949794059022[53] = 0; + out_2955093949794059022[54] = 0; + out_2955093949794059022[55] = 0; + out_2955093949794059022[56] = 0; + out_2955093949794059022[57] = 0; + out_2955093949794059022[58] = 0; + out_2955093949794059022[59] = 0; + out_2955093949794059022[60] = 0; + out_2955093949794059022[61] = 0; + out_2955093949794059022[62] = 0; + out_2955093949794059022[63] = 0; + out_2955093949794059022[64] = 0; + out_2955093949794059022[65] = 0; +} +void h_35(double *state, double *unused, double *out_9093746190498438204) { + out_9093746190498438204[0] = state[7]; + out_9093746190498438204[1] = state[8]; + out_9093746190498438204[2] = state[9]; +} +void H_35(double *state, double *unused, double *out_1302299599134704603) { + out_1302299599134704603[0] = 0; + out_1302299599134704603[1] = 0; + out_1302299599134704603[2] = 0; + out_1302299599134704603[3] = 0; + out_1302299599134704603[4] = 0; + out_1302299599134704603[5] = 0; + out_1302299599134704603[6] = 0; + out_1302299599134704603[7] = 1; + out_1302299599134704603[8] = 0; + out_1302299599134704603[9] = 0; + out_1302299599134704603[10] = 0; + out_1302299599134704603[11] = 0; + out_1302299599134704603[12] = 0; + out_1302299599134704603[13] = 0; + out_1302299599134704603[14] = 0; + out_1302299599134704603[15] = 0; + out_1302299599134704603[16] = 0; + out_1302299599134704603[17] = 0; + out_1302299599134704603[18] = 0; + out_1302299599134704603[19] = 0; + out_1302299599134704603[20] = 0; + out_1302299599134704603[21] = 0; + out_1302299599134704603[22] = 0; + out_1302299599134704603[23] = 0; + out_1302299599134704603[24] = 0; + out_1302299599134704603[25] = 0; + out_1302299599134704603[26] = 0; + out_1302299599134704603[27] = 0; + out_1302299599134704603[28] = 0; + out_1302299599134704603[29] = 0; + out_1302299599134704603[30] = 1; + out_1302299599134704603[31] = 0; + out_1302299599134704603[32] = 0; + out_1302299599134704603[33] = 0; + out_1302299599134704603[34] = 0; + out_1302299599134704603[35] = 0; + out_1302299599134704603[36] = 0; + out_1302299599134704603[37] = 0; + out_1302299599134704603[38] = 0; + out_1302299599134704603[39] = 0; + out_1302299599134704603[40] = 0; + out_1302299599134704603[41] = 0; + out_1302299599134704603[42] = 0; + out_1302299599134704603[43] = 0; + out_1302299599134704603[44] = 0; + out_1302299599134704603[45] = 0; + out_1302299599134704603[46] = 0; + out_1302299599134704603[47] = 0; + out_1302299599134704603[48] = 0; + out_1302299599134704603[49] = 0; + out_1302299599134704603[50] = 0; + out_1302299599134704603[51] = 0; + out_1302299599134704603[52] = 0; + out_1302299599134704603[53] = 1; + out_1302299599134704603[54] = 0; + out_1302299599134704603[55] = 0; + out_1302299599134704603[56] = 0; + out_1302299599134704603[57] = 0; + out_1302299599134704603[58] = 0; + out_1302299599134704603[59] = 0; + out_1302299599134704603[60] = 0; + out_1302299599134704603[61] = 0; + out_1302299599134704603[62] = 0; + out_1302299599134704603[63] = 0; + out_1302299599134704603[64] = 0; + out_1302299599134704603[65] = 0; +} +void h_32(double *state, double *unused, double *out_5484223878963608382) { + out_5484223878963608382[0] = state[3]; + out_5484223878963608382[1] = state[4]; + out_5484223878963608382[2] = state[5]; + out_5484223878963608382[3] = state[6]; +} +void H_32(double *state, double *unused, double *out_5612564904559411753) { + out_5612564904559411753[0] = 0; + out_5612564904559411753[1] = 0; + out_5612564904559411753[2] = 0; + out_5612564904559411753[3] = 1; + out_5612564904559411753[4] = 0; + out_5612564904559411753[5] = 0; + out_5612564904559411753[6] = 0; + out_5612564904559411753[7] = 0; + out_5612564904559411753[8] = 0; + out_5612564904559411753[9] = 0; + out_5612564904559411753[10] = 0; + out_5612564904559411753[11] = 0; + out_5612564904559411753[12] = 0; + out_5612564904559411753[13] = 0; + out_5612564904559411753[14] = 0; + out_5612564904559411753[15] = 0; + out_5612564904559411753[16] = 0; + out_5612564904559411753[17] = 0; + out_5612564904559411753[18] = 0; + out_5612564904559411753[19] = 0; + out_5612564904559411753[20] = 0; + out_5612564904559411753[21] = 0; + out_5612564904559411753[22] = 0; + out_5612564904559411753[23] = 0; + out_5612564904559411753[24] = 0; + out_5612564904559411753[25] = 0; + out_5612564904559411753[26] = 1; + out_5612564904559411753[27] = 0; + out_5612564904559411753[28] = 0; + out_5612564904559411753[29] = 0; + out_5612564904559411753[30] = 0; + out_5612564904559411753[31] = 0; + out_5612564904559411753[32] = 0; + out_5612564904559411753[33] = 0; + out_5612564904559411753[34] = 0; + out_5612564904559411753[35] = 0; + out_5612564904559411753[36] = 0; + out_5612564904559411753[37] = 0; + out_5612564904559411753[38] = 0; + out_5612564904559411753[39] = 0; + out_5612564904559411753[40] = 0; + out_5612564904559411753[41] = 0; + out_5612564904559411753[42] = 0; + out_5612564904559411753[43] = 0; + out_5612564904559411753[44] = 0; + out_5612564904559411753[45] = 0; + out_5612564904559411753[46] = 0; + out_5612564904559411753[47] = 0; + out_5612564904559411753[48] = 0; + out_5612564904559411753[49] = 1; + out_5612564904559411753[50] = 0; + out_5612564904559411753[51] = 0; + out_5612564904559411753[52] = 0; + out_5612564904559411753[53] = 0; + out_5612564904559411753[54] = 0; + out_5612564904559411753[55] = 0; + out_5612564904559411753[56] = 0; + out_5612564904559411753[57] = 0; + out_5612564904559411753[58] = 0; + out_5612564904559411753[59] = 0; + out_5612564904559411753[60] = 0; + out_5612564904559411753[61] = 0; + out_5612564904559411753[62] = 0; + out_5612564904559411753[63] = 0; + out_5612564904559411753[64] = 0; + out_5612564904559411753[65] = 0; + out_5612564904559411753[66] = 0; + out_5612564904559411753[67] = 0; + out_5612564904559411753[68] = 0; + out_5612564904559411753[69] = 0; + out_5612564904559411753[70] = 0; + out_5612564904559411753[71] = 0; + out_5612564904559411753[72] = 1; + out_5612564904559411753[73] = 0; + out_5612564904559411753[74] = 0; + out_5612564904559411753[75] = 0; + out_5612564904559411753[76] = 0; + out_5612564904559411753[77] = 0; + out_5612564904559411753[78] = 0; + out_5612564904559411753[79] = 0; + out_5612564904559411753[80] = 0; + out_5612564904559411753[81] = 0; + out_5612564904559411753[82] = 0; + out_5612564904559411753[83] = 0; + out_5612564904559411753[84] = 0; + out_5612564904559411753[85] = 0; + out_5612564904559411753[86] = 0; + out_5612564904559411753[87] = 0; +} +void h_13(double *state, double *unused, double *out_7023021544313133462) { + out_7023021544313133462[0] = (-2*state[3]*state[5] + 2*state[4]*state[6])*state[9] + (2*state[3]*state[6] + 2*state[4]*state[5])*state[8] + (pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2))*state[7]; + out_7023021544313133462[1] = (2*state[3]*state[4] + 2*state[5]*state[6])*state[9] + (-2*state[3]*state[6] + 2*state[4]*state[5])*state[7] + (pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2))*state[8]; + out_7023021544313133462[2] = (-2*state[3]*state[4] + 2*state[5]*state[6])*state[8] + (2*state[3]*state[5] + 2*state[4]*state[6])*state[7] + (pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2))*state[9]; +} +void H_13(double *state, double *unused, double *out_6405415510614721399) { + out_6405415510614721399[0] = 0; + out_6405415510614721399[1] = 0; + out_6405415510614721399[2] = 0; + out_6405415510614721399[3] = 2*state[3]*state[7] - 2*state[5]*state[9] + 2*state[6]*state[8]; + out_6405415510614721399[4] = 2*state[4]*state[7] + 2*state[5]*state[8] + 2*state[6]*state[9]; + out_6405415510614721399[5] = -2*state[3]*state[9] + 2*state[4]*state[8] - 2*state[5]*state[7]; + out_6405415510614721399[6] = 2*state[3]*state[8] + 2*state[4]*state[9] - 2*state[6]*state[7]; + out_6405415510614721399[7] = pow(state[3], 2) + pow(state[4], 2) - pow(state[5], 2) - pow(state[6], 2); + out_6405415510614721399[8] = 2*state[3]*state[6] + 2*state[4]*state[5]; + out_6405415510614721399[9] = -2*state[3]*state[5] + 2*state[4]*state[6]; + out_6405415510614721399[10] = 0; + out_6405415510614721399[11] = 0; + out_6405415510614721399[12] = 0; + out_6405415510614721399[13] = 0; + out_6405415510614721399[14] = 0; + out_6405415510614721399[15] = 0; + out_6405415510614721399[16] = 0; + out_6405415510614721399[17] = 0; + out_6405415510614721399[18] = 0; + out_6405415510614721399[19] = 0; + out_6405415510614721399[20] = 0; + out_6405415510614721399[21] = 0; + out_6405415510614721399[22] = 0; + out_6405415510614721399[23] = 0; + out_6405415510614721399[24] = 0; + out_6405415510614721399[25] = 2*state[3]*state[8] + 2*state[4]*state[9] - 2*state[6]*state[7]; + out_6405415510614721399[26] = 2*state[3]*state[9] - 2*state[4]*state[8] + 2*state[5]*state[7]; + out_6405415510614721399[27] = 2*state[4]*state[7] + 2*state[5]*state[8] + 2*state[6]*state[9]; + out_6405415510614721399[28] = -2*state[3]*state[7] + 2*state[5]*state[9] - 2*state[6]*state[8]; + out_6405415510614721399[29] = -2*state[3]*state[6] + 2*state[4]*state[5]; + out_6405415510614721399[30] = pow(state[3], 2) - pow(state[4], 2) + pow(state[5], 2) - pow(state[6], 2); + out_6405415510614721399[31] = 2*state[3]*state[4] + 2*state[5]*state[6]; + out_6405415510614721399[32] = 0; + out_6405415510614721399[33] = 0; + out_6405415510614721399[34] = 0; + out_6405415510614721399[35] = 0; + out_6405415510614721399[36] = 0; + out_6405415510614721399[37] = 0; + out_6405415510614721399[38] = 0; + out_6405415510614721399[39] = 0; + out_6405415510614721399[40] = 0; + out_6405415510614721399[41] = 0; + out_6405415510614721399[42] = 0; + out_6405415510614721399[43] = 0; + out_6405415510614721399[44] = 0; + out_6405415510614721399[45] = 0; + out_6405415510614721399[46] = 0; + out_6405415510614721399[47] = 2*state[3]*state[9] - 2*state[4]*state[8] + 2*state[5]*state[7]; + out_6405415510614721399[48] = -2*state[3]*state[8] - 2*state[4]*state[9] + 2*state[6]*state[7]; + out_6405415510614721399[49] = 2*state[3]*state[7] - 2*state[5]*state[9] + 2*state[6]*state[8]; + out_6405415510614721399[50] = 2*state[4]*state[7] + 2*state[5]*state[8] + 2*state[6]*state[9]; + out_6405415510614721399[51] = 2*state[3]*state[5] + 2*state[4]*state[6]; + out_6405415510614721399[52] = -2*state[3]*state[4] + 2*state[5]*state[6]; + out_6405415510614721399[53] = pow(state[3], 2) - pow(state[4], 2) - pow(state[5], 2) + pow(state[6], 2); + out_6405415510614721399[54] = 0; + out_6405415510614721399[55] = 0; + out_6405415510614721399[56] = 0; + out_6405415510614721399[57] = 0; + out_6405415510614721399[58] = 0; + out_6405415510614721399[59] = 0; + out_6405415510614721399[60] = 0; + out_6405415510614721399[61] = 0; + out_6405415510614721399[62] = 0; + out_6405415510614721399[63] = 0; + out_6405415510614721399[64] = 0; + out_6405415510614721399[65] = 0; +} +void h_14(double *state, double *unused, double *out_4201404494137813277) { + out_4201404494137813277[0] = state[10]; + out_4201404494137813277[1] = state[11]; + out_4201404494137813277[2] = state[12]; +} +void H_14(double *state, double *unused, double *out_1823172811608312128) { + out_1823172811608312128[0] = 0; + out_1823172811608312128[1] = 0; + out_1823172811608312128[2] = 0; + out_1823172811608312128[3] = 0; + out_1823172811608312128[4] = 0; + out_1823172811608312128[5] = 0; + out_1823172811608312128[6] = 0; + out_1823172811608312128[7] = 0; + out_1823172811608312128[8] = 0; + out_1823172811608312128[9] = 0; + out_1823172811608312128[10] = 1; + out_1823172811608312128[11] = 0; + out_1823172811608312128[12] = 0; + out_1823172811608312128[13] = 0; + out_1823172811608312128[14] = 0; + out_1823172811608312128[15] = 0; + out_1823172811608312128[16] = 0; + out_1823172811608312128[17] = 0; + out_1823172811608312128[18] = 0; + out_1823172811608312128[19] = 0; + out_1823172811608312128[20] = 0; + out_1823172811608312128[21] = 0; + out_1823172811608312128[22] = 0; + out_1823172811608312128[23] = 0; + out_1823172811608312128[24] = 0; + out_1823172811608312128[25] = 0; + out_1823172811608312128[26] = 0; + out_1823172811608312128[27] = 0; + out_1823172811608312128[28] = 0; + out_1823172811608312128[29] = 0; + out_1823172811608312128[30] = 0; + out_1823172811608312128[31] = 0; + out_1823172811608312128[32] = 0; + out_1823172811608312128[33] = 1; + out_1823172811608312128[34] = 0; + out_1823172811608312128[35] = 0; + out_1823172811608312128[36] = 0; + out_1823172811608312128[37] = 0; + out_1823172811608312128[38] = 0; + out_1823172811608312128[39] = 0; + out_1823172811608312128[40] = 0; + out_1823172811608312128[41] = 0; + out_1823172811608312128[42] = 0; + out_1823172811608312128[43] = 0; + out_1823172811608312128[44] = 0; + out_1823172811608312128[45] = 0; + out_1823172811608312128[46] = 0; + out_1823172811608312128[47] = 0; + out_1823172811608312128[48] = 0; + out_1823172811608312128[49] = 0; + out_1823172811608312128[50] = 0; + out_1823172811608312128[51] = 0; + out_1823172811608312128[52] = 0; + out_1823172811608312128[53] = 0; + out_1823172811608312128[54] = 0; + out_1823172811608312128[55] = 0; + out_1823172811608312128[56] = 1; + out_1823172811608312128[57] = 0; + out_1823172811608312128[58] = 0; + out_1823172811608312128[59] = 0; + out_1823172811608312128[60] = 0; + out_1823172811608312128[61] = 0; + out_1823172811608312128[62] = 0; + out_1823172811608312128[63] = 0; + out_1823172811608312128[64] = 0; + out_1823172811608312128[65] = 0; +} +void h_33(double *state, double *unused, double *out_3622091043585692181) { + out_3622091043585692181[0] = state[16]; + out_3622091043585692181[1] = state[17]; + out_3622091043585692181[2] = state[18]; +} +void H_33(double *state, double *unused, double *out_4452856603773562207) { + out_4452856603773562207[0] = 0; + out_4452856603773562207[1] = 0; + out_4452856603773562207[2] = 0; + out_4452856603773562207[3] = 0; + out_4452856603773562207[4] = 0; + out_4452856603773562207[5] = 0; + out_4452856603773562207[6] = 0; + out_4452856603773562207[7] = 0; + out_4452856603773562207[8] = 0; + out_4452856603773562207[9] = 0; + out_4452856603773562207[10] = 0; + out_4452856603773562207[11] = 0; + out_4452856603773562207[12] = 0; + out_4452856603773562207[13] = 0; + out_4452856603773562207[14] = 0; + out_4452856603773562207[15] = 0; + out_4452856603773562207[16] = 1; + out_4452856603773562207[17] = 0; + out_4452856603773562207[18] = 0; + out_4452856603773562207[19] = 0; + out_4452856603773562207[20] = 0; + out_4452856603773562207[21] = 0; + out_4452856603773562207[22] = 0; + out_4452856603773562207[23] = 0; + out_4452856603773562207[24] = 0; + out_4452856603773562207[25] = 0; + out_4452856603773562207[26] = 0; + out_4452856603773562207[27] = 0; + out_4452856603773562207[28] = 0; + out_4452856603773562207[29] = 0; + out_4452856603773562207[30] = 0; + out_4452856603773562207[31] = 0; + out_4452856603773562207[32] = 0; + out_4452856603773562207[33] = 0; + out_4452856603773562207[34] = 0; + out_4452856603773562207[35] = 0; + out_4452856603773562207[36] = 0; + out_4452856603773562207[37] = 0; + out_4452856603773562207[38] = 0; + out_4452856603773562207[39] = 1; + out_4452856603773562207[40] = 0; + out_4452856603773562207[41] = 0; + out_4452856603773562207[42] = 0; + out_4452856603773562207[43] = 0; + out_4452856603773562207[44] = 0; + out_4452856603773562207[45] = 0; + out_4452856603773562207[46] = 0; + out_4452856603773562207[47] = 0; + out_4452856603773562207[48] = 0; + out_4452856603773562207[49] = 0; + out_4452856603773562207[50] = 0; + out_4452856603773562207[51] = 0; + out_4452856603773562207[52] = 0; + out_4452856603773562207[53] = 0; + out_4452856603773562207[54] = 0; + out_4452856603773562207[55] = 0; + out_4452856603773562207[56] = 0; + out_4452856603773562207[57] = 0; + out_4452856603773562207[58] = 0; + out_4452856603773562207[59] = 0; + out_4452856603773562207[60] = 0; + out_4452856603773562207[61] = 0; + out_4452856603773562207[62] = 1; + out_4452856603773562207[63] = 0; + out_4452856603773562207[64] = 0; + out_4452856603773562207[65] = 0; +} +#include +#include + +typedef Eigen::Matrix DDM; +typedef Eigen::Matrix EEM; +typedef Eigen::Matrix DEM; + +void predict(double *in_x, double *in_P, double *in_Q, double dt) { + typedef Eigen::Matrix RRM; + + double nx[DIM] = {0}; + double in_F[EDIM*EDIM] = {0}; + + // functions from sympy + f_fun(in_x, dt, nx); + F_fun(in_x, dt, in_F); + + + EEM F(in_F); + EEM P(in_P); + EEM Q(in_Q); + + RRM F_main = F.topLeftCorner(MEDIM, MEDIM); + P.topLeftCorner(MEDIM, MEDIM) = (F_main * P.topLeftCorner(MEDIM, MEDIM)) * F_main.transpose(); + P.topRightCorner(MEDIM, EDIM - MEDIM) = F_main * P.topRightCorner(MEDIM, EDIM - MEDIM); + P.bottomLeftCorner(EDIM - MEDIM, MEDIM) = P.bottomLeftCorner(EDIM - MEDIM, MEDIM) * F_main.transpose(); + + P = P + dt*Q; + + // copy out state + memcpy(in_x, nx, DIM * sizeof(double)); + memcpy(in_P, P.data(), EDIM * EDIM * sizeof(double)); +} + +// note: extra_args dim only correct when null space projecting +// otherwise 1 +template +void update(double *in_x, double *in_P, Hfun h_fun, Hfun H_fun, Hfun Hea_fun, double *in_z, double *in_R, double *in_ea, double MAHA_THRESHOLD) { + typedef Eigen::Matrix ZZM; + typedef Eigen::Matrix ZDM; + typedef Eigen::Matrix XEM; + //typedef Eigen::Matrix EZM; + typedef Eigen::Matrix X1M; + typedef Eigen::Matrix XXM; + + double in_hx[ZDIM] = {0}; + double in_H[ZDIM * DIM] = {0}; + double in_H_mod[EDIM * DIM] = {0}; + double delta_x[EDIM] = {0}; + double x_new[DIM] = {0}; + + + // state x, P + Eigen::Matrix z(in_z); + EEM P(in_P); + ZZM pre_R(in_R); + + // functions from sympy + h_fun(in_x, in_ea, in_hx); + H_fun(in_x, in_ea, in_H); + ZDM pre_H(in_H); + + // get y (y = z - hx) + Eigen::Matrix pre_y(in_hx); pre_y = z - pre_y; + X1M y; XXM H; XXM R; + if (Hea_fun){ + typedef Eigen::Matrix ZAM; + double in_Hea[ZDIM * EADIM] = {0}; + Hea_fun(in_x, in_ea, in_Hea); + ZAM Hea(in_Hea); + XXM A = Hea.transpose().fullPivLu().kernel(); + + + y = A.transpose() * pre_y; + H = A.transpose() * pre_H; + R = A.transpose() * pre_R * A; + } else { + y = pre_y; + H = pre_H; + R = pre_R; + } + // get modified H + H_mod_fun(in_x, in_H_mod); + DEM H_mod(in_H_mod); + XEM H_err = H * H_mod; + + // Do mahalobis distance test + if (MAHA_TEST){ + XXM a = (H_err * P * H_err.transpose() + R).inverse(); + double maha_dist = y.transpose() * a * y; + if (maha_dist > MAHA_THRESHOLD){ + R = 1.0e16 * R; + } + } + + // Outlier resilient weighting + double weight = 1;//(1.5)/(1 + y.squaredNorm()/R.sum()); + + // kalman gains and I_KH + XXM S = ((H_err * P) * H_err.transpose()) + R/weight; + XEM KT = S.fullPivLu().solve(H_err * P.transpose()); + //EZM K = KT.transpose(); TODO: WHY DOES THIS NOT COMPILE? + //EZM K = S.fullPivLu().solve(H_err * P.transpose()).transpose(); + //std::cout << "Here is the matrix rot:\n" << K << std::endl; + EEM I_KH = Eigen::Matrix::Identity() - (KT.transpose() * H_err); + + // update state by injecting dx + Eigen::Matrix dx(delta_x); + dx = (KT.transpose() * y); + memcpy(delta_x, dx.data(), EDIM * sizeof(double)); + err_fun(in_x, delta_x, x_new); + Eigen::Matrix x(x_new); + + // update cov + P = ((I_KH * P) * I_KH.transpose()) + ((KT.transpose() * R) * KT); + + // copy out state + memcpy(in_x, x.data(), DIM * sizeof(double)); + memcpy(in_P, P.data(), EDIM * EDIM * sizeof(double)); + memcpy(in_z, y.data(), y.rows() * sizeof(double)); +} + + + + +} +extern "C" { + +void live_update_4(double *in_x, double *in_P, double *in_z, double *in_R, double *in_ea) { + update<3, 3, 0>(in_x, in_P, h_4, H_4, NULL, in_z, in_R, in_ea, MAHA_THRESH_4); +} +void live_update_9(double *in_x, double *in_P, double *in_z, double *in_R, double *in_ea) { + update<3, 3, 0>(in_x, in_P, h_9, H_9, NULL, in_z, in_R, in_ea, MAHA_THRESH_9); +} +void live_update_10(double *in_x, double *in_P, double *in_z, double *in_R, double *in_ea) { + update<3, 3, 0>(in_x, in_P, h_10, H_10, NULL, in_z, in_R, in_ea, MAHA_THRESH_10); +} +void live_update_12(double *in_x, double *in_P, double *in_z, double *in_R, double *in_ea) { + update<3, 3, 0>(in_x, in_P, h_12, H_12, NULL, in_z, in_R, in_ea, MAHA_THRESH_12); +} +void live_update_35(double *in_x, double *in_P, double *in_z, double *in_R, double *in_ea) { + update<3, 3, 0>(in_x, in_P, h_35, H_35, NULL, in_z, in_R, in_ea, MAHA_THRESH_35); +} +void live_update_32(double *in_x, double *in_P, double *in_z, double *in_R, double *in_ea) { + update<4, 3, 0>(in_x, in_P, h_32, H_32, NULL, in_z, in_R, in_ea, MAHA_THRESH_32); +} +void live_update_13(double *in_x, double *in_P, double *in_z, double *in_R, double *in_ea) { + update<3, 3, 0>(in_x, in_P, h_13, H_13, NULL, in_z, in_R, in_ea, MAHA_THRESH_13); +} +void live_update_14(double *in_x, double *in_P, double *in_z, double *in_R, double *in_ea) { + update<3, 3, 0>(in_x, in_P, h_14, H_14, NULL, in_z, in_R, in_ea, MAHA_THRESH_14); +} +void live_update_33(double *in_x, double *in_P, double *in_z, double *in_R, double *in_ea) { + update<3, 3, 0>(in_x, in_P, h_33, H_33, NULL, in_z, in_R, in_ea, MAHA_THRESH_33); +} +void live_H(double *in_vec, double *out_3655759921532451903) { + H(in_vec, out_3655759921532451903); +} +void live_err_fun(double *nom_x, double *delta_x, double *out_6606438496319011893) { + err_fun(nom_x, delta_x, out_6606438496319011893); +} +void live_inv_err_fun(double *nom_x, double *true_x, double *out_1892773414432101423) { + inv_err_fun(nom_x, true_x, out_1892773414432101423); +} +void live_H_mod_fun(double *state, double *out_31505903139368806) { + H_mod_fun(state, out_31505903139368806); +} +void live_f_fun(double *state, double dt, double *out_4984514158829912596) { + f_fun(state, dt, out_4984514158829912596); +} +void live_F_fun(double *state, double dt, double *out_495900107318952904) { + F_fun(state, dt, out_495900107318952904); +} +void live_h_4(double *state, double *unused, double *out_4218409302925889705) { + h_4(state, unused, out_4218409302925889705); +} +void live_H_4(double *state, double *unused, double *out_2064362458237902773) { + H_4(state, unused, out_2064362458237902773); +} +void live_h_9(double *state, double *unused, double *out_4201404494137813277) { + h_9(state, unused, out_4201404494137813277); +} +void live_H_9(double *state, double *unused, double *out_1823172811608312128) { + H_9(state, unused, out_1823172811608312128); +} +void live_h_10(double *state, double *unused, double *out_4904878276509257913) { + h_10(state, unused, out_4904878276509257913); +} +void live_H_10(double *state, double *unused, double *out_7361770315712994123) { + H_10(state, unused, out_7361770315712994123); +} +void live_h_12(double *state, double *unused, double *out_3237267128515768115) { + h_12(state, unused, out_3237267128515768115); +} +void live_H_12(double *state, double *unused, double *out_2955093949794059022) { + H_12(state, unused, out_2955093949794059022); +} +void live_h_35(double *state, double *unused, double *out_9093746190498438204) { + h_35(state, unused, out_9093746190498438204); +} +void live_H_35(double *state, double *unused, double *out_1302299599134704603) { + H_35(state, unused, out_1302299599134704603); +} +void live_h_32(double *state, double *unused, double *out_5484223878963608382) { + h_32(state, unused, out_5484223878963608382); +} +void live_H_32(double *state, double *unused, double *out_5612564904559411753) { + H_32(state, unused, out_5612564904559411753); +} +void live_h_13(double *state, double *unused, double *out_7023021544313133462) { + h_13(state, unused, out_7023021544313133462); +} +void live_H_13(double *state, double *unused, double *out_6405415510614721399) { + H_13(state, unused, out_6405415510614721399); +} +void live_h_14(double *state, double *unused, double *out_4201404494137813277) { + h_14(state, unused, out_4201404494137813277); +} +void live_H_14(double *state, double *unused, double *out_1823172811608312128) { + H_14(state, unused, out_1823172811608312128); +} +void live_h_33(double *state, double *unused, double *out_3622091043585692181) { + h_33(state, unused, out_3622091043585692181); +} +void live_H_33(double *state, double *unused, double *out_4452856603773562207) { + H_33(state, unused, out_4452856603773562207); +} +void live_predict(double *in_x, double *in_P, double *in_Q, double dt) { + predict(in_x, in_P, in_Q, dt); +} +} + +const EKF live = { + .name = "live", + .kinds = { 4, 9, 10, 12, 35, 32, 13, 14, 33 }, + .feature_kinds = { }, + .f_fun = live_f_fun, + .F_fun = live_F_fun, + .err_fun = live_err_fun, + .inv_err_fun = live_inv_err_fun, + .H_mod_fun = live_H_mod_fun, + .predict = live_predict, + .hs = { + { 4, live_h_4 }, + { 9, live_h_9 }, + { 10, live_h_10 }, + { 12, live_h_12 }, + { 35, live_h_35 }, + { 32, live_h_32 }, + { 13, live_h_13 }, + { 14, live_h_14 }, + { 33, live_h_33 }, + }, + .Hs = { + { 4, live_H_4 }, + { 9, live_H_9 }, + { 10, live_H_10 }, + { 12, live_H_12 }, + { 35, live_H_35 }, + { 32, live_H_32 }, + { 13, live_H_13 }, + { 14, live_H_14 }, + { 33, live_H_33 }, + }, + .updates = { + { 4, live_update_4 }, + { 9, live_update_9 }, + { 10, live_update_10 }, + { 12, live_update_12 }, + { 35, live_update_35 }, + { 32, live_update_32 }, + { 13, live_update_13 }, + { 14, live_update_14 }, + { 33, live_update_33 }, + }, + .Hes = { + }, + .sets = { + }, + .extra_routines = { + { "H", live_H }, + }, +}; + +ekf_lib_init(live) diff --git a/selfdrive/locationd/models/live_kf.cc b/selfdrive/locationd/models/live_kf.cc deleted file mode 100644 index fc3bfb7..0000000 --- a/selfdrive/locationd/models/live_kf.cc +++ /dev/null @@ -1,122 +0,0 @@ -#include "selfdrive/locationd/models/live_kf.h" - -using namespace EKFS; -using namespace Eigen; - -Eigen::Map get_mapvec(const Eigen::VectorXd &vec) { - return Eigen::Map((double*)vec.data(), vec.rows(), vec.cols()); -} - -Eigen::Map get_mapmat(const MatrixXdr &mat) { - return Eigen::Map((double*)mat.data(), mat.rows(), mat.cols()); -} - -std::vector> get_vec_mapvec(const std::vector &vec_vec) { - std::vector> res; - for (const Eigen::VectorXd &vec : vec_vec) { - res.push_back(get_mapvec(vec)); - } - return res; -} - -std::vector> get_vec_mapmat(const std::vector &mat_vec) { - std::vector> res; - for (const MatrixXdr &mat : mat_vec) { - res.push_back(get_mapmat(mat)); - } - return res; -} - -LiveKalman::LiveKalman() { - this->dim_state = live_initial_x.rows(); - this->dim_state_err = live_initial_P_diag.rows(); - - this->initial_x = live_initial_x; - this->initial_P = live_initial_P_diag.asDiagonal(); - this->fake_gps_pos_cov = live_fake_gps_pos_cov_diag.asDiagonal(); - this->fake_gps_vel_cov = live_fake_gps_vel_cov_diag.asDiagonal(); - this->reset_orientation_P = live_reset_orientation_diag.asDiagonal(); - this->Q = live_Q_diag.asDiagonal(); - for (auto& pair : live_obs_noise_diag) { - this->obs_noise[pair.first] = pair.second.asDiagonal(); - } - - // init filter - this->filter = std::make_shared(this->name, get_mapmat(this->Q), get_mapvec(this->initial_x), - get_mapmat(initial_P), this->dim_state, this->dim_state_err, 0, 0, 0, std::vector(), - std::vector{3}, std::vector(), 0.8); -} - -void LiveKalman::init_state(const VectorXd &state, const VectorXd &covs_diag, double filter_time) { - MatrixXdr covs = covs_diag.asDiagonal(); - this->filter->init_state(get_mapvec(state), get_mapmat(covs), filter_time); -} - -void LiveKalman::init_state(const VectorXd &state, const MatrixXdr &covs, double filter_time) { - this->filter->init_state(get_mapvec(state), get_mapmat(covs), filter_time); -} - -void LiveKalman::init_state(const VectorXd &state, double filter_time) { - MatrixXdr covs = this->filter->covs(); - this->filter->init_state(get_mapvec(state), get_mapmat(covs), filter_time); -} - -VectorXd LiveKalman::get_x() { - return this->filter->state(); -} - -MatrixXdr LiveKalman::get_P() { - return this->filter->covs(); -} - -double LiveKalman::get_filter_time() { - return this->filter->get_filter_time(); -} - -std::vector LiveKalman::get_R(int kind, int n) { - std::vector R; - for (int i = 0; i < n; i++) { - R.push_back(this->obs_noise[kind]); - } - return R; -} - -std::optional LiveKalman::predict_and_observe(double t, int kind, const std::vector &meas, std::vector R) { - std::optional r; - if (R.size() == 0) { - R = this->get_R(kind, meas.size()); - } - r = this->filter->predict_and_update_batch(t, kind, get_vec_mapvec(meas), get_vec_mapmat(R)); - return r; -} - -void LiveKalman::predict(double t) { - this->filter->predict(t); -} - -const Eigen::VectorXd &LiveKalman::get_initial_x() { - return this->initial_x; -} - -const MatrixXdr &LiveKalman::get_initial_P() { - return this->initial_P; -} - -const MatrixXdr &LiveKalman::get_fake_gps_pos_cov() { - return this->fake_gps_pos_cov; -} - -const MatrixXdr &LiveKalman::get_fake_gps_vel_cov() { - return this->fake_gps_vel_cov; -} - -const MatrixXdr &LiveKalman::get_reset_orientation_P() { - return this->reset_orientation_P; -} - -MatrixXdr LiveKalman::H(const VectorXd &in) { - assert(in.size() == 6); - Matrix res; - this->filter->get_extra_routine("H")((double*)in.data(), res.data()); - return res; -} diff --git a/selfdrive/locationd/models/live_kf.h b/selfdrive/locationd/models/live_kf.h deleted file mode 100644 index e4b3e32..0000000 --- a/selfdrive/locationd/models/live_kf.h +++ /dev/null @@ -1,66 +0,0 @@ -#pragma once - -#include -#include -#include -#include -#include - -#include -#include - -#include "generated/live_kf_constants.h" -#include "rednose/helpers/ekf_sym.h" - -#define EARTH_GM 3.986005e14 // m^3/s^2 (gravitational constant * mass of earth) - -using namespace EKFS; - -Eigen::Map get_mapvec(const Eigen::VectorXd &vec); -Eigen::Map get_mapmat(const MatrixXdr &mat); -std::vector> get_vec_mapvec(const std::vector &vec_vec); -std::vector> get_vec_mapmat(const std::vector &mat_vec); - -class LiveKalman { -public: - LiveKalman(); - - void init_state(const Eigen::VectorXd &state, const Eigen::VectorXd &covs_diag, double filter_time); - void init_state(const Eigen::VectorXd &state, const MatrixXdr &covs, double filter_time); - void init_state(const Eigen::VectorXd &state, double filter_time); - - Eigen::VectorXd get_x(); - MatrixXdr get_P(); - double get_filter_time(); - std::vector get_R(int kind, int n); - - std::optional predict_and_observe(double t, int kind, const std::vector &meas, std::vector R = {}); - std::optional predict_and_update_odo_speed(std::vector speed, double t, int kind); - std::optional predict_and_update_odo_trans(std::vector trans, double t, int kind); - std::optional predict_and_update_odo_rot(std::vector rot, double t, int kind); - void predict(double t); - - const Eigen::VectorXd &get_initial_x(); - const MatrixXdr &get_initial_P(); - const MatrixXdr &get_fake_gps_pos_cov(); - const MatrixXdr &get_fake_gps_vel_cov(); - const MatrixXdr &get_reset_orientation_P(); - - MatrixXdr H(const Eigen::VectorXd &in); - -private: - std::string name = "live"; - - std::shared_ptr filter; - - int dim_state; - int dim_state_err; - - Eigen::VectorXd initial_x; - MatrixXdr initial_P; - MatrixXdr fake_gps_pos_cov; - MatrixXdr fake_gps_vel_cov; - MatrixXdr reset_orientation_P; - MatrixXdr Q; // process noise - std::unordered_map obs_noise; -}; diff --git a/selfdrive/locationd/test/.gitignore b/selfdrive/locationd/test/.gitignore deleted file mode 100644 index 89f9ac0..0000000 --- a/selfdrive/locationd/test/.gitignore +++ /dev/null @@ -1 +0,0 @@ -out/ diff --git a/selfdrive/locationd/test/__init__.py b/selfdrive/locationd/test/__init__.py deleted file mode 100644 index e69de29..0000000 diff --git a/selfdrive/locationd/test/test_calibrationd.py b/selfdrive/locationd/test/test_calibrationd.py deleted file mode 100644 index e2db094..0000000 --- a/selfdrive/locationd/test/test_calibrationd.py +++ /dev/null @@ -1,117 +0,0 @@ -#!/usr/bin/env python3 -import random -import unittest - -import numpy as np - -import cereal.messaging as messaging -from cereal import log -from openpilot.common.params import Params -from openpilot.selfdrive.locationd.calibrationd import Calibrator, INPUTS_NEEDED, INPUTS_WANTED, BLOCK_SIZE, MIN_SPEED_FILTER, \ - MAX_YAW_RATE_FILTER, SMOOTH_CYCLES, HEIGHT_INIT, MAX_ALLOWED_PITCH_SPREAD, MAX_ALLOWED_YAW_SPREAD - - -def process_messages(c, cam_odo_calib, cycles, - cam_odo_speed=MIN_SPEED_FILTER + 1, - carstate_speed=MIN_SPEED_FILTER + 1, - cam_odo_yr=0.0, - cam_odo_speed_std=1e-3, - cam_odo_height_std=1e-3): - old_rpy_weight_prev = 0.0 - for _ in range(cycles): - assert (old_rpy_weight_prev - c.old_rpy_weight < 1/SMOOTH_CYCLES + 1e-3) - old_rpy_weight_prev = c.old_rpy_weight - c.handle_v_ego(carstate_speed) - c.handle_cam_odom([cam_odo_speed, - np.sin(cam_odo_calib[2]) * cam_odo_speed, - -np.sin(cam_odo_calib[1]) * cam_odo_speed], - [0.0, 0.0, cam_odo_yr], - [0.0, 0.0, 0.0], - [cam_odo_speed_std, cam_odo_speed_std, cam_odo_speed_std], - [0.0, 0.0, HEIGHT_INIT.item()], - [cam_odo_height_std, cam_odo_height_std, cam_odo_height_std]) - -class TestCalibrationd(unittest.TestCase): - - def test_read_saved_params(self): - msg = messaging.new_message('liveCalibration') - msg.liveCalibration.validBlocks = random.randint(1, 10) - msg.liveCalibration.rpyCalib = [random.random() for _ in range(3)] - msg.liveCalibration.height = [random.random() for _ in range(1)] - Params().put("CalibrationParams", msg.to_bytes()) - c = Calibrator(param_put=True) - - np.testing.assert_allclose(msg.liveCalibration.rpyCalib, c.rpy) - np.testing.assert_allclose(msg.liveCalibration.height, c.height) - self.assertEqual(msg.liveCalibration.validBlocks, c.valid_blocks) - - - def test_calibration_basics(self): - c = Calibrator(param_put=False) - process_messages(c, [0.0, 0.0, 0.0], BLOCK_SIZE * INPUTS_WANTED) - self.assertEqual(c.valid_blocks, INPUTS_WANTED) - np.testing.assert_allclose(c.rpy, np.zeros(3)) - np.testing.assert_allclose(c.height, HEIGHT_INIT) - c.reset() - - - def test_calibration_low_speed_reject(self): - c = Calibrator(param_put=False) - process_messages(c, [0.0, 0.0, 0.0], BLOCK_SIZE * INPUTS_WANTED, cam_odo_speed=MIN_SPEED_FILTER - 1) - process_messages(c, [0.0, 0.0, 0.0], BLOCK_SIZE * INPUTS_WANTED, carstate_speed=MIN_SPEED_FILTER - 1) - self.assertEqual(c.valid_blocks, 0) - np.testing.assert_allclose(c.rpy, np.zeros(3)) - np.testing.assert_allclose(c.height, HEIGHT_INIT) - - - def test_calibration_yaw_rate_reject(self): - c = Calibrator(param_put=False) - process_messages(c, [0.0, 0.0, 0.0], BLOCK_SIZE * INPUTS_WANTED, cam_odo_yr=MAX_YAW_RATE_FILTER) - self.assertEqual(c.valid_blocks, 0) - np.testing.assert_allclose(c.rpy, np.zeros(3)) - np.testing.assert_allclose(c.height, HEIGHT_INIT) - - - def test_calibration_speed_std_reject(self): - c = Calibrator(param_put=False) - process_messages(c, [0.0, 0.0, 0.0], BLOCK_SIZE * INPUTS_WANTED, cam_odo_speed_std=1e3) - self.assertEqual(c.valid_blocks, INPUTS_NEEDED) - np.testing.assert_allclose(c.rpy, np.zeros(3)) - - - def test_calibration_speed_std_height_reject(self): - c = Calibrator(param_put=False) - process_messages(c, [0.0, 0.0, 0.0], BLOCK_SIZE * INPUTS_WANTED, cam_odo_height_std=1e3) - self.assertEqual(c.valid_blocks, INPUTS_NEEDED) - np.testing.assert_allclose(c.rpy, np.zeros(3)) - - - def test_calibration_auto_reset(self): - c = Calibrator(param_put=False) - process_messages(c, [0.0, 0.0, 0.0], BLOCK_SIZE * INPUTS_NEEDED) - self.assertEqual(c.valid_blocks, INPUTS_NEEDED) - np.testing.assert_allclose(c.rpy, [0.0, 0.0, 0.0], atol=1e-3) - process_messages(c, [0.0, MAX_ALLOWED_PITCH_SPREAD*0.9, MAX_ALLOWED_YAW_SPREAD*0.9], BLOCK_SIZE + 10) - self.assertEqual(c.valid_blocks, INPUTS_NEEDED + 1) - self.assertEqual(c.cal_status, log.LiveCalibrationData.Status.calibrated) - - c = Calibrator(param_put=False) - process_messages(c, [0.0, 0.0, 0.0], BLOCK_SIZE * INPUTS_NEEDED) - self.assertEqual(c.valid_blocks, INPUTS_NEEDED) - np.testing.assert_allclose(c.rpy, [0.0, 0.0, 0.0]) - process_messages(c, [0.0, MAX_ALLOWED_PITCH_SPREAD*1.1, 0.0], BLOCK_SIZE + 10) - self.assertEqual(c.valid_blocks, 1) - self.assertEqual(c.cal_status, log.LiveCalibrationData.Status.recalibrating) - np.testing.assert_allclose(c.rpy, [0.0, MAX_ALLOWED_PITCH_SPREAD*1.1, 0.0], atol=1e-2) - - c = Calibrator(param_put=False) - process_messages(c, [0.0, 0.0, 0.0], BLOCK_SIZE * INPUTS_NEEDED) - self.assertEqual(c.valid_blocks, INPUTS_NEEDED) - np.testing.assert_allclose(c.rpy, [0.0, 0.0, 0.0]) - process_messages(c, [0.0, 0.0, MAX_ALLOWED_YAW_SPREAD*1.1], BLOCK_SIZE + 10) - self.assertEqual(c.valid_blocks, 1) - self.assertEqual(c.cal_status, log.LiveCalibrationData.Status.recalibrating) - np.testing.assert_allclose(c.rpy, [0.0, 0.0, MAX_ALLOWED_YAW_SPREAD*1.1], atol=1e-2) - -if __name__ == "__main__": - unittest.main() diff --git a/selfdrive/locationd/test/test_locationd.py b/selfdrive/locationd/test/test_locationd.py deleted file mode 100644 index 78de921..0000000 --- a/selfdrive/locationd/test/test_locationd.py +++ /dev/null @@ -1,94 +0,0 @@ -#!/usr/bin/env python3 -import json -import random -import unittest -import time -import capnp - -import cereal.messaging as messaging -from cereal.services import SERVICE_LIST -from openpilot.common.params import Params -from openpilot.common.transformations.coordinates import ecef2geodetic - -from openpilot.selfdrive.manager.process_config import managed_processes - - -class TestLocationdProc(unittest.TestCase): - LLD_MSGS = ['gpsLocationExternal', 'cameraOdometry', 'carState', 'liveCalibration', - 'accelerometer', 'gyroscope', 'magnetometer'] - - def setUp(self): - random.seed(123489234) - - self.pm = messaging.PubMaster(self.LLD_MSGS) - - self.params = Params() - self.params.put_bool("UbloxAvailable", True) - managed_processes['locationd'].prepare() - managed_processes['locationd'].start() - - def tearDown(self): - managed_processes['locationd'].stop() - - def get_msg(self, name, t): - try: - msg = messaging.new_message(name) - except capnp.lib.capnp.KjException: - msg = messaging.new_message(name, 0) - - if name == "gpsLocationExternal": - msg.gpsLocationExternal.flags = 1 - msg.gpsLocationExternal.verticalAccuracy = 1.0 - msg.gpsLocationExternal.speedAccuracy = 1.0 - msg.gpsLocationExternal.bearingAccuracyDeg = 1.0 - msg.gpsLocationExternal.vNED = [0.0, 0.0, 0.0] - msg.gpsLocationExternal.latitude = float(self.lat) - msg.gpsLocationExternal.longitude = float(self.lon) - msg.gpsLocationExternal.unixTimestampMillis = t * 1e6 - msg.gpsLocationExternal.altitude = float(self.alt) - #if name == "gnssMeasurements": - # msg.gnssMeasurements.measTime = t - # msg.gnssMeasurements.positionECEF.value = [self.x , self.y, self.z] - # msg.gnssMeasurements.positionECEF.std = [0,0,0] - # msg.gnssMeasurements.positionECEF.valid = True - # msg.gnssMeasurements.velocityECEF.value = [] - # msg.gnssMeasurements.velocityECEF.std = [0,0,0] - # msg.gnssMeasurements.velocityECEF.valid = True - elif name == 'cameraOdometry': - msg.cameraOdometry.rot = [0.0, 0.0, 0.0] - msg.cameraOdometry.rotStd = [0.0, 0.0, 0.0] - msg.cameraOdometry.trans = [0.0, 0.0, 0.0] - msg.cameraOdometry.transStd = [0.0, 0.0, 0.0] - msg.logMonoTime = t - msg.valid = True - return msg - - def test_params_gps(self): - self.params.remove('LastGPSPosition') - - self.x = -2710700 + (random.random() * 1e5) - self.y = -4280600 + (random.random() * 1e5) - self.z = 3850300 + (random.random() * 1e5) - self.lat, self.lon, self.alt = ecef2geodetic([self.x, self.y, self.z]) - - # get fake messages at the correct frequency, listed in services.py - msgs = [] - for sec in range(65): - for name in self.LLD_MSGS: - for j in range(int(SERVICE_LIST[name].frequency)): - msgs.append(self.get_msg(name, int((sec + j / SERVICE_LIST[name].frequency) * 1e9))) - - for msg in sorted(msgs, key=lambda x: x.logMonoTime): - self.pm.send(msg.which(), msg) - if msg.which() == "cameraOdometry": - self.pm.wait_for_readers_to_update(msg.which(), 0.1, dt=0.005) - time.sleep(1) # wait for async params write - - lastGPS = json.loads(self.params.get('LastGPSPosition')) - self.assertAlmostEqual(lastGPS['latitude'], self.lat, places=3) - self.assertAlmostEqual(lastGPS['longitude'], self.lon, places=3) - self.assertAlmostEqual(lastGPS['altitude'], self.alt, places=3) - - -if __name__ == "__main__": - unittest.main() diff --git a/selfdrive/locationd/test/test_locationd_scenarios.py b/selfdrive/locationd/test/test_locationd_scenarios.py deleted file mode 100644 index f48c83c..0000000 --- a/selfdrive/locationd/test/test_locationd_scenarios.py +++ /dev/null @@ -1,228 +0,0 @@ -#!/usr/bin/env python3 -import pytest -import unittest -import numpy as np -from collections import defaultdict -from enum import Enum - -from openpilot.tools.lib.logreader import LogReader -from openpilot.selfdrive.test.process_replay.process_replay import replay_process_with_name - -TEST_ROUTE = "ff2bd20623fcaeaa|2023-09-05--10-14-54/4" -GPS_MESSAGES = ['gpsLocationExternal', 'gpsLocation'] -SELECT_COMPARE_FIELDS = { - 'yaw_rate': ['angularVelocityCalibrated', 'value', 2], - 'roll': ['orientationNED', 'value', 0], - 'gps_flag': ['gpsOK'], - 'inputs_flag': ['inputsOK'], - 'sensors_flag': ['sensorsOK'], -} -JUNK_IDX = 100 - - -class Scenario(Enum): - BASE = 'base' - GPS_OFF = 'gps_off' - GPS_OFF_MIDWAY = 'gps_off_midway' - GPS_ON_MIDWAY = 'gps_on_midway' - GPS_TUNNEL = 'gps_tunnel' - GYRO_OFF = 'gyro_off' - GYRO_SPIKE_MIDWAY = 'gyro_spike_midway' - ACCEL_OFF = 'accel_off' - ACCEL_SPIKE_MIDWAY = 'accel_spike_midway' - - -def get_select_fields_data(logs): - def get_nested_keys(msg, keys): - val = None - for key in keys: - val = getattr(msg if val is None else val, key) if isinstance(key, str) else val[key] - return val - llk = [x.liveLocationKalman for x in logs if x.which() == 'liveLocationKalman'] - data = defaultdict(list) - for msg in llk: - for key, fields in SELECT_COMPARE_FIELDS.items(): - data[key].append(get_nested_keys(msg, fields)) - for key in data: - data[key] = np.array(data[key][JUNK_IDX:], dtype=float) - return data - - -def run_scenarios(scenario, logs): - if scenario == Scenario.BASE: - pass - - elif scenario == Scenario.GPS_OFF: - logs = sorted([x for x in logs if x.which() not in GPS_MESSAGES], key=lambda x: x.logMonoTime) - - elif scenario == Scenario.GPS_OFF_MIDWAY: - non_gps = [x for x in logs if x.which() not in GPS_MESSAGES] - gps = [x for x in logs if x.which() in GPS_MESSAGES] - logs = sorted(non_gps + gps[: len(gps) // 2], key=lambda x: x.logMonoTime) - - elif scenario == Scenario.GPS_ON_MIDWAY: - non_gps = [x for x in logs if x.which() not in GPS_MESSAGES] - gps = [x for x in logs if x.which() in GPS_MESSAGES] - logs = sorted(non_gps + gps[len(gps) // 2:], key=lambda x: x.logMonoTime) - - elif scenario == Scenario.GPS_TUNNEL: - non_gps = [x for x in logs if x.which() not in GPS_MESSAGES] - gps = [x for x in logs if x.which() in GPS_MESSAGES] - logs = sorted(non_gps + gps[:len(gps) // 4] + gps[-len(gps) // 4:], key=lambda x: x.logMonoTime) - - elif scenario == Scenario.GYRO_OFF: - logs = sorted([x for x in logs if x.which() != 'gyroscope'], key=lambda x: x.logMonoTime) - - elif scenario == Scenario.GYRO_SPIKE_MIDWAY: - non_gyro = [x for x in logs if x.which() not in 'gyroscope'] - gyro = [x for x in logs if x.which() in 'gyroscope'] - temp = gyro[len(gyro) // 2].as_builder() - temp.gyroscope.gyroUncalibrated.v[0] += 3.0 - gyro[len(gyro) // 2] = temp.as_reader() - logs = sorted(non_gyro + gyro, key=lambda x: x.logMonoTime) - - elif scenario == Scenario.ACCEL_OFF: - logs = sorted([x for x in logs if x.which() != 'accelerometer'], key=lambda x: x.logMonoTime) - - elif scenario == Scenario.ACCEL_SPIKE_MIDWAY: - non_accel = [x for x in logs if x.which() not in 'accelerometer'] - accel = [x for x in logs if x.which() in 'accelerometer'] - temp = accel[len(accel) // 2].as_builder() - temp.accelerometer.acceleration.v[0] += 10.0 - accel[len(accel) // 2] = temp.as_reader() - logs = sorted(non_accel + accel, key=lambda x: x.logMonoTime) - - replayed_logs = replay_process_with_name(name='locationd', lr=logs) - return get_select_fields_data(logs), get_select_fields_data(replayed_logs) - - -@pytest.mark.xdist_group("test_locationd_scenarios") -@pytest.mark.shared_download_cache -class TestLocationdScenarios(unittest.TestCase): - """ - Test locationd with different scenarios. In all these scenarios, we expect the following: - - locationd kalman filter should never go unstable (we care mostly about yaw_rate, roll, gpsOK, inputsOK, sensorsOK) - - faulty values should be ignored, with appropriate flags set - """ - - @classmethod - def setUpClass(cls): - cls.logs = list(LogReader(TEST_ROUTE)) - - def test_base(self): - """ - Test: unchanged log - Expected Result: - - yaw_rate: unchanged - - roll: unchanged - """ - orig_data, replayed_data = run_scenarios(Scenario.BASE, self.logs) - self.assertTrue(np.allclose(orig_data['yaw_rate'], replayed_data['yaw_rate'], atol=np.radians(0.2))) - self.assertTrue(np.allclose(orig_data['roll'], replayed_data['roll'], atol=np.radians(0.5))) - - def test_gps_off(self): - """ - Test: no GPS message for the entire segment - Expected Result: - - yaw_rate: unchanged - - roll: - - gpsOK: False - """ - orig_data, replayed_data = run_scenarios(Scenario.GPS_OFF, self.logs) - self.assertTrue(np.allclose(orig_data['yaw_rate'], replayed_data['yaw_rate'], atol=np.radians(0.2))) - self.assertTrue(np.allclose(orig_data['roll'], replayed_data['roll'], atol=np.radians(0.5))) - self.assertTrue(np.all(replayed_data['gps_flag'] == 0.0)) - - def test_gps_off_midway(self): - """ - Test: no GPS message for the second half of the segment - Expected Result: - - yaw_rate: unchanged - - roll: - - gpsOK: True for the first half, False for the second half - """ - orig_data, replayed_data = run_scenarios(Scenario.GPS_OFF_MIDWAY, self.logs) - self.assertTrue(np.allclose(orig_data['yaw_rate'], replayed_data['yaw_rate'], atol=np.radians(0.2))) - self.assertTrue(np.allclose(orig_data['roll'], replayed_data['roll'], atol=np.radians(0.5))) - self.assertTrue(np.diff(replayed_data['gps_flag'])[512] == -1.0) - - def test_gps_on_midway(self): - """ - Test: no GPS message for the first half of the segment - Expected Result: - - yaw_rate: unchanged - - roll: - - gpsOK: False for the first half, True for the second half - """ - orig_data, replayed_data = run_scenarios(Scenario.GPS_ON_MIDWAY, self.logs) - self.assertTrue(np.allclose(orig_data['yaw_rate'], replayed_data['yaw_rate'], atol=np.radians(0.2))) - self.assertTrue(np.allclose(orig_data['roll'], replayed_data['roll'], atol=np.radians(1.5))) - self.assertTrue(np.diff(replayed_data['gps_flag'])[505] == 1.0) - - def test_gps_tunnel(self): - """ - Test: no GPS message for the middle section of the segment - Expected Result: - - yaw_rate: unchanged - - roll: - - gpsOK: False for the middle section, True for the rest - """ - orig_data, replayed_data = run_scenarios(Scenario.GPS_TUNNEL, self.logs) - self.assertTrue(np.allclose(orig_data['yaw_rate'], replayed_data['yaw_rate'], atol=np.radians(0.2))) - self.assertTrue(np.allclose(orig_data['roll'], replayed_data['roll'], atol=np.radians(0.5))) - self.assertTrue(np.diff(replayed_data['gps_flag'])[213] == -1.0) - self.assertTrue(np.diff(replayed_data['gps_flag'])[805] == 1.0) - - def test_gyro_off(self): - """ - Test: no gyroscope message for the entire segment - Expected Result: - - yaw_rate: 0 - - roll: 0 - - sensorsOK: False - """ - _, replayed_data = run_scenarios(Scenario.GYRO_OFF, self.logs) - self.assertTrue(np.allclose(replayed_data['yaw_rate'], 0.0)) - self.assertTrue(np.allclose(replayed_data['roll'], 0.0)) - self.assertTrue(np.all(replayed_data['sensors_flag'] == 0.0)) - - def test_gyro_spikes(self): - """ - Test: a gyroscope spike in the middle of the segment - Expected Result: - - yaw_rate: unchanged - - roll: unchanged - - inputsOK: False for some time after the spike, True for the rest - """ - orig_data, replayed_data = run_scenarios(Scenario.GYRO_SPIKE_MIDWAY, self.logs) - self.assertTrue(np.allclose(orig_data['yaw_rate'], replayed_data['yaw_rate'], atol=np.radians(0.2))) - self.assertTrue(np.allclose(orig_data['roll'], replayed_data['roll'], atol=np.radians(0.5))) - self.assertTrue(np.diff(replayed_data['inputs_flag'])[500] == -1.0) - self.assertTrue(np.diff(replayed_data['inputs_flag'])[694] == 1.0) - - def test_accel_off(self): - """ - Test: no accelerometer message for the entire segment - Expected Result: - - yaw_rate: 0 - - roll: 0 - - sensorsOK: False - """ - _, replayed_data = run_scenarios(Scenario.ACCEL_OFF, self.logs) - self.assertTrue(np.allclose(replayed_data['yaw_rate'], 0.0)) - self.assertTrue(np.allclose(replayed_data['roll'], 0.0)) - self.assertTrue(np.all(replayed_data['sensors_flag'] == 0.0)) - - def test_accel_spikes(self): - """ - ToDo: - Test: an accelerometer spike in the middle of the segment - Expected Result: Right now, the kalman filter is not robust to small spikes like it is to gyroscope spikes. - """ - orig_data, replayed_data = run_scenarios(Scenario.ACCEL_SPIKE_MIDWAY, self.logs) - self.assertTrue(np.allclose(orig_data['yaw_rate'], replayed_data['yaw_rate'], atol=np.radians(0.2))) - self.assertTrue(np.allclose(orig_data['roll'], replayed_data['roll'], atol=np.radians(0.5))) - - -if __name__ == "__main__": - unittest.main() diff --git a/selfdrive/manager/manager.py b/selfdrive/manager/manager.py index 776ff35..d750a7d 100755 --- a/selfdrive/manager/manager.py +++ b/selfdrive/manager/manager.py @@ -31,10 +31,6 @@ from openpilot.selfdrive.frogpilot.functions.frogpilot_functions import DEFAULT_ def manager_init() -> None: save_bootlog() - # Clear the error log on boot to prevent old errors from hanging around - if os.path.isfile(os.path.join(sentry.CRASHES_DIR, 'error.txt')): - os.remove(os.path.join(sentry.CRASHES_DIR, 'error.txt')) - params = Params() params_storage = Params("/persist/comma/params") params.clear_all(ParamKeyType.CLEAR_ON_MANAGER_START) @@ -389,14 +385,15 @@ def manager_thread() -> None: if started and not started_prev: params.clear_all(ParamKeyType.CLEAR_ON_ONROAD_TRANSITION) - elif not started and started_prev: - params.clear_all(ParamKeyType.CLEAR_ON_OFFROAD_TRANSITION) - params_memory.clear_all(ParamKeyType.CLEAR_ON_OFFROAD_TRANSITION) # Clear the error log on offroad transition to prevent old errors from hanging around if os.path.isfile(os.path.join(sentry.CRASHES_DIR, 'error.txt')): os.remove(os.path.join(sentry.CRASHES_DIR, 'error.txt')) + elif not started and started_prev: + params.clear_all(ParamKeyType.CLEAR_ON_OFFROAD_TRANSITION) + params_memory.clear_all(ParamKeyType.CLEAR_ON_OFFROAD_TRANSITION) + # update onroad params, which drives boardd's safety setter thread if started != started_prev: write_onroad_params(started, params) @@ -417,7 +414,7 @@ def manager_thread() -> None: # Exit main loop when uninstall/shutdown/reboot is needed shutdown = False - for param in ("DoUninstall", "DoShutdown", "DoReboot", "DoSoftReboot"): + for param in ("DoUninstall", "DoShutdown", "DoReboot"): if params.get_bool(param): shutdown = True params.put("LastManagerExitReason", f"{param} {datetime.datetime.now()}") @@ -493,9 +490,6 @@ def main() -> None: if params.get_bool("DoUninstall"): cloudlog.warning("uninstalling") HARDWARE.uninstall() - elif params.get_bool("DoSoftReboot"): - cloudlog.warning("softreboot") - HARDWARE.soft_reboot() elif params.get_bool("DoReboot"): cloudlog.warning("reboot") HARDWARE.reboot() diff --git a/selfdrive/manager/test/__init__.py b/selfdrive/manager/test/__init__.py deleted file mode 100644 index e69de29..0000000 diff --git a/selfdrive/manager/test/test_manager.py b/selfdrive/manager/test/test_manager.py deleted file mode 100755 index 1ae94b2..0000000 --- a/selfdrive/manager/test/test_manager.py +++ /dev/null @@ -1,82 +0,0 @@ -#!/usr/bin/env python3 -import os -import pytest -import signal -import time -import unittest - -from parameterized import parameterized - -from cereal import car -from openpilot.common.params import Params -import openpilot.selfdrive.manager.manager as manager -from openpilot.selfdrive.manager.process import ensure_running -from openpilot.selfdrive.manager.process_config import managed_processes -from openpilot.system.hardware import HARDWARE - -os.environ['FAKEUPLOAD'] = "1" - -MAX_STARTUP_TIME = 3 -BLACKLIST_PROCS = ['manage_athenad', 'pandad', 'pigeond'] - - -@pytest.mark.tici -class TestManager(unittest.TestCase): - def setUp(self): - HARDWARE.set_power_save(False) - - # ensure clean CarParams - params = Params() - params.clear_all() - - def tearDown(self): - manager.manager_cleanup() - - def test_manager_prepare(self): - os.environ['PREPAREONLY'] = '1' - manager.main() - - def test_blacklisted_procs(self): - # TODO: ensure there are blacklisted procs until we have a dedicated test - self.assertTrue(len(BLACKLIST_PROCS), "No blacklisted procs to test not_run") - - @parameterized.expand([(i,) for i in range(10)]) - def test_startup_time(self, index): - start = time.monotonic() - os.environ['PREPAREONLY'] = '1' - manager.main() - t = time.monotonic() - start - assert t < MAX_STARTUP_TIME, f"startup took {t}s, expected <{MAX_STARTUP_TIME}s" - - @unittest.skip("this test is flaky the way it's currently written, should be moved to test_onroad") - def test_clean_exit(self): - """ - Ensure all processes exit cleanly when stopped. - """ - HARDWARE.set_power_save(False) - manager.manager_init() - - CP = car.CarParams.new_message() - procs = ensure_running(managed_processes.values(), True, Params(), CP, not_run=BLACKLIST_PROCS) - - time.sleep(10) - - for p in procs: - with self.subTest(proc=p.name): - state = p.get_process_state_msg() - self.assertTrue(state.running, f"{p.name} not running") - exit_code = p.stop(retry=False) - - self.assertNotIn(p.name, BLACKLIST_PROCS, f"{p.name} was started") - - self.assertTrue(exit_code is not None, f"{p.name} failed to exit") - - # TODO: interrupted blocking read exits with 1 in cereal. use a more unique return code - exit_codes = [0, 1] - if p.sigkill: - exit_codes = [-signal.SIGKILL] - self.assertIn(exit_code, exit_codes, f"{p.name} died with {exit_code}") - - -if __name__ == "__main__": - unittest.main() diff --git a/selfdrive/modeld/SConscript b/selfdrive/modeld/SConscript deleted file mode 100644 index 2d15223..0000000 --- a/selfdrive/modeld/SConscript +++ /dev/null @@ -1,72 +0,0 @@ -Import('env', 'envCython', 'arch', 'cereal', 'messaging', 'common', 'gpucommon', 'visionipc', 'transformations') -lenv = env.Clone() -lenvCython = envCython.Clone() - -libs = [cereal, messaging, visionipc, gpucommon, common, 'capnp', 'zmq', 'kj', 'pthread'] -frameworks = [] - -common_src = [ - "models/commonmodel.cc", - "transforms/loadyuv.cc", - "transforms/transform.cc", -] - -thneed_src_common = [ - "thneed/thneed_common.cc", - "thneed/serialize.cc", -] - -thneed_src_qcom = thneed_src_common + ["thneed/thneed_qcom2.cc"] -thneed_src_pc = thneed_src_common + ["thneed/thneed_pc.cc"] -thneed_src = thneed_src_qcom if arch == "larch64" else thneed_src_pc - -# SNPE except on Mac and ARM Linux -snpe_lib = [] -if arch != "Darwin" and arch != "aarch64": - common_src += ['runners/snpemodel.cc'] - snpe_lib += ['SNPE'] - -# OpenCL is a framework on Mac -if arch == "Darwin": - frameworks += ['OpenCL'] -else: - libs += ['OpenCL'] - -# Set path definitions -for pathdef, fn in {'TRANSFORM': 'transforms/transform.cl', 'LOADYUV': 'transforms/loadyuv.cl'}.items(): - for xenv in (lenv, lenvCython): - xenv['CXXFLAGS'].append(f'-D{pathdef}_PATH=\\"{File(fn).abspath}\\"') - -# Compile cython -snpe_rpath_qcom = "/data/pythonpath/third_party/snpe/larch64" -snpe_rpath_pc = f"{Dir('#').abspath}/third_party/snpe/x86_64-linux-clang" -snpe_rpath = lenvCython['RPATH'] + [snpe_rpath_qcom if arch == "larch64" else snpe_rpath_pc] - -cython_libs = envCython["LIBS"] + libs -snpemodel_lib = lenv.Library('snpemodel', ['runners/snpemodel.cc']) -commonmodel_lib = lenv.Library('commonmodel', common_src) - -lenvCython.Program('runners/runmodel_pyx.so', 'runners/runmodel_pyx.pyx', LIBS=cython_libs, FRAMEWORKS=frameworks) -lenvCython.Program('runners/snpemodel_pyx.so', 'runners/snpemodel_pyx.pyx', LIBS=[snpemodel_lib, snpe_lib, *cython_libs], FRAMEWORKS=frameworks, RPATH=snpe_rpath) -lenvCython.Program('models/commonmodel_pyx.so', 'models/commonmodel_pyx.pyx', LIBS=[commonmodel_lib, *cython_libs], FRAMEWORKS=frameworks) - -# Get model metadata -fn = File("models/supercombo").abspath -cmd = f'python3 {Dir("#selfdrive/modeld").abspath}/get_model_metadata.py {fn}.onnx' -files = sum([lenv.Glob("#"+x) for x in open(File("#release/files_common").abspath).read().split("\n") if x.endswith("get_model_metadata.py")], []) -lenv.Command(fn + "_metadata.pkl", [fn + ".onnx"]+files, cmd) - -# Build thneed model -if arch == "larch64" or GetOption('pc_thneed'): - tinygrad_opts = [] - if not GetOption('pc_thneed'): - # use FLOAT16 on device for speed + don't cache the CL kernels for space - tinygrad_opts += ["FLOAT16=1", "PYOPENCL_NO_CACHE=1"] - cmd = f"cd {Dir('#').abspath}/tinygrad_repo && " + ' '.join(tinygrad_opts) + f" python3 openpilot/compile2.py {fn}.onnx {fn}.thneed" - - tinygrad_files = sum([lenv.Glob("#"+x) for x in open(File("#release/files_common").abspath).read().split("\n") if x.startswith("tinygrad_repo/")], []) - lenv.Command(fn + ".thneed", [fn + ".onnx"] + tinygrad_files, cmd) - - thneed_lib = env.SharedLibrary('thneed', thneed_src, LIBS=[gpucommon, common, 'zmq', 'OpenCL', 'dl']) - thneedmodel_lib = env.Library('thneedmodel', ['runners/thneedmodel.cc']) - lenvCython.Program('runners/thneedmodel_pyx.so', 'runners/thneedmodel_pyx.pyx', LIBS=envCython["LIBS"]+[thneedmodel_lib, thneed_lib, gpucommon, common, 'dl', 'zmq', 'OpenCL']) diff --git a/selfdrive/modeld/libthneed.so b/selfdrive/modeld/libthneed.so new file mode 100755 index 0000000..235eb7d Binary files /dev/null and b/selfdrive/modeld/libthneed.so differ diff --git a/selfdrive/modeld/models/commonmodel.cc b/selfdrive/modeld/models/commonmodel.cc deleted file mode 100644 index 5e28e9b..0000000 --- a/selfdrive/modeld/models/commonmodel.cc +++ /dev/null @@ -1,72 +0,0 @@ -#include "selfdrive/modeld/models/commonmodel.h" - -#include -#include -#include -#include - -#include "common/clutil.h" -#include "common/mat.h" -#include "common/timing.h" - -ModelFrame::ModelFrame(cl_device_id device_id, cl_context context) { - input_frames = std::make_unique(buf_size); - - q = CL_CHECK_ERR(clCreateCommandQueue(context, device_id, 0, &err)); - y_cl = CL_CHECK_ERR(clCreateBuffer(context, CL_MEM_READ_WRITE, MODEL_WIDTH * MODEL_HEIGHT, NULL, &err)); - u_cl = CL_CHECK_ERR(clCreateBuffer(context, CL_MEM_READ_WRITE, (MODEL_WIDTH / 2) * (MODEL_HEIGHT / 2), NULL, &err)); - v_cl = CL_CHECK_ERR(clCreateBuffer(context, CL_MEM_READ_WRITE, (MODEL_WIDTH / 2) * (MODEL_HEIGHT / 2), NULL, &err)); - net_input_cl = CL_CHECK_ERR(clCreateBuffer(context, CL_MEM_READ_WRITE, MODEL_FRAME_SIZE * sizeof(float), NULL, &err)); - - transform_init(&transform, context, device_id); - loadyuv_init(&loadyuv, context, device_id, MODEL_WIDTH, MODEL_HEIGHT); -} - -float* ModelFrame::prepare(cl_mem yuv_cl, int frame_width, int frame_height, int frame_stride, int frame_uv_offset, const mat3 &projection, cl_mem *output) { - transform_queue(&this->transform, q, - yuv_cl, frame_width, frame_height, frame_stride, frame_uv_offset, - y_cl, u_cl, v_cl, MODEL_WIDTH, MODEL_HEIGHT, projection); - - if (output == NULL) { - loadyuv_queue(&loadyuv, q, y_cl, u_cl, v_cl, net_input_cl); - - std::memmove(&input_frames[0], &input_frames[MODEL_FRAME_SIZE], sizeof(float) * MODEL_FRAME_SIZE); - CL_CHECK(clEnqueueReadBuffer(q, net_input_cl, CL_TRUE, 0, MODEL_FRAME_SIZE * sizeof(float), &input_frames[MODEL_FRAME_SIZE], 0, nullptr, nullptr)); - clFinish(q); - return &input_frames[0]; - } else { - loadyuv_queue(&loadyuv, q, y_cl, u_cl, v_cl, *output, true); - // NOTE: Since thneed is using a different command queue, this clFinish is needed to ensure the image is ready. - clFinish(q); - return NULL; - } -} - -ModelFrame::~ModelFrame() { - transform_destroy(&transform); - loadyuv_destroy(&loadyuv); - CL_CHECK(clReleaseMemObject(net_input_cl)); - CL_CHECK(clReleaseMemObject(v_cl)); - CL_CHECK(clReleaseMemObject(u_cl)); - CL_CHECK(clReleaseMemObject(y_cl)); - CL_CHECK(clReleaseCommandQueue(q)); -} - -void softmax(const float* input, float* output, size_t len) { - const float max_val = *std::max_element(input, input + len); - float denominator = 0; - for (int i = 0; i < len; i++) { - float const v_exp = expf(input[i] - max_val); - denominator += v_exp; - output[i] = v_exp; - } - - const float inv_denominator = 1. / denominator; - for (int i = 0; i < len; i++) { - output[i] *= inv_denominator; - } -} - -float sigmoid(float input) { - return 1 / (1 + expf(-input)); -} diff --git a/selfdrive/modeld/models/commonmodel.h b/selfdrive/modeld/models/commonmodel.h deleted file mode 100644 index 1a079da..0000000 --- a/selfdrive/modeld/models/commonmodel.h +++ /dev/null @@ -1,47 +0,0 @@ -#pragma once - -#include -#include - -#include - -#define CL_USE_DEPRECATED_OPENCL_1_2_APIS -#ifdef __APPLE__ -#include -#else -#include -#endif - -#include "common/mat.h" -#include "cereal/messaging/messaging.h" -#include "selfdrive/modeld/transforms/loadyuv.h" -#include "selfdrive/modeld/transforms/transform.h" - -const bool send_raw_pred = getenv("SEND_RAW_PRED") != NULL; - -void softmax(const float* input, float* output, size_t len); -float sigmoid(float input); - -template -constexpr const kj::ArrayPtr to_kj_array_ptr(const std::array &arr) { - return kj::ArrayPtr(arr.data(), arr.size()); -} - -class ModelFrame { -public: - ModelFrame(cl_device_id device_id, cl_context context); - ~ModelFrame(); - float* prepare(cl_mem yuv_cl, int width, int height, int frame_stride, int frame_uv_offset, const mat3& transform, cl_mem *output); - - const int MODEL_WIDTH = 512; - const int MODEL_HEIGHT = 256; - const int MODEL_FRAME_SIZE = MODEL_WIDTH * MODEL_HEIGHT * 3 / 2; - const int buf_size = MODEL_FRAME_SIZE * 2; - -private: - Transform transform; - LoadYUVState loadyuv; - cl_command_queue q; - cl_mem y_cl, u_cl, v_cl, net_input_cl; - std::unique_ptr input_frames; -}; diff --git a/selfdrive/modeld/models/commonmodel_pyx.cpp b/selfdrive/modeld/models/commonmodel_pyx.cpp new file mode 100644 index 0000000..cdae9e9 --- /dev/null +++ b/selfdrive/modeld/models/commonmodel_pyx.cpp @@ -0,0 +1,32016 @@ +/* Generated by Cython 3.0.8 */ + +/* BEGIN: Cython Metadata +{ + "distutils": { + "depends": [ + "cereal/visionipc/visionbuf.h", + "cereal/visionipc/visionipc.h", + "cereal/visionipc/visionipc_client.h", + "cereal/visionipc/visionipc_server.h", + "common/clutil.h", + "common/mat.h", + "selfdrive/modeld/models/commonmodel.h" + ], + "language": "c++", + "name": "selfdrive.modeld.models.commonmodel_pyx", + "sources": [ + "/data/openpilot/selfdrive/modeld/models/commonmodel_pyx.pyx" + ] + }, + "module_name": "selfdrive.modeld.models.commonmodel_pyx" +} +END: Cython Metadata */ + +#ifndef PY_SSIZE_T_CLEAN +#define PY_SSIZE_T_CLEAN +#endif /* PY_SSIZE_T_CLEAN */ +#if defined(CYTHON_LIMITED_API) && 0 + #ifndef Py_LIMITED_API + #if CYTHON_LIMITED_API+0 > 0x03030000 + #define Py_LIMITED_API CYTHON_LIMITED_API + #else + #define Py_LIMITED_API 0x03030000 + #endif + #endif +#endif + +#include "Python.h" +#ifndef Py_PYTHON_H + #error Python headers needed to compile C extensions, please install development version of Python. +#elif PY_VERSION_HEX < 0x02070000 || (0x03000000 <= PY_VERSION_HEX && PY_VERSION_HEX < 0x03030000) + #error Cython requires Python 2.7+ or Python 3.3+. +#else +#if defined(CYTHON_LIMITED_API) && CYTHON_LIMITED_API +#define __PYX_EXTRA_ABI_MODULE_NAME "limited" +#else +#define __PYX_EXTRA_ABI_MODULE_NAME "" +#endif +#define CYTHON_ABI "3_0_8" __PYX_EXTRA_ABI_MODULE_NAME +#define __PYX_ABI_MODULE_NAME "_cython_" CYTHON_ABI +#define __PYX_TYPE_MODULE_PREFIX __PYX_ABI_MODULE_NAME "." +#define CYTHON_HEX_VERSION 0x030008F0 +#define CYTHON_FUTURE_DIVISION 1 +#include +#ifndef offsetof + #define offsetof(type, member) ( (size_t) & ((type*)0) -> member ) +#endif +#if !defined(_WIN32) && !defined(WIN32) && !defined(MS_WINDOWS) + #ifndef __stdcall + #define __stdcall + #endif + #ifndef __cdecl + #define __cdecl + #endif + #ifndef __fastcall + #define __fastcall + #endif +#endif +#ifndef DL_IMPORT + #define DL_IMPORT(t) t +#endif +#ifndef DL_EXPORT + #define DL_EXPORT(t) t +#endif +#define __PYX_COMMA , +#ifndef HAVE_LONG_LONG + #define HAVE_LONG_LONG +#endif +#ifndef PY_LONG_LONG + #define PY_LONG_LONG LONG_LONG +#endif +#ifndef Py_HUGE_VAL + #define Py_HUGE_VAL HUGE_VAL +#endif +#define __PYX_LIMITED_VERSION_HEX PY_VERSION_HEX +#if defined(GRAALVM_PYTHON) + /* For very preliminary testing purposes. Most variables are set the same as PyPy. + The existence of this section does not imply that anything works or is even tested */ + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 1 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(PYPY_VERSION) + #define CYTHON_COMPILING_IN_PYPY 1 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #ifndef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #endif + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #if PY_VERSION_HEX < 0x03090000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE (PY_VERSION_HEX >= 0x030400a1 && PYPY_VERSION_NUM >= 0x07030C00) + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(CYTHON_LIMITED_API) + #ifdef Py_LIMITED_API + #undef __PYX_LIMITED_VERSION_HEX + #define __PYX_LIMITED_VERSION_HEX Py_LIMITED_API + #endif + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 1 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_CLINE_IN_TRACEBACK + #define CYTHON_CLINE_IN_TRACEBACK 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 1 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #endif + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 1 + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(Py_GIL_DISABLED) || defined(Py_NOGIL) + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 1 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #ifndef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 +#else + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 1 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #ifndef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #endif + #ifndef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 1 + #endif + #if PY_MAJOR_VERSION < 3 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #ifndef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 1 + #endif + #ifndef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 1 + #endif + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #if PY_VERSION_HEX < 0x030300F0 || PY_VERSION_HEX >= 0x030B00A2 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #elif !defined(CYTHON_USE_UNICODE_WRITER) + #define CYTHON_USE_UNICODE_WRITER 1 + #endif + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #ifndef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 1 + #endif + #ifndef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL (PY_MAJOR_VERSION < 3 || PY_VERSION_HEX >= 0x03060000 && PY_VERSION_HEX < 0x030C00A6) + #endif + #ifndef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL (PY_VERSION_HEX >= 0x030700A1) + #endif + #ifndef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 1 + #endif + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #endif + #if PY_VERSION_HEX < 0x030400a1 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #elif !defined(CYTHON_USE_TP_FINALIZE) + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #if PY_VERSION_HEX < 0x030600B1 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #elif !defined(CYTHON_USE_DICT_VERSIONS) + #define CYTHON_USE_DICT_VERSIONS (PY_VERSION_HEX < 0x030C00A5) + #endif + #if PY_VERSION_HEX < 0x030700A3 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #elif !defined(CYTHON_USE_EXC_INFO_STACK) + #define CYTHON_USE_EXC_INFO_STACK 1 + #endif + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 1 + #endif +#endif +#if !defined(CYTHON_FAST_PYCCALL) +#define CYTHON_FAST_PYCCALL (CYTHON_FAST_PYCALL && PY_VERSION_HEX >= 0x030600B1) +#endif +#if !defined(CYTHON_VECTORCALL) +#define CYTHON_VECTORCALL (CYTHON_FAST_PYCCALL && PY_VERSION_HEX >= 0x030800B1) +#endif +#define CYTHON_BACKPORT_VECTORCALL (CYTHON_METH_FASTCALL && PY_VERSION_HEX < 0x030800B1) +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_MAJOR_VERSION < 3 + #include "longintrepr.h" + #endif + #undef SHIFT + #undef BASE + #undef MASK + #ifdef SIZEOF_VOID_P + enum { __pyx_check_sizeof_voidp = 1 / (int)(SIZEOF_VOID_P == sizeof(void*)) }; + #endif +#endif +#ifndef __has_attribute + #define __has_attribute(x) 0 +#endif +#ifndef __has_cpp_attribute + #define __has_cpp_attribute(x) 0 +#endif +#ifndef CYTHON_RESTRICT + #if defined(__GNUC__) + #define CYTHON_RESTRICT __restrict__ + #elif defined(_MSC_VER) && _MSC_VER >= 1400 + #define CYTHON_RESTRICT __restrict + #elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define CYTHON_RESTRICT restrict + #else + #define CYTHON_RESTRICT + #endif +#endif +#ifndef CYTHON_UNUSED + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(maybe_unused) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(maybe_unused) + #define CYTHON_UNUSED [[maybe_unused]] + #endif + #endif + #endif +#endif +#ifndef CYTHON_UNUSED +# if defined(__GNUC__) +# if !(defined(__cplusplus)) || (__GNUC__ > 3 || (__GNUC__ == 3 && __GNUC_MINOR__ >= 4)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +# elif defined(__ICC) || (defined(__INTEL_COMPILER) && !defined(_MSC_VER)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +#endif +#ifndef CYTHON_UNUSED_VAR +# if defined(__cplusplus) + template void CYTHON_UNUSED_VAR( const T& ) { } +# else +# define CYTHON_UNUSED_VAR(x) (void)(x) +# endif +#endif +#ifndef CYTHON_MAYBE_UNUSED_VAR + #define CYTHON_MAYBE_UNUSED_VAR(x) CYTHON_UNUSED_VAR(x) +#endif +#ifndef CYTHON_NCP_UNUSED +# if CYTHON_COMPILING_IN_CPYTHON +# define CYTHON_NCP_UNUSED +# else +# define CYTHON_NCP_UNUSED CYTHON_UNUSED +# endif +#endif +#ifndef CYTHON_USE_CPP_STD_MOVE + #if defined(__cplusplus) && (\ + __cplusplus >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1600)) + #define CYTHON_USE_CPP_STD_MOVE 1 + #else + #define CYTHON_USE_CPP_STD_MOVE 0 + #endif +#endif +#define __Pyx_void_to_None(void_result) ((void)(void_result), Py_INCREF(Py_None), Py_None) +#ifdef _MSC_VER + #ifndef _MSC_STDINT_H_ + #if _MSC_VER < 1300 + typedef unsigned char uint8_t; + typedef unsigned short uint16_t; + typedef unsigned int uint32_t; + #else + typedef unsigned __int8 uint8_t; + typedef unsigned __int16 uint16_t; + typedef unsigned __int32 uint32_t; + #endif + #endif + #if _MSC_VER < 1300 + #ifdef _WIN64 + typedef unsigned long long __pyx_uintptr_t; + #else + typedef unsigned int __pyx_uintptr_t; + #endif + #else + #ifdef _WIN64 + typedef unsigned __int64 __pyx_uintptr_t; + #else + typedef unsigned __int32 __pyx_uintptr_t; + #endif + #endif +#else + #include + typedef uintptr_t __pyx_uintptr_t; +#endif +#ifndef CYTHON_FALLTHROUGH + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(fallthrough) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(fallthrough) + #define CYTHON_FALLTHROUGH [[fallthrough]] + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_cpp_attribute(clang::fallthrough) + #define CYTHON_FALLTHROUGH [[clang::fallthrough]] + #elif __has_cpp_attribute(gnu::fallthrough) + #define CYTHON_FALLTHROUGH [[gnu::fallthrough]] + #endif + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_attribute(fallthrough) + #define CYTHON_FALLTHROUGH __attribute__((fallthrough)) + #else + #define CYTHON_FALLTHROUGH + #endif + #endif + #if defined(__clang__) && defined(__apple_build_version__) + #if __apple_build_version__ < 7000000 + #undef CYTHON_FALLTHROUGH + #define CYTHON_FALLTHROUGH + #endif + #endif +#endif +#ifdef __cplusplus + template + struct __PYX_IS_UNSIGNED_IMPL {static const bool value = T(0) < T(-1);}; + #define __PYX_IS_UNSIGNED(type) (__PYX_IS_UNSIGNED_IMPL::value) +#else + #define __PYX_IS_UNSIGNED(type) (((type)-1) > 0) +#endif +#if CYTHON_COMPILING_IN_PYPY == 1 + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x030A0000) +#else + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x03090000) +#endif +#define __PYX_REINTERPRET_FUNCION(func_pointer, other_pointer) ((func_pointer)(void(*)(void))(other_pointer)) + +#ifndef __cplusplus + #error "Cython files generated with the C++ option must be compiled with a C++ compiler." +#endif +#ifndef CYTHON_INLINE + #if defined(__clang__) + #define CYTHON_INLINE __inline__ __attribute__ ((__unused__)) + #else + #define CYTHON_INLINE inline + #endif +#endif +template +void __Pyx_call_destructor(T& x) { + x.~T(); +} +template +class __Pyx_FakeReference { + public: + __Pyx_FakeReference() : ptr(NULL) { } + __Pyx_FakeReference(const T& ref) : ptr(const_cast(&ref)) { } + T *operator->() { return ptr; } + T *operator&() { return ptr; } + operator T&() { return *ptr; } + template bool operator ==(const U& other) const { return *ptr == other; } + template bool operator !=(const U& other) const { return *ptr != other; } + template bool operator==(const __Pyx_FakeReference& other) const { return *ptr == *other.ptr; } + template bool operator!=(const __Pyx_FakeReference& other) const { return *ptr != *other.ptr; } + private: + T *ptr; +}; + +#define __PYX_BUILD_PY_SSIZE_T "n" +#define CYTHON_FORMAT_SSIZE_T "z" +#if PY_MAJOR_VERSION < 3 + #define __Pyx_BUILTIN_MODULE_NAME "__builtin__" + #define __Pyx_DefaultClassType PyClass_Type + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a+k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_BUILTIN_MODULE_NAME "builtins" + #define __Pyx_DefaultClassType PyType_Type +#if CYTHON_COMPILING_IN_LIMITED_API + static CYTHON_INLINE PyObject* __Pyx_PyCode_New(int a, int p, int k, int l, int s, int f, + PyObject *code, PyObject *c, PyObject* n, PyObject *v, + PyObject *fv, PyObject *cell, PyObject* fn, + PyObject *name, int fline, PyObject *lnos) { + PyObject *exception_table = NULL; + PyObject *types_module=NULL, *code_type=NULL, *result=NULL; + #if __PYX_LIMITED_VERSION_HEX < 0x030B0000 + PyObject *version_info; + PyObject *py_minor_version = NULL; + #endif + long minor_version = 0; + PyObject *type, *value, *traceback; + PyErr_Fetch(&type, &value, &traceback); + #if __PYX_LIMITED_VERSION_HEX >= 0x030B0000 + minor_version = 11; + #else + if (!(version_info = PySys_GetObject("version_info"))) goto end; + if (!(py_minor_version = PySequence_GetItem(version_info, 1))) goto end; + minor_version = PyLong_AsLong(py_minor_version); + Py_DECREF(py_minor_version); + if (minor_version == -1 && PyErr_Occurred()) goto end; + #endif + if (!(types_module = PyImport_ImportModule("types"))) goto end; + if (!(code_type = PyObject_GetAttrString(types_module, "CodeType"))) goto end; + if (minor_version <= 7) { + (void)p; + result = PyObject_CallFunction(code_type, "iiiiiOOOOOOiOO", a, k, l, s, f, code, + c, n, v, fn, name, fline, lnos, fv, cell); + } else if (minor_version <= 10) { + result = PyObject_CallFunction(code_type, "iiiiiiOOOOOOiOO", a,p, k, l, s, f, code, + c, n, v, fn, name, fline, lnos, fv, cell); + } else { + if (!(exception_table = PyBytes_FromStringAndSize(NULL, 0))) goto end; + result = PyObject_CallFunction(code_type, "iiiiiiOOOOOOOiOO", a,p, k, l, s, f, code, + c, n, v, fn, name, name, fline, lnos, exception_table, fv, cell); + } + end: + Py_XDECREF(code_type); + Py_XDECREF(exception_table); + Py_XDECREF(types_module); + if (type) { + PyErr_Restore(type, value, traceback); + } + return result; + } + #ifndef CO_OPTIMIZED + #define CO_OPTIMIZED 0x0001 + #endif + #ifndef CO_NEWLOCALS + #define CO_NEWLOCALS 0x0002 + #endif + #ifndef CO_VARARGS + #define CO_VARARGS 0x0004 + #endif + #ifndef CO_VARKEYWORDS + #define CO_VARKEYWORDS 0x0008 + #endif + #ifndef CO_ASYNC_GENERATOR + #define CO_ASYNC_GENERATOR 0x0200 + #endif + #ifndef CO_GENERATOR + #define CO_GENERATOR 0x0020 + #endif + #ifndef CO_COROUTINE + #define CO_COROUTINE 0x0080 + #endif +#elif PY_VERSION_HEX >= 0x030B0000 + static CYTHON_INLINE PyCodeObject* __Pyx_PyCode_New(int a, int p, int k, int l, int s, int f, + PyObject *code, PyObject *c, PyObject* n, PyObject *v, + PyObject *fv, PyObject *cell, PyObject* fn, + PyObject *name, int fline, PyObject *lnos) { + PyCodeObject *result; + PyObject *empty_bytes = PyBytes_FromStringAndSize("", 0); + if (!empty_bytes) return NULL; + result = + #if PY_VERSION_HEX >= 0x030C0000 + PyUnstable_Code_NewWithPosOnlyArgs + #else + PyCode_NewWithPosOnlyArgs + #endif + (a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, name, fline, lnos, empty_bytes); + Py_DECREF(empty_bytes); + return result; + } +#elif PY_VERSION_HEX >= 0x030800B2 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_NewWithPosOnlyArgs(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#endif +#endif +#if PY_VERSION_HEX >= 0x030900A4 || defined(Py_IS_TYPE) + #define __Pyx_IS_TYPE(ob, type) Py_IS_TYPE(ob, type) +#else + #define __Pyx_IS_TYPE(ob, type) (((const PyObject*)ob)->ob_type == (type)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_Is) + #define __Pyx_Py_Is(x, y) Py_Is(x, y) +#else + #define __Pyx_Py_Is(x, y) ((x) == (y)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsNone) + #define __Pyx_Py_IsNone(ob) Py_IsNone(ob) +#else + #define __Pyx_Py_IsNone(ob) __Pyx_Py_Is((ob), Py_None) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsTrue) + #define __Pyx_Py_IsTrue(ob) Py_IsTrue(ob) +#else + #define __Pyx_Py_IsTrue(ob) __Pyx_Py_Is((ob), Py_True) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsFalse) + #define __Pyx_Py_IsFalse(ob) Py_IsFalse(ob) +#else + #define __Pyx_Py_IsFalse(ob) __Pyx_Py_Is((ob), Py_False) +#endif +#define __Pyx_NoneAsNull(obj) (__Pyx_Py_IsNone(obj) ? NULL : (obj)) +#if PY_VERSION_HEX >= 0x030900F0 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_GC_IsFinalized(o) PyObject_GC_IsFinalized(o) +#else + #define __Pyx_PyObject_GC_IsFinalized(o) _PyGC_FINALIZED(o) +#endif +#ifndef CO_COROUTINE + #define CO_COROUTINE 0x80 +#endif +#ifndef CO_ASYNC_GENERATOR + #define CO_ASYNC_GENERATOR 0x200 +#endif +#ifndef Py_TPFLAGS_CHECKTYPES + #define Py_TPFLAGS_CHECKTYPES 0 +#endif +#ifndef Py_TPFLAGS_HAVE_INDEX + #define Py_TPFLAGS_HAVE_INDEX 0 +#endif +#ifndef Py_TPFLAGS_HAVE_NEWBUFFER + #define Py_TPFLAGS_HAVE_NEWBUFFER 0 +#endif +#ifndef Py_TPFLAGS_HAVE_FINALIZE + #define Py_TPFLAGS_HAVE_FINALIZE 0 +#endif +#ifndef Py_TPFLAGS_SEQUENCE + #define Py_TPFLAGS_SEQUENCE 0 +#endif +#ifndef Py_TPFLAGS_MAPPING + #define Py_TPFLAGS_MAPPING 0 +#endif +#ifndef METH_STACKLESS + #define METH_STACKLESS 0 +#endif +#if PY_VERSION_HEX <= 0x030700A3 || !defined(METH_FASTCALL) + #ifndef METH_FASTCALL + #define METH_FASTCALL 0x80 + #endif + typedef PyObject *(*__Pyx_PyCFunctionFast) (PyObject *self, PyObject *const *args, Py_ssize_t nargs); + typedef PyObject *(*__Pyx_PyCFunctionFastWithKeywords) (PyObject *self, PyObject *const *args, + Py_ssize_t nargs, PyObject *kwnames); +#else + #define __Pyx_PyCFunctionFast _PyCFunctionFast + #define __Pyx_PyCFunctionFastWithKeywords _PyCFunctionFastWithKeywords +#endif +#if CYTHON_METH_FASTCALL + #define __Pyx_METH_FASTCALL METH_FASTCALL + #define __Pyx_PyCFunction_FastCall __Pyx_PyCFunctionFast + #define __Pyx_PyCFunction_FastCallWithKeywords __Pyx_PyCFunctionFastWithKeywords +#else + #define __Pyx_METH_FASTCALL METH_VARARGS + #define __Pyx_PyCFunction_FastCall PyCFunction + #define __Pyx_PyCFunction_FastCallWithKeywords PyCFunctionWithKeywords +#endif +#if CYTHON_VECTORCALL + #define __pyx_vectorcallfunc vectorcallfunc + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET PY_VECTORCALL_ARGUMENTS_OFFSET + #define __Pyx_PyVectorcall_NARGS(n) PyVectorcall_NARGS((size_t)(n)) +#elif CYTHON_BACKPORT_VECTORCALL + typedef PyObject *(*__pyx_vectorcallfunc)(PyObject *callable, PyObject *const *args, + size_t nargsf, PyObject *kwnames); + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET ((size_t)1 << (8 * sizeof(size_t) - 1)) + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(((size_t)(n)) & ~__Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET)) +#else + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET 0 + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(n)) +#endif +#if PY_MAJOR_VERSION >= 0x030900B1 +#define __Pyx_PyCFunction_CheckExact(func) PyCFunction_CheckExact(func) +#else +#define __Pyx_PyCFunction_CheckExact(func) PyCFunction_Check(func) +#endif +#define __Pyx_CyOrPyCFunction_Check(func) PyCFunction_Check(func) +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_CyOrPyCFunction_GET_FUNCTION(func) (((PyCFunctionObject*)(func))->m_ml->ml_meth) +#elif !CYTHON_COMPILING_IN_LIMITED_API +#define __Pyx_CyOrPyCFunction_GET_FUNCTION(func) PyCFunction_GET_FUNCTION(func) +#endif +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_CyOrPyCFunction_GET_FLAGS(func) (((PyCFunctionObject*)(func))->m_ml->ml_flags) +static CYTHON_INLINE PyObject* __Pyx_CyOrPyCFunction_GET_SELF(PyObject *func) { + return (__Pyx_CyOrPyCFunction_GET_FLAGS(func) & METH_STATIC) ? NULL : ((PyCFunctionObject*)func)->m_self; +} +#endif +static CYTHON_INLINE int __Pyx__IsSameCFunction(PyObject *func, void *cfunc) { +#if CYTHON_COMPILING_IN_LIMITED_API + return PyCFunction_Check(func) && PyCFunction_GetFunction(func) == (PyCFunction) cfunc; +#else + return PyCFunction_Check(func) && PyCFunction_GET_FUNCTION(func) == (PyCFunction) cfunc; +#endif +} +#define __Pyx_IsSameCFunction(func, cfunc) __Pyx__IsSameCFunction(func, cfunc) +#if __PYX_LIMITED_VERSION_HEX < 0x030900B1 + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) ((void)m, PyType_FromSpecWithBases(s, b)) + typedef PyObject *(*__Pyx_PyCMethod)(PyObject *, PyTypeObject *, PyObject *const *, size_t, PyObject *); +#else + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) PyType_FromModuleAndSpec(m, s, b) + #define __Pyx_PyCMethod PyCMethod +#endif +#ifndef METH_METHOD + #define METH_METHOD 0x200 +#endif +#if CYTHON_COMPILING_IN_PYPY && !defined(PyObject_Malloc) + #define PyObject_Malloc(s) PyMem_Malloc(s) + #define PyObject_Free(p) PyMem_Free(p) + #define PyObject_Realloc(p) PyMem_Realloc(p) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) +#else + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) (frame)->f_lineno = (lineno) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyThreadState_Current PyThreadState_Get() +#elif !CYTHON_FAST_THREAD_STATE + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#elif PY_VERSION_HEX >= 0x030d00A1 + #define __Pyx_PyThreadState_Current PyThreadState_GetUnchecked() +#elif PY_VERSION_HEX >= 0x03060000 + #define __Pyx_PyThreadState_Current _PyThreadState_UncheckedGet() +#elif PY_VERSION_HEX >= 0x03000000 + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#else + #define __Pyx_PyThreadState_Current _PyThreadState_Current +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE void *__Pyx_PyModule_GetState(PyObject *op) +{ + void *result; + result = PyModule_GetState(op); + if (!result) + Py_FatalError("Couldn't find the module state"); + return result; +} +#endif +#define __Pyx_PyObject_GetSlot(obj, name, func_ctype) __Pyx_PyType_GetSlot(Py_TYPE(obj), name, func_ctype) +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((func_ctype) PyType_GetSlot((type), Py_##name)) +#else + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((type)->name) +#endif +#if PY_VERSION_HEX < 0x030700A2 && !defined(PyThread_tss_create) && !defined(Py_tss_NEEDS_INIT) +#include "pythread.h" +#define Py_tss_NEEDS_INIT 0 +typedef int Py_tss_t; +static CYTHON_INLINE int PyThread_tss_create(Py_tss_t *key) { + *key = PyThread_create_key(); + return 0; +} +static CYTHON_INLINE Py_tss_t * PyThread_tss_alloc(void) { + Py_tss_t *key = (Py_tss_t *)PyObject_Malloc(sizeof(Py_tss_t)); + *key = Py_tss_NEEDS_INIT; + return key; +} +static CYTHON_INLINE void PyThread_tss_free(Py_tss_t *key) { + PyObject_Free(key); +} +static CYTHON_INLINE int PyThread_tss_is_created(Py_tss_t *key) { + return *key != Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE void PyThread_tss_delete(Py_tss_t *key) { + PyThread_delete_key(*key); + *key = Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE int PyThread_tss_set(Py_tss_t *key, void *value) { + return PyThread_set_key_value(*key, value); +} +static CYTHON_INLINE void * PyThread_tss_get(Py_tss_t *key) { + return PyThread_get_key_value(*key); +} +#endif +#if PY_MAJOR_VERSION < 3 + #if CYTHON_COMPILING_IN_PYPY + #if PYPY_VERSION_NUM < 0x07030600 + #if defined(__cplusplus) && __cplusplus >= 201402L + [[deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")]] + #elif defined(__GNUC__) || defined(__clang__) + __attribute__ ((__deprecated__("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6"))) + #elif defined(_MSC_VER) + __declspec(deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")) + #endif + static CYTHON_INLINE int PyGILState_Check(void) { + return 0; + } + #else // PYPY_VERSION_NUM < 0x07030600 + #endif // PYPY_VERSION_NUM < 0x07030600 + #else + static CYTHON_INLINE int PyGILState_Check(void) { + PyThreadState * tstate = _PyThreadState_Current; + return tstate && (tstate == PyGILState_GetThisThreadState()); + } + #endif +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030d0000 || defined(_PyDict_NewPresized) +#define __Pyx_PyDict_NewPresized(n) ((n <= 8) ? PyDict_New() : _PyDict_NewPresized(n)) +#else +#define __Pyx_PyDict_NewPresized(n) PyDict_New() +#endif +#if PY_MAJOR_VERSION >= 3 || CYTHON_FUTURE_DIVISION + #define __Pyx_PyNumber_Divide(x,y) PyNumber_TrueDivide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceTrueDivide(x,y) +#else + #define __Pyx_PyNumber_Divide(x,y) PyNumber_Divide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceDivide(x,y) +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX > 0x030600B4 && PY_VERSION_HEX < 0x030d0000 && CYTHON_USE_UNICODE_INTERNALS +#define __Pyx_PyDict_GetItemStrWithError(dict, name) _PyDict_GetItem_KnownHash(dict, name, ((PyASCIIObject *) name)->hash) +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStr(PyObject *dict, PyObject *name) { + PyObject *res = __Pyx_PyDict_GetItemStrWithError(dict, name); + if (res == NULL) PyErr_Clear(); + return res; +} +#elif PY_MAJOR_VERSION >= 3 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07020000) +#define __Pyx_PyDict_GetItemStrWithError PyDict_GetItemWithError +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#else +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStrWithError(PyObject *dict, PyObject *name) { +#if CYTHON_COMPILING_IN_PYPY + return PyDict_GetItem(dict, name); +#else + PyDictEntry *ep; + PyDictObject *mp = (PyDictObject*) dict; + long hash = ((PyStringObject *) name)->ob_shash; + assert(hash != -1); + ep = (mp->ma_lookup)(mp, name, hash); + if (ep == NULL) { + return NULL; + } + return ep->me_value; +#endif +} +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#endif +#if CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyType_GetFlags(tp) (((PyTypeObject *)tp)->tp_flags) + #define __Pyx_PyType_HasFeature(type, feature) ((__Pyx_PyType_GetFlags(type) & (feature)) != 0) + #define __Pyx_PyObject_GetIterNextFunc(obj) (Py_TYPE(obj)->tp_iternext) +#else + #define __Pyx_PyType_GetFlags(tp) (PyType_GetFlags((PyTypeObject *)tp)) + #define __Pyx_PyType_HasFeature(type, feature) PyType_HasFeature(type, feature) + #define __Pyx_PyObject_GetIterNextFunc(obj) PyIter_Next +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_SetItemOnTypeDict(tp, k, v) PyObject_GenericSetAttr((PyObject*)tp, k, v) +#else + #define __Pyx_SetItemOnTypeDict(tp, k, v) PyDict_SetItem(tp->tp_dict, k, v) +#endif +#if CYTHON_USE_TYPE_SPECS && PY_VERSION_HEX >= 0x03080000 +#define __Pyx_PyHeapTypeObject_GC_Del(obj) {\ + PyTypeObject *type = Py_TYPE((PyObject*)obj);\ + assert(__Pyx_PyType_HasFeature(type, Py_TPFLAGS_HEAPTYPE));\ + PyObject_GC_Del(obj);\ + Py_DECREF(type);\ +} +#else +#define __Pyx_PyHeapTypeObject_GC_Del(obj) PyObject_GC_Del(obj) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define CYTHON_PEP393_ENABLED 1 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GetLength(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_ReadChar(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((void)u, 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((void)u, (0)) + #define __Pyx_PyUnicode_DATA(u) ((void*)u) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)k, PyUnicode_ReadChar((PyObject*)(d), i)) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GetLength(u)) +#elif PY_VERSION_HEX > 0x03030000 && defined(PyUnicode_KIND) + #define CYTHON_PEP393_ENABLED 1 + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_READY(op) (0) + #else + #define __Pyx_PyUnicode_READY(op) (likely(PyUnicode_IS_READY(op)) ?\ + 0 : _PyUnicode_Ready((PyObject *)(op))) + #endif + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_LENGTH(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_READ_CHAR(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) PyUnicode_MAX_CHAR_VALUE(u) + #define __Pyx_PyUnicode_KIND(u) ((int)PyUnicode_KIND(u)) + #define __Pyx_PyUnicode_DATA(u) PyUnicode_DATA(u) + #define __Pyx_PyUnicode_READ(k, d, i) PyUnicode_READ(k, d, i) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) PyUnicode_WRITE(k, d, i, (Py_UCS4) ch) + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_LENGTH(u)) + #else + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x03090000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : ((PyCompactUnicodeObject *)(u))->wstr_length)) + #else + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : PyUnicode_GET_SIZE(u))) + #endif + #endif +#else + #define CYTHON_PEP393_ENABLED 0 + #define PyUnicode_1BYTE_KIND 1 + #define PyUnicode_2BYTE_KIND 2 + #define PyUnicode_4BYTE_KIND 4 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_SIZE(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) ((Py_UCS4)(PyUnicode_AS_UNICODE(u)[i])) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((sizeof(Py_UNICODE) == 2) ? 65535U : 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((int)sizeof(Py_UNICODE)) + #define __Pyx_PyUnicode_DATA(u) ((void*)PyUnicode_AS_UNICODE(u)) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)(k), (Py_UCS4)(((Py_UNICODE*)d)[i])) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) (((void)(k)), ((Py_UNICODE*)d)[i] = (Py_UNICODE) ch) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_SIZE(u)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyUnicode_Concat(a, b) PyNumber_Add(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) PyNumber_Add(a, b) +#else + #define __Pyx_PyUnicode_Concat(a, b) PyUnicode_Concat(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) ((unlikely((a) == Py_None) || unlikely((b) == Py_None)) ?\ + PyNumber_Add(a, b) : __Pyx_PyUnicode_Concat(a, b)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #if !defined(PyUnicode_DecodeUnicodeEscape) + #define PyUnicode_DecodeUnicodeEscape(s, size, errors) PyUnicode_Decode(s, size, "unicode_escape", errors) + #endif + #if !defined(PyUnicode_Contains) || (PY_MAJOR_VERSION == 2 && PYPY_VERSION_NUM < 0x07030500) + #undef PyUnicode_Contains + #define PyUnicode_Contains(u, s) PySequence_Contains(u, s) + #endif + #if !defined(PyByteArray_Check) + #define PyByteArray_Check(obj) PyObject_TypeCheck(obj, &PyByteArray_Type) + #endif + #if !defined(PyObject_Format) + #define PyObject_Format(obj, fmt) PyObject_CallMethod(obj, "__format__", "O", fmt) + #endif +#endif +#define __Pyx_PyString_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyString_Check(b) && !PyString_CheckExact(b)))) ? PyNumber_Remainder(a, b) : __Pyx_PyString_Format(a, b)) +#define __Pyx_PyUnicode_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyUnicode_Check(b) && !PyUnicode_CheckExact(b)))) ? PyNumber_Remainder(a, b) : PyUnicode_Format(a, b)) +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyString_Format(a, b) PyUnicode_Format(a, b) +#else + #define __Pyx_PyString_Format(a, b) PyString_Format(a, b) +#endif +#if PY_MAJOR_VERSION < 3 && !defined(PyObject_ASCII) + #define PyObject_ASCII(o) PyObject_Repr(o) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBaseString_Type PyUnicode_Type + #define PyStringObject PyUnicodeObject + #define PyString_Type PyUnicode_Type + #define PyString_Check PyUnicode_Check + #define PyString_CheckExact PyUnicode_CheckExact +#ifndef PyObject_Unicode + #define PyObject_Unicode PyObject_Str +#endif +#endif +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyBaseString_Check(obj) PyUnicode_Check(obj) + #define __Pyx_PyBaseString_CheckExact(obj) PyUnicode_CheckExact(obj) +#else + #define __Pyx_PyBaseString_Check(obj) (PyString_Check(obj) || PyUnicode_Check(obj)) + #define __Pyx_PyBaseString_CheckExact(obj) (PyString_CheckExact(obj) || PyUnicode_CheckExact(obj)) +#endif +#if CYTHON_COMPILING_IN_CPYTHON + #define __Pyx_PySequence_ListKeepNew(obj)\ + (likely(PyList_CheckExact(obj) && Py_REFCNT(obj) == 1) ? __Pyx_NewRef(obj) : PySequence_List(obj)) +#else + #define __Pyx_PySequence_ListKeepNew(obj) PySequence_List(obj) +#endif +#ifndef PySet_CheckExact + #define PySet_CheckExact(obj) __Pyx_IS_TYPE(obj, &PySet_Type) +#endif +#if PY_VERSION_HEX >= 0x030900A4 + #define __Pyx_SET_REFCNT(obj, refcnt) Py_SET_REFCNT(obj, refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SET_SIZE(obj, size) +#else + #define __Pyx_SET_REFCNT(obj, refcnt) Py_REFCNT(obj) = (refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SIZE(obj) = (size) +#endif +#if CYTHON_ASSUME_SAFE_MACROS + #define __Pyx_PySequence_ITEM(o, i) PySequence_ITEM(o, i) + #define __Pyx_PySequence_SIZE(seq) Py_SIZE(seq) + #define __Pyx_PyTuple_SET_ITEM(o, i, v) (PyTuple_SET_ITEM(o, i, v), (0)) + #define __Pyx_PyList_SET_ITEM(o, i, v) (PyList_SET_ITEM(o, i, v), (0)) + #define __Pyx_PyTuple_GET_SIZE(o) PyTuple_GET_SIZE(o) + #define __Pyx_PyList_GET_SIZE(o) PyList_GET_SIZE(o) + #define __Pyx_PySet_GET_SIZE(o) PySet_GET_SIZE(o) + #define __Pyx_PyBytes_GET_SIZE(o) PyBytes_GET_SIZE(o) + #define __Pyx_PyByteArray_GET_SIZE(o) PyByteArray_GET_SIZE(o) +#else + #define __Pyx_PySequence_ITEM(o, i) PySequence_GetItem(o, i) + #define __Pyx_PySequence_SIZE(seq) PySequence_Size(seq) + #define __Pyx_PyTuple_SET_ITEM(o, i, v) PyTuple_SetItem(o, i, v) + #define __Pyx_PyList_SET_ITEM(o, i, v) PyList_SetItem(o, i, v) + #define __Pyx_PyTuple_GET_SIZE(o) PyTuple_Size(o) + #define __Pyx_PyList_GET_SIZE(o) PyList_Size(o) + #define __Pyx_PySet_GET_SIZE(o) PySet_Size(o) + #define __Pyx_PyBytes_GET_SIZE(o) PyBytes_Size(o) + #define __Pyx_PyByteArray_GET_SIZE(o) PyByteArray_Size(o) +#endif +#if PY_VERSION_HEX >= 0x030d00A1 + #define __Pyx_PyImport_AddModuleRef(name) PyImport_AddModuleRef(name) +#else + static CYTHON_INLINE PyObject *__Pyx_PyImport_AddModuleRef(const char *name) { + PyObject *module = PyImport_AddModule(name); + Py_XINCREF(module); + return module; + } +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyIntObject PyLongObject + #define PyInt_Type PyLong_Type + #define PyInt_Check(op) PyLong_Check(op) + #define PyInt_CheckExact(op) PyLong_CheckExact(op) + #define __Pyx_Py3Int_Check(op) PyLong_Check(op) + #define __Pyx_Py3Int_CheckExact(op) PyLong_CheckExact(op) + #define PyInt_FromString PyLong_FromString + #define PyInt_FromUnicode PyLong_FromUnicode + #define PyInt_FromLong PyLong_FromLong + #define PyInt_FromSize_t PyLong_FromSize_t + #define PyInt_FromSsize_t PyLong_FromSsize_t + #define PyInt_AsLong PyLong_AsLong + #define PyInt_AS_LONG PyLong_AS_LONG + #define PyInt_AsSsize_t PyLong_AsSsize_t + #define PyInt_AsUnsignedLongMask PyLong_AsUnsignedLongMask + #define PyInt_AsUnsignedLongLongMask PyLong_AsUnsignedLongLongMask + #define PyNumber_Int PyNumber_Long +#else + #define __Pyx_Py3Int_Check(op) (PyLong_Check(op) || PyInt_Check(op)) + #define __Pyx_Py3Int_CheckExact(op) (PyLong_CheckExact(op) || PyInt_CheckExact(op)) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBoolObject PyLongObject +#endif +#if PY_MAJOR_VERSION >= 3 && CYTHON_COMPILING_IN_PYPY + #ifndef PyUnicode_InternFromString + #define PyUnicode_InternFromString(s) PyUnicode_FromString(s) + #endif +#endif +#if PY_VERSION_HEX < 0x030200A4 + typedef long Py_hash_t; + #define __Pyx_PyInt_FromHash_t PyInt_FromLong + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsHash_t +#else + #define __Pyx_PyInt_FromHash_t PyInt_FromSsize_t + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsSsize_t +#endif +#if CYTHON_USE_ASYNC_SLOTS + #if PY_VERSION_HEX >= 0x030500B1 + #define __Pyx_PyAsyncMethodsStruct PyAsyncMethods + #define __Pyx_PyType_AsAsync(obj) (Py_TYPE(obj)->tp_as_async) + #else + #define __Pyx_PyType_AsAsync(obj) ((__Pyx_PyAsyncMethodsStruct*) (Py_TYPE(obj)->tp_reserved)) + #endif +#else + #define __Pyx_PyType_AsAsync(obj) NULL +#endif +#ifndef __Pyx_PyAsyncMethodsStruct + typedef struct { + unaryfunc am_await; + unaryfunc am_aiter; + unaryfunc am_anext; + } __Pyx_PyAsyncMethodsStruct; +#endif + +#if defined(_WIN32) || defined(WIN32) || defined(MS_WINDOWS) + #if !defined(_USE_MATH_DEFINES) + #define _USE_MATH_DEFINES + #endif +#endif +#include +#ifdef NAN +#define __PYX_NAN() ((float) NAN) +#else +static CYTHON_INLINE float __PYX_NAN() { + float value; + memset(&value, 0xFF, sizeof(value)); + return value; +} +#endif +#if defined(__CYGWIN__) && defined(_LDBL_EQ_DBL) +#define __Pyx_truncl trunc +#else +#define __Pyx_truncl truncl +#endif + +#define __PYX_MARK_ERR_POS(f_index, lineno) \ + { __pyx_filename = __pyx_f[f_index]; (void)__pyx_filename; __pyx_lineno = lineno; (void)__pyx_lineno; __pyx_clineno = __LINE__; (void)__pyx_clineno; } +#define __PYX_ERR(f_index, lineno, Ln_error) \ + { __PYX_MARK_ERR_POS(f_index, lineno) goto Ln_error; } + +#ifdef CYTHON_EXTERN_C + #undef __PYX_EXTERN_C + #define __PYX_EXTERN_C CYTHON_EXTERN_C +#elif defined(__PYX_EXTERN_C) + #ifdef _MSC_VER + #pragma message ("Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead.") + #else + #warning Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead. + #endif +#else + #define __PYX_EXTERN_C extern "C++" +#endif + +#define __PYX_HAVE__selfdrive__modeld__models__commonmodel_pyx +#define __PYX_HAVE_API__selfdrive__modeld__models__commonmodel_pyx +/* Early includes */ +#include +#include +#include "ios" +#include "new" +#include "stdexcept" +#include "typeinfo" +#include +#include + + #if __cplusplus >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1600) + // move should be defined for these versions of MSVC, but __cplusplus isn't set usefully + #include + + namespace cython_std { + template typename std::remove_reference::type&& move(T& t) noexcept { return std::move(t); } + template typename std::remove_reference::type&& move(T&& t) noexcept { return std::move(t); } + } + + #endif + +#include +#include +#include "cereal/visionipc/visionbuf.h" +#include "cereal/visionipc/visionipc.h" +#include "cereal/visionipc/visionipc_server.h" +#include "cereal/visionipc/visionipc_client.h" +#include + + /* Using NumPy API declarations from "numpy/__init__.cython-30.pxd" */ + +#include "numpy/arrayobject.h" +#include "numpy/ndarrayobject.h" +#include "numpy/ndarraytypes.h" +#include "numpy/arrayscalars.h" +#include "numpy/ufuncobject.h" +#include "common/mat.h" +#include "common/clutil.h" +#include "selfdrive/modeld/models/commonmodel.h" +#include "pythread.h" +#include +#ifdef _OPENMP +#include +#endif /* _OPENMP */ + +#if defined(PYREX_WITHOUT_ASSERTIONS) && !defined(CYTHON_WITHOUT_ASSERTIONS) +#define CYTHON_WITHOUT_ASSERTIONS +#endif + +typedef struct {PyObject **p; const char *s; const Py_ssize_t n; const char* encoding; + const char is_unicode; const char is_str; const char intern; } __Pyx_StringTabEntry; + +#define __PYX_DEFAULT_STRING_ENCODING_IS_ASCII 1 +#define __PYX_DEFAULT_STRING_ENCODING_IS_UTF8 0 +#define __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT (PY_MAJOR_VERSION >= 3 && __PYX_DEFAULT_STRING_ENCODING_IS_UTF8) +#define __PYX_DEFAULT_STRING_ENCODING "ascii" +#define __Pyx_PyObject_FromString __Pyx_PyBytes_FromString +#define __Pyx_PyObject_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#define __Pyx_uchar_cast(c) ((unsigned char)c) +#define __Pyx_long_cast(x) ((long)x) +#define __Pyx_fits_Py_ssize_t(v, type, is_signed) (\ + (sizeof(type) < sizeof(Py_ssize_t)) ||\ + (sizeof(type) > sizeof(Py_ssize_t) &&\ + likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX) &&\ + (!is_signed || likely(v > (type)PY_SSIZE_T_MIN ||\ + v == (type)PY_SSIZE_T_MIN))) ||\ + (sizeof(type) == sizeof(Py_ssize_t) &&\ + (is_signed || likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX))) ) +static CYTHON_INLINE int __Pyx_is_valid_index(Py_ssize_t i, Py_ssize_t limit) { + return (size_t) i < (size_t) limit; +} +#if defined (__cplusplus) && __cplusplus >= 201103L + #include + #define __Pyx_sst_abs(value) std::abs(value) +#elif SIZEOF_INT >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) abs(value) +#elif SIZEOF_LONG >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) labs(value) +#elif defined (_MSC_VER) + #define __Pyx_sst_abs(value) ((Py_ssize_t)_abs64(value)) +#elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define __Pyx_sst_abs(value) llabs(value) +#elif defined (__GNUC__) + #define __Pyx_sst_abs(value) __builtin_llabs(value) +#else + #define __Pyx_sst_abs(value) ((value<0) ? -value : value) +#endif +static CYTHON_INLINE Py_ssize_t __Pyx_ssize_strlen(const char *s); +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject*); +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject*, Py_ssize_t* length); +static CYTHON_INLINE PyObject* __Pyx_PyByteArray_FromString(const char*); +#define __Pyx_PyByteArray_FromStringAndSize(s, l) PyByteArray_FromStringAndSize((const char*)s, l) +#define __Pyx_PyBytes_FromString PyBytes_FromString +#define __Pyx_PyBytes_FromStringAndSize PyBytes_FromStringAndSize +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char*); +#if PY_MAJOR_VERSION < 3 + #define __Pyx_PyStr_FromString __Pyx_PyBytes_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#else + #define __Pyx_PyStr_FromString __Pyx_PyUnicode_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyUnicode_FromStringAndSize +#endif +#define __Pyx_PyBytes_AsWritableString(s) ((char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableSString(s) ((signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableUString(s) ((unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsString(s) ((const char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsSString(s) ((const signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsUString(s) ((const unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyObject_AsWritableString(s) ((char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableSString(s) ((signed char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableUString(s) ((unsigned char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsSString(s) ((const signed char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsUString(s) ((const unsigned char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_FromCString(s) __Pyx_PyObject_FromString((const char*)s) +#define __Pyx_PyBytes_FromCString(s) __Pyx_PyBytes_FromString((const char*)s) +#define __Pyx_PyByteArray_FromCString(s) __Pyx_PyByteArray_FromString((const char*)s) +#define __Pyx_PyStr_FromCString(s) __Pyx_PyStr_FromString((const char*)s) +#define __Pyx_PyUnicode_FromCString(s) __Pyx_PyUnicode_FromString((const char*)s) +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const wchar_t *u) +{ + const wchar_t *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#else +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const Py_UNICODE *u) +{ + const Py_UNICODE *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#endif +#define __Pyx_PyUnicode_FromOrdinal(o) PyUnicode_FromOrdinal((int)o) +#define __Pyx_PyUnicode_FromUnicode(u) PyUnicode_FromUnicode(u, __Pyx_Py_UNICODE_strlen(u)) +#define __Pyx_PyUnicode_FromUnicodeAndLength PyUnicode_FromUnicode +#define __Pyx_PyUnicode_AsUnicode PyUnicode_AsUnicode +#define __Pyx_NewRef(obj) (Py_INCREF(obj), obj) +#define __Pyx_Owned_Py_None(b) __Pyx_NewRef(Py_None) +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b); +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject*); +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject*); +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x); +#define __Pyx_PySequence_Tuple(obj)\ + (likely(PyTuple_CheckExact(obj)) ? __Pyx_NewRef(obj) : PySequence_Tuple(obj)) +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject*); +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t); +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject*); +#if CYTHON_ASSUME_SAFE_MACROS +#define __pyx_PyFloat_AsDouble(x) (PyFloat_CheckExact(x) ? PyFloat_AS_DOUBLE(x) : PyFloat_AsDouble(x)) +#else +#define __pyx_PyFloat_AsDouble(x) PyFloat_AsDouble(x) +#endif +#define __pyx_PyFloat_AsFloat(x) ((float) __pyx_PyFloat_AsDouble(x)) +#if PY_MAJOR_VERSION >= 3 +#define __Pyx_PyNumber_Int(x) (PyLong_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Long(x)) +#else +#define __Pyx_PyNumber_Int(x) (PyInt_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Int(x)) +#endif +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_VERSION_HEX >= 0x030C00A7 + #ifndef _PyLong_SIGN_MASK + #define _PyLong_SIGN_MASK 3 + #endif + #ifndef _PyLong_NON_SIZE_BITS + #define _PyLong_NON_SIZE_BITS 3 + #endif + #define __Pyx_PyLong_Sign(x) (((PyLongObject*)x)->long_value.lv_tag & _PyLong_SIGN_MASK) + #define __Pyx_PyLong_IsNeg(x) ((__Pyx_PyLong_Sign(x) & 2) != 0) + #define __Pyx_PyLong_IsNonNeg(x) (!__Pyx_PyLong_IsNeg(x)) + #define __Pyx_PyLong_IsZero(x) (__Pyx_PyLong_Sign(x) & 1) + #define __Pyx_PyLong_IsPos(x) (__Pyx_PyLong_Sign(x) == 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) (__Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) ((Py_ssize_t) (((PyLongObject*)x)->long_value.lv_tag >> _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_SignedDigitCount(x)\ + ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * __Pyx_PyLong_DigitCount(x)) + #if defined(PyUnstable_Long_IsCompact) && defined(PyUnstable_Long_CompactValue) + #define __Pyx_PyLong_IsCompact(x) PyUnstable_Long_IsCompact((PyLongObject*) x) + #define __Pyx_PyLong_CompactValue(x) PyUnstable_Long_CompactValue((PyLongObject*) x) + #else + #define __Pyx_PyLong_IsCompact(x) (((PyLongObject*)x)->long_value.lv_tag < (2 << _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_CompactValue(x) ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * (Py_ssize_t) __Pyx_PyLong_Digits(x)[0]) + #endif + typedef Py_ssize_t __Pyx_compact_pylong; + typedef size_t __Pyx_compact_upylong; + #else + #define __Pyx_PyLong_IsNeg(x) (Py_SIZE(x) < 0) + #define __Pyx_PyLong_IsNonNeg(x) (Py_SIZE(x) >= 0) + #define __Pyx_PyLong_IsZero(x) (Py_SIZE(x) == 0) + #define __Pyx_PyLong_IsPos(x) (Py_SIZE(x) > 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) ((Py_SIZE(x) == 0) ? 0 : __Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) __Pyx_sst_abs(Py_SIZE(x)) + #define __Pyx_PyLong_SignedDigitCount(x) Py_SIZE(x) + #define __Pyx_PyLong_IsCompact(x) (Py_SIZE(x) == 0 || Py_SIZE(x) == 1 || Py_SIZE(x) == -1) + #define __Pyx_PyLong_CompactValue(x)\ + ((Py_SIZE(x) == 0) ? (sdigit) 0 : ((Py_SIZE(x) < 0) ? -(sdigit)__Pyx_PyLong_Digits(x)[0] : (sdigit)__Pyx_PyLong_Digits(x)[0])) + typedef sdigit __Pyx_compact_pylong; + typedef digit __Pyx_compact_upylong; + #endif + #if PY_VERSION_HEX >= 0x030C00A5 + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->long_value.ob_digit) + #else + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->ob_digit) + #endif +#endif +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII +#include +static int __Pyx_sys_getdefaultencoding_not_ascii; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + PyObject* ascii_chars_u = NULL; + PyObject* ascii_chars_b = NULL; + const char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + if (strcmp(default_encoding_c, "ascii") == 0) { + __Pyx_sys_getdefaultencoding_not_ascii = 0; + } else { + char ascii_chars[128]; + int c; + for (c = 0; c < 128; c++) { + ascii_chars[c] = (char) c; + } + __Pyx_sys_getdefaultencoding_not_ascii = 1; + ascii_chars_u = PyUnicode_DecodeASCII(ascii_chars, 128, NULL); + if (!ascii_chars_u) goto bad; + ascii_chars_b = PyUnicode_AsEncodedString(ascii_chars_u, default_encoding_c, NULL); + if (!ascii_chars_b || !PyBytes_Check(ascii_chars_b) || memcmp(ascii_chars, PyBytes_AS_STRING(ascii_chars_b), 128) != 0) { + PyErr_Format( + PyExc_ValueError, + "This module compiled with c_string_encoding=ascii, but default encoding '%.200s' is not a superset of ascii.", + default_encoding_c); + goto bad; + } + Py_DECREF(ascii_chars_u); + Py_DECREF(ascii_chars_b); + } + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + Py_XDECREF(ascii_chars_u); + Py_XDECREF(ascii_chars_b); + return -1; +} +#endif +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT && PY_MAJOR_VERSION >= 3 +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_DecodeUTF8(c_str, size, NULL) +#else +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_Decode(c_str, size, __PYX_DEFAULT_STRING_ENCODING, NULL) +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +#include +static char* __PYX_DEFAULT_STRING_ENCODING; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) (const char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + __PYX_DEFAULT_STRING_ENCODING = (char*) malloc(strlen(default_encoding_c) + 1); + if (!__PYX_DEFAULT_STRING_ENCODING) goto bad; + strcpy(__PYX_DEFAULT_STRING_ENCODING, default_encoding_c); + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + return -1; +} +#endif +#endif + + +/* Test for GCC > 2.95 */ +#if defined(__GNUC__) && (__GNUC__ > 2 || (__GNUC__ == 2 && (__GNUC_MINOR__ > 95))) + #define likely(x) __builtin_expect(!!(x), 1) + #define unlikely(x) __builtin_expect(!!(x), 0) +#else /* !__GNUC__ or GCC < 2.95 */ + #define likely(x) (x) + #define unlikely(x) (x) +#endif /* __GNUC__ */ +static CYTHON_INLINE void __Pyx_pretend_to_initialize(void* ptr) { (void)ptr; } + +#if !CYTHON_USE_MODULE_STATE +static PyObject *__pyx_m = NULL; +#endif +static int __pyx_lineno; +static int __pyx_clineno = 0; +static const char * __pyx_cfilenm = __FILE__; +static const char *__pyx_filename; + +/* Header.proto */ +#if !defined(CYTHON_CCOMPLEX) + #if defined(__cplusplus) + #define CYTHON_CCOMPLEX 1 + #elif (defined(_Complex_I) && !defined(_MSC_VER)) || ((defined (__STDC_VERSION__) && __STDC_VERSION__ >= 201112L) && !defined(__STDC_NO_COMPLEX__) && !defined(_MSC_VER)) + #define CYTHON_CCOMPLEX 1 + #else + #define CYTHON_CCOMPLEX 0 + #endif +#endif +#if CYTHON_CCOMPLEX + #ifdef __cplusplus + #include + #else + #include + #endif +#endif +#if CYTHON_CCOMPLEX && !defined(__cplusplus) && defined(__sun__) && defined(__GNUC__) + #undef _Complex_I + #define _Complex_I 1.0fj +#endif + +/* #### Code section: filename_table ### */ + +static const char *__pyx_f[] = { + "", + "selfdrive/modeld/models/commonmodel_pyx.pyx", + "__init__.cython-30.pxd", + "cereal/visionipc/visionipc_pyx.pxd", + "type.pxd", +}; +/* #### Code section: utility_code_proto_before_types ### */ +/* ForceInitThreads.proto */ +#ifndef __PYX_FORCE_INIT_THREADS + #define __PYX_FORCE_INIT_THREADS 0 +#endif + +/* NoFastGil.proto */ +#define __Pyx_PyGILState_Ensure PyGILState_Ensure +#define __Pyx_PyGILState_Release PyGILState_Release +#define __Pyx_FastGIL_Remember() +#define __Pyx_FastGIL_Forget() +#define __Pyx_FastGilFuncInit() + +/* BufferFormatStructs.proto */ +struct __Pyx_StructField_; +#define __PYX_BUF_FLAGS_PACKED_STRUCT (1 << 0) +typedef struct { + const char* name; + struct __Pyx_StructField_* fields; + size_t size; + size_t arraysize[8]; + int ndim; + char typegroup; + char is_unsigned; + int flags; +} __Pyx_TypeInfo; +typedef struct __Pyx_StructField_ { + __Pyx_TypeInfo* type; + const char* name; + size_t offset; +} __Pyx_StructField; +typedef struct { + __Pyx_StructField* field; + size_t parent_offset; +} __Pyx_BufFmt_StackElem; +typedef struct { + __Pyx_StructField root; + __Pyx_BufFmt_StackElem* head; + size_t fmt_offset; + size_t new_count, enc_count; + size_t struct_alignment; + int is_complex; + char enc_type; + char new_packmode; + char enc_packmode; + char is_valid_array; +} __Pyx_BufFmt_Context; + +/* Atomics.proto */ +#include +#ifndef CYTHON_ATOMICS + #define CYTHON_ATOMICS 1 +#endif +#define __PYX_CYTHON_ATOMICS_ENABLED() CYTHON_ATOMICS +#define __pyx_atomic_int_type int +#define __pyx_nonatomic_int_type int +#if CYTHON_ATOMICS && (defined(__STDC_VERSION__) &&\ + (__STDC_VERSION__ >= 201112L) &&\ + !defined(__STDC_NO_ATOMICS__)) + #include +#elif CYTHON_ATOMICS && (defined(__cplusplus) && (\ + (__cplusplus >= 201103L) ||\ + (defined(_MSC_VER) && _MSC_VER >= 1700))) + #include +#endif +#if CYTHON_ATOMICS && (defined(__STDC_VERSION__) &&\ + (__STDC_VERSION__ >= 201112L) &&\ + !defined(__STDC_NO_ATOMICS__) &&\ + ATOMIC_INT_LOCK_FREE == 2) + #undef __pyx_atomic_int_type + #define __pyx_atomic_int_type atomic_int + #define __pyx_atomic_incr_aligned(value) atomic_fetch_add_explicit(value, 1, memory_order_relaxed) + #define __pyx_atomic_decr_aligned(value) atomic_fetch_sub_explicit(value, 1, memory_order_acq_rel) + #if defined(__PYX_DEBUG_ATOMICS) && defined(_MSC_VER) + #pragma message ("Using standard C atomics") + #elif defined(__PYX_DEBUG_ATOMICS) + #warning "Using standard C atomics" + #endif +#elif CYTHON_ATOMICS && (defined(__cplusplus) && (\ + (__cplusplus >= 201103L) ||\ +\ + (defined(_MSC_VER) && _MSC_VER >= 1700)) &&\ + ATOMIC_INT_LOCK_FREE == 2) + #undef __pyx_atomic_int_type + #define __pyx_atomic_int_type std::atomic_int + #define __pyx_atomic_incr_aligned(value) std::atomic_fetch_add_explicit(value, 1, std::memory_order_relaxed) + #define __pyx_atomic_decr_aligned(value) std::atomic_fetch_sub_explicit(value, 1, std::memory_order_acq_rel) + #if defined(__PYX_DEBUG_ATOMICS) && defined(_MSC_VER) + #pragma message ("Using standard C++ atomics") + #elif defined(__PYX_DEBUG_ATOMICS) + #warning "Using standard C++ atomics" + #endif +#elif CYTHON_ATOMICS && (__GNUC__ >= 5 || (__GNUC__ == 4 &&\ + (__GNUC_MINOR__ > 1 ||\ + (__GNUC_MINOR__ == 1 && __GNUC_PATCHLEVEL__ >= 2)))) + #define __pyx_atomic_incr_aligned(value) __sync_fetch_and_add(value, 1) + #define __pyx_atomic_decr_aligned(value) __sync_fetch_and_sub(value, 1) + #ifdef __PYX_DEBUG_ATOMICS + #warning "Using GNU atomics" + #endif +#elif CYTHON_ATOMICS && defined(_MSC_VER) + #include + #undef __pyx_atomic_int_type + #define __pyx_atomic_int_type long + #undef __pyx_nonatomic_int_type + #define __pyx_nonatomic_int_type long + #pragma intrinsic (_InterlockedExchangeAdd) + #define __pyx_atomic_incr_aligned(value) _InterlockedExchangeAdd(value, 1) + #define __pyx_atomic_decr_aligned(value) _InterlockedExchangeAdd(value, -1) + #ifdef __PYX_DEBUG_ATOMICS + #pragma message ("Using MSVC atomics") + #endif +#else + #undef CYTHON_ATOMICS + #define CYTHON_ATOMICS 0 + #ifdef __PYX_DEBUG_ATOMICS + #warning "Not using atomics" + #endif +#endif +#if CYTHON_ATOMICS + #define __pyx_add_acquisition_count(memview)\ + __pyx_atomic_incr_aligned(__pyx_get_slice_count_pointer(memview)) + #define __pyx_sub_acquisition_count(memview)\ + __pyx_atomic_decr_aligned(__pyx_get_slice_count_pointer(memview)) +#else + #define __pyx_add_acquisition_count(memview)\ + __pyx_add_acquisition_count_locked(__pyx_get_slice_count_pointer(memview), memview->lock) + #define __pyx_sub_acquisition_count(memview)\ + __pyx_sub_acquisition_count_locked(__pyx_get_slice_count_pointer(memview), memview->lock) +#endif + +/* MemviewSliceStruct.proto */ +struct __pyx_memoryview_obj; +typedef struct { + struct __pyx_memoryview_obj *memview; + char *data; + Py_ssize_t shape[8]; + Py_ssize_t strides[8]; + Py_ssize_t suboffsets[8]; +} __Pyx_memviewslice; +#define __Pyx_MemoryView_Len(m) (m.shape[0]) + +/* #### Code section: numeric_typedefs ### */ + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":730 + * # in Cython to enable them only on the right systems. + * + * ctypedef npy_int8 int8_t # <<<<<<<<<<<<<< + * ctypedef npy_int16 int16_t + * ctypedef npy_int32 int32_t + */ +typedef npy_int8 __pyx_t_5numpy_int8_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":731 + * + * ctypedef npy_int8 int8_t + * ctypedef npy_int16 int16_t # <<<<<<<<<<<<<< + * ctypedef npy_int32 int32_t + * ctypedef npy_int64 int64_t + */ +typedef npy_int16 __pyx_t_5numpy_int16_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":732 + * ctypedef npy_int8 int8_t + * ctypedef npy_int16 int16_t + * ctypedef npy_int32 int32_t # <<<<<<<<<<<<<< + * ctypedef npy_int64 int64_t + * #ctypedef npy_int96 int96_t + */ +typedef npy_int32 __pyx_t_5numpy_int32_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":733 + * ctypedef npy_int16 int16_t + * ctypedef npy_int32 int32_t + * ctypedef npy_int64 int64_t # <<<<<<<<<<<<<< + * #ctypedef npy_int96 int96_t + * #ctypedef npy_int128 int128_t + */ +typedef npy_int64 __pyx_t_5numpy_int64_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":737 + * #ctypedef npy_int128 int128_t + * + * ctypedef npy_uint8 uint8_t # <<<<<<<<<<<<<< + * ctypedef npy_uint16 uint16_t + * ctypedef npy_uint32 uint32_t + */ +typedef npy_uint8 __pyx_t_5numpy_uint8_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":738 + * + * ctypedef npy_uint8 uint8_t + * ctypedef npy_uint16 uint16_t # <<<<<<<<<<<<<< + * ctypedef npy_uint32 uint32_t + * ctypedef npy_uint64 uint64_t + */ +typedef npy_uint16 __pyx_t_5numpy_uint16_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":739 + * ctypedef npy_uint8 uint8_t + * ctypedef npy_uint16 uint16_t + * ctypedef npy_uint32 uint32_t # <<<<<<<<<<<<<< + * ctypedef npy_uint64 uint64_t + * #ctypedef npy_uint96 uint96_t + */ +typedef npy_uint32 __pyx_t_5numpy_uint32_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":740 + * ctypedef npy_uint16 uint16_t + * ctypedef npy_uint32 uint32_t + * ctypedef npy_uint64 uint64_t # <<<<<<<<<<<<<< + * #ctypedef npy_uint96 uint96_t + * #ctypedef npy_uint128 uint128_t + */ +typedef npy_uint64 __pyx_t_5numpy_uint64_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":744 + * #ctypedef npy_uint128 uint128_t + * + * ctypedef npy_float32 float32_t # <<<<<<<<<<<<<< + * ctypedef npy_float64 float64_t + * #ctypedef npy_float80 float80_t + */ +typedef npy_float32 __pyx_t_5numpy_float32_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":745 + * + * ctypedef npy_float32 float32_t + * ctypedef npy_float64 float64_t # <<<<<<<<<<<<<< + * #ctypedef npy_float80 float80_t + * #ctypedef npy_float128 float128_t + */ +typedef npy_float64 __pyx_t_5numpy_float64_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":754 + * # The int types are mapped a bit surprising -- + * # numpy.int corresponds to 'l' and numpy.long to 'q' + * ctypedef npy_long int_t # <<<<<<<<<<<<<< + * ctypedef npy_longlong longlong_t + * + */ +typedef npy_long __pyx_t_5numpy_int_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":755 + * # numpy.int corresponds to 'l' and numpy.long to 'q' + * ctypedef npy_long int_t + * ctypedef npy_longlong longlong_t # <<<<<<<<<<<<<< + * + * ctypedef npy_ulong uint_t + */ +typedef npy_longlong __pyx_t_5numpy_longlong_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":757 + * ctypedef npy_longlong longlong_t + * + * ctypedef npy_ulong uint_t # <<<<<<<<<<<<<< + * ctypedef npy_ulonglong ulonglong_t + * + */ +typedef npy_ulong __pyx_t_5numpy_uint_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":758 + * + * ctypedef npy_ulong uint_t + * ctypedef npy_ulonglong ulonglong_t # <<<<<<<<<<<<<< + * + * ctypedef npy_intp intp_t + */ +typedef npy_ulonglong __pyx_t_5numpy_ulonglong_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":760 + * ctypedef npy_ulonglong ulonglong_t + * + * ctypedef npy_intp intp_t # <<<<<<<<<<<<<< + * ctypedef npy_uintp uintp_t + * + */ +typedef npy_intp __pyx_t_5numpy_intp_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":761 + * + * ctypedef npy_intp intp_t + * ctypedef npy_uintp uintp_t # <<<<<<<<<<<<<< + * + * ctypedef npy_double float_t + */ +typedef npy_uintp __pyx_t_5numpy_uintp_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":763 + * ctypedef npy_uintp uintp_t + * + * ctypedef npy_double float_t # <<<<<<<<<<<<<< + * ctypedef npy_double double_t + * ctypedef npy_longdouble longdouble_t + */ +typedef npy_double __pyx_t_5numpy_float_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":764 + * + * ctypedef npy_double float_t + * ctypedef npy_double double_t # <<<<<<<<<<<<<< + * ctypedef npy_longdouble longdouble_t + * + */ +typedef npy_double __pyx_t_5numpy_double_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":765 + * ctypedef npy_double float_t + * ctypedef npy_double double_t + * ctypedef npy_longdouble longdouble_t # <<<<<<<<<<<<<< + * + * ctypedef npy_cfloat cfloat_t + */ +typedef npy_longdouble __pyx_t_5numpy_longdouble_t; +/* #### Code section: complex_type_declarations ### */ +/* Declarations.proto */ +#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #ifdef __cplusplus + typedef ::std::complex< float > __pyx_t_float_complex; + #else + typedef float _Complex __pyx_t_float_complex; + #endif +#else + typedef struct { float real, imag; } __pyx_t_float_complex; +#endif +static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float, float); + +/* Declarations.proto */ +#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #ifdef __cplusplus + typedef ::std::complex< double > __pyx_t_double_complex; + #else + typedef double _Complex __pyx_t_double_complex; + #endif +#else + typedef struct { double real, imag; } __pyx_t_double_complex; +#endif +static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double, double); + +/* #### Code section: type_declarations ### */ + +/*--- Type declarations ---*/ +struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_CLContext; +struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf; +struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext; +struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem; +struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame; +struct __pyx_array_obj; +struct __pyx_MemviewEnum_obj; +struct __pyx_memoryview_obj; +struct __pyx_memoryviewslice_obj; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":767 + * ctypedef npy_longdouble longdouble_t + * + * ctypedef npy_cfloat cfloat_t # <<<<<<<<<<<<<< + * ctypedef npy_cdouble cdouble_t + * ctypedef npy_clongdouble clongdouble_t + */ +typedef npy_cfloat __pyx_t_5numpy_cfloat_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":768 + * + * ctypedef npy_cfloat cfloat_t + * ctypedef npy_cdouble cdouble_t # <<<<<<<<<<<<<< + * ctypedef npy_clongdouble clongdouble_t + * + */ +typedef npy_cdouble __pyx_t_5numpy_cdouble_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":769 + * ctypedef npy_cfloat cfloat_t + * ctypedef npy_cdouble cdouble_t + * ctypedef npy_clongdouble clongdouble_t # <<<<<<<<<<<<<< + * + * ctypedef npy_cdouble complex_t + */ +typedef npy_clongdouble __pyx_t_5numpy_clongdouble_t; + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":771 + * ctypedef npy_clongdouble clongdouble_t + * + * ctypedef npy_cdouble complex_t # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew1(a): + */ +typedef npy_cdouble __pyx_t_5numpy_complex_t; + +/* "cereal/visionipc/visionipc_pyx.pxd":7 + * from .visionipc cimport cl_device_id, cl_context + * + * cdef class CLContext: # <<<<<<<<<<<<<< + * cdef cl_device_id device_id + * cdef cl_context context + */ +struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_CLContext { + PyObject_HEAD + cl_device_id device_id; + cl_context context; +}; + + +/* "cereal/visionipc/visionipc_pyx.pxd":11 + * cdef cl_context context + * + * cdef class VisionBuf: # <<<<<<<<<<<<<< + * cdef cppVisionBuf * buf + * + */ +struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf { + PyObject_HEAD + struct __pyx_vtabstruct_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_vtab; + VisionBuf *buf; +}; + + +/* "selfdrive/modeld/models/commonmodel_pyx.pxd":6 + * from cereal.visionipc.visionipc_pyx cimport CLContext as BaseCLContext + * + * cdef class CLContext(BaseCLContext): # <<<<<<<<<<<<<< + * pass + * + */ +struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext { + struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_CLContext __pyx_base; +}; + + +/* "selfdrive/modeld/models/commonmodel_pyx.pxd":9 + * pass + * + * cdef class CLMem: # <<<<<<<<<<<<<< + * cdef cl_mem * mem + * + */ +struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem { + PyObject_HEAD + struct __pyx_vtabstruct_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem *__pyx_vtab; + cl_mem *mem; +}; + + +/* "selfdrive/modeld/models/commonmodel_pyx.pyx":28 + * return mem + * + * cdef class ModelFrame: # <<<<<<<<<<<<<< + * cdef cppModelFrame * frame + * + */ +struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame { + PyObject_HEAD + ModelFrame *frame; +}; + + +/* "View.MemoryView":114 + * @cython.collection_type("sequence") + * @cname("__pyx_array") + * cdef class array: # <<<<<<<<<<<<<< + * + * cdef: + */ +struct __pyx_array_obj { + PyObject_HEAD + struct __pyx_vtabstruct_array *__pyx_vtab; + char *data; + Py_ssize_t len; + char *format; + int ndim; + Py_ssize_t *_shape; + Py_ssize_t *_strides; + Py_ssize_t itemsize; + PyObject *mode; + PyObject *_format; + void (*callback_free_data)(void *); + int free_data; + int dtype_is_object; +}; + + +/* "View.MemoryView":302 + * + * @cname('__pyx_MemviewEnum') + * cdef class Enum(object): # <<<<<<<<<<<<<< + * cdef object name + * def __init__(self, name): + */ +struct __pyx_MemviewEnum_obj { + PyObject_HEAD + PyObject *name; +}; + + +/* "View.MemoryView":337 + * + * @cname('__pyx_memoryview') + * cdef class memoryview: # <<<<<<<<<<<<<< + * + * cdef object obj + */ +struct __pyx_memoryview_obj { + PyObject_HEAD + struct __pyx_vtabstruct_memoryview *__pyx_vtab; + PyObject *obj; + PyObject *_size; + PyObject *_array_interface; + PyThread_type_lock lock; + __pyx_atomic_int_type acquisition_count; + Py_buffer view; + int flags; + int dtype_is_object; + __Pyx_TypeInfo *typeinfo; +}; + + +/* "View.MemoryView":952 + * @cython.collection_type("sequence") + * @cname('__pyx_memoryviewslice') + * cdef class _memoryviewslice(memoryview): # <<<<<<<<<<<<<< + * "Internal class for passing memoryview slices to Python" + * + */ +struct __pyx_memoryviewslice_obj { + struct __pyx_memoryview_obj __pyx_base; + __Pyx_memviewslice from_slice; + PyObject *from_object; + PyObject *(*to_object_func)(char *); + int (*to_dtype_func)(char *, PyObject *); +}; + + + +/* "cereal/visionipc/visionipc_pyx.pxd":11 + * cdef cl_context context + * + * cdef class VisionBuf: # <<<<<<<<<<<<<< + * cdef cppVisionBuf * buf + * + */ + +struct __pyx_vtabstruct_6cereal_9visionipc_13visionipc_pyx_VisionBuf { + PyObject *(*create)(VisionBuf *); +}; +static struct __pyx_vtabstruct_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_vtabptr_6cereal_9visionipc_13visionipc_pyx_VisionBuf; + + +/* "selfdrive/modeld/models/commonmodel_pyx.pyx":21 + * self.context = cl_create_context(self.device_id) + * + * cdef class CLMem: # <<<<<<<<<<<<<< + * @staticmethod + * cdef create(void * cmem): + */ + +struct __pyx_vtabstruct_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem { + PyObject *(*create)(void *); +}; +static struct __pyx_vtabstruct_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem *__pyx_vtabptr_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem; + + +/* "View.MemoryView":114 + * @cython.collection_type("sequence") + * @cname("__pyx_array") + * cdef class array: # <<<<<<<<<<<<<< + * + * cdef: + */ + +struct __pyx_vtabstruct_array { + PyObject *(*get_memview)(struct __pyx_array_obj *); +}; +static struct __pyx_vtabstruct_array *__pyx_vtabptr_array; + + +/* "View.MemoryView":337 + * + * @cname('__pyx_memoryview') + * cdef class memoryview: # <<<<<<<<<<<<<< + * + * cdef object obj + */ + +struct __pyx_vtabstruct_memoryview { + char *(*get_item_pointer)(struct __pyx_memoryview_obj *, PyObject *); + PyObject *(*is_slice)(struct __pyx_memoryview_obj *, PyObject *); + PyObject *(*setitem_slice_assignment)(struct __pyx_memoryview_obj *, PyObject *, PyObject *); + PyObject *(*setitem_slice_assign_scalar)(struct __pyx_memoryview_obj *, struct __pyx_memoryview_obj *, PyObject *); + PyObject *(*setitem_indexed)(struct __pyx_memoryview_obj *, PyObject *, PyObject *); + PyObject *(*convert_item_to_object)(struct __pyx_memoryview_obj *, char *); + PyObject *(*assign_item_from_object)(struct __pyx_memoryview_obj *, char *, PyObject *); + PyObject *(*_get_base)(struct __pyx_memoryview_obj *); +}; +static struct __pyx_vtabstruct_memoryview *__pyx_vtabptr_memoryview; + + +/* "View.MemoryView":952 + * @cython.collection_type("sequence") + * @cname('__pyx_memoryviewslice') + * cdef class _memoryviewslice(memoryview): # <<<<<<<<<<<<<< + * "Internal class for passing memoryview slices to Python" + * + */ + +struct __pyx_vtabstruct__memoryviewslice { + struct __pyx_vtabstruct_memoryview __pyx_base; +}; +static struct __pyx_vtabstruct__memoryviewslice *__pyx_vtabptr__memoryviewslice; +/* #### Code section: utility_code_proto ### */ + +/* --- Runtime support code (head) --- */ +/* Refnanny.proto */ +#ifndef CYTHON_REFNANNY + #define CYTHON_REFNANNY 0 +#endif +#if CYTHON_REFNANNY + typedef struct { + void (*INCREF)(void*, PyObject*, Py_ssize_t); + void (*DECREF)(void*, PyObject*, Py_ssize_t); + void (*GOTREF)(void*, PyObject*, Py_ssize_t); + void (*GIVEREF)(void*, PyObject*, Py_ssize_t); + void* (*SetupContext)(const char*, Py_ssize_t, const char*); + void (*FinishContext)(void**); + } __Pyx_RefNannyAPIStruct; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNanny = NULL; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname); + #define __Pyx_RefNannyDeclarations void *__pyx_refnanny = NULL; +#ifdef WITH_THREAD + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + if (acquire_gil) {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + PyGILState_Release(__pyx_gilstate_save);\ + } else {\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + } + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } +#else + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__)) + #define __Pyx_RefNannyFinishContextNogil() __Pyx_RefNannyFinishContext() +#endif + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } + #define __Pyx_RefNannyFinishContext()\ + __Pyx_RefNanny->FinishContext(&__pyx_refnanny) + #define __Pyx_INCREF(r) __Pyx_RefNanny->INCREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_DECREF(r) __Pyx_RefNanny->DECREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GOTREF(r) __Pyx_RefNanny->GOTREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GIVEREF(r) __Pyx_RefNanny->GIVEREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_XINCREF(r) do { if((r) == NULL); else {__Pyx_INCREF(r); }} while(0) + #define __Pyx_XDECREF(r) do { if((r) == NULL); else {__Pyx_DECREF(r); }} while(0) + #define __Pyx_XGOTREF(r) do { if((r) == NULL); else {__Pyx_GOTREF(r); }} while(0) + #define __Pyx_XGIVEREF(r) do { if((r) == NULL); else {__Pyx_GIVEREF(r);}} while(0) +#else + #define __Pyx_RefNannyDeclarations + #define __Pyx_RefNannySetupContext(name, acquire_gil) + #define __Pyx_RefNannyFinishContextNogil() + #define __Pyx_RefNannyFinishContext() + #define __Pyx_INCREF(r) Py_INCREF(r) + #define __Pyx_DECREF(r) Py_DECREF(r) + #define __Pyx_GOTREF(r) + #define __Pyx_GIVEREF(r) + #define __Pyx_XINCREF(r) Py_XINCREF(r) + #define __Pyx_XDECREF(r) Py_XDECREF(r) + #define __Pyx_XGOTREF(r) + #define __Pyx_XGIVEREF(r) +#endif +#define __Pyx_Py_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; Py_XDECREF(tmp);\ + } while (0) +#define __Pyx_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_XDECREF(tmp);\ + } while (0) +#define __Pyx_DECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_DECREF(tmp);\ + } while (0) +#define __Pyx_CLEAR(r) do { PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);} while(0) +#define __Pyx_XCLEAR(r) do { if((r) != NULL) {PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);}} while(0) + +/* PyErrExceptionMatches.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_ExceptionMatches(err) __Pyx_PyErr_ExceptionMatchesInState(__pyx_tstate, err) +static CYTHON_INLINE int __Pyx_PyErr_ExceptionMatchesInState(PyThreadState* tstate, PyObject* err); +#else +#define __Pyx_PyErr_ExceptionMatches(err) PyErr_ExceptionMatches(err) +#endif + +/* PyThreadStateGet.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyThreadState_declare PyThreadState *__pyx_tstate; +#define __Pyx_PyThreadState_assign __pyx_tstate = __Pyx_PyThreadState_Current; +#if PY_VERSION_HEX >= 0x030C00A6 +#define __Pyx_PyErr_Occurred() (__pyx_tstate->current_exception != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->current_exception ? (PyObject*) Py_TYPE(__pyx_tstate->current_exception) : (PyObject*) NULL) +#else +#define __Pyx_PyErr_Occurred() (__pyx_tstate->curexc_type != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->curexc_type) +#endif +#else +#define __Pyx_PyThreadState_declare +#define __Pyx_PyThreadState_assign +#define __Pyx_PyErr_Occurred() (PyErr_Occurred() != NULL) +#define __Pyx_PyErr_CurrentExceptionType() PyErr_Occurred() +#endif + +/* PyErrFetchRestore.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_Clear() __Pyx_ErrRestore(NULL, NULL, NULL) +#define __Pyx_ErrRestoreWithState(type, value, tb) __Pyx_ErrRestoreInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) __Pyx_ErrFetchInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) __Pyx_ErrRestoreInState(__pyx_tstate, type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) __Pyx_ErrFetchInState(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb); +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A6 +#define __Pyx_PyErr_SetNone(exc) (Py_INCREF(exc), __Pyx_ErrRestore((exc), NULL, NULL)) +#else +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#endif +#else +#define __Pyx_PyErr_Clear() PyErr_Clear() +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#define __Pyx_ErrRestoreWithState(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestoreInState(tstate, type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchInState(tstate, type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) PyErr_Fetch(type, value, tb) +#endif + +/* PyObjectGetAttrStr.proto */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GetAttrStr(o,n) PyObject_GetAttr(o,n) +#endif + +/* PyObjectGetAttrStrNoError.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name); + +/* GetBuiltinName.proto */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name); + +/* TupleAndListFromArray.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n); +static CYTHON_INLINE PyObject* __Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n); +#endif + +/* IncludeStringH.proto */ +#include + +/* BytesEquals.proto */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals); + +/* UnicodeEquals.proto */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals); + +/* fastcall.proto */ +#if CYTHON_AVOID_BORROWED_REFS + #define __Pyx_Arg_VARARGS(args, i) PySequence_GetItem(args, i) +#elif CYTHON_ASSUME_SAFE_MACROS + #define __Pyx_Arg_VARARGS(args, i) PyTuple_GET_ITEM(args, i) +#else + #define __Pyx_Arg_VARARGS(args, i) PyTuple_GetItem(args, i) +#endif +#if CYTHON_AVOID_BORROWED_REFS + #define __Pyx_Arg_NewRef_VARARGS(arg) __Pyx_NewRef(arg) + #define __Pyx_Arg_XDECREF_VARARGS(arg) Py_XDECREF(arg) +#else + #define __Pyx_Arg_NewRef_VARARGS(arg) arg + #define __Pyx_Arg_XDECREF_VARARGS(arg) +#endif +#define __Pyx_NumKwargs_VARARGS(kwds) PyDict_Size(kwds) +#define __Pyx_KwValues_VARARGS(args, nargs) NULL +#define __Pyx_GetKwValue_VARARGS(kw, kwvalues, s) __Pyx_PyDict_GetItemStrWithError(kw, s) +#define __Pyx_KwargsAsDict_VARARGS(kw, kwvalues) PyDict_Copy(kw) +#if CYTHON_METH_FASTCALL + #define __Pyx_Arg_FASTCALL(args, i) args[i] + #define __Pyx_NumKwargs_FASTCALL(kwds) PyTuple_GET_SIZE(kwds) + #define __Pyx_KwValues_FASTCALL(args, nargs) ((args) + (nargs)) + static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 + CYTHON_UNUSED static PyObject *__Pyx_KwargsAsDict_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues); + #else + #define __Pyx_KwargsAsDict_FASTCALL(kw, kwvalues) _PyStack_AsDict(kwvalues, kw) + #endif + #define __Pyx_Arg_NewRef_FASTCALL(arg) arg /* no-op, __Pyx_Arg_FASTCALL is direct and this needs + to have the same reference counting */ + #define __Pyx_Arg_XDECREF_FASTCALL(arg) +#else + #define __Pyx_Arg_FASTCALL __Pyx_Arg_VARARGS + #define __Pyx_NumKwargs_FASTCALL __Pyx_NumKwargs_VARARGS + #define __Pyx_KwValues_FASTCALL __Pyx_KwValues_VARARGS + #define __Pyx_GetKwValue_FASTCALL __Pyx_GetKwValue_VARARGS + #define __Pyx_KwargsAsDict_FASTCALL __Pyx_KwargsAsDict_VARARGS + #define __Pyx_Arg_NewRef_FASTCALL(arg) __Pyx_Arg_NewRef_VARARGS(arg) + #define __Pyx_Arg_XDECREF_FASTCALL(arg) __Pyx_Arg_XDECREF_VARARGS(arg) +#endif +#if CYTHON_COMPILING_IN_CPYTHON && CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_VARARGS(args, start), stop - start) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_FASTCALL(args, start), stop - start) +#else +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) PyTuple_GetSlice(args, start, stop) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) PyTuple_GetSlice(args, start, stop) +#endif + +/* RaiseArgTupleInvalid.proto */ +static void __Pyx_RaiseArgtupleInvalid(const char* func_name, int exact, + Py_ssize_t num_min, Py_ssize_t num_max, Py_ssize_t num_found); + +/* RaiseDoubleKeywords.proto */ +static void __Pyx_RaiseDoubleKeywordsError(const char* func_name, PyObject* kw_name); + +/* ParseKeywords.proto */ +static int __Pyx_ParseOptionalKeywords(PyObject *kwds, PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, PyObject *values[], Py_ssize_t num_pos_args, + const char* function_name); + +/* ArgTypeTest.proto */ +#define __Pyx_ArgTypeTest(obj, type, none_allowed, name, exact)\ + ((likely(__Pyx_IS_TYPE(obj, type) | (none_allowed && (obj == Py_None)))) ? 1 :\ + __Pyx__ArgTypeTest(obj, type, name, exact)) +static int __Pyx__ArgTypeTest(PyObject *obj, PyTypeObject *type, const char *name, int exact); + +/* RaiseException.proto */ +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause); + +/* PyFunctionFastCall.proto */ +#if CYTHON_FAST_PYCALL +#if !CYTHON_VECTORCALL +#define __Pyx_PyFunction_FastCall(func, args, nargs)\ + __Pyx_PyFunction_FastCallDict((func), (args), (nargs), NULL) +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs); +#endif +#define __Pyx_BUILD_ASSERT_EXPR(cond)\ + (sizeof(char [1 - 2*!(cond)]) - 1) +#ifndef Py_MEMBER_SIZE +#define Py_MEMBER_SIZE(type, member) sizeof(((type *)0)->member) +#endif +#if !CYTHON_VECTORCALL +#if PY_VERSION_HEX >= 0x03080000 + #include "frameobject.h" +#if PY_VERSION_HEX >= 0x030b00a6 && !CYTHON_COMPILING_IN_LIMITED_API + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif + #define __Pxy_PyFrame_Initialize_Offsets() + #define __Pyx_PyFrame_GetLocalsplus(frame) ((frame)->f_localsplus) +#else + static size_t __pyx_pyframe_localsplus_offset = 0; + #include "frameobject.h" + #define __Pxy_PyFrame_Initialize_Offsets()\ + ((void)__Pyx_BUILD_ASSERT_EXPR(sizeof(PyFrameObject) == offsetof(PyFrameObject, f_localsplus) + Py_MEMBER_SIZE(PyFrameObject, f_localsplus)),\ + (void)(__pyx_pyframe_localsplus_offset = ((size_t)PyFrame_Type.tp_basicsize) - Py_MEMBER_SIZE(PyFrameObject, f_localsplus))) + #define __Pyx_PyFrame_GetLocalsplus(frame)\ + (assert(__pyx_pyframe_localsplus_offset), (PyObject **)(((char *)(frame)) + __pyx_pyframe_localsplus_offset)) +#endif +#endif +#endif + +/* PyObjectCall.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw); +#else +#define __Pyx_PyObject_Call(func, arg, kw) PyObject_Call(func, arg, kw) +#endif + +/* PyObjectCallMethO.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg); +#endif + +/* PyObjectFastCall.proto */ +#define __Pyx_PyObject_FastCall(func, args, nargs) __Pyx_PyObject_FastCallDict(func, args, (size_t)(nargs), NULL) +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs); + +/* RaiseUnexpectedTypeError.proto */ +static int __Pyx_RaiseUnexpectedTypeError(const char *expected, PyObject *obj); + +/* GCCDiagnostics.proto */ +#if !defined(__INTEL_COMPILER) && defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 6)) +#define __Pyx_HAS_GCC_DIAGNOSTIC +#endif + +/* BuildPyUnicode.proto */ +static PyObject* __Pyx_PyUnicode_BuildFromAscii(Py_ssize_t ulength, char* chars, int clength, + int prepend_sign, char padding_char); + +/* CIntToPyUnicode.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_int(int value, Py_ssize_t width, char padding_char, char format_char); + +/* CIntToPyUnicode.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_Py_ssize_t(Py_ssize_t value, Py_ssize_t width, char padding_char, char format_char); + +/* JoinPyUnicode.proto */ +static PyObject* __Pyx_PyUnicode_Join(PyObject* value_tuple, Py_ssize_t value_count, Py_ssize_t result_ulength, + Py_UCS4 max_char); + +/* StrEquals.proto */ +#if PY_MAJOR_VERSION >= 3 +#define __Pyx_PyString_Equals __Pyx_PyUnicode_Equals +#else +#define __Pyx_PyString_Equals __Pyx_PyBytes_Equals +#endif + +/* PyObjectFormatSimple.proto */ +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + PyObject_Format(s, f)) +#elif PY_MAJOR_VERSION < 3 + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + likely(PyString_CheckExact(s)) ? PyUnicode_FromEncodedObject(s, NULL, "strict") :\ + PyObject_Format(s, f)) +#elif CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + likely(PyLong_CheckExact(s)) ? PyLong_Type.tp_repr(s) :\ + likely(PyFloat_CheckExact(s)) ? PyFloat_Type.tp_repr(s) :\ + PyObject_Format(s, f)) +#else + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + PyObject_Format(s, f)) +#endif + +CYTHON_UNUSED static int __pyx_array_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +static PyObject *__pyx_array_get_memview(struct __pyx_array_obj *); /*proto*/ +/* GetAttr.proto */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr(PyObject *, PyObject *); + +/* GetItemInt.proto */ +#define __Pyx_GetItemInt(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_Fast(o, (Py_ssize_t)i, is_list, wraparound, boundscheck) :\ + (is_list ? (PyErr_SetString(PyExc_IndexError, "list index out of range"), (PyObject*)NULL) :\ + __Pyx_GetItemInt_Generic(o, to_py_func(i)))) +#define __Pyx_GetItemInt_List(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_List_Fast(o, (Py_ssize_t)i, wraparound, boundscheck) :\ + (PyErr_SetString(PyExc_IndexError, "list index out of range"), (PyObject*)NULL)) +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_List_Fast(PyObject *o, Py_ssize_t i, + int wraparound, int boundscheck); +#define __Pyx_GetItemInt_Tuple(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_Tuple_Fast(o, (Py_ssize_t)i, wraparound, boundscheck) :\ + (PyErr_SetString(PyExc_IndexError, "tuple index out of range"), (PyObject*)NULL)) +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Tuple_Fast(PyObject *o, Py_ssize_t i, + int wraparound, int boundscheck); +static PyObject *__Pyx_GetItemInt_Generic(PyObject *o, PyObject* j); +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Fast(PyObject *o, Py_ssize_t i, + int is_list, int wraparound, int boundscheck); + +/* PyObjectCallOneArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg); + +/* ObjectGetItem.proto */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject *__Pyx_PyObject_GetItem(PyObject *obj, PyObject *key); +#else +#define __Pyx_PyObject_GetItem(obj, key) PyObject_GetItem(obj, key) +#endif + +/* KeywordStringCheck.proto */ +static int __Pyx_CheckKeywordStrings(PyObject *kw, const char* function_name, int kw_allowed); + +/* DivInt[Py_ssize_t].proto */ +static CYTHON_INLINE Py_ssize_t __Pyx_div_Py_ssize_t(Py_ssize_t, Py_ssize_t); + +/* UnaryNegOverflows.proto */ +#define __Pyx_UNARY_NEG_WOULD_OVERFLOW(x)\ + (((x) < 0) & ((unsigned long)(x) == 0-(unsigned long)(x))) + +/* GetAttr3.proto */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr3(PyObject *, PyObject *, PyObject *); + +/* PyDictVersioning.proto */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +#define __PYX_DICT_VERSION_INIT ((PY_UINT64_T) -1) +#define __PYX_GET_DICT_VERSION(dict) (((PyDictObject*)(dict))->ma_version_tag) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var)\ + (version_var) = __PYX_GET_DICT_VERSION(dict);\ + (cache_var) = (value); +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + if (likely(__PYX_GET_DICT_VERSION(DICT) == __pyx_dict_version)) {\ + (VAR) = __pyx_dict_cached_value;\ + } else {\ + (VAR) = __pyx_dict_cached_value = (LOOKUP);\ + __pyx_dict_version = __PYX_GET_DICT_VERSION(DICT);\ + }\ +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj); +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj); +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version); +#else +#define __PYX_GET_DICT_VERSION(dict) (0) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var) +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) (VAR) = (LOOKUP); +#endif + +/* GetModuleGlobalName.proto */ +#if CYTHON_USE_DICT_VERSIONS +#define __Pyx_GetModuleGlobalName(var, name) do {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + (var) = (likely(__pyx_dict_version == __PYX_GET_DICT_VERSION(__pyx_d))) ?\ + (likely(__pyx_dict_cached_value) ? __Pyx_NewRef(__pyx_dict_cached_value) : __Pyx_GetBuiltinName(name)) :\ + __Pyx__GetModuleGlobalName(name, &__pyx_dict_version, &__pyx_dict_cached_value);\ +} while(0) +#define __Pyx_GetModuleGlobalNameUncached(var, name) do {\ + PY_UINT64_T __pyx_dict_version;\ + PyObject *__pyx_dict_cached_value;\ + (var) = __Pyx__GetModuleGlobalName(name, &__pyx_dict_version, &__pyx_dict_cached_value);\ +} while(0) +static PyObject *__Pyx__GetModuleGlobalName(PyObject *name, PY_UINT64_T *dict_version, PyObject **dict_cached_value); +#else +#define __Pyx_GetModuleGlobalName(var, name) (var) = __Pyx__GetModuleGlobalName(name) +#define __Pyx_GetModuleGlobalNameUncached(var, name) (var) = __Pyx__GetModuleGlobalName(name) +static CYTHON_INLINE PyObject *__Pyx__GetModuleGlobalName(PyObject *name); +#endif + +/* AssertionsEnabled.proto */ +#if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX < 0x02070600 && !defined(Py_OptimizeFlag) + #define __Pyx_init_assertions_enabled() (0) + #define __pyx_assertions_enabled() (1) +#elif CYTHON_COMPILING_IN_LIMITED_API || (CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030C0000) + static int __pyx_assertions_enabled_flag; + #define __pyx_assertions_enabled() (__pyx_assertions_enabled_flag) + static int __Pyx_init_assertions_enabled(void) { + PyObject *builtins, *debug, *debug_str; + int flag; + builtins = PyEval_GetBuiltins(); + if (!builtins) goto bad; + debug_str = PyUnicode_FromStringAndSize("__debug__", 9); + if (!debug_str) goto bad; + debug = PyObject_GetItem(builtins, debug_str); + Py_DECREF(debug_str); + if (!debug) goto bad; + flag = PyObject_IsTrue(debug); + Py_DECREF(debug); + if (flag == -1) goto bad; + __pyx_assertions_enabled_flag = flag; + return 0; + bad: + __pyx_assertions_enabled_flag = 1; + return -1; + } +#else + #define __Pyx_init_assertions_enabled() (0) + #define __pyx_assertions_enabled() (!Py_OptimizeFlag) +#endif + +/* RaiseTooManyValuesToUnpack.proto */ +static CYTHON_INLINE void __Pyx_RaiseTooManyValuesError(Py_ssize_t expected); + +/* RaiseNeedMoreValuesToUnpack.proto */ +static CYTHON_INLINE void __Pyx_RaiseNeedMoreValuesError(Py_ssize_t index); + +/* RaiseNoneIterError.proto */ +static CYTHON_INLINE void __Pyx_RaiseNoneNotIterableError(void); + +/* ExtTypeTest.proto */ +static CYTHON_INLINE int __Pyx_TypeTest(PyObject *obj, PyTypeObject *type); + +/* GetTopmostException.proto */ +#if CYTHON_USE_EXC_INFO_STACK && CYTHON_FAST_THREAD_STATE +static _PyErr_StackItem * __Pyx_PyErr_GetTopmostException(PyThreadState *tstate); +#endif + +/* SaveResetException.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_ExceptionSave(type, value, tb) __Pyx__ExceptionSave(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx__ExceptionSave(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#define __Pyx_ExceptionReset(type, value, tb) __Pyx__ExceptionReset(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx__ExceptionReset(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb); +#else +#define __Pyx_ExceptionSave(type, value, tb) PyErr_GetExcInfo(type, value, tb) +#define __Pyx_ExceptionReset(type, value, tb) PyErr_SetExcInfo(type, value, tb) +#endif + +/* GetException.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_GetException(type, value, tb) __Pyx__GetException(__pyx_tstate, type, value, tb) +static int __Pyx__GetException(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#else +static int __Pyx_GetException(PyObject **type, PyObject **value, PyObject **tb); +#endif + +/* SwapException.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_ExceptionSwap(type, value, tb) __Pyx__ExceptionSwap(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx__ExceptionSwap(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#else +static CYTHON_INLINE void __Pyx_ExceptionSwap(PyObject **type, PyObject **value, PyObject **tb); +#endif + +/* Import.proto */ +static PyObject *__Pyx_Import(PyObject *name, PyObject *from_list, int level); + +/* ImportDottedModule.proto */ +static PyObject *__Pyx_ImportDottedModule(PyObject *name, PyObject *parts_tuple); +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_ImportDottedModule_WalkParts(PyObject *module, PyObject *name, PyObject *parts_tuple); +#endif + +/* FastTypeChecks.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_TypeCheck(obj, type) __Pyx_IsSubtype(Py_TYPE(obj), (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) __Pyx_IsAnySubtype2(Py_TYPE(obj), (PyTypeObject *)type1, (PyTypeObject *)type2) +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches(PyObject *err, PyObject *type); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches2(PyObject *err, PyObject *type1, PyObject *type2); +#else +#define __Pyx_TypeCheck(obj, type) PyObject_TypeCheck(obj, (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) (PyObject_TypeCheck(obj, (PyTypeObject *)type1) || PyObject_TypeCheck(obj, (PyTypeObject *)type2)) +#define __Pyx_PyErr_GivenExceptionMatches(err, type) PyErr_GivenExceptionMatches(err, type) +#define __Pyx_PyErr_GivenExceptionMatches2(err, type1, type2) (PyErr_GivenExceptionMatches(err, type1) || PyErr_GivenExceptionMatches(err, type2)) +#endif +#define __Pyx_PyErr_ExceptionMatches2(err1, err2) __Pyx_PyErr_GivenExceptionMatches2(__Pyx_PyErr_CurrentExceptionType(), err1, err2) +#define __Pyx_PyException_Check(obj) __Pyx_TypeCheck(obj, PyExc_Exception) + +CYTHON_UNUSED static int __pyx_memoryview_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +/* ListCompAppend.proto */ +#if CYTHON_USE_PYLIST_INTERNALS && CYTHON_ASSUME_SAFE_MACROS +static CYTHON_INLINE int __Pyx_ListComp_Append(PyObject* list, PyObject* x) { + PyListObject* L = (PyListObject*) list; + Py_ssize_t len = Py_SIZE(list); + if (likely(L->allocated > len)) { + Py_INCREF(x); + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 + L->ob_item[len] = x; + #else + PyList_SET_ITEM(list, len, x); + #endif + __Pyx_SET_SIZE(list, len + 1); + return 0; + } + return PyList_Append(list, x); +} +#else +#define __Pyx_ListComp_Append(L,x) PyList_Append(L,x) +#endif + +/* PySequenceMultiply.proto */ +#define __Pyx_PySequence_Multiply_Left(mul, seq) __Pyx_PySequence_Multiply(seq, mul) +static CYTHON_INLINE PyObject* __Pyx_PySequence_Multiply(PyObject *seq, Py_ssize_t mul); + +/* SetItemInt.proto */ +#define __Pyx_SetItemInt(o, i, v, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_SetItemInt_Fast(o, (Py_ssize_t)i, v, is_list, wraparound, boundscheck) :\ + (is_list ? (PyErr_SetString(PyExc_IndexError, "list assignment index out of range"), -1) :\ + __Pyx_SetItemInt_Generic(o, to_py_func(i), v))) +static int __Pyx_SetItemInt_Generic(PyObject *o, PyObject *j, PyObject *v); +static CYTHON_INLINE int __Pyx_SetItemInt_Fast(PyObject *o, Py_ssize_t i, PyObject *v, + int is_list, int wraparound, int boundscheck); + +/* RaiseUnboundLocalError.proto */ +static CYTHON_INLINE void __Pyx_RaiseUnboundLocalError(const char *varname); + +/* DivInt[long].proto */ +static CYTHON_INLINE long __Pyx_div_long(long, long); + +/* PySequenceContains.proto */ +static CYTHON_INLINE int __Pyx_PySequence_ContainsTF(PyObject* item, PyObject* seq, int eq) { + int result = PySequence_Contains(seq, item); + return unlikely(result < 0) ? result : (result == (eq == Py_EQ)); +} + +/* ImportFrom.proto */ +static PyObject* __Pyx_ImportFrom(PyObject* module, PyObject* name); + +/* HasAttr.proto */ +#if __PYX_LIMITED_VERSION_HEX >= 0x030d00A1 +#define __Pyx_HasAttr(o, n) PyObject_HasAttrWithError(o, n) +#else +static CYTHON_INLINE int __Pyx_HasAttr(PyObject *, PyObject *); +#endif + +/* ListAppend.proto */ +#if CYTHON_USE_PYLIST_INTERNALS && CYTHON_ASSUME_SAFE_MACROS +static CYTHON_INLINE int __Pyx_PyList_Append(PyObject* list, PyObject* x) { + PyListObject* L = (PyListObject*) list; + Py_ssize_t len = Py_SIZE(list); + if (likely(L->allocated > len) & likely(len > (L->allocated >> 1))) { + Py_INCREF(x); + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 + L->ob_item[len] = x; + #else + PyList_SET_ITEM(list, len, x); + #endif + __Pyx_SET_SIZE(list, len + 1); + return 0; + } + return PyList_Append(list, x); +} +#else +#define __Pyx_PyList_Append(L,x) PyList_Append(L,x) +#endif + +/* PyObjectCall2Args.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call2Args(PyObject* function, PyObject* arg1, PyObject* arg2); + +/* PyObjectGetMethod.proto */ +static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method); + +/* PyObjectCallMethod1.proto */ +static PyObject* __Pyx_PyObject_CallMethod1(PyObject* obj, PyObject* method_name, PyObject* arg); + +/* StringJoin.proto */ +#if PY_MAJOR_VERSION < 3 +#define __Pyx_PyString_Join __Pyx_PyBytes_Join +#define __Pyx_PyBaseString_Join(s, v) (PyUnicode_CheckExact(s) ? PyUnicode_Join(s, v) : __Pyx_PyBytes_Join(s, v)) +#else +#define __Pyx_PyString_Join PyUnicode_Join +#define __Pyx_PyBaseString_Join PyUnicode_Join +#endif +static CYTHON_INLINE PyObject* __Pyx_PyBytes_Join(PyObject* sep, PyObject* values); + +/* CIntToPyUnicode.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_size_t(size_t value, Py_ssize_t width, char padding_char, char format_char); + +/* PyObjectCallNoArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func); + +/* BufferIndexError.proto */ +static void __Pyx_RaiseBufferIndexError(int axis); + +/* PyObject_GenericGetAttrNoDict.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttrNoDict PyObject_GenericGetAttr +#endif + +/* PyObject_GenericGetAttr.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttr PyObject_GenericGetAttr +#endif + +/* TypeImport.proto */ +#ifndef __PYX_HAVE_RT_ImportType_proto_3_0_8 +#define __PYX_HAVE_RT_ImportType_proto_3_0_8 +#if defined (__STDC_VERSION__) && __STDC_VERSION__ >= 201112L +#include +#endif +#if (defined (__STDC_VERSION__) && __STDC_VERSION__ >= 201112L) || __cplusplus >= 201103L +#define __PYX_GET_STRUCT_ALIGNMENT_3_0_8(s) alignof(s) +#else +#define __PYX_GET_STRUCT_ALIGNMENT_3_0_8(s) sizeof(void*) +#endif +enum __Pyx_ImportType_CheckSize_3_0_8 { + __Pyx_ImportType_CheckSize_Error_3_0_8 = 0, + __Pyx_ImportType_CheckSize_Warn_3_0_8 = 1, + __Pyx_ImportType_CheckSize_Ignore_3_0_8 = 2 +}; +static PyTypeObject *__Pyx_ImportType_3_0_8(PyObject* module, const char *module_name, const char *class_name, size_t size, size_t alignment, enum __Pyx_ImportType_CheckSize_3_0_8 check_size); +#endif + +/* IncludeStructmemberH.proto */ +#include + +/* FixUpExtensionType.proto */ +#if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type); +#endif + +/* PyObjectCallMethod0.proto */ +static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name); + +/* ValidateBasesTuple.proto */ +#if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases); +#endif + +/* PyType_Ready.proto */ +CYTHON_UNUSED static int __Pyx_PyType_Ready(PyTypeObject *t); + +/* SetupReduce.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce(PyObject* type_obj); +#endif + +/* SetVTable.proto */ +static int __Pyx_SetVtable(PyTypeObject* typeptr , void* vtable); + +/* GetVTable.proto */ +static void* __Pyx_GetVtable(PyTypeObject *type); + +/* MergeVTables.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_MergeVtables(PyTypeObject *type); +#endif + +/* FetchSharedCythonModule.proto */ +static PyObject *__Pyx_FetchSharedCythonABIModule(void); + +/* FetchCommonType.proto */ +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type); +#else +static PyTypeObject* __Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases); +#endif + +/* PyMethodNew.proto */ +#if CYTHON_COMPILING_IN_LIMITED_API +static PyObject *__Pyx_PyMethod_New(PyObject *func, PyObject *self, PyObject *typ) { + PyObject *typesModule=NULL, *methodType=NULL, *result=NULL; + CYTHON_UNUSED_VAR(typ); + if (!self) + return __Pyx_NewRef(func); + typesModule = PyImport_ImportModule("types"); + if (!typesModule) return NULL; + methodType = PyObject_GetAttrString(typesModule, "MethodType"); + Py_DECREF(typesModule); + if (!methodType) return NULL; + result = PyObject_CallFunctionObjArgs(methodType, func, self, NULL); + Py_DECREF(methodType); + return result; +} +#elif PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_PyMethod_New(PyObject *func, PyObject *self, PyObject *typ) { + CYTHON_UNUSED_VAR(typ); + if (!self) + return __Pyx_NewRef(func); + return PyMethod_New(func, self); +} +#else + #define __Pyx_PyMethod_New PyMethod_New +#endif + +/* PyVectorcallFastCallDict.proto */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw); +#endif + +/* CythonFunctionShared.proto */ +#define __Pyx_CyFunction_USED +#define __Pyx_CYFUNCTION_STATICMETHOD 0x01 +#define __Pyx_CYFUNCTION_CLASSMETHOD 0x02 +#define __Pyx_CYFUNCTION_CCLASS 0x04 +#define __Pyx_CYFUNCTION_COROUTINE 0x08 +#define __Pyx_CyFunction_GetClosure(f)\ + (((__pyx_CyFunctionObject *) (f))->func_closure) +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_CyFunction_GetClassObj(f)\ + (((__pyx_CyFunctionObject *) (f))->func_classobj) +#else + #define __Pyx_CyFunction_GetClassObj(f)\ + ((PyObject*) ((PyCMethodObject *) (f))->mm_class) +#endif +#define __Pyx_CyFunction_SetClassObj(f, classobj)\ + __Pyx__CyFunction_SetClassObj((__pyx_CyFunctionObject *) (f), (classobj)) +#define __Pyx_CyFunction_Defaults(type, f)\ + ((type *)(((__pyx_CyFunctionObject *) (f))->defaults)) +#define __Pyx_CyFunction_SetDefaultsGetter(f, g)\ + ((__pyx_CyFunctionObject *) (f))->defaults_getter = (g) +typedef struct { +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject_HEAD + PyObject *func; +#elif PY_VERSION_HEX < 0x030900B1 + PyCFunctionObject func; +#else + PyCMethodObject func; +#endif +#if CYTHON_BACKPORT_VECTORCALL + __pyx_vectorcallfunc func_vectorcall; +#endif +#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API + PyObject *func_weakreflist; +#endif + PyObject *func_dict; + PyObject *func_name; + PyObject *func_qualname; + PyObject *func_doc; + PyObject *func_globals; + PyObject *func_code; + PyObject *func_closure; +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + PyObject *func_classobj; +#endif + void *defaults; + int defaults_pyobjects; + size_t defaults_size; + int flags; + PyObject *defaults_tuple; + PyObject *defaults_kwdict; + PyObject *(*defaults_getter)(PyObject *); + PyObject *func_annotations; + PyObject *func_is_coroutine; +} __pyx_CyFunctionObject; +#undef __Pyx_CyOrPyCFunction_Check +#define __Pyx_CyFunction_Check(obj) __Pyx_TypeCheck(obj, __pyx_CyFunctionType) +#define __Pyx_CyOrPyCFunction_Check(obj) __Pyx_TypeCheck2(obj, __pyx_CyFunctionType, &PyCFunction_Type) +#define __Pyx_CyFunction_CheckExact(obj) __Pyx_IS_TYPE(obj, __pyx_CyFunctionType) +static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc); +#undef __Pyx_IsSameCFunction +#define __Pyx_IsSameCFunction(func, cfunc) __Pyx__IsSameCyOrCFunction(func, cfunc) +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject* op, PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj); +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *m, + size_t size, + int pyobjects); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *m, + PyObject *tuple); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *m, + PyObject *dict); +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *m, + PyObject *dict); +static int __pyx_CyFunction_init(PyObject *module); +#if CYTHON_METH_FASTCALL +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +#if CYTHON_BACKPORT_VECTORCALL +#define __Pyx_CyFunction_func_vectorcall(f) (((__pyx_CyFunctionObject*)f)->func_vectorcall) +#else +#define __Pyx_CyFunction_func_vectorcall(f) (((PyCFunctionObject*)f)->vectorcall) +#endif +#endif + +/* CythonFunction.proto */ +static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); + +/* CLineInTraceback.proto */ +#ifdef CYTHON_CLINE_IN_TRACEBACK +#define __Pyx_CLineForTraceback(tstate, c_line) (((CYTHON_CLINE_IN_TRACEBACK)) ? c_line : 0) +#else +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line); +#endif + +/* CodeObjectCache.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +typedef struct { + PyCodeObject* code_object; + int code_line; +} __Pyx_CodeObjectCacheEntry; +struct __Pyx_CodeObjectCache { + int count; + int max_count; + __Pyx_CodeObjectCacheEntry* entries; +}; +static struct __Pyx_CodeObjectCache __pyx_code_cache = {0,0,NULL}; +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line); +static PyCodeObject *__pyx_find_code_object(int code_line); +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object); +#endif + +/* AddTraceback.proto */ +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename); + +#if PY_MAJOR_VERSION < 3 + static int __Pyx_GetBuffer(PyObject *obj, Py_buffer *view, int flags); + static void __Pyx_ReleaseBuffer(Py_buffer *view); +#else + #define __Pyx_GetBuffer PyObject_GetBuffer + #define __Pyx_ReleaseBuffer PyBuffer_Release +#endif + + +/* BufferStructDeclare.proto */ +typedef struct { + Py_ssize_t shape, strides, suboffsets; +} __Pyx_Buf_DimInfo; +typedef struct { + size_t refcount; + Py_buffer pybuffer; +} __Pyx_Buffer; +typedef struct { + __Pyx_Buffer *rcbuffer; + char *data; + __Pyx_Buf_DimInfo diminfo[8]; +} __Pyx_LocalBuf_ND; + +/* MemviewSliceIsContig.proto */ +static int __pyx_memviewslice_is_contig(const __Pyx_memviewslice mvs, char order, int ndim); + +/* OverlappingSlices.proto */ +static int __pyx_slices_overlap(__Pyx_memviewslice *slice1, + __Pyx_memviewslice *slice2, + int ndim, size_t itemsize); + +/* IsLittleEndian.proto */ +static CYTHON_INLINE int __Pyx_Is_Little_Endian(void); + +/* BufferFormatCheck.proto */ +static const char* __Pyx_BufFmt_CheckString(__Pyx_BufFmt_Context* ctx, const char* ts); +static void __Pyx_BufFmt_Init(__Pyx_BufFmt_Context* ctx, + __Pyx_BufFmt_StackElem* stack, + __Pyx_TypeInfo* type); + +/* TypeInfoCompare.proto */ +static int __pyx_typeinfo_cmp(__Pyx_TypeInfo *a, __Pyx_TypeInfo *b); + +/* MemviewSliceValidateAndInit.proto */ +static int __Pyx_ValidateAndInit_memviewslice( + int *axes_specs, + int c_or_f_flag, + int buf_flags, + int ndim, + __Pyx_TypeInfo *dtype, + __Pyx_BufFmt_StackElem stack[], + __Pyx_memviewslice *memviewslice, + PyObject *original_obj); + +/* ObjectToMemviewSlice.proto */ +static CYTHON_INLINE __Pyx_memviewslice __Pyx_PyObject_to_MemoryviewSlice_ds_float(PyObject *, int writable_flag); + +/* MemviewDtypeToObject.proto */ +static CYTHON_INLINE PyObject *__pyx_memview_get_nn___pyx_t_5numpy_float32_t(const char *itemp); +static CYTHON_INLINE int __pyx_memview_set_nn___pyx_t_5numpy_float32_t(const char *itemp, PyObject *obj); + +/* RealImag.proto */ +#if CYTHON_CCOMPLEX + #ifdef __cplusplus + #define __Pyx_CREAL(z) ((z).real()) + #define __Pyx_CIMAG(z) ((z).imag()) + #else + #define __Pyx_CREAL(z) (__real__(z)) + #define __Pyx_CIMAG(z) (__imag__(z)) + #endif +#else + #define __Pyx_CREAL(z) ((z).real) + #define __Pyx_CIMAG(z) ((z).imag) +#endif +#if defined(__cplusplus) && CYTHON_CCOMPLEX\ + && (defined(_WIN32) || defined(__clang__) || (defined(__GNUC__) && (__GNUC__ >= 5 || __GNUC__ == 4 && __GNUC_MINOR__ >= 4 )) || __cplusplus >= 201103) + #define __Pyx_SET_CREAL(z,x) ((z).real(x)) + #define __Pyx_SET_CIMAG(z,y) ((z).imag(y)) +#else + #define __Pyx_SET_CREAL(z,x) __Pyx_CREAL(z) = (x) + #define __Pyx_SET_CIMAG(z,y) __Pyx_CIMAG(z) = (y) +#endif + +/* Arithmetic.proto */ +#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #define __Pyx_c_eq_float(a, b) ((a)==(b)) + #define __Pyx_c_sum_float(a, b) ((a)+(b)) + #define __Pyx_c_diff_float(a, b) ((a)-(b)) + #define __Pyx_c_prod_float(a, b) ((a)*(b)) + #define __Pyx_c_quot_float(a, b) ((a)/(b)) + #define __Pyx_c_neg_float(a) (-(a)) + #ifdef __cplusplus + #define __Pyx_c_is_zero_float(z) ((z)==(float)0) + #define __Pyx_c_conj_float(z) (::std::conj(z)) + #if 1 + #define __Pyx_c_abs_float(z) (::std::abs(z)) + #define __Pyx_c_pow_float(a, b) (::std::pow(a, b)) + #endif + #else + #define __Pyx_c_is_zero_float(z) ((z)==0) + #define __Pyx_c_conj_float(z) (conjf(z)) + #if 1 + #define __Pyx_c_abs_float(z) (cabsf(z)) + #define __Pyx_c_pow_float(a, b) (cpowf(a, b)) + #endif + #endif +#else + static CYTHON_INLINE int __Pyx_c_eq_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_sum_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_diff_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_prod_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_quot_float(__pyx_t_float_complex, __pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_neg_float(__pyx_t_float_complex); + static CYTHON_INLINE int __Pyx_c_is_zero_float(__pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_conj_float(__pyx_t_float_complex); + #if 1 + static CYTHON_INLINE float __Pyx_c_abs_float(__pyx_t_float_complex); + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_pow_float(__pyx_t_float_complex, __pyx_t_float_complex); + #endif +#endif + +/* Arithmetic.proto */ +#if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #define __Pyx_c_eq_double(a, b) ((a)==(b)) + #define __Pyx_c_sum_double(a, b) ((a)+(b)) + #define __Pyx_c_diff_double(a, b) ((a)-(b)) + #define __Pyx_c_prod_double(a, b) ((a)*(b)) + #define __Pyx_c_quot_double(a, b) ((a)/(b)) + #define __Pyx_c_neg_double(a) (-(a)) + #ifdef __cplusplus + #define __Pyx_c_is_zero_double(z) ((z)==(double)0) + #define __Pyx_c_conj_double(z) (::std::conj(z)) + #if 1 + #define __Pyx_c_abs_double(z) (::std::abs(z)) + #define __Pyx_c_pow_double(a, b) (::std::pow(a, b)) + #endif + #else + #define __Pyx_c_is_zero_double(z) ((z)==0) + #define __Pyx_c_conj_double(z) (conj(z)) + #if 1 + #define __Pyx_c_abs_double(z) (cabs(z)) + #define __Pyx_c_pow_double(a, b) (cpow(a, b)) + #endif + #endif +#else + static CYTHON_INLINE int __Pyx_c_eq_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_sum_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_diff_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_prod_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_quot_double(__pyx_t_double_complex, __pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_neg_double(__pyx_t_double_complex); + static CYTHON_INLINE int __Pyx_c_is_zero_double(__pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_conj_double(__pyx_t_double_complex); + #if 1 + static CYTHON_INLINE double __Pyx_c_abs_double(__pyx_t_double_complex); + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_pow_double(__pyx_t_double_complex, __pyx_t_double_complex); + #endif +#endif + +/* MemviewSliceCopyTemplate.proto */ +static __Pyx_memviewslice +__pyx_memoryview_copy_new_contig(const __Pyx_memviewslice *from_mvs, + const char *mode, int ndim, + size_t sizeof_dtype, int contig_flag, + int dtype_is_object); + +/* MemviewSliceInit.proto */ +#define __Pyx_BUF_MAX_NDIMS %(BUF_MAX_NDIMS)d +#define __Pyx_MEMVIEW_DIRECT 1 +#define __Pyx_MEMVIEW_PTR 2 +#define __Pyx_MEMVIEW_FULL 4 +#define __Pyx_MEMVIEW_CONTIG 8 +#define __Pyx_MEMVIEW_STRIDED 16 +#define __Pyx_MEMVIEW_FOLLOW 32 +#define __Pyx_IS_C_CONTIG 1 +#define __Pyx_IS_F_CONTIG 2 +static int __Pyx_init_memviewslice( + struct __pyx_memoryview_obj *memview, + int ndim, + __Pyx_memviewslice *memviewslice, + int memview_is_new_reference); +static CYTHON_INLINE int __pyx_add_acquisition_count_locked( + __pyx_atomic_int_type *acquisition_count, PyThread_type_lock lock); +static CYTHON_INLINE int __pyx_sub_acquisition_count_locked( + __pyx_atomic_int_type *acquisition_count, PyThread_type_lock lock); +#define __pyx_get_slice_count_pointer(memview) (&memview->acquisition_count) +#define __PYX_INC_MEMVIEW(slice, have_gil) __Pyx_INC_MEMVIEW(slice, have_gil, __LINE__) +#define __PYX_XCLEAR_MEMVIEW(slice, have_gil) __Pyx_XCLEAR_MEMVIEW(slice, have_gil, __LINE__) +static CYTHON_INLINE void __Pyx_INC_MEMVIEW(__Pyx_memviewslice *, int, int); +static CYTHON_INLINE void __Pyx_XCLEAR_MEMVIEW(__Pyx_memviewslice *, int, int); + +/* TypeInfoToFormat.proto */ +struct __pyx_typeinfo_string { + char string[3]; +}; +static struct __pyx_typeinfo_string __Pyx_TypeInfoToFormat(__Pyx_TypeInfo *type); + +/* CIntFromPy.proto */ +static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *); + +/* None.proto */ +#include + +/* CIntFromPy.proto */ +static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_int(int value); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value); + +/* CIntFromPy.proto */ +static CYTHON_INLINE char __Pyx_PyInt_As_char(PyObject *); + +/* FormatTypeName.proto */ +#if CYTHON_COMPILING_IN_LIMITED_API +typedef PyObject *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%U" +static __Pyx_TypeName __Pyx_PyType_GetName(PyTypeObject* tp); +#define __Pyx_DECREF_TypeName(obj) Py_XDECREF(obj) +#else +typedef const char *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%.200s" +#define __Pyx_PyType_GetName(tp) ((tp)->tp_name) +#define __Pyx_DECREF_TypeName(obj) +#endif + +/* CheckBinaryVersion.proto */ +static unsigned long __Pyx_get_runtime_version(void); +static int __Pyx_check_binary_version(unsigned long ct_version, unsigned long rt_version, int allow_newer); + +/* InitStrings.proto */ +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t); + +/* #### Code section: module_declarations ### */ +static PyObject *__pyx_array_get_memview(struct __pyx_array_obj *__pyx_v_self); /* proto*/ +static char *__pyx_memoryview_get_item_pointer(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index); /* proto*/ +static PyObject *__pyx_memoryview_is_slice(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj); /* proto*/ +static PyObject *__pyx_memoryview_setitem_slice_assignment(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_dst, PyObject *__pyx_v_src); /* proto*/ +static PyObject *__pyx_memoryview_setitem_slice_assign_scalar(struct __pyx_memoryview_obj *__pyx_v_self, struct __pyx_memoryview_obj *__pyx_v_dst, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryview_setitem_indexed(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryview_convert_item_to_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp); /* proto*/ +static PyObject *__pyx_memoryview_assign_item_from_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryview__get_base(struct __pyx_memoryview_obj *__pyx_v_self); /* proto*/ +static PyObject *__pyx_memoryviewslice_convert_item_to_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp); /* proto*/ +static PyObject *__pyx_memoryviewslice_assign_item_from_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryviewslice__get_base(struct __pyx_memoryviewslice_obj *__pyx_v_self); /* proto*/ +static CYTHON_INLINE PyObject *__pyx_f_5numpy_7ndarray_4base_base(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE PyArray_Descr *__pyx_f_5numpy_7ndarray_5descr_descr(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE int __pyx_f_5numpy_7ndarray_4ndim_ndim(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_5shape_shape(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_7strides_strides(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE npy_intp __pyx_f_5numpy_7ndarray_4size_size(PyArrayObject *__pyx_v_self); /* proto*/ +static CYTHON_INLINE char *__pyx_f_5numpy_7ndarray_4data_data(PyArrayObject *__pyx_v_self); /* proto*/ +static PyObject *__pyx_f_9selfdrive_6modeld_6models_15commonmodel_pyx_5CLMem_create(void *__pyx_v_cmem); /* proto*/ + +/* Module declarations from "libc.string" */ + +/* Module declarations from "libcpp.string" */ + +/* Module declarations from "libcpp.vector" */ + +/* Module declarations from "libcpp.utility" */ + +/* Module declarations from "libcpp.set" */ + +/* Module declarations from "libc.stdint" */ + +/* Module declarations from "libcpp" */ + +/* Module declarations from "cereal.visionipc.visionipc" */ + +/* Module declarations from "cereal.visionipc.visionipc_pyx" */ + +/* Module declarations from "libc.stdio" */ + +/* Module declarations from "__builtin__" */ + +/* Module declarations from "cpython.type" */ + +/* Module declarations from "cpython" */ + +/* Module declarations from "cpython.object" */ + +/* Module declarations from "cpython.ref" */ + +/* Module declarations from "numpy" */ + +/* Module declarations from "numpy" */ + +/* Module declarations from "selfdrive.modeld.models.commonmodel" */ + +/* Module declarations from "selfdrive.modeld.models.commonmodel_pyx" */ +static PyObject *__pyx_collections_abc_Sequence = 0; +static PyObject *generic = 0; +static PyObject *strided = 0; +static PyObject *indirect = 0; +static PyObject *contiguous = 0; +static PyObject *indirect_contiguous = 0; +static int __pyx_memoryview_thread_locks_used; +static PyThread_type_lock __pyx_memoryview_thread_locks[8]; +static int __pyx_array_allocate_buffer(struct __pyx_array_obj *); /*proto*/ +static struct __pyx_array_obj *__pyx_array_new(PyObject *, Py_ssize_t, char *, char *, char *); /*proto*/ +static PyObject *__pyx_memoryview_new(PyObject *, int, int, __Pyx_TypeInfo *); /*proto*/ +static CYTHON_INLINE int __pyx_memoryview_check(PyObject *); /*proto*/ +static PyObject *_unellipsify(PyObject *, int); /*proto*/ +static int assert_direct_dimensions(Py_ssize_t *, int); /*proto*/ +static struct __pyx_memoryview_obj *__pyx_memview_slice(struct __pyx_memoryview_obj *, PyObject *); /*proto*/ +static int __pyx_memoryview_slice_memviewslice(__Pyx_memviewslice *, Py_ssize_t, Py_ssize_t, Py_ssize_t, int, int, int *, Py_ssize_t, Py_ssize_t, Py_ssize_t, int, int, int, int); /*proto*/ +static char *__pyx_pybuffer_index(Py_buffer *, char *, Py_ssize_t, Py_ssize_t); /*proto*/ +static int __pyx_memslice_transpose(__Pyx_memviewslice *); /*proto*/ +static PyObject *__pyx_memoryview_fromslice(__Pyx_memviewslice, int, PyObject *(*)(char *), int (*)(char *, PyObject *), int); /*proto*/ +static __Pyx_memviewslice *__pyx_memoryview_get_slice_from_memoryview(struct __pyx_memoryview_obj *, __Pyx_memviewslice *); /*proto*/ +static void __pyx_memoryview_slice_copy(struct __pyx_memoryview_obj *, __Pyx_memviewslice *); /*proto*/ +static PyObject *__pyx_memoryview_copy_object(struct __pyx_memoryview_obj *); /*proto*/ +static PyObject *__pyx_memoryview_copy_object_from_slice(struct __pyx_memoryview_obj *, __Pyx_memviewslice *); /*proto*/ +static Py_ssize_t abs_py_ssize_t(Py_ssize_t); /*proto*/ +static char __pyx_get_best_slice_order(__Pyx_memviewslice *, int); /*proto*/ +static void _copy_strided_to_strided(char *, Py_ssize_t *, char *, Py_ssize_t *, Py_ssize_t *, Py_ssize_t *, int, size_t); /*proto*/ +static void copy_strided_to_strided(__Pyx_memviewslice *, __Pyx_memviewslice *, int, size_t); /*proto*/ +static Py_ssize_t __pyx_memoryview_slice_get_size(__Pyx_memviewslice *, int); /*proto*/ +static Py_ssize_t __pyx_fill_contig_strides_array(Py_ssize_t *, Py_ssize_t *, Py_ssize_t, int, char); /*proto*/ +static void *__pyx_memoryview_copy_data_to_temp(__Pyx_memviewslice *, __Pyx_memviewslice *, char, int); /*proto*/ +static int __pyx_memoryview_err_extents(int, Py_ssize_t, Py_ssize_t); /*proto*/ +static int __pyx_memoryview_err_dim(PyObject *, PyObject *, int); /*proto*/ +static int __pyx_memoryview_err(PyObject *, PyObject *); /*proto*/ +static int __pyx_memoryview_err_no_memory(void); /*proto*/ +static int __pyx_memoryview_copy_contents(__Pyx_memviewslice, __Pyx_memviewslice, int, int, int); /*proto*/ +static void __pyx_memoryview_broadcast_leading(__Pyx_memviewslice *, int, int); /*proto*/ +static void __pyx_memoryview_refcount_copying(__Pyx_memviewslice *, int, int, int); /*proto*/ +static void __pyx_memoryview_refcount_objects_in_slice_with_gil(char *, Py_ssize_t *, Py_ssize_t *, int, int); /*proto*/ +static void __pyx_memoryview_refcount_objects_in_slice(char *, Py_ssize_t *, Py_ssize_t *, int, int); /*proto*/ +static void __pyx_memoryview_slice_assign_scalar(__Pyx_memviewslice *, int, size_t, void *, int); /*proto*/ +static void __pyx_memoryview__slice_assign_scalar(char *, Py_ssize_t *, Py_ssize_t *, int, size_t, void *); /*proto*/ +static PyObject *__pyx_unpickle_Enum__set_state(struct __pyx_MemviewEnum_obj *, PyObject *); /*proto*/ +static PyObject *__pyx_format_from_typeinfo(__Pyx_TypeInfo *); /*proto*/ +/* #### Code section: typeinfo ### */ +static __Pyx_TypeInfo __Pyx_TypeInfo_nn___pyx_t_5numpy_float32_t = { "float32_t", NULL, sizeof(__pyx_t_5numpy_float32_t), { 0 }, 0, 'R', 0, 0 }; +static __Pyx_TypeInfo __Pyx_TypeInfo_float = { "float", NULL, sizeof(float), { 0 }, 0, 'R', 0, 0 }; +/* #### Code section: before_global_var ### */ +#define __Pyx_MODULE_NAME "selfdrive.modeld.models.commonmodel_pyx" +extern int __pyx_module_is_main_selfdrive__modeld__models__commonmodel_pyx; +int __pyx_module_is_main_selfdrive__modeld__models__commonmodel_pyx = 0; + +/* Implementation of "selfdrive.modeld.models.commonmodel_pyx" */ +/* #### Code section: global_var ### */ +static PyObject *__pyx_builtin_TypeError; +static PyObject *__pyx_builtin___import__; +static PyObject *__pyx_builtin_ValueError; +static PyObject *__pyx_builtin_MemoryError; +static PyObject *__pyx_builtin_enumerate; +static PyObject *__pyx_builtin_range; +static PyObject *__pyx_builtin_AssertionError; +static PyObject *__pyx_builtin_Ellipsis; +static PyObject *__pyx_builtin_id; +static PyObject *__pyx_builtin_IndexError; +static PyObject *__pyx_builtin_ImportError; +/* #### Code section: string_decls ### */ +static const char __pyx_k_[] = ": "; +static const char __pyx_k_O[] = "O"; +static const char __pyx_k_T[] = "T{"; + static const char __pyx_k_c[] = "c"; + static const char __pyx_k_x[] = "x"; + static const char __pyx_k__2[] = "."; + static const char __pyx_k__3[] = "*"; + static const char __pyx_k__6[] = "'"; + static const char __pyx_k__7[] = ")"; + static const char __pyx_k__9[] = "^"; + static const char __pyx_k_gc[] = "gc"; + static const char __pyx_k_id[] = "id"; + static const char __pyx_k_np[] = "np"; + static const char __pyx_k__10[] = ""; + static const char __pyx_k__11[] = ":"; +static const char __pyx_k__12[] = "}"; +static const char __pyx_k__13[] = "("; +static const char __pyx_k__14[] = ","; +static const char __pyx_k__40[] = "?"; +static const char __pyx_k_abc[] = "abc"; +static const char __pyx_k_and[] = " and "; +static const char __pyx_k_buf[] = "buf"; +static const char __pyx_k_got[] = " (got "; +static const char __pyx_k_new[] = "__new__"; +static const char __pyx_k_obj[] = "obj"; +static const char __pyx_k_sys[] = "sys"; +static const char __pyx_k_base[] = "base"; +static const char __pyx_k_data[] = "data"; +static const char __pyx_k_dict[] = "__dict__"; +static const char __pyx_k_join[] = "join"; +static const char __pyx_k_main[] = "__main__"; +static const char __pyx_k_mode[] = "mode"; +static const char __pyx_k_name[] = "name"; +static const char __pyx_k_ndim[] = "ndim"; +static const char __pyx_k_pack[] = "pack"; +static const char __pyx_k_self[] = "self"; +static const char __pyx_k_size[] = "size"; +static const char __pyx_k_spec[] = "__spec__"; +static const char __pyx_k_step[] = "step"; +static const char __pyx_k_stop[] = "stop"; +static const char __pyx_k_test[] = "__test__"; +static const char __pyx_k_ASCII[] = "ASCII"; +static const char __pyx_k_CLMem[] = "CLMem"; +static const char __pyx_k_class[] = "__class__"; +static const char __pyx_k_count[] = "count"; +static const char __pyx_k_error[] = "error"; +static const char __pyx_k_flags[] = "flags"; +static const char __pyx_k_index[] = "index"; +static const char __pyx_k_numpy[] = "numpy"; +static const char __pyx_k_range[] = "range"; +static const char __pyx_k_shape[] = "shape"; +static const char __pyx_k_start[] = "start"; +static const char __pyx_k_width[] = "width"; +static const char __pyx_k_enable[] = "enable"; +static const char __pyx_k_encode[] = "encode"; +static const char __pyx_k_format[] = "format"; +static const char __pyx_k_height[] = "height"; +static const char __pyx_k_import[] = "__import__"; +static const char __pyx_k_name_2[] = "__name__"; +static const char __pyx_k_output[] = "output"; +static const char __pyx_k_pickle[] = "pickle"; +static const char __pyx_k_reduce[] = "__reduce__"; +static const char __pyx_k_stride[] = "stride"; +static const char __pyx_k_struct[] = "struct"; +static const char __pyx_k_unpack[] = "unpack"; +static const char __pyx_k_update[] = "update"; +static const char __pyx_k_asarray[] = "asarray"; +static const char __pyx_k_context[] = "context"; +static const char __pyx_k_disable[] = "disable"; +static const char __pyx_k_fortran[] = "fortran"; +static const char __pyx_k_memview[] = "memview"; +static const char __pyx_k_prepare[] = "prepare"; +static const char __pyx_k_sigmoid[] = "sigmoid"; +static const char __pyx_k_Ellipsis[] = "Ellipsis"; +static const char __pyx_k_Sequence[] = "Sequence"; +static const char __pyx_k_getstate[] = "__getstate__"; +static const char __pyx_k_itemsize[] = "itemsize"; +static const char __pyx_k_pyx_type[] = "__pyx_type"; +static const char __pyx_k_register[] = "register"; +static const char __pyx_k_setstate[] = "__setstate__"; +static const char __pyx_k_CLContext[] = "CLContext"; +static const char __pyx_k_TypeError[] = "TypeError"; +static const char __pyx_k_enumerate[] = "enumerate"; +static const char __pyx_k_isenabled[] = "isenabled"; +static const char __pyx_k_pyx_state[] = "__pyx_state"; +static const char __pyx_k_reduce_ex[] = "__reduce_ex__"; +static const char __pyx_k_uv_offset[] = "uv_offset"; +static const char __pyx_k_IndexError[] = "IndexError"; +static const char __pyx_k_ModelFrame[] = "ModelFrame"; +static const char __pyx_k_ValueError[] = "ValueError"; +static const char __pyx_k_projection[] = "projection"; +static const char __pyx_k_pyx_result[] = "__pyx_result"; +static const char __pyx_k_pyx_vtable[] = "__pyx_vtable__"; +static const char __pyx_k_ImportError[] = "ImportError"; +static const char __pyx_k_MemoryError[] = "MemoryError"; +static const char __pyx_k_PickleError[] = "PickleError"; +static const char __pyx_k_collections[] = "collections"; +static const char __pyx_k_cprojection[] = "cprojection"; +static const char __pyx_k_initializing[] = "_initializing"; +static const char __pyx_k_is_coroutine[] = "_is_coroutine"; +static const char __pyx_k_pyx_checksum[] = "__pyx_checksum"; +static const char __pyx_k_stringsource[] = ""; +static const char __pyx_k_version_info[] = "version_info"; +static const char __pyx_k_class_getitem[] = "__class_getitem__"; +static const char __pyx_k_reduce_cython[] = "__reduce_cython__"; +static const char __pyx_k_AssertionError[] = "AssertionError"; +static const char __pyx_k_View_MemoryView[] = "View.MemoryView"; +static const char __pyx_k_allocate_buffer[] = "allocate_buffer"; +static const char __pyx_k_collections_abc[] = "collections.abc"; +static const char __pyx_k_dtype_is_object[] = "dtype_is_object"; +static const char __pyx_k_pyx_PickleError[] = "__pyx_PickleError"; +static const char __pyx_k_setstate_cython[] = "__setstate_cython__"; +static const char __pyx_k_pyx_unpickle_Enum[] = "__pyx_unpickle_Enum"; +static const char __pyx_k_ModelFrame_prepare[] = "ModelFrame.prepare"; +static const char __pyx_k_asyncio_coroutines[] = "asyncio.coroutines"; +static const char __pyx_k_cline_in_traceback[] = "cline_in_traceback"; +static const char __pyx_k_strided_and_direct[] = ""; +static const char __pyx_k_strided_and_indirect[] = ""; +static const char __pyx_k_CLMem___reduce_cython[] = "CLMem.__reduce_cython__"; +static const char __pyx_k_Invalid_shape_in_axis[] = "Invalid shape in axis "; +static const char __pyx_k_contiguous_and_direct[] = ""; +static const char __pyx_k_Cannot_index_with_type[] = "Cannot index with type '"; +static const char __pyx_k_MemoryView_of_r_object[] = ""; +static const char __pyx_k_CLMem___setstate_cython[] = "CLMem.__setstate_cython__"; +static const char __pyx_k_MemoryView_of_r_at_0x_x[] = ""; +static const char __pyx_k_contiguous_and_indirect[] = ""; +static const char __pyx_k_CLContext___reduce_cython[] = "CLContext.__reduce_cython__"; +static const char __pyx_k_Dimension_d_is_not_direct[] = "Dimension %d is not direct"; +static const char __pyx_k_Index_out_of_bounds_axis_d[] = "Index out of bounds (axis %d)"; +static const char __pyx_k_ModelFrame___reduce_cython[] = "ModelFrame.__reduce_cython__"; +static const char __pyx_k_CLContext___setstate_cython[] = "CLContext.__setstate_cython__"; +static const char __pyx_k_Step_may_not_be_zero_axis_d[] = "Step may not be zero (axis %d)"; +static const char __pyx_k_itemsize_0_for_cython_array[] = "itemsize <= 0 for cython.array"; +static const char __pyx_k_ModelFrame___setstate_cython[] = "ModelFrame.__setstate_cython__"; +static const char __pyx_k_unable_to_allocate_array_data[] = "unable to allocate array data."; +static const char __pyx_k_strided_and_direct_or_indirect[] = ""; +static const char __pyx_k_numpy_core_multiarray_failed_to[] = "numpy.core.multiarray failed to import"; +static const char __pyx_k_self_mem_cannot_be_converted_to[] = "self.mem cannot be converted to a Python object for pickling"; +static const char __pyx_k_All_dimensions_preceding_dimensi[] = "All dimensions preceding dimension %d must be indexed and not sliced"; +static const char __pyx_k_Buffer_view_does_not_expose_stri[] = "Buffer view does not expose strides"; +static const char __pyx_k_Can_only_create_a_buffer_that_is[] = "Can only create a buffer that is contiguous in memory."; +static const char __pyx_k_Cannot_assign_to_read_only_memor[] = "Cannot assign to read-only memoryview"; +static const char __pyx_k_Cannot_create_writable_memory_vi[] = "Cannot create writable memory view from read-only memoryview"; +static const char __pyx_k_Cannot_transpose_memoryview_with[] = "Cannot transpose memoryview with indirect dimensions"; +static const char __pyx_k_Empty_shape_tuple_for_cython_arr[] = "Empty shape tuple for cython.array"; +static const char __pyx_k_Incompatible_checksums_0x_x_vs_0[] = "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))"; +static const char __pyx_k_Indirect_dimensions_not_supporte[] = "Indirect dimensions not supported"; +static const char __pyx_k_Invalid_mode_expected_c_or_fortr[] = "Invalid mode, expected 'c' or 'fortran', got "; +static const char __pyx_k_Out_of_bounds_on_buffer_access_a[] = "Out of bounds on buffer access (axis "; +static const char __pyx_k_Unable_to_convert_item_to_object[] = "Unable to convert item to object"; +static const char __pyx_k_got_differing_extents_in_dimensi[] = "got differing extents in dimension "; +static const char __pyx_k_no_default___reduce___due_to_non[] = "no default __reduce__ due to non-trivial __cinit__"; +static const char __pyx_k_numpy_core_umath_failed_to_impor[] = "numpy.core.umath failed to import"; +static const char __pyx_k_selfdrive_modeld_models_commonmo[] = "selfdrive/modeld/models/commonmodel_pyx.pyx"; +static const char __pyx_k_unable_to_allocate_shape_and_str[] = "unable to allocate shape and strides."; +static const char __pyx_k_selfdrive_modeld_models_commonmo_2[] = "selfdrive.modeld.models.commonmodel_pyx"; +/* #### Code section: decls ### */ +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array___cinit__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_shape, Py_ssize_t __pyx_v_itemsize, PyObject *__pyx_v_format, PyObject *__pyx_v_mode, int __pyx_v_allocate_buffer); /* proto */ +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_2__getbuffer__(struct __pyx_array_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /* proto */ +static void __pyx_array___pyx_pf_15View_dot_MemoryView_5array_4__dealloc__(struct __pyx_array_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_5array_7memview___get__(struct __pyx_array_obj *__pyx_v_self); /* proto */ +static Py_ssize_t __pyx_array___pyx_pf_15View_dot_MemoryView_5array_6__len__(struct __pyx_array_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_8__getattr__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_attr); /* proto */ +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_10__getitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item); /* proto */ +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_12__setitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value); /* proto */ +static PyObject *__pyx_pf___pyx_array___reduce_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_array_2__setstate_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum___init__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v_name); /* proto */ +static PyObject *__pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum_2__repr__(struct __pyx_MemviewEnum_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_MemviewEnum___reduce_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_MemviewEnum_2__setstate_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview___cinit__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj, int __pyx_v_flags, int __pyx_v_dtype_is_object); /* proto */ +static void __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_2__dealloc__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_4__getitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index); /* proto */ +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_6__setitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value); /* proto */ +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_8__getbuffer__(struct __pyx_memoryview_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_1T___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4base___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_5shape___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_7strides___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_10suboffsets___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4ndim___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_8itemsize___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_6nbytes___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4size___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static Py_ssize_t __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_10__len__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_12__repr__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_14__str__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_16is_c_contig(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_18is_f_contig(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_20copy(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_22copy_fortran(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryview___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryview_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static void __pyx_memoryviewslice___pyx_pf_15View_dot_MemoryView_16_memoryviewslice___dealloc__(struct __pyx_memoryviewslice_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryviewslice___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryviewslice_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView___pyx_unpickle_Enum(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v___pyx_type, long __pyx_v___pyx_checksum, PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_pf_9selfdrive_6modeld_6models_15commonmodel_pyx_sigmoid(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_x); /* proto */ +static int __pyx_pf_9selfdrive_6modeld_6models_15commonmodel_pyx_9CLContext___cinit__(struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_9selfdrive_6modeld_6models_15commonmodel_pyx_9CLContext_2__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_9selfdrive_6modeld_6models_15commonmodel_pyx_9CLContext_4__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_pf_9selfdrive_6modeld_6models_15commonmodel_pyx_5CLMem___reduce_cython__(CYTHON_UNUSED struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_9selfdrive_6modeld_6models_15commonmodel_pyx_5CLMem_2__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_pf_9selfdrive_6modeld_6models_15commonmodel_pyx_10ModelFrame___cinit__(struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame *__pyx_v_self, struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext *__pyx_v_context); /* proto */ +static void __pyx_pf_9selfdrive_6modeld_6models_15commonmodel_pyx_10ModelFrame_2__dealloc__(struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_9selfdrive_6modeld_6models_15commonmodel_pyx_10ModelFrame_4prepare(struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame *__pyx_v_self, struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_v_buf, __Pyx_memviewslice __pyx_v_projection, struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem *__pyx_v_output); /* proto */ +static PyObject *__pyx_pf_9selfdrive_6modeld_6models_15commonmodel_pyx_10ModelFrame_6__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_9selfdrive_6modeld_6models_15commonmodel_pyx_10ModelFrame_8__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_tp_new_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_array(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_Enum(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_memoryview(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new__memoryviewslice(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +/* #### Code section: late_includes ### */ +/* #### Code section: module_state ### */ +typedef struct { + PyObject *__pyx_d; + PyObject *__pyx_b; + PyObject *__pyx_cython_runtime; + PyObject *__pyx_empty_tuple; + PyObject *__pyx_empty_bytes; + PyObject *__pyx_empty_unicode; + #ifdef __Pyx_CyFunction_USED + PyTypeObject *__pyx_CyFunctionType; + #endif + #ifdef __Pyx_FusedFunction_USED + PyTypeObject *__pyx_FusedFunctionType; + #endif + #ifdef __Pyx_Generator_USED + PyTypeObject *__pyx_GeneratorType; + #endif + #ifdef __Pyx_IterableCoroutine_USED + PyTypeObject *__pyx_IterableCoroutineType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineAwaitType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineType; + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + PyTypeObject *__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext; + PyTypeObject *__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf; + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + PyTypeObject *__pyx_ptype_7cpython_4type_type; + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + PyTypeObject *__pyx_ptype_5numpy_dtype; + PyTypeObject *__pyx_ptype_5numpy_flatiter; + PyTypeObject *__pyx_ptype_5numpy_broadcast; + PyTypeObject *__pyx_ptype_5numpy_ndarray; + PyTypeObject *__pyx_ptype_5numpy_generic; + PyTypeObject *__pyx_ptype_5numpy_number; + PyTypeObject *__pyx_ptype_5numpy_integer; + PyTypeObject *__pyx_ptype_5numpy_signedinteger; + PyTypeObject *__pyx_ptype_5numpy_unsignedinteger; + PyTypeObject *__pyx_ptype_5numpy_inexact; + PyTypeObject *__pyx_ptype_5numpy_floating; + PyTypeObject *__pyx_ptype_5numpy_complexfloating; + PyTypeObject *__pyx_ptype_5numpy_flexible; + PyTypeObject *__pyx_ptype_5numpy_character; + PyTypeObject *__pyx_ptype_5numpy_ufunc; + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + PyObject *__pyx_type_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext; + PyObject *__pyx_type_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem; + PyObject *__pyx_type_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame; + PyObject *__pyx_type___pyx_array; + PyObject *__pyx_type___pyx_MemviewEnum; + PyObject *__pyx_type___pyx_memoryview; + PyObject *__pyx_type___pyx_memoryviewslice; + #endif + PyTypeObject *__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext; + PyTypeObject *__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem; + PyTypeObject *__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame; + PyTypeObject *__pyx_array_type; + PyTypeObject *__pyx_MemviewEnum_type; + PyTypeObject *__pyx_memoryview_type; + PyTypeObject *__pyx_memoryviewslice_type; + PyObject *__pyx_kp_u_; + PyObject *__pyx_n_s_ASCII; + PyObject *__pyx_kp_s_All_dimensions_preceding_dimensi; + PyObject *__pyx_n_s_AssertionError; + PyObject *__pyx_kp_s_Buffer_view_does_not_expose_stri; + PyObject *__pyx_n_s_CLContext; + PyObject *__pyx_n_s_CLContext___reduce_cython; + PyObject *__pyx_n_s_CLContext___setstate_cython; + PyObject *__pyx_n_s_CLMem; + PyObject *__pyx_n_s_CLMem___reduce_cython; + PyObject *__pyx_n_s_CLMem___setstate_cython; + PyObject *__pyx_kp_s_Can_only_create_a_buffer_that_is; + PyObject *__pyx_kp_s_Cannot_assign_to_read_only_memor; + PyObject *__pyx_kp_s_Cannot_create_writable_memory_vi; + PyObject *__pyx_kp_u_Cannot_index_with_type; + PyObject *__pyx_kp_s_Cannot_transpose_memoryview_with; + PyObject *__pyx_kp_s_Dimension_d_is_not_direct; + PyObject *__pyx_n_s_Ellipsis; + PyObject *__pyx_kp_s_Empty_shape_tuple_for_cython_arr; + PyObject *__pyx_n_s_ImportError; + PyObject *__pyx_kp_s_Incompatible_checksums_0x_x_vs_0; + PyObject *__pyx_n_s_IndexError; + PyObject *__pyx_kp_s_Index_out_of_bounds_axis_d; + PyObject *__pyx_kp_s_Indirect_dimensions_not_supporte; + PyObject *__pyx_kp_u_Invalid_mode_expected_c_or_fortr; + PyObject *__pyx_kp_u_Invalid_shape_in_axis; + PyObject *__pyx_n_s_MemoryError; + PyObject *__pyx_kp_s_MemoryView_of_r_at_0x_x; + PyObject *__pyx_kp_s_MemoryView_of_r_object; + PyObject *__pyx_n_s_ModelFrame; + PyObject *__pyx_n_s_ModelFrame___reduce_cython; + PyObject *__pyx_n_s_ModelFrame___setstate_cython; + PyObject *__pyx_n_s_ModelFrame_prepare; + PyObject *__pyx_n_b_O; + PyObject *__pyx_kp_u_Out_of_bounds_on_buffer_access_a; + PyObject *__pyx_n_s_PickleError; + PyObject *__pyx_n_s_Sequence; + PyObject *__pyx_kp_s_Step_may_not_be_zero_axis_d; + PyObject *__pyx_kp_b_T; + PyObject *__pyx_n_s_TypeError; + PyObject *__pyx_kp_s_Unable_to_convert_item_to_object; + PyObject *__pyx_n_s_ValueError; + PyObject *__pyx_n_s_View_MemoryView; + PyObject *__pyx_kp_b__10; + PyObject *__pyx_kp_b__11; + PyObject *__pyx_kp_b__12; + PyObject *__pyx_kp_u__13; + PyObject *__pyx_kp_u__14; + PyObject *__pyx_kp_u__2; + PyObject *__pyx_n_s__3; + PyObject *__pyx_n_s__40; + PyObject *__pyx_kp_u__6; + PyObject *__pyx_kp_u__7; + PyObject *__pyx_kp_b__9; + PyObject *__pyx_n_s_abc; + PyObject *__pyx_n_s_allocate_buffer; + PyObject *__pyx_kp_u_and; + PyObject *__pyx_n_s_asarray; + PyObject *__pyx_n_s_asyncio_coroutines; + PyObject *__pyx_n_s_base; + PyObject *__pyx_n_s_buf; + PyObject *__pyx_n_s_c; + PyObject *__pyx_n_u_c; + PyObject *__pyx_n_s_class; + PyObject *__pyx_n_s_class_getitem; + PyObject *__pyx_n_s_cline_in_traceback; + PyObject *__pyx_n_s_collections; + PyObject *__pyx_kp_s_collections_abc; + PyObject *__pyx_n_s_context; + PyObject *__pyx_kp_s_contiguous_and_direct; + PyObject *__pyx_kp_s_contiguous_and_indirect; + PyObject *__pyx_n_s_count; + PyObject *__pyx_n_s_cprojection; + PyObject *__pyx_n_s_data; + PyObject *__pyx_n_s_dict; + PyObject *__pyx_kp_u_disable; + PyObject *__pyx_n_s_dtype_is_object; + PyObject *__pyx_kp_u_enable; + PyObject *__pyx_n_s_encode; + PyObject *__pyx_n_s_enumerate; + PyObject *__pyx_n_s_error; + PyObject *__pyx_n_s_flags; + PyObject *__pyx_n_s_format; + PyObject *__pyx_n_s_fortran; + PyObject *__pyx_n_u_fortran; + PyObject *__pyx_kp_u_gc; + PyObject *__pyx_n_s_getstate; + PyObject *__pyx_kp_u_got; + PyObject *__pyx_kp_u_got_differing_extents_in_dimensi; + PyObject *__pyx_n_s_height; + PyObject *__pyx_n_s_id; + PyObject *__pyx_n_s_import; + PyObject *__pyx_n_s_index; + PyObject *__pyx_n_s_initializing; + PyObject *__pyx_n_s_is_coroutine; + PyObject *__pyx_kp_u_isenabled; + PyObject *__pyx_n_s_itemsize; + PyObject *__pyx_kp_s_itemsize_0_for_cython_array; + PyObject *__pyx_n_s_join; + PyObject *__pyx_n_s_main; + PyObject *__pyx_n_s_memview; + PyObject *__pyx_n_s_mode; + PyObject *__pyx_n_s_name; + PyObject *__pyx_n_s_name_2; + PyObject *__pyx_n_s_ndim; + PyObject *__pyx_n_s_new; + PyObject *__pyx_kp_s_no_default___reduce___due_to_non; + PyObject *__pyx_n_s_np; + PyObject *__pyx_n_s_numpy; + PyObject *__pyx_kp_u_numpy_core_multiarray_failed_to; + PyObject *__pyx_kp_u_numpy_core_umath_failed_to_impor; + PyObject *__pyx_n_s_obj; + PyObject *__pyx_n_s_output; + PyObject *__pyx_n_s_pack; + PyObject *__pyx_n_s_pickle; + PyObject *__pyx_n_s_prepare; + PyObject *__pyx_n_s_projection; + PyObject *__pyx_n_s_pyx_PickleError; + PyObject *__pyx_n_s_pyx_checksum; + PyObject *__pyx_n_s_pyx_result; + PyObject *__pyx_n_s_pyx_state; + PyObject *__pyx_n_s_pyx_type; + PyObject *__pyx_n_s_pyx_unpickle_Enum; + PyObject *__pyx_n_s_pyx_vtable; + PyObject *__pyx_n_s_range; + PyObject *__pyx_n_s_reduce; + PyObject *__pyx_n_s_reduce_cython; + PyObject *__pyx_n_s_reduce_ex; + PyObject *__pyx_n_s_register; + PyObject *__pyx_n_s_self; + PyObject *__pyx_kp_s_self_mem_cannot_be_converted_to; + PyObject *__pyx_kp_s_selfdrive_modeld_models_commonmo; + PyObject *__pyx_n_s_selfdrive_modeld_models_commonmo_2; + PyObject *__pyx_n_s_setstate; + PyObject *__pyx_n_s_setstate_cython; + PyObject *__pyx_n_s_shape; + PyObject *__pyx_n_s_sigmoid; + PyObject *__pyx_n_s_size; + PyObject *__pyx_n_s_spec; + PyObject *__pyx_n_s_start; + PyObject *__pyx_n_s_step; + PyObject *__pyx_n_s_stop; + PyObject *__pyx_n_s_stride; + PyObject *__pyx_kp_s_strided_and_direct; + PyObject *__pyx_kp_s_strided_and_direct_or_indirect; + PyObject *__pyx_kp_s_strided_and_indirect; + PyObject *__pyx_kp_s_stringsource; + PyObject *__pyx_n_s_struct; + PyObject *__pyx_n_s_sys; + PyObject *__pyx_n_s_test; + PyObject *__pyx_kp_s_unable_to_allocate_array_data; + PyObject *__pyx_kp_s_unable_to_allocate_shape_and_str; + PyObject *__pyx_n_s_unpack; + PyObject *__pyx_n_s_update; + PyObject *__pyx_n_s_uv_offset; + PyObject *__pyx_n_s_version_info; + PyObject *__pyx_n_s_width; + PyObject *__pyx_n_s_x; + PyObject *__pyx_int_0; + PyObject *__pyx_int_1; + PyObject *__pyx_int_3; + PyObject *__pyx_int_112105877; + PyObject *__pyx_int_136983863; + PyObject *__pyx_int_184977713; + PyObject *__pyx_int_neg_1; + PyObject *__pyx_slice__5; + PyObject *__pyx_tuple__4; + PyObject *__pyx_tuple__8; + PyObject *__pyx_tuple__15; + PyObject *__pyx_tuple__16; + PyObject *__pyx_tuple__17; + PyObject *__pyx_tuple__18; + PyObject *__pyx_tuple__19; + PyObject *__pyx_tuple__20; + PyObject *__pyx_tuple__21; + PyObject *__pyx_tuple__22; + PyObject *__pyx_tuple__23; + PyObject *__pyx_tuple__24; + PyObject *__pyx_tuple__25; + PyObject *__pyx_tuple__26; + PyObject *__pyx_tuple__28; + PyObject *__pyx_tuple__30; + PyObject *__pyx_tuple__32; + PyObject *__pyx_tuple__36; + PyObject *__pyx_codeobj__27; + PyObject *__pyx_codeobj__29; + PyObject *__pyx_codeobj__31; + PyObject *__pyx_codeobj__33; + PyObject *__pyx_codeobj__34; + PyObject *__pyx_codeobj__35; + PyObject *__pyx_codeobj__37; + PyObject *__pyx_codeobj__38; + PyObject *__pyx_codeobj__39; +} __pyx_mstate; + +#if CYTHON_USE_MODULE_STATE +#ifdef __cplusplus +namespace { + extern struct PyModuleDef __pyx_moduledef; +} /* anonymous namespace */ +#else +static struct PyModuleDef __pyx_moduledef; +#endif + +#define __pyx_mstate(o) ((__pyx_mstate *)__Pyx_PyModule_GetState(o)) + +#define __pyx_mstate_global (__pyx_mstate(PyState_FindModule(&__pyx_moduledef))) + +#define __pyx_m (PyState_FindModule(&__pyx_moduledef)) +#else +static __pyx_mstate __pyx_mstate_global_static = +#ifdef __cplusplus + {}; +#else + {0}; +#endif +static __pyx_mstate *__pyx_mstate_global = &__pyx_mstate_global_static; +#endif +/* #### Code section: module_state_clear ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_clear(PyObject *m) { + __pyx_mstate *clear_module_state = __pyx_mstate(m); + if (!clear_module_state) return 0; + Py_CLEAR(clear_module_state->__pyx_d); + Py_CLEAR(clear_module_state->__pyx_b); + Py_CLEAR(clear_module_state->__pyx_cython_runtime); + Py_CLEAR(clear_module_state->__pyx_empty_tuple); + Py_CLEAR(clear_module_state->__pyx_empty_bytes); + Py_CLEAR(clear_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_CLEAR(clear_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_CLEAR(clear_module_state->__pyx_FusedFunctionType); + #endif + Py_CLEAR(clear_module_state->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext); + Py_CLEAR(clear_module_state->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf); + Py_CLEAR(clear_module_state->__pyx_ptype_7cpython_4type_type); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_dtype); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_flatiter); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_broadcast); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_ndarray); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_generic); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_number); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_integer); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_signedinteger); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_unsignedinteger); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_inexact); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_floating); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_complexfloating); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_flexible); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_character); + Py_CLEAR(clear_module_state->__pyx_ptype_5numpy_ufunc); + Py_CLEAR(clear_module_state->__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext); + Py_CLEAR(clear_module_state->__pyx_type_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext); + Py_CLEAR(clear_module_state->__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem); + Py_CLEAR(clear_module_state->__pyx_type_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem); + Py_CLEAR(clear_module_state->__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame); + Py_CLEAR(clear_module_state->__pyx_type_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame); + Py_CLEAR(clear_module_state->__pyx_array_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_array); + Py_CLEAR(clear_module_state->__pyx_MemviewEnum_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_MemviewEnum); + Py_CLEAR(clear_module_state->__pyx_memoryview_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_memoryview); + Py_CLEAR(clear_module_state->__pyx_memoryviewslice_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_memoryviewslice); + Py_CLEAR(clear_module_state->__pyx_kp_u_); + Py_CLEAR(clear_module_state->__pyx_n_s_ASCII); + Py_CLEAR(clear_module_state->__pyx_kp_s_All_dimensions_preceding_dimensi); + Py_CLEAR(clear_module_state->__pyx_n_s_AssertionError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Buffer_view_does_not_expose_stri); + Py_CLEAR(clear_module_state->__pyx_n_s_CLContext); + Py_CLEAR(clear_module_state->__pyx_n_s_CLContext___reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_CLContext___setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_CLMem); + Py_CLEAR(clear_module_state->__pyx_n_s_CLMem___reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_CLMem___setstate_cython); + Py_CLEAR(clear_module_state->__pyx_kp_s_Can_only_create_a_buffer_that_is); + Py_CLEAR(clear_module_state->__pyx_kp_s_Cannot_assign_to_read_only_memor); + Py_CLEAR(clear_module_state->__pyx_kp_s_Cannot_create_writable_memory_vi); + Py_CLEAR(clear_module_state->__pyx_kp_u_Cannot_index_with_type); + Py_CLEAR(clear_module_state->__pyx_kp_s_Cannot_transpose_memoryview_with); + Py_CLEAR(clear_module_state->__pyx_kp_s_Dimension_d_is_not_direct); + Py_CLEAR(clear_module_state->__pyx_n_s_Ellipsis); + Py_CLEAR(clear_module_state->__pyx_kp_s_Empty_shape_tuple_for_cython_arr); + Py_CLEAR(clear_module_state->__pyx_n_s_ImportError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0); + Py_CLEAR(clear_module_state->__pyx_n_s_IndexError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Index_out_of_bounds_axis_d); + Py_CLEAR(clear_module_state->__pyx_kp_s_Indirect_dimensions_not_supporte); + Py_CLEAR(clear_module_state->__pyx_kp_u_Invalid_mode_expected_c_or_fortr); + Py_CLEAR(clear_module_state->__pyx_kp_u_Invalid_shape_in_axis); + Py_CLEAR(clear_module_state->__pyx_n_s_MemoryError); + Py_CLEAR(clear_module_state->__pyx_kp_s_MemoryView_of_r_at_0x_x); + Py_CLEAR(clear_module_state->__pyx_kp_s_MemoryView_of_r_object); + Py_CLEAR(clear_module_state->__pyx_n_s_ModelFrame); + Py_CLEAR(clear_module_state->__pyx_n_s_ModelFrame___reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_ModelFrame___setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_ModelFrame_prepare); + Py_CLEAR(clear_module_state->__pyx_n_b_O); + Py_CLEAR(clear_module_state->__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + Py_CLEAR(clear_module_state->__pyx_n_s_PickleError); + Py_CLEAR(clear_module_state->__pyx_n_s_Sequence); + Py_CLEAR(clear_module_state->__pyx_kp_s_Step_may_not_be_zero_axis_d); + Py_CLEAR(clear_module_state->__pyx_kp_b_T); + Py_CLEAR(clear_module_state->__pyx_n_s_TypeError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Unable_to_convert_item_to_object); + Py_CLEAR(clear_module_state->__pyx_n_s_ValueError); + Py_CLEAR(clear_module_state->__pyx_n_s_View_MemoryView); + Py_CLEAR(clear_module_state->__pyx_kp_b__10); + Py_CLEAR(clear_module_state->__pyx_kp_b__11); + Py_CLEAR(clear_module_state->__pyx_kp_b__12); + Py_CLEAR(clear_module_state->__pyx_kp_u__13); + Py_CLEAR(clear_module_state->__pyx_kp_u__14); + Py_CLEAR(clear_module_state->__pyx_kp_u__2); + Py_CLEAR(clear_module_state->__pyx_n_s__3); + Py_CLEAR(clear_module_state->__pyx_n_s__40); + Py_CLEAR(clear_module_state->__pyx_kp_u__6); + Py_CLEAR(clear_module_state->__pyx_kp_u__7); + Py_CLEAR(clear_module_state->__pyx_kp_b__9); + Py_CLEAR(clear_module_state->__pyx_n_s_abc); + Py_CLEAR(clear_module_state->__pyx_n_s_allocate_buffer); + Py_CLEAR(clear_module_state->__pyx_kp_u_and); + Py_CLEAR(clear_module_state->__pyx_n_s_asarray); + Py_CLEAR(clear_module_state->__pyx_n_s_asyncio_coroutines); + Py_CLEAR(clear_module_state->__pyx_n_s_base); + Py_CLEAR(clear_module_state->__pyx_n_s_buf); + Py_CLEAR(clear_module_state->__pyx_n_s_c); + Py_CLEAR(clear_module_state->__pyx_n_u_c); + Py_CLEAR(clear_module_state->__pyx_n_s_class); + Py_CLEAR(clear_module_state->__pyx_n_s_class_getitem); + Py_CLEAR(clear_module_state->__pyx_n_s_cline_in_traceback); + Py_CLEAR(clear_module_state->__pyx_n_s_collections); + Py_CLEAR(clear_module_state->__pyx_kp_s_collections_abc); + Py_CLEAR(clear_module_state->__pyx_n_s_context); + Py_CLEAR(clear_module_state->__pyx_kp_s_contiguous_and_direct); + Py_CLEAR(clear_module_state->__pyx_kp_s_contiguous_and_indirect); + Py_CLEAR(clear_module_state->__pyx_n_s_count); + Py_CLEAR(clear_module_state->__pyx_n_s_cprojection); + Py_CLEAR(clear_module_state->__pyx_n_s_data); + Py_CLEAR(clear_module_state->__pyx_n_s_dict); + Py_CLEAR(clear_module_state->__pyx_kp_u_disable); + Py_CLEAR(clear_module_state->__pyx_n_s_dtype_is_object); + Py_CLEAR(clear_module_state->__pyx_kp_u_enable); + Py_CLEAR(clear_module_state->__pyx_n_s_encode); + Py_CLEAR(clear_module_state->__pyx_n_s_enumerate); + Py_CLEAR(clear_module_state->__pyx_n_s_error); + Py_CLEAR(clear_module_state->__pyx_n_s_flags); + Py_CLEAR(clear_module_state->__pyx_n_s_format); + Py_CLEAR(clear_module_state->__pyx_n_s_fortran); + Py_CLEAR(clear_module_state->__pyx_n_u_fortran); + Py_CLEAR(clear_module_state->__pyx_kp_u_gc); + Py_CLEAR(clear_module_state->__pyx_n_s_getstate); + Py_CLEAR(clear_module_state->__pyx_kp_u_got); + Py_CLEAR(clear_module_state->__pyx_kp_u_got_differing_extents_in_dimensi); + Py_CLEAR(clear_module_state->__pyx_n_s_height); + Py_CLEAR(clear_module_state->__pyx_n_s_id); + Py_CLEAR(clear_module_state->__pyx_n_s_import); + Py_CLEAR(clear_module_state->__pyx_n_s_index); + Py_CLEAR(clear_module_state->__pyx_n_s_initializing); + Py_CLEAR(clear_module_state->__pyx_n_s_is_coroutine); + Py_CLEAR(clear_module_state->__pyx_kp_u_isenabled); + Py_CLEAR(clear_module_state->__pyx_n_s_itemsize); + Py_CLEAR(clear_module_state->__pyx_kp_s_itemsize_0_for_cython_array); + Py_CLEAR(clear_module_state->__pyx_n_s_join); + Py_CLEAR(clear_module_state->__pyx_n_s_main); + Py_CLEAR(clear_module_state->__pyx_n_s_memview); + Py_CLEAR(clear_module_state->__pyx_n_s_mode); + Py_CLEAR(clear_module_state->__pyx_n_s_name); + Py_CLEAR(clear_module_state->__pyx_n_s_name_2); + Py_CLEAR(clear_module_state->__pyx_n_s_ndim); + Py_CLEAR(clear_module_state->__pyx_n_s_new); + Py_CLEAR(clear_module_state->__pyx_kp_s_no_default___reduce___due_to_non); + Py_CLEAR(clear_module_state->__pyx_n_s_np); + Py_CLEAR(clear_module_state->__pyx_n_s_numpy); + Py_CLEAR(clear_module_state->__pyx_kp_u_numpy_core_multiarray_failed_to); + Py_CLEAR(clear_module_state->__pyx_kp_u_numpy_core_umath_failed_to_impor); + Py_CLEAR(clear_module_state->__pyx_n_s_obj); + Py_CLEAR(clear_module_state->__pyx_n_s_output); + Py_CLEAR(clear_module_state->__pyx_n_s_pack); + Py_CLEAR(clear_module_state->__pyx_n_s_pickle); + Py_CLEAR(clear_module_state->__pyx_n_s_prepare); + Py_CLEAR(clear_module_state->__pyx_n_s_projection); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_PickleError); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_checksum); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_result); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_state); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_type); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_unpickle_Enum); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_vtable); + Py_CLEAR(clear_module_state->__pyx_n_s_range); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_ex); + Py_CLEAR(clear_module_state->__pyx_n_s_register); + Py_CLEAR(clear_module_state->__pyx_n_s_self); + Py_CLEAR(clear_module_state->__pyx_kp_s_self_mem_cannot_be_converted_to); + Py_CLEAR(clear_module_state->__pyx_kp_s_selfdrive_modeld_models_commonmo); + Py_CLEAR(clear_module_state->__pyx_n_s_selfdrive_modeld_models_commonmo_2); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_shape); + Py_CLEAR(clear_module_state->__pyx_n_s_sigmoid); + Py_CLEAR(clear_module_state->__pyx_n_s_size); + Py_CLEAR(clear_module_state->__pyx_n_s_spec); + Py_CLEAR(clear_module_state->__pyx_n_s_start); + Py_CLEAR(clear_module_state->__pyx_n_s_step); + Py_CLEAR(clear_module_state->__pyx_n_s_stop); + Py_CLEAR(clear_module_state->__pyx_n_s_stride); + Py_CLEAR(clear_module_state->__pyx_kp_s_strided_and_direct); + Py_CLEAR(clear_module_state->__pyx_kp_s_strided_and_direct_or_indirect); + Py_CLEAR(clear_module_state->__pyx_kp_s_strided_and_indirect); + Py_CLEAR(clear_module_state->__pyx_kp_s_stringsource); + Py_CLEAR(clear_module_state->__pyx_n_s_struct); + Py_CLEAR(clear_module_state->__pyx_n_s_sys); + Py_CLEAR(clear_module_state->__pyx_n_s_test); + Py_CLEAR(clear_module_state->__pyx_kp_s_unable_to_allocate_array_data); + Py_CLEAR(clear_module_state->__pyx_kp_s_unable_to_allocate_shape_and_str); + Py_CLEAR(clear_module_state->__pyx_n_s_unpack); + Py_CLEAR(clear_module_state->__pyx_n_s_update); + Py_CLEAR(clear_module_state->__pyx_n_s_uv_offset); + Py_CLEAR(clear_module_state->__pyx_n_s_version_info); + Py_CLEAR(clear_module_state->__pyx_n_s_width); + Py_CLEAR(clear_module_state->__pyx_n_s_x); + Py_CLEAR(clear_module_state->__pyx_int_0); + Py_CLEAR(clear_module_state->__pyx_int_1); + Py_CLEAR(clear_module_state->__pyx_int_3); + Py_CLEAR(clear_module_state->__pyx_int_112105877); + Py_CLEAR(clear_module_state->__pyx_int_136983863); + Py_CLEAR(clear_module_state->__pyx_int_184977713); + Py_CLEAR(clear_module_state->__pyx_int_neg_1); + Py_CLEAR(clear_module_state->__pyx_slice__5); + Py_CLEAR(clear_module_state->__pyx_tuple__4); + Py_CLEAR(clear_module_state->__pyx_tuple__8); + Py_CLEAR(clear_module_state->__pyx_tuple__15); + Py_CLEAR(clear_module_state->__pyx_tuple__16); + Py_CLEAR(clear_module_state->__pyx_tuple__17); + Py_CLEAR(clear_module_state->__pyx_tuple__18); + Py_CLEAR(clear_module_state->__pyx_tuple__19); + Py_CLEAR(clear_module_state->__pyx_tuple__20); + Py_CLEAR(clear_module_state->__pyx_tuple__21); + Py_CLEAR(clear_module_state->__pyx_tuple__22); + Py_CLEAR(clear_module_state->__pyx_tuple__23); + Py_CLEAR(clear_module_state->__pyx_tuple__24); + Py_CLEAR(clear_module_state->__pyx_tuple__25); + Py_CLEAR(clear_module_state->__pyx_tuple__26); + Py_CLEAR(clear_module_state->__pyx_tuple__28); + Py_CLEAR(clear_module_state->__pyx_tuple__30); + Py_CLEAR(clear_module_state->__pyx_tuple__32); + Py_CLEAR(clear_module_state->__pyx_tuple__36); + Py_CLEAR(clear_module_state->__pyx_codeobj__27); + Py_CLEAR(clear_module_state->__pyx_codeobj__29); + Py_CLEAR(clear_module_state->__pyx_codeobj__31); + Py_CLEAR(clear_module_state->__pyx_codeobj__33); + Py_CLEAR(clear_module_state->__pyx_codeobj__34); + Py_CLEAR(clear_module_state->__pyx_codeobj__35); + Py_CLEAR(clear_module_state->__pyx_codeobj__37); + Py_CLEAR(clear_module_state->__pyx_codeobj__38); + Py_CLEAR(clear_module_state->__pyx_codeobj__39); + return 0; +} +#endif +/* #### Code section: module_state_traverse ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { + __pyx_mstate *traverse_module_state = __pyx_mstate(m); + if (!traverse_module_state) return 0; + Py_VISIT(traverse_module_state->__pyx_d); + Py_VISIT(traverse_module_state->__pyx_b); + Py_VISIT(traverse_module_state->__pyx_cython_runtime); + Py_VISIT(traverse_module_state->__pyx_empty_tuple); + Py_VISIT(traverse_module_state->__pyx_empty_bytes); + Py_VISIT(traverse_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_VISIT(traverse_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_VISIT(traverse_module_state->__pyx_FusedFunctionType); + #endif + Py_VISIT(traverse_module_state->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext); + Py_VISIT(traverse_module_state->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf); + Py_VISIT(traverse_module_state->__pyx_ptype_7cpython_4type_type); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_dtype); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_flatiter); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_broadcast); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_ndarray); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_generic); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_number); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_integer); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_signedinteger); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_unsignedinteger); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_inexact); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_floating); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_complexfloating); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_flexible); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_character); + Py_VISIT(traverse_module_state->__pyx_ptype_5numpy_ufunc); + Py_VISIT(traverse_module_state->__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext); + Py_VISIT(traverse_module_state->__pyx_type_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext); + Py_VISIT(traverse_module_state->__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem); + Py_VISIT(traverse_module_state->__pyx_type_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem); + Py_VISIT(traverse_module_state->__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame); + Py_VISIT(traverse_module_state->__pyx_type_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame); + Py_VISIT(traverse_module_state->__pyx_array_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_array); + Py_VISIT(traverse_module_state->__pyx_MemviewEnum_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_MemviewEnum); + Py_VISIT(traverse_module_state->__pyx_memoryview_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_memoryview); + Py_VISIT(traverse_module_state->__pyx_memoryviewslice_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_memoryviewslice); + Py_VISIT(traverse_module_state->__pyx_kp_u_); + Py_VISIT(traverse_module_state->__pyx_n_s_ASCII); + Py_VISIT(traverse_module_state->__pyx_kp_s_All_dimensions_preceding_dimensi); + Py_VISIT(traverse_module_state->__pyx_n_s_AssertionError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Buffer_view_does_not_expose_stri); + Py_VISIT(traverse_module_state->__pyx_n_s_CLContext); + Py_VISIT(traverse_module_state->__pyx_n_s_CLContext___reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_CLContext___setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_CLMem); + Py_VISIT(traverse_module_state->__pyx_n_s_CLMem___reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_CLMem___setstate_cython); + Py_VISIT(traverse_module_state->__pyx_kp_s_Can_only_create_a_buffer_that_is); + Py_VISIT(traverse_module_state->__pyx_kp_s_Cannot_assign_to_read_only_memor); + Py_VISIT(traverse_module_state->__pyx_kp_s_Cannot_create_writable_memory_vi); + Py_VISIT(traverse_module_state->__pyx_kp_u_Cannot_index_with_type); + Py_VISIT(traverse_module_state->__pyx_kp_s_Cannot_transpose_memoryview_with); + Py_VISIT(traverse_module_state->__pyx_kp_s_Dimension_d_is_not_direct); + Py_VISIT(traverse_module_state->__pyx_n_s_Ellipsis); + Py_VISIT(traverse_module_state->__pyx_kp_s_Empty_shape_tuple_for_cython_arr); + Py_VISIT(traverse_module_state->__pyx_n_s_ImportError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0); + Py_VISIT(traverse_module_state->__pyx_n_s_IndexError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Index_out_of_bounds_axis_d); + Py_VISIT(traverse_module_state->__pyx_kp_s_Indirect_dimensions_not_supporte); + Py_VISIT(traverse_module_state->__pyx_kp_u_Invalid_mode_expected_c_or_fortr); + Py_VISIT(traverse_module_state->__pyx_kp_u_Invalid_shape_in_axis); + Py_VISIT(traverse_module_state->__pyx_n_s_MemoryError); + Py_VISIT(traverse_module_state->__pyx_kp_s_MemoryView_of_r_at_0x_x); + Py_VISIT(traverse_module_state->__pyx_kp_s_MemoryView_of_r_object); + Py_VISIT(traverse_module_state->__pyx_n_s_ModelFrame); + Py_VISIT(traverse_module_state->__pyx_n_s_ModelFrame___reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_ModelFrame___setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_ModelFrame_prepare); + Py_VISIT(traverse_module_state->__pyx_n_b_O); + Py_VISIT(traverse_module_state->__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + Py_VISIT(traverse_module_state->__pyx_n_s_PickleError); + Py_VISIT(traverse_module_state->__pyx_n_s_Sequence); + Py_VISIT(traverse_module_state->__pyx_kp_s_Step_may_not_be_zero_axis_d); + Py_VISIT(traverse_module_state->__pyx_kp_b_T); + Py_VISIT(traverse_module_state->__pyx_n_s_TypeError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Unable_to_convert_item_to_object); + Py_VISIT(traverse_module_state->__pyx_n_s_ValueError); + Py_VISIT(traverse_module_state->__pyx_n_s_View_MemoryView); + Py_VISIT(traverse_module_state->__pyx_kp_b__10); + Py_VISIT(traverse_module_state->__pyx_kp_b__11); + Py_VISIT(traverse_module_state->__pyx_kp_b__12); + Py_VISIT(traverse_module_state->__pyx_kp_u__13); + Py_VISIT(traverse_module_state->__pyx_kp_u__14); + Py_VISIT(traverse_module_state->__pyx_kp_u__2); + Py_VISIT(traverse_module_state->__pyx_n_s__3); + Py_VISIT(traverse_module_state->__pyx_n_s__40); + Py_VISIT(traverse_module_state->__pyx_kp_u__6); + Py_VISIT(traverse_module_state->__pyx_kp_u__7); + Py_VISIT(traverse_module_state->__pyx_kp_b__9); + Py_VISIT(traverse_module_state->__pyx_n_s_abc); + Py_VISIT(traverse_module_state->__pyx_n_s_allocate_buffer); + Py_VISIT(traverse_module_state->__pyx_kp_u_and); + Py_VISIT(traverse_module_state->__pyx_n_s_asarray); + Py_VISIT(traverse_module_state->__pyx_n_s_asyncio_coroutines); + Py_VISIT(traverse_module_state->__pyx_n_s_base); + Py_VISIT(traverse_module_state->__pyx_n_s_buf); + Py_VISIT(traverse_module_state->__pyx_n_s_c); + Py_VISIT(traverse_module_state->__pyx_n_u_c); + Py_VISIT(traverse_module_state->__pyx_n_s_class); + Py_VISIT(traverse_module_state->__pyx_n_s_class_getitem); + Py_VISIT(traverse_module_state->__pyx_n_s_cline_in_traceback); + Py_VISIT(traverse_module_state->__pyx_n_s_collections); + Py_VISIT(traverse_module_state->__pyx_kp_s_collections_abc); + Py_VISIT(traverse_module_state->__pyx_n_s_context); + Py_VISIT(traverse_module_state->__pyx_kp_s_contiguous_and_direct); + Py_VISIT(traverse_module_state->__pyx_kp_s_contiguous_and_indirect); + Py_VISIT(traverse_module_state->__pyx_n_s_count); + Py_VISIT(traverse_module_state->__pyx_n_s_cprojection); + Py_VISIT(traverse_module_state->__pyx_n_s_data); + Py_VISIT(traverse_module_state->__pyx_n_s_dict); + Py_VISIT(traverse_module_state->__pyx_kp_u_disable); + Py_VISIT(traverse_module_state->__pyx_n_s_dtype_is_object); + Py_VISIT(traverse_module_state->__pyx_kp_u_enable); + Py_VISIT(traverse_module_state->__pyx_n_s_encode); + Py_VISIT(traverse_module_state->__pyx_n_s_enumerate); + Py_VISIT(traverse_module_state->__pyx_n_s_error); + Py_VISIT(traverse_module_state->__pyx_n_s_flags); + Py_VISIT(traverse_module_state->__pyx_n_s_format); + Py_VISIT(traverse_module_state->__pyx_n_s_fortran); + Py_VISIT(traverse_module_state->__pyx_n_u_fortran); + Py_VISIT(traverse_module_state->__pyx_kp_u_gc); + Py_VISIT(traverse_module_state->__pyx_n_s_getstate); + Py_VISIT(traverse_module_state->__pyx_kp_u_got); + Py_VISIT(traverse_module_state->__pyx_kp_u_got_differing_extents_in_dimensi); + Py_VISIT(traverse_module_state->__pyx_n_s_height); + Py_VISIT(traverse_module_state->__pyx_n_s_id); + Py_VISIT(traverse_module_state->__pyx_n_s_import); + Py_VISIT(traverse_module_state->__pyx_n_s_index); + Py_VISIT(traverse_module_state->__pyx_n_s_initializing); + Py_VISIT(traverse_module_state->__pyx_n_s_is_coroutine); + Py_VISIT(traverse_module_state->__pyx_kp_u_isenabled); + Py_VISIT(traverse_module_state->__pyx_n_s_itemsize); + Py_VISIT(traverse_module_state->__pyx_kp_s_itemsize_0_for_cython_array); + Py_VISIT(traverse_module_state->__pyx_n_s_join); + Py_VISIT(traverse_module_state->__pyx_n_s_main); + Py_VISIT(traverse_module_state->__pyx_n_s_memview); + Py_VISIT(traverse_module_state->__pyx_n_s_mode); + Py_VISIT(traverse_module_state->__pyx_n_s_name); + Py_VISIT(traverse_module_state->__pyx_n_s_name_2); + Py_VISIT(traverse_module_state->__pyx_n_s_ndim); + Py_VISIT(traverse_module_state->__pyx_n_s_new); + Py_VISIT(traverse_module_state->__pyx_kp_s_no_default___reduce___due_to_non); + Py_VISIT(traverse_module_state->__pyx_n_s_np); + Py_VISIT(traverse_module_state->__pyx_n_s_numpy); + Py_VISIT(traverse_module_state->__pyx_kp_u_numpy_core_multiarray_failed_to); + Py_VISIT(traverse_module_state->__pyx_kp_u_numpy_core_umath_failed_to_impor); + Py_VISIT(traverse_module_state->__pyx_n_s_obj); + Py_VISIT(traverse_module_state->__pyx_n_s_output); + Py_VISIT(traverse_module_state->__pyx_n_s_pack); + Py_VISIT(traverse_module_state->__pyx_n_s_pickle); + Py_VISIT(traverse_module_state->__pyx_n_s_prepare); + Py_VISIT(traverse_module_state->__pyx_n_s_projection); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_PickleError); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_checksum); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_result); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_state); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_type); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_unpickle_Enum); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_vtable); + Py_VISIT(traverse_module_state->__pyx_n_s_range); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_ex); + Py_VISIT(traverse_module_state->__pyx_n_s_register); + Py_VISIT(traverse_module_state->__pyx_n_s_self); + Py_VISIT(traverse_module_state->__pyx_kp_s_self_mem_cannot_be_converted_to); + Py_VISIT(traverse_module_state->__pyx_kp_s_selfdrive_modeld_models_commonmo); + Py_VISIT(traverse_module_state->__pyx_n_s_selfdrive_modeld_models_commonmo_2); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_shape); + Py_VISIT(traverse_module_state->__pyx_n_s_sigmoid); + Py_VISIT(traverse_module_state->__pyx_n_s_size); + Py_VISIT(traverse_module_state->__pyx_n_s_spec); + Py_VISIT(traverse_module_state->__pyx_n_s_start); + Py_VISIT(traverse_module_state->__pyx_n_s_step); + Py_VISIT(traverse_module_state->__pyx_n_s_stop); + Py_VISIT(traverse_module_state->__pyx_n_s_stride); + Py_VISIT(traverse_module_state->__pyx_kp_s_strided_and_direct); + Py_VISIT(traverse_module_state->__pyx_kp_s_strided_and_direct_or_indirect); + Py_VISIT(traverse_module_state->__pyx_kp_s_strided_and_indirect); + Py_VISIT(traverse_module_state->__pyx_kp_s_stringsource); + Py_VISIT(traverse_module_state->__pyx_n_s_struct); + Py_VISIT(traverse_module_state->__pyx_n_s_sys); + Py_VISIT(traverse_module_state->__pyx_n_s_test); + Py_VISIT(traverse_module_state->__pyx_kp_s_unable_to_allocate_array_data); + Py_VISIT(traverse_module_state->__pyx_kp_s_unable_to_allocate_shape_and_str); + Py_VISIT(traverse_module_state->__pyx_n_s_unpack); + Py_VISIT(traverse_module_state->__pyx_n_s_update); + Py_VISIT(traverse_module_state->__pyx_n_s_uv_offset); + Py_VISIT(traverse_module_state->__pyx_n_s_version_info); + Py_VISIT(traverse_module_state->__pyx_n_s_width); + Py_VISIT(traverse_module_state->__pyx_n_s_x); + Py_VISIT(traverse_module_state->__pyx_int_0); + Py_VISIT(traverse_module_state->__pyx_int_1); + Py_VISIT(traverse_module_state->__pyx_int_3); + Py_VISIT(traverse_module_state->__pyx_int_112105877); + Py_VISIT(traverse_module_state->__pyx_int_136983863); + Py_VISIT(traverse_module_state->__pyx_int_184977713); + Py_VISIT(traverse_module_state->__pyx_int_neg_1); + Py_VISIT(traverse_module_state->__pyx_slice__5); + Py_VISIT(traverse_module_state->__pyx_tuple__4); + Py_VISIT(traverse_module_state->__pyx_tuple__8); + Py_VISIT(traverse_module_state->__pyx_tuple__15); + Py_VISIT(traverse_module_state->__pyx_tuple__16); + Py_VISIT(traverse_module_state->__pyx_tuple__17); + Py_VISIT(traverse_module_state->__pyx_tuple__18); + Py_VISIT(traverse_module_state->__pyx_tuple__19); + Py_VISIT(traverse_module_state->__pyx_tuple__20); + Py_VISIT(traverse_module_state->__pyx_tuple__21); + Py_VISIT(traverse_module_state->__pyx_tuple__22); + Py_VISIT(traverse_module_state->__pyx_tuple__23); + Py_VISIT(traverse_module_state->__pyx_tuple__24); + Py_VISIT(traverse_module_state->__pyx_tuple__25); + Py_VISIT(traverse_module_state->__pyx_tuple__26); + Py_VISIT(traverse_module_state->__pyx_tuple__28); + Py_VISIT(traverse_module_state->__pyx_tuple__30); + Py_VISIT(traverse_module_state->__pyx_tuple__32); + Py_VISIT(traverse_module_state->__pyx_tuple__36); + Py_VISIT(traverse_module_state->__pyx_codeobj__27); + Py_VISIT(traverse_module_state->__pyx_codeobj__29); + Py_VISIT(traverse_module_state->__pyx_codeobj__31); + Py_VISIT(traverse_module_state->__pyx_codeobj__33); + Py_VISIT(traverse_module_state->__pyx_codeobj__34); + Py_VISIT(traverse_module_state->__pyx_codeobj__35); + Py_VISIT(traverse_module_state->__pyx_codeobj__37); + Py_VISIT(traverse_module_state->__pyx_codeobj__38); + Py_VISIT(traverse_module_state->__pyx_codeobj__39); + return 0; +} +#endif +/* #### Code section: module_state_defines ### */ +#define __pyx_d __pyx_mstate_global->__pyx_d +#define __pyx_b __pyx_mstate_global->__pyx_b +#define __pyx_cython_runtime __pyx_mstate_global->__pyx_cython_runtime +#define __pyx_empty_tuple __pyx_mstate_global->__pyx_empty_tuple +#define __pyx_empty_bytes __pyx_mstate_global->__pyx_empty_bytes +#define __pyx_empty_unicode __pyx_mstate_global->__pyx_empty_unicode +#ifdef __Pyx_CyFunction_USED +#define __pyx_CyFunctionType __pyx_mstate_global->__pyx_CyFunctionType +#endif +#ifdef __Pyx_FusedFunction_USED +#define __pyx_FusedFunctionType __pyx_mstate_global->__pyx_FusedFunctionType +#endif +#ifdef __Pyx_Generator_USED +#define __pyx_GeneratorType __pyx_mstate_global->__pyx_GeneratorType +#endif +#ifdef __Pyx_IterableCoroutine_USED +#define __pyx_IterableCoroutineType __pyx_mstate_global->__pyx_IterableCoroutineType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineAwaitType __pyx_mstate_global->__pyx_CoroutineAwaitType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineType __pyx_mstate_global->__pyx_CoroutineType +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#define __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext __pyx_mstate_global->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext +#define __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf __pyx_mstate_global->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#define __pyx_ptype_7cpython_4type_type __pyx_mstate_global->__pyx_ptype_7cpython_4type_type +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#define __pyx_ptype_5numpy_dtype __pyx_mstate_global->__pyx_ptype_5numpy_dtype +#define __pyx_ptype_5numpy_flatiter __pyx_mstate_global->__pyx_ptype_5numpy_flatiter +#define __pyx_ptype_5numpy_broadcast __pyx_mstate_global->__pyx_ptype_5numpy_broadcast +#define __pyx_ptype_5numpy_ndarray __pyx_mstate_global->__pyx_ptype_5numpy_ndarray +#define __pyx_ptype_5numpy_generic __pyx_mstate_global->__pyx_ptype_5numpy_generic +#define __pyx_ptype_5numpy_number __pyx_mstate_global->__pyx_ptype_5numpy_number +#define __pyx_ptype_5numpy_integer __pyx_mstate_global->__pyx_ptype_5numpy_integer +#define __pyx_ptype_5numpy_signedinteger __pyx_mstate_global->__pyx_ptype_5numpy_signedinteger +#define __pyx_ptype_5numpy_unsignedinteger __pyx_mstate_global->__pyx_ptype_5numpy_unsignedinteger +#define __pyx_ptype_5numpy_inexact __pyx_mstate_global->__pyx_ptype_5numpy_inexact +#define __pyx_ptype_5numpy_floating __pyx_mstate_global->__pyx_ptype_5numpy_floating +#define __pyx_ptype_5numpy_complexfloating __pyx_mstate_global->__pyx_ptype_5numpy_complexfloating +#define __pyx_ptype_5numpy_flexible __pyx_mstate_global->__pyx_ptype_5numpy_flexible +#define __pyx_ptype_5numpy_character __pyx_mstate_global->__pyx_ptype_5numpy_character +#define __pyx_ptype_5numpy_ufunc __pyx_mstate_global->__pyx_ptype_5numpy_ufunc +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#define __pyx_type_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext __pyx_mstate_global->__pyx_type_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext +#define __pyx_type_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem __pyx_mstate_global->__pyx_type_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem +#define __pyx_type_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame __pyx_mstate_global->__pyx_type_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame +#define __pyx_type___pyx_array __pyx_mstate_global->__pyx_type___pyx_array +#define __pyx_type___pyx_MemviewEnum __pyx_mstate_global->__pyx_type___pyx_MemviewEnum +#define __pyx_type___pyx_memoryview __pyx_mstate_global->__pyx_type___pyx_memoryview +#define __pyx_type___pyx_memoryviewslice __pyx_mstate_global->__pyx_type___pyx_memoryviewslice +#endif +#define __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext __pyx_mstate_global->__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext +#define __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem __pyx_mstate_global->__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem +#define __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame __pyx_mstate_global->__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame +#define __pyx_array_type __pyx_mstate_global->__pyx_array_type +#define __pyx_MemviewEnum_type __pyx_mstate_global->__pyx_MemviewEnum_type +#define __pyx_memoryview_type __pyx_mstate_global->__pyx_memoryview_type +#define __pyx_memoryviewslice_type __pyx_mstate_global->__pyx_memoryviewslice_type +#define __pyx_kp_u_ __pyx_mstate_global->__pyx_kp_u_ +#define __pyx_n_s_ASCII __pyx_mstate_global->__pyx_n_s_ASCII +#define __pyx_kp_s_All_dimensions_preceding_dimensi __pyx_mstate_global->__pyx_kp_s_All_dimensions_preceding_dimensi +#define __pyx_n_s_AssertionError __pyx_mstate_global->__pyx_n_s_AssertionError +#define __pyx_kp_s_Buffer_view_does_not_expose_stri __pyx_mstate_global->__pyx_kp_s_Buffer_view_does_not_expose_stri +#define __pyx_n_s_CLContext __pyx_mstate_global->__pyx_n_s_CLContext +#define __pyx_n_s_CLContext___reduce_cython __pyx_mstate_global->__pyx_n_s_CLContext___reduce_cython +#define __pyx_n_s_CLContext___setstate_cython __pyx_mstate_global->__pyx_n_s_CLContext___setstate_cython +#define __pyx_n_s_CLMem __pyx_mstate_global->__pyx_n_s_CLMem +#define __pyx_n_s_CLMem___reduce_cython __pyx_mstate_global->__pyx_n_s_CLMem___reduce_cython +#define __pyx_n_s_CLMem___setstate_cython __pyx_mstate_global->__pyx_n_s_CLMem___setstate_cython +#define __pyx_kp_s_Can_only_create_a_buffer_that_is __pyx_mstate_global->__pyx_kp_s_Can_only_create_a_buffer_that_is +#define __pyx_kp_s_Cannot_assign_to_read_only_memor __pyx_mstate_global->__pyx_kp_s_Cannot_assign_to_read_only_memor +#define __pyx_kp_s_Cannot_create_writable_memory_vi __pyx_mstate_global->__pyx_kp_s_Cannot_create_writable_memory_vi +#define __pyx_kp_u_Cannot_index_with_type __pyx_mstate_global->__pyx_kp_u_Cannot_index_with_type +#define __pyx_kp_s_Cannot_transpose_memoryview_with __pyx_mstate_global->__pyx_kp_s_Cannot_transpose_memoryview_with +#define __pyx_kp_s_Dimension_d_is_not_direct __pyx_mstate_global->__pyx_kp_s_Dimension_d_is_not_direct +#define __pyx_n_s_Ellipsis __pyx_mstate_global->__pyx_n_s_Ellipsis +#define __pyx_kp_s_Empty_shape_tuple_for_cython_arr __pyx_mstate_global->__pyx_kp_s_Empty_shape_tuple_for_cython_arr +#define __pyx_n_s_ImportError __pyx_mstate_global->__pyx_n_s_ImportError +#define __pyx_kp_s_Incompatible_checksums_0x_x_vs_0 __pyx_mstate_global->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0 +#define __pyx_n_s_IndexError __pyx_mstate_global->__pyx_n_s_IndexError +#define __pyx_kp_s_Index_out_of_bounds_axis_d __pyx_mstate_global->__pyx_kp_s_Index_out_of_bounds_axis_d +#define __pyx_kp_s_Indirect_dimensions_not_supporte __pyx_mstate_global->__pyx_kp_s_Indirect_dimensions_not_supporte +#define __pyx_kp_u_Invalid_mode_expected_c_or_fortr __pyx_mstate_global->__pyx_kp_u_Invalid_mode_expected_c_or_fortr +#define __pyx_kp_u_Invalid_shape_in_axis __pyx_mstate_global->__pyx_kp_u_Invalid_shape_in_axis +#define __pyx_n_s_MemoryError __pyx_mstate_global->__pyx_n_s_MemoryError +#define __pyx_kp_s_MemoryView_of_r_at_0x_x __pyx_mstate_global->__pyx_kp_s_MemoryView_of_r_at_0x_x +#define __pyx_kp_s_MemoryView_of_r_object __pyx_mstate_global->__pyx_kp_s_MemoryView_of_r_object +#define __pyx_n_s_ModelFrame __pyx_mstate_global->__pyx_n_s_ModelFrame +#define __pyx_n_s_ModelFrame___reduce_cython __pyx_mstate_global->__pyx_n_s_ModelFrame___reduce_cython +#define __pyx_n_s_ModelFrame___setstate_cython __pyx_mstate_global->__pyx_n_s_ModelFrame___setstate_cython +#define __pyx_n_s_ModelFrame_prepare __pyx_mstate_global->__pyx_n_s_ModelFrame_prepare +#define __pyx_n_b_O __pyx_mstate_global->__pyx_n_b_O +#define __pyx_kp_u_Out_of_bounds_on_buffer_access_a __pyx_mstate_global->__pyx_kp_u_Out_of_bounds_on_buffer_access_a +#define __pyx_n_s_PickleError __pyx_mstate_global->__pyx_n_s_PickleError +#define __pyx_n_s_Sequence __pyx_mstate_global->__pyx_n_s_Sequence +#define __pyx_kp_s_Step_may_not_be_zero_axis_d __pyx_mstate_global->__pyx_kp_s_Step_may_not_be_zero_axis_d +#define __pyx_kp_b_T __pyx_mstate_global->__pyx_kp_b_T +#define __pyx_n_s_TypeError __pyx_mstate_global->__pyx_n_s_TypeError +#define __pyx_kp_s_Unable_to_convert_item_to_object __pyx_mstate_global->__pyx_kp_s_Unable_to_convert_item_to_object +#define __pyx_n_s_ValueError __pyx_mstate_global->__pyx_n_s_ValueError +#define __pyx_n_s_View_MemoryView __pyx_mstate_global->__pyx_n_s_View_MemoryView +#define __pyx_kp_b__10 __pyx_mstate_global->__pyx_kp_b__10 +#define __pyx_kp_b__11 __pyx_mstate_global->__pyx_kp_b__11 +#define __pyx_kp_b__12 __pyx_mstate_global->__pyx_kp_b__12 +#define __pyx_kp_u__13 __pyx_mstate_global->__pyx_kp_u__13 +#define __pyx_kp_u__14 __pyx_mstate_global->__pyx_kp_u__14 +#define __pyx_kp_u__2 __pyx_mstate_global->__pyx_kp_u__2 +#define __pyx_n_s__3 __pyx_mstate_global->__pyx_n_s__3 +#define __pyx_n_s__40 __pyx_mstate_global->__pyx_n_s__40 +#define __pyx_kp_u__6 __pyx_mstate_global->__pyx_kp_u__6 +#define __pyx_kp_u__7 __pyx_mstate_global->__pyx_kp_u__7 +#define __pyx_kp_b__9 __pyx_mstate_global->__pyx_kp_b__9 +#define __pyx_n_s_abc __pyx_mstate_global->__pyx_n_s_abc +#define __pyx_n_s_allocate_buffer __pyx_mstate_global->__pyx_n_s_allocate_buffer +#define __pyx_kp_u_and __pyx_mstate_global->__pyx_kp_u_and +#define __pyx_n_s_asarray __pyx_mstate_global->__pyx_n_s_asarray +#define __pyx_n_s_asyncio_coroutines __pyx_mstate_global->__pyx_n_s_asyncio_coroutines +#define __pyx_n_s_base __pyx_mstate_global->__pyx_n_s_base +#define __pyx_n_s_buf __pyx_mstate_global->__pyx_n_s_buf +#define __pyx_n_s_c __pyx_mstate_global->__pyx_n_s_c +#define __pyx_n_u_c __pyx_mstate_global->__pyx_n_u_c +#define __pyx_n_s_class __pyx_mstate_global->__pyx_n_s_class +#define __pyx_n_s_class_getitem __pyx_mstate_global->__pyx_n_s_class_getitem +#define __pyx_n_s_cline_in_traceback __pyx_mstate_global->__pyx_n_s_cline_in_traceback +#define __pyx_n_s_collections __pyx_mstate_global->__pyx_n_s_collections +#define __pyx_kp_s_collections_abc __pyx_mstate_global->__pyx_kp_s_collections_abc +#define __pyx_n_s_context __pyx_mstate_global->__pyx_n_s_context +#define __pyx_kp_s_contiguous_and_direct __pyx_mstate_global->__pyx_kp_s_contiguous_and_direct +#define __pyx_kp_s_contiguous_and_indirect __pyx_mstate_global->__pyx_kp_s_contiguous_and_indirect +#define __pyx_n_s_count __pyx_mstate_global->__pyx_n_s_count +#define __pyx_n_s_cprojection __pyx_mstate_global->__pyx_n_s_cprojection +#define __pyx_n_s_data __pyx_mstate_global->__pyx_n_s_data +#define __pyx_n_s_dict __pyx_mstate_global->__pyx_n_s_dict +#define __pyx_kp_u_disable __pyx_mstate_global->__pyx_kp_u_disable +#define __pyx_n_s_dtype_is_object __pyx_mstate_global->__pyx_n_s_dtype_is_object +#define __pyx_kp_u_enable __pyx_mstate_global->__pyx_kp_u_enable +#define __pyx_n_s_encode __pyx_mstate_global->__pyx_n_s_encode +#define __pyx_n_s_enumerate __pyx_mstate_global->__pyx_n_s_enumerate +#define __pyx_n_s_error __pyx_mstate_global->__pyx_n_s_error +#define __pyx_n_s_flags __pyx_mstate_global->__pyx_n_s_flags +#define __pyx_n_s_format __pyx_mstate_global->__pyx_n_s_format +#define __pyx_n_s_fortran __pyx_mstate_global->__pyx_n_s_fortran +#define __pyx_n_u_fortran __pyx_mstate_global->__pyx_n_u_fortran +#define __pyx_kp_u_gc __pyx_mstate_global->__pyx_kp_u_gc +#define __pyx_n_s_getstate __pyx_mstate_global->__pyx_n_s_getstate +#define __pyx_kp_u_got __pyx_mstate_global->__pyx_kp_u_got +#define __pyx_kp_u_got_differing_extents_in_dimensi __pyx_mstate_global->__pyx_kp_u_got_differing_extents_in_dimensi +#define __pyx_n_s_height __pyx_mstate_global->__pyx_n_s_height +#define __pyx_n_s_id __pyx_mstate_global->__pyx_n_s_id +#define __pyx_n_s_import __pyx_mstate_global->__pyx_n_s_import +#define __pyx_n_s_index __pyx_mstate_global->__pyx_n_s_index +#define __pyx_n_s_initializing __pyx_mstate_global->__pyx_n_s_initializing +#define __pyx_n_s_is_coroutine __pyx_mstate_global->__pyx_n_s_is_coroutine +#define __pyx_kp_u_isenabled __pyx_mstate_global->__pyx_kp_u_isenabled +#define __pyx_n_s_itemsize __pyx_mstate_global->__pyx_n_s_itemsize +#define __pyx_kp_s_itemsize_0_for_cython_array __pyx_mstate_global->__pyx_kp_s_itemsize_0_for_cython_array +#define __pyx_n_s_join __pyx_mstate_global->__pyx_n_s_join +#define __pyx_n_s_main __pyx_mstate_global->__pyx_n_s_main +#define __pyx_n_s_memview __pyx_mstate_global->__pyx_n_s_memview +#define __pyx_n_s_mode __pyx_mstate_global->__pyx_n_s_mode +#define __pyx_n_s_name __pyx_mstate_global->__pyx_n_s_name +#define __pyx_n_s_name_2 __pyx_mstate_global->__pyx_n_s_name_2 +#define __pyx_n_s_ndim __pyx_mstate_global->__pyx_n_s_ndim +#define __pyx_n_s_new __pyx_mstate_global->__pyx_n_s_new +#define __pyx_kp_s_no_default___reduce___due_to_non __pyx_mstate_global->__pyx_kp_s_no_default___reduce___due_to_non +#define __pyx_n_s_np __pyx_mstate_global->__pyx_n_s_np +#define __pyx_n_s_numpy __pyx_mstate_global->__pyx_n_s_numpy +#define __pyx_kp_u_numpy_core_multiarray_failed_to __pyx_mstate_global->__pyx_kp_u_numpy_core_multiarray_failed_to +#define __pyx_kp_u_numpy_core_umath_failed_to_impor __pyx_mstate_global->__pyx_kp_u_numpy_core_umath_failed_to_impor +#define __pyx_n_s_obj __pyx_mstate_global->__pyx_n_s_obj +#define __pyx_n_s_output __pyx_mstate_global->__pyx_n_s_output +#define __pyx_n_s_pack __pyx_mstate_global->__pyx_n_s_pack +#define __pyx_n_s_pickle __pyx_mstate_global->__pyx_n_s_pickle +#define __pyx_n_s_prepare __pyx_mstate_global->__pyx_n_s_prepare +#define __pyx_n_s_projection __pyx_mstate_global->__pyx_n_s_projection +#define __pyx_n_s_pyx_PickleError __pyx_mstate_global->__pyx_n_s_pyx_PickleError +#define __pyx_n_s_pyx_checksum __pyx_mstate_global->__pyx_n_s_pyx_checksum +#define __pyx_n_s_pyx_result __pyx_mstate_global->__pyx_n_s_pyx_result +#define __pyx_n_s_pyx_state __pyx_mstate_global->__pyx_n_s_pyx_state +#define __pyx_n_s_pyx_type __pyx_mstate_global->__pyx_n_s_pyx_type +#define __pyx_n_s_pyx_unpickle_Enum __pyx_mstate_global->__pyx_n_s_pyx_unpickle_Enum +#define __pyx_n_s_pyx_vtable __pyx_mstate_global->__pyx_n_s_pyx_vtable +#define __pyx_n_s_range __pyx_mstate_global->__pyx_n_s_range +#define __pyx_n_s_reduce __pyx_mstate_global->__pyx_n_s_reduce +#define __pyx_n_s_reduce_cython __pyx_mstate_global->__pyx_n_s_reduce_cython +#define __pyx_n_s_reduce_ex __pyx_mstate_global->__pyx_n_s_reduce_ex +#define __pyx_n_s_register __pyx_mstate_global->__pyx_n_s_register +#define __pyx_n_s_self __pyx_mstate_global->__pyx_n_s_self +#define __pyx_kp_s_self_mem_cannot_be_converted_to __pyx_mstate_global->__pyx_kp_s_self_mem_cannot_be_converted_to +#define __pyx_kp_s_selfdrive_modeld_models_commonmo __pyx_mstate_global->__pyx_kp_s_selfdrive_modeld_models_commonmo +#define __pyx_n_s_selfdrive_modeld_models_commonmo_2 __pyx_mstate_global->__pyx_n_s_selfdrive_modeld_models_commonmo_2 +#define __pyx_n_s_setstate __pyx_mstate_global->__pyx_n_s_setstate +#define __pyx_n_s_setstate_cython __pyx_mstate_global->__pyx_n_s_setstate_cython +#define __pyx_n_s_shape __pyx_mstate_global->__pyx_n_s_shape +#define __pyx_n_s_sigmoid __pyx_mstate_global->__pyx_n_s_sigmoid +#define __pyx_n_s_size __pyx_mstate_global->__pyx_n_s_size +#define __pyx_n_s_spec __pyx_mstate_global->__pyx_n_s_spec +#define __pyx_n_s_start __pyx_mstate_global->__pyx_n_s_start +#define __pyx_n_s_step __pyx_mstate_global->__pyx_n_s_step +#define __pyx_n_s_stop __pyx_mstate_global->__pyx_n_s_stop +#define __pyx_n_s_stride __pyx_mstate_global->__pyx_n_s_stride +#define __pyx_kp_s_strided_and_direct __pyx_mstate_global->__pyx_kp_s_strided_and_direct +#define __pyx_kp_s_strided_and_direct_or_indirect __pyx_mstate_global->__pyx_kp_s_strided_and_direct_or_indirect +#define __pyx_kp_s_strided_and_indirect __pyx_mstate_global->__pyx_kp_s_strided_and_indirect +#define __pyx_kp_s_stringsource __pyx_mstate_global->__pyx_kp_s_stringsource +#define __pyx_n_s_struct __pyx_mstate_global->__pyx_n_s_struct +#define __pyx_n_s_sys __pyx_mstate_global->__pyx_n_s_sys +#define __pyx_n_s_test __pyx_mstate_global->__pyx_n_s_test +#define __pyx_kp_s_unable_to_allocate_array_data __pyx_mstate_global->__pyx_kp_s_unable_to_allocate_array_data +#define __pyx_kp_s_unable_to_allocate_shape_and_str __pyx_mstate_global->__pyx_kp_s_unable_to_allocate_shape_and_str +#define __pyx_n_s_unpack __pyx_mstate_global->__pyx_n_s_unpack +#define __pyx_n_s_update __pyx_mstate_global->__pyx_n_s_update +#define __pyx_n_s_uv_offset __pyx_mstate_global->__pyx_n_s_uv_offset +#define __pyx_n_s_version_info __pyx_mstate_global->__pyx_n_s_version_info +#define __pyx_n_s_width __pyx_mstate_global->__pyx_n_s_width +#define __pyx_n_s_x __pyx_mstate_global->__pyx_n_s_x +#define __pyx_int_0 __pyx_mstate_global->__pyx_int_0 +#define __pyx_int_1 __pyx_mstate_global->__pyx_int_1 +#define __pyx_int_3 __pyx_mstate_global->__pyx_int_3 +#define __pyx_int_112105877 __pyx_mstate_global->__pyx_int_112105877 +#define __pyx_int_136983863 __pyx_mstate_global->__pyx_int_136983863 +#define __pyx_int_184977713 __pyx_mstate_global->__pyx_int_184977713 +#define __pyx_int_neg_1 __pyx_mstate_global->__pyx_int_neg_1 +#define __pyx_slice__5 __pyx_mstate_global->__pyx_slice__5 +#define __pyx_tuple__4 __pyx_mstate_global->__pyx_tuple__4 +#define __pyx_tuple__8 __pyx_mstate_global->__pyx_tuple__8 +#define __pyx_tuple__15 __pyx_mstate_global->__pyx_tuple__15 +#define __pyx_tuple__16 __pyx_mstate_global->__pyx_tuple__16 +#define __pyx_tuple__17 __pyx_mstate_global->__pyx_tuple__17 +#define __pyx_tuple__18 __pyx_mstate_global->__pyx_tuple__18 +#define __pyx_tuple__19 __pyx_mstate_global->__pyx_tuple__19 +#define __pyx_tuple__20 __pyx_mstate_global->__pyx_tuple__20 +#define __pyx_tuple__21 __pyx_mstate_global->__pyx_tuple__21 +#define __pyx_tuple__22 __pyx_mstate_global->__pyx_tuple__22 +#define __pyx_tuple__23 __pyx_mstate_global->__pyx_tuple__23 +#define __pyx_tuple__24 __pyx_mstate_global->__pyx_tuple__24 +#define __pyx_tuple__25 __pyx_mstate_global->__pyx_tuple__25 +#define __pyx_tuple__26 __pyx_mstate_global->__pyx_tuple__26 +#define __pyx_tuple__28 __pyx_mstate_global->__pyx_tuple__28 +#define __pyx_tuple__30 __pyx_mstate_global->__pyx_tuple__30 +#define __pyx_tuple__32 __pyx_mstate_global->__pyx_tuple__32 +#define __pyx_tuple__36 __pyx_mstate_global->__pyx_tuple__36 +#define __pyx_codeobj__27 __pyx_mstate_global->__pyx_codeobj__27 +#define __pyx_codeobj__29 __pyx_mstate_global->__pyx_codeobj__29 +#define __pyx_codeobj__31 __pyx_mstate_global->__pyx_codeobj__31 +#define __pyx_codeobj__33 __pyx_mstate_global->__pyx_codeobj__33 +#define __pyx_codeobj__34 __pyx_mstate_global->__pyx_codeobj__34 +#define __pyx_codeobj__35 __pyx_mstate_global->__pyx_codeobj__35 +#define __pyx_codeobj__37 __pyx_mstate_global->__pyx_codeobj__37 +#define __pyx_codeobj__38 __pyx_mstate_global->__pyx_codeobj__38 +#define __pyx_codeobj__39 __pyx_mstate_global->__pyx_codeobj__39 +/* #### Code section: module_code ### */ + +/* "View.MemoryView":131 + * cdef bint dtype_is_object + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, # <<<<<<<<<<<<<< + * mode="c", bint allocate_buffer=True): + * + */ + +/* Python wrapper */ +static int __pyx_array___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_array___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_shape = 0; + Py_ssize_t __pyx_v_itemsize; + PyObject *__pyx_v_format = 0; + PyObject *__pyx_v_mode = 0; + int __pyx_v_allocate_buffer; + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[5] = {0,0,0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_shape,&__pyx_n_s_itemsize,&__pyx_n_s_format,&__pyx_n_s_mode,&__pyx_n_s_allocate_buffer,0}; + values[3] = __Pyx_Arg_NewRef_VARARGS(((PyObject *)__pyx_n_s_c)); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 5: values[4] = __Pyx_Arg_VARARGS(__pyx_args, 4); + CYTHON_FALLTHROUGH; + case 4: values[3] = __Pyx_Arg_VARARGS(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_shape)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 131, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_itemsize)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 131, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 3, 5, 1); __PYX_ERR(0, 131, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_format)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 131, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 3, 5, 2); __PYX_ERR(0, 131, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 3: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_mode); + if (value) { values[3] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 131, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 4: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_allocate_buffer); + if (value) { values[4] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 131, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(0, 131, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 5: values[4] = __Pyx_Arg_VARARGS(__pyx_args, 4); + CYTHON_FALLTHROUGH; + case 4: values[3] = __Pyx_Arg_VARARGS(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_shape = ((PyObject*)values[0]); + __pyx_v_itemsize = __Pyx_PyIndex_AsSsize_t(values[1]); if (unlikely((__pyx_v_itemsize == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 131, __pyx_L3_error) + __pyx_v_format = values[2]; + __pyx_v_mode = values[3]; + if (values[4]) { + __pyx_v_allocate_buffer = __Pyx_PyObject_IsTrue(values[4]); if (unlikely((__pyx_v_allocate_buffer == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 132, __pyx_L3_error) + } else { + + /* "View.MemoryView":132 + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, + * mode="c", bint allocate_buffer=True): # <<<<<<<<<<<<<< + * + * cdef int idx + */ + __pyx_v_allocate_buffer = ((int)1); + } + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 3, 5, __pyx_nargs); __PYX_ERR(0, 131, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.array.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_shape), (&PyTuple_Type), 1, "shape", 1))) __PYX_ERR(0, 131, __pyx_L1_error) + if (unlikely(((PyObject *)__pyx_v_format) == Py_None)) { + PyErr_Format(PyExc_TypeError, "Argument '%.200s' must not be None", "format"); __PYX_ERR(0, 131, __pyx_L1_error) + } + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array___cinit__(((struct __pyx_array_obj *)__pyx_v_self), __pyx_v_shape, __pyx_v_itemsize, __pyx_v_format, __pyx_v_mode, __pyx_v_allocate_buffer); + + /* "View.MemoryView":131 + * cdef bint dtype_is_object + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, # <<<<<<<<<<<<<< + * mode="c", bint allocate_buffer=True): + * + */ + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = -1; + __pyx_L0:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array___cinit__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_shape, Py_ssize_t __pyx_v_itemsize, PyObject *__pyx_v_format, PyObject *__pyx_v_mode, int __pyx_v_allocate_buffer) { + int __pyx_v_idx; + Py_ssize_t __pyx_v_dim; + char __pyx_v_order; + int __pyx_r; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + int __pyx_t_7; + char *__pyx_t_8; + Py_ssize_t __pyx_t_9; + Py_UCS4 __pyx_t_10; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__cinit__", 0); + __Pyx_INCREF(__pyx_v_format); + + /* "View.MemoryView":137 + * cdef Py_ssize_t dim + * + * self.ndim = len(shape) # <<<<<<<<<<<<<< + * self.itemsize = itemsize + * + */ + if (unlikely(__pyx_v_shape == Py_None)) { + PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); + __PYX_ERR(0, 137, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_PyTuple_GET_SIZE(__pyx_v_shape); if (unlikely(__pyx_t_1 == ((Py_ssize_t)-1))) __PYX_ERR(0, 137, __pyx_L1_error) + __pyx_v_self->ndim = ((int)__pyx_t_1); + + /* "View.MemoryView":138 + * + * self.ndim = len(shape) + * self.itemsize = itemsize # <<<<<<<<<<<<<< + * + * if not self.ndim: + */ + __pyx_v_self->itemsize = __pyx_v_itemsize; + + /* "View.MemoryView":140 + * self.itemsize = itemsize + * + * if not self.ndim: # <<<<<<<<<<<<<< + * raise ValueError, "Empty shape tuple for cython.array" + * + */ + __pyx_t_2 = (!(__pyx_v_self->ndim != 0)); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":141 + * + * if not self.ndim: + * raise ValueError, "Empty shape tuple for cython.array" # <<<<<<<<<<<<<< + * + * if itemsize <= 0: + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Empty_shape_tuple_for_cython_arr, 0, 0); + __PYX_ERR(0, 141, __pyx_L1_error) + + /* "View.MemoryView":140 + * self.itemsize = itemsize + * + * if not self.ndim: # <<<<<<<<<<<<<< + * raise ValueError, "Empty shape tuple for cython.array" + * + */ + } + + /* "View.MemoryView":143 + * raise ValueError, "Empty shape tuple for cython.array" + * + * if itemsize <= 0: # <<<<<<<<<<<<<< + * raise ValueError, "itemsize <= 0 for cython.array" + * + */ + __pyx_t_2 = (__pyx_v_itemsize <= 0); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":144 + * + * if itemsize <= 0: + * raise ValueError, "itemsize <= 0 for cython.array" # <<<<<<<<<<<<<< + * + * if not isinstance(format, bytes): + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_itemsize_0_for_cython_array, 0, 0); + __PYX_ERR(0, 144, __pyx_L1_error) + + /* "View.MemoryView":143 + * raise ValueError, "Empty shape tuple for cython.array" + * + * if itemsize <= 0: # <<<<<<<<<<<<<< + * raise ValueError, "itemsize <= 0 for cython.array" + * + */ + } + + /* "View.MemoryView":146 + * raise ValueError, "itemsize <= 0 for cython.array" + * + * if not isinstance(format, bytes): # <<<<<<<<<<<<<< + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string + */ + __pyx_t_2 = PyBytes_Check(__pyx_v_format); + __pyx_t_3 = (!__pyx_t_2); + if (__pyx_t_3) { + + /* "View.MemoryView":147 + * + * if not isinstance(format, bytes): + * format = format.encode('ASCII') # <<<<<<<<<<<<<< + * self._format = format # keep a reference to the byte string + * self.format = self._format + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_format, __pyx_n_s_encode); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 147, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = NULL; + __pyx_t_7 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_6 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_6)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_6); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_7 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_6, __pyx_n_s_ASCII}; + __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_7, 1+__pyx_t_7); + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 147, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + __Pyx_DECREF_SET(__pyx_v_format, __pyx_t_4); + __pyx_t_4 = 0; + + /* "View.MemoryView":146 + * raise ValueError, "itemsize <= 0 for cython.array" + * + * if not isinstance(format, bytes): # <<<<<<<<<<<<<< + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string + */ + } + + /* "View.MemoryView":148 + * if not isinstance(format, bytes): + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string # <<<<<<<<<<<<<< + * self.format = self._format + * + */ + if (!(likely(PyBytes_CheckExact(__pyx_v_format))||((__pyx_v_format) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_v_format))) __PYX_ERR(0, 148, __pyx_L1_error) + __pyx_t_4 = __pyx_v_format; + __Pyx_INCREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + __Pyx_GOTREF(__pyx_v_self->_format); + __Pyx_DECREF(__pyx_v_self->_format); + __pyx_v_self->_format = ((PyObject*)__pyx_t_4); + __pyx_t_4 = 0; + + /* "View.MemoryView":149 + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string + * self.format = self._format # <<<<<<<<<<<<<< + * + * + */ + if (unlikely(__pyx_v_self->_format == Py_None)) { + PyErr_SetString(PyExc_TypeError, "expected bytes, NoneType found"); + __PYX_ERR(0, 149, __pyx_L1_error) + } + __pyx_t_8 = __Pyx_PyBytes_AsWritableString(__pyx_v_self->_format); if (unlikely((!__pyx_t_8) && PyErr_Occurred())) __PYX_ERR(0, 149, __pyx_L1_error) + __pyx_v_self->format = __pyx_t_8; + + /* "View.MemoryView":152 + * + * + * self._shape = PyObject_Malloc(sizeof(Py_ssize_t)*self.ndim*2) # <<<<<<<<<<<<<< + * self._strides = self._shape + self.ndim + * + */ + __pyx_v_self->_shape = ((Py_ssize_t *)PyObject_Malloc((((sizeof(Py_ssize_t)) * __pyx_v_self->ndim) * 2))); + + /* "View.MemoryView":153 + * + * self._shape = PyObject_Malloc(sizeof(Py_ssize_t)*self.ndim*2) + * self._strides = self._shape + self.ndim # <<<<<<<<<<<<<< + * + * if not self._shape: + */ + __pyx_v_self->_strides = (__pyx_v_self->_shape + __pyx_v_self->ndim); + + /* "View.MemoryView":155 + * self._strides = self._shape + self.ndim + * + * if not self._shape: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate shape and strides." + * + */ + __pyx_t_3 = (!(__pyx_v_self->_shape != 0)); + if (unlikely(__pyx_t_3)) { + + /* "View.MemoryView":156 + * + * if not self._shape: + * raise MemoryError, "unable to allocate shape and strides." # <<<<<<<<<<<<<< + * + * + */ + __Pyx_Raise(__pyx_builtin_MemoryError, __pyx_kp_s_unable_to_allocate_shape_and_str, 0, 0); + __PYX_ERR(0, 156, __pyx_L1_error) + + /* "View.MemoryView":155 + * self._strides = self._shape + self.ndim + * + * if not self._shape: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate shape and strides." + * + */ + } + + /* "View.MemoryView":159 + * + * + * for idx, dim in enumerate(shape): # <<<<<<<<<<<<<< + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + */ + __pyx_t_7 = 0; + __pyx_t_4 = __pyx_v_shape; __Pyx_INCREF(__pyx_t_4); + __pyx_t_1 = 0; + for (;;) { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_4); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 159, __pyx_L1_error) + #endif + if (__pyx_t_1 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_5 = PyTuple_GET_ITEM(__pyx_t_4, __pyx_t_1); __Pyx_INCREF(__pyx_t_5); __pyx_t_1++; if (unlikely((0 < 0))) __PYX_ERR(0, 159, __pyx_L1_error) + #else + __pyx_t_5 = __Pyx_PySequence_ITEM(__pyx_t_4, __pyx_t_1); __pyx_t_1++; if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 159, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + #endif + __pyx_t_9 = __Pyx_PyIndex_AsSsize_t(__pyx_t_5); if (unlikely((__pyx_t_9 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 159, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_v_dim = __pyx_t_9; + __pyx_v_idx = __pyx_t_7; + __pyx_t_7 = (__pyx_t_7 + 1); + + /* "View.MemoryView":160 + * + * for idx, dim in enumerate(shape): + * if dim <= 0: # <<<<<<<<<<<<<< + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + * self._shape[idx] = dim + */ + __pyx_t_3 = (__pyx_v_dim <= 0); + if (unlikely(__pyx_t_3)) { + + /* "View.MemoryView":161 + * for idx, dim in enumerate(shape): + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." # <<<<<<<<<<<<<< + * self._shape[idx] = dim + * + */ + __pyx_t_5 = PyTuple_New(5); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_9 = 0; + __pyx_t_10 = 127; + __Pyx_INCREF(__pyx_kp_u_Invalid_shape_in_axis); + __pyx_t_9 += 22; + __Pyx_GIVEREF(__pyx_kp_u_Invalid_shape_in_axis); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_kp_u_Invalid_shape_in_axis); + __pyx_t_6 = __Pyx_PyUnicode_From_int(__pyx_v_idx, 0, ' ', 'd'); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_9 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_6); + __Pyx_GIVEREF(__pyx_t_6); + PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_6); + __pyx_t_6 = 0; + __Pyx_INCREF(__pyx_kp_u_); + __pyx_t_9 += 2; + __Pyx_GIVEREF(__pyx_kp_u_); + PyTuple_SET_ITEM(__pyx_t_5, 2, __pyx_kp_u_); + __pyx_t_6 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_dim, 0, ' ', 'd'); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_9 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_6); + __Pyx_GIVEREF(__pyx_t_6); + PyTuple_SET_ITEM(__pyx_t_5, 3, __pyx_t_6); + __pyx_t_6 = 0; + __Pyx_INCREF(__pyx_kp_u__2); + __pyx_t_9 += 1; + __Pyx_GIVEREF(__pyx_kp_u__2); + PyTuple_SET_ITEM(__pyx_t_5, 4, __pyx_kp_u__2); + __pyx_t_6 = __Pyx_PyUnicode_Join(__pyx_t_5, 5, __pyx_t_9, __pyx_t_10); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_t_6, 0, 0); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __PYX_ERR(0, 161, __pyx_L1_error) + + /* "View.MemoryView":160 + * + * for idx, dim in enumerate(shape): + * if dim <= 0: # <<<<<<<<<<<<<< + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + * self._shape[idx] = dim + */ + } + + /* "View.MemoryView":162 + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + * self._shape[idx] = dim # <<<<<<<<<<<<<< + * + * cdef char order + */ + (__pyx_v_self->_shape[__pyx_v_idx]) = __pyx_v_dim; + + /* "View.MemoryView":159 + * + * + * for idx, dim in enumerate(shape): # <<<<<<<<<<<<<< + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + */ + } + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "View.MemoryView":165 + * + * cdef char order + * if mode == 'c': # <<<<<<<<<<<<<< + * order = b'C' + * self.mode = u'c' + */ + __pyx_t_3 = (__Pyx_PyString_Equals(__pyx_v_mode, __pyx_n_s_c, Py_EQ)); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(0, 165, __pyx_L1_error) + if (__pyx_t_3) { + + /* "View.MemoryView":166 + * cdef char order + * if mode == 'c': + * order = b'C' # <<<<<<<<<<<<<< + * self.mode = u'c' + * elif mode == 'fortran': + */ + __pyx_v_order = 'C'; + + /* "View.MemoryView":167 + * if mode == 'c': + * order = b'C' + * self.mode = u'c' # <<<<<<<<<<<<<< + * elif mode == 'fortran': + * order = b'F' + */ + __Pyx_INCREF(__pyx_n_u_c); + __Pyx_GIVEREF(__pyx_n_u_c); + __Pyx_GOTREF(__pyx_v_self->mode); + __Pyx_DECREF(__pyx_v_self->mode); + __pyx_v_self->mode = __pyx_n_u_c; + + /* "View.MemoryView":165 + * + * cdef char order + * if mode == 'c': # <<<<<<<<<<<<<< + * order = b'C' + * self.mode = u'c' + */ + goto __pyx_L11; + } + + /* "View.MemoryView":168 + * order = b'C' + * self.mode = u'c' + * elif mode == 'fortran': # <<<<<<<<<<<<<< + * order = b'F' + * self.mode = u'fortran' + */ + __pyx_t_3 = (__Pyx_PyString_Equals(__pyx_v_mode, __pyx_n_s_fortran, Py_EQ)); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(0, 168, __pyx_L1_error) + if (likely(__pyx_t_3)) { + + /* "View.MemoryView":169 + * self.mode = u'c' + * elif mode == 'fortran': + * order = b'F' # <<<<<<<<<<<<<< + * self.mode = u'fortran' + * else: + */ + __pyx_v_order = 'F'; + + /* "View.MemoryView":170 + * elif mode == 'fortran': + * order = b'F' + * self.mode = u'fortran' # <<<<<<<<<<<<<< + * else: + * raise ValueError, f"Invalid mode, expected 'c' or 'fortran', got {mode}" + */ + __Pyx_INCREF(__pyx_n_u_fortran); + __Pyx_GIVEREF(__pyx_n_u_fortran); + __Pyx_GOTREF(__pyx_v_self->mode); + __Pyx_DECREF(__pyx_v_self->mode); + __pyx_v_self->mode = __pyx_n_u_fortran; + + /* "View.MemoryView":168 + * order = b'C' + * self.mode = u'c' + * elif mode == 'fortran': # <<<<<<<<<<<<<< + * order = b'F' + * self.mode = u'fortran' + */ + goto __pyx_L11; + } + + /* "View.MemoryView":172 + * self.mode = u'fortran' + * else: + * raise ValueError, f"Invalid mode, expected 'c' or 'fortran', got {mode}" # <<<<<<<<<<<<<< + * + * self.len = fill_contig_strides_array(self._shape, self._strides, itemsize, self.ndim, order) + */ + /*else*/ { + __pyx_t_4 = __Pyx_PyObject_FormatSimple(__pyx_v_mode, __pyx_empty_unicode); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 172, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_6 = __Pyx_PyUnicode_Concat(__pyx_kp_u_Invalid_mode_expected_c_or_fortr, __pyx_t_4); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 172, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_t_6, 0, 0); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __PYX_ERR(0, 172, __pyx_L1_error) + } + __pyx_L11:; + + /* "View.MemoryView":174 + * raise ValueError, f"Invalid mode, expected 'c' or 'fortran', got {mode}" + * + * self.len = fill_contig_strides_array(self._shape, self._strides, itemsize, self.ndim, order) # <<<<<<<<<<<<<< + * + * self.free_data = allocate_buffer + */ + __pyx_v_self->len = __pyx_fill_contig_strides_array(__pyx_v_self->_shape, __pyx_v_self->_strides, __pyx_v_itemsize, __pyx_v_self->ndim, __pyx_v_order); + + /* "View.MemoryView":176 + * self.len = fill_contig_strides_array(self._shape, self._strides, itemsize, self.ndim, order) + * + * self.free_data = allocate_buffer # <<<<<<<<<<<<<< + * self.dtype_is_object = format == b'O' + * + */ + __pyx_v_self->free_data = __pyx_v_allocate_buffer; + + /* "View.MemoryView":177 + * + * self.free_data = allocate_buffer + * self.dtype_is_object = format == b'O' # <<<<<<<<<<<<<< + * + * if allocate_buffer: + */ + __pyx_t_6 = PyObject_RichCompare(__pyx_v_format, __pyx_n_b_O, Py_EQ); __Pyx_XGOTREF(__pyx_t_6); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 177, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_IsTrue(__pyx_t_6); if (unlikely((__pyx_t_3 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 177, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __pyx_v_self->dtype_is_object = __pyx_t_3; + + /* "View.MemoryView":179 + * self.dtype_is_object = format == b'O' + * + * if allocate_buffer: # <<<<<<<<<<<<<< + * _allocate_buffer(self) + * + */ + if (__pyx_v_allocate_buffer) { + + /* "View.MemoryView":180 + * + * if allocate_buffer: + * _allocate_buffer(self) # <<<<<<<<<<<<<< + * + * @cname('getbuffer') + */ + __pyx_t_7 = __pyx_array_allocate_buffer(__pyx_v_self); if (unlikely(__pyx_t_7 == ((int)-1))) __PYX_ERR(0, 180, __pyx_L1_error) + + /* "View.MemoryView":179 + * self.dtype_is_object = format == b'O' + * + * if allocate_buffer: # <<<<<<<<<<<<<< + * _allocate_buffer(self) + * + */ + } + + /* "View.MemoryView":131 + * cdef bint dtype_is_object + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, # <<<<<<<<<<<<<< + * mode="c", bint allocate_buffer=True): + * + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("View.MemoryView.array.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_format); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":182 + * _allocate_buffer(self) + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + */ + +/* Python wrapper */ +CYTHON_UNUSED static int __pyx_array_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +CYTHON_UNUSED static int __pyx_array_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getbuffer__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_2__getbuffer__(((struct __pyx_array_obj *)__pyx_v_self), ((Py_buffer *)__pyx_v_info), ((int)__pyx_v_flags)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_2__getbuffer__(struct __pyx_array_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + int __pyx_v_bufmode; + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + char *__pyx_t_2; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + Py_ssize_t *__pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + if (unlikely(__pyx_v_info == NULL)) { + PyErr_SetString(PyExc_BufferError, "PyObject_GetBuffer: view==NULL argument is obsolete"); + return -1; + } + __Pyx_RefNannySetupContext("__getbuffer__", 0); + __pyx_v_info->obj = Py_None; __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(__pyx_v_info->obj); + + /* "View.MemoryView":184 + * @cname('getbuffer') + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 # <<<<<<<<<<<<<< + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": + */ + __pyx_v_bufmode = -1; + + /* "View.MemoryView":185 + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): # <<<<<<<<<<<<<< + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + */ + __pyx_t_1 = ((__pyx_v_flags & ((PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS) | PyBUF_ANY_CONTIGUOUS)) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":186 + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": # <<<<<<<<<<<<<< + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": + */ + __pyx_t_1 = (__Pyx_PyUnicode_Equals(__pyx_v_self->mode, __pyx_n_u_c, Py_EQ)); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(0, 186, __pyx_L1_error) + if (__pyx_t_1) { + + /* "View.MemoryView":187 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS # <<<<<<<<<<<<<< + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + */ + __pyx_v_bufmode = (PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS); + + /* "View.MemoryView":186 + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": # <<<<<<<<<<<<<< + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": + */ + goto __pyx_L4; + } + + /* "View.MemoryView":188 + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": # <<<<<<<<<<<<<< + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): + */ + __pyx_t_1 = (__Pyx_PyUnicode_Equals(__pyx_v_self->mode, __pyx_n_u_fortran, Py_EQ)); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(0, 188, __pyx_L1_error) + if (__pyx_t_1) { + + /* "View.MemoryView":189 + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS # <<<<<<<<<<<<<< + * if not (flags & bufmode): + * raise ValueError, "Can only create a buffer that is contiguous in memory." + */ + __pyx_v_bufmode = (PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS); + + /* "View.MemoryView":188 + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": # <<<<<<<<<<<<<< + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): + */ + } + __pyx_L4:; + + /* "View.MemoryView":190 + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): # <<<<<<<<<<<<<< + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data + */ + __pyx_t_1 = (!((__pyx_v_flags & __pyx_v_bufmode) != 0)); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":191 + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): + * raise ValueError, "Can only create a buffer that is contiguous in memory." # <<<<<<<<<<<<<< + * info.buf = self.data + * info.len = self.len + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Can_only_create_a_buffer_that_is, 0, 0); + __PYX_ERR(0, 191, __pyx_L1_error) + + /* "View.MemoryView":190 + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): # <<<<<<<<<<<<<< + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data + */ + } + + /* "View.MemoryView":185 + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): # <<<<<<<<<<<<<< + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + */ + } + + /* "View.MemoryView":192 + * if not (flags & bufmode): + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data # <<<<<<<<<<<<<< + * info.len = self.len + * + */ + __pyx_t_2 = __pyx_v_self->data; + __pyx_v_info->buf = __pyx_t_2; + + /* "View.MemoryView":193 + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data + * info.len = self.len # <<<<<<<<<<<<<< + * + * if flags & PyBUF_STRIDES: + */ + __pyx_t_3 = __pyx_v_self->len; + __pyx_v_info->len = __pyx_t_3; + + /* "View.MemoryView":195 + * info.len = self.len + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.ndim = self.ndim + * info.shape = self._shape + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_STRIDES) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":196 + * + * if flags & PyBUF_STRIDES: + * info.ndim = self.ndim # <<<<<<<<<<<<<< + * info.shape = self._shape + * info.strides = self._strides + */ + __pyx_t_4 = __pyx_v_self->ndim; + __pyx_v_info->ndim = __pyx_t_4; + + /* "View.MemoryView":197 + * if flags & PyBUF_STRIDES: + * info.ndim = self.ndim + * info.shape = self._shape # <<<<<<<<<<<<<< + * info.strides = self._strides + * else: + */ + __pyx_t_5 = __pyx_v_self->_shape; + __pyx_v_info->shape = __pyx_t_5; + + /* "View.MemoryView":198 + * info.ndim = self.ndim + * info.shape = self._shape + * info.strides = self._strides # <<<<<<<<<<<<<< + * else: + * info.ndim = 1 + */ + __pyx_t_5 = __pyx_v_self->_strides; + __pyx_v_info->strides = __pyx_t_5; + + /* "View.MemoryView":195 + * info.len = self.len + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.ndim = self.ndim + * info.shape = self._shape + */ + goto __pyx_L6; + } + + /* "View.MemoryView":200 + * info.strides = self._strides + * else: + * info.ndim = 1 # <<<<<<<<<<<<<< + * info.shape = &self.len if flags & PyBUF_ND else NULL + * info.strides = NULL + */ + /*else*/ { + __pyx_v_info->ndim = 1; + + /* "View.MemoryView":201 + * else: + * info.ndim = 1 + * info.shape = &self.len if flags & PyBUF_ND else NULL # <<<<<<<<<<<<<< + * info.strides = NULL + * + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_ND) != 0); + if (__pyx_t_1) { + __pyx_t_5 = (&__pyx_v_self->len); + } else { + __pyx_t_5 = NULL; + } + __pyx_v_info->shape = __pyx_t_5; + + /* "View.MemoryView":202 + * info.ndim = 1 + * info.shape = &self.len if flags & PyBUF_ND else NULL + * info.strides = NULL # <<<<<<<<<<<<<< + * + * info.suboffsets = NULL + */ + __pyx_v_info->strides = NULL; + } + __pyx_L6:; + + /* "View.MemoryView":204 + * info.strides = NULL + * + * info.suboffsets = NULL # <<<<<<<<<<<<<< + * info.itemsize = self.itemsize + * info.readonly = 0 + */ + __pyx_v_info->suboffsets = NULL; + + /* "View.MemoryView":205 + * + * info.suboffsets = NULL + * info.itemsize = self.itemsize # <<<<<<<<<<<<<< + * info.readonly = 0 + * info.format = self.format if flags & PyBUF_FORMAT else NULL + */ + __pyx_t_3 = __pyx_v_self->itemsize; + __pyx_v_info->itemsize = __pyx_t_3; + + /* "View.MemoryView":206 + * info.suboffsets = NULL + * info.itemsize = self.itemsize + * info.readonly = 0 # <<<<<<<<<<<<<< + * info.format = self.format if flags & PyBUF_FORMAT else NULL + * info.obj = self + */ + __pyx_v_info->readonly = 0; + + /* "View.MemoryView":207 + * info.itemsize = self.itemsize + * info.readonly = 0 + * info.format = self.format if flags & PyBUF_FORMAT else NULL # <<<<<<<<<<<<<< + * info.obj = self + * + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_FORMAT) != 0); + if (__pyx_t_1) { + __pyx_t_2 = __pyx_v_self->format; + } else { + __pyx_t_2 = NULL; + } + __pyx_v_info->format = __pyx_t_2; + + /* "View.MemoryView":208 + * info.readonly = 0 + * info.format = self.format if flags & PyBUF_FORMAT else NULL + * info.obj = self # <<<<<<<<<<<<<< + * + * def __dealloc__(array self): + */ + __Pyx_INCREF((PyObject *)__pyx_v_self); + __Pyx_GIVEREF((PyObject *)__pyx_v_self); + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); + __pyx_v_info->obj = ((PyObject *)__pyx_v_self); + + /* "View.MemoryView":182 + * _allocate_buffer(self) + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.array.__getbuffer__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + if (__pyx_v_info->obj != NULL) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + goto __pyx_L2; + __pyx_L0:; + if (__pyx_v_info->obj == Py_None) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + __pyx_L2:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":210 + * info.obj = self + * + * def __dealloc__(array self): # <<<<<<<<<<<<<< + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + */ + +/* Python wrapper */ +static void __pyx_array___dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_array___dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_array___pyx_pf_15View_dot_MemoryView_5array_4__dealloc__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_array___pyx_pf_15View_dot_MemoryView_5array_4__dealloc__(struct __pyx_array_obj *__pyx_v_self) { + int __pyx_t_1; + int __pyx_t_2; + + /* "View.MemoryView":211 + * + * def __dealloc__(array self): + * if self.callback_free_data != NULL: # <<<<<<<<<<<<<< + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + */ + __pyx_t_1 = (__pyx_v_self->callback_free_data != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":212 + * def __dealloc__(array self): + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) # <<<<<<<<<<<<<< + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: + */ + __pyx_v_self->callback_free_data(__pyx_v_self->data); + + /* "View.MemoryView":211 + * + * def __dealloc__(array self): + * if self.callback_free_data != NULL: # <<<<<<<<<<<<<< + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":213 + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: # <<<<<<<<<<<<<< + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + */ + if (__pyx_v_self->free_data) { + } else { + __pyx_t_1 = __pyx_v_self->free_data; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_2 = (__pyx_v_self->data != NULL); + __pyx_t_1 = __pyx_t_2; + __pyx_L4_bool_binop_done:; + if (__pyx_t_1) { + + /* "View.MemoryView":214 + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) + */ + if (__pyx_v_self->dtype_is_object) { + + /* "View.MemoryView":215 + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) # <<<<<<<<<<<<<< + * free(self.data) + * PyObject_Free(self._shape) + */ + __pyx_memoryview_refcount_objects_in_slice(__pyx_v_self->data, __pyx_v_self->_shape, __pyx_v_self->_strides, __pyx_v_self->ndim, 0); + + /* "View.MemoryView":214 + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) + */ + } + + /* "View.MemoryView":216 + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) # <<<<<<<<<<<<<< + * PyObject_Free(self._shape) + * + */ + free(__pyx_v_self->data); + + /* "View.MemoryView":213 + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: # <<<<<<<<<<<<<< + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + */ + } + __pyx_L3:; + + /* "View.MemoryView":217 + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) + * PyObject_Free(self._shape) # <<<<<<<<<<<<<< + * + * @property + */ + PyObject_Free(__pyx_v_self->_shape); + + /* "View.MemoryView":210 + * info.obj = self + * + * def __dealloc__(array self): # <<<<<<<<<<<<<< + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + */ + + /* function exit code */ +} + +/* "View.MemoryView":219 + * PyObject_Free(self._shape) + * + * @property # <<<<<<<<<<<<<< + * def memview(self): + * return self.get_memview() + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_5array_7memview_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_5array_7memview_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_5array_7memview___get__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_5array_7memview___get__(struct __pyx_array_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":221 + * @property + * def memview(self): + * return self.get_memview() # <<<<<<<<<<<<<< + * + * @cname('get_memview') + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = ((struct __pyx_vtabstruct_array *)__pyx_v_self->__pyx_vtab)->get_memview(__pyx_v_self); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 221, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":219 + * PyObject_Free(self._shape) + * + * @property # <<<<<<<<<<<<<< + * def memview(self): + * return self.get_memview() + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.array.memview.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":224 + * + * @cname('get_memview') + * cdef get_memview(self): # <<<<<<<<<<<<<< + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE + * return memoryview(self, flags, self.dtype_is_object) + */ + +static PyObject *__pyx_array_get_memview(struct __pyx_array_obj *__pyx_v_self) { + int __pyx_v_flags; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_memview", 1); + + /* "View.MemoryView":225 + * @cname('get_memview') + * cdef get_memview(self): + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE # <<<<<<<<<<<<<< + * return memoryview(self, flags, self.dtype_is_object) + * + */ + __pyx_v_flags = ((PyBUF_ANY_CONTIGUOUS | PyBUF_FORMAT) | PyBUF_WRITABLE); + + /* "View.MemoryView":226 + * cdef get_memview(self): + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE + * return memoryview(self, flags, self.dtype_is_object) # <<<<<<<<<<<<<< + * + * def __len__(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_flags); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_v_self->dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF((PyObject *)__pyx_v_self); + __Pyx_GIVEREF((PyObject *)__pyx_v_self); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, ((PyObject *)__pyx_v_self))) __PYX_ERR(0, 226, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1)) __PYX_ERR(0, 226, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_t_2)) __PYX_ERR(0, 226, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_Call(((PyObject *)__pyx_memoryview_type), __pyx_t_3, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":224 + * + * @cname('get_memview') + * cdef get_memview(self): # <<<<<<<<<<<<<< + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE + * return memoryview(self, flags, self.dtype_is_object) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.array.get_memview", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":228 + * return memoryview(self, flags, self.dtype_is_object) + * + * def __len__(self): # <<<<<<<<<<<<<< + * return self._shape[0] + * + */ + +/* Python wrapper */ +static Py_ssize_t __pyx_array___len__(PyObject *__pyx_v_self); /*proto*/ +static Py_ssize_t __pyx_array___len__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + Py_ssize_t __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__len__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_6__len__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static Py_ssize_t __pyx_array___pyx_pf_15View_dot_MemoryView_5array_6__len__(struct __pyx_array_obj *__pyx_v_self) { + Py_ssize_t __pyx_r; + + /* "View.MemoryView":229 + * + * def __len__(self): + * return self._shape[0] # <<<<<<<<<<<<<< + * + * def __getattr__(self, attr): + */ + __pyx_r = (__pyx_v_self->_shape[0]); + goto __pyx_L0; + + /* "View.MemoryView":228 + * return memoryview(self, flags, self.dtype_is_object) + * + * def __len__(self): # <<<<<<<<<<<<<< + * return self._shape[0] + * + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":231 + * return self._shape[0] + * + * def __getattr__(self, attr): # <<<<<<<<<<<<<< + * return getattr(self.memview, attr) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_array___getattr__(PyObject *__pyx_v_self, PyObject *__pyx_v_attr); /*proto*/ +static PyObject *__pyx_array___getattr__(PyObject *__pyx_v_self, PyObject *__pyx_v_attr) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getattr__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_8__getattr__(((struct __pyx_array_obj *)__pyx_v_self), ((PyObject *)__pyx_v_attr)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_8__getattr__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_attr) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__getattr__", 1); + + /* "View.MemoryView":232 + * + * def __getattr__(self, attr): + * return getattr(self.memview, attr) # <<<<<<<<<<<<<< + * + * def __getitem__(self, item): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_memview); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 232, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_GetAttr(__pyx_t_1, __pyx_v_attr); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 232, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":231 + * return self._shape[0] + * + * def __getattr__(self, attr): # <<<<<<<<<<<<<< + * return getattr(self.memview, attr) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.array.__getattr__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":234 + * return getattr(self.memview, attr) + * + * def __getitem__(self, item): # <<<<<<<<<<<<<< + * return self.memview[item] + * + */ + +/* Python wrapper */ +static PyObject *__pyx_array___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item); /*proto*/ +static PyObject *__pyx_array___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getitem__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_10__getitem__(((struct __pyx_array_obj *)__pyx_v_self), ((PyObject *)__pyx_v_item)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_10__getitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__getitem__", 1); + + /* "View.MemoryView":235 + * + * def __getitem__(self, item): + * return self.memview[item] # <<<<<<<<<<<<<< + * + * def __setitem__(self, item, value): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_memview); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 235, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_t_1, __pyx_v_item); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 235, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":234 + * return getattr(self.memview, attr) + * + * def __getitem__(self, item): # <<<<<<<<<<<<<< + * return self.memview[item] + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.array.__getitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":237 + * return self.memview[item] + * + * def __setitem__(self, item, value): # <<<<<<<<<<<<<< + * self.memview[item] = value + * + */ + +/* Python wrapper */ +static int __pyx_array___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value); /*proto*/ +static int __pyx_array___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setitem__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_12__setitem__(((struct __pyx_array_obj *)__pyx_v_self), ((PyObject *)__pyx_v_item), ((PyObject *)__pyx_v_value)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_12__setitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setitem__", 1); + + /* "View.MemoryView":238 + * + * def __setitem__(self, item, value): + * self.memview[item] = value # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_memview); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 238, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyObject_SetItem(__pyx_t_1, __pyx_v_item, __pyx_v_value) < 0))) __PYX_ERR(0, 238, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "View.MemoryView":237 + * return self.memview[item] + * + * def __setitem__(self, item, value): # <<<<<<<<<<<<<< + * self.memview[item] = value + * + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.array.__setitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_array_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_array_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_array___reduce_cython__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_array___reduce_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(0, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.array.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_array_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_array_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(0, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.array.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_array_2__setstate_cython__(((struct __pyx_array_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_array_2__setstate_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(0, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.array.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":248 + * + * @cname("__pyx_array_allocate_buffer") + * cdef int _allocate_buffer(array self) except -1: # <<<<<<<<<<<<<< + * + * + */ + +static int __pyx_array_allocate_buffer(struct __pyx_array_obj *__pyx_v_self) { + Py_ssize_t __pyx_v_i; + PyObject **__pyx_v_p; + int __pyx_r; + int __pyx_t_1; + Py_ssize_t __pyx_t_2; + Py_ssize_t __pyx_t_3; + Py_ssize_t __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + + /* "View.MemoryView":254 + * cdef PyObject **p + * + * self.free_data = True # <<<<<<<<<<<<<< + * self.data = malloc(self.len) + * if not self.data: + */ + __pyx_v_self->free_data = 1; + + /* "View.MemoryView":255 + * + * self.free_data = True + * self.data = malloc(self.len) # <<<<<<<<<<<<<< + * if not self.data: + * raise MemoryError, "unable to allocate array data." + */ + __pyx_v_self->data = ((char *)malloc(__pyx_v_self->len)); + + /* "View.MemoryView":256 + * self.free_data = True + * self.data = malloc(self.len) + * if not self.data: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate array data." + * + */ + __pyx_t_1 = (!(__pyx_v_self->data != 0)); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":257 + * self.data = malloc(self.len) + * if not self.data: + * raise MemoryError, "unable to allocate array data." # <<<<<<<<<<<<<< + * + * if self.dtype_is_object: + */ + __Pyx_Raise(__pyx_builtin_MemoryError, __pyx_kp_s_unable_to_allocate_array_data, 0, 0); + __PYX_ERR(0, 257, __pyx_L1_error) + + /* "View.MemoryView":256 + * self.free_data = True + * self.data = malloc(self.len) + * if not self.data: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate array data." + * + */ + } + + /* "View.MemoryView":259 + * raise MemoryError, "unable to allocate array data." + * + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * p = self.data + * for i in range(self.len // self.itemsize): + */ + if (__pyx_v_self->dtype_is_object) { + + /* "View.MemoryView":260 + * + * if self.dtype_is_object: + * p = self.data # <<<<<<<<<<<<<< + * for i in range(self.len // self.itemsize): + * p[i] = Py_None + */ + __pyx_v_p = ((PyObject **)__pyx_v_self->data); + + /* "View.MemoryView":261 + * if self.dtype_is_object: + * p = self.data + * for i in range(self.len // self.itemsize): # <<<<<<<<<<<<<< + * p[i] = Py_None + * Py_INCREF(Py_None) + */ + if (unlikely(__pyx_v_self->itemsize == 0)) { + PyErr_SetString(PyExc_ZeroDivisionError, "integer division or modulo by zero"); + __PYX_ERR(0, 261, __pyx_L1_error) + } + else if (sizeof(Py_ssize_t) == sizeof(long) && (!(((Py_ssize_t)-1) > 0)) && unlikely(__pyx_v_self->itemsize == (Py_ssize_t)-1) && unlikely(__Pyx_UNARY_NEG_WOULD_OVERFLOW(__pyx_v_self->len))) { + PyErr_SetString(PyExc_OverflowError, "value too large to perform division"); + __PYX_ERR(0, 261, __pyx_L1_error) + } + __pyx_t_2 = __Pyx_div_Py_ssize_t(__pyx_v_self->len, __pyx_v_self->itemsize); + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":262 + * p = self.data + * for i in range(self.len // self.itemsize): + * p[i] = Py_None # <<<<<<<<<<<<<< + * Py_INCREF(Py_None) + * return 0 + */ + (__pyx_v_p[__pyx_v_i]) = Py_None; + + /* "View.MemoryView":263 + * for i in range(self.len // self.itemsize): + * p[i] = Py_None + * Py_INCREF(Py_None) # <<<<<<<<<<<<<< + * return 0 + * + */ + Py_INCREF(Py_None); + } + + /* "View.MemoryView":259 + * raise MemoryError, "unable to allocate array data." + * + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * p = self.data + * for i in range(self.len // self.itemsize): + */ + } + + /* "View.MemoryView":264 + * p[i] = Py_None + * Py_INCREF(Py_None) + * return 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":248 + * + * @cname("__pyx_array_allocate_buffer") + * cdef int _allocate_buffer(array self) except -1: # <<<<<<<<<<<<<< + * + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._allocate_buffer", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":268 + * + * @cname("__pyx_array_new") + * cdef array array_cwrapper(tuple shape, Py_ssize_t itemsize, char *format, char *c_mode, char *buf): # <<<<<<<<<<<<<< + * cdef array result + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + */ + +static struct __pyx_array_obj *__pyx_array_new(PyObject *__pyx_v_shape, Py_ssize_t __pyx_v_itemsize, char *__pyx_v_format, char *__pyx_v_c_mode, char *__pyx_v_buf) { + struct __pyx_array_obj *__pyx_v_result = 0; + PyObject *__pyx_v_mode = 0; + struct __pyx_array_obj *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("array_cwrapper", 1); + + /* "View.MemoryView":270 + * cdef array array_cwrapper(tuple shape, Py_ssize_t itemsize, char *format, char *c_mode, char *buf): + * cdef array result + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. # <<<<<<<<<<<<<< + * + * if buf is NULL: + */ + __pyx_t_2 = ((__pyx_v_c_mode[0]) == 'f'); + if (__pyx_t_2) { + __Pyx_INCREF(__pyx_n_s_fortran); + __pyx_t_1 = __pyx_n_s_fortran; + } else { + __Pyx_INCREF(__pyx_n_s_c); + __pyx_t_1 = __pyx_n_s_c; + } + __pyx_v_mode = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":272 + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + * + * if buf is NULL: # <<<<<<<<<<<<<< + * result = array.__new__(array, shape, itemsize, format, mode) + * else: + */ + __pyx_t_2 = (__pyx_v_buf == NULL); + if (__pyx_t_2) { + + /* "View.MemoryView":273 + * + * if buf is NULL: + * result = array.__new__(array, shape, itemsize, format, mode) # <<<<<<<<<<<<<< + * else: + * result = array.__new__(array, shape, itemsize, format, mode, allocate_buffer=False) + */ + __pyx_t_1 = PyInt_FromSsize_t(__pyx_v_itemsize); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 273, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyBytes_FromString(__pyx_v_format); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 273, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PyTuple_New(4); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 273, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_INCREF(__pyx_v_shape); + __Pyx_GIVEREF(__pyx_v_shape); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_v_shape)) __PYX_ERR(0, 273, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_t_1)) __PYX_ERR(0, 273, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 2, __pyx_t_3)) __PYX_ERR(0, 273, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_mode); + __Pyx_GIVEREF(__pyx_v_mode); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 3, __pyx_v_mode)) __PYX_ERR(0, 273, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_3 = 0; + __pyx_t_3 = ((PyObject *)__pyx_tp_new_array(((PyTypeObject *)__pyx_array_type), __pyx_t_4, NULL)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 273, __pyx_L1_error) + __Pyx_GOTREF((PyObject *)__pyx_t_3); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_v_result = ((struct __pyx_array_obj *)__pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":272 + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + * + * if buf is NULL: # <<<<<<<<<<<<<< + * result = array.__new__(array, shape, itemsize, format, mode) + * else: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":275 + * result = array.__new__(array, shape, itemsize, format, mode) + * else: + * result = array.__new__(array, shape, itemsize, format, mode, allocate_buffer=False) # <<<<<<<<<<<<<< + * result.data = buf + * + */ + /*else*/ { + __pyx_t_3 = PyInt_FromSsize_t(__pyx_v_itemsize); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = __Pyx_PyBytes_FromString(__pyx_v_format); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_1 = PyTuple_New(4); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v_shape); + __Pyx_GIVEREF(__pyx_v_shape); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v_shape)) __PYX_ERR(0, 275, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_t_3)) __PYX_ERR(0, 275, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_4); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_t_4)) __PYX_ERR(0, 275, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_mode); + __Pyx_GIVEREF(__pyx_v_mode); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 3, __pyx_v_mode)) __PYX_ERR(0, 275, __pyx_L1_error); + __pyx_t_3 = 0; + __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem(__pyx_t_4, __pyx_n_s_allocate_buffer, Py_False) < 0) __PYX_ERR(0, 275, __pyx_L1_error) + __pyx_t_3 = ((PyObject *)__pyx_tp_new_array(((PyTypeObject *)__pyx_array_type), __pyx_t_1, __pyx_t_4)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 275, __pyx_L1_error) + __Pyx_GOTREF((PyObject *)__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_v_result = ((struct __pyx_array_obj *)__pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":276 + * else: + * result = array.__new__(array, shape, itemsize, format, mode, allocate_buffer=False) + * result.data = buf # <<<<<<<<<<<<<< + * + * return result + */ + __pyx_v_result->data = __pyx_v_buf; + } + __pyx_L3:; + + /* "View.MemoryView":278 + * result.data = buf + * + * return result # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF((PyObject *)__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = __pyx_v_result; + goto __pyx_L0; + + /* "View.MemoryView":268 + * + * @cname("__pyx_array_new") + * cdef array array_cwrapper(tuple shape, Py_ssize_t itemsize, char *format, char *c_mode, char *buf): # <<<<<<<<<<<<<< + * cdef array result + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.array_cwrapper", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XDECREF(__pyx_v_mode); + __Pyx_XGIVEREF((PyObject *)__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":304 + * cdef class Enum(object): + * cdef object name + * def __init__(self, name): # <<<<<<<<<<<<<< + * self.name = name + * def __repr__(self): + */ + +/* Python wrapper */ +static int __pyx_MemviewEnum___init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_MemviewEnum___init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_name = 0; + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__init__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_name,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_name)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 304, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__init__") < 0)) __PYX_ERR(0, 304, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + } + __pyx_v_name = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__init__", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 304, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.Enum.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum___init__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self), __pyx_v_name); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum___init__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v_name) { + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__init__", 1); + + /* "View.MemoryView":305 + * cdef object name + * def __init__(self, name): + * self.name = name # <<<<<<<<<<<<<< + * def __repr__(self): + * return self.name + */ + __Pyx_INCREF(__pyx_v_name); + __Pyx_GIVEREF(__pyx_v_name); + __Pyx_GOTREF(__pyx_v_self->name); + __Pyx_DECREF(__pyx_v_self->name); + __pyx_v_self->name = __pyx_v_name; + + /* "View.MemoryView":304 + * cdef class Enum(object): + * cdef object name + * def __init__(self, name): # <<<<<<<<<<<<<< + * self.name = name + * def __repr__(self): + */ + + /* function exit code */ + __pyx_r = 0; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":306 + * def __init__(self, name): + * self.name = name + * def __repr__(self): # <<<<<<<<<<<<<< + * return self.name + * + */ + +/* Python wrapper */ +static PyObject *__pyx_MemviewEnum___repr__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_MemviewEnum___repr__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__repr__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum_2__repr__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum_2__repr__(struct __pyx_MemviewEnum_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__repr__", 1); + + /* "View.MemoryView":307 + * self.name = name + * def __repr__(self): + * return self.name # <<<<<<<<<<<<<< + * + * cdef generic = Enum("") + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->name); + __pyx_r = __pyx_v_self->name; + goto __pyx_L0; + + /* "View.MemoryView":306 + * def __init__(self, name): + * self.name = name + * def __repr__(self): # <<<<<<<<<<<<<< + * return self.name + * + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * cdef tuple state + * cdef object _dict + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_MemviewEnum_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_MemviewEnum_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_MemviewEnum___reduce_cython__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_MemviewEnum___reduce_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self) { + PyObject *__pyx_v_state = 0; + PyObject *__pyx_v__dict = 0; + int __pyx_v_use_setstate; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":5 + * cdef object _dict + * cdef bint use_setstate + * state = (self.name,) # <<<<<<<<<<<<<< + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: + */ + __pyx_t_1 = PyTuple_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v_self->name); + __Pyx_GIVEREF(__pyx_v_self->name); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v_self->name)) __PYX_ERR(0, 5, __pyx_L1_error); + __pyx_v_state = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "(tree fragment)":6 + * cdef bint use_setstate + * state = (self.name,) + * _dict = getattr(self, '__dict__', None) # <<<<<<<<<<<<<< + * if _dict is not None: + * state += (_dict,) + */ + __pyx_t_1 = __Pyx_GetAttr3(((PyObject *)__pyx_v_self), __pyx_n_s_dict, Py_None); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v__dict = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":7 + * state = (self.name,) + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: # <<<<<<<<<<<<<< + * state += (_dict,) + * use_setstate = True + */ + __pyx_t_2 = (__pyx_v__dict != Py_None); + if (__pyx_t_2) { + + /* "(tree fragment)":8 + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: + * state += (_dict,) # <<<<<<<<<<<<<< + * use_setstate = True + * else: + */ + __pyx_t_1 = PyTuple_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 8, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v__dict); + __Pyx_GIVEREF(__pyx_v__dict); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v__dict)) __PYX_ERR(0, 8, __pyx_L1_error); + __pyx_t_3 = PyNumber_InPlaceAdd(__pyx_v_state, __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 8, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF_SET(__pyx_v_state, ((PyObject*)__pyx_t_3)); + __pyx_t_3 = 0; + + /* "(tree fragment)":9 + * if _dict is not None: + * state += (_dict,) + * use_setstate = True # <<<<<<<<<<<<<< + * else: + * use_setstate = self.name is not None + */ + __pyx_v_use_setstate = 1; + + /* "(tree fragment)":7 + * state = (self.name,) + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: # <<<<<<<<<<<<<< + * state += (_dict,) + * use_setstate = True + */ + goto __pyx_L3; + } + + /* "(tree fragment)":11 + * use_setstate = True + * else: + * use_setstate = self.name is not None # <<<<<<<<<<<<<< + * if use_setstate: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + */ + /*else*/ { + __pyx_t_2 = (__pyx_v_self->name != Py_None); + __pyx_v_use_setstate = __pyx_t_2; + } + __pyx_L3:; + + /* "(tree fragment)":12 + * else: + * use_setstate = self.name is not None + * if use_setstate: # <<<<<<<<<<<<<< + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + * else: + */ + if (__pyx_v_use_setstate) { + + /* "(tree fragment)":13 + * use_setstate = self.name is not None + * if use_setstate: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state # <<<<<<<<<<<<<< + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_pyx_unpickle_Enum); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = PyTuple_New(3); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_GIVEREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, ((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self))))) __PYX_ERR(0, 13, __pyx_L1_error); + __Pyx_INCREF(__pyx_int_136983863); + __Pyx_GIVEREF(__pyx_int_136983863); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_int_136983863)) __PYX_ERR(0, 13, __pyx_L1_error); + __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(Py_None); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 2, Py_None)) __PYX_ERR(0, 13, __pyx_L1_error); + __pyx_t_4 = PyTuple_New(3); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_3)) __PYX_ERR(0, 13, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_t_1)) __PYX_ERR(0, 13, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_state); + __Pyx_GIVEREF(__pyx_v_state); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 2, __pyx_v_state)) __PYX_ERR(0, 13, __pyx_L1_error); + __pyx_t_3 = 0; + __pyx_t_1 = 0; + __pyx_r = __pyx_t_4; + __pyx_t_4 = 0; + goto __pyx_L0; + + /* "(tree fragment)":12 + * else: + * use_setstate = self.name is not None + * if use_setstate: # <<<<<<<<<<<<<< + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + * else: + */ + } + + /* "(tree fragment)":15 + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * __pyx_unpickle_Enum__set_state(self, __pyx_state) + */ + /*else*/ { + __Pyx_XDECREF(__pyx_r); + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_pyx_unpickle_Enum); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_1 = PyTuple_New(3); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_GIVEREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, ((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self))))) __PYX_ERR(0, 15, __pyx_L1_error); + __Pyx_INCREF(__pyx_int_136983863); + __Pyx_GIVEREF(__pyx_int_136983863); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_int_136983863)) __PYX_ERR(0, 15, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_state); + __Pyx_GIVEREF(__pyx_v_state); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_v_state)) __PYX_ERR(0, 15, __pyx_L1_error); + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_4); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_4)) __PYX_ERR(0, 15, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1)) __PYX_ERR(0, 15, __pyx_L1_error); + __pyx_t_4 = 0; + __pyx_t_1 = 0; + __pyx_r = __pyx_t_3; + __pyx_t_3 = 0; + goto __pyx_L0; + } + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * cdef tuple state + * cdef object _dict + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.Enum.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_state); + __Pyx_XDECREF(__pyx_v__dict); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":16 + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state(self, __pyx_state) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_MemviewEnum_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_MemviewEnum_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 16, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(0, 16, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 16, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.Enum.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_MemviewEnum_2__setstate_cython__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_MemviewEnum_2__setstate_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":17 + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + * def __setstate_cython__(self, __pyx_state): + * __pyx_unpickle_Enum__set_state(self, __pyx_state) # <<<<<<<<<<<<<< + */ + if (!(likely(PyTuple_CheckExact(__pyx_v___pyx_state))||((__pyx_v___pyx_state) == Py_None) || __Pyx_RaiseUnexpectedTypeError("tuple", __pyx_v___pyx_state))) __PYX_ERR(0, 17, __pyx_L1_error) + __pyx_t_1 = __pyx_unpickle_Enum__set_state(__pyx_v_self, ((PyObject*)__pyx_v___pyx_state)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 17, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":16 + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state(self, __pyx_state) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.Enum.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":349 + * cdef __Pyx_TypeInfo *typeinfo + * + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): # <<<<<<<<<<<<<< + * self.obj = obj + * self.flags = flags + */ + +/* Python wrapper */ +static int __pyx_memoryview___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_memoryview___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_obj = 0; + int __pyx_v_flags; + int __pyx_v_dtype_is_object; + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_obj,&__pyx_n_s_flags,&__pyx_n_s_dtype_is_object,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_obj)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 349, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_flags)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 349, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 2, 3, 1); __PYX_ERR(0, 349, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_dtype_is_object); + if (value) { values[2] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 349, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(0, 349, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_obj = values[0]; + __pyx_v_flags = __Pyx_PyInt_As_int(values[1]); if (unlikely((__pyx_v_flags == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 349, __pyx_L3_error) + if (values[2]) { + __pyx_v_dtype_is_object = __Pyx_PyObject_IsTrue(values[2]); if (unlikely((__pyx_v_dtype_is_object == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 349, __pyx_L3_error) + } else { + __pyx_v_dtype_is_object = ((int)0); + } + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 2, 3, __pyx_nargs); __PYX_ERR(0, 349, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.memoryview.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview___cinit__(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v_obj, __pyx_v_flags, __pyx_v_dtype_is_object); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview___cinit__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj, int __pyx_v_flags, int __pyx_v_dtype_is_object) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + Py_intptr_t __pyx_t_4; + size_t __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__cinit__", 1); + + /* "View.MemoryView":350 + * + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): + * self.obj = obj # <<<<<<<<<<<<<< + * self.flags = flags + * if type(self) is memoryview or obj is not None: + */ + __Pyx_INCREF(__pyx_v_obj); + __Pyx_GIVEREF(__pyx_v_obj); + __Pyx_GOTREF(__pyx_v_self->obj); + __Pyx_DECREF(__pyx_v_self->obj); + __pyx_v_self->obj = __pyx_v_obj; + + /* "View.MemoryView":351 + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): + * self.obj = obj + * self.flags = flags # <<<<<<<<<<<<<< + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) + */ + __pyx_v_self->flags = __pyx_v_flags; + + /* "View.MemoryView":352 + * self.obj = obj + * self.flags = flags + * if type(self) is memoryview or obj is not None: # <<<<<<<<<<<<<< + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: + */ + __pyx_t_2 = (((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self))) == ((PyObject *)__pyx_memoryview_type)); + if (!__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_2 = (__pyx_v_obj != Py_None); + __pyx_t_1 = __pyx_t_2; + __pyx_L4_bool_binop_done:; + if (__pyx_t_1) { + + /* "View.MemoryView":353 + * self.flags = flags + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) # <<<<<<<<<<<<<< + * if self.view.obj == NULL: + * (<__pyx_buffer *> &self.view).obj = Py_None + */ + __pyx_t_3 = __Pyx_GetBuffer(__pyx_v_obj, (&__pyx_v_self->view), __pyx_v_flags); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(0, 353, __pyx_L1_error) + + /* "View.MemoryView":354 + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: # <<<<<<<<<<<<<< + * (<__pyx_buffer *> &self.view).obj = Py_None + * Py_INCREF(Py_None) + */ + __pyx_t_1 = (((PyObject *)__pyx_v_self->view.obj) == NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":355 + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: + * (<__pyx_buffer *> &self.view).obj = Py_None # <<<<<<<<<<<<<< + * Py_INCREF(Py_None) + * + */ + ((Py_buffer *)(&__pyx_v_self->view))->obj = Py_None; + + /* "View.MemoryView":356 + * if self.view.obj == NULL: + * (<__pyx_buffer *> &self.view).obj = Py_None + * Py_INCREF(Py_None) # <<<<<<<<<<<<<< + * + * if not __PYX_CYTHON_ATOMICS_ENABLED(): + */ + Py_INCREF(Py_None); + + /* "View.MemoryView":354 + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: # <<<<<<<<<<<<<< + * (<__pyx_buffer *> &self.view).obj = Py_None + * Py_INCREF(Py_None) + */ + } + + /* "View.MemoryView":352 + * self.obj = obj + * self.flags = flags + * if type(self) is memoryview or obj is not None: # <<<<<<<<<<<<<< + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: + */ + } + + /* "View.MemoryView":358 + * Py_INCREF(Py_None) + * + * if not __PYX_CYTHON_ATOMICS_ENABLED(): # <<<<<<<<<<<<<< + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: + */ + __pyx_t_1 = (!__PYX_CYTHON_ATOMICS_ENABLED()); + if (__pyx_t_1) { + + /* "View.MemoryView":360 + * if not __PYX_CYTHON_ATOMICS_ENABLED(): + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: # <<<<<<<<<<<<<< + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + */ + __pyx_t_1 = (__pyx_memoryview_thread_locks_used < 8); + if (__pyx_t_1) { + + /* "View.MemoryView":361 + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: + */ + __pyx_v_self->lock = (__pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used]); + + /* "View.MemoryView":362 + * if __pyx_memoryview_thread_locks_used < 8: + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 # <<<<<<<<<<<<<< + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() + */ + __pyx_memoryview_thread_locks_used = (__pyx_memoryview_thread_locks_used + 1); + + /* "View.MemoryView":360 + * if not __PYX_CYTHON_ATOMICS_ENABLED(): + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: # <<<<<<<<<<<<<< + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + */ + } + + /* "View.MemoryView":363 + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: # <<<<<<<<<<<<<< + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: + */ + __pyx_t_1 = (__pyx_v_self->lock == NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":364 + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() # <<<<<<<<<<<<<< + * if self.lock is NULL: + * raise MemoryError + */ + __pyx_v_self->lock = PyThread_allocate_lock(); + + /* "View.MemoryView":365 + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + __pyx_t_1 = (__pyx_v_self->lock == NULL); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":366 + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: + * raise MemoryError # <<<<<<<<<<<<<< + * + * if flags & PyBUF_FORMAT: + */ + PyErr_NoMemory(); __PYX_ERR(0, 366, __pyx_L1_error) + + /* "View.MemoryView":365 + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + } + + /* "View.MemoryView":363 + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: # <<<<<<<<<<<<<< + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: + */ + } + + /* "View.MemoryView":358 + * Py_INCREF(Py_None) + * + * if not __PYX_CYTHON_ATOMICS_ENABLED(): # <<<<<<<<<<<<<< + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: + */ + } + + /* "View.MemoryView":368 + * raise MemoryError + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_FORMAT) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":369 + * + * if flags & PyBUF_FORMAT: + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') # <<<<<<<<<<<<<< + * else: + * self.dtype_is_object = dtype_is_object + */ + __pyx_t_2 = ((__pyx_v_self->view.format[0]) == 'O'); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L12_bool_binop_done; + } + __pyx_t_2 = ((__pyx_v_self->view.format[1]) == '\x00'); + __pyx_t_1 = __pyx_t_2; + __pyx_L12_bool_binop_done:; + __pyx_v_self->dtype_is_object = __pyx_t_1; + + /* "View.MemoryView":368 + * raise MemoryError + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') + * else: + */ + goto __pyx_L11; + } + + /* "View.MemoryView":371 + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') + * else: + * self.dtype_is_object = dtype_is_object # <<<<<<<<<<<<<< + * + * assert (&self.acquisition_count) % sizeof(__pyx_atomic_int_type) == 0 + */ + /*else*/ { + __pyx_v_self->dtype_is_object = __pyx_v_dtype_is_object; + } + __pyx_L11:; + + /* "View.MemoryView":373 + * self.dtype_is_object = dtype_is_object + * + * assert (&self.acquisition_count) % sizeof(__pyx_atomic_int_type) == 0 # <<<<<<<<<<<<<< + * self.typeinfo = NULL + * + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_4 = ((Py_intptr_t)((void *)(&__pyx_v_self->acquisition_count))); + __pyx_t_5 = (sizeof(__pyx_atomic_int_type)); + if (unlikely(__pyx_t_5 == 0)) { + PyErr_SetString(PyExc_ZeroDivisionError, "integer division or modulo by zero"); + __PYX_ERR(0, 373, __pyx_L1_error) + } + __pyx_t_1 = ((__pyx_t_4 % __pyx_t_5) == 0); + if (unlikely(!__pyx_t_1)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(0, 373, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(0, 373, __pyx_L1_error) + #endif + + /* "View.MemoryView":374 + * + * assert (&self.acquisition_count) % sizeof(__pyx_atomic_int_type) == 0 + * self.typeinfo = NULL # <<<<<<<<<<<<<< + * + * def __dealloc__(memoryview self): + */ + __pyx_v_self->typeinfo = NULL; + + /* "View.MemoryView":349 + * cdef __Pyx_TypeInfo *typeinfo + * + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): # <<<<<<<<<<<<<< + * self.obj = obj + * self.flags = flags + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":376 + * self.typeinfo = NULL + * + * def __dealloc__(memoryview self): # <<<<<<<<<<<<<< + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + */ + +/* Python wrapper */ +static void __pyx_memoryview___dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_memoryview___dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_2__dealloc__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_2__dealloc__(struct __pyx_memoryview_obj *__pyx_v_self) { + int __pyx_v_i; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + PyThread_type_lock __pyx_t_5; + PyThread_type_lock __pyx_t_6; + + /* "View.MemoryView":377 + * + * def __dealloc__(memoryview self): + * if self.obj is not None: # <<<<<<<<<<<<<< + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + */ + __pyx_t_1 = (__pyx_v_self->obj != Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":378 + * def __dealloc__(memoryview self): + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) # <<<<<<<<<<<<<< + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + * + */ + __Pyx_ReleaseBuffer((&__pyx_v_self->view)); + + /* "View.MemoryView":377 + * + * def __dealloc__(memoryview self): + * if self.obj is not None: # <<<<<<<<<<<<<< + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":379 + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: # <<<<<<<<<<<<<< + * + * (<__pyx_buffer *> &self.view).obj = NULL + */ + __pyx_t_1 = (((Py_buffer *)(&__pyx_v_self->view))->obj == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":381 + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + * + * (<__pyx_buffer *> &self.view).obj = NULL # <<<<<<<<<<<<<< + * Py_DECREF(Py_None) + * + */ + ((Py_buffer *)(&__pyx_v_self->view))->obj = NULL; + + /* "View.MemoryView":382 + * + * (<__pyx_buffer *> &self.view).obj = NULL + * Py_DECREF(Py_None) # <<<<<<<<<<<<<< + * + * cdef int i + */ + Py_DECREF(Py_None); + + /* "View.MemoryView":379 + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: # <<<<<<<<<<<<<< + * + * (<__pyx_buffer *> &self.view).obj = NULL + */ + } + __pyx_L3:; + + /* "View.MemoryView":386 + * cdef int i + * global __pyx_memoryview_thread_locks_used + * if self.lock != NULL: # <<<<<<<<<<<<<< + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: + */ + __pyx_t_1 = (__pyx_v_self->lock != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":387 + * global __pyx_memoryview_thread_locks_used + * if self.lock != NULL: + * for i in range(__pyx_memoryview_thread_locks_used): # <<<<<<<<<<<<<< + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 + */ + __pyx_t_2 = __pyx_memoryview_thread_locks_used; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":388 + * if self.lock != NULL: + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: + */ + __pyx_t_1 = ((__pyx_memoryview_thread_locks[__pyx_v_i]) == __pyx_v_self->lock); + if (__pyx_t_1) { + + /* "View.MemoryView":389 + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 # <<<<<<<<<<<<<< + * if i != __pyx_memoryview_thread_locks_used: + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + */ + __pyx_memoryview_thread_locks_used = (__pyx_memoryview_thread_locks_used - 1); + + /* "View.MemoryView":390 + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + */ + __pyx_t_1 = (__pyx_v_i != __pyx_memoryview_thread_locks_used); + if (__pyx_t_1) { + + /* "View.MemoryView":392 + * if i != __pyx_memoryview_thread_locks_used: + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) # <<<<<<<<<<<<<< + * break + * else: + */ + __pyx_t_5 = (__pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used]); + __pyx_t_6 = (__pyx_memoryview_thread_locks[__pyx_v_i]); + + /* "View.MemoryView":391 + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + * break + */ + (__pyx_memoryview_thread_locks[__pyx_v_i]) = __pyx_t_5; + (__pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used]) = __pyx_t_6; + + /* "View.MemoryView":390 + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + */ + } + + /* "View.MemoryView":393 + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + * break # <<<<<<<<<<<<<< + * else: + * PyThread_free_lock(self.lock) + */ + goto __pyx_L6_break; + + /* "View.MemoryView":388 + * if self.lock != NULL: + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: + */ + } + } + /*else*/ { + + /* "View.MemoryView":395 + * break + * else: + * PyThread_free_lock(self.lock) # <<<<<<<<<<<<<< + * + * cdef char *get_item_pointer(memoryview self, object index) except NULL: + */ + PyThread_free_lock(__pyx_v_self->lock); + } + __pyx_L6_break:; + + /* "View.MemoryView":386 + * cdef int i + * global __pyx_memoryview_thread_locks_used + * if self.lock != NULL: # <<<<<<<<<<<<<< + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: + */ + } + + /* "View.MemoryView":376 + * self.typeinfo = NULL + * + * def __dealloc__(memoryview self): # <<<<<<<<<<<<<< + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + */ + + /* function exit code */ +} + +/* "View.MemoryView":397 + * PyThread_free_lock(self.lock) + * + * cdef char *get_item_pointer(memoryview self, object index) except NULL: # <<<<<<<<<<<<<< + * cdef Py_ssize_t dim + * cdef char *itemp = self.view.buf + */ + +static char *__pyx_memoryview_get_item_pointer(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index) { + Py_ssize_t __pyx_v_dim; + char *__pyx_v_itemp; + PyObject *__pyx_v_idx = NULL; + char *__pyx_r; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + Py_ssize_t __pyx_t_3; + PyObject *(*__pyx_t_4)(PyObject *); + PyObject *__pyx_t_5 = NULL; + Py_ssize_t __pyx_t_6; + char *__pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_item_pointer", 1); + + /* "View.MemoryView":399 + * cdef char *get_item_pointer(memoryview self, object index) except NULL: + * cdef Py_ssize_t dim + * cdef char *itemp = self.view.buf # <<<<<<<<<<<<<< + * + * for dim, idx in enumerate(index): + */ + __pyx_v_itemp = ((char *)__pyx_v_self->view.buf); + + /* "View.MemoryView":401 + * cdef char *itemp = self.view.buf + * + * for dim, idx in enumerate(index): # <<<<<<<<<<<<<< + * itemp = pybuffer_index(&self.view, itemp, idx, dim) + * + */ + __pyx_t_1 = 0; + if (likely(PyList_CheckExact(__pyx_v_index)) || PyTuple_CheckExact(__pyx_v_index)) { + __pyx_t_2 = __pyx_v_index; __Pyx_INCREF(__pyx_t_2); + __pyx_t_3 = 0; + __pyx_t_4 = NULL; + } else { + __pyx_t_3 = -1; __pyx_t_2 = PyObject_GetIter(__pyx_v_index); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 401, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_2); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 401, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_4)) { + if (likely(PyList_CheckExact(__pyx_t_2))) { + { + Py_ssize_t __pyx_temp = __Pyx_PyList_GET_SIZE(__pyx_t_2); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 401, __pyx_L1_error) + #endif + if (__pyx_t_3 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_5 = PyList_GET_ITEM(__pyx_t_2, __pyx_t_3); __Pyx_INCREF(__pyx_t_5); __pyx_t_3++; if (unlikely((0 < 0))) __PYX_ERR(0, 401, __pyx_L1_error) + #else + __pyx_t_5 = __Pyx_PySequence_ITEM(__pyx_t_2, __pyx_t_3); __pyx_t_3++; if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 401, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + #endif + } else { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_2); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 401, __pyx_L1_error) + #endif + if (__pyx_t_3 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_5 = PyTuple_GET_ITEM(__pyx_t_2, __pyx_t_3); __Pyx_INCREF(__pyx_t_5); __pyx_t_3++; if (unlikely((0 < 0))) __PYX_ERR(0, 401, __pyx_L1_error) + #else + __pyx_t_5 = __Pyx_PySequence_ITEM(__pyx_t_2, __pyx_t_3); __pyx_t_3++; if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 401, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + #endif + } + } else { + __pyx_t_5 = __pyx_t_4(__pyx_t_2); + if (unlikely(!__pyx_t_5)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(0, 401, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_5); + } + __Pyx_XDECREF_SET(__pyx_v_idx, __pyx_t_5); + __pyx_t_5 = 0; + __pyx_v_dim = __pyx_t_1; + __pyx_t_1 = (__pyx_t_1 + 1); + + /* "View.MemoryView":402 + * + * for dim, idx in enumerate(index): + * itemp = pybuffer_index(&self.view, itemp, idx, dim) # <<<<<<<<<<<<<< + * + * return itemp + */ + __pyx_t_6 = __Pyx_PyIndex_AsSsize_t(__pyx_v_idx); if (unlikely((__pyx_t_6 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 402, __pyx_L1_error) + __pyx_t_7 = __pyx_pybuffer_index((&__pyx_v_self->view), __pyx_v_itemp, __pyx_t_6, __pyx_v_dim); if (unlikely(__pyx_t_7 == ((char *)NULL))) __PYX_ERR(0, 402, __pyx_L1_error) + __pyx_v_itemp = __pyx_t_7; + + /* "View.MemoryView":401 + * cdef char *itemp = self.view.buf + * + * for dim, idx in enumerate(index): # <<<<<<<<<<<<<< + * itemp = pybuffer_index(&self.view, itemp, idx, dim) + * + */ + } + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":404 + * itemp = pybuffer_index(&self.view, itemp, idx, dim) + * + * return itemp # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = __pyx_v_itemp; + goto __pyx_L0; + + /* "View.MemoryView":397 + * PyThread_free_lock(self.lock) + * + * cdef char *get_item_pointer(memoryview self, object index) except NULL: # <<<<<<<<<<<<<< + * cdef Py_ssize_t dim + * cdef char *itemp = self.view.buf + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.memoryview.get_item_pointer", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_idx); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":407 + * + * + * def __getitem__(memoryview self, object index): # <<<<<<<<<<<<<< + * if index is Ellipsis: + * return self + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index); /*proto*/ +static PyObject *__pyx_memoryview___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getitem__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_4__getitem__(((struct __pyx_memoryview_obj *)__pyx_v_self), ((PyObject *)__pyx_v_index)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_4__getitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index) { + PyObject *__pyx_v_have_slices = NULL; + PyObject *__pyx_v_indices = NULL; + char *__pyx_v_itemp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + char *__pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__getitem__", 1); + + /* "View.MemoryView":408 + * + * def __getitem__(memoryview self, object index): + * if index is Ellipsis: # <<<<<<<<<<<<<< + * return self + * + */ + __pyx_t_1 = (__pyx_v_index == __pyx_builtin_Ellipsis); + if (__pyx_t_1) { + + /* "View.MemoryView":409 + * def __getitem__(memoryview self, object index): + * if index is Ellipsis: + * return self # <<<<<<<<<<<<<< + * + * have_slices, indices = _unellipsify(index, self.view.ndim) + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_self); + __pyx_r = ((PyObject *)__pyx_v_self); + goto __pyx_L0; + + /* "View.MemoryView":408 + * + * def __getitem__(memoryview self, object index): + * if index is Ellipsis: # <<<<<<<<<<<<<< + * return self + * + */ + } + + /* "View.MemoryView":411 + * return self + * + * have_slices, indices = _unellipsify(index, self.view.ndim) # <<<<<<<<<<<<<< + * + * cdef char *itemp + */ + __pyx_t_2 = _unellipsify(__pyx_v_index, __pyx_v_self->view.ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 411, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (likely(__pyx_t_2 != Py_None)) { + PyObject* sequence = __pyx_t_2; + Py_ssize_t size = __Pyx_PySequence_SIZE(sequence); + if (unlikely(size != 2)) { + if (size > 2) __Pyx_RaiseTooManyValuesError(2); + else if (size >= 0) __Pyx_RaiseNeedMoreValuesError(size); + __PYX_ERR(0, 411, __pyx_L1_error) + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_3 = PyTuple_GET_ITEM(sequence, 0); + __pyx_t_4 = PyTuple_GET_ITEM(sequence, 1); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(__pyx_t_4); + #else + __pyx_t_3 = PySequence_ITEM(sequence, 0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 411, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PySequence_ITEM(sequence, 1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 411, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } else { + __Pyx_RaiseNoneNotIterableError(); __PYX_ERR(0, 411, __pyx_L1_error) + } + __pyx_v_have_slices = __pyx_t_3; + __pyx_t_3 = 0; + __pyx_v_indices = __pyx_t_4; + __pyx_t_4 = 0; + + /* "View.MemoryView":414 + * + * cdef char *itemp + * if have_slices: # <<<<<<<<<<<<<< + * return memview_slice(self, indices) + * else: + */ + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_v_have_slices); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(0, 414, __pyx_L1_error) + if (__pyx_t_1) { + + /* "View.MemoryView":415 + * cdef char *itemp + * if have_slices: + * return memview_slice(self, indices) # <<<<<<<<<<<<<< + * else: + * itemp = self.get_item_pointer(indices) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = ((PyObject *)__pyx_memview_slice(__pyx_v_self, __pyx_v_indices)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 415, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":414 + * + * cdef char *itemp + * if have_slices: # <<<<<<<<<<<<<< + * return memview_slice(self, indices) + * else: + */ + } + + /* "View.MemoryView":417 + * return memview_slice(self, indices) + * else: + * itemp = self.get_item_pointer(indices) # <<<<<<<<<<<<<< + * return self.convert_item_to_object(itemp) + * + */ + /*else*/ { + __pyx_t_5 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->get_item_pointer(__pyx_v_self, __pyx_v_indices); if (unlikely(__pyx_t_5 == ((char *)NULL))) __PYX_ERR(0, 417, __pyx_L1_error) + __pyx_v_itemp = __pyx_t_5; + + /* "View.MemoryView":418 + * else: + * itemp = self.get_item_pointer(indices) + * return self.convert_item_to_object(itemp) # <<<<<<<<<<<<<< + * + * def __setitem__(memoryview self, object index, object value): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->convert_item_to_object(__pyx_v_self, __pyx_v_itemp); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 418, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + } + + /* "View.MemoryView":407 + * + * + * def __getitem__(memoryview self, object index): # <<<<<<<<<<<<<< + * if index is Ellipsis: + * return self + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.memoryview.__getitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_have_slices); + __Pyx_XDECREF(__pyx_v_indices); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":420 + * return self.convert_item_to_object(itemp) + * + * def __setitem__(memoryview self, object index, object value): # <<<<<<<<<<<<<< + * if self.view.readonly: + * raise TypeError, "Cannot assign to read-only memoryview" + */ + +/* Python wrapper */ +static int __pyx_memoryview___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value); /*proto*/ +static int __pyx_memoryview___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setitem__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_6__setitem__(((struct __pyx_memoryview_obj *)__pyx_v_self), ((PyObject *)__pyx_v_index), ((PyObject *)__pyx_v_value)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_6__setitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value) { + PyObject *__pyx_v_have_slices = NULL; + PyObject *__pyx_v_obj = NULL; + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setitem__", 0); + __Pyx_INCREF(__pyx_v_index); + + /* "View.MemoryView":421 + * + * def __setitem__(memoryview self, object index, object value): + * if self.view.readonly: # <<<<<<<<<<<<<< + * raise TypeError, "Cannot assign to read-only memoryview" + * + */ + if (unlikely(__pyx_v_self->view.readonly)) { + + /* "View.MemoryView":422 + * def __setitem__(memoryview self, object index, object value): + * if self.view.readonly: + * raise TypeError, "Cannot assign to read-only memoryview" # <<<<<<<<<<<<<< + * + * have_slices, index = _unellipsify(index, self.view.ndim) + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_Cannot_assign_to_read_only_memor, 0, 0); + __PYX_ERR(0, 422, __pyx_L1_error) + + /* "View.MemoryView":421 + * + * def __setitem__(memoryview self, object index, object value): + * if self.view.readonly: # <<<<<<<<<<<<<< + * raise TypeError, "Cannot assign to read-only memoryview" + * + */ + } + + /* "View.MemoryView":424 + * raise TypeError, "Cannot assign to read-only memoryview" + * + * have_slices, index = _unellipsify(index, self.view.ndim) # <<<<<<<<<<<<<< + * + * if have_slices: + */ + __pyx_t_1 = _unellipsify(__pyx_v_index, __pyx_v_self->view.ndim); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 424, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (likely(__pyx_t_1 != Py_None)) { + PyObject* sequence = __pyx_t_1; + Py_ssize_t size = __Pyx_PySequence_SIZE(sequence); + if (unlikely(size != 2)) { + if (size > 2) __Pyx_RaiseTooManyValuesError(2); + else if (size >= 0) __Pyx_RaiseNeedMoreValuesError(size); + __PYX_ERR(0, 424, __pyx_L1_error) + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_2 = PyTuple_GET_ITEM(sequence, 0); + __pyx_t_3 = PyTuple_GET_ITEM(sequence, 1); + __Pyx_INCREF(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + #else + __pyx_t_2 = PySequence_ITEM(sequence, 0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 424, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PySequence_ITEM(sequence, 1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 424, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + #endif + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } else { + __Pyx_RaiseNoneNotIterableError(); __PYX_ERR(0, 424, __pyx_L1_error) + } + __pyx_v_have_slices = __pyx_t_2; + __pyx_t_2 = 0; + __Pyx_DECREF_SET(__pyx_v_index, __pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":426 + * have_slices, index = _unellipsify(index, self.view.ndim) + * + * if have_slices: # <<<<<<<<<<<<<< + * obj = self.is_slice(value) + * if obj: + */ + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_v_have_slices); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 426, __pyx_L1_error) + if (__pyx_t_4) { + + /* "View.MemoryView":427 + * + * if have_slices: + * obj = self.is_slice(value) # <<<<<<<<<<<<<< + * if obj: + * self.setitem_slice_assignment(self[index], obj) + */ + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->is_slice(__pyx_v_self, __pyx_v_value); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 427, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_obj = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":428 + * if have_slices: + * obj = self.is_slice(value) + * if obj: # <<<<<<<<<<<<<< + * self.setitem_slice_assignment(self[index], obj) + * else: + */ + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_v_obj); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 428, __pyx_L1_error) + if (__pyx_t_4) { + + /* "View.MemoryView":429 + * obj = self.is_slice(value) + * if obj: + * self.setitem_slice_assignment(self[index], obj) # <<<<<<<<<<<<<< + * else: + * self.setitem_slice_assign_scalar(self[index], value) + */ + __pyx_t_1 = __Pyx_PyObject_GetItem(((PyObject *)__pyx_v_self), __pyx_v_index); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 429, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->setitem_slice_assignment(__pyx_v_self, __pyx_t_1, __pyx_v_obj); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 429, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "View.MemoryView":428 + * if have_slices: + * obj = self.is_slice(value) + * if obj: # <<<<<<<<<<<<<< + * self.setitem_slice_assignment(self[index], obj) + * else: + */ + goto __pyx_L5; + } + + /* "View.MemoryView":431 + * self.setitem_slice_assignment(self[index], obj) + * else: + * self.setitem_slice_assign_scalar(self[index], value) # <<<<<<<<<<<<<< + * else: + * self.setitem_indexed(index, value) + */ + /*else*/ { + __pyx_t_3 = __Pyx_PyObject_GetItem(((PyObject *)__pyx_v_self), __pyx_v_index); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 431, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (!(likely(((__pyx_t_3) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_3, __pyx_memoryview_type))))) __PYX_ERR(0, 431, __pyx_L1_error) + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->setitem_slice_assign_scalar(__pyx_v_self, ((struct __pyx_memoryview_obj *)__pyx_t_3), __pyx_v_value); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 431, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_L5:; + + /* "View.MemoryView":426 + * have_slices, index = _unellipsify(index, self.view.ndim) + * + * if have_slices: # <<<<<<<<<<<<<< + * obj = self.is_slice(value) + * if obj: + */ + goto __pyx_L4; + } + + /* "View.MemoryView":433 + * self.setitem_slice_assign_scalar(self[index], value) + * else: + * self.setitem_indexed(index, value) # <<<<<<<<<<<<<< + * + * cdef is_slice(self, obj): + */ + /*else*/ { + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->setitem_indexed(__pyx_v_self, __pyx_v_index, __pyx_v_value); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 433, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_L4:; + + /* "View.MemoryView":420 + * return self.convert_item_to_object(itemp) + * + * def __setitem__(memoryview self, object index, object value): # <<<<<<<<<<<<<< + * if self.view.readonly: + * raise TypeError, "Cannot assign to read-only memoryview" + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.__setitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_have_slices); + __Pyx_XDECREF(__pyx_v_obj); + __Pyx_XDECREF(__pyx_v_index); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":435 + * self.setitem_indexed(index, value) + * + * cdef is_slice(self, obj): # <<<<<<<<<<<<<< + * if not isinstance(obj, memoryview): + * try: + */ + +static PyObject *__pyx_memoryview_is_slice(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("is_slice", 0); + __Pyx_INCREF(__pyx_v_obj); + + /* "View.MemoryView":436 + * + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): # <<<<<<<<<<<<<< + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + */ + __pyx_t_1 = __Pyx_TypeCheck(__pyx_v_obj, __pyx_memoryview_type); + __pyx_t_2 = (!__pyx_t_1); + if (__pyx_t_2) { + + /* "View.MemoryView":437 + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): + * try: # <<<<<<<<<<<<<< + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_3, &__pyx_t_4, &__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_4); + __Pyx_XGOTREF(__pyx_t_5); + /*try:*/ { + + /* "View.MemoryView":438 + * if not isinstance(obj, memoryview): + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, # <<<<<<<<<<<<<< + * self.dtype_is_object) + * except TypeError: + */ + __pyx_t_6 = __Pyx_PyInt_From_int(((__pyx_v_self->flags & (~PyBUF_WRITABLE)) | PyBUF_ANY_CONTIGUOUS)); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 438, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_6); + + /* "View.MemoryView":439 + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) # <<<<<<<<<<<<<< + * except TypeError: + * return None + */ + __pyx_t_7 = __Pyx_PyBool_FromLong(__pyx_v_self->dtype_is_object); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 439, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_7); + + /* "View.MemoryView":438 + * if not isinstance(obj, memoryview): + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, # <<<<<<<<<<<<<< + * self.dtype_is_object) + * except TypeError: + */ + __pyx_t_8 = PyTuple_New(3); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 438, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_INCREF(__pyx_v_obj); + __Pyx_GIVEREF(__pyx_v_obj); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_8, 0, __pyx_v_obj)) __PYX_ERR(0, 438, __pyx_L4_error); + __Pyx_GIVEREF(__pyx_t_6); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_8, 1, __pyx_t_6)) __PYX_ERR(0, 438, __pyx_L4_error); + __Pyx_GIVEREF(__pyx_t_7); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_8, 2, __pyx_t_7)) __PYX_ERR(0, 438, __pyx_L4_error); + __pyx_t_6 = 0; + __pyx_t_7 = 0; + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_memoryview_type), __pyx_t_8, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 438, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_DECREF_SET(__pyx_v_obj, __pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":437 + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): + * try: # <<<<<<<<<<<<<< + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + */ + } + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + goto __pyx_L9_try_end; + __pyx_L4_error:; + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + + /* "View.MemoryView":440 + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + * except TypeError: # <<<<<<<<<<<<<< + * return None + * + */ + __pyx_t_9 = __Pyx_PyErr_ExceptionMatches(__pyx_builtin_TypeError); + if (__pyx_t_9) { + __Pyx_AddTraceback("View.MemoryView.memoryview.is_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_7, &__pyx_t_8, &__pyx_t_6) < 0) __PYX_ERR(0, 440, __pyx_L6_except_error) + __Pyx_XGOTREF(__pyx_t_7); + __Pyx_XGOTREF(__pyx_t_8); + __Pyx_XGOTREF(__pyx_t_6); + + /* "View.MemoryView":441 + * self.dtype_is_object) + * except TypeError: + * return None # <<<<<<<<<<<<<< + * + * return obj + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L7_except_return; + } + goto __pyx_L6_except_error; + + /* "View.MemoryView":437 + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): + * try: # <<<<<<<<<<<<<< + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + */ + __pyx_L6_except_error:; + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_XGIVEREF(__pyx_t_5); + __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_4, __pyx_t_5); + goto __pyx_L1_error; + __pyx_L7_except_return:; + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_XGIVEREF(__pyx_t_5); + __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_4, __pyx_t_5); + goto __pyx_L0; + __pyx_L9_try_end:; + } + + /* "View.MemoryView":436 + * + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): # <<<<<<<<<<<<<< + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + */ + } + + /* "View.MemoryView":443 + * return None + * + * return obj # <<<<<<<<<<<<<< + * + * cdef setitem_slice_assignment(self, dst, src): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_obj); + __pyx_r = __pyx_v_obj; + goto __pyx_L0; + + /* "View.MemoryView":435 + * self.setitem_indexed(index, value) + * + * cdef is_slice(self, obj): # <<<<<<<<<<<<<< + * if not isinstance(obj, memoryview): + * try: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("View.MemoryView.memoryview.is_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_obj); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":445 + * return obj + * + * cdef setitem_slice_assignment(self, dst, src): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice dst_slice + * cdef __Pyx_memviewslice src_slice + */ + +static PyObject *__pyx_memoryview_setitem_slice_assignment(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_dst, PyObject *__pyx_v_src) { + __Pyx_memviewslice __pyx_v_dst_slice; + __Pyx_memviewslice __pyx_v_src_slice; + __Pyx_memviewslice __pyx_v_msrc; + __Pyx_memviewslice __pyx_v_mdst; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_t_3; + int __pyx_t_4; + int __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("setitem_slice_assignment", 1); + + /* "View.MemoryView":448 + * cdef __Pyx_memviewslice dst_slice + * cdef __Pyx_memviewslice src_slice + * cdef __Pyx_memviewslice msrc = get_slice_from_memview(src, &src_slice)[0] # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice mdst = get_slice_from_memview(dst, &dst_slice)[0] + * + */ + if (!(likely(((__pyx_v_src) == Py_None) || likely(__Pyx_TypeTest(__pyx_v_src, __pyx_memoryview_type))))) __PYX_ERR(0, 448, __pyx_L1_error) + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(((struct __pyx_memoryview_obj *)__pyx_v_src), (&__pyx_v_src_slice)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(0, 448, __pyx_L1_error) + __pyx_v_msrc = (__pyx_t_1[0]); + + /* "View.MemoryView":449 + * cdef __Pyx_memviewslice src_slice + * cdef __Pyx_memviewslice msrc = get_slice_from_memview(src, &src_slice)[0] + * cdef __Pyx_memviewslice mdst = get_slice_from_memview(dst, &dst_slice)[0] # <<<<<<<<<<<<<< + * + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) + */ + if (!(likely(((__pyx_v_dst) == Py_None) || likely(__Pyx_TypeTest(__pyx_v_dst, __pyx_memoryview_type))))) __PYX_ERR(0, 449, __pyx_L1_error) + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(((struct __pyx_memoryview_obj *)__pyx_v_dst), (&__pyx_v_dst_slice)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(0, 449, __pyx_L1_error) + __pyx_v_mdst = (__pyx_t_1[0]); + + /* "View.MemoryView":451 + * cdef __Pyx_memviewslice mdst = get_slice_from_memview(dst, &dst_slice)[0] + * + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) # <<<<<<<<<<<<<< + * + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_src, __pyx_n_s_ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 451, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_PyInt_As_int(__pyx_t_2); if (unlikely((__pyx_t_3 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 451, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_dst, __pyx_n_s_ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 451, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __Pyx_PyInt_As_int(__pyx_t_2); if (unlikely((__pyx_t_4 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 451, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_5 = __pyx_memoryview_copy_contents(__pyx_v_msrc, __pyx_v_mdst, __pyx_t_3, __pyx_t_4, __pyx_v_self->dtype_is_object); if (unlikely(__pyx_t_5 == ((int)-1))) __PYX_ERR(0, 451, __pyx_L1_error) + + /* "View.MemoryView":445 + * return obj + * + * cdef setitem_slice_assignment(self, dst, src): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice dst_slice + * cdef __Pyx_memviewslice src_slice + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.setitem_slice_assignment", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":453 + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) + * + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): # <<<<<<<<<<<<<< + * cdef int array[128] + * cdef void *tmp = NULL + */ + +static PyObject *__pyx_memoryview_setitem_slice_assign_scalar(struct __pyx_memoryview_obj *__pyx_v_self, struct __pyx_memoryview_obj *__pyx_v_dst, PyObject *__pyx_v_value) { + int __pyx_v_array[0x80]; + void *__pyx_v_tmp; + void *__pyx_v_item; + __Pyx_memviewslice *__pyx_v_dst_slice; + __Pyx_memviewslice __pyx_v_tmp_slice; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_t_5; + char const *__pyx_t_6; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + PyObject *__pyx_t_9 = NULL; + PyObject *__pyx_t_10 = NULL; + PyObject *__pyx_t_11 = NULL; + PyObject *__pyx_t_12 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("setitem_slice_assign_scalar", 1); + + /* "View.MemoryView":455 + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): + * cdef int array[128] + * cdef void *tmp = NULL # <<<<<<<<<<<<<< + * cdef void *item + * + */ + __pyx_v_tmp = NULL; + + /* "View.MemoryView":460 + * cdef __Pyx_memviewslice *dst_slice + * cdef __Pyx_memviewslice tmp_slice + * dst_slice = get_slice_from_memview(dst, &tmp_slice) # <<<<<<<<<<<<<< + * + * if self.view.itemsize > sizeof(array): + */ + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(__pyx_v_dst, (&__pyx_v_tmp_slice)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(0, 460, __pyx_L1_error) + __pyx_v_dst_slice = __pyx_t_1; + + /* "View.MemoryView":462 + * dst_slice = get_slice_from_memview(dst, &tmp_slice) + * + * if self.view.itemsize > sizeof(array): # <<<<<<<<<<<<<< + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: + */ + __pyx_t_2 = (((size_t)__pyx_v_self->view.itemsize) > (sizeof(__pyx_v_array))); + if (__pyx_t_2) { + + /* "View.MemoryView":463 + * + * if self.view.itemsize > sizeof(array): + * tmp = PyMem_Malloc(self.view.itemsize) # <<<<<<<<<<<<<< + * if tmp == NULL: + * raise MemoryError + */ + __pyx_v_tmp = PyMem_Malloc(__pyx_v_self->view.itemsize); + + /* "View.MemoryView":464 + * if self.view.itemsize > sizeof(array): + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * item = tmp + */ + __pyx_t_2 = (__pyx_v_tmp == NULL); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":465 + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: + * raise MemoryError # <<<<<<<<<<<<<< + * item = tmp + * else: + */ + PyErr_NoMemory(); __PYX_ERR(0, 465, __pyx_L1_error) + + /* "View.MemoryView":464 + * if self.view.itemsize > sizeof(array): + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * item = tmp + */ + } + + /* "View.MemoryView":466 + * if tmp == NULL: + * raise MemoryError + * item = tmp # <<<<<<<<<<<<<< + * else: + * item = array + */ + __pyx_v_item = __pyx_v_tmp; + + /* "View.MemoryView":462 + * dst_slice = get_slice_from_memview(dst, &tmp_slice) + * + * if self.view.itemsize > sizeof(array): # <<<<<<<<<<<<<< + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":468 + * item = tmp + * else: + * item = array # <<<<<<<<<<<<<< + * + * try: + */ + /*else*/ { + __pyx_v_item = ((void *)__pyx_v_array); + } + __pyx_L3:; + + /* "View.MemoryView":470 + * item = array + * + * try: # <<<<<<<<<<<<<< + * if self.dtype_is_object: + * ( item)[0] = value + */ + /*try:*/ { + + /* "View.MemoryView":471 + * + * try: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * ( item)[0] = value + * else: + */ + if (__pyx_v_self->dtype_is_object) { + + /* "View.MemoryView":472 + * try: + * if self.dtype_is_object: + * ( item)[0] = value # <<<<<<<<<<<<<< + * else: + * self.assign_item_from_object( item, value) + */ + (((PyObject **)__pyx_v_item)[0]) = ((PyObject *)__pyx_v_value); + + /* "View.MemoryView":471 + * + * try: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * ( item)[0] = value + * else: + */ + goto __pyx_L8; + } + + /* "View.MemoryView":474 + * ( item)[0] = value + * else: + * self.assign_item_from_object( item, value) # <<<<<<<<<<<<<< + * + * + */ + /*else*/ { + __pyx_t_3 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->assign_item_from_object(__pyx_v_self, ((char *)__pyx_v_item), __pyx_v_value); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 474, __pyx_L6_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_L8:; + + /* "View.MemoryView":478 + * + * + * if self.view.suboffsets != NULL: # <<<<<<<<<<<<<< + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, + */ + __pyx_t_2 = (__pyx_v_self->view.suboffsets != NULL); + if (__pyx_t_2) { + + /* "View.MemoryView":479 + * + * if self.view.suboffsets != NULL: + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) # <<<<<<<<<<<<<< + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, + * item, self.dtype_is_object) + */ + __pyx_t_4 = assert_direct_dimensions(__pyx_v_self->view.suboffsets, __pyx_v_self->view.ndim); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(0, 479, __pyx_L6_error) + + /* "View.MemoryView":478 + * + * + * if self.view.suboffsets != NULL: # <<<<<<<<<<<<<< + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, + */ + } + + /* "View.MemoryView":480 + * if self.view.suboffsets != NULL: + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, # <<<<<<<<<<<<<< + * item, self.dtype_is_object) + * finally: + */ + __pyx_memoryview_slice_assign_scalar(__pyx_v_dst_slice, __pyx_v_dst->view.ndim, __pyx_v_self->view.itemsize, __pyx_v_item, __pyx_v_self->dtype_is_object); + } + + /* "View.MemoryView":483 + * item, self.dtype_is_object) + * finally: + * PyMem_Free(tmp) # <<<<<<<<<<<<<< + * + * cdef setitem_indexed(self, index, value): + */ + /*finally:*/ { + /*normal exit:*/{ + PyMem_Free(__pyx_v_tmp); + goto __pyx_L7; + } + __pyx_L6_error:; + /*exception exit:*/{ + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __pyx_t_7 = 0; __pyx_t_8 = 0; __pyx_t_9 = 0; __pyx_t_10 = 0; __pyx_t_11 = 0; __pyx_t_12 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (PY_MAJOR_VERSION >= 3) __Pyx_ExceptionSwap(&__pyx_t_10, &__pyx_t_11, &__pyx_t_12); + if ((PY_MAJOR_VERSION < 3) || unlikely(__Pyx_GetException(&__pyx_t_7, &__pyx_t_8, &__pyx_t_9) < 0)) __Pyx_ErrFetch(&__pyx_t_7, &__pyx_t_8, &__pyx_t_9); + __Pyx_XGOTREF(__pyx_t_7); + __Pyx_XGOTREF(__pyx_t_8); + __Pyx_XGOTREF(__pyx_t_9); + __Pyx_XGOTREF(__pyx_t_10); + __Pyx_XGOTREF(__pyx_t_11); + __Pyx_XGOTREF(__pyx_t_12); + __pyx_t_4 = __pyx_lineno; __pyx_t_5 = __pyx_clineno; __pyx_t_6 = __pyx_filename; + { + PyMem_Free(__pyx_v_tmp); + } + if (PY_MAJOR_VERSION >= 3) { + __Pyx_XGIVEREF(__pyx_t_10); + __Pyx_XGIVEREF(__pyx_t_11); + __Pyx_XGIVEREF(__pyx_t_12); + __Pyx_ExceptionReset(__pyx_t_10, __pyx_t_11, __pyx_t_12); + } + __Pyx_XGIVEREF(__pyx_t_7); + __Pyx_XGIVEREF(__pyx_t_8); + __Pyx_XGIVEREF(__pyx_t_9); + __Pyx_ErrRestore(__pyx_t_7, __pyx_t_8, __pyx_t_9); + __pyx_t_7 = 0; __pyx_t_8 = 0; __pyx_t_9 = 0; __pyx_t_10 = 0; __pyx_t_11 = 0; __pyx_t_12 = 0; + __pyx_lineno = __pyx_t_4; __pyx_clineno = __pyx_t_5; __pyx_filename = __pyx_t_6; + goto __pyx_L1_error; + } + __pyx_L7:; + } + + /* "View.MemoryView":453 + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) + * + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): # <<<<<<<<<<<<<< + * cdef int array[128] + * cdef void *tmp = NULL + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.setitem_slice_assign_scalar", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":485 + * PyMem_Free(tmp) + * + * cdef setitem_indexed(self, index, value): # <<<<<<<<<<<<<< + * cdef char *itemp = self.get_item_pointer(index) + * self.assign_item_from_object(itemp, value) + */ + +static PyObject *__pyx_memoryview_setitem_indexed(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value) { + char *__pyx_v_itemp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + char *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("setitem_indexed", 1); + + /* "View.MemoryView":486 + * + * cdef setitem_indexed(self, index, value): + * cdef char *itemp = self.get_item_pointer(index) # <<<<<<<<<<<<<< + * self.assign_item_from_object(itemp, value) + * + */ + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->get_item_pointer(__pyx_v_self, __pyx_v_index); if (unlikely(__pyx_t_1 == ((char *)NULL))) __PYX_ERR(0, 486, __pyx_L1_error) + __pyx_v_itemp = __pyx_t_1; + + /* "View.MemoryView":487 + * cdef setitem_indexed(self, index, value): + * cdef char *itemp = self.get_item_pointer(index) + * self.assign_item_from_object(itemp, value) # <<<<<<<<<<<<<< + * + * cdef convert_item_to_object(self, char *itemp): + */ + __pyx_t_2 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->assign_item_from_object(__pyx_v_self, __pyx_v_itemp, __pyx_v_value); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 487, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":485 + * PyMem_Free(tmp) + * + * cdef setitem_indexed(self, index, value): # <<<<<<<<<<<<<< + * cdef char *itemp = self.get_item_pointer(index) + * self.assign_item_from_object(itemp, value) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.setitem_indexed", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":489 + * self.assign_item_from_object(itemp, value) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + +static PyObject *__pyx_memoryview_convert_item_to_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp) { + PyObject *__pyx_v_struct = NULL; + PyObject *__pyx_v_bytesitem = 0; + PyObject *__pyx_v_result = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + int __pyx_t_8; + Py_ssize_t __pyx_t_9; + int __pyx_t_10; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("convert_item_to_object", 1); + + /* "View.MemoryView":492 + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + * import struct # <<<<<<<<<<<<<< + * cdef bytes bytesitem + * + */ + __pyx_t_1 = __Pyx_ImportDottedModule(__pyx_n_s_struct, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 492, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_struct = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":495 + * cdef bytes bytesitem + * + * bytesitem = itemp[:self.view.itemsize] # <<<<<<<<<<<<<< + * try: + * result = struct.unpack(self.view.format, bytesitem) + */ + __pyx_t_1 = __Pyx_PyBytes_FromStringAndSize(__pyx_v_itemp + 0, __pyx_v_self->view.itemsize - 0); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 495, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_bytesitem = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":496 + * + * bytesitem = itemp[:self.view.itemsize] + * try: # <<<<<<<<<<<<<< + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_2, &__pyx_t_3, &__pyx_t_4); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_4); + /*try:*/ { + + /* "View.MemoryView":497 + * bytesitem = itemp[:self.view.itemsize] + * try: + * result = struct.unpack(self.view.format, bytesitem) # <<<<<<<<<<<<<< + * except struct.error: + * raise ValueError, "Unable to convert item to object" + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_unpack); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 497, __pyx_L3_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = __Pyx_PyBytes_FromString(__pyx_v_self->view.format); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 497, __pyx_L3_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_7 = NULL; + __pyx_t_8 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_8 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_7, __pyx_t_6, __pyx_v_bytesitem}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_8, 2+__pyx_t_8); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 497, __pyx_L3_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + __pyx_v_result = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":496 + * + * bytesitem = itemp[:self.view.itemsize] + * try: # <<<<<<<<<<<<<< + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + */ + } + + /* "View.MemoryView":501 + * raise ValueError, "Unable to convert item to object" + * else: + * if len(self.view.format) == 1: # <<<<<<<<<<<<<< + * return result[0] + * return result + */ + /*else:*/ { + __pyx_t_9 = __Pyx_ssize_strlen(__pyx_v_self->view.format); if (unlikely(__pyx_t_9 == ((Py_ssize_t)-1))) __PYX_ERR(0, 501, __pyx_L5_except_error) + __pyx_t_10 = (__pyx_t_9 == 1); + if (__pyx_t_10) { + + /* "View.MemoryView":502 + * else: + * if len(self.view.format) == 1: + * return result[0] # <<<<<<<<<<<<<< + * return result + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_result, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 502, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L6_except_return; + + /* "View.MemoryView":501 + * raise ValueError, "Unable to convert item to object" + * else: + * if len(self.view.format) == 1: # <<<<<<<<<<<<<< + * return result[0] + * return result + */ + } + + /* "View.MemoryView":503 + * if len(self.view.format) == 1: + * return result[0] + * return result # <<<<<<<<<<<<<< + * + * cdef assign_item_from_object(self, char *itemp, object value): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_result); + __pyx_r = __pyx_v_result; + goto __pyx_L6_except_return; + } + __pyx_L3_error:; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":498 + * try: + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: # <<<<<<<<<<<<<< + * raise ValueError, "Unable to convert item to object" + * else: + */ + __Pyx_ErrFetch(&__pyx_t_1, &__pyx_t_5, &__pyx_t_6); + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_error); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 498, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_8 = __Pyx_PyErr_GivenExceptionMatches(__pyx_t_1, __pyx_t_7); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_ErrRestore(__pyx_t_1, __pyx_t_5, __pyx_t_6); + __pyx_t_1 = 0; __pyx_t_5 = 0; __pyx_t_6 = 0; + if (__pyx_t_8) { + __Pyx_AddTraceback("View.MemoryView.memoryview.convert_item_to_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_6, &__pyx_t_5, &__pyx_t_1) < 0) __PYX_ERR(0, 498, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_1); + + /* "View.MemoryView":499 + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + * raise ValueError, "Unable to convert item to object" # <<<<<<<<<<<<<< + * else: + * if len(self.view.format) == 1: + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Unable_to_convert_item_to_object, 0, 0); + __PYX_ERR(0, 499, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "View.MemoryView":496 + * + * bytesitem = itemp[:self.view.itemsize] + * try: # <<<<<<<<<<<<<< + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_ExceptionReset(__pyx_t_2, __pyx_t_3, __pyx_t_4); + goto __pyx_L1_error; + __pyx_L6_except_return:; + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_ExceptionReset(__pyx_t_2, __pyx_t_3, __pyx_t_4); + goto __pyx_L0; + } + + /* "View.MemoryView":489 + * self.assign_item_from_object(itemp, value) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("View.MemoryView.memoryview.convert_item_to_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_struct); + __Pyx_XDECREF(__pyx_v_bytesitem); + __Pyx_XDECREF(__pyx_v_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":505 + * return result + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + +static PyObject *__pyx_memoryview_assign_item_from_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value) { + PyObject *__pyx_v_struct = NULL; + char __pyx_v_c; + PyObject *__pyx_v_bytesvalue = 0; + Py_ssize_t __pyx_v_i; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + Py_ssize_t __pyx_t_7; + PyObject *__pyx_t_8 = NULL; + char *__pyx_t_9; + char *__pyx_t_10; + char *__pyx_t_11; + char *__pyx_t_12; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("assign_item_from_object", 1); + + /* "View.MemoryView":508 + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + * import struct # <<<<<<<<<<<<<< + * cdef char c + * cdef bytes bytesvalue + */ + __pyx_t_1 = __Pyx_ImportDottedModule(__pyx_n_s_struct, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 508, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_struct = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":513 + * cdef Py_ssize_t i + * + * if isinstance(value, tuple): # <<<<<<<<<<<<<< + * bytesvalue = struct.pack(self.view.format, *value) + * else: + */ + __pyx_t_2 = PyTuple_Check(__pyx_v_value); + if (__pyx_t_2) { + + /* "View.MemoryView":514 + * + * if isinstance(value, tuple): + * bytesvalue = struct.pack(self.view.format, *value) # <<<<<<<<<<<<<< + * else: + * bytesvalue = struct.pack(self.view.format, value) + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_pack); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyBytes_FromString(__pyx_v_self->view.format); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PyTuple_New(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_3)) __PYX_ERR(0, 514, __pyx_L1_error); + __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PySequence_Tuple(__pyx_v_value); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = PyNumber_Add(__pyx_t_4, __pyx_t_3); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PyObject_Call(__pyx_t_1, __pyx_t_5, NULL); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (!(likely(PyBytes_CheckExact(__pyx_t_3))||((__pyx_t_3) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_t_3))) __PYX_ERR(0, 514, __pyx_L1_error) + __pyx_v_bytesvalue = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":513 + * cdef Py_ssize_t i + * + * if isinstance(value, tuple): # <<<<<<<<<<<<<< + * bytesvalue = struct.pack(self.view.format, *value) + * else: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":516 + * bytesvalue = struct.pack(self.view.format, *value) + * else: + * bytesvalue = struct.pack(self.view.format, value) # <<<<<<<<<<<<<< + * + * for i, c in enumerate(bytesvalue): + */ + /*else*/ { + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_pack); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 516, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 = __Pyx_PyBytes_FromString(__pyx_v_self->view.format); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 516, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_4 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_4, __pyx_t_1, __pyx_v_value}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 516, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + if (!(likely(PyBytes_CheckExact(__pyx_t_3))||((__pyx_t_3) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_t_3))) __PYX_ERR(0, 516, __pyx_L1_error) + __pyx_v_bytesvalue = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; + } + __pyx_L3:; + + /* "View.MemoryView":518 + * bytesvalue = struct.pack(self.view.format, value) + * + * for i, c in enumerate(bytesvalue): # <<<<<<<<<<<<<< + * itemp[i] = c + * + */ + __pyx_t_7 = 0; + if (unlikely(__pyx_v_bytesvalue == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' is not iterable"); + __PYX_ERR(0, 518, __pyx_L1_error) + } + __Pyx_INCREF(__pyx_v_bytesvalue); + __pyx_t_8 = __pyx_v_bytesvalue; + __pyx_t_10 = PyBytes_AS_STRING(__pyx_t_8); + __pyx_t_11 = (__pyx_t_10 + PyBytes_GET_SIZE(__pyx_t_8)); + for (__pyx_t_12 = __pyx_t_10; __pyx_t_12 < __pyx_t_11; __pyx_t_12++) { + __pyx_t_9 = __pyx_t_12; + __pyx_v_c = (__pyx_t_9[0]); + + /* "View.MemoryView":519 + * + * for i, c in enumerate(bytesvalue): + * itemp[i] = c # <<<<<<<<<<<<<< + * + * @cname('getbuffer') + */ + __pyx_v_i = __pyx_t_7; + + /* "View.MemoryView":518 + * bytesvalue = struct.pack(self.view.format, value) + * + * for i, c in enumerate(bytesvalue): # <<<<<<<<<<<<<< + * itemp[i] = c + * + */ + __pyx_t_7 = (__pyx_t_7 + 1); + + /* "View.MemoryView":519 + * + * for i, c in enumerate(bytesvalue): + * itemp[i] = c # <<<<<<<<<<<<<< + * + * @cname('getbuffer') + */ + (__pyx_v_itemp[__pyx_v_i]) = __pyx_v_c; + } + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + + /* "View.MemoryView":505 + * return result + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("View.MemoryView.memoryview.assign_item_from_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_struct); + __Pyx_XDECREF(__pyx_v_bytesvalue); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":521 + * itemp[i] = c + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: + */ + +/* Python wrapper */ +CYTHON_UNUSED static int __pyx_memoryview_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +CYTHON_UNUSED static int __pyx_memoryview_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getbuffer__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_8__getbuffer__(((struct __pyx_memoryview_obj *)__pyx_v_self), ((Py_buffer *)__pyx_v_info), ((int)__pyx_v_flags)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_8__getbuffer__(struct __pyx_memoryview_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + Py_ssize_t *__pyx_t_3; + char *__pyx_t_4; + void *__pyx_t_5; + int __pyx_t_6; + Py_ssize_t __pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + if (unlikely(__pyx_v_info == NULL)) { + PyErr_SetString(PyExc_BufferError, "PyObject_GetBuffer: view==NULL argument is obsolete"); + return -1; + } + __Pyx_RefNannySetupContext("__getbuffer__", 0); + __pyx_v_info->obj = Py_None; __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(__pyx_v_info->obj); + + /* "View.MemoryView":523 + * @cname('getbuffer') + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: # <<<<<<<<<<<<<< + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + */ + __pyx_t_2 = ((__pyx_v_flags & PyBUF_WRITABLE) != 0); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_1 = __pyx_v_self->view.readonly; + __pyx_L4_bool_binop_done:; + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":524 + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: + * raise ValueError, "Cannot create writable memory view from read-only memoryview" # <<<<<<<<<<<<<< + * + * if flags & PyBUF_ND: + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Cannot_create_writable_memory_vi, 0, 0); + __PYX_ERR(0, 524, __pyx_L1_error) + + /* "View.MemoryView":523 + * @cname('getbuffer') + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: # <<<<<<<<<<<<<< + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + */ + } + + /* "View.MemoryView":526 + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + * if flags & PyBUF_ND: # <<<<<<<<<<<<<< + * info.shape = self.view.shape + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_ND) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":527 + * + * if flags & PyBUF_ND: + * info.shape = self.view.shape # <<<<<<<<<<<<<< + * else: + * info.shape = NULL + */ + __pyx_t_3 = __pyx_v_self->view.shape; + __pyx_v_info->shape = __pyx_t_3; + + /* "View.MemoryView":526 + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + * if flags & PyBUF_ND: # <<<<<<<<<<<<<< + * info.shape = self.view.shape + * else: + */ + goto __pyx_L6; + } + + /* "View.MemoryView":529 + * info.shape = self.view.shape + * else: + * info.shape = NULL # <<<<<<<<<<<<<< + * + * if flags & PyBUF_STRIDES: + */ + /*else*/ { + __pyx_v_info->shape = NULL; + } + __pyx_L6:; + + /* "View.MemoryView":531 + * info.shape = NULL + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.strides = self.view.strides + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_STRIDES) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":532 + * + * if flags & PyBUF_STRIDES: + * info.strides = self.view.strides # <<<<<<<<<<<<<< + * else: + * info.strides = NULL + */ + __pyx_t_3 = __pyx_v_self->view.strides; + __pyx_v_info->strides = __pyx_t_3; + + /* "View.MemoryView":531 + * info.shape = NULL + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.strides = self.view.strides + * else: + */ + goto __pyx_L7; + } + + /* "View.MemoryView":534 + * info.strides = self.view.strides + * else: + * info.strides = NULL # <<<<<<<<<<<<<< + * + * if flags & PyBUF_INDIRECT: + */ + /*else*/ { + __pyx_v_info->strides = NULL; + } + __pyx_L7:; + + /* "View.MemoryView":536 + * info.strides = NULL + * + * if flags & PyBUF_INDIRECT: # <<<<<<<<<<<<<< + * info.suboffsets = self.view.suboffsets + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_INDIRECT) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":537 + * + * if flags & PyBUF_INDIRECT: + * info.suboffsets = self.view.suboffsets # <<<<<<<<<<<<<< + * else: + * info.suboffsets = NULL + */ + __pyx_t_3 = __pyx_v_self->view.suboffsets; + __pyx_v_info->suboffsets = __pyx_t_3; + + /* "View.MemoryView":536 + * info.strides = NULL + * + * if flags & PyBUF_INDIRECT: # <<<<<<<<<<<<<< + * info.suboffsets = self.view.suboffsets + * else: + */ + goto __pyx_L8; + } + + /* "View.MemoryView":539 + * info.suboffsets = self.view.suboffsets + * else: + * info.suboffsets = NULL # <<<<<<<<<<<<<< + * + * if flags & PyBUF_FORMAT: + */ + /*else*/ { + __pyx_v_info->suboffsets = NULL; + } + __pyx_L8:; + + /* "View.MemoryView":541 + * info.suboffsets = NULL + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * info.format = self.view.format + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_FORMAT) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":542 + * + * if flags & PyBUF_FORMAT: + * info.format = self.view.format # <<<<<<<<<<<<<< + * else: + * info.format = NULL + */ + __pyx_t_4 = __pyx_v_self->view.format; + __pyx_v_info->format = __pyx_t_4; + + /* "View.MemoryView":541 + * info.suboffsets = NULL + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * info.format = self.view.format + * else: + */ + goto __pyx_L9; + } + + /* "View.MemoryView":544 + * info.format = self.view.format + * else: + * info.format = NULL # <<<<<<<<<<<<<< + * + * info.buf = self.view.buf + */ + /*else*/ { + __pyx_v_info->format = NULL; + } + __pyx_L9:; + + /* "View.MemoryView":546 + * info.format = NULL + * + * info.buf = self.view.buf # <<<<<<<<<<<<<< + * info.ndim = self.view.ndim + * info.itemsize = self.view.itemsize + */ + __pyx_t_5 = __pyx_v_self->view.buf; + __pyx_v_info->buf = __pyx_t_5; + + /* "View.MemoryView":547 + * + * info.buf = self.view.buf + * info.ndim = self.view.ndim # <<<<<<<<<<<<<< + * info.itemsize = self.view.itemsize + * info.len = self.view.len + */ + __pyx_t_6 = __pyx_v_self->view.ndim; + __pyx_v_info->ndim = __pyx_t_6; + + /* "View.MemoryView":548 + * info.buf = self.view.buf + * info.ndim = self.view.ndim + * info.itemsize = self.view.itemsize # <<<<<<<<<<<<<< + * info.len = self.view.len + * info.readonly = self.view.readonly + */ + __pyx_t_7 = __pyx_v_self->view.itemsize; + __pyx_v_info->itemsize = __pyx_t_7; + + /* "View.MemoryView":549 + * info.ndim = self.view.ndim + * info.itemsize = self.view.itemsize + * info.len = self.view.len # <<<<<<<<<<<<<< + * info.readonly = self.view.readonly + * info.obj = self + */ + __pyx_t_7 = __pyx_v_self->view.len; + __pyx_v_info->len = __pyx_t_7; + + /* "View.MemoryView":550 + * info.itemsize = self.view.itemsize + * info.len = self.view.len + * info.readonly = self.view.readonly # <<<<<<<<<<<<<< + * info.obj = self + * + */ + __pyx_t_1 = __pyx_v_self->view.readonly; + __pyx_v_info->readonly = __pyx_t_1; + + /* "View.MemoryView":551 + * info.len = self.view.len + * info.readonly = self.view.readonly + * info.obj = self # <<<<<<<<<<<<<< + * + * + */ + __Pyx_INCREF((PyObject *)__pyx_v_self); + __Pyx_GIVEREF((PyObject *)__pyx_v_self); + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); + __pyx_v_info->obj = ((PyObject *)__pyx_v_self); + + /* "View.MemoryView":521 + * itemp[i] = c + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__getbuffer__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + if (__pyx_v_info->obj != NULL) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + goto __pyx_L2; + __pyx_L0:; + if (__pyx_v_info->obj == Py_None) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + __pyx_L2:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":554 + * + * + * @property # <<<<<<<<<<<<<< + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_1T_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_1T_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_1T___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_1T___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + struct __pyx_memoryviewslice_obj *__pyx_v_result = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":556 + * @property + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) # <<<<<<<<<<<<<< + * transpose_memslice(&result.from_slice) + * return result + */ + __pyx_t_1 = __pyx_memoryview_copy_object(__pyx_v_self); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 556, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (!(likely(((__pyx_t_1) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_1, __pyx_memoryviewslice_type))))) __PYX_ERR(0, 556, __pyx_L1_error) + __pyx_v_result = ((struct __pyx_memoryviewslice_obj *)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":557 + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) + * transpose_memslice(&result.from_slice) # <<<<<<<<<<<<<< + * return result + * + */ + __pyx_t_2 = __pyx_memslice_transpose((&__pyx_v_result->from_slice)); if (unlikely(__pyx_t_2 == ((int)-1))) __PYX_ERR(0, 557, __pyx_L1_error) + + /* "View.MemoryView":558 + * cdef _memoryviewslice result = memoryview_copy(self) + * transpose_memslice(&result.from_slice) + * return result # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = ((PyObject *)__pyx_v_result); + goto __pyx_L0; + + /* "View.MemoryView":554 + * + * + * @property # <<<<<<<<<<<<<< + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.T.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":560 + * return result + * + * @property # <<<<<<<<<<<<<< + * def base(self): + * return self._get_base() + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4base_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4base_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_4base___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4base___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":562 + * @property + * def base(self): + * return self._get_base() # <<<<<<<<<<<<<< + * + * cdef _get_base(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->_get_base(__pyx_v_self); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 562, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":560 + * return result + * + * @property # <<<<<<<<<<<<<< + * def base(self): + * return self._get_base() + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.base.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":564 + * return self._get_base() + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.obj + * + */ + +static PyObject *__pyx_memoryview__get_base(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("_get_base", 1); + + /* "View.MemoryView":565 + * + * cdef _get_base(self): + * return self.obj # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->obj); + __pyx_r = __pyx_v_self->obj; + goto __pyx_L0; + + /* "View.MemoryView":564 + * return self._get_base() + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.obj + * + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":567 + * return self.obj + * + * @property # <<<<<<<<<<<<<< + * def shape(self): + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_5shape_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_5shape_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_5shape___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_5shape___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_7genexpr__pyx_v_length; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + PyObject *__pyx_t_5 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":569 + * @property + * def shape(self): + * return tuple([length for length in self.view.shape[:self.view.ndim]]) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + { /* enter inner scope */ + __pyx_t_1 = PyList_New(0); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 569, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = (__pyx_v_self->view.shape + __pyx_v_self->view.ndim); + for (__pyx_t_4 = __pyx_v_self->view.shape; __pyx_t_4 < __pyx_t_3; __pyx_t_4++) { + __pyx_t_2 = __pyx_t_4; + __pyx_7genexpr__pyx_v_length = (__pyx_t_2[0]); + __pyx_t_5 = PyInt_FromSsize_t(__pyx_7genexpr__pyx_v_length); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 569, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_1, (PyObject*)__pyx_t_5))) __PYX_ERR(0, 569, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + } /* exit inner scope */ + __pyx_t_5 = PyList_AsTuple(((PyObject*)__pyx_t_1)); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 569, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_5; + __pyx_t_5 = 0; + goto __pyx_L0; + + /* "View.MemoryView":567 + * return self.obj + * + * @property # <<<<<<<<<<<<<< + * def shape(self): + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.memoryview.shape.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":571 + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def strides(self): + * if self.view.strides == NULL: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_7strides_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_7strides_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_7strides___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_7strides___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_8genexpr1__pyx_v_stride; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + Py_ssize_t *__pyx_t_5; + PyObject *__pyx_t_6 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":573 + * @property + * def strides(self): + * if self.view.strides == NULL: # <<<<<<<<<<<<<< + * + * raise ValueError, "Buffer view does not expose strides" + */ + __pyx_t_1 = (__pyx_v_self->view.strides == NULL); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":575 + * if self.view.strides == NULL: + * + * raise ValueError, "Buffer view does not expose strides" # <<<<<<<<<<<<<< + * + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Buffer_view_does_not_expose_stri, 0, 0); + __PYX_ERR(0, 575, __pyx_L1_error) + + /* "View.MemoryView":573 + * @property + * def strides(self): + * if self.view.strides == NULL: # <<<<<<<<<<<<<< + * + * raise ValueError, "Buffer view does not expose strides" + */ + } + + /* "View.MemoryView":577 + * raise ValueError, "Buffer view does not expose strides" + * + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + { /* enter inner scope */ + __pyx_t_2 = PyList_New(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 577, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = (__pyx_v_self->view.strides + __pyx_v_self->view.ndim); + for (__pyx_t_5 = __pyx_v_self->view.strides; __pyx_t_5 < __pyx_t_4; __pyx_t_5++) { + __pyx_t_3 = __pyx_t_5; + __pyx_8genexpr1__pyx_v_stride = (__pyx_t_3[0]); + __pyx_t_6 = PyInt_FromSsize_t(__pyx_8genexpr1__pyx_v_stride); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 577, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_2, (PyObject*)__pyx_t_6))) __PYX_ERR(0, 577, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + } /* exit inner scope */ + __pyx_t_6 = PyList_AsTuple(((PyObject*)__pyx_t_2)); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 577, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_6; + __pyx_t_6 = 0; + goto __pyx_L0; + + /* "View.MemoryView":571 + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def strides(self): + * if self.view.strides == NULL: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("View.MemoryView.memoryview.strides.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":579 + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def suboffsets(self): + * if self.view.suboffsets == NULL: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_10suboffsets_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_10suboffsets_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_10suboffsets___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_10suboffsets___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_8genexpr2__pyx_v_suboffset; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + Py_ssize_t *__pyx_t_5; + PyObject *__pyx_t_6 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":581 + * @property + * def suboffsets(self): + * if self.view.suboffsets == NULL: # <<<<<<<<<<<<<< + * return (-1,) * self.view.ndim + * + */ + __pyx_t_1 = (__pyx_v_self->view.suboffsets == NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":582 + * def suboffsets(self): + * if self.view.suboffsets == NULL: + * return (-1,) * self.view.ndim # <<<<<<<<<<<<<< + * + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PySequence_Multiply(__pyx_tuple__4, __pyx_v_self->view.ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 582, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":581 + * @property + * def suboffsets(self): + * if self.view.suboffsets == NULL: # <<<<<<<<<<<<<< + * return (-1,) * self.view.ndim + * + */ + } + + /* "View.MemoryView":584 + * return (-1,) * self.view.ndim + * + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + { /* enter inner scope */ + __pyx_t_2 = PyList_New(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 584, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = (__pyx_v_self->view.suboffsets + __pyx_v_self->view.ndim); + for (__pyx_t_5 = __pyx_v_self->view.suboffsets; __pyx_t_5 < __pyx_t_4; __pyx_t_5++) { + __pyx_t_3 = __pyx_t_5; + __pyx_8genexpr2__pyx_v_suboffset = (__pyx_t_3[0]); + __pyx_t_6 = PyInt_FromSsize_t(__pyx_8genexpr2__pyx_v_suboffset); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 584, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_2, (PyObject*)__pyx_t_6))) __PYX_ERR(0, 584, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + } /* exit inner scope */ + __pyx_t_6 = PyList_AsTuple(((PyObject*)__pyx_t_2)); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 584, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_6; + __pyx_t_6 = 0; + goto __pyx_L0; + + /* "View.MemoryView":579 + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def suboffsets(self): + * if self.view.suboffsets == NULL: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("View.MemoryView.memoryview.suboffsets.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":586 + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def ndim(self): + * return self.view.ndim + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4ndim_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4ndim_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_4ndim___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4ndim___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":588 + * @property + * def ndim(self): + * return self.view.ndim # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_self->view.ndim); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 588, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":586 + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def ndim(self): + * return self.view.ndim + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.ndim.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":590 + * return self.view.ndim + * + * @property # <<<<<<<<<<<<<< + * def itemsize(self): + * return self.view.itemsize + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_8itemsize_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_8itemsize_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_8itemsize___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_8itemsize___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":592 + * @property + * def itemsize(self): + * return self.view.itemsize # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyInt_FromSsize_t(__pyx_v_self->view.itemsize); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 592, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":590 + * return self.view.ndim + * + * @property # <<<<<<<<<<<<<< + * def itemsize(self): + * return self.view.itemsize + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.itemsize.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":594 + * return self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def nbytes(self): + * return self.size * self.view.itemsize + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_6nbytes_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_6nbytes_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_6nbytes___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_6nbytes___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":596 + * @property + * def nbytes(self): + * return self.size * self.view.itemsize # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_size); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 596, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = PyInt_FromSsize_t(__pyx_v_self->view.itemsize); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 596, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyNumber_Multiply(__pyx_t_1, __pyx_t_2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 596, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_3; + __pyx_t_3 = 0; + goto __pyx_L0; + + /* "View.MemoryView":594 + * return self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def nbytes(self): + * return self.size * self.view.itemsize + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.nbytes.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":598 + * return self.size * self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def size(self): + * if self._size is None: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4size_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4size_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_4size___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4size___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_v_result = NULL; + PyObject *__pyx_v_length = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + PyObject *__pyx_t_5 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":600 + * @property + * def size(self): + * if self._size is None: # <<<<<<<<<<<<<< + * result = 1 + * + */ + __pyx_t_1 = (__pyx_v_self->_size == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":601 + * def size(self): + * if self._size is None: + * result = 1 # <<<<<<<<<<<<<< + * + * for length in self.view.shape[:self.view.ndim]: + */ + __Pyx_INCREF(__pyx_int_1); + __pyx_v_result = __pyx_int_1; + + /* "View.MemoryView":603 + * result = 1 + * + * for length in self.view.shape[:self.view.ndim]: # <<<<<<<<<<<<<< + * result *= length + * + */ + __pyx_t_3 = (__pyx_v_self->view.shape + __pyx_v_self->view.ndim); + for (__pyx_t_4 = __pyx_v_self->view.shape; __pyx_t_4 < __pyx_t_3; __pyx_t_4++) { + __pyx_t_2 = __pyx_t_4; + __pyx_t_5 = PyInt_FromSsize_t((__pyx_t_2[0])); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 603, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_XDECREF_SET(__pyx_v_length, __pyx_t_5); + __pyx_t_5 = 0; + + /* "View.MemoryView":604 + * + * for length in self.view.shape[:self.view.ndim]: + * result *= length # <<<<<<<<<<<<<< + * + * self._size = result + */ + __pyx_t_5 = PyNumber_InPlaceMultiply(__pyx_v_result, __pyx_v_length); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 604, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF_SET(__pyx_v_result, __pyx_t_5); + __pyx_t_5 = 0; + } + + /* "View.MemoryView":606 + * result *= length + * + * self._size = result # <<<<<<<<<<<<<< + * + * return self._size + */ + __Pyx_INCREF(__pyx_v_result); + __Pyx_GIVEREF(__pyx_v_result); + __Pyx_GOTREF(__pyx_v_self->_size); + __Pyx_DECREF(__pyx_v_self->_size); + __pyx_v_self->_size = __pyx_v_result; + + /* "View.MemoryView":600 + * @property + * def size(self): + * if self._size is None: # <<<<<<<<<<<<<< + * result = 1 + * + */ + } + + /* "View.MemoryView":608 + * self._size = result + * + * return self._size # <<<<<<<<<<<<<< + * + * def __len__(self): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->_size); + __pyx_r = __pyx_v_self->_size; + goto __pyx_L0; + + /* "View.MemoryView":598 + * return self.size * self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def size(self): + * if self._size is None: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.memoryview.size.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_result); + __Pyx_XDECREF(__pyx_v_length); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":610 + * return self._size + * + * def __len__(self): # <<<<<<<<<<<<<< + * if self.view.ndim >= 1: + * return self.view.shape[0] + */ + +/* Python wrapper */ +static Py_ssize_t __pyx_memoryview___len__(PyObject *__pyx_v_self); /*proto*/ +static Py_ssize_t __pyx_memoryview___len__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + Py_ssize_t __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__len__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_10__len__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static Py_ssize_t __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_10__len__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_r; + int __pyx_t_1; + + /* "View.MemoryView":611 + * + * def __len__(self): + * if self.view.ndim >= 1: # <<<<<<<<<<<<<< + * return self.view.shape[0] + * + */ + __pyx_t_1 = (__pyx_v_self->view.ndim >= 1); + if (__pyx_t_1) { + + /* "View.MemoryView":612 + * def __len__(self): + * if self.view.ndim >= 1: + * return self.view.shape[0] # <<<<<<<<<<<<<< + * + * return 0 + */ + __pyx_r = (__pyx_v_self->view.shape[0]); + goto __pyx_L0; + + /* "View.MemoryView":611 + * + * def __len__(self): + * if self.view.ndim >= 1: # <<<<<<<<<<<<<< + * return self.view.shape[0] + * + */ + } + + /* "View.MemoryView":614 + * return self.view.shape[0] + * + * return 0 # <<<<<<<<<<<<<< + * + * def __repr__(self): + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":610 + * return self._size + * + * def __len__(self): # <<<<<<<<<<<<<< + * if self.view.ndim >= 1: + * return self.view.shape[0] + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":616 + * return 0 + * + * def __repr__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__, + * id(self)) + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview___repr__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_memoryview___repr__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__repr__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_12__repr__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_12__repr__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__repr__", 1); + + /* "View.MemoryView":617 + * + * def __repr__(self): + * return "" % (self.base.__class__.__name__, # <<<<<<<<<<<<<< + * id(self)) + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_base); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_class); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_name_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":618 + * def __repr__(self): + * return "" % (self.base.__class__.__name__, + * id(self)) # <<<<<<<<<<<<<< + * + * def __str__(self): + */ + __pyx_t_2 = __Pyx_PyObject_CallOneArg(__pyx_builtin_id, ((PyObject *)__pyx_v_self)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 618, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + + /* "View.MemoryView":617 + * + * def __repr__(self): + * return "" % (self.base.__class__.__name__, # <<<<<<<<<<<<<< + * id(self)) + * + */ + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_1)) __PYX_ERR(0, 617, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_2)) __PYX_ERR(0, 617, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyString_Format(__pyx_kp_s_MemoryView_of_r_at_0x_x, __pyx_t_3); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":616 + * return 0 + * + * def __repr__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__, + * id(self)) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.__repr__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":620 + * id(self)) + * + * def __str__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__,) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview___str__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_memoryview___str__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__str__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_14__str__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_14__str__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__str__", 1); + + /* "View.MemoryView":621 + * + * def __str__(self): + * return "" % (self.base.__class__.__name__,) # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_base); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_class); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_name_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = PyTuple_New(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_t_1)) __PYX_ERR(0, 621, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_MemoryView_of_r_object, __pyx_t_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":620 + * id(self)) + * + * def __str__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__,) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.__str__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":624 + * + * + * def is_c_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_is_c_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_is_c_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("is_c_contig (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("is_c_contig", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "is_c_contig", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_16is_c_contig(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_16is_c_contig(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice *__pyx_v_mslice; + __Pyx_memviewslice __pyx_v_tmp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("is_c_contig", 1); + + /* "View.MemoryView":627 + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) # <<<<<<<<<<<<<< + * return slice_is_contig(mslice[0], 'C', self.view.ndim) + * + */ + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(__pyx_v_self, (&__pyx_v_tmp)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(0, 627, __pyx_L1_error) + __pyx_v_mslice = __pyx_t_1; + + /* "View.MemoryView":628 + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) + * return slice_is_contig(mslice[0], 'C', self.view.ndim) # <<<<<<<<<<<<<< + * + * def is_f_contig(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_memviewslice_is_contig((__pyx_v_mslice[0]), 'C', __pyx_v_self->view.ndim)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 628, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":624 + * + * + * def is_c_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.is_c_contig", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":630 + * return slice_is_contig(mslice[0], 'C', self.view.ndim) + * + * def is_f_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_is_f_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_is_f_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("is_f_contig (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("is_f_contig", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "is_f_contig", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_18is_f_contig(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_18is_f_contig(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice *__pyx_v_mslice; + __Pyx_memviewslice __pyx_v_tmp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("is_f_contig", 1); + + /* "View.MemoryView":633 + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) # <<<<<<<<<<<<<< + * return slice_is_contig(mslice[0], 'F', self.view.ndim) + * + */ + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(__pyx_v_self, (&__pyx_v_tmp)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(0, 633, __pyx_L1_error) + __pyx_v_mslice = __pyx_t_1; + + /* "View.MemoryView":634 + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) + * return slice_is_contig(mslice[0], 'F', self.view.ndim) # <<<<<<<<<<<<<< + * + * def copy(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_memviewslice_is_contig((__pyx_v_mslice[0]), 'F', __pyx_v_self->view.ndim)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 634, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":630 + * return slice_is_contig(mslice[0], 'C', self.view.ndim) + * + * def is_f_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.is_f_contig", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":636 + * return slice_is_contig(mslice[0], 'F', self.view.ndim) + * + * def copy(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice mslice + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_copy(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_copy(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("copy (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("copy", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "copy", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_20copy(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_20copy(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice __pyx_v_mslice; + int __pyx_v_flags; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("copy", 1); + + /* "View.MemoryView":638 + * def copy(self): + * cdef __Pyx_memviewslice mslice + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS # <<<<<<<<<<<<<< + * + * slice_copy(self, &mslice) + */ + __pyx_v_flags = (__pyx_v_self->flags & (~PyBUF_F_CONTIGUOUS)); + + /* "View.MemoryView":640 + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS + * + * slice_copy(self, &mslice) # <<<<<<<<<<<<<< + * mslice = slice_copy_contig(&mslice, "c", self.view.ndim, + * self.view.itemsize, + */ + __pyx_memoryview_slice_copy(__pyx_v_self, (&__pyx_v_mslice)); + + /* "View.MemoryView":641 + * + * slice_copy(self, &mslice) + * mslice = slice_copy_contig(&mslice, "c", self.view.ndim, # <<<<<<<<<<<<<< + * self.view.itemsize, + * flags|PyBUF_C_CONTIGUOUS, + */ + __pyx_t_1 = __pyx_memoryview_copy_new_contig((&__pyx_v_mslice), ((char *)"c"), __pyx_v_self->view.ndim, __pyx_v_self->view.itemsize, (__pyx_v_flags | PyBUF_C_CONTIGUOUS), __pyx_v_self->dtype_is_object); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 641, __pyx_L1_error) + __pyx_v_mslice = __pyx_t_1; + + /* "View.MemoryView":646 + * self.dtype_is_object) + * + * return memoryview_copy_from_slice(self, &mslice) # <<<<<<<<<<<<<< + * + * def copy_fortran(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_memoryview_copy_object_from_slice(__pyx_v_self, (&__pyx_v_mslice)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 646, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":636 + * return slice_is_contig(mslice[0], 'F', self.view.ndim) + * + * def copy(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice mslice + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.copy", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":648 + * return memoryview_copy_from_slice(self, &mslice) + * + * def copy_fortran(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice src, dst + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_copy_fortran(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_copy_fortran(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("copy_fortran (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("copy_fortran", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "copy_fortran", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_22copy_fortran(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_22copy_fortran(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice __pyx_v_src; + __Pyx_memviewslice __pyx_v_dst; + int __pyx_v_flags; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("copy_fortran", 1); + + /* "View.MemoryView":650 + * def copy_fortran(self): + * cdef __Pyx_memviewslice src, dst + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS # <<<<<<<<<<<<<< + * + * slice_copy(self, &src) + */ + __pyx_v_flags = (__pyx_v_self->flags & (~PyBUF_C_CONTIGUOUS)); + + /* "View.MemoryView":652 + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS + * + * slice_copy(self, &src) # <<<<<<<<<<<<<< + * dst = slice_copy_contig(&src, "fortran", self.view.ndim, + * self.view.itemsize, + */ + __pyx_memoryview_slice_copy(__pyx_v_self, (&__pyx_v_src)); + + /* "View.MemoryView":653 + * + * slice_copy(self, &src) + * dst = slice_copy_contig(&src, "fortran", self.view.ndim, # <<<<<<<<<<<<<< + * self.view.itemsize, + * flags|PyBUF_F_CONTIGUOUS, + */ + __pyx_t_1 = __pyx_memoryview_copy_new_contig((&__pyx_v_src), ((char *)"fortran"), __pyx_v_self->view.ndim, __pyx_v_self->view.itemsize, (__pyx_v_flags | PyBUF_F_CONTIGUOUS), __pyx_v_self->dtype_is_object); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 653, __pyx_L1_error) + __pyx_v_dst = __pyx_t_1; + + /* "View.MemoryView":658 + * self.dtype_is_object) + * + * return memoryview_copy_from_slice(self, &dst) # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_memoryview_copy_object_from_slice(__pyx_v_self, (&__pyx_v_dst)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 658, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":648 + * return memoryview_copy_from_slice(self, &mslice) + * + * def copy_fortran(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice src, dst + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.copy_fortran", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryview_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryview_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_memoryview___reduce_cython__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryview___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(0, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryview_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryview_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(0, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.memoryview.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_memoryview_2__setstate_cython__(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryview_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(0, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":662 + * + * @cname('__pyx_memoryview_new') + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): # <<<<<<<<<<<<<< + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo + */ + +static PyObject *__pyx_memoryview_new(PyObject *__pyx_v_o, int __pyx_v_flags, int __pyx_v_dtype_is_object, __Pyx_TypeInfo *__pyx_v_typeinfo) { + struct __pyx_memoryview_obj *__pyx_v_result = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_cwrapper", 1); + + /* "View.MemoryView":663 + * @cname('__pyx_memoryview_new') + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): + * cdef memoryview result = memoryview(o, flags, dtype_is_object) # <<<<<<<<<<<<<< + * result.typeinfo = typeinfo + * return result + */ + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_flags); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_v_dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_v_o); + __Pyx_GIVEREF(__pyx_v_o); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_v_o)) __PYX_ERR(0, 663, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1)) __PYX_ERR(0, 663, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_t_2)) __PYX_ERR(0, 663, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_Call(((PyObject *)__pyx_memoryview_type), __pyx_t_3, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_v_result = ((struct __pyx_memoryview_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":664 + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo # <<<<<<<<<<<<<< + * return result + * + */ + __pyx_v_result->typeinfo = __pyx_v_typeinfo; + + /* "View.MemoryView":665 + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo + * return result # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_check') + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = ((PyObject *)__pyx_v_result); + goto __pyx_L0; + + /* "View.MemoryView":662 + * + * @cname('__pyx_memoryview_new') + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): # <<<<<<<<<<<<<< + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview_cwrapper", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":668 + * + * @cname('__pyx_memoryview_check') + * cdef inline bint memoryview_check(object o) noexcept: # <<<<<<<<<<<<<< + * return isinstance(o, memoryview) + * + */ + +static CYTHON_INLINE int __pyx_memoryview_check(PyObject *__pyx_v_o) { + int __pyx_r; + int __pyx_t_1; + + /* "View.MemoryView":669 + * @cname('__pyx_memoryview_check') + * cdef inline bint memoryview_check(object o) noexcept: + * return isinstance(o, memoryview) # <<<<<<<<<<<<<< + * + * cdef tuple _unellipsify(object index, int ndim): + */ + __pyx_t_1 = __Pyx_TypeCheck(__pyx_v_o, __pyx_memoryview_type); + __pyx_r = __pyx_t_1; + goto __pyx_L0; + + /* "View.MemoryView":668 + * + * @cname('__pyx_memoryview_check') + * cdef inline bint memoryview_check(object o) noexcept: # <<<<<<<<<<<<<< + * return isinstance(o, memoryview) + * + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":671 + * return isinstance(o, memoryview) + * + * cdef tuple _unellipsify(object index, int ndim): # <<<<<<<<<<<<<< + * """ + * Replace all ellipses with full slices and fill incomplete indices with + */ + +static PyObject *_unellipsify(PyObject *__pyx_v_index, int __pyx_v_ndim) { + Py_ssize_t __pyx_v_idx; + PyObject *__pyx_v_tup = NULL; + PyObject *__pyx_v_result = NULL; + int __pyx_v_have_slices; + int __pyx_v_seen_ellipsis; + PyObject *__pyx_v_item = NULL; + Py_ssize_t __pyx_v_nslices; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + Py_ssize_t __pyx_t_4; + Py_ssize_t __pyx_t_5; + Py_UCS4 __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("_unellipsify", 1); + + /* "View.MemoryView":677 + * """ + * cdef Py_ssize_t idx + * tup = index if isinstance(index, tuple) else (index,) # <<<<<<<<<<<<<< + * + * result = [slice(None)] * ndim + */ + __pyx_t_2 = PyTuple_Check(__pyx_v_index); + if (__pyx_t_2) { + __Pyx_INCREF(((PyObject*)__pyx_v_index)); + __pyx_t_1 = __pyx_v_index; + } else { + __pyx_t_3 = PyTuple_New(1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 677, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_v_index); + __Pyx_GIVEREF(__pyx_v_index); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_v_index)) __PYX_ERR(0, 677, __pyx_L1_error); + __pyx_t_1 = __pyx_t_3; + __pyx_t_3 = 0; + } + __pyx_v_tup = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":679 + * tup = index if isinstance(index, tuple) else (index,) + * + * result = [slice(None)] * ndim # <<<<<<<<<<<<<< + * have_slices = False + * seen_ellipsis = False + */ + __pyx_t_1 = PyList_New(1 * ((__pyx_v_ndim<0) ? 0:__pyx_v_ndim)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 679, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + { Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < __pyx_v_ndim; __pyx_temp++) { + __Pyx_INCREF(__pyx_slice__5); + __Pyx_GIVEREF(__pyx_slice__5); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, __pyx_temp, __pyx_slice__5)) __PYX_ERR(0, 679, __pyx_L1_error); + } + } + __pyx_v_result = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":680 + * + * result = [slice(None)] * ndim + * have_slices = False # <<<<<<<<<<<<<< + * seen_ellipsis = False + * idx = 0 + */ + __pyx_v_have_slices = 0; + + /* "View.MemoryView":681 + * result = [slice(None)] * ndim + * have_slices = False + * seen_ellipsis = False # <<<<<<<<<<<<<< + * idx = 0 + * for item in tup: + */ + __pyx_v_seen_ellipsis = 0; + + /* "View.MemoryView":682 + * have_slices = False + * seen_ellipsis = False + * idx = 0 # <<<<<<<<<<<<<< + * for item in tup: + * if item is Ellipsis: + */ + __pyx_v_idx = 0; + + /* "View.MemoryView":683 + * seen_ellipsis = False + * idx = 0 + * for item in tup: # <<<<<<<<<<<<<< + * if item is Ellipsis: + * if not seen_ellipsis: + */ + if (unlikely(__pyx_v_tup == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not iterable"); + __PYX_ERR(0, 683, __pyx_L1_error) + } + __pyx_t_1 = __pyx_v_tup; __Pyx_INCREF(__pyx_t_1); + __pyx_t_4 = 0; + for (;;) { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_1); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 683, __pyx_L1_error) + #endif + if (__pyx_t_4 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_3 = PyTuple_GET_ITEM(__pyx_t_1, __pyx_t_4); __Pyx_INCREF(__pyx_t_3); __pyx_t_4++; if (unlikely((0 < 0))) __PYX_ERR(0, 683, __pyx_L1_error) + #else + __pyx_t_3 = __Pyx_PySequence_ITEM(__pyx_t_1, __pyx_t_4); __pyx_t_4++; if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 683, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + #endif + __Pyx_XDECREF_SET(__pyx_v_item, __pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":684 + * idx = 0 + * for item in tup: + * if item is Ellipsis: # <<<<<<<<<<<<<< + * if not seen_ellipsis: + * idx += ndim - len(tup) + */ + __pyx_t_2 = (__pyx_v_item == __pyx_builtin_Ellipsis); + if (__pyx_t_2) { + + /* "View.MemoryView":685 + * for item in tup: + * if item is Ellipsis: + * if not seen_ellipsis: # <<<<<<<<<<<<<< + * idx += ndim - len(tup) + * seen_ellipsis = True + */ + __pyx_t_2 = (!__pyx_v_seen_ellipsis); + if (__pyx_t_2) { + + /* "View.MemoryView":686 + * if item is Ellipsis: + * if not seen_ellipsis: + * idx += ndim - len(tup) # <<<<<<<<<<<<<< + * seen_ellipsis = True + * have_slices = True + */ + if (unlikely(__pyx_v_tup == Py_None)) { + PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); + __PYX_ERR(0, 686, __pyx_L1_error) + } + __pyx_t_5 = __Pyx_PyTuple_GET_SIZE(__pyx_v_tup); if (unlikely(__pyx_t_5 == ((Py_ssize_t)-1))) __PYX_ERR(0, 686, __pyx_L1_error) + __pyx_v_idx = (__pyx_v_idx + (__pyx_v_ndim - __pyx_t_5)); + + /* "View.MemoryView":687 + * if not seen_ellipsis: + * idx += ndim - len(tup) + * seen_ellipsis = True # <<<<<<<<<<<<<< + * have_slices = True + * else: + */ + __pyx_v_seen_ellipsis = 1; + + /* "View.MemoryView":685 + * for item in tup: + * if item is Ellipsis: + * if not seen_ellipsis: # <<<<<<<<<<<<<< + * idx += ndim - len(tup) + * seen_ellipsis = True + */ + } + + /* "View.MemoryView":688 + * idx += ndim - len(tup) + * seen_ellipsis = True + * have_slices = True # <<<<<<<<<<<<<< + * else: + * if isinstance(item, slice): + */ + __pyx_v_have_slices = 1; + + /* "View.MemoryView":684 + * idx = 0 + * for item in tup: + * if item is Ellipsis: # <<<<<<<<<<<<<< + * if not seen_ellipsis: + * idx += ndim - len(tup) + */ + goto __pyx_L5; + } + + /* "View.MemoryView":690 + * have_slices = True + * else: + * if isinstance(item, slice): # <<<<<<<<<<<<<< + * have_slices = True + * elif not PyIndex_Check(item): + */ + /*else*/ { + __pyx_t_2 = PySlice_Check(__pyx_v_item); + if (__pyx_t_2) { + + /* "View.MemoryView":691 + * else: + * if isinstance(item, slice): + * have_slices = True # <<<<<<<<<<<<<< + * elif not PyIndex_Check(item): + * raise TypeError, f"Cannot index with type '{type(item)}'" + */ + __pyx_v_have_slices = 1; + + /* "View.MemoryView":690 + * have_slices = True + * else: + * if isinstance(item, slice): # <<<<<<<<<<<<<< + * have_slices = True + * elif not PyIndex_Check(item): + */ + goto __pyx_L7; + } + + /* "View.MemoryView":692 + * if isinstance(item, slice): + * have_slices = True + * elif not PyIndex_Check(item): # <<<<<<<<<<<<<< + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item + */ + __pyx_t_2 = (!(PyIndex_Check(__pyx_v_item) != 0)); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":693 + * have_slices = True + * elif not PyIndex_Check(item): + * raise TypeError, f"Cannot index with type '{type(item)}'" # <<<<<<<<<<<<<< + * result[idx] = item + * idx += 1 + */ + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 693, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = 0; + __pyx_t_6 = 127; + __Pyx_INCREF(__pyx_kp_u_Cannot_index_with_type); + __pyx_t_5 += 24; + __Pyx_GIVEREF(__pyx_kp_u_Cannot_index_with_type); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_kp_u_Cannot_index_with_type); + __pyx_t_7 = __Pyx_PyObject_FormatSimple(((PyObject *)Py_TYPE(__pyx_v_item)), __pyx_empty_unicode); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 693, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_7) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_7) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_7); + __pyx_t_7 = 0; + __Pyx_INCREF(__pyx_kp_u__6); + __pyx_t_5 += 1; + __Pyx_GIVEREF(__pyx_kp_u__6); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_kp_u__6); + __pyx_t_7 = __Pyx_PyUnicode_Join(__pyx_t_3, 3, __pyx_t_5, __pyx_t_6); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 693, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_t_7, 0, 0); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __PYX_ERR(0, 693, __pyx_L1_error) + + /* "View.MemoryView":692 + * if isinstance(item, slice): + * have_slices = True + * elif not PyIndex_Check(item): # <<<<<<<<<<<<<< + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item + */ + } + __pyx_L7:; + + /* "View.MemoryView":694 + * elif not PyIndex_Check(item): + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item # <<<<<<<<<<<<<< + * idx += 1 + * + */ + if (unlikely((__Pyx_SetItemInt(__pyx_v_result, __pyx_v_idx, __pyx_v_item, Py_ssize_t, 1, PyInt_FromSsize_t, 1, 1, 1) < 0))) __PYX_ERR(0, 694, __pyx_L1_error) + } + __pyx_L5:; + + /* "View.MemoryView":695 + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item + * idx += 1 # <<<<<<<<<<<<<< + * + * nslices = ndim - idx + */ + __pyx_v_idx = (__pyx_v_idx + 1); + + /* "View.MemoryView":683 + * seen_ellipsis = False + * idx = 0 + * for item in tup: # <<<<<<<<<<<<<< + * if item is Ellipsis: + * if not seen_ellipsis: + */ + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "View.MemoryView":697 + * idx += 1 + * + * nslices = ndim - idx # <<<<<<<<<<<<<< + * return have_slices or nslices, tuple(result) + * + */ + __pyx_v_nslices = (__pyx_v_ndim - __pyx_v_idx); + + /* "View.MemoryView":698 + * + * nslices = ndim - idx + * return have_slices or nslices, tuple(result) # <<<<<<<<<<<<<< + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + */ + __Pyx_XDECREF(__pyx_r); + if (!__pyx_v_have_slices) { + } else { + __pyx_t_7 = __Pyx_PyBool_FromLong(__pyx_v_have_slices); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_1 = __pyx_t_7; + __pyx_t_7 = 0; + goto __pyx_L9_bool_binop_done; + } + __pyx_t_7 = PyInt_FromSsize_t(__pyx_v_nslices); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_1 = __pyx_t_7; + __pyx_t_7 = 0; + __pyx_L9_bool_binop_done:; + __pyx_t_7 = PyList_AsTuple(__pyx_v_result); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_1)) __PYX_ERR(0, 698, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_7); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_7)) __PYX_ERR(0, 698, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_7 = 0; + __pyx_r = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; + goto __pyx_L0; + + /* "View.MemoryView":671 + * return isinstance(o, memoryview) + * + * cdef tuple _unellipsify(object index, int ndim): # <<<<<<<<<<<<<< + * """ + * Replace all ellipses with full slices and fill incomplete indices with + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("View.MemoryView._unellipsify", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_tup); + __Pyx_XDECREF(__pyx_v_result); + __Pyx_XDECREF(__pyx_v_item); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":700 + * return have_slices or nslices, tuple(result) + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: # <<<<<<<<<<<<<< + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: + */ + +static int assert_direct_dimensions(Py_ssize_t *__pyx_v_suboffsets, int __pyx_v_ndim) { + Py_ssize_t __pyx_v_suboffset; + int __pyx_r; + Py_ssize_t *__pyx_t_1; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + int __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + + /* "View.MemoryView":701 + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + * for suboffset in suboffsets[:ndim]: # <<<<<<<<<<<<<< + * if suboffset >= 0: + * raise ValueError, "Indirect dimensions not supported" + */ + __pyx_t_2 = (__pyx_v_suboffsets + __pyx_v_ndim); + for (__pyx_t_3 = __pyx_v_suboffsets; __pyx_t_3 < __pyx_t_2; __pyx_t_3++) { + __pyx_t_1 = __pyx_t_3; + __pyx_v_suboffset = (__pyx_t_1[0]); + + /* "View.MemoryView":702 + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * raise ValueError, "Indirect dimensions not supported" + * return 0 # return type just used as an error flag + */ + __pyx_t_4 = (__pyx_v_suboffset >= 0); + if (unlikely(__pyx_t_4)) { + + /* "View.MemoryView":703 + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: + * raise ValueError, "Indirect dimensions not supported" # <<<<<<<<<<<<<< + * return 0 # return type just used as an error flag + * + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Indirect_dimensions_not_supporte, 0, 0); + __PYX_ERR(0, 703, __pyx_L1_error) + + /* "View.MemoryView":702 + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * raise ValueError, "Indirect dimensions not supported" + * return 0 # return type just used as an error flag + */ + } + } + + /* "View.MemoryView":704 + * if suboffset >= 0: + * raise ValueError, "Indirect dimensions not supported" + * return 0 # return type just used as an error flag # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":700 + * return have_slices or nslices, tuple(result) + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: # <<<<<<<<<<<<<< + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.assert_direct_dimensions", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":711 + * + * @cname('__pyx_memview_slice') + * cdef memoryview memview_slice(memoryview memview, object indices): # <<<<<<<<<<<<<< + * cdef int new_ndim = 0, suboffset_dim = -1, dim + * cdef bint negative_step + */ + +static struct __pyx_memoryview_obj *__pyx_memview_slice(struct __pyx_memoryview_obj *__pyx_v_memview, PyObject *__pyx_v_indices) { + int __pyx_v_new_ndim; + int __pyx_v_suboffset_dim; + int __pyx_v_dim; + __Pyx_memviewslice __pyx_v_src; + __Pyx_memviewslice __pyx_v_dst; + __Pyx_memviewslice *__pyx_v_p_src; + struct __pyx_memoryviewslice_obj *__pyx_v_memviewsliceobj = 0; + __Pyx_memviewslice *__pyx_v_p_dst; + int *__pyx_v_p_suboffset_dim; + Py_ssize_t __pyx_v_start; + Py_ssize_t __pyx_v_stop; + Py_ssize_t __pyx_v_step; + Py_ssize_t __pyx_v_cindex; + int __pyx_v_have_start; + int __pyx_v_have_stop; + int __pyx_v_have_step; + PyObject *__pyx_v_index = NULL; + struct __pyx_memoryview_obj *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + struct __pyx_memoryview_obj *__pyx_t_3; + char *__pyx_t_4; + int __pyx_t_5; + Py_ssize_t __pyx_t_6; + PyObject *(*__pyx_t_7)(PyObject *); + PyObject *__pyx_t_8 = NULL; + Py_ssize_t __pyx_t_9; + int __pyx_t_10; + Py_ssize_t __pyx_t_11; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memview_slice", 1); + + /* "View.MemoryView":712 + * @cname('__pyx_memview_slice') + * cdef memoryview memview_slice(memoryview memview, object indices): + * cdef int new_ndim = 0, suboffset_dim = -1, dim # <<<<<<<<<<<<<< + * cdef bint negative_step + * cdef __Pyx_memviewslice src, dst + */ + __pyx_v_new_ndim = 0; + __pyx_v_suboffset_dim = -1; + + /* "View.MemoryView":719 + * + * + * memset(&dst, 0, sizeof(dst)) # <<<<<<<<<<<<<< + * + * cdef _memoryviewslice memviewsliceobj + */ + (void)(memset((&__pyx_v_dst), 0, (sizeof(__pyx_v_dst)))); + + /* "View.MemoryView":723 + * cdef _memoryviewslice memviewsliceobj + * + * assert memview.view.ndim > 0 # <<<<<<<<<<<<<< + * + * if isinstance(memview, _memoryviewslice): + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_1 = (__pyx_v_memview->view.ndim > 0); + if (unlikely(!__pyx_t_1)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(0, 723, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(0, 723, __pyx_L1_error) + #endif + + /* "View.MemoryView":725 + * assert memview.view.ndim > 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * memviewsliceobj = memview + * p_src = &memviewsliceobj.from_slice + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":726 + * + * if isinstance(memview, _memoryviewslice): + * memviewsliceobj = memview # <<<<<<<<<<<<<< + * p_src = &memviewsliceobj.from_slice + * else: + */ + if (!(likely(((((PyObject *)__pyx_v_memview)) == Py_None) || likely(__Pyx_TypeTest(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type))))) __PYX_ERR(0, 726, __pyx_L1_error) + __pyx_t_2 = ((PyObject *)__pyx_v_memview); + __Pyx_INCREF(__pyx_t_2); + __pyx_v_memviewsliceobj = ((struct __pyx_memoryviewslice_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":727 + * if isinstance(memview, _memoryviewslice): + * memviewsliceobj = memview + * p_src = &memviewsliceobj.from_slice # <<<<<<<<<<<<<< + * else: + * slice_copy(memview, &src) + */ + __pyx_v_p_src = (&__pyx_v_memviewsliceobj->from_slice); + + /* "View.MemoryView":725 + * assert memview.view.ndim > 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * memviewsliceobj = memview + * p_src = &memviewsliceobj.from_slice + */ + goto __pyx_L3; + } + + /* "View.MemoryView":729 + * p_src = &memviewsliceobj.from_slice + * else: + * slice_copy(memview, &src) # <<<<<<<<<<<<<< + * p_src = &src + * + */ + /*else*/ { + __pyx_memoryview_slice_copy(__pyx_v_memview, (&__pyx_v_src)); + + /* "View.MemoryView":730 + * else: + * slice_copy(memview, &src) + * p_src = &src # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_p_src = (&__pyx_v_src); + } + __pyx_L3:; + + /* "View.MemoryView":736 + * + * + * dst.memview = p_src.memview # <<<<<<<<<<<<<< + * dst.data = p_src.data + * + */ + __pyx_t_3 = __pyx_v_p_src->memview; + __pyx_v_dst.memview = __pyx_t_3; + + /* "View.MemoryView":737 + * + * dst.memview = p_src.memview + * dst.data = p_src.data # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_4 = __pyx_v_p_src->data; + __pyx_v_dst.data = __pyx_t_4; + + /* "View.MemoryView":742 + * + * + * cdef __Pyx_memviewslice *p_dst = &dst # <<<<<<<<<<<<<< + * cdef int *p_suboffset_dim = &suboffset_dim + * cdef Py_ssize_t start, stop, step, cindex + */ + __pyx_v_p_dst = (&__pyx_v_dst); + + /* "View.MemoryView":743 + * + * cdef __Pyx_memviewslice *p_dst = &dst + * cdef int *p_suboffset_dim = &suboffset_dim # <<<<<<<<<<<<<< + * cdef Py_ssize_t start, stop, step, cindex + * cdef bint have_start, have_stop, have_step + */ + __pyx_v_p_suboffset_dim = (&__pyx_v_suboffset_dim); + + /* "View.MemoryView":747 + * cdef bint have_start, have_stop, have_step + * + * for dim, index in enumerate(indices): # <<<<<<<<<<<<<< + * if PyIndex_Check(index): + * cindex = index + */ + __pyx_t_5 = 0; + if (likely(PyList_CheckExact(__pyx_v_indices)) || PyTuple_CheckExact(__pyx_v_indices)) { + __pyx_t_2 = __pyx_v_indices; __Pyx_INCREF(__pyx_t_2); + __pyx_t_6 = 0; + __pyx_t_7 = NULL; + } else { + __pyx_t_6 = -1; __pyx_t_2 = PyObject_GetIter(__pyx_v_indices); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 747, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_7 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_2); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 747, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_7)) { + if (likely(PyList_CheckExact(__pyx_t_2))) { + { + Py_ssize_t __pyx_temp = __Pyx_PyList_GET_SIZE(__pyx_t_2); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 747, __pyx_L1_error) + #endif + if (__pyx_t_6 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_8 = PyList_GET_ITEM(__pyx_t_2, __pyx_t_6); __Pyx_INCREF(__pyx_t_8); __pyx_t_6++; if (unlikely((0 < 0))) __PYX_ERR(0, 747, __pyx_L1_error) + #else + __pyx_t_8 = __Pyx_PySequence_ITEM(__pyx_t_2, __pyx_t_6); __pyx_t_6++; if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 747, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + #endif + } else { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_2); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 747, __pyx_L1_error) + #endif + if (__pyx_t_6 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_8 = PyTuple_GET_ITEM(__pyx_t_2, __pyx_t_6); __Pyx_INCREF(__pyx_t_8); __pyx_t_6++; if (unlikely((0 < 0))) __PYX_ERR(0, 747, __pyx_L1_error) + #else + __pyx_t_8 = __Pyx_PySequence_ITEM(__pyx_t_2, __pyx_t_6); __pyx_t_6++; if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 747, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + #endif + } + } else { + __pyx_t_8 = __pyx_t_7(__pyx_t_2); + if (unlikely(!__pyx_t_8)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(0, 747, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_8); + } + __Pyx_XDECREF_SET(__pyx_v_index, __pyx_t_8); + __pyx_t_8 = 0; + __pyx_v_dim = __pyx_t_5; + __pyx_t_5 = (__pyx_t_5 + 1); + + /* "View.MemoryView":748 + * + * for dim, index in enumerate(indices): + * if PyIndex_Check(index): # <<<<<<<<<<<<<< + * cindex = index + * slice_memviewslice( + */ + __pyx_t_1 = (PyIndex_Check(__pyx_v_index) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":749 + * for dim, index in enumerate(indices): + * if PyIndex_Check(index): + * cindex = index # <<<<<<<<<<<<<< + * slice_memviewslice( + * p_dst, p_src.shape[dim], p_src.strides[dim], p_src.suboffsets[dim], + */ + __pyx_t_9 = __Pyx_PyIndex_AsSsize_t(__pyx_v_index); if (unlikely((__pyx_t_9 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 749, __pyx_L1_error) + __pyx_v_cindex = __pyx_t_9; + + /* "View.MemoryView":750 + * if PyIndex_Check(index): + * cindex = index + * slice_memviewslice( # <<<<<<<<<<<<<< + * p_dst, p_src.shape[dim], p_src.strides[dim], p_src.suboffsets[dim], + * dim, new_ndim, p_suboffset_dim, + */ + __pyx_t_10 = __pyx_memoryview_slice_memviewslice(__pyx_v_p_dst, (__pyx_v_p_src->shape[__pyx_v_dim]), (__pyx_v_p_src->strides[__pyx_v_dim]), (__pyx_v_p_src->suboffsets[__pyx_v_dim]), __pyx_v_dim, __pyx_v_new_ndim, __pyx_v_p_suboffset_dim, __pyx_v_cindex, 0, 0, 0, 0, 0, 0); if (unlikely(__pyx_t_10 == ((int)-1))) __PYX_ERR(0, 750, __pyx_L1_error) + + /* "View.MemoryView":748 + * + * for dim, index in enumerate(indices): + * if PyIndex_Check(index): # <<<<<<<<<<<<<< + * cindex = index + * slice_memviewslice( + */ + goto __pyx_L6; + } + + /* "View.MemoryView":756 + * 0, 0, 0, # have_{start,stop,step} + * False) + * elif index is None: # <<<<<<<<<<<<<< + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 + */ + __pyx_t_1 = (__pyx_v_index == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":757 + * False) + * elif index is None: + * p_dst.shape[new_ndim] = 1 # <<<<<<<<<<<<<< + * p_dst.strides[new_ndim] = 0 + * p_dst.suboffsets[new_ndim] = -1 + */ + (__pyx_v_p_dst->shape[__pyx_v_new_ndim]) = 1; + + /* "View.MemoryView":758 + * elif index is None: + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 # <<<<<<<<<<<<<< + * p_dst.suboffsets[new_ndim] = -1 + * new_ndim += 1 + */ + (__pyx_v_p_dst->strides[__pyx_v_new_ndim]) = 0; + + /* "View.MemoryView":759 + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 + * p_dst.suboffsets[new_ndim] = -1 # <<<<<<<<<<<<<< + * new_ndim += 1 + * else: + */ + (__pyx_v_p_dst->suboffsets[__pyx_v_new_ndim]) = -1L; + + /* "View.MemoryView":760 + * p_dst.strides[new_ndim] = 0 + * p_dst.suboffsets[new_ndim] = -1 + * new_ndim += 1 # <<<<<<<<<<<<<< + * else: + * start = index.start or 0 + */ + __pyx_v_new_ndim = (__pyx_v_new_ndim + 1); + + /* "View.MemoryView":756 + * 0, 0, 0, # have_{start,stop,step} + * False) + * elif index is None: # <<<<<<<<<<<<<< + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 + */ + goto __pyx_L6; + } + + /* "View.MemoryView":762 + * new_ndim += 1 + * else: + * start = index.start or 0 # <<<<<<<<<<<<<< + * stop = index.stop or 0 + * step = index.step or 0 + */ + /*else*/ { + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_start); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 762, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_t_8); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(0, 762, __pyx_L1_error) + if (!__pyx_t_1) { + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } else { + __pyx_t_11 = __Pyx_PyIndex_AsSsize_t(__pyx_t_8); if (unlikely((__pyx_t_11 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 762, __pyx_L1_error) + __pyx_t_9 = __pyx_t_11; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L7_bool_binop_done; + } + __pyx_t_9 = 0; + __pyx_L7_bool_binop_done:; + __pyx_v_start = __pyx_t_9; + + /* "View.MemoryView":763 + * else: + * start = index.start or 0 + * stop = index.stop or 0 # <<<<<<<<<<<<<< + * step = index.step or 0 + * + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_stop); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 763, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_t_8); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(0, 763, __pyx_L1_error) + if (!__pyx_t_1) { + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } else { + __pyx_t_11 = __Pyx_PyIndex_AsSsize_t(__pyx_t_8); if (unlikely((__pyx_t_11 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 763, __pyx_L1_error) + __pyx_t_9 = __pyx_t_11; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L9_bool_binop_done; + } + __pyx_t_9 = 0; + __pyx_L9_bool_binop_done:; + __pyx_v_stop = __pyx_t_9; + + /* "View.MemoryView":764 + * start = index.start or 0 + * stop = index.stop or 0 + * step = index.step or 0 # <<<<<<<<<<<<<< + * + * have_start = index.start is not None + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_step); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 764, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_t_8); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(0, 764, __pyx_L1_error) + if (!__pyx_t_1) { + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } else { + __pyx_t_11 = __Pyx_PyIndex_AsSsize_t(__pyx_t_8); if (unlikely((__pyx_t_11 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 764, __pyx_L1_error) + __pyx_t_9 = __pyx_t_11; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L11_bool_binop_done; + } + __pyx_t_9 = 0; + __pyx_L11_bool_binop_done:; + __pyx_v_step = __pyx_t_9; + + /* "View.MemoryView":766 + * step = index.step or 0 + * + * have_start = index.start is not None # <<<<<<<<<<<<<< + * have_stop = index.stop is not None + * have_step = index.step is not None + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_start); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 766, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = (__pyx_t_8 != Py_None); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_v_have_start = __pyx_t_1; + + /* "View.MemoryView":767 + * + * have_start = index.start is not None + * have_stop = index.stop is not None # <<<<<<<<<<<<<< + * have_step = index.step is not None + * + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_stop); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 767, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = (__pyx_t_8 != Py_None); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_v_have_stop = __pyx_t_1; + + /* "View.MemoryView":768 + * have_start = index.start is not None + * have_stop = index.stop is not None + * have_step = index.step is not None # <<<<<<<<<<<<<< + * + * slice_memviewslice( + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_step); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 768, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = (__pyx_t_8 != Py_None); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_v_have_step = __pyx_t_1; + + /* "View.MemoryView":770 + * have_step = index.step is not None + * + * slice_memviewslice( # <<<<<<<<<<<<<< + * p_dst, p_src.shape[dim], p_src.strides[dim], p_src.suboffsets[dim], + * dim, new_ndim, p_suboffset_dim, + */ + __pyx_t_10 = __pyx_memoryview_slice_memviewslice(__pyx_v_p_dst, (__pyx_v_p_src->shape[__pyx_v_dim]), (__pyx_v_p_src->strides[__pyx_v_dim]), (__pyx_v_p_src->suboffsets[__pyx_v_dim]), __pyx_v_dim, __pyx_v_new_ndim, __pyx_v_p_suboffset_dim, __pyx_v_start, __pyx_v_stop, __pyx_v_step, __pyx_v_have_start, __pyx_v_have_stop, __pyx_v_have_step, 1); if (unlikely(__pyx_t_10 == ((int)-1))) __PYX_ERR(0, 770, __pyx_L1_error) + + /* "View.MemoryView":776 + * have_start, have_stop, have_step, + * True) + * new_ndim += 1 # <<<<<<<<<<<<<< + * + * if isinstance(memview, _memoryviewslice): + */ + __pyx_v_new_ndim = (__pyx_v_new_ndim + 1); + } + __pyx_L6:; + + /* "View.MemoryView":747 + * cdef bint have_start, have_stop, have_step + * + * for dim, index in enumerate(indices): # <<<<<<<<<<<<<< + * if PyIndex_Check(index): + * cindex = index + */ + } + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":778 + * new_ndim += 1 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":779 + * + * if isinstance(memview, _memoryviewslice): + * return memoryview_fromslice(dst, new_ndim, # <<<<<<<<<<<<<< + * memviewsliceobj.to_object_func, + * memviewsliceobj.to_dtype_func, + */ + __Pyx_XDECREF((PyObject *)__pyx_r); + + /* "View.MemoryView":780 + * if isinstance(memview, _memoryviewslice): + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, # <<<<<<<<<<<<<< + * memviewsliceobj.to_dtype_func, + * memview.dtype_is_object) + */ + if (unlikely(!__pyx_v_memviewsliceobj)) { __Pyx_RaiseUnboundLocalError("memviewsliceobj"); __PYX_ERR(0, 780, __pyx_L1_error) } + + /* "View.MemoryView":781 + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, + * memviewsliceobj.to_dtype_func, # <<<<<<<<<<<<<< + * memview.dtype_is_object) + * else: + */ + if (unlikely(!__pyx_v_memviewsliceobj)) { __Pyx_RaiseUnboundLocalError("memviewsliceobj"); __PYX_ERR(0, 781, __pyx_L1_error) } + + /* "View.MemoryView":779 + * + * if isinstance(memview, _memoryviewslice): + * return memoryview_fromslice(dst, new_ndim, # <<<<<<<<<<<<<< + * memviewsliceobj.to_object_func, + * memviewsliceobj.to_dtype_func, + */ + __pyx_t_2 = __pyx_memoryview_fromslice(__pyx_v_dst, __pyx_v_new_ndim, __pyx_v_memviewsliceobj->to_object_func, __pyx_v_memviewsliceobj->to_dtype_func, __pyx_v_memview->dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 779, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (!(likely(((__pyx_t_2) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_2, __pyx_memoryview_type))))) __PYX_ERR(0, 779, __pyx_L1_error) + __pyx_r = ((struct __pyx_memoryview_obj *)__pyx_t_2); + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":778 + * new_ndim += 1 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, + */ + } + + /* "View.MemoryView":784 + * memview.dtype_is_object) + * else: + * return memoryview_fromslice(dst, new_ndim, NULL, NULL, # <<<<<<<<<<<<<< + * memview.dtype_is_object) + * + */ + /*else*/ { + __Pyx_XDECREF((PyObject *)__pyx_r); + + /* "View.MemoryView":785 + * else: + * return memoryview_fromslice(dst, new_ndim, NULL, NULL, + * memview.dtype_is_object) # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = __pyx_memoryview_fromslice(__pyx_v_dst, __pyx_v_new_ndim, NULL, NULL, __pyx_v_memview->dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 784, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + + /* "View.MemoryView":784 + * memview.dtype_is_object) + * else: + * return memoryview_fromslice(dst, new_ndim, NULL, NULL, # <<<<<<<<<<<<<< + * memview.dtype_is_object) + * + */ + if (!(likely(((__pyx_t_2) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_2, __pyx_memoryview_type))))) __PYX_ERR(0, 784, __pyx_L1_error) + __pyx_r = ((struct __pyx_memoryview_obj *)__pyx_t_2); + __pyx_t_2 = 0; + goto __pyx_L0; + } + + /* "View.MemoryView":711 + * + * @cname('__pyx_memview_slice') + * cdef memoryview memview_slice(memoryview memview, object indices): # <<<<<<<<<<<<<< + * cdef int new_ndim = 0, suboffset_dim = -1, dim + * cdef bint negative_step + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("View.MemoryView.memview_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_memviewsliceobj); + __Pyx_XDECREF(__pyx_v_index); + __Pyx_XGIVEREF((PyObject *)__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":793 + * + * @cname('__pyx_memoryview_slice_memviewslice') + * cdef int slice_memviewslice( # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * Py_ssize_t shape, Py_ssize_t stride, Py_ssize_t suboffset, + */ + +static int __pyx_memoryview_slice_memviewslice(__Pyx_memviewslice *__pyx_v_dst, Py_ssize_t __pyx_v_shape, Py_ssize_t __pyx_v_stride, Py_ssize_t __pyx_v_suboffset, int __pyx_v_dim, int __pyx_v_new_ndim, int *__pyx_v_suboffset_dim, Py_ssize_t __pyx_v_start, Py_ssize_t __pyx_v_stop, Py_ssize_t __pyx_v_step, int __pyx_v_have_start, int __pyx_v_have_stop, int __pyx_v_have_step, int __pyx_v_is_slice) { + Py_ssize_t __pyx_v_new_shape; + int __pyx_v_negative_step; + int __pyx_r; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":813 + * cdef bint negative_step + * + * if not is_slice: # <<<<<<<<<<<<<< + * + * if start < 0: + */ + __pyx_t_1 = (!__pyx_v_is_slice); + if (__pyx_t_1) { + + /* "View.MemoryView":815 + * if not is_slice: + * + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if not 0 <= start < shape: + */ + __pyx_t_1 = (__pyx_v_start < 0); + if (__pyx_t_1) { + + /* "View.MemoryView":816 + * + * if start < 0: + * start += shape # <<<<<<<<<<<<<< + * if not 0 <= start < shape: + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) + */ + __pyx_v_start = (__pyx_v_start + __pyx_v_shape); + + /* "View.MemoryView":815 + * if not is_slice: + * + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if not 0 <= start < shape: + */ + } + + /* "View.MemoryView":817 + * if start < 0: + * start += shape + * if not 0 <= start < shape: # <<<<<<<<<<<<<< + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) + * else: + */ + __pyx_t_1 = (0 <= __pyx_v_start); + if (__pyx_t_1) { + __pyx_t_1 = (__pyx_v_start < __pyx_v_shape); + } + __pyx_t_2 = (!__pyx_t_1); + if (__pyx_t_2) { + + /* "View.MemoryView":818 + * start += shape + * if not 0 <= start < shape: + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) # <<<<<<<<<<<<<< + * else: + * + */ + __pyx_t_3 = __pyx_memoryview_err_dim(PyExc_IndexError, __pyx_kp_s_Index_out_of_bounds_axis_d, __pyx_v_dim); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(0, 818, __pyx_L1_error) + + /* "View.MemoryView":817 + * if start < 0: + * start += shape + * if not 0 <= start < shape: # <<<<<<<<<<<<<< + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) + * else: + */ + } + + /* "View.MemoryView":813 + * cdef bint negative_step + * + * if not is_slice: # <<<<<<<<<<<<<< + * + * if start < 0: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":821 + * else: + * + * if have_step: # <<<<<<<<<<<<<< + * negative_step = step < 0 + * if step == 0: + */ + /*else*/ { + __pyx_t_2 = (__pyx_v_have_step != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":822 + * + * if have_step: + * negative_step = step < 0 # <<<<<<<<<<<<<< + * if step == 0: + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + */ + __pyx_v_negative_step = (__pyx_v_step < 0); + + /* "View.MemoryView":823 + * if have_step: + * negative_step = step < 0 + * if step == 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + * else: + */ + __pyx_t_2 = (__pyx_v_step == 0); + if (__pyx_t_2) { + + /* "View.MemoryView":824 + * negative_step = step < 0 + * if step == 0: + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) # <<<<<<<<<<<<<< + * else: + * negative_step = False + */ + __pyx_t_3 = __pyx_memoryview_err_dim(PyExc_ValueError, __pyx_kp_s_Step_may_not_be_zero_axis_d, __pyx_v_dim); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(0, 824, __pyx_L1_error) + + /* "View.MemoryView":823 + * if have_step: + * negative_step = step < 0 + * if step == 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + * else: + */ + } + + /* "View.MemoryView":821 + * else: + * + * if have_step: # <<<<<<<<<<<<<< + * negative_step = step < 0 + * if step == 0: + */ + goto __pyx_L6; + } + + /* "View.MemoryView":826 + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + * else: + * negative_step = False # <<<<<<<<<<<<<< + * step = 1 + * + */ + /*else*/ { + __pyx_v_negative_step = 0; + + /* "View.MemoryView":827 + * else: + * negative_step = False + * step = 1 # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_step = 1; + } + __pyx_L6:; + + /* "View.MemoryView":830 + * + * + * if have_start: # <<<<<<<<<<<<<< + * if start < 0: + * start += shape + */ + __pyx_t_2 = (__pyx_v_have_start != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":831 + * + * if have_start: + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if start < 0: + */ + __pyx_t_2 = (__pyx_v_start < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":832 + * if have_start: + * if start < 0: + * start += shape # <<<<<<<<<<<<<< + * if start < 0: + * start = 0 + */ + __pyx_v_start = (__pyx_v_start + __pyx_v_shape); + + /* "View.MemoryView":833 + * if start < 0: + * start += shape + * if start < 0: # <<<<<<<<<<<<<< + * start = 0 + * elif start >= shape: + */ + __pyx_t_2 = (__pyx_v_start < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":834 + * start += shape + * if start < 0: + * start = 0 # <<<<<<<<<<<<<< + * elif start >= shape: + * if negative_step: + */ + __pyx_v_start = 0; + + /* "View.MemoryView":833 + * if start < 0: + * start += shape + * if start < 0: # <<<<<<<<<<<<<< + * start = 0 + * elif start >= shape: + */ + } + + /* "View.MemoryView":831 + * + * if have_start: + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if start < 0: + */ + goto __pyx_L9; + } + + /* "View.MemoryView":835 + * if start < 0: + * start = 0 + * elif start >= shape: # <<<<<<<<<<<<<< + * if negative_step: + * start = shape - 1 + */ + __pyx_t_2 = (__pyx_v_start >= __pyx_v_shape); + if (__pyx_t_2) { + + /* "View.MemoryView":836 + * start = 0 + * elif start >= shape: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + if (__pyx_v_negative_step) { + + /* "View.MemoryView":837 + * elif start >= shape: + * if negative_step: + * start = shape - 1 # <<<<<<<<<<<<<< + * else: + * start = shape + */ + __pyx_v_start = (__pyx_v_shape - 1); + + /* "View.MemoryView":836 + * start = 0 + * elif start >= shape: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + goto __pyx_L11; + } + + /* "View.MemoryView":839 + * start = shape - 1 + * else: + * start = shape # <<<<<<<<<<<<<< + * else: + * if negative_step: + */ + /*else*/ { + __pyx_v_start = __pyx_v_shape; + } + __pyx_L11:; + + /* "View.MemoryView":835 + * if start < 0: + * start = 0 + * elif start >= shape: # <<<<<<<<<<<<<< + * if negative_step: + * start = shape - 1 + */ + } + __pyx_L9:; + + /* "View.MemoryView":830 + * + * + * if have_start: # <<<<<<<<<<<<<< + * if start < 0: + * start += shape + */ + goto __pyx_L8; + } + + /* "View.MemoryView":841 + * start = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + /*else*/ { + if (__pyx_v_negative_step) { + + /* "View.MemoryView":842 + * else: + * if negative_step: + * start = shape - 1 # <<<<<<<<<<<<<< + * else: + * start = 0 + */ + __pyx_v_start = (__pyx_v_shape - 1); + + /* "View.MemoryView":841 + * start = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + goto __pyx_L12; + } + + /* "View.MemoryView":844 + * start = shape - 1 + * else: + * start = 0 # <<<<<<<<<<<<<< + * + * if have_stop: + */ + /*else*/ { + __pyx_v_start = 0; + } + __pyx_L12:; + } + __pyx_L8:; + + /* "View.MemoryView":846 + * start = 0 + * + * if have_stop: # <<<<<<<<<<<<<< + * if stop < 0: + * stop += shape + */ + __pyx_t_2 = (__pyx_v_have_stop != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":847 + * + * if have_stop: + * if stop < 0: # <<<<<<<<<<<<<< + * stop += shape + * if stop < 0: + */ + __pyx_t_2 = (__pyx_v_stop < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":848 + * if have_stop: + * if stop < 0: + * stop += shape # <<<<<<<<<<<<<< + * if stop < 0: + * stop = 0 + */ + __pyx_v_stop = (__pyx_v_stop + __pyx_v_shape); + + /* "View.MemoryView":849 + * if stop < 0: + * stop += shape + * if stop < 0: # <<<<<<<<<<<<<< + * stop = 0 + * elif stop > shape: + */ + __pyx_t_2 = (__pyx_v_stop < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":850 + * stop += shape + * if stop < 0: + * stop = 0 # <<<<<<<<<<<<<< + * elif stop > shape: + * stop = shape + */ + __pyx_v_stop = 0; + + /* "View.MemoryView":849 + * if stop < 0: + * stop += shape + * if stop < 0: # <<<<<<<<<<<<<< + * stop = 0 + * elif stop > shape: + */ + } + + /* "View.MemoryView":847 + * + * if have_stop: + * if stop < 0: # <<<<<<<<<<<<<< + * stop += shape + * if stop < 0: + */ + goto __pyx_L14; + } + + /* "View.MemoryView":851 + * if stop < 0: + * stop = 0 + * elif stop > shape: # <<<<<<<<<<<<<< + * stop = shape + * else: + */ + __pyx_t_2 = (__pyx_v_stop > __pyx_v_shape); + if (__pyx_t_2) { + + /* "View.MemoryView":852 + * stop = 0 + * elif stop > shape: + * stop = shape # <<<<<<<<<<<<<< + * else: + * if negative_step: + */ + __pyx_v_stop = __pyx_v_shape; + + /* "View.MemoryView":851 + * if stop < 0: + * stop = 0 + * elif stop > shape: # <<<<<<<<<<<<<< + * stop = shape + * else: + */ + } + __pyx_L14:; + + /* "View.MemoryView":846 + * start = 0 + * + * if have_stop: # <<<<<<<<<<<<<< + * if stop < 0: + * stop += shape + */ + goto __pyx_L13; + } + + /* "View.MemoryView":854 + * stop = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * stop = -1 + * else: + */ + /*else*/ { + if (__pyx_v_negative_step) { + + /* "View.MemoryView":855 + * else: + * if negative_step: + * stop = -1 # <<<<<<<<<<<<<< + * else: + * stop = shape + */ + __pyx_v_stop = -1L; + + /* "View.MemoryView":854 + * stop = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * stop = -1 + * else: + */ + goto __pyx_L16; + } + + /* "View.MemoryView":857 + * stop = -1 + * else: + * stop = shape # <<<<<<<<<<<<<< + * + * + */ + /*else*/ { + __pyx_v_stop = __pyx_v_shape; + } + __pyx_L16:; + } + __pyx_L13:; + + /* "View.MemoryView":861 + * + * with cython.cdivision(True): + * new_shape = (stop - start) // step # <<<<<<<<<<<<<< + * + * if (stop - start) - step * new_shape: + */ + __pyx_v_new_shape = ((__pyx_v_stop - __pyx_v_start) / __pyx_v_step); + + /* "View.MemoryView":863 + * new_shape = (stop - start) // step + * + * if (stop - start) - step * new_shape: # <<<<<<<<<<<<<< + * new_shape += 1 + * + */ + __pyx_t_2 = (((__pyx_v_stop - __pyx_v_start) - (__pyx_v_step * __pyx_v_new_shape)) != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":864 + * + * if (stop - start) - step * new_shape: + * new_shape += 1 # <<<<<<<<<<<<<< + * + * if new_shape < 0: + */ + __pyx_v_new_shape = (__pyx_v_new_shape + 1); + + /* "View.MemoryView":863 + * new_shape = (stop - start) // step + * + * if (stop - start) - step * new_shape: # <<<<<<<<<<<<<< + * new_shape += 1 + * + */ + } + + /* "View.MemoryView":866 + * new_shape += 1 + * + * if new_shape < 0: # <<<<<<<<<<<<<< + * new_shape = 0 + * + */ + __pyx_t_2 = (__pyx_v_new_shape < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":867 + * + * if new_shape < 0: + * new_shape = 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_new_shape = 0; + + /* "View.MemoryView":866 + * new_shape += 1 + * + * if new_shape < 0: # <<<<<<<<<<<<<< + * new_shape = 0 + * + */ + } + + /* "View.MemoryView":870 + * + * + * dst.strides[new_ndim] = stride * step # <<<<<<<<<<<<<< + * dst.shape[new_ndim] = new_shape + * dst.suboffsets[new_ndim] = suboffset + */ + (__pyx_v_dst->strides[__pyx_v_new_ndim]) = (__pyx_v_stride * __pyx_v_step); + + /* "View.MemoryView":871 + * + * dst.strides[new_ndim] = stride * step + * dst.shape[new_ndim] = new_shape # <<<<<<<<<<<<<< + * dst.suboffsets[new_ndim] = suboffset + * + */ + (__pyx_v_dst->shape[__pyx_v_new_ndim]) = __pyx_v_new_shape; + + /* "View.MemoryView":872 + * dst.strides[new_ndim] = stride * step + * dst.shape[new_ndim] = new_shape + * dst.suboffsets[new_ndim] = suboffset # <<<<<<<<<<<<<< + * + * + */ + (__pyx_v_dst->suboffsets[__pyx_v_new_ndim]) = __pyx_v_suboffset; + } + __pyx_L3:; + + /* "View.MemoryView":875 + * + * + * if suboffset_dim[0] < 0: # <<<<<<<<<<<<<< + * dst.data += start * stride + * else: + */ + __pyx_t_2 = ((__pyx_v_suboffset_dim[0]) < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":876 + * + * if suboffset_dim[0] < 0: + * dst.data += start * stride # <<<<<<<<<<<<<< + * else: + * dst.suboffsets[suboffset_dim[0]] += start * stride + */ + __pyx_v_dst->data = (__pyx_v_dst->data + (__pyx_v_start * __pyx_v_stride)); + + /* "View.MemoryView":875 + * + * + * if suboffset_dim[0] < 0: # <<<<<<<<<<<<<< + * dst.data += start * stride + * else: + */ + goto __pyx_L19; + } + + /* "View.MemoryView":878 + * dst.data += start * stride + * else: + * dst.suboffsets[suboffset_dim[0]] += start * stride # <<<<<<<<<<<<<< + * + * if suboffset >= 0: + */ + /*else*/ { + __pyx_t_3 = (__pyx_v_suboffset_dim[0]); + (__pyx_v_dst->suboffsets[__pyx_t_3]) = ((__pyx_v_dst->suboffsets[__pyx_t_3]) + (__pyx_v_start * __pyx_v_stride)); + } + __pyx_L19:; + + /* "View.MemoryView":880 + * dst.suboffsets[suboffset_dim[0]] += start * stride + * + * if suboffset >= 0: # <<<<<<<<<<<<<< + * if not is_slice: + * if new_ndim == 0: + */ + __pyx_t_2 = (__pyx_v_suboffset >= 0); + if (__pyx_t_2) { + + /* "View.MemoryView":881 + * + * if suboffset >= 0: + * if not is_slice: # <<<<<<<<<<<<<< + * if new_ndim == 0: + * dst.data = ( dst.data)[0] + suboffset + */ + __pyx_t_2 = (!__pyx_v_is_slice); + if (__pyx_t_2) { + + /* "View.MemoryView":882 + * if suboffset >= 0: + * if not is_slice: + * if new_ndim == 0: # <<<<<<<<<<<<<< + * dst.data = ( dst.data)[0] + suboffset + * else: + */ + __pyx_t_2 = (__pyx_v_new_ndim == 0); + if (__pyx_t_2) { + + /* "View.MemoryView":883 + * if not is_slice: + * if new_ndim == 0: + * dst.data = ( dst.data)[0] + suboffset # <<<<<<<<<<<<<< + * else: + * _err_dim(PyExc_IndexError, "All dimensions preceding dimension %d " + */ + __pyx_v_dst->data = ((((char **)__pyx_v_dst->data)[0]) + __pyx_v_suboffset); + + /* "View.MemoryView":882 + * if suboffset >= 0: + * if not is_slice: + * if new_ndim == 0: # <<<<<<<<<<<<<< + * dst.data = ( dst.data)[0] + suboffset + * else: + */ + goto __pyx_L22; + } + + /* "View.MemoryView":885 + * dst.data = ( dst.data)[0] + suboffset + * else: + * _err_dim(PyExc_IndexError, "All dimensions preceding dimension %d " # <<<<<<<<<<<<<< + * "must be indexed and not sliced", dim) + * else: + */ + /*else*/ { + + /* "View.MemoryView":886 + * else: + * _err_dim(PyExc_IndexError, "All dimensions preceding dimension %d " + * "must be indexed and not sliced", dim) # <<<<<<<<<<<<<< + * else: + * suboffset_dim[0] = new_ndim + */ + __pyx_t_3 = __pyx_memoryview_err_dim(PyExc_IndexError, __pyx_kp_s_All_dimensions_preceding_dimensi, __pyx_v_dim); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(0, 885, __pyx_L1_error) + } + __pyx_L22:; + + /* "View.MemoryView":881 + * + * if suboffset >= 0: + * if not is_slice: # <<<<<<<<<<<<<< + * if new_ndim == 0: + * dst.data = ( dst.data)[0] + suboffset + */ + goto __pyx_L21; + } + + /* "View.MemoryView":888 + * "must be indexed and not sliced", dim) + * else: + * suboffset_dim[0] = new_ndim # <<<<<<<<<<<<<< + * + * return 0 + */ + /*else*/ { + (__pyx_v_suboffset_dim[0]) = __pyx_v_new_ndim; + } + __pyx_L21:; + + /* "View.MemoryView":880 + * dst.suboffsets[suboffset_dim[0]] += start * stride + * + * if suboffset >= 0: # <<<<<<<<<<<<<< + * if not is_slice: + * if new_ndim == 0: + */ + } + + /* "View.MemoryView":890 + * suboffset_dim[0] = new_ndim + * + * return 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":793 + * + * @cname('__pyx_memoryview_slice_memviewslice') + * cdef int slice_memviewslice( # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * Py_ssize_t shape, Py_ssize_t stride, Py_ssize_t suboffset, + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.slice_memviewslice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":896 + * + * @cname('__pyx_pybuffer_index') + * cdef char *pybuffer_index(Py_buffer *view, char *bufp, Py_ssize_t index, # <<<<<<<<<<<<<< + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 + */ + +static char *__pyx_pybuffer_index(Py_buffer *__pyx_v_view, char *__pyx_v_bufp, Py_ssize_t __pyx_v_index, Py_ssize_t __pyx_v_dim) { + Py_ssize_t __pyx_v_shape; + Py_ssize_t __pyx_v_stride; + Py_ssize_t __pyx_v_suboffset; + Py_ssize_t __pyx_v_itemsize; + char *__pyx_v_resultp; + char *__pyx_r; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + Py_UCS4 __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("pybuffer_index", 1); + + /* "View.MemoryView":898 + * cdef char *pybuffer_index(Py_buffer *view, char *bufp, Py_ssize_t index, + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 # <<<<<<<<<<<<<< + * cdef Py_ssize_t itemsize = view.itemsize + * cdef char *resultp + */ + __pyx_v_suboffset = -1L; + + /* "View.MemoryView":899 + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 + * cdef Py_ssize_t itemsize = view.itemsize # <<<<<<<<<<<<<< + * cdef char *resultp + * + */ + __pyx_t_1 = __pyx_v_view->itemsize; + __pyx_v_itemsize = __pyx_t_1; + + /* "View.MemoryView":902 + * cdef char *resultp + * + * if view.ndim == 0: # <<<<<<<<<<<<<< + * shape = view.len // itemsize + * stride = itemsize + */ + __pyx_t_2 = (__pyx_v_view->ndim == 0); + if (__pyx_t_2) { + + /* "View.MemoryView":903 + * + * if view.ndim == 0: + * shape = view.len // itemsize # <<<<<<<<<<<<<< + * stride = itemsize + * else: + */ + if (unlikely(__pyx_v_itemsize == 0)) { + PyErr_SetString(PyExc_ZeroDivisionError, "integer division or modulo by zero"); + __PYX_ERR(0, 903, __pyx_L1_error) + } + else if (sizeof(Py_ssize_t) == sizeof(long) && (!(((Py_ssize_t)-1) > 0)) && unlikely(__pyx_v_itemsize == (Py_ssize_t)-1) && unlikely(__Pyx_UNARY_NEG_WOULD_OVERFLOW(__pyx_v_view->len))) { + PyErr_SetString(PyExc_OverflowError, "value too large to perform division"); + __PYX_ERR(0, 903, __pyx_L1_error) + } + __pyx_v_shape = __Pyx_div_Py_ssize_t(__pyx_v_view->len, __pyx_v_itemsize); + + /* "View.MemoryView":904 + * if view.ndim == 0: + * shape = view.len // itemsize + * stride = itemsize # <<<<<<<<<<<<<< + * else: + * shape = view.shape[dim] + */ + __pyx_v_stride = __pyx_v_itemsize; + + /* "View.MemoryView":902 + * cdef char *resultp + * + * if view.ndim == 0: # <<<<<<<<<<<<<< + * shape = view.len // itemsize + * stride = itemsize + */ + goto __pyx_L3; + } + + /* "View.MemoryView":906 + * stride = itemsize + * else: + * shape = view.shape[dim] # <<<<<<<<<<<<<< + * stride = view.strides[dim] + * if view.suboffsets != NULL: + */ + /*else*/ { + __pyx_v_shape = (__pyx_v_view->shape[__pyx_v_dim]); + + /* "View.MemoryView":907 + * else: + * shape = view.shape[dim] + * stride = view.strides[dim] # <<<<<<<<<<<<<< + * if view.suboffsets != NULL: + * suboffset = view.suboffsets[dim] + */ + __pyx_v_stride = (__pyx_v_view->strides[__pyx_v_dim]); + + /* "View.MemoryView":908 + * shape = view.shape[dim] + * stride = view.strides[dim] + * if view.suboffsets != NULL: # <<<<<<<<<<<<<< + * suboffset = view.suboffsets[dim] + * + */ + __pyx_t_2 = (__pyx_v_view->suboffsets != NULL); + if (__pyx_t_2) { + + /* "View.MemoryView":909 + * stride = view.strides[dim] + * if view.suboffsets != NULL: + * suboffset = view.suboffsets[dim] # <<<<<<<<<<<<<< + * + * if index < 0: + */ + __pyx_v_suboffset = (__pyx_v_view->suboffsets[__pyx_v_dim]); + + /* "View.MemoryView":908 + * shape = view.shape[dim] + * stride = view.strides[dim] + * if view.suboffsets != NULL: # <<<<<<<<<<<<<< + * suboffset = view.suboffsets[dim] + * + */ + } + } + __pyx_L3:; + + /* "View.MemoryView":911 + * suboffset = view.suboffsets[dim] + * + * if index < 0: # <<<<<<<<<<<<<< + * index += view.shape[dim] + * if index < 0: + */ + __pyx_t_2 = (__pyx_v_index < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":912 + * + * if index < 0: + * index += view.shape[dim] # <<<<<<<<<<<<<< + * if index < 0: + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + */ + __pyx_v_index = (__pyx_v_index + (__pyx_v_view->shape[__pyx_v_dim])); + + /* "View.MemoryView":913 + * if index < 0: + * index += view.shape[dim] + * if index < 0: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + __pyx_t_2 = (__pyx_v_index < 0); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":914 + * index += view.shape[dim] + * if index < 0: + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" # <<<<<<<<<<<<<< + * + * if index >= shape: + */ + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 914, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = 0; + __pyx_t_4 = 127; + __Pyx_INCREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_1 += 37; + __Pyx_GIVEREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_5 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_dim, 0, ' ', 'd'); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 914, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_5); + __Pyx_GIVEREF(__pyx_t_5); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_5); + __pyx_t_5 = 0; + __Pyx_INCREF(__pyx_kp_u__7); + __pyx_t_1 += 1; + __Pyx_GIVEREF(__pyx_kp_u__7); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_kp_u__7); + __pyx_t_5 = __Pyx_PyUnicode_Join(__pyx_t_3, 3, __pyx_t_1, __pyx_t_4); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 914, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_builtin_IndexError, __pyx_t_5, 0, 0); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __PYX_ERR(0, 914, __pyx_L1_error) + + /* "View.MemoryView":913 + * if index < 0: + * index += view.shape[dim] + * if index < 0: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + } + + /* "View.MemoryView":911 + * suboffset = view.suboffsets[dim] + * + * if index < 0: # <<<<<<<<<<<<<< + * index += view.shape[dim] + * if index < 0: + */ + } + + /* "View.MemoryView":916 + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + * if index >= shape: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + __pyx_t_2 = (__pyx_v_index >= __pyx_v_shape); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":917 + * + * if index >= shape: + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" # <<<<<<<<<<<<<< + * + * resultp = bufp + index * stride + */ + __pyx_t_5 = PyTuple_New(3); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 917, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 = 0; + __pyx_t_4 = 127; + __Pyx_INCREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_1 += 37; + __Pyx_GIVEREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_3 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_dim, 0, ' ', 'd'); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 917, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_3); + PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_3); + __pyx_t_3 = 0; + __Pyx_INCREF(__pyx_kp_u__7); + __pyx_t_1 += 1; + __Pyx_GIVEREF(__pyx_kp_u__7); + PyTuple_SET_ITEM(__pyx_t_5, 2, __pyx_kp_u__7); + __pyx_t_3 = __Pyx_PyUnicode_Join(__pyx_t_5, 3, __pyx_t_1, __pyx_t_4); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 917, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_Raise(__pyx_builtin_IndexError, __pyx_t_3, 0, 0); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __PYX_ERR(0, 917, __pyx_L1_error) + + /* "View.MemoryView":916 + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + * if index >= shape: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + } + + /* "View.MemoryView":919 + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + * resultp = bufp + index * stride # <<<<<<<<<<<<<< + * if suboffset >= 0: + * resultp = ( resultp)[0] + suboffset + */ + __pyx_v_resultp = (__pyx_v_bufp + (__pyx_v_index * __pyx_v_stride)); + + /* "View.MemoryView":920 + * + * resultp = bufp + index * stride + * if suboffset >= 0: # <<<<<<<<<<<<<< + * resultp = ( resultp)[0] + suboffset + * + */ + __pyx_t_2 = (__pyx_v_suboffset >= 0); + if (__pyx_t_2) { + + /* "View.MemoryView":921 + * resultp = bufp + index * stride + * if suboffset >= 0: + * resultp = ( resultp)[0] + suboffset # <<<<<<<<<<<<<< + * + * return resultp + */ + __pyx_v_resultp = ((((char **)__pyx_v_resultp)[0]) + __pyx_v_suboffset); + + /* "View.MemoryView":920 + * + * resultp = bufp + index * stride + * if suboffset >= 0: # <<<<<<<<<<<<<< + * resultp = ( resultp)[0] + suboffset + * + */ + } + + /* "View.MemoryView":923 + * resultp = ( resultp)[0] + suboffset + * + * return resultp # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = __pyx_v_resultp; + goto __pyx_L0; + + /* "View.MemoryView":896 + * + * @cname('__pyx_pybuffer_index') + * cdef char *pybuffer_index(Py_buffer *view, char *bufp, Py_ssize_t index, # <<<<<<<<<<<<<< + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.pybuffer_index", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":929 + * + * @cname('__pyx_memslice_transpose') + * cdef int transpose_memslice(__Pyx_memviewslice *memslice) except -1 nogil: # <<<<<<<<<<<<<< + * cdef int ndim = memslice.memview.view.ndim + * + */ + +static int __pyx_memslice_transpose(__Pyx_memviewslice *__pyx_v_memslice) { + int __pyx_v_ndim; + Py_ssize_t *__pyx_v_shape; + Py_ssize_t *__pyx_v_strides; + int __pyx_v_i; + int __pyx_v_j; + int __pyx_r; + int __pyx_t_1; + Py_ssize_t *__pyx_t_2; + long __pyx_t_3; + long __pyx_t_4; + Py_ssize_t __pyx_t_5; + Py_ssize_t __pyx_t_6; + int __pyx_t_7; + int __pyx_t_8; + int __pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":930 + * @cname('__pyx_memslice_transpose') + * cdef int transpose_memslice(__Pyx_memviewslice *memslice) except -1 nogil: + * cdef int ndim = memslice.memview.view.ndim # <<<<<<<<<<<<<< + * + * cdef Py_ssize_t *shape = memslice.shape + */ + __pyx_t_1 = __pyx_v_memslice->memview->view.ndim; + __pyx_v_ndim = __pyx_t_1; + + /* "View.MemoryView":932 + * cdef int ndim = memslice.memview.view.ndim + * + * cdef Py_ssize_t *shape = memslice.shape # <<<<<<<<<<<<<< + * cdef Py_ssize_t *strides = memslice.strides + * + */ + __pyx_t_2 = __pyx_v_memslice->shape; + __pyx_v_shape = __pyx_t_2; + + /* "View.MemoryView":933 + * + * cdef Py_ssize_t *shape = memslice.shape + * cdef Py_ssize_t *strides = memslice.strides # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = __pyx_v_memslice->strides; + __pyx_v_strides = __pyx_t_2; + + /* "View.MemoryView":937 + * + * cdef int i, j + * for i in range(ndim // 2): # <<<<<<<<<<<<<< + * j = ndim - 1 - i + * strides[i], strides[j] = strides[j], strides[i] + */ + __pyx_t_3 = __Pyx_div_long(__pyx_v_ndim, 2); + __pyx_t_4 = __pyx_t_3; + for (__pyx_t_1 = 0; __pyx_t_1 < __pyx_t_4; __pyx_t_1+=1) { + __pyx_v_i = __pyx_t_1; + + /* "View.MemoryView":938 + * cdef int i, j + * for i in range(ndim // 2): + * j = ndim - 1 - i # <<<<<<<<<<<<<< + * strides[i], strides[j] = strides[j], strides[i] + * shape[i], shape[j] = shape[j], shape[i] + */ + __pyx_v_j = ((__pyx_v_ndim - 1) - __pyx_v_i); + + /* "View.MemoryView":939 + * for i in range(ndim // 2): + * j = ndim - 1 - i + * strides[i], strides[j] = strides[j], strides[i] # <<<<<<<<<<<<<< + * shape[i], shape[j] = shape[j], shape[i] + * + */ + __pyx_t_5 = (__pyx_v_strides[__pyx_v_j]); + __pyx_t_6 = (__pyx_v_strides[__pyx_v_i]); + (__pyx_v_strides[__pyx_v_i]) = __pyx_t_5; + (__pyx_v_strides[__pyx_v_j]) = __pyx_t_6; + + /* "View.MemoryView":940 + * j = ndim - 1 - i + * strides[i], strides[j] = strides[j], strides[i] + * shape[i], shape[j] = shape[j], shape[i] # <<<<<<<<<<<<<< + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: + */ + __pyx_t_6 = (__pyx_v_shape[__pyx_v_j]); + __pyx_t_5 = (__pyx_v_shape[__pyx_v_i]); + (__pyx_v_shape[__pyx_v_i]) = __pyx_t_6; + (__pyx_v_shape[__pyx_v_j]) = __pyx_t_5; + + /* "View.MemoryView":942 + * shape[i], shape[j] = shape[j], shape[i] + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: # <<<<<<<<<<<<<< + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") + * + */ + __pyx_t_8 = ((__pyx_v_memslice->suboffsets[__pyx_v_i]) >= 0); + if (!__pyx_t_8) { + } else { + __pyx_t_7 = __pyx_t_8; + goto __pyx_L6_bool_binop_done; + } + __pyx_t_8 = ((__pyx_v_memslice->suboffsets[__pyx_v_j]) >= 0); + __pyx_t_7 = __pyx_t_8; + __pyx_L6_bool_binop_done:; + if (__pyx_t_7) { + + /* "View.MemoryView":943 + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") # <<<<<<<<<<<<<< + * + * return 0 + */ + __pyx_t_9 = __pyx_memoryview_err(PyExc_ValueError, __pyx_kp_s_Cannot_transpose_memoryview_with); if (unlikely(__pyx_t_9 == ((int)-1))) __PYX_ERR(0, 943, __pyx_L1_error) + + /* "View.MemoryView":942 + * shape[i], shape[j] = shape[j], shape[i] + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: # <<<<<<<<<<<<<< + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") + * + */ + } + } + + /* "View.MemoryView":945 + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") + * + * return 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":929 + * + * @cname('__pyx_memslice_transpose') + * cdef int transpose_memslice(__Pyx_memviewslice *memslice) except -1 nogil: # <<<<<<<<<<<<<< + * cdef int ndim = memslice.memview.view.ndim + * + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.transpose_memslice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":963 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + */ + +/* Python wrapper */ +static void __pyx_memoryviewslice___dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_memoryviewslice___dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_memoryviewslice___pyx_pf_15View_dot_MemoryView_16_memoryviewslice___dealloc__(((struct __pyx_memoryviewslice_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_memoryviewslice___pyx_pf_15View_dot_MemoryView_16_memoryviewslice___dealloc__(struct __pyx_memoryviewslice_obj *__pyx_v_self) { + + /* "View.MemoryView":964 + * + * def __dealloc__(self): + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) # <<<<<<<<<<<<<< + * + * cdef convert_item_to_object(self, char *itemp): + */ + __PYX_XCLEAR_MEMVIEW((&__pyx_v_self->from_slice), 1); + + /* "View.MemoryView":963 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + */ + + /* function exit code */ +} + +/* "View.MemoryView":966 + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * if self.to_object_func != NULL: + * return self.to_object_func(itemp) + */ + +static PyObject *__pyx_memoryviewslice_convert_item_to_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("convert_item_to_object", 1); + + /* "View.MemoryView":967 + * + * cdef convert_item_to_object(self, char *itemp): + * if self.to_object_func != NULL: # <<<<<<<<<<<<<< + * return self.to_object_func(itemp) + * else: + */ + __pyx_t_1 = (__pyx_v_self->to_object_func != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":968 + * cdef convert_item_to_object(self, char *itemp): + * if self.to_object_func != NULL: + * return self.to_object_func(itemp) # <<<<<<<<<<<<<< + * else: + * return memoryview.convert_item_to_object(self, itemp) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_v_self->to_object_func(__pyx_v_itemp); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 968, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":967 + * + * cdef convert_item_to_object(self, char *itemp): + * if self.to_object_func != NULL: # <<<<<<<<<<<<<< + * return self.to_object_func(itemp) + * else: + */ + } + + /* "View.MemoryView":970 + * return self.to_object_func(itemp) + * else: + * return memoryview.convert_item_to_object(self, itemp) # <<<<<<<<<<<<<< + * + * cdef assign_item_from_object(self, char *itemp, object value): + */ + /*else*/ { + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_memoryview_convert_item_to_object(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v_itemp); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 970, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + } + + /* "View.MemoryView":966 + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * if self.to_object_func != NULL: + * return self.to_object_func(itemp) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.convert_item_to_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":972 + * return memoryview.convert_item_to_object(self, itemp) + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * if self.to_dtype_func != NULL: + * self.to_dtype_func(itemp, value) + */ + +static PyObject *__pyx_memoryviewslice_assign_item_from_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("assign_item_from_object", 1); + + /* "View.MemoryView":973 + * + * cdef assign_item_from_object(self, char *itemp, object value): + * if self.to_dtype_func != NULL: # <<<<<<<<<<<<<< + * self.to_dtype_func(itemp, value) + * else: + */ + __pyx_t_1 = (__pyx_v_self->to_dtype_func != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":974 + * cdef assign_item_from_object(self, char *itemp, object value): + * if self.to_dtype_func != NULL: + * self.to_dtype_func(itemp, value) # <<<<<<<<<<<<<< + * else: + * memoryview.assign_item_from_object(self, itemp, value) + */ + __pyx_t_2 = __pyx_v_self->to_dtype_func(__pyx_v_itemp, __pyx_v_value); if (unlikely(__pyx_t_2 == ((int)0))) __PYX_ERR(0, 974, __pyx_L1_error) + + /* "View.MemoryView":973 + * + * cdef assign_item_from_object(self, char *itemp, object value): + * if self.to_dtype_func != NULL: # <<<<<<<<<<<<<< + * self.to_dtype_func(itemp, value) + * else: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":976 + * self.to_dtype_func(itemp, value) + * else: + * memoryview.assign_item_from_object(self, itemp, value) # <<<<<<<<<<<<<< + * + * cdef _get_base(self): + */ + /*else*/ { + __pyx_t_3 = __pyx_memoryview_assign_item_from_object(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v_itemp, __pyx_v_value); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 976, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_L3:; + + /* "View.MemoryView":972 + * return memoryview.convert_item_to_object(self, itemp) + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * if self.to_dtype_func != NULL: + * self.to_dtype_func(itemp, value) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.assign_item_from_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":978 + * memoryview.assign_item_from_object(self, itemp, value) + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.from_object + * + */ + +static PyObject *__pyx_memoryviewslice__get_base(struct __pyx_memoryviewslice_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("_get_base", 1); + + /* "View.MemoryView":979 + * + * cdef _get_base(self): + * return self.from_object # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->from_object); + __pyx_r = __pyx_v_self->from_object; + goto __pyx_L0; + + /* "View.MemoryView":978 + * memoryview.assign_item_from_object(self, itemp, value) + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.from_object + * + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryviewslice_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryviewslice_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_memoryviewslice___reduce_cython__(((struct __pyx_memoryviewslice_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryviewslice___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(0, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryviewslice_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryviewslice_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(0, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_memoryviewslice_2__setstate_cython__(((struct __pyx_memoryviewslice_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryviewslice_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(0, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":999 + * + * @cname('__pyx_memoryview_fromslice') + * cdef memoryview_fromslice(__Pyx_memviewslice memviewslice, # <<<<<<<<<<<<<< + * int ndim, + * object (*to_object_func)(char *), + */ + +static PyObject *__pyx_memoryview_fromslice(__Pyx_memviewslice __pyx_v_memviewslice, int __pyx_v_ndim, PyObject *(*__pyx_v_to_object_func)(char *), int (*__pyx_v_to_dtype_func)(char *, PyObject *), int __pyx_v_dtype_is_object) { + struct __pyx_memoryviewslice_obj *__pyx_v_result = 0; + Py_ssize_t __pyx_v_suboffset; + PyObject *__pyx_v_length = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + __Pyx_TypeInfo *__pyx_t_4; + Py_buffer __pyx_t_5; + Py_ssize_t *__pyx_t_6; + Py_ssize_t *__pyx_t_7; + Py_ssize_t *__pyx_t_8; + Py_ssize_t __pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_fromslice", 1); + + /* "View.MemoryView":1007 + * cdef _memoryviewslice result + * + * if memviewslice.memview == Py_None: # <<<<<<<<<<<<<< + * return None + * + */ + __pyx_t_1 = (((PyObject *)__pyx_v_memviewslice.memview) == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":1008 + * + * if memviewslice.memview == Py_None: + * return None # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "View.MemoryView":1007 + * cdef _memoryviewslice result + * + * if memviewslice.memview == Py_None: # <<<<<<<<<<<<<< + * return None + * + */ + } + + /* "View.MemoryView":1013 + * + * + * result = _memoryviewslice.__new__(_memoryviewslice, None, 0, dtype_is_object) # <<<<<<<<<<<<<< + * + * result.from_slice = memviewslice + */ + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_v_dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 1013, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 1013, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(Py_None); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, Py_None)) __PYX_ERR(0, 1013, __pyx_L1_error); + __Pyx_INCREF(__pyx_int_0); + __Pyx_GIVEREF(__pyx_int_0); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_int_0)) __PYX_ERR(0, 1013, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_t_2)) __PYX_ERR(0, 1013, __pyx_L1_error); + __pyx_t_2 = 0; + __pyx_t_2 = ((PyObject *)__pyx_tp_new__memoryviewslice(((PyTypeObject *)__pyx_memoryviewslice_type), __pyx_t_3, NULL)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 1013, __pyx_L1_error) + __Pyx_GOTREF((PyObject *)__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_v_result = ((struct __pyx_memoryviewslice_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":1015 + * result = _memoryviewslice.__new__(_memoryviewslice, None, 0, dtype_is_object) + * + * result.from_slice = memviewslice # <<<<<<<<<<<<<< + * __PYX_INC_MEMVIEW(&memviewslice, 1) + * + */ + __pyx_v_result->from_slice = __pyx_v_memviewslice; + + /* "View.MemoryView":1016 + * + * result.from_slice = memviewslice + * __PYX_INC_MEMVIEW(&memviewslice, 1) # <<<<<<<<<<<<<< + * + * result.from_object = ( memviewslice.memview)._get_base() + */ + __PYX_INC_MEMVIEW((&__pyx_v_memviewslice), 1); + + /* "View.MemoryView":1018 + * __PYX_INC_MEMVIEW(&memviewslice, 1) + * + * result.from_object = ( memviewslice.memview)._get_base() # <<<<<<<<<<<<<< + * result.typeinfo = memviewslice.memview.typeinfo + * + */ + __pyx_t_2 = ((struct __pyx_vtabstruct_memoryview *)((struct __pyx_memoryview_obj *)__pyx_v_memviewslice.memview)->__pyx_vtab)->_get_base(((struct __pyx_memoryview_obj *)__pyx_v_memviewslice.memview)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 1018, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + __Pyx_GOTREF(__pyx_v_result->from_object); + __Pyx_DECREF(__pyx_v_result->from_object); + __pyx_v_result->from_object = __pyx_t_2; + __pyx_t_2 = 0; + + /* "View.MemoryView":1019 + * + * result.from_object = ( memviewslice.memview)._get_base() + * result.typeinfo = memviewslice.memview.typeinfo # <<<<<<<<<<<<<< + * + * result.view = memviewslice.memview.view + */ + __pyx_t_4 = __pyx_v_memviewslice.memview->typeinfo; + __pyx_v_result->__pyx_base.typeinfo = __pyx_t_4; + + /* "View.MemoryView":1021 + * result.typeinfo = memviewslice.memview.typeinfo + * + * result.view = memviewslice.memview.view # <<<<<<<<<<<<<< + * result.view.buf = memviewslice.data + * result.view.ndim = ndim + */ + __pyx_t_5 = __pyx_v_memviewslice.memview->view; + __pyx_v_result->__pyx_base.view = __pyx_t_5; + + /* "View.MemoryView":1022 + * + * result.view = memviewslice.memview.view + * result.view.buf = memviewslice.data # <<<<<<<<<<<<<< + * result.view.ndim = ndim + * (<__pyx_buffer *> &result.view).obj = Py_None + */ + __pyx_v_result->__pyx_base.view.buf = ((void *)__pyx_v_memviewslice.data); + + /* "View.MemoryView":1023 + * result.view = memviewslice.memview.view + * result.view.buf = memviewslice.data + * result.view.ndim = ndim # <<<<<<<<<<<<<< + * (<__pyx_buffer *> &result.view).obj = Py_None + * Py_INCREF(Py_None) + */ + __pyx_v_result->__pyx_base.view.ndim = __pyx_v_ndim; + + /* "View.MemoryView":1024 + * result.view.buf = memviewslice.data + * result.view.ndim = ndim + * (<__pyx_buffer *> &result.view).obj = Py_None # <<<<<<<<<<<<<< + * Py_INCREF(Py_None) + * + */ + ((Py_buffer *)(&__pyx_v_result->__pyx_base.view))->obj = Py_None; + + /* "View.MemoryView":1025 + * result.view.ndim = ndim + * (<__pyx_buffer *> &result.view).obj = Py_None + * Py_INCREF(Py_None) # <<<<<<<<<<<<<< + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: + */ + Py_INCREF(Py_None); + + /* "View.MemoryView":1027 + * Py_INCREF(Py_None) + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: # <<<<<<<<<<<<<< + * result.flags = PyBUF_RECORDS + * else: + */ + __pyx_t_1 = ((((struct __pyx_memoryview_obj *)__pyx_v_memviewslice.memview)->flags & PyBUF_WRITABLE) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":1028 + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: + * result.flags = PyBUF_RECORDS # <<<<<<<<<<<<<< + * else: + * result.flags = PyBUF_RECORDS_RO + */ + __pyx_v_result->__pyx_base.flags = PyBUF_RECORDS; + + /* "View.MemoryView":1027 + * Py_INCREF(Py_None) + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: # <<<<<<<<<<<<<< + * result.flags = PyBUF_RECORDS + * else: + */ + goto __pyx_L4; + } + + /* "View.MemoryView":1030 + * result.flags = PyBUF_RECORDS + * else: + * result.flags = PyBUF_RECORDS_RO # <<<<<<<<<<<<<< + * + * result.view.shape = result.from_slice.shape + */ + /*else*/ { + __pyx_v_result->__pyx_base.flags = PyBUF_RECORDS_RO; + } + __pyx_L4:; + + /* "View.MemoryView":1032 + * result.flags = PyBUF_RECORDS_RO + * + * result.view.shape = result.from_slice.shape # <<<<<<<<<<<<<< + * result.view.strides = result.from_slice.strides + * + */ + __pyx_v_result->__pyx_base.view.shape = ((Py_ssize_t *)__pyx_v_result->from_slice.shape); + + /* "View.MemoryView":1033 + * + * result.view.shape = result.from_slice.shape + * result.view.strides = result.from_slice.strides # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_result->__pyx_base.view.strides = ((Py_ssize_t *)__pyx_v_result->from_slice.strides); + + /* "View.MemoryView":1036 + * + * + * result.view.suboffsets = NULL # <<<<<<<<<<<<<< + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: + */ + __pyx_v_result->__pyx_base.view.suboffsets = NULL; + + /* "View.MemoryView":1037 + * + * result.view.suboffsets = NULL + * for suboffset in result.from_slice.suboffsets[:ndim]: # <<<<<<<<<<<<<< + * if suboffset >= 0: + * result.view.suboffsets = result.from_slice.suboffsets + */ + __pyx_t_7 = (__pyx_v_result->from_slice.suboffsets + __pyx_v_ndim); + for (__pyx_t_8 = __pyx_v_result->from_slice.suboffsets; __pyx_t_8 < __pyx_t_7; __pyx_t_8++) { + __pyx_t_6 = __pyx_t_8; + __pyx_v_suboffset = (__pyx_t_6[0]); + + /* "View.MemoryView":1038 + * result.view.suboffsets = NULL + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * result.view.suboffsets = result.from_slice.suboffsets + * break + */ + __pyx_t_1 = (__pyx_v_suboffset >= 0); + if (__pyx_t_1) { + + /* "View.MemoryView":1039 + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: + * result.view.suboffsets = result.from_slice.suboffsets # <<<<<<<<<<<<<< + * break + * + */ + __pyx_v_result->__pyx_base.view.suboffsets = ((Py_ssize_t *)__pyx_v_result->from_slice.suboffsets); + + /* "View.MemoryView":1040 + * if suboffset >= 0: + * result.view.suboffsets = result.from_slice.suboffsets + * break # <<<<<<<<<<<<<< + * + * result.view.len = result.view.itemsize + */ + goto __pyx_L6_break; + + /* "View.MemoryView":1038 + * result.view.suboffsets = NULL + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * result.view.suboffsets = result.from_slice.suboffsets + * break + */ + } + } + __pyx_L6_break:; + + /* "View.MemoryView":1042 + * break + * + * result.view.len = result.view.itemsize # <<<<<<<<<<<<<< + * for length in result.view.shape[:ndim]: + * result.view.len *= length + */ + __pyx_t_9 = __pyx_v_result->__pyx_base.view.itemsize; + __pyx_v_result->__pyx_base.view.len = __pyx_t_9; + + /* "View.MemoryView":1043 + * + * result.view.len = result.view.itemsize + * for length in result.view.shape[:ndim]: # <<<<<<<<<<<<<< + * result.view.len *= length + * + */ + __pyx_t_7 = (__pyx_v_result->__pyx_base.view.shape + __pyx_v_ndim); + for (__pyx_t_8 = __pyx_v_result->__pyx_base.view.shape; __pyx_t_8 < __pyx_t_7; __pyx_t_8++) { + __pyx_t_6 = __pyx_t_8; + __pyx_t_2 = PyInt_FromSsize_t((__pyx_t_6[0])); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 1043, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_XDECREF_SET(__pyx_v_length, __pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":1044 + * result.view.len = result.view.itemsize + * for length in result.view.shape[:ndim]: + * result.view.len *= length # <<<<<<<<<<<<<< + * + * result.to_object_func = to_object_func + */ + __pyx_t_2 = PyInt_FromSsize_t(__pyx_v_result->__pyx_base.view.len); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 1044, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyNumber_InPlaceMultiply(__pyx_t_2, __pyx_v_length); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 1044, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_9 = __Pyx_PyIndex_AsSsize_t(__pyx_t_3); if (unlikely((__pyx_t_9 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 1044, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_v_result->__pyx_base.view.len = __pyx_t_9; + } + + /* "View.MemoryView":1046 + * result.view.len *= length + * + * result.to_object_func = to_object_func # <<<<<<<<<<<<<< + * result.to_dtype_func = to_dtype_func + * + */ + __pyx_v_result->to_object_func = __pyx_v_to_object_func; + + /* "View.MemoryView":1047 + * + * result.to_object_func = to_object_func + * result.to_dtype_func = to_dtype_func # <<<<<<<<<<<<<< + * + * return result + */ + __pyx_v_result->to_dtype_func = __pyx_v_to_dtype_func; + + /* "View.MemoryView":1049 + * result.to_dtype_func = to_dtype_func + * + * return result # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_get_slice_from_memoryview') + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = ((PyObject *)__pyx_v_result); + goto __pyx_L0; + + /* "View.MemoryView":999 + * + * @cname('__pyx_memoryview_fromslice') + * cdef memoryview_fromslice(__Pyx_memviewslice memviewslice, # <<<<<<<<<<<<<< + * int ndim, + * object (*to_object_func)(char *), + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview_fromslice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XDECREF(__pyx_v_length); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1052 + * + * @cname('__pyx_memoryview_get_slice_from_memoryview') + * cdef __Pyx_memviewslice *get_slice_from_memview(memoryview memview, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + */ + +static __Pyx_memviewslice *__pyx_memoryview_get_slice_from_memoryview(struct __pyx_memoryview_obj *__pyx_v_memview, __Pyx_memviewslice *__pyx_v_mslice) { + struct __pyx_memoryviewslice_obj *__pyx_v_obj = 0; + __Pyx_memviewslice *__pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_slice_from_memview", 1); + + /* "View.MemoryView":1055 + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * obj = memview + * return &obj.from_slice + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":1056 + * cdef _memoryviewslice obj + * if isinstance(memview, _memoryviewslice): + * obj = memview # <<<<<<<<<<<<<< + * return &obj.from_slice + * else: + */ + if (!(likely(((((PyObject *)__pyx_v_memview)) == Py_None) || likely(__Pyx_TypeTest(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type))))) __PYX_ERR(0, 1056, __pyx_L1_error) + __pyx_t_2 = ((PyObject *)__pyx_v_memview); + __Pyx_INCREF(__pyx_t_2); + __pyx_v_obj = ((struct __pyx_memoryviewslice_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":1057 + * if isinstance(memview, _memoryviewslice): + * obj = memview + * return &obj.from_slice # <<<<<<<<<<<<<< + * else: + * slice_copy(memview, mslice) + */ + __pyx_r = (&__pyx_v_obj->from_slice); + goto __pyx_L0; + + /* "View.MemoryView":1055 + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * obj = memview + * return &obj.from_slice + */ + } + + /* "View.MemoryView":1059 + * return &obj.from_slice + * else: + * slice_copy(memview, mslice) # <<<<<<<<<<<<<< + * return mslice + * + */ + /*else*/ { + __pyx_memoryview_slice_copy(__pyx_v_memview, __pyx_v_mslice); + + /* "View.MemoryView":1060 + * else: + * slice_copy(memview, mslice) + * return mslice # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_slice_copy') + */ + __pyx_r = __pyx_v_mslice; + goto __pyx_L0; + } + + /* "View.MemoryView":1052 + * + * @cname('__pyx_memoryview_get_slice_from_memoryview') + * cdef __Pyx_memviewslice *get_slice_from_memview(memoryview memview, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.get_slice_from_memview", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_obj); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1063 + * + * @cname('__pyx_memoryview_slice_copy') + * cdef void slice_copy(memoryview memview, __Pyx_memviewslice *dst) noexcept: # <<<<<<<<<<<<<< + * cdef int dim + * cdef (Py_ssize_t*) shape, strides, suboffsets + */ + +static void __pyx_memoryview_slice_copy(struct __pyx_memoryview_obj *__pyx_v_memview, __Pyx_memviewslice *__pyx_v_dst) { + int __pyx_v_dim; + Py_ssize_t *__pyx_v_shape; + Py_ssize_t *__pyx_v_strides; + Py_ssize_t *__pyx_v_suboffsets; + Py_ssize_t *__pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + Py_ssize_t __pyx_t_5; + int __pyx_t_6; + + /* "View.MemoryView":1067 + * cdef (Py_ssize_t*) shape, strides, suboffsets + * + * shape = memview.view.shape # <<<<<<<<<<<<<< + * strides = memview.view.strides + * suboffsets = memview.view.suboffsets + */ + __pyx_t_1 = __pyx_v_memview->view.shape; + __pyx_v_shape = __pyx_t_1; + + /* "View.MemoryView":1068 + * + * shape = memview.view.shape + * strides = memview.view.strides # <<<<<<<<<<<<<< + * suboffsets = memview.view.suboffsets + * + */ + __pyx_t_1 = __pyx_v_memview->view.strides; + __pyx_v_strides = __pyx_t_1; + + /* "View.MemoryView":1069 + * shape = memview.view.shape + * strides = memview.view.strides + * suboffsets = memview.view.suboffsets # <<<<<<<<<<<<<< + * + * dst.memview = <__pyx_memoryview *> memview + */ + __pyx_t_1 = __pyx_v_memview->view.suboffsets; + __pyx_v_suboffsets = __pyx_t_1; + + /* "View.MemoryView":1071 + * suboffsets = memview.view.suboffsets + * + * dst.memview = <__pyx_memoryview *> memview # <<<<<<<<<<<<<< + * dst.data = memview.view.buf + * + */ + __pyx_v_dst->memview = ((struct __pyx_memoryview_obj *)__pyx_v_memview); + + /* "View.MemoryView":1072 + * + * dst.memview = <__pyx_memoryview *> memview + * dst.data = memview.view.buf # <<<<<<<<<<<<<< + * + * for dim in range(memview.view.ndim): + */ + __pyx_v_dst->data = ((char *)__pyx_v_memview->view.buf); + + /* "View.MemoryView":1074 + * dst.data = memview.view.buf + * + * for dim in range(memview.view.ndim): # <<<<<<<<<<<<<< + * dst.shape[dim] = shape[dim] + * dst.strides[dim] = strides[dim] + */ + __pyx_t_2 = __pyx_v_memview->view.ndim; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_dim = __pyx_t_4; + + /* "View.MemoryView":1075 + * + * for dim in range(memview.view.ndim): + * dst.shape[dim] = shape[dim] # <<<<<<<<<<<<<< + * dst.strides[dim] = strides[dim] + * dst.suboffsets[dim] = suboffsets[dim] if suboffsets else -1 + */ + (__pyx_v_dst->shape[__pyx_v_dim]) = (__pyx_v_shape[__pyx_v_dim]); + + /* "View.MemoryView":1076 + * for dim in range(memview.view.ndim): + * dst.shape[dim] = shape[dim] + * dst.strides[dim] = strides[dim] # <<<<<<<<<<<<<< + * dst.suboffsets[dim] = suboffsets[dim] if suboffsets else -1 + * + */ + (__pyx_v_dst->strides[__pyx_v_dim]) = (__pyx_v_strides[__pyx_v_dim]); + + /* "View.MemoryView":1077 + * dst.shape[dim] = shape[dim] + * dst.strides[dim] = strides[dim] + * dst.suboffsets[dim] = suboffsets[dim] if suboffsets else -1 # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_copy_object') + */ + __pyx_t_6 = (__pyx_v_suboffsets != 0); + if (__pyx_t_6) { + __pyx_t_5 = (__pyx_v_suboffsets[__pyx_v_dim]); + } else { + __pyx_t_5 = -1L; + } + (__pyx_v_dst->suboffsets[__pyx_v_dim]) = __pyx_t_5; + } + + /* "View.MemoryView":1063 + * + * @cname('__pyx_memoryview_slice_copy') + * cdef void slice_copy(memoryview memview, __Pyx_memviewslice *dst) noexcept: # <<<<<<<<<<<<<< + * cdef int dim + * cdef (Py_ssize_t*) shape, strides, suboffsets + */ + + /* function exit code */ +} + +/* "View.MemoryView":1080 + * + * @cname('__pyx_memoryview_copy_object') + * cdef memoryview_copy(memoryview memview): # <<<<<<<<<<<<<< + * "Create a new memoryview object" + * cdef __Pyx_memviewslice memviewslice + */ + +static PyObject *__pyx_memoryview_copy_object(struct __pyx_memoryview_obj *__pyx_v_memview) { + __Pyx_memviewslice __pyx_v_memviewslice; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_copy", 1); + + /* "View.MemoryView":1083 + * "Create a new memoryview object" + * cdef __Pyx_memviewslice memviewslice + * slice_copy(memview, &memviewslice) # <<<<<<<<<<<<<< + * return memoryview_copy_from_slice(memview, &memviewslice) + * + */ + __pyx_memoryview_slice_copy(__pyx_v_memview, (&__pyx_v_memviewslice)); + + /* "View.MemoryView":1084 + * cdef __Pyx_memviewslice memviewslice + * slice_copy(memview, &memviewslice) + * return memoryview_copy_from_slice(memview, &memviewslice) # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_copy_object_from_slice') + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __pyx_memoryview_copy_object_from_slice(__pyx_v_memview, (&__pyx_v_memviewslice)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 1084, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":1080 + * + * @cname('__pyx_memoryview_copy_object') + * cdef memoryview_copy(memoryview memview): # <<<<<<<<<<<<<< + * "Create a new memoryview object" + * cdef __Pyx_memviewslice memviewslice + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview_copy", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1087 + * + * @cname('__pyx_memoryview_copy_object_from_slice') + * cdef memoryview_copy_from_slice(memoryview memview, __Pyx_memviewslice *memviewslice): # <<<<<<<<<<<<<< + * """ + * Create a new memoryview object from a given memoryview object and slice. + */ + +static PyObject *__pyx_memoryview_copy_object_from_slice(struct __pyx_memoryview_obj *__pyx_v_memview, __Pyx_memviewslice *__pyx_v_memviewslice) { + PyObject *(*__pyx_v_to_object_func)(char *); + int (*__pyx_v_to_dtype_func)(char *, PyObject *); + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *(*__pyx_t_2)(char *); + int (*__pyx_t_3)(char *, PyObject *); + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_copy_from_slice", 1); + + /* "View.MemoryView":1094 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * to_object_func = (<_memoryviewslice> memview).to_object_func + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":1095 + * + * if isinstance(memview, _memoryviewslice): + * to_object_func = (<_memoryviewslice> memview).to_object_func # <<<<<<<<<<<<<< + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + * else: + */ + __pyx_t_2 = ((struct __pyx_memoryviewslice_obj *)__pyx_v_memview)->to_object_func; + __pyx_v_to_object_func = __pyx_t_2; + + /* "View.MemoryView":1096 + * if isinstance(memview, _memoryviewslice): + * to_object_func = (<_memoryviewslice> memview).to_object_func + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func # <<<<<<<<<<<<<< + * else: + * to_object_func = NULL + */ + __pyx_t_3 = ((struct __pyx_memoryviewslice_obj *)__pyx_v_memview)->to_dtype_func; + __pyx_v_to_dtype_func = __pyx_t_3; + + /* "View.MemoryView":1094 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * to_object_func = (<_memoryviewslice> memview).to_object_func + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1098 + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + * else: + * to_object_func = NULL # <<<<<<<<<<<<<< + * to_dtype_func = NULL + * + */ + /*else*/ { + __pyx_v_to_object_func = NULL; + + /* "View.MemoryView":1099 + * else: + * to_object_func = NULL + * to_dtype_func = NULL # <<<<<<<<<<<<<< + * + * return memoryview_fromslice(memviewslice[0], memview.view.ndim, + */ + __pyx_v_to_dtype_func = NULL; + } + __pyx_L3:; + + /* "View.MemoryView":1101 + * to_dtype_func = NULL + * + * return memoryview_fromslice(memviewslice[0], memview.view.ndim, # <<<<<<<<<<<<<< + * to_object_func, to_dtype_func, + * memview.dtype_is_object) + */ + __Pyx_XDECREF(__pyx_r); + + /* "View.MemoryView":1103 + * return memoryview_fromslice(memviewslice[0], memview.view.ndim, + * to_object_func, to_dtype_func, + * memview.dtype_is_object) # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_4 = __pyx_memoryview_fromslice((__pyx_v_memviewslice[0]), __pyx_v_memview->view.ndim, __pyx_v_to_object_func, __pyx_v_to_dtype_func, __pyx_v_memview->dtype_is_object); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 1101, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_r = __pyx_t_4; + __pyx_t_4 = 0; + goto __pyx_L0; + + /* "View.MemoryView":1087 + * + * @cname('__pyx_memoryview_copy_object_from_slice') + * cdef memoryview_copy_from_slice(memoryview memview, __Pyx_memviewslice *memviewslice): # <<<<<<<<<<<<<< + * """ + * Create a new memoryview object from a given memoryview object and slice. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.memoryview_copy_from_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1109 + * + * + * cdef Py_ssize_t abs_py_ssize_t(Py_ssize_t arg) noexcept nogil: # <<<<<<<<<<<<<< + * return -arg if arg < 0 else arg + * + */ + +static Py_ssize_t abs_py_ssize_t(Py_ssize_t __pyx_v_arg) { + Py_ssize_t __pyx_r; + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + + /* "View.MemoryView":1110 + * + * cdef Py_ssize_t abs_py_ssize_t(Py_ssize_t arg) noexcept nogil: + * return -arg if arg < 0 else arg # <<<<<<<<<<<<<< + * + * @cname('__pyx_get_best_slice_order') + */ + __pyx_t_2 = (__pyx_v_arg < 0); + if (__pyx_t_2) { + __pyx_t_1 = (-__pyx_v_arg); + } else { + __pyx_t_1 = __pyx_v_arg; + } + __pyx_r = __pyx_t_1; + goto __pyx_L0; + + /* "View.MemoryView":1109 + * + * + * cdef Py_ssize_t abs_py_ssize_t(Py_ssize_t arg) noexcept nogil: # <<<<<<<<<<<<<< + * return -arg if arg < 0 else arg + * + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1113 + * + * @cname('__pyx_get_best_slice_order') + * cdef char get_best_order(__Pyx_memviewslice *mslice, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * """ + * Figure out the best memory access order for a given slice. + */ + +static char __pyx_get_best_slice_order(__Pyx_memviewslice *__pyx_v_mslice, int __pyx_v_ndim) { + int __pyx_v_i; + Py_ssize_t __pyx_v_c_stride; + Py_ssize_t __pyx_v_f_stride; + char __pyx_r; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + + /* "View.MemoryView":1118 + * """ + * cdef int i + * cdef Py_ssize_t c_stride = 0 # <<<<<<<<<<<<<< + * cdef Py_ssize_t f_stride = 0 + * + */ + __pyx_v_c_stride = 0; + + /* "View.MemoryView":1119 + * cdef int i + * cdef Py_ssize_t c_stride = 0 + * cdef Py_ssize_t f_stride = 0 # <<<<<<<<<<<<<< + * + * for i in range(ndim - 1, -1, -1): + */ + __pyx_v_f_stride = 0; + + /* "View.MemoryView":1121 + * cdef Py_ssize_t f_stride = 0 + * + * for i in range(ndim - 1, -1, -1): # <<<<<<<<<<<<<< + * if mslice.shape[i] > 1: + * c_stride = mslice.strides[i] + */ + for (__pyx_t_1 = (__pyx_v_ndim - 1); __pyx_t_1 > -1; __pyx_t_1-=1) { + __pyx_v_i = __pyx_t_1; + + /* "View.MemoryView":1122 + * + * for i in range(ndim - 1, -1, -1): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * c_stride = mslice.strides[i] + * break + */ + __pyx_t_2 = ((__pyx_v_mslice->shape[__pyx_v_i]) > 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1123 + * for i in range(ndim - 1, -1, -1): + * if mslice.shape[i] > 1: + * c_stride = mslice.strides[i] # <<<<<<<<<<<<<< + * break + * + */ + __pyx_v_c_stride = (__pyx_v_mslice->strides[__pyx_v_i]); + + /* "View.MemoryView":1124 + * if mslice.shape[i] > 1: + * c_stride = mslice.strides[i] + * break # <<<<<<<<<<<<<< + * + * for i in range(ndim): + */ + goto __pyx_L4_break; + + /* "View.MemoryView":1122 + * + * for i in range(ndim - 1, -1, -1): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * c_stride = mslice.strides[i] + * break + */ + } + } + __pyx_L4_break:; + + /* "View.MemoryView":1126 + * break + * + * for i in range(ndim): # <<<<<<<<<<<<<< + * if mslice.shape[i] > 1: + * f_stride = mslice.strides[i] + */ + __pyx_t_1 = __pyx_v_ndim; + __pyx_t_3 = __pyx_t_1; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1127 + * + * for i in range(ndim): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * f_stride = mslice.strides[i] + * break + */ + __pyx_t_2 = ((__pyx_v_mslice->shape[__pyx_v_i]) > 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1128 + * for i in range(ndim): + * if mslice.shape[i] > 1: + * f_stride = mslice.strides[i] # <<<<<<<<<<<<<< + * break + * + */ + __pyx_v_f_stride = (__pyx_v_mslice->strides[__pyx_v_i]); + + /* "View.MemoryView":1129 + * if mslice.shape[i] > 1: + * f_stride = mslice.strides[i] + * break # <<<<<<<<<<<<<< + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): + */ + goto __pyx_L7_break; + + /* "View.MemoryView":1127 + * + * for i in range(ndim): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * f_stride = mslice.strides[i] + * break + */ + } + } + __pyx_L7_break:; + + /* "View.MemoryView":1131 + * break + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): # <<<<<<<<<<<<<< + * return 'C' + * else: + */ + __pyx_t_2 = (abs_py_ssize_t(__pyx_v_c_stride) <= abs_py_ssize_t(__pyx_v_f_stride)); + if (__pyx_t_2) { + + /* "View.MemoryView":1132 + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): + * return 'C' # <<<<<<<<<<<<<< + * else: + * return 'F' + */ + __pyx_r = 'C'; + goto __pyx_L0; + + /* "View.MemoryView":1131 + * break + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): # <<<<<<<<<<<<<< + * return 'C' + * else: + */ + } + + /* "View.MemoryView":1134 + * return 'C' + * else: + * return 'F' # <<<<<<<<<<<<<< + * + * @cython.cdivision(True) + */ + /*else*/ { + __pyx_r = 'F'; + goto __pyx_L0; + } + + /* "View.MemoryView":1113 + * + * @cname('__pyx_get_best_slice_order') + * cdef char get_best_order(__Pyx_memviewslice *mslice, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * """ + * Figure out the best memory access order for a given slice. + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1137 + * + * @cython.cdivision(True) + * cdef void _copy_strided_to_strided(char *src_data, Py_ssize_t *src_strides, # <<<<<<<<<<<<<< + * char *dst_data, Py_ssize_t *dst_strides, + * Py_ssize_t *src_shape, Py_ssize_t *dst_shape, + */ + +static void _copy_strided_to_strided(char *__pyx_v_src_data, Py_ssize_t *__pyx_v_src_strides, char *__pyx_v_dst_data, Py_ssize_t *__pyx_v_dst_strides, Py_ssize_t *__pyx_v_src_shape, Py_ssize_t *__pyx_v_dst_shape, int __pyx_v_ndim, size_t __pyx_v_itemsize) { + CYTHON_UNUSED Py_ssize_t __pyx_v_i; + CYTHON_UNUSED Py_ssize_t __pyx_v_src_extent; + Py_ssize_t __pyx_v_dst_extent; + Py_ssize_t __pyx_v_src_stride; + Py_ssize_t __pyx_v_dst_stride; + int __pyx_t_1; + int __pyx_t_2; + Py_ssize_t __pyx_t_3; + Py_ssize_t __pyx_t_4; + Py_ssize_t __pyx_t_5; + + /* "View.MemoryView":1144 + * + * cdef Py_ssize_t i + * cdef Py_ssize_t src_extent = src_shape[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t dst_extent = dst_shape[0] + * cdef Py_ssize_t src_stride = src_strides[0] + */ + __pyx_v_src_extent = (__pyx_v_src_shape[0]); + + /* "View.MemoryView":1145 + * cdef Py_ssize_t i + * cdef Py_ssize_t src_extent = src_shape[0] + * cdef Py_ssize_t dst_extent = dst_shape[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t src_stride = src_strides[0] + * cdef Py_ssize_t dst_stride = dst_strides[0] + */ + __pyx_v_dst_extent = (__pyx_v_dst_shape[0]); + + /* "View.MemoryView":1146 + * cdef Py_ssize_t src_extent = src_shape[0] + * cdef Py_ssize_t dst_extent = dst_shape[0] + * cdef Py_ssize_t src_stride = src_strides[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t dst_stride = dst_strides[0] + * + */ + __pyx_v_src_stride = (__pyx_v_src_strides[0]); + + /* "View.MemoryView":1147 + * cdef Py_ssize_t dst_extent = dst_shape[0] + * cdef Py_ssize_t src_stride = src_strides[0] + * cdef Py_ssize_t dst_stride = dst_strides[0] # <<<<<<<<<<<<<< + * + * if ndim == 1: + */ + __pyx_v_dst_stride = (__pyx_v_dst_strides[0]); + + /* "View.MemoryView":1149 + * cdef Py_ssize_t dst_stride = dst_strides[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): + */ + __pyx_t_1 = (__pyx_v_ndim == 1); + if (__pyx_t_1) { + + /* "View.MemoryView":1150 + * + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and # <<<<<<<<<<<<<< + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) + */ + __pyx_t_2 = (__pyx_v_src_stride > 0); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L5_bool_binop_done; + } + __pyx_t_2 = (__pyx_v_dst_stride > 0); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L5_bool_binop_done; + } + + /* "View.MemoryView":1151 + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): # <<<<<<<<<<<<<< + * memcpy(dst_data, src_data, itemsize * dst_extent) + * else: + */ + __pyx_t_2 = (((size_t)__pyx_v_src_stride) == __pyx_v_itemsize); + if (__pyx_t_2) { + __pyx_t_2 = (__pyx_v_itemsize == ((size_t)__pyx_v_dst_stride)); + } + __pyx_t_1 = __pyx_t_2; + __pyx_L5_bool_binop_done:; + + /* "View.MemoryView":1150 + * + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and # <<<<<<<<<<<<<< + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) + */ + if (__pyx_t_1) { + + /* "View.MemoryView":1152 + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) # <<<<<<<<<<<<<< + * else: + * for i in range(dst_extent): + */ + (void)(memcpy(__pyx_v_dst_data, __pyx_v_src_data, (__pyx_v_itemsize * __pyx_v_dst_extent))); + + /* "View.MemoryView":1150 + * + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and # <<<<<<<<<<<<<< + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) + */ + goto __pyx_L4; + } + + /* "View.MemoryView":1154 + * memcpy(dst_data, src_data, itemsize * dst_extent) + * else: + * for i in range(dst_extent): # <<<<<<<<<<<<<< + * memcpy(dst_data, src_data, itemsize) + * src_data += src_stride + */ + /*else*/ { + __pyx_t_3 = __pyx_v_dst_extent; + __pyx_t_4 = __pyx_t_3; + for (__pyx_t_5 = 0; __pyx_t_5 < __pyx_t_4; __pyx_t_5+=1) { + __pyx_v_i = __pyx_t_5; + + /* "View.MemoryView":1155 + * else: + * for i in range(dst_extent): + * memcpy(dst_data, src_data, itemsize) # <<<<<<<<<<<<<< + * src_data += src_stride + * dst_data += dst_stride + */ + (void)(memcpy(__pyx_v_dst_data, __pyx_v_src_data, __pyx_v_itemsize)); + + /* "View.MemoryView":1156 + * for i in range(dst_extent): + * memcpy(dst_data, src_data, itemsize) + * src_data += src_stride # <<<<<<<<<<<<<< + * dst_data += dst_stride + * else: + */ + __pyx_v_src_data = (__pyx_v_src_data + __pyx_v_src_stride); + + /* "View.MemoryView":1157 + * memcpy(dst_data, src_data, itemsize) + * src_data += src_stride + * dst_data += dst_stride # <<<<<<<<<<<<<< + * else: + * for i in range(dst_extent): + */ + __pyx_v_dst_data = (__pyx_v_dst_data + __pyx_v_dst_stride); + } + } + __pyx_L4:; + + /* "View.MemoryView":1149 + * cdef Py_ssize_t dst_stride = dst_strides[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1159 + * dst_data += dst_stride + * else: + * for i in range(dst_extent): # <<<<<<<<<<<<<< + * _copy_strided_to_strided(src_data, src_strides + 1, + * dst_data, dst_strides + 1, + */ + /*else*/ { + __pyx_t_3 = __pyx_v_dst_extent; + __pyx_t_4 = __pyx_t_3; + for (__pyx_t_5 = 0; __pyx_t_5 < __pyx_t_4; __pyx_t_5+=1) { + __pyx_v_i = __pyx_t_5; + + /* "View.MemoryView":1160 + * else: + * for i in range(dst_extent): + * _copy_strided_to_strided(src_data, src_strides + 1, # <<<<<<<<<<<<<< + * dst_data, dst_strides + 1, + * src_shape + 1, dst_shape + 1, + */ + _copy_strided_to_strided(__pyx_v_src_data, (__pyx_v_src_strides + 1), __pyx_v_dst_data, (__pyx_v_dst_strides + 1), (__pyx_v_src_shape + 1), (__pyx_v_dst_shape + 1), (__pyx_v_ndim - 1), __pyx_v_itemsize); + + /* "View.MemoryView":1164 + * src_shape + 1, dst_shape + 1, + * ndim - 1, itemsize) + * src_data += src_stride # <<<<<<<<<<<<<< + * dst_data += dst_stride + * + */ + __pyx_v_src_data = (__pyx_v_src_data + __pyx_v_src_stride); + + /* "View.MemoryView":1165 + * ndim - 1, itemsize) + * src_data += src_stride + * dst_data += dst_stride # <<<<<<<<<<<<<< + * + * cdef void copy_strided_to_strided(__Pyx_memviewslice *src, + */ + __pyx_v_dst_data = (__pyx_v_dst_data + __pyx_v_dst_stride); + } + } + __pyx_L3:; + + /* "View.MemoryView":1137 + * + * @cython.cdivision(True) + * cdef void _copy_strided_to_strided(char *src_data, Py_ssize_t *src_strides, # <<<<<<<<<<<<<< + * char *dst_data, Py_ssize_t *dst_strides, + * Py_ssize_t *src_shape, Py_ssize_t *dst_shape, + */ + + /* function exit code */ +} + +/* "View.MemoryView":1167 + * dst_data += dst_stride + * + * cdef void copy_strided_to_strided(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * int ndim, size_t itemsize) noexcept nogil: + */ + +static void copy_strided_to_strided(__Pyx_memviewslice *__pyx_v_src, __Pyx_memviewslice *__pyx_v_dst, int __pyx_v_ndim, size_t __pyx_v_itemsize) { + + /* "View.MemoryView":1170 + * __Pyx_memviewslice *dst, + * int ndim, size_t itemsize) noexcept nogil: + * _copy_strided_to_strided(src.data, src.strides, dst.data, dst.strides, # <<<<<<<<<<<<<< + * src.shape, dst.shape, ndim, itemsize) + * + */ + _copy_strided_to_strided(__pyx_v_src->data, __pyx_v_src->strides, __pyx_v_dst->data, __pyx_v_dst->strides, __pyx_v_src->shape, __pyx_v_dst->shape, __pyx_v_ndim, __pyx_v_itemsize); + + /* "View.MemoryView":1167 + * dst_data += dst_stride + * + * cdef void copy_strided_to_strided(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * int ndim, size_t itemsize) noexcept nogil: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1174 + * + * @cname('__pyx_memoryview_slice_get_size') + * cdef Py_ssize_t slice_get_size(__Pyx_memviewslice *src, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * "Return the size of the memory occupied by the slice in number of bytes" + * cdef Py_ssize_t shape, size = src.memview.view.itemsize + */ + +static Py_ssize_t __pyx_memoryview_slice_get_size(__Pyx_memviewslice *__pyx_v_src, int __pyx_v_ndim) { + Py_ssize_t __pyx_v_shape; + Py_ssize_t __pyx_v_size; + Py_ssize_t __pyx_r; + Py_ssize_t __pyx_t_1; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + + /* "View.MemoryView":1176 + * cdef Py_ssize_t slice_get_size(__Pyx_memviewslice *src, int ndim) noexcept nogil: + * "Return the size of the memory occupied by the slice in number of bytes" + * cdef Py_ssize_t shape, size = src.memview.view.itemsize # <<<<<<<<<<<<<< + * + * for shape in src.shape[:ndim]: + */ + __pyx_t_1 = __pyx_v_src->memview->view.itemsize; + __pyx_v_size = __pyx_t_1; + + /* "View.MemoryView":1178 + * cdef Py_ssize_t shape, size = src.memview.view.itemsize + * + * for shape in src.shape[:ndim]: # <<<<<<<<<<<<<< + * size *= shape + * + */ + __pyx_t_3 = (__pyx_v_src->shape + __pyx_v_ndim); + for (__pyx_t_4 = __pyx_v_src->shape; __pyx_t_4 < __pyx_t_3; __pyx_t_4++) { + __pyx_t_2 = __pyx_t_4; + __pyx_v_shape = (__pyx_t_2[0]); + + /* "View.MemoryView":1179 + * + * for shape in src.shape[:ndim]: + * size *= shape # <<<<<<<<<<<<<< + * + * return size + */ + __pyx_v_size = (__pyx_v_size * __pyx_v_shape); + } + + /* "View.MemoryView":1181 + * size *= shape + * + * return size # <<<<<<<<<<<<<< + * + * @cname('__pyx_fill_contig_strides_array') + */ + __pyx_r = __pyx_v_size; + goto __pyx_L0; + + /* "View.MemoryView":1174 + * + * @cname('__pyx_memoryview_slice_get_size') + * cdef Py_ssize_t slice_get_size(__Pyx_memviewslice *src, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * "Return the size of the memory occupied by the slice in number of bytes" + * cdef Py_ssize_t shape, size = src.memview.view.itemsize + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1184 + * + * @cname('__pyx_fill_contig_strides_array') + * cdef Py_ssize_t fill_contig_strides_array( # <<<<<<<<<<<<<< + * Py_ssize_t *shape, Py_ssize_t *strides, Py_ssize_t stride, + * int ndim, char order) noexcept nogil: + */ + +static Py_ssize_t __pyx_fill_contig_strides_array(Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, Py_ssize_t __pyx_v_stride, int __pyx_v_ndim, char __pyx_v_order) { + int __pyx_v_idx; + Py_ssize_t __pyx_r; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + + /* "View.MemoryView":1193 + * cdef int idx + * + * if order == 'F': # <<<<<<<<<<<<<< + * for idx in range(ndim): + * strides[idx] = stride + */ + __pyx_t_1 = (__pyx_v_order == 'F'); + if (__pyx_t_1) { + + /* "View.MemoryView":1194 + * + * if order == 'F': + * for idx in range(ndim): # <<<<<<<<<<<<<< + * strides[idx] = stride + * stride *= shape[idx] + */ + __pyx_t_2 = __pyx_v_ndim; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_idx = __pyx_t_4; + + /* "View.MemoryView":1195 + * if order == 'F': + * for idx in range(ndim): + * strides[idx] = stride # <<<<<<<<<<<<<< + * stride *= shape[idx] + * else: + */ + (__pyx_v_strides[__pyx_v_idx]) = __pyx_v_stride; + + /* "View.MemoryView":1196 + * for idx in range(ndim): + * strides[idx] = stride + * stride *= shape[idx] # <<<<<<<<<<<<<< + * else: + * for idx in range(ndim - 1, -1, -1): + */ + __pyx_v_stride = (__pyx_v_stride * (__pyx_v_shape[__pyx_v_idx])); + } + + /* "View.MemoryView":1193 + * cdef int idx + * + * if order == 'F': # <<<<<<<<<<<<<< + * for idx in range(ndim): + * strides[idx] = stride + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1198 + * stride *= shape[idx] + * else: + * for idx in range(ndim - 1, -1, -1): # <<<<<<<<<<<<<< + * strides[idx] = stride + * stride *= shape[idx] + */ + /*else*/ { + for (__pyx_t_2 = (__pyx_v_ndim - 1); __pyx_t_2 > -1; __pyx_t_2-=1) { + __pyx_v_idx = __pyx_t_2; + + /* "View.MemoryView":1199 + * else: + * for idx in range(ndim - 1, -1, -1): + * strides[idx] = stride # <<<<<<<<<<<<<< + * stride *= shape[idx] + * + */ + (__pyx_v_strides[__pyx_v_idx]) = __pyx_v_stride; + + /* "View.MemoryView":1200 + * for idx in range(ndim - 1, -1, -1): + * strides[idx] = stride + * stride *= shape[idx] # <<<<<<<<<<<<<< + * + * return stride + */ + __pyx_v_stride = (__pyx_v_stride * (__pyx_v_shape[__pyx_v_idx])); + } + } + __pyx_L3:; + + /* "View.MemoryView":1202 + * stride *= shape[idx] + * + * return stride # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_copy_data_to_temp') + */ + __pyx_r = __pyx_v_stride; + goto __pyx_L0; + + /* "View.MemoryView":1184 + * + * @cname('__pyx_fill_contig_strides_array') + * cdef Py_ssize_t fill_contig_strides_array( # <<<<<<<<<<<<<< + * Py_ssize_t *shape, Py_ssize_t *strides, Py_ssize_t stride, + * int ndim, char order) noexcept nogil: + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1205 + * + * @cname('__pyx_memoryview_copy_data_to_temp') + * cdef void *copy_data_to_temp(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *tmpslice, + * char order, + */ + +static void *__pyx_memoryview_copy_data_to_temp(__Pyx_memviewslice *__pyx_v_src, __Pyx_memviewslice *__pyx_v_tmpslice, char __pyx_v_order, int __pyx_v_ndim) { + int __pyx_v_i; + void *__pyx_v_result; + size_t __pyx_v_itemsize; + size_t __pyx_v_size; + void *__pyx_r; + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + struct __pyx_memoryview_obj *__pyx_t_4; + int __pyx_t_5; + int __pyx_t_6; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":1216 + * cdef void *result + * + * cdef size_t itemsize = src.memview.view.itemsize # <<<<<<<<<<<<<< + * cdef size_t size = slice_get_size(src, ndim) + * + */ + __pyx_t_1 = __pyx_v_src->memview->view.itemsize; + __pyx_v_itemsize = __pyx_t_1; + + /* "View.MemoryView":1217 + * + * cdef size_t itemsize = src.memview.view.itemsize + * cdef size_t size = slice_get_size(src, ndim) # <<<<<<<<<<<<<< + * + * result = malloc(size) + */ + __pyx_v_size = __pyx_memoryview_slice_get_size(__pyx_v_src, __pyx_v_ndim); + + /* "View.MemoryView":1219 + * cdef size_t size = slice_get_size(src, ndim) + * + * result = malloc(size) # <<<<<<<<<<<<<< + * if not result: + * _err_no_memory() + */ + __pyx_v_result = malloc(__pyx_v_size); + + /* "View.MemoryView":1220 + * + * result = malloc(size) + * if not result: # <<<<<<<<<<<<<< + * _err_no_memory() + * + */ + __pyx_t_2 = (!(__pyx_v_result != 0)); + if (__pyx_t_2) { + + /* "View.MemoryView":1221 + * result = malloc(size) + * if not result: + * _err_no_memory() # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_3 = __pyx_memoryview_err_no_memory(); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(0, 1221, __pyx_L1_error) + + /* "View.MemoryView":1220 + * + * result = malloc(size) + * if not result: # <<<<<<<<<<<<<< + * _err_no_memory() + * + */ + } + + /* "View.MemoryView":1224 + * + * + * tmpslice.data = result # <<<<<<<<<<<<<< + * tmpslice.memview = src.memview + * for i in range(ndim): + */ + __pyx_v_tmpslice->data = ((char *)__pyx_v_result); + + /* "View.MemoryView":1225 + * + * tmpslice.data = result + * tmpslice.memview = src.memview # <<<<<<<<<<<<<< + * for i in range(ndim): + * tmpslice.shape[i] = src.shape[i] + */ + __pyx_t_4 = __pyx_v_src->memview; + __pyx_v_tmpslice->memview = __pyx_t_4; + + /* "View.MemoryView":1226 + * tmpslice.data = result + * tmpslice.memview = src.memview + * for i in range(ndim): # <<<<<<<<<<<<<< + * tmpslice.shape[i] = src.shape[i] + * tmpslice.suboffsets[i] = -1 + */ + __pyx_t_3 = __pyx_v_ndim; + __pyx_t_5 = __pyx_t_3; + for (__pyx_t_6 = 0; __pyx_t_6 < __pyx_t_5; __pyx_t_6+=1) { + __pyx_v_i = __pyx_t_6; + + /* "View.MemoryView":1227 + * tmpslice.memview = src.memview + * for i in range(ndim): + * tmpslice.shape[i] = src.shape[i] # <<<<<<<<<<<<<< + * tmpslice.suboffsets[i] = -1 + * + */ + (__pyx_v_tmpslice->shape[__pyx_v_i]) = (__pyx_v_src->shape[__pyx_v_i]); + + /* "View.MemoryView":1228 + * for i in range(ndim): + * tmpslice.shape[i] = src.shape[i] + * tmpslice.suboffsets[i] = -1 # <<<<<<<<<<<<<< + * + * fill_contig_strides_array(&tmpslice.shape[0], &tmpslice.strides[0], itemsize, ndim, order) + */ + (__pyx_v_tmpslice->suboffsets[__pyx_v_i]) = -1L; + } + + /* "View.MemoryView":1230 + * tmpslice.suboffsets[i] = -1 + * + * fill_contig_strides_array(&tmpslice.shape[0], &tmpslice.strides[0], itemsize, ndim, order) # <<<<<<<<<<<<<< + * + * + */ + (void)(__pyx_fill_contig_strides_array((&(__pyx_v_tmpslice->shape[0])), (&(__pyx_v_tmpslice->strides[0])), __pyx_v_itemsize, __pyx_v_ndim, __pyx_v_order)); + + /* "View.MemoryView":1233 + * + * + * for i in range(ndim): # <<<<<<<<<<<<<< + * if tmpslice.shape[i] == 1: + * tmpslice.strides[i] = 0 + */ + __pyx_t_3 = __pyx_v_ndim; + __pyx_t_5 = __pyx_t_3; + for (__pyx_t_6 = 0; __pyx_t_6 < __pyx_t_5; __pyx_t_6+=1) { + __pyx_v_i = __pyx_t_6; + + /* "View.MemoryView":1234 + * + * for i in range(ndim): + * if tmpslice.shape[i] == 1: # <<<<<<<<<<<<<< + * tmpslice.strides[i] = 0 + * + */ + __pyx_t_2 = ((__pyx_v_tmpslice->shape[__pyx_v_i]) == 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1235 + * for i in range(ndim): + * if tmpslice.shape[i] == 1: + * tmpslice.strides[i] = 0 # <<<<<<<<<<<<<< + * + * if slice_is_contig(src[0], order, ndim): + */ + (__pyx_v_tmpslice->strides[__pyx_v_i]) = 0; + + /* "View.MemoryView":1234 + * + * for i in range(ndim): + * if tmpslice.shape[i] == 1: # <<<<<<<<<<<<<< + * tmpslice.strides[i] = 0 + * + */ + } + } + + /* "View.MemoryView":1237 + * tmpslice.strides[i] = 0 + * + * if slice_is_contig(src[0], order, ndim): # <<<<<<<<<<<<<< + * memcpy(result, src.data, size) + * else: + */ + __pyx_t_2 = __pyx_memviewslice_is_contig((__pyx_v_src[0]), __pyx_v_order, __pyx_v_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1238 + * + * if slice_is_contig(src[0], order, ndim): + * memcpy(result, src.data, size) # <<<<<<<<<<<<<< + * else: + * copy_strided_to_strided(src, tmpslice, ndim, itemsize) + */ + (void)(memcpy(__pyx_v_result, __pyx_v_src->data, __pyx_v_size)); + + /* "View.MemoryView":1237 + * tmpslice.strides[i] = 0 + * + * if slice_is_contig(src[0], order, ndim): # <<<<<<<<<<<<<< + * memcpy(result, src.data, size) + * else: + */ + goto __pyx_L9; + } + + /* "View.MemoryView":1240 + * memcpy(result, src.data, size) + * else: + * copy_strided_to_strided(src, tmpslice, ndim, itemsize) # <<<<<<<<<<<<<< + * + * return result + */ + /*else*/ { + copy_strided_to_strided(__pyx_v_src, __pyx_v_tmpslice, __pyx_v_ndim, __pyx_v_itemsize); + } + __pyx_L9:; + + /* "View.MemoryView":1242 + * copy_strided_to_strided(src, tmpslice, ndim, itemsize) + * + * return result # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = __pyx_v_result; + goto __pyx_L0; + + /* "View.MemoryView":1205 + * + * @cname('__pyx_memoryview_copy_data_to_temp') + * cdef void *copy_data_to_temp(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *tmpslice, + * char order, + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.copy_data_to_temp", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1247 + * + * @cname('__pyx_memoryview_err_extents') + * cdef int _err_extents(int i, Py_ssize_t extent1, # <<<<<<<<<<<<<< + * Py_ssize_t extent2) except -1 with gil: + * raise ValueError, f"got differing extents in dimension {i} (got {extent1} and {extent2})" + */ + +static int __pyx_memoryview_err_extents(int __pyx_v_i, Py_ssize_t __pyx_v_extent1, Py_ssize_t __pyx_v_extent2) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + Py_ssize_t __pyx_t_2; + Py_UCS4 __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_RefNannySetupContext("_err_extents", 0); + + /* "View.MemoryView":1249 + * cdef int _err_extents(int i, Py_ssize_t extent1, + * Py_ssize_t extent2) except -1 with gil: + * raise ValueError, f"got differing extents in dimension {i} (got {extent1} and {extent2})" # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_err_dim') + */ + __pyx_t_1 = PyTuple_New(7); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = 0; + __pyx_t_3 = 127; + __Pyx_INCREF(__pyx_kp_u_got_differing_extents_in_dimensi); + __pyx_t_2 += 35; + __Pyx_GIVEREF(__pyx_kp_u_got_differing_extents_in_dimensi); + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_kp_u_got_differing_extents_in_dimensi); + __pyx_t_4 = __Pyx_PyUnicode_From_int(__pyx_v_i, 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_2 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_t_4); + __pyx_t_4 = 0; + __Pyx_INCREF(__pyx_kp_u_got); + __pyx_t_2 += 6; + __Pyx_GIVEREF(__pyx_kp_u_got); + PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_kp_u_got); + __pyx_t_4 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_extent1, 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_2 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_1, 3, __pyx_t_4); + __pyx_t_4 = 0; + __Pyx_INCREF(__pyx_kp_u_and); + __pyx_t_2 += 5; + __Pyx_GIVEREF(__pyx_kp_u_and); + PyTuple_SET_ITEM(__pyx_t_1, 4, __pyx_kp_u_and); + __pyx_t_4 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_extent2, 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_2 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_1, 5, __pyx_t_4); + __pyx_t_4 = 0; + __Pyx_INCREF(__pyx_kp_u__7); + __pyx_t_2 += 1; + __Pyx_GIVEREF(__pyx_kp_u__7); + PyTuple_SET_ITEM(__pyx_t_1, 6, __pyx_kp_u__7); + __pyx_t_4 = __Pyx_PyUnicode_Join(__pyx_t_1, 7, __pyx_t_2, __pyx_t_3); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_t_4, 0, 0); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __PYX_ERR(0, 1249, __pyx_L1_error) + + /* "View.MemoryView":1247 + * + * @cname('__pyx_memoryview_err_extents') + * cdef int _err_extents(int i, Py_ssize_t extent1, # <<<<<<<<<<<<<< + * Py_ssize_t extent2) except -1 with gil: + * raise ValueError, f"got differing extents in dimension {i} (got {extent1} and {extent2})" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView._err_extents", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __Pyx_RefNannyFinishContext(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1252 + * + * @cname('__pyx_memoryview_err_dim') + * cdef int _err_dim(PyObject *error, str msg, int dim) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg % dim + * + */ + +static int __pyx_memoryview_err_dim(PyObject *__pyx_v_error, PyObject *__pyx_v_msg, int __pyx_v_dim) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_RefNannySetupContext("_err_dim", 0); + __Pyx_INCREF(__pyx_v_msg); + + /* "View.MemoryView":1253 + * @cname('__pyx_memoryview_err_dim') + * cdef int _err_dim(PyObject *error, str msg, int dim) except -1 with gil: + * raise error, msg % dim # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_err') + */ + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_dim); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 1253, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyString_FormatSafe(__pyx_v_msg, __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 1253, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(((PyObject *)__pyx_v_error), __pyx_t_2, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 1253, __pyx_L1_error) + + /* "View.MemoryView":1252 + * + * @cname('__pyx_memoryview_err_dim') + * cdef int _err_dim(PyObject *error, str msg, int dim) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg % dim + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView._err_dim", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __Pyx_XDECREF(__pyx_v_msg); + __Pyx_RefNannyFinishContext(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1256 + * + * @cname('__pyx_memoryview_err') + * cdef int _err(PyObject *error, str msg) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg + * + */ + +static int __pyx_memoryview_err(PyObject *__pyx_v_error, PyObject *__pyx_v_msg) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_RefNannySetupContext("_err", 0); + __Pyx_INCREF(__pyx_v_msg); + + /* "View.MemoryView":1257 + * @cname('__pyx_memoryview_err') + * cdef int _err(PyObject *error, str msg) except -1 with gil: + * raise error, msg # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_err_no_memory') + */ + __Pyx_Raise(((PyObject *)__pyx_v_error), __pyx_v_msg, 0, 0); + __PYX_ERR(0, 1257, __pyx_L1_error) + + /* "View.MemoryView":1256 + * + * @cname('__pyx_memoryview_err') + * cdef int _err(PyObject *error, str msg) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._err", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __Pyx_XDECREF(__pyx_v_msg); + __Pyx_RefNannyFinishContext(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1260 + * + * @cname('__pyx_memoryview_err_no_memory') + * cdef int _err_no_memory() except -1 with gil: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + +static int __pyx_memoryview_err_no_memory(void) { + int __pyx_r; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + + /* "View.MemoryView":1261 + * @cname('__pyx_memoryview_err_no_memory') + * cdef int _err_no_memory() except -1 with gil: + * raise MemoryError # <<<<<<<<<<<<<< + * + * + */ + PyErr_NoMemory(); __PYX_ERR(0, 1261, __pyx_L1_error) + + /* "View.MemoryView":1260 + * + * @cname('__pyx_memoryview_err_no_memory') + * cdef int _err_no_memory() except -1 with gil: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._err_no_memory", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1265 + * + * @cname('__pyx_memoryview_copy_contents') + * cdef int memoryview_copy_contents(__Pyx_memviewslice src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice dst, + * int src_ndim, int dst_ndim, + */ + +static int __pyx_memoryview_copy_contents(__Pyx_memviewslice __pyx_v_src, __Pyx_memviewslice __pyx_v_dst, int __pyx_v_src_ndim, int __pyx_v_dst_ndim, int __pyx_v_dtype_is_object) { + void *__pyx_v_tmpdata; + size_t __pyx_v_itemsize; + int __pyx_v_i; + char __pyx_v_order; + int __pyx_v_broadcasting; + int __pyx_v_direct_copy; + __Pyx_memviewslice __pyx_v_tmp; + int __pyx_v_ndim; + int __pyx_r; + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + int __pyx_t_5; + int __pyx_t_6; + void *__pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":1273 + * Check for overlapping memory and verify the shapes. + * """ + * cdef void *tmpdata = NULL # <<<<<<<<<<<<<< + * cdef size_t itemsize = src.memview.view.itemsize + * cdef int i + */ + __pyx_v_tmpdata = NULL; + + /* "View.MemoryView":1274 + * """ + * cdef void *tmpdata = NULL + * cdef size_t itemsize = src.memview.view.itemsize # <<<<<<<<<<<<<< + * cdef int i + * cdef char order = get_best_order(&src, src_ndim) + */ + __pyx_t_1 = __pyx_v_src.memview->view.itemsize; + __pyx_v_itemsize = __pyx_t_1; + + /* "View.MemoryView":1276 + * cdef size_t itemsize = src.memview.view.itemsize + * cdef int i + * cdef char order = get_best_order(&src, src_ndim) # <<<<<<<<<<<<<< + * cdef bint broadcasting = False + * cdef bint direct_copy = False + */ + __pyx_v_order = __pyx_get_best_slice_order((&__pyx_v_src), __pyx_v_src_ndim); + + /* "View.MemoryView":1277 + * cdef int i + * cdef char order = get_best_order(&src, src_ndim) + * cdef bint broadcasting = False # <<<<<<<<<<<<<< + * cdef bint direct_copy = False + * cdef __Pyx_memviewslice tmp + */ + __pyx_v_broadcasting = 0; + + /* "View.MemoryView":1278 + * cdef char order = get_best_order(&src, src_ndim) + * cdef bint broadcasting = False + * cdef bint direct_copy = False # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice tmp + * + */ + __pyx_v_direct_copy = 0; + + /* "View.MemoryView":1281 + * cdef __Pyx_memviewslice tmp + * + * if src_ndim < dst_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: + */ + __pyx_t_2 = (__pyx_v_src_ndim < __pyx_v_dst_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1282 + * + * if src_ndim < dst_ndim: + * broadcast_leading(&src, src_ndim, dst_ndim) # <<<<<<<<<<<<<< + * elif dst_ndim < src_ndim: + * broadcast_leading(&dst, dst_ndim, src_ndim) + */ + __pyx_memoryview_broadcast_leading((&__pyx_v_src), __pyx_v_src_ndim, __pyx_v_dst_ndim); + + /* "View.MemoryView":1281 + * cdef __Pyx_memviewslice tmp + * + * if src_ndim < dst_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1283 + * if src_ndim < dst_ndim: + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&dst, dst_ndim, src_ndim) + * + */ + __pyx_t_2 = (__pyx_v_dst_ndim < __pyx_v_src_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1284 + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: + * broadcast_leading(&dst, dst_ndim, src_ndim) # <<<<<<<<<<<<<< + * + * cdef int ndim = max(src_ndim, dst_ndim) + */ + __pyx_memoryview_broadcast_leading((&__pyx_v_dst), __pyx_v_dst_ndim, __pyx_v_src_ndim); + + /* "View.MemoryView":1283 + * if src_ndim < dst_ndim: + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&dst, dst_ndim, src_ndim) + * + */ + } + __pyx_L3:; + + /* "View.MemoryView":1286 + * broadcast_leading(&dst, dst_ndim, src_ndim) + * + * cdef int ndim = max(src_ndim, dst_ndim) # <<<<<<<<<<<<<< + * + * for i in range(ndim): + */ + __pyx_t_3 = __pyx_v_dst_ndim; + __pyx_t_4 = __pyx_v_src_ndim; + __pyx_t_2 = (__pyx_t_3 > __pyx_t_4); + if (__pyx_t_2) { + __pyx_t_5 = __pyx_t_3; + } else { + __pyx_t_5 = __pyx_t_4; + } + __pyx_v_ndim = __pyx_t_5; + + /* "View.MemoryView":1288 + * cdef int ndim = max(src_ndim, dst_ndim) + * + * for i in range(ndim): # <<<<<<<<<<<<<< + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: + */ + __pyx_t_5 = __pyx_v_ndim; + __pyx_t_3 = __pyx_t_5; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1289 + * + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: # <<<<<<<<<<<<<< + * if src.shape[i] == 1: + * broadcasting = True + */ + __pyx_t_2 = ((__pyx_v_src.shape[__pyx_v_i]) != (__pyx_v_dst.shape[__pyx_v_i])); + if (__pyx_t_2) { + + /* "View.MemoryView":1290 + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: # <<<<<<<<<<<<<< + * broadcasting = True + * src.strides[i] = 0 + */ + __pyx_t_2 = ((__pyx_v_src.shape[__pyx_v_i]) == 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1291 + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: + * broadcasting = True # <<<<<<<<<<<<<< + * src.strides[i] = 0 + * else: + */ + __pyx_v_broadcasting = 1; + + /* "View.MemoryView":1292 + * if src.shape[i] == 1: + * broadcasting = True + * src.strides[i] = 0 # <<<<<<<<<<<<<< + * else: + * _err_extents(i, dst.shape[i], src.shape[i]) + */ + (__pyx_v_src.strides[__pyx_v_i]) = 0; + + /* "View.MemoryView":1290 + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: # <<<<<<<<<<<<<< + * broadcasting = True + * src.strides[i] = 0 + */ + goto __pyx_L7; + } + + /* "View.MemoryView":1294 + * src.strides[i] = 0 + * else: + * _err_extents(i, dst.shape[i], src.shape[i]) # <<<<<<<<<<<<<< + * + * if src.suboffsets[i] >= 0: + */ + /*else*/ { + __pyx_t_6 = __pyx_memoryview_err_extents(__pyx_v_i, (__pyx_v_dst.shape[__pyx_v_i]), (__pyx_v_src.shape[__pyx_v_i])); if (unlikely(__pyx_t_6 == ((int)-1))) __PYX_ERR(0, 1294, __pyx_L1_error) + } + __pyx_L7:; + + /* "View.MemoryView":1289 + * + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: # <<<<<<<<<<<<<< + * if src.shape[i] == 1: + * broadcasting = True + */ + } + + /* "View.MemoryView":1296 + * _err_extents(i, dst.shape[i], src.shape[i]) + * + * if src.suboffsets[i] >= 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + */ + __pyx_t_2 = ((__pyx_v_src.suboffsets[__pyx_v_i]) >= 0); + if (__pyx_t_2) { + + /* "View.MemoryView":1297 + * + * if src.suboffsets[i] >= 0: + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) # <<<<<<<<<<<<<< + * + * if slices_overlap(&src, &dst, ndim, itemsize): + */ + __pyx_t_6 = __pyx_memoryview_err_dim(PyExc_ValueError, __pyx_kp_s_Dimension_d_is_not_direct, __pyx_v_i); if (unlikely(__pyx_t_6 == ((int)-1))) __PYX_ERR(0, 1297, __pyx_L1_error) + + /* "View.MemoryView":1296 + * _err_extents(i, dst.shape[i], src.shape[i]) + * + * if src.suboffsets[i] >= 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + */ + } + } + + /* "View.MemoryView":1299 + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + * if slices_overlap(&src, &dst, ndim, itemsize): # <<<<<<<<<<<<<< + * + * if not slice_is_contig(src, order, ndim): + */ + __pyx_t_2 = __pyx_slices_overlap((&__pyx_v_src), (&__pyx_v_dst), __pyx_v_ndim, __pyx_v_itemsize); + if (__pyx_t_2) { + + /* "View.MemoryView":1301 + * if slices_overlap(&src, &dst, ndim, itemsize): + * + * if not slice_is_contig(src, order, ndim): # <<<<<<<<<<<<<< + * order = get_best_order(&dst, ndim) + * + */ + __pyx_t_2 = (!__pyx_memviewslice_is_contig(__pyx_v_src, __pyx_v_order, __pyx_v_ndim)); + if (__pyx_t_2) { + + /* "View.MemoryView":1302 + * + * if not slice_is_contig(src, order, ndim): + * order = get_best_order(&dst, ndim) # <<<<<<<<<<<<<< + * + * tmpdata = copy_data_to_temp(&src, &tmp, order, ndim) + */ + __pyx_v_order = __pyx_get_best_slice_order((&__pyx_v_dst), __pyx_v_ndim); + + /* "View.MemoryView":1301 + * if slices_overlap(&src, &dst, ndim, itemsize): + * + * if not slice_is_contig(src, order, ndim): # <<<<<<<<<<<<<< + * order = get_best_order(&dst, ndim) + * + */ + } + + /* "View.MemoryView":1304 + * order = get_best_order(&dst, ndim) + * + * tmpdata = copy_data_to_temp(&src, &tmp, order, ndim) # <<<<<<<<<<<<<< + * src = tmp + * + */ + __pyx_t_7 = __pyx_memoryview_copy_data_to_temp((&__pyx_v_src), (&__pyx_v_tmp), __pyx_v_order, __pyx_v_ndim); if (unlikely(__pyx_t_7 == ((void *)NULL))) __PYX_ERR(0, 1304, __pyx_L1_error) + __pyx_v_tmpdata = __pyx_t_7; + + /* "View.MemoryView":1305 + * + * tmpdata = copy_data_to_temp(&src, &tmp, order, ndim) + * src = tmp # <<<<<<<<<<<<<< + * + * if not broadcasting: + */ + __pyx_v_src = __pyx_v_tmp; + + /* "View.MemoryView":1299 + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + * if slices_overlap(&src, &dst, ndim, itemsize): # <<<<<<<<<<<<<< + * + * if not slice_is_contig(src, order, ndim): + */ + } + + /* "View.MemoryView":1307 + * src = tmp + * + * if not broadcasting: # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = (!__pyx_v_broadcasting); + if (__pyx_t_2) { + + /* "View.MemoryView":1310 + * + * + * if slice_is_contig(src, 'C', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): + */ + __pyx_t_2 = __pyx_memviewslice_is_contig(__pyx_v_src, 'C', __pyx_v_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1311 + * + * if slice_is_contig(src, 'C', ndim): + * direct_copy = slice_is_contig(dst, 'C', ndim) # <<<<<<<<<<<<<< + * elif slice_is_contig(src, 'F', ndim): + * direct_copy = slice_is_contig(dst, 'F', ndim) + */ + __pyx_v_direct_copy = __pyx_memviewslice_is_contig(__pyx_v_dst, 'C', __pyx_v_ndim); + + /* "View.MemoryView":1310 + * + * + * if slice_is_contig(src, 'C', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): + */ + goto __pyx_L12; + } + + /* "View.MemoryView":1312 + * if slice_is_contig(src, 'C', ndim): + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + */ + __pyx_t_2 = __pyx_memviewslice_is_contig(__pyx_v_src, 'F', __pyx_v_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1313 + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): + * direct_copy = slice_is_contig(dst, 'F', ndim) # <<<<<<<<<<<<<< + * + * if direct_copy: + */ + __pyx_v_direct_copy = __pyx_memviewslice_is_contig(__pyx_v_dst, 'F', __pyx_v_ndim); + + /* "View.MemoryView":1312 + * if slice_is_contig(src, 'C', ndim): + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + */ + } + __pyx_L12:; + + /* "View.MemoryView":1315 + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + * if direct_copy: # <<<<<<<<<<<<<< + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + */ + if (__pyx_v_direct_copy) { + + /* "View.MemoryView":1317 + * if direct_copy: + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) # <<<<<<<<<<<<<< + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 0); + + /* "View.MemoryView":1318 + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) # <<<<<<<<<<<<<< + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * free(tmpdata) + */ + (void)(memcpy(__pyx_v_dst.data, __pyx_v_src.data, __pyx_memoryview_slice_get_size((&__pyx_v_src), __pyx_v_ndim))); + + /* "View.MemoryView":1319 + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) # <<<<<<<<<<<<<< + * free(tmpdata) + * return 0 + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 1); + + /* "View.MemoryView":1320 + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * free(tmpdata) # <<<<<<<<<<<<<< + * return 0 + * + */ + free(__pyx_v_tmpdata); + + /* "View.MemoryView":1321 + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * free(tmpdata) + * return 0 # <<<<<<<<<<<<<< + * + * if order == 'F' == get_best_order(&dst, ndim): + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":1315 + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + * if direct_copy: # <<<<<<<<<<<<<< + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + */ + } + + /* "View.MemoryView":1307 + * src = tmp + * + * if not broadcasting: # <<<<<<<<<<<<<< + * + * + */ + } + + /* "View.MemoryView":1323 + * return 0 + * + * if order == 'F' == get_best_order(&dst, ndim): # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = (__pyx_v_order == 'F'); + if (__pyx_t_2) { + __pyx_t_2 = ('F' == __pyx_get_best_slice_order((&__pyx_v_dst), __pyx_v_ndim)); + } + if (__pyx_t_2) { + + /* "View.MemoryView":1326 + * + * + * transpose_memslice(&src) # <<<<<<<<<<<<<< + * transpose_memslice(&dst) + * + */ + __pyx_t_5 = __pyx_memslice_transpose((&__pyx_v_src)); if (unlikely(__pyx_t_5 == ((int)-1))) __PYX_ERR(0, 1326, __pyx_L1_error) + + /* "View.MemoryView":1327 + * + * transpose_memslice(&src) + * transpose_memslice(&dst) # <<<<<<<<<<<<<< + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + */ + __pyx_t_5 = __pyx_memslice_transpose((&__pyx_v_dst)); if (unlikely(__pyx_t_5 == ((int)-1))) __PYX_ERR(0, 1327, __pyx_L1_error) + + /* "View.MemoryView":1323 + * return 0 + * + * if order == 'F' == get_best_order(&dst, ndim): # <<<<<<<<<<<<<< + * + * + */ + } + + /* "View.MemoryView":1329 + * transpose_memslice(&dst) + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) # <<<<<<<<<<<<<< + * copy_strided_to_strided(&src, &dst, ndim, itemsize) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 0); + + /* "View.MemoryView":1330 + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * copy_strided_to_strided(&src, &dst, ndim, itemsize) # <<<<<<<<<<<<<< + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * + */ + copy_strided_to_strided((&__pyx_v_src), (&__pyx_v_dst), __pyx_v_ndim, __pyx_v_itemsize); + + /* "View.MemoryView":1331 + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * copy_strided_to_strided(&src, &dst, ndim, itemsize) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) # <<<<<<<<<<<<<< + * + * free(tmpdata) + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 1); + + /* "View.MemoryView":1333 + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * + * free(tmpdata) # <<<<<<<<<<<<<< + * return 0 + * + */ + free(__pyx_v_tmpdata); + + /* "View.MemoryView":1334 + * + * free(tmpdata) + * return 0 # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_broadcast_leading') + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":1265 + * + * @cname('__pyx_memoryview_copy_contents') + * cdef int memoryview_copy_contents(__Pyx_memviewslice src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice dst, + * int src_ndim, int dst_ndim, + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.memoryview_copy_contents", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1337 + * + * @cname('__pyx_memoryview_broadcast_leading') + * cdef void broadcast_leading(__Pyx_memviewslice *mslice, # <<<<<<<<<<<<<< + * int ndim, + * int ndim_other) noexcept nogil: + */ + +static void __pyx_memoryview_broadcast_leading(__Pyx_memviewslice *__pyx_v_mslice, int __pyx_v_ndim, int __pyx_v_ndim_other) { + int __pyx_v_i; + int __pyx_v_offset; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + + /* "View.MemoryView":1341 + * int ndim_other) noexcept nogil: + * cdef int i + * cdef int offset = ndim_other - ndim # <<<<<<<<<<<<<< + * + * for i in range(ndim - 1, -1, -1): + */ + __pyx_v_offset = (__pyx_v_ndim_other - __pyx_v_ndim); + + /* "View.MemoryView":1343 + * cdef int offset = ndim_other - ndim + * + * for i in range(ndim - 1, -1, -1): # <<<<<<<<<<<<<< + * mslice.shape[i + offset] = mslice.shape[i] + * mslice.strides[i + offset] = mslice.strides[i] + */ + for (__pyx_t_1 = (__pyx_v_ndim - 1); __pyx_t_1 > -1; __pyx_t_1-=1) { + __pyx_v_i = __pyx_t_1; + + /* "View.MemoryView":1344 + * + * for i in range(ndim - 1, -1, -1): + * mslice.shape[i + offset] = mslice.shape[i] # <<<<<<<<<<<<<< + * mslice.strides[i + offset] = mslice.strides[i] + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] + */ + (__pyx_v_mslice->shape[(__pyx_v_i + __pyx_v_offset)]) = (__pyx_v_mslice->shape[__pyx_v_i]); + + /* "View.MemoryView":1345 + * for i in range(ndim - 1, -1, -1): + * mslice.shape[i + offset] = mslice.shape[i] + * mslice.strides[i + offset] = mslice.strides[i] # <<<<<<<<<<<<<< + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] + * + */ + (__pyx_v_mslice->strides[(__pyx_v_i + __pyx_v_offset)]) = (__pyx_v_mslice->strides[__pyx_v_i]); + + /* "View.MemoryView":1346 + * mslice.shape[i + offset] = mslice.shape[i] + * mslice.strides[i + offset] = mslice.strides[i] + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] # <<<<<<<<<<<<<< + * + * for i in range(offset): + */ + (__pyx_v_mslice->suboffsets[(__pyx_v_i + __pyx_v_offset)]) = (__pyx_v_mslice->suboffsets[__pyx_v_i]); + } + + /* "View.MemoryView":1348 + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] + * + * for i in range(offset): # <<<<<<<<<<<<<< + * mslice.shape[i] = 1 + * mslice.strides[i] = mslice.strides[0] + */ + __pyx_t_1 = __pyx_v_offset; + __pyx_t_2 = __pyx_t_1; + for (__pyx_t_3 = 0; __pyx_t_3 < __pyx_t_2; __pyx_t_3+=1) { + __pyx_v_i = __pyx_t_3; + + /* "View.MemoryView":1349 + * + * for i in range(offset): + * mslice.shape[i] = 1 # <<<<<<<<<<<<<< + * mslice.strides[i] = mslice.strides[0] + * mslice.suboffsets[i] = -1 + */ + (__pyx_v_mslice->shape[__pyx_v_i]) = 1; + + /* "View.MemoryView":1350 + * for i in range(offset): + * mslice.shape[i] = 1 + * mslice.strides[i] = mslice.strides[0] # <<<<<<<<<<<<<< + * mslice.suboffsets[i] = -1 + * + */ + (__pyx_v_mslice->strides[__pyx_v_i]) = (__pyx_v_mslice->strides[0]); + + /* "View.MemoryView":1351 + * mslice.shape[i] = 1 + * mslice.strides[i] = mslice.strides[0] + * mslice.suboffsets[i] = -1 # <<<<<<<<<<<<<< + * + * + */ + (__pyx_v_mslice->suboffsets[__pyx_v_i]) = -1L; + } + + /* "View.MemoryView":1337 + * + * @cname('__pyx_memoryview_broadcast_leading') + * cdef void broadcast_leading(__Pyx_memviewslice *mslice, # <<<<<<<<<<<<<< + * int ndim, + * int ndim_other) noexcept nogil: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1359 + * + * @cname('__pyx_memoryview_refcount_copying') + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: # <<<<<<<<<<<<<< + * + * if dtype_is_object: + */ + +static void __pyx_memoryview_refcount_copying(__Pyx_memviewslice *__pyx_v_dst, int __pyx_v_dtype_is_object, int __pyx_v_ndim, int __pyx_v_inc) { + + /* "View.MemoryView":1361 + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: + * + * if dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice_with_gil(dst.data, dst.shape, dst.strides, ndim, inc) + * + */ + if (__pyx_v_dtype_is_object) { + + /* "View.MemoryView":1362 + * + * if dtype_is_object: + * refcount_objects_in_slice_with_gil(dst.data, dst.shape, dst.strides, ndim, inc) # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_refcount_objects_in_slice_with_gil') + */ + __pyx_memoryview_refcount_objects_in_slice_with_gil(__pyx_v_dst->data, __pyx_v_dst->shape, __pyx_v_dst->strides, __pyx_v_ndim, __pyx_v_inc); + + /* "View.MemoryView":1361 + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: + * + * if dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice_with_gil(dst.data, dst.shape, dst.strides, ndim, inc) + * + */ + } + + /* "View.MemoryView":1359 + * + * @cname('__pyx_memoryview_refcount_copying') + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: # <<<<<<<<<<<<<< + * + * if dtype_is_object: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1365 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice_with_gil') + * cdef void refcount_objects_in_slice_with_gil(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * bint inc) noexcept with gil: + */ + +static void __pyx_memoryview_refcount_objects_in_slice_with_gil(char *__pyx_v_data, Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, int __pyx_v_ndim, int __pyx_v_inc) { + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + + /* "View.MemoryView":1368 + * Py_ssize_t *strides, int ndim, + * bint inc) noexcept with gil: + * refcount_objects_in_slice(data, shape, strides, ndim, inc) # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_refcount_objects_in_slice') + */ + __pyx_memoryview_refcount_objects_in_slice(__pyx_v_data, __pyx_v_shape, __pyx_v_strides, __pyx_v_ndim, __pyx_v_inc); + + /* "View.MemoryView":1365 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice_with_gil') + * cdef void refcount_objects_in_slice_with_gil(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * bint inc) noexcept with gil: + */ + + /* function exit code */ + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif +} + +/* "View.MemoryView":1371 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice') + * cdef void refcount_objects_in_slice(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, bint inc) noexcept: + * cdef Py_ssize_t i + */ + +static void __pyx_memoryview_refcount_objects_in_slice(char *__pyx_v_data, Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, int __pyx_v_ndim, int __pyx_v_inc) { + CYTHON_UNUSED Py_ssize_t __pyx_v_i; + Py_ssize_t __pyx_v_stride; + Py_ssize_t __pyx_t_1; + Py_ssize_t __pyx_t_2; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + + /* "View.MemoryView":1374 + * Py_ssize_t *strides, int ndim, bint inc) noexcept: + * cdef Py_ssize_t i + * cdef Py_ssize_t stride = strides[0] # <<<<<<<<<<<<<< + * + * for i in range(shape[0]): + */ + __pyx_v_stride = (__pyx_v_strides[0]); + + /* "View.MemoryView":1376 + * cdef Py_ssize_t stride = strides[0] + * + * for i in range(shape[0]): # <<<<<<<<<<<<<< + * if ndim == 1: + * if inc: + */ + __pyx_t_1 = (__pyx_v_shape[0]); + __pyx_t_2 = __pyx_t_1; + for (__pyx_t_3 = 0; __pyx_t_3 < __pyx_t_2; __pyx_t_3+=1) { + __pyx_v_i = __pyx_t_3; + + /* "View.MemoryView":1377 + * + * for i in range(shape[0]): + * if ndim == 1: # <<<<<<<<<<<<<< + * if inc: + * Py_INCREF(( data)[0]) + */ + __pyx_t_4 = (__pyx_v_ndim == 1); + if (__pyx_t_4) { + + /* "View.MemoryView":1378 + * for i in range(shape[0]): + * if ndim == 1: + * if inc: # <<<<<<<<<<<<<< + * Py_INCREF(( data)[0]) + * else: + */ + if (__pyx_v_inc) { + + /* "View.MemoryView":1379 + * if ndim == 1: + * if inc: + * Py_INCREF(( data)[0]) # <<<<<<<<<<<<<< + * else: + * Py_DECREF(( data)[0]) + */ + Py_INCREF((((PyObject **)__pyx_v_data)[0])); + + /* "View.MemoryView":1378 + * for i in range(shape[0]): + * if ndim == 1: + * if inc: # <<<<<<<<<<<<<< + * Py_INCREF(( data)[0]) + * else: + */ + goto __pyx_L6; + } + + /* "View.MemoryView":1381 + * Py_INCREF(( data)[0]) + * else: + * Py_DECREF(( data)[0]) # <<<<<<<<<<<<<< + * else: + * refcount_objects_in_slice(data, shape + 1, strides + 1, ndim - 1, inc) + */ + /*else*/ { + Py_DECREF((((PyObject **)__pyx_v_data)[0])); + } + __pyx_L6:; + + /* "View.MemoryView":1377 + * + * for i in range(shape[0]): + * if ndim == 1: # <<<<<<<<<<<<<< + * if inc: + * Py_INCREF(( data)[0]) + */ + goto __pyx_L5; + } + + /* "View.MemoryView":1383 + * Py_DECREF(( data)[0]) + * else: + * refcount_objects_in_slice(data, shape + 1, strides + 1, ndim - 1, inc) # <<<<<<<<<<<<<< + * + * data += stride + */ + /*else*/ { + __pyx_memoryview_refcount_objects_in_slice(__pyx_v_data, (__pyx_v_shape + 1), (__pyx_v_strides + 1), (__pyx_v_ndim - 1), __pyx_v_inc); + } + __pyx_L5:; + + /* "View.MemoryView":1385 + * refcount_objects_in_slice(data, shape + 1, strides + 1, ndim - 1, inc) + * + * data += stride # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_data = (__pyx_v_data + __pyx_v_stride); + } + + /* "View.MemoryView":1371 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice') + * cdef void refcount_objects_in_slice(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, bint inc) noexcept: + * cdef Py_ssize_t i + */ + + /* function exit code */ +} + +/* "View.MemoryView":1391 + * + * @cname('__pyx_memoryview_slice_assign_scalar') + * cdef void slice_assign_scalar(__Pyx_memviewslice *dst, int ndim, # <<<<<<<<<<<<<< + * size_t itemsize, void *item, + * bint dtype_is_object) noexcept nogil: + */ + +static void __pyx_memoryview_slice_assign_scalar(__Pyx_memviewslice *__pyx_v_dst, int __pyx_v_ndim, size_t __pyx_v_itemsize, void *__pyx_v_item, int __pyx_v_dtype_is_object) { + + /* "View.MemoryView":1394 + * size_t itemsize, void *item, + * bint dtype_is_object) noexcept nogil: + * refcount_copying(dst, dtype_is_object, ndim, inc=False) # <<<<<<<<<<<<<< + * _slice_assign_scalar(dst.data, dst.shape, dst.strides, ndim, itemsize, item) + * refcount_copying(dst, dtype_is_object, ndim, inc=True) + */ + __pyx_memoryview_refcount_copying(__pyx_v_dst, __pyx_v_dtype_is_object, __pyx_v_ndim, 0); + + /* "View.MemoryView":1395 + * bint dtype_is_object) noexcept nogil: + * refcount_copying(dst, dtype_is_object, ndim, inc=False) + * _slice_assign_scalar(dst.data, dst.shape, dst.strides, ndim, itemsize, item) # <<<<<<<<<<<<<< + * refcount_copying(dst, dtype_is_object, ndim, inc=True) + * + */ + __pyx_memoryview__slice_assign_scalar(__pyx_v_dst->data, __pyx_v_dst->shape, __pyx_v_dst->strides, __pyx_v_ndim, __pyx_v_itemsize, __pyx_v_item); + + /* "View.MemoryView":1396 + * refcount_copying(dst, dtype_is_object, ndim, inc=False) + * _slice_assign_scalar(dst.data, dst.shape, dst.strides, ndim, itemsize, item) + * refcount_copying(dst, dtype_is_object, ndim, inc=True) # <<<<<<<<<<<<<< + * + * + */ + __pyx_memoryview_refcount_copying(__pyx_v_dst, __pyx_v_dtype_is_object, __pyx_v_ndim, 1); + + /* "View.MemoryView":1391 + * + * @cname('__pyx_memoryview_slice_assign_scalar') + * cdef void slice_assign_scalar(__Pyx_memviewslice *dst, int ndim, # <<<<<<<<<<<<<< + * size_t itemsize, void *item, + * bint dtype_is_object) noexcept nogil: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1400 + * + * @cname('__pyx_memoryview__slice_assign_scalar') + * cdef void _slice_assign_scalar(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * size_t itemsize, void *item) noexcept nogil: + */ + +static void __pyx_memoryview__slice_assign_scalar(char *__pyx_v_data, Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, int __pyx_v_ndim, size_t __pyx_v_itemsize, void *__pyx_v_item) { + CYTHON_UNUSED Py_ssize_t __pyx_v_i; + Py_ssize_t __pyx_v_stride; + Py_ssize_t __pyx_v_extent; + int __pyx_t_1; + Py_ssize_t __pyx_t_2; + Py_ssize_t __pyx_t_3; + Py_ssize_t __pyx_t_4; + + /* "View.MemoryView":1404 + * size_t itemsize, void *item) noexcept nogil: + * cdef Py_ssize_t i + * cdef Py_ssize_t stride = strides[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t extent = shape[0] + * + */ + __pyx_v_stride = (__pyx_v_strides[0]); + + /* "View.MemoryView":1405 + * cdef Py_ssize_t i + * cdef Py_ssize_t stride = strides[0] + * cdef Py_ssize_t extent = shape[0] # <<<<<<<<<<<<<< + * + * if ndim == 1: + */ + __pyx_v_extent = (__pyx_v_shape[0]); + + /* "View.MemoryView":1407 + * cdef Py_ssize_t extent = shape[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * for i in range(extent): + * memcpy(data, item, itemsize) + */ + __pyx_t_1 = (__pyx_v_ndim == 1); + if (__pyx_t_1) { + + /* "View.MemoryView":1408 + * + * if ndim == 1: + * for i in range(extent): # <<<<<<<<<<<<<< + * memcpy(data, item, itemsize) + * data += stride + */ + __pyx_t_2 = __pyx_v_extent; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1409 + * if ndim == 1: + * for i in range(extent): + * memcpy(data, item, itemsize) # <<<<<<<<<<<<<< + * data += stride + * else: + */ + (void)(memcpy(__pyx_v_data, __pyx_v_item, __pyx_v_itemsize)); + + /* "View.MemoryView":1410 + * for i in range(extent): + * memcpy(data, item, itemsize) + * data += stride # <<<<<<<<<<<<<< + * else: + * for i in range(extent): + */ + __pyx_v_data = (__pyx_v_data + __pyx_v_stride); + } + + /* "View.MemoryView":1407 + * cdef Py_ssize_t extent = shape[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * for i in range(extent): + * memcpy(data, item, itemsize) + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1412 + * data += stride + * else: + * for i in range(extent): # <<<<<<<<<<<<<< + * _slice_assign_scalar(data, shape + 1, strides + 1, ndim - 1, itemsize, item) + * data += stride + */ + /*else*/ { + __pyx_t_2 = __pyx_v_extent; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1413 + * else: + * for i in range(extent): + * _slice_assign_scalar(data, shape + 1, strides + 1, ndim - 1, itemsize, item) # <<<<<<<<<<<<<< + * data += stride + * + */ + __pyx_memoryview__slice_assign_scalar(__pyx_v_data, (__pyx_v_shape + 1), (__pyx_v_strides + 1), (__pyx_v_ndim - 1), __pyx_v_itemsize, __pyx_v_item); + + /* "View.MemoryView":1414 + * for i in range(extent): + * _slice_assign_scalar(data, shape + 1, strides + 1, ndim - 1, itemsize, item) + * data += stride # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_data = (__pyx_v_data + __pyx_v_stride); + } + } + __pyx_L3:; + + /* "View.MemoryView":1400 + * + * @cname('__pyx_memoryview__slice_assign_scalar') + * cdef void _slice_assign_scalar(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * size_t itemsize, void *item) noexcept nogil: + */ + + /* function exit code */ +} + +/* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_1__pyx_unpickle_Enum(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_15View_dot_MemoryView_1__pyx_unpickle_Enum = {"__pyx_unpickle_Enum", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15View_dot_MemoryView_1__pyx_unpickle_Enum, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15View_dot_MemoryView_1__pyx_unpickle_Enum(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v___pyx_type = 0; + long __pyx_v___pyx_checksum; + PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__pyx_unpickle_Enum (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_type,&__pyx_n_s_pyx_checksum,&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_type)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 1, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_checksum)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 1, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle_Enum", 1, 3, 3, 1); __PYX_ERR(0, 1, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 1, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle_Enum", 1, 3, 3, 2); __PYX_ERR(0, 1, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__pyx_unpickle_Enum") < 0)) __PYX_ERR(0, 1, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + } + __pyx_v___pyx_type = values[0]; + __pyx_v___pyx_checksum = __Pyx_PyInt_As_long(values[1]); if (unlikely((__pyx_v___pyx_checksum == (long)-1) && PyErr_Occurred())) __PYX_ERR(0, 1, __pyx_L3_error) + __pyx_v___pyx_state = values[2]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle_Enum", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 1, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.__pyx_unpickle_Enum", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15View_dot_MemoryView___pyx_unpickle_Enum(__pyx_self, __pyx_v___pyx_type, __pyx_v___pyx_checksum, __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView___pyx_unpickle_Enum(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v___pyx_type, long __pyx_v___pyx_checksum, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_v___pyx_PickleError = 0; + PyObject *__pyx_v___pyx_result = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_unpickle_Enum", 1); + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + */ + __pyx_t_1 = __Pyx_PyInt_From_long(__pyx_v___pyx_checksum); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 4, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = (__Pyx_PySequence_ContainsTF(__pyx_t_1, __pyx_tuple__8, Py_NE)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 4, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (__pyx_t_2) { + + /* "(tree fragment)":5 + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): + * from pickle import PickleError as __pyx_PickleError # <<<<<<<<<<<<<< + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) + */ + __pyx_t_1 = PyList_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_s_PickleError); + __Pyx_GIVEREF(__pyx_n_s_PickleError); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_s_PickleError)) __PYX_ERR(0, 5, __pyx_L1_error); + __pyx_t_3 = __Pyx_Import(__pyx_n_s_pickle, __pyx_t_1, 0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_ImportFrom(__pyx_t_3, __pyx_n_s_PickleError); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_t_1); + __pyx_v___pyx_PickleError = __pyx_t_1; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "(tree fragment)":6 + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum # <<<<<<<<<<<<<< + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: + */ + __pyx_t_3 = __Pyx_PyInt_From_long(__pyx_v___pyx_checksum); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_Incompatible_checksums_0x_x_vs_0, __pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_v___pyx_PickleError, __pyx_t_1, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 6, __pyx_L1_error) + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + */ + } + + /* "(tree fragment)":7 + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) # <<<<<<<<<<<<<< + * if __pyx_state is not None: + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_MemviewEnum_type), __pyx_n_s_new); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 7, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = NULL; + __pyx_t_5 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_5 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_4, __pyx_v___pyx_type}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_5, 1+__pyx_t_5); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 7, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_v___pyx_result = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":8 + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + */ + __pyx_t_2 = (__pyx_v___pyx_state != Py_None); + if (__pyx_t_2) { + + /* "(tree fragment)":9 + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) # <<<<<<<<<<<<<< + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + */ + if (!(likely(PyTuple_CheckExact(__pyx_v___pyx_state))||((__pyx_v___pyx_state) == Py_None) || __Pyx_RaiseUnexpectedTypeError("tuple", __pyx_v___pyx_state))) __PYX_ERR(0, 9, __pyx_L1_error) + __pyx_t_1 = __pyx_unpickle_Enum__set_state(((struct __pyx_MemviewEnum_obj *)__pyx_v___pyx_result), ((PyObject*)__pyx_v___pyx_state)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 9, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":8 + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + */ + } + + /* "(tree fragment)":10 + * if __pyx_state is not None: + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result # <<<<<<<<<<<<<< + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v___pyx_result); + __pyx_r = __pyx_v___pyx_result; + goto __pyx_L0; + + /* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.__pyx_unpickle_Enum", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v___pyx_PickleError); + __Pyx_XDECREF(__pyx_v___pyx_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":11 + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): # <<<<<<<<<<<<<< + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + */ + +static PyObject *__pyx_unpickle_Enum__set_state(struct __pyx_MemviewEnum_obj *__pyx_v___pyx_result, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + int __pyx_t_8; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_unpickle_Enum__set_state", 1); + + /* "(tree fragment)":12 + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] # <<<<<<<<<<<<<< + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + * __pyx_result.__dict__.update(__pyx_state[1]) + */ + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(0, 12, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 12, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + __Pyx_GOTREF(__pyx_v___pyx_result->name); + __Pyx_DECREF(__pyx_v___pyx_result->name); + __pyx_v___pyx_result->name = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":13 + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): # <<<<<<<<<<<<<< + * __pyx_result.__dict__.update(__pyx_state[1]) + */ + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); + __PYX_ERR(0, 13, __pyx_L1_error) + } + __pyx_t_3 = __Pyx_PyTuple_GET_SIZE(__pyx_v___pyx_state); if (unlikely(__pyx_t_3 == ((Py_ssize_t)-1))) __PYX_ERR(0, 13, __pyx_L1_error) + __pyx_t_4 = (__pyx_t_3 > 1); + if (__pyx_t_4) { + } else { + __pyx_t_2 = __pyx_t_4; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_4 = __Pyx_HasAttr(((PyObject *)__pyx_v___pyx_result), __pyx_n_s_dict); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(0, 13, __pyx_L1_error) + __pyx_t_2 = __pyx_t_4; + __pyx_L4_bool_binop_done:; + if (__pyx_t_2) { + + /* "(tree fragment)":14 + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + * __pyx_result.__dict__.update(__pyx_state[1]) # <<<<<<<<<<<<<< + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v___pyx_result), __pyx_n_s_dict); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_update); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(0, 14, __pyx_L1_error) + } + __pyx_t_5 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_7 = NULL; + __pyx_t_8 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_6))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_6); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_6); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_6, function); + __pyx_t_8 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_7, __pyx_t_5}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_6, __pyx_callargs+1-__pyx_t_8, 1+__pyx_t_8); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":13 + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): # <<<<<<<<<<<<<< + * __pyx_result.__dict__.update(__pyx_state[1]) + */ + } + + /* "(tree fragment)":11 + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): # <<<<<<<<<<<<<< + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("View.MemoryView.__pyx_unpickle_Enum__set_state", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "BufferFormatFromTypeInfo":1450 + * + * @cname('__pyx_format_from_typeinfo') + * cdef bytes format_from_typeinfo(__Pyx_TypeInfo *type): # <<<<<<<<<<<<<< + * cdef __Pyx_StructField *field + * cdef __pyx_typeinfo_string fmt + */ + +static PyObject *__pyx_format_from_typeinfo(__Pyx_TypeInfo *__pyx_v_type) { + __Pyx_StructField *__pyx_v_field; + struct __pyx_typeinfo_string __pyx_v_fmt; + PyObject *__pyx_v_part = 0; + PyObject *__pyx_v_result = 0; + PyObject *__pyx_v_alignment = NULL; + PyObject *__pyx_v_parts = NULL; + PyObject *__pyx_v_extents = NULL; + Py_ssize_t __pyx_7genexpr__pyx_v_i; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + __Pyx_StructField *__pyx_t_3; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + int __pyx_t_7; + int __pyx_t_8; + Py_ssize_t __pyx_t_9; + Py_UCS4 __pyx_t_10; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("format_from_typeinfo", 1); + + /* "BufferFormatFromTypeInfo":1456 + * cdef Py_ssize_t i + * + * if type.typegroup == 'S': # <<<<<<<<<<<<<< + * assert type.fields != NULL + * assert type.fields.type != NULL + */ + __pyx_t_1 = (__pyx_v_type->typegroup == 'S'); + if (__pyx_t_1) { + + /* "BufferFormatFromTypeInfo":1457 + * + * if type.typegroup == 'S': + * assert type.fields != NULL # <<<<<<<<<<<<<< + * assert type.fields.type != NULL + * + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_1 = (__pyx_v_type->fields != NULL); + if (unlikely(!__pyx_t_1)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(0, 1457, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(0, 1457, __pyx_L1_error) + #endif + + /* "BufferFormatFromTypeInfo":1458 + * if type.typegroup == 'S': + * assert type.fields != NULL + * assert type.fields.type != NULL # <<<<<<<<<<<<<< + * + * if type.flags & __PYX_BUF_FLAGS_PACKED_STRUCT: + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_1 = (__pyx_v_type->fields->type != NULL); + if (unlikely(!__pyx_t_1)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(0, 1458, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(0, 1458, __pyx_L1_error) + #endif + + /* "BufferFormatFromTypeInfo":1460 + * assert type.fields.type != NULL + * + * if type.flags & __PYX_BUF_FLAGS_PACKED_STRUCT: # <<<<<<<<<<<<<< + * alignment = b'^' + * else: + */ + __pyx_t_1 = ((__pyx_v_type->flags & __PYX_BUF_FLAGS_PACKED_STRUCT) != 0); + if (__pyx_t_1) { + + /* "BufferFormatFromTypeInfo":1461 + * + * if type.flags & __PYX_BUF_FLAGS_PACKED_STRUCT: + * alignment = b'^' # <<<<<<<<<<<<<< + * else: + * alignment = b'' + */ + __Pyx_INCREF(__pyx_kp_b__9); + __pyx_v_alignment = __pyx_kp_b__9; + + /* "BufferFormatFromTypeInfo":1460 + * assert type.fields.type != NULL + * + * if type.flags & __PYX_BUF_FLAGS_PACKED_STRUCT: # <<<<<<<<<<<<<< + * alignment = b'^' + * else: + */ + goto __pyx_L4; + } + + /* "BufferFormatFromTypeInfo":1463 + * alignment = b'^' + * else: + * alignment = b'' # <<<<<<<<<<<<<< + * + * parts = [b"T{"] + */ + /*else*/ { + __Pyx_INCREF(__pyx_kp_b__10); + __pyx_v_alignment = __pyx_kp_b__10; + } + __pyx_L4:; + + /* "BufferFormatFromTypeInfo":1465 + * alignment = b'' + * + * parts = [b"T{"] # <<<<<<<<<<<<<< + * field = type.fields + * + */ + __pyx_t_2 = PyList_New(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 1465, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_INCREF(__pyx_kp_b_T); + __Pyx_GIVEREF(__pyx_kp_b_T); + if (__Pyx_PyList_SET_ITEM(__pyx_t_2, 0, __pyx_kp_b_T)) __PYX_ERR(0, 1465, __pyx_L1_error); + __pyx_v_parts = ((PyObject*)__pyx_t_2); + __pyx_t_2 = 0; + + /* "BufferFormatFromTypeInfo":1466 + * + * parts = [b"T{"] + * field = type.fields # <<<<<<<<<<<<<< + * + * while field.type: + */ + __pyx_t_3 = __pyx_v_type->fields; + __pyx_v_field = __pyx_t_3; + + /* "BufferFormatFromTypeInfo":1468 + * field = type.fields + * + * while field.type: # <<<<<<<<<<<<<< + * part = format_from_typeinfo(field.type) + * parts.append(part + b':' + field.name + b':') + */ + while (1) { + __pyx_t_1 = (__pyx_v_field->type != 0); + if (!__pyx_t_1) break; + + /* "BufferFormatFromTypeInfo":1469 + * + * while field.type: + * part = format_from_typeinfo(field.type) # <<<<<<<<<<<<<< + * parts.append(part + b':' + field.name + b':') + * field += 1 + */ + __pyx_t_2 = __pyx_format_from_typeinfo(__pyx_v_field->type); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 1469, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_XDECREF_SET(__pyx_v_part, ((PyObject*)__pyx_t_2)); + __pyx_t_2 = 0; + + /* "BufferFormatFromTypeInfo":1470 + * while field.type: + * part = format_from_typeinfo(field.type) + * parts.append(part + b':' + field.name + b':') # <<<<<<<<<<<<<< + * field += 1 + * + */ + __pyx_t_2 = PyNumber_Add(__pyx_v_part, __pyx_kp_b__11); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 1470, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __Pyx_PyBytes_FromString(__pyx_v_field->name); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 1470, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = PyNumber_Add(__pyx_t_2, __pyx_t_4); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 1470, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = PyNumber_Add(__pyx_t_5, __pyx_kp_b__11); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 1470, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_6 = __Pyx_PyList_Append(__pyx_v_parts, __pyx_t_4); if (unlikely(__pyx_t_6 == ((int)-1))) __PYX_ERR(0, 1470, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "BufferFormatFromTypeInfo":1471 + * part = format_from_typeinfo(field.type) + * parts.append(part + b':' + field.name + b':') + * field += 1 # <<<<<<<<<<<<<< + * + * result = alignment.join(parts) + b'}' + */ + __pyx_v_field = (__pyx_v_field + 1); + } + + /* "BufferFormatFromTypeInfo":1473 + * field += 1 + * + * result = alignment.join(parts) + b'}' # <<<<<<<<<<<<<< + * else: + * fmt = __Pyx_TypeInfoToFormat(type) + */ + __pyx_t_4 = __Pyx_PyBytes_Join(__pyx_v_alignment, __pyx_v_parts); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 1473, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = PyNumber_Add(__pyx_t_4, __pyx_kp_b__12); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 1473, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (!(likely(PyBytes_CheckExact(__pyx_t_5))||((__pyx_t_5) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_t_5))) __PYX_ERR(0, 1473, __pyx_L1_error) + __pyx_v_result = ((PyObject*)__pyx_t_5); + __pyx_t_5 = 0; + + /* "BufferFormatFromTypeInfo":1456 + * cdef Py_ssize_t i + * + * if type.typegroup == 'S': # <<<<<<<<<<<<<< + * assert type.fields != NULL + * assert type.fields.type != NULL + */ + goto __pyx_L3; + } + + /* "BufferFormatFromTypeInfo":1475 + * result = alignment.join(parts) + b'}' + * else: + * fmt = __Pyx_TypeInfoToFormat(type) # <<<<<<<<<<<<<< + * result = fmt.string + * if type.arraysize[0]: + */ + /*else*/ { + __pyx_v_fmt = __Pyx_TypeInfoToFormat(__pyx_v_type); + + /* "BufferFormatFromTypeInfo":1476 + * else: + * fmt = __Pyx_TypeInfoToFormat(type) + * result = fmt.string # <<<<<<<<<<<<<< + * if type.arraysize[0]: + * extents = [f"{type.arraysize[i]}" for i in range(type.ndim)] + */ + __pyx_t_5 = __Pyx_PyObject_FromString(__pyx_v_fmt.string); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 1476, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_v_result = ((PyObject*)__pyx_t_5); + __pyx_t_5 = 0; + + /* "BufferFormatFromTypeInfo":1477 + * fmt = __Pyx_TypeInfoToFormat(type) + * result = fmt.string + * if type.arraysize[0]: # <<<<<<<<<<<<<< + * extents = [f"{type.arraysize[i]}" for i in range(type.ndim)] + * result = f"({u','.join(extents)})".encode('ascii') + result + */ + __pyx_t_1 = ((__pyx_v_type->arraysize[0]) != 0); + if (__pyx_t_1) { + + /* "BufferFormatFromTypeInfo":1478 + * result = fmt.string + * if type.arraysize[0]: + * extents = [f"{type.arraysize[i]}" for i in range(type.ndim)] # <<<<<<<<<<<<<< + * result = f"({u','.join(extents)})".encode('ascii') + result + * + */ + { /* enter inner scope */ + __pyx_t_5 = PyList_New(0); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 1478, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_7 = __pyx_v_type->ndim; + __pyx_t_8 = __pyx_t_7; + for (__pyx_t_9 = 0; __pyx_t_9 < __pyx_t_8; __pyx_t_9+=1) { + __pyx_7genexpr__pyx_v_i = __pyx_t_9; + __pyx_t_4 = __Pyx_PyUnicode_From_size_t((__pyx_v_type->arraysize[__pyx_7genexpr__pyx_v_i]), 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 1478, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_5, (PyObject*)__pyx_t_4))) __PYX_ERR(0, 1478, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + } + } /* exit inner scope */ + __pyx_v_extents = ((PyObject*)__pyx_t_5); + __pyx_t_5 = 0; + + /* "BufferFormatFromTypeInfo":1479 + * if type.arraysize[0]: + * extents = [f"{type.arraysize[i]}" for i in range(type.ndim)] + * result = f"({u','.join(extents)})".encode('ascii') + result # <<<<<<<<<<<<<< + * + * return result + */ + __pyx_t_5 = PyTuple_New(3); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 1479, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_9 = 0; + __pyx_t_10 = 127; + __Pyx_INCREF(__pyx_kp_u__13); + __pyx_t_9 += 1; + __Pyx_GIVEREF(__pyx_kp_u__13); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_kp_u__13); + __pyx_t_4 = PyUnicode_Join(__pyx_kp_u__14, __pyx_v_extents); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 1479, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_10 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_4) > __pyx_t_10) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_4) : __pyx_t_10; + __pyx_t_9 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_4); + __pyx_t_4 = 0; + __Pyx_INCREF(__pyx_kp_u__7); + __pyx_t_9 += 1; + __Pyx_GIVEREF(__pyx_kp_u__7); + PyTuple_SET_ITEM(__pyx_t_5, 2, __pyx_kp_u__7); + __pyx_t_4 = __Pyx_PyUnicode_Join(__pyx_t_5, 3, __pyx_t_9, __pyx_t_10); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 1479, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_5 = PyUnicode_AsASCIIString(((PyObject*)__pyx_t_4)); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 1479, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = PyNumber_Add(__pyx_t_5, __pyx_v_result); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 1479, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (!(likely(PyBytes_CheckExact(__pyx_t_4)) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_t_4))) __PYX_ERR(0, 1479, __pyx_L1_error) + __Pyx_DECREF_SET(__pyx_v_result, ((PyObject*)__pyx_t_4)); + __pyx_t_4 = 0; + + /* "BufferFormatFromTypeInfo":1477 + * fmt = __Pyx_TypeInfoToFormat(type) + * result = fmt.string + * if type.arraysize[0]: # <<<<<<<<<<<<<< + * extents = [f"{type.arraysize[i]}" for i in range(type.ndim)] + * result = f"({u','.join(extents)})".encode('ascii') + result + */ + } + } + __pyx_L3:; + + /* "BufferFormatFromTypeInfo":1481 + * result = f"({u','.join(extents)})".encode('ascii') + result + * + * return result # <<<<<<<<<<<<<< + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_result); + __pyx_r = __pyx_v_result; + goto __pyx_L0; + + /* "BufferFormatFromTypeInfo":1450 + * + * @cname('__pyx_format_from_typeinfo') + * cdef bytes format_from_typeinfo(__Pyx_TypeInfo *type): # <<<<<<<<<<<<<< + * cdef __Pyx_StructField *field + * cdef __pyx_typeinfo_string fmt + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("BufferFormatFromTypeInfo.format_from_typeinfo", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_part); + __Pyx_XDECREF(__pyx_v_result); + __Pyx_XDECREF(__pyx_v_alignment); + __Pyx_XDECREF(__pyx_v_parts); + __Pyx_XDECREF(__pyx_v_extents); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":245 + * + * @property + * cdef inline PyObject* base(self) nogil: # <<<<<<<<<<<<<< + * """Returns a borrowed reference to the object owning the data/memory. + * """ + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_7ndarray_4base_base(PyArrayObject *__pyx_v_self) { + PyObject *__pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":248 + * """Returns a borrowed reference to the object owning the data/memory. + * """ + * return PyArray_BASE(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_BASE(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":245 + * + * @property + * cdef inline PyObject* base(self) nogil: # <<<<<<<<<<<<<< + * """Returns a borrowed reference to the object owning the data/memory. + * """ + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":251 + * + * @property + * cdef inline dtype descr(self): # <<<<<<<<<<<<<< + * """Returns an owned reference to the dtype of the array. + * """ + */ + +static CYTHON_INLINE PyArray_Descr *__pyx_f_5numpy_7ndarray_5descr_descr(PyArrayObject *__pyx_v_self) { + PyArray_Descr *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyArray_Descr *__pyx_t_1; + __Pyx_RefNannySetupContext("descr", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":254 + * """Returns an owned reference to the dtype of the array. + * """ + * return PyArray_DESCR(self) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF((PyObject *)__pyx_r); + __pyx_t_1 = PyArray_DESCR(__pyx_v_self); + __Pyx_INCREF((PyObject *)((PyArray_Descr *)__pyx_t_1)); + __pyx_r = ((PyArray_Descr *)__pyx_t_1); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":251 + * + * @property + * cdef inline dtype descr(self): # <<<<<<<<<<<<<< + * """Returns an owned reference to the dtype of the array. + * """ + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF((PyObject *)__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":257 + * + * @property + * cdef inline int ndim(self) nogil: # <<<<<<<<<<<<<< + * """Returns the number of dimensions in the array. + * """ + */ + +static CYTHON_INLINE int __pyx_f_5numpy_7ndarray_4ndim_ndim(PyArrayObject *__pyx_v_self) { + int __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":260 + * """Returns the number of dimensions in the array. + * """ + * return PyArray_NDIM(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_NDIM(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":257 + * + * @property + * cdef inline int ndim(self) nogil: # <<<<<<<<<<<<<< + * """Returns the number of dimensions in the array. + * """ + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":263 + * + * @property + * cdef inline npy_intp *shape(self) nogil: # <<<<<<<<<<<<<< + * """Returns a pointer to the dimensions/shape of the array. + * The number of elements matches the number of dimensions of the array (ndim). + */ + +static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_5shape_shape(PyArrayObject *__pyx_v_self) { + npy_intp *__pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":268 + * Can return NULL for 0-dimensional arrays. + * """ + * return PyArray_DIMS(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_DIMS(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":263 + * + * @property + * cdef inline npy_intp *shape(self) nogil: # <<<<<<<<<<<<<< + * """Returns a pointer to the dimensions/shape of the array. + * The number of elements matches the number of dimensions of the array (ndim). + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":271 + * + * @property + * cdef inline npy_intp *strides(self) nogil: # <<<<<<<<<<<<<< + * """Returns a pointer to the strides of the array. + * The number of elements matches the number of dimensions of the array (ndim). + */ + +static CYTHON_INLINE npy_intp *__pyx_f_5numpy_7ndarray_7strides_strides(PyArrayObject *__pyx_v_self) { + npy_intp *__pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":275 + * The number of elements matches the number of dimensions of the array (ndim). + * """ + * return PyArray_STRIDES(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_STRIDES(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":271 + * + * @property + * cdef inline npy_intp *strides(self) nogil: # <<<<<<<<<<<<<< + * """Returns a pointer to the strides of the array. + * The number of elements matches the number of dimensions of the array (ndim). + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":278 + * + * @property + * cdef inline npy_intp size(self) nogil: # <<<<<<<<<<<<<< + * """Returns the total size (in number of elements) of the array. + * """ + */ + +static CYTHON_INLINE npy_intp __pyx_f_5numpy_7ndarray_4size_size(PyArrayObject *__pyx_v_self) { + npy_intp __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":281 + * """Returns the total size (in number of elements) of the array. + * """ + * return PyArray_SIZE(self) # <<<<<<<<<<<<<< + * + * @property + */ + __pyx_r = PyArray_SIZE(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":278 + * + * @property + * cdef inline npy_intp size(self) nogil: # <<<<<<<<<<<<<< + * """Returns the total size (in number of elements) of the array. + * """ + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":284 + * + * @property + * cdef inline char* data(self) nogil: # <<<<<<<<<<<<<< + * """The pointer to the data buffer as a char*. + * This is provided for legacy reasons to avoid direct struct field access. + */ + +static CYTHON_INLINE char *__pyx_f_5numpy_7ndarray_4data_data(PyArrayObject *__pyx_v_self) { + char *__pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":290 + * of `PyArray_DATA()` instead, which returns a 'void*'. + * """ + * return PyArray_BYTES(self) # <<<<<<<<<<<<<< + * + * ctypedef unsigned char npy_bool + */ + __pyx_r = PyArray_BYTES(__pyx_v_self); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":284 + * + * @property + * cdef inline char* data(self) nogil: # <<<<<<<<<<<<<< + * """The pointer to the data buffer as a char*. + * This is provided for legacy reasons to avoid direct struct field access. + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":773 + * ctypedef npy_cdouble complex_t + * + * cdef inline object PyArray_MultiIterNew1(a): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(1, a) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew1(PyObject *__pyx_v_a) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew1", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":774 + * + * cdef inline object PyArray_MultiIterNew1(a): + * return PyArray_MultiIterNew(1, a) # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew2(a, b): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(1, ((void *)__pyx_v_a)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 774, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":773 + * ctypedef npy_cdouble complex_t + * + * cdef inline object PyArray_MultiIterNew1(a): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(1, a) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew1", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":776 + * return PyArray_MultiIterNew(1, a) + * + * cdef inline object PyArray_MultiIterNew2(a, b): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(2, a, b) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew2(PyObject *__pyx_v_a, PyObject *__pyx_v_b) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew2", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":777 + * + * cdef inline object PyArray_MultiIterNew2(a, b): + * return PyArray_MultiIterNew(2, a, b) # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew3(a, b, c): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(2, ((void *)__pyx_v_a), ((void *)__pyx_v_b)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 777, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":776 + * return PyArray_MultiIterNew(1, a) + * + * cdef inline object PyArray_MultiIterNew2(a, b): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(2, a, b) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew2", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":779 + * return PyArray_MultiIterNew(2, a, b) + * + * cdef inline object PyArray_MultiIterNew3(a, b, c): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(3, a, b, c) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew3(PyObject *__pyx_v_a, PyObject *__pyx_v_b, PyObject *__pyx_v_c) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew3", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":780 + * + * cdef inline object PyArray_MultiIterNew3(a, b, c): + * return PyArray_MultiIterNew(3, a, b, c) # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew4(a, b, c, d): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(3, ((void *)__pyx_v_a), ((void *)__pyx_v_b), ((void *)__pyx_v_c)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 780, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":779 + * return PyArray_MultiIterNew(2, a, b) + * + * cdef inline object PyArray_MultiIterNew3(a, b, c): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(3, a, b, c) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew3", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":782 + * return PyArray_MultiIterNew(3, a, b, c) + * + * cdef inline object PyArray_MultiIterNew4(a, b, c, d): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(4, a, b, c, d) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew4(PyObject *__pyx_v_a, PyObject *__pyx_v_b, PyObject *__pyx_v_c, PyObject *__pyx_v_d) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew4", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":783 + * + * cdef inline object PyArray_MultiIterNew4(a, b, c, d): + * return PyArray_MultiIterNew(4, a, b, c, d) # <<<<<<<<<<<<<< + * + * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(4, ((void *)__pyx_v_a), ((void *)__pyx_v_b), ((void *)__pyx_v_c), ((void *)__pyx_v_d)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 783, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":782 + * return PyArray_MultiIterNew(3, a, b, c) + * + * cdef inline object PyArray_MultiIterNew4(a, b, c, d): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(4, a, b, c, d) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew4", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":785 + * return PyArray_MultiIterNew(4, a, b, c, d) + * + * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(5, a, b, c, d, e) + * + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyArray_MultiIterNew5(PyObject *__pyx_v_a, PyObject *__pyx_v_b, PyObject *__pyx_v_c, PyObject *__pyx_v_d, PyObject *__pyx_v_e) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("PyArray_MultiIterNew5", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":786 + * + * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): + * return PyArray_MultiIterNew(5, a, b, c, d, e) # <<<<<<<<<<<<<< + * + * cdef inline tuple PyDataType_SHAPE(dtype d): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyArray_MultiIterNew(5, ((void *)__pyx_v_a), ((void *)__pyx_v_b), ((void *)__pyx_v_c), ((void *)__pyx_v_d), ((void *)__pyx_v_e)); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 786, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":785 + * return PyArray_MultiIterNew(4, a, b, c, d) + * + * cdef inline object PyArray_MultiIterNew5(a, b, c, d, e): # <<<<<<<<<<<<<< + * return PyArray_MultiIterNew(5, a, b, c, d, e) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("numpy.PyArray_MultiIterNew5", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":788 + * return PyArray_MultiIterNew(5, a, b, c, d, e) + * + * cdef inline tuple PyDataType_SHAPE(dtype d): # <<<<<<<<<<<<<< + * if PyDataType_HASSUBARRAY(d): + * return d.subarray.shape + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_PyDataType_SHAPE(PyArray_Descr *__pyx_v_d) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + __Pyx_RefNannySetupContext("PyDataType_SHAPE", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":789 + * + * cdef inline tuple PyDataType_SHAPE(dtype d): + * if PyDataType_HASSUBARRAY(d): # <<<<<<<<<<<<<< + * return d.subarray.shape + * else: + */ + __pyx_t_1 = PyDataType_HASSUBARRAY(__pyx_v_d); + if (__pyx_t_1) { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":790 + * cdef inline tuple PyDataType_SHAPE(dtype d): + * if PyDataType_HASSUBARRAY(d): + * return d.subarray.shape # <<<<<<<<<<<<<< + * else: + * return () + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(((PyObject*)__pyx_v_d->subarray->shape)); + __pyx_r = ((PyObject*)__pyx_v_d->subarray->shape); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":789 + * + * cdef inline tuple PyDataType_SHAPE(dtype d): + * if PyDataType_HASSUBARRAY(d): # <<<<<<<<<<<<<< + * return d.subarray.shape + * else: + */ + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":792 + * return d.subarray.shape + * else: + * return () # <<<<<<<<<<<<<< + * + * + */ + /*else*/ { + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_empty_tuple); + __pyx_r = __pyx_empty_tuple; + goto __pyx_L0; + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":788 + * return PyArray_MultiIterNew(5, a, b, c, d, e) + * + * cdef inline tuple PyDataType_SHAPE(dtype d): # <<<<<<<<<<<<<< + * if PyDataType_HASSUBARRAY(d): + * return d.subarray.shape + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":968 + * int _import_umath() except -1 + * + * cdef inline void set_array_base(ndarray arr, object base): # <<<<<<<<<<<<<< + * Py_INCREF(base) # important to do this before stealing the reference below! + * PyArray_SetBaseObject(arr, base) + */ + +static CYTHON_INLINE void __pyx_f_5numpy_set_array_base(PyArrayObject *__pyx_v_arr, PyObject *__pyx_v_base) { + int __pyx_t_1; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":969 + * + * cdef inline void set_array_base(ndarray arr, object base): + * Py_INCREF(base) # important to do this before stealing the reference below! # <<<<<<<<<<<<<< + * PyArray_SetBaseObject(arr, base) + * + */ + Py_INCREF(__pyx_v_base); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":970 + * cdef inline void set_array_base(ndarray arr, object base): + * Py_INCREF(base) # important to do this before stealing the reference below! + * PyArray_SetBaseObject(arr, base) # <<<<<<<<<<<<<< + * + * cdef inline object get_array_base(ndarray arr): + */ + __pyx_t_1 = PyArray_SetBaseObject(__pyx_v_arr, __pyx_v_base); if (unlikely(__pyx_t_1 == ((int)-1))) __PYX_ERR(2, 970, __pyx_L1_error) + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":968 + * int _import_umath() except -1 + * + * cdef inline void set_array_base(ndarray arr, object base): # <<<<<<<<<<<<<< + * Py_INCREF(base) # important to do this before stealing the reference below! + * PyArray_SetBaseObject(arr, base) + */ + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("numpy.set_array_base", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_L0:; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":972 + * PyArray_SetBaseObject(arr, base) + * + * cdef inline object get_array_base(ndarray arr): # <<<<<<<<<<<<<< + * base = PyArray_BASE(arr) + * if base is NULL: + */ + +static CYTHON_INLINE PyObject *__pyx_f_5numpy_get_array_base(PyArrayObject *__pyx_v_arr) { + PyObject *__pyx_v_base; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + __Pyx_RefNannySetupContext("get_array_base", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":973 + * + * cdef inline object get_array_base(ndarray arr): + * base = PyArray_BASE(arr) # <<<<<<<<<<<<<< + * if base is NULL: + * return None + */ + __pyx_v_base = PyArray_BASE(__pyx_v_arr); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":974 + * cdef inline object get_array_base(ndarray arr): + * base = PyArray_BASE(arr) + * if base is NULL: # <<<<<<<<<<<<<< + * return None + * return base + */ + __pyx_t_1 = (__pyx_v_base == NULL); + if (__pyx_t_1) { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":975 + * base = PyArray_BASE(arr) + * if base is NULL: + * return None # <<<<<<<<<<<<<< + * return base + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":974 + * cdef inline object get_array_base(ndarray arr): + * base = PyArray_BASE(arr) + * if base is NULL: # <<<<<<<<<<<<<< + * return None + * return base + */ + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":976 + * if base is NULL: + * return None + * return base # <<<<<<<<<<<<<< + * + * # Versions of the import_* functions which are more suitable for + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(((PyObject *)__pyx_v_base)); + __pyx_r = ((PyObject *)__pyx_v_base); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":972 + * PyArray_SetBaseObject(arr, base) + * + * cdef inline object get_array_base(ndarray arr): # <<<<<<<<<<<<<< + * base = PyArray_BASE(arr) + * if base is NULL: + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":980 + * # Versions of the import_* functions which are more suitable for + * # Cython code. + * cdef inline int import_array() except -1: # <<<<<<<<<<<<<< + * try: + * __pyx_import_array() + */ + +static CYTHON_INLINE int __pyx_f_5numpy_import_array(void) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("import_array", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":981 + * # Cython code. + * cdef inline int import_array() except -1: + * try: # <<<<<<<<<<<<<< + * __pyx_import_array() + * except Exception: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":982 + * cdef inline int import_array() except -1: + * try: + * __pyx_import_array() # <<<<<<<<<<<<<< + * except Exception: + * raise ImportError("numpy.core.multiarray failed to import") + */ + __pyx_t_4 = _import_array(); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(2, 982, __pyx_L3_error) + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":981 + * # Cython code. + * cdef inline int import_array() except -1: + * try: # <<<<<<<<<<<<<< + * __pyx_import_array() + * except Exception: + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L8_try_end; + __pyx_L3_error:; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":983 + * try: + * __pyx_import_array() + * except Exception: # <<<<<<<<<<<<<< + * raise ImportError("numpy.core.multiarray failed to import") + * + */ + __pyx_t_4 = __Pyx_PyErr_ExceptionMatches(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0]))); + if (__pyx_t_4) { + __Pyx_AddTraceback("numpy.import_array", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_6, &__pyx_t_7) < 0) __PYX_ERR(2, 983, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_7); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":984 + * __pyx_import_array() + * except Exception: + * raise ImportError("numpy.core.multiarray failed to import") # <<<<<<<<<<<<<< + * + * cdef inline int import_umath() except -1: + */ + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_builtin_ImportError, __pyx_tuple__15, NULL); if (unlikely(!__pyx_t_8)) __PYX_ERR(2, 984, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_Raise(__pyx_t_8, 0, 0, 0); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __PYX_ERR(2, 984, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":981 + * # Cython code. + * cdef inline int import_array() except -1: + * try: # <<<<<<<<<<<<<< + * __pyx_import_array() + * except Exception: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + goto __pyx_L1_error; + __pyx_L8_try_end:; + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":980 + * # Versions of the import_* functions which are more suitable for + * # Cython code. + * cdef inline int import_array() except -1: # <<<<<<<<<<<<<< + * try: + * __pyx_import_array() + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("numpy.import_array", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":986 + * raise ImportError("numpy.core.multiarray failed to import") + * + * cdef inline int import_umath() except -1: # <<<<<<<<<<<<<< + * try: + * _import_umath() + */ + +static CYTHON_INLINE int __pyx_f_5numpy_import_umath(void) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("import_umath", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":987 + * + * cdef inline int import_umath() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":988 + * cdef inline int import_umath() except -1: + * try: + * _import_umath() # <<<<<<<<<<<<<< + * except Exception: + * raise ImportError("numpy.core.umath failed to import") + */ + __pyx_t_4 = _import_umath(); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(2, 988, __pyx_L3_error) + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":987 + * + * cdef inline int import_umath() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L8_try_end; + __pyx_L3_error:; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":989 + * try: + * _import_umath() + * except Exception: # <<<<<<<<<<<<<< + * raise ImportError("numpy.core.umath failed to import") + * + */ + __pyx_t_4 = __Pyx_PyErr_ExceptionMatches(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0]))); + if (__pyx_t_4) { + __Pyx_AddTraceback("numpy.import_umath", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_6, &__pyx_t_7) < 0) __PYX_ERR(2, 989, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_7); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":990 + * _import_umath() + * except Exception: + * raise ImportError("numpy.core.umath failed to import") # <<<<<<<<<<<<<< + * + * cdef inline int import_ufunc() except -1: + */ + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_builtin_ImportError, __pyx_tuple__16, NULL); if (unlikely(!__pyx_t_8)) __PYX_ERR(2, 990, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_Raise(__pyx_t_8, 0, 0, 0); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __PYX_ERR(2, 990, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":987 + * + * cdef inline int import_umath() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + goto __pyx_L1_error; + __pyx_L8_try_end:; + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":986 + * raise ImportError("numpy.core.multiarray failed to import") + * + * cdef inline int import_umath() except -1: # <<<<<<<<<<<<<< + * try: + * _import_umath() + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("numpy.import_umath", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":992 + * raise ImportError("numpy.core.umath failed to import") + * + * cdef inline int import_ufunc() except -1: # <<<<<<<<<<<<<< + * try: + * _import_umath() + */ + +static CYTHON_INLINE int __pyx_f_5numpy_import_ufunc(void) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("import_ufunc", 1); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":993 + * + * cdef inline int import_ufunc() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":994 + * cdef inline int import_ufunc() except -1: + * try: + * _import_umath() # <<<<<<<<<<<<<< + * except Exception: + * raise ImportError("numpy.core.umath failed to import") + */ + __pyx_t_4 = _import_umath(); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(2, 994, __pyx_L3_error) + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":993 + * + * cdef inline int import_ufunc() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L8_try_end; + __pyx_L3_error:; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":995 + * try: + * _import_umath() + * except Exception: # <<<<<<<<<<<<<< + * raise ImportError("numpy.core.umath failed to import") + * + */ + __pyx_t_4 = __Pyx_PyErr_ExceptionMatches(((PyObject *)(&((PyTypeObject*)PyExc_Exception)[0]))); + if (__pyx_t_4) { + __Pyx_AddTraceback("numpy.import_ufunc", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_6, &__pyx_t_7) < 0) __PYX_ERR(2, 995, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_7); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":996 + * _import_umath() + * except Exception: + * raise ImportError("numpy.core.umath failed to import") # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_8 = __Pyx_PyObject_Call(__pyx_builtin_ImportError, __pyx_tuple__16, NULL); if (unlikely(!__pyx_t_8)) __PYX_ERR(2, 996, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_Raise(__pyx_t_8, 0, 0, 0); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __PYX_ERR(2, 996, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":993 + * + * cdef inline int import_ufunc() except -1: + * try: # <<<<<<<<<<<<<< + * _import_umath() + * except Exception: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + goto __pyx_L1_error; + __pyx_L8_try_end:; + } + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":992 + * raise ImportError("numpy.core.umath failed to import") + * + * cdef inline int import_ufunc() except -1: # <<<<<<<<<<<<<< + * try: + * _import_umath() + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("numpy.import_ufunc", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":999 + * + * + * cdef inline bint is_timedelta64_object(object obj): # <<<<<<<<<<<<<< + * """ + * Cython equivalent of `isinstance(obj, np.timedelta64)` + */ + +static CYTHON_INLINE int __pyx_f_5numpy_is_timedelta64_object(PyObject *__pyx_v_obj) { + int __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1011 + * bool + * """ + * return PyObject_TypeCheck(obj, &PyTimedeltaArrType_Type) # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = PyObject_TypeCheck(__pyx_v_obj, (&PyTimedeltaArrType_Type)); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":999 + * + * + * cdef inline bint is_timedelta64_object(object obj): # <<<<<<<<<<<<<< + * """ + * Cython equivalent of `isinstance(obj, np.timedelta64)` + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1014 + * + * + * cdef inline bint is_datetime64_object(object obj): # <<<<<<<<<<<<<< + * """ + * Cython equivalent of `isinstance(obj, np.datetime64)` + */ + +static CYTHON_INLINE int __pyx_f_5numpy_is_datetime64_object(PyObject *__pyx_v_obj) { + int __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1026 + * bool + * """ + * return PyObject_TypeCheck(obj, &PyDatetimeArrType_Type) # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = PyObject_TypeCheck(__pyx_v_obj, (&PyDatetimeArrType_Type)); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1014 + * + * + * cdef inline bint is_datetime64_object(object obj): # <<<<<<<<<<<<<< + * """ + * Cython equivalent of `isinstance(obj, np.datetime64)` + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1029 + * + * + * cdef inline npy_datetime get_datetime64_value(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the int64 value underlying scalar numpy datetime64 object + */ + +static CYTHON_INLINE npy_datetime __pyx_f_5numpy_get_datetime64_value(PyObject *__pyx_v_obj) { + npy_datetime __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1036 + * also needed. That can be found using `get_datetime64_unit`. + * """ + * return (obj).obval # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = ((PyDatetimeScalarObject *)__pyx_v_obj)->obval; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1029 + * + * + * cdef inline npy_datetime get_datetime64_value(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the int64 value underlying scalar numpy datetime64 object + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1039 + * + * + * cdef inline npy_timedelta get_timedelta64_value(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the int64 value underlying scalar numpy timedelta64 object + */ + +static CYTHON_INLINE npy_timedelta __pyx_f_5numpy_get_timedelta64_value(PyObject *__pyx_v_obj) { + npy_timedelta __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1043 + * returns the int64 value underlying scalar numpy timedelta64 object + * """ + * return (obj).obval # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = ((PyTimedeltaScalarObject *)__pyx_v_obj)->obval; + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1039 + * + * + * cdef inline npy_timedelta get_timedelta64_value(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the int64 value underlying scalar numpy timedelta64 object + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1046 + * + * + * cdef inline NPY_DATETIMEUNIT get_datetime64_unit(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the unit part of the dtype for a numpy datetime64 object. + */ + +static CYTHON_INLINE NPY_DATETIMEUNIT __pyx_f_5numpy_get_datetime64_unit(PyObject *__pyx_v_obj) { + NPY_DATETIMEUNIT __pyx_r; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1050 + * returns the unit part of the dtype for a numpy datetime64 object. + * """ + * return (obj).obmeta.base # <<<<<<<<<<<<<< + */ + __pyx_r = ((NPY_DATETIMEUNIT)((PyDatetimeScalarObject *)__pyx_v_obj)->obmeta.base); + goto __pyx_L0; + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":1046 + * + * + * cdef inline NPY_DATETIMEUNIT get_datetime64_unit(object obj) nogil: # <<<<<<<<<<<<<< + * """ + * returns the unit part of the dtype for a numpy datetime64 object. + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "selfdrive/modeld/models/commonmodel_pyx.pyx":13 + * from .commonmodel cimport mat3, sigmoid as cppSigmoid, ModelFrame as cppModelFrame + * + * def sigmoid(x): # <<<<<<<<<<<<<< + * return cppSigmoid(x) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_9selfdrive_6modeld_6models_15commonmodel_pyx_1sigmoid(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_9selfdrive_6modeld_6models_15commonmodel_pyx_1sigmoid = {"sigmoid", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_9selfdrive_6modeld_6models_15commonmodel_pyx_1sigmoid, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_9selfdrive_6modeld_6models_15commonmodel_pyx_1sigmoid(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v_x = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("sigmoid (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_x,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_x)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 13, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "sigmoid") < 0)) __PYX_ERR(1, 13, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_x = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("sigmoid", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 13, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("selfdrive.modeld.models.commonmodel_pyx.sigmoid", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_9selfdrive_6modeld_6models_15commonmodel_pyx_sigmoid(__pyx_self, __pyx_v_x); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_9selfdrive_6modeld_6models_15commonmodel_pyx_sigmoid(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v_x) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + float __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("sigmoid", 1); + + /* "selfdrive/modeld/models/commonmodel_pyx.pyx":14 + * + * def sigmoid(x): + * return cppSigmoid(x) # <<<<<<<<<<<<<< + * + * cdef class CLContext(BaseCLContext): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __pyx_PyFloat_AsFloat(__pyx_v_x); if (unlikely((__pyx_t_1 == (float)-1) && PyErr_Occurred())) __PYX_ERR(1, 14, __pyx_L1_error) + __pyx_t_2 = PyFloat_FromDouble(sigmoid(__pyx_t_1)); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "selfdrive/modeld/models/commonmodel_pyx.pyx":13 + * from .commonmodel cimport mat3, sigmoid as cppSigmoid, ModelFrame as cppModelFrame + * + * def sigmoid(x): # <<<<<<<<<<<<<< + * return cppSigmoid(x) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("selfdrive.modeld.models.commonmodel_pyx.sigmoid", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "selfdrive/modeld/models/commonmodel_pyx.pyx":17 + * + * cdef class CLContext(BaseCLContext): + * def __cinit__(self): # <<<<<<<<<<<<<< + * self.device_id = cl_get_device_id(CL_DEVICE_TYPE_DEFAULT) + * self.context = cl_create_context(self.device_id) + */ + +/* Python wrapper */ +static int __pyx_pw_9selfdrive_6modeld_6models_15commonmodel_pyx_9CLContext_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_pw_9selfdrive_6modeld_6models_15commonmodel_pyx_9CLContext_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 0, 0, __pyx_nargs); return -1;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_VARARGS(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__cinit__", 0))) return -1; + __pyx_r = __pyx_pf_9selfdrive_6modeld_6models_15commonmodel_pyx_9CLContext___cinit__(((struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_9selfdrive_6modeld_6models_15commonmodel_pyx_9CLContext___cinit__(struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext *__pyx_v_self) { + int __pyx_r; + + /* "selfdrive/modeld/models/commonmodel_pyx.pyx":18 + * cdef class CLContext(BaseCLContext): + * def __cinit__(self): + * self.device_id = cl_get_device_id(CL_DEVICE_TYPE_DEFAULT) # <<<<<<<<<<<<<< + * self.context = cl_create_context(self.device_id) + * + */ + __pyx_v_self->__pyx_base.device_id = cl_get_device_id(CL_DEVICE_TYPE_DEFAULT); + + /* "selfdrive/modeld/models/commonmodel_pyx.pyx":19 + * def __cinit__(self): + * self.device_id = cl_get_device_id(CL_DEVICE_TYPE_DEFAULT) + * self.context = cl_create_context(self.device_id) # <<<<<<<<<<<<<< + * + * cdef class CLMem: + */ + __pyx_v_self->__pyx_base.context = cl_create_context(__pyx_v_self->__pyx_base.device_id); + + /* "selfdrive/modeld/models/commonmodel_pyx.pyx":17 + * + * cdef class CLContext(BaseCLContext): + * def __cinit__(self): # <<<<<<<<<<<<<< + * self.device_id = cl_get_device_id(CL_DEVICE_TYPE_DEFAULT) + * self.context = cl_create_context(self.device_id) + */ + + /* function exit code */ + __pyx_r = 0; + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_9selfdrive_6modeld_6models_15commonmodel_pyx_9CLContext_3__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_9selfdrive_6modeld_6models_15commonmodel_pyx_9CLContext_3__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_9selfdrive_6modeld_6models_15commonmodel_pyx_9CLContext_3__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_9selfdrive_6modeld_6models_15commonmodel_pyx_9CLContext_3__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_9selfdrive_6modeld_6models_15commonmodel_pyx_9CLContext_2__reduce_cython__(((struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_9selfdrive_6modeld_6models_15commonmodel_pyx_9CLContext_2__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(0, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("selfdrive.modeld.models.commonmodel_pyx.CLContext.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_9selfdrive_6modeld_6models_15commonmodel_pyx_9CLContext_5__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_9selfdrive_6modeld_6models_15commonmodel_pyx_9CLContext_5__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_9selfdrive_6modeld_6models_15commonmodel_pyx_9CLContext_5__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_9selfdrive_6modeld_6models_15commonmodel_pyx_9CLContext_5__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(0, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("selfdrive.modeld.models.commonmodel_pyx.CLContext.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_9selfdrive_6modeld_6models_15commonmodel_pyx_9CLContext_4__setstate_cython__(((struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_9selfdrive_6modeld_6models_15commonmodel_pyx_9CLContext_4__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(0, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("selfdrive.modeld.models.commonmodel_pyx.CLContext.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "selfdrive/modeld/models/commonmodel_pyx.pyx":23 + * cdef class CLMem: + * @staticmethod + * cdef create(void * cmem): # <<<<<<<<<<<<<< + * mem = CLMem() + * mem.mem = cmem + */ + +static PyObject *__pyx_f_9selfdrive_6modeld_6models_15commonmodel_pyx_5CLMem_create(void *__pyx_v_cmem) { + struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem *__pyx_v_mem = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("create", 1); + + /* "selfdrive/modeld/models/commonmodel_pyx.pyx":24 + * @staticmethod + * cdef create(void * cmem): + * mem = CLMem() # <<<<<<<<<<<<<< + * mem.mem = cmem + * return mem + */ + __pyx_t_1 = __Pyx_PyObject_CallNoArg(((PyObject *)__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem)); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 24, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_mem = ((struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem *)__pyx_t_1); + __pyx_t_1 = 0; + + /* "selfdrive/modeld/models/commonmodel_pyx.pyx":25 + * cdef create(void * cmem): + * mem = CLMem() + * mem.mem = cmem # <<<<<<<<<<<<<< + * return mem + * + */ + __pyx_v_mem->mem = ((cl_mem *)__pyx_v_cmem); + + /* "selfdrive/modeld/models/commonmodel_pyx.pyx":26 + * mem = CLMem() + * mem.mem = cmem + * return mem # <<<<<<<<<<<<<< + * + * cdef class ModelFrame: + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_mem); + __pyx_r = ((PyObject *)__pyx_v_mem); + goto __pyx_L0; + + /* "selfdrive/modeld/models/commonmodel_pyx.pyx":23 + * cdef class CLMem: + * @staticmethod + * cdef create(void * cmem): # <<<<<<<<<<<<<< + * mem = CLMem() + * mem.mem = cmem + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("selfdrive.modeld.models.commonmodel_pyx.CLMem.create", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_mem); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.mem cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_9selfdrive_6modeld_6models_15commonmodel_pyx_5CLMem_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_9selfdrive_6modeld_6models_15commonmodel_pyx_5CLMem_1__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_9selfdrive_6modeld_6models_15commonmodel_pyx_5CLMem_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_9selfdrive_6modeld_6models_15commonmodel_pyx_5CLMem_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_9selfdrive_6modeld_6models_15commonmodel_pyx_5CLMem___reduce_cython__(((struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_9selfdrive_6modeld_6models_15commonmodel_pyx_5CLMem___reduce_cython__(CYTHON_UNUSED struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "self.mem cannot be converted to a Python object for pickling" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "self.mem cannot be converted to a Python object for pickling" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_self_mem_cannot_be_converted_to, 0, 0); + __PYX_ERR(0, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.mem cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("selfdrive.modeld.models.commonmodel_pyx.CLMem.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.mem cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.mem cannot be converted to a Python object for pickling" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_9selfdrive_6modeld_6models_15commonmodel_pyx_5CLMem_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_9selfdrive_6modeld_6models_15commonmodel_pyx_5CLMem_3__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_9selfdrive_6modeld_6models_15commonmodel_pyx_5CLMem_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_9selfdrive_6modeld_6models_15commonmodel_pyx_5CLMem_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(0, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("selfdrive.modeld.models.commonmodel_pyx.CLMem.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_9selfdrive_6modeld_6models_15commonmodel_pyx_5CLMem_2__setstate_cython__(((struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_9selfdrive_6modeld_6models_15commonmodel_pyx_5CLMem_2__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "self.mem cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "self.mem cannot be converted to a Python object for pickling" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_self_mem_cannot_be_converted_to, 0, 0); + __PYX_ERR(0, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.mem cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.mem cannot be converted to a Python object for pickling" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("selfdrive.modeld.models.commonmodel_pyx.CLMem.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "selfdrive/modeld/models/commonmodel_pyx.pyx":31 + * cdef cppModelFrame * frame + * + * def __cinit__(self, CLContext context): # <<<<<<<<<<<<<< + * self.frame = new cppModelFrame(context.device_id, context.context) + * + */ + +/* Python wrapper */ +static int __pyx_pw_9selfdrive_6modeld_6models_15commonmodel_pyx_10ModelFrame_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_pw_9selfdrive_6modeld_6models_15commonmodel_pyx_10ModelFrame_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext *__pyx_v_context = 0; + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_context,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_context)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 31, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(1, 31, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + } + __pyx_v_context = ((struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext *)values[0]); + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 31, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("selfdrive.modeld.models.commonmodel_pyx.ModelFrame.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_context), __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext, 1, "context", 0))) __PYX_ERR(1, 31, __pyx_L1_error) + __pyx_r = __pyx_pf_9selfdrive_6modeld_6models_15commonmodel_pyx_10ModelFrame___cinit__(((struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame *)__pyx_v_self), __pyx_v_context); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = -1; + __pyx_L0:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_9selfdrive_6modeld_6models_15commonmodel_pyx_10ModelFrame___cinit__(struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame *__pyx_v_self, struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext *__pyx_v_context) { + int __pyx_r; + + /* "selfdrive/modeld/models/commonmodel_pyx.pyx":32 + * + * def __cinit__(self, CLContext context): + * self.frame = new cppModelFrame(context.device_id, context.context) # <<<<<<<<<<<<<< + * + * def __dealloc__(self): + */ + __pyx_v_self->frame = new ModelFrame(__pyx_v_context->__pyx_base.device_id, __pyx_v_context->__pyx_base.context); + + /* "selfdrive/modeld/models/commonmodel_pyx.pyx":31 + * cdef cppModelFrame * frame + * + * def __cinit__(self, CLContext context): # <<<<<<<<<<<<<< + * self.frame = new cppModelFrame(context.device_id, context.context) + * + */ + + /* function exit code */ + __pyx_r = 0; + return __pyx_r; +} + +/* "selfdrive/modeld/models/commonmodel_pyx.pyx":34 + * self.frame = new cppModelFrame(context.device_id, context.context) + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * del self.frame + * + */ + +/* Python wrapper */ +static void __pyx_pw_9selfdrive_6modeld_6models_15commonmodel_pyx_10ModelFrame_3__dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_pw_9selfdrive_6modeld_6models_15commonmodel_pyx_10ModelFrame_3__dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_pf_9selfdrive_6modeld_6models_15commonmodel_pyx_10ModelFrame_2__dealloc__(((struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_pf_9selfdrive_6modeld_6models_15commonmodel_pyx_10ModelFrame_2__dealloc__(struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame *__pyx_v_self) { + + /* "selfdrive/modeld/models/commonmodel_pyx.pyx":35 + * + * def __dealloc__(self): + * del self.frame # <<<<<<<<<<<<<< + * + * def prepare(self, VisionBuf buf, float[:] projection, CLMem output): + */ + delete __pyx_v_self->frame; + + /* "selfdrive/modeld/models/commonmodel_pyx.pyx":34 + * self.frame = new cppModelFrame(context.device_id, context.context) + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * del self.frame + * + */ + + /* function exit code */ +} + +/* "selfdrive/modeld/models/commonmodel_pyx.pyx":37 + * del self.frame + * + * def prepare(self, VisionBuf buf, float[:] projection, CLMem output): # <<<<<<<<<<<<<< + * cdef mat3 cprojection + * memcpy(cprojection.v, &projection[0], 9*sizeof(float)) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_9selfdrive_6modeld_6models_15commonmodel_pyx_10ModelFrame_5prepare(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_9selfdrive_6modeld_6models_15commonmodel_pyx_10ModelFrame_5prepare = {"prepare", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_9selfdrive_6modeld_6models_15commonmodel_pyx_10ModelFrame_5prepare, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_9selfdrive_6modeld_6models_15commonmodel_pyx_10ModelFrame_5prepare(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_v_buf = 0; + __Pyx_memviewslice __pyx_v_projection = { 0, 0, { 0 }, { 0 }, { 0 } }; + struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem *__pyx_v_output = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("prepare (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_buf,&__pyx_n_s_projection,&__pyx_n_s_output,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_buf)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 37, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_projection)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 37, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("prepare", 1, 3, 3, 1); __PYX_ERR(1, 37, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_output)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 37, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("prepare", 1, 3, 3, 2); __PYX_ERR(1, 37, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "prepare") < 0)) __PYX_ERR(1, 37, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + } + __pyx_v_buf = ((struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *)values[0]); + __pyx_v_projection = __Pyx_PyObject_to_MemoryviewSlice_ds_float(values[1], PyBUF_WRITABLE); if (unlikely(!__pyx_v_projection.memview)) __PYX_ERR(1, 37, __pyx_L3_error) + __pyx_v_output = ((struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem *)values[2]); + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("prepare", 1, 3, 3, __pyx_nargs); __PYX_ERR(1, 37, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __PYX_XCLEAR_MEMVIEW(&__pyx_v_projection, 1); + __Pyx_AddTraceback("selfdrive.modeld.models.commonmodel_pyx.ModelFrame.prepare", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_buf), __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf, 1, "buf", 0))) __PYX_ERR(1, 37, __pyx_L1_error) + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_output), __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem, 1, "output", 0))) __PYX_ERR(1, 37, __pyx_L1_error) + __pyx_r = __pyx_pf_9selfdrive_6modeld_6models_15commonmodel_pyx_10ModelFrame_4prepare(((struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame *)__pyx_v_self), __pyx_v_buf, __pyx_v_projection, __pyx_v_output); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = NULL; + __pyx_L0:; + __PYX_XCLEAR_MEMVIEW(&__pyx_v_projection, 1); + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_9selfdrive_6modeld_6models_15commonmodel_pyx_10ModelFrame_4prepare(struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame *__pyx_v_self, struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_v_buf, __Pyx_memviewslice __pyx_v_projection, struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem *__pyx_v_output) { + struct mat3 __pyx_v_cprojection; + float *__pyx_v_data; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_t_5; + int __pyx_t_6; + int __pyx_t_7; + PyObject *__pyx_t_8 = NULL; + PyObject *__pyx_t_9 = NULL; + struct __pyx_array_obj *__pyx_t_10 = NULL; + PyObject *__pyx_t_11 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("prepare", 1); + + /* "selfdrive/modeld/models/commonmodel_pyx.pyx":39 + * def prepare(self, VisionBuf buf, float[:] projection, CLMem output): + * cdef mat3 cprojection + * memcpy(cprojection.v, &projection[0], 9*sizeof(float)) # <<<<<<<<<<<<<< + * cdef float * data = self.frame.prepare(buf.buf.buf_cl, buf.width, buf.height, buf.stride, buf.uv_offset, cprojection, output.mem) + * if not data: + */ + __pyx_t_1 = 0; + __pyx_t_2 = -1; + if (__pyx_t_1 < 0) { + __pyx_t_1 += __pyx_v_projection.shape[0]; + if (unlikely(__pyx_t_1 < 0)) __pyx_t_2 = 0; + } else if (unlikely(__pyx_t_1 >= __pyx_v_projection.shape[0])) __pyx_t_2 = 0; + if (unlikely(__pyx_t_2 != -1)) { + __Pyx_RaiseBufferIndexError(__pyx_t_2); + __PYX_ERR(1, 39, __pyx_L1_error) + } + (void)(memcpy(__pyx_v_cprojection.v, (&(*((float *) ( /* dim=0 */ (__pyx_v_projection.data + __pyx_t_1 * __pyx_v_projection.strides[0]) )))), (9 * (sizeof(float))))); + + /* "selfdrive/modeld/models/commonmodel_pyx.pyx":40 + * cdef mat3 cprojection + * memcpy(cprojection.v, &projection[0], 9*sizeof(float)) + * cdef float * data = self.frame.prepare(buf.buf.buf_cl, buf.width, buf.height, buf.stride, buf.uv_offset, cprojection, output.mem) # <<<<<<<<<<<<<< + * if not data: + * return None + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_buf), __pyx_n_s_width); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_2 = __Pyx_PyInt_As_int(__pyx_t_3); if (unlikely((__pyx_t_2 == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 40, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_buf), __pyx_n_s_height); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = __Pyx_PyInt_As_int(__pyx_t_3); if (unlikely((__pyx_t_4 == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 40, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_buf), __pyx_n_s_stride); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = __Pyx_PyInt_As_int(__pyx_t_3); if (unlikely((__pyx_t_5 == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 40, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_buf), __pyx_n_s_uv_offset); if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 40, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_6 = __Pyx_PyInt_As_int(__pyx_t_3); if (unlikely((__pyx_t_6 == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 40, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_v_data = __pyx_v_self->frame->prepare(__pyx_v_buf->buf->buf_cl, __pyx_t_2, __pyx_t_4, __pyx_t_5, __pyx_t_6, __pyx_v_cprojection, __pyx_v_output->mem); + + /* "selfdrive/modeld/models/commonmodel_pyx.pyx":41 + * memcpy(cprojection.v, &projection[0], 9*sizeof(float)) + * cdef float * data = self.frame.prepare(buf.buf.buf_cl, buf.width, buf.height, buf.stride, buf.uv_offset, cprojection, output.mem) + * if not data: # <<<<<<<<<<<<<< + * return None + * return np.asarray( data) + */ + __pyx_t_7 = (!(__pyx_v_data != 0)); + if (__pyx_t_7) { + + /* "selfdrive/modeld/models/commonmodel_pyx.pyx":42 + * cdef float * data = self.frame.prepare(buf.buf.buf_cl, buf.width, buf.height, buf.stride, buf.uv_offset, cprojection, output.mem) + * if not data: + * return None # <<<<<<<<<<<<<< + * return np.asarray( data) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "selfdrive/modeld/models/commonmodel_pyx.pyx":41 + * memcpy(cprojection.v, &projection[0], 9*sizeof(float)) + * cdef float * data = self.frame.prepare(buf.buf.buf_cl, buf.width, buf.height, buf.stride, buf.uv_offset, cprojection, output.mem) + * if not data: # <<<<<<<<<<<<<< + * return None + * return np.asarray( data) + */ + } + + /* "selfdrive/modeld/models/commonmodel_pyx.pyx":43 + * if not data: + * return None + * return np.asarray( data) # <<<<<<<<<<<<<< + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_GetModuleGlobalName(__pyx_t_8, __pyx_n_s_np); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 43, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_9 = __Pyx_PyObject_GetAttrStr(__pyx_t_8, __pyx_n_s_asarray); if (unlikely(!__pyx_t_9)) __PYX_ERR(1, 43, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_9); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + if (!__pyx_v_data) { + PyErr_SetString(PyExc_ValueError,"Cannot create cython.array from NULL pointer"); + __PYX_ERR(1, 43, __pyx_L1_error) + } + __pyx_t_11 = __pyx_format_from_typeinfo(&__Pyx_TypeInfo_nn___pyx_t_5numpy_float32_t); if (unlikely(!__pyx_t_11)) __PYX_ERR(1, 43, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_11); + __pyx_t_8 = Py_BuildValue((char*) "(" __PYX_BUILD_PY_SSIZE_T ")", ((Py_ssize_t)__pyx_v_self->frame->buf_size)); if (unlikely(!__pyx_t_8)) __PYX_ERR(1, 43, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_10 = __pyx_array_new(__pyx_t_8, sizeof(__pyx_t_5numpy_float32_t), PyBytes_AS_STRING(__pyx_t_11), (char *) "c", (char *) __pyx_v_data); if (unlikely(!__pyx_t_10)) __PYX_ERR(1, 43, __pyx_L1_error) + __Pyx_GOTREF((PyObject *)__pyx_t_10); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_DECREF(__pyx_t_11); __pyx_t_11 = 0; + __pyx_t_11 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (unlikely(PyMethod_Check(__pyx_t_9))) { + __pyx_t_11 = PyMethod_GET_SELF(__pyx_t_9); + if (likely(__pyx_t_11)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_9); + __Pyx_INCREF(__pyx_t_11); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_9, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_11, ((PyObject *)__pyx_t_10)}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_9, __pyx_callargs+1-__pyx_t_6, 1+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_11); __pyx_t_11 = 0; + __Pyx_DECREF((PyObject *)__pyx_t_10); __pyx_t_10 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(1, 43, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_9); __pyx_t_9 = 0; + } + __pyx_r = __pyx_t_3; + __pyx_t_3 = 0; + goto __pyx_L0; + + /* "selfdrive/modeld/models/commonmodel_pyx.pyx":37 + * del self.frame + * + * def prepare(self, VisionBuf buf, float[:] projection, CLMem output): # <<<<<<<<<<<<<< + * cdef mat3 cprojection + * memcpy(cprojection.v, &projection[0], 9*sizeof(float)) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_XDECREF(__pyx_t_9); + __Pyx_XDECREF((PyObject *)__pyx_t_10); + __Pyx_XDECREF(__pyx_t_11); + __Pyx_AddTraceback("selfdrive.modeld.models.commonmodel_pyx.ModelFrame.prepare", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_9selfdrive_6modeld_6models_15commonmodel_pyx_10ModelFrame_7__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_9selfdrive_6modeld_6models_15commonmodel_pyx_10ModelFrame_7__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_9selfdrive_6modeld_6models_15commonmodel_pyx_10ModelFrame_7__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_9selfdrive_6modeld_6models_15commonmodel_pyx_10ModelFrame_7__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_9selfdrive_6modeld_6models_15commonmodel_pyx_10ModelFrame_6__reduce_cython__(((struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_9selfdrive_6modeld_6models_15commonmodel_pyx_10ModelFrame_6__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(0, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("selfdrive.modeld.models.commonmodel_pyx.ModelFrame.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_9selfdrive_6modeld_6models_15commonmodel_pyx_10ModelFrame_9__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_9selfdrive_6modeld_6models_15commonmodel_pyx_10ModelFrame_9__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_9selfdrive_6modeld_6models_15commonmodel_pyx_10ModelFrame_9__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_9selfdrive_6modeld_6models_15commonmodel_pyx_10ModelFrame_9__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(0, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("selfdrive.modeld.models.commonmodel_pyx.ModelFrame.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_9selfdrive_6modeld_6models_15commonmodel_pyx_10ModelFrame_8__setstate_cython__(((struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_9selfdrive_6modeld_6models_15commonmodel_pyx_10ModelFrame_8__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(0, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("selfdrive.modeld.models.commonmodel_pyx.ModelFrame.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_tp_new_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext(PyTypeObject *t, PyObject *a, PyObject *k) { + PyObject *o = __Pyx_PyType_GetSlot(__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext, tp_new, newfunc)(t, a, k); + if (unlikely(!o)) return 0; + if (unlikely(__pyx_pw_9selfdrive_6modeld_6models_15commonmodel_pyx_9CLContext_1__cinit__(o, __pyx_empty_tuple, NULL) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static PyMethodDef __pyx_methods_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext[] = { + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_9selfdrive_6modeld_6models_15commonmodel_pyx_9CLContext_3__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_9selfdrive_6modeld_6models_15commonmodel_pyx_9CLContext_5__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext_slots[] = { + {Py_tp_methods, (void *)__pyx_methods_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext}, + {Py_tp_new, (void *)__pyx_tp_new_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext}, + {0, 0}, +}; +static PyType_Spec __pyx_type_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext_spec = { + "selfdrive.modeld.models.commonmodel_pyx.CLContext", + sizeof(struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_FINALIZE, + __pyx_type_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext_slots, +}; +#else + +static PyTypeObject __pyx_type_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext = { + PyVarObject_HEAD_INIT(0, 0) + "selfdrive.modeld.models.commonmodel_pyx.""CLContext", /*tp_name*/ + sizeof(struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + 0, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_FINALIZE, /*tp_flags*/ + 0, /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif +static struct __pyx_vtabstruct_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem __pyx_vtable_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem; + +static PyObject *__pyx_tp_new_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { + struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem *)o); + p->__pyx_vtab = __pyx_vtabptr_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem; + return o; +} + +static void __pyx_tp_dealloc_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem(PyObject *o) { + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} + +static PyMethodDef __pyx_methods_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem[] = { + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_9selfdrive_6modeld_6models_15commonmodel_pyx_5CLMem_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_9selfdrive_6modeld_6models_15commonmodel_pyx_5CLMem_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem}, + {Py_tp_methods, (void *)__pyx_methods_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem}, + {Py_tp_new, (void *)__pyx_tp_new_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem}, + {0, 0}, +}; +static PyType_Spec __pyx_type_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem_spec = { + "selfdrive.modeld.models.commonmodel_pyx.CLMem", + sizeof(struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, + __pyx_type_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem_slots, +}; +#else + +static PyTypeObject __pyx_type_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem = { + PyVarObject_HEAD_INIT(0, 0) + "selfdrive.modeld.models.commonmodel_pyx.""CLMem", /*tp_name*/ + sizeof(struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, /*tp_flags*/ + 0, /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyObject *__pyx_tp_new_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame(PyTypeObject *t, PyObject *a, PyObject *k) { + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + if (unlikely(__pyx_pw_9selfdrive_6modeld_6models_15commonmodel_pyx_10ModelFrame_1__cinit__(o, a, k) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static void __pyx_tp_dealloc_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame(PyObject *o) { + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_pw_9selfdrive_6modeld_6models_15commonmodel_pyx_10ModelFrame_3__dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} + +static PyMethodDef __pyx_methods_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame[] = { + {"prepare", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_9selfdrive_6modeld_6models_15commonmodel_pyx_10ModelFrame_5prepare, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_9selfdrive_6modeld_6models_15commonmodel_pyx_10ModelFrame_7__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_9selfdrive_6modeld_6models_15commonmodel_pyx_10ModelFrame_9__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame}, + {Py_tp_methods, (void *)__pyx_methods_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame}, + {Py_tp_new, (void *)__pyx_tp_new_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame}, + {0, 0}, +}; +static PyType_Spec __pyx_type_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame_spec = { + "selfdrive.modeld.models.commonmodel_pyx.ModelFrame", + sizeof(struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, + __pyx_type_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame_slots, +}; +#else + +static PyTypeObject __pyx_type_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame = { + PyVarObject_HEAD_INIT(0, 0) + "selfdrive.modeld.models.commonmodel_pyx.""ModelFrame", /*tp_name*/ + sizeof(struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, /*tp_flags*/ + 0, /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif +static struct __pyx_vtabstruct_array __pyx_vtable_array; + +static PyObject *__pyx_tp_new_array(PyTypeObject *t, PyObject *a, PyObject *k) { + struct __pyx_array_obj *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_array_obj *)o); + p->__pyx_vtab = __pyx_vtabptr_array; + p->mode = ((PyObject*)Py_None); Py_INCREF(Py_None); + p->_format = ((PyObject*)Py_None); Py_INCREF(Py_None); + if (unlikely(__pyx_array___cinit__(o, a, k) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static void __pyx_tp_dealloc_array(PyObject *o) { + struct __pyx_array_obj *p = (struct __pyx_array_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_array) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_array___dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + Py_CLEAR(p->mode); + Py_CLEAR(p->_format); + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} +static PyObject *__pyx_sq_item_array(PyObject *o, Py_ssize_t i) { + PyObject *r; + PyObject *x = PyInt_FromSsize_t(i); if(!x) return 0; + r = Py_TYPE(o)->tp_as_mapping->mp_subscript(o, x); + Py_DECREF(x); + return r; +} + +static int __pyx_mp_ass_subscript_array(PyObject *o, PyObject *i, PyObject *v) { + if (v) { + return __pyx_array___setitem__(o, i, v); + } + else { + __Pyx_TypeName o_type_name; + o_type_name = __Pyx_PyType_GetName(Py_TYPE(o)); + PyErr_Format(PyExc_NotImplementedError, + "Subscript deletion not supported by " __Pyx_FMT_TYPENAME, o_type_name); + __Pyx_DECREF_TypeName(o_type_name); + return -1; + } +} + +static PyObject *__pyx_tp_getattro_array(PyObject *o, PyObject *n) { + PyObject *v = __Pyx_PyObject_GenericGetAttr(o, n); + if (!v && PyErr_ExceptionMatches(PyExc_AttributeError)) { + PyErr_Clear(); + v = __pyx_array___getattr__(o, n); + } + return v; +} + +static PyObject *__pyx_getprop___pyx_array_memview(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_5array_7memview_1__get__(o); +} + +static PyMethodDef __pyx_methods_array[] = { + {"__getattr__", (PyCFunction)__pyx_array___getattr__, METH_O|METH_COEXIST, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_array_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_array_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; + +static struct PyGetSetDef __pyx_getsets_array[] = { + {(char *)"memview", __pyx_getprop___pyx_array_memview, 0, (char *)0, 0}, + {0, 0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +#if !CYTHON_COMPILING_IN_LIMITED_API + +static PyBufferProcs __pyx_tp_as_buffer_array = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_array_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; +#endif +static PyType_Slot __pyx_type___pyx_array_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_array}, + {Py_sq_length, (void *)__pyx_array___len__}, + {Py_sq_item, (void *)__pyx_sq_item_array}, + {Py_mp_length, (void *)__pyx_array___len__}, + {Py_mp_subscript, (void *)__pyx_array___getitem__}, + {Py_mp_ass_subscript, (void *)__pyx_mp_ass_subscript_array}, + {Py_tp_getattro, (void *)__pyx_tp_getattro_array}, + #if defined(Py_bf_getbuffer) + {Py_bf_getbuffer, (void *)__pyx_array_getbuffer}, + #endif + {Py_tp_methods, (void *)__pyx_methods_array}, + {Py_tp_getset, (void *)__pyx_getsets_array}, + {Py_tp_new, (void *)__pyx_tp_new_array}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_array_spec = { + "selfdrive.modeld.models.commonmodel_pyx.array", + sizeof(struct __pyx_array_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_SEQUENCE, + __pyx_type___pyx_array_slots, +}; +#else + +static PySequenceMethods __pyx_tp_as_sequence_array = { + __pyx_array___len__, /*sq_length*/ + 0, /*sq_concat*/ + 0, /*sq_repeat*/ + __pyx_sq_item_array, /*sq_item*/ + 0, /*sq_slice*/ + 0, /*sq_ass_item*/ + 0, /*sq_ass_slice*/ + 0, /*sq_contains*/ + 0, /*sq_inplace_concat*/ + 0, /*sq_inplace_repeat*/ +}; + +static PyMappingMethods __pyx_tp_as_mapping_array = { + __pyx_array___len__, /*mp_length*/ + __pyx_array___getitem__, /*mp_subscript*/ + __pyx_mp_ass_subscript_array, /*mp_ass_subscript*/ +}; + +static PyBufferProcs __pyx_tp_as_buffer_array = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_array_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; + +static PyTypeObject __pyx_type___pyx_array = { + PyVarObject_HEAD_INIT(0, 0) + "selfdrive.modeld.models.commonmodel_pyx.""array", /*tp_name*/ + sizeof(struct __pyx_array_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_array, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + &__pyx_tp_as_sequence_array, /*tp_as_sequence*/ + &__pyx_tp_as_mapping_array, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + __pyx_tp_getattro_array, /*tp_getattro*/ + 0, /*tp_setattro*/ + &__pyx_tp_as_buffer_array, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_SEQUENCE, /*tp_flags*/ + 0, /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_array, /*tp_methods*/ + 0, /*tp_members*/ + __pyx_getsets_array, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_array, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyObject *__pyx_tp_new_Enum(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { + struct __pyx_MemviewEnum_obj *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_MemviewEnum_obj *)o); + p->name = Py_None; Py_INCREF(Py_None); + return o; +} + +static void __pyx_tp_dealloc_Enum(PyObject *o) { + struct __pyx_MemviewEnum_obj *p = (struct __pyx_MemviewEnum_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_Enum) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + Py_CLEAR(p->name); + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} + +static int __pyx_tp_traverse_Enum(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_MemviewEnum_obj *p = (struct __pyx_MemviewEnum_obj *)o; + if (p->name) { + e = (*v)(p->name, a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear_Enum(PyObject *o) { + PyObject* tmp; + struct __pyx_MemviewEnum_obj *p = (struct __pyx_MemviewEnum_obj *)o; + tmp = ((PyObject*)p->name); + p->name = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + return 0; +} + +static PyObject *__pyx_specialmethod___pyx_MemviewEnum___repr__(PyObject *self, CYTHON_UNUSED PyObject *arg) { + return __pyx_MemviewEnum___repr__(self); +} + +static PyMethodDef __pyx_methods_Enum[] = { + {"__repr__", (PyCFunction)__pyx_specialmethod___pyx_MemviewEnum___repr__, METH_NOARGS|METH_COEXIST, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_MemviewEnum_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_MemviewEnum_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type___pyx_MemviewEnum_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_Enum}, + {Py_tp_repr, (void *)__pyx_MemviewEnum___repr__}, + {Py_tp_traverse, (void *)__pyx_tp_traverse_Enum}, + {Py_tp_clear, (void *)__pyx_tp_clear_Enum}, + {Py_tp_methods, (void *)__pyx_methods_Enum}, + {Py_tp_init, (void *)__pyx_MemviewEnum___init__}, + {Py_tp_new, (void *)__pyx_tp_new_Enum}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_MemviewEnum_spec = { + "selfdrive.modeld.models.commonmodel_pyx.Enum", + sizeof(struct __pyx_MemviewEnum_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, + __pyx_type___pyx_MemviewEnum_slots, +}; +#else + +static PyTypeObject __pyx_type___pyx_MemviewEnum = { + PyVarObject_HEAD_INIT(0, 0) + "selfdrive.modeld.models.commonmodel_pyx.""Enum", /*tp_name*/ + sizeof(struct __pyx_MemviewEnum_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_Enum, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + __pyx_MemviewEnum___repr__, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, /*tp_flags*/ + 0, /*tp_doc*/ + __pyx_tp_traverse_Enum, /*tp_traverse*/ + __pyx_tp_clear_Enum, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_Enum, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + __pyx_MemviewEnum___init__, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_Enum, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif +static struct __pyx_vtabstruct_memoryview __pyx_vtable_memoryview; + +static PyObject *__pyx_tp_new_memoryview(PyTypeObject *t, PyObject *a, PyObject *k) { + struct __pyx_memoryview_obj *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_memoryview_obj *)o); + p->__pyx_vtab = __pyx_vtabptr_memoryview; + p->obj = Py_None; Py_INCREF(Py_None); + p->_size = Py_None; Py_INCREF(Py_None); + p->_array_interface = Py_None; Py_INCREF(Py_None); + p->view.obj = NULL; + if (unlikely(__pyx_memoryview___cinit__(o, a, k) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static void __pyx_tp_dealloc_memoryview(PyObject *o) { + struct __pyx_memoryview_obj *p = (struct __pyx_memoryview_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_memoryview) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_memoryview___dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + Py_CLEAR(p->obj); + Py_CLEAR(p->_size); + Py_CLEAR(p->_array_interface); + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} + +static int __pyx_tp_traverse_memoryview(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_memoryview_obj *p = (struct __pyx_memoryview_obj *)o; + if (p->obj) { + e = (*v)(p->obj, a); if (e) return e; + } + if (p->_size) { + e = (*v)(p->_size, a); if (e) return e; + } + if (p->_array_interface) { + e = (*v)(p->_array_interface, a); if (e) return e; + } + if (p->view.obj) { + e = (*v)(p->view.obj, a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear_memoryview(PyObject *o) { + PyObject* tmp; + struct __pyx_memoryview_obj *p = (struct __pyx_memoryview_obj *)o; + tmp = ((PyObject*)p->obj); + p->obj = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + tmp = ((PyObject*)p->_size); + p->_size = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + tmp = ((PyObject*)p->_array_interface); + p->_array_interface = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + Py_CLEAR(p->view.obj); + return 0; +} +static PyObject *__pyx_sq_item_memoryview(PyObject *o, Py_ssize_t i) { + PyObject *r; + PyObject *x = PyInt_FromSsize_t(i); if(!x) return 0; + r = Py_TYPE(o)->tp_as_mapping->mp_subscript(o, x); + Py_DECREF(x); + return r; +} + +static int __pyx_mp_ass_subscript_memoryview(PyObject *o, PyObject *i, PyObject *v) { + if (v) { + return __pyx_memoryview___setitem__(o, i, v); + } + else { + __Pyx_TypeName o_type_name; + o_type_name = __Pyx_PyType_GetName(Py_TYPE(o)); + PyErr_Format(PyExc_NotImplementedError, + "Subscript deletion not supported by " __Pyx_FMT_TYPENAME, o_type_name); + __Pyx_DECREF_TypeName(o_type_name); + return -1; + } +} + +static PyObject *__pyx_getprop___pyx_memoryview_T(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_1T_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_base(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_4base_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_shape(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_5shape_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_strides(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_7strides_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_suboffsets(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_10suboffsets_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_ndim(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_4ndim_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_itemsize(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_8itemsize_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_nbytes(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_6nbytes_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_size(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_4size_1__get__(o); +} + +static PyObject *__pyx_specialmethod___pyx_memoryview___repr__(PyObject *self, CYTHON_UNUSED PyObject *arg) { + return __pyx_memoryview___repr__(self); +} + +static PyMethodDef __pyx_methods_memoryview[] = { + {"__repr__", (PyCFunction)__pyx_specialmethod___pyx_memoryview___repr__, METH_NOARGS|METH_COEXIST, 0}, + {"is_c_contig", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_is_c_contig, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"is_f_contig", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_is_f_contig, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"copy", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_copy, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"copy_fortran", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_copy_fortran, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryview_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryview_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; + +static struct PyGetSetDef __pyx_getsets_memoryview[] = { + {(char *)"T", __pyx_getprop___pyx_memoryview_T, 0, (char *)0, 0}, + {(char *)"base", __pyx_getprop___pyx_memoryview_base, 0, (char *)0, 0}, + {(char *)"shape", __pyx_getprop___pyx_memoryview_shape, 0, (char *)0, 0}, + {(char *)"strides", __pyx_getprop___pyx_memoryview_strides, 0, (char *)0, 0}, + {(char *)"suboffsets", __pyx_getprop___pyx_memoryview_suboffsets, 0, (char *)0, 0}, + {(char *)"ndim", __pyx_getprop___pyx_memoryview_ndim, 0, (char *)0, 0}, + {(char *)"itemsize", __pyx_getprop___pyx_memoryview_itemsize, 0, (char *)0, 0}, + {(char *)"nbytes", __pyx_getprop___pyx_memoryview_nbytes, 0, (char *)0, 0}, + {(char *)"size", __pyx_getprop___pyx_memoryview_size, 0, (char *)0, 0}, + {0, 0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +#if !CYTHON_COMPILING_IN_LIMITED_API + +static PyBufferProcs __pyx_tp_as_buffer_memoryview = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_memoryview_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; +#endif +static PyType_Slot __pyx_type___pyx_memoryview_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_memoryview}, + {Py_tp_repr, (void *)__pyx_memoryview___repr__}, + {Py_sq_length, (void *)__pyx_memoryview___len__}, + {Py_sq_item, (void *)__pyx_sq_item_memoryview}, + {Py_mp_length, (void *)__pyx_memoryview___len__}, + {Py_mp_subscript, (void *)__pyx_memoryview___getitem__}, + {Py_mp_ass_subscript, (void *)__pyx_mp_ass_subscript_memoryview}, + {Py_tp_str, (void *)__pyx_memoryview___str__}, + #if defined(Py_bf_getbuffer) + {Py_bf_getbuffer, (void *)__pyx_memoryview_getbuffer}, + #endif + {Py_tp_traverse, (void *)__pyx_tp_traverse_memoryview}, + {Py_tp_clear, (void *)__pyx_tp_clear_memoryview}, + {Py_tp_methods, (void *)__pyx_methods_memoryview}, + {Py_tp_getset, (void *)__pyx_getsets_memoryview}, + {Py_tp_new, (void *)__pyx_tp_new_memoryview}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_memoryview_spec = { + "selfdrive.modeld.models.commonmodel_pyx.memoryview", + sizeof(struct __pyx_memoryview_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, + __pyx_type___pyx_memoryview_slots, +}; +#else + +static PySequenceMethods __pyx_tp_as_sequence_memoryview = { + __pyx_memoryview___len__, /*sq_length*/ + 0, /*sq_concat*/ + 0, /*sq_repeat*/ + __pyx_sq_item_memoryview, /*sq_item*/ + 0, /*sq_slice*/ + 0, /*sq_ass_item*/ + 0, /*sq_ass_slice*/ + 0, /*sq_contains*/ + 0, /*sq_inplace_concat*/ + 0, /*sq_inplace_repeat*/ +}; + +static PyMappingMethods __pyx_tp_as_mapping_memoryview = { + __pyx_memoryview___len__, /*mp_length*/ + __pyx_memoryview___getitem__, /*mp_subscript*/ + __pyx_mp_ass_subscript_memoryview, /*mp_ass_subscript*/ +}; + +static PyBufferProcs __pyx_tp_as_buffer_memoryview = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_memoryview_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; + +static PyTypeObject __pyx_type___pyx_memoryview = { + PyVarObject_HEAD_INIT(0, 0) + "selfdrive.modeld.models.commonmodel_pyx.""memoryview", /*tp_name*/ + sizeof(struct __pyx_memoryview_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_memoryview, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + __pyx_memoryview___repr__, /*tp_repr*/ + 0, /*tp_as_number*/ + &__pyx_tp_as_sequence_memoryview, /*tp_as_sequence*/ + &__pyx_tp_as_mapping_memoryview, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + __pyx_memoryview___str__, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + &__pyx_tp_as_buffer_memoryview, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, /*tp_flags*/ + 0, /*tp_doc*/ + __pyx_tp_traverse_memoryview, /*tp_traverse*/ + __pyx_tp_clear_memoryview, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_memoryview, /*tp_methods*/ + 0, /*tp_members*/ + __pyx_getsets_memoryview, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_memoryview, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif +static struct __pyx_vtabstruct__memoryviewslice __pyx_vtable__memoryviewslice; + +static PyObject *__pyx_tp_new__memoryviewslice(PyTypeObject *t, PyObject *a, PyObject *k) { + struct __pyx_memoryviewslice_obj *p; + PyObject *o = __pyx_tp_new_memoryview(t, a, k); + if (unlikely(!o)) return 0; + p = ((struct __pyx_memoryviewslice_obj *)o); + p->__pyx_base.__pyx_vtab = (struct __pyx_vtabstruct_memoryview*)__pyx_vtabptr__memoryviewslice; + new((void*)&(p->from_slice)) __Pyx_memviewslice(); + p->from_object = Py_None; Py_INCREF(Py_None); + p->from_slice.memview = NULL; + return o; +} + +static void __pyx_tp_dealloc__memoryviewslice(PyObject *o) { + struct __pyx_memoryviewslice_obj *p = (struct __pyx_memoryviewslice_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc__memoryviewslice) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_memoryviewslice___dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + __Pyx_call_destructor(p->from_slice); + Py_CLEAR(p->from_object); + PyObject_GC_Track(o); + __pyx_tp_dealloc_memoryview(o); +} + +static int __pyx_tp_traverse__memoryviewslice(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_memoryviewslice_obj *p = (struct __pyx_memoryviewslice_obj *)o; + e = __pyx_tp_traverse_memoryview(o, v, a); if (e) return e; + if (p->from_object) { + e = (*v)(p->from_object, a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear__memoryviewslice(PyObject *o) { + PyObject* tmp; + struct __pyx_memoryviewslice_obj *p = (struct __pyx_memoryviewslice_obj *)o; + __pyx_tp_clear_memoryview(o); + tmp = ((PyObject*)p->from_object); + p->from_object = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + __PYX_XCLEAR_MEMVIEW(&p->from_slice, 1); + return 0; +} + +static PyMethodDef __pyx_methods__memoryviewslice[] = { + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryviewslice_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryviewslice_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type___pyx_memoryviewslice_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc__memoryviewslice}, + {Py_tp_doc, (void *)PyDoc_STR("Internal class for passing memoryview slices to Python")}, + {Py_tp_traverse, (void *)__pyx_tp_traverse__memoryviewslice}, + {Py_tp_clear, (void *)__pyx_tp_clear__memoryviewslice}, + {Py_tp_methods, (void *)__pyx_methods__memoryviewslice}, + {Py_tp_new, (void *)__pyx_tp_new__memoryviewslice}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_memoryviewslice_spec = { + "selfdrive.modeld.models.commonmodel_pyx._memoryviewslice", + sizeof(struct __pyx_memoryviewslice_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_SEQUENCE, + __pyx_type___pyx_memoryviewslice_slots, +}; +#else + +static PyTypeObject __pyx_type___pyx_memoryviewslice = { + PyVarObject_HEAD_INIT(0, 0) + "selfdrive.modeld.models.commonmodel_pyx.""_memoryviewslice", /*tp_name*/ + sizeof(struct __pyx_memoryviewslice_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc__memoryviewslice, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + #if CYTHON_COMPILING_IN_PYPY || 0 + __pyx_memoryview___repr__, /*tp_repr*/ + #else + 0, /*tp_repr*/ + #endif + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + #if CYTHON_COMPILING_IN_PYPY || 0 + __pyx_memoryview___str__, /*tp_str*/ + #else + 0, /*tp_str*/ + #endif + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_SEQUENCE, /*tp_flags*/ + PyDoc_STR("Internal class for passing memoryview slices to Python"), /*tp_doc*/ + __pyx_tp_traverse__memoryviewslice, /*tp_traverse*/ + __pyx_tp_clear__memoryviewslice, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods__memoryviewslice, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new__memoryviewslice, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyMethodDef __pyx_methods[] = { + {0, 0, 0, 0} +}; +#ifndef CYTHON_SMALL_CODE +#if defined(__clang__) + #define CYTHON_SMALL_CODE +#elif defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 3)) + #define CYTHON_SMALL_CODE __attribute__((cold)) +#else + #define CYTHON_SMALL_CODE +#endif +#endif +/* #### Code section: pystring_table ### */ + +static int __Pyx_CreateStringTabAndInitStrings(void) { + __Pyx_StringTabEntry __pyx_string_tab[] = { + {&__pyx_kp_u_, __pyx_k_, sizeof(__pyx_k_), 0, 1, 0, 0}, + {&__pyx_n_s_ASCII, __pyx_k_ASCII, sizeof(__pyx_k_ASCII), 0, 0, 1, 1}, + {&__pyx_kp_s_All_dimensions_preceding_dimensi, __pyx_k_All_dimensions_preceding_dimensi, sizeof(__pyx_k_All_dimensions_preceding_dimensi), 0, 0, 1, 0}, + {&__pyx_n_s_AssertionError, __pyx_k_AssertionError, sizeof(__pyx_k_AssertionError), 0, 0, 1, 1}, + {&__pyx_kp_s_Buffer_view_does_not_expose_stri, __pyx_k_Buffer_view_does_not_expose_stri, sizeof(__pyx_k_Buffer_view_does_not_expose_stri), 0, 0, 1, 0}, + {&__pyx_n_s_CLContext, __pyx_k_CLContext, sizeof(__pyx_k_CLContext), 0, 0, 1, 1}, + {&__pyx_n_s_CLContext___reduce_cython, __pyx_k_CLContext___reduce_cython, sizeof(__pyx_k_CLContext___reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_CLContext___setstate_cython, __pyx_k_CLContext___setstate_cython, sizeof(__pyx_k_CLContext___setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_CLMem, __pyx_k_CLMem, sizeof(__pyx_k_CLMem), 0, 0, 1, 1}, + {&__pyx_n_s_CLMem___reduce_cython, __pyx_k_CLMem___reduce_cython, sizeof(__pyx_k_CLMem___reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_CLMem___setstate_cython, __pyx_k_CLMem___setstate_cython, sizeof(__pyx_k_CLMem___setstate_cython), 0, 0, 1, 1}, + {&__pyx_kp_s_Can_only_create_a_buffer_that_is, __pyx_k_Can_only_create_a_buffer_that_is, sizeof(__pyx_k_Can_only_create_a_buffer_that_is), 0, 0, 1, 0}, + {&__pyx_kp_s_Cannot_assign_to_read_only_memor, __pyx_k_Cannot_assign_to_read_only_memor, sizeof(__pyx_k_Cannot_assign_to_read_only_memor), 0, 0, 1, 0}, + {&__pyx_kp_s_Cannot_create_writable_memory_vi, __pyx_k_Cannot_create_writable_memory_vi, sizeof(__pyx_k_Cannot_create_writable_memory_vi), 0, 0, 1, 0}, + {&__pyx_kp_u_Cannot_index_with_type, __pyx_k_Cannot_index_with_type, sizeof(__pyx_k_Cannot_index_with_type), 0, 1, 0, 0}, + {&__pyx_kp_s_Cannot_transpose_memoryview_with, __pyx_k_Cannot_transpose_memoryview_with, sizeof(__pyx_k_Cannot_transpose_memoryview_with), 0, 0, 1, 0}, + {&__pyx_kp_s_Dimension_d_is_not_direct, __pyx_k_Dimension_d_is_not_direct, sizeof(__pyx_k_Dimension_d_is_not_direct), 0, 0, 1, 0}, + {&__pyx_n_s_Ellipsis, __pyx_k_Ellipsis, sizeof(__pyx_k_Ellipsis), 0, 0, 1, 1}, + {&__pyx_kp_s_Empty_shape_tuple_for_cython_arr, __pyx_k_Empty_shape_tuple_for_cython_arr, sizeof(__pyx_k_Empty_shape_tuple_for_cython_arr), 0, 0, 1, 0}, + {&__pyx_n_s_ImportError, __pyx_k_ImportError, sizeof(__pyx_k_ImportError), 0, 0, 1, 1}, + {&__pyx_kp_s_Incompatible_checksums_0x_x_vs_0, __pyx_k_Incompatible_checksums_0x_x_vs_0, sizeof(__pyx_k_Incompatible_checksums_0x_x_vs_0), 0, 0, 1, 0}, + {&__pyx_n_s_IndexError, __pyx_k_IndexError, sizeof(__pyx_k_IndexError), 0, 0, 1, 1}, + {&__pyx_kp_s_Index_out_of_bounds_axis_d, __pyx_k_Index_out_of_bounds_axis_d, sizeof(__pyx_k_Index_out_of_bounds_axis_d), 0, 0, 1, 0}, + {&__pyx_kp_s_Indirect_dimensions_not_supporte, __pyx_k_Indirect_dimensions_not_supporte, sizeof(__pyx_k_Indirect_dimensions_not_supporte), 0, 0, 1, 0}, + {&__pyx_kp_u_Invalid_mode_expected_c_or_fortr, __pyx_k_Invalid_mode_expected_c_or_fortr, sizeof(__pyx_k_Invalid_mode_expected_c_or_fortr), 0, 1, 0, 0}, + {&__pyx_kp_u_Invalid_shape_in_axis, __pyx_k_Invalid_shape_in_axis, sizeof(__pyx_k_Invalid_shape_in_axis), 0, 1, 0, 0}, + {&__pyx_n_s_MemoryError, __pyx_k_MemoryError, sizeof(__pyx_k_MemoryError), 0, 0, 1, 1}, + {&__pyx_kp_s_MemoryView_of_r_at_0x_x, __pyx_k_MemoryView_of_r_at_0x_x, sizeof(__pyx_k_MemoryView_of_r_at_0x_x), 0, 0, 1, 0}, + {&__pyx_kp_s_MemoryView_of_r_object, __pyx_k_MemoryView_of_r_object, sizeof(__pyx_k_MemoryView_of_r_object), 0, 0, 1, 0}, + {&__pyx_n_s_ModelFrame, __pyx_k_ModelFrame, sizeof(__pyx_k_ModelFrame), 0, 0, 1, 1}, + {&__pyx_n_s_ModelFrame___reduce_cython, __pyx_k_ModelFrame___reduce_cython, sizeof(__pyx_k_ModelFrame___reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_ModelFrame___setstate_cython, __pyx_k_ModelFrame___setstate_cython, sizeof(__pyx_k_ModelFrame___setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_ModelFrame_prepare, __pyx_k_ModelFrame_prepare, sizeof(__pyx_k_ModelFrame_prepare), 0, 0, 1, 1}, + {&__pyx_n_b_O, __pyx_k_O, sizeof(__pyx_k_O), 0, 0, 0, 1}, + {&__pyx_kp_u_Out_of_bounds_on_buffer_access_a, __pyx_k_Out_of_bounds_on_buffer_access_a, sizeof(__pyx_k_Out_of_bounds_on_buffer_access_a), 0, 1, 0, 0}, + {&__pyx_n_s_PickleError, __pyx_k_PickleError, sizeof(__pyx_k_PickleError), 0, 0, 1, 1}, + {&__pyx_n_s_Sequence, __pyx_k_Sequence, sizeof(__pyx_k_Sequence), 0, 0, 1, 1}, + {&__pyx_kp_s_Step_may_not_be_zero_axis_d, __pyx_k_Step_may_not_be_zero_axis_d, sizeof(__pyx_k_Step_may_not_be_zero_axis_d), 0, 0, 1, 0}, + {&__pyx_kp_b_T, __pyx_k_T, sizeof(__pyx_k_T), 0, 0, 0, 0}, + {&__pyx_n_s_TypeError, __pyx_k_TypeError, sizeof(__pyx_k_TypeError), 0, 0, 1, 1}, + {&__pyx_kp_s_Unable_to_convert_item_to_object, __pyx_k_Unable_to_convert_item_to_object, sizeof(__pyx_k_Unable_to_convert_item_to_object), 0, 0, 1, 0}, + {&__pyx_n_s_ValueError, __pyx_k_ValueError, sizeof(__pyx_k_ValueError), 0, 0, 1, 1}, + {&__pyx_n_s_View_MemoryView, __pyx_k_View_MemoryView, sizeof(__pyx_k_View_MemoryView), 0, 0, 1, 1}, + {&__pyx_kp_b__10, __pyx_k__10, sizeof(__pyx_k__10), 0, 0, 0, 0}, + {&__pyx_kp_b__11, __pyx_k__11, sizeof(__pyx_k__11), 0, 0, 0, 0}, + {&__pyx_kp_b__12, __pyx_k__12, sizeof(__pyx_k__12), 0, 0, 0, 0}, + {&__pyx_kp_u__13, __pyx_k__13, sizeof(__pyx_k__13), 0, 1, 0, 0}, + {&__pyx_kp_u__14, __pyx_k__14, sizeof(__pyx_k__14), 0, 1, 0, 0}, + {&__pyx_kp_u__2, __pyx_k__2, sizeof(__pyx_k__2), 0, 1, 0, 0}, + {&__pyx_n_s__3, __pyx_k__3, sizeof(__pyx_k__3), 0, 0, 1, 1}, + {&__pyx_n_s__40, __pyx_k__40, sizeof(__pyx_k__40), 0, 0, 1, 1}, + {&__pyx_kp_u__6, __pyx_k__6, sizeof(__pyx_k__6), 0, 1, 0, 0}, + {&__pyx_kp_u__7, __pyx_k__7, sizeof(__pyx_k__7), 0, 1, 0, 0}, + {&__pyx_kp_b__9, __pyx_k__9, sizeof(__pyx_k__9), 0, 0, 0, 0}, + {&__pyx_n_s_abc, __pyx_k_abc, sizeof(__pyx_k_abc), 0, 0, 1, 1}, + {&__pyx_n_s_allocate_buffer, __pyx_k_allocate_buffer, sizeof(__pyx_k_allocate_buffer), 0, 0, 1, 1}, + {&__pyx_kp_u_and, __pyx_k_and, sizeof(__pyx_k_and), 0, 1, 0, 0}, + {&__pyx_n_s_asarray, __pyx_k_asarray, sizeof(__pyx_k_asarray), 0, 0, 1, 1}, + {&__pyx_n_s_asyncio_coroutines, __pyx_k_asyncio_coroutines, sizeof(__pyx_k_asyncio_coroutines), 0, 0, 1, 1}, + {&__pyx_n_s_base, __pyx_k_base, sizeof(__pyx_k_base), 0, 0, 1, 1}, + {&__pyx_n_s_buf, __pyx_k_buf, sizeof(__pyx_k_buf), 0, 0, 1, 1}, + {&__pyx_n_s_c, __pyx_k_c, sizeof(__pyx_k_c), 0, 0, 1, 1}, + {&__pyx_n_u_c, __pyx_k_c, sizeof(__pyx_k_c), 0, 1, 0, 1}, + {&__pyx_n_s_class, __pyx_k_class, sizeof(__pyx_k_class), 0, 0, 1, 1}, + {&__pyx_n_s_class_getitem, __pyx_k_class_getitem, sizeof(__pyx_k_class_getitem), 0, 0, 1, 1}, + {&__pyx_n_s_cline_in_traceback, __pyx_k_cline_in_traceback, sizeof(__pyx_k_cline_in_traceback), 0, 0, 1, 1}, + {&__pyx_n_s_collections, __pyx_k_collections, sizeof(__pyx_k_collections), 0, 0, 1, 1}, + {&__pyx_kp_s_collections_abc, __pyx_k_collections_abc, sizeof(__pyx_k_collections_abc), 0, 0, 1, 0}, + {&__pyx_n_s_context, __pyx_k_context, sizeof(__pyx_k_context), 0, 0, 1, 1}, + {&__pyx_kp_s_contiguous_and_direct, __pyx_k_contiguous_and_direct, sizeof(__pyx_k_contiguous_and_direct), 0, 0, 1, 0}, + {&__pyx_kp_s_contiguous_and_indirect, __pyx_k_contiguous_and_indirect, sizeof(__pyx_k_contiguous_and_indirect), 0, 0, 1, 0}, + {&__pyx_n_s_count, __pyx_k_count, sizeof(__pyx_k_count), 0, 0, 1, 1}, + {&__pyx_n_s_cprojection, __pyx_k_cprojection, sizeof(__pyx_k_cprojection), 0, 0, 1, 1}, + {&__pyx_n_s_data, __pyx_k_data, sizeof(__pyx_k_data), 0, 0, 1, 1}, + {&__pyx_n_s_dict, __pyx_k_dict, sizeof(__pyx_k_dict), 0, 0, 1, 1}, + {&__pyx_kp_u_disable, __pyx_k_disable, sizeof(__pyx_k_disable), 0, 1, 0, 0}, + {&__pyx_n_s_dtype_is_object, __pyx_k_dtype_is_object, sizeof(__pyx_k_dtype_is_object), 0, 0, 1, 1}, + {&__pyx_kp_u_enable, __pyx_k_enable, sizeof(__pyx_k_enable), 0, 1, 0, 0}, + {&__pyx_n_s_encode, __pyx_k_encode, sizeof(__pyx_k_encode), 0, 0, 1, 1}, + {&__pyx_n_s_enumerate, __pyx_k_enumerate, sizeof(__pyx_k_enumerate), 0, 0, 1, 1}, + {&__pyx_n_s_error, __pyx_k_error, sizeof(__pyx_k_error), 0, 0, 1, 1}, + {&__pyx_n_s_flags, __pyx_k_flags, sizeof(__pyx_k_flags), 0, 0, 1, 1}, + {&__pyx_n_s_format, __pyx_k_format, sizeof(__pyx_k_format), 0, 0, 1, 1}, + {&__pyx_n_s_fortran, __pyx_k_fortran, sizeof(__pyx_k_fortran), 0, 0, 1, 1}, + {&__pyx_n_u_fortran, __pyx_k_fortran, sizeof(__pyx_k_fortran), 0, 1, 0, 1}, + {&__pyx_kp_u_gc, __pyx_k_gc, sizeof(__pyx_k_gc), 0, 1, 0, 0}, + {&__pyx_n_s_getstate, __pyx_k_getstate, sizeof(__pyx_k_getstate), 0, 0, 1, 1}, + {&__pyx_kp_u_got, __pyx_k_got, sizeof(__pyx_k_got), 0, 1, 0, 0}, + {&__pyx_kp_u_got_differing_extents_in_dimensi, __pyx_k_got_differing_extents_in_dimensi, sizeof(__pyx_k_got_differing_extents_in_dimensi), 0, 1, 0, 0}, + {&__pyx_n_s_height, __pyx_k_height, sizeof(__pyx_k_height), 0, 0, 1, 1}, + {&__pyx_n_s_id, __pyx_k_id, sizeof(__pyx_k_id), 0, 0, 1, 1}, + {&__pyx_n_s_import, __pyx_k_import, sizeof(__pyx_k_import), 0, 0, 1, 1}, + {&__pyx_n_s_index, __pyx_k_index, sizeof(__pyx_k_index), 0, 0, 1, 1}, + {&__pyx_n_s_initializing, __pyx_k_initializing, sizeof(__pyx_k_initializing), 0, 0, 1, 1}, + {&__pyx_n_s_is_coroutine, __pyx_k_is_coroutine, sizeof(__pyx_k_is_coroutine), 0, 0, 1, 1}, + {&__pyx_kp_u_isenabled, __pyx_k_isenabled, sizeof(__pyx_k_isenabled), 0, 1, 0, 0}, + {&__pyx_n_s_itemsize, __pyx_k_itemsize, sizeof(__pyx_k_itemsize), 0, 0, 1, 1}, + {&__pyx_kp_s_itemsize_0_for_cython_array, __pyx_k_itemsize_0_for_cython_array, sizeof(__pyx_k_itemsize_0_for_cython_array), 0, 0, 1, 0}, + {&__pyx_n_s_join, __pyx_k_join, sizeof(__pyx_k_join), 0, 0, 1, 1}, + {&__pyx_n_s_main, __pyx_k_main, sizeof(__pyx_k_main), 0, 0, 1, 1}, + {&__pyx_n_s_memview, __pyx_k_memview, sizeof(__pyx_k_memview), 0, 0, 1, 1}, + {&__pyx_n_s_mode, __pyx_k_mode, sizeof(__pyx_k_mode), 0, 0, 1, 1}, + {&__pyx_n_s_name, __pyx_k_name, sizeof(__pyx_k_name), 0, 0, 1, 1}, + {&__pyx_n_s_name_2, __pyx_k_name_2, sizeof(__pyx_k_name_2), 0, 0, 1, 1}, + {&__pyx_n_s_ndim, __pyx_k_ndim, sizeof(__pyx_k_ndim), 0, 0, 1, 1}, + {&__pyx_n_s_new, __pyx_k_new, sizeof(__pyx_k_new), 0, 0, 1, 1}, + {&__pyx_kp_s_no_default___reduce___due_to_non, __pyx_k_no_default___reduce___due_to_non, sizeof(__pyx_k_no_default___reduce___due_to_non), 0, 0, 1, 0}, + {&__pyx_n_s_np, __pyx_k_np, sizeof(__pyx_k_np), 0, 0, 1, 1}, + {&__pyx_n_s_numpy, __pyx_k_numpy, sizeof(__pyx_k_numpy), 0, 0, 1, 1}, + {&__pyx_kp_u_numpy_core_multiarray_failed_to, __pyx_k_numpy_core_multiarray_failed_to, sizeof(__pyx_k_numpy_core_multiarray_failed_to), 0, 1, 0, 0}, + {&__pyx_kp_u_numpy_core_umath_failed_to_impor, __pyx_k_numpy_core_umath_failed_to_impor, sizeof(__pyx_k_numpy_core_umath_failed_to_impor), 0, 1, 0, 0}, + {&__pyx_n_s_obj, __pyx_k_obj, sizeof(__pyx_k_obj), 0, 0, 1, 1}, + {&__pyx_n_s_output, __pyx_k_output, sizeof(__pyx_k_output), 0, 0, 1, 1}, + {&__pyx_n_s_pack, __pyx_k_pack, sizeof(__pyx_k_pack), 0, 0, 1, 1}, + {&__pyx_n_s_pickle, __pyx_k_pickle, sizeof(__pyx_k_pickle), 0, 0, 1, 1}, + {&__pyx_n_s_prepare, __pyx_k_prepare, sizeof(__pyx_k_prepare), 0, 0, 1, 1}, + {&__pyx_n_s_projection, __pyx_k_projection, sizeof(__pyx_k_projection), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_PickleError, __pyx_k_pyx_PickleError, sizeof(__pyx_k_pyx_PickleError), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_checksum, __pyx_k_pyx_checksum, sizeof(__pyx_k_pyx_checksum), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_result, __pyx_k_pyx_result, sizeof(__pyx_k_pyx_result), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_state, __pyx_k_pyx_state, sizeof(__pyx_k_pyx_state), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_type, __pyx_k_pyx_type, sizeof(__pyx_k_pyx_type), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_unpickle_Enum, __pyx_k_pyx_unpickle_Enum, sizeof(__pyx_k_pyx_unpickle_Enum), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_vtable, __pyx_k_pyx_vtable, sizeof(__pyx_k_pyx_vtable), 0, 0, 1, 1}, + {&__pyx_n_s_range, __pyx_k_range, sizeof(__pyx_k_range), 0, 0, 1, 1}, + {&__pyx_n_s_reduce, __pyx_k_reduce, sizeof(__pyx_k_reduce), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_cython, __pyx_k_reduce_cython, sizeof(__pyx_k_reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_ex, __pyx_k_reduce_ex, sizeof(__pyx_k_reduce_ex), 0, 0, 1, 1}, + {&__pyx_n_s_register, __pyx_k_register, sizeof(__pyx_k_register), 0, 0, 1, 1}, + {&__pyx_n_s_self, __pyx_k_self, sizeof(__pyx_k_self), 0, 0, 1, 1}, + {&__pyx_kp_s_self_mem_cannot_be_converted_to, __pyx_k_self_mem_cannot_be_converted_to, sizeof(__pyx_k_self_mem_cannot_be_converted_to), 0, 0, 1, 0}, + {&__pyx_kp_s_selfdrive_modeld_models_commonmo, __pyx_k_selfdrive_modeld_models_commonmo, sizeof(__pyx_k_selfdrive_modeld_models_commonmo), 0, 0, 1, 0}, + {&__pyx_n_s_selfdrive_modeld_models_commonmo_2, __pyx_k_selfdrive_modeld_models_commonmo_2, sizeof(__pyx_k_selfdrive_modeld_models_commonmo_2), 0, 0, 1, 1}, + {&__pyx_n_s_setstate, __pyx_k_setstate, sizeof(__pyx_k_setstate), 0, 0, 1, 1}, + {&__pyx_n_s_setstate_cython, __pyx_k_setstate_cython, sizeof(__pyx_k_setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_shape, __pyx_k_shape, sizeof(__pyx_k_shape), 0, 0, 1, 1}, + {&__pyx_n_s_sigmoid, __pyx_k_sigmoid, sizeof(__pyx_k_sigmoid), 0, 0, 1, 1}, + {&__pyx_n_s_size, __pyx_k_size, sizeof(__pyx_k_size), 0, 0, 1, 1}, + {&__pyx_n_s_spec, __pyx_k_spec, sizeof(__pyx_k_spec), 0, 0, 1, 1}, + {&__pyx_n_s_start, __pyx_k_start, sizeof(__pyx_k_start), 0, 0, 1, 1}, + {&__pyx_n_s_step, __pyx_k_step, sizeof(__pyx_k_step), 0, 0, 1, 1}, + {&__pyx_n_s_stop, __pyx_k_stop, sizeof(__pyx_k_stop), 0, 0, 1, 1}, + {&__pyx_n_s_stride, __pyx_k_stride, sizeof(__pyx_k_stride), 0, 0, 1, 1}, + {&__pyx_kp_s_strided_and_direct, __pyx_k_strided_and_direct, sizeof(__pyx_k_strided_and_direct), 0, 0, 1, 0}, + {&__pyx_kp_s_strided_and_direct_or_indirect, __pyx_k_strided_and_direct_or_indirect, sizeof(__pyx_k_strided_and_direct_or_indirect), 0, 0, 1, 0}, + {&__pyx_kp_s_strided_and_indirect, __pyx_k_strided_and_indirect, sizeof(__pyx_k_strided_and_indirect), 0, 0, 1, 0}, + {&__pyx_kp_s_stringsource, __pyx_k_stringsource, sizeof(__pyx_k_stringsource), 0, 0, 1, 0}, + {&__pyx_n_s_struct, __pyx_k_struct, sizeof(__pyx_k_struct), 0, 0, 1, 1}, + {&__pyx_n_s_sys, __pyx_k_sys, sizeof(__pyx_k_sys), 0, 0, 1, 1}, + {&__pyx_n_s_test, __pyx_k_test, sizeof(__pyx_k_test), 0, 0, 1, 1}, + {&__pyx_kp_s_unable_to_allocate_array_data, __pyx_k_unable_to_allocate_array_data, sizeof(__pyx_k_unable_to_allocate_array_data), 0, 0, 1, 0}, + {&__pyx_kp_s_unable_to_allocate_shape_and_str, __pyx_k_unable_to_allocate_shape_and_str, sizeof(__pyx_k_unable_to_allocate_shape_and_str), 0, 0, 1, 0}, + {&__pyx_n_s_unpack, __pyx_k_unpack, sizeof(__pyx_k_unpack), 0, 0, 1, 1}, + {&__pyx_n_s_update, __pyx_k_update, sizeof(__pyx_k_update), 0, 0, 1, 1}, + {&__pyx_n_s_uv_offset, __pyx_k_uv_offset, sizeof(__pyx_k_uv_offset), 0, 0, 1, 1}, + {&__pyx_n_s_version_info, __pyx_k_version_info, sizeof(__pyx_k_version_info), 0, 0, 1, 1}, + {&__pyx_n_s_width, __pyx_k_width, sizeof(__pyx_k_width), 0, 0, 1, 1}, + {&__pyx_n_s_x, __pyx_k_x, sizeof(__pyx_k_x), 0, 0, 1, 1}, + {0, 0, 0, 0, 0, 0, 0} + }; + return __Pyx_InitStrings(__pyx_string_tab); +} +/* #### Code section: cached_builtins ### */ +static CYTHON_SMALL_CODE int __Pyx_InitCachedBuiltins(void) { + __pyx_builtin_TypeError = __Pyx_GetBuiltinName(__pyx_n_s_TypeError); if (!__pyx_builtin_TypeError) __PYX_ERR(0, 2, __pyx_L1_error) + __pyx_builtin___import__ = __Pyx_GetBuiltinName(__pyx_n_s_import); if (!__pyx_builtin___import__) __PYX_ERR(0, 100, __pyx_L1_error) + __pyx_builtin_ValueError = __Pyx_GetBuiltinName(__pyx_n_s_ValueError); if (!__pyx_builtin_ValueError) __PYX_ERR(0, 141, __pyx_L1_error) + __pyx_builtin_MemoryError = __Pyx_GetBuiltinName(__pyx_n_s_MemoryError); if (!__pyx_builtin_MemoryError) __PYX_ERR(0, 156, __pyx_L1_error) + __pyx_builtin_enumerate = __Pyx_GetBuiltinName(__pyx_n_s_enumerate); if (!__pyx_builtin_enumerate) __PYX_ERR(0, 159, __pyx_L1_error) + __pyx_builtin_range = __Pyx_GetBuiltinName(__pyx_n_s_range); if (!__pyx_builtin_range) __PYX_ERR(0, 261, __pyx_L1_error) + __pyx_builtin_AssertionError = __Pyx_GetBuiltinName(__pyx_n_s_AssertionError); if (!__pyx_builtin_AssertionError) __PYX_ERR(0, 373, __pyx_L1_error) + __pyx_builtin_Ellipsis = __Pyx_GetBuiltinName(__pyx_n_s_Ellipsis); if (!__pyx_builtin_Ellipsis) __PYX_ERR(0, 408, __pyx_L1_error) + __pyx_builtin_id = __Pyx_GetBuiltinName(__pyx_n_s_id); if (!__pyx_builtin_id) __PYX_ERR(0, 618, __pyx_L1_error) + __pyx_builtin_IndexError = __Pyx_GetBuiltinName(__pyx_n_s_IndexError); if (!__pyx_builtin_IndexError) __PYX_ERR(0, 914, __pyx_L1_error) + __pyx_builtin_ImportError = __Pyx_GetBuiltinName(__pyx_n_s_ImportError); if (!__pyx_builtin_ImportError) __PYX_ERR(2, 984, __pyx_L1_error) + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: cached_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_InitCachedConstants", 0); + + /* "View.MemoryView":582 + * def suboffsets(self): + * if self.view.suboffsets == NULL: + * return (-1,) * self.view.ndim # <<<<<<<<<<<<<< + * + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + */ + __pyx_tuple__4 = PyTuple_New(1); if (unlikely(!__pyx_tuple__4)) __PYX_ERR(0, 582, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__4); + __Pyx_INCREF(__pyx_int_neg_1); + __Pyx_GIVEREF(__pyx_int_neg_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_tuple__4, 0, __pyx_int_neg_1)) __PYX_ERR(0, 582, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_tuple__4); + + /* "View.MemoryView":679 + * tup = index if isinstance(index, tuple) else (index,) + * + * result = [slice(None)] * ndim # <<<<<<<<<<<<<< + * have_slices = False + * seen_ellipsis = False + */ + __pyx_slice__5 = PySlice_New(Py_None, Py_None, Py_None); if (unlikely(!__pyx_slice__5)) __PYX_ERR(0, 679, __pyx_L1_error) + __Pyx_GOTREF(__pyx_slice__5); + __Pyx_GIVEREF(__pyx_slice__5); + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + */ + __pyx_tuple__8 = PyTuple_Pack(3, __pyx_int_136983863, __pyx_int_112105877, __pyx_int_184977713); if (unlikely(!__pyx_tuple__8)) __PYX_ERR(0, 4, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__8); + __Pyx_GIVEREF(__pyx_tuple__8); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":984 + * __pyx_import_array() + * except Exception: + * raise ImportError("numpy.core.multiarray failed to import") # <<<<<<<<<<<<<< + * + * cdef inline int import_umath() except -1: + */ + __pyx_tuple__15 = PyTuple_Pack(1, __pyx_kp_u_numpy_core_multiarray_failed_to); if (unlikely(!__pyx_tuple__15)) __PYX_ERR(2, 984, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__15); + __Pyx_GIVEREF(__pyx_tuple__15); + + /* "../../usr/local/pyenv/versions/3.11.4/lib/python3.11/site-packages/numpy/__init__.cython-30.pxd":990 + * _import_umath() + * except Exception: + * raise ImportError("numpy.core.umath failed to import") # <<<<<<<<<<<<<< + * + * cdef inline int import_ufunc() except -1: + */ + __pyx_tuple__16 = PyTuple_Pack(1, __pyx_kp_u_numpy_core_umath_failed_to_impor); if (unlikely(!__pyx_tuple__16)) __PYX_ERR(2, 990, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__16); + __Pyx_GIVEREF(__pyx_tuple__16); + + /* "View.MemoryView":100 + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: + * if __import__("sys").version_info >= (3, 3): # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + */ + __pyx_tuple__17 = PyTuple_Pack(1, __pyx_n_s_sys); if (unlikely(!__pyx_tuple__17)) __PYX_ERR(0, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__17); + __Pyx_GIVEREF(__pyx_tuple__17); + __pyx_tuple__18 = PyTuple_Pack(2, __pyx_int_3, __pyx_int_3); if (unlikely(!__pyx_tuple__18)) __PYX_ERR(0, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__18); + __Pyx_GIVEREF(__pyx_tuple__18); + + /* "View.MemoryView":101 + * try: + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence # <<<<<<<<<<<<<< + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence + */ + __pyx_tuple__19 = PyTuple_Pack(1, __pyx_kp_s_collections_abc); if (unlikely(!__pyx_tuple__19)) __PYX_ERR(0, 101, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__19); + __Pyx_GIVEREF(__pyx_tuple__19); + + /* "View.MemoryView":103 + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence # <<<<<<<<<<<<<< + * except: + * + */ + __pyx_tuple__20 = PyTuple_Pack(1, __pyx_n_s_collections); if (unlikely(!__pyx_tuple__20)) __PYX_ERR(0, 103, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__20); + __Pyx_GIVEREF(__pyx_tuple__20); + + /* "View.MemoryView":309 + * return self.name + * + * cdef generic = Enum("") # <<<<<<<<<<<<<< + * cdef strided = Enum("") # default + * cdef indirect = Enum("") + */ + __pyx_tuple__21 = PyTuple_Pack(1, __pyx_kp_s_strided_and_direct_or_indirect); if (unlikely(!__pyx_tuple__21)) __PYX_ERR(0, 309, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__21); + __Pyx_GIVEREF(__pyx_tuple__21); + + /* "View.MemoryView":310 + * + * cdef generic = Enum("") + * cdef strided = Enum("") # default # <<<<<<<<<<<<<< + * cdef indirect = Enum("") + * + */ + __pyx_tuple__22 = PyTuple_Pack(1, __pyx_kp_s_strided_and_direct); if (unlikely(!__pyx_tuple__22)) __PYX_ERR(0, 310, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__22); + __Pyx_GIVEREF(__pyx_tuple__22); + + /* "View.MemoryView":311 + * cdef generic = Enum("") + * cdef strided = Enum("") # default + * cdef indirect = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_tuple__23 = PyTuple_Pack(1, __pyx_kp_s_strided_and_indirect); if (unlikely(!__pyx_tuple__23)) __PYX_ERR(0, 311, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__23); + __Pyx_GIVEREF(__pyx_tuple__23); + + /* "View.MemoryView":314 + * + * + * cdef contiguous = Enum("") # <<<<<<<<<<<<<< + * cdef indirect_contiguous = Enum("") + * + */ + __pyx_tuple__24 = PyTuple_Pack(1, __pyx_kp_s_contiguous_and_direct); if (unlikely(!__pyx_tuple__24)) __PYX_ERR(0, 314, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__24); + __Pyx_GIVEREF(__pyx_tuple__24); + + /* "View.MemoryView":315 + * + * cdef contiguous = Enum("") + * cdef indirect_contiguous = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_tuple__25 = PyTuple_Pack(1, __pyx_kp_s_contiguous_and_indirect); if (unlikely(!__pyx_tuple__25)) __PYX_ERR(0, 315, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__25); + __Pyx_GIVEREF(__pyx_tuple__25); + + /* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + __pyx_tuple__26 = PyTuple_Pack(5, __pyx_n_s_pyx_type, __pyx_n_s_pyx_checksum, __pyx_n_s_pyx_state, __pyx_n_s_pyx_PickleError, __pyx_n_s_pyx_result); if (unlikely(!__pyx_tuple__26)) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__26); + __Pyx_GIVEREF(__pyx_tuple__26); + __pyx_codeobj__27 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__26, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_pyx_unpickle_Enum, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__27)) __PYX_ERR(0, 1, __pyx_L1_error) + + /* "selfdrive/modeld/models/commonmodel_pyx.pyx":13 + * from .commonmodel cimport mat3, sigmoid as cppSigmoid, ModelFrame as cppModelFrame + * + * def sigmoid(x): # <<<<<<<<<<<<<< + * return cppSigmoid(x) + * + */ + __pyx_tuple__28 = PyTuple_Pack(1, __pyx_n_s_x); if (unlikely(!__pyx_tuple__28)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__28); + __Pyx_GIVEREF(__pyx_tuple__28); + __pyx_codeobj__29 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__28, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_selfdrive_modeld_models_commonmo, __pyx_n_s_sigmoid, 13, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__29)) __PYX_ERR(1, 13, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_tuple__30 = PyTuple_Pack(1, __pyx_n_s_self); if (unlikely(!__pyx_tuple__30)) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__30); + __Pyx_GIVEREF(__pyx_tuple__30); + __pyx_codeobj__31 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__30, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__31)) __PYX_ERR(0, 1, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_tuple__32 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_pyx_state); if (unlikely(!__pyx_tuple__32)) __PYX_ERR(0, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__32); + __Pyx_GIVEREF(__pyx_tuple__32); + __pyx_codeobj__33 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__32, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__33)) __PYX_ERR(0, 3, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.mem cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_codeobj__34 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__30, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__34)) __PYX_ERR(0, 1, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.mem cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.mem cannot be converted to a Python object for pickling" + */ + __pyx_codeobj__35 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__32, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__35)) __PYX_ERR(0, 3, __pyx_L1_error) + + /* "selfdrive/modeld/models/commonmodel_pyx.pyx":37 + * del self.frame + * + * def prepare(self, VisionBuf buf, float[:] projection, CLMem output): # <<<<<<<<<<<<<< + * cdef mat3 cprojection + * memcpy(cprojection.v, &projection[0], 9*sizeof(float)) + */ + __pyx_tuple__36 = PyTuple_Pack(6, __pyx_n_s_self, __pyx_n_s_buf, __pyx_n_s_projection, __pyx_n_s_output, __pyx_n_s_cprojection, __pyx_n_s_data); if (unlikely(!__pyx_tuple__36)) __PYX_ERR(1, 37, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__36); + __Pyx_GIVEREF(__pyx_tuple__36); + __pyx_codeobj__37 = (PyObject*)__Pyx_PyCode_New(4, 0, 0, 6, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__36, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_selfdrive_modeld_models_commonmo, __pyx_n_s_prepare, 37, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__37)) __PYX_ERR(1, 37, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_codeobj__38 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__30, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__38)) __PYX_ERR(0, 1, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_codeobj__39 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__32, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__39)) __PYX_ERR(0, 3, __pyx_L1_error) + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_RefNannyFinishContext(); + return -1; +} +/* #### Code section: init_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitConstants(void) { + if (__Pyx_CreateStringTabAndInitStrings() < 0) __PYX_ERR(1, 1, __pyx_L1_error); + __pyx_int_0 = PyInt_FromLong(0); if (unlikely(!__pyx_int_0)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_int_1 = PyInt_FromLong(1); if (unlikely(!__pyx_int_1)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_int_3 = PyInt_FromLong(3); if (unlikely(!__pyx_int_3)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_int_112105877 = PyInt_FromLong(112105877L); if (unlikely(!__pyx_int_112105877)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_int_136983863 = PyInt_FromLong(136983863L); if (unlikely(!__pyx_int_136983863)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_int_184977713 = PyInt_FromLong(184977713L); if (unlikely(!__pyx_int_184977713)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_int_neg_1 = PyInt_FromLong(-1); if (unlikely(!__pyx_int_neg_1)) __PYX_ERR(1, 1, __pyx_L1_error) + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: init_globals ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitGlobals(void) { + /* AssertionsEnabled.init */ + if (likely(__Pyx_init_assertions_enabled() == 0)); else + +if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L1_error) + + /* NumpyImportArray.init */ + /* + * Cython has automatically inserted a call to _import_array since + * you didn't include one when you cimported numpy. To disable this + * add the line + * numpy._import_array + */ +#ifdef NPY_FEATURE_VERSION +#ifndef NO_IMPORT_ARRAY +if (unlikely(_import_array() == -1)) { + PyErr_SetString(PyExc_ImportError, "numpy.core.multiarray failed to import " + "(auto-generated because you didn't call 'numpy.import_array()' after cimporting numpy; " + "use 'numpy._import_array' to disable if you are certain you don't need it)."); +} +#endif +#endif + +if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L1_error) + + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: init_module ### */ + +static CYTHON_SMALL_CODE int __Pyx_modinit_global_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_import_code(void); /*proto*/ + +static int __Pyx_modinit_global_init_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_global_init_code", 0); + /*--- Global init code ---*/ + __pyx_collections_abc_Sequence = Py_None; Py_INCREF(Py_None); + generic = Py_None; Py_INCREF(Py_None); + strided = Py_None; Py_INCREF(Py_None); + indirect = Py_None; Py_INCREF(Py_None); + contiguous = Py_None; Py_INCREF(Py_None); + indirect_contiguous = Py_None; Py_INCREF(Py_None); + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_variable_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_export_code", 0); + /*--- Variable export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_export_code", 0); + /*--- Function export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_type_init_code(void) { + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_modinit_type_init_code", 0); + /*--- Type init code ---*/ + __pyx_t_1 = PyImport_ImportModule("cereal.visionipc.visionipc_pyx"); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext = __Pyx_ImportType_3_0_8(__pyx_t_1, "cereal.visionipc.visionipc_pyx", "CLContext", sizeof(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_CLContext), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_CLContext),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext) __PYX_ERR(1, 1, __pyx_L1_error) + #if CYTHON_USE_TYPE_SPECS + __pyx_t_2 = PyTuple_Pack(1, (PyObject *)__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 16, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext_spec, __pyx_t_2); + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + if (unlikely(!__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext)) __PYX_ERR(1, 16, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext_spec, __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext) < 0) __PYX_ERR(1, 16, __pyx_L1_error) + #else + __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext = &__pyx_type_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext->tp_dealloc = __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext->tp_dealloc; + __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext->tp_base = __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext; + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext) < 0) __PYX_ERR(1, 16, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext->tp_dictoffset && __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_CLContext, (PyObject *) __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext) < 0) __PYX_ERR(1, 16, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext) < 0) __PYX_ERR(1, 16, __pyx_L1_error) + #endif + __pyx_vtabptr_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem = &__pyx_vtable_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem; + __pyx_vtable_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem.create = (PyObject *(*)(void *))__pyx_f_9selfdrive_6modeld_6models_15commonmodel_pyx_5CLMem_create; + #if CYTHON_USE_TYPE_SPECS + __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem_spec, NULL); if (unlikely(!__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem)) __PYX_ERR(1, 21, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem_spec, __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem) < 0) __PYX_ERR(1, 21, __pyx_L1_error) + #else + __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem = &__pyx_type_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem) < 0) __PYX_ERR(1, 21, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem->tp_dictoffset && __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (__Pyx_SetVtable(__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem, __pyx_vtabptr_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem) < 0) __PYX_ERR(1, 21, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem) < 0) __PYX_ERR(1, 21, __pyx_L1_error) + #endif + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_CLMem, (PyObject *) __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem) < 0) __PYX_ERR(1, 21, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem) < 0) __PYX_ERR(1, 21, __pyx_L1_error) + #endif + #if CYTHON_USE_TYPE_SPECS + __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame_spec, NULL); if (unlikely(!__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame)) __PYX_ERR(1, 28, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame_spec, __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame) < 0) __PYX_ERR(1, 28, __pyx_L1_error) + #else + __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame = &__pyx_type_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame) < 0) __PYX_ERR(1, 28, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame->tp_dictoffset && __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_ModelFrame, (PyObject *) __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame) < 0) __PYX_ERR(1, 28, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame) < 0) __PYX_ERR(1, 28, __pyx_L1_error) + #endif + __pyx_vtabptr_array = &__pyx_vtable_array; + __pyx_vtable_array.get_memview = (PyObject *(*)(struct __pyx_array_obj *))__pyx_array_get_memview; + #if CYTHON_USE_TYPE_SPECS + __pyx_array_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_array_spec, NULL); if (unlikely(!__pyx_array_type)) __PYX_ERR(0, 114, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + __pyx_array_type->tp_as_buffer = &__pyx_tp_as_buffer_array; + if (!__pyx_array_type->tp_as_buffer->bf_releasebuffer && __pyx_array_type->tp_base->tp_as_buffer && __pyx_array_type->tp_base->tp_as_buffer->bf_releasebuffer) { + __pyx_array_type->tp_as_buffer->bf_releasebuffer = __pyx_array_type->tp_base->tp_as_buffer->bf_releasebuffer; + } + #elif defined(Py_bf_getbuffer) && defined(Py_bf_releasebuffer) + /* PY_VERSION_HEX >= 0x03090000 || Py_LIMITED_API >= 0x030B0000 */ + #elif defined(_MSC_VER) + #pragma message ("The buffer protocol is not supported in the Limited C-API < 3.11.") + #else + #warning "The buffer protocol is not supported in the Limited C-API < 3.11." + #endif + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_array_spec, __pyx_array_type) < 0) __PYX_ERR(0, 114, __pyx_L1_error) + #else + __pyx_array_type = &__pyx_type___pyx_array; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_array_type) < 0) __PYX_ERR(0, 114, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_array_type->tp_print = 0; + #endif + if (__Pyx_SetVtable(__pyx_array_type, __pyx_vtabptr_array) < 0) __PYX_ERR(0, 114, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_array_type) < 0) __PYX_ERR(0, 114, __pyx_L1_error) + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_array_type) < 0) __PYX_ERR(0, 114, __pyx_L1_error) + #endif + #if CYTHON_USE_TYPE_SPECS + __pyx_MemviewEnum_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_MemviewEnum_spec, NULL); if (unlikely(!__pyx_MemviewEnum_type)) __PYX_ERR(0, 302, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_MemviewEnum_spec, __pyx_MemviewEnum_type) < 0) __PYX_ERR(0, 302, __pyx_L1_error) + #else + __pyx_MemviewEnum_type = &__pyx_type___pyx_MemviewEnum; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_MemviewEnum_type) < 0) __PYX_ERR(0, 302, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_MemviewEnum_type->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_MemviewEnum_type->tp_dictoffset && __pyx_MemviewEnum_type->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_MemviewEnum_type->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_MemviewEnum_type) < 0) __PYX_ERR(0, 302, __pyx_L1_error) + #endif + __pyx_vtabptr_memoryview = &__pyx_vtable_memoryview; + __pyx_vtable_memoryview.get_item_pointer = (char *(*)(struct __pyx_memoryview_obj *, PyObject *))__pyx_memoryview_get_item_pointer; + __pyx_vtable_memoryview.is_slice = (PyObject *(*)(struct __pyx_memoryview_obj *, PyObject *))__pyx_memoryview_is_slice; + __pyx_vtable_memoryview.setitem_slice_assignment = (PyObject *(*)(struct __pyx_memoryview_obj *, PyObject *, PyObject *))__pyx_memoryview_setitem_slice_assignment; + __pyx_vtable_memoryview.setitem_slice_assign_scalar = (PyObject *(*)(struct __pyx_memoryview_obj *, struct __pyx_memoryview_obj *, PyObject *))__pyx_memoryview_setitem_slice_assign_scalar; + __pyx_vtable_memoryview.setitem_indexed = (PyObject *(*)(struct __pyx_memoryview_obj *, PyObject *, PyObject *))__pyx_memoryview_setitem_indexed; + __pyx_vtable_memoryview.convert_item_to_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *))__pyx_memoryview_convert_item_to_object; + __pyx_vtable_memoryview.assign_item_from_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *, PyObject *))__pyx_memoryview_assign_item_from_object; + __pyx_vtable_memoryview._get_base = (PyObject *(*)(struct __pyx_memoryview_obj *))__pyx_memoryview__get_base; + #if CYTHON_USE_TYPE_SPECS + __pyx_memoryview_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_memoryview_spec, NULL); if (unlikely(!__pyx_memoryview_type)) __PYX_ERR(0, 337, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + __pyx_memoryview_type->tp_as_buffer = &__pyx_tp_as_buffer_memoryview; + if (!__pyx_memoryview_type->tp_as_buffer->bf_releasebuffer && __pyx_memoryview_type->tp_base->tp_as_buffer && __pyx_memoryview_type->tp_base->tp_as_buffer->bf_releasebuffer) { + __pyx_memoryview_type->tp_as_buffer->bf_releasebuffer = __pyx_memoryview_type->tp_base->tp_as_buffer->bf_releasebuffer; + } + #elif defined(Py_bf_getbuffer) && defined(Py_bf_releasebuffer) + /* PY_VERSION_HEX >= 0x03090000 || Py_LIMITED_API >= 0x030B0000 */ + #elif defined(_MSC_VER) + #pragma message ("The buffer protocol is not supported in the Limited C-API < 3.11.") + #else + #warning "The buffer protocol is not supported in the Limited C-API < 3.11." + #endif + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_memoryview_spec, __pyx_memoryview_type) < 0) __PYX_ERR(0, 337, __pyx_L1_error) + #else + __pyx_memoryview_type = &__pyx_type___pyx_memoryview; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_memoryview_type) < 0) __PYX_ERR(0, 337, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_memoryview_type->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_memoryview_type->tp_dictoffset && __pyx_memoryview_type->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_memoryview_type->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (__Pyx_SetVtable(__pyx_memoryview_type, __pyx_vtabptr_memoryview) < 0) __PYX_ERR(0, 337, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_memoryview_type) < 0) __PYX_ERR(0, 337, __pyx_L1_error) + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_memoryview_type) < 0) __PYX_ERR(0, 337, __pyx_L1_error) + #endif + __pyx_vtabptr__memoryviewslice = &__pyx_vtable__memoryviewslice; + __pyx_vtable__memoryviewslice.__pyx_base = *__pyx_vtabptr_memoryview; + __pyx_vtable__memoryviewslice.__pyx_base.convert_item_to_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *))__pyx_memoryviewslice_convert_item_to_object; + __pyx_vtable__memoryviewslice.__pyx_base.assign_item_from_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *, PyObject *))__pyx_memoryviewslice_assign_item_from_object; + __pyx_vtable__memoryviewslice.__pyx_base._get_base = (PyObject *(*)(struct __pyx_memoryview_obj *))__pyx_memoryviewslice__get_base; + #if CYTHON_USE_TYPE_SPECS + __pyx_t_2 = PyTuple_Pack(1, (PyObject *)__pyx_memoryview_type); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 952, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_memoryviewslice_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_memoryviewslice_spec, __pyx_t_2); + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + if (unlikely(!__pyx_memoryviewslice_type)) __PYX_ERR(0, 952, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_memoryviewslice_spec, __pyx_memoryviewslice_type) < 0) __PYX_ERR(0, 952, __pyx_L1_error) + #else + __pyx_memoryviewslice_type = &__pyx_type___pyx_memoryviewslice; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + __pyx_memoryviewslice_type->tp_base = __pyx_memoryview_type; + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_memoryviewslice_type) < 0) __PYX_ERR(0, 952, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_memoryviewslice_type->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_memoryviewslice_type->tp_dictoffset && __pyx_memoryviewslice_type->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_memoryviewslice_type->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (__Pyx_SetVtable(__pyx_memoryviewslice_type, __pyx_vtabptr__memoryviewslice) < 0) __PYX_ERR(0, 952, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_memoryviewslice_type) < 0) __PYX_ERR(0, 952, __pyx_L1_error) + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_memoryviewslice_type) < 0) __PYX_ERR(0, 952, __pyx_L1_error) + #endif + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_RefNannyFinishContext(); + return -1; +} + +static int __Pyx_modinit_type_import_code(void) { + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_modinit_type_import_code", 0); + /*--- Type import code ---*/ + __pyx_t_1 = PyImport_ImportModule("cereal.visionipc.visionipc_pyx"); if (unlikely(!__pyx_t_1)) __PYX_ERR(3, 11, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf = __Pyx_ImportType_3_0_8(__pyx_t_1, "cereal.visionipc.visionipc_pyx", "VisionBuf", sizeof(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf) __PYX_ERR(3, 11, __pyx_L1_error) + __pyx_vtabptr_6cereal_9visionipc_13visionipc_pyx_VisionBuf = (struct __pyx_vtabstruct_6cereal_9visionipc_13visionipc_pyx_VisionBuf*)__Pyx_GetVtable(__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf); if (unlikely(!__pyx_vtabptr_6cereal_9visionipc_13visionipc_pyx_VisionBuf)) __PYX_ERR(3, 11, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = PyImport_ImportModule(__Pyx_BUILTIN_MODULE_NAME); if (unlikely(!__pyx_t_1)) __PYX_ERR(4, 9, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_ptype_7cpython_4type_type = __Pyx_ImportType_3_0_8(__pyx_t_1, __Pyx_BUILTIN_MODULE_NAME, "type", + #if defined(PYPY_VERSION_NUM) && PYPY_VERSION_NUM < 0x050B0000 + sizeof(PyTypeObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyTypeObject), + #elif CYTHON_COMPILING_IN_LIMITED_API + sizeof(PyTypeObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyTypeObject), + #else + sizeof(PyHeapTypeObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyHeapTypeObject), + #endif + __Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_7cpython_4type_type) __PYX_ERR(4, 9, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = PyImport_ImportModule("numpy"); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 202, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_ptype_5numpy_dtype = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "dtype", sizeof(PyArray_Descr), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyArray_Descr),__Pyx_ImportType_CheckSize_Ignore_3_0_8); if (!__pyx_ptype_5numpy_dtype) __PYX_ERR(2, 202, __pyx_L1_error) + __pyx_ptype_5numpy_flatiter = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "flatiter", sizeof(PyArrayIterObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyArrayIterObject),__Pyx_ImportType_CheckSize_Ignore_3_0_8); if (!__pyx_ptype_5numpy_flatiter) __PYX_ERR(2, 225, __pyx_L1_error) + __pyx_ptype_5numpy_broadcast = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "broadcast", sizeof(PyArrayMultiIterObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyArrayMultiIterObject),__Pyx_ImportType_CheckSize_Ignore_3_0_8); if (!__pyx_ptype_5numpy_broadcast) __PYX_ERR(2, 229, __pyx_L1_error) + __pyx_ptype_5numpy_ndarray = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "ndarray", sizeof(PyArrayObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyArrayObject),__Pyx_ImportType_CheckSize_Ignore_3_0_8); if (!__pyx_ptype_5numpy_ndarray) __PYX_ERR(2, 238, __pyx_L1_error) + __pyx_ptype_5numpy_generic = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "generic", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_generic) __PYX_ERR(2, 809, __pyx_L1_error) + __pyx_ptype_5numpy_number = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "number", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_number) __PYX_ERR(2, 811, __pyx_L1_error) + __pyx_ptype_5numpy_integer = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "integer", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_integer) __PYX_ERR(2, 813, __pyx_L1_error) + __pyx_ptype_5numpy_signedinteger = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "signedinteger", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_signedinteger) __PYX_ERR(2, 815, __pyx_L1_error) + __pyx_ptype_5numpy_unsignedinteger = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "unsignedinteger", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_unsignedinteger) __PYX_ERR(2, 817, __pyx_L1_error) + __pyx_ptype_5numpy_inexact = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "inexact", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_inexact) __PYX_ERR(2, 819, __pyx_L1_error) + __pyx_ptype_5numpy_floating = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "floating", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_floating) __PYX_ERR(2, 821, __pyx_L1_error) + __pyx_ptype_5numpy_complexfloating = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "complexfloating", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_complexfloating) __PYX_ERR(2, 823, __pyx_L1_error) + __pyx_ptype_5numpy_flexible = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "flexible", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_flexible) __PYX_ERR(2, 825, __pyx_L1_error) + __pyx_ptype_5numpy_character = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "character", sizeof(PyObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyObject),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_5numpy_character) __PYX_ERR(2, 827, __pyx_L1_error) + __pyx_ptype_5numpy_ufunc = __Pyx_ImportType_3_0_8(__pyx_t_1, "numpy", "ufunc", sizeof(PyUFuncObject), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(PyUFuncObject),__Pyx_ImportType_CheckSize_Ignore_3_0_8); if (!__pyx_ptype_5numpy_ufunc) __PYX_ERR(2, 866, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_RefNannyFinishContext(); + return -1; +} + +static int __Pyx_modinit_variable_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_import_code", 0); + /*--- Variable import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_import_code", 0); + /*--- Function import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + + +#if PY_MAJOR_VERSION >= 3 +#if CYTHON_PEP489_MULTI_PHASE_INIT +static PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def); /*proto*/ +static int __pyx_pymod_exec_commonmodel_pyx(PyObject* module); /*proto*/ +static PyModuleDef_Slot __pyx_moduledef_slots[] = { + {Py_mod_create, (void*)__pyx_pymod_create}, + {Py_mod_exec, (void*)__pyx_pymod_exec_commonmodel_pyx}, + {0, NULL} +}; +#endif + +#ifdef __cplusplus +namespace { + struct PyModuleDef __pyx_moduledef = + #else + static struct PyModuleDef __pyx_moduledef = + #endif + { + PyModuleDef_HEAD_INIT, + "commonmodel_pyx", + 0, /* m_doc */ + #if CYTHON_PEP489_MULTI_PHASE_INIT + 0, /* m_size */ + #elif CYTHON_USE_MODULE_STATE + sizeof(__pyx_mstate), /* m_size */ + #else + -1, /* m_size */ + #endif + __pyx_methods /* m_methods */, + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_moduledef_slots, /* m_slots */ + #else + NULL, /* m_reload */ + #endif + #if CYTHON_USE_MODULE_STATE + __pyx_m_traverse, /* m_traverse */ + __pyx_m_clear, /* m_clear */ + NULL /* m_free */ + #else + NULL, /* m_traverse */ + NULL, /* m_clear */ + NULL /* m_free */ + #endif + }; + #ifdef __cplusplus +} /* anonymous namespace */ +#endif +#endif + +#ifndef CYTHON_NO_PYINIT_EXPORT +#define __Pyx_PyMODINIT_FUNC PyMODINIT_FUNC +#elif PY_MAJOR_VERSION < 3 +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" void +#else +#define __Pyx_PyMODINIT_FUNC void +#endif +#else +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" PyObject * +#else +#define __Pyx_PyMODINIT_FUNC PyObject * +#endif +#endif + + +#if PY_MAJOR_VERSION < 3 +__Pyx_PyMODINIT_FUNC initcommonmodel_pyx(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC initcommonmodel_pyx(void) +#else +__Pyx_PyMODINIT_FUNC PyInit_commonmodel_pyx(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC PyInit_commonmodel_pyx(void) +#if CYTHON_PEP489_MULTI_PHASE_INIT +{ + return PyModuleDef_Init(&__pyx_moduledef); +} +static CYTHON_SMALL_CODE int __Pyx_check_single_interpreter(void) { + #if PY_VERSION_HEX >= 0x030700A1 + static PY_INT64_T main_interpreter_id = -1; + PY_INT64_T current_id = PyInterpreterState_GetID(PyThreadState_Get()->interp); + if (main_interpreter_id == -1) { + main_interpreter_id = current_id; + return (unlikely(current_id == -1)) ? -1 : 0; + } else if (unlikely(main_interpreter_id != current_id)) + #else + static PyInterpreterState *main_interpreter = NULL; + PyInterpreterState *current_interpreter = PyThreadState_Get()->interp; + if (!main_interpreter) { + main_interpreter = current_interpreter; + } else if (unlikely(main_interpreter != current_interpreter)) + #endif + { + PyErr_SetString( + PyExc_ImportError, + "Interpreter change detected - this module can only be loaded into one interpreter per process."); + return -1; + } + return 0; +} +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *module, const char* from_name, const char* to_name, int allow_none) +#else +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *moddict, const char* from_name, const char* to_name, int allow_none) +#endif +{ + PyObject *value = PyObject_GetAttrString(spec, from_name); + int result = 0; + if (likely(value)) { + if (allow_none || value != Py_None) { +#if CYTHON_COMPILING_IN_LIMITED_API + result = PyModule_AddObject(module, to_name, value); +#else + result = PyDict_SetItemString(moddict, to_name, value); +#endif + } + Py_DECREF(value); + } else if (PyErr_ExceptionMatches(PyExc_AttributeError)) { + PyErr_Clear(); + } else { + result = -1; + } + return result; +} +static CYTHON_SMALL_CODE PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def) { + PyObject *module = NULL, *moddict, *modname; + CYTHON_UNUSED_VAR(def); + if (__Pyx_check_single_interpreter()) + return NULL; + if (__pyx_m) + return __Pyx_NewRef(__pyx_m); + modname = PyObject_GetAttrString(spec, "name"); + if (unlikely(!modname)) goto bad; + module = PyModule_NewObject(modname); + Py_DECREF(modname); + if (unlikely(!module)) goto bad; +#if CYTHON_COMPILING_IN_LIMITED_API + moddict = module; +#else + moddict = PyModule_GetDict(module); + if (unlikely(!moddict)) goto bad; +#endif + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "loader", "__loader__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "origin", "__file__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "parent", "__package__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "submodule_search_locations", "__path__", 0) < 0)) goto bad; + return module; +bad: + Py_XDECREF(module); + return NULL; +} + + +static CYTHON_SMALL_CODE int __pyx_pymod_exec_commonmodel_pyx(PyObject *__pyx_pyinit_module) +#endif +#endif +{ + int stringtab_initialized = 0; + #if CYTHON_USE_MODULE_STATE + int pystate_addmodule_run = 0; + #endif + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + static PyThread_type_lock __pyx_t_8[8]; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannyDeclarations + #if CYTHON_PEP489_MULTI_PHASE_INIT + if (__pyx_m) { + if (__pyx_m == __pyx_pyinit_module) return 0; + PyErr_SetString(PyExc_RuntimeError, "Module 'commonmodel_pyx' has already been imported. Re-initialisation is not supported."); + return -1; + } + #elif PY_MAJOR_VERSION >= 3 + if (__pyx_m) return __Pyx_NewRef(__pyx_m); + #endif + /*--- Module creation code ---*/ + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_m = __pyx_pyinit_module; + Py_INCREF(__pyx_m); + #else + #if PY_MAJOR_VERSION < 3 + __pyx_m = Py_InitModule4("commonmodel_pyx", __pyx_methods, 0, 0, PYTHON_API_VERSION); Py_XINCREF(__pyx_m); + if (unlikely(!__pyx_m)) __PYX_ERR(1, 1, __pyx_L1_error) + #elif CYTHON_USE_MODULE_STATE + __pyx_t_1 = PyModule_Create(&__pyx_moduledef); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 1, __pyx_L1_error) + { + int add_module_result = PyState_AddModule(__pyx_t_1, &__pyx_moduledef); + __pyx_t_1 = 0; /* transfer ownership from __pyx_t_1 to "commonmodel_pyx" pseudovariable */ + if (unlikely((add_module_result < 0))) __PYX_ERR(1, 1, __pyx_L1_error) + pystate_addmodule_run = 1; + } + #else + __pyx_m = PyModule_Create(&__pyx_moduledef); + if (unlikely(!__pyx_m)) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + #endif + CYTHON_UNUSED_VAR(__pyx_t_1); + __pyx_d = PyModule_GetDict(__pyx_m); if (unlikely(!__pyx_d)) __PYX_ERR(1, 1, __pyx_L1_error) + Py_INCREF(__pyx_d); + __pyx_b = __Pyx_PyImport_AddModuleRef(__Pyx_BUILTIN_MODULE_NAME); if (unlikely(!__pyx_b)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_cython_runtime = __Pyx_PyImport_AddModuleRef((const char *) "cython_runtime"); if (unlikely(!__pyx_cython_runtime)) __PYX_ERR(1, 1, __pyx_L1_error) + if (PyObject_SetAttrString(__pyx_m, "__builtins__", __pyx_b) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #if CYTHON_REFNANNY +__Pyx_RefNanny = __Pyx_RefNannyImportAPI("refnanny"); +if (!__Pyx_RefNanny) { + PyErr_Clear(); + __Pyx_RefNanny = __Pyx_RefNannyImportAPI("Cython.Runtime.refnanny"); + if (!__Pyx_RefNanny) + Py_FatalError("failed to import 'refnanny' module"); +} +#endif + __Pyx_RefNannySetupContext("__Pyx_PyMODINIT_FUNC PyInit_commonmodel_pyx(void)", 0); + if (__Pyx_check_binary_version(__PYX_LIMITED_VERSION_HEX, __Pyx_get_runtime_version(), CYTHON_COMPILING_IN_LIMITED_API) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #ifdef __Pxy_PyFrame_Initialize_Offsets + __Pxy_PyFrame_Initialize_Offsets(); + #endif + __pyx_empty_tuple = PyTuple_New(0); if (unlikely(!__pyx_empty_tuple)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_empty_bytes = PyBytes_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_bytes)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_empty_unicode = PyUnicode_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_unicode)) __PYX_ERR(1, 1, __pyx_L1_error) + #ifdef __Pyx_CyFunction_USED + if (__pyx_CyFunction_init(__pyx_m) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_FusedFunction_USED + if (__pyx_FusedFunction_init(__pyx_m) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Coroutine_USED + if (__pyx_Coroutine_init(__pyx_m) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Generator_USED + if (__pyx_Generator_init(__pyx_m) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_AsyncGen_USED + if (__pyx_AsyncGen_init(__pyx_m) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_StopAsyncIteration_USED + if (__pyx_StopAsyncIteration_init(__pyx_m) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + /*--- Library function declarations ---*/ + /*--- Threads initialization code ---*/ + #if defined(WITH_THREAD) && PY_VERSION_HEX < 0x030700F0 && defined(__PYX_FORCE_INIT_THREADS) && __PYX_FORCE_INIT_THREADS + PyEval_InitThreads(); + #endif + /*--- Initialize various global constants etc. ---*/ + if (__Pyx_InitConstants() < 0) __PYX_ERR(1, 1, __pyx_L1_error) + stringtab_initialized = 1; + if (__Pyx_InitGlobals() < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #if PY_MAJOR_VERSION < 3 && (__PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT) + if (__Pyx_init_sys_getdefaultencoding_params() < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + if (__pyx_module_is_main_selfdrive__modeld__models__commonmodel_pyx) { + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_name_2, __pyx_n_s_main) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + } + #if PY_MAJOR_VERSION >= 3 + { + PyObject *modules = PyImport_GetModuleDict(); if (unlikely(!modules)) __PYX_ERR(1, 1, __pyx_L1_error) + if (!PyDict_GetItemString(modules, "selfdrive.modeld.models.commonmodel_pyx")) { + if (unlikely((PyDict_SetItemString(modules, "selfdrive.modeld.models.commonmodel_pyx", __pyx_m) < 0))) __PYX_ERR(1, 1, __pyx_L1_error) + } + } + #endif + /*--- Builtin init code ---*/ + if (__Pyx_InitCachedBuiltins() < 0) __PYX_ERR(1, 1, __pyx_L1_error) + /*--- Constants init code ---*/ + if (__Pyx_InitCachedConstants() < 0) __PYX_ERR(1, 1, __pyx_L1_error) + /*--- Global type/function init code ---*/ + (void)__Pyx_modinit_global_init_code(); + (void)__Pyx_modinit_variable_export_code(); + (void)__Pyx_modinit_function_export_code(); + if (unlikely((__Pyx_modinit_type_init_code() < 0))) __PYX_ERR(1, 1, __pyx_L1_error) + if (unlikely((__Pyx_modinit_type_import_code() < 0))) __PYX_ERR(1, 1, __pyx_L1_error) + (void)__Pyx_modinit_variable_import_code(); + (void)__Pyx_modinit_function_import_code(); + /*--- Execution code ---*/ + #if defined(__Pyx_Generator_USED) || defined(__Pyx_Coroutine_USED) + if (__Pyx_patch_abc() < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + + /* "View.MemoryView":99 + * + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: # <<<<<<<<<<<<<< + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "View.MemoryView":100 + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: + * if __import__("sys").version_info >= (3, 3): # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + */ + __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__17, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 100, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_version_info); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 100, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = PyObject_RichCompare(__pyx_t_5, __pyx_tuple__18, Py_GE); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 100, __pyx_L2_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_6 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 100, __pyx_L2_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (__pyx_t_6) { + + /* "View.MemoryView":101 + * try: + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence # <<<<<<<<<<<<<< + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence + */ + __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__19, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 101, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_abc); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 101, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_Sequence); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 101, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XGOTREF(__pyx_collections_abc_Sequence); + __Pyx_DECREF_SET(__pyx_collections_abc_Sequence, __pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + __pyx_t_4 = 0; + + /* "View.MemoryView":100 + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: + * if __import__("sys").version_info >= (3, 3): # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + */ + goto __pyx_L8; + } + + /* "View.MemoryView":103 + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence # <<<<<<<<<<<<<< + * except: + * + */ + /*else*/ { + __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__20, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 103, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_Sequence); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 103, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XGOTREF(__pyx_collections_abc_Sequence); + __Pyx_DECREF_SET(__pyx_collections_abc_Sequence, __pyx_t_5); + __Pyx_GIVEREF(__pyx_t_5); + __pyx_t_5 = 0; + } + __pyx_L8:; + + /* "View.MemoryView":99 + * + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: # <<<<<<<<<<<<<< + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L7_try_end; + __pyx_L2_error:; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "View.MemoryView":104 + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence + * except: # <<<<<<<<<<<<<< + * + * __pyx_collections_abc_Sequence = None + */ + /*except:*/ { + __Pyx_AddTraceback("View.MemoryView", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_4, &__pyx_t_7) < 0) __PYX_ERR(0, 104, __pyx_L4_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_4); + __Pyx_XGOTREF(__pyx_t_7); + + /* "View.MemoryView":106 + * except: + * + * __pyx_collections_abc_Sequence = None # <<<<<<<<<<<<<< + * + * + */ + __Pyx_INCREF(Py_None); + __Pyx_XGOTREF(__pyx_collections_abc_Sequence); + __Pyx_DECREF_SET(__pyx_collections_abc_Sequence, Py_None); + __Pyx_GIVEREF(Py_None); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + goto __pyx_L3_exception_handled; + } + + /* "View.MemoryView":99 + * + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: # <<<<<<<<<<<<<< + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + */ + __pyx_L4_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + goto __pyx_L1_error; + __pyx_L3_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + __pyx_L7_try_end:; + } + + /* "View.MemoryView":241 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_3, &__pyx_t_2, &__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_1); + /*try:*/ { + + /* "View.MemoryView":242 + * + * try: + * count = __pyx_collections_abc_Sequence.count # <<<<<<<<<<<<<< + * index = __pyx_collections_abc_Sequence.index + * except: + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_count); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 242, __pyx_L11_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict(__pyx_array_type, __pyx_n_s_count, __pyx_t_7) < 0) __PYX_ERR(0, 242, __pyx_L11_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_array_type); + + /* "View.MemoryView":243 + * try: + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index # <<<<<<<<<<<<<< + * except: + * pass + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_index); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 243, __pyx_L11_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict(__pyx_array_type, __pyx_n_s_index, __pyx_t_7) < 0) __PYX_ERR(0, 243, __pyx_L11_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_array_type); + + /* "View.MemoryView":241 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + } + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + goto __pyx_L16_try_end; + __pyx_L11_error:; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":244 + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + * except: # <<<<<<<<<<<<<< + * pass + * + */ + /*except:*/ { + __Pyx_ErrRestore(0,0,0); + goto __pyx_L12_exception_handled; + } + __pyx_L12_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_2, __pyx_t_1); + __pyx_L16_try_end:; + } + + /* "View.MemoryView":309 + * return self.name + * + * cdef generic = Enum("") # <<<<<<<<<<<<<< + * cdef strided = Enum("") # default + * cdef indirect = Enum("") + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__21, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 309, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(generic); + __Pyx_DECREF_SET(generic, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":310 + * + * cdef generic = Enum("") + * cdef strided = Enum("") # default # <<<<<<<<<<<<<< + * cdef indirect = Enum("") + * + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__22, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 310, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(strided); + __Pyx_DECREF_SET(strided, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":311 + * cdef generic = Enum("") + * cdef strided = Enum("") # default + * cdef indirect = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__23, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 311, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(indirect); + __Pyx_DECREF_SET(indirect, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":314 + * + * + * cdef contiguous = Enum("") # <<<<<<<<<<<<<< + * cdef indirect_contiguous = Enum("") + * + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__24, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 314, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(contiguous); + __Pyx_DECREF_SET(contiguous, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":315 + * + * cdef contiguous = Enum("") + * cdef indirect_contiguous = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__25, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 315, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(indirect_contiguous); + __Pyx_DECREF_SET(indirect_contiguous, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":323 + * + * + * cdef int __pyx_memoryview_thread_locks_used = 0 # <<<<<<<<<<<<<< + * cdef PyThread_type_lock[8] __pyx_memoryview_thread_locks = [ + * PyThread_allocate_lock(), + */ + __pyx_memoryview_thread_locks_used = 0; + + /* "View.MemoryView":324 + * + * cdef int __pyx_memoryview_thread_locks_used = 0 + * cdef PyThread_type_lock[8] __pyx_memoryview_thread_locks = [ # <<<<<<<<<<<<<< + * PyThread_allocate_lock(), + * PyThread_allocate_lock(), + */ + __pyx_t_8[0] = PyThread_allocate_lock(); + __pyx_t_8[1] = PyThread_allocate_lock(); + __pyx_t_8[2] = PyThread_allocate_lock(); + __pyx_t_8[3] = PyThread_allocate_lock(); + __pyx_t_8[4] = PyThread_allocate_lock(); + __pyx_t_8[5] = PyThread_allocate_lock(); + __pyx_t_8[6] = PyThread_allocate_lock(); + __pyx_t_8[7] = PyThread_allocate_lock(); + memcpy(&(__pyx_memoryview_thread_locks[0]), __pyx_t_8, sizeof(__pyx_memoryview_thread_locks[0]) * (8)); + + /* "View.MemoryView":982 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "View.MemoryView":983 + * + * try: + * count = __pyx_collections_abc_Sequence.count # <<<<<<<<<<<<<< + * index = __pyx_collections_abc_Sequence.index + * except: + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_count); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 983, __pyx_L17_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict(__pyx_memoryviewslice_type, __pyx_n_s_count, __pyx_t_7) < 0) __PYX_ERR(0, 983, __pyx_L17_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_memoryviewslice_type); + + /* "View.MemoryView":984 + * try: + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index # <<<<<<<<<<<<<< + * except: + * pass + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_index); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 984, __pyx_L17_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict(__pyx_memoryviewslice_type, __pyx_n_s_index, __pyx_t_7) < 0) __PYX_ERR(0, 984, __pyx_L17_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_memoryviewslice_type); + + /* "View.MemoryView":982 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L22_try_end; + __pyx_L17_error:; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":985 + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + * except: # <<<<<<<<<<<<<< + * pass + * + */ + /*except:*/ { + __Pyx_ErrRestore(0,0,0); + goto __pyx_L18_exception_handled; + } + __pyx_L18_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + __pyx_L22_try_end:; + } + + /* "View.MemoryView":988 + * pass + * + * try: # <<<<<<<<<<<<<< + * if __pyx_collections_abc_Sequence: + * + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_3, &__pyx_t_2, &__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_1); + /*try:*/ { + + /* "View.MemoryView":989 + * + * try: + * if __pyx_collections_abc_Sequence: # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_6 = __Pyx_PyObject_IsTrue(__pyx_collections_abc_Sequence); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 989, __pyx_L23_error) + if (__pyx_t_6) { + + /* "View.MemoryView":993 + * + * + * __pyx_collections_abc_Sequence.register(_memoryviewslice) # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence.register(array) + * except: + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_register); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 993, __pyx_L23_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_4 = __Pyx_PyObject_CallOneArg(__pyx_t_7, ((PyObject *)__pyx_memoryviewslice_type)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 993, __pyx_L23_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "View.MemoryView":994 + * + * __pyx_collections_abc_Sequence.register(_memoryviewslice) + * __pyx_collections_abc_Sequence.register(array) # <<<<<<<<<<<<<< + * except: + * pass # ignore failure, it's a minor issue + */ + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_register); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 994, __pyx_L23_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_7 = __Pyx_PyObject_CallOneArg(__pyx_t_4, ((PyObject *)__pyx_array_type)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 994, __pyx_L23_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":989 + * + * try: + * if __pyx_collections_abc_Sequence: # <<<<<<<<<<<<<< + * + * + */ + } + + /* "View.MemoryView":988 + * pass + * + * try: # <<<<<<<<<<<<<< + * if __pyx_collections_abc_Sequence: + * + */ + } + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + goto __pyx_L28_try_end; + __pyx_L23_error:; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":995 + * __pyx_collections_abc_Sequence.register(_memoryviewslice) + * __pyx_collections_abc_Sequence.register(array) + * except: # <<<<<<<<<<<<<< + * pass # ignore failure, it's a minor issue + * + */ + /*except:*/ { + __Pyx_ErrRestore(0,0,0); + goto __pyx_L24_exception_handled; + } + __pyx_L24_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_2, __pyx_t_1); + __pyx_L28_try_end:; + } + + /* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + __pyx_t_7 = PyCFunction_NewEx(&__pyx_mdef_15View_dot_MemoryView_1__pyx_unpickle_Enum, NULL, __pyx_n_s_View_MemoryView); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_pyx_unpickle_Enum, __pyx_t_7) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "selfdrive/modeld/models/commonmodel_pyx.pyx":4 + * # cython: c_string_encoding=ascii + * + * import numpy as np # <<<<<<<<<<<<<< + * cimport numpy as cnp + * from libc.string cimport memcpy + */ + __pyx_t_7 = __Pyx_ImportDottedModule(__pyx_n_s_numpy, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 4, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_np, __pyx_t_7) < 0) __PYX_ERR(1, 4, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "selfdrive/modeld/models/commonmodel_pyx.pyx":13 + * from .commonmodel cimport mat3, sigmoid as cppSigmoid, ModelFrame as cppModelFrame + * + * def sigmoid(x): # <<<<<<<<<<<<<< + * return cppSigmoid(x) + * + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_9selfdrive_6modeld_6models_15commonmodel_pyx_1sigmoid, 0, __pyx_n_s_sigmoid, NULL, __pyx_n_s_selfdrive_modeld_models_commonmo_2, __pyx_d, ((PyObject *)__pyx_codeobj__29)); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_sigmoid, __pyx_t_7) < 0) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_9selfdrive_6modeld_6models_15commonmodel_pyx_9CLContext_3__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_CLContext___reduce_cython, NULL, __pyx_n_s_selfdrive_modeld_models_commonmo_2, __pyx_d, ((PyObject *)__pyx_codeobj__31)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_7) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_9selfdrive_6modeld_6models_15commonmodel_pyx_9CLContext_5__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_CLContext___setstate_cython, NULL, __pyx_n_s_selfdrive_modeld_models_commonmo_2, __pyx_d, ((PyObject *)__pyx_codeobj__33)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_7) < 0) __PYX_ERR(0, 3, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.mem cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_9selfdrive_6modeld_6models_15commonmodel_pyx_5CLMem_1__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_CLMem___reduce_cython, NULL, __pyx_n_s_selfdrive_modeld_models_commonmo_2, __pyx_d, ((PyObject *)__pyx_codeobj__34)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_7) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.mem cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.mem cannot be converted to a Python object for pickling" + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_9selfdrive_6modeld_6models_15commonmodel_pyx_5CLMem_3__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_CLMem___setstate_cython, NULL, __pyx_n_s_selfdrive_modeld_models_commonmo_2, __pyx_d, ((PyObject *)__pyx_codeobj__35)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_7) < 0) __PYX_ERR(0, 3, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "selfdrive/modeld/models/commonmodel_pyx.pyx":37 + * del self.frame + * + * def prepare(self, VisionBuf buf, float[:] projection, CLMem output): # <<<<<<<<<<<<<< + * cdef mat3 cprojection + * memcpy(cprojection.v, &projection[0], 9*sizeof(float)) + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_9selfdrive_6modeld_6models_15commonmodel_pyx_10ModelFrame_5prepare, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_ModelFrame_prepare, NULL, __pyx_n_s_selfdrive_modeld_models_commonmo_2, __pyx_d, ((PyObject *)__pyx_codeobj__37)); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 37, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame, __pyx_n_s_prepare, __pyx_t_7) < 0) __PYX_ERR(1, 37, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_ModelFrame); + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_9selfdrive_6modeld_6models_15commonmodel_pyx_10ModelFrame_7__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_ModelFrame___reduce_cython, NULL, __pyx_n_s_selfdrive_modeld_models_commonmo_2, __pyx_d, ((PyObject *)__pyx_codeobj__38)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_7) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_9selfdrive_6modeld_6models_15commonmodel_pyx_10ModelFrame_9__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_ModelFrame___setstate_cython, NULL, __pyx_n_s_selfdrive_modeld_models_commonmo_2, __pyx_d, ((PyObject *)__pyx_codeobj__39)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_7) < 0) __PYX_ERR(0, 3, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "selfdrive/modeld/models/commonmodel_pyx.pyx":1 + * # distutils: language = c++ # <<<<<<<<<<<<<< + * # cython: c_string_encoding=ascii + * + */ + __pyx_t_7 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_test, __pyx_t_7) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /*--- Wrapped vars code ---*/ + + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_7); + if (__pyx_m) { + if (__pyx_d && stringtab_initialized) { + __Pyx_AddTraceback("init selfdrive.modeld.models.commonmodel_pyx", __pyx_clineno, __pyx_lineno, __pyx_filename); + } + #if !CYTHON_USE_MODULE_STATE + Py_CLEAR(__pyx_m); + #else + Py_DECREF(__pyx_m); + if (pystate_addmodule_run) { + PyObject *tp, *value, *tb; + PyErr_Fetch(&tp, &value, &tb); + PyState_RemoveModule(&__pyx_moduledef); + PyErr_Restore(tp, value, tb); + } + #endif + } else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_ImportError, "init selfdrive.modeld.models.commonmodel_pyx"); + } + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + #if CYTHON_PEP489_MULTI_PHASE_INIT + return (__pyx_m != NULL) ? 0 : -1; + #elif PY_MAJOR_VERSION >= 3 + return __pyx_m; + #else + return; + #endif +} +/* #### Code section: cleanup_globals ### */ +/* #### Code section: cleanup_module ### */ +/* #### Code section: main_method ### */ +/* #### Code section: utility_code_pragmas ### */ +#ifdef _MSC_VER +#pragma warning( push ) +/* Warning 4127: conditional expression is constant + * Cython uses constant conditional expressions to allow in inline functions to be optimized at + * compile-time, so this warning is not useful + */ +#pragma warning( disable : 4127 ) +#endif + + + +/* #### Code section: utility_code_def ### */ + +/* --- Runtime support code --- */ +/* Refnanny */ +#if CYTHON_REFNANNY +static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname) { + PyObject *m = NULL, *p = NULL; + void *r = NULL; + m = PyImport_ImportModule(modname); + if (!m) goto end; + p = PyObject_GetAttrString(m, "RefNannyAPI"); + if (!p) goto end; + r = PyLong_AsVoidPtr(p); +end: + Py_XDECREF(p); + Py_XDECREF(m); + return (__Pyx_RefNannyAPIStruct *)r; +} +#endif + +/* PyErrExceptionMatches */ +#if CYTHON_FAST_THREAD_STATE +static int __Pyx_PyErr_ExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; i= 0x030C00A6 + PyObject *current_exception = tstate->current_exception; + if (unlikely(!current_exception)) return 0; + exc_type = (PyObject*) Py_TYPE(current_exception); + if (exc_type == err) return 1; +#else + exc_type = tstate->curexc_type; + if (exc_type == err) return 1; + if (unlikely(!exc_type)) return 0; +#endif + #if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(exc_type); + #endif + if (unlikely(PyTuple_Check(err))) { + result = __Pyx_PyErr_ExceptionMatchesTuple(exc_type, err); + } else { + result = __Pyx_PyErr_GivenExceptionMatches(exc_type, err); + } + #if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(exc_type); + #endif + return result; +} +#endif + +/* PyErrFetchRestore */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject *tmp_value; + assert(type == NULL || (value != NULL && type == (PyObject*) Py_TYPE(value))); + if (value) { + #if CYTHON_COMPILING_IN_CPYTHON + if (unlikely(((PyBaseExceptionObject*) value)->traceback != tb)) + #endif + PyException_SetTraceback(value, tb); + } + tmp_value = tstate->current_exception; + tstate->current_exception = value; + Py_XDECREF(tmp_value); + Py_XDECREF(type); + Py_XDECREF(tb); +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + tmp_type = tstate->curexc_type; + tmp_value = tstate->curexc_value; + tmp_tb = tstate->curexc_traceback; + tstate->curexc_type = type; + tstate->curexc_value = value; + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); +#endif +} +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject* exc_value; + exc_value = tstate->current_exception; + tstate->current_exception = 0; + *value = exc_value; + *type = NULL; + *tb = NULL; + if (exc_value) { + *type = (PyObject*) Py_TYPE(exc_value); + Py_INCREF(*type); + #if CYTHON_COMPILING_IN_CPYTHON + *tb = ((PyBaseExceptionObject*) exc_value)->traceback; + Py_XINCREF(*tb); + #else + *tb = PyException_GetTraceback(exc_value); + #endif + } +#else + *type = tstate->curexc_type; + *value = tstate->curexc_value; + *tb = tstate->curexc_traceback; + tstate->curexc_type = 0; + tstate->curexc_value = 0; + tstate->curexc_traceback = 0; +#endif +} +#endif + +/* PyObjectGetAttrStr */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name) { + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro)) + return tp->tp_getattro(obj, attr_name); +#if PY_MAJOR_VERSION < 3 + if (likely(tp->tp_getattr)) + return tp->tp_getattr(obj, PyString_AS_STRING(attr_name)); +#endif + return PyObject_GetAttr(obj, attr_name); +} +#endif + +/* PyObjectGetAttrStrNoError */ +#if __PYX_LIMITED_VERSION_HEX < 0x030d00A1 +static void __Pyx_PyObject_GetAttrStr_ClearAttributeError(void) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + if (likely(__Pyx_PyErr_ExceptionMatches(PyExc_AttributeError))) + __Pyx_PyErr_Clear(); +} +#endif +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name) { + PyObject *result; +#if __PYX_LIMITED_VERSION_HEX >= 0x030d00A1 + (void) PyObject_GetOptionalAttr(obj, attr_name, &result); + return result; +#else +#if CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_TYPE_SLOTS && PY_VERSION_HEX >= 0x030700B1 + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro == PyObject_GenericGetAttr)) { + return _PyObject_GenericGetAttrWithDict(obj, attr_name, NULL, 1); + } +#endif + result = __Pyx_PyObject_GetAttrStr(obj, attr_name); + if (unlikely(!result)) { + __Pyx_PyObject_GetAttrStr_ClearAttributeError(); + } + return result; +#endif +} + +/* GetBuiltinName */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name) { + PyObject* result = __Pyx_PyObject_GetAttrStrNoError(__pyx_b, name); + if (unlikely(!result) && !PyErr_Occurred()) { + PyErr_Format(PyExc_NameError, +#if PY_MAJOR_VERSION >= 3 + "name '%U' is not defined", name); +#else + "name '%.200s' is not defined", PyString_AS_STRING(name)); +#endif + } + return result; +} + +/* TupleAndListFromArray */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE void __Pyx_copy_object_array(PyObject *const *CYTHON_RESTRICT src, PyObject** CYTHON_RESTRICT dest, Py_ssize_t length) { + PyObject *v; + Py_ssize_t i; + for (i = 0; i < length; i++) { + v = dest[i] = src[i]; + Py_INCREF(v); + } +} +static CYTHON_INLINE PyObject * +__Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + Py_INCREF(__pyx_empty_tuple); + return __pyx_empty_tuple; + } + res = PyTuple_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyTupleObject*)res)->ob_item, n); + return res; +} +static CYTHON_INLINE PyObject * +__Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + return PyList_New(0); + } + res = PyList_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyListObject*)res)->ob_item, n); + return res; +} +#endif + +/* BytesEquals */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else + if (s1 == s2) { + return (equals == Py_EQ); + } else if (PyBytes_CheckExact(s1) & PyBytes_CheckExact(s2)) { + const char *ps1, *ps2; + Py_ssize_t length = PyBytes_GET_SIZE(s1); + if (length != PyBytes_GET_SIZE(s2)) + return (equals == Py_NE); + ps1 = PyBytes_AS_STRING(s1); + ps2 = PyBytes_AS_STRING(s2); + if (ps1[0] != ps2[0]) { + return (equals == Py_NE); + } else if (length == 1) { + return (equals == Py_EQ); + } else { + int result; +#if CYTHON_USE_UNICODE_INTERNALS && (PY_VERSION_HEX < 0x030B0000) + Py_hash_t hash1, hash2; + hash1 = ((PyBytesObject*)s1)->ob_shash; + hash2 = ((PyBytesObject*)s2)->ob_shash; + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + return (equals == Py_NE); + } +#endif + result = memcmp(ps1, ps2, (size_t)length); + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & PyBytes_CheckExact(s2)) { + return (equals == Py_NE); + } else if ((s2 == Py_None) & PyBytes_CheckExact(s1)) { + return (equals == Py_NE); + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +#endif +} + +/* UnicodeEquals */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else +#if PY_MAJOR_VERSION < 3 + PyObject* owned_ref = NULL; +#endif + int s1_is_unicode, s2_is_unicode; + if (s1 == s2) { + goto return_eq; + } + s1_is_unicode = PyUnicode_CheckExact(s1); + s2_is_unicode = PyUnicode_CheckExact(s2); +#if PY_MAJOR_VERSION < 3 + if ((s1_is_unicode & (!s2_is_unicode)) && PyString_CheckExact(s2)) { + owned_ref = PyUnicode_FromObject(s2); + if (unlikely(!owned_ref)) + return -1; + s2 = owned_ref; + s2_is_unicode = 1; + } else if ((s2_is_unicode & (!s1_is_unicode)) && PyString_CheckExact(s1)) { + owned_ref = PyUnicode_FromObject(s1); + if (unlikely(!owned_ref)) + return -1; + s1 = owned_ref; + s1_is_unicode = 1; + } else if (((!s2_is_unicode) & (!s1_is_unicode))) { + return __Pyx_PyBytes_Equals(s1, s2, equals); + } +#endif + if (s1_is_unicode & s2_is_unicode) { + Py_ssize_t length; + int kind; + void *data1, *data2; + if (unlikely(__Pyx_PyUnicode_READY(s1) < 0) || unlikely(__Pyx_PyUnicode_READY(s2) < 0)) + return -1; + length = __Pyx_PyUnicode_GET_LENGTH(s1); + if (length != __Pyx_PyUnicode_GET_LENGTH(s2)) { + goto return_ne; + } +#if CYTHON_USE_UNICODE_INTERNALS + { + Py_hash_t hash1, hash2; + #if CYTHON_PEP393_ENABLED + hash1 = ((PyASCIIObject*)s1)->hash; + hash2 = ((PyASCIIObject*)s2)->hash; + #else + hash1 = ((PyUnicodeObject*)s1)->hash; + hash2 = ((PyUnicodeObject*)s2)->hash; + #endif + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + goto return_ne; + } + } +#endif + kind = __Pyx_PyUnicode_KIND(s1); + if (kind != __Pyx_PyUnicode_KIND(s2)) { + goto return_ne; + } + data1 = __Pyx_PyUnicode_DATA(s1); + data2 = __Pyx_PyUnicode_DATA(s2); + if (__Pyx_PyUnicode_READ(kind, data1, 0) != __Pyx_PyUnicode_READ(kind, data2, 0)) { + goto return_ne; + } else if (length == 1) { + goto return_eq; + } else { + int result = memcmp(data1, data2, (size_t)(length * kind)); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & s2_is_unicode) { + goto return_ne; + } else if ((s2 == Py_None) & s1_is_unicode) { + goto return_ne; + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +return_eq: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ); +return_ne: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_NE); +#endif +} + +/* fastcall */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s) +{ + Py_ssize_t i, n = PyTuple_GET_SIZE(kwnames); + for (i = 0; i < n; i++) + { + if (s == PyTuple_GET_ITEM(kwnames, i)) return kwvalues[i]; + } + for (i = 0; i < n; i++) + { + int eq = __Pyx_PyUnicode_Equals(s, PyTuple_GET_ITEM(kwnames, i), Py_EQ); + if (unlikely(eq != 0)) { + if (unlikely(eq < 0)) return NULL; + return kwvalues[i]; + } + } + return NULL; +} +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 +CYTHON_UNUSED static PyObject *__Pyx_KwargsAsDict_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues) { + Py_ssize_t i, nkwargs = PyTuple_GET_SIZE(kwnames); + PyObject *dict; + dict = PyDict_New(); + if (unlikely(!dict)) + return NULL; + for (i=0; i= 3 + "%s() got multiple values for keyword argument '%U'", func_name, kw_name); + #else + "%s() got multiple values for keyword argument '%s'", func_name, + PyString_AsString(kw_name)); + #endif +} + +/* ParseKeywords */ +static int __Pyx_ParseOptionalKeywords( + PyObject *kwds, + PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, + PyObject *values[], + Py_ssize_t num_pos_args, + const char* function_name) +{ + PyObject *key = 0, *value = 0; + Py_ssize_t pos = 0; + PyObject*** name; + PyObject*** first_kw_arg = argnames + num_pos_args; + int kwds_is_tuple = CYTHON_METH_FASTCALL && likely(PyTuple_Check(kwds)); + while (1) { + Py_XDECREF(key); key = NULL; + Py_XDECREF(value); value = NULL; + if (kwds_is_tuple) { + Py_ssize_t size; +#if CYTHON_ASSUME_SAFE_MACROS + size = PyTuple_GET_SIZE(kwds); +#else + size = PyTuple_Size(kwds); + if (size < 0) goto bad; +#endif + if (pos >= size) break; +#if CYTHON_AVOID_BORROWED_REFS + key = __Pyx_PySequence_ITEM(kwds, pos); + if (!key) goto bad; +#elif CYTHON_ASSUME_SAFE_MACROS + key = PyTuple_GET_ITEM(kwds, pos); +#else + key = PyTuple_GetItem(kwds, pos); + if (!key) goto bad; +#endif + value = kwvalues[pos]; + pos++; + } + else + { + if (!PyDict_Next(kwds, &pos, &key, &value)) break; +#if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(key); +#endif + } + name = first_kw_arg; + while (*name && (**name != key)) name++; + if (*name) { + values[name-argnames] = value; +#if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(value); + Py_DECREF(key); +#endif + key = NULL; + value = NULL; + continue; + } +#if !CYTHON_AVOID_BORROWED_REFS + Py_INCREF(key); +#endif + Py_INCREF(value); + name = first_kw_arg; + #if PY_MAJOR_VERSION < 3 + if (likely(PyString_Check(key))) { + while (*name) { + if ((CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**name) == PyString_GET_SIZE(key)) + && _PyString_Eq(**name, key)) { + values[name-argnames] = value; +#if CYTHON_AVOID_BORROWED_REFS + value = NULL; +#endif + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + if ((**argname == key) || ( + (CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**argname) == PyString_GET_SIZE(key)) + && _PyString_Eq(**argname, key))) { + goto arg_passed_twice; + } + argname++; + } + } + } else + #endif + if (likely(PyUnicode_Check(key))) { + while (*name) { + int cmp = ( + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**name) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**name, key) + ); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) { + values[name-argnames] = value; +#if CYTHON_AVOID_BORROWED_REFS + value = NULL; +#endif + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + int cmp = (**argname == key) ? 0 : + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**argname) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**argname, key); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) goto arg_passed_twice; + argname++; + } + } + } else + goto invalid_keyword_type; + if (kwds2) { + if (unlikely(PyDict_SetItem(kwds2, key, value))) goto bad; + } else { + goto invalid_keyword; + } + } + Py_XDECREF(key); + Py_XDECREF(value); + return 0; +arg_passed_twice: + __Pyx_RaiseDoubleKeywordsError(function_name, key); + goto bad; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + goto bad; +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif +bad: + Py_XDECREF(key); + Py_XDECREF(value); + return -1; +} + +/* ArgTypeTest */ +static int __Pyx__ArgTypeTest(PyObject *obj, PyTypeObject *type, const char *name, int exact) +{ + __Pyx_TypeName type_name; + __Pyx_TypeName obj_type_name; + if (unlikely(!type)) { + PyErr_SetString(PyExc_SystemError, "Missing type object"); + return 0; + } + else if (exact) { + #if PY_MAJOR_VERSION == 2 + if ((type == &PyBaseString_Type) && likely(__Pyx_PyBaseString_CheckExact(obj))) return 1; + #endif + } + else { + if (likely(__Pyx_TypeCheck(obj, type))) return 1; + } + type_name = __Pyx_PyType_GetName(type); + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "Argument '%.200s' has incorrect type (expected " __Pyx_FMT_TYPENAME + ", got " __Pyx_FMT_TYPENAME ")", name, type_name, obj_type_name); + __Pyx_DECREF_TypeName(type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return 0; +} + +/* RaiseException */ +#if PY_MAJOR_VERSION < 3 +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + __Pyx_PyThreadState_declare + CYTHON_UNUSED_VAR(cause); + Py_XINCREF(type); + if (!value || value == Py_None) + value = NULL; + else + Py_INCREF(value); + if (!tb || tb == Py_None) + tb = NULL; + else { + Py_INCREF(tb); + if (!PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto raise_error; + } + } + if (PyType_Check(type)) { +#if CYTHON_COMPILING_IN_PYPY + if (!value) { + Py_INCREF(Py_None); + value = Py_None; + } +#endif + PyErr_NormalizeException(&type, &value, &tb); + } else { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto raise_error; + } + value = type; + type = (PyObject*) Py_TYPE(type); + Py_INCREF(type); + if (!PyType_IsSubtype((PyTypeObject *)type, (PyTypeObject *)PyExc_BaseException)) { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto raise_error; + } + } + __Pyx_PyThreadState_assign + __Pyx_ErrRestore(type, value, tb); + return; +raise_error: + Py_XDECREF(value); + Py_XDECREF(type); + Py_XDECREF(tb); + return; +} +#else +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + PyObject* owned_instance = NULL; + if (tb == Py_None) { + tb = 0; + } else if (tb && !PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto bad; + } + if (value == Py_None) + value = 0; + if (PyExceptionInstance_Check(type)) { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto bad; + } + value = type; + type = (PyObject*) Py_TYPE(value); + } else if (PyExceptionClass_Check(type)) { + PyObject *instance_class = NULL; + if (value && PyExceptionInstance_Check(value)) { + instance_class = (PyObject*) Py_TYPE(value); + if (instance_class != type) { + int is_subclass = PyObject_IsSubclass(instance_class, type); + if (!is_subclass) { + instance_class = NULL; + } else if (unlikely(is_subclass == -1)) { + goto bad; + } else { + type = instance_class; + } + } + } + if (!instance_class) { + PyObject *args; + if (!value) + args = PyTuple_New(0); + else if (PyTuple_Check(value)) { + Py_INCREF(value); + args = value; + } else + args = PyTuple_Pack(1, value); + if (!args) + goto bad; + owned_instance = PyObject_Call(type, args, NULL); + Py_DECREF(args); + if (!owned_instance) + goto bad; + value = owned_instance; + if (!PyExceptionInstance_Check(value)) { + PyErr_Format(PyExc_TypeError, + "calling %R should have returned an instance of " + "BaseException, not %R", + type, Py_TYPE(value)); + goto bad; + } + } + } else { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto bad; + } + if (cause) { + PyObject *fixed_cause; + if (cause == Py_None) { + fixed_cause = NULL; + } else if (PyExceptionClass_Check(cause)) { + fixed_cause = PyObject_CallObject(cause, NULL); + if (fixed_cause == NULL) + goto bad; + } else if (PyExceptionInstance_Check(cause)) { + fixed_cause = cause; + Py_INCREF(fixed_cause); + } else { + PyErr_SetString(PyExc_TypeError, + "exception causes must derive from " + "BaseException"); + goto bad; + } + PyException_SetCause(value, fixed_cause); + } + PyErr_SetObject(type, value); + if (tb) { + #if PY_VERSION_HEX >= 0x030C00A6 + PyException_SetTraceback(value, tb); + #elif CYTHON_FAST_THREAD_STATE + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject* tmp_tb = tstate->curexc_traceback; + if (tb != tmp_tb) { + Py_INCREF(tb); + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_tb); + } +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + PyErr_Fetch(&tmp_type, &tmp_value, &tmp_tb); + Py_INCREF(tb); + PyErr_Restore(tmp_type, tmp_value, tb); + Py_XDECREF(tmp_tb); +#endif + } +bad: + Py_XDECREF(owned_instance); + return; +} +#endif + +/* PyFunctionFastCall */ +#if CYTHON_FAST_PYCALL && !CYTHON_VECTORCALL +static PyObject* __Pyx_PyFunction_FastCallNoKw(PyCodeObject *co, PyObject **args, Py_ssize_t na, + PyObject *globals) { + PyFrameObject *f; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject **fastlocals; + Py_ssize_t i; + PyObject *result; + assert(globals != NULL); + /* XXX Perhaps we should create a specialized + PyFrame_New() that doesn't take locals, but does + take builtins without sanity checking them. + */ + assert(tstate != NULL); + f = PyFrame_New(tstate, co, globals, NULL); + if (f == NULL) { + return NULL; + } + fastlocals = __Pyx_PyFrame_GetLocalsplus(f); + for (i = 0; i < na; i++) { + Py_INCREF(*args); + fastlocals[i] = *args++; + } + result = PyEval_EvalFrameEx(f,0); + ++tstate->recursion_depth; + Py_DECREF(f); + --tstate->recursion_depth; + return result; +} +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs) { + PyCodeObject *co = (PyCodeObject *)PyFunction_GET_CODE(func); + PyObject *globals = PyFunction_GET_GLOBALS(func); + PyObject *argdefs = PyFunction_GET_DEFAULTS(func); + PyObject *closure; +#if PY_MAJOR_VERSION >= 3 + PyObject *kwdefs; +#endif + PyObject *kwtuple, **k; + PyObject **d; + Py_ssize_t nd; + Py_ssize_t nk; + PyObject *result; + assert(kwargs == NULL || PyDict_Check(kwargs)); + nk = kwargs ? PyDict_Size(kwargs) : 0; + #if PY_MAJOR_VERSION < 3 + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) { + return NULL; + } + #else + if (unlikely(Py_EnterRecursiveCall(" while calling a Python object"))) { + return NULL; + } + #endif + if ( +#if PY_MAJOR_VERSION >= 3 + co->co_kwonlyargcount == 0 && +#endif + likely(kwargs == NULL || nk == 0) && + co->co_flags == (CO_OPTIMIZED | CO_NEWLOCALS | CO_NOFREE)) { + if (argdefs == NULL && co->co_argcount == nargs) { + result = __Pyx_PyFunction_FastCallNoKw(co, args, nargs, globals); + goto done; + } + else if (nargs == 0 && argdefs != NULL + && co->co_argcount == Py_SIZE(argdefs)) { + /* function called with no arguments, but all parameters have + a default value: use default values as arguments .*/ + args = &PyTuple_GET_ITEM(argdefs, 0); + result =__Pyx_PyFunction_FastCallNoKw(co, args, Py_SIZE(argdefs), globals); + goto done; + } + } + if (kwargs != NULL) { + Py_ssize_t pos, i; + kwtuple = PyTuple_New(2 * nk); + if (kwtuple == NULL) { + result = NULL; + goto done; + } + k = &PyTuple_GET_ITEM(kwtuple, 0); + pos = i = 0; + while (PyDict_Next(kwargs, &pos, &k[i], &k[i+1])) { + Py_INCREF(k[i]); + Py_INCREF(k[i+1]); + i += 2; + } + nk = i / 2; + } + else { + kwtuple = NULL; + k = NULL; + } + closure = PyFunction_GET_CLOSURE(func); +#if PY_MAJOR_VERSION >= 3 + kwdefs = PyFunction_GET_KW_DEFAULTS(func); +#endif + if (argdefs != NULL) { + d = &PyTuple_GET_ITEM(argdefs, 0); + nd = Py_SIZE(argdefs); + } + else { + d = NULL; + nd = 0; + } +#if PY_MAJOR_VERSION >= 3 + result = PyEval_EvalCodeEx((PyObject*)co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, kwdefs, closure); +#else + result = PyEval_EvalCodeEx(co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, closure); +#endif + Py_XDECREF(kwtuple); +done: + Py_LeaveRecursiveCall(); + return result; +} +#endif + +/* PyObjectCall */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw) { + PyObject *result; + ternaryfunc call = Py_TYPE(func)->tp_call; + if (unlikely(!call)) + return PyObject_Call(func, arg, kw); + #if PY_MAJOR_VERSION < 3 + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + #else + if (unlikely(Py_EnterRecursiveCall(" while calling a Python object"))) + return NULL; + #endif + result = (*call)(func, arg, kw); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* PyObjectCallMethO */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg) { + PyObject *self, *result; + PyCFunction cfunc; + cfunc = __Pyx_CyOrPyCFunction_GET_FUNCTION(func); + self = __Pyx_CyOrPyCFunction_GET_SELF(func); + #if PY_MAJOR_VERSION < 3 + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + #else + if (unlikely(Py_EnterRecursiveCall(" while calling a Python object"))) + return NULL; + #endif + result = cfunc(self, arg); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* PyObjectFastCall */ +#if PY_VERSION_HEX < 0x03090000 || CYTHON_COMPILING_IN_LIMITED_API +static PyObject* __Pyx_PyObject_FastCall_fallback(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs) { + PyObject *argstuple; + PyObject *result = 0; + size_t i; + argstuple = PyTuple_New((Py_ssize_t)nargs); + if (unlikely(!argstuple)) return NULL; + for (i = 0; i < nargs; i++) { + Py_INCREF(args[i]); + if (__Pyx_PyTuple_SET_ITEM(argstuple, (Py_ssize_t)i, args[i]) < 0) goto bad; + } + result = __Pyx_PyObject_Call(func, argstuple, kwargs); + bad: + Py_DECREF(argstuple); + return result; +} +#endif +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t _nargs, PyObject *kwargs) { + Py_ssize_t nargs = __Pyx_PyVectorcall_NARGS(_nargs); +#if CYTHON_COMPILING_IN_CPYTHON + if (nargs == 0 && kwargs == NULL) { + if (__Pyx_CyOrPyCFunction_Check(func) && likely( __Pyx_CyOrPyCFunction_GET_FLAGS(func) & METH_NOARGS)) + return __Pyx_PyObject_CallMethO(func, NULL); + } + else if (nargs == 1 && kwargs == NULL) { + if (__Pyx_CyOrPyCFunction_Check(func) && likely( __Pyx_CyOrPyCFunction_GET_FLAGS(func) & METH_O)) + return __Pyx_PyObject_CallMethO(func, args[0]); + } +#endif + #if PY_VERSION_HEX < 0x030800B1 + #if CYTHON_FAST_PYCCALL + if (PyCFunction_Check(func)) { + if (kwargs) { + return _PyCFunction_FastCallDict(func, args, nargs, kwargs); + } else { + return _PyCFunction_FastCallKeywords(func, args, nargs, NULL); + } + } + #if PY_VERSION_HEX >= 0x030700A1 + if (!kwargs && __Pyx_IS_TYPE(func, &PyMethodDescr_Type)) { + return _PyMethodDescr_FastCallKeywords(func, args, nargs, NULL); + } + #endif + #endif + #if CYTHON_FAST_PYCALL + if (PyFunction_Check(func)) { + return __Pyx_PyFunction_FastCallDict(func, args, nargs, kwargs); + } + #endif + #endif + if (kwargs == NULL) { + #if CYTHON_VECTORCALL + #if PY_VERSION_HEX < 0x03090000 + vectorcallfunc f = _PyVectorcall_Function(func); + #else + vectorcallfunc f = PyVectorcall_Function(func); + #endif + if (f) { + return f(func, args, (size_t)nargs, NULL); + } + #elif defined(__Pyx_CyFunction_USED) && CYTHON_BACKPORT_VECTORCALL + if (__Pyx_CyFunction_CheckExact(func)) { + __pyx_vectorcallfunc f = __Pyx_CyFunction_func_vectorcall(func); + if (f) return f(func, args, (size_t)nargs, NULL); + } + #endif + } + if (nargs == 0) { + return __Pyx_PyObject_Call(func, __pyx_empty_tuple, kwargs); + } + #if PY_VERSION_HEX >= 0x03090000 && !CYTHON_COMPILING_IN_LIMITED_API + return PyObject_VectorcallDict(func, args, (size_t)nargs, kwargs); + #else + return __Pyx_PyObject_FastCall_fallback(func, args, (size_t)nargs, kwargs); + #endif +} + +/* RaiseUnexpectedTypeError */ +static int +__Pyx_RaiseUnexpectedTypeError(const char *expected, PyObject *obj) +{ + __Pyx_TypeName obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, "Expected %s, got " __Pyx_FMT_TYPENAME, + expected, obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return 0; +} + +/* CIntToDigits */ +static const char DIGIT_PAIRS_10[2*10*10+1] = { + "00010203040506070809" + "10111213141516171819" + "20212223242526272829" + "30313233343536373839" + "40414243444546474849" + "50515253545556575859" + "60616263646566676869" + "70717273747576777879" + "80818283848586878889" + "90919293949596979899" +}; +static const char DIGIT_PAIRS_8[2*8*8+1] = { + "0001020304050607" + "1011121314151617" + "2021222324252627" + "3031323334353637" + "4041424344454647" + "5051525354555657" + "6061626364656667" + "7071727374757677" +}; +static const char DIGITS_HEX[2*16+1] = { + "0123456789abcdef" + "0123456789ABCDEF" +}; + +/* BuildPyUnicode */ +static PyObject* __Pyx_PyUnicode_BuildFromAscii(Py_ssize_t ulength, char* chars, int clength, + int prepend_sign, char padding_char) { + PyObject *uval; + Py_ssize_t uoffset = ulength - clength; +#if CYTHON_USE_UNICODE_INTERNALS + Py_ssize_t i; +#if CYTHON_PEP393_ENABLED + void *udata; + uval = PyUnicode_New(ulength, 127); + if (unlikely(!uval)) return NULL; + udata = PyUnicode_DATA(uval); +#else + Py_UNICODE *udata; + uval = PyUnicode_FromUnicode(NULL, ulength); + if (unlikely(!uval)) return NULL; + udata = PyUnicode_AS_UNICODE(uval); +#endif + if (uoffset > 0) { + i = 0; + if (prepend_sign) { + __Pyx_PyUnicode_WRITE(PyUnicode_1BYTE_KIND, udata, 0, '-'); + i++; + } + for (; i < uoffset; i++) { + __Pyx_PyUnicode_WRITE(PyUnicode_1BYTE_KIND, udata, i, padding_char); + } + } + for (i=0; i < clength; i++) { + __Pyx_PyUnicode_WRITE(PyUnicode_1BYTE_KIND, udata, uoffset+i, chars[i]); + } +#else + { + PyObject *sign = NULL, *padding = NULL; + uval = NULL; + if (uoffset > 0) { + prepend_sign = !!prepend_sign; + if (uoffset > prepend_sign) { + padding = PyUnicode_FromOrdinal(padding_char); + if (likely(padding) && uoffset > prepend_sign + 1) { + PyObject *tmp; + PyObject *repeat = PyInt_FromSsize_t(uoffset - prepend_sign); + if (unlikely(!repeat)) goto done_or_error; + tmp = PyNumber_Multiply(padding, repeat); + Py_DECREF(repeat); + Py_DECREF(padding); + padding = tmp; + } + if (unlikely(!padding)) goto done_or_error; + } + if (prepend_sign) { + sign = PyUnicode_FromOrdinal('-'); + if (unlikely(!sign)) goto done_or_error; + } + } + uval = PyUnicode_DecodeASCII(chars, clength, NULL); + if (likely(uval) && padding) { + PyObject *tmp = PyNumber_Add(padding, uval); + Py_DECREF(uval); + uval = tmp; + } + if (likely(uval) && sign) { + PyObject *tmp = PyNumber_Add(sign, uval); + Py_DECREF(uval); + uval = tmp; + } +done_or_error: + Py_XDECREF(padding); + Py_XDECREF(sign); + } +#endif + return uval; +} + +/* CIntToPyUnicode */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_int(int value, Py_ssize_t width, char padding_char, char format_char) { + char digits[sizeof(int)*3+2]; + char *dpos, *end = digits + sizeof(int)*3+2; + const char *hex_digits = DIGITS_HEX; + Py_ssize_t length, ulength; + int prepend_sign, last_one_off; + int remaining; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (format_char == 'X') { + hex_digits += 16; + format_char = 'x'; + } + remaining = value; + last_one_off = 0; + dpos = end; + do { + int digit_pos; + switch (format_char) { + case 'o': + digit_pos = abs((int)(remaining % (8*8))); + remaining = (int) (remaining / (8*8)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_8 + digit_pos * 2, 2); + last_one_off = (digit_pos < 8); + break; + case 'd': + digit_pos = abs((int)(remaining % (10*10))); + remaining = (int) (remaining / (10*10)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_10 + digit_pos * 2, 2); + last_one_off = (digit_pos < 10); + break; + case 'x': + *(--dpos) = hex_digits[abs((int)(remaining % 16))]; + remaining = (int) (remaining / 16); + break; + default: + assert(0); + break; + } + } while (unlikely(remaining != 0)); + assert(!last_one_off || *dpos == '0'); + dpos += last_one_off; + length = end - dpos; + ulength = length; + prepend_sign = 0; + if (!is_unsigned && value <= neg_one) { + if (padding_char == ' ' || width <= length + 1) { + *(--dpos) = '-'; + ++length; + } else { + prepend_sign = 1; + } + ++ulength; + } + if (width > ulength) { + ulength = width; + } + if (ulength == 1) { + return PyUnicode_FromOrdinal(*dpos); + } + return __Pyx_PyUnicode_BuildFromAscii(ulength, dpos, (int) length, prepend_sign, padding_char); +} + +/* CIntToPyUnicode */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_Py_ssize_t(Py_ssize_t value, Py_ssize_t width, char padding_char, char format_char) { + char digits[sizeof(Py_ssize_t)*3+2]; + char *dpos, *end = digits + sizeof(Py_ssize_t)*3+2; + const char *hex_digits = DIGITS_HEX; + Py_ssize_t length, ulength; + int prepend_sign, last_one_off; + Py_ssize_t remaining; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const Py_ssize_t neg_one = (Py_ssize_t) -1, const_zero = (Py_ssize_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (format_char == 'X') { + hex_digits += 16; + format_char = 'x'; + } + remaining = value; + last_one_off = 0; + dpos = end; + do { + int digit_pos; + switch (format_char) { + case 'o': + digit_pos = abs((int)(remaining % (8*8))); + remaining = (Py_ssize_t) (remaining / (8*8)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_8 + digit_pos * 2, 2); + last_one_off = (digit_pos < 8); + break; + case 'd': + digit_pos = abs((int)(remaining % (10*10))); + remaining = (Py_ssize_t) (remaining / (10*10)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_10 + digit_pos * 2, 2); + last_one_off = (digit_pos < 10); + break; + case 'x': + *(--dpos) = hex_digits[abs((int)(remaining % 16))]; + remaining = (Py_ssize_t) (remaining / 16); + break; + default: + assert(0); + break; + } + } while (unlikely(remaining != 0)); + assert(!last_one_off || *dpos == '0'); + dpos += last_one_off; + length = end - dpos; + ulength = length; + prepend_sign = 0; + if (!is_unsigned && value <= neg_one) { + if (padding_char == ' ' || width <= length + 1) { + *(--dpos) = '-'; + ++length; + } else { + prepend_sign = 1; + } + ++ulength; + } + if (width > ulength) { + ulength = width; + } + if (ulength == 1) { + return PyUnicode_FromOrdinal(*dpos); + } + return __Pyx_PyUnicode_BuildFromAscii(ulength, dpos, (int) length, prepend_sign, padding_char); +} + +/* JoinPyUnicode */ +static PyObject* __Pyx_PyUnicode_Join(PyObject* value_tuple, Py_ssize_t value_count, Py_ssize_t result_ulength, + Py_UCS4 max_char) { +#if CYTHON_USE_UNICODE_INTERNALS && CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + PyObject *result_uval; + int result_ukind, kind_shift; + Py_ssize_t i, char_pos; + void *result_udata; + CYTHON_MAYBE_UNUSED_VAR(max_char); +#if CYTHON_PEP393_ENABLED + result_uval = PyUnicode_New(result_ulength, max_char); + if (unlikely(!result_uval)) return NULL; + result_ukind = (max_char <= 255) ? PyUnicode_1BYTE_KIND : (max_char <= 65535) ? PyUnicode_2BYTE_KIND : PyUnicode_4BYTE_KIND; + kind_shift = (result_ukind == PyUnicode_4BYTE_KIND) ? 2 : result_ukind - 1; + result_udata = PyUnicode_DATA(result_uval); +#else + result_uval = PyUnicode_FromUnicode(NULL, result_ulength); + if (unlikely(!result_uval)) return NULL; + result_ukind = sizeof(Py_UNICODE); + kind_shift = (result_ukind == 4) ? 2 : result_ukind - 1; + result_udata = PyUnicode_AS_UNICODE(result_uval); +#endif + assert(kind_shift == 2 || kind_shift == 1 || kind_shift == 0); + char_pos = 0; + for (i=0; i < value_count; i++) { + int ukind; + Py_ssize_t ulength; + void *udata; + PyObject *uval = PyTuple_GET_ITEM(value_tuple, i); + if (unlikely(__Pyx_PyUnicode_READY(uval))) + goto bad; + ulength = __Pyx_PyUnicode_GET_LENGTH(uval); + if (unlikely(!ulength)) + continue; + if (unlikely((PY_SSIZE_T_MAX >> kind_shift) - ulength < char_pos)) + goto overflow; + ukind = __Pyx_PyUnicode_KIND(uval); + udata = __Pyx_PyUnicode_DATA(uval); + if (!CYTHON_PEP393_ENABLED || ukind == result_ukind) { + memcpy((char *)result_udata + (char_pos << kind_shift), udata, (size_t) (ulength << kind_shift)); + } else { + #if PY_VERSION_HEX >= 0x030d0000 + if (unlikely(PyUnicode_CopyCharacters(result_uval, char_pos, uval, 0, ulength) < 0)) goto bad; + #elif CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030300F0 || defined(_PyUnicode_FastCopyCharacters) + _PyUnicode_FastCopyCharacters(result_uval, char_pos, uval, 0, ulength); + #else + Py_ssize_t j; + for (j=0; j < ulength; j++) { + Py_UCS4 uchar = __Pyx_PyUnicode_READ(ukind, udata, j); + __Pyx_PyUnicode_WRITE(result_ukind, result_udata, char_pos+j, uchar); + } + #endif + } + char_pos += ulength; + } + return result_uval; +overflow: + PyErr_SetString(PyExc_OverflowError, "join() result is too long for a Python string"); +bad: + Py_DECREF(result_uval); + return NULL; +#else + CYTHON_UNUSED_VAR(max_char); + CYTHON_UNUSED_VAR(result_ulength); + CYTHON_UNUSED_VAR(value_count); + return PyUnicode_Join(__pyx_empty_unicode, value_tuple); +#endif +} + +/* GetAttr */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr(PyObject *o, PyObject *n) { +#if CYTHON_USE_TYPE_SLOTS +#if PY_MAJOR_VERSION >= 3 + if (likely(PyUnicode_Check(n))) +#else + if (likely(PyString_Check(n))) +#endif + return __Pyx_PyObject_GetAttrStr(o, n); +#endif + return PyObject_GetAttr(o, n); +} + +/* GetItemInt */ +static PyObject *__Pyx_GetItemInt_Generic(PyObject *o, PyObject* j) { + PyObject *r; + if (unlikely(!j)) return NULL; + r = PyObject_GetItem(o, j); + Py_DECREF(j); + return r; +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_List_Fast(PyObject *o, Py_ssize_t i, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + Py_ssize_t wrapped_i = i; + if (wraparound & unlikely(i < 0)) { + wrapped_i += PyList_GET_SIZE(o); + } + if ((!boundscheck) || likely(__Pyx_is_valid_index(wrapped_i, PyList_GET_SIZE(o)))) { + PyObject *r = PyList_GET_ITEM(o, wrapped_i); + Py_INCREF(r); + return r; + } + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +#else + return PySequence_GetItem(o, i); +#endif +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Tuple_Fast(PyObject *o, Py_ssize_t i, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + Py_ssize_t wrapped_i = i; + if (wraparound & unlikely(i < 0)) { + wrapped_i += PyTuple_GET_SIZE(o); + } + if ((!boundscheck) || likely(__Pyx_is_valid_index(wrapped_i, PyTuple_GET_SIZE(o)))) { + PyObject *r = PyTuple_GET_ITEM(o, wrapped_i); + Py_INCREF(r); + return r; + } + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +#else + return PySequence_GetItem(o, i); +#endif +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Fast(PyObject *o, Py_ssize_t i, int is_list, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS && CYTHON_USE_TYPE_SLOTS + if (is_list || PyList_CheckExact(o)) { + Py_ssize_t n = ((!wraparound) | likely(i >= 0)) ? i : i + PyList_GET_SIZE(o); + if ((!boundscheck) || (likely(__Pyx_is_valid_index(n, PyList_GET_SIZE(o))))) { + PyObject *r = PyList_GET_ITEM(o, n); + Py_INCREF(r); + return r; + } + } + else if (PyTuple_CheckExact(o)) { + Py_ssize_t n = ((!wraparound) | likely(i >= 0)) ? i : i + PyTuple_GET_SIZE(o); + if ((!boundscheck) || likely(__Pyx_is_valid_index(n, PyTuple_GET_SIZE(o)))) { + PyObject *r = PyTuple_GET_ITEM(o, n); + Py_INCREF(r); + return r; + } + } else { + PyMappingMethods *mm = Py_TYPE(o)->tp_as_mapping; + PySequenceMethods *sm = Py_TYPE(o)->tp_as_sequence; + if (mm && mm->mp_subscript) { + PyObject *r, *key = PyInt_FromSsize_t(i); + if (unlikely(!key)) return NULL; + r = mm->mp_subscript(o, key); + Py_DECREF(key); + return r; + } + if (likely(sm && sm->sq_item)) { + if (wraparound && unlikely(i < 0) && likely(sm->sq_length)) { + Py_ssize_t l = sm->sq_length(o); + if (likely(l >= 0)) { + i += l; + } else { + if (!PyErr_ExceptionMatches(PyExc_OverflowError)) + return NULL; + PyErr_Clear(); + } + } + return sm->sq_item(o, i); + } + } +#else + if (is_list || !PyMapping_Check(o)) { + return PySequence_GetItem(o, i); + } +#endif + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +} + +/* PyObjectCallOneArg */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg) { + PyObject *args[2] = {NULL, arg}; + return __Pyx_PyObject_FastCall(func, args+1, 1 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* ObjectGetItem */ +#if CYTHON_USE_TYPE_SLOTS +static PyObject *__Pyx_PyObject_GetIndex(PyObject *obj, PyObject *index) { + PyObject *runerr = NULL; + Py_ssize_t key_value; + key_value = __Pyx_PyIndex_AsSsize_t(index); + if (likely(key_value != -1 || !(runerr = PyErr_Occurred()))) { + return __Pyx_GetItemInt_Fast(obj, key_value, 0, 1, 1); + } + if (PyErr_GivenExceptionMatches(runerr, PyExc_OverflowError)) { + __Pyx_TypeName index_type_name = __Pyx_PyType_GetName(Py_TYPE(index)); + PyErr_Clear(); + PyErr_Format(PyExc_IndexError, + "cannot fit '" __Pyx_FMT_TYPENAME "' into an index-sized integer", index_type_name); + __Pyx_DECREF_TypeName(index_type_name); + } + return NULL; +} +static PyObject *__Pyx_PyObject_GetItem_Slow(PyObject *obj, PyObject *key) { + __Pyx_TypeName obj_type_name; + if (likely(PyType_Check(obj))) { + PyObject *meth = __Pyx_PyObject_GetAttrStrNoError(obj, __pyx_n_s_class_getitem); + if (!meth) { + PyErr_Clear(); + } else { + PyObject *result = __Pyx_PyObject_CallOneArg(meth, key); + Py_DECREF(meth); + return result; + } + } + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "'" __Pyx_FMT_TYPENAME "' object is not subscriptable", obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return NULL; +} +static PyObject *__Pyx_PyObject_GetItem(PyObject *obj, PyObject *key) { + PyTypeObject *tp = Py_TYPE(obj); + PyMappingMethods *mm = tp->tp_as_mapping; + PySequenceMethods *sm = tp->tp_as_sequence; + if (likely(mm && mm->mp_subscript)) { + return mm->mp_subscript(obj, key); + } + if (likely(sm && sm->sq_item)) { + return __Pyx_PyObject_GetIndex(obj, key); + } + return __Pyx_PyObject_GetItem_Slow(obj, key); +} +#endif + +/* KeywordStringCheck */ +static int __Pyx_CheckKeywordStrings( + PyObject *kw, + const char* function_name, + int kw_allowed) +{ + PyObject* key = 0; + Py_ssize_t pos = 0; +#if CYTHON_COMPILING_IN_PYPY + if (!kw_allowed && PyDict_Next(kw, &pos, &key, 0)) + goto invalid_keyword; + return 1; +#else + if (CYTHON_METH_FASTCALL && likely(PyTuple_Check(kw))) { + Py_ssize_t kwsize; +#if CYTHON_ASSUME_SAFE_MACROS + kwsize = PyTuple_GET_SIZE(kw); +#else + kwsize = PyTuple_Size(kw); + if (kwsize < 0) return 0; +#endif + if (unlikely(kwsize == 0)) + return 1; + if (!kw_allowed) { +#if CYTHON_ASSUME_SAFE_MACROS + key = PyTuple_GET_ITEM(kw, 0); +#else + key = PyTuple_GetItem(kw, pos); + if (!key) return 0; +#endif + goto invalid_keyword; + } +#if PY_VERSION_HEX < 0x03090000 + for (pos = 0; pos < kwsize; pos++) { +#if CYTHON_ASSUME_SAFE_MACROS + key = PyTuple_GET_ITEM(kw, pos); +#else + key = PyTuple_GetItem(kw, pos); + if (!key) return 0; +#endif + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } +#endif + return 1; + } + while (PyDict_Next(kw, &pos, &key, 0)) { + #if PY_MAJOR_VERSION < 3 + if (unlikely(!PyString_Check(key))) + #endif + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } + if (!kw_allowed && unlikely(key)) + goto invalid_keyword; + return 1; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + return 0; +#endif +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif + return 0; +} + +/* DivInt[Py_ssize_t] */ +static CYTHON_INLINE Py_ssize_t __Pyx_div_Py_ssize_t(Py_ssize_t a, Py_ssize_t b) { + Py_ssize_t q = a / b; + Py_ssize_t r = a - q*b; + q -= ((r != 0) & ((r ^ b) < 0)); + return q; +} + +/* GetAttr3 */ +#if __PYX_LIMITED_VERSION_HEX < 0x030d00A1 +static PyObject *__Pyx_GetAttr3Default(PyObject *d) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + if (unlikely(!__Pyx_PyErr_ExceptionMatches(PyExc_AttributeError))) + return NULL; + __Pyx_PyErr_Clear(); + Py_INCREF(d); + return d; +} +#endif +static CYTHON_INLINE PyObject *__Pyx_GetAttr3(PyObject *o, PyObject *n, PyObject *d) { + PyObject *r; +#if __PYX_LIMITED_VERSION_HEX >= 0x030d00A1 + int res = PyObject_GetOptionalAttr(o, n, &r); + return (res != 0) ? r : __Pyx_NewRef(d); +#else + #if CYTHON_USE_TYPE_SLOTS + if (likely(PyString_Check(n))) { + r = __Pyx_PyObject_GetAttrStrNoError(o, n); + if (unlikely(!r) && likely(!PyErr_Occurred())) { + r = __Pyx_NewRef(d); + } + return r; + } + #endif + r = PyObject_GetAttr(o, n); + return (likely(r)) ? r : __Pyx_GetAttr3Default(d); +#endif +} + +/* PyDictVersioning */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + return likely(dict) ? __PYX_GET_DICT_VERSION(dict) : 0; +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj) { + PyObject **dictptr = NULL; + Py_ssize_t offset = Py_TYPE(obj)->tp_dictoffset; + if (offset) { +#if CYTHON_COMPILING_IN_CPYTHON + dictptr = (likely(offset > 0)) ? (PyObject **) ((char *)obj + offset) : _PyObject_GetDictPtr(obj); +#else + dictptr = _PyObject_GetDictPtr(obj); +#endif + } + return (dictptr && *dictptr) ? __PYX_GET_DICT_VERSION(*dictptr) : 0; +} +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + if (unlikely(!dict) || unlikely(tp_dict_version != __PYX_GET_DICT_VERSION(dict))) + return 0; + return obj_dict_version == __Pyx_get_object_dict_version(obj); +} +#endif + +/* GetModuleGlobalName */ +#if CYTHON_USE_DICT_VERSIONS +static PyObject *__Pyx__GetModuleGlobalName(PyObject *name, PY_UINT64_T *dict_version, PyObject **dict_cached_value) +#else +static CYTHON_INLINE PyObject *__Pyx__GetModuleGlobalName(PyObject *name) +#endif +{ + PyObject *result; +#if !CYTHON_AVOID_BORROWED_REFS +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030500A1 && PY_VERSION_HEX < 0x030d0000 + result = _PyDict_GetItem_KnownHash(__pyx_d, name, ((PyASCIIObject *) name)->hash); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } else if (unlikely(PyErr_Occurred())) { + return NULL; + } +#elif CYTHON_COMPILING_IN_LIMITED_API + if (unlikely(!__pyx_m)) { + return NULL; + } + result = PyObject_GetAttr(__pyx_m, name); + if (likely(result)) { + return result; + } +#else + result = PyDict_GetItem(__pyx_d, name); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } +#endif +#else + result = PyObject_GetItem(__pyx_d, name); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } + PyErr_Clear(); +#endif + return __Pyx_GetBuiltinName(name); +} + +/* RaiseTooManyValuesToUnpack */ +static CYTHON_INLINE void __Pyx_RaiseTooManyValuesError(Py_ssize_t expected) { + PyErr_Format(PyExc_ValueError, + "too many values to unpack (expected %" CYTHON_FORMAT_SSIZE_T "d)", expected); +} + +/* RaiseNeedMoreValuesToUnpack */ +static CYTHON_INLINE void __Pyx_RaiseNeedMoreValuesError(Py_ssize_t index) { + PyErr_Format(PyExc_ValueError, + "need more than %" CYTHON_FORMAT_SSIZE_T "d value%.1s to unpack", + index, (index == 1) ? "" : "s"); +} + +/* RaiseNoneIterError */ +static CYTHON_INLINE void __Pyx_RaiseNoneNotIterableError(void) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not iterable"); +} + +/* ExtTypeTest */ +static CYTHON_INLINE int __Pyx_TypeTest(PyObject *obj, PyTypeObject *type) { + __Pyx_TypeName obj_type_name; + __Pyx_TypeName type_name; + if (unlikely(!type)) { + PyErr_SetString(PyExc_SystemError, "Missing type object"); + return 0; + } + if (likely(__Pyx_TypeCheck(obj, type))) + return 1; + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + type_name = __Pyx_PyType_GetName(type); + PyErr_Format(PyExc_TypeError, + "Cannot convert " __Pyx_FMT_TYPENAME " to " __Pyx_FMT_TYPENAME, + obj_type_name, type_name); + __Pyx_DECREF_TypeName(obj_type_name); + __Pyx_DECREF_TypeName(type_name); + return 0; +} + +/* GetTopmostException */ +#if CYTHON_USE_EXC_INFO_STACK && CYTHON_FAST_THREAD_STATE +static _PyErr_StackItem * +__Pyx_PyErr_GetTopmostException(PyThreadState *tstate) +{ + _PyErr_StackItem *exc_info = tstate->exc_info; + while ((exc_info->exc_value == NULL || exc_info->exc_value == Py_None) && + exc_info->previous_item != NULL) + { + exc_info = exc_info->previous_item; + } + return exc_info; +} +#endif + +/* SaveResetException */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx__ExceptionSave(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { + #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 + _PyErr_StackItem *exc_info = __Pyx_PyErr_GetTopmostException(tstate); + PyObject *exc_value = exc_info->exc_value; + if (exc_value == NULL || exc_value == Py_None) { + *value = NULL; + *type = NULL; + *tb = NULL; + } else { + *value = exc_value; + Py_INCREF(*value); + *type = (PyObject*) Py_TYPE(exc_value); + Py_INCREF(*type); + *tb = PyException_GetTraceback(exc_value); + } + #elif CYTHON_USE_EXC_INFO_STACK + _PyErr_StackItem *exc_info = __Pyx_PyErr_GetTopmostException(tstate); + *type = exc_info->exc_type; + *value = exc_info->exc_value; + *tb = exc_info->exc_traceback; + Py_XINCREF(*type); + Py_XINCREF(*value); + Py_XINCREF(*tb); + #else + *type = tstate->exc_type; + *value = tstate->exc_value; + *tb = tstate->exc_traceback; + Py_XINCREF(*type); + Py_XINCREF(*value); + Py_XINCREF(*tb); + #endif +} +static CYTHON_INLINE void __Pyx__ExceptionReset(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb) { + #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 + _PyErr_StackItem *exc_info = tstate->exc_info; + PyObject *tmp_value = exc_info->exc_value; + exc_info->exc_value = value; + Py_XDECREF(tmp_value); + Py_XDECREF(type); + Py_XDECREF(tb); + #else + PyObject *tmp_type, *tmp_value, *tmp_tb; + #if CYTHON_USE_EXC_INFO_STACK + _PyErr_StackItem *exc_info = tstate->exc_info; + tmp_type = exc_info->exc_type; + tmp_value = exc_info->exc_value; + tmp_tb = exc_info->exc_traceback; + exc_info->exc_type = type; + exc_info->exc_value = value; + exc_info->exc_traceback = tb; + #else + tmp_type = tstate->exc_type; + tmp_value = tstate->exc_value; + tmp_tb = tstate->exc_traceback; + tstate->exc_type = type; + tstate->exc_value = value; + tstate->exc_traceback = tb; + #endif + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); + #endif +} +#endif + +/* GetException */ +#if CYTHON_FAST_THREAD_STATE +static int __Pyx__GetException(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) +#else +static int __Pyx_GetException(PyObject **type, PyObject **value, PyObject **tb) +#endif +{ + PyObject *local_type = NULL, *local_value, *local_tb = NULL; +#if CYTHON_FAST_THREAD_STATE + PyObject *tmp_type, *tmp_value, *tmp_tb; + #if PY_VERSION_HEX >= 0x030C00A6 + local_value = tstate->current_exception; + tstate->current_exception = 0; + if (likely(local_value)) { + local_type = (PyObject*) Py_TYPE(local_value); + Py_INCREF(local_type); + local_tb = PyException_GetTraceback(local_value); + } + #else + local_type = tstate->curexc_type; + local_value = tstate->curexc_value; + local_tb = tstate->curexc_traceback; + tstate->curexc_type = 0; + tstate->curexc_value = 0; + tstate->curexc_traceback = 0; + #endif +#else + PyErr_Fetch(&local_type, &local_value, &local_tb); +#endif + PyErr_NormalizeException(&local_type, &local_value, &local_tb); +#if CYTHON_FAST_THREAD_STATE && PY_VERSION_HEX >= 0x030C00A6 + if (unlikely(tstate->current_exception)) +#elif CYTHON_FAST_THREAD_STATE + if (unlikely(tstate->curexc_type)) +#else + if (unlikely(PyErr_Occurred())) +#endif + goto bad; + #if PY_MAJOR_VERSION >= 3 + if (local_tb) { + if (unlikely(PyException_SetTraceback(local_value, local_tb) < 0)) + goto bad; + } + #endif + Py_XINCREF(local_tb); + Py_XINCREF(local_type); + Py_XINCREF(local_value); + *type = local_type; + *value = local_value; + *tb = local_tb; +#if CYTHON_FAST_THREAD_STATE + #if CYTHON_USE_EXC_INFO_STACK + { + _PyErr_StackItem *exc_info = tstate->exc_info; + #if PY_VERSION_HEX >= 0x030B00a4 + tmp_value = exc_info->exc_value; + exc_info->exc_value = local_value; + tmp_type = NULL; + tmp_tb = NULL; + Py_XDECREF(local_type); + Py_XDECREF(local_tb); + #else + tmp_type = exc_info->exc_type; + tmp_value = exc_info->exc_value; + tmp_tb = exc_info->exc_traceback; + exc_info->exc_type = local_type; + exc_info->exc_value = local_value; + exc_info->exc_traceback = local_tb; + #endif + } + #else + tmp_type = tstate->exc_type; + tmp_value = tstate->exc_value; + tmp_tb = tstate->exc_traceback; + tstate->exc_type = local_type; + tstate->exc_value = local_value; + tstate->exc_traceback = local_tb; + #endif + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); +#else + PyErr_SetExcInfo(local_type, local_value, local_tb); +#endif + return 0; +bad: + *type = 0; + *value = 0; + *tb = 0; + Py_XDECREF(local_type); + Py_XDECREF(local_value); + Py_XDECREF(local_tb); + return -1; +} + +/* SwapException */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx__ExceptionSwap(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { + PyObject *tmp_type, *tmp_value, *tmp_tb; + #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 + _PyErr_StackItem *exc_info = tstate->exc_info; + tmp_value = exc_info->exc_value; + exc_info->exc_value = *value; + if (tmp_value == NULL || tmp_value == Py_None) { + Py_XDECREF(tmp_value); + tmp_value = NULL; + tmp_type = NULL; + tmp_tb = NULL; + } else { + tmp_type = (PyObject*) Py_TYPE(tmp_value); + Py_INCREF(tmp_type); + #if CYTHON_COMPILING_IN_CPYTHON + tmp_tb = ((PyBaseExceptionObject*) tmp_value)->traceback; + Py_XINCREF(tmp_tb); + #else + tmp_tb = PyException_GetTraceback(tmp_value); + #endif + } + #elif CYTHON_USE_EXC_INFO_STACK + _PyErr_StackItem *exc_info = tstate->exc_info; + tmp_type = exc_info->exc_type; + tmp_value = exc_info->exc_value; + tmp_tb = exc_info->exc_traceback; + exc_info->exc_type = *type; + exc_info->exc_value = *value; + exc_info->exc_traceback = *tb; + #else + tmp_type = tstate->exc_type; + tmp_value = tstate->exc_value; + tmp_tb = tstate->exc_traceback; + tstate->exc_type = *type; + tstate->exc_value = *value; + tstate->exc_traceback = *tb; + #endif + *type = tmp_type; + *value = tmp_value; + *tb = tmp_tb; +} +#else +static CYTHON_INLINE void __Pyx_ExceptionSwap(PyObject **type, PyObject **value, PyObject **tb) { + PyObject *tmp_type, *tmp_value, *tmp_tb; + PyErr_GetExcInfo(&tmp_type, &tmp_value, &tmp_tb); + PyErr_SetExcInfo(*type, *value, *tb); + *type = tmp_type; + *value = tmp_value; + *tb = tmp_tb; +} +#endif + +/* Import */ +static PyObject *__Pyx_Import(PyObject *name, PyObject *from_list, int level) { + PyObject *module = 0; + PyObject *empty_dict = 0; + PyObject *empty_list = 0; + #if PY_MAJOR_VERSION < 3 + PyObject *py_import; + py_import = __Pyx_PyObject_GetAttrStr(__pyx_b, __pyx_n_s_import); + if (unlikely(!py_import)) + goto bad; + if (!from_list) { + empty_list = PyList_New(0); + if (unlikely(!empty_list)) + goto bad; + from_list = empty_list; + } + #endif + empty_dict = PyDict_New(); + if (unlikely(!empty_dict)) + goto bad; + { + #if PY_MAJOR_VERSION >= 3 + if (level == -1) { + if (strchr(__Pyx_MODULE_NAME, '.') != NULL) { + module = PyImport_ImportModuleLevelObject( + name, __pyx_d, empty_dict, from_list, 1); + if (unlikely(!module)) { + if (unlikely(!PyErr_ExceptionMatches(PyExc_ImportError))) + goto bad; + PyErr_Clear(); + } + } + level = 0; + } + #endif + if (!module) { + #if PY_MAJOR_VERSION < 3 + PyObject *py_level = PyInt_FromLong(level); + if (unlikely(!py_level)) + goto bad; + module = PyObject_CallFunctionObjArgs(py_import, + name, __pyx_d, empty_dict, from_list, py_level, (PyObject *)NULL); + Py_DECREF(py_level); + #else + module = PyImport_ImportModuleLevelObject( + name, __pyx_d, empty_dict, from_list, level); + #endif + } + } +bad: + Py_XDECREF(empty_dict); + Py_XDECREF(empty_list); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_import); + #endif + return module; +} + +/* ImportDottedModule */ +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx__ImportDottedModule_Error(PyObject *name, PyObject *parts_tuple, Py_ssize_t count) { + PyObject *partial_name = NULL, *slice = NULL, *sep = NULL; + if (unlikely(PyErr_Occurred())) { + PyErr_Clear(); + } + if (likely(PyTuple_GET_SIZE(parts_tuple) == count)) { + partial_name = name; + } else { + slice = PySequence_GetSlice(parts_tuple, 0, count); + if (unlikely(!slice)) + goto bad; + sep = PyUnicode_FromStringAndSize(".", 1); + if (unlikely(!sep)) + goto bad; + partial_name = PyUnicode_Join(sep, slice); + } + PyErr_Format( +#if PY_MAJOR_VERSION < 3 + PyExc_ImportError, + "No module named '%s'", PyString_AS_STRING(partial_name)); +#else +#if PY_VERSION_HEX >= 0x030600B1 + PyExc_ModuleNotFoundError, +#else + PyExc_ImportError, +#endif + "No module named '%U'", partial_name); +#endif +bad: + Py_XDECREF(sep); + Py_XDECREF(slice); + Py_XDECREF(partial_name); + return NULL; +} +#endif +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx__ImportDottedModule_Lookup(PyObject *name) { + PyObject *imported_module; +#if PY_VERSION_HEX < 0x030700A1 || (CYTHON_COMPILING_IN_PYPY && PYPY_VERSION_NUM < 0x07030400) + PyObject *modules = PyImport_GetModuleDict(); + if (unlikely(!modules)) + return NULL; + imported_module = __Pyx_PyDict_GetItemStr(modules, name); + Py_XINCREF(imported_module); +#else + imported_module = PyImport_GetModule(name); +#endif + return imported_module; +} +#endif +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_ImportDottedModule_WalkParts(PyObject *module, PyObject *name, PyObject *parts_tuple) { + Py_ssize_t i, nparts; + nparts = PyTuple_GET_SIZE(parts_tuple); + for (i=1; i < nparts && module; i++) { + PyObject *part, *submodule; +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + part = PyTuple_GET_ITEM(parts_tuple, i); +#else + part = PySequence_ITEM(parts_tuple, i); +#endif + submodule = __Pyx_PyObject_GetAttrStrNoError(module, part); +#if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(part); +#endif + Py_DECREF(module); + module = submodule; + } + if (unlikely(!module)) { + return __Pyx__ImportDottedModule_Error(name, parts_tuple, i); + } + return module; +} +#endif +static PyObject *__Pyx__ImportDottedModule(PyObject *name, PyObject *parts_tuple) { +#if PY_MAJOR_VERSION < 3 + PyObject *module, *from_list, *star = __pyx_n_s__3; + CYTHON_UNUSED_VAR(parts_tuple); + from_list = PyList_New(1); + if (unlikely(!from_list)) + return NULL; + Py_INCREF(star); + PyList_SET_ITEM(from_list, 0, star); + module = __Pyx_Import(name, from_list, 0); + Py_DECREF(from_list); + return module; +#else + PyObject *imported_module; + PyObject *module = __Pyx_Import(name, NULL, 0); + if (!parts_tuple || unlikely(!module)) + return module; + imported_module = __Pyx__ImportDottedModule_Lookup(name); + if (likely(imported_module)) { + Py_DECREF(module); + return imported_module; + } + PyErr_Clear(); + return __Pyx_ImportDottedModule_WalkParts(module, name, parts_tuple); +#endif +} +static PyObject *__Pyx_ImportDottedModule(PyObject *name, PyObject *parts_tuple) { +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030400B1 + PyObject *module = __Pyx__ImportDottedModule_Lookup(name); + if (likely(module)) { + PyObject *spec = __Pyx_PyObject_GetAttrStrNoError(module, __pyx_n_s_spec); + if (likely(spec)) { + PyObject *unsafe = __Pyx_PyObject_GetAttrStrNoError(spec, __pyx_n_s_initializing); + if (likely(!unsafe || !__Pyx_PyObject_IsTrue(unsafe))) { + Py_DECREF(spec); + spec = NULL; + } + Py_XDECREF(unsafe); + } + if (likely(!spec)) { + PyErr_Clear(); + return module; + } + Py_DECREF(spec); + Py_DECREF(module); + } else if (PyErr_Occurred()) { + PyErr_Clear(); + } +#endif + return __Pyx__ImportDottedModule(name, parts_tuple); +} + +/* FastTypeChecks */ +#if CYTHON_COMPILING_IN_CPYTHON +static int __Pyx_InBases(PyTypeObject *a, PyTypeObject *b) { + while (a) { + a = __Pyx_PyType_GetSlot(a, tp_base, PyTypeObject*); + if (a == b) + return 1; + } + return b == &PyBaseObject_Type; +} +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (a == b) return 1; + mro = a->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + if (PyTuple_GET_ITEM(mro, i) == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(a, b); +} +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (cls == a || cls == b) return 1; + mro = cls->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + PyObject *base = PyTuple_GET_ITEM(mro, i); + if (base == (PyObject *)a || base == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(cls, a) || __Pyx_InBases(cls, b); +} +#if PY_MAJOR_VERSION == 2 +static int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject* exc_type2) { + PyObject *exception, *value, *tb; + int res; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&exception, &value, &tb); + res = exc_type1 ? PyObject_IsSubclass(err, exc_type1) : 0; + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + if (!res) { + res = PyObject_IsSubclass(err, exc_type2); + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + } + __Pyx_ErrRestore(exception, value, tb); + return res; +} +#else +static CYTHON_INLINE int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject *exc_type2) { + if (exc_type1) { + return __Pyx_IsAnySubtype2((PyTypeObject*)err, (PyTypeObject*)exc_type1, (PyTypeObject*)exc_type2); + } else { + return __Pyx_IsSubtype((PyTypeObject*)err, (PyTypeObject*)exc_type2); + } +} +#endif +static int __Pyx_PyErr_GivenExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + assert(PyExceptionClass_Check(exc_type)); + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; itp_as_sequence && type->tp_as_sequence->sq_repeat)) { + return type->tp_as_sequence->sq_repeat(seq, mul); + } else +#endif + { + return __Pyx_PySequence_Multiply_Generic(seq, mul); + } +} + +/* SetItemInt */ +static int __Pyx_SetItemInt_Generic(PyObject *o, PyObject *j, PyObject *v) { + int r; + if (unlikely(!j)) return -1; + r = PyObject_SetItem(o, j, v); + Py_DECREF(j); + return r; +} +static CYTHON_INLINE int __Pyx_SetItemInt_Fast(PyObject *o, Py_ssize_t i, PyObject *v, int is_list, + CYTHON_NCP_UNUSED int wraparound, CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS && CYTHON_USE_TYPE_SLOTS + if (is_list || PyList_CheckExact(o)) { + Py_ssize_t n = (!wraparound) ? i : ((likely(i >= 0)) ? i : i + PyList_GET_SIZE(o)); + if ((!boundscheck) || likely(__Pyx_is_valid_index(n, PyList_GET_SIZE(o)))) { + PyObject* old = PyList_GET_ITEM(o, n); + Py_INCREF(v); + PyList_SET_ITEM(o, n, v); + Py_DECREF(old); + return 1; + } + } else { + PyMappingMethods *mm = Py_TYPE(o)->tp_as_mapping; + PySequenceMethods *sm = Py_TYPE(o)->tp_as_sequence; + if (mm && mm->mp_ass_subscript) { + int r; + PyObject *key = PyInt_FromSsize_t(i); + if (unlikely(!key)) return -1; + r = mm->mp_ass_subscript(o, key, v); + Py_DECREF(key); + return r; + } + if (likely(sm && sm->sq_ass_item)) { + if (wraparound && unlikely(i < 0) && likely(sm->sq_length)) { + Py_ssize_t l = sm->sq_length(o); + if (likely(l >= 0)) { + i += l; + } else { + if (!PyErr_ExceptionMatches(PyExc_OverflowError)) + return -1; + PyErr_Clear(); + } + } + return sm->sq_ass_item(o, i, v); + } + } +#else + if (is_list || !PyMapping_Check(o)) + { + return PySequence_SetItem(o, i, v); + } +#endif + return __Pyx_SetItemInt_Generic(o, PyInt_FromSsize_t(i), v); +} + +/* RaiseUnboundLocalError */ +static CYTHON_INLINE void __Pyx_RaiseUnboundLocalError(const char *varname) { + PyErr_Format(PyExc_UnboundLocalError, "local variable '%s' referenced before assignment", varname); +} + +/* DivInt[long] */ +static CYTHON_INLINE long __Pyx_div_long(long a, long b) { + long q = a / b; + long r = a - q*b; + q -= ((r != 0) & ((r ^ b) < 0)); + return q; +} + +/* ImportFrom */ +static PyObject* __Pyx_ImportFrom(PyObject* module, PyObject* name) { + PyObject* value = __Pyx_PyObject_GetAttrStr(module, name); + if (unlikely(!value) && PyErr_ExceptionMatches(PyExc_AttributeError)) { + const char* module_name_str = 0; + PyObject* module_name = 0; + PyObject* module_dot = 0; + PyObject* full_name = 0; + PyErr_Clear(); + module_name_str = PyModule_GetName(module); + if (unlikely(!module_name_str)) { goto modbad; } + module_name = PyUnicode_FromString(module_name_str); + if (unlikely(!module_name)) { goto modbad; } + module_dot = PyUnicode_Concat(module_name, __pyx_kp_u__2); + if (unlikely(!module_dot)) { goto modbad; } + full_name = PyUnicode_Concat(module_dot, name); + if (unlikely(!full_name)) { goto modbad; } + #if PY_VERSION_HEX < 0x030700A1 || (CYTHON_COMPILING_IN_PYPY && PYPY_VERSION_NUM < 0x07030400) + { + PyObject *modules = PyImport_GetModuleDict(); + if (unlikely(!modules)) + goto modbad; + value = PyObject_GetItem(modules, full_name); + } + #else + value = PyImport_GetModule(full_name); + #endif + modbad: + Py_XDECREF(full_name); + Py_XDECREF(module_dot); + Py_XDECREF(module_name); + } + if (unlikely(!value)) { + PyErr_Format(PyExc_ImportError, + #if PY_MAJOR_VERSION < 3 + "cannot import name %.230s", PyString_AS_STRING(name)); + #else + "cannot import name %S", name); + #endif + } + return value; +} + +/* HasAttr */ +#if __PYX_LIMITED_VERSION_HEX < 0x030d00A1 +static CYTHON_INLINE int __Pyx_HasAttr(PyObject *o, PyObject *n) { + PyObject *r; + if (unlikely(!__Pyx_PyBaseString_Check(n))) { + PyErr_SetString(PyExc_TypeError, + "hasattr(): attribute name must be string"); + return -1; + } + r = __Pyx_GetAttr(o, n); + if (!r) { + PyErr_Clear(); + return 0; + } else { + Py_DECREF(r); + return 1; + } +} +#endif + +/* PyObjectCall2Args */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call2Args(PyObject* function, PyObject* arg1, PyObject* arg2) { + PyObject *args[3] = {NULL, arg1, arg2}; + return __Pyx_PyObject_FastCall(function, args+1, 2 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* PyObjectGetMethod */ +static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method) { + PyObject *attr; +#if CYTHON_UNPACK_METHODS && CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_PYTYPE_LOOKUP + __Pyx_TypeName type_name; + PyTypeObject *tp = Py_TYPE(obj); + PyObject *descr; + descrgetfunc f = NULL; + PyObject **dictptr, *dict; + int meth_found = 0; + assert (*method == NULL); + if (unlikely(tp->tp_getattro != PyObject_GenericGetAttr)) { + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; + } + if (unlikely(tp->tp_dict == NULL) && unlikely(PyType_Ready(tp) < 0)) { + return 0; + } + descr = _PyType_Lookup(tp, name); + if (likely(descr != NULL)) { + Py_INCREF(descr); +#if defined(Py_TPFLAGS_METHOD_DESCRIPTOR) && Py_TPFLAGS_METHOD_DESCRIPTOR + if (__Pyx_PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_METHOD_DESCRIPTOR)) +#elif PY_MAJOR_VERSION >= 3 + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type))) + #endif +#else + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr))) + #endif +#endif + { + meth_found = 1; + } else { + f = Py_TYPE(descr)->tp_descr_get; + if (f != NULL && PyDescr_IsData(descr)) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + } + } + dictptr = _PyObject_GetDictPtr(obj); + if (dictptr != NULL && (dict = *dictptr) != NULL) { + Py_INCREF(dict); + attr = __Pyx_PyDict_GetItemStr(dict, name); + if (attr != NULL) { + Py_INCREF(attr); + Py_DECREF(dict); + Py_XDECREF(descr); + goto try_unpack; + } + Py_DECREF(dict); + } + if (meth_found) { + *method = descr; + return 1; + } + if (f != NULL) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + if (likely(descr != NULL)) { + *method = descr; + return 0; + } + type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return 0; +#else + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; +#endif +try_unpack: +#if CYTHON_UNPACK_METHODS + if (likely(attr) && PyMethod_Check(attr) && likely(PyMethod_GET_SELF(attr) == obj)) { + PyObject *function = PyMethod_GET_FUNCTION(attr); + Py_INCREF(function); + Py_DECREF(attr); + *method = function; + return 1; + } +#endif + *method = attr; + return 0; +} + +/* PyObjectCallMethod1 */ +#if !(CYTHON_VECTORCALL && __PYX_LIMITED_VERSION_HEX >= 0x030C00A2) +static PyObject* __Pyx__PyObject_CallMethod1(PyObject* method, PyObject* arg) { + PyObject *result = __Pyx_PyObject_CallOneArg(method, arg); + Py_DECREF(method); + return result; +} +#endif +static PyObject* __Pyx_PyObject_CallMethod1(PyObject* obj, PyObject* method_name, PyObject* arg) { +#if CYTHON_VECTORCALL && __PYX_LIMITED_VERSION_HEX >= 0x030C00A2 + PyObject *args[2] = {obj, arg}; + (void) __Pyx_PyObject_GetMethod; + (void) __Pyx_PyObject_CallOneArg; + (void) __Pyx_PyObject_Call2Args; + return PyObject_VectorcallMethod(method_name, args, 2 | PY_VECTORCALL_ARGUMENTS_OFFSET, NULL); +#else + PyObject *method = NULL, *result; + int is_method = __Pyx_PyObject_GetMethod(obj, method_name, &method); + if (likely(is_method)) { + result = __Pyx_PyObject_Call2Args(method, obj, arg); + Py_DECREF(method); + return result; + } + if (unlikely(!method)) return NULL; + return __Pyx__PyObject_CallMethod1(method, arg); +#endif +} + +/* StringJoin */ +static CYTHON_INLINE PyObject* __Pyx_PyBytes_Join(PyObject* sep, PyObject* values) { + (void) __Pyx_PyObject_CallMethod1; +#if CYTHON_COMPILING_IN_CPYTHON && PY_MAJOR_VERSION < 3 + return _PyString_Join(sep, values); +#elif CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030d0000 + return _PyBytes_Join(sep, values); +#else + return __Pyx_PyObject_CallMethod1(sep, __pyx_n_s_join, values); +#endif +} + +/* CIntToPyUnicode */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_size_t(size_t value, Py_ssize_t width, char padding_char, char format_char) { + char digits[sizeof(size_t)*3+2]; + char *dpos, *end = digits + sizeof(size_t)*3+2; + const char *hex_digits = DIGITS_HEX; + Py_ssize_t length, ulength; + int prepend_sign, last_one_off; + size_t remaining; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const size_t neg_one = (size_t) -1, const_zero = (size_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (format_char == 'X') { + hex_digits += 16; + format_char = 'x'; + } + remaining = value; + last_one_off = 0; + dpos = end; + do { + int digit_pos; + switch (format_char) { + case 'o': + digit_pos = abs((int)(remaining % (8*8))); + remaining = (size_t) (remaining / (8*8)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_8 + digit_pos * 2, 2); + last_one_off = (digit_pos < 8); + break; + case 'd': + digit_pos = abs((int)(remaining % (10*10))); + remaining = (size_t) (remaining / (10*10)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_10 + digit_pos * 2, 2); + last_one_off = (digit_pos < 10); + break; + case 'x': + *(--dpos) = hex_digits[abs((int)(remaining % 16))]; + remaining = (size_t) (remaining / 16); + break; + default: + assert(0); + break; + } + } while (unlikely(remaining != 0)); + assert(!last_one_off || *dpos == '0'); + dpos += last_one_off; + length = end - dpos; + ulength = length; + prepend_sign = 0; + if (!is_unsigned && value <= neg_one) { + if (padding_char == ' ' || width <= length + 1) { + *(--dpos) = '-'; + ++length; + } else { + prepend_sign = 1; + } + ++ulength; + } + if (width > ulength) { + ulength = width; + } + if (ulength == 1) { + return PyUnicode_FromOrdinal(*dpos); + } + return __Pyx_PyUnicode_BuildFromAscii(ulength, dpos, (int) length, prepend_sign, padding_char); +} + +/* PyObjectCallNoArg */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func) { + PyObject *arg[2] = {NULL, NULL}; + return __Pyx_PyObject_FastCall(func, arg + 1, 0 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* BufferIndexError */ +static void __Pyx_RaiseBufferIndexError(int axis) { + PyErr_Format(PyExc_IndexError, + "Out of bounds on buffer access (axis %d)", axis); +} + +/* PyObject_GenericGetAttrNoDict */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject *__Pyx_RaiseGenericGetAttributeError(PyTypeObject *tp, PyObject *attr_name) { + __Pyx_TypeName type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, attr_name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(attr_name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name) { + PyObject *descr; + PyTypeObject *tp = Py_TYPE(obj); + if (unlikely(!PyString_Check(attr_name))) { + return PyObject_GenericGetAttr(obj, attr_name); + } + assert(!tp->tp_dictoffset); + descr = _PyType_Lookup(tp, attr_name); + if (unlikely(!descr)) { + return __Pyx_RaiseGenericGetAttributeError(tp, attr_name); + } + Py_INCREF(descr); + #if PY_MAJOR_VERSION < 3 + if (likely(PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_HAVE_CLASS))) + #endif + { + descrgetfunc f = Py_TYPE(descr)->tp_descr_get; + if (unlikely(f)) { + PyObject *res = f(descr, obj, (PyObject *)tp); + Py_DECREF(descr); + return res; + } + } + return descr; +} +#endif + +/* PyObject_GenericGetAttr */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name) { + if (unlikely(Py_TYPE(obj)->tp_dictoffset)) { + return PyObject_GenericGetAttr(obj, attr_name); + } + return __Pyx_PyObject_GenericGetAttrNoDict(obj, attr_name); +} +#endif + +/* TypeImport */ +#ifndef __PYX_HAVE_RT_ImportType_3_0_8 +#define __PYX_HAVE_RT_ImportType_3_0_8 +static PyTypeObject *__Pyx_ImportType_3_0_8(PyObject *module, const char *module_name, const char *class_name, + size_t size, size_t alignment, enum __Pyx_ImportType_CheckSize_3_0_8 check_size) +{ + PyObject *result = 0; + char warning[200]; + Py_ssize_t basicsize; + Py_ssize_t itemsize; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *py_basicsize; + PyObject *py_itemsize; +#endif + result = PyObject_GetAttrString(module, class_name); + if (!result) + goto bad; + if (!PyType_Check(result)) { + PyErr_Format(PyExc_TypeError, + "%.200s.%.200s is not a type object", + module_name, class_name); + goto bad; + } +#if !CYTHON_COMPILING_IN_LIMITED_API + basicsize = ((PyTypeObject *)result)->tp_basicsize; + itemsize = ((PyTypeObject *)result)->tp_itemsize; +#else + py_basicsize = PyObject_GetAttrString(result, "__basicsize__"); + if (!py_basicsize) + goto bad; + basicsize = PyLong_AsSsize_t(py_basicsize); + Py_DECREF(py_basicsize); + py_basicsize = 0; + if (basicsize == (Py_ssize_t)-1 && PyErr_Occurred()) + goto bad; + py_itemsize = PyObject_GetAttrString(result, "__itemsize__"); + if (!py_itemsize) + goto bad; + itemsize = PyLong_AsSsize_t(py_itemsize); + Py_DECREF(py_itemsize); + py_itemsize = 0; + if (itemsize == (Py_ssize_t)-1 && PyErr_Occurred()) + goto bad; +#endif + if (itemsize) { + if (size % alignment) { + alignment = size % alignment; + } + if (itemsize < (Py_ssize_t)alignment) + itemsize = (Py_ssize_t)alignment; + } + if ((size_t)(basicsize + itemsize) < size) { + PyErr_Format(PyExc_ValueError, + "%.200s.%.200s size changed, may indicate binary incompatibility. " + "Expected %zd from C header, got %zd from PyObject", + module_name, class_name, size, basicsize+itemsize); + goto bad; + } + if (check_size == __Pyx_ImportType_CheckSize_Error_3_0_8 && + ((size_t)basicsize > size || (size_t)(basicsize + itemsize) < size)) { + PyErr_Format(PyExc_ValueError, + "%.200s.%.200s size changed, may indicate binary incompatibility. " + "Expected %zd from C header, got %zd-%zd from PyObject", + module_name, class_name, size, basicsize, basicsize+itemsize); + goto bad; + } + else if (check_size == __Pyx_ImportType_CheckSize_Warn_3_0_8 && (size_t)basicsize > size) { + PyOS_snprintf(warning, sizeof(warning), + "%s.%s size changed, may indicate binary incompatibility. " + "Expected %zd from C header, got %zd from PyObject", + module_name, class_name, size, basicsize); + if (PyErr_WarnEx(NULL, warning, 0) < 0) goto bad; + } + return (PyTypeObject *)result; +bad: + Py_XDECREF(result); + return NULL; +} +#endif + +/* FixUpExtensionType */ +#if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type) { +#if PY_VERSION_HEX > 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + CYTHON_UNUSED_VAR(spec); + CYTHON_UNUSED_VAR(type); +#else + const PyType_Slot *slot = spec->slots; + while (slot && slot->slot && slot->slot != Py_tp_members) + slot++; + if (slot && slot->slot == Py_tp_members) { + int changed = 0; +#if !(PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON) + const +#endif + PyMemberDef *memb = (PyMemberDef*) slot->pfunc; + while (memb && memb->name) { + if (memb->name[0] == '_' && memb->name[1] == '_') { +#if PY_VERSION_HEX < 0x030900b1 + if (strcmp(memb->name, "__weaklistoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_weaklistoffset = memb->offset; + changed = 1; + } + else if (strcmp(memb->name, "__dictoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_dictoffset = memb->offset; + changed = 1; + } +#if CYTHON_METH_FASTCALL + else if (strcmp(memb->name, "__vectorcalloffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); +#if PY_VERSION_HEX >= 0x030800b4 + type->tp_vectorcall_offset = memb->offset; +#else + type->tp_print = (printfunc) memb->offset; +#endif + changed = 1; + } +#endif +#else + if ((0)); +#endif +#if PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON + else if (strcmp(memb->name, "__module__") == 0) { + PyObject *descr; + assert(memb->type == T_OBJECT); + assert(memb->flags == 0 || memb->flags == READONLY); + descr = PyDescr_NewMember(type, memb); + if (unlikely(!descr)) + return -1; + if (unlikely(PyDict_SetItem(type->tp_dict, PyDescr_NAME(descr), descr) < 0)) { + Py_DECREF(descr); + return -1; + } + Py_DECREF(descr); + changed = 1; + } +#endif + } + memb++; + } + if (changed) + PyType_Modified(type); + } +#endif + return 0; +} +#endif + +/* PyObjectCallMethod0 */ +static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name) { + PyObject *method = NULL, *result = NULL; + int is_method = __Pyx_PyObject_GetMethod(obj, method_name, &method); + if (likely(is_method)) { + result = __Pyx_PyObject_CallOneArg(method, obj); + Py_DECREF(method); + return result; + } + if (unlikely(!method)) goto bad; + result = __Pyx_PyObject_CallNoArg(method); + Py_DECREF(method); +bad: + return result; +} + +/* ValidateBasesTuple */ +#if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases) { + Py_ssize_t i, n; +#if CYTHON_ASSUME_SAFE_MACROS + n = PyTuple_GET_SIZE(bases); +#else + n = PyTuple_Size(bases); + if (n < 0) return -1; +#endif + for (i = 1; i < n; i++) + { +#if CYTHON_AVOID_BORROWED_REFS + PyObject *b0 = PySequence_GetItem(bases, i); + if (!b0) return -1; +#elif CYTHON_ASSUME_SAFE_MACROS + PyObject *b0 = PyTuple_GET_ITEM(bases, i); +#else + PyObject *b0 = PyTuple_GetItem(bases, i); + if (!b0) return -1; +#endif + PyTypeObject *b; +#if PY_MAJOR_VERSION < 3 + if (PyClass_Check(b0)) + { + PyErr_Format(PyExc_TypeError, "base class '%.200s' is an old-style class", + PyString_AS_STRING(((PyClassObject*)b0)->cl_name)); +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + return -1; + } +#endif + b = (PyTypeObject*) b0; + if (!__Pyx_PyType_HasFeature(b, Py_TPFLAGS_HEAPTYPE)) + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "base class '" __Pyx_FMT_TYPENAME "' is not a heap type", b_name); + __Pyx_DECREF_TypeName(b_name); +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + return -1; + } + if (dictoffset == 0) + { + Py_ssize_t b_dictoffset = 0; +#if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + b_dictoffset = b->tp_dictoffset; +#else + PyObject *py_b_dictoffset = PyObject_GetAttrString((PyObject*)b, "__dictoffset__"); + if (!py_b_dictoffset) goto dictoffset_return; + b_dictoffset = PyLong_AsSsize_t(py_b_dictoffset); + Py_DECREF(py_b_dictoffset); + if (b_dictoffset == -1 && PyErr_Occurred()) goto dictoffset_return; +#endif + if (b_dictoffset) { + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "extension type '%.200s' has no __dict__ slot, " + "but base type '" __Pyx_FMT_TYPENAME "' has: " + "either add 'cdef dict __dict__' to the extension type " + "or add '__slots__ = [...]' to the base type", + type_name, b_name); + __Pyx_DECREF_TypeName(b_name); + } +#if !(CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY) + dictoffset_return: +#endif +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + return -1; + } + } +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + } + return 0; +} +#endif + +/* PyType_Ready */ +static int __Pyx_PyType_Ready(PyTypeObject *t) { +#if CYTHON_USE_TYPE_SPECS || !(CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API) || defined(PYSTON_MAJOR_VERSION) + (void)__Pyx_PyObject_CallMethod0; +#if CYTHON_USE_TYPE_SPECS + (void)__Pyx_validate_bases_tuple; +#endif + return PyType_Ready(t); +#else + int r; + PyObject *bases = __Pyx_PyType_GetSlot(t, tp_bases, PyObject*); + if (bases && unlikely(__Pyx_validate_bases_tuple(t->tp_name, t->tp_dictoffset, bases) == -1)) + return -1; +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + { + int gc_was_enabled; + #if PY_VERSION_HEX >= 0x030A00b1 + gc_was_enabled = PyGC_Disable(); + (void)__Pyx_PyObject_CallMethod0; + #else + PyObject *ret, *py_status; + PyObject *gc = NULL; + #if PY_VERSION_HEX >= 0x030700a1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM+0 >= 0x07030400) + gc = PyImport_GetModule(__pyx_kp_u_gc); + #endif + if (unlikely(!gc)) gc = PyImport_Import(__pyx_kp_u_gc); + if (unlikely(!gc)) return -1; + py_status = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_isenabled); + if (unlikely(!py_status)) { + Py_DECREF(gc); + return -1; + } + gc_was_enabled = __Pyx_PyObject_IsTrue(py_status); + Py_DECREF(py_status); + if (gc_was_enabled > 0) { + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_disable); + if (unlikely(!ret)) { + Py_DECREF(gc); + return -1; + } + Py_DECREF(ret); + } else if (unlikely(gc_was_enabled == -1)) { + Py_DECREF(gc); + return -1; + } + #endif + t->tp_flags |= Py_TPFLAGS_HEAPTYPE; +#if PY_VERSION_HEX >= 0x030A0000 + t->tp_flags |= Py_TPFLAGS_IMMUTABLETYPE; +#endif +#else + (void)__Pyx_PyObject_CallMethod0; +#endif + r = PyType_Ready(t); +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + t->tp_flags &= ~Py_TPFLAGS_HEAPTYPE; + #if PY_VERSION_HEX >= 0x030A00b1 + if (gc_was_enabled) + PyGC_Enable(); + #else + if (gc_was_enabled) { + PyObject *tp, *v, *tb; + PyErr_Fetch(&tp, &v, &tb); + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_enable); + if (likely(ret || r == -1)) { + Py_XDECREF(ret); + PyErr_Restore(tp, v, tb); + } else { + Py_XDECREF(tp); + Py_XDECREF(v); + Py_XDECREF(tb); + r = -1; + } + } + Py_DECREF(gc); + #endif + } +#endif + return r; +#endif +} + +/* SetupReduce */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce_is_named(PyObject* meth, PyObject* name) { + int ret; + PyObject *name_attr; + name_attr = __Pyx_PyObject_GetAttrStrNoError(meth, __pyx_n_s_name_2); + if (likely(name_attr)) { + ret = PyObject_RichCompareBool(name_attr, name, Py_EQ); + } else { + ret = -1; + } + if (unlikely(ret < 0)) { + PyErr_Clear(); + ret = 0; + } + Py_XDECREF(name_attr); + return ret; +} +static int __Pyx_setup_reduce(PyObject* type_obj) { + int ret = 0; + PyObject *object_reduce = NULL; + PyObject *object_getstate = NULL; + PyObject *object_reduce_ex = NULL; + PyObject *reduce = NULL; + PyObject *reduce_ex = NULL; + PyObject *reduce_cython = NULL; + PyObject *setstate = NULL; + PyObject *setstate_cython = NULL; + PyObject *getstate = NULL; +#if CYTHON_USE_PYTYPE_LOOKUP + getstate = _PyType_Lookup((PyTypeObject*)type_obj, __pyx_n_s_getstate); +#else + getstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_getstate); + if (!getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (getstate) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_getstate = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_getstate); +#else + object_getstate = __Pyx_PyObject_GetAttrStrNoError((PyObject*)&PyBaseObject_Type, __pyx_n_s_getstate); + if (!object_getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (object_getstate != getstate) { + goto __PYX_GOOD; + } + } +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce_ex = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#else + object_reduce_ex = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#endif + reduce_ex = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce_ex); if (unlikely(!reduce_ex)) goto __PYX_BAD; + if (reduce_ex == object_reduce_ex) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#else + object_reduce = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#endif + reduce = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce); if (unlikely(!reduce)) goto __PYX_BAD; + if (reduce == object_reduce || __Pyx_setup_reduce_is_named(reduce, __pyx_n_s_reduce_cython)) { + reduce_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_reduce_cython); + if (likely(reduce_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce, reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (reduce == object_reduce || PyErr_Occurred()) { + goto __PYX_BAD; + } + setstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate); + if (!setstate) PyErr_Clear(); + if (!setstate || __Pyx_setup_reduce_is_named(setstate, __pyx_n_s_setstate_cython)) { + setstate_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate_cython); + if (likely(setstate_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate, setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (!setstate || PyErr_Occurred()) { + goto __PYX_BAD; + } + } + PyType_Modified((PyTypeObject*)type_obj); + } + } + goto __PYX_GOOD; +__PYX_BAD: + if (!PyErr_Occurred()) { + __Pyx_TypeName type_obj_name = + __Pyx_PyType_GetName((PyTypeObject*)type_obj); + PyErr_Format(PyExc_RuntimeError, + "Unable to initialize pickling for " __Pyx_FMT_TYPENAME, type_obj_name); + __Pyx_DECREF_TypeName(type_obj_name); + } + ret = -1; +__PYX_GOOD: +#if !CYTHON_USE_PYTYPE_LOOKUP + Py_XDECREF(object_reduce); + Py_XDECREF(object_reduce_ex); + Py_XDECREF(object_getstate); + Py_XDECREF(getstate); +#endif + Py_XDECREF(reduce); + Py_XDECREF(reduce_ex); + Py_XDECREF(reduce_cython); + Py_XDECREF(setstate); + Py_XDECREF(setstate_cython); + return ret; +} +#endif + +/* SetVTable */ +static int __Pyx_SetVtable(PyTypeObject *type, void *vtable) { + PyObject *ob = PyCapsule_New(vtable, 0, 0); + if (unlikely(!ob)) + goto bad; +#if CYTHON_COMPILING_IN_LIMITED_API + if (unlikely(PyObject_SetAttr((PyObject *) type, __pyx_n_s_pyx_vtable, ob) < 0)) +#else + if (unlikely(PyDict_SetItem(type->tp_dict, __pyx_n_s_pyx_vtable, ob) < 0)) +#endif + goto bad; + Py_DECREF(ob); + return 0; +bad: + Py_XDECREF(ob); + return -1; +} + +/* GetVTable */ +static void* __Pyx_GetVtable(PyTypeObject *type) { + void* ptr; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *ob = PyObject_GetAttr((PyObject *)type, __pyx_n_s_pyx_vtable); +#else + PyObject *ob = PyObject_GetItem(type->tp_dict, __pyx_n_s_pyx_vtable); +#endif + if (!ob) + goto bad; + ptr = PyCapsule_GetPointer(ob, 0); + if (!ptr && !PyErr_Occurred()) + PyErr_SetString(PyExc_RuntimeError, "invalid vtable found for imported type"); + Py_DECREF(ob); + return ptr; +bad: + Py_XDECREF(ob); + return NULL; +} + +/* MergeVTables */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_MergeVtables(PyTypeObject *type) { + int i; + void** base_vtables; + __Pyx_TypeName tp_base_name; + __Pyx_TypeName base_name; + void* unknown = (void*)-1; + PyObject* bases = type->tp_bases; + int base_depth = 0; + { + PyTypeObject* base = type->tp_base; + while (base) { + base_depth += 1; + base = base->tp_base; + } + } + base_vtables = (void**) malloc(sizeof(void*) * (size_t)(base_depth + 1)); + base_vtables[0] = unknown; + for (i = 1; i < PyTuple_GET_SIZE(bases); i++) { + void* base_vtable = __Pyx_GetVtable(((PyTypeObject*)PyTuple_GET_ITEM(bases, i))); + if (base_vtable != NULL) { + int j; + PyTypeObject* base = type->tp_base; + for (j = 0; j < base_depth; j++) { + if (base_vtables[j] == unknown) { + base_vtables[j] = __Pyx_GetVtable(base); + base_vtables[j + 1] = unknown; + } + if (base_vtables[j] == base_vtable) { + break; + } else if (base_vtables[j] == NULL) { + goto bad; + } + base = base->tp_base; + } + } + } + PyErr_Clear(); + free(base_vtables); + return 0; +bad: + tp_base_name = __Pyx_PyType_GetName(type->tp_base); + base_name = __Pyx_PyType_GetName((PyTypeObject*)PyTuple_GET_ITEM(bases, i)); + PyErr_Format(PyExc_TypeError, + "multiple bases have vtable conflict: '" __Pyx_FMT_TYPENAME "' and '" __Pyx_FMT_TYPENAME "'", tp_base_name, base_name); + __Pyx_DECREF_TypeName(tp_base_name); + __Pyx_DECREF_TypeName(base_name); + free(base_vtables); + return -1; +} +#endif + +/* FetchSharedCythonModule */ +static PyObject *__Pyx_FetchSharedCythonABIModule(void) { + return __Pyx_PyImport_AddModuleRef((char*) __PYX_ABI_MODULE_NAME); +} + +/* FetchCommonType */ +static int __Pyx_VerifyCachedType(PyObject *cached_type, + const char *name, + Py_ssize_t basicsize, + Py_ssize_t expected_basicsize) { + if (!PyType_Check(cached_type)) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s is not a type object", name); + return -1; + } + if (basicsize != expected_basicsize) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s has the wrong size, try recompiling", + name); + return -1; + } + return 0; +} +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type) { + PyObject* abi_module; + const char* object_name; + PyTypeObject *cached_type = NULL; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + object_name = strrchr(type->tp_name, '.'); + object_name = object_name ? object_name+1 : type->tp_name; + cached_type = (PyTypeObject*) PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + if (__Pyx_VerifyCachedType( + (PyObject *)cached_type, + object_name, + cached_type->tp_basicsize, + type->tp_basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + if (PyType_Ready(type) < 0) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, (PyObject *)type) < 0) + goto bad; + Py_INCREF(type); + cached_type = type; +done: + Py_DECREF(abi_module); + return cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#else +static PyTypeObject *__Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases) { + PyObject *abi_module, *cached_type = NULL; + const char* object_name = strrchr(spec->name, '.'); + object_name = object_name ? object_name+1 : spec->name; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + cached_type = PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + Py_ssize_t basicsize; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *py_basicsize; + py_basicsize = PyObject_GetAttrString(cached_type, "__basicsize__"); + if (unlikely(!py_basicsize)) goto bad; + basicsize = PyLong_AsSsize_t(py_basicsize); + Py_DECREF(py_basicsize); + py_basicsize = 0; + if (unlikely(basicsize == (Py_ssize_t)-1) && PyErr_Occurred()) goto bad; +#else + basicsize = likely(PyType_Check(cached_type)) ? ((PyTypeObject*) cached_type)->tp_basicsize : -1; +#endif + if (__Pyx_VerifyCachedType( + cached_type, + object_name, + basicsize, + spec->basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + CYTHON_UNUSED_VAR(module); + cached_type = __Pyx_PyType_FromModuleAndSpec(abi_module, spec, bases); + if (unlikely(!cached_type)) goto bad; + if (unlikely(__Pyx_fix_up_extension_type_from_spec(spec, (PyTypeObject *) cached_type) < 0)) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, cached_type) < 0) goto bad; +done: + Py_DECREF(abi_module); + assert(cached_type == NULL || PyType_Check(cached_type)); + return (PyTypeObject *) cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#endif + +/* PyVectorcallFastCallDict */ +#if CYTHON_METH_FASTCALL +static PyObject *__Pyx_PyVectorcall_FastCallDict_kw(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + PyObject *res = NULL; + PyObject *kwnames; + PyObject **newargs; + PyObject **kwvalues; + Py_ssize_t i, pos; + size_t j; + PyObject *key, *value; + unsigned long keys_are_strings; + Py_ssize_t nkw = PyDict_GET_SIZE(kw); + newargs = (PyObject **)PyMem_Malloc((nargs + (size_t)nkw) * sizeof(args[0])); + if (unlikely(newargs == NULL)) { + PyErr_NoMemory(); + return NULL; + } + for (j = 0; j < nargs; j++) newargs[j] = args[j]; + kwnames = PyTuple_New(nkw); + if (unlikely(kwnames == NULL)) { + PyMem_Free(newargs); + return NULL; + } + kwvalues = newargs + nargs; + pos = i = 0; + keys_are_strings = Py_TPFLAGS_UNICODE_SUBCLASS; + while (PyDict_Next(kw, &pos, &key, &value)) { + keys_are_strings &= Py_TYPE(key)->tp_flags; + Py_INCREF(key); + Py_INCREF(value); + PyTuple_SET_ITEM(kwnames, i, key); + kwvalues[i] = value; + i++; + } + if (unlikely(!keys_are_strings)) { + PyErr_SetString(PyExc_TypeError, "keywords must be strings"); + goto cleanup; + } + res = vc(func, newargs, nargs, kwnames); +cleanup: + Py_DECREF(kwnames); + for (i = 0; i < nkw; i++) + Py_DECREF(kwvalues[i]); + PyMem_Free(newargs); + return res; +} +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + if (likely(kw == NULL) || PyDict_GET_SIZE(kw) == 0) { + return vc(func, args, nargs, NULL); + } + return __Pyx_PyVectorcall_FastCallDict_kw(func, vc, args, nargs, kw); +} +#endif + +/* CythonFunctionShared */ +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc) { + if (__Pyx_CyFunction_Check(func)) { + return PyCFunction_GetFunction(((__pyx_CyFunctionObject*)func)->func) == (PyCFunction) cfunc; + } else if (PyCFunction_Check(func)) { + return PyCFunction_GetFunction(func) == (PyCFunction) cfunc; + } + return 0; +} +#else +static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc) { + return __Pyx_CyOrPyCFunction_Check(func) && __Pyx_CyOrPyCFunction_GET_FUNCTION(func) == (PyCFunction) cfunc; +} +#endif +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj) { +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + __Pyx_Py_XDECREF_SET( + __Pyx_CyFunction_GetClassObj(f), + ((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#else + __Pyx_Py_XDECREF_SET( + ((PyCMethodObject *) (f))->mm_class, + (PyTypeObject*)((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#endif +} +static PyObject * +__Pyx_CyFunction_get_doc(__pyx_CyFunctionObject *op, void *closure) +{ + CYTHON_UNUSED_VAR(closure); + if (unlikely(op->func_doc == NULL)) { +#if CYTHON_COMPILING_IN_LIMITED_API + op->func_doc = PyObject_GetAttrString(op->func, "__doc__"); + if (unlikely(!op->func_doc)) return NULL; +#else + if (((PyCFunctionObject*)op)->m_ml->ml_doc) { +#if PY_MAJOR_VERSION >= 3 + op->func_doc = PyUnicode_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#else + op->func_doc = PyString_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#endif + if (unlikely(op->func_doc == NULL)) + return NULL; + } else { + Py_INCREF(Py_None); + return Py_None; + } +#endif + } + Py_INCREF(op->func_doc); + return op->func_doc; +} +static int +__Pyx_CyFunction_set_doc(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (value == NULL) { + value = Py_None; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_doc, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_name(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_name == NULL)) { +#if CYTHON_COMPILING_IN_LIMITED_API + op->func_name = PyObject_GetAttrString(op->func, "__name__"); +#elif PY_MAJOR_VERSION >= 3 + op->func_name = PyUnicode_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#else + op->func_name = PyString_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#endif + if (unlikely(op->func_name == NULL)) + return NULL; + } + Py_INCREF(op->func_name); + return op->func_name; +} +static int +__Pyx_CyFunction_set_name(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__name__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_name, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_qualname(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_qualname); + return op->func_qualname; +} +static int +__Pyx_CyFunction_set_qualname(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__qualname__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_qualname, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_dict(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_dict == NULL)) { + op->func_dict = PyDict_New(); + if (unlikely(op->func_dict == NULL)) + return NULL; + } + Py_INCREF(op->func_dict); + return op->func_dict; +} +static int +__Pyx_CyFunction_set_dict(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(value == NULL)) { + PyErr_SetString(PyExc_TypeError, + "function's dictionary may not be deleted"); + return -1; + } + if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "setting function's dictionary to a non-dict"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_dict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_globals(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_globals); + return op->func_globals; +} +static PyObject * +__Pyx_CyFunction_get_closure(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(op); + CYTHON_UNUSED_VAR(context); + Py_INCREF(Py_None); + return Py_None; +} +static PyObject * +__Pyx_CyFunction_get_code(__pyx_CyFunctionObject *op, void *context) +{ + PyObject* result = (op->func_code) ? op->func_code : Py_None; + CYTHON_UNUSED_VAR(context); + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_init_defaults(__pyx_CyFunctionObject *op) { + int result = 0; + PyObject *res = op->defaults_getter((PyObject *) op); + if (unlikely(!res)) + return -1; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + op->defaults_tuple = PyTuple_GET_ITEM(res, 0); + Py_INCREF(op->defaults_tuple); + op->defaults_kwdict = PyTuple_GET_ITEM(res, 1); + Py_INCREF(op->defaults_kwdict); + #else + op->defaults_tuple = __Pyx_PySequence_ITEM(res, 0); + if (unlikely(!op->defaults_tuple)) result = -1; + else { + op->defaults_kwdict = __Pyx_PySequence_ITEM(res, 1); + if (unlikely(!op->defaults_kwdict)) result = -1; + } + #endif + Py_DECREF(res); + return result; +} +static int +__Pyx_CyFunction_set_defaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyTuple_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__defaults__ must be set to a tuple object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__defaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_tuple, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_defaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_tuple; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_tuple; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_kwdefaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__kwdefaults__ must be set to a dict object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__kwdefaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_kwdict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_kwdefaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_kwdict; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_kwdict; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_annotations(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value || value == Py_None) { + value = NULL; + } else if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__annotations__ must be set to a dict object"); + return -1; + } + Py_XINCREF(value); + __Pyx_Py_XDECREF_SET(op->func_annotations, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_annotations(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->func_annotations; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + result = PyDict_New(); + if (unlikely(!result)) return NULL; + op->func_annotations = result; + } + Py_INCREF(result); + return result; +} +static PyObject * +__Pyx_CyFunction_get_is_coroutine(__pyx_CyFunctionObject *op, void *context) { + int is_coroutine; + CYTHON_UNUSED_VAR(context); + if (op->func_is_coroutine) { + return __Pyx_NewRef(op->func_is_coroutine); + } + is_coroutine = op->flags & __Pyx_CYFUNCTION_COROUTINE; +#if PY_VERSION_HEX >= 0x03050000 + if (is_coroutine) { + PyObject *module, *fromlist, *marker = __pyx_n_s_is_coroutine; + fromlist = PyList_New(1); + if (unlikely(!fromlist)) return NULL; + Py_INCREF(marker); +#if CYTHON_ASSUME_SAFE_MACROS + PyList_SET_ITEM(fromlist, 0, marker); +#else + if (unlikely(PyList_SetItem(fromlist, 0, marker) < 0)) { + Py_DECREF(marker); + Py_DECREF(fromlist); + return NULL; + } +#endif + module = PyImport_ImportModuleLevelObject(__pyx_n_s_asyncio_coroutines, NULL, NULL, fromlist, 0); + Py_DECREF(fromlist); + if (unlikely(!module)) goto ignore; + op->func_is_coroutine = __Pyx_PyObject_GetAttrStr(module, marker); + Py_DECREF(module); + if (likely(op->func_is_coroutine)) { + return __Pyx_NewRef(op->func_is_coroutine); + } +ignore: + PyErr_Clear(); + } +#endif + op->func_is_coroutine = __Pyx_PyBool_FromLong(is_coroutine); + return __Pyx_NewRef(op->func_is_coroutine); +} +#if CYTHON_COMPILING_IN_LIMITED_API +static PyObject * +__Pyx_CyFunction_get_module(__pyx_CyFunctionObject *op, void *context) { + CYTHON_UNUSED_VAR(context); + return PyObject_GetAttrString(op->func, "__module__"); +} +static int +__Pyx_CyFunction_set_module(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + return PyObject_SetAttrString(op->func, "__module__", value); +} +#endif +static PyGetSetDef __pyx_CyFunction_getsets[] = { + {(char *) "func_doc", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "__doc__", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "func_name", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__name__", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__qualname__", (getter)__Pyx_CyFunction_get_qualname, (setter)__Pyx_CyFunction_set_qualname, 0, 0}, + {(char *) "func_dict", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "__dict__", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "func_globals", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "__globals__", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "func_closure", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "__closure__", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "func_code", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "__code__", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "func_defaults", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__defaults__", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__kwdefaults__", (getter)__Pyx_CyFunction_get_kwdefaults, (setter)__Pyx_CyFunction_set_kwdefaults, 0, 0}, + {(char *) "__annotations__", (getter)__Pyx_CyFunction_get_annotations, (setter)__Pyx_CyFunction_set_annotations, 0, 0}, + {(char *) "_is_coroutine", (getter)__Pyx_CyFunction_get_is_coroutine, 0, 0, 0}, +#if CYTHON_COMPILING_IN_LIMITED_API + {"__module__", (getter)__Pyx_CyFunction_get_module, (setter)__Pyx_CyFunction_set_module, 0, 0}, +#endif + {0, 0, 0, 0, 0} +}; +static PyMemberDef __pyx_CyFunction_members[] = { +#if !CYTHON_COMPILING_IN_LIMITED_API + {(char *) "__module__", T_OBJECT, offsetof(PyCFunctionObject, m_module), 0, 0}, +#endif +#if CYTHON_USE_TYPE_SPECS + {(char *) "__dictoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_dict), READONLY, 0}, +#if CYTHON_METH_FASTCALL +#if CYTHON_BACKPORT_VECTORCALL + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_vectorcall), READONLY, 0}, +#else +#if !CYTHON_COMPILING_IN_LIMITED_API + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(PyCFunctionObject, vectorcall), READONLY, 0}, +#endif +#endif +#endif +#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_weakreflist), READONLY, 0}, +#else + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(PyCFunctionObject, m_weakreflist), READONLY, 0}, +#endif +#endif + {0, 0, 0, 0, 0} +}; +static PyObject * +__Pyx_CyFunction_reduce(__pyx_CyFunctionObject *m, PyObject *args) +{ + CYTHON_UNUSED_VAR(args); +#if PY_MAJOR_VERSION >= 3 + Py_INCREF(m->func_qualname); + return m->func_qualname; +#else + return PyString_FromString(((PyCFunctionObject*)m)->m_ml->ml_name); +#endif +} +static PyMethodDef __pyx_CyFunction_methods[] = { + {"__reduce__", (PyCFunction)__Pyx_CyFunction_reduce, METH_VARARGS, 0}, + {0, 0, 0, 0} +}; +#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API +#define __Pyx_CyFunction_weakreflist(cyfunc) ((cyfunc)->func_weakreflist) +#else +#define __Pyx_CyFunction_weakreflist(cyfunc) (((PyCFunctionObject*)cyfunc)->m_weakreflist) +#endif +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject *op, PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { +#if !CYTHON_COMPILING_IN_LIMITED_API + PyCFunctionObject *cf = (PyCFunctionObject*) op; +#endif + if (unlikely(op == NULL)) + return NULL; +#if CYTHON_COMPILING_IN_LIMITED_API + op->func = PyCFunction_NewEx(ml, (PyObject*)op, module); + if (unlikely(!op->func)) return NULL; +#endif + op->flags = flags; + __Pyx_CyFunction_weakreflist(op) = NULL; +#if !CYTHON_COMPILING_IN_LIMITED_API + cf->m_ml = ml; + cf->m_self = (PyObject *) op; +#endif + Py_XINCREF(closure); + op->func_closure = closure; +#if !CYTHON_COMPILING_IN_LIMITED_API + Py_XINCREF(module); + cf->m_module = module; +#endif + op->func_dict = NULL; + op->func_name = NULL; + Py_INCREF(qualname); + op->func_qualname = qualname; + op->func_doc = NULL; +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + op->func_classobj = NULL; +#else + ((PyCMethodObject*)op)->mm_class = NULL; +#endif + op->func_globals = globals; + Py_INCREF(op->func_globals); + Py_XINCREF(code); + op->func_code = code; + op->defaults_pyobjects = 0; + op->defaults_size = 0; + op->defaults = NULL; + op->defaults_tuple = NULL; + op->defaults_kwdict = NULL; + op->defaults_getter = NULL; + op->func_annotations = NULL; + op->func_is_coroutine = NULL; +#if CYTHON_METH_FASTCALL + switch (ml->ml_flags & (METH_VARARGS | METH_FASTCALL | METH_NOARGS | METH_O | METH_KEYWORDS | METH_METHOD)) { + case METH_NOARGS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_NOARGS; + break; + case METH_O: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_O; + break; + case METH_METHOD | METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD; + break; + case METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS; + break; + case METH_VARARGS | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = NULL; + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + Py_DECREF(op); + return NULL; + } +#endif + return (PyObject *) op; +} +static int +__Pyx_CyFunction_clear(__pyx_CyFunctionObject *m) +{ + Py_CLEAR(m->func_closure); +#if CYTHON_COMPILING_IN_LIMITED_API + Py_CLEAR(m->func); +#else + Py_CLEAR(((PyCFunctionObject*)m)->m_module); +#endif + Py_CLEAR(m->func_dict); + Py_CLEAR(m->func_name); + Py_CLEAR(m->func_qualname); + Py_CLEAR(m->func_doc); + Py_CLEAR(m->func_globals); + Py_CLEAR(m->func_code); +#if !CYTHON_COMPILING_IN_LIMITED_API +#if PY_VERSION_HEX < 0x030900B1 + Py_CLEAR(__Pyx_CyFunction_GetClassObj(m)); +#else + { + PyObject *cls = (PyObject*) ((PyCMethodObject *) (m))->mm_class; + ((PyCMethodObject *) (m))->mm_class = NULL; + Py_XDECREF(cls); + } +#endif +#endif + Py_CLEAR(m->defaults_tuple); + Py_CLEAR(m->defaults_kwdict); + Py_CLEAR(m->func_annotations); + Py_CLEAR(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_XDECREF(pydefaults[i]); + PyObject_Free(m->defaults); + m->defaults = NULL; + } + return 0; +} +static void __Pyx__CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + if (__Pyx_CyFunction_weakreflist(m) != NULL) + PyObject_ClearWeakRefs((PyObject *) m); + __Pyx_CyFunction_clear(m); + __Pyx_PyHeapTypeObject_GC_Del(m); +} +static void __Pyx_CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + PyObject_GC_UnTrack(m); + __Pyx__CyFunction_dealloc(m); +} +static int __Pyx_CyFunction_traverse(__pyx_CyFunctionObject *m, visitproc visit, void *arg) +{ + Py_VISIT(m->func_closure); +#if CYTHON_COMPILING_IN_LIMITED_API + Py_VISIT(m->func); +#else + Py_VISIT(((PyCFunctionObject*)m)->m_module); +#endif + Py_VISIT(m->func_dict); + Py_VISIT(m->func_name); + Py_VISIT(m->func_qualname); + Py_VISIT(m->func_doc); + Py_VISIT(m->func_globals); + Py_VISIT(m->func_code); +#if !CYTHON_COMPILING_IN_LIMITED_API + Py_VISIT(__Pyx_CyFunction_GetClassObj(m)); +#endif + Py_VISIT(m->defaults_tuple); + Py_VISIT(m->defaults_kwdict); + Py_VISIT(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_VISIT(pydefaults[i]); + } + return 0; +} +static PyObject* +__Pyx_CyFunction_repr(__pyx_CyFunctionObject *op) +{ +#if PY_MAJOR_VERSION >= 3 + return PyUnicode_FromFormat("", + op->func_qualname, (void *)op); +#else + return PyString_FromFormat("", + PyString_AsString(op->func_qualname), (void *)op); +#endif +} +static PyObject * __Pyx_CyFunction_CallMethod(PyObject *func, PyObject *self, PyObject *arg, PyObject *kw) { +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *f = ((__pyx_CyFunctionObject*)func)->func; + PyObject *py_name = NULL; + PyCFunction meth; + int flags; + meth = PyCFunction_GetFunction(f); + if (unlikely(!meth)) return NULL; + flags = PyCFunction_GetFlags(f); + if (unlikely(flags < 0)) return NULL; +#else + PyCFunctionObject* f = (PyCFunctionObject*)func; + PyCFunction meth = f->m_ml->ml_meth; + int flags = f->m_ml->ml_flags; +#endif + Py_ssize_t size; + switch (flags & (METH_VARARGS | METH_KEYWORDS | METH_NOARGS | METH_O)) { + case METH_VARARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) + return (*meth)(self, arg); + break; + case METH_VARARGS | METH_KEYWORDS: + return (*(PyCFunctionWithKeywords)(void*)meth)(self, arg, kw); + case METH_NOARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { +#if CYTHON_ASSUME_SAFE_MACROS + size = PyTuple_GET_SIZE(arg); +#else + size = PyTuple_Size(arg); + if (unlikely(size < 0)) return NULL; +#endif + if (likely(size == 0)) + return (*meth)(self, NULL); +#if CYTHON_COMPILING_IN_LIMITED_API + py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); + if (!py_name) return NULL; + PyErr_Format(PyExc_TypeError, + "%.200S() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + py_name, size); + Py_DECREF(py_name); +#else + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); +#endif + return NULL; + } + break; + case METH_O: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { +#if CYTHON_ASSUME_SAFE_MACROS + size = PyTuple_GET_SIZE(arg); +#else + size = PyTuple_Size(arg); + if (unlikely(size < 0)) return NULL; +#endif + if (likely(size == 1)) { + PyObject *result, *arg0; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + arg0 = PyTuple_GET_ITEM(arg, 0); + #else + arg0 = __Pyx_PySequence_ITEM(arg, 0); if (unlikely(!arg0)) return NULL; + #endif + result = (*meth)(self, arg0); + #if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(arg0); + #endif + return result; + } +#if CYTHON_COMPILING_IN_LIMITED_API + py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); + if (!py_name) return NULL; + PyErr_Format(PyExc_TypeError, + "%.200S() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + py_name, size); + Py_DECREF(py_name); +#else + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); +#endif + return NULL; + } + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + return NULL; + } +#if CYTHON_COMPILING_IN_LIMITED_API + py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); + if (!py_name) return NULL; + PyErr_Format(PyExc_TypeError, "%.200S() takes no keyword arguments", + py_name); + Py_DECREF(py_name); +#else + PyErr_Format(PyExc_TypeError, "%.200s() takes no keyword arguments", + f->m_ml->ml_name); +#endif + return NULL; +} +static CYTHON_INLINE PyObject *__Pyx_CyFunction_Call(PyObject *func, PyObject *arg, PyObject *kw) { + PyObject *self, *result; +#if CYTHON_COMPILING_IN_LIMITED_API + self = PyCFunction_GetSelf(((__pyx_CyFunctionObject*)func)->func); + if (unlikely(!self) && PyErr_Occurred()) return NULL; +#else + self = ((PyCFunctionObject*)func)->m_self; +#endif + result = __Pyx_CyFunction_CallMethod(func, self, arg, kw); + return result; +} +static PyObject *__Pyx_CyFunction_CallAsMethod(PyObject *func, PyObject *args, PyObject *kw) { + PyObject *result; + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *) func; +#if CYTHON_METH_FASTCALL + __pyx_vectorcallfunc vc = __Pyx_CyFunction_func_vectorcall(cyfunc); + if (vc) { +#if CYTHON_ASSUME_SAFE_MACROS + return __Pyx_PyVectorcall_FastCallDict(func, vc, &PyTuple_GET_ITEM(args, 0), (size_t)PyTuple_GET_SIZE(args), kw); +#else + (void) &__Pyx_PyVectorcall_FastCallDict; + return PyVectorcall_Call(func, args, kw); +#endif + } +#endif + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + Py_ssize_t argc; + PyObject *new_args; + PyObject *self; +#if CYTHON_ASSUME_SAFE_MACROS + argc = PyTuple_GET_SIZE(args); +#else + argc = PyTuple_Size(args); + if (unlikely(!argc) < 0) return NULL; +#endif + new_args = PyTuple_GetSlice(args, 1, argc); + if (unlikely(!new_args)) + return NULL; + self = PyTuple_GetItem(args, 0); + if (unlikely(!self)) { + Py_DECREF(new_args); +#if PY_MAJOR_VERSION > 2 + PyErr_Format(PyExc_TypeError, + "unbound method %.200S() needs an argument", + cyfunc->func_qualname); +#else + PyErr_SetString(PyExc_TypeError, + "unbound method needs an argument"); +#endif + return NULL; + } + result = __Pyx_CyFunction_CallMethod(func, self, new_args, kw); + Py_DECREF(new_args); + } else { + result = __Pyx_CyFunction_Call(func, args, kw); + } + return result; +} +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE int __Pyx_CyFunction_Vectorcall_CheckArgs(__pyx_CyFunctionObject *cyfunc, Py_ssize_t nargs, PyObject *kwnames) +{ + int ret = 0; + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + if (unlikely(nargs < 1)) { + PyErr_Format(PyExc_TypeError, "%.200s() needs an argument", + ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + ret = 1; + } + if (unlikely(kwnames) && unlikely(PyTuple_GET_SIZE(kwnames))) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no keyword arguments", ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + return ret; +} +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 0)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, NULL); +} +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 1)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, args[0]); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((_PyCFunctionFastWithKeywords)(void(*)(void))def->ml_meth)(self, args, nargs, kwnames); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; + PyTypeObject *cls = (PyTypeObject *) __Pyx_CyFunction_GetClassObj(cyfunc); +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((__Pyx_PyCMethod)(void(*)(void))def->ml_meth)(self, cls, args, (size_t)nargs, kwnames); +} +#endif +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_CyFunctionType_slots[] = { + {Py_tp_dealloc, (void *)__Pyx_CyFunction_dealloc}, + {Py_tp_repr, (void *)__Pyx_CyFunction_repr}, + {Py_tp_call, (void *)__Pyx_CyFunction_CallAsMethod}, + {Py_tp_traverse, (void *)__Pyx_CyFunction_traverse}, + {Py_tp_clear, (void *)__Pyx_CyFunction_clear}, + {Py_tp_methods, (void *)__pyx_CyFunction_methods}, + {Py_tp_members, (void *)__pyx_CyFunction_members}, + {Py_tp_getset, (void *)__pyx_CyFunction_getsets}, + {Py_tp_descr_get, (void *)__Pyx_PyMethod_New}, + {0, 0}, +}; +static PyType_Spec __pyx_CyFunctionType_spec = { + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#if (defined(_Py_TPFLAGS_HAVE_VECTORCALL) && CYTHON_METH_FASTCALL) + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + __pyx_CyFunctionType_slots +}; +#else +static PyTypeObject __pyx_CyFunctionType_type = { + PyVarObject_HEAD_INIT(0, 0) + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, + (destructor) __Pyx_CyFunction_dealloc, +#if !CYTHON_METH_FASTCALL + 0, +#elif CYTHON_BACKPORT_VECTORCALL + (printfunc)offsetof(__pyx_CyFunctionObject, func_vectorcall), +#else + offsetof(PyCFunctionObject, vectorcall), +#endif + 0, + 0, +#if PY_MAJOR_VERSION < 3 + 0, +#else + 0, +#endif + (reprfunc) __Pyx_CyFunction_repr, + 0, + 0, + 0, + 0, + __Pyx_CyFunction_CallAsMethod, + 0, + 0, + 0, + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#if defined(_Py_TPFLAGS_HAVE_VECTORCALL) && CYTHON_METH_FASTCALL + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + 0, + (traverseproc) __Pyx_CyFunction_traverse, + (inquiry) __Pyx_CyFunction_clear, + 0, +#if PY_VERSION_HEX < 0x030500A0 + offsetof(__pyx_CyFunctionObject, func_weakreflist), +#else + offsetof(PyCFunctionObject, m_weakreflist), +#endif + 0, + 0, + __pyx_CyFunction_methods, + __pyx_CyFunction_members, + __pyx_CyFunction_getsets, + 0, + 0, + __Pyx_PyMethod_New, + 0, + offsetof(__pyx_CyFunctionObject, func_dict), + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, +#if PY_VERSION_HEX >= 0x030400a1 + 0, +#endif +#if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, +#endif +#if __PYX_NEED_TP_PRINT_SLOT + 0, +#endif +#if PY_VERSION_HEX >= 0x030C0000 + 0, +#endif +#if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, +#endif +}; +#endif +static int __pyx_CyFunction_init(PyObject *module) { +#if CYTHON_USE_TYPE_SPECS + __pyx_CyFunctionType = __Pyx_FetchCommonTypeFromSpec(module, &__pyx_CyFunctionType_spec, NULL); +#else + CYTHON_UNUSED_VAR(module); + __pyx_CyFunctionType = __Pyx_FetchCommonType(&__pyx_CyFunctionType_type); +#endif + if (unlikely(__pyx_CyFunctionType == NULL)) { + return -1; + } + return 0; +} +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *func, size_t size, int pyobjects) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults = PyObject_Malloc(size); + if (unlikely(!m->defaults)) + return PyErr_NoMemory(); + memset(m->defaults, 0, size); + m->defaults_pyobjects = pyobjects; + m->defaults_size = size; + return m->defaults; +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *func, PyObject *tuple) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_tuple = tuple; + Py_INCREF(tuple); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_kwdict = dict; + Py_INCREF(dict); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->func_annotations = dict; + Py_INCREF(dict); +} + +/* CythonFunction */ +static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { + PyObject *op = __Pyx_CyFunction_Init( + PyObject_GC_New(__pyx_CyFunctionObject, __pyx_CyFunctionType), + ml, flags, qualname, closure, module, globals, code + ); + if (likely(op)) { + PyObject_GC_Track(op); + } + return op; +} + +/* CLineInTraceback */ +#ifndef CYTHON_CLINE_IN_TRACEBACK +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line) { + PyObject *use_cline; + PyObject *ptype, *pvalue, *ptraceback; +#if CYTHON_COMPILING_IN_CPYTHON + PyObject **cython_runtime_dict; +#endif + CYTHON_MAYBE_UNUSED_VAR(tstate); + if (unlikely(!__pyx_cython_runtime)) { + return c_line; + } + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); +#if CYTHON_COMPILING_IN_CPYTHON + cython_runtime_dict = _PyObject_GetDictPtr(__pyx_cython_runtime); + if (likely(cython_runtime_dict)) { + __PYX_PY_DICT_LOOKUP_IF_MODIFIED( + use_cline, *cython_runtime_dict, + __Pyx_PyDict_GetItemStr(*cython_runtime_dict, __pyx_n_s_cline_in_traceback)) + } else +#endif + { + PyObject *use_cline_obj = __Pyx_PyObject_GetAttrStrNoError(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback); + if (use_cline_obj) { + use_cline = PyObject_Not(use_cline_obj) ? Py_False : Py_True; + Py_DECREF(use_cline_obj); + } else { + PyErr_Clear(); + use_cline = NULL; + } + } + if (!use_cline) { + c_line = 0; + (void) PyObject_SetAttr(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback, Py_False); + } + else if (use_cline == Py_False || (use_cline != Py_True && PyObject_Not(use_cline) != 0)) { + c_line = 0; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + return c_line; +} +#endif + +/* CodeObjectCache */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line) { + int start = 0, mid = 0, end = count - 1; + if (end >= 0 && code_line > entries[end].code_line) { + return count; + } + while (start < end) { + mid = start + (end - start) / 2; + if (code_line < entries[mid].code_line) { + end = mid; + } else if (code_line > entries[mid].code_line) { + start = mid + 1; + } else { + return mid; + } + } + if (code_line <= entries[mid].code_line) { + return mid; + } else { + return mid + 1; + } +} +static PyCodeObject *__pyx_find_code_object(int code_line) { + PyCodeObject* code_object; + int pos; + if (unlikely(!code_line) || unlikely(!__pyx_code_cache.entries)) { + return NULL; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if (unlikely(pos >= __pyx_code_cache.count) || unlikely(__pyx_code_cache.entries[pos].code_line != code_line)) { + return NULL; + } + code_object = __pyx_code_cache.entries[pos].code_object; + Py_INCREF(code_object); + return code_object; +} +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object) { + int pos, i; + __Pyx_CodeObjectCacheEntry* entries = __pyx_code_cache.entries; + if (unlikely(!code_line)) { + return; + } + if (unlikely(!entries)) { + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Malloc(64*sizeof(__Pyx_CodeObjectCacheEntry)); + if (likely(entries)) { + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = 64; + __pyx_code_cache.count = 1; + entries[0].code_line = code_line; + entries[0].code_object = code_object; + Py_INCREF(code_object); + } + return; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if ((pos < __pyx_code_cache.count) && unlikely(__pyx_code_cache.entries[pos].code_line == code_line)) { + PyCodeObject* tmp = entries[pos].code_object; + entries[pos].code_object = code_object; + Py_DECREF(tmp); + return; + } + if (__pyx_code_cache.count == __pyx_code_cache.max_count) { + int new_max = __pyx_code_cache.max_count + 64; + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Realloc( + __pyx_code_cache.entries, ((size_t)new_max) * sizeof(__Pyx_CodeObjectCacheEntry)); + if (unlikely(!entries)) { + return; + } + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = new_max; + } + for (i=__pyx_code_cache.count; i>pos; i--) { + entries[i] = entries[i-1]; + } + entries[pos].code_line = code_line; + entries[pos].code_object = code_object; + __pyx_code_cache.count++; + Py_INCREF(code_object); +} +#endif + +/* AddTraceback */ +#include "compile.h" +#include "frameobject.h" +#include "traceback.h" +#if PY_VERSION_HEX >= 0x030b00a6 && !CYTHON_COMPILING_IN_LIMITED_API + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static PyObject *__Pyx_PyCode_Replace_For_AddTraceback(PyObject *code, PyObject *scratch_dict, + PyObject *firstlineno, PyObject *name) { + PyObject *replace = NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "co_firstlineno", firstlineno))) return NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "co_name", name))) return NULL; + replace = PyObject_GetAttrString(code, "replace"); + if (likely(replace)) { + PyObject *result; + result = PyObject_Call(replace, __pyx_empty_tuple, scratch_dict); + Py_DECREF(replace); + return result; + } + PyErr_Clear(); + #if __PYX_LIMITED_VERSION_HEX < 0x030780000 + { + PyObject *compiled = NULL, *result = NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "code", code))) return NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "type", (PyObject*)(&PyType_Type)))) return NULL; + compiled = Py_CompileString( + "out = type(code)(\n" + " code.co_argcount, code.co_kwonlyargcount, code.co_nlocals, code.co_stacksize,\n" + " code.co_flags, code.co_code, code.co_consts, code.co_names,\n" + " code.co_varnames, code.co_filename, co_name, co_firstlineno,\n" + " code.co_lnotab)\n", "", Py_file_input); + if (!compiled) return NULL; + result = PyEval_EvalCode(compiled, scratch_dict, scratch_dict); + Py_DECREF(compiled); + if (!result) PyErr_Print(); + Py_DECREF(result); + result = PyDict_GetItemString(scratch_dict, "out"); + if (result) Py_INCREF(result); + return result; + } + #else + return NULL; + #endif +} +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + PyObject *code_object = NULL, *py_py_line = NULL, *py_funcname = NULL, *dict = NULL; + PyObject *replace = NULL, *getframe = NULL, *frame = NULL; + PyObject *exc_type, *exc_value, *exc_traceback; + int success = 0; + if (c_line) { + (void) __pyx_cfilenm; + (void) __Pyx_CLineForTraceback(__Pyx_PyThreadState_Current, c_line); + } + PyErr_Fetch(&exc_type, &exc_value, &exc_traceback); + code_object = Py_CompileString("_getframe()", filename, Py_eval_input); + if (unlikely(!code_object)) goto bad; + py_py_line = PyLong_FromLong(py_line); + if (unlikely(!py_py_line)) goto bad; + py_funcname = PyUnicode_FromString(funcname); + if (unlikely(!py_funcname)) goto bad; + dict = PyDict_New(); + if (unlikely(!dict)) goto bad; + { + PyObject *old_code_object = code_object; + code_object = __Pyx_PyCode_Replace_For_AddTraceback(code_object, dict, py_py_line, py_funcname); + Py_DECREF(old_code_object); + } + if (unlikely(!code_object)) goto bad; + getframe = PySys_GetObject("_getframe"); + if (unlikely(!getframe)) goto bad; + if (unlikely(PyDict_SetItemString(dict, "_getframe", getframe))) goto bad; + frame = PyEval_EvalCode(code_object, dict, dict); + if (unlikely(!frame) || frame == Py_None) goto bad; + success = 1; + bad: + PyErr_Restore(exc_type, exc_value, exc_traceback); + Py_XDECREF(code_object); + Py_XDECREF(py_py_line); + Py_XDECREF(py_funcname); + Py_XDECREF(dict); + Py_XDECREF(replace); + if (success) { + PyTraceBack_Here( + (struct _frame*)frame); + } + Py_XDECREF(frame); +} +#else +static PyCodeObject* __Pyx_CreateCodeObjectForTraceback( + const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = NULL; + PyObject *py_funcname = NULL; + #if PY_MAJOR_VERSION < 3 + PyObject *py_srcfile = NULL; + py_srcfile = PyString_FromString(filename); + if (!py_srcfile) goto bad; + #endif + if (c_line) { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + #else + py_funcname = PyUnicode_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + funcname = PyUnicode_AsUTF8(py_funcname); + if (!funcname) goto bad; + #endif + } + else { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromString(funcname); + if (!py_funcname) goto bad; + #endif + } + #if PY_MAJOR_VERSION < 3 + py_code = __Pyx_PyCode_New( + 0, + 0, + 0, + 0, + 0, + 0, + __pyx_empty_bytes, /*PyObject *code,*/ + __pyx_empty_tuple, /*PyObject *consts,*/ + __pyx_empty_tuple, /*PyObject *names,*/ + __pyx_empty_tuple, /*PyObject *varnames,*/ + __pyx_empty_tuple, /*PyObject *freevars,*/ + __pyx_empty_tuple, /*PyObject *cellvars,*/ + py_srcfile, /*PyObject *filename,*/ + py_funcname, /*PyObject *name,*/ + py_line, + __pyx_empty_bytes /*PyObject *lnotab*/ + ); + Py_DECREF(py_srcfile); + #else + py_code = PyCode_NewEmpty(filename, funcname, py_line); + #endif + Py_XDECREF(py_funcname); + return py_code; +bad: + Py_XDECREF(py_funcname); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_srcfile); + #endif + return NULL; +} +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = 0; + PyFrameObject *py_frame = 0; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject *ptype, *pvalue, *ptraceback; + if (c_line) { + c_line = __Pyx_CLineForTraceback(tstate, c_line); + } + py_code = __pyx_find_code_object(c_line ? -c_line : py_line); + if (!py_code) { + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); + py_code = __Pyx_CreateCodeObjectForTraceback( + funcname, c_line, py_line, filename); + if (!py_code) { + /* If the code object creation fails, then we should clear the + fetched exception references and propagate the new exception */ + Py_XDECREF(ptype); + Py_XDECREF(pvalue); + Py_XDECREF(ptraceback); + goto bad; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + __pyx_insert_code_object(c_line ? -c_line : py_line, py_code); + } + py_frame = PyFrame_New( + tstate, /*PyThreadState *tstate,*/ + py_code, /*PyCodeObject *code,*/ + __pyx_d, /*PyObject *globals,*/ + 0 /*PyObject *locals*/ + ); + if (!py_frame) goto bad; + __Pyx_PyFrame_SetLineNumber(py_frame, py_line); + PyTraceBack_Here(py_frame); +bad: + Py_XDECREF(py_code); + Py_XDECREF(py_frame); +} +#endif + +#if PY_MAJOR_VERSION < 3 +static int __Pyx_GetBuffer(PyObject *obj, Py_buffer *view, int flags) { + __Pyx_TypeName obj_type_name; + if (PyObject_CheckBuffer(obj)) return PyObject_GetBuffer(obj, view, flags); + if (__Pyx_TypeCheck(obj, __pyx_array_type)) return __pyx_array_getbuffer(obj, view, flags); + if (__Pyx_TypeCheck(obj, __pyx_memoryview_type)) return __pyx_memoryview_getbuffer(obj, view, flags); + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "'" __Pyx_FMT_TYPENAME "' does not have the buffer interface", + obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return -1; +} +static void __Pyx_ReleaseBuffer(Py_buffer *view) { + PyObject *obj = view->obj; + if (!obj) return; + if (PyObject_CheckBuffer(obj)) { + PyBuffer_Release(view); + return; + } + if ((0)) {} + view->obj = NULL; + Py_DECREF(obj); +} +#endif + + +/* MemviewSliceIsContig */ +static int +__pyx_memviewslice_is_contig(const __Pyx_memviewslice mvs, char order, int ndim) +{ + int i, index, step, start; + Py_ssize_t itemsize = mvs.memview->view.itemsize; + if (order == 'F') { + step = 1; + start = 0; + } else { + step = -1; + start = ndim - 1; + } + for (i = 0; i < ndim; i++) { + index = start + step * i; + if (mvs.suboffsets[index] >= 0 || mvs.strides[index] != itemsize) + return 0; + itemsize *= mvs.shape[index]; + } + return 1; +} + +/* OverlappingSlices */ +static void +__pyx_get_array_memory_extents(__Pyx_memviewslice *slice, + void **out_start, void **out_end, + int ndim, size_t itemsize) +{ + char *start, *end; + int i; + start = end = slice->data; + for (i = 0; i < ndim; i++) { + Py_ssize_t stride = slice->strides[i]; + Py_ssize_t extent = slice->shape[i]; + if (extent == 0) { + *out_start = *out_end = start; + return; + } else { + if (stride > 0) + end += stride * (extent - 1); + else + start += stride * (extent - 1); + } + } + *out_start = start; + *out_end = end + itemsize; +} +static int +__pyx_slices_overlap(__Pyx_memviewslice *slice1, + __Pyx_memviewslice *slice2, + int ndim, size_t itemsize) +{ + void *start1, *end1, *start2, *end2; + __pyx_get_array_memory_extents(slice1, &start1, &end1, ndim, itemsize); + __pyx_get_array_memory_extents(slice2, &start2, &end2, ndim, itemsize); + return (start1 < end2) && (start2 < end1); +} + +/* IsLittleEndian */ +static CYTHON_INLINE int __Pyx_Is_Little_Endian(void) +{ + union { + uint32_t u32; + uint8_t u8[4]; + } S; + S.u32 = 0x01020304; + return S.u8[0] == 4; +} + +/* BufferFormatCheck */ +static void __Pyx_BufFmt_Init(__Pyx_BufFmt_Context* ctx, + __Pyx_BufFmt_StackElem* stack, + __Pyx_TypeInfo* type) { + stack[0].field = &ctx->root; + stack[0].parent_offset = 0; + ctx->root.type = type; + ctx->root.name = "buffer dtype"; + ctx->root.offset = 0; + ctx->head = stack; + ctx->head->field = &ctx->root; + ctx->fmt_offset = 0; + ctx->head->parent_offset = 0; + ctx->new_packmode = '@'; + ctx->enc_packmode = '@'; + ctx->new_count = 1; + ctx->enc_count = 0; + ctx->enc_type = 0; + ctx->is_complex = 0; + ctx->is_valid_array = 0; + ctx->struct_alignment = 0; + while (type->typegroup == 'S') { + ++ctx->head; + ctx->head->field = type->fields; + ctx->head->parent_offset = 0; + type = type->fields->type; + } +} +static int __Pyx_BufFmt_ParseNumber(const char** ts) { + int count; + const char* t = *ts; + if (*t < '0' || *t > '9') { + return -1; + } else { + count = *t++ - '0'; + while (*t >= '0' && *t <= '9') { + count *= 10; + count += *t++ - '0'; + } + } + *ts = t; + return count; +} +static int __Pyx_BufFmt_ExpectNumber(const char **ts) { + int number = __Pyx_BufFmt_ParseNumber(ts); + if (number == -1) + PyErr_Format(PyExc_ValueError,\ + "Does not understand character buffer dtype format string ('%c')", **ts); + return number; +} +static void __Pyx_BufFmt_RaiseUnexpectedChar(char ch) { + PyErr_Format(PyExc_ValueError, + "Unexpected format string character: '%c'", ch); +} +static const char* __Pyx_BufFmt_DescribeTypeChar(char ch, int is_complex) { + switch (ch) { + case '?': return "'bool'"; + case 'c': return "'char'"; + case 'b': return "'signed char'"; + case 'B': return "'unsigned char'"; + case 'h': return "'short'"; + case 'H': return "'unsigned short'"; + case 'i': return "'int'"; + case 'I': return "'unsigned int'"; + case 'l': return "'long'"; + case 'L': return "'unsigned long'"; + case 'q': return "'long long'"; + case 'Q': return "'unsigned long long'"; + case 'f': return (is_complex ? "'complex float'" : "'float'"); + case 'd': return (is_complex ? "'complex double'" : "'double'"); + case 'g': return (is_complex ? "'complex long double'" : "'long double'"); + case 'T': return "a struct"; + case 'O': return "Python object"; + case 'P': return "a pointer"; + case 's': case 'p': return "a string"; + case 0: return "end"; + default: return "unparsable format string"; + } +} +static size_t __Pyx_BufFmt_TypeCharToStandardSize(char ch, int is_complex) { + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return 2; + case 'i': case 'I': case 'l': case 'L': return 4; + case 'q': case 'Q': return 8; + case 'f': return (is_complex ? 8 : 4); + case 'd': return (is_complex ? 16 : 8); + case 'g': { + PyErr_SetString(PyExc_ValueError, "Python does not define a standard format string size for long double ('g').."); + return 0; + } + case 'O': case 'P': return sizeof(void*); + default: + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } +} +static size_t __Pyx_BufFmt_TypeCharToNativeSize(char ch, int is_complex) { + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return sizeof(short); + case 'i': case 'I': return sizeof(int); + case 'l': case 'L': return sizeof(long); + #ifdef HAVE_LONG_LONG + case 'q': case 'Q': return sizeof(PY_LONG_LONG); + #endif + case 'f': return sizeof(float) * (is_complex ? 2 : 1); + case 'd': return sizeof(double) * (is_complex ? 2 : 1); + case 'g': return sizeof(long double) * (is_complex ? 2 : 1); + case 'O': case 'P': return sizeof(void*); + default: { + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } + } +} +typedef struct { char c; short x; } __Pyx_st_short; +typedef struct { char c; int x; } __Pyx_st_int; +typedef struct { char c; long x; } __Pyx_st_long; +typedef struct { char c; float x; } __Pyx_st_float; +typedef struct { char c; double x; } __Pyx_st_double; +typedef struct { char c; long double x; } __Pyx_st_longdouble; +typedef struct { char c; void *x; } __Pyx_st_void_p; +#ifdef HAVE_LONG_LONG +typedef struct { char c; PY_LONG_LONG x; } __Pyx_st_longlong; +#endif +static size_t __Pyx_BufFmt_TypeCharToAlignment(char ch, int is_complex) { + CYTHON_UNUSED_VAR(is_complex); + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return sizeof(__Pyx_st_short) - sizeof(short); + case 'i': case 'I': return sizeof(__Pyx_st_int) - sizeof(int); + case 'l': case 'L': return sizeof(__Pyx_st_long) - sizeof(long); +#ifdef HAVE_LONG_LONG + case 'q': case 'Q': return sizeof(__Pyx_st_longlong) - sizeof(PY_LONG_LONG); +#endif + case 'f': return sizeof(__Pyx_st_float) - sizeof(float); + case 'd': return sizeof(__Pyx_st_double) - sizeof(double); + case 'g': return sizeof(__Pyx_st_longdouble) - sizeof(long double); + case 'P': case 'O': return sizeof(__Pyx_st_void_p) - sizeof(void*); + default: + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } +} +/* These are for computing the padding at the end of the struct to align + on the first member of the struct. This will probably the same as above, + but we don't have any guarantees. + */ +typedef struct { short x; char c; } __Pyx_pad_short; +typedef struct { int x; char c; } __Pyx_pad_int; +typedef struct { long x; char c; } __Pyx_pad_long; +typedef struct { float x; char c; } __Pyx_pad_float; +typedef struct { double x; char c; } __Pyx_pad_double; +typedef struct { long double x; char c; } __Pyx_pad_longdouble; +typedef struct { void *x; char c; } __Pyx_pad_void_p; +#ifdef HAVE_LONG_LONG +typedef struct { PY_LONG_LONG x; char c; } __Pyx_pad_longlong; +#endif +static size_t __Pyx_BufFmt_TypeCharToPadding(char ch, int is_complex) { + CYTHON_UNUSED_VAR(is_complex); + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return sizeof(__Pyx_pad_short) - sizeof(short); + case 'i': case 'I': return sizeof(__Pyx_pad_int) - sizeof(int); + case 'l': case 'L': return sizeof(__Pyx_pad_long) - sizeof(long); +#ifdef HAVE_LONG_LONG + case 'q': case 'Q': return sizeof(__Pyx_pad_longlong) - sizeof(PY_LONG_LONG); +#endif + case 'f': return sizeof(__Pyx_pad_float) - sizeof(float); + case 'd': return sizeof(__Pyx_pad_double) - sizeof(double); + case 'g': return sizeof(__Pyx_pad_longdouble) - sizeof(long double); + case 'P': case 'O': return sizeof(__Pyx_pad_void_p) - sizeof(void*); + default: + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } +} +static char __Pyx_BufFmt_TypeCharToGroup(char ch, int is_complex) { + switch (ch) { + case 'c': + return 'H'; + case 'b': case 'h': case 'i': + case 'l': case 'q': case 's': case 'p': + return 'I'; + case '?': case 'B': case 'H': case 'I': case 'L': case 'Q': + return 'U'; + case 'f': case 'd': case 'g': + return (is_complex ? 'C' : 'R'); + case 'O': + return 'O'; + case 'P': + return 'P'; + default: { + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } + } +} +static void __Pyx_BufFmt_RaiseExpected(__Pyx_BufFmt_Context* ctx) { + if (ctx->head == NULL || ctx->head->field == &ctx->root) { + const char* expected; + const char* quote; + if (ctx->head == NULL) { + expected = "end"; + quote = ""; + } else { + expected = ctx->head->field->type->name; + quote = "'"; + } + PyErr_Format(PyExc_ValueError, + "Buffer dtype mismatch, expected %s%s%s but got %s", + quote, expected, quote, + __Pyx_BufFmt_DescribeTypeChar(ctx->enc_type, ctx->is_complex)); + } else { + __Pyx_StructField* field = ctx->head->field; + __Pyx_StructField* parent = (ctx->head - 1)->field; + PyErr_Format(PyExc_ValueError, + "Buffer dtype mismatch, expected '%s' but got %s in '%s.%s'", + field->type->name, __Pyx_BufFmt_DescribeTypeChar(ctx->enc_type, ctx->is_complex), + parent->type->name, field->name); + } +} +static int __Pyx_BufFmt_ProcessTypeChunk(__Pyx_BufFmt_Context* ctx) { + char group; + size_t size, offset, arraysize = 1; + if (ctx->enc_type == 0) return 0; + if (ctx->head->field->type->arraysize[0]) { + int i, ndim = 0; + if (ctx->enc_type == 's' || ctx->enc_type == 'p') { + ctx->is_valid_array = ctx->head->field->type->ndim == 1; + ndim = 1; + if (ctx->enc_count != ctx->head->field->type->arraysize[0]) { + PyErr_Format(PyExc_ValueError, + "Expected a dimension of size %zu, got %zu", + ctx->head->field->type->arraysize[0], ctx->enc_count); + return -1; + } + } + if (!ctx->is_valid_array) { + PyErr_Format(PyExc_ValueError, "Expected %d dimensions, got %d", + ctx->head->field->type->ndim, ndim); + return -1; + } + for (i = 0; i < ctx->head->field->type->ndim; i++) { + arraysize *= ctx->head->field->type->arraysize[i]; + } + ctx->is_valid_array = 0; + ctx->enc_count = 1; + } + group = __Pyx_BufFmt_TypeCharToGroup(ctx->enc_type, ctx->is_complex); + do { + __Pyx_StructField* field = ctx->head->field; + __Pyx_TypeInfo* type = field->type; + if (ctx->enc_packmode == '@' || ctx->enc_packmode == '^') { + size = __Pyx_BufFmt_TypeCharToNativeSize(ctx->enc_type, ctx->is_complex); + } else { + size = __Pyx_BufFmt_TypeCharToStandardSize(ctx->enc_type, ctx->is_complex); + } + if (ctx->enc_packmode == '@') { + size_t align_at = __Pyx_BufFmt_TypeCharToAlignment(ctx->enc_type, ctx->is_complex); + size_t align_mod_offset; + if (align_at == 0) return -1; + align_mod_offset = ctx->fmt_offset % align_at; + if (align_mod_offset > 0) ctx->fmt_offset += align_at - align_mod_offset; + if (ctx->struct_alignment == 0) + ctx->struct_alignment = __Pyx_BufFmt_TypeCharToPadding(ctx->enc_type, + ctx->is_complex); + } + if (type->size != size || type->typegroup != group) { + if (type->typegroup == 'C' && type->fields != NULL) { + size_t parent_offset = ctx->head->parent_offset + field->offset; + ++ctx->head; + ctx->head->field = type->fields; + ctx->head->parent_offset = parent_offset; + continue; + } + if ((type->typegroup == 'H' || group == 'H') && type->size == size) { + } else { + __Pyx_BufFmt_RaiseExpected(ctx); + return -1; + } + } + offset = ctx->head->parent_offset + field->offset; + if (ctx->fmt_offset != offset) { + PyErr_Format(PyExc_ValueError, + "Buffer dtype mismatch; next field is at offset %" CYTHON_FORMAT_SSIZE_T "d but %" CYTHON_FORMAT_SSIZE_T "d expected", + (Py_ssize_t)ctx->fmt_offset, (Py_ssize_t)offset); + return -1; + } + ctx->fmt_offset += size; + if (arraysize) + ctx->fmt_offset += (arraysize - 1) * size; + --ctx->enc_count; + while (1) { + if (field == &ctx->root) { + ctx->head = NULL; + if (ctx->enc_count != 0) { + __Pyx_BufFmt_RaiseExpected(ctx); + return -1; + } + break; + } + ctx->head->field = ++field; + if (field->type == NULL) { + --ctx->head; + field = ctx->head->field; + continue; + } else if (field->type->typegroup == 'S') { + size_t parent_offset = ctx->head->parent_offset + field->offset; + if (field->type->fields->type == NULL) continue; + field = field->type->fields; + ++ctx->head; + ctx->head->field = field; + ctx->head->parent_offset = parent_offset; + break; + } else { + break; + } + } + } while (ctx->enc_count); + ctx->enc_type = 0; + ctx->is_complex = 0; + return 0; +} +static int +__pyx_buffmt_parse_array(__Pyx_BufFmt_Context* ctx, const char** tsp) +{ + const char *ts = *tsp; + int i = 0, number, ndim; + ++ts; + if (ctx->new_count != 1) { + PyErr_SetString(PyExc_ValueError, + "Cannot handle repeated arrays in format string"); + return -1; + } + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return -1; + ndim = ctx->head->field->type->ndim; + while (*ts && *ts != ')') { + switch (*ts) { + case ' ': case '\f': case '\r': case '\n': case '\t': case '\v': continue; + default: break; + } + number = __Pyx_BufFmt_ExpectNumber(&ts); + if (number == -1) return -1; + if (i < ndim && (size_t) number != ctx->head->field->type->arraysize[i]) { + PyErr_Format(PyExc_ValueError, + "Expected a dimension of size %zu, got %d", + ctx->head->field->type->arraysize[i], number); + return -1; + } + if (*ts != ',' && *ts != ')') { + PyErr_Format(PyExc_ValueError, + "Expected a comma in format string, got '%c'", *ts); + return -1; + } + if (*ts == ',') ts++; + i++; + } + if (i != ndim) { + PyErr_Format(PyExc_ValueError, "Expected %d dimension(s), got %d", + ctx->head->field->type->ndim, i); + return -1; + } + if (!*ts) { + PyErr_SetString(PyExc_ValueError, + "Unexpected end of format string, expected ')'"); + return -1; + } + ctx->is_valid_array = 1; + ctx->new_count = 1; + *tsp = ++ts; + return 0; +} +static const char* __Pyx_BufFmt_CheckString(__Pyx_BufFmt_Context* ctx, const char* ts) { + int got_Z = 0; + while (1) { + switch(*ts) { + case 0: + if (ctx->enc_type != 0 && ctx->head == NULL) { + __Pyx_BufFmt_RaiseExpected(ctx); + return NULL; + } + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + if (ctx->head != NULL) { + __Pyx_BufFmt_RaiseExpected(ctx); + return NULL; + } + return ts; + case ' ': + case '\r': + case '\n': + ++ts; + break; + case '<': + if (!__Pyx_Is_Little_Endian()) { + PyErr_SetString(PyExc_ValueError, "Little-endian buffer not supported on big-endian compiler"); + return NULL; + } + ctx->new_packmode = '='; + ++ts; + break; + case '>': + case '!': + if (__Pyx_Is_Little_Endian()) { + PyErr_SetString(PyExc_ValueError, "Big-endian buffer not supported on little-endian compiler"); + return NULL; + } + ctx->new_packmode = '='; + ++ts; + break; + case '=': + case '@': + case '^': + ctx->new_packmode = *ts++; + break; + case 'T': + { + const char* ts_after_sub; + size_t i, struct_count = ctx->new_count; + size_t struct_alignment = ctx->struct_alignment; + ctx->new_count = 1; + ++ts; + if (*ts != '{') { + PyErr_SetString(PyExc_ValueError, "Buffer acquisition: Expected '{' after 'T'"); + return NULL; + } + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->enc_type = 0; + ctx->enc_count = 0; + ctx->struct_alignment = 0; + ++ts; + ts_after_sub = ts; + for (i = 0; i != struct_count; ++i) { + ts_after_sub = __Pyx_BufFmt_CheckString(ctx, ts); + if (!ts_after_sub) return NULL; + } + ts = ts_after_sub; + if (struct_alignment) ctx->struct_alignment = struct_alignment; + } + break; + case '}': + { + size_t alignment = ctx->struct_alignment; + ++ts; + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->enc_type = 0; + if (alignment && ctx->fmt_offset % alignment) { + ctx->fmt_offset += alignment - (ctx->fmt_offset % alignment); + } + } + return ts; + case 'x': + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->fmt_offset += ctx->new_count; + ctx->new_count = 1; + ctx->enc_count = 0; + ctx->enc_type = 0; + ctx->enc_packmode = ctx->new_packmode; + ++ts; + break; + case 'Z': + got_Z = 1; + ++ts; + if (*ts != 'f' && *ts != 'd' && *ts != 'g') { + __Pyx_BufFmt_RaiseUnexpectedChar('Z'); + return NULL; + } + CYTHON_FALLTHROUGH; + case '?': case 'c': case 'b': case 'B': case 'h': case 'H': case 'i': case 'I': + case 'l': case 'L': case 'q': case 'Q': + case 'f': case 'd': case 'g': + case 'O': case 'p': + if ((ctx->enc_type == *ts) && (got_Z == ctx->is_complex) && + (ctx->enc_packmode == ctx->new_packmode) && (!ctx->is_valid_array)) { + ctx->enc_count += ctx->new_count; + ctx->new_count = 1; + got_Z = 0; + ++ts; + break; + } + CYTHON_FALLTHROUGH; + case 's': + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->enc_count = ctx->new_count; + ctx->enc_packmode = ctx->new_packmode; + ctx->enc_type = *ts; + ctx->is_complex = got_Z; + ++ts; + ctx->new_count = 1; + got_Z = 0; + break; + case ':': + ++ts; + while(*ts != ':') ++ts; + ++ts; + break; + case '(': + if (__pyx_buffmt_parse_array(ctx, &ts) < 0) return NULL; + break; + default: + { + int number = __Pyx_BufFmt_ExpectNumber(&ts); + if (number == -1) return NULL; + ctx->new_count = (size_t)number; + } + } + } +} + +/* TypeInfoCompare */ + static int +__pyx_typeinfo_cmp(__Pyx_TypeInfo *a, __Pyx_TypeInfo *b) +{ + int i; + if (!a || !b) + return 0; + if (a == b) + return 1; + if (a->size != b->size || a->typegroup != b->typegroup || + a->is_unsigned != b->is_unsigned || a->ndim != b->ndim) { + if (a->typegroup == 'H' || b->typegroup == 'H') { + return a->size == b->size; + } else { + return 0; + } + } + if (a->ndim) { + for (i = 0; i < a->ndim; i++) + if (a->arraysize[i] != b->arraysize[i]) + return 0; + } + if (a->typegroup == 'S') { + if (a->flags != b->flags) + return 0; + if (a->fields || b->fields) { + if (!(a->fields && b->fields)) + return 0; + for (i = 0; a->fields[i].type && b->fields[i].type; i++) { + __Pyx_StructField *field_a = a->fields + i; + __Pyx_StructField *field_b = b->fields + i; + if (field_a->offset != field_b->offset || + !__pyx_typeinfo_cmp(field_a->type, field_b->type)) + return 0; + } + return !a->fields[i].type && !b->fields[i].type; + } + } + return 1; +} + +/* MemviewSliceValidateAndInit */ + static int +__pyx_check_strides(Py_buffer *buf, int dim, int ndim, int spec) +{ + if (buf->shape[dim] <= 1) + return 1; + if (buf->strides) { + if (spec & __Pyx_MEMVIEW_CONTIG) { + if (spec & (__Pyx_MEMVIEW_PTR|__Pyx_MEMVIEW_FULL)) { + if (unlikely(buf->strides[dim] != sizeof(void *))) { + PyErr_Format(PyExc_ValueError, + "Buffer is not indirectly contiguous " + "in dimension %d.", dim); + goto fail; + } + } else if (unlikely(buf->strides[dim] != buf->itemsize)) { + PyErr_SetString(PyExc_ValueError, + "Buffer and memoryview are not contiguous " + "in the same dimension."); + goto fail; + } + } + if (spec & __Pyx_MEMVIEW_FOLLOW) { + Py_ssize_t stride = buf->strides[dim]; + if (stride < 0) + stride = -stride; + if (unlikely(stride < buf->itemsize)) { + PyErr_SetString(PyExc_ValueError, + "Buffer and memoryview are not contiguous " + "in the same dimension."); + goto fail; + } + } + } else { + if (unlikely(spec & __Pyx_MEMVIEW_CONTIG && dim != ndim - 1)) { + PyErr_Format(PyExc_ValueError, + "C-contiguous buffer is not contiguous in " + "dimension %d", dim); + goto fail; + } else if (unlikely(spec & (__Pyx_MEMVIEW_PTR))) { + PyErr_Format(PyExc_ValueError, + "C-contiguous buffer is not indirect in " + "dimension %d", dim); + goto fail; + } else if (unlikely(buf->suboffsets)) { + PyErr_SetString(PyExc_ValueError, + "Buffer exposes suboffsets but no strides"); + goto fail; + } + } + return 1; +fail: + return 0; +} +static int +__pyx_check_suboffsets(Py_buffer *buf, int dim, int ndim, int spec) +{ + CYTHON_UNUSED_VAR(ndim); + if (spec & __Pyx_MEMVIEW_DIRECT) { + if (unlikely(buf->suboffsets && buf->suboffsets[dim] >= 0)) { + PyErr_Format(PyExc_ValueError, + "Buffer not compatible with direct access " + "in dimension %d.", dim); + goto fail; + } + } + if (spec & __Pyx_MEMVIEW_PTR) { + if (unlikely(!buf->suboffsets || (buf->suboffsets[dim] < 0))) { + PyErr_Format(PyExc_ValueError, + "Buffer is not indirectly accessible " + "in dimension %d.", dim); + goto fail; + } + } + return 1; +fail: + return 0; +} +static int +__pyx_verify_contig(Py_buffer *buf, int ndim, int c_or_f_flag) +{ + int i; + if (c_or_f_flag & __Pyx_IS_F_CONTIG) { + Py_ssize_t stride = 1; + for (i = 0; i < ndim; i++) { + if (unlikely(stride * buf->itemsize != buf->strides[i] && buf->shape[i] > 1)) { + PyErr_SetString(PyExc_ValueError, + "Buffer not fortran contiguous."); + goto fail; + } + stride = stride * buf->shape[i]; + } + } else if (c_or_f_flag & __Pyx_IS_C_CONTIG) { + Py_ssize_t stride = 1; + for (i = ndim - 1; i >- 1; i--) { + if (unlikely(stride * buf->itemsize != buf->strides[i] && buf->shape[i] > 1)) { + PyErr_SetString(PyExc_ValueError, + "Buffer not C contiguous."); + goto fail; + } + stride = stride * buf->shape[i]; + } + } + return 1; +fail: + return 0; +} +static int __Pyx_ValidateAndInit_memviewslice( + int *axes_specs, + int c_or_f_flag, + int buf_flags, + int ndim, + __Pyx_TypeInfo *dtype, + __Pyx_BufFmt_StackElem stack[], + __Pyx_memviewslice *memviewslice, + PyObject *original_obj) +{ + struct __pyx_memoryview_obj *memview, *new_memview; + __Pyx_RefNannyDeclarations + Py_buffer *buf; + int i, spec = 0, retval = -1; + __Pyx_BufFmt_Context ctx; + int from_memoryview = __pyx_memoryview_check(original_obj); + __Pyx_RefNannySetupContext("ValidateAndInit_memviewslice", 0); + if (from_memoryview && __pyx_typeinfo_cmp(dtype, ((struct __pyx_memoryview_obj *) + original_obj)->typeinfo)) { + memview = (struct __pyx_memoryview_obj *) original_obj; + new_memview = NULL; + } else { + memview = (struct __pyx_memoryview_obj *) __pyx_memoryview_new( + original_obj, buf_flags, 0, dtype); + new_memview = memview; + if (unlikely(!memview)) + goto fail; + } + buf = &memview->view; + if (unlikely(buf->ndim != ndim)) { + PyErr_Format(PyExc_ValueError, + "Buffer has wrong number of dimensions (expected %d, got %d)", + ndim, buf->ndim); + goto fail; + } + if (new_memview) { + __Pyx_BufFmt_Init(&ctx, stack, dtype); + if (unlikely(!__Pyx_BufFmt_CheckString(&ctx, buf->format))) goto fail; + } + if (unlikely((unsigned) buf->itemsize != dtype->size)) { + PyErr_Format(PyExc_ValueError, + "Item size of buffer (%" CYTHON_FORMAT_SSIZE_T "u byte%s) " + "does not match size of '%s' (%" CYTHON_FORMAT_SSIZE_T "u byte%s)", + buf->itemsize, + (buf->itemsize > 1) ? "s" : "", + dtype->name, + dtype->size, + (dtype->size > 1) ? "s" : ""); + goto fail; + } + if (buf->len > 0) { + for (i = 0; i < ndim; i++) { + spec = axes_specs[i]; + if (unlikely(!__pyx_check_strides(buf, i, ndim, spec))) + goto fail; + if (unlikely(!__pyx_check_suboffsets(buf, i, ndim, spec))) + goto fail; + } + if (unlikely(buf->strides && !__pyx_verify_contig(buf, ndim, c_or_f_flag))) + goto fail; + } + if (unlikely(__Pyx_init_memviewslice(memview, ndim, memviewslice, + new_memview != NULL) == -1)) { + goto fail; + } + retval = 0; + goto no_fail; +fail: + Py_XDECREF(new_memview); + retval = -1; +no_fail: + __Pyx_RefNannyFinishContext(); + return retval; +} + +/* ObjectToMemviewSlice */ + static CYTHON_INLINE __Pyx_memviewslice __Pyx_PyObject_to_MemoryviewSlice_ds_float(PyObject *obj, int writable_flag) { + __Pyx_memviewslice result = { 0, 0, { 0 }, { 0 }, { 0 } }; + __Pyx_BufFmt_StackElem stack[1]; + int axes_specs[] = { (__Pyx_MEMVIEW_DIRECT | __Pyx_MEMVIEW_STRIDED) }; + int retcode; + if (obj == Py_None) { + result.memview = (struct __pyx_memoryview_obj *) Py_None; + return result; + } + retcode = __Pyx_ValidateAndInit_memviewslice(axes_specs, 0, + PyBUF_RECORDS_RO | writable_flag, 1, + &__Pyx_TypeInfo_float, stack, + &result, obj); + if (unlikely(retcode == -1)) + goto __pyx_fail; + return result; +__pyx_fail: + result.memview = NULL; + result.data = NULL; + return result; +} + +/* CIntFromPyVerify */ + #define __PYX_VERIFY_RETURN_INT(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 0) +#define __PYX_VERIFY_RETURN_INT_EXC(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 1) +#define __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, exc)\ + {\ + func_type value = func_value;\ + if (sizeof(target_type) < sizeof(func_type)) {\ + if (unlikely(value != (func_type) (target_type) value)) {\ + func_type zero = 0;\ + if (exc && unlikely(value == (func_type)-1 && PyErr_Occurred()))\ + return (target_type) -1;\ + if (is_unsigned && unlikely(value < zero))\ + goto raise_neg_overflow;\ + else\ + goto raise_overflow;\ + }\ + }\ + return (target_type) value;\ + } + +/* MemviewDtypeToObject */ + static CYTHON_INLINE PyObject *__pyx_memview_get_nn___pyx_t_5numpy_float32_t(const char *itemp) { + return (PyObject *) PyFloat_FromDouble(*(__pyx_t_5numpy_float32_t *) itemp); +} +static CYTHON_INLINE int __pyx_memview_set_nn___pyx_t_5numpy_float32_t(const char *itemp, PyObject *obj) { + __pyx_t_5numpy_float32_t value = __pyx_PyFloat_AsFloat(obj); + if (unlikely((value == ((npy_float32)-1)) && PyErr_Occurred())) + return 0; + *(__pyx_t_5numpy_float32_t *) itemp = value; + return 1; +} + +/* Declarations */ + #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #ifdef __cplusplus + static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float x, float y) { + return ::std::complex< float >(x, y); + } + #else + static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float x, float y) { + return x + y*(__pyx_t_float_complex)_Complex_I; + } + #endif +#else + static CYTHON_INLINE __pyx_t_float_complex __pyx_t_float_complex_from_parts(float x, float y) { + __pyx_t_float_complex z; + z.real = x; + z.imag = y; + return z; + } +#endif + +/* Arithmetic */ + #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) +#else + static CYTHON_INLINE int __Pyx_c_eq_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + return (a.real == b.real) && (a.imag == b.imag); + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_sum_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + __pyx_t_float_complex z; + z.real = a.real + b.real; + z.imag = a.imag + b.imag; + return z; + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_diff_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + __pyx_t_float_complex z; + z.real = a.real - b.real; + z.imag = a.imag - b.imag; + return z; + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_prod_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + __pyx_t_float_complex z; + z.real = a.real * b.real - a.imag * b.imag; + z.imag = a.real * b.imag + a.imag * b.real; + return z; + } + #if 1 + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_quot_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + if (b.imag == 0) { + return __pyx_t_float_complex_from_parts(a.real / b.real, a.imag / b.real); + } else if (fabsf(b.real) >= fabsf(b.imag)) { + if (b.real == 0 && b.imag == 0) { + return __pyx_t_float_complex_from_parts(a.real / b.real, a.imag / b.imag); + } else { + float r = b.imag / b.real; + float s = (float)(1.0) / (b.real + b.imag * r); + return __pyx_t_float_complex_from_parts( + (a.real + a.imag * r) * s, (a.imag - a.real * r) * s); + } + } else { + float r = b.real / b.imag; + float s = (float)(1.0) / (b.imag + b.real * r); + return __pyx_t_float_complex_from_parts( + (a.real * r + a.imag) * s, (a.imag * r - a.real) * s); + } + } + #else + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_quot_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + if (b.imag == 0) { + return __pyx_t_float_complex_from_parts(a.real / b.real, a.imag / b.real); + } else { + float denom = b.real * b.real + b.imag * b.imag; + return __pyx_t_float_complex_from_parts( + (a.real * b.real + a.imag * b.imag) / denom, + (a.imag * b.real - a.real * b.imag) / denom); + } + } + #endif + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_neg_float(__pyx_t_float_complex a) { + __pyx_t_float_complex z; + z.real = -a.real; + z.imag = -a.imag; + return z; + } + static CYTHON_INLINE int __Pyx_c_is_zero_float(__pyx_t_float_complex a) { + return (a.real == 0) && (a.imag == 0); + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_conj_float(__pyx_t_float_complex a) { + __pyx_t_float_complex z; + z.real = a.real; + z.imag = -a.imag; + return z; + } + #if 1 + static CYTHON_INLINE float __Pyx_c_abs_float(__pyx_t_float_complex z) { + #if !defined(HAVE_HYPOT) || defined(_MSC_VER) + return sqrtf(z.real*z.real + z.imag*z.imag); + #else + return hypotf(z.real, z.imag); + #endif + } + static CYTHON_INLINE __pyx_t_float_complex __Pyx_c_pow_float(__pyx_t_float_complex a, __pyx_t_float_complex b) { + __pyx_t_float_complex z; + float r, lnr, theta, z_r, z_theta; + if (b.imag == 0 && b.real == (int)b.real) { + if (b.real < 0) { + float denom = a.real * a.real + a.imag * a.imag; + a.real = a.real / denom; + a.imag = -a.imag / denom; + b.real = -b.real; + } + switch ((int)b.real) { + case 0: + z.real = 1; + z.imag = 0; + return z; + case 1: + return a; + case 2: + return __Pyx_c_prod_float(a, a); + case 3: + z = __Pyx_c_prod_float(a, a); + return __Pyx_c_prod_float(z, a); + case 4: + z = __Pyx_c_prod_float(a, a); + return __Pyx_c_prod_float(z, z); + } + } + if (a.imag == 0) { + if (a.real == 0) { + return a; + } else if ((b.imag == 0) && (a.real >= 0)) { + z.real = powf(a.real, b.real); + z.imag = 0; + return z; + } else if (a.real > 0) { + r = a.real; + theta = 0; + } else { + r = -a.real; + theta = atan2f(0.0, -1.0); + } + } else { + r = __Pyx_c_abs_float(a); + theta = atan2f(a.imag, a.real); + } + lnr = logf(r); + z_r = expf(lnr * b.real - theta * b.imag); + z_theta = theta * b.real + lnr * b.imag; + z.real = z_r * cosf(z_theta); + z.imag = z_r * sinf(z_theta); + return z; + } + #endif +#endif + +/* Declarations */ + #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) + #ifdef __cplusplus + static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double x, double y) { + return ::std::complex< double >(x, y); + } + #else + static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double x, double y) { + return x + y*(__pyx_t_double_complex)_Complex_I; + } + #endif +#else + static CYTHON_INLINE __pyx_t_double_complex __pyx_t_double_complex_from_parts(double x, double y) { + __pyx_t_double_complex z; + z.real = x; + z.imag = y; + return z; + } +#endif + +/* Arithmetic */ + #if CYTHON_CCOMPLEX && (1) && (!0 || __cplusplus) +#else + static CYTHON_INLINE int __Pyx_c_eq_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + return (a.real == b.real) && (a.imag == b.imag); + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_sum_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + __pyx_t_double_complex z; + z.real = a.real + b.real; + z.imag = a.imag + b.imag; + return z; + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_diff_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + __pyx_t_double_complex z; + z.real = a.real - b.real; + z.imag = a.imag - b.imag; + return z; + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_prod_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + __pyx_t_double_complex z; + z.real = a.real * b.real - a.imag * b.imag; + z.imag = a.real * b.imag + a.imag * b.real; + return z; + } + #if 1 + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_quot_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + if (b.imag == 0) { + return __pyx_t_double_complex_from_parts(a.real / b.real, a.imag / b.real); + } else if (fabs(b.real) >= fabs(b.imag)) { + if (b.real == 0 && b.imag == 0) { + return __pyx_t_double_complex_from_parts(a.real / b.real, a.imag / b.imag); + } else { + double r = b.imag / b.real; + double s = (double)(1.0) / (b.real + b.imag * r); + return __pyx_t_double_complex_from_parts( + (a.real + a.imag * r) * s, (a.imag - a.real * r) * s); + } + } else { + double r = b.real / b.imag; + double s = (double)(1.0) / (b.imag + b.real * r); + return __pyx_t_double_complex_from_parts( + (a.real * r + a.imag) * s, (a.imag * r - a.real) * s); + } + } + #else + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_quot_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + if (b.imag == 0) { + return __pyx_t_double_complex_from_parts(a.real / b.real, a.imag / b.real); + } else { + double denom = b.real * b.real + b.imag * b.imag; + return __pyx_t_double_complex_from_parts( + (a.real * b.real + a.imag * b.imag) / denom, + (a.imag * b.real - a.real * b.imag) / denom); + } + } + #endif + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_neg_double(__pyx_t_double_complex a) { + __pyx_t_double_complex z; + z.real = -a.real; + z.imag = -a.imag; + return z; + } + static CYTHON_INLINE int __Pyx_c_is_zero_double(__pyx_t_double_complex a) { + return (a.real == 0) && (a.imag == 0); + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_conj_double(__pyx_t_double_complex a) { + __pyx_t_double_complex z; + z.real = a.real; + z.imag = -a.imag; + return z; + } + #if 1 + static CYTHON_INLINE double __Pyx_c_abs_double(__pyx_t_double_complex z) { + #if !defined(HAVE_HYPOT) || defined(_MSC_VER) + return sqrt(z.real*z.real + z.imag*z.imag); + #else + return hypot(z.real, z.imag); + #endif + } + static CYTHON_INLINE __pyx_t_double_complex __Pyx_c_pow_double(__pyx_t_double_complex a, __pyx_t_double_complex b) { + __pyx_t_double_complex z; + double r, lnr, theta, z_r, z_theta; + if (b.imag == 0 && b.real == (int)b.real) { + if (b.real < 0) { + double denom = a.real * a.real + a.imag * a.imag; + a.real = a.real / denom; + a.imag = -a.imag / denom; + b.real = -b.real; + } + switch ((int)b.real) { + case 0: + z.real = 1; + z.imag = 0; + return z; + case 1: + return a; + case 2: + return __Pyx_c_prod_double(a, a); + case 3: + z = __Pyx_c_prod_double(a, a); + return __Pyx_c_prod_double(z, a); + case 4: + z = __Pyx_c_prod_double(a, a); + return __Pyx_c_prod_double(z, z); + } + } + if (a.imag == 0) { + if (a.real == 0) { + return a; + } else if ((b.imag == 0) && (a.real >= 0)) { + z.real = pow(a.real, b.real); + z.imag = 0; + return z; + } else if (a.real > 0) { + r = a.real; + theta = 0; + } else { + r = -a.real; + theta = atan2(0.0, -1.0); + } + } else { + r = __Pyx_c_abs_double(a); + theta = atan2(a.imag, a.real); + } + lnr = log(r); + z_r = exp(lnr * b.real - theta * b.imag); + z_theta = theta * b.real + lnr * b.imag; + z.real = z_r * cos(z_theta); + z.imag = z_r * sin(z_theta); + return z; + } + #endif +#endif + +/* MemviewSliceCopyTemplate */ + static __Pyx_memviewslice +__pyx_memoryview_copy_new_contig(const __Pyx_memviewslice *from_mvs, + const char *mode, int ndim, + size_t sizeof_dtype, int contig_flag, + int dtype_is_object) +{ + __Pyx_RefNannyDeclarations + int i; + __Pyx_memviewslice new_mvs = { 0, 0, { 0 }, { 0 }, { 0 } }; + struct __pyx_memoryview_obj *from_memview = from_mvs->memview; + Py_buffer *buf = &from_memview->view; + PyObject *shape_tuple = NULL; + PyObject *temp_int = NULL; + struct __pyx_array_obj *array_obj = NULL; + struct __pyx_memoryview_obj *memview_obj = NULL; + __Pyx_RefNannySetupContext("__pyx_memoryview_copy_new_contig", 0); + for (i = 0; i < ndim; i++) { + if (unlikely(from_mvs->suboffsets[i] >= 0)) { + PyErr_Format(PyExc_ValueError, "Cannot copy memoryview slice with " + "indirect dimensions (axis %d)", i); + goto fail; + } + } + shape_tuple = PyTuple_New(ndim); + if (unlikely(!shape_tuple)) { + goto fail; + } + __Pyx_GOTREF(shape_tuple); + for(i = 0; i < ndim; i++) { + temp_int = PyInt_FromSsize_t(from_mvs->shape[i]); + if(unlikely(!temp_int)) { + goto fail; + } else { + PyTuple_SET_ITEM(shape_tuple, i, temp_int); + temp_int = NULL; + } + } + array_obj = __pyx_array_new(shape_tuple, sizeof_dtype, buf->format, (char *) mode, NULL); + if (unlikely(!array_obj)) { + goto fail; + } + __Pyx_GOTREF(array_obj); + memview_obj = (struct __pyx_memoryview_obj *) __pyx_memoryview_new( + (PyObject *) array_obj, contig_flag, + dtype_is_object, + from_mvs->memview->typeinfo); + if (unlikely(!memview_obj)) + goto fail; + if (unlikely(__Pyx_init_memviewslice(memview_obj, ndim, &new_mvs, 1) < 0)) + goto fail; + if (unlikely(__pyx_memoryview_copy_contents(*from_mvs, new_mvs, ndim, ndim, + dtype_is_object) < 0)) + goto fail; + goto no_fail; +fail: + __Pyx_XDECREF(new_mvs.memview); + new_mvs.memview = NULL; + new_mvs.data = NULL; +no_fail: + __Pyx_XDECREF(shape_tuple); + __Pyx_XDECREF(temp_int); + __Pyx_XDECREF(array_obj); + __Pyx_RefNannyFinishContext(); + return new_mvs; +} + +/* MemviewSliceInit */ + static int +__Pyx_init_memviewslice(struct __pyx_memoryview_obj *memview, + int ndim, + __Pyx_memviewslice *memviewslice, + int memview_is_new_reference) +{ + __Pyx_RefNannyDeclarations + int i, retval=-1; + Py_buffer *buf = &memview->view; + __Pyx_RefNannySetupContext("init_memviewslice", 0); + if (unlikely(memviewslice->memview || memviewslice->data)) { + PyErr_SetString(PyExc_ValueError, + "memviewslice is already initialized!"); + goto fail; + } + if (buf->strides) { + for (i = 0; i < ndim; i++) { + memviewslice->strides[i] = buf->strides[i]; + } + } else { + Py_ssize_t stride = buf->itemsize; + for (i = ndim - 1; i >= 0; i--) { + memviewslice->strides[i] = stride; + stride *= buf->shape[i]; + } + } + for (i = 0; i < ndim; i++) { + memviewslice->shape[i] = buf->shape[i]; + if (buf->suboffsets) { + memviewslice->suboffsets[i] = buf->suboffsets[i]; + } else { + memviewslice->suboffsets[i] = -1; + } + } + memviewslice->memview = memview; + memviewslice->data = (char *)buf->buf; + if (__pyx_add_acquisition_count(memview) == 0 && !memview_is_new_reference) { + Py_INCREF(memview); + } + retval = 0; + goto no_fail; +fail: + memviewslice->memview = 0; + memviewslice->data = 0; + retval = -1; +no_fail: + __Pyx_RefNannyFinishContext(); + return retval; +} +#ifndef Py_NO_RETURN +#define Py_NO_RETURN +#endif +static void __pyx_fatalerror(const char *fmt, ...) Py_NO_RETURN { + va_list vargs; + char msg[200]; +#if PY_VERSION_HEX >= 0x030A0000 || defined(HAVE_STDARG_PROTOTYPES) + va_start(vargs, fmt); +#else + va_start(vargs); +#endif + vsnprintf(msg, 200, fmt, vargs); + va_end(vargs); + Py_FatalError(msg); +} +static CYTHON_INLINE int +__pyx_add_acquisition_count_locked(__pyx_atomic_int_type *acquisition_count, + PyThread_type_lock lock) +{ + int result; + PyThread_acquire_lock(lock, 1); + result = (*acquisition_count)++; + PyThread_release_lock(lock); + return result; +} +static CYTHON_INLINE int +__pyx_sub_acquisition_count_locked(__pyx_atomic_int_type *acquisition_count, + PyThread_type_lock lock) +{ + int result; + PyThread_acquire_lock(lock, 1); + result = (*acquisition_count)--; + PyThread_release_lock(lock); + return result; +} +static CYTHON_INLINE void +__Pyx_INC_MEMVIEW(__Pyx_memviewslice *memslice, int have_gil, int lineno) +{ + __pyx_nonatomic_int_type old_acquisition_count; + struct __pyx_memoryview_obj *memview = memslice->memview; + if (unlikely(!memview || (PyObject *) memview == Py_None)) { + return; + } + old_acquisition_count = __pyx_add_acquisition_count(memview); + if (unlikely(old_acquisition_count <= 0)) { + if (likely(old_acquisition_count == 0)) { + if (have_gil) { + Py_INCREF((PyObject *) memview); + } else { + PyGILState_STATE _gilstate = PyGILState_Ensure(); + Py_INCREF((PyObject *) memview); + PyGILState_Release(_gilstate); + } + } else { + __pyx_fatalerror("Acquisition count is %d (line %d)", + old_acquisition_count+1, lineno); + } + } +} +static CYTHON_INLINE void __Pyx_XCLEAR_MEMVIEW(__Pyx_memviewslice *memslice, + int have_gil, int lineno) { + __pyx_nonatomic_int_type old_acquisition_count; + struct __pyx_memoryview_obj *memview = memslice->memview; + if (unlikely(!memview || (PyObject *) memview == Py_None)) { + memslice->memview = NULL; + return; + } + old_acquisition_count = __pyx_sub_acquisition_count(memview); + memslice->data = NULL; + if (likely(old_acquisition_count > 1)) { + memslice->memview = NULL; + } else if (likely(old_acquisition_count == 1)) { + if (have_gil) { + Py_CLEAR(memslice->memview); + } else { + PyGILState_STATE _gilstate = PyGILState_Ensure(); + Py_CLEAR(memslice->memview); + PyGILState_Release(_gilstate); + } + } else { + __pyx_fatalerror("Acquisition count is %d (line %d)", + old_acquisition_count-1, lineno); + } +} + +/* TypeInfoToFormat */ + static struct __pyx_typeinfo_string __Pyx_TypeInfoToFormat(__Pyx_TypeInfo *type) { + struct __pyx_typeinfo_string result = { {0} }; + char *buf = (char *) result.string; + size_t size = type->size; + switch (type->typegroup) { + case 'H': + *buf = 'c'; + break; + case 'I': + case 'U': + if (size == 1) + *buf = (type->is_unsigned) ? 'B' : 'b'; + else if (size == 2) + *buf = (type->is_unsigned) ? 'H' : 'h'; + else if (size == 4) + *buf = (type->is_unsigned) ? 'I' : 'i'; + else if (size == 8) + *buf = (type->is_unsigned) ? 'Q' : 'q'; + break; + case 'P': + *buf = 'P'; + break; + case 'C': + { + __Pyx_TypeInfo complex_type = *type; + complex_type.typegroup = 'R'; + complex_type.size /= 2; + *buf++ = 'Z'; + *buf = __Pyx_TypeInfoToFormat(&complex_type).string[0]; + break; + } + case 'R': + if (size == 4) + *buf = 'f'; + else if (size == 8) + *buf = 'd'; + else + *buf = 'g'; + break; + } + return result; +} + +/* CIntFromPy */ + static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(int) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(int, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (int) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 2 * PyLong_SHIFT)) { + return (int) (((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 3 * PyLong_SHIFT)) { + return (int) (((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 4 * PyLong_SHIFT)) { + return (int) (((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(int) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(int) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) ((((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) ((((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) ((((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(int) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + int val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (int) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (int) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (int) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (int) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(int) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(int) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((int) 1) << (sizeof(int) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (int) -1; + } + } else { + int val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (int) -1; + val = __Pyx_PyInt_As_int(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to int"); + return (int) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to int"); + return (int) -1; +} + +/* CIntFromPy */ + static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(long) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(long, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (long) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 2 * PyLong_SHIFT)) { + return (long) (((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 3 * PyLong_SHIFT)) { + return (long) (((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 4 * PyLong_SHIFT)) { + return (long) (((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(long) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(long) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) ((((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) ((((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) ((((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(long) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + long val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (long) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (long) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (long) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (long) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(long) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(long) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((long) 1) << (sizeof(long) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (long) -1; + } + } else { + long val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (long) -1; + val = __Pyx_PyInt_As_long(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to long"); + return (long) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to long"); + return (long) -1; +} + +/* CIntToPy */ + static CYTHON_INLINE PyObject* __Pyx_PyInt_From_int(int value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(int) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(int) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(int) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(int) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(int) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; +#if !CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030d0000 + return _PyLong_FromByteArray(bytes, sizeof(int), + little, !is_unsigned); +#else + PyObject *from_bytes, *result = NULL; + PyObject *py_bytes = NULL, *arg_tuple = NULL, *kwds = NULL, *order_str = NULL; + from_bytes = PyObject_GetAttrString((PyObject*)&PyLong_Type, "from_bytes"); + if (!from_bytes) return NULL; + py_bytes = PyBytes_FromStringAndSize((char*)bytes, sizeof(int)); + if (!py_bytes) goto limited_bad; + order_str = PyUnicode_FromString(little ? "little" : "big"); + if (!order_str) goto limited_bad; + arg_tuple = PyTuple_Pack(2, py_bytes, order_str); + if (!arg_tuple) goto limited_bad; + if (!is_unsigned) { + kwds = PyDict_New(); + if (!kwds) goto limited_bad; + if (PyDict_SetItemString(kwds, "signed", __Pyx_NewRef(Py_True))) goto limited_bad; + } + result = PyObject_Call(from_bytes, arg_tuple, kwds); + limited_bad: + Py_XDECREF(kwds); + Py_XDECREF(arg_tuple); + Py_XDECREF(order_str); + Py_XDECREF(py_bytes); + Py_XDECREF(from_bytes); + return result; +#endif + } +} + +/* CIntToPy */ + static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(long) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(long) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(long) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; +#if !CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030d0000 + return _PyLong_FromByteArray(bytes, sizeof(long), + little, !is_unsigned); +#else + PyObject *from_bytes, *result = NULL; + PyObject *py_bytes = NULL, *arg_tuple = NULL, *kwds = NULL, *order_str = NULL; + from_bytes = PyObject_GetAttrString((PyObject*)&PyLong_Type, "from_bytes"); + if (!from_bytes) return NULL; + py_bytes = PyBytes_FromStringAndSize((char*)bytes, sizeof(long)); + if (!py_bytes) goto limited_bad; + order_str = PyUnicode_FromString(little ? "little" : "big"); + if (!order_str) goto limited_bad; + arg_tuple = PyTuple_Pack(2, py_bytes, order_str); + if (!arg_tuple) goto limited_bad; + if (!is_unsigned) { + kwds = PyDict_New(); + if (!kwds) goto limited_bad; + if (PyDict_SetItemString(kwds, "signed", __Pyx_NewRef(Py_True))) goto limited_bad; + } + result = PyObject_Call(from_bytes, arg_tuple, kwds); + limited_bad: + Py_XDECREF(kwds); + Py_XDECREF(arg_tuple); + Py_XDECREF(order_str); + Py_XDECREF(py_bytes); + Py_XDECREF(from_bytes); + return result; +#endif + } +} + +/* CIntFromPy */ + static CYTHON_INLINE char __Pyx_PyInt_As_char(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const char neg_one = (char) -1, const_zero = (char) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(char) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(char, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (char) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(char, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(char) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) >= 2 * PyLong_SHIFT)) { + return (char) (((((char)digits[1]) << PyLong_SHIFT) | (char)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(char) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) >= 3 * PyLong_SHIFT)) { + return (char) (((((((char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(char) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) >= 4 * PyLong_SHIFT)) { + return (char) (((((((((char)digits[3]) << PyLong_SHIFT) | (char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (char) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(char) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(char, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(char) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(char, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(char, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(char) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 2 * PyLong_SHIFT)) { + return (char) (((char)-1)*(((((char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(char) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 2 * PyLong_SHIFT)) { + return (char) ((((((char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(char) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 3 * PyLong_SHIFT)) { + return (char) (((char)-1)*(((((((char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(char) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 3 * PyLong_SHIFT)) { + return (char) ((((((((char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(char) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 4 * PyLong_SHIFT)) { + return (char) (((char)-1)*(((((((((char)digits[3]) << PyLong_SHIFT) | (char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(char) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 4 * PyLong_SHIFT)) { + return (char) ((((((((((char)digits[3]) << PyLong_SHIFT) | (char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(char) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(char, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(char) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(char, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + char val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (char) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (char) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (char) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (char) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (char) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(char) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((char) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(char) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((char) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((char) 1) << (sizeof(char) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (char) -1; + } + } else { + char val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (char) -1; + val = __Pyx_PyInt_As_char(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to char"); + return (char) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to char"); + return (char) -1; +} + +/* FormatTypeName */ + #if CYTHON_COMPILING_IN_LIMITED_API +static __Pyx_TypeName +__Pyx_PyType_GetName(PyTypeObject* tp) +{ + PyObject *name = __Pyx_PyObject_GetAttrStr((PyObject *)tp, + __pyx_n_s_name_2); + if (unlikely(name == NULL) || unlikely(!PyUnicode_Check(name))) { + PyErr_Clear(); + Py_XDECREF(name); + name = __Pyx_NewRef(__pyx_n_s__40); + } + return name; +} +#endif + +/* CheckBinaryVersion */ + static unsigned long __Pyx_get_runtime_version(void) { +#if __PYX_LIMITED_VERSION_HEX >= 0x030B00A4 + return Py_Version & ~0xFFUL; +#else + const char* rt_version = Py_GetVersion(); + unsigned long version = 0; + unsigned long factor = 0x01000000UL; + unsigned int digit = 0; + int i = 0; + while (factor) { + while ('0' <= rt_version[i] && rt_version[i] <= '9') { + digit = digit * 10 + (unsigned int) (rt_version[i] - '0'); + ++i; + } + version += factor * digit; + if (rt_version[i] != '.') + break; + digit = 0; + factor >>= 8; + ++i; + } + return version; +#endif +} +static int __Pyx_check_binary_version(unsigned long ct_version, unsigned long rt_version, int allow_newer) { + const unsigned long MAJOR_MINOR = 0xFFFF0000UL; + if ((rt_version & MAJOR_MINOR) == (ct_version & MAJOR_MINOR)) + return 0; + if (likely(allow_newer && (rt_version & MAJOR_MINOR) > (ct_version & MAJOR_MINOR))) + return 1; + { + char message[200]; + PyOS_snprintf(message, sizeof(message), + "compile time Python version %d.%d " + "of module '%.100s' " + "%s " + "runtime version %d.%d", + (int) (ct_version >> 24), (int) ((ct_version >> 16) & 0xFF), + __Pyx_MODULE_NAME, + (allow_newer) ? "was newer than" : "does not match", + (int) (rt_version >> 24), (int) ((rt_version >> 16) & 0xFF) + ); + return PyErr_WarnEx(NULL, message, 1); + } +} + +/* InitStrings */ + #if PY_MAJOR_VERSION >= 3 +static int __Pyx_InitString(__Pyx_StringTabEntry t, PyObject **str) { + if (t.is_unicode | t.is_str) { + if (t.intern) { + *str = PyUnicode_InternFromString(t.s); + } else if (t.encoding) { + *str = PyUnicode_Decode(t.s, t.n - 1, t.encoding, NULL); + } else { + *str = PyUnicode_FromStringAndSize(t.s, t.n - 1); + } + } else { + *str = PyBytes_FromStringAndSize(t.s, t.n - 1); + } + if (!*str) + return -1; + if (PyObject_Hash(*str) == -1) + return -1; + return 0; +} +#endif +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t) { + while (t->p) { + #if PY_MAJOR_VERSION >= 3 + __Pyx_InitString(*t, t->p); + #else + if (t->is_unicode) { + *t->p = PyUnicode_DecodeUTF8(t->s, t->n - 1, NULL); + } else if (t->intern) { + *t->p = PyString_InternFromString(t->s); + } else { + *t->p = PyString_FromStringAndSize(t->s, t->n - 1); + } + if (!*t->p) + return -1; + if (PyObject_Hash(*t->p) == -1) + return -1; + #endif + ++t; + } + return 0; +} + +#include +static CYTHON_INLINE Py_ssize_t __Pyx_ssize_strlen(const char *s) { + size_t len = strlen(s); + if (unlikely(len > (size_t) PY_SSIZE_T_MAX)) { + PyErr_SetString(PyExc_OverflowError, "byte string is too long"); + return -1; + } + return (Py_ssize_t) len; +} +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char* c_str) { + Py_ssize_t len = __Pyx_ssize_strlen(c_str); + if (unlikely(len < 0)) return NULL; + return __Pyx_PyUnicode_FromStringAndSize(c_str, len); +} +static CYTHON_INLINE PyObject* __Pyx_PyByteArray_FromString(const char* c_str) { + Py_ssize_t len = __Pyx_ssize_strlen(c_str); + if (unlikely(len < 0)) return NULL; + return PyByteArray_FromStringAndSize(c_str, len); +} +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject* o) { + Py_ssize_t ignore; + return __Pyx_PyObject_AsStringAndSize(o, &ignore); +} +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +#if !CYTHON_PEP393_ENABLED +static const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + char* defenc_c; + PyObject* defenc = _PyUnicode_AsDefaultEncodedString(o, NULL); + if (!defenc) return NULL; + defenc_c = PyBytes_AS_STRING(defenc); +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + { + char* end = defenc_c + PyBytes_GET_SIZE(defenc); + char* c; + for (c = defenc_c; c < end; c++) { + if ((unsigned char) (*c) >= 128) { + PyUnicode_AsASCIIString(o); + return NULL; + } + } + } +#endif + *length = PyBytes_GET_SIZE(defenc); + return defenc_c; +} +#else +static CYTHON_INLINE const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + if (unlikely(__Pyx_PyUnicode_READY(o) == -1)) return NULL; +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + if (likely(PyUnicode_IS_ASCII(o))) { + *length = PyUnicode_GET_LENGTH(o); + return PyUnicode_AsUTF8(o); + } else { + PyUnicode_AsASCIIString(o); + return NULL; + } +#else + return PyUnicode_AsUTF8AndSize(o, length); +#endif +} +#endif +#endif +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject* o, Py_ssize_t *length) { +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT + if ( +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + __Pyx_sys_getdefaultencoding_not_ascii && +#endif + PyUnicode_Check(o)) { + return __Pyx_PyUnicode_AsStringAndSize(o, length); + } else +#endif +#if (!CYTHON_COMPILING_IN_PYPY && !CYTHON_COMPILING_IN_LIMITED_API) || (defined(PyByteArray_AS_STRING) && defined(PyByteArray_GET_SIZE)) + if (PyByteArray_Check(o)) { + *length = PyByteArray_GET_SIZE(o); + return PyByteArray_AS_STRING(o); + } else +#endif + { + char* result; + int r = PyBytes_AsStringAndSize(o, &result, length); + if (unlikely(r < 0)) { + return NULL; + } else { + return result; + } + } +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject* x) { + int is_true = x == Py_True; + if (is_true | (x == Py_False) | (x == Py_None)) return is_true; + else return PyObject_IsTrue(x); +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject* x) { + int retval; + if (unlikely(!x)) return -1; + retval = __Pyx_PyObject_IsTrue(x); + Py_DECREF(x); + return retval; +} +static PyObject* __Pyx_PyNumber_IntOrLongWrongResultType(PyObject* result, const char* type_name) { + __Pyx_TypeName result_type_name = __Pyx_PyType_GetName(Py_TYPE(result)); +#if PY_MAJOR_VERSION >= 3 + if (PyLong_Check(result)) { + if (PyErr_WarnFormat(PyExc_DeprecationWarning, 1, + "__int__ returned non-int (type " __Pyx_FMT_TYPENAME "). " + "The ability to return an instance of a strict subclass of int is deprecated, " + "and may be removed in a future version of Python.", + result_type_name)) { + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; + } + __Pyx_DECREF_TypeName(result_type_name); + return result; + } +#endif + PyErr_Format(PyExc_TypeError, + "__%.4s__ returned non-%.4s (type " __Pyx_FMT_TYPENAME ")", + type_name, type_name, result_type_name); + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x) { +#if CYTHON_USE_TYPE_SLOTS + PyNumberMethods *m; +#endif + const char *name = NULL; + PyObject *res = NULL; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x) || PyLong_Check(x))) +#else + if (likely(PyLong_Check(x))) +#endif + return __Pyx_NewRef(x); +#if CYTHON_USE_TYPE_SLOTS + m = Py_TYPE(x)->tp_as_number; + #if PY_MAJOR_VERSION < 3 + if (m && m->nb_int) { + name = "int"; + res = m->nb_int(x); + } + else if (m && m->nb_long) { + name = "long"; + res = m->nb_long(x); + } + #else + if (likely(m && m->nb_int)) { + name = "int"; + res = m->nb_int(x); + } + #endif +#else + if (!PyBytes_CheckExact(x) && !PyUnicode_CheckExact(x)) { + res = PyNumber_Int(x); + } +#endif + if (likely(res)) { +#if PY_MAJOR_VERSION < 3 + if (unlikely(!PyInt_Check(res) && !PyLong_Check(res))) { +#else + if (unlikely(!PyLong_CheckExact(res))) { +#endif + return __Pyx_PyNumber_IntOrLongWrongResultType(res, name); + } + } + else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_TypeError, + "an integer is required"); + } + return res; +} +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject* b) { + Py_ssize_t ival; + PyObject *x; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_CheckExact(b))) { + if (sizeof(Py_ssize_t) >= sizeof(long)) + return PyInt_AS_LONG(b); + else + return PyInt_AsSsize_t(b); + } +#endif + if (likely(PyLong_CheckExact(b))) { + #if CYTHON_USE_PYLONG_INTERNALS + if (likely(__Pyx_PyLong_IsCompact(b))) { + return __Pyx_PyLong_CompactValue(b); + } else { + const digit* digits = __Pyx_PyLong_Digits(b); + const Py_ssize_t size = __Pyx_PyLong_SignedDigitCount(b); + switch (size) { + case 2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return (Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + } + } + #endif + return PyLong_AsSsize_t(b); + } + x = PyNumber_Index(b); + if (!x) return -1; + ival = PyInt_AsSsize_t(x); + Py_DECREF(x); + return ival; +} +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject* o) { + if (sizeof(Py_hash_t) == sizeof(Py_ssize_t)) { + return (Py_hash_t) __Pyx_PyIndex_AsSsize_t(o); +#if PY_MAJOR_VERSION < 3 + } else if (likely(PyInt_CheckExact(o))) { + return PyInt_AS_LONG(o); +#endif + } else { + Py_ssize_t ival; + PyObject *x; + x = PyNumber_Index(o); + if (!x) return -1; + ival = PyInt_AsLong(x); + Py_DECREF(x); + return ival; + } +} +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b) { + return b ? __Pyx_NewRef(Py_True) : __Pyx_NewRef(Py_False); +} +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t ival) { + return PyInt_FromSize_t(ival); +} + + +/* #### Code section: utility_code_pragmas_end ### */ +#ifdef _MSC_VER +#pragma warning( pop ) +#endif + + + +/* #### Code section: end ### */ +#endif /* Py_PYTHON_H */ diff --git a/selfdrive/modeld/models/commonmodel_pyx.so b/selfdrive/modeld/models/commonmodel_pyx.so new file mode 100755 index 0000000..8f9fdeb Binary files /dev/null and b/selfdrive/modeld/models/commonmodel_pyx.so differ diff --git a/selfdrive/modeld/models/supercombo.onnx b/selfdrive/modeld/models/supercombo.thneed similarity index 78% rename from selfdrive/modeld/models/supercombo.onnx rename to selfdrive/modeld/models/supercombo.thneed index acd7490..d3af3f5 100644 Binary files a/selfdrive/modeld/models/supercombo.onnx and b/selfdrive/modeld/models/supercombo.thneed differ diff --git a/selfdrive/modeld/models/supercombo_metadata.pkl b/selfdrive/modeld/models/supercombo_metadata.pkl new file mode 100644 index 0000000..c61356a Binary files /dev/null and b/selfdrive/modeld/models/supercombo_metadata.pkl differ diff --git a/selfdrive/modeld/runners/run.h b/selfdrive/modeld/runners/run.h deleted file mode 100644 index 36ad262..0000000 --- a/selfdrive/modeld/runners/run.h +++ /dev/null @@ -1,4 +0,0 @@ -#pragma once - -#include "selfdrive/modeld/runners/runmodel.h" -#include "selfdrive/modeld/runners/snpemodel.h" diff --git a/selfdrive/modeld/runners/runmodel.h b/selfdrive/modeld/runners/runmodel.h deleted file mode 100644 index 18cc180..0000000 --- a/selfdrive/modeld/runners/runmodel.h +++ /dev/null @@ -1,49 +0,0 @@ -#pragma once - -#include -#include -#include -#include - -#include "common/clutil.h" -#include "common/swaglog.h" - -#define USE_CPU_RUNTIME 0 -#define USE_GPU_RUNTIME 1 -#define USE_DSP_RUNTIME 2 - -struct ModelInput { - const std::string name; - float *buffer; - int size; - - ModelInput(const std::string _name, float *_buffer, int _size) : name(_name), buffer(_buffer), size(_size) {} - virtual void setBuffer(float *_buffer, int _size) { - assert(size == _size || size == 0); - buffer = _buffer; - size = _size; - } -}; - -class RunModel { -public: - std::vector> inputs; - - virtual ~RunModel() {} - virtual void execute() {} - virtual void* getCLBuffer(const std::string name) { return nullptr; } - - virtual void addInput(const std::string name, float *buffer, int size) { - inputs.push_back(std::unique_ptr(new ModelInput(name, buffer, size))); - } - virtual void setInputBuffer(const std::string name, float *buffer, int size) { - for (auto &input : inputs) { - if (name == input->name) { - input->setBuffer(buffer, size); - return; - } - } - LOGE("Tried to update input `%s` but no input with this name exists", name.c_str()); - assert(false); - } -}; diff --git a/selfdrive/modeld/runners/runmodel_pyx.cpp b/selfdrive/modeld/runners/runmodel_pyx.cpp new file mode 100644 index 0000000..0c9c373 --- /dev/null +++ b/selfdrive/modeld/runners/runmodel_pyx.cpp @@ -0,0 +1,28888 @@ +/* Generated by Cython 3.0.8 */ + +/* BEGIN: Cython Metadata +{ + "distutils": { + "depends": [ + "cereal/visionipc/visionbuf.h", + "cereal/visionipc/visionipc.h", + "cereal/visionipc/visionipc_client.h", + "cereal/visionipc/visionipc_server.h", + "selfdrive/modeld/runners/runmodel.h" + ], + "language": "c++", + "name": "selfdrive.modeld.runners.runmodel_pyx", + "sources": [ + "/data/openpilot/selfdrive/modeld/runners/runmodel_pyx.pyx" + ] + }, + "module_name": "selfdrive.modeld.runners.runmodel_pyx" +} +END: Cython Metadata */ + +#ifndef PY_SSIZE_T_CLEAN +#define PY_SSIZE_T_CLEAN +#endif /* PY_SSIZE_T_CLEAN */ +#if defined(CYTHON_LIMITED_API) && 0 + #ifndef Py_LIMITED_API + #if CYTHON_LIMITED_API+0 > 0x03030000 + #define Py_LIMITED_API CYTHON_LIMITED_API + #else + #define Py_LIMITED_API 0x03030000 + #endif + #endif +#endif + +#include "Python.h" +#ifndef Py_PYTHON_H + #error Python headers needed to compile C extensions, please install development version of Python. +#elif PY_VERSION_HEX < 0x02070000 || (0x03000000 <= PY_VERSION_HEX && PY_VERSION_HEX < 0x03030000) + #error Cython requires Python 2.7+ or Python 3.3+. +#else +#if defined(CYTHON_LIMITED_API) && CYTHON_LIMITED_API +#define __PYX_EXTRA_ABI_MODULE_NAME "limited" +#else +#define __PYX_EXTRA_ABI_MODULE_NAME "" +#endif +#define CYTHON_ABI "3_0_8" __PYX_EXTRA_ABI_MODULE_NAME +#define __PYX_ABI_MODULE_NAME "_cython_" CYTHON_ABI +#define __PYX_TYPE_MODULE_PREFIX __PYX_ABI_MODULE_NAME "." +#define CYTHON_HEX_VERSION 0x030008F0 +#define CYTHON_FUTURE_DIVISION 1 +#include +#ifndef offsetof + #define offsetof(type, member) ( (size_t) & ((type*)0) -> member ) +#endif +#if !defined(_WIN32) && !defined(WIN32) && !defined(MS_WINDOWS) + #ifndef __stdcall + #define __stdcall + #endif + #ifndef __cdecl + #define __cdecl + #endif + #ifndef __fastcall + #define __fastcall + #endif +#endif +#ifndef DL_IMPORT + #define DL_IMPORT(t) t +#endif +#ifndef DL_EXPORT + #define DL_EXPORT(t) t +#endif +#define __PYX_COMMA , +#ifndef HAVE_LONG_LONG + #define HAVE_LONG_LONG +#endif +#ifndef PY_LONG_LONG + #define PY_LONG_LONG LONG_LONG +#endif +#ifndef Py_HUGE_VAL + #define Py_HUGE_VAL HUGE_VAL +#endif +#define __PYX_LIMITED_VERSION_HEX PY_VERSION_HEX +#if defined(GRAALVM_PYTHON) + /* For very preliminary testing purposes. Most variables are set the same as PyPy. + The existence of this section does not imply that anything works or is even tested */ + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 1 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(PYPY_VERSION) + #define CYTHON_COMPILING_IN_PYPY 1 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #ifndef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #endif + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #if PY_VERSION_HEX < 0x03090000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE (PY_VERSION_HEX >= 0x030400a1 && PYPY_VERSION_NUM >= 0x07030C00) + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(CYTHON_LIMITED_API) + #ifdef Py_LIMITED_API + #undef __PYX_LIMITED_VERSION_HEX + #define __PYX_LIMITED_VERSION_HEX Py_LIMITED_API + #endif + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 1 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_CLINE_IN_TRACEBACK + #define CYTHON_CLINE_IN_TRACEBACK 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 1 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #endif + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 1 + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(Py_GIL_DISABLED) || defined(Py_NOGIL) + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 1 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #ifndef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 +#else + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 1 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #ifndef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #endif + #ifndef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 1 + #endif + #if PY_MAJOR_VERSION < 3 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #ifndef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 1 + #endif + #ifndef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 1 + #endif + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #if PY_VERSION_HEX < 0x030300F0 || PY_VERSION_HEX >= 0x030B00A2 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #elif !defined(CYTHON_USE_UNICODE_WRITER) + #define CYTHON_USE_UNICODE_WRITER 1 + #endif + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #ifndef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 1 + #endif + #ifndef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL (PY_MAJOR_VERSION < 3 || PY_VERSION_HEX >= 0x03060000 && PY_VERSION_HEX < 0x030C00A6) + #endif + #ifndef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL (PY_VERSION_HEX >= 0x030700A1) + #endif + #ifndef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 1 + #endif + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #endif + #if PY_VERSION_HEX < 0x030400a1 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #elif !defined(CYTHON_USE_TP_FINALIZE) + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #if PY_VERSION_HEX < 0x030600B1 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #elif !defined(CYTHON_USE_DICT_VERSIONS) + #define CYTHON_USE_DICT_VERSIONS (PY_VERSION_HEX < 0x030C00A5) + #endif + #if PY_VERSION_HEX < 0x030700A3 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #elif !defined(CYTHON_USE_EXC_INFO_STACK) + #define CYTHON_USE_EXC_INFO_STACK 1 + #endif + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 1 + #endif +#endif +#if !defined(CYTHON_FAST_PYCCALL) +#define CYTHON_FAST_PYCCALL (CYTHON_FAST_PYCALL && PY_VERSION_HEX >= 0x030600B1) +#endif +#if !defined(CYTHON_VECTORCALL) +#define CYTHON_VECTORCALL (CYTHON_FAST_PYCCALL && PY_VERSION_HEX >= 0x030800B1) +#endif +#define CYTHON_BACKPORT_VECTORCALL (CYTHON_METH_FASTCALL && PY_VERSION_HEX < 0x030800B1) +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_MAJOR_VERSION < 3 + #include "longintrepr.h" + #endif + #undef SHIFT + #undef BASE + #undef MASK + #ifdef SIZEOF_VOID_P + enum { __pyx_check_sizeof_voidp = 1 / (int)(SIZEOF_VOID_P == sizeof(void*)) }; + #endif +#endif +#ifndef __has_attribute + #define __has_attribute(x) 0 +#endif +#ifndef __has_cpp_attribute + #define __has_cpp_attribute(x) 0 +#endif +#ifndef CYTHON_RESTRICT + #if defined(__GNUC__) + #define CYTHON_RESTRICT __restrict__ + #elif defined(_MSC_VER) && _MSC_VER >= 1400 + #define CYTHON_RESTRICT __restrict + #elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define CYTHON_RESTRICT restrict + #else + #define CYTHON_RESTRICT + #endif +#endif +#ifndef CYTHON_UNUSED + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(maybe_unused) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(maybe_unused) + #define CYTHON_UNUSED [[maybe_unused]] + #endif + #endif + #endif +#endif +#ifndef CYTHON_UNUSED +# if defined(__GNUC__) +# if !(defined(__cplusplus)) || (__GNUC__ > 3 || (__GNUC__ == 3 && __GNUC_MINOR__ >= 4)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +# elif defined(__ICC) || (defined(__INTEL_COMPILER) && !defined(_MSC_VER)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +#endif +#ifndef CYTHON_UNUSED_VAR +# if defined(__cplusplus) + template void CYTHON_UNUSED_VAR( const T& ) { } +# else +# define CYTHON_UNUSED_VAR(x) (void)(x) +# endif +#endif +#ifndef CYTHON_MAYBE_UNUSED_VAR + #define CYTHON_MAYBE_UNUSED_VAR(x) CYTHON_UNUSED_VAR(x) +#endif +#ifndef CYTHON_NCP_UNUSED +# if CYTHON_COMPILING_IN_CPYTHON +# define CYTHON_NCP_UNUSED +# else +# define CYTHON_NCP_UNUSED CYTHON_UNUSED +# endif +#endif +#ifndef CYTHON_USE_CPP_STD_MOVE + #if defined(__cplusplus) && (\ + __cplusplus >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1600)) + #define CYTHON_USE_CPP_STD_MOVE 1 + #else + #define CYTHON_USE_CPP_STD_MOVE 0 + #endif +#endif +#define __Pyx_void_to_None(void_result) ((void)(void_result), Py_INCREF(Py_None), Py_None) +#ifdef _MSC_VER + #ifndef _MSC_STDINT_H_ + #if _MSC_VER < 1300 + typedef unsigned char uint8_t; + typedef unsigned short uint16_t; + typedef unsigned int uint32_t; + #else + typedef unsigned __int8 uint8_t; + typedef unsigned __int16 uint16_t; + typedef unsigned __int32 uint32_t; + #endif + #endif + #if _MSC_VER < 1300 + #ifdef _WIN64 + typedef unsigned long long __pyx_uintptr_t; + #else + typedef unsigned int __pyx_uintptr_t; + #endif + #else + #ifdef _WIN64 + typedef unsigned __int64 __pyx_uintptr_t; + #else + typedef unsigned __int32 __pyx_uintptr_t; + #endif + #endif +#else + #include + typedef uintptr_t __pyx_uintptr_t; +#endif +#ifndef CYTHON_FALLTHROUGH + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(fallthrough) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(fallthrough) + #define CYTHON_FALLTHROUGH [[fallthrough]] + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_cpp_attribute(clang::fallthrough) + #define CYTHON_FALLTHROUGH [[clang::fallthrough]] + #elif __has_cpp_attribute(gnu::fallthrough) + #define CYTHON_FALLTHROUGH [[gnu::fallthrough]] + #endif + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_attribute(fallthrough) + #define CYTHON_FALLTHROUGH __attribute__((fallthrough)) + #else + #define CYTHON_FALLTHROUGH + #endif + #endif + #if defined(__clang__) && defined(__apple_build_version__) + #if __apple_build_version__ < 7000000 + #undef CYTHON_FALLTHROUGH + #define CYTHON_FALLTHROUGH + #endif + #endif +#endif +#ifdef __cplusplus + template + struct __PYX_IS_UNSIGNED_IMPL {static const bool value = T(0) < T(-1);}; + #define __PYX_IS_UNSIGNED(type) (__PYX_IS_UNSIGNED_IMPL::value) +#else + #define __PYX_IS_UNSIGNED(type) (((type)-1) > 0) +#endif +#if CYTHON_COMPILING_IN_PYPY == 1 + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x030A0000) +#else + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x03090000) +#endif +#define __PYX_REINTERPRET_FUNCION(func_pointer, other_pointer) ((func_pointer)(void(*)(void))(other_pointer)) + +#ifndef __cplusplus + #error "Cython files generated with the C++ option must be compiled with a C++ compiler." +#endif +#ifndef CYTHON_INLINE + #if defined(__clang__) + #define CYTHON_INLINE __inline__ __attribute__ ((__unused__)) + #else + #define CYTHON_INLINE inline + #endif +#endif +template +void __Pyx_call_destructor(T& x) { + x.~T(); +} +template +class __Pyx_FakeReference { + public: + __Pyx_FakeReference() : ptr(NULL) { } + __Pyx_FakeReference(const T& ref) : ptr(const_cast(&ref)) { } + T *operator->() { return ptr; } + T *operator&() { return ptr; } + operator T&() { return *ptr; } + template bool operator ==(const U& other) const { return *ptr == other; } + template bool operator !=(const U& other) const { return *ptr != other; } + template bool operator==(const __Pyx_FakeReference& other) const { return *ptr == *other.ptr; } + template bool operator!=(const __Pyx_FakeReference& other) const { return *ptr != *other.ptr; } + private: + T *ptr; +}; + +#define __PYX_BUILD_PY_SSIZE_T "n" +#define CYTHON_FORMAT_SSIZE_T "z" +#if PY_MAJOR_VERSION < 3 + #define __Pyx_BUILTIN_MODULE_NAME "__builtin__" + #define __Pyx_DefaultClassType PyClass_Type + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a+k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_BUILTIN_MODULE_NAME "builtins" + #define __Pyx_DefaultClassType PyType_Type +#if CYTHON_COMPILING_IN_LIMITED_API + static CYTHON_INLINE PyObject* __Pyx_PyCode_New(int a, int p, int k, int l, int s, int f, + PyObject *code, PyObject *c, PyObject* n, PyObject *v, + PyObject *fv, PyObject *cell, PyObject* fn, + PyObject *name, int fline, PyObject *lnos) { + PyObject *exception_table = NULL; + PyObject *types_module=NULL, *code_type=NULL, *result=NULL; + #if __PYX_LIMITED_VERSION_HEX < 0x030B0000 + PyObject *version_info; + PyObject *py_minor_version = NULL; + #endif + long minor_version = 0; + PyObject *type, *value, *traceback; + PyErr_Fetch(&type, &value, &traceback); + #if __PYX_LIMITED_VERSION_HEX >= 0x030B0000 + minor_version = 11; + #else + if (!(version_info = PySys_GetObject("version_info"))) goto end; + if (!(py_minor_version = PySequence_GetItem(version_info, 1))) goto end; + minor_version = PyLong_AsLong(py_minor_version); + Py_DECREF(py_minor_version); + if (minor_version == -1 && PyErr_Occurred()) goto end; + #endif + if (!(types_module = PyImport_ImportModule("types"))) goto end; + if (!(code_type = PyObject_GetAttrString(types_module, "CodeType"))) goto end; + if (minor_version <= 7) { + (void)p; + result = PyObject_CallFunction(code_type, "iiiiiOOOOOOiOO", a, k, l, s, f, code, + c, n, v, fn, name, fline, lnos, fv, cell); + } else if (minor_version <= 10) { + result = PyObject_CallFunction(code_type, "iiiiiiOOOOOOiOO", a,p, k, l, s, f, code, + c, n, v, fn, name, fline, lnos, fv, cell); + } else { + if (!(exception_table = PyBytes_FromStringAndSize(NULL, 0))) goto end; + result = PyObject_CallFunction(code_type, "iiiiiiOOOOOOOiOO", a,p, k, l, s, f, code, + c, n, v, fn, name, name, fline, lnos, exception_table, fv, cell); + } + end: + Py_XDECREF(code_type); + Py_XDECREF(exception_table); + Py_XDECREF(types_module); + if (type) { + PyErr_Restore(type, value, traceback); + } + return result; + } + #ifndef CO_OPTIMIZED + #define CO_OPTIMIZED 0x0001 + #endif + #ifndef CO_NEWLOCALS + #define CO_NEWLOCALS 0x0002 + #endif + #ifndef CO_VARARGS + #define CO_VARARGS 0x0004 + #endif + #ifndef CO_VARKEYWORDS + #define CO_VARKEYWORDS 0x0008 + #endif + #ifndef CO_ASYNC_GENERATOR + #define CO_ASYNC_GENERATOR 0x0200 + #endif + #ifndef CO_GENERATOR + #define CO_GENERATOR 0x0020 + #endif + #ifndef CO_COROUTINE + #define CO_COROUTINE 0x0080 + #endif +#elif PY_VERSION_HEX >= 0x030B0000 + static CYTHON_INLINE PyCodeObject* __Pyx_PyCode_New(int a, int p, int k, int l, int s, int f, + PyObject *code, PyObject *c, PyObject* n, PyObject *v, + PyObject *fv, PyObject *cell, PyObject* fn, + PyObject *name, int fline, PyObject *lnos) { + PyCodeObject *result; + PyObject *empty_bytes = PyBytes_FromStringAndSize("", 0); + if (!empty_bytes) return NULL; + result = + #if PY_VERSION_HEX >= 0x030C0000 + PyUnstable_Code_NewWithPosOnlyArgs + #else + PyCode_NewWithPosOnlyArgs + #endif + (a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, name, fline, lnos, empty_bytes); + Py_DECREF(empty_bytes); + return result; + } +#elif PY_VERSION_HEX >= 0x030800B2 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_NewWithPosOnlyArgs(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#endif +#endif +#if PY_VERSION_HEX >= 0x030900A4 || defined(Py_IS_TYPE) + #define __Pyx_IS_TYPE(ob, type) Py_IS_TYPE(ob, type) +#else + #define __Pyx_IS_TYPE(ob, type) (((const PyObject*)ob)->ob_type == (type)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_Is) + #define __Pyx_Py_Is(x, y) Py_Is(x, y) +#else + #define __Pyx_Py_Is(x, y) ((x) == (y)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsNone) + #define __Pyx_Py_IsNone(ob) Py_IsNone(ob) +#else + #define __Pyx_Py_IsNone(ob) __Pyx_Py_Is((ob), Py_None) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsTrue) + #define __Pyx_Py_IsTrue(ob) Py_IsTrue(ob) +#else + #define __Pyx_Py_IsTrue(ob) __Pyx_Py_Is((ob), Py_True) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsFalse) + #define __Pyx_Py_IsFalse(ob) Py_IsFalse(ob) +#else + #define __Pyx_Py_IsFalse(ob) __Pyx_Py_Is((ob), Py_False) +#endif +#define __Pyx_NoneAsNull(obj) (__Pyx_Py_IsNone(obj) ? NULL : (obj)) +#if PY_VERSION_HEX >= 0x030900F0 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_GC_IsFinalized(o) PyObject_GC_IsFinalized(o) +#else + #define __Pyx_PyObject_GC_IsFinalized(o) _PyGC_FINALIZED(o) +#endif +#ifndef CO_COROUTINE + #define CO_COROUTINE 0x80 +#endif +#ifndef CO_ASYNC_GENERATOR + #define CO_ASYNC_GENERATOR 0x200 +#endif +#ifndef Py_TPFLAGS_CHECKTYPES + #define Py_TPFLAGS_CHECKTYPES 0 +#endif +#ifndef Py_TPFLAGS_HAVE_INDEX + #define Py_TPFLAGS_HAVE_INDEX 0 +#endif +#ifndef Py_TPFLAGS_HAVE_NEWBUFFER + #define Py_TPFLAGS_HAVE_NEWBUFFER 0 +#endif +#ifndef Py_TPFLAGS_HAVE_FINALIZE + #define Py_TPFLAGS_HAVE_FINALIZE 0 +#endif +#ifndef Py_TPFLAGS_SEQUENCE + #define Py_TPFLAGS_SEQUENCE 0 +#endif +#ifndef Py_TPFLAGS_MAPPING + #define Py_TPFLAGS_MAPPING 0 +#endif +#ifndef METH_STACKLESS + #define METH_STACKLESS 0 +#endif +#if PY_VERSION_HEX <= 0x030700A3 || !defined(METH_FASTCALL) + #ifndef METH_FASTCALL + #define METH_FASTCALL 0x80 + #endif + typedef PyObject *(*__Pyx_PyCFunctionFast) (PyObject *self, PyObject *const *args, Py_ssize_t nargs); + typedef PyObject *(*__Pyx_PyCFunctionFastWithKeywords) (PyObject *self, PyObject *const *args, + Py_ssize_t nargs, PyObject *kwnames); +#else + #define __Pyx_PyCFunctionFast _PyCFunctionFast + #define __Pyx_PyCFunctionFastWithKeywords _PyCFunctionFastWithKeywords +#endif +#if CYTHON_METH_FASTCALL + #define __Pyx_METH_FASTCALL METH_FASTCALL + #define __Pyx_PyCFunction_FastCall __Pyx_PyCFunctionFast + #define __Pyx_PyCFunction_FastCallWithKeywords __Pyx_PyCFunctionFastWithKeywords +#else + #define __Pyx_METH_FASTCALL METH_VARARGS + #define __Pyx_PyCFunction_FastCall PyCFunction + #define __Pyx_PyCFunction_FastCallWithKeywords PyCFunctionWithKeywords +#endif +#if CYTHON_VECTORCALL + #define __pyx_vectorcallfunc vectorcallfunc + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET PY_VECTORCALL_ARGUMENTS_OFFSET + #define __Pyx_PyVectorcall_NARGS(n) PyVectorcall_NARGS((size_t)(n)) +#elif CYTHON_BACKPORT_VECTORCALL + typedef PyObject *(*__pyx_vectorcallfunc)(PyObject *callable, PyObject *const *args, + size_t nargsf, PyObject *kwnames); + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET ((size_t)1 << (8 * sizeof(size_t) - 1)) + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(((size_t)(n)) & ~__Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET)) +#else + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET 0 + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(n)) +#endif +#if PY_MAJOR_VERSION >= 0x030900B1 +#define __Pyx_PyCFunction_CheckExact(func) PyCFunction_CheckExact(func) +#else +#define __Pyx_PyCFunction_CheckExact(func) PyCFunction_Check(func) +#endif +#define __Pyx_CyOrPyCFunction_Check(func) PyCFunction_Check(func) +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_CyOrPyCFunction_GET_FUNCTION(func) (((PyCFunctionObject*)(func))->m_ml->ml_meth) +#elif !CYTHON_COMPILING_IN_LIMITED_API +#define __Pyx_CyOrPyCFunction_GET_FUNCTION(func) PyCFunction_GET_FUNCTION(func) +#endif +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_CyOrPyCFunction_GET_FLAGS(func) (((PyCFunctionObject*)(func))->m_ml->ml_flags) +static CYTHON_INLINE PyObject* __Pyx_CyOrPyCFunction_GET_SELF(PyObject *func) { + return (__Pyx_CyOrPyCFunction_GET_FLAGS(func) & METH_STATIC) ? NULL : ((PyCFunctionObject*)func)->m_self; +} +#endif +static CYTHON_INLINE int __Pyx__IsSameCFunction(PyObject *func, void *cfunc) { +#if CYTHON_COMPILING_IN_LIMITED_API + return PyCFunction_Check(func) && PyCFunction_GetFunction(func) == (PyCFunction) cfunc; +#else + return PyCFunction_Check(func) && PyCFunction_GET_FUNCTION(func) == (PyCFunction) cfunc; +#endif +} +#define __Pyx_IsSameCFunction(func, cfunc) __Pyx__IsSameCFunction(func, cfunc) +#if __PYX_LIMITED_VERSION_HEX < 0x030900B1 + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) ((void)m, PyType_FromSpecWithBases(s, b)) + typedef PyObject *(*__Pyx_PyCMethod)(PyObject *, PyTypeObject *, PyObject *const *, size_t, PyObject *); +#else + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) PyType_FromModuleAndSpec(m, s, b) + #define __Pyx_PyCMethod PyCMethod +#endif +#ifndef METH_METHOD + #define METH_METHOD 0x200 +#endif +#if CYTHON_COMPILING_IN_PYPY && !defined(PyObject_Malloc) + #define PyObject_Malloc(s) PyMem_Malloc(s) + #define PyObject_Free(p) PyMem_Free(p) + #define PyObject_Realloc(p) PyMem_Realloc(p) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) +#else + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) (frame)->f_lineno = (lineno) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyThreadState_Current PyThreadState_Get() +#elif !CYTHON_FAST_THREAD_STATE + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#elif PY_VERSION_HEX >= 0x030d00A1 + #define __Pyx_PyThreadState_Current PyThreadState_GetUnchecked() +#elif PY_VERSION_HEX >= 0x03060000 + #define __Pyx_PyThreadState_Current _PyThreadState_UncheckedGet() +#elif PY_VERSION_HEX >= 0x03000000 + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#else + #define __Pyx_PyThreadState_Current _PyThreadState_Current +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE void *__Pyx_PyModule_GetState(PyObject *op) +{ + void *result; + result = PyModule_GetState(op); + if (!result) + Py_FatalError("Couldn't find the module state"); + return result; +} +#endif +#define __Pyx_PyObject_GetSlot(obj, name, func_ctype) __Pyx_PyType_GetSlot(Py_TYPE(obj), name, func_ctype) +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((func_ctype) PyType_GetSlot((type), Py_##name)) +#else + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((type)->name) +#endif +#if PY_VERSION_HEX < 0x030700A2 && !defined(PyThread_tss_create) && !defined(Py_tss_NEEDS_INIT) +#include "pythread.h" +#define Py_tss_NEEDS_INIT 0 +typedef int Py_tss_t; +static CYTHON_INLINE int PyThread_tss_create(Py_tss_t *key) { + *key = PyThread_create_key(); + return 0; +} +static CYTHON_INLINE Py_tss_t * PyThread_tss_alloc(void) { + Py_tss_t *key = (Py_tss_t *)PyObject_Malloc(sizeof(Py_tss_t)); + *key = Py_tss_NEEDS_INIT; + return key; +} +static CYTHON_INLINE void PyThread_tss_free(Py_tss_t *key) { + PyObject_Free(key); +} +static CYTHON_INLINE int PyThread_tss_is_created(Py_tss_t *key) { + return *key != Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE void PyThread_tss_delete(Py_tss_t *key) { + PyThread_delete_key(*key); + *key = Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE int PyThread_tss_set(Py_tss_t *key, void *value) { + return PyThread_set_key_value(*key, value); +} +static CYTHON_INLINE void * PyThread_tss_get(Py_tss_t *key) { + return PyThread_get_key_value(*key); +} +#endif +#if PY_MAJOR_VERSION < 3 + #if CYTHON_COMPILING_IN_PYPY + #if PYPY_VERSION_NUM < 0x07030600 + #if defined(__cplusplus) && __cplusplus >= 201402L + [[deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")]] + #elif defined(__GNUC__) || defined(__clang__) + __attribute__ ((__deprecated__("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6"))) + #elif defined(_MSC_VER) + __declspec(deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")) + #endif + static CYTHON_INLINE int PyGILState_Check(void) { + return 0; + } + #else // PYPY_VERSION_NUM < 0x07030600 + #endif // PYPY_VERSION_NUM < 0x07030600 + #else + static CYTHON_INLINE int PyGILState_Check(void) { + PyThreadState * tstate = _PyThreadState_Current; + return tstate && (tstate == PyGILState_GetThisThreadState()); + } + #endif +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030d0000 || defined(_PyDict_NewPresized) +#define __Pyx_PyDict_NewPresized(n) ((n <= 8) ? PyDict_New() : _PyDict_NewPresized(n)) +#else +#define __Pyx_PyDict_NewPresized(n) PyDict_New() +#endif +#if PY_MAJOR_VERSION >= 3 || CYTHON_FUTURE_DIVISION + #define __Pyx_PyNumber_Divide(x,y) PyNumber_TrueDivide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceTrueDivide(x,y) +#else + #define __Pyx_PyNumber_Divide(x,y) PyNumber_Divide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceDivide(x,y) +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX > 0x030600B4 && PY_VERSION_HEX < 0x030d0000 && CYTHON_USE_UNICODE_INTERNALS +#define __Pyx_PyDict_GetItemStrWithError(dict, name) _PyDict_GetItem_KnownHash(dict, name, ((PyASCIIObject *) name)->hash) +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStr(PyObject *dict, PyObject *name) { + PyObject *res = __Pyx_PyDict_GetItemStrWithError(dict, name); + if (res == NULL) PyErr_Clear(); + return res; +} +#elif PY_MAJOR_VERSION >= 3 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07020000) +#define __Pyx_PyDict_GetItemStrWithError PyDict_GetItemWithError +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#else +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStrWithError(PyObject *dict, PyObject *name) { +#if CYTHON_COMPILING_IN_PYPY + return PyDict_GetItem(dict, name); +#else + PyDictEntry *ep; + PyDictObject *mp = (PyDictObject*) dict; + long hash = ((PyStringObject *) name)->ob_shash; + assert(hash != -1); + ep = (mp->ma_lookup)(mp, name, hash); + if (ep == NULL) { + return NULL; + } + return ep->me_value; +#endif +} +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#endif +#if CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyType_GetFlags(tp) (((PyTypeObject *)tp)->tp_flags) + #define __Pyx_PyType_HasFeature(type, feature) ((__Pyx_PyType_GetFlags(type) & (feature)) != 0) + #define __Pyx_PyObject_GetIterNextFunc(obj) (Py_TYPE(obj)->tp_iternext) +#else + #define __Pyx_PyType_GetFlags(tp) (PyType_GetFlags((PyTypeObject *)tp)) + #define __Pyx_PyType_HasFeature(type, feature) PyType_HasFeature(type, feature) + #define __Pyx_PyObject_GetIterNextFunc(obj) PyIter_Next +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_SetItemOnTypeDict(tp, k, v) PyObject_GenericSetAttr((PyObject*)tp, k, v) +#else + #define __Pyx_SetItemOnTypeDict(tp, k, v) PyDict_SetItem(tp->tp_dict, k, v) +#endif +#if CYTHON_USE_TYPE_SPECS && PY_VERSION_HEX >= 0x03080000 +#define __Pyx_PyHeapTypeObject_GC_Del(obj) {\ + PyTypeObject *type = Py_TYPE((PyObject*)obj);\ + assert(__Pyx_PyType_HasFeature(type, Py_TPFLAGS_HEAPTYPE));\ + PyObject_GC_Del(obj);\ + Py_DECREF(type);\ +} +#else +#define __Pyx_PyHeapTypeObject_GC_Del(obj) PyObject_GC_Del(obj) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define CYTHON_PEP393_ENABLED 1 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GetLength(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_ReadChar(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((void)u, 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((void)u, (0)) + #define __Pyx_PyUnicode_DATA(u) ((void*)u) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)k, PyUnicode_ReadChar((PyObject*)(d), i)) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GetLength(u)) +#elif PY_VERSION_HEX > 0x03030000 && defined(PyUnicode_KIND) + #define CYTHON_PEP393_ENABLED 1 + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_READY(op) (0) + #else + #define __Pyx_PyUnicode_READY(op) (likely(PyUnicode_IS_READY(op)) ?\ + 0 : _PyUnicode_Ready((PyObject *)(op))) + #endif + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_LENGTH(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_READ_CHAR(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) PyUnicode_MAX_CHAR_VALUE(u) + #define __Pyx_PyUnicode_KIND(u) ((int)PyUnicode_KIND(u)) + #define __Pyx_PyUnicode_DATA(u) PyUnicode_DATA(u) + #define __Pyx_PyUnicode_READ(k, d, i) PyUnicode_READ(k, d, i) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) PyUnicode_WRITE(k, d, i, (Py_UCS4) ch) + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_LENGTH(u)) + #else + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x03090000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : ((PyCompactUnicodeObject *)(u))->wstr_length)) + #else + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : PyUnicode_GET_SIZE(u))) + #endif + #endif +#else + #define CYTHON_PEP393_ENABLED 0 + #define PyUnicode_1BYTE_KIND 1 + #define PyUnicode_2BYTE_KIND 2 + #define PyUnicode_4BYTE_KIND 4 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_SIZE(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) ((Py_UCS4)(PyUnicode_AS_UNICODE(u)[i])) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((sizeof(Py_UNICODE) == 2) ? 65535U : 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((int)sizeof(Py_UNICODE)) + #define __Pyx_PyUnicode_DATA(u) ((void*)PyUnicode_AS_UNICODE(u)) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)(k), (Py_UCS4)(((Py_UNICODE*)d)[i])) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) (((void)(k)), ((Py_UNICODE*)d)[i] = (Py_UNICODE) ch) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_SIZE(u)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyUnicode_Concat(a, b) PyNumber_Add(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) PyNumber_Add(a, b) +#else + #define __Pyx_PyUnicode_Concat(a, b) PyUnicode_Concat(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) ((unlikely((a) == Py_None) || unlikely((b) == Py_None)) ?\ + PyNumber_Add(a, b) : __Pyx_PyUnicode_Concat(a, b)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #if !defined(PyUnicode_DecodeUnicodeEscape) + #define PyUnicode_DecodeUnicodeEscape(s, size, errors) PyUnicode_Decode(s, size, "unicode_escape", errors) + #endif + #if !defined(PyUnicode_Contains) || (PY_MAJOR_VERSION == 2 && PYPY_VERSION_NUM < 0x07030500) + #undef PyUnicode_Contains + #define PyUnicode_Contains(u, s) PySequence_Contains(u, s) + #endif + #if !defined(PyByteArray_Check) + #define PyByteArray_Check(obj) PyObject_TypeCheck(obj, &PyByteArray_Type) + #endif + #if !defined(PyObject_Format) + #define PyObject_Format(obj, fmt) PyObject_CallMethod(obj, "__format__", "O", fmt) + #endif +#endif +#define __Pyx_PyString_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyString_Check(b) && !PyString_CheckExact(b)))) ? PyNumber_Remainder(a, b) : __Pyx_PyString_Format(a, b)) +#define __Pyx_PyUnicode_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyUnicode_Check(b) && !PyUnicode_CheckExact(b)))) ? PyNumber_Remainder(a, b) : PyUnicode_Format(a, b)) +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyString_Format(a, b) PyUnicode_Format(a, b) +#else + #define __Pyx_PyString_Format(a, b) PyString_Format(a, b) +#endif +#if PY_MAJOR_VERSION < 3 && !defined(PyObject_ASCII) + #define PyObject_ASCII(o) PyObject_Repr(o) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBaseString_Type PyUnicode_Type + #define PyStringObject PyUnicodeObject + #define PyString_Type PyUnicode_Type + #define PyString_Check PyUnicode_Check + #define PyString_CheckExact PyUnicode_CheckExact +#ifndef PyObject_Unicode + #define PyObject_Unicode PyObject_Str +#endif +#endif +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyBaseString_Check(obj) PyUnicode_Check(obj) + #define __Pyx_PyBaseString_CheckExact(obj) PyUnicode_CheckExact(obj) +#else + #define __Pyx_PyBaseString_Check(obj) (PyString_Check(obj) || PyUnicode_Check(obj)) + #define __Pyx_PyBaseString_CheckExact(obj) (PyString_CheckExact(obj) || PyUnicode_CheckExact(obj)) +#endif +#if CYTHON_COMPILING_IN_CPYTHON + #define __Pyx_PySequence_ListKeepNew(obj)\ + (likely(PyList_CheckExact(obj) && Py_REFCNT(obj) == 1) ? __Pyx_NewRef(obj) : PySequence_List(obj)) +#else + #define __Pyx_PySequence_ListKeepNew(obj) PySequence_List(obj) +#endif +#ifndef PySet_CheckExact + #define PySet_CheckExact(obj) __Pyx_IS_TYPE(obj, &PySet_Type) +#endif +#if PY_VERSION_HEX >= 0x030900A4 + #define __Pyx_SET_REFCNT(obj, refcnt) Py_SET_REFCNT(obj, refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SET_SIZE(obj, size) +#else + #define __Pyx_SET_REFCNT(obj, refcnt) Py_REFCNT(obj) = (refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SIZE(obj) = (size) +#endif +#if CYTHON_ASSUME_SAFE_MACROS + #define __Pyx_PySequence_ITEM(o, i) PySequence_ITEM(o, i) + #define __Pyx_PySequence_SIZE(seq) Py_SIZE(seq) + #define __Pyx_PyTuple_SET_ITEM(o, i, v) (PyTuple_SET_ITEM(o, i, v), (0)) + #define __Pyx_PyList_SET_ITEM(o, i, v) (PyList_SET_ITEM(o, i, v), (0)) + #define __Pyx_PyTuple_GET_SIZE(o) PyTuple_GET_SIZE(o) + #define __Pyx_PyList_GET_SIZE(o) PyList_GET_SIZE(o) + #define __Pyx_PySet_GET_SIZE(o) PySet_GET_SIZE(o) + #define __Pyx_PyBytes_GET_SIZE(o) PyBytes_GET_SIZE(o) + #define __Pyx_PyByteArray_GET_SIZE(o) PyByteArray_GET_SIZE(o) +#else + #define __Pyx_PySequence_ITEM(o, i) PySequence_GetItem(o, i) + #define __Pyx_PySequence_SIZE(seq) PySequence_Size(seq) + #define __Pyx_PyTuple_SET_ITEM(o, i, v) PyTuple_SetItem(o, i, v) + #define __Pyx_PyList_SET_ITEM(o, i, v) PyList_SetItem(o, i, v) + #define __Pyx_PyTuple_GET_SIZE(o) PyTuple_Size(o) + #define __Pyx_PyList_GET_SIZE(o) PyList_Size(o) + #define __Pyx_PySet_GET_SIZE(o) PySet_Size(o) + #define __Pyx_PyBytes_GET_SIZE(o) PyBytes_Size(o) + #define __Pyx_PyByteArray_GET_SIZE(o) PyByteArray_Size(o) +#endif +#if PY_VERSION_HEX >= 0x030d00A1 + #define __Pyx_PyImport_AddModuleRef(name) PyImport_AddModuleRef(name) +#else + static CYTHON_INLINE PyObject *__Pyx_PyImport_AddModuleRef(const char *name) { + PyObject *module = PyImport_AddModule(name); + Py_XINCREF(module); + return module; + } +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyIntObject PyLongObject + #define PyInt_Type PyLong_Type + #define PyInt_Check(op) PyLong_Check(op) + #define PyInt_CheckExact(op) PyLong_CheckExact(op) + #define __Pyx_Py3Int_Check(op) PyLong_Check(op) + #define __Pyx_Py3Int_CheckExact(op) PyLong_CheckExact(op) + #define PyInt_FromString PyLong_FromString + #define PyInt_FromUnicode PyLong_FromUnicode + #define PyInt_FromLong PyLong_FromLong + #define PyInt_FromSize_t PyLong_FromSize_t + #define PyInt_FromSsize_t PyLong_FromSsize_t + #define PyInt_AsLong PyLong_AsLong + #define PyInt_AS_LONG PyLong_AS_LONG + #define PyInt_AsSsize_t PyLong_AsSsize_t + #define PyInt_AsUnsignedLongMask PyLong_AsUnsignedLongMask + #define PyInt_AsUnsignedLongLongMask PyLong_AsUnsignedLongLongMask + #define PyNumber_Int PyNumber_Long +#else + #define __Pyx_Py3Int_Check(op) (PyLong_Check(op) || PyInt_Check(op)) + #define __Pyx_Py3Int_CheckExact(op) (PyLong_CheckExact(op) || PyInt_CheckExact(op)) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBoolObject PyLongObject +#endif +#if PY_MAJOR_VERSION >= 3 && CYTHON_COMPILING_IN_PYPY + #ifndef PyUnicode_InternFromString + #define PyUnicode_InternFromString(s) PyUnicode_FromString(s) + #endif +#endif +#if PY_VERSION_HEX < 0x030200A4 + typedef long Py_hash_t; + #define __Pyx_PyInt_FromHash_t PyInt_FromLong + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsHash_t +#else + #define __Pyx_PyInt_FromHash_t PyInt_FromSsize_t + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsSsize_t +#endif +#if CYTHON_USE_ASYNC_SLOTS + #if PY_VERSION_HEX >= 0x030500B1 + #define __Pyx_PyAsyncMethodsStruct PyAsyncMethods + #define __Pyx_PyType_AsAsync(obj) (Py_TYPE(obj)->tp_as_async) + #else + #define __Pyx_PyType_AsAsync(obj) ((__Pyx_PyAsyncMethodsStruct*) (Py_TYPE(obj)->tp_reserved)) + #endif +#else + #define __Pyx_PyType_AsAsync(obj) NULL +#endif +#ifndef __Pyx_PyAsyncMethodsStruct + typedef struct { + unaryfunc am_await; + unaryfunc am_aiter; + unaryfunc am_anext; + } __Pyx_PyAsyncMethodsStruct; +#endif + +#if defined(_WIN32) || defined(WIN32) || defined(MS_WINDOWS) + #if !defined(_USE_MATH_DEFINES) + #define _USE_MATH_DEFINES + #endif +#endif +#include +#ifdef NAN +#define __PYX_NAN() ((float) NAN) +#else +static CYTHON_INLINE float __PYX_NAN() { + float value; + memset(&value, 0xFF, sizeof(value)); + return value; +} +#endif +#if defined(__CYGWIN__) && defined(_LDBL_EQ_DBL) +#define __Pyx_truncl trunc +#else +#define __Pyx_truncl truncl +#endif + +#define __PYX_MARK_ERR_POS(f_index, lineno) \ + { __pyx_filename = __pyx_f[f_index]; (void)__pyx_filename; __pyx_lineno = lineno; (void)__pyx_lineno; __pyx_clineno = __LINE__; (void)__pyx_clineno; } +#define __PYX_ERR(f_index, lineno, Ln_error) \ + { __PYX_MARK_ERR_POS(f_index, lineno) goto Ln_error; } + +#ifdef CYTHON_EXTERN_C + #undef __PYX_EXTERN_C + #define __PYX_EXTERN_C CYTHON_EXTERN_C +#elif defined(__PYX_EXTERN_C) + #ifdef _MSC_VER + #pragma message ("Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead.") + #else + #warning Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead. + #endif +#else + #define __PYX_EXTERN_C extern "C++" +#endif + +#define __PYX_HAVE__selfdrive__modeld__runners__runmodel_pyx +#define __PYX_HAVE_API__selfdrive__modeld__runners__runmodel_pyx +/* Early includes */ +#include +#include +#include "ios" +#include "new" +#include "stdexcept" +#include "typeinfo" +#include "selfdrive/modeld/runners/runmodel.h" +#include +#include + + #if __cplusplus >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1600) + // move should be defined for these versions of MSVC, but __cplusplus isn't set usefully + #include + + namespace cython_std { + template typename std::remove_reference::type&& move(T& t) noexcept { return std::move(t); } + template typename std::remove_reference::type&& move(T&& t) noexcept { return std::move(t); } + } + + #endif + +#include +#include +#include "cereal/visionipc/visionbuf.h" +#include "cereal/visionipc/visionipc.h" +#include "cereal/visionipc/visionipc_server.h" +#include "cereal/visionipc/visionipc_client.h" +#include "pythread.h" +#include +#ifdef _OPENMP +#include +#endif /* _OPENMP */ + +#if defined(PYREX_WITHOUT_ASSERTIONS) && !defined(CYTHON_WITHOUT_ASSERTIONS) +#define CYTHON_WITHOUT_ASSERTIONS +#endif + +typedef struct {PyObject **p; const char *s; const Py_ssize_t n; const char* encoding; + const char is_unicode; const char is_str; const char intern; } __Pyx_StringTabEntry; + +#define __PYX_DEFAULT_STRING_ENCODING_IS_ASCII 1 +#define __PYX_DEFAULT_STRING_ENCODING_IS_UTF8 0 +#define __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT (PY_MAJOR_VERSION >= 3 && __PYX_DEFAULT_STRING_ENCODING_IS_UTF8) +#define __PYX_DEFAULT_STRING_ENCODING "ascii" +#define __Pyx_PyObject_FromString __Pyx_PyBytes_FromString +#define __Pyx_PyObject_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#define __Pyx_uchar_cast(c) ((unsigned char)c) +#define __Pyx_long_cast(x) ((long)x) +#define __Pyx_fits_Py_ssize_t(v, type, is_signed) (\ + (sizeof(type) < sizeof(Py_ssize_t)) ||\ + (sizeof(type) > sizeof(Py_ssize_t) &&\ + likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX) &&\ + (!is_signed || likely(v > (type)PY_SSIZE_T_MIN ||\ + v == (type)PY_SSIZE_T_MIN))) ||\ + (sizeof(type) == sizeof(Py_ssize_t) &&\ + (is_signed || likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX))) ) +static CYTHON_INLINE int __Pyx_is_valid_index(Py_ssize_t i, Py_ssize_t limit) { + return (size_t) i < (size_t) limit; +} +#if defined (__cplusplus) && __cplusplus >= 201103L + #include + #define __Pyx_sst_abs(value) std::abs(value) +#elif SIZEOF_INT >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) abs(value) +#elif SIZEOF_LONG >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) labs(value) +#elif defined (_MSC_VER) + #define __Pyx_sst_abs(value) ((Py_ssize_t)_abs64(value)) +#elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define __Pyx_sst_abs(value) llabs(value) +#elif defined (__GNUC__) + #define __Pyx_sst_abs(value) __builtin_llabs(value) +#else + #define __Pyx_sst_abs(value) ((value<0) ? -value : value) +#endif +static CYTHON_INLINE Py_ssize_t __Pyx_ssize_strlen(const char *s); +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject*); +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject*, Py_ssize_t* length); +static CYTHON_INLINE PyObject* __Pyx_PyByteArray_FromString(const char*); +#define __Pyx_PyByteArray_FromStringAndSize(s, l) PyByteArray_FromStringAndSize((const char*)s, l) +#define __Pyx_PyBytes_FromString PyBytes_FromString +#define __Pyx_PyBytes_FromStringAndSize PyBytes_FromStringAndSize +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char*); +#if PY_MAJOR_VERSION < 3 + #define __Pyx_PyStr_FromString __Pyx_PyBytes_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#else + #define __Pyx_PyStr_FromString __Pyx_PyUnicode_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyUnicode_FromStringAndSize +#endif +#define __Pyx_PyBytes_AsWritableString(s) ((char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableSString(s) ((signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableUString(s) ((unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsString(s) ((const char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsSString(s) ((const signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsUString(s) ((const unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyObject_AsWritableString(s) ((char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableSString(s) ((signed char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableUString(s) ((unsigned char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsSString(s) ((const signed char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsUString(s) ((const unsigned char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_FromCString(s) __Pyx_PyObject_FromString((const char*)s) +#define __Pyx_PyBytes_FromCString(s) __Pyx_PyBytes_FromString((const char*)s) +#define __Pyx_PyByteArray_FromCString(s) __Pyx_PyByteArray_FromString((const char*)s) +#define __Pyx_PyStr_FromCString(s) __Pyx_PyStr_FromString((const char*)s) +#define __Pyx_PyUnicode_FromCString(s) __Pyx_PyUnicode_FromString((const char*)s) +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const wchar_t *u) +{ + const wchar_t *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#else +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const Py_UNICODE *u) +{ + const Py_UNICODE *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#endif +#define __Pyx_PyUnicode_FromOrdinal(o) PyUnicode_FromOrdinal((int)o) +#define __Pyx_PyUnicode_FromUnicode(u) PyUnicode_FromUnicode(u, __Pyx_Py_UNICODE_strlen(u)) +#define __Pyx_PyUnicode_FromUnicodeAndLength PyUnicode_FromUnicode +#define __Pyx_PyUnicode_AsUnicode PyUnicode_AsUnicode +#define __Pyx_NewRef(obj) (Py_INCREF(obj), obj) +#define __Pyx_Owned_Py_None(b) __Pyx_NewRef(Py_None) +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b); +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject*); +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject*); +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x); +#define __Pyx_PySequence_Tuple(obj)\ + (likely(PyTuple_CheckExact(obj)) ? __Pyx_NewRef(obj) : PySequence_Tuple(obj)) +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject*); +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t); +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject*); +#if CYTHON_ASSUME_SAFE_MACROS +#define __pyx_PyFloat_AsDouble(x) (PyFloat_CheckExact(x) ? PyFloat_AS_DOUBLE(x) : PyFloat_AsDouble(x)) +#else +#define __pyx_PyFloat_AsDouble(x) PyFloat_AsDouble(x) +#endif +#define __pyx_PyFloat_AsFloat(x) ((float) __pyx_PyFloat_AsDouble(x)) +#if PY_MAJOR_VERSION >= 3 +#define __Pyx_PyNumber_Int(x) (PyLong_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Long(x)) +#else +#define __Pyx_PyNumber_Int(x) (PyInt_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Int(x)) +#endif +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_VERSION_HEX >= 0x030C00A7 + #ifndef _PyLong_SIGN_MASK + #define _PyLong_SIGN_MASK 3 + #endif + #ifndef _PyLong_NON_SIZE_BITS + #define _PyLong_NON_SIZE_BITS 3 + #endif + #define __Pyx_PyLong_Sign(x) (((PyLongObject*)x)->long_value.lv_tag & _PyLong_SIGN_MASK) + #define __Pyx_PyLong_IsNeg(x) ((__Pyx_PyLong_Sign(x) & 2) != 0) + #define __Pyx_PyLong_IsNonNeg(x) (!__Pyx_PyLong_IsNeg(x)) + #define __Pyx_PyLong_IsZero(x) (__Pyx_PyLong_Sign(x) & 1) + #define __Pyx_PyLong_IsPos(x) (__Pyx_PyLong_Sign(x) == 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) (__Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) ((Py_ssize_t) (((PyLongObject*)x)->long_value.lv_tag >> _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_SignedDigitCount(x)\ + ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * __Pyx_PyLong_DigitCount(x)) + #if defined(PyUnstable_Long_IsCompact) && defined(PyUnstable_Long_CompactValue) + #define __Pyx_PyLong_IsCompact(x) PyUnstable_Long_IsCompact((PyLongObject*) x) + #define __Pyx_PyLong_CompactValue(x) PyUnstable_Long_CompactValue((PyLongObject*) x) + #else + #define __Pyx_PyLong_IsCompact(x) (((PyLongObject*)x)->long_value.lv_tag < (2 << _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_CompactValue(x) ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * (Py_ssize_t) __Pyx_PyLong_Digits(x)[0]) + #endif + typedef Py_ssize_t __Pyx_compact_pylong; + typedef size_t __Pyx_compact_upylong; + #else + #define __Pyx_PyLong_IsNeg(x) (Py_SIZE(x) < 0) + #define __Pyx_PyLong_IsNonNeg(x) (Py_SIZE(x) >= 0) + #define __Pyx_PyLong_IsZero(x) (Py_SIZE(x) == 0) + #define __Pyx_PyLong_IsPos(x) (Py_SIZE(x) > 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) ((Py_SIZE(x) == 0) ? 0 : __Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) __Pyx_sst_abs(Py_SIZE(x)) + #define __Pyx_PyLong_SignedDigitCount(x) Py_SIZE(x) + #define __Pyx_PyLong_IsCompact(x) (Py_SIZE(x) == 0 || Py_SIZE(x) == 1 || Py_SIZE(x) == -1) + #define __Pyx_PyLong_CompactValue(x)\ + ((Py_SIZE(x) == 0) ? (sdigit) 0 : ((Py_SIZE(x) < 0) ? -(sdigit)__Pyx_PyLong_Digits(x)[0] : (sdigit)__Pyx_PyLong_Digits(x)[0])) + typedef sdigit __Pyx_compact_pylong; + typedef digit __Pyx_compact_upylong; + #endif + #if PY_VERSION_HEX >= 0x030C00A5 + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->long_value.ob_digit) + #else + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->ob_digit) + #endif +#endif +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII +#include +static int __Pyx_sys_getdefaultencoding_not_ascii; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + PyObject* ascii_chars_u = NULL; + PyObject* ascii_chars_b = NULL; + const char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + if (strcmp(default_encoding_c, "ascii") == 0) { + __Pyx_sys_getdefaultencoding_not_ascii = 0; + } else { + char ascii_chars[128]; + int c; + for (c = 0; c < 128; c++) { + ascii_chars[c] = (char) c; + } + __Pyx_sys_getdefaultencoding_not_ascii = 1; + ascii_chars_u = PyUnicode_DecodeASCII(ascii_chars, 128, NULL); + if (!ascii_chars_u) goto bad; + ascii_chars_b = PyUnicode_AsEncodedString(ascii_chars_u, default_encoding_c, NULL); + if (!ascii_chars_b || !PyBytes_Check(ascii_chars_b) || memcmp(ascii_chars, PyBytes_AS_STRING(ascii_chars_b), 128) != 0) { + PyErr_Format( + PyExc_ValueError, + "This module compiled with c_string_encoding=ascii, but default encoding '%.200s' is not a superset of ascii.", + default_encoding_c); + goto bad; + } + Py_DECREF(ascii_chars_u); + Py_DECREF(ascii_chars_b); + } + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + Py_XDECREF(ascii_chars_u); + Py_XDECREF(ascii_chars_b); + return -1; +} +#endif +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT && PY_MAJOR_VERSION >= 3 +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_DecodeUTF8(c_str, size, NULL) +#else +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_Decode(c_str, size, __PYX_DEFAULT_STRING_ENCODING, NULL) +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +#include +static char* __PYX_DEFAULT_STRING_ENCODING; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) (const char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + __PYX_DEFAULT_STRING_ENCODING = (char*) malloc(strlen(default_encoding_c) + 1); + if (!__PYX_DEFAULT_STRING_ENCODING) goto bad; + strcpy(__PYX_DEFAULT_STRING_ENCODING, default_encoding_c); + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + return -1; +} +#endif +#endif + + +/* Test for GCC > 2.95 */ +#if defined(__GNUC__) && (__GNUC__ > 2 || (__GNUC__ == 2 && (__GNUC_MINOR__ > 95))) + #define likely(x) __builtin_expect(!!(x), 1) + #define unlikely(x) __builtin_expect(!!(x), 0) +#else /* !__GNUC__ or GCC < 2.95 */ + #define likely(x) (x) + #define unlikely(x) (x) +#endif /* __GNUC__ */ +static CYTHON_INLINE void __Pyx_pretend_to_initialize(void* ptr) { (void)ptr; } + +#if !CYTHON_USE_MODULE_STATE +static PyObject *__pyx_m = NULL; +#endif +static int __pyx_lineno; +static int __pyx_clineno = 0; +static const char * __pyx_cfilenm = __FILE__; +static const char *__pyx_filename; + +/* #### Code section: filename_table ### */ + +static const char *__pyx_f[] = { + "", + "selfdrive/modeld/runners/runmodel_pyx.pyx", + "cereal/visionipc/visionipc_pyx.pxd", + "selfdrive/modeld/models/commonmodel_pyx.pxd", +}; +/* #### Code section: utility_code_proto_before_types ### */ +/* ForceInitThreads.proto */ +#ifndef __PYX_FORCE_INIT_THREADS + #define __PYX_FORCE_INIT_THREADS 0 +#endif + +/* NoFastGil.proto */ +#define __Pyx_PyGILState_Ensure PyGILState_Ensure +#define __Pyx_PyGILState_Release PyGILState_Release +#define __Pyx_FastGIL_Remember() +#define __Pyx_FastGIL_Forget() +#define __Pyx_FastGilFuncInit() + +/* BufferFormatStructs.proto */ +struct __Pyx_StructField_; +#define __PYX_BUF_FLAGS_PACKED_STRUCT (1 << 0) +typedef struct { + const char* name; + struct __Pyx_StructField_* fields; + size_t size; + size_t arraysize[8]; + int ndim; + char typegroup; + char is_unsigned; + int flags; +} __Pyx_TypeInfo; +typedef struct __Pyx_StructField_ { + __Pyx_TypeInfo* type; + const char* name; + size_t offset; +} __Pyx_StructField; +typedef struct { + __Pyx_StructField* field; + size_t parent_offset; +} __Pyx_BufFmt_StackElem; +typedef struct { + __Pyx_StructField root; + __Pyx_BufFmt_StackElem* head; + size_t fmt_offset; + size_t new_count, enc_count; + size_t struct_alignment; + int is_complex; + char enc_type; + char new_packmode; + char enc_packmode; + char is_valid_array; +} __Pyx_BufFmt_Context; + +/* Atomics.proto */ +#include +#ifndef CYTHON_ATOMICS + #define CYTHON_ATOMICS 1 +#endif +#define __PYX_CYTHON_ATOMICS_ENABLED() CYTHON_ATOMICS +#define __pyx_atomic_int_type int +#define __pyx_nonatomic_int_type int +#if CYTHON_ATOMICS && (defined(__STDC_VERSION__) &&\ + (__STDC_VERSION__ >= 201112L) &&\ + !defined(__STDC_NO_ATOMICS__)) + #include +#elif CYTHON_ATOMICS && (defined(__cplusplus) && (\ + (__cplusplus >= 201103L) ||\ + (defined(_MSC_VER) && _MSC_VER >= 1700))) + #include +#endif +#if CYTHON_ATOMICS && (defined(__STDC_VERSION__) &&\ + (__STDC_VERSION__ >= 201112L) &&\ + !defined(__STDC_NO_ATOMICS__) &&\ + ATOMIC_INT_LOCK_FREE == 2) + #undef __pyx_atomic_int_type + #define __pyx_atomic_int_type atomic_int + #define __pyx_atomic_incr_aligned(value) atomic_fetch_add_explicit(value, 1, memory_order_relaxed) + #define __pyx_atomic_decr_aligned(value) atomic_fetch_sub_explicit(value, 1, memory_order_acq_rel) + #if defined(__PYX_DEBUG_ATOMICS) && defined(_MSC_VER) + #pragma message ("Using standard C atomics") + #elif defined(__PYX_DEBUG_ATOMICS) + #warning "Using standard C atomics" + #endif +#elif CYTHON_ATOMICS && (defined(__cplusplus) && (\ + (__cplusplus >= 201103L) ||\ +\ + (defined(_MSC_VER) && _MSC_VER >= 1700)) &&\ + ATOMIC_INT_LOCK_FREE == 2) + #undef __pyx_atomic_int_type + #define __pyx_atomic_int_type std::atomic_int + #define __pyx_atomic_incr_aligned(value) std::atomic_fetch_add_explicit(value, 1, std::memory_order_relaxed) + #define __pyx_atomic_decr_aligned(value) std::atomic_fetch_sub_explicit(value, 1, std::memory_order_acq_rel) + #if defined(__PYX_DEBUG_ATOMICS) && defined(_MSC_VER) + #pragma message ("Using standard C++ atomics") + #elif defined(__PYX_DEBUG_ATOMICS) + #warning "Using standard C++ atomics" + #endif +#elif CYTHON_ATOMICS && (__GNUC__ >= 5 || (__GNUC__ == 4 &&\ + (__GNUC_MINOR__ > 1 ||\ + (__GNUC_MINOR__ == 1 && __GNUC_PATCHLEVEL__ >= 2)))) + #define __pyx_atomic_incr_aligned(value) __sync_fetch_and_add(value, 1) + #define __pyx_atomic_decr_aligned(value) __sync_fetch_and_sub(value, 1) + #ifdef __PYX_DEBUG_ATOMICS + #warning "Using GNU atomics" + #endif +#elif CYTHON_ATOMICS && defined(_MSC_VER) + #include + #undef __pyx_atomic_int_type + #define __pyx_atomic_int_type long + #undef __pyx_nonatomic_int_type + #define __pyx_nonatomic_int_type long + #pragma intrinsic (_InterlockedExchangeAdd) + #define __pyx_atomic_incr_aligned(value) _InterlockedExchangeAdd(value, 1) + #define __pyx_atomic_decr_aligned(value) _InterlockedExchangeAdd(value, -1) + #ifdef __PYX_DEBUG_ATOMICS + #pragma message ("Using MSVC atomics") + #endif +#else + #undef CYTHON_ATOMICS + #define CYTHON_ATOMICS 0 + #ifdef __PYX_DEBUG_ATOMICS + #warning "Not using atomics" + #endif +#endif +#if CYTHON_ATOMICS + #define __pyx_add_acquisition_count(memview)\ + __pyx_atomic_incr_aligned(__pyx_get_slice_count_pointer(memview)) + #define __pyx_sub_acquisition_count(memview)\ + __pyx_atomic_decr_aligned(__pyx_get_slice_count_pointer(memview)) +#else + #define __pyx_add_acquisition_count(memview)\ + __pyx_add_acquisition_count_locked(__pyx_get_slice_count_pointer(memview), memview->lock) + #define __pyx_sub_acquisition_count(memview)\ + __pyx_sub_acquisition_count_locked(__pyx_get_slice_count_pointer(memview), memview->lock) +#endif + +/* MemviewSliceStruct.proto */ +struct __pyx_memoryview_obj; +typedef struct { + struct __pyx_memoryview_obj *memview; + char *data; + Py_ssize_t shape[8]; + Py_ssize_t strides[8]; + Py_ssize_t suboffsets[8]; +} __Pyx_memviewslice; +#define __Pyx_MemoryView_Len(m) (m.shape[0]) + +/* #### Code section: numeric_typedefs ### */ +/* #### Code section: complex_type_declarations ### */ +/* #### Code section: type_declarations ### */ + +/*--- Type declarations ---*/ +struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_CLContext; +struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf; +struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext; +struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem; +struct __pyx_obj_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel; +struct __pyx_array_obj; +struct __pyx_MemviewEnum_obj; +struct __pyx_memoryview_obj; +struct __pyx_memoryviewslice_obj; + +/* "cereal/visionipc/visionipc_pyx.pxd":7 + * from .visionipc cimport cl_device_id, cl_context + * + * cdef class CLContext: # <<<<<<<<<<<<<< + * cdef cl_device_id device_id + * cdef cl_context context + */ +struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_CLContext { + PyObject_HEAD + cl_device_id device_id; + cl_context context; +}; + + +/* "cereal/visionipc/visionipc_pyx.pxd":11 + * cdef cl_context context + * + * cdef class VisionBuf: # <<<<<<<<<<<<<< + * cdef cppVisionBuf * buf + * + */ +struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf { + PyObject_HEAD + struct __pyx_vtabstruct_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_vtab; + VisionBuf *buf; +}; + + +/* "selfdrive/modeld/models/commonmodel_pyx.pxd":6 + * from cereal.visionipc.visionipc_pyx cimport CLContext as BaseCLContext + * + * cdef class CLContext(BaseCLContext): # <<<<<<<<<<<<<< + * pass + * + */ +struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext { + struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_CLContext __pyx_base; +}; + + +/* "selfdrive/modeld/models/commonmodel_pyx.pxd":9 + * pass + * + * cdef class CLMem: # <<<<<<<<<<<<<< + * cdef cl_mem * mem + * + */ +struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem { + PyObject_HEAD + struct __pyx_vtabstruct_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem *__pyx_vtab; + cl_mem *mem; +}; + + +/* "selfdrive/modeld/runners/runmodel_pyx.pxd":5 + * from .runmodel cimport RunModel as cppRunModel + * + * cdef class RunModel: # <<<<<<<<<<<<<< + * cdef cppRunModel * model + */ +struct __pyx_obj_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel { + PyObject_HEAD + RunModel *model; +}; + + +/* "View.MemoryView":114 + * @cython.collection_type("sequence") + * @cname("__pyx_array") + * cdef class array: # <<<<<<<<<<<<<< + * + * cdef: + */ +struct __pyx_array_obj { + PyObject_HEAD + struct __pyx_vtabstruct_array *__pyx_vtab; + char *data; + Py_ssize_t len; + char *format; + int ndim; + Py_ssize_t *_shape; + Py_ssize_t *_strides; + Py_ssize_t itemsize; + PyObject *mode; + PyObject *_format; + void (*callback_free_data)(void *); + int free_data; + int dtype_is_object; +}; + + +/* "View.MemoryView":302 + * + * @cname('__pyx_MemviewEnum') + * cdef class Enum(object): # <<<<<<<<<<<<<< + * cdef object name + * def __init__(self, name): + */ +struct __pyx_MemviewEnum_obj { + PyObject_HEAD + PyObject *name; +}; + + +/* "View.MemoryView":337 + * + * @cname('__pyx_memoryview') + * cdef class memoryview: # <<<<<<<<<<<<<< + * + * cdef object obj + */ +struct __pyx_memoryview_obj { + PyObject_HEAD + struct __pyx_vtabstruct_memoryview *__pyx_vtab; + PyObject *obj; + PyObject *_size; + PyObject *_array_interface; + PyThread_type_lock lock; + __pyx_atomic_int_type acquisition_count; + Py_buffer view; + int flags; + int dtype_is_object; + __Pyx_TypeInfo *typeinfo; +}; + + +/* "View.MemoryView":952 + * @cython.collection_type("sequence") + * @cname('__pyx_memoryviewslice') + * cdef class _memoryviewslice(memoryview): # <<<<<<<<<<<<<< + * "Internal class for passing memoryview slices to Python" + * + */ +struct __pyx_memoryviewslice_obj { + struct __pyx_memoryview_obj __pyx_base; + __Pyx_memviewslice from_slice; + PyObject *from_object; + PyObject *(*to_object_func)(char *); + int (*to_dtype_func)(char *, PyObject *); +}; + + + +/* "cereal/visionipc/visionipc_pyx.pxd":11 + * cdef cl_context context + * + * cdef class VisionBuf: # <<<<<<<<<<<<<< + * cdef cppVisionBuf * buf + * + */ + +struct __pyx_vtabstruct_6cereal_9visionipc_13visionipc_pyx_VisionBuf { + PyObject *(*create)(VisionBuf *); +}; +static struct __pyx_vtabstruct_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_vtabptr_6cereal_9visionipc_13visionipc_pyx_VisionBuf; + + +/* "selfdrive/modeld/models/commonmodel_pyx.pxd":9 + * pass + * + * cdef class CLMem: # <<<<<<<<<<<<<< + * cdef cl_mem * mem + * + */ + +struct __pyx_vtabstruct_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem { + PyObject *(*create)(void *); +}; +static struct __pyx_vtabstruct_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem *__pyx_vtabptr_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem; + + +/* "View.MemoryView":114 + * @cython.collection_type("sequence") + * @cname("__pyx_array") + * cdef class array: # <<<<<<<<<<<<<< + * + * cdef: + */ + +struct __pyx_vtabstruct_array { + PyObject *(*get_memview)(struct __pyx_array_obj *); +}; +static struct __pyx_vtabstruct_array *__pyx_vtabptr_array; + + +/* "View.MemoryView":337 + * + * @cname('__pyx_memoryview') + * cdef class memoryview: # <<<<<<<<<<<<<< + * + * cdef object obj + */ + +struct __pyx_vtabstruct_memoryview { + char *(*get_item_pointer)(struct __pyx_memoryview_obj *, PyObject *); + PyObject *(*is_slice)(struct __pyx_memoryview_obj *, PyObject *); + PyObject *(*setitem_slice_assignment)(struct __pyx_memoryview_obj *, PyObject *, PyObject *); + PyObject *(*setitem_slice_assign_scalar)(struct __pyx_memoryview_obj *, struct __pyx_memoryview_obj *, PyObject *); + PyObject *(*setitem_indexed)(struct __pyx_memoryview_obj *, PyObject *, PyObject *); + PyObject *(*convert_item_to_object)(struct __pyx_memoryview_obj *, char *); + PyObject *(*assign_item_from_object)(struct __pyx_memoryview_obj *, char *, PyObject *); + PyObject *(*_get_base)(struct __pyx_memoryview_obj *); +}; +static struct __pyx_vtabstruct_memoryview *__pyx_vtabptr_memoryview; + + +/* "View.MemoryView":952 + * @cython.collection_type("sequence") + * @cname('__pyx_memoryviewslice') + * cdef class _memoryviewslice(memoryview): # <<<<<<<<<<<<<< + * "Internal class for passing memoryview slices to Python" + * + */ + +struct __pyx_vtabstruct__memoryviewslice { + struct __pyx_vtabstruct_memoryview __pyx_base; +}; +static struct __pyx_vtabstruct__memoryviewslice *__pyx_vtabptr__memoryviewslice; +/* #### Code section: utility_code_proto ### */ + +/* --- Runtime support code (head) --- */ +/* Refnanny.proto */ +#ifndef CYTHON_REFNANNY + #define CYTHON_REFNANNY 0 +#endif +#if CYTHON_REFNANNY + typedef struct { + void (*INCREF)(void*, PyObject*, Py_ssize_t); + void (*DECREF)(void*, PyObject*, Py_ssize_t); + void (*GOTREF)(void*, PyObject*, Py_ssize_t); + void (*GIVEREF)(void*, PyObject*, Py_ssize_t); + void* (*SetupContext)(const char*, Py_ssize_t, const char*); + void (*FinishContext)(void**); + } __Pyx_RefNannyAPIStruct; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNanny = NULL; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname); + #define __Pyx_RefNannyDeclarations void *__pyx_refnanny = NULL; +#ifdef WITH_THREAD + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + if (acquire_gil) {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + PyGILState_Release(__pyx_gilstate_save);\ + } else {\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + } + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } +#else + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__)) + #define __Pyx_RefNannyFinishContextNogil() __Pyx_RefNannyFinishContext() +#endif + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } + #define __Pyx_RefNannyFinishContext()\ + __Pyx_RefNanny->FinishContext(&__pyx_refnanny) + #define __Pyx_INCREF(r) __Pyx_RefNanny->INCREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_DECREF(r) __Pyx_RefNanny->DECREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GOTREF(r) __Pyx_RefNanny->GOTREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GIVEREF(r) __Pyx_RefNanny->GIVEREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_XINCREF(r) do { if((r) == NULL); else {__Pyx_INCREF(r); }} while(0) + #define __Pyx_XDECREF(r) do { if((r) == NULL); else {__Pyx_DECREF(r); }} while(0) + #define __Pyx_XGOTREF(r) do { if((r) == NULL); else {__Pyx_GOTREF(r); }} while(0) + #define __Pyx_XGIVEREF(r) do { if((r) == NULL); else {__Pyx_GIVEREF(r);}} while(0) +#else + #define __Pyx_RefNannyDeclarations + #define __Pyx_RefNannySetupContext(name, acquire_gil) + #define __Pyx_RefNannyFinishContextNogil() + #define __Pyx_RefNannyFinishContext() + #define __Pyx_INCREF(r) Py_INCREF(r) + #define __Pyx_DECREF(r) Py_DECREF(r) + #define __Pyx_GOTREF(r) + #define __Pyx_GIVEREF(r) + #define __Pyx_XINCREF(r) Py_XINCREF(r) + #define __Pyx_XDECREF(r) Py_XDECREF(r) + #define __Pyx_XGOTREF(r) + #define __Pyx_XGIVEREF(r) +#endif +#define __Pyx_Py_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; Py_XDECREF(tmp);\ + } while (0) +#define __Pyx_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_XDECREF(tmp);\ + } while (0) +#define __Pyx_DECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_DECREF(tmp);\ + } while (0) +#define __Pyx_CLEAR(r) do { PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);} while(0) +#define __Pyx_XCLEAR(r) do { if((r) != NULL) {PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);}} while(0) + +/* PyErrExceptionMatches.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_ExceptionMatches(err) __Pyx_PyErr_ExceptionMatchesInState(__pyx_tstate, err) +static CYTHON_INLINE int __Pyx_PyErr_ExceptionMatchesInState(PyThreadState* tstate, PyObject* err); +#else +#define __Pyx_PyErr_ExceptionMatches(err) PyErr_ExceptionMatches(err) +#endif + +/* PyThreadStateGet.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyThreadState_declare PyThreadState *__pyx_tstate; +#define __Pyx_PyThreadState_assign __pyx_tstate = __Pyx_PyThreadState_Current; +#if PY_VERSION_HEX >= 0x030C00A6 +#define __Pyx_PyErr_Occurred() (__pyx_tstate->current_exception != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->current_exception ? (PyObject*) Py_TYPE(__pyx_tstate->current_exception) : (PyObject*) NULL) +#else +#define __Pyx_PyErr_Occurred() (__pyx_tstate->curexc_type != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->curexc_type) +#endif +#else +#define __Pyx_PyThreadState_declare +#define __Pyx_PyThreadState_assign +#define __Pyx_PyErr_Occurred() (PyErr_Occurred() != NULL) +#define __Pyx_PyErr_CurrentExceptionType() PyErr_Occurred() +#endif + +/* PyErrFetchRestore.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_Clear() __Pyx_ErrRestore(NULL, NULL, NULL) +#define __Pyx_ErrRestoreWithState(type, value, tb) __Pyx_ErrRestoreInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) __Pyx_ErrFetchInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) __Pyx_ErrRestoreInState(__pyx_tstate, type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) __Pyx_ErrFetchInState(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb); +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A6 +#define __Pyx_PyErr_SetNone(exc) (Py_INCREF(exc), __Pyx_ErrRestore((exc), NULL, NULL)) +#else +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#endif +#else +#define __Pyx_PyErr_Clear() PyErr_Clear() +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#define __Pyx_ErrRestoreWithState(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestoreInState(tstate, type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchInState(tstate, type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) PyErr_Fetch(type, value, tb) +#endif + +/* PyObjectGetAttrStr.proto */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GetAttrStr(o,n) PyObject_GetAttr(o,n) +#endif + +/* PyObjectGetAttrStrNoError.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name); + +/* GetBuiltinName.proto */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name); + +/* TupleAndListFromArray.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n); +static CYTHON_INLINE PyObject* __Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n); +#endif + +/* IncludeStringH.proto */ +#include + +/* BytesEquals.proto */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals); + +/* UnicodeEquals.proto */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals); + +/* fastcall.proto */ +#if CYTHON_AVOID_BORROWED_REFS + #define __Pyx_Arg_VARARGS(args, i) PySequence_GetItem(args, i) +#elif CYTHON_ASSUME_SAFE_MACROS + #define __Pyx_Arg_VARARGS(args, i) PyTuple_GET_ITEM(args, i) +#else + #define __Pyx_Arg_VARARGS(args, i) PyTuple_GetItem(args, i) +#endif +#if CYTHON_AVOID_BORROWED_REFS + #define __Pyx_Arg_NewRef_VARARGS(arg) __Pyx_NewRef(arg) + #define __Pyx_Arg_XDECREF_VARARGS(arg) Py_XDECREF(arg) +#else + #define __Pyx_Arg_NewRef_VARARGS(arg) arg + #define __Pyx_Arg_XDECREF_VARARGS(arg) +#endif +#define __Pyx_NumKwargs_VARARGS(kwds) PyDict_Size(kwds) +#define __Pyx_KwValues_VARARGS(args, nargs) NULL +#define __Pyx_GetKwValue_VARARGS(kw, kwvalues, s) __Pyx_PyDict_GetItemStrWithError(kw, s) +#define __Pyx_KwargsAsDict_VARARGS(kw, kwvalues) PyDict_Copy(kw) +#if CYTHON_METH_FASTCALL + #define __Pyx_Arg_FASTCALL(args, i) args[i] + #define __Pyx_NumKwargs_FASTCALL(kwds) PyTuple_GET_SIZE(kwds) + #define __Pyx_KwValues_FASTCALL(args, nargs) ((args) + (nargs)) + static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 + CYTHON_UNUSED static PyObject *__Pyx_KwargsAsDict_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues); + #else + #define __Pyx_KwargsAsDict_FASTCALL(kw, kwvalues) _PyStack_AsDict(kwvalues, kw) + #endif + #define __Pyx_Arg_NewRef_FASTCALL(arg) arg /* no-op, __Pyx_Arg_FASTCALL is direct and this needs + to have the same reference counting */ + #define __Pyx_Arg_XDECREF_FASTCALL(arg) +#else + #define __Pyx_Arg_FASTCALL __Pyx_Arg_VARARGS + #define __Pyx_NumKwargs_FASTCALL __Pyx_NumKwargs_VARARGS + #define __Pyx_KwValues_FASTCALL __Pyx_KwValues_VARARGS + #define __Pyx_GetKwValue_FASTCALL __Pyx_GetKwValue_VARARGS + #define __Pyx_KwargsAsDict_FASTCALL __Pyx_KwargsAsDict_VARARGS + #define __Pyx_Arg_NewRef_FASTCALL(arg) __Pyx_Arg_NewRef_VARARGS(arg) + #define __Pyx_Arg_XDECREF_FASTCALL(arg) __Pyx_Arg_XDECREF_VARARGS(arg) +#endif +#if CYTHON_COMPILING_IN_CPYTHON && CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_VARARGS(args, start), stop - start) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_FASTCALL(args, start), stop - start) +#else +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) PyTuple_GetSlice(args, start, stop) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) PyTuple_GetSlice(args, start, stop) +#endif + +/* RaiseArgTupleInvalid.proto */ +static void __Pyx_RaiseArgtupleInvalid(const char* func_name, int exact, + Py_ssize_t num_min, Py_ssize_t num_max, Py_ssize_t num_found); + +/* RaiseDoubleKeywords.proto */ +static void __Pyx_RaiseDoubleKeywordsError(const char* func_name, PyObject* kw_name); + +/* ParseKeywords.proto */ +static int __Pyx_ParseOptionalKeywords(PyObject *kwds, PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, PyObject *values[], Py_ssize_t num_pos_args, + const char* function_name); + +/* ArgTypeTest.proto */ +#define __Pyx_ArgTypeTest(obj, type, none_allowed, name, exact)\ + ((likely(__Pyx_IS_TYPE(obj, type) | (none_allowed && (obj == Py_None)))) ? 1 :\ + __Pyx__ArgTypeTest(obj, type, name, exact)) +static int __Pyx__ArgTypeTest(PyObject *obj, PyTypeObject *type, const char *name, int exact); + +/* RaiseException.proto */ +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause); + +/* PyFunctionFastCall.proto */ +#if CYTHON_FAST_PYCALL +#if !CYTHON_VECTORCALL +#define __Pyx_PyFunction_FastCall(func, args, nargs)\ + __Pyx_PyFunction_FastCallDict((func), (args), (nargs), NULL) +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs); +#endif +#define __Pyx_BUILD_ASSERT_EXPR(cond)\ + (sizeof(char [1 - 2*!(cond)]) - 1) +#ifndef Py_MEMBER_SIZE +#define Py_MEMBER_SIZE(type, member) sizeof(((type *)0)->member) +#endif +#if !CYTHON_VECTORCALL +#if PY_VERSION_HEX >= 0x03080000 + #include "frameobject.h" +#if PY_VERSION_HEX >= 0x030b00a6 && !CYTHON_COMPILING_IN_LIMITED_API + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif + #define __Pxy_PyFrame_Initialize_Offsets() + #define __Pyx_PyFrame_GetLocalsplus(frame) ((frame)->f_localsplus) +#else + static size_t __pyx_pyframe_localsplus_offset = 0; + #include "frameobject.h" + #define __Pxy_PyFrame_Initialize_Offsets()\ + ((void)__Pyx_BUILD_ASSERT_EXPR(sizeof(PyFrameObject) == offsetof(PyFrameObject, f_localsplus) + Py_MEMBER_SIZE(PyFrameObject, f_localsplus)),\ + (void)(__pyx_pyframe_localsplus_offset = ((size_t)PyFrame_Type.tp_basicsize) - Py_MEMBER_SIZE(PyFrameObject, f_localsplus))) + #define __Pyx_PyFrame_GetLocalsplus(frame)\ + (assert(__pyx_pyframe_localsplus_offset), (PyObject **)(((char *)(frame)) + __pyx_pyframe_localsplus_offset)) +#endif +#endif +#endif + +/* PyObjectCall.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw); +#else +#define __Pyx_PyObject_Call(func, arg, kw) PyObject_Call(func, arg, kw) +#endif + +/* PyObjectCallMethO.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg); +#endif + +/* PyObjectFastCall.proto */ +#define __Pyx_PyObject_FastCall(func, args, nargs) __Pyx_PyObject_FastCallDict(func, args, (size_t)(nargs), NULL) +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs); + +/* RaiseUnexpectedTypeError.proto */ +static int __Pyx_RaiseUnexpectedTypeError(const char *expected, PyObject *obj); + +/* GCCDiagnostics.proto */ +#if !defined(__INTEL_COMPILER) && defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 6)) +#define __Pyx_HAS_GCC_DIAGNOSTIC +#endif + +/* BuildPyUnicode.proto */ +static PyObject* __Pyx_PyUnicode_BuildFromAscii(Py_ssize_t ulength, char* chars, int clength, + int prepend_sign, char padding_char); + +/* CIntToPyUnicode.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_int(int value, Py_ssize_t width, char padding_char, char format_char); + +/* CIntToPyUnicode.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_Py_ssize_t(Py_ssize_t value, Py_ssize_t width, char padding_char, char format_char); + +/* JoinPyUnicode.proto */ +static PyObject* __Pyx_PyUnicode_Join(PyObject* value_tuple, Py_ssize_t value_count, Py_ssize_t result_ulength, + Py_UCS4 max_char); + +/* StrEquals.proto */ +#if PY_MAJOR_VERSION >= 3 +#define __Pyx_PyString_Equals __Pyx_PyUnicode_Equals +#else +#define __Pyx_PyString_Equals __Pyx_PyBytes_Equals +#endif + +/* PyObjectFormatSimple.proto */ +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + PyObject_Format(s, f)) +#elif PY_MAJOR_VERSION < 3 + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + likely(PyString_CheckExact(s)) ? PyUnicode_FromEncodedObject(s, NULL, "strict") :\ + PyObject_Format(s, f)) +#elif CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + likely(PyLong_CheckExact(s)) ? PyLong_Type.tp_repr(s) :\ + likely(PyFloat_CheckExact(s)) ? PyFloat_Type.tp_repr(s) :\ + PyObject_Format(s, f)) +#else + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + PyObject_Format(s, f)) +#endif + +CYTHON_UNUSED static int __pyx_array_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +static PyObject *__pyx_array_get_memview(struct __pyx_array_obj *); /*proto*/ +/* GetAttr.proto */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr(PyObject *, PyObject *); + +/* GetItemInt.proto */ +#define __Pyx_GetItemInt(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_Fast(o, (Py_ssize_t)i, is_list, wraparound, boundscheck) :\ + (is_list ? (PyErr_SetString(PyExc_IndexError, "list index out of range"), (PyObject*)NULL) :\ + __Pyx_GetItemInt_Generic(o, to_py_func(i)))) +#define __Pyx_GetItemInt_List(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_List_Fast(o, (Py_ssize_t)i, wraparound, boundscheck) :\ + (PyErr_SetString(PyExc_IndexError, "list index out of range"), (PyObject*)NULL)) +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_List_Fast(PyObject *o, Py_ssize_t i, + int wraparound, int boundscheck); +#define __Pyx_GetItemInt_Tuple(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_Tuple_Fast(o, (Py_ssize_t)i, wraparound, boundscheck) :\ + (PyErr_SetString(PyExc_IndexError, "tuple index out of range"), (PyObject*)NULL)) +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Tuple_Fast(PyObject *o, Py_ssize_t i, + int wraparound, int boundscheck); +static PyObject *__Pyx_GetItemInt_Generic(PyObject *o, PyObject* j); +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Fast(PyObject *o, Py_ssize_t i, + int is_list, int wraparound, int boundscheck); + +/* PyObjectCallOneArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg); + +/* ObjectGetItem.proto */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject *__Pyx_PyObject_GetItem(PyObject *obj, PyObject *key); +#else +#define __Pyx_PyObject_GetItem(obj, key) PyObject_GetItem(obj, key) +#endif + +/* KeywordStringCheck.proto */ +static int __Pyx_CheckKeywordStrings(PyObject *kw, const char* function_name, int kw_allowed); + +/* DivInt[Py_ssize_t].proto */ +static CYTHON_INLINE Py_ssize_t __Pyx_div_Py_ssize_t(Py_ssize_t, Py_ssize_t); + +/* UnaryNegOverflows.proto */ +#define __Pyx_UNARY_NEG_WOULD_OVERFLOW(x)\ + (((x) < 0) & ((unsigned long)(x) == 0-(unsigned long)(x))) + +/* GetAttr3.proto */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr3(PyObject *, PyObject *, PyObject *); + +/* PyDictVersioning.proto */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +#define __PYX_DICT_VERSION_INIT ((PY_UINT64_T) -1) +#define __PYX_GET_DICT_VERSION(dict) (((PyDictObject*)(dict))->ma_version_tag) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var)\ + (version_var) = __PYX_GET_DICT_VERSION(dict);\ + (cache_var) = (value); +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + if (likely(__PYX_GET_DICT_VERSION(DICT) == __pyx_dict_version)) {\ + (VAR) = __pyx_dict_cached_value;\ + } else {\ + (VAR) = __pyx_dict_cached_value = (LOOKUP);\ + __pyx_dict_version = __PYX_GET_DICT_VERSION(DICT);\ + }\ +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj); +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj); +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version); +#else +#define __PYX_GET_DICT_VERSION(dict) (0) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var) +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) (VAR) = (LOOKUP); +#endif + +/* GetModuleGlobalName.proto */ +#if CYTHON_USE_DICT_VERSIONS +#define __Pyx_GetModuleGlobalName(var, name) do {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + (var) = (likely(__pyx_dict_version == __PYX_GET_DICT_VERSION(__pyx_d))) ?\ + (likely(__pyx_dict_cached_value) ? __Pyx_NewRef(__pyx_dict_cached_value) : __Pyx_GetBuiltinName(name)) :\ + __Pyx__GetModuleGlobalName(name, &__pyx_dict_version, &__pyx_dict_cached_value);\ +} while(0) +#define __Pyx_GetModuleGlobalNameUncached(var, name) do {\ + PY_UINT64_T __pyx_dict_version;\ + PyObject *__pyx_dict_cached_value;\ + (var) = __Pyx__GetModuleGlobalName(name, &__pyx_dict_version, &__pyx_dict_cached_value);\ +} while(0) +static PyObject *__Pyx__GetModuleGlobalName(PyObject *name, PY_UINT64_T *dict_version, PyObject **dict_cached_value); +#else +#define __Pyx_GetModuleGlobalName(var, name) (var) = __Pyx__GetModuleGlobalName(name) +#define __Pyx_GetModuleGlobalNameUncached(var, name) (var) = __Pyx__GetModuleGlobalName(name) +static CYTHON_INLINE PyObject *__Pyx__GetModuleGlobalName(PyObject *name); +#endif + +/* AssertionsEnabled.proto */ +#if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX < 0x02070600 && !defined(Py_OptimizeFlag) + #define __Pyx_init_assertions_enabled() (0) + #define __pyx_assertions_enabled() (1) +#elif CYTHON_COMPILING_IN_LIMITED_API || (CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030C0000) + static int __pyx_assertions_enabled_flag; + #define __pyx_assertions_enabled() (__pyx_assertions_enabled_flag) + static int __Pyx_init_assertions_enabled(void) { + PyObject *builtins, *debug, *debug_str; + int flag; + builtins = PyEval_GetBuiltins(); + if (!builtins) goto bad; + debug_str = PyUnicode_FromStringAndSize("__debug__", 9); + if (!debug_str) goto bad; + debug = PyObject_GetItem(builtins, debug_str); + Py_DECREF(debug_str); + if (!debug) goto bad; + flag = PyObject_IsTrue(debug); + Py_DECREF(debug); + if (flag == -1) goto bad; + __pyx_assertions_enabled_flag = flag; + return 0; + bad: + __pyx_assertions_enabled_flag = 1; + return -1; + } +#else + #define __Pyx_init_assertions_enabled() (0) + #define __pyx_assertions_enabled() (!Py_OptimizeFlag) +#endif + +/* RaiseTooManyValuesToUnpack.proto */ +static CYTHON_INLINE void __Pyx_RaiseTooManyValuesError(Py_ssize_t expected); + +/* RaiseNeedMoreValuesToUnpack.proto */ +static CYTHON_INLINE void __Pyx_RaiseNeedMoreValuesError(Py_ssize_t index); + +/* RaiseNoneIterError.proto */ +static CYTHON_INLINE void __Pyx_RaiseNoneNotIterableError(void); + +/* ExtTypeTest.proto */ +static CYTHON_INLINE int __Pyx_TypeTest(PyObject *obj, PyTypeObject *type); + +/* GetTopmostException.proto */ +#if CYTHON_USE_EXC_INFO_STACK && CYTHON_FAST_THREAD_STATE +static _PyErr_StackItem * __Pyx_PyErr_GetTopmostException(PyThreadState *tstate); +#endif + +/* SaveResetException.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_ExceptionSave(type, value, tb) __Pyx__ExceptionSave(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx__ExceptionSave(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#define __Pyx_ExceptionReset(type, value, tb) __Pyx__ExceptionReset(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx__ExceptionReset(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb); +#else +#define __Pyx_ExceptionSave(type, value, tb) PyErr_GetExcInfo(type, value, tb) +#define __Pyx_ExceptionReset(type, value, tb) PyErr_SetExcInfo(type, value, tb) +#endif + +/* GetException.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_GetException(type, value, tb) __Pyx__GetException(__pyx_tstate, type, value, tb) +static int __Pyx__GetException(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#else +static int __Pyx_GetException(PyObject **type, PyObject **value, PyObject **tb); +#endif + +/* SwapException.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_ExceptionSwap(type, value, tb) __Pyx__ExceptionSwap(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx__ExceptionSwap(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#else +static CYTHON_INLINE void __Pyx_ExceptionSwap(PyObject **type, PyObject **value, PyObject **tb); +#endif + +/* Import.proto */ +static PyObject *__Pyx_Import(PyObject *name, PyObject *from_list, int level); + +/* ImportDottedModule.proto */ +static PyObject *__Pyx_ImportDottedModule(PyObject *name, PyObject *parts_tuple); +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_ImportDottedModule_WalkParts(PyObject *module, PyObject *name, PyObject *parts_tuple); +#endif + +/* FastTypeChecks.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_TypeCheck(obj, type) __Pyx_IsSubtype(Py_TYPE(obj), (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) __Pyx_IsAnySubtype2(Py_TYPE(obj), (PyTypeObject *)type1, (PyTypeObject *)type2) +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches(PyObject *err, PyObject *type); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches2(PyObject *err, PyObject *type1, PyObject *type2); +#else +#define __Pyx_TypeCheck(obj, type) PyObject_TypeCheck(obj, (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) (PyObject_TypeCheck(obj, (PyTypeObject *)type1) || PyObject_TypeCheck(obj, (PyTypeObject *)type2)) +#define __Pyx_PyErr_GivenExceptionMatches(err, type) PyErr_GivenExceptionMatches(err, type) +#define __Pyx_PyErr_GivenExceptionMatches2(err, type1, type2) (PyErr_GivenExceptionMatches(err, type1) || PyErr_GivenExceptionMatches(err, type2)) +#endif +#define __Pyx_PyErr_ExceptionMatches2(err1, err2) __Pyx_PyErr_GivenExceptionMatches2(__Pyx_PyErr_CurrentExceptionType(), err1, err2) +#define __Pyx_PyException_Check(obj) __Pyx_TypeCheck(obj, PyExc_Exception) + +CYTHON_UNUSED static int __pyx_memoryview_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +/* ListCompAppend.proto */ +#if CYTHON_USE_PYLIST_INTERNALS && CYTHON_ASSUME_SAFE_MACROS +static CYTHON_INLINE int __Pyx_ListComp_Append(PyObject* list, PyObject* x) { + PyListObject* L = (PyListObject*) list; + Py_ssize_t len = Py_SIZE(list); + if (likely(L->allocated > len)) { + Py_INCREF(x); + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 + L->ob_item[len] = x; + #else + PyList_SET_ITEM(list, len, x); + #endif + __Pyx_SET_SIZE(list, len + 1); + return 0; + } + return PyList_Append(list, x); +} +#else +#define __Pyx_ListComp_Append(L,x) PyList_Append(L,x) +#endif + +/* PySequenceMultiply.proto */ +#define __Pyx_PySequence_Multiply_Left(mul, seq) __Pyx_PySequence_Multiply(seq, mul) +static CYTHON_INLINE PyObject* __Pyx_PySequence_Multiply(PyObject *seq, Py_ssize_t mul); + +/* SetItemInt.proto */ +#define __Pyx_SetItemInt(o, i, v, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_SetItemInt_Fast(o, (Py_ssize_t)i, v, is_list, wraparound, boundscheck) :\ + (is_list ? (PyErr_SetString(PyExc_IndexError, "list assignment index out of range"), -1) :\ + __Pyx_SetItemInt_Generic(o, to_py_func(i), v))) +static int __Pyx_SetItemInt_Generic(PyObject *o, PyObject *j, PyObject *v); +static CYTHON_INLINE int __Pyx_SetItemInt_Fast(PyObject *o, Py_ssize_t i, PyObject *v, + int is_list, int wraparound, int boundscheck); + +/* RaiseUnboundLocalError.proto */ +static CYTHON_INLINE void __Pyx_RaiseUnboundLocalError(const char *varname); + +/* DivInt[long].proto */ +static CYTHON_INLINE long __Pyx_div_long(long, long); + +/* PySequenceContains.proto */ +static CYTHON_INLINE int __Pyx_PySequence_ContainsTF(PyObject* item, PyObject* seq, int eq) { + int result = PySequence_Contains(seq, item); + return unlikely(result < 0) ? result : (result == (eq == Py_EQ)); +} + +/* ImportFrom.proto */ +static PyObject* __Pyx_ImportFrom(PyObject* module, PyObject* name); + +/* HasAttr.proto */ +#if __PYX_LIMITED_VERSION_HEX >= 0x030d00A1 +#define __Pyx_HasAttr(o, n) PyObject_HasAttrWithError(o, n) +#else +static CYTHON_INLINE int __Pyx_HasAttr(PyObject *, PyObject *); +#endif + +/* MoveIfSupported.proto */ +#if CYTHON_USE_CPP_STD_MOVE + #include + #define __PYX_STD_MOVE_IF_SUPPORTED(x) std::move(x) +#else + #define __PYX_STD_MOVE_IF_SUPPORTED(x) x +#endif + +/* BufferIndexError.proto */ +static void __Pyx_RaiseBufferIndexError(int axis); + +/* PyObject_GenericGetAttrNoDict.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttrNoDict PyObject_GenericGetAttr +#endif + +/* PyObject_GenericGetAttr.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttr PyObject_GenericGetAttr +#endif + +/* IncludeStructmemberH.proto */ +#include + +/* FixUpExtensionType.proto */ +#if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type); +#endif + +/* PyObjectCallNoArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func); + +/* PyObjectGetMethod.proto */ +static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method); + +/* PyObjectCallMethod0.proto */ +static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name); + +/* ValidateBasesTuple.proto */ +#if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases); +#endif + +/* PyType_Ready.proto */ +CYTHON_UNUSED static int __Pyx_PyType_Ready(PyTypeObject *t); + +/* SetupReduce.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce(PyObject* type_obj); +#endif + +/* SetVTable.proto */ +static int __Pyx_SetVtable(PyTypeObject* typeptr , void* vtable); + +/* GetVTable.proto */ +static void* __Pyx_GetVtable(PyTypeObject *type); + +/* MergeVTables.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_MergeVtables(PyTypeObject *type); +#endif + +/* TypeImport.proto */ +#ifndef __PYX_HAVE_RT_ImportType_proto_3_0_8 +#define __PYX_HAVE_RT_ImportType_proto_3_0_8 +#if defined (__STDC_VERSION__) && __STDC_VERSION__ >= 201112L +#include +#endif +#if (defined (__STDC_VERSION__) && __STDC_VERSION__ >= 201112L) || __cplusplus >= 201103L +#define __PYX_GET_STRUCT_ALIGNMENT_3_0_8(s) alignof(s) +#else +#define __PYX_GET_STRUCT_ALIGNMENT_3_0_8(s) sizeof(void*) +#endif +enum __Pyx_ImportType_CheckSize_3_0_8 { + __Pyx_ImportType_CheckSize_Error_3_0_8 = 0, + __Pyx_ImportType_CheckSize_Warn_3_0_8 = 1, + __Pyx_ImportType_CheckSize_Ignore_3_0_8 = 2 +}; +static PyTypeObject *__Pyx_ImportType_3_0_8(PyObject* module, const char *module_name, const char *class_name, size_t size, size_t alignment, enum __Pyx_ImportType_CheckSize_3_0_8 check_size); +#endif + +/* SetNameInClass.proto */ +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030500A1 && PY_VERSION_HEX < 0x030d0000 +#define __Pyx_SetNameInClass(ns, name, value)\ + (likely(PyDict_CheckExact(ns)) ? _PyDict_SetItem_KnownHash(ns, name, value, ((PyASCIIObject *) name)->hash) : PyObject_SetItem(ns, name, value)) +#elif CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_SetNameInClass(ns, name, value)\ + (likely(PyDict_CheckExact(ns)) ? PyDict_SetItem(ns, name, value) : PyObject_SetItem(ns, name, value)) +#else +#define __Pyx_SetNameInClass(ns, name, value) PyObject_SetItem(ns, name, value) +#endif + +/* CalculateMetaclass.proto */ +static PyObject *__Pyx_CalculateMetaclass(PyTypeObject *metaclass, PyObject *bases); + +/* PyObjectCall2Args.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call2Args(PyObject* function, PyObject* arg1, PyObject* arg2); + +/* PyObjectLookupSpecial.proto */ +#if CYTHON_USE_PYTYPE_LOOKUP && CYTHON_USE_TYPE_SLOTS +#define __Pyx_PyObject_LookupSpecialNoError(obj, attr_name) __Pyx__PyObject_LookupSpecial(obj, attr_name, 0) +#define __Pyx_PyObject_LookupSpecial(obj, attr_name) __Pyx__PyObject_LookupSpecial(obj, attr_name, 1) +static CYTHON_INLINE PyObject* __Pyx__PyObject_LookupSpecial(PyObject* obj, PyObject* attr_name, int with_error); +#else +#define __Pyx_PyObject_LookupSpecialNoError(o,n) __Pyx_PyObject_GetAttrStrNoError(o,n) +#define __Pyx_PyObject_LookupSpecial(o,n) __Pyx_PyObject_GetAttrStr(o,n) +#endif + +/* Py3ClassCreate.proto */ +static PyObject *__Pyx_Py3MetaclassPrepare(PyObject *metaclass, PyObject *bases, PyObject *name, PyObject *qualname, + PyObject *mkw, PyObject *modname, PyObject *doc); +static PyObject *__Pyx_Py3ClassCreate(PyObject *metaclass, PyObject *name, PyObject *bases, PyObject *dict, + PyObject *mkw, int calculate_metaclass, int allow_py2_metaclass); + +/* FetchSharedCythonModule.proto */ +static PyObject *__Pyx_FetchSharedCythonABIModule(void); + +/* FetchCommonType.proto */ +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type); +#else +static PyTypeObject* __Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases); +#endif + +/* PyMethodNew.proto */ +#if CYTHON_COMPILING_IN_LIMITED_API +static PyObject *__Pyx_PyMethod_New(PyObject *func, PyObject *self, PyObject *typ) { + PyObject *typesModule=NULL, *methodType=NULL, *result=NULL; + CYTHON_UNUSED_VAR(typ); + if (!self) + return __Pyx_NewRef(func); + typesModule = PyImport_ImportModule("types"); + if (!typesModule) return NULL; + methodType = PyObject_GetAttrString(typesModule, "MethodType"); + Py_DECREF(typesModule); + if (!methodType) return NULL; + result = PyObject_CallFunctionObjArgs(methodType, func, self, NULL); + Py_DECREF(methodType); + return result; +} +#elif PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_PyMethod_New(PyObject *func, PyObject *self, PyObject *typ) { + CYTHON_UNUSED_VAR(typ); + if (!self) + return __Pyx_NewRef(func); + return PyMethod_New(func, self); +} +#else + #define __Pyx_PyMethod_New PyMethod_New +#endif + +/* PyVectorcallFastCallDict.proto */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw); +#endif + +/* CythonFunctionShared.proto */ +#define __Pyx_CyFunction_USED +#define __Pyx_CYFUNCTION_STATICMETHOD 0x01 +#define __Pyx_CYFUNCTION_CLASSMETHOD 0x02 +#define __Pyx_CYFUNCTION_CCLASS 0x04 +#define __Pyx_CYFUNCTION_COROUTINE 0x08 +#define __Pyx_CyFunction_GetClosure(f)\ + (((__pyx_CyFunctionObject *) (f))->func_closure) +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_CyFunction_GetClassObj(f)\ + (((__pyx_CyFunctionObject *) (f))->func_classobj) +#else + #define __Pyx_CyFunction_GetClassObj(f)\ + ((PyObject*) ((PyCMethodObject *) (f))->mm_class) +#endif +#define __Pyx_CyFunction_SetClassObj(f, classobj)\ + __Pyx__CyFunction_SetClassObj((__pyx_CyFunctionObject *) (f), (classobj)) +#define __Pyx_CyFunction_Defaults(type, f)\ + ((type *)(((__pyx_CyFunctionObject *) (f))->defaults)) +#define __Pyx_CyFunction_SetDefaultsGetter(f, g)\ + ((__pyx_CyFunctionObject *) (f))->defaults_getter = (g) +typedef struct { +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject_HEAD + PyObject *func; +#elif PY_VERSION_HEX < 0x030900B1 + PyCFunctionObject func; +#else + PyCMethodObject func; +#endif +#if CYTHON_BACKPORT_VECTORCALL + __pyx_vectorcallfunc func_vectorcall; +#endif +#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API + PyObject *func_weakreflist; +#endif + PyObject *func_dict; + PyObject *func_name; + PyObject *func_qualname; + PyObject *func_doc; + PyObject *func_globals; + PyObject *func_code; + PyObject *func_closure; +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + PyObject *func_classobj; +#endif + void *defaults; + int defaults_pyobjects; + size_t defaults_size; + int flags; + PyObject *defaults_tuple; + PyObject *defaults_kwdict; + PyObject *(*defaults_getter)(PyObject *); + PyObject *func_annotations; + PyObject *func_is_coroutine; +} __pyx_CyFunctionObject; +#undef __Pyx_CyOrPyCFunction_Check +#define __Pyx_CyFunction_Check(obj) __Pyx_TypeCheck(obj, __pyx_CyFunctionType) +#define __Pyx_CyOrPyCFunction_Check(obj) __Pyx_TypeCheck2(obj, __pyx_CyFunctionType, &PyCFunction_Type) +#define __Pyx_CyFunction_CheckExact(obj) __Pyx_IS_TYPE(obj, __pyx_CyFunctionType) +static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc); +#undef __Pyx_IsSameCFunction +#define __Pyx_IsSameCFunction(func, cfunc) __Pyx__IsSameCyOrCFunction(func, cfunc) +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject* op, PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj); +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *m, + size_t size, + int pyobjects); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *m, + PyObject *tuple); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *m, + PyObject *dict); +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *m, + PyObject *dict); +static int __pyx_CyFunction_init(PyObject *module); +#if CYTHON_METH_FASTCALL +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +#if CYTHON_BACKPORT_VECTORCALL +#define __Pyx_CyFunction_func_vectorcall(f) (((__pyx_CyFunctionObject*)f)->func_vectorcall) +#else +#define __Pyx_CyFunction_func_vectorcall(f) (((PyCFunctionObject*)f)->vectorcall) +#endif +#endif + +/* CythonFunction.proto */ +static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); + +/* CLineInTraceback.proto */ +#ifdef CYTHON_CLINE_IN_TRACEBACK +#define __Pyx_CLineForTraceback(tstate, c_line) (((CYTHON_CLINE_IN_TRACEBACK)) ? c_line : 0) +#else +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line); +#endif + +/* CodeObjectCache.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +typedef struct { + PyCodeObject* code_object; + int code_line; +} __Pyx_CodeObjectCacheEntry; +struct __Pyx_CodeObjectCache { + int count; + int max_count; + __Pyx_CodeObjectCacheEntry* entries; +}; +static struct __Pyx_CodeObjectCache __pyx_code_cache = {0,0,NULL}; +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line); +static PyCodeObject *__pyx_find_code_object(int code_line); +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object); +#endif + +/* AddTraceback.proto */ +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename); + +#if PY_MAJOR_VERSION < 3 + static int __Pyx_GetBuffer(PyObject *obj, Py_buffer *view, int flags); + static void __Pyx_ReleaseBuffer(Py_buffer *view); +#else + #define __Pyx_GetBuffer PyObject_GetBuffer + #define __Pyx_ReleaseBuffer PyBuffer_Release +#endif + + +/* BufferStructDeclare.proto */ +typedef struct { + Py_ssize_t shape, strides, suboffsets; +} __Pyx_Buf_DimInfo; +typedef struct { + size_t refcount; + Py_buffer pybuffer; +} __Pyx_Buffer; +typedef struct { + __Pyx_Buffer *rcbuffer; + char *data; + __Pyx_Buf_DimInfo diminfo[8]; +} __Pyx_LocalBuf_ND; + +/* MemviewSliceIsContig.proto */ +static int __pyx_memviewslice_is_contig(const __Pyx_memviewslice mvs, char order, int ndim); + +/* OverlappingSlices.proto */ +static int __pyx_slices_overlap(__Pyx_memviewslice *slice1, + __Pyx_memviewslice *slice2, + int ndim, size_t itemsize); + +/* IsLittleEndian.proto */ +static CYTHON_INLINE int __Pyx_Is_Little_Endian(void); + +/* BufferFormatCheck.proto */ +static const char* __Pyx_BufFmt_CheckString(__Pyx_BufFmt_Context* ctx, const char* ts); +static void __Pyx_BufFmt_Init(__Pyx_BufFmt_Context* ctx, + __Pyx_BufFmt_StackElem* stack, + __Pyx_TypeInfo* type); + +/* TypeInfoCompare.proto */ +static int __pyx_typeinfo_cmp(__Pyx_TypeInfo *a, __Pyx_TypeInfo *b); + +/* MemviewSliceValidateAndInit.proto */ +static int __Pyx_ValidateAndInit_memviewslice( + int *axes_specs, + int c_or_f_flag, + int buf_flags, + int ndim, + __Pyx_TypeInfo *dtype, + __Pyx_BufFmt_StackElem stack[], + __Pyx_memviewslice *memviewslice, + PyObject *original_obj); + +/* ObjectToMemviewSlice.proto */ +static CYTHON_INLINE __Pyx_memviewslice __Pyx_PyObject_to_MemoryviewSlice_ds_float(PyObject *, int writable_flag); + +/* MemviewDtypeToObject.proto */ +static CYTHON_INLINE PyObject *__pyx_memview_get_float(const char *itemp); +static CYTHON_INLINE int __pyx_memview_set_float(const char *itemp, PyObject *obj); + +/* MemviewSliceCopyTemplate.proto */ +static __Pyx_memviewslice +__pyx_memoryview_copy_new_contig(const __Pyx_memviewslice *from_mvs, + const char *mode, int ndim, + size_t sizeof_dtype, int contig_flag, + int dtype_is_object); + +/* MemviewSliceInit.proto */ +#define __Pyx_BUF_MAX_NDIMS %(BUF_MAX_NDIMS)d +#define __Pyx_MEMVIEW_DIRECT 1 +#define __Pyx_MEMVIEW_PTR 2 +#define __Pyx_MEMVIEW_FULL 4 +#define __Pyx_MEMVIEW_CONTIG 8 +#define __Pyx_MEMVIEW_STRIDED 16 +#define __Pyx_MEMVIEW_FOLLOW 32 +#define __Pyx_IS_C_CONTIG 1 +#define __Pyx_IS_F_CONTIG 2 +static int __Pyx_init_memviewslice( + struct __pyx_memoryview_obj *memview, + int ndim, + __Pyx_memviewslice *memviewslice, + int memview_is_new_reference); +static CYTHON_INLINE int __pyx_add_acquisition_count_locked( + __pyx_atomic_int_type *acquisition_count, PyThread_type_lock lock); +static CYTHON_INLINE int __pyx_sub_acquisition_count_locked( + __pyx_atomic_int_type *acquisition_count, PyThread_type_lock lock); +#define __pyx_get_slice_count_pointer(memview) (&memview->acquisition_count) +#define __PYX_INC_MEMVIEW(slice, have_gil) __Pyx_INC_MEMVIEW(slice, have_gil, __LINE__) +#define __PYX_XCLEAR_MEMVIEW(slice, have_gil) __Pyx_XCLEAR_MEMVIEW(slice, have_gil, __LINE__) +static CYTHON_INLINE void __Pyx_INC_MEMVIEW(__Pyx_memviewslice *, int, int); +static CYTHON_INLINE void __Pyx_XCLEAR_MEMVIEW(__Pyx_memviewslice *, int, int); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_int(int value); + +/* CppExceptionConversion.proto */ +#ifndef __Pyx_CppExn2PyErr +#include +#include +#include +#include +static void __Pyx_CppExn2PyErr() { + try { + if (PyErr_Occurred()) + ; // let the latest Python exn pass through and ignore the current one + else + throw; + } catch (const std::bad_alloc& exn) { + PyErr_SetString(PyExc_MemoryError, exn.what()); + } catch (const std::bad_cast& exn) { + PyErr_SetString(PyExc_TypeError, exn.what()); + } catch (const std::bad_typeid& exn) { + PyErr_SetString(PyExc_TypeError, exn.what()); + } catch (const std::domain_error& exn) { + PyErr_SetString(PyExc_ValueError, exn.what()); + } catch (const std::invalid_argument& exn) { + PyErr_SetString(PyExc_ValueError, exn.what()); + } catch (const std::ios_base::failure& exn) { + PyErr_SetString(PyExc_IOError, exn.what()); + } catch (const std::out_of_range& exn) { + PyErr_SetString(PyExc_IndexError, exn.what()); + } catch (const std::overflow_error& exn) { + PyErr_SetString(PyExc_OverflowError, exn.what()); + } catch (const std::range_error& exn) { + PyErr_SetString(PyExc_ArithmeticError, exn.what()); + } catch (const std::underflow_error& exn) { + PyErr_SetString(PyExc_ArithmeticError, exn.what()); + } catch (const std::exception& exn) { + PyErr_SetString(PyExc_RuntimeError, exn.what()); + } + catch (...) + { + PyErr_SetString(PyExc_RuntimeError, "Unknown exception"); + } +} +#endif + +/* None.proto */ +#include + +/* CIntFromPy.proto */ +static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *); + +/* CIntFromPy.proto */ +static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value); + +/* CIntFromPy.proto */ +static CYTHON_INLINE char __Pyx_PyInt_As_char(PyObject *); + +/* FormatTypeName.proto */ +#if CYTHON_COMPILING_IN_LIMITED_API +typedef PyObject *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%U" +static __Pyx_TypeName __Pyx_PyType_GetName(PyTypeObject* tp); +#define __Pyx_DECREF_TypeName(obj) Py_XDECREF(obj) +#else +typedef const char *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%.200s" +#define __Pyx_PyType_GetName(tp) ((tp)->tp_name) +#define __Pyx_DECREF_TypeName(obj) +#endif + +/* CheckBinaryVersion.proto */ +static unsigned long __Pyx_get_runtime_version(void); +static int __Pyx_check_binary_version(unsigned long ct_version, unsigned long rt_version, int allow_newer); + +/* InitStrings.proto */ +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t); + +/* #### Code section: module_declarations ### */ +static PyObject *__pyx_array_get_memview(struct __pyx_array_obj *__pyx_v_self); /* proto*/ +static char *__pyx_memoryview_get_item_pointer(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index); /* proto*/ +static PyObject *__pyx_memoryview_is_slice(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj); /* proto*/ +static PyObject *__pyx_memoryview_setitem_slice_assignment(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_dst, PyObject *__pyx_v_src); /* proto*/ +static PyObject *__pyx_memoryview_setitem_slice_assign_scalar(struct __pyx_memoryview_obj *__pyx_v_self, struct __pyx_memoryview_obj *__pyx_v_dst, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryview_setitem_indexed(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryview_convert_item_to_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp); /* proto*/ +static PyObject *__pyx_memoryview_assign_item_from_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryview__get_base(struct __pyx_memoryview_obj *__pyx_v_self); /* proto*/ +static PyObject *__pyx_memoryviewslice_convert_item_to_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp); /* proto*/ +static PyObject *__pyx_memoryviewslice_assign_item_from_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryviewslice__get_base(struct __pyx_memoryviewslice_obj *__pyx_v_self); /* proto*/ + +/* Module declarations from "libc.string" */ + +/* Module declarations from "libcpp.string" */ + +/* Module declarations from "selfdrive.modeld.runners.runmodel" */ + +/* Module declarations from "libcpp.vector" */ + +/* Module declarations from "libcpp.utility" */ + +/* Module declarations from "libcpp.set" */ + +/* Module declarations from "libc.stdint" */ + +/* Module declarations from "libcpp" */ + +/* Module declarations from "cereal.visionipc.visionipc" */ + +/* Module declarations from "cereal.visionipc.visionipc_pyx" */ + +/* Module declarations from "selfdrive.modeld.models.commonmodel_pyx" */ + +/* Module declarations from "selfdrive.modeld.runners.runmodel_pyx" */ +static PyObject *__pyx_collections_abc_Sequence = 0; +static PyObject *generic = 0; +static PyObject *strided = 0; +static PyObject *indirect = 0; +static PyObject *contiguous = 0; +static PyObject *indirect_contiguous = 0; +static int __pyx_memoryview_thread_locks_used; +static PyThread_type_lock __pyx_memoryview_thread_locks[8]; +static std::string __pyx_convert_string_from_py_std__in_string(PyObject *); /*proto*/ +static int __pyx_array_allocate_buffer(struct __pyx_array_obj *); /*proto*/ +static struct __pyx_array_obj *__pyx_array_new(PyObject *, Py_ssize_t, char *, char *, char *); /*proto*/ +static PyObject *__pyx_memoryview_new(PyObject *, int, int, __Pyx_TypeInfo *); /*proto*/ +static CYTHON_INLINE int __pyx_memoryview_check(PyObject *); /*proto*/ +static PyObject *_unellipsify(PyObject *, int); /*proto*/ +static int assert_direct_dimensions(Py_ssize_t *, int); /*proto*/ +static struct __pyx_memoryview_obj *__pyx_memview_slice(struct __pyx_memoryview_obj *, PyObject *); /*proto*/ +static int __pyx_memoryview_slice_memviewslice(__Pyx_memviewslice *, Py_ssize_t, Py_ssize_t, Py_ssize_t, int, int, int *, Py_ssize_t, Py_ssize_t, Py_ssize_t, int, int, int, int); /*proto*/ +static char *__pyx_pybuffer_index(Py_buffer *, char *, Py_ssize_t, Py_ssize_t); /*proto*/ +static int __pyx_memslice_transpose(__Pyx_memviewslice *); /*proto*/ +static PyObject *__pyx_memoryview_fromslice(__Pyx_memviewslice, int, PyObject *(*)(char *), int (*)(char *, PyObject *), int); /*proto*/ +static __Pyx_memviewslice *__pyx_memoryview_get_slice_from_memoryview(struct __pyx_memoryview_obj *, __Pyx_memviewslice *); /*proto*/ +static void __pyx_memoryview_slice_copy(struct __pyx_memoryview_obj *, __Pyx_memviewslice *); /*proto*/ +static PyObject *__pyx_memoryview_copy_object(struct __pyx_memoryview_obj *); /*proto*/ +static PyObject *__pyx_memoryview_copy_object_from_slice(struct __pyx_memoryview_obj *, __Pyx_memviewslice *); /*proto*/ +static Py_ssize_t abs_py_ssize_t(Py_ssize_t); /*proto*/ +static char __pyx_get_best_slice_order(__Pyx_memviewslice *, int); /*proto*/ +static void _copy_strided_to_strided(char *, Py_ssize_t *, char *, Py_ssize_t *, Py_ssize_t *, Py_ssize_t *, int, size_t); /*proto*/ +static void copy_strided_to_strided(__Pyx_memviewslice *, __Pyx_memviewslice *, int, size_t); /*proto*/ +static Py_ssize_t __pyx_memoryview_slice_get_size(__Pyx_memviewslice *, int); /*proto*/ +static Py_ssize_t __pyx_fill_contig_strides_array(Py_ssize_t *, Py_ssize_t *, Py_ssize_t, int, char); /*proto*/ +static void *__pyx_memoryview_copy_data_to_temp(__Pyx_memviewslice *, __Pyx_memviewslice *, char, int); /*proto*/ +static int __pyx_memoryview_err_extents(int, Py_ssize_t, Py_ssize_t); /*proto*/ +static int __pyx_memoryview_err_dim(PyObject *, PyObject *, int); /*proto*/ +static int __pyx_memoryview_err(PyObject *, PyObject *); /*proto*/ +static int __pyx_memoryview_err_no_memory(void); /*proto*/ +static int __pyx_memoryview_copy_contents(__Pyx_memviewslice, __Pyx_memviewslice, int, int, int); /*proto*/ +static void __pyx_memoryview_broadcast_leading(__Pyx_memviewslice *, int, int); /*proto*/ +static void __pyx_memoryview_refcount_copying(__Pyx_memviewslice *, int, int, int); /*proto*/ +static void __pyx_memoryview_refcount_objects_in_slice_with_gil(char *, Py_ssize_t *, Py_ssize_t *, int, int); /*proto*/ +static void __pyx_memoryview_refcount_objects_in_slice(char *, Py_ssize_t *, Py_ssize_t *, int, int); /*proto*/ +static void __pyx_memoryview_slice_assign_scalar(__Pyx_memviewslice *, int, size_t, void *, int); /*proto*/ +static void __pyx_memoryview__slice_assign_scalar(char *, Py_ssize_t *, Py_ssize_t *, int, size_t, void *); /*proto*/ +static PyObject *__pyx_unpickle_Enum__set_state(struct __pyx_MemviewEnum_obj *, PyObject *); /*proto*/ +/* #### Code section: typeinfo ### */ +static __Pyx_TypeInfo __Pyx_TypeInfo_float = { "float", NULL, sizeof(float), { 0 }, 0, 'R', 0, 0 }; +/* #### Code section: before_global_var ### */ +#define __Pyx_MODULE_NAME "selfdrive.modeld.runners.runmodel_pyx" +extern int __pyx_module_is_main_selfdrive__modeld__runners__runmodel_pyx; +int __pyx_module_is_main_selfdrive__modeld__runners__runmodel_pyx = 0; + +/* Implementation of "selfdrive.modeld.runners.runmodel_pyx" */ +/* #### Code section: global_var ### */ +static PyObject *__pyx_builtin_TypeError; +static PyObject *__pyx_builtin___import__; +static PyObject *__pyx_builtin_ValueError; +static PyObject *__pyx_builtin_MemoryError; +static PyObject *__pyx_builtin_enumerate; +static PyObject *__pyx_builtin_range; +static PyObject *__pyx_builtin_AssertionError; +static PyObject *__pyx_builtin_Ellipsis; +static PyObject *__pyx_builtin_id; +static PyObject *__pyx_builtin_IndexError; +/* #### Code section: string_decls ### */ +static const char __pyx_k_[] = ": "; +static const char __pyx_k_O[] = "O"; +static const char __pyx_k_c[] = "c"; +static const char __pyx_k__2[] = "."; +static const char __pyx_k__3[] = "*"; +static const char __pyx_k__6[] = "'"; +static const char __pyx_k__7[] = ")"; +static const char __pyx_k_gc[] = "gc"; +static const char __pyx_k_id[] = "id"; +static const char __pyx_k_CPU[] = "CPU"; +static const char __pyx_k_DSP[] = "DSP"; +static const char __pyx_k_GPU[] = "GPU"; +static const char __pyx_k__30[] = "?"; +static const char __pyx_k_abc[] = "abc"; +static const char __pyx_k_and[] = " and "; +static const char __pyx_k_doc[] = "__doc__"; +static const char __pyx_k_got[] = " (got "; +static const char __pyx_k_new[] = "__new__"; +static const char __pyx_k_obj[] = "obj"; +static const char __pyx_k_sys[] = "sys"; +static const char __pyx_k_base[] = "base"; +static const char __pyx_k_dict[] = "__dict__"; +static const char __pyx_k_main[] = "__main__"; +static const char __pyx_k_mode[] = "mode"; +static const char __pyx_k_name[] = "name"; +static const char __pyx_k_ndim[] = "ndim"; +static const char __pyx_k_pack[] = "pack"; +static const char __pyx_k_self[] = "self"; +static const char __pyx_k_size[] = "size"; +static const char __pyx_k_spec[] = "__spec__"; +static const char __pyx_k_step[] = "step"; +static const char __pyx_k_stop[] = "stop"; +static const char __pyx_k_test[] = "__test__"; +static const char __pyx_k_ASCII[] = "ASCII"; +static const char __pyx_k_class[] = "__class__"; +static const char __pyx_k_count[] = "count"; +static const char __pyx_k_error[] = "error"; +static const char __pyx_k_flags[] = "flags"; +static const char __pyx_k_index[] = "index"; +static const char __pyx_k_range[] = "range"; +static const char __pyx_k_shape[] = "shape"; +static const char __pyx_k_start[] = "start"; +static const char __pyx_k_super[] = "super"; +static const char __pyx_k_buffer[] = "buffer"; +static const char __pyx_k_cl_buf[] = "cl_buf"; +static const char __pyx_k_enable[] = "enable"; +static const char __pyx_k_encode[] = "encode"; +static const char __pyx_k_format[] = "format"; +static const char __pyx_k_import[] = "__import__"; +static const char __pyx_k_module[] = "__module__"; +static const char __pyx_k_name_2[] = "__name__"; +static const char __pyx_k_pickle[] = "pickle"; +static const char __pyx_k_reduce[] = "__reduce__"; +static const char __pyx_k_struct[] = "struct"; +static const char __pyx_k_unpack[] = "unpack"; +static const char __pyx_k_update[] = "update"; +static const char __pyx_k_Runtime[] = "Runtime"; +static const char __pyx_k_disable[] = "disable"; +static const char __pyx_k_execute[] = "execute"; +static const char __pyx_k_fortran[] = "fortran"; +static const char __pyx_k_memview[] = "memview"; +static const char __pyx_k_prepare[] = "__prepare__"; +static const char __pyx_k_Ellipsis[] = "Ellipsis"; +static const char __pyx_k_RunModel[] = "RunModel"; +static const char __pyx_k_Sequence[] = "Sequence"; +static const char __pyx_k_addInput[] = "addInput"; +static const char __pyx_k_getstate[] = "__getstate__"; +static const char __pyx_k_itemsize[] = "itemsize"; +static const char __pyx_k_pyx_type[] = "__pyx_type"; +static const char __pyx_k_qualname[] = "__qualname__"; +static const char __pyx_k_register[] = "register"; +static const char __pyx_k_set_name[] = "__set_name__"; +static const char __pyx_k_setstate[] = "__setstate__"; +static const char __pyx_k_TypeError[] = "TypeError"; +static const char __pyx_k_enumerate[] = "enumerate"; +static const char __pyx_k_isenabled[] = "isenabled"; +static const char __pyx_k_metaclass[] = "__metaclass__"; +static const char __pyx_k_pyx_state[] = "__pyx_state"; +static const char __pyx_k_reduce_ex[] = "__reduce_ex__"; +static const char __pyx_k_IndexError[] = "IndexError"; +static const char __pyx_k_ValueError[] = "ValueError"; +static const char __pyx_k_pyx_result[] = "__pyx_result"; +static const char __pyx_k_pyx_vtable[] = "__pyx_vtable__"; +static const char __pyx_k_MemoryError[] = "MemoryError"; +static const char __pyx_k_PickleError[] = "PickleError"; +static const char __pyx_k_collections[] = "collections"; +static const char __pyx_k_getCLBuffer[] = "getCLBuffer"; +static const char __pyx_k_initializing[] = "_initializing"; +static const char __pyx_k_is_coroutine[] = "_is_coroutine"; +static const char __pyx_k_pyx_checksum[] = "__pyx_checksum"; +static const char __pyx_k_stringsource[] = ""; +static const char __pyx_k_version_info[] = "version_info"; +static const char __pyx_k_class_getitem[] = "__class_getitem__"; +static const char __pyx_k_init_subclass[] = "__init_subclass__"; +static const char __pyx_k_reduce_cython[] = "__reduce_cython__"; +static const char __pyx_k_AssertionError[] = "AssertionError"; +static const char __pyx_k_setInputBuffer[] = "setInputBuffer"; +static const char __pyx_k_View_MemoryView[] = "View.MemoryView"; +static const char __pyx_k_allocate_buffer[] = "allocate_buffer"; +static const char __pyx_k_collections_abc[] = "collections.abc"; +static const char __pyx_k_dtype_is_object[] = "dtype_is_object"; +static const char __pyx_k_pyx_PickleError[] = "__pyx_PickleError"; +static const char __pyx_k_setstate_cython[] = "__setstate_cython__"; +static const char __pyx_k_RunModel_execute[] = "RunModel.execute"; +static const char __pyx_k_RunModel_addInput[] = "RunModel.addInput"; +static const char __pyx_k_pyx_unpickle_Enum[] = "__pyx_unpickle_Enum"; +static const char __pyx_k_asyncio_coroutines[] = "asyncio.coroutines"; +static const char __pyx_k_cline_in_traceback[] = "cline_in_traceback"; +static const char __pyx_k_strided_and_direct[] = ""; +static const char __pyx_k_RunModel_getCLBuffer[] = "RunModel.getCLBuffer"; +static const char __pyx_k_strided_and_indirect[] = ""; +static const char __pyx_k_Invalid_shape_in_axis[] = "Invalid shape in axis "; +static const char __pyx_k_contiguous_and_direct[] = ""; +static const char __pyx_k_Cannot_index_with_type[] = "Cannot index with type '"; +static const char __pyx_k_MemoryView_of_r_object[] = ""; +static const char __pyx_k_MemoryView_of_r_at_0x_x[] = ""; +static const char __pyx_k_RunModel_setInputBuffer[] = "RunModel.setInputBuffer"; +static const char __pyx_k_contiguous_and_indirect[] = ""; +static const char __pyx_k_RunModel___reduce_cython[] = "RunModel.__reduce_cython__"; +static const char __pyx_k_Dimension_d_is_not_direct[] = "Dimension %d is not direct"; +static const char __pyx_k_Index_out_of_bounds_axis_d[] = "Index out of bounds (axis %d)"; +static const char __pyx_k_RunModel___setstate_cython[] = "RunModel.__setstate_cython__"; +static const char __pyx_k_Step_may_not_be_zero_axis_d[] = "Step may not be zero (axis %d)"; +static const char __pyx_k_itemsize_0_for_cython_array[] = "itemsize <= 0 for cython.array"; +static const char __pyx_k_unable_to_allocate_array_data[] = "unable to allocate array data."; +static const char __pyx_k_strided_and_direct_or_indirect[] = ""; +static const char __pyx_k_All_dimensions_preceding_dimensi[] = "All dimensions preceding dimension %d must be indexed and not sliced"; +static const char __pyx_k_Buffer_view_does_not_expose_stri[] = "Buffer view does not expose strides"; +static const char __pyx_k_Can_only_create_a_buffer_that_is[] = "Can only create a buffer that is contiguous in memory."; +static const char __pyx_k_Cannot_assign_to_read_only_memor[] = "Cannot assign to read-only memoryview"; +static const char __pyx_k_Cannot_create_writable_memory_vi[] = "Cannot create writable memory view from read-only memoryview"; +static const char __pyx_k_Cannot_transpose_memoryview_with[] = "Cannot transpose memoryview with indirect dimensions"; +static const char __pyx_k_Empty_shape_tuple_for_cython_arr[] = "Empty shape tuple for cython.array"; +static const char __pyx_k_Incompatible_checksums_0x_x_vs_0[] = "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))"; +static const char __pyx_k_Indirect_dimensions_not_supporte[] = "Indirect dimensions not supported"; +static const char __pyx_k_Invalid_mode_expected_c_or_fortr[] = "Invalid mode, expected 'c' or 'fortran', got "; +static const char __pyx_k_Out_of_bounds_on_buffer_access_a[] = "Out of bounds on buffer access (axis "; +static const char __pyx_k_Unable_to_convert_item_to_object[] = "Unable to convert item to object"; +static const char __pyx_k_got_differing_extents_in_dimensi[] = "got differing extents in dimension "; +static const char __pyx_k_no_default___reduce___due_to_non[] = "no default __reduce__ due to non-trivial __cinit__"; +static const char __pyx_k_self_model_cannot_be_converted_t[] = "self.model cannot be converted to a Python object for pickling"; +static const char __pyx_k_selfdrive_modeld_runners_runmode[] = "selfdrive.modeld.runners.runmodel_pyx"; +static const char __pyx_k_unable_to_allocate_shape_and_str[] = "unable to allocate shape and strides."; +static const char __pyx_k_selfdrive_modeld_runners_runmode_2[] = "selfdrive/modeld/runners/runmodel_pyx.pyx"; +/* #### Code section: decls ### */ +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array___cinit__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_shape, Py_ssize_t __pyx_v_itemsize, PyObject *__pyx_v_format, PyObject *__pyx_v_mode, int __pyx_v_allocate_buffer); /* proto */ +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_2__getbuffer__(struct __pyx_array_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /* proto */ +static void __pyx_array___pyx_pf_15View_dot_MemoryView_5array_4__dealloc__(struct __pyx_array_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_5array_7memview___get__(struct __pyx_array_obj *__pyx_v_self); /* proto */ +static Py_ssize_t __pyx_array___pyx_pf_15View_dot_MemoryView_5array_6__len__(struct __pyx_array_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_8__getattr__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_attr); /* proto */ +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_10__getitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item); /* proto */ +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_12__setitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value); /* proto */ +static PyObject *__pyx_pf___pyx_array___reduce_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_array_2__setstate_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum___init__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v_name); /* proto */ +static PyObject *__pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum_2__repr__(struct __pyx_MemviewEnum_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_MemviewEnum___reduce_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_MemviewEnum_2__setstate_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview___cinit__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj, int __pyx_v_flags, int __pyx_v_dtype_is_object); /* proto */ +static void __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_2__dealloc__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_4__getitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index); /* proto */ +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_6__setitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value); /* proto */ +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_8__getbuffer__(struct __pyx_memoryview_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_1T___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4base___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_5shape___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_7strides___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_10suboffsets___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4ndim___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_8itemsize___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_6nbytes___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4size___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static Py_ssize_t __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_10__len__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_12__repr__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_14__str__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_16is_c_contig(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_18is_f_contig(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_20copy(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_22copy_fortran(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryview___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryview_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static void __pyx_memoryviewslice___pyx_pf_15View_dot_MemoryView_16_memoryviewslice___dealloc__(struct __pyx_memoryviewslice_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryviewslice___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryviewslice_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView___pyx_unpickle_Enum(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v___pyx_type, long __pyx_v___pyx_checksum, PyObject *__pyx_v___pyx_state); /* proto */ +static void __pyx_pf_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel___dealloc__(struct __pyx_obj_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_2addInput(struct __pyx_obj_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel *__pyx_v_self, std::string __pyx_v_name, __Pyx_memviewslice __pyx_v_buffer); /* proto */ +static PyObject *__pyx_pf_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_4setInputBuffer(struct __pyx_obj_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel *__pyx_v_self, std::string __pyx_v_name, __Pyx_memviewslice __pyx_v_buffer); /* proto */ +static PyObject *__pyx_pf_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_6getCLBuffer(struct __pyx_obj_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel *__pyx_v_self, std::string __pyx_v_name); /* proto */ +static PyObject *__pyx_pf_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_8execute(struct __pyx_obj_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_10__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_12__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_tp_new_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_array(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_Enum(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_memoryview(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new__memoryviewslice(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +/* #### Code section: late_includes ### */ +/* #### Code section: module_state ### */ +typedef struct { + PyObject *__pyx_d; + PyObject *__pyx_b; + PyObject *__pyx_cython_runtime; + PyObject *__pyx_empty_tuple; + PyObject *__pyx_empty_bytes; + PyObject *__pyx_empty_unicode; + #ifdef __Pyx_CyFunction_USED + PyTypeObject *__pyx_CyFunctionType; + #endif + #ifdef __Pyx_FusedFunction_USED + PyTypeObject *__pyx_FusedFunctionType; + #endif + #ifdef __Pyx_Generator_USED + PyTypeObject *__pyx_GeneratorType; + #endif + #ifdef __Pyx_IterableCoroutine_USED + PyTypeObject *__pyx_IterableCoroutineType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineAwaitType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineType; + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + PyTypeObject *__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext; + PyTypeObject *__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf; + #if CYTHON_USE_MODULE_STATE + #endif + PyTypeObject *__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext; + PyTypeObject *__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem; + #if CYTHON_USE_MODULE_STATE + PyObject *__pyx_type_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel; + PyObject *__pyx_type___pyx_array; + PyObject *__pyx_type___pyx_MemviewEnum; + PyObject *__pyx_type___pyx_memoryview; + PyObject *__pyx_type___pyx_memoryviewslice; + #endif + PyTypeObject *__pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel; + PyTypeObject *__pyx_array_type; + PyTypeObject *__pyx_MemviewEnum_type; + PyTypeObject *__pyx_memoryview_type; + PyTypeObject *__pyx_memoryviewslice_type; + PyObject *__pyx_kp_u_; + PyObject *__pyx_n_s_ASCII; + PyObject *__pyx_kp_s_All_dimensions_preceding_dimensi; + PyObject *__pyx_n_s_AssertionError; + PyObject *__pyx_kp_s_Buffer_view_does_not_expose_stri; + PyObject *__pyx_n_s_CPU; + PyObject *__pyx_kp_s_Can_only_create_a_buffer_that_is; + PyObject *__pyx_kp_s_Cannot_assign_to_read_only_memor; + PyObject *__pyx_kp_s_Cannot_create_writable_memory_vi; + PyObject *__pyx_kp_u_Cannot_index_with_type; + PyObject *__pyx_kp_s_Cannot_transpose_memoryview_with; + PyObject *__pyx_n_s_DSP; + PyObject *__pyx_kp_s_Dimension_d_is_not_direct; + PyObject *__pyx_n_s_Ellipsis; + PyObject *__pyx_kp_s_Empty_shape_tuple_for_cython_arr; + PyObject *__pyx_n_s_GPU; + PyObject *__pyx_kp_s_Incompatible_checksums_0x_x_vs_0; + PyObject *__pyx_n_s_IndexError; + PyObject *__pyx_kp_s_Index_out_of_bounds_axis_d; + PyObject *__pyx_kp_s_Indirect_dimensions_not_supporte; + PyObject *__pyx_kp_u_Invalid_mode_expected_c_or_fortr; + PyObject *__pyx_kp_u_Invalid_shape_in_axis; + PyObject *__pyx_n_s_MemoryError; + PyObject *__pyx_kp_s_MemoryView_of_r_at_0x_x; + PyObject *__pyx_kp_s_MemoryView_of_r_object; + PyObject *__pyx_n_b_O; + PyObject *__pyx_kp_u_Out_of_bounds_on_buffer_access_a; + PyObject *__pyx_n_s_PickleError; + PyObject *__pyx_n_s_RunModel; + PyObject *__pyx_n_s_RunModel___reduce_cython; + PyObject *__pyx_n_s_RunModel___setstate_cython; + PyObject *__pyx_n_s_RunModel_addInput; + PyObject *__pyx_n_s_RunModel_execute; + PyObject *__pyx_n_s_RunModel_getCLBuffer; + PyObject *__pyx_n_s_RunModel_setInputBuffer; + PyObject *__pyx_n_s_Runtime; + PyObject *__pyx_n_s_Sequence; + PyObject *__pyx_kp_s_Step_may_not_be_zero_axis_d; + PyObject *__pyx_n_s_TypeError; + PyObject *__pyx_kp_s_Unable_to_convert_item_to_object; + PyObject *__pyx_n_s_ValueError; + PyObject *__pyx_n_s_View_MemoryView; + PyObject *__pyx_kp_u__2; + PyObject *__pyx_n_s__3; + PyObject *__pyx_n_s__30; + PyObject *__pyx_kp_u__6; + PyObject *__pyx_kp_u__7; + PyObject *__pyx_n_s_abc; + PyObject *__pyx_n_s_addInput; + PyObject *__pyx_n_s_allocate_buffer; + PyObject *__pyx_kp_u_and; + PyObject *__pyx_n_s_asyncio_coroutines; + PyObject *__pyx_n_s_base; + PyObject *__pyx_n_s_buffer; + PyObject *__pyx_n_s_c; + PyObject *__pyx_n_u_c; + PyObject *__pyx_n_s_cl_buf; + PyObject *__pyx_n_s_class; + PyObject *__pyx_n_s_class_getitem; + PyObject *__pyx_n_s_cline_in_traceback; + PyObject *__pyx_n_s_collections; + PyObject *__pyx_kp_s_collections_abc; + PyObject *__pyx_kp_s_contiguous_and_direct; + PyObject *__pyx_kp_s_contiguous_and_indirect; + PyObject *__pyx_n_s_count; + PyObject *__pyx_n_s_dict; + PyObject *__pyx_kp_u_disable; + PyObject *__pyx_n_s_doc; + PyObject *__pyx_n_s_dtype_is_object; + PyObject *__pyx_kp_u_enable; + PyObject *__pyx_n_s_encode; + PyObject *__pyx_n_s_enumerate; + PyObject *__pyx_n_s_error; + PyObject *__pyx_n_s_execute; + PyObject *__pyx_n_s_flags; + PyObject *__pyx_n_s_format; + PyObject *__pyx_n_s_fortran; + PyObject *__pyx_n_u_fortran; + PyObject *__pyx_kp_u_gc; + PyObject *__pyx_n_s_getCLBuffer; + PyObject *__pyx_n_s_getstate; + PyObject *__pyx_kp_u_got; + PyObject *__pyx_kp_u_got_differing_extents_in_dimensi; + PyObject *__pyx_n_s_id; + PyObject *__pyx_n_s_import; + PyObject *__pyx_n_s_index; + PyObject *__pyx_n_s_init_subclass; + PyObject *__pyx_n_s_initializing; + PyObject *__pyx_n_s_is_coroutine; + PyObject *__pyx_kp_u_isenabled; + PyObject *__pyx_n_s_itemsize; + PyObject *__pyx_kp_s_itemsize_0_for_cython_array; + PyObject *__pyx_n_s_main; + PyObject *__pyx_n_s_memview; + PyObject *__pyx_n_s_metaclass; + PyObject *__pyx_n_s_mode; + PyObject *__pyx_n_s_module; + PyObject *__pyx_n_s_name; + PyObject *__pyx_n_s_name_2; + PyObject *__pyx_n_s_ndim; + PyObject *__pyx_n_s_new; + PyObject *__pyx_kp_s_no_default___reduce___due_to_non; + PyObject *__pyx_n_s_obj; + PyObject *__pyx_n_s_pack; + PyObject *__pyx_n_s_pickle; + PyObject *__pyx_n_s_prepare; + PyObject *__pyx_n_s_pyx_PickleError; + PyObject *__pyx_n_s_pyx_checksum; + PyObject *__pyx_n_s_pyx_result; + PyObject *__pyx_n_s_pyx_state; + PyObject *__pyx_n_s_pyx_type; + PyObject *__pyx_n_s_pyx_unpickle_Enum; + PyObject *__pyx_n_s_pyx_vtable; + PyObject *__pyx_n_s_qualname; + PyObject *__pyx_n_s_range; + PyObject *__pyx_n_s_reduce; + PyObject *__pyx_n_s_reduce_cython; + PyObject *__pyx_n_s_reduce_ex; + PyObject *__pyx_n_s_register; + PyObject *__pyx_n_s_self; + PyObject *__pyx_kp_s_self_model_cannot_be_converted_t; + PyObject *__pyx_n_s_selfdrive_modeld_runners_runmode; + PyObject *__pyx_kp_s_selfdrive_modeld_runners_runmode_2; + PyObject *__pyx_n_s_setInputBuffer; + PyObject *__pyx_n_s_set_name; + PyObject *__pyx_n_s_setstate; + PyObject *__pyx_n_s_setstate_cython; + PyObject *__pyx_n_s_shape; + PyObject *__pyx_n_s_size; + PyObject *__pyx_n_s_spec; + PyObject *__pyx_n_s_start; + PyObject *__pyx_n_s_step; + PyObject *__pyx_n_s_stop; + PyObject *__pyx_kp_s_strided_and_direct; + PyObject *__pyx_kp_s_strided_and_direct_or_indirect; + PyObject *__pyx_kp_s_strided_and_indirect; + PyObject *__pyx_kp_s_stringsource; + PyObject *__pyx_n_s_struct; + PyObject *__pyx_n_s_super; + PyObject *__pyx_n_s_sys; + PyObject *__pyx_n_s_test; + PyObject *__pyx_kp_s_unable_to_allocate_array_data; + PyObject *__pyx_kp_s_unable_to_allocate_shape_and_str; + PyObject *__pyx_n_s_unpack; + PyObject *__pyx_n_s_update; + PyObject *__pyx_n_s_version_info; + PyObject *__pyx_int_0; + PyObject *__pyx_int_1; + PyObject *__pyx_int_3; + PyObject *__pyx_int_112105877; + PyObject *__pyx_int_136983863; + PyObject *__pyx_int_184977713; + PyObject *__pyx_int_neg_1; + PyObject *__pyx_slice__5; + PyObject *__pyx_tuple__4; + PyObject *__pyx_tuple__8; + PyObject *__pyx_tuple__9; + PyObject *__pyx_tuple__10; + PyObject *__pyx_tuple__11; + PyObject *__pyx_tuple__12; + PyObject *__pyx_tuple__13; + PyObject *__pyx_tuple__14; + PyObject *__pyx_tuple__15; + PyObject *__pyx_tuple__16; + PyObject *__pyx_tuple__17; + PyObject *__pyx_tuple__18; + PyObject *__pyx_tuple__20; + PyObject *__pyx_tuple__23; + PyObject *__pyx_tuple__25; + PyObject *__pyx_tuple__28; + PyObject *__pyx_codeobj__19; + PyObject *__pyx_codeobj__21; + PyObject *__pyx_codeobj__22; + PyObject *__pyx_codeobj__24; + PyObject *__pyx_codeobj__26; + PyObject *__pyx_codeobj__27; + PyObject *__pyx_codeobj__29; +} __pyx_mstate; + +#if CYTHON_USE_MODULE_STATE +#ifdef __cplusplus +namespace { + extern struct PyModuleDef __pyx_moduledef; +} /* anonymous namespace */ +#else +static struct PyModuleDef __pyx_moduledef; +#endif + +#define __pyx_mstate(o) ((__pyx_mstate *)__Pyx_PyModule_GetState(o)) + +#define __pyx_mstate_global (__pyx_mstate(PyState_FindModule(&__pyx_moduledef))) + +#define __pyx_m (PyState_FindModule(&__pyx_moduledef)) +#else +static __pyx_mstate __pyx_mstate_global_static = +#ifdef __cplusplus + {}; +#else + {0}; +#endif +static __pyx_mstate *__pyx_mstate_global = &__pyx_mstate_global_static; +#endif +/* #### Code section: module_state_clear ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_clear(PyObject *m) { + __pyx_mstate *clear_module_state = __pyx_mstate(m); + if (!clear_module_state) return 0; + Py_CLEAR(clear_module_state->__pyx_d); + Py_CLEAR(clear_module_state->__pyx_b); + Py_CLEAR(clear_module_state->__pyx_cython_runtime); + Py_CLEAR(clear_module_state->__pyx_empty_tuple); + Py_CLEAR(clear_module_state->__pyx_empty_bytes); + Py_CLEAR(clear_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_CLEAR(clear_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_CLEAR(clear_module_state->__pyx_FusedFunctionType); + #endif + Py_CLEAR(clear_module_state->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext); + Py_CLEAR(clear_module_state->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf); + Py_CLEAR(clear_module_state->__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext); + Py_CLEAR(clear_module_state->__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem); + Py_CLEAR(clear_module_state->__pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel); + Py_CLEAR(clear_module_state->__pyx_type_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel); + Py_CLEAR(clear_module_state->__pyx_array_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_array); + Py_CLEAR(clear_module_state->__pyx_MemviewEnum_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_MemviewEnum); + Py_CLEAR(clear_module_state->__pyx_memoryview_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_memoryview); + Py_CLEAR(clear_module_state->__pyx_memoryviewslice_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_memoryviewslice); + Py_CLEAR(clear_module_state->__pyx_kp_u_); + Py_CLEAR(clear_module_state->__pyx_n_s_ASCII); + Py_CLEAR(clear_module_state->__pyx_kp_s_All_dimensions_preceding_dimensi); + Py_CLEAR(clear_module_state->__pyx_n_s_AssertionError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Buffer_view_does_not_expose_stri); + Py_CLEAR(clear_module_state->__pyx_n_s_CPU); + Py_CLEAR(clear_module_state->__pyx_kp_s_Can_only_create_a_buffer_that_is); + Py_CLEAR(clear_module_state->__pyx_kp_s_Cannot_assign_to_read_only_memor); + Py_CLEAR(clear_module_state->__pyx_kp_s_Cannot_create_writable_memory_vi); + Py_CLEAR(clear_module_state->__pyx_kp_u_Cannot_index_with_type); + Py_CLEAR(clear_module_state->__pyx_kp_s_Cannot_transpose_memoryview_with); + Py_CLEAR(clear_module_state->__pyx_n_s_DSP); + Py_CLEAR(clear_module_state->__pyx_kp_s_Dimension_d_is_not_direct); + Py_CLEAR(clear_module_state->__pyx_n_s_Ellipsis); + Py_CLEAR(clear_module_state->__pyx_kp_s_Empty_shape_tuple_for_cython_arr); + Py_CLEAR(clear_module_state->__pyx_n_s_GPU); + Py_CLEAR(clear_module_state->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0); + Py_CLEAR(clear_module_state->__pyx_n_s_IndexError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Index_out_of_bounds_axis_d); + Py_CLEAR(clear_module_state->__pyx_kp_s_Indirect_dimensions_not_supporte); + Py_CLEAR(clear_module_state->__pyx_kp_u_Invalid_mode_expected_c_or_fortr); + Py_CLEAR(clear_module_state->__pyx_kp_u_Invalid_shape_in_axis); + Py_CLEAR(clear_module_state->__pyx_n_s_MemoryError); + Py_CLEAR(clear_module_state->__pyx_kp_s_MemoryView_of_r_at_0x_x); + Py_CLEAR(clear_module_state->__pyx_kp_s_MemoryView_of_r_object); + Py_CLEAR(clear_module_state->__pyx_n_b_O); + Py_CLEAR(clear_module_state->__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + Py_CLEAR(clear_module_state->__pyx_n_s_PickleError); + Py_CLEAR(clear_module_state->__pyx_n_s_RunModel); + Py_CLEAR(clear_module_state->__pyx_n_s_RunModel___reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_RunModel___setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_RunModel_addInput); + Py_CLEAR(clear_module_state->__pyx_n_s_RunModel_execute); + Py_CLEAR(clear_module_state->__pyx_n_s_RunModel_getCLBuffer); + Py_CLEAR(clear_module_state->__pyx_n_s_RunModel_setInputBuffer); + Py_CLEAR(clear_module_state->__pyx_n_s_Runtime); + Py_CLEAR(clear_module_state->__pyx_n_s_Sequence); + Py_CLEAR(clear_module_state->__pyx_kp_s_Step_may_not_be_zero_axis_d); + Py_CLEAR(clear_module_state->__pyx_n_s_TypeError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Unable_to_convert_item_to_object); + Py_CLEAR(clear_module_state->__pyx_n_s_ValueError); + Py_CLEAR(clear_module_state->__pyx_n_s_View_MemoryView); + Py_CLEAR(clear_module_state->__pyx_kp_u__2); + Py_CLEAR(clear_module_state->__pyx_n_s__3); + Py_CLEAR(clear_module_state->__pyx_n_s__30); + Py_CLEAR(clear_module_state->__pyx_kp_u__6); + Py_CLEAR(clear_module_state->__pyx_kp_u__7); + Py_CLEAR(clear_module_state->__pyx_n_s_abc); + Py_CLEAR(clear_module_state->__pyx_n_s_addInput); + Py_CLEAR(clear_module_state->__pyx_n_s_allocate_buffer); + Py_CLEAR(clear_module_state->__pyx_kp_u_and); + Py_CLEAR(clear_module_state->__pyx_n_s_asyncio_coroutines); + Py_CLEAR(clear_module_state->__pyx_n_s_base); + Py_CLEAR(clear_module_state->__pyx_n_s_buffer); + Py_CLEAR(clear_module_state->__pyx_n_s_c); + Py_CLEAR(clear_module_state->__pyx_n_u_c); + Py_CLEAR(clear_module_state->__pyx_n_s_cl_buf); + Py_CLEAR(clear_module_state->__pyx_n_s_class); + Py_CLEAR(clear_module_state->__pyx_n_s_class_getitem); + Py_CLEAR(clear_module_state->__pyx_n_s_cline_in_traceback); + Py_CLEAR(clear_module_state->__pyx_n_s_collections); + Py_CLEAR(clear_module_state->__pyx_kp_s_collections_abc); + Py_CLEAR(clear_module_state->__pyx_kp_s_contiguous_and_direct); + Py_CLEAR(clear_module_state->__pyx_kp_s_contiguous_and_indirect); + Py_CLEAR(clear_module_state->__pyx_n_s_count); + Py_CLEAR(clear_module_state->__pyx_n_s_dict); + Py_CLEAR(clear_module_state->__pyx_kp_u_disable); + Py_CLEAR(clear_module_state->__pyx_n_s_doc); + Py_CLEAR(clear_module_state->__pyx_n_s_dtype_is_object); + Py_CLEAR(clear_module_state->__pyx_kp_u_enable); + Py_CLEAR(clear_module_state->__pyx_n_s_encode); + Py_CLEAR(clear_module_state->__pyx_n_s_enumerate); + Py_CLEAR(clear_module_state->__pyx_n_s_error); + Py_CLEAR(clear_module_state->__pyx_n_s_execute); + Py_CLEAR(clear_module_state->__pyx_n_s_flags); + Py_CLEAR(clear_module_state->__pyx_n_s_format); + Py_CLEAR(clear_module_state->__pyx_n_s_fortran); + Py_CLEAR(clear_module_state->__pyx_n_u_fortran); + Py_CLEAR(clear_module_state->__pyx_kp_u_gc); + Py_CLEAR(clear_module_state->__pyx_n_s_getCLBuffer); + Py_CLEAR(clear_module_state->__pyx_n_s_getstate); + Py_CLEAR(clear_module_state->__pyx_kp_u_got); + Py_CLEAR(clear_module_state->__pyx_kp_u_got_differing_extents_in_dimensi); + Py_CLEAR(clear_module_state->__pyx_n_s_id); + Py_CLEAR(clear_module_state->__pyx_n_s_import); + Py_CLEAR(clear_module_state->__pyx_n_s_index); + Py_CLEAR(clear_module_state->__pyx_n_s_init_subclass); + Py_CLEAR(clear_module_state->__pyx_n_s_initializing); + Py_CLEAR(clear_module_state->__pyx_n_s_is_coroutine); + Py_CLEAR(clear_module_state->__pyx_kp_u_isenabled); + Py_CLEAR(clear_module_state->__pyx_n_s_itemsize); + Py_CLEAR(clear_module_state->__pyx_kp_s_itemsize_0_for_cython_array); + Py_CLEAR(clear_module_state->__pyx_n_s_main); + Py_CLEAR(clear_module_state->__pyx_n_s_memview); + Py_CLEAR(clear_module_state->__pyx_n_s_metaclass); + Py_CLEAR(clear_module_state->__pyx_n_s_mode); + Py_CLEAR(clear_module_state->__pyx_n_s_module); + Py_CLEAR(clear_module_state->__pyx_n_s_name); + Py_CLEAR(clear_module_state->__pyx_n_s_name_2); + Py_CLEAR(clear_module_state->__pyx_n_s_ndim); + Py_CLEAR(clear_module_state->__pyx_n_s_new); + Py_CLEAR(clear_module_state->__pyx_kp_s_no_default___reduce___due_to_non); + Py_CLEAR(clear_module_state->__pyx_n_s_obj); + Py_CLEAR(clear_module_state->__pyx_n_s_pack); + Py_CLEAR(clear_module_state->__pyx_n_s_pickle); + Py_CLEAR(clear_module_state->__pyx_n_s_prepare); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_PickleError); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_checksum); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_result); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_state); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_type); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_unpickle_Enum); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_vtable); + Py_CLEAR(clear_module_state->__pyx_n_s_qualname); + Py_CLEAR(clear_module_state->__pyx_n_s_range); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_ex); + Py_CLEAR(clear_module_state->__pyx_n_s_register); + Py_CLEAR(clear_module_state->__pyx_n_s_self); + Py_CLEAR(clear_module_state->__pyx_kp_s_self_model_cannot_be_converted_t); + Py_CLEAR(clear_module_state->__pyx_n_s_selfdrive_modeld_runners_runmode); + Py_CLEAR(clear_module_state->__pyx_kp_s_selfdrive_modeld_runners_runmode_2); + Py_CLEAR(clear_module_state->__pyx_n_s_setInputBuffer); + Py_CLEAR(clear_module_state->__pyx_n_s_set_name); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_shape); + Py_CLEAR(clear_module_state->__pyx_n_s_size); + Py_CLEAR(clear_module_state->__pyx_n_s_spec); + Py_CLEAR(clear_module_state->__pyx_n_s_start); + Py_CLEAR(clear_module_state->__pyx_n_s_step); + Py_CLEAR(clear_module_state->__pyx_n_s_stop); + Py_CLEAR(clear_module_state->__pyx_kp_s_strided_and_direct); + Py_CLEAR(clear_module_state->__pyx_kp_s_strided_and_direct_or_indirect); + Py_CLEAR(clear_module_state->__pyx_kp_s_strided_and_indirect); + Py_CLEAR(clear_module_state->__pyx_kp_s_stringsource); + Py_CLEAR(clear_module_state->__pyx_n_s_struct); + Py_CLEAR(clear_module_state->__pyx_n_s_super); + Py_CLEAR(clear_module_state->__pyx_n_s_sys); + Py_CLEAR(clear_module_state->__pyx_n_s_test); + Py_CLEAR(clear_module_state->__pyx_kp_s_unable_to_allocate_array_data); + Py_CLEAR(clear_module_state->__pyx_kp_s_unable_to_allocate_shape_and_str); + Py_CLEAR(clear_module_state->__pyx_n_s_unpack); + Py_CLEAR(clear_module_state->__pyx_n_s_update); + Py_CLEAR(clear_module_state->__pyx_n_s_version_info); + Py_CLEAR(clear_module_state->__pyx_int_0); + Py_CLEAR(clear_module_state->__pyx_int_1); + Py_CLEAR(clear_module_state->__pyx_int_3); + Py_CLEAR(clear_module_state->__pyx_int_112105877); + Py_CLEAR(clear_module_state->__pyx_int_136983863); + Py_CLEAR(clear_module_state->__pyx_int_184977713); + Py_CLEAR(clear_module_state->__pyx_int_neg_1); + Py_CLEAR(clear_module_state->__pyx_slice__5); + Py_CLEAR(clear_module_state->__pyx_tuple__4); + Py_CLEAR(clear_module_state->__pyx_tuple__8); + Py_CLEAR(clear_module_state->__pyx_tuple__9); + Py_CLEAR(clear_module_state->__pyx_tuple__10); + Py_CLEAR(clear_module_state->__pyx_tuple__11); + Py_CLEAR(clear_module_state->__pyx_tuple__12); + Py_CLEAR(clear_module_state->__pyx_tuple__13); + Py_CLEAR(clear_module_state->__pyx_tuple__14); + Py_CLEAR(clear_module_state->__pyx_tuple__15); + Py_CLEAR(clear_module_state->__pyx_tuple__16); + Py_CLEAR(clear_module_state->__pyx_tuple__17); + Py_CLEAR(clear_module_state->__pyx_tuple__18); + Py_CLEAR(clear_module_state->__pyx_tuple__20); + Py_CLEAR(clear_module_state->__pyx_tuple__23); + Py_CLEAR(clear_module_state->__pyx_tuple__25); + Py_CLEAR(clear_module_state->__pyx_tuple__28); + Py_CLEAR(clear_module_state->__pyx_codeobj__19); + Py_CLEAR(clear_module_state->__pyx_codeobj__21); + Py_CLEAR(clear_module_state->__pyx_codeobj__22); + Py_CLEAR(clear_module_state->__pyx_codeobj__24); + Py_CLEAR(clear_module_state->__pyx_codeobj__26); + Py_CLEAR(clear_module_state->__pyx_codeobj__27); + Py_CLEAR(clear_module_state->__pyx_codeobj__29); + return 0; +} +#endif +/* #### Code section: module_state_traverse ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { + __pyx_mstate *traverse_module_state = __pyx_mstate(m); + if (!traverse_module_state) return 0; + Py_VISIT(traverse_module_state->__pyx_d); + Py_VISIT(traverse_module_state->__pyx_b); + Py_VISIT(traverse_module_state->__pyx_cython_runtime); + Py_VISIT(traverse_module_state->__pyx_empty_tuple); + Py_VISIT(traverse_module_state->__pyx_empty_bytes); + Py_VISIT(traverse_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_VISIT(traverse_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_VISIT(traverse_module_state->__pyx_FusedFunctionType); + #endif + Py_VISIT(traverse_module_state->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext); + Py_VISIT(traverse_module_state->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf); + Py_VISIT(traverse_module_state->__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext); + Py_VISIT(traverse_module_state->__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem); + Py_VISIT(traverse_module_state->__pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel); + Py_VISIT(traverse_module_state->__pyx_type_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel); + Py_VISIT(traverse_module_state->__pyx_array_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_array); + Py_VISIT(traverse_module_state->__pyx_MemviewEnum_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_MemviewEnum); + Py_VISIT(traverse_module_state->__pyx_memoryview_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_memoryview); + Py_VISIT(traverse_module_state->__pyx_memoryviewslice_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_memoryviewslice); + Py_VISIT(traverse_module_state->__pyx_kp_u_); + Py_VISIT(traverse_module_state->__pyx_n_s_ASCII); + Py_VISIT(traverse_module_state->__pyx_kp_s_All_dimensions_preceding_dimensi); + Py_VISIT(traverse_module_state->__pyx_n_s_AssertionError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Buffer_view_does_not_expose_stri); + Py_VISIT(traverse_module_state->__pyx_n_s_CPU); + Py_VISIT(traverse_module_state->__pyx_kp_s_Can_only_create_a_buffer_that_is); + Py_VISIT(traverse_module_state->__pyx_kp_s_Cannot_assign_to_read_only_memor); + Py_VISIT(traverse_module_state->__pyx_kp_s_Cannot_create_writable_memory_vi); + Py_VISIT(traverse_module_state->__pyx_kp_u_Cannot_index_with_type); + Py_VISIT(traverse_module_state->__pyx_kp_s_Cannot_transpose_memoryview_with); + Py_VISIT(traverse_module_state->__pyx_n_s_DSP); + Py_VISIT(traverse_module_state->__pyx_kp_s_Dimension_d_is_not_direct); + Py_VISIT(traverse_module_state->__pyx_n_s_Ellipsis); + Py_VISIT(traverse_module_state->__pyx_kp_s_Empty_shape_tuple_for_cython_arr); + Py_VISIT(traverse_module_state->__pyx_n_s_GPU); + Py_VISIT(traverse_module_state->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0); + Py_VISIT(traverse_module_state->__pyx_n_s_IndexError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Index_out_of_bounds_axis_d); + Py_VISIT(traverse_module_state->__pyx_kp_s_Indirect_dimensions_not_supporte); + Py_VISIT(traverse_module_state->__pyx_kp_u_Invalid_mode_expected_c_or_fortr); + Py_VISIT(traverse_module_state->__pyx_kp_u_Invalid_shape_in_axis); + Py_VISIT(traverse_module_state->__pyx_n_s_MemoryError); + Py_VISIT(traverse_module_state->__pyx_kp_s_MemoryView_of_r_at_0x_x); + Py_VISIT(traverse_module_state->__pyx_kp_s_MemoryView_of_r_object); + Py_VISIT(traverse_module_state->__pyx_n_b_O); + Py_VISIT(traverse_module_state->__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + Py_VISIT(traverse_module_state->__pyx_n_s_PickleError); + Py_VISIT(traverse_module_state->__pyx_n_s_RunModel); + Py_VISIT(traverse_module_state->__pyx_n_s_RunModel___reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_RunModel___setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_RunModel_addInput); + Py_VISIT(traverse_module_state->__pyx_n_s_RunModel_execute); + Py_VISIT(traverse_module_state->__pyx_n_s_RunModel_getCLBuffer); + Py_VISIT(traverse_module_state->__pyx_n_s_RunModel_setInputBuffer); + Py_VISIT(traverse_module_state->__pyx_n_s_Runtime); + Py_VISIT(traverse_module_state->__pyx_n_s_Sequence); + Py_VISIT(traverse_module_state->__pyx_kp_s_Step_may_not_be_zero_axis_d); + Py_VISIT(traverse_module_state->__pyx_n_s_TypeError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Unable_to_convert_item_to_object); + Py_VISIT(traverse_module_state->__pyx_n_s_ValueError); + Py_VISIT(traverse_module_state->__pyx_n_s_View_MemoryView); + Py_VISIT(traverse_module_state->__pyx_kp_u__2); + Py_VISIT(traverse_module_state->__pyx_n_s__3); + Py_VISIT(traverse_module_state->__pyx_n_s__30); + Py_VISIT(traverse_module_state->__pyx_kp_u__6); + Py_VISIT(traverse_module_state->__pyx_kp_u__7); + Py_VISIT(traverse_module_state->__pyx_n_s_abc); + Py_VISIT(traverse_module_state->__pyx_n_s_addInput); + Py_VISIT(traverse_module_state->__pyx_n_s_allocate_buffer); + Py_VISIT(traverse_module_state->__pyx_kp_u_and); + Py_VISIT(traverse_module_state->__pyx_n_s_asyncio_coroutines); + Py_VISIT(traverse_module_state->__pyx_n_s_base); + Py_VISIT(traverse_module_state->__pyx_n_s_buffer); + Py_VISIT(traverse_module_state->__pyx_n_s_c); + Py_VISIT(traverse_module_state->__pyx_n_u_c); + Py_VISIT(traverse_module_state->__pyx_n_s_cl_buf); + Py_VISIT(traverse_module_state->__pyx_n_s_class); + Py_VISIT(traverse_module_state->__pyx_n_s_class_getitem); + Py_VISIT(traverse_module_state->__pyx_n_s_cline_in_traceback); + Py_VISIT(traverse_module_state->__pyx_n_s_collections); + Py_VISIT(traverse_module_state->__pyx_kp_s_collections_abc); + Py_VISIT(traverse_module_state->__pyx_kp_s_contiguous_and_direct); + Py_VISIT(traverse_module_state->__pyx_kp_s_contiguous_and_indirect); + Py_VISIT(traverse_module_state->__pyx_n_s_count); + Py_VISIT(traverse_module_state->__pyx_n_s_dict); + Py_VISIT(traverse_module_state->__pyx_kp_u_disable); + Py_VISIT(traverse_module_state->__pyx_n_s_doc); + Py_VISIT(traverse_module_state->__pyx_n_s_dtype_is_object); + Py_VISIT(traverse_module_state->__pyx_kp_u_enable); + Py_VISIT(traverse_module_state->__pyx_n_s_encode); + Py_VISIT(traverse_module_state->__pyx_n_s_enumerate); + Py_VISIT(traverse_module_state->__pyx_n_s_error); + Py_VISIT(traverse_module_state->__pyx_n_s_execute); + Py_VISIT(traverse_module_state->__pyx_n_s_flags); + Py_VISIT(traverse_module_state->__pyx_n_s_format); + Py_VISIT(traverse_module_state->__pyx_n_s_fortran); + Py_VISIT(traverse_module_state->__pyx_n_u_fortran); + Py_VISIT(traverse_module_state->__pyx_kp_u_gc); + Py_VISIT(traverse_module_state->__pyx_n_s_getCLBuffer); + Py_VISIT(traverse_module_state->__pyx_n_s_getstate); + Py_VISIT(traverse_module_state->__pyx_kp_u_got); + Py_VISIT(traverse_module_state->__pyx_kp_u_got_differing_extents_in_dimensi); + Py_VISIT(traverse_module_state->__pyx_n_s_id); + Py_VISIT(traverse_module_state->__pyx_n_s_import); + Py_VISIT(traverse_module_state->__pyx_n_s_index); + Py_VISIT(traverse_module_state->__pyx_n_s_init_subclass); + Py_VISIT(traverse_module_state->__pyx_n_s_initializing); + Py_VISIT(traverse_module_state->__pyx_n_s_is_coroutine); + Py_VISIT(traverse_module_state->__pyx_kp_u_isenabled); + Py_VISIT(traverse_module_state->__pyx_n_s_itemsize); + Py_VISIT(traverse_module_state->__pyx_kp_s_itemsize_0_for_cython_array); + Py_VISIT(traverse_module_state->__pyx_n_s_main); + Py_VISIT(traverse_module_state->__pyx_n_s_memview); + Py_VISIT(traverse_module_state->__pyx_n_s_metaclass); + Py_VISIT(traverse_module_state->__pyx_n_s_mode); + Py_VISIT(traverse_module_state->__pyx_n_s_module); + Py_VISIT(traverse_module_state->__pyx_n_s_name); + Py_VISIT(traverse_module_state->__pyx_n_s_name_2); + Py_VISIT(traverse_module_state->__pyx_n_s_ndim); + Py_VISIT(traverse_module_state->__pyx_n_s_new); + Py_VISIT(traverse_module_state->__pyx_kp_s_no_default___reduce___due_to_non); + Py_VISIT(traverse_module_state->__pyx_n_s_obj); + Py_VISIT(traverse_module_state->__pyx_n_s_pack); + Py_VISIT(traverse_module_state->__pyx_n_s_pickle); + Py_VISIT(traverse_module_state->__pyx_n_s_prepare); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_PickleError); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_checksum); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_result); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_state); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_type); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_unpickle_Enum); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_vtable); + Py_VISIT(traverse_module_state->__pyx_n_s_qualname); + Py_VISIT(traverse_module_state->__pyx_n_s_range); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_ex); + Py_VISIT(traverse_module_state->__pyx_n_s_register); + Py_VISIT(traverse_module_state->__pyx_n_s_self); + Py_VISIT(traverse_module_state->__pyx_kp_s_self_model_cannot_be_converted_t); + Py_VISIT(traverse_module_state->__pyx_n_s_selfdrive_modeld_runners_runmode); + Py_VISIT(traverse_module_state->__pyx_kp_s_selfdrive_modeld_runners_runmode_2); + Py_VISIT(traverse_module_state->__pyx_n_s_setInputBuffer); + Py_VISIT(traverse_module_state->__pyx_n_s_set_name); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_shape); + Py_VISIT(traverse_module_state->__pyx_n_s_size); + Py_VISIT(traverse_module_state->__pyx_n_s_spec); + Py_VISIT(traverse_module_state->__pyx_n_s_start); + Py_VISIT(traverse_module_state->__pyx_n_s_step); + Py_VISIT(traverse_module_state->__pyx_n_s_stop); + Py_VISIT(traverse_module_state->__pyx_kp_s_strided_and_direct); + Py_VISIT(traverse_module_state->__pyx_kp_s_strided_and_direct_or_indirect); + Py_VISIT(traverse_module_state->__pyx_kp_s_strided_and_indirect); + Py_VISIT(traverse_module_state->__pyx_kp_s_stringsource); + Py_VISIT(traverse_module_state->__pyx_n_s_struct); + Py_VISIT(traverse_module_state->__pyx_n_s_super); + Py_VISIT(traverse_module_state->__pyx_n_s_sys); + Py_VISIT(traverse_module_state->__pyx_n_s_test); + Py_VISIT(traverse_module_state->__pyx_kp_s_unable_to_allocate_array_data); + Py_VISIT(traverse_module_state->__pyx_kp_s_unable_to_allocate_shape_and_str); + Py_VISIT(traverse_module_state->__pyx_n_s_unpack); + Py_VISIT(traverse_module_state->__pyx_n_s_update); + Py_VISIT(traverse_module_state->__pyx_n_s_version_info); + Py_VISIT(traverse_module_state->__pyx_int_0); + Py_VISIT(traverse_module_state->__pyx_int_1); + Py_VISIT(traverse_module_state->__pyx_int_3); + Py_VISIT(traverse_module_state->__pyx_int_112105877); + Py_VISIT(traverse_module_state->__pyx_int_136983863); + Py_VISIT(traverse_module_state->__pyx_int_184977713); + Py_VISIT(traverse_module_state->__pyx_int_neg_1); + Py_VISIT(traverse_module_state->__pyx_slice__5); + Py_VISIT(traverse_module_state->__pyx_tuple__4); + Py_VISIT(traverse_module_state->__pyx_tuple__8); + Py_VISIT(traverse_module_state->__pyx_tuple__9); + Py_VISIT(traverse_module_state->__pyx_tuple__10); + Py_VISIT(traverse_module_state->__pyx_tuple__11); + Py_VISIT(traverse_module_state->__pyx_tuple__12); + Py_VISIT(traverse_module_state->__pyx_tuple__13); + Py_VISIT(traverse_module_state->__pyx_tuple__14); + Py_VISIT(traverse_module_state->__pyx_tuple__15); + Py_VISIT(traverse_module_state->__pyx_tuple__16); + Py_VISIT(traverse_module_state->__pyx_tuple__17); + Py_VISIT(traverse_module_state->__pyx_tuple__18); + Py_VISIT(traverse_module_state->__pyx_tuple__20); + Py_VISIT(traverse_module_state->__pyx_tuple__23); + Py_VISIT(traverse_module_state->__pyx_tuple__25); + Py_VISIT(traverse_module_state->__pyx_tuple__28); + Py_VISIT(traverse_module_state->__pyx_codeobj__19); + Py_VISIT(traverse_module_state->__pyx_codeobj__21); + Py_VISIT(traverse_module_state->__pyx_codeobj__22); + Py_VISIT(traverse_module_state->__pyx_codeobj__24); + Py_VISIT(traverse_module_state->__pyx_codeobj__26); + Py_VISIT(traverse_module_state->__pyx_codeobj__27); + Py_VISIT(traverse_module_state->__pyx_codeobj__29); + return 0; +} +#endif +/* #### Code section: module_state_defines ### */ +#define __pyx_d __pyx_mstate_global->__pyx_d +#define __pyx_b __pyx_mstate_global->__pyx_b +#define __pyx_cython_runtime __pyx_mstate_global->__pyx_cython_runtime +#define __pyx_empty_tuple __pyx_mstate_global->__pyx_empty_tuple +#define __pyx_empty_bytes __pyx_mstate_global->__pyx_empty_bytes +#define __pyx_empty_unicode __pyx_mstate_global->__pyx_empty_unicode +#ifdef __Pyx_CyFunction_USED +#define __pyx_CyFunctionType __pyx_mstate_global->__pyx_CyFunctionType +#endif +#ifdef __Pyx_FusedFunction_USED +#define __pyx_FusedFunctionType __pyx_mstate_global->__pyx_FusedFunctionType +#endif +#ifdef __Pyx_Generator_USED +#define __pyx_GeneratorType __pyx_mstate_global->__pyx_GeneratorType +#endif +#ifdef __Pyx_IterableCoroutine_USED +#define __pyx_IterableCoroutineType __pyx_mstate_global->__pyx_IterableCoroutineType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineAwaitType __pyx_mstate_global->__pyx_CoroutineAwaitType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineType __pyx_mstate_global->__pyx_CoroutineType +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#define __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext __pyx_mstate_global->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext +#define __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf __pyx_mstate_global->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf +#if CYTHON_USE_MODULE_STATE +#endif +#define __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext __pyx_mstate_global->__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext +#define __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem __pyx_mstate_global->__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem +#if CYTHON_USE_MODULE_STATE +#define __pyx_type_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel __pyx_mstate_global->__pyx_type_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel +#define __pyx_type___pyx_array __pyx_mstate_global->__pyx_type___pyx_array +#define __pyx_type___pyx_MemviewEnum __pyx_mstate_global->__pyx_type___pyx_MemviewEnum +#define __pyx_type___pyx_memoryview __pyx_mstate_global->__pyx_type___pyx_memoryview +#define __pyx_type___pyx_memoryviewslice __pyx_mstate_global->__pyx_type___pyx_memoryviewslice +#endif +#define __pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel __pyx_mstate_global->__pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel +#define __pyx_array_type __pyx_mstate_global->__pyx_array_type +#define __pyx_MemviewEnum_type __pyx_mstate_global->__pyx_MemviewEnum_type +#define __pyx_memoryview_type __pyx_mstate_global->__pyx_memoryview_type +#define __pyx_memoryviewslice_type __pyx_mstate_global->__pyx_memoryviewslice_type +#define __pyx_kp_u_ __pyx_mstate_global->__pyx_kp_u_ +#define __pyx_n_s_ASCII __pyx_mstate_global->__pyx_n_s_ASCII +#define __pyx_kp_s_All_dimensions_preceding_dimensi __pyx_mstate_global->__pyx_kp_s_All_dimensions_preceding_dimensi +#define __pyx_n_s_AssertionError __pyx_mstate_global->__pyx_n_s_AssertionError +#define __pyx_kp_s_Buffer_view_does_not_expose_stri __pyx_mstate_global->__pyx_kp_s_Buffer_view_does_not_expose_stri +#define __pyx_n_s_CPU __pyx_mstate_global->__pyx_n_s_CPU +#define __pyx_kp_s_Can_only_create_a_buffer_that_is __pyx_mstate_global->__pyx_kp_s_Can_only_create_a_buffer_that_is +#define __pyx_kp_s_Cannot_assign_to_read_only_memor __pyx_mstate_global->__pyx_kp_s_Cannot_assign_to_read_only_memor +#define __pyx_kp_s_Cannot_create_writable_memory_vi __pyx_mstate_global->__pyx_kp_s_Cannot_create_writable_memory_vi +#define __pyx_kp_u_Cannot_index_with_type __pyx_mstate_global->__pyx_kp_u_Cannot_index_with_type +#define __pyx_kp_s_Cannot_transpose_memoryview_with __pyx_mstate_global->__pyx_kp_s_Cannot_transpose_memoryview_with +#define __pyx_n_s_DSP __pyx_mstate_global->__pyx_n_s_DSP +#define __pyx_kp_s_Dimension_d_is_not_direct __pyx_mstate_global->__pyx_kp_s_Dimension_d_is_not_direct +#define __pyx_n_s_Ellipsis __pyx_mstate_global->__pyx_n_s_Ellipsis +#define __pyx_kp_s_Empty_shape_tuple_for_cython_arr __pyx_mstate_global->__pyx_kp_s_Empty_shape_tuple_for_cython_arr +#define __pyx_n_s_GPU __pyx_mstate_global->__pyx_n_s_GPU +#define __pyx_kp_s_Incompatible_checksums_0x_x_vs_0 __pyx_mstate_global->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0 +#define __pyx_n_s_IndexError __pyx_mstate_global->__pyx_n_s_IndexError +#define __pyx_kp_s_Index_out_of_bounds_axis_d __pyx_mstate_global->__pyx_kp_s_Index_out_of_bounds_axis_d +#define __pyx_kp_s_Indirect_dimensions_not_supporte __pyx_mstate_global->__pyx_kp_s_Indirect_dimensions_not_supporte +#define __pyx_kp_u_Invalid_mode_expected_c_or_fortr __pyx_mstate_global->__pyx_kp_u_Invalid_mode_expected_c_or_fortr +#define __pyx_kp_u_Invalid_shape_in_axis __pyx_mstate_global->__pyx_kp_u_Invalid_shape_in_axis +#define __pyx_n_s_MemoryError __pyx_mstate_global->__pyx_n_s_MemoryError +#define __pyx_kp_s_MemoryView_of_r_at_0x_x __pyx_mstate_global->__pyx_kp_s_MemoryView_of_r_at_0x_x +#define __pyx_kp_s_MemoryView_of_r_object __pyx_mstate_global->__pyx_kp_s_MemoryView_of_r_object +#define __pyx_n_b_O __pyx_mstate_global->__pyx_n_b_O +#define __pyx_kp_u_Out_of_bounds_on_buffer_access_a __pyx_mstate_global->__pyx_kp_u_Out_of_bounds_on_buffer_access_a +#define __pyx_n_s_PickleError __pyx_mstate_global->__pyx_n_s_PickleError +#define __pyx_n_s_RunModel __pyx_mstate_global->__pyx_n_s_RunModel +#define __pyx_n_s_RunModel___reduce_cython __pyx_mstate_global->__pyx_n_s_RunModel___reduce_cython +#define __pyx_n_s_RunModel___setstate_cython __pyx_mstate_global->__pyx_n_s_RunModel___setstate_cython +#define __pyx_n_s_RunModel_addInput __pyx_mstate_global->__pyx_n_s_RunModel_addInput +#define __pyx_n_s_RunModel_execute __pyx_mstate_global->__pyx_n_s_RunModel_execute +#define __pyx_n_s_RunModel_getCLBuffer __pyx_mstate_global->__pyx_n_s_RunModel_getCLBuffer +#define __pyx_n_s_RunModel_setInputBuffer __pyx_mstate_global->__pyx_n_s_RunModel_setInputBuffer +#define __pyx_n_s_Runtime __pyx_mstate_global->__pyx_n_s_Runtime +#define __pyx_n_s_Sequence __pyx_mstate_global->__pyx_n_s_Sequence +#define __pyx_kp_s_Step_may_not_be_zero_axis_d __pyx_mstate_global->__pyx_kp_s_Step_may_not_be_zero_axis_d +#define __pyx_n_s_TypeError __pyx_mstate_global->__pyx_n_s_TypeError +#define __pyx_kp_s_Unable_to_convert_item_to_object __pyx_mstate_global->__pyx_kp_s_Unable_to_convert_item_to_object +#define __pyx_n_s_ValueError __pyx_mstate_global->__pyx_n_s_ValueError +#define __pyx_n_s_View_MemoryView __pyx_mstate_global->__pyx_n_s_View_MemoryView +#define __pyx_kp_u__2 __pyx_mstate_global->__pyx_kp_u__2 +#define __pyx_n_s__3 __pyx_mstate_global->__pyx_n_s__3 +#define __pyx_n_s__30 __pyx_mstate_global->__pyx_n_s__30 +#define __pyx_kp_u__6 __pyx_mstate_global->__pyx_kp_u__6 +#define __pyx_kp_u__7 __pyx_mstate_global->__pyx_kp_u__7 +#define __pyx_n_s_abc __pyx_mstate_global->__pyx_n_s_abc +#define __pyx_n_s_addInput __pyx_mstate_global->__pyx_n_s_addInput +#define __pyx_n_s_allocate_buffer __pyx_mstate_global->__pyx_n_s_allocate_buffer +#define __pyx_kp_u_and __pyx_mstate_global->__pyx_kp_u_and +#define __pyx_n_s_asyncio_coroutines __pyx_mstate_global->__pyx_n_s_asyncio_coroutines +#define __pyx_n_s_base __pyx_mstate_global->__pyx_n_s_base +#define __pyx_n_s_buffer __pyx_mstate_global->__pyx_n_s_buffer +#define __pyx_n_s_c __pyx_mstate_global->__pyx_n_s_c +#define __pyx_n_u_c __pyx_mstate_global->__pyx_n_u_c +#define __pyx_n_s_cl_buf __pyx_mstate_global->__pyx_n_s_cl_buf +#define __pyx_n_s_class __pyx_mstate_global->__pyx_n_s_class +#define __pyx_n_s_class_getitem __pyx_mstate_global->__pyx_n_s_class_getitem +#define __pyx_n_s_cline_in_traceback __pyx_mstate_global->__pyx_n_s_cline_in_traceback +#define __pyx_n_s_collections __pyx_mstate_global->__pyx_n_s_collections +#define __pyx_kp_s_collections_abc __pyx_mstate_global->__pyx_kp_s_collections_abc +#define __pyx_kp_s_contiguous_and_direct __pyx_mstate_global->__pyx_kp_s_contiguous_and_direct +#define __pyx_kp_s_contiguous_and_indirect __pyx_mstate_global->__pyx_kp_s_contiguous_and_indirect +#define __pyx_n_s_count __pyx_mstate_global->__pyx_n_s_count +#define __pyx_n_s_dict __pyx_mstate_global->__pyx_n_s_dict +#define __pyx_kp_u_disable __pyx_mstate_global->__pyx_kp_u_disable +#define __pyx_n_s_doc __pyx_mstate_global->__pyx_n_s_doc +#define __pyx_n_s_dtype_is_object __pyx_mstate_global->__pyx_n_s_dtype_is_object +#define __pyx_kp_u_enable __pyx_mstate_global->__pyx_kp_u_enable +#define __pyx_n_s_encode __pyx_mstate_global->__pyx_n_s_encode +#define __pyx_n_s_enumerate __pyx_mstate_global->__pyx_n_s_enumerate +#define __pyx_n_s_error __pyx_mstate_global->__pyx_n_s_error +#define __pyx_n_s_execute __pyx_mstate_global->__pyx_n_s_execute +#define __pyx_n_s_flags __pyx_mstate_global->__pyx_n_s_flags +#define __pyx_n_s_format __pyx_mstate_global->__pyx_n_s_format +#define __pyx_n_s_fortran __pyx_mstate_global->__pyx_n_s_fortran +#define __pyx_n_u_fortran __pyx_mstate_global->__pyx_n_u_fortran +#define __pyx_kp_u_gc __pyx_mstate_global->__pyx_kp_u_gc +#define __pyx_n_s_getCLBuffer __pyx_mstate_global->__pyx_n_s_getCLBuffer +#define __pyx_n_s_getstate __pyx_mstate_global->__pyx_n_s_getstate +#define __pyx_kp_u_got __pyx_mstate_global->__pyx_kp_u_got +#define __pyx_kp_u_got_differing_extents_in_dimensi __pyx_mstate_global->__pyx_kp_u_got_differing_extents_in_dimensi +#define __pyx_n_s_id __pyx_mstate_global->__pyx_n_s_id +#define __pyx_n_s_import __pyx_mstate_global->__pyx_n_s_import +#define __pyx_n_s_index __pyx_mstate_global->__pyx_n_s_index +#define __pyx_n_s_init_subclass __pyx_mstate_global->__pyx_n_s_init_subclass +#define __pyx_n_s_initializing __pyx_mstate_global->__pyx_n_s_initializing +#define __pyx_n_s_is_coroutine __pyx_mstate_global->__pyx_n_s_is_coroutine +#define __pyx_kp_u_isenabled __pyx_mstate_global->__pyx_kp_u_isenabled +#define __pyx_n_s_itemsize __pyx_mstate_global->__pyx_n_s_itemsize +#define __pyx_kp_s_itemsize_0_for_cython_array __pyx_mstate_global->__pyx_kp_s_itemsize_0_for_cython_array +#define __pyx_n_s_main __pyx_mstate_global->__pyx_n_s_main +#define __pyx_n_s_memview __pyx_mstate_global->__pyx_n_s_memview +#define __pyx_n_s_metaclass __pyx_mstate_global->__pyx_n_s_metaclass +#define __pyx_n_s_mode __pyx_mstate_global->__pyx_n_s_mode +#define __pyx_n_s_module __pyx_mstate_global->__pyx_n_s_module +#define __pyx_n_s_name __pyx_mstate_global->__pyx_n_s_name +#define __pyx_n_s_name_2 __pyx_mstate_global->__pyx_n_s_name_2 +#define __pyx_n_s_ndim __pyx_mstate_global->__pyx_n_s_ndim +#define __pyx_n_s_new __pyx_mstate_global->__pyx_n_s_new +#define __pyx_kp_s_no_default___reduce___due_to_non __pyx_mstate_global->__pyx_kp_s_no_default___reduce___due_to_non +#define __pyx_n_s_obj __pyx_mstate_global->__pyx_n_s_obj +#define __pyx_n_s_pack __pyx_mstate_global->__pyx_n_s_pack +#define __pyx_n_s_pickle __pyx_mstate_global->__pyx_n_s_pickle +#define __pyx_n_s_prepare __pyx_mstate_global->__pyx_n_s_prepare +#define __pyx_n_s_pyx_PickleError __pyx_mstate_global->__pyx_n_s_pyx_PickleError +#define __pyx_n_s_pyx_checksum __pyx_mstate_global->__pyx_n_s_pyx_checksum +#define __pyx_n_s_pyx_result __pyx_mstate_global->__pyx_n_s_pyx_result +#define __pyx_n_s_pyx_state __pyx_mstate_global->__pyx_n_s_pyx_state +#define __pyx_n_s_pyx_type __pyx_mstate_global->__pyx_n_s_pyx_type +#define __pyx_n_s_pyx_unpickle_Enum __pyx_mstate_global->__pyx_n_s_pyx_unpickle_Enum +#define __pyx_n_s_pyx_vtable __pyx_mstate_global->__pyx_n_s_pyx_vtable +#define __pyx_n_s_qualname __pyx_mstate_global->__pyx_n_s_qualname +#define __pyx_n_s_range __pyx_mstate_global->__pyx_n_s_range +#define __pyx_n_s_reduce __pyx_mstate_global->__pyx_n_s_reduce +#define __pyx_n_s_reduce_cython __pyx_mstate_global->__pyx_n_s_reduce_cython +#define __pyx_n_s_reduce_ex __pyx_mstate_global->__pyx_n_s_reduce_ex +#define __pyx_n_s_register __pyx_mstate_global->__pyx_n_s_register +#define __pyx_n_s_self __pyx_mstate_global->__pyx_n_s_self +#define __pyx_kp_s_self_model_cannot_be_converted_t __pyx_mstate_global->__pyx_kp_s_self_model_cannot_be_converted_t +#define __pyx_n_s_selfdrive_modeld_runners_runmode __pyx_mstate_global->__pyx_n_s_selfdrive_modeld_runners_runmode +#define __pyx_kp_s_selfdrive_modeld_runners_runmode_2 __pyx_mstate_global->__pyx_kp_s_selfdrive_modeld_runners_runmode_2 +#define __pyx_n_s_setInputBuffer __pyx_mstate_global->__pyx_n_s_setInputBuffer +#define __pyx_n_s_set_name __pyx_mstate_global->__pyx_n_s_set_name +#define __pyx_n_s_setstate __pyx_mstate_global->__pyx_n_s_setstate +#define __pyx_n_s_setstate_cython __pyx_mstate_global->__pyx_n_s_setstate_cython +#define __pyx_n_s_shape __pyx_mstate_global->__pyx_n_s_shape +#define __pyx_n_s_size __pyx_mstate_global->__pyx_n_s_size +#define __pyx_n_s_spec __pyx_mstate_global->__pyx_n_s_spec +#define __pyx_n_s_start __pyx_mstate_global->__pyx_n_s_start +#define __pyx_n_s_step __pyx_mstate_global->__pyx_n_s_step +#define __pyx_n_s_stop __pyx_mstate_global->__pyx_n_s_stop +#define __pyx_kp_s_strided_and_direct __pyx_mstate_global->__pyx_kp_s_strided_and_direct +#define __pyx_kp_s_strided_and_direct_or_indirect __pyx_mstate_global->__pyx_kp_s_strided_and_direct_or_indirect +#define __pyx_kp_s_strided_and_indirect __pyx_mstate_global->__pyx_kp_s_strided_and_indirect +#define __pyx_kp_s_stringsource __pyx_mstate_global->__pyx_kp_s_stringsource +#define __pyx_n_s_struct __pyx_mstate_global->__pyx_n_s_struct +#define __pyx_n_s_super __pyx_mstate_global->__pyx_n_s_super +#define __pyx_n_s_sys __pyx_mstate_global->__pyx_n_s_sys +#define __pyx_n_s_test __pyx_mstate_global->__pyx_n_s_test +#define __pyx_kp_s_unable_to_allocate_array_data __pyx_mstate_global->__pyx_kp_s_unable_to_allocate_array_data +#define __pyx_kp_s_unable_to_allocate_shape_and_str __pyx_mstate_global->__pyx_kp_s_unable_to_allocate_shape_and_str +#define __pyx_n_s_unpack __pyx_mstate_global->__pyx_n_s_unpack +#define __pyx_n_s_update __pyx_mstate_global->__pyx_n_s_update +#define __pyx_n_s_version_info __pyx_mstate_global->__pyx_n_s_version_info +#define __pyx_int_0 __pyx_mstate_global->__pyx_int_0 +#define __pyx_int_1 __pyx_mstate_global->__pyx_int_1 +#define __pyx_int_3 __pyx_mstate_global->__pyx_int_3 +#define __pyx_int_112105877 __pyx_mstate_global->__pyx_int_112105877 +#define __pyx_int_136983863 __pyx_mstate_global->__pyx_int_136983863 +#define __pyx_int_184977713 __pyx_mstate_global->__pyx_int_184977713 +#define __pyx_int_neg_1 __pyx_mstate_global->__pyx_int_neg_1 +#define __pyx_slice__5 __pyx_mstate_global->__pyx_slice__5 +#define __pyx_tuple__4 __pyx_mstate_global->__pyx_tuple__4 +#define __pyx_tuple__8 __pyx_mstate_global->__pyx_tuple__8 +#define __pyx_tuple__9 __pyx_mstate_global->__pyx_tuple__9 +#define __pyx_tuple__10 __pyx_mstate_global->__pyx_tuple__10 +#define __pyx_tuple__11 __pyx_mstate_global->__pyx_tuple__11 +#define __pyx_tuple__12 __pyx_mstate_global->__pyx_tuple__12 +#define __pyx_tuple__13 __pyx_mstate_global->__pyx_tuple__13 +#define __pyx_tuple__14 __pyx_mstate_global->__pyx_tuple__14 +#define __pyx_tuple__15 __pyx_mstate_global->__pyx_tuple__15 +#define __pyx_tuple__16 __pyx_mstate_global->__pyx_tuple__16 +#define __pyx_tuple__17 __pyx_mstate_global->__pyx_tuple__17 +#define __pyx_tuple__18 __pyx_mstate_global->__pyx_tuple__18 +#define __pyx_tuple__20 __pyx_mstate_global->__pyx_tuple__20 +#define __pyx_tuple__23 __pyx_mstate_global->__pyx_tuple__23 +#define __pyx_tuple__25 __pyx_mstate_global->__pyx_tuple__25 +#define __pyx_tuple__28 __pyx_mstate_global->__pyx_tuple__28 +#define __pyx_codeobj__19 __pyx_mstate_global->__pyx_codeobj__19 +#define __pyx_codeobj__21 __pyx_mstate_global->__pyx_codeobj__21 +#define __pyx_codeobj__22 __pyx_mstate_global->__pyx_codeobj__22 +#define __pyx_codeobj__24 __pyx_mstate_global->__pyx_codeobj__24 +#define __pyx_codeobj__26 __pyx_mstate_global->__pyx_codeobj__26 +#define __pyx_codeobj__27 __pyx_mstate_global->__pyx_codeobj__27 +#define __pyx_codeobj__29 __pyx_mstate_global->__pyx_codeobj__29 +/* #### Code section: module_code ### */ + +/* "string.from_py":13 + * + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: # <<<<<<<<<<<<<< + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + */ + +static std::string __pyx_convert_string_from_py_std__in_string(PyObject *__pyx_v_o) { + Py_ssize_t __pyx_v_length; + char const *__pyx_v_data; + std::string __pyx_r; + char const *__pyx_t_1; + std::string __pyx_t_2; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + + /* "string.from_py":14 + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: + * cdef Py_ssize_t length = 0 # <<<<<<<<<<<<<< + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + * return string(data, length) + */ + __pyx_v_length = 0; + + /* "string.from_py":15 + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) # <<<<<<<<<<<<<< + * return string(data, length) + * + */ + __pyx_t_1 = __Pyx_PyObject_AsStringAndSize(__pyx_v_o, (&__pyx_v_length)); if (unlikely(__pyx_t_1 == ((char const *)NULL))) __PYX_ERR(0, 15, __pyx_L1_error) + __pyx_v_data = __pyx_t_1; + + /* "string.from_py":16 + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + * return string(data, length) # <<<<<<<<<<<<<< + * + * + */ + try { + __pyx_t_2 = std::string(__pyx_v_data, __pyx_v_length); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(0, 16, __pyx_L1_error) + } + __pyx_r = __pyx_t_2; + goto __pyx_L0; + + /* "string.from_py":13 + * + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: # <<<<<<<<<<<<<< + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("string.from_py.__pyx_convert_string_from_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_pretend_to_initialize(&__pyx_r); + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":131 + * cdef bint dtype_is_object + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, # <<<<<<<<<<<<<< + * mode="c", bint allocate_buffer=True): + * + */ + +/* Python wrapper */ +static int __pyx_array___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_array___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_shape = 0; + Py_ssize_t __pyx_v_itemsize; + PyObject *__pyx_v_format = 0; + PyObject *__pyx_v_mode = 0; + int __pyx_v_allocate_buffer; + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[5] = {0,0,0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_shape,&__pyx_n_s_itemsize,&__pyx_n_s_format,&__pyx_n_s_mode,&__pyx_n_s_allocate_buffer,0}; + values[3] = __Pyx_Arg_NewRef_VARARGS(((PyObject *)__pyx_n_s_c)); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 5: values[4] = __Pyx_Arg_VARARGS(__pyx_args, 4); + CYTHON_FALLTHROUGH; + case 4: values[3] = __Pyx_Arg_VARARGS(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_shape)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 131, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_itemsize)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 131, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 3, 5, 1); __PYX_ERR(0, 131, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_format)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 131, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 3, 5, 2); __PYX_ERR(0, 131, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 3: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_mode); + if (value) { values[3] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 131, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 4: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_allocate_buffer); + if (value) { values[4] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 131, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(0, 131, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 5: values[4] = __Pyx_Arg_VARARGS(__pyx_args, 4); + CYTHON_FALLTHROUGH; + case 4: values[3] = __Pyx_Arg_VARARGS(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_shape = ((PyObject*)values[0]); + __pyx_v_itemsize = __Pyx_PyIndex_AsSsize_t(values[1]); if (unlikely((__pyx_v_itemsize == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 131, __pyx_L3_error) + __pyx_v_format = values[2]; + __pyx_v_mode = values[3]; + if (values[4]) { + __pyx_v_allocate_buffer = __Pyx_PyObject_IsTrue(values[4]); if (unlikely((__pyx_v_allocate_buffer == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 132, __pyx_L3_error) + } else { + + /* "View.MemoryView":132 + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, + * mode="c", bint allocate_buffer=True): # <<<<<<<<<<<<<< + * + * cdef int idx + */ + __pyx_v_allocate_buffer = ((int)1); + } + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 3, 5, __pyx_nargs); __PYX_ERR(0, 131, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.array.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_shape), (&PyTuple_Type), 1, "shape", 1))) __PYX_ERR(0, 131, __pyx_L1_error) + if (unlikely(((PyObject *)__pyx_v_format) == Py_None)) { + PyErr_Format(PyExc_TypeError, "Argument '%.200s' must not be None", "format"); __PYX_ERR(0, 131, __pyx_L1_error) + } + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array___cinit__(((struct __pyx_array_obj *)__pyx_v_self), __pyx_v_shape, __pyx_v_itemsize, __pyx_v_format, __pyx_v_mode, __pyx_v_allocate_buffer); + + /* "View.MemoryView":131 + * cdef bint dtype_is_object + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, # <<<<<<<<<<<<<< + * mode="c", bint allocate_buffer=True): + * + */ + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = -1; + __pyx_L0:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array___cinit__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_shape, Py_ssize_t __pyx_v_itemsize, PyObject *__pyx_v_format, PyObject *__pyx_v_mode, int __pyx_v_allocate_buffer) { + int __pyx_v_idx; + Py_ssize_t __pyx_v_dim; + char __pyx_v_order; + int __pyx_r; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + int __pyx_t_7; + char *__pyx_t_8; + Py_ssize_t __pyx_t_9; + Py_UCS4 __pyx_t_10; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__cinit__", 0); + __Pyx_INCREF(__pyx_v_format); + + /* "View.MemoryView":137 + * cdef Py_ssize_t dim + * + * self.ndim = len(shape) # <<<<<<<<<<<<<< + * self.itemsize = itemsize + * + */ + if (unlikely(__pyx_v_shape == Py_None)) { + PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); + __PYX_ERR(0, 137, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_PyTuple_GET_SIZE(__pyx_v_shape); if (unlikely(__pyx_t_1 == ((Py_ssize_t)-1))) __PYX_ERR(0, 137, __pyx_L1_error) + __pyx_v_self->ndim = ((int)__pyx_t_1); + + /* "View.MemoryView":138 + * + * self.ndim = len(shape) + * self.itemsize = itemsize # <<<<<<<<<<<<<< + * + * if not self.ndim: + */ + __pyx_v_self->itemsize = __pyx_v_itemsize; + + /* "View.MemoryView":140 + * self.itemsize = itemsize + * + * if not self.ndim: # <<<<<<<<<<<<<< + * raise ValueError, "Empty shape tuple for cython.array" + * + */ + __pyx_t_2 = (!(__pyx_v_self->ndim != 0)); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":141 + * + * if not self.ndim: + * raise ValueError, "Empty shape tuple for cython.array" # <<<<<<<<<<<<<< + * + * if itemsize <= 0: + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Empty_shape_tuple_for_cython_arr, 0, 0); + __PYX_ERR(0, 141, __pyx_L1_error) + + /* "View.MemoryView":140 + * self.itemsize = itemsize + * + * if not self.ndim: # <<<<<<<<<<<<<< + * raise ValueError, "Empty shape tuple for cython.array" + * + */ + } + + /* "View.MemoryView":143 + * raise ValueError, "Empty shape tuple for cython.array" + * + * if itemsize <= 0: # <<<<<<<<<<<<<< + * raise ValueError, "itemsize <= 0 for cython.array" + * + */ + __pyx_t_2 = (__pyx_v_itemsize <= 0); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":144 + * + * if itemsize <= 0: + * raise ValueError, "itemsize <= 0 for cython.array" # <<<<<<<<<<<<<< + * + * if not isinstance(format, bytes): + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_itemsize_0_for_cython_array, 0, 0); + __PYX_ERR(0, 144, __pyx_L1_error) + + /* "View.MemoryView":143 + * raise ValueError, "Empty shape tuple for cython.array" + * + * if itemsize <= 0: # <<<<<<<<<<<<<< + * raise ValueError, "itemsize <= 0 for cython.array" + * + */ + } + + /* "View.MemoryView":146 + * raise ValueError, "itemsize <= 0 for cython.array" + * + * if not isinstance(format, bytes): # <<<<<<<<<<<<<< + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string + */ + __pyx_t_2 = PyBytes_Check(__pyx_v_format); + __pyx_t_3 = (!__pyx_t_2); + if (__pyx_t_3) { + + /* "View.MemoryView":147 + * + * if not isinstance(format, bytes): + * format = format.encode('ASCII') # <<<<<<<<<<<<<< + * self._format = format # keep a reference to the byte string + * self.format = self._format + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_format, __pyx_n_s_encode); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 147, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = NULL; + __pyx_t_7 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_6 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_6)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_6); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_7 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_6, __pyx_n_s_ASCII}; + __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_7, 1+__pyx_t_7); + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 147, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + __Pyx_DECREF_SET(__pyx_v_format, __pyx_t_4); + __pyx_t_4 = 0; + + /* "View.MemoryView":146 + * raise ValueError, "itemsize <= 0 for cython.array" + * + * if not isinstance(format, bytes): # <<<<<<<<<<<<<< + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string + */ + } + + /* "View.MemoryView":148 + * if not isinstance(format, bytes): + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string # <<<<<<<<<<<<<< + * self.format = self._format + * + */ + if (!(likely(PyBytes_CheckExact(__pyx_v_format))||((__pyx_v_format) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_v_format))) __PYX_ERR(0, 148, __pyx_L1_error) + __pyx_t_4 = __pyx_v_format; + __Pyx_INCREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + __Pyx_GOTREF(__pyx_v_self->_format); + __Pyx_DECREF(__pyx_v_self->_format); + __pyx_v_self->_format = ((PyObject*)__pyx_t_4); + __pyx_t_4 = 0; + + /* "View.MemoryView":149 + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string + * self.format = self._format # <<<<<<<<<<<<<< + * + * + */ + if (unlikely(__pyx_v_self->_format == Py_None)) { + PyErr_SetString(PyExc_TypeError, "expected bytes, NoneType found"); + __PYX_ERR(0, 149, __pyx_L1_error) + } + __pyx_t_8 = __Pyx_PyBytes_AsWritableString(__pyx_v_self->_format); if (unlikely((!__pyx_t_8) && PyErr_Occurred())) __PYX_ERR(0, 149, __pyx_L1_error) + __pyx_v_self->format = __pyx_t_8; + + /* "View.MemoryView":152 + * + * + * self._shape = PyObject_Malloc(sizeof(Py_ssize_t)*self.ndim*2) # <<<<<<<<<<<<<< + * self._strides = self._shape + self.ndim + * + */ + __pyx_v_self->_shape = ((Py_ssize_t *)PyObject_Malloc((((sizeof(Py_ssize_t)) * __pyx_v_self->ndim) * 2))); + + /* "View.MemoryView":153 + * + * self._shape = PyObject_Malloc(sizeof(Py_ssize_t)*self.ndim*2) + * self._strides = self._shape + self.ndim # <<<<<<<<<<<<<< + * + * if not self._shape: + */ + __pyx_v_self->_strides = (__pyx_v_self->_shape + __pyx_v_self->ndim); + + /* "View.MemoryView":155 + * self._strides = self._shape + self.ndim + * + * if not self._shape: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate shape and strides." + * + */ + __pyx_t_3 = (!(__pyx_v_self->_shape != 0)); + if (unlikely(__pyx_t_3)) { + + /* "View.MemoryView":156 + * + * if not self._shape: + * raise MemoryError, "unable to allocate shape and strides." # <<<<<<<<<<<<<< + * + * + */ + __Pyx_Raise(__pyx_builtin_MemoryError, __pyx_kp_s_unable_to_allocate_shape_and_str, 0, 0); + __PYX_ERR(0, 156, __pyx_L1_error) + + /* "View.MemoryView":155 + * self._strides = self._shape + self.ndim + * + * if not self._shape: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate shape and strides." + * + */ + } + + /* "View.MemoryView":159 + * + * + * for idx, dim in enumerate(shape): # <<<<<<<<<<<<<< + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + */ + __pyx_t_7 = 0; + __pyx_t_4 = __pyx_v_shape; __Pyx_INCREF(__pyx_t_4); + __pyx_t_1 = 0; + for (;;) { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_4); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 159, __pyx_L1_error) + #endif + if (__pyx_t_1 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_5 = PyTuple_GET_ITEM(__pyx_t_4, __pyx_t_1); __Pyx_INCREF(__pyx_t_5); __pyx_t_1++; if (unlikely((0 < 0))) __PYX_ERR(0, 159, __pyx_L1_error) + #else + __pyx_t_5 = __Pyx_PySequence_ITEM(__pyx_t_4, __pyx_t_1); __pyx_t_1++; if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 159, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + #endif + __pyx_t_9 = __Pyx_PyIndex_AsSsize_t(__pyx_t_5); if (unlikely((__pyx_t_9 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 159, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_v_dim = __pyx_t_9; + __pyx_v_idx = __pyx_t_7; + __pyx_t_7 = (__pyx_t_7 + 1); + + /* "View.MemoryView":160 + * + * for idx, dim in enumerate(shape): + * if dim <= 0: # <<<<<<<<<<<<<< + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + * self._shape[idx] = dim + */ + __pyx_t_3 = (__pyx_v_dim <= 0); + if (unlikely(__pyx_t_3)) { + + /* "View.MemoryView":161 + * for idx, dim in enumerate(shape): + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." # <<<<<<<<<<<<<< + * self._shape[idx] = dim + * + */ + __pyx_t_5 = PyTuple_New(5); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_9 = 0; + __pyx_t_10 = 127; + __Pyx_INCREF(__pyx_kp_u_Invalid_shape_in_axis); + __pyx_t_9 += 22; + __Pyx_GIVEREF(__pyx_kp_u_Invalid_shape_in_axis); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_kp_u_Invalid_shape_in_axis); + __pyx_t_6 = __Pyx_PyUnicode_From_int(__pyx_v_idx, 0, ' ', 'd'); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_9 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_6); + __Pyx_GIVEREF(__pyx_t_6); + PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_6); + __pyx_t_6 = 0; + __Pyx_INCREF(__pyx_kp_u_); + __pyx_t_9 += 2; + __Pyx_GIVEREF(__pyx_kp_u_); + PyTuple_SET_ITEM(__pyx_t_5, 2, __pyx_kp_u_); + __pyx_t_6 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_dim, 0, ' ', 'd'); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_9 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_6); + __Pyx_GIVEREF(__pyx_t_6); + PyTuple_SET_ITEM(__pyx_t_5, 3, __pyx_t_6); + __pyx_t_6 = 0; + __Pyx_INCREF(__pyx_kp_u__2); + __pyx_t_9 += 1; + __Pyx_GIVEREF(__pyx_kp_u__2); + PyTuple_SET_ITEM(__pyx_t_5, 4, __pyx_kp_u__2); + __pyx_t_6 = __Pyx_PyUnicode_Join(__pyx_t_5, 5, __pyx_t_9, __pyx_t_10); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_t_6, 0, 0); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __PYX_ERR(0, 161, __pyx_L1_error) + + /* "View.MemoryView":160 + * + * for idx, dim in enumerate(shape): + * if dim <= 0: # <<<<<<<<<<<<<< + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + * self._shape[idx] = dim + */ + } + + /* "View.MemoryView":162 + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + * self._shape[idx] = dim # <<<<<<<<<<<<<< + * + * cdef char order + */ + (__pyx_v_self->_shape[__pyx_v_idx]) = __pyx_v_dim; + + /* "View.MemoryView":159 + * + * + * for idx, dim in enumerate(shape): # <<<<<<<<<<<<<< + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + */ + } + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "View.MemoryView":165 + * + * cdef char order + * if mode == 'c': # <<<<<<<<<<<<<< + * order = b'C' + * self.mode = u'c' + */ + __pyx_t_3 = (__Pyx_PyString_Equals(__pyx_v_mode, __pyx_n_s_c, Py_EQ)); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(0, 165, __pyx_L1_error) + if (__pyx_t_3) { + + /* "View.MemoryView":166 + * cdef char order + * if mode == 'c': + * order = b'C' # <<<<<<<<<<<<<< + * self.mode = u'c' + * elif mode == 'fortran': + */ + __pyx_v_order = 'C'; + + /* "View.MemoryView":167 + * if mode == 'c': + * order = b'C' + * self.mode = u'c' # <<<<<<<<<<<<<< + * elif mode == 'fortran': + * order = b'F' + */ + __Pyx_INCREF(__pyx_n_u_c); + __Pyx_GIVEREF(__pyx_n_u_c); + __Pyx_GOTREF(__pyx_v_self->mode); + __Pyx_DECREF(__pyx_v_self->mode); + __pyx_v_self->mode = __pyx_n_u_c; + + /* "View.MemoryView":165 + * + * cdef char order + * if mode == 'c': # <<<<<<<<<<<<<< + * order = b'C' + * self.mode = u'c' + */ + goto __pyx_L11; + } + + /* "View.MemoryView":168 + * order = b'C' + * self.mode = u'c' + * elif mode == 'fortran': # <<<<<<<<<<<<<< + * order = b'F' + * self.mode = u'fortran' + */ + __pyx_t_3 = (__Pyx_PyString_Equals(__pyx_v_mode, __pyx_n_s_fortran, Py_EQ)); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(0, 168, __pyx_L1_error) + if (likely(__pyx_t_3)) { + + /* "View.MemoryView":169 + * self.mode = u'c' + * elif mode == 'fortran': + * order = b'F' # <<<<<<<<<<<<<< + * self.mode = u'fortran' + * else: + */ + __pyx_v_order = 'F'; + + /* "View.MemoryView":170 + * elif mode == 'fortran': + * order = b'F' + * self.mode = u'fortran' # <<<<<<<<<<<<<< + * else: + * raise ValueError, f"Invalid mode, expected 'c' or 'fortran', got {mode}" + */ + __Pyx_INCREF(__pyx_n_u_fortran); + __Pyx_GIVEREF(__pyx_n_u_fortran); + __Pyx_GOTREF(__pyx_v_self->mode); + __Pyx_DECREF(__pyx_v_self->mode); + __pyx_v_self->mode = __pyx_n_u_fortran; + + /* "View.MemoryView":168 + * order = b'C' + * self.mode = u'c' + * elif mode == 'fortran': # <<<<<<<<<<<<<< + * order = b'F' + * self.mode = u'fortran' + */ + goto __pyx_L11; + } + + /* "View.MemoryView":172 + * self.mode = u'fortran' + * else: + * raise ValueError, f"Invalid mode, expected 'c' or 'fortran', got {mode}" # <<<<<<<<<<<<<< + * + * self.len = fill_contig_strides_array(self._shape, self._strides, itemsize, self.ndim, order) + */ + /*else*/ { + __pyx_t_4 = __Pyx_PyObject_FormatSimple(__pyx_v_mode, __pyx_empty_unicode); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 172, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_6 = __Pyx_PyUnicode_Concat(__pyx_kp_u_Invalid_mode_expected_c_or_fortr, __pyx_t_4); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 172, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_t_6, 0, 0); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __PYX_ERR(0, 172, __pyx_L1_error) + } + __pyx_L11:; + + /* "View.MemoryView":174 + * raise ValueError, f"Invalid mode, expected 'c' or 'fortran', got {mode}" + * + * self.len = fill_contig_strides_array(self._shape, self._strides, itemsize, self.ndim, order) # <<<<<<<<<<<<<< + * + * self.free_data = allocate_buffer + */ + __pyx_v_self->len = __pyx_fill_contig_strides_array(__pyx_v_self->_shape, __pyx_v_self->_strides, __pyx_v_itemsize, __pyx_v_self->ndim, __pyx_v_order); + + /* "View.MemoryView":176 + * self.len = fill_contig_strides_array(self._shape, self._strides, itemsize, self.ndim, order) + * + * self.free_data = allocate_buffer # <<<<<<<<<<<<<< + * self.dtype_is_object = format == b'O' + * + */ + __pyx_v_self->free_data = __pyx_v_allocate_buffer; + + /* "View.MemoryView":177 + * + * self.free_data = allocate_buffer + * self.dtype_is_object = format == b'O' # <<<<<<<<<<<<<< + * + * if allocate_buffer: + */ + __pyx_t_6 = PyObject_RichCompare(__pyx_v_format, __pyx_n_b_O, Py_EQ); __Pyx_XGOTREF(__pyx_t_6); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 177, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_IsTrue(__pyx_t_6); if (unlikely((__pyx_t_3 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 177, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __pyx_v_self->dtype_is_object = __pyx_t_3; + + /* "View.MemoryView":179 + * self.dtype_is_object = format == b'O' + * + * if allocate_buffer: # <<<<<<<<<<<<<< + * _allocate_buffer(self) + * + */ + if (__pyx_v_allocate_buffer) { + + /* "View.MemoryView":180 + * + * if allocate_buffer: + * _allocate_buffer(self) # <<<<<<<<<<<<<< + * + * @cname('getbuffer') + */ + __pyx_t_7 = __pyx_array_allocate_buffer(__pyx_v_self); if (unlikely(__pyx_t_7 == ((int)-1))) __PYX_ERR(0, 180, __pyx_L1_error) + + /* "View.MemoryView":179 + * self.dtype_is_object = format == b'O' + * + * if allocate_buffer: # <<<<<<<<<<<<<< + * _allocate_buffer(self) + * + */ + } + + /* "View.MemoryView":131 + * cdef bint dtype_is_object + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, # <<<<<<<<<<<<<< + * mode="c", bint allocate_buffer=True): + * + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("View.MemoryView.array.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_format); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":182 + * _allocate_buffer(self) + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + */ + +/* Python wrapper */ +CYTHON_UNUSED static int __pyx_array_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +CYTHON_UNUSED static int __pyx_array_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getbuffer__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_2__getbuffer__(((struct __pyx_array_obj *)__pyx_v_self), ((Py_buffer *)__pyx_v_info), ((int)__pyx_v_flags)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_2__getbuffer__(struct __pyx_array_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + int __pyx_v_bufmode; + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + char *__pyx_t_2; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + Py_ssize_t *__pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + if (unlikely(__pyx_v_info == NULL)) { + PyErr_SetString(PyExc_BufferError, "PyObject_GetBuffer: view==NULL argument is obsolete"); + return -1; + } + __Pyx_RefNannySetupContext("__getbuffer__", 0); + __pyx_v_info->obj = Py_None; __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(__pyx_v_info->obj); + + /* "View.MemoryView":184 + * @cname('getbuffer') + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 # <<<<<<<<<<<<<< + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": + */ + __pyx_v_bufmode = -1; + + /* "View.MemoryView":185 + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): # <<<<<<<<<<<<<< + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + */ + __pyx_t_1 = ((__pyx_v_flags & ((PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS) | PyBUF_ANY_CONTIGUOUS)) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":186 + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": # <<<<<<<<<<<<<< + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": + */ + __pyx_t_1 = (__Pyx_PyUnicode_Equals(__pyx_v_self->mode, __pyx_n_u_c, Py_EQ)); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(0, 186, __pyx_L1_error) + if (__pyx_t_1) { + + /* "View.MemoryView":187 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS # <<<<<<<<<<<<<< + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + */ + __pyx_v_bufmode = (PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS); + + /* "View.MemoryView":186 + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": # <<<<<<<<<<<<<< + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": + */ + goto __pyx_L4; + } + + /* "View.MemoryView":188 + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": # <<<<<<<<<<<<<< + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): + */ + __pyx_t_1 = (__Pyx_PyUnicode_Equals(__pyx_v_self->mode, __pyx_n_u_fortran, Py_EQ)); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(0, 188, __pyx_L1_error) + if (__pyx_t_1) { + + /* "View.MemoryView":189 + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS # <<<<<<<<<<<<<< + * if not (flags & bufmode): + * raise ValueError, "Can only create a buffer that is contiguous in memory." + */ + __pyx_v_bufmode = (PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS); + + /* "View.MemoryView":188 + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": # <<<<<<<<<<<<<< + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): + */ + } + __pyx_L4:; + + /* "View.MemoryView":190 + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): # <<<<<<<<<<<<<< + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data + */ + __pyx_t_1 = (!((__pyx_v_flags & __pyx_v_bufmode) != 0)); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":191 + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): + * raise ValueError, "Can only create a buffer that is contiguous in memory." # <<<<<<<<<<<<<< + * info.buf = self.data + * info.len = self.len + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Can_only_create_a_buffer_that_is, 0, 0); + __PYX_ERR(0, 191, __pyx_L1_error) + + /* "View.MemoryView":190 + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): # <<<<<<<<<<<<<< + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data + */ + } + + /* "View.MemoryView":185 + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): # <<<<<<<<<<<<<< + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + */ + } + + /* "View.MemoryView":192 + * if not (flags & bufmode): + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data # <<<<<<<<<<<<<< + * info.len = self.len + * + */ + __pyx_t_2 = __pyx_v_self->data; + __pyx_v_info->buf = __pyx_t_2; + + /* "View.MemoryView":193 + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data + * info.len = self.len # <<<<<<<<<<<<<< + * + * if flags & PyBUF_STRIDES: + */ + __pyx_t_3 = __pyx_v_self->len; + __pyx_v_info->len = __pyx_t_3; + + /* "View.MemoryView":195 + * info.len = self.len + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.ndim = self.ndim + * info.shape = self._shape + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_STRIDES) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":196 + * + * if flags & PyBUF_STRIDES: + * info.ndim = self.ndim # <<<<<<<<<<<<<< + * info.shape = self._shape + * info.strides = self._strides + */ + __pyx_t_4 = __pyx_v_self->ndim; + __pyx_v_info->ndim = __pyx_t_4; + + /* "View.MemoryView":197 + * if flags & PyBUF_STRIDES: + * info.ndim = self.ndim + * info.shape = self._shape # <<<<<<<<<<<<<< + * info.strides = self._strides + * else: + */ + __pyx_t_5 = __pyx_v_self->_shape; + __pyx_v_info->shape = __pyx_t_5; + + /* "View.MemoryView":198 + * info.ndim = self.ndim + * info.shape = self._shape + * info.strides = self._strides # <<<<<<<<<<<<<< + * else: + * info.ndim = 1 + */ + __pyx_t_5 = __pyx_v_self->_strides; + __pyx_v_info->strides = __pyx_t_5; + + /* "View.MemoryView":195 + * info.len = self.len + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.ndim = self.ndim + * info.shape = self._shape + */ + goto __pyx_L6; + } + + /* "View.MemoryView":200 + * info.strides = self._strides + * else: + * info.ndim = 1 # <<<<<<<<<<<<<< + * info.shape = &self.len if flags & PyBUF_ND else NULL + * info.strides = NULL + */ + /*else*/ { + __pyx_v_info->ndim = 1; + + /* "View.MemoryView":201 + * else: + * info.ndim = 1 + * info.shape = &self.len if flags & PyBUF_ND else NULL # <<<<<<<<<<<<<< + * info.strides = NULL + * + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_ND) != 0); + if (__pyx_t_1) { + __pyx_t_5 = (&__pyx_v_self->len); + } else { + __pyx_t_5 = NULL; + } + __pyx_v_info->shape = __pyx_t_5; + + /* "View.MemoryView":202 + * info.ndim = 1 + * info.shape = &self.len if flags & PyBUF_ND else NULL + * info.strides = NULL # <<<<<<<<<<<<<< + * + * info.suboffsets = NULL + */ + __pyx_v_info->strides = NULL; + } + __pyx_L6:; + + /* "View.MemoryView":204 + * info.strides = NULL + * + * info.suboffsets = NULL # <<<<<<<<<<<<<< + * info.itemsize = self.itemsize + * info.readonly = 0 + */ + __pyx_v_info->suboffsets = NULL; + + /* "View.MemoryView":205 + * + * info.suboffsets = NULL + * info.itemsize = self.itemsize # <<<<<<<<<<<<<< + * info.readonly = 0 + * info.format = self.format if flags & PyBUF_FORMAT else NULL + */ + __pyx_t_3 = __pyx_v_self->itemsize; + __pyx_v_info->itemsize = __pyx_t_3; + + /* "View.MemoryView":206 + * info.suboffsets = NULL + * info.itemsize = self.itemsize + * info.readonly = 0 # <<<<<<<<<<<<<< + * info.format = self.format if flags & PyBUF_FORMAT else NULL + * info.obj = self + */ + __pyx_v_info->readonly = 0; + + /* "View.MemoryView":207 + * info.itemsize = self.itemsize + * info.readonly = 0 + * info.format = self.format if flags & PyBUF_FORMAT else NULL # <<<<<<<<<<<<<< + * info.obj = self + * + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_FORMAT) != 0); + if (__pyx_t_1) { + __pyx_t_2 = __pyx_v_self->format; + } else { + __pyx_t_2 = NULL; + } + __pyx_v_info->format = __pyx_t_2; + + /* "View.MemoryView":208 + * info.readonly = 0 + * info.format = self.format if flags & PyBUF_FORMAT else NULL + * info.obj = self # <<<<<<<<<<<<<< + * + * def __dealloc__(array self): + */ + __Pyx_INCREF((PyObject *)__pyx_v_self); + __Pyx_GIVEREF((PyObject *)__pyx_v_self); + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); + __pyx_v_info->obj = ((PyObject *)__pyx_v_self); + + /* "View.MemoryView":182 + * _allocate_buffer(self) + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.array.__getbuffer__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + if (__pyx_v_info->obj != NULL) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + goto __pyx_L2; + __pyx_L0:; + if (__pyx_v_info->obj == Py_None) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + __pyx_L2:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":210 + * info.obj = self + * + * def __dealloc__(array self): # <<<<<<<<<<<<<< + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + */ + +/* Python wrapper */ +static void __pyx_array___dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_array___dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_array___pyx_pf_15View_dot_MemoryView_5array_4__dealloc__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_array___pyx_pf_15View_dot_MemoryView_5array_4__dealloc__(struct __pyx_array_obj *__pyx_v_self) { + int __pyx_t_1; + int __pyx_t_2; + + /* "View.MemoryView":211 + * + * def __dealloc__(array self): + * if self.callback_free_data != NULL: # <<<<<<<<<<<<<< + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + */ + __pyx_t_1 = (__pyx_v_self->callback_free_data != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":212 + * def __dealloc__(array self): + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) # <<<<<<<<<<<<<< + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: + */ + __pyx_v_self->callback_free_data(__pyx_v_self->data); + + /* "View.MemoryView":211 + * + * def __dealloc__(array self): + * if self.callback_free_data != NULL: # <<<<<<<<<<<<<< + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":213 + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: # <<<<<<<<<<<<<< + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + */ + if (__pyx_v_self->free_data) { + } else { + __pyx_t_1 = __pyx_v_self->free_data; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_2 = (__pyx_v_self->data != NULL); + __pyx_t_1 = __pyx_t_2; + __pyx_L4_bool_binop_done:; + if (__pyx_t_1) { + + /* "View.MemoryView":214 + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) + */ + if (__pyx_v_self->dtype_is_object) { + + /* "View.MemoryView":215 + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) # <<<<<<<<<<<<<< + * free(self.data) + * PyObject_Free(self._shape) + */ + __pyx_memoryview_refcount_objects_in_slice(__pyx_v_self->data, __pyx_v_self->_shape, __pyx_v_self->_strides, __pyx_v_self->ndim, 0); + + /* "View.MemoryView":214 + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) + */ + } + + /* "View.MemoryView":216 + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) # <<<<<<<<<<<<<< + * PyObject_Free(self._shape) + * + */ + free(__pyx_v_self->data); + + /* "View.MemoryView":213 + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: # <<<<<<<<<<<<<< + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + */ + } + __pyx_L3:; + + /* "View.MemoryView":217 + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) + * PyObject_Free(self._shape) # <<<<<<<<<<<<<< + * + * @property + */ + PyObject_Free(__pyx_v_self->_shape); + + /* "View.MemoryView":210 + * info.obj = self + * + * def __dealloc__(array self): # <<<<<<<<<<<<<< + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + */ + + /* function exit code */ +} + +/* "View.MemoryView":219 + * PyObject_Free(self._shape) + * + * @property # <<<<<<<<<<<<<< + * def memview(self): + * return self.get_memview() + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_5array_7memview_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_5array_7memview_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_5array_7memview___get__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_5array_7memview___get__(struct __pyx_array_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":221 + * @property + * def memview(self): + * return self.get_memview() # <<<<<<<<<<<<<< + * + * @cname('get_memview') + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = ((struct __pyx_vtabstruct_array *)__pyx_v_self->__pyx_vtab)->get_memview(__pyx_v_self); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 221, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":219 + * PyObject_Free(self._shape) + * + * @property # <<<<<<<<<<<<<< + * def memview(self): + * return self.get_memview() + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.array.memview.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":224 + * + * @cname('get_memview') + * cdef get_memview(self): # <<<<<<<<<<<<<< + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE + * return memoryview(self, flags, self.dtype_is_object) + */ + +static PyObject *__pyx_array_get_memview(struct __pyx_array_obj *__pyx_v_self) { + int __pyx_v_flags; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_memview", 1); + + /* "View.MemoryView":225 + * @cname('get_memview') + * cdef get_memview(self): + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE # <<<<<<<<<<<<<< + * return memoryview(self, flags, self.dtype_is_object) + * + */ + __pyx_v_flags = ((PyBUF_ANY_CONTIGUOUS | PyBUF_FORMAT) | PyBUF_WRITABLE); + + /* "View.MemoryView":226 + * cdef get_memview(self): + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE + * return memoryview(self, flags, self.dtype_is_object) # <<<<<<<<<<<<<< + * + * def __len__(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_flags); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_v_self->dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF((PyObject *)__pyx_v_self); + __Pyx_GIVEREF((PyObject *)__pyx_v_self); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, ((PyObject *)__pyx_v_self))) __PYX_ERR(0, 226, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1)) __PYX_ERR(0, 226, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_t_2)) __PYX_ERR(0, 226, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_Call(((PyObject *)__pyx_memoryview_type), __pyx_t_3, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":224 + * + * @cname('get_memview') + * cdef get_memview(self): # <<<<<<<<<<<<<< + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE + * return memoryview(self, flags, self.dtype_is_object) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.array.get_memview", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":228 + * return memoryview(self, flags, self.dtype_is_object) + * + * def __len__(self): # <<<<<<<<<<<<<< + * return self._shape[0] + * + */ + +/* Python wrapper */ +static Py_ssize_t __pyx_array___len__(PyObject *__pyx_v_self); /*proto*/ +static Py_ssize_t __pyx_array___len__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + Py_ssize_t __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__len__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_6__len__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static Py_ssize_t __pyx_array___pyx_pf_15View_dot_MemoryView_5array_6__len__(struct __pyx_array_obj *__pyx_v_self) { + Py_ssize_t __pyx_r; + + /* "View.MemoryView":229 + * + * def __len__(self): + * return self._shape[0] # <<<<<<<<<<<<<< + * + * def __getattr__(self, attr): + */ + __pyx_r = (__pyx_v_self->_shape[0]); + goto __pyx_L0; + + /* "View.MemoryView":228 + * return memoryview(self, flags, self.dtype_is_object) + * + * def __len__(self): # <<<<<<<<<<<<<< + * return self._shape[0] + * + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":231 + * return self._shape[0] + * + * def __getattr__(self, attr): # <<<<<<<<<<<<<< + * return getattr(self.memview, attr) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_array___getattr__(PyObject *__pyx_v_self, PyObject *__pyx_v_attr); /*proto*/ +static PyObject *__pyx_array___getattr__(PyObject *__pyx_v_self, PyObject *__pyx_v_attr) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getattr__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_8__getattr__(((struct __pyx_array_obj *)__pyx_v_self), ((PyObject *)__pyx_v_attr)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_8__getattr__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_attr) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__getattr__", 1); + + /* "View.MemoryView":232 + * + * def __getattr__(self, attr): + * return getattr(self.memview, attr) # <<<<<<<<<<<<<< + * + * def __getitem__(self, item): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_memview); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 232, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_GetAttr(__pyx_t_1, __pyx_v_attr); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 232, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":231 + * return self._shape[0] + * + * def __getattr__(self, attr): # <<<<<<<<<<<<<< + * return getattr(self.memview, attr) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.array.__getattr__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":234 + * return getattr(self.memview, attr) + * + * def __getitem__(self, item): # <<<<<<<<<<<<<< + * return self.memview[item] + * + */ + +/* Python wrapper */ +static PyObject *__pyx_array___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item); /*proto*/ +static PyObject *__pyx_array___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getitem__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_10__getitem__(((struct __pyx_array_obj *)__pyx_v_self), ((PyObject *)__pyx_v_item)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_10__getitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__getitem__", 1); + + /* "View.MemoryView":235 + * + * def __getitem__(self, item): + * return self.memview[item] # <<<<<<<<<<<<<< + * + * def __setitem__(self, item, value): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_memview); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 235, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_t_1, __pyx_v_item); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 235, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":234 + * return getattr(self.memview, attr) + * + * def __getitem__(self, item): # <<<<<<<<<<<<<< + * return self.memview[item] + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.array.__getitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":237 + * return self.memview[item] + * + * def __setitem__(self, item, value): # <<<<<<<<<<<<<< + * self.memview[item] = value + * + */ + +/* Python wrapper */ +static int __pyx_array___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value); /*proto*/ +static int __pyx_array___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setitem__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_12__setitem__(((struct __pyx_array_obj *)__pyx_v_self), ((PyObject *)__pyx_v_item), ((PyObject *)__pyx_v_value)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_12__setitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setitem__", 1); + + /* "View.MemoryView":238 + * + * def __setitem__(self, item, value): + * self.memview[item] = value # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_memview); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 238, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyObject_SetItem(__pyx_t_1, __pyx_v_item, __pyx_v_value) < 0))) __PYX_ERR(0, 238, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "View.MemoryView":237 + * return self.memview[item] + * + * def __setitem__(self, item, value): # <<<<<<<<<<<<<< + * self.memview[item] = value + * + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.array.__setitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_array_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_array_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_array___reduce_cython__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_array___reduce_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(0, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.array.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_array_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_array_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(0, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.array.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_array_2__setstate_cython__(((struct __pyx_array_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_array_2__setstate_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(0, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.array.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":248 + * + * @cname("__pyx_array_allocate_buffer") + * cdef int _allocate_buffer(array self) except -1: # <<<<<<<<<<<<<< + * + * + */ + +static int __pyx_array_allocate_buffer(struct __pyx_array_obj *__pyx_v_self) { + Py_ssize_t __pyx_v_i; + PyObject **__pyx_v_p; + int __pyx_r; + int __pyx_t_1; + Py_ssize_t __pyx_t_2; + Py_ssize_t __pyx_t_3; + Py_ssize_t __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + + /* "View.MemoryView":254 + * cdef PyObject **p + * + * self.free_data = True # <<<<<<<<<<<<<< + * self.data = malloc(self.len) + * if not self.data: + */ + __pyx_v_self->free_data = 1; + + /* "View.MemoryView":255 + * + * self.free_data = True + * self.data = malloc(self.len) # <<<<<<<<<<<<<< + * if not self.data: + * raise MemoryError, "unable to allocate array data." + */ + __pyx_v_self->data = ((char *)malloc(__pyx_v_self->len)); + + /* "View.MemoryView":256 + * self.free_data = True + * self.data = malloc(self.len) + * if not self.data: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate array data." + * + */ + __pyx_t_1 = (!(__pyx_v_self->data != 0)); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":257 + * self.data = malloc(self.len) + * if not self.data: + * raise MemoryError, "unable to allocate array data." # <<<<<<<<<<<<<< + * + * if self.dtype_is_object: + */ + __Pyx_Raise(__pyx_builtin_MemoryError, __pyx_kp_s_unable_to_allocate_array_data, 0, 0); + __PYX_ERR(0, 257, __pyx_L1_error) + + /* "View.MemoryView":256 + * self.free_data = True + * self.data = malloc(self.len) + * if not self.data: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate array data." + * + */ + } + + /* "View.MemoryView":259 + * raise MemoryError, "unable to allocate array data." + * + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * p = self.data + * for i in range(self.len // self.itemsize): + */ + if (__pyx_v_self->dtype_is_object) { + + /* "View.MemoryView":260 + * + * if self.dtype_is_object: + * p = self.data # <<<<<<<<<<<<<< + * for i in range(self.len // self.itemsize): + * p[i] = Py_None + */ + __pyx_v_p = ((PyObject **)__pyx_v_self->data); + + /* "View.MemoryView":261 + * if self.dtype_is_object: + * p = self.data + * for i in range(self.len // self.itemsize): # <<<<<<<<<<<<<< + * p[i] = Py_None + * Py_INCREF(Py_None) + */ + if (unlikely(__pyx_v_self->itemsize == 0)) { + PyErr_SetString(PyExc_ZeroDivisionError, "integer division or modulo by zero"); + __PYX_ERR(0, 261, __pyx_L1_error) + } + else if (sizeof(Py_ssize_t) == sizeof(long) && (!(((Py_ssize_t)-1) > 0)) && unlikely(__pyx_v_self->itemsize == (Py_ssize_t)-1) && unlikely(__Pyx_UNARY_NEG_WOULD_OVERFLOW(__pyx_v_self->len))) { + PyErr_SetString(PyExc_OverflowError, "value too large to perform division"); + __PYX_ERR(0, 261, __pyx_L1_error) + } + __pyx_t_2 = __Pyx_div_Py_ssize_t(__pyx_v_self->len, __pyx_v_self->itemsize); + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":262 + * p = self.data + * for i in range(self.len // self.itemsize): + * p[i] = Py_None # <<<<<<<<<<<<<< + * Py_INCREF(Py_None) + * return 0 + */ + (__pyx_v_p[__pyx_v_i]) = Py_None; + + /* "View.MemoryView":263 + * for i in range(self.len // self.itemsize): + * p[i] = Py_None + * Py_INCREF(Py_None) # <<<<<<<<<<<<<< + * return 0 + * + */ + Py_INCREF(Py_None); + } + + /* "View.MemoryView":259 + * raise MemoryError, "unable to allocate array data." + * + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * p = self.data + * for i in range(self.len // self.itemsize): + */ + } + + /* "View.MemoryView":264 + * p[i] = Py_None + * Py_INCREF(Py_None) + * return 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":248 + * + * @cname("__pyx_array_allocate_buffer") + * cdef int _allocate_buffer(array self) except -1: # <<<<<<<<<<<<<< + * + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._allocate_buffer", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":268 + * + * @cname("__pyx_array_new") + * cdef array array_cwrapper(tuple shape, Py_ssize_t itemsize, char *format, char *c_mode, char *buf): # <<<<<<<<<<<<<< + * cdef array result + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + */ + +static struct __pyx_array_obj *__pyx_array_new(PyObject *__pyx_v_shape, Py_ssize_t __pyx_v_itemsize, char *__pyx_v_format, char *__pyx_v_c_mode, char *__pyx_v_buf) { + struct __pyx_array_obj *__pyx_v_result = 0; + PyObject *__pyx_v_mode = 0; + struct __pyx_array_obj *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("array_cwrapper", 1); + + /* "View.MemoryView":270 + * cdef array array_cwrapper(tuple shape, Py_ssize_t itemsize, char *format, char *c_mode, char *buf): + * cdef array result + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. # <<<<<<<<<<<<<< + * + * if buf is NULL: + */ + __pyx_t_2 = ((__pyx_v_c_mode[0]) == 'f'); + if (__pyx_t_2) { + __Pyx_INCREF(__pyx_n_s_fortran); + __pyx_t_1 = __pyx_n_s_fortran; + } else { + __Pyx_INCREF(__pyx_n_s_c); + __pyx_t_1 = __pyx_n_s_c; + } + __pyx_v_mode = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":272 + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + * + * if buf is NULL: # <<<<<<<<<<<<<< + * result = array.__new__(array, shape, itemsize, format, mode) + * else: + */ + __pyx_t_2 = (__pyx_v_buf == NULL); + if (__pyx_t_2) { + + /* "View.MemoryView":273 + * + * if buf is NULL: + * result = array.__new__(array, shape, itemsize, format, mode) # <<<<<<<<<<<<<< + * else: + * result = array.__new__(array, shape, itemsize, format, mode, allocate_buffer=False) + */ + __pyx_t_1 = PyInt_FromSsize_t(__pyx_v_itemsize); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 273, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyBytes_FromString(__pyx_v_format); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 273, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PyTuple_New(4); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 273, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_INCREF(__pyx_v_shape); + __Pyx_GIVEREF(__pyx_v_shape); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_v_shape)) __PYX_ERR(0, 273, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_t_1)) __PYX_ERR(0, 273, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 2, __pyx_t_3)) __PYX_ERR(0, 273, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_mode); + __Pyx_GIVEREF(__pyx_v_mode); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 3, __pyx_v_mode)) __PYX_ERR(0, 273, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_3 = 0; + __pyx_t_3 = ((PyObject *)__pyx_tp_new_array(((PyTypeObject *)__pyx_array_type), __pyx_t_4, NULL)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 273, __pyx_L1_error) + __Pyx_GOTREF((PyObject *)__pyx_t_3); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_v_result = ((struct __pyx_array_obj *)__pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":272 + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + * + * if buf is NULL: # <<<<<<<<<<<<<< + * result = array.__new__(array, shape, itemsize, format, mode) + * else: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":275 + * result = array.__new__(array, shape, itemsize, format, mode) + * else: + * result = array.__new__(array, shape, itemsize, format, mode, allocate_buffer=False) # <<<<<<<<<<<<<< + * result.data = buf + * + */ + /*else*/ { + __pyx_t_3 = PyInt_FromSsize_t(__pyx_v_itemsize); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = __Pyx_PyBytes_FromString(__pyx_v_format); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_1 = PyTuple_New(4); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v_shape); + __Pyx_GIVEREF(__pyx_v_shape); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v_shape)) __PYX_ERR(0, 275, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_t_3)) __PYX_ERR(0, 275, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_4); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_t_4)) __PYX_ERR(0, 275, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_mode); + __Pyx_GIVEREF(__pyx_v_mode); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 3, __pyx_v_mode)) __PYX_ERR(0, 275, __pyx_L1_error); + __pyx_t_3 = 0; + __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem(__pyx_t_4, __pyx_n_s_allocate_buffer, Py_False) < 0) __PYX_ERR(0, 275, __pyx_L1_error) + __pyx_t_3 = ((PyObject *)__pyx_tp_new_array(((PyTypeObject *)__pyx_array_type), __pyx_t_1, __pyx_t_4)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 275, __pyx_L1_error) + __Pyx_GOTREF((PyObject *)__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_v_result = ((struct __pyx_array_obj *)__pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":276 + * else: + * result = array.__new__(array, shape, itemsize, format, mode, allocate_buffer=False) + * result.data = buf # <<<<<<<<<<<<<< + * + * return result + */ + __pyx_v_result->data = __pyx_v_buf; + } + __pyx_L3:; + + /* "View.MemoryView":278 + * result.data = buf + * + * return result # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF((PyObject *)__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = __pyx_v_result; + goto __pyx_L0; + + /* "View.MemoryView":268 + * + * @cname("__pyx_array_new") + * cdef array array_cwrapper(tuple shape, Py_ssize_t itemsize, char *format, char *c_mode, char *buf): # <<<<<<<<<<<<<< + * cdef array result + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.array_cwrapper", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XDECREF(__pyx_v_mode); + __Pyx_XGIVEREF((PyObject *)__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":304 + * cdef class Enum(object): + * cdef object name + * def __init__(self, name): # <<<<<<<<<<<<<< + * self.name = name + * def __repr__(self): + */ + +/* Python wrapper */ +static int __pyx_MemviewEnum___init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_MemviewEnum___init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_name = 0; + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__init__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_name,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_name)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 304, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__init__") < 0)) __PYX_ERR(0, 304, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + } + __pyx_v_name = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__init__", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 304, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.Enum.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum___init__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self), __pyx_v_name); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum___init__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v_name) { + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__init__", 1); + + /* "View.MemoryView":305 + * cdef object name + * def __init__(self, name): + * self.name = name # <<<<<<<<<<<<<< + * def __repr__(self): + * return self.name + */ + __Pyx_INCREF(__pyx_v_name); + __Pyx_GIVEREF(__pyx_v_name); + __Pyx_GOTREF(__pyx_v_self->name); + __Pyx_DECREF(__pyx_v_self->name); + __pyx_v_self->name = __pyx_v_name; + + /* "View.MemoryView":304 + * cdef class Enum(object): + * cdef object name + * def __init__(self, name): # <<<<<<<<<<<<<< + * self.name = name + * def __repr__(self): + */ + + /* function exit code */ + __pyx_r = 0; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":306 + * def __init__(self, name): + * self.name = name + * def __repr__(self): # <<<<<<<<<<<<<< + * return self.name + * + */ + +/* Python wrapper */ +static PyObject *__pyx_MemviewEnum___repr__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_MemviewEnum___repr__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__repr__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum_2__repr__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum_2__repr__(struct __pyx_MemviewEnum_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__repr__", 1); + + /* "View.MemoryView":307 + * self.name = name + * def __repr__(self): + * return self.name # <<<<<<<<<<<<<< + * + * cdef generic = Enum("") + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->name); + __pyx_r = __pyx_v_self->name; + goto __pyx_L0; + + /* "View.MemoryView":306 + * def __init__(self, name): + * self.name = name + * def __repr__(self): # <<<<<<<<<<<<<< + * return self.name + * + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * cdef tuple state + * cdef object _dict + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_MemviewEnum_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_MemviewEnum_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_MemviewEnum___reduce_cython__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_MemviewEnum___reduce_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self) { + PyObject *__pyx_v_state = 0; + PyObject *__pyx_v__dict = 0; + int __pyx_v_use_setstate; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":5 + * cdef object _dict + * cdef bint use_setstate + * state = (self.name,) # <<<<<<<<<<<<<< + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: + */ + __pyx_t_1 = PyTuple_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v_self->name); + __Pyx_GIVEREF(__pyx_v_self->name); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v_self->name)) __PYX_ERR(0, 5, __pyx_L1_error); + __pyx_v_state = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "(tree fragment)":6 + * cdef bint use_setstate + * state = (self.name,) + * _dict = getattr(self, '__dict__', None) # <<<<<<<<<<<<<< + * if _dict is not None: + * state += (_dict,) + */ + __pyx_t_1 = __Pyx_GetAttr3(((PyObject *)__pyx_v_self), __pyx_n_s_dict, Py_None); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v__dict = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":7 + * state = (self.name,) + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: # <<<<<<<<<<<<<< + * state += (_dict,) + * use_setstate = True + */ + __pyx_t_2 = (__pyx_v__dict != Py_None); + if (__pyx_t_2) { + + /* "(tree fragment)":8 + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: + * state += (_dict,) # <<<<<<<<<<<<<< + * use_setstate = True + * else: + */ + __pyx_t_1 = PyTuple_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 8, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v__dict); + __Pyx_GIVEREF(__pyx_v__dict); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v__dict)) __PYX_ERR(0, 8, __pyx_L1_error); + __pyx_t_3 = PyNumber_InPlaceAdd(__pyx_v_state, __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 8, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF_SET(__pyx_v_state, ((PyObject*)__pyx_t_3)); + __pyx_t_3 = 0; + + /* "(tree fragment)":9 + * if _dict is not None: + * state += (_dict,) + * use_setstate = True # <<<<<<<<<<<<<< + * else: + * use_setstate = self.name is not None + */ + __pyx_v_use_setstate = 1; + + /* "(tree fragment)":7 + * state = (self.name,) + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: # <<<<<<<<<<<<<< + * state += (_dict,) + * use_setstate = True + */ + goto __pyx_L3; + } + + /* "(tree fragment)":11 + * use_setstate = True + * else: + * use_setstate = self.name is not None # <<<<<<<<<<<<<< + * if use_setstate: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + */ + /*else*/ { + __pyx_t_2 = (__pyx_v_self->name != Py_None); + __pyx_v_use_setstate = __pyx_t_2; + } + __pyx_L3:; + + /* "(tree fragment)":12 + * else: + * use_setstate = self.name is not None + * if use_setstate: # <<<<<<<<<<<<<< + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + * else: + */ + if (__pyx_v_use_setstate) { + + /* "(tree fragment)":13 + * use_setstate = self.name is not None + * if use_setstate: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state # <<<<<<<<<<<<<< + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_pyx_unpickle_Enum); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = PyTuple_New(3); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_GIVEREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, ((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self))))) __PYX_ERR(0, 13, __pyx_L1_error); + __Pyx_INCREF(__pyx_int_136983863); + __Pyx_GIVEREF(__pyx_int_136983863); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_int_136983863)) __PYX_ERR(0, 13, __pyx_L1_error); + __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(Py_None); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 2, Py_None)) __PYX_ERR(0, 13, __pyx_L1_error); + __pyx_t_4 = PyTuple_New(3); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_3)) __PYX_ERR(0, 13, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_t_1)) __PYX_ERR(0, 13, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_state); + __Pyx_GIVEREF(__pyx_v_state); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 2, __pyx_v_state)) __PYX_ERR(0, 13, __pyx_L1_error); + __pyx_t_3 = 0; + __pyx_t_1 = 0; + __pyx_r = __pyx_t_4; + __pyx_t_4 = 0; + goto __pyx_L0; + + /* "(tree fragment)":12 + * else: + * use_setstate = self.name is not None + * if use_setstate: # <<<<<<<<<<<<<< + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + * else: + */ + } + + /* "(tree fragment)":15 + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * __pyx_unpickle_Enum__set_state(self, __pyx_state) + */ + /*else*/ { + __Pyx_XDECREF(__pyx_r); + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_pyx_unpickle_Enum); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_1 = PyTuple_New(3); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_GIVEREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, ((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self))))) __PYX_ERR(0, 15, __pyx_L1_error); + __Pyx_INCREF(__pyx_int_136983863); + __Pyx_GIVEREF(__pyx_int_136983863); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_int_136983863)) __PYX_ERR(0, 15, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_state); + __Pyx_GIVEREF(__pyx_v_state); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_v_state)) __PYX_ERR(0, 15, __pyx_L1_error); + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_4); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_4)) __PYX_ERR(0, 15, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1)) __PYX_ERR(0, 15, __pyx_L1_error); + __pyx_t_4 = 0; + __pyx_t_1 = 0; + __pyx_r = __pyx_t_3; + __pyx_t_3 = 0; + goto __pyx_L0; + } + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * cdef tuple state + * cdef object _dict + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.Enum.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_state); + __Pyx_XDECREF(__pyx_v__dict); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":16 + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state(self, __pyx_state) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_MemviewEnum_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_MemviewEnum_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 16, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(0, 16, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 16, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.Enum.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_MemviewEnum_2__setstate_cython__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_MemviewEnum_2__setstate_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":17 + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + * def __setstate_cython__(self, __pyx_state): + * __pyx_unpickle_Enum__set_state(self, __pyx_state) # <<<<<<<<<<<<<< + */ + if (!(likely(PyTuple_CheckExact(__pyx_v___pyx_state))||((__pyx_v___pyx_state) == Py_None) || __Pyx_RaiseUnexpectedTypeError("tuple", __pyx_v___pyx_state))) __PYX_ERR(0, 17, __pyx_L1_error) + __pyx_t_1 = __pyx_unpickle_Enum__set_state(__pyx_v_self, ((PyObject*)__pyx_v___pyx_state)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 17, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":16 + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state(self, __pyx_state) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.Enum.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":349 + * cdef __Pyx_TypeInfo *typeinfo + * + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): # <<<<<<<<<<<<<< + * self.obj = obj + * self.flags = flags + */ + +/* Python wrapper */ +static int __pyx_memoryview___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_memoryview___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_obj = 0; + int __pyx_v_flags; + int __pyx_v_dtype_is_object; + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_obj,&__pyx_n_s_flags,&__pyx_n_s_dtype_is_object,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_obj)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 349, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_flags)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 349, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 2, 3, 1); __PYX_ERR(0, 349, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_dtype_is_object); + if (value) { values[2] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 349, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(0, 349, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_obj = values[0]; + __pyx_v_flags = __Pyx_PyInt_As_int(values[1]); if (unlikely((__pyx_v_flags == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 349, __pyx_L3_error) + if (values[2]) { + __pyx_v_dtype_is_object = __Pyx_PyObject_IsTrue(values[2]); if (unlikely((__pyx_v_dtype_is_object == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 349, __pyx_L3_error) + } else { + __pyx_v_dtype_is_object = ((int)0); + } + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 2, 3, __pyx_nargs); __PYX_ERR(0, 349, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.memoryview.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview___cinit__(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v_obj, __pyx_v_flags, __pyx_v_dtype_is_object); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview___cinit__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj, int __pyx_v_flags, int __pyx_v_dtype_is_object) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + Py_intptr_t __pyx_t_4; + size_t __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__cinit__", 1); + + /* "View.MemoryView":350 + * + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): + * self.obj = obj # <<<<<<<<<<<<<< + * self.flags = flags + * if type(self) is memoryview or obj is not None: + */ + __Pyx_INCREF(__pyx_v_obj); + __Pyx_GIVEREF(__pyx_v_obj); + __Pyx_GOTREF(__pyx_v_self->obj); + __Pyx_DECREF(__pyx_v_self->obj); + __pyx_v_self->obj = __pyx_v_obj; + + /* "View.MemoryView":351 + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): + * self.obj = obj + * self.flags = flags # <<<<<<<<<<<<<< + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) + */ + __pyx_v_self->flags = __pyx_v_flags; + + /* "View.MemoryView":352 + * self.obj = obj + * self.flags = flags + * if type(self) is memoryview or obj is not None: # <<<<<<<<<<<<<< + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: + */ + __pyx_t_2 = (((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self))) == ((PyObject *)__pyx_memoryview_type)); + if (!__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_2 = (__pyx_v_obj != Py_None); + __pyx_t_1 = __pyx_t_2; + __pyx_L4_bool_binop_done:; + if (__pyx_t_1) { + + /* "View.MemoryView":353 + * self.flags = flags + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) # <<<<<<<<<<<<<< + * if self.view.obj == NULL: + * (<__pyx_buffer *> &self.view).obj = Py_None + */ + __pyx_t_3 = __Pyx_GetBuffer(__pyx_v_obj, (&__pyx_v_self->view), __pyx_v_flags); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(0, 353, __pyx_L1_error) + + /* "View.MemoryView":354 + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: # <<<<<<<<<<<<<< + * (<__pyx_buffer *> &self.view).obj = Py_None + * Py_INCREF(Py_None) + */ + __pyx_t_1 = (((PyObject *)__pyx_v_self->view.obj) == NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":355 + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: + * (<__pyx_buffer *> &self.view).obj = Py_None # <<<<<<<<<<<<<< + * Py_INCREF(Py_None) + * + */ + ((Py_buffer *)(&__pyx_v_self->view))->obj = Py_None; + + /* "View.MemoryView":356 + * if self.view.obj == NULL: + * (<__pyx_buffer *> &self.view).obj = Py_None + * Py_INCREF(Py_None) # <<<<<<<<<<<<<< + * + * if not __PYX_CYTHON_ATOMICS_ENABLED(): + */ + Py_INCREF(Py_None); + + /* "View.MemoryView":354 + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: # <<<<<<<<<<<<<< + * (<__pyx_buffer *> &self.view).obj = Py_None + * Py_INCREF(Py_None) + */ + } + + /* "View.MemoryView":352 + * self.obj = obj + * self.flags = flags + * if type(self) is memoryview or obj is not None: # <<<<<<<<<<<<<< + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: + */ + } + + /* "View.MemoryView":358 + * Py_INCREF(Py_None) + * + * if not __PYX_CYTHON_ATOMICS_ENABLED(): # <<<<<<<<<<<<<< + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: + */ + __pyx_t_1 = (!__PYX_CYTHON_ATOMICS_ENABLED()); + if (__pyx_t_1) { + + /* "View.MemoryView":360 + * if not __PYX_CYTHON_ATOMICS_ENABLED(): + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: # <<<<<<<<<<<<<< + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + */ + __pyx_t_1 = (__pyx_memoryview_thread_locks_used < 8); + if (__pyx_t_1) { + + /* "View.MemoryView":361 + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: + */ + __pyx_v_self->lock = (__pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used]); + + /* "View.MemoryView":362 + * if __pyx_memoryview_thread_locks_used < 8: + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 # <<<<<<<<<<<<<< + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() + */ + __pyx_memoryview_thread_locks_used = (__pyx_memoryview_thread_locks_used + 1); + + /* "View.MemoryView":360 + * if not __PYX_CYTHON_ATOMICS_ENABLED(): + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: # <<<<<<<<<<<<<< + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + */ + } + + /* "View.MemoryView":363 + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: # <<<<<<<<<<<<<< + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: + */ + __pyx_t_1 = (__pyx_v_self->lock == NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":364 + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() # <<<<<<<<<<<<<< + * if self.lock is NULL: + * raise MemoryError + */ + __pyx_v_self->lock = PyThread_allocate_lock(); + + /* "View.MemoryView":365 + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + __pyx_t_1 = (__pyx_v_self->lock == NULL); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":366 + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: + * raise MemoryError # <<<<<<<<<<<<<< + * + * if flags & PyBUF_FORMAT: + */ + PyErr_NoMemory(); __PYX_ERR(0, 366, __pyx_L1_error) + + /* "View.MemoryView":365 + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + } + + /* "View.MemoryView":363 + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: # <<<<<<<<<<<<<< + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: + */ + } + + /* "View.MemoryView":358 + * Py_INCREF(Py_None) + * + * if not __PYX_CYTHON_ATOMICS_ENABLED(): # <<<<<<<<<<<<<< + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: + */ + } + + /* "View.MemoryView":368 + * raise MemoryError + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_FORMAT) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":369 + * + * if flags & PyBUF_FORMAT: + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') # <<<<<<<<<<<<<< + * else: + * self.dtype_is_object = dtype_is_object + */ + __pyx_t_2 = ((__pyx_v_self->view.format[0]) == 'O'); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L12_bool_binop_done; + } + __pyx_t_2 = ((__pyx_v_self->view.format[1]) == '\x00'); + __pyx_t_1 = __pyx_t_2; + __pyx_L12_bool_binop_done:; + __pyx_v_self->dtype_is_object = __pyx_t_1; + + /* "View.MemoryView":368 + * raise MemoryError + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') + * else: + */ + goto __pyx_L11; + } + + /* "View.MemoryView":371 + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') + * else: + * self.dtype_is_object = dtype_is_object # <<<<<<<<<<<<<< + * + * assert (&self.acquisition_count) % sizeof(__pyx_atomic_int_type) == 0 + */ + /*else*/ { + __pyx_v_self->dtype_is_object = __pyx_v_dtype_is_object; + } + __pyx_L11:; + + /* "View.MemoryView":373 + * self.dtype_is_object = dtype_is_object + * + * assert (&self.acquisition_count) % sizeof(__pyx_atomic_int_type) == 0 # <<<<<<<<<<<<<< + * self.typeinfo = NULL + * + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_4 = ((Py_intptr_t)((void *)(&__pyx_v_self->acquisition_count))); + __pyx_t_5 = (sizeof(__pyx_atomic_int_type)); + if (unlikely(__pyx_t_5 == 0)) { + PyErr_SetString(PyExc_ZeroDivisionError, "integer division or modulo by zero"); + __PYX_ERR(0, 373, __pyx_L1_error) + } + __pyx_t_1 = ((__pyx_t_4 % __pyx_t_5) == 0); + if (unlikely(!__pyx_t_1)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(0, 373, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(0, 373, __pyx_L1_error) + #endif + + /* "View.MemoryView":374 + * + * assert (&self.acquisition_count) % sizeof(__pyx_atomic_int_type) == 0 + * self.typeinfo = NULL # <<<<<<<<<<<<<< + * + * def __dealloc__(memoryview self): + */ + __pyx_v_self->typeinfo = NULL; + + /* "View.MemoryView":349 + * cdef __Pyx_TypeInfo *typeinfo + * + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): # <<<<<<<<<<<<<< + * self.obj = obj + * self.flags = flags + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":376 + * self.typeinfo = NULL + * + * def __dealloc__(memoryview self): # <<<<<<<<<<<<<< + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + */ + +/* Python wrapper */ +static void __pyx_memoryview___dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_memoryview___dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_2__dealloc__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_2__dealloc__(struct __pyx_memoryview_obj *__pyx_v_self) { + int __pyx_v_i; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + PyThread_type_lock __pyx_t_5; + PyThread_type_lock __pyx_t_6; + + /* "View.MemoryView":377 + * + * def __dealloc__(memoryview self): + * if self.obj is not None: # <<<<<<<<<<<<<< + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + */ + __pyx_t_1 = (__pyx_v_self->obj != Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":378 + * def __dealloc__(memoryview self): + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) # <<<<<<<<<<<<<< + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + * + */ + __Pyx_ReleaseBuffer((&__pyx_v_self->view)); + + /* "View.MemoryView":377 + * + * def __dealloc__(memoryview self): + * if self.obj is not None: # <<<<<<<<<<<<<< + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":379 + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: # <<<<<<<<<<<<<< + * + * (<__pyx_buffer *> &self.view).obj = NULL + */ + __pyx_t_1 = (((Py_buffer *)(&__pyx_v_self->view))->obj == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":381 + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + * + * (<__pyx_buffer *> &self.view).obj = NULL # <<<<<<<<<<<<<< + * Py_DECREF(Py_None) + * + */ + ((Py_buffer *)(&__pyx_v_self->view))->obj = NULL; + + /* "View.MemoryView":382 + * + * (<__pyx_buffer *> &self.view).obj = NULL + * Py_DECREF(Py_None) # <<<<<<<<<<<<<< + * + * cdef int i + */ + Py_DECREF(Py_None); + + /* "View.MemoryView":379 + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: # <<<<<<<<<<<<<< + * + * (<__pyx_buffer *> &self.view).obj = NULL + */ + } + __pyx_L3:; + + /* "View.MemoryView":386 + * cdef int i + * global __pyx_memoryview_thread_locks_used + * if self.lock != NULL: # <<<<<<<<<<<<<< + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: + */ + __pyx_t_1 = (__pyx_v_self->lock != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":387 + * global __pyx_memoryview_thread_locks_used + * if self.lock != NULL: + * for i in range(__pyx_memoryview_thread_locks_used): # <<<<<<<<<<<<<< + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 + */ + __pyx_t_2 = __pyx_memoryview_thread_locks_used; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":388 + * if self.lock != NULL: + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: + */ + __pyx_t_1 = ((__pyx_memoryview_thread_locks[__pyx_v_i]) == __pyx_v_self->lock); + if (__pyx_t_1) { + + /* "View.MemoryView":389 + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 # <<<<<<<<<<<<<< + * if i != __pyx_memoryview_thread_locks_used: + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + */ + __pyx_memoryview_thread_locks_used = (__pyx_memoryview_thread_locks_used - 1); + + /* "View.MemoryView":390 + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + */ + __pyx_t_1 = (__pyx_v_i != __pyx_memoryview_thread_locks_used); + if (__pyx_t_1) { + + /* "View.MemoryView":392 + * if i != __pyx_memoryview_thread_locks_used: + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) # <<<<<<<<<<<<<< + * break + * else: + */ + __pyx_t_5 = (__pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used]); + __pyx_t_6 = (__pyx_memoryview_thread_locks[__pyx_v_i]); + + /* "View.MemoryView":391 + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + * break + */ + (__pyx_memoryview_thread_locks[__pyx_v_i]) = __pyx_t_5; + (__pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used]) = __pyx_t_6; + + /* "View.MemoryView":390 + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + */ + } + + /* "View.MemoryView":393 + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + * break # <<<<<<<<<<<<<< + * else: + * PyThread_free_lock(self.lock) + */ + goto __pyx_L6_break; + + /* "View.MemoryView":388 + * if self.lock != NULL: + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: + */ + } + } + /*else*/ { + + /* "View.MemoryView":395 + * break + * else: + * PyThread_free_lock(self.lock) # <<<<<<<<<<<<<< + * + * cdef char *get_item_pointer(memoryview self, object index) except NULL: + */ + PyThread_free_lock(__pyx_v_self->lock); + } + __pyx_L6_break:; + + /* "View.MemoryView":386 + * cdef int i + * global __pyx_memoryview_thread_locks_used + * if self.lock != NULL: # <<<<<<<<<<<<<< + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: + */ + } + + /* "View.MemoryView":376 + * self.typeinfo = NULL + * + * def __dealloc__(memoryview self): # <<<<<<<<<<<<<< + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + */ + + /* function exit code */ +} + +/* "View.MemoryView":397 + * PyThread_free_lock(self.lock) + * + * cdef char *get_item_pointer(memoryview self, object index) except NULL: # <<<<<<<<<<<<<< + * cdef Py_ssize_t dim + * cdef char *itemp = self.view.buf + */ + +static char *__pyx_memoryview_get_item_pointer(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index) { + Py_ssize_t __pyx_v_dim; + char *__pyx_v_itemp; + PyObject *__pyx_v_idx = NULL; + char *__pyx_r; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + Py_ssize_t __pyx_t_3; + PyObject *(*__pyx_t_4)(PyObject *); + PyObject *__pyx_t_5 = NULL; + Py_ssize_t __pyx_t_6; + char *__pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_item_pointer", 1); + + /* "View.MemoryView":399 + * cdef char *get_item_pointer(memoryview self, object index) except NULL: + * cdef Py_ssize_t dim + * cdef char *itemp = self.view.buf # <<<<<<<<<<<<<< + * + * for dim, idx in enumerate(index): + */ + __pyx_v_itemp = ((char *)__pyx_v_self->view.buf); + + /* "View.MemoryView":401 + * cdef char *itemp = self.view.buf + * + * for dim, idx in enumerate(index): # <<<<<<<<<<<<<< + * itemp = pybuffer_index(&self.view, itemp, idx, dim) + * + */ + __pyx_t_1 = 0; + if (likely(PyList_CheckExact(__pyx_v_index)) || PyTuple_CheckExact(__pyx_v_index)) { + __pyx_t_2 = __pyx_v_index; __Pyx_INCREF(__pyx_t_2); + __pyx_t_3 = 0; + __pyx_t_4 = NULL; + } else { + __pyx_t_3 = -1; __pyx_t_2 = PyObject_GetIter(__pyx_v_index); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 401, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_2); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 401, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_4)) { + if (likely(PyList_CheckExact(__pyx_t_2))) { + { + Py_ssize_t __pyx_temp = __Pyx_PyList_GET_SIZE(__pyx_t_2); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 401, __pyx_L1_error) + #endif + if (__pyx_t_3 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_5 = PyList_GET_ITEM(__pyx_t_2, __pyx_t_3); __Pyx_INCREF(__pyx_t_5); __pyx_t_3++; if (unlikely((0 < 0))) __PYX_ERR(0, 401, __pyx_L1_error) + #else + __pyx_t_5 = __Pyx_PySequence_ITEM(__pyx_t_2, __pyx_t_3); __pyx_t_3++; if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 401, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + #endif + } else { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_2); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 401, __pyx_L1_error) + #endif + if (__pyx_t_3 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_5 = PyTuple_GET_ITEM(__pyx_t_2, __pyx_t_3); __Pyx_INCREF(__pyx_t_5); __pyx_t_3++; if (unlikely((0 < 0))) __PYX_ERR(0, 401, __pyx_L1_error) + #else + __pyx_t_5 = __Pyx_PySequence_ITEM(__pyx_t_2, __pyx_t_3); __pyx_t_3++; if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 401, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + #endif + } + } else { + __pyx_t_5 = __pyx_t_4(__pyx_t_2); + if (unlikely(!__pyx_t_5)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(0, 401, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_5); + } + __Pyx_XDECREF_SET(__pyx_v_idx, __pyx_t_5); + __pyx_t_5 = 0; + __pyx_v_dim = __pyx_t_1; + __pyx_t_1 = (__pyx_t_1 + 1); + + /* "View.MemoryView":402 + * + * for dim, idx in enumerate(index): + * itemp = pybuffer_index(&self.view, itemp, idx, dim) # <<<<<<<<<<<<<< + * + * return itemp + */ + __pyx_t_6 = __Pyx_PyIndex_AsSsize_t(__pyx_v_idx); if (unlikely((__pyx_t_6 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 402, __pyx_L1_error) + __pyx_t_7 = __pyx_pybuffer_index((&__pyx_v_self->view), __pyx_v_itemp, __pyx_t_6, __pyx_v_dim); if (unlikely(__pyx_t_7 == ((char *)NULL))) __PYX_ERR(0, 402, __pyx_L1_error) + __pyx_v_itemp = __pyx_t_7; + + /* "View.MemoryView":401 + * cdef char *itemp = self.view.buf + * + * for dim, idx in enumerate(index): # <<<<<<<<<<<<<< + * itemp = pybuffer_index(&self.view, itemp, idx, dim) + * + */ + } + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":404 + * itemp = pybuffer_index(&self.view, itemp, idx, dim) + * + * return itemp # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = __pyx_v_itemp; + goto __pyx_L0; + + /* "View.MemoryView":397 + * PyThread_free_lock(self.lock) + * + * cdef char *get_item_pointer(memoryview self, object index) except NULL: # <<<<<<<<<<<<<< + * cdef Py_ssize_t dim + * cdef char *itemp = self.view.buf + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.memoryview.get_item_pointer", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_idx); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":407 + * + * + * def __getitem__(memoryview self, object index): # <<<<<<<<<<<<<< + * if index is Ellipsis: + * return self + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index); /*proto*/ +static PyObject *__pyx_memoryview___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getitem__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_4__getitem__(((struct __pyx_memoryview_obj *)__pyx_v_self), ((PyObject *)__pyx_v_index)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_4__getitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index) { + PyObject *__pyx_v_have_slices = NULL; + PyObject *__pyx_v_indices = NULL; + char *__pyx_v_itemp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + char *__pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__getitem__", 1); + + /* "View.MemoryView":408 + * + * def __getitem__(memoryview self, object index): + * if index is Ellipsis: # <<<<<<<<<<<<<< + * return self + * + */ + __pyx_t_1 = (__pyx_v_index == __pyx_builtin_Ellipsis); + if (__pyx_t_1) { + + /* "View.MemoryView":409 + * def __getitem__(memoryview self, object index): + * if index is Ellipsis: + * return self # <<<<<<<<<<<<<< + * + * have_slices, indices = _unellipsify(index, self.view.ndim) + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_self); + __pyx_r = ((PyObject *)__pyx_v_self); + goto __pyx_L0; + + /* "View.MemoryView":408 + * + * def __getitem__(memoryview self, object index): + * if index is Ellipsis: # <<<<<<<<<<<<<< + * return self + * + */ + } + + /* "View.MemoryView":411 + * return self + * + * have_slices, indices = _unellipsify(index, self.view.ndim) # <<<<<<<<<<<<<< + * + * cdef char *itemp + */ + __pyx_t_2 = _unellipsify(__pyx_v_index, __pyx_v_self->view.ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 411, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (likely(__pyx_t_2 != Py_None)) { + PyObject* sequence = __pyx_t_2; + Py_ssize_t size = __Pyx_PySequence_SIZE(sequence); + if (unlikely(size != 2)) { + if (size > 2) __Pyx_RaiseTooManyValuesError(2); + else if (size >= 0) __Pyx_RaiseNeedMoreValuesError(size); + __PYX_ERR(0, 411, __pyx_L1_error) + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_3 = PyTuple_GET_ITEM(sequence, 0); + __pyx_t_4 = PyTuple_GET_ITEM(sequence, 1); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(__pyx_t_4); + #else + __pyx_t_3 = PySequence_ITEM(sequence, 0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 411, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PySequence_ITEM(sequence, 1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 411, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } else { + __Pyx_RaiseNoneNotIterableError(); __PYX_ERR(0, 411, __pyx_L1_error) + } + __pyx_v_have_slices = __pyx_t_3; + __pyx_t_3 = 0; + __pyx_v_indices = __pyx_t_4; + __pyx_t_4 = 0; + + /* "View.MemoryView":414 + * + * cdef char *itemp + * if have_slices: # <<<<<<<<<<<<<< + * return memview_slice(self, indices) + * else: + */ + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_v_have_slices); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(0, 414, __pyx_L1_error) + if (__pyx_t_1) { + + /* "View.MemoryView":415 + * cdef char *itemp + * if have_slices: + * return memview_slice(self, indices) # <<<<<<<<<<<<<< + * else: + * itemp = self.get_item_pointer(indices) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = ((PyObject *)__pyx_memview_slice(__pyx_v_self, __pyx_v_indices)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 415, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":414 + * + * cdef char *itemp + * if have_slices: # <<<<<<<<<<<<<< + * return memview_slice(self, indices) + * else: + */ + } + + /* "View.MemoryView":417 + * return memview_slice(self, indices) + * else: + * itemp = self.get_item_pointer(indices) # <<<<<<<<<<<<<< + * return self.convert_item_to_object(itemp) + * + */ + /*else*/ { + __pyx_t_5 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->get_item_pointer(__pyx_v_self, __pyx_v_indices); if (unlikely(__pyx_t_5 == ((char *)NULL))) __PYX_ERR(0, 417, __pyx_L1_error) + __pyx_v_itemp = __pyx_t_5; + + /* "View.MemoryView":418 + * else: + * itemp = self.get_item_pointer(indices) + * return self.convert_item_to_object(itemp) # <<<<<<<<<<<<<< + * + * def __setitem__(memoryview self, object index, object value): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->convert_item_to_object(__pyx_v_self, __pyx_v_itemp); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 418, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + } + + /* "View.MemoryView":407 + * + * + * def __getitem__(memoryview self, object index): # <<<<<<<<<<<<<< + * if index is Ellipsis: + * return self + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.memoryview.__getitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_have_slices); + __Pyx_XDECREF(__pyx_v_indices); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":420 + * return self.convert_item_to_object(itemp) + * + * def __setitem__(memoryview self, object index, object value): # <<<<<<<<<<<<<< + * if self.view.readonly: + * raise TypeError, "Cannot assign to read-only memoryview" + */ + +/* Python wrapper */ +static int __pyx_memoryview___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value); /*proto*/ +static int __pyx_memoryview___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setitem__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_6__setitem__(((struct __pyx_memoryview_obj *)__pyx_v_self), ((PyObject *)__pyx_v_index), ((PyObject *)__pyx_v_value)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_6__setitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value) { + PyObject *__pyx_v_have_slices = NULL; + PyObject *__pyx_v_obj = NULL; + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setitem__", 0); + __Pyx_INCREF(__pyx_v_index); + + /* "View.MemoryView":421 + * + * def __setitem__(memoryview self, object index, object value): + * if self.view.readonly: # <<<<<<<<<<<<<< + * raise TypeError, "Cannot assign to read-only memoryview" + * + */ + if (unlikely(__pyx_v_self->view.readonly)) { + + /* "View.MemoryView":422 + * def __setitem__(memoryview self, object index, object value): + * if self.view.readonly: + * raise TypeError, "Cannot assign to read-only memoryview" # <<<<<<<<<<<<<< + * + * have_slices, index = _unellipsify(index, self.view.ndim) + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_Cannot_assign_to_read_only_memor, 0, 0); + __PYX_ERR(0, 422, __pyx_L1_error) + + /* "View.MemoryView":421 + * + * def __setitem__(memoryview self, object index, object value): + * if self.view.readonly: # <<<<<<<<<<<<<< + * raise TypeError, "Cannot assign to read-only memoryview" + * + */ + } + + /* "View.MemoryView":424 + * raise TypeError, "Cannot assign to read-only memoryview" + * + * have_slices, index = _unellipsify(index, self.view.ndim) # <<<<<<<<<<<<<< + * + * if have_slices: + */ + __pyx_t_1 = _unellipsify(__pyx_v_index, __pyx_v_self->view.ndim); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 424, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (likely(__pyx_t_1 != Py_None)) { + PyObject* sequence = __pyx_t_1; + Py_ssize_t size = __Pyx_PySequence_SIZE(sequence); + if (unlikely(size != 2)) { + if (size > 2) __Pyx_RaiseTooManyValuesError(2); + else if (size >= 0) __Pyx_RaiseNeedMoreValuesError(size); + __PYX_ERR(0, 424, __pyx_L1_error) + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_2 = PyTuple_GET_ITEM(sequence, 0); + __pyx_t_3 = PyTuple_GET_ITEM(sequence, 1); + __Pyx_INCREF(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + #else + __pyx_t_2 = PySequence_ITEM(sequence, 0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 424, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PySequence_ITEM(sequence, 1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 424, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + #endif + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } else { + __Pyx_RaiseNoneNotIterableError(); __PYX_ERR(0, 424, __pyx_L1_error) + } + __pyx_v_have_slices = __pyx_t_2; + __pyx_t_2 = 0; + __Pyx_DECREF_SET(__pyx_v_index, __pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":426 + * have_slices, index = _unellipsify(index, self.view.ndim) + * + * if have_slices: # <<<<<<<<<<<<<< + * obj = self.is_slice(value) + * if obj: + */ + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_v_have_slices); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 426, __pyx_L1_error) + if (__pyx_t_4) { + + /* "View.MemoryView":427 + * + * if have_slices: + * obj = self.is_slice(value) # <<<<<<<<<<<<<< + * if obj: + * self.setitem_slice_assignment(self[index], obj) + */ + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->is_slice(__pyx_v_self, __pyx_v_value); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 427, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_obj = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":428 + * if have_slices: + * obj = self.is_slice(value) + * if obj: # <<<<<<<<<<<<<< + * self.setitem_slice_assignment(self[index], obj) + * else: + */ + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_v_obj); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 428, __pyx_L1_error) + if (__pyx_t_4) { + + /* "View.MemoryView":429 + * obj = self.is_slice(value) + * if obj: + * self.setitem_slice_assignment(self[index], obj) # <<<<<<<<<<<<<< + * else: + * self.setitem_slice_assign_scalar(self[index], value) + */ + __pyx_t_1 = __Pyx_PyObject_GetItem(((PyObject *)__pyx_v_self), __pyx_v_index); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 429, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->setitem_slice_assignment(__pyx_v_self, __pyx_t_1, __pyx_v_obj); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 429, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "View.MemoryView":428 + * if have_slices: + * obj = self.is_slice(value) + * if obj: # <<<<<<<<<<<<<< + * self.setitem_slice_assignment(self[index], obj) + * else: + */ + goto __pyx_L5; + } + + /* "View.MemoryView":431 + * self.setitem_slice_assignment(self[index], obj) + * else: + * self.setitem_slice_assign_scalar(self[index], value) # <<<<<<<<<<<<<< + * else: + * self.setitem_indexed(index, value) + */ + /*else*/ { + __pyx_t_3 = __Pyx_PyObject_GetItem(((PyObject *)__pyx_v_self), __pyx_v_index); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 431, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (!(likely(((__pyx_t_3) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_3, __pyx_memoryview_type))))) __PYX_ERR(0, 431, __pyx_L1_error) + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->setitem_slice_assign_scalar(__pyx_v_self, ((struct __pyx_memoryview_obj *)__pyx_t_3), __pyx_v_value); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 431, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_L5:; + + /* "View.MemoryView":426 + * have_slices, index = _unellipsify(index, self.view.ndim) + * + * if have_slices: # <<<<<<<<<<<<<< + * obj = self.is_slice(value) + * if obj: + */ + goto __pyx_L4; + } + + /* "View.MemoryView":433 + * self.setitem_slice_assign_scalar(self[index], value) + * else: + * self.setitem_indexed(index, value) # <<<<<<<<<<<<<< + * + * cdef is_slice(self, obj): + */ + /*else*/ { + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->setitem_indexed(__pyx_v_self, __pyx_v_index, __pyx_v_value); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 433, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_L4:; + + /* "View.MemoryView":420 + * return self.convert_item_to_object(itemp) + * + * def __setitem__(memoryview self, object index, object value): # <<<<<<<<<<<<<< + * if self.view.readonly: + * raise TypeError, "Cannot assign to read-only memoryview" + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.__setitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_have_slices); + __Pyx_XDECREF(__pyx_v_obj); + __Pyx_XDECREF(__pyx_v_index); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":435 + * self.setitem_indexed(index, value) + * + * cdef is_slice(self, obj): # <<<<<<<<<<<<<< + * if not isinstance(obj, memoryview): + * try: + */ + +static PyObject *__pyx_memoryview_is_slice(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("is_slice", 0); + __Pyx_INCREF(__pyx_v_obj); + + /* "View.MemoryView":436 + * + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): # <<<<<<<<<<<<<< + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + */ + __pyx_t_1 = __Pyx_TypeCheck(__pyx_v_obj, __pyx_memoryview_type); + __pyx_t_2 = (!__pyx_t_1); + if (__pyx_t_2) { + + /* "View.MemoryView":437 + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): + * try: # <<<<<<<<<<<<<< + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_3, &__pyx_t_4, &__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_4); + __Pyx_XGOTREF(__pyx_t_5); + /*try:*/ { + + /* "View.MemoryView":438 + * if not isinstance(obj, memoryview): + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, # <<<<<<<<<<<<<< + * self.dtype_is_object) + * except TypeError: + */ + __pyx_t_6 = __Pyx_PyInt_From_int(((__pyx_v_self->flags & (~PyBUF_WRITABLE)) | PyBUF_ANY_CONTIGUOUS)); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 438, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_6); + + /* "View.MemoryView":439 + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) # <<<<<<<<<<<<<< + * except TypeError: + * return None + */ + __pyx_t_7 = __Pyx_PyBool_FromLong(__pyx_v_self->dtype_is_object); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 439, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_7); + + /* "View.MemoryView":438 + * if not isinstance(obj, memoryview): + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, # <<<<<<<<<<<<<< + * self.dtype_is_object) + * except TypeError: + */ + __pyx_t_8 = PyTuple_New(3); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 438, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_INCREF(__pyx_v_obj); + __Pyx_GIVEREF(__pyx_v_obj); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_8, 0, __pyx_v_obj)) __PYX_ERR(0, 438, __pyx_L4_error); + __Pyx_GIVEREF(__pyx_t_6); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_8, 1, __pyx_t_6)) __PYX_ERR(0, 438, __pyx_L4_error); + __Pyx_GIVEREF(__pyx_t_7); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_8, 2, __pyx_t_7)) __PYX_ERR(0, 438, __pyx_L4_error); + __pyx_t_6 = 0; + __pyx_t_7 = 0; + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_memoryview_type), __pyx_t_8, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 438, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_DECREF_SET(__pyx_v_obj, __pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":437 + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): + * try: # <<<<<<<<<<<<<< + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + */ + } + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + goto __pyx_L9_try_end; + __pyx_L4_error:; + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + + /* "View.MemoryView":440 + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + * except TypeError: # <<<<<<<<<<<<<< + * return None + * + */ + __pyx_t_9 = __Pyx_PyErr_ExceptionMatches(__pyx_builtin_TypeError); + if (__pyx_t_9) { + __Pyx_AddTraceback("View.MemoryView.memoryview.is_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_7, &__pyx_t_8, &__pyx_t_6) < 0) __PYX_ERR(0, 440, __pyx_L6_except_error) + __Pyx_XGOTREF(__pyx_t_7); + __Pyx_XGOTREF(__pyx_t_8); + __Pyx_XGOTREF(__pyx_t_6); + + /* "View.MemoryView":441 + * self.dtype_is_object) + * except TypeError: + * return None # <<<<<<<<<<<<<< + * + * return obj + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L7_except_return; + } + goto __pyx_L6_except_error; + + /* "View.MemoryView":437 + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): + * try: # <<<<<<<<<<<<<< + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + */ + __pyx_L6_except_error:; + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_XGIVEREF(__pyx_t_5); + __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_4, __pyx_t_5); + goto __pyx_L1_error; + __pyx_L7_except_return:; + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_XGIVEREF(__pyx_t_5); + __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_4, __pyx_t_5); + goto __pyx_L0; + __pyx_L9_try_end:; + } + + /* "View.MemoryView":436 + * + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): # <<<<<<<<<<<<<< + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + */ + } + + /* "View.MemoryView":443 + * return None + * + * return obj # <<<<<<<<<<<<<< + * + * cdef setitem_slice_assignment(self, dst, src): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_obj); + __pyx_r = __pyx_v_obj; + goto __pyx_L0; + + /* "View.MemoryView":435 + * self.setitem_indexed(index, value) + * + * cdef is_slice(self, obj): # <<<<<<<<<<<<<< + * if not isinstance(obj, memoryview): + * try: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("View.MemoryView.memoryview.is_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_obj); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":445 + * return obj + * + * cdef setitem_slice_assignment(self, dst, src): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice dst_slice + * cdef __Pyx_memviewslice src_slice + */ + +static PyObject *__pyx_memoryview_setitem_slice_assignment(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_dst, PyObject *__pyx_v_src) { + __Pyx_memviewslice __pyx_v_dst_slice; + __Pyx_memviewslice __pyx_v_src_slice; + __Pyx_memviewslice __pyx_v_msrc; + __Pyx_memviewslice __pyx_v_mdst; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_t_3; + int __pyx_t_4; + int __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("setitem_slice_assignment", 1); + + /* "View.MemoryView":448 + * cdef __Pyx_memviewslice dst_slice + * cdef __Pyx_memviewslice src_slice + * cdef __Pyx_memviewslice msrc = get_slice_from_memview(src, &src_slice)[0] # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice mdst = get_slice_from_memview(dst, &dst_slice)[0] + * + */ + if (!(likely(((__pyx_v_src) == Py_None) || likely(__Pyx_TypeTest(__pyx_v_src, __pyx_memoryview_type))))) __PYX_ERR(0, 448, __pyx_L1_error) + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(((struct __pyx_memoryview_obj *)__pyx_v_src), (&__pyx_v_src_slice)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(0, 448, __pyx_L1_error) + __pyx_v_msrc = (__pyx_t_1[0]); + + /* "View.MemoryView":449 + * cdef __Pyx_memviewslice src_slice + * cdef __Pyx_memviewslice msrc = get_slice_from_memview(src, &src_slice)[0] + * cdef __Pyx_memviewslice mdst = get_slice_from_memview(dst, &dst_slice)[0] # <<<<<<<<<<<<<< + * + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) + */ + if (!(likely(((__pyx_v_dst) == Py_None) || likely(__Pyx_TypeTest(__pyx_v_dst, __pyx_memoryview_type))))) __PYX_ERR(0, 449, __pyx_L1_error) + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(((struct __pyx_memoryview_obj *)__pyx_v_dst), (&__pyx_v_dst_slice)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(0, 449, __pyx_L1_error) + __pyx_v_mdst = (__pyx_t_1[0]); + + /* "View.MemoryView":451 + * cdef __Pyx_memviewslice mdst = get_slice_from_memview(dst, &dst_slice)[0] + * + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) # <<<<<<<<<<<<<< + * + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_src, __pyx_n_s_ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 451, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_PyInt_As_int(__pyx_t_2); if (unlikely((__pyx_t_3 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 451, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_dst, __pyx_n_s_ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 451, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __Pyx_PyInt_As_int(__pyx_t_2); if (unlikely((__pyx_t_4 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 451, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_5 = __pyx_memoryview_copy_contents(__pyx_v_msrc, __pyx_v_mdst, __pyx_t_3, __pyx_t_4, __pyx_v_self->dtype_is_object); if (unlikely(__pyx_t_5 == ((int)-1))) __PYX_ERR(0, 451, __pyx_L1_error) + + /* "View.MemoryView":445 + * return obj + * + * cdef setitem_slice_assignment(self, dst, src): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice dst_slice + * cdef __Pyx_memviewslice src_slice + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.setitem_slice_assignment", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":453 + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) + * + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): # <<<<<<<<<<<<<< + * cdef int array[128] + * cdef void *tmp = NULL + */ + +static PyObject *__pyx_memoryview_setitem_slice_assign_scalar(struct __pyx_memoryview_obj *__pyx_v_self, struct __pyx_memoryview_obj *__pyx_v_dst, PyObject *__pyx_v_value) { + int __pyx_v_array[0x80]; + void *__pyx_v_tmp; + void *__pyx_v_item; + __Pyx_memviewslice *__pyx_v_dst_slice; + __Pyx_memviewslice __pyx_v_tmp_slice; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_t_5; + char const *__pyx_t_6; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + PyObject *__pyx_t_9 = NULL; + PyObject *__pyx_t_10 = NULL; + PyObject *__pyx_t_11 = NULL; + PyObject *__pyx_t_12 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("setitem_slice_assign_scalar", 1); + + /* "View.MemoryView":455 + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): + * cdef int array[128] + * cdef void *tmp = NULL # <<<<<<<<<<<<<< + * cdef void *item + * + */ + __pyx_v_tmp = NULL; + + /* "View.MemoryView":460 + * cdef __Pyx_memviewslice *dst_slice + * cdef __Pyx_memviewslice tmp_slice + * dst_slice = get_slice_from_memview(dst, &tmp_slice) # <<<<<<<<<<<<<< + * + * if self.view.itemsize > sizeof(array): + */ + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(__pyx_v_dst, (&__pyx_v_tmp_slice)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(0, 460, __pyx_L1_error) + __pyx_v_dst_slice = __pyx_t_1; + + /* "View.MemoryView":462 + * dst_slice = get_slice_from_memview(dst, &tmp_slice) + * + * if self.view.itemsize > sizeof(array): # <<<<<<<<<<<<<< + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: + */ + __pyx_t_2 = (((size_t)__pyx_v_self->view.itemsize) > (sizeof(__pyx_v_array))); + if (__pyx_t_2) { + + /* "View.MemoryView":463 + * + * if self.view.itemsize > sizeof(array): + * tmp = PyMem_Malloc(self.view.itemsize) # <<<<<<<<<<<<<< + * if tmp == NULL: + * raise MemoryError + */ + __pyx_v_tmp = PyMem_Malloc(__pyx_v_self->view.itemsize); + + /* "View.MemoryView":464 + * if self.view.itemsize > sizeof(array): + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * item = tmp + */ + __pyx_t_2 = (__pyx_v_tmp == NULL); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":465 + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: + * raise MemoryError # <<<<<<<<<<<<<< + * item = tmp + * else: + */ + PyErr_NoMemory(); __PYX_ERR(0, 465, __pyx_L1_error) + + /* "View.MemoryView":464 + * if self.view.itemsize > sizeof(array): + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * item = tmp + */ + } + + /* "View.MemoryView":466 + * if tmp == NULL: + * raise MemoryError + * item = tmp # <<<<<<<<<<<<<< + * else: + * item = array + */ + __pyx_v_item = __pyx_v_tmp; + + /* "View.MemoryView":462 + * dst_slice = get_slice_from_memview(dst, &tmp_slice) + * + * if self.view.itemsize > sizeof(array): # <<<<<<<<<<<<<< + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":468 + * item = tmp + * else: + * item = array # <<<<<<<<<<<<<< + * + * try: + */ + /*else*/ { + __pyx_v_item = ((void *)__pyx_v_array); + } + __pyx_L3:; + + /* "View.MemoryView":470 + * item = array + * + * try: # <<<<<<<<<<<<<< + * if self.dtype_is_object: + * ( item)[0] = value + */ + /*try:*/ { + + /* "View.MemoryView":471 + * + * try: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * ( item)[0] = value + * else: + */ + if (__pyx_v_self->dtype_is_object) { + + /* "View.MemoryView":472 + * try: + * if self.dtype_is_object: + * ( item)[0] = value # <<<<<<<<<<<<<< + * else: + * self.assign_item_from_object( item, value) + */ + (((PyObject **)__pyx_v_item)[0]) = ((PyObject *)__pyx_v_value); + + /* "View.MemoryView":471 + * + * try: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * ( item)[0] = value + * else: + */ + goto __pyx_L8; + } + + /* "View.MemoryView":474 + * ( item)[0] = value + * else: + * self.assign_item_from_object( item, value) # <<<<<<<<<<<<<< + * + * + */ + /*else*/ { + __pyx_t_3 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->assign_item_from_object(__pyx_v_self, ((char *)__pyx_v_item), __pyx_v_value); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 474, __pyx_L6_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_L8:; + + /* "View.MemoryView":478 + * + * + * if self.view.suboffsets != NULL: # <<<<<<<<<<<<<< + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, + */ + __pyx_t_2 = (__pyx_v_self->view.suboffsets != NULL); + if (__pyx_t_2) { + + /* "View.MemoryView":479 + * + * if self.view.suboffsets != NULL: + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) # <<<<<<<<<<<<<< + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, + * item, self.dtype_is_object) + */ + __pyx_t_4 = assert_direct_dimensions(__pyx_v_self->view.suboffsets, __pyx_v_self->view.ndim); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(0, 479, __pyx_L6_error) + + /* "View.MemoryView":478 + * + * + * if self.view.suboffsets != NULL: # <<<<<<<<<<<<<< + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, + */ + } + + /* "View.MemoryView":480 + * if self.view.suboffsets != NULL: + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, # <<<<<<<<<<<<<< + * item, self.dtype_is_object) + * finally: + */ + __pyx_memoryview_slice_assign_scalar(__pyx_v_dst_slice, __pyx_v_dst->view.ndim, __pyx_v_self->view.itemsize, __pyx_v_item, __pyx_v_self->dtype_is_object); + } + + /* "View.MemoryView":483 + * item, self.dtype_is_object) + * finally: + * PyMem_Free(tmp) # <<<<<<<<<<<<<< + * + * cdef setitem_indexed(self, index, value): + */ + /*finally:*/ { + /*normal exit:*/{ + PyMem_Free(__pyx_v_tmp); + goto __pyx_L7; + } + __pyx_L6_error:; + /*exception exit:*/{ + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __pyx_t_7 = 0; __pyx_t_8 = 0; __pyx_t_9 = 0; __pyx_t_10 = 0; __pyx_t_11 = 0; __pyx_t_12 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (PY_MAJOR_VERSION >= 3) __Pyx_ExceptionSwap(&__pyx_t_10, &__pyx_t_11, &__pyx_t_12); + if ((PY_MAJOR_VERSION < 3) || unlikely(__Pyx_GetException(&__pyx_t_7, &__pyx_t_8, &__pyx_t_9) < 0)) __Pyx_ErrFetch(&__pyx_t_7, &__pyx_t_8, &__pyx_t_9); + __Pyx_XGOTREF(__pyx_t_7); + __Pyx_XGOTREF(__pyx_t_8); + __Pyx_XGOTREF(__pyx_t_9); + __Pyx_XGOTREF(__pyx_t_10); + __Pyx_XGOTREF(__pyx_t_11); + __Pyx_XGOTREF(__pyx_t_12); + __pyx_t_4 = __pyx_lineno; __pyx_t_5 = __pyx_clineno; __pyx_t_6 = __pyx_filename; + { + PyMem_Free(__pyx_v_tmp); + } + if (PY_MAJOR_VERSION >= 3) { + __Pyx_XGIVEREF(__pyx_t_10); + __Pyx_XGIVEREF(__pyx_t_11); + __Pyx_XGIVEREF(__pyx_t_12); + __Pyx_ExceptionReset(__pyx_t_10, __pyx_t_11, __pyx_t_12); + } + __Pyx_XGIVEREF(__pyx_t_7); + __Pyx_XGIVEREF(__pyx_t_8); + __Pyx_XGIVEREF(__pyx_t_9); + __Pyx_ErrRestore(__pyx_t_7, __pyx_t_8, __pyx_t_9); + __pyx_t_7 = 0; __pyx_t_8 = 0; __pyx_t_9 = 0; __pyx_t_10 = 0; __pyx_t_11 = 0; __pyx_t_12 = 0; + __pyx_lineno = __pyx_t_4; __pyx_clineno = __pyx_t_5; __pyx_filename = __pyx_t_6; + goto __pyx_L1_error; + } + __pyx_L7:; + } + + /* "View.MemoryView":453 + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) + * + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): # <<<<<<<<<<<<<< + * cdef int array[128] + * cdef void *tmp = NULL + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.setitem_slice_assign_scalar", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":485 + * PyMem_Free(tmp) + * + * cdef setitem_indexed(self, index, value): # <<<<<<<<<<<<<< + * cdef char *itemp = self.get_item_pointer(index) + * self.assign_item_from_object(itemp, value) + */ + +static PyObject *__pyx_memoryview_setitem_indexed(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value) { + char *__pyx_v_itemp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + char *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("setitem_indexed", 1); + + /* "View.MemoryView":486 + * + * cdef setitem_indexed(self, index, value): + * cdef char *itemp = self.get_item_pointer(index) # <<<<<<<<<<<<<< + * self.assign_item_from_object(itemp, value) + * + */ + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->get_item_pointer(__pyx_v_self, __pyx_v_index); if (unlikely(__pyx_t_1 == ((char *)NULL))) __PYX_ERR(0, 486, __pyx_L1_error) + __pyx_v_itemp = __pyx_t_1; + + /* "View.MemoryView":487 + * cdef setitem_indexed(self, index, value): + * cdef char *itemp = self.get_item_pointer(index) + * self.assign_item_from_object(itemp, value) # <<<<<<<<<<<<<< + * + * cdef convert_item_to_object(self, char *itemp): + */ + __pyx_t_2 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->assign_item_from_object(__pyx_v_self, __pyx_v_itemp, __pyx_v_value); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 487, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":485 + * PyMem_Free(tmp) + * + * cdef setitem_indexed(self, index, value): # <<<<<<<<<<<<<< + * cdef char *itemp = self.get_item_pointer(index) + * self.assign_item_from_object(itemp, value) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.setitem_indexed", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":489 + * self.assign_item_from_object(itemp, value) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + +static PyObject *__pyx_memoryview_convert_item_to_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp) { + PyObject *__pyx_v_struct = NULL; + PyObject *__pyx_v_bytesitem = 0; + PyObject *__pyx_v_result = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + int __pyx_t_8; + Py_ssize_t __pyx_t_9; + int __pyx_t_10; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("convert_item_to_object", 1); + + /* "View.MemoryView":492 + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + * import struct # <<<<<<<<<<<<<< + * cdef bytes bytesitem + * + */ + __pyx_t_1 = __Pyx_ImportDottedModule(__pyx_n_s_struct, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 492, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_struct = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":495 + * cdef bytes bytesitem + * + * bytesitem = itemp[:self.view.itemsize] # <<<<<<<<<<<<<< + * try: + * result = struct.unpack(self.view.format, bytesitem) + */ + __pyx_t_1 = __Pyx_PyBytes_FromStringAndSize(__pyx_v_itemp + 0, __pyx_v_self->view.itemsize - 0); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 495, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_bytesitem = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":496 + * + * bytesitem = itemp[:self.view.itemsize] + * try: # <<<<<<<<<<<<<< + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_2, &__pyx_t_3, &__pyx_t_4); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_4); + /*try:*/ { + + /* "View.MemoryView":497 + * bytesitem = itemp[:self.view.itemsize] + * try: + * result = struct.unpack(self.view.format, bytesitem) # <<<<<<<<<<<<<< + * except struct.error: + * raise ValueError, "Unable to convert item to object" + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_unpack); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 497, __pyx_L3_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = __Pyx_PyBytes_FromString(__pyx_v_self->view.format); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 497, __pyx_L3_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_7 = NULL; + __pyx_t_8 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_8 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_7, __pyx_t_6, __pyx_v_bytesitem}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_8, 2+__pyx_t_8); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 497, __pyx_L3_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + __pyx_v_result = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":496 + * + * bytesitem = itemp[:self.view.itemsize] + * try: # <<<<<<<<<<<<<< + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + */ + } + + /* "View.MemoryView":501 + * raise ValueError, "Unable to convert item to object" + * else: + * if len(self.view.format) == 1: # <<<<<<<<<<<<<< + * return result[0] + * return result + */ + /*else:*/ { + __pyx_t_9 = __Pyx_ssize_strlen(__pyx_v_self->view.format); if (unlikely(__pyx_t_9 == ((Py_ssize_t)-1))) __PYX_ERR(0, 501, __pyx_L5_except_error) + __pyx_t_10 = (__pyx_t_9 == 1); + if (__pyx_t_10) { + + /* "View.MemoryView":502 + * else: + * if len(self.view.format) == 1: + * return result[0] # <<<<<<<<<<<<<< + * return result + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_result, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 502, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L6_except_return; + + /* "View.MemoryView":501 + * raise ValueError, "Unable to convert item to object" + * else: + * if len(self.view.format) == 1: # <<<<<<<<<<<<<< + * return result[0] + * return result + */ + } + + /* "View.MemoryView":503 + * if len(self.view.format) == 1: + * return result[0] + * return result # <<<<<<<<<<<<<< + * + * cdef assign_item_from_object(self, char *itemp, object value): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_result); + __pyx_r = __pyx_v_result; + goto __pyx_L6_except_return; + } + __pyx_L3_error:; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":498 + * try: + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: # <<<<<<<<<<<<<< + * raise ValueError, "Unable to convert item to object" + * else: + */ + __Pyx_ErrFetch(&__pyx_t_1, &__pyx_t_5, &__pyx_t_6); + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_error); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 498, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_8 = __Pyx_PyErr_GivenExceptionMatches(__pyx_t_1, __pyx_t_7); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_ErrRestore(__pyx_t_1, __pyx_t_5, __pyx_t_6); + __pyx_t_1 = 0; __pyx_t_5 = 0; __pyx_t_6 = 0; + if (__pyx_t_8) { + __Pyx_AddTraceback("View.MemoryView.memoryview.convert_item_to_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_6, &__pyx_t_5, &__pyx_t_1) < 0) __PYX_ERR(0, 498, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_1); + + /* "View.MemoryView":499 + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + * raise ValueError, "Unable to convert item to object" # <<<<<<<<<<<<<< + * else: + * if len(self.view.format) == 1: + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Unable_to_convert_item_to_object, 0, 0); + __PYX_ERR(0, 499, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "View.MemoryView":496 + * + * bytesitem = itemp[:self.view.itemsize] + * try: # <<<<<<<<<<<<<< + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_ExceptionReset(__pyx_t_2, __pyx_t_3, __pyx_t_4); + goto __pyx_L1_error; + __pyx_L6_except_return:; + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_ExceptionReset(__pyx_t_2, __pyx_t_3, __pyx_t_4); + goto __pyx_L0; + } + + /* "View.MemoryView":489 + * self.assign_item_from_object(itemp, value) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("View.MemoryView.memoryview.convert_item_to_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_struct); + __Pyx_XDECREF(__pyx_v_bytesitem); + __Pyx_XDECREF(__pyx_v_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":505 + * return result + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + +static PyObject *__pyx_memoryview_assign_item_from_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value) { + PyObject *__pyx_v_struct = NULL; + char __pyx_v_c; + PyObject *__pyx_v_bytesvalue = 0; + Py_ssize_t __pyx_v_i; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + Py_ssize_t __pyx_t_7; + PyObject *__pyx_t_8 = NULL; + char *__pyx_t_9; + char *__pyx_t_10; + char *__pyx_t_11; + char *__pyx_t_12; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("assign_item_from_object", 1); + + /* "View.MemoryView":508 + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + * import struct # <<<<<<<<<<<<<< + * cdef char c + * cdef bytes bytesvalue + */ + __pyx_t_1 = __Pyx_ImportDottedModule(__pyx_n_s_struct, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 508, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_struct = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":513 + * cdef Py_ssize_t i + * + * if isinstance(value, tuple): # <<<<<<<<<<<<<< + * bytesvalue = struct.pack(self.view.format, *value) + * else: + */ + __pyx_t_2 = PyTuple_Check(__pyx_v_value); + if (__pyx_t_2) { + + /* "View.MemoryView":514 + * + * if isinstance(value, tuple): + * bytesvalue = struct.pack(self.view.format, *value) # <<<<<<<<<<<<<< + * else: + * bytesvalue = struct.pack(self.view.format, value) + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_pack); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyBytes_FromString(__pyx_v_self->view.format); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PyTuple_New(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_3)) __PYX_ERR(0, 514, __pyx_L1_error); + __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PySequence_Tuple(__pyx_v_value); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = PyNumber_Add(__pyx_t_4, __pyx_t_3); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PyObject_Call(__pyx_t_1, __pyx_t_5, NULL); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (!(likely(PyBytes_CheckExact(__pyx_t_3))||((__pyx_t_3) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_t_3))) __PYX_ERR(0, 514, __pyx_L1_error) + __pyx_v_bytesvalue = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":513 + * cdef Py_ssize_t i + * + * if isinstance(value, tuple): # <<<<<<<<<<<<<< + * bytesvalue = struct.pack(self.view.format, *value) + * else: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":516 + * bytesvalue = struct.pack(self.view.format, *value) + * else: + * bytesvalue = struct.pack(self.view.format, value) # <<<<<<<<<<<<<< + * + * for i, c in enumerate(bytesvalue): + */ + /*else*/ { + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_pack); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 516, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 = __Pyx_PyBytes_FromString(__pyx_v_self->view.format); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 516, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_4 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_4, __pyx_t_1, __pyx_v_value}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 516, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + if (!(likely(PyBytes_CheckExact(__pyx_t_3))||((__pyx_t_3) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_t_3))) __PYX_ERR(0, 516, __pyx_L1_error) + __pyx_v_bytesvalue = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; + } + __pyx_L3:; + + /* "View.MemoryView":518 + * bytesvalue = struct.pack(self.view.format, value) + * + * for i, c in enumerate(bytesvalue): # <<<<<<<<<<<<<< + * itemp[i] = c + * + */ + __pyx_t_7 = 0; + if (unlikely(__pyx_v_bytesvalue == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' is not iterable"); + __PYX_ERR(0, 518, __pyx_L1_error) + } + __Pyx_INCREF(__pyx_v_bytesvalue); + __pyx_t_8 = __pyx_v_bytesvalue; + __pyx_t_10 = PyBytes_AS_STRING(__pyx_t_8); + __pyx_t_11 = (__pyx_t_10 + PyBytes_GET_SIZE(__pyx_t_8)); + for (__pyx_t_12 = __pyx_t_10; __pyx_t_12 < __pyx_t_11; __pyx_t_12++) { + __pyx_t_9 = __pyx_t_12; + __pyx_v_c = (__pyx_t_9[0]); + + /* "View.MemoryView":519 + * + * for i, c in enumerate(bytesvalue): + * itemp[i] = c # <<<<<<<<<<<<<< + * + * @cname('getbuffer') + */ + __pyx_v_i = __pyx_t_7; + + /* "View.MemoryView":518 + * bytesvalue = struct.pack(self.view.format, value) + * + * for i, c in enumerate(bytesvalue): # <<<<<<<<<<<<<< + * itemp[i] = c + * + */ + __pyx_t_7 = (__pyx_t_7 + 1); + + /* "View.MemoryView":519 + * + * for i, c in enumerate(bytesvalue): + * itemp[i] = c # <<<<<<<<<<<<<< + * + * @cname('getbuffer') + */ + (__pyx_v_itemp[__pyx_v_i]) = __pyx_v_c; + } + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + + /* "View.MemoryView":505 + * return result + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("View.MemoryView.memoryview.assign_item_from_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_struct); + __Pyx_XDECREF(__pyx_v_bytesvalue); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":521 + * itemp[i] = c + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: + */ + +/* Python wrapper */ +CYTHON_UNUSED static int __pyx_memoryview_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +CYTHON_UNUSED static int __pyx_memoryview_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getbuffer__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_8__getbuffer__(((struct __pyx_memoryview_obj *)__pyx_v_self), ((Py_buffer *)__pyx_v_info), ((int)__pyx_v_flags)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_8__getbuffer__(struct __pyx_memoryview_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + Py_ssize_t *__pyx_t_3; + char *__pyx_t_4; + void *__pyx_t_5; + int __pyx_t_6; + Py_ssize_t __pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + if (unlikely(__pyx_v_info == NULL)) { + PyErr_SetString(PyExc_BufferError, "PyObject_GetBuffer: view==NULL argument is obsolete"); + return -1; + } + __Pyx_RefNannySetupContext("__getbuffer__", 0); + __pyx_v_info->obj = Py_None; __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(__pyx_v_info->obj); + + /* "View.MemoryView":523 + * @cname('getbuffer') + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: # <<<<<<<<<<<<<< + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + */ + __pyx_t_2 = ((__pyx_v_flags & PyBUF_WRITABLE) != 0); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_1 = __pyx_v_self->view.readonly; + __pyx_L4_bool_binop_done:; + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":524 + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: + * raise ValueError, "Cannot create writable memory view from read-only memoryview" # <<<<<<<<<<<<<< + * + * if flags & PyBUF_ND: + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Cannot_create_writable_memory_vi, 0, 0); + __PYX_ERR(0, 524, __pyx_L1_error) + + /* "View.MemoryView":523 + * @cname('getbuffer') + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: # <<<<<<<<<<<<<< + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + */ + } + + /* "View.MemoryView":526 + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + * if flags & PyBUF_ND: # <<<<<<<<<<<<<< + * info.shape = self.view.shape + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_ND) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":527 + * + * if flags & PyBUF_ND: + * info.shape = self.view.shape # <<<<<<<<<<<<<< + * else: + * info.shape = NULL + */ + __pyx_t_3 = __pyx_v_self->view.shape; + __pyx_v_info->shape = __pyx_t_3; + + /* "View.MemoryView":526 + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + * if flags & PyBUF_ND: # <<<<<<<<<<<<<< + * info.shape = self.view.shape + * else: + */ + goto __pyx_L6; + } + + /* "View.MemoryView":529 + * info.shape = self.view.shape + * else: + * info.shape = NULL # <<<<<<<<<<<<<< + * + * if flags & PyBUF_STRIDES: + */ + /*else*/ { + __pyx_v_info->shape = NULL; + } + __pyx_L6:; + + /* "View.MemoryView":531 + * info.shape = NULL + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.strides = self.view.strides + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_STRIDES) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":532 + * + * if flags & PyBUF_STRIDES: + * info.strides = self.view.strides # <<<<<<<<<<<<<< + * else: + * info.strides = NULL + */ + __pyx_t_3 = __pyx_v_self->view.strides; + __pyx_v_info->strides = __pyx_t_3; + + /* "View.MemoryView":531 + * info.shape = NULL + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.strides = self.view.strides + * else: + */ + goto __pyx_L7; + } + + /* "View.MemoryView":534 + * info.strides = self.view.strides + * else: + * info.strides = NULL # <<<<<<<<<<<<<< + * + * if flags & PyBUF_INDIRECT: + */ + /*else*/ { + __pyx_v_info->strides = NULL; + } + __pyx_L7:; + + /* "View.MemoryView":536 + * info.strides = NULL + * + * if flags & PyBUF_INDIRECT: # <<<<<<<<<<<<<< + * info.suboffsets = self.view.suboffsets + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_INDIRECT) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":537 + * + * if flags & PyBUF_INDIRECT: + * info.suboffsets = self.view.suboffsets # <<<<<<<<<<<<<< + * else: + * info.suboffsets = NULL + */ + __pyx_t_3 = __pyx_v_self->view.suboffsets; + __pyx_v_info->suboffsets = __pyx_t_3; + + /* "View.MemoryView":536 + * info.strides = NULL + * + * if flags & PyBUF_INDIRECT: # <<<<<<<<<<<<<< + * info.suboffsets = self.view.suboffsets + * else: + */ + goto __pyx_L8; + } + + /* "View.MemoryView":539 + * info.suboffsets = self.view.suboffsets + * else: + * info.suboffsets = NULL # <<<<<<<<<<<<<< + * + * if flags & PyBUF_FORMAT: + */ + /*else*/ { + __pyx_v_info->suboffsets = NULL; + } + __pyx_L8:; + + /* "View.MemoryView":541 + * info.suboffsets = NULL + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * info.format = self.view.format + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_FORMAT) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":542 + * + * if flags & PyBUF_FORMAT: + * info.format = self.view.format # <<<<<<<<<<<<<< + * else: + * info.format = NULL + */ + __pyx_t_4 = __pyx_v_self->view.format; + __pyx_v_info->format = __pyx_t_4; + + /* "View.MemoryView":541 + * info.suboffsets = NULL + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * info.format = self.view.format + * else: + */ + goto __pyx_L9; + } + + /* "View.MemoryView":544 + * info.format = self.view.format + * else: + * info.format = NULL # <<<<<<<<<<<<<< + * + * info.buf = self.view.buf + */ + /*else*/ { + __pyx_v_info->format = NULL; + } + __pyx_L9:; + + /* "View.MemoryView":546 + * info.format = NULL + * + * info.buf = self.view.buf # <<<<<<<<<<<<<< + * info.ndim = self.view.ndim + * info.itemsize = self.view.itemsize + */ + __pyx_t_5 = __pyx_v_self->view.buf; + __pyx_v_info->buf = __pyx_t_5; + + /* "View.MemoryView":547 + * + * info.buf = self.view.buf + * info.ndim = self.view.ndim # <<<<<<<<<<<<<< + * info.itemsize = self.view.itemsize + * info.len = self.view.len + */ + __pyx_t_6 = __pyx_v_self->view.ndim; + __pyx_v_info->ndim = __pyx_t_6; + + /* "View.MemoryView":548 + * info.buf = self.view.buf + * info.ndim = self.view.ndim + * info.itemsize = self.view.itemsize # <<<<<<<<<<<<<< + * info.len = self.view.len + * info.readonly = self.view.readonly + */ + __pyx_t_7 = __pyx_v_self->view.itemsize; + __pyx_v_info->itemsize = __pyx_t_7; + + /* "View.MemoryView":549 + * info.ndim = self.view.ndim + * info.itemsize = self.view.itemsize + * info.len = self.view.len # <<<<<<<<<<<<<< + * info.readonly = self.view.readonly + * info.obj = self + */ + __pyx_t_7 = __pyx_v_self->view.len; + __pyx_v_info->len = __pyx_t_7; + + /* "View.MemoryView":550 + * info.itemsize = self.view.itemsize + * info.len = self.view.len + * info.readonly = self.view.readonly # <<<<<<<<<<<<<< + * info.obj = self + * + */ + __pyx_t_1 = __pyx_v_self->view.readonly; + __pyx_v_info->readonly = __pyx_t_1; + + /* "View.MemoryView":551 + * info.len = self.view.len + * info.readonly = self.view.readonly + * info.obj = self # <<<<<<<<<<<<<< + * + * + */ + __Pyx_INCREF((PyObject *)__pyx_v_self); + __Pyx_GIVEREF((PyObject *)__pyx_v_self); + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); + __pyx_v_info->obj = ((PyObject *)__pyx_v_self); + + /* "View.MemoryView":521 + * itemp[i] = c + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__getbuffer__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + if (__pyx_v_info->obj != NULL) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + goto __pyx_L2; + __pyx_L0:; + if (__pyx_v_info->obj == Py_None) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + __pyx_L2:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":554 + * + * + * @property # <<<<<<<<<<<<<< + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_1T_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_1T_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_1T___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_1T___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + struct __pyx_memoryviewslice_obj *__pyx_v_result = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":556 + * @property + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) # <<<<<<<<<<<<<< + * transpose_memslice(&result.from_slice) + * return result + */ + __pyx_t_1 = __pyx_memoryview_copy_object(__pyx_v_self); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 556, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (!(likely(((__pyx_t_1) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_1, __pyx_memoryviewslice_type))))) __PYX_ERR(0, 556, __pyx_L1_error) + __pyx_v_result = ((struct __pyx_memoryviewslice_obj *)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":557 + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) + * transpose_memslice(&result.from_slice) # <<<<<<<<<<<<<< + * return result + * + */ + __pyx_t_2 = __pyx_memslice_transpose((&__pyx_v_result->from_slice)); if (unlikely(__pyx_t_2 == ((int)-1))) __PYX_ERR(0, 557, __pyx_L1_error) + + /* "View.MemoryView":558 + * cdef _memoryviewslice result = memoryview_copy(self) + * transpose_memslice(&result.from_slice) + * return result # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = ((PyObject *)__pyx_v_result); + goto __pyx_L0; + + /* "View.MemoryView":554 + * + * + * @property # <<<<<<<<<<<<<< + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.T.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":560 + * return result + * + * @property # <<<<<<<<<<<<<< + * def base(self): + * return self._get_base() + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4base_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4base_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_4base___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4base___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":562 + * @property + * def base(self): + * return self._get_base() # <<<<<<<<<<<<<< + * + * cdef _get_base(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->_get_base(__pyx_v_self); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 562, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":560 + * return result + * + * @property # <<<<<<<<<<<<<< + * def base(self): + * return self._get_base() + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.base.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":564 + * return self._get_base() + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.obj + * + */ + +static PyObject *__pyx_memoryview__get_base(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("_get_base", 1); + + /* "View.MemoryView":565 + * + * cdef _get_base(self): + * return self.obj # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->obj); + __pyx_r = __pyx_v_self->obj; + goto __pyx_L0; + + /* "View.MemoryView":564 + * return self._get_base() + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.obj + * + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":567 + * return self.obj + * + * @property # <<<<<<<<<<<<<< + * def shape(self): + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_5shape_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_5shape_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_5shape___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_5shape___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_7genexpr__pyx_v_length; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + PyObject *__pyx_t_5 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":569 + * @property + * def shape(self): + * return tuple([length for length in self.view.shape[:self.view.ndim]]) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + { /* enter inner scope */ + __pyx_t_1 = PyList_New(0); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 569, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = (__pyx_v_self->view.shape + __pyx_v_self->view.ndim); + for (__pyx_t_4 = __pyx_v_self->view.shape; __pyx_t_4 < __pyx_t_3; __pyx_t_4++) { + __pyx_t_2 = __pyx_t_4; + __pyx_7genexpr__pyx_v_length = (__pyx_t_2[0]); + __pyx_t_5 = PyInt_FromSsize_t(__pyx_7genexpr__pyx_v_length); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 569, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_1, (PyObject*)__pyx_t_5))) __PYX_ERR(0, 569, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + } /* exit inner scope */ + __pyx_t_5 = PyList_AsTuple(((PyObject*)__pyx_t_1)); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 569, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_5; + __pyx_t_5 = 0; + goto __pyx_L0; + + /* "View.MemoryView":567 + * return self.obj + * + * @property # <<<<<<<<<<<<<< + * def shape(self): + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.memoryview.shape.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":571 + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def strides(self): + * if self.view.strides == NULL: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_7strides_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_7strides_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_7strides___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_7strides___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_8genexpr1__pyx_v_stride; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + Py_ssize_t *__pyx_t_5; + PyObject *__pyx_t_6 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":573 + * @property + * def strides(self): + * if self.view.strides == NULL: # <<<<<<<<<<<<<< + * + * raise ValueError, "Buffer view does not expose strides" + */ + __pyx_t_1 = (__pyx_v_self->view.strides == NULL); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":575 + * if self.view.strides == NULL: + * + * raise ValueError, "Buffer view does not expose strides" # <<<<<<<<<<<<<< + * + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Buffer_view_does_not_expose_stri, 0, 0); + __PYX_ERR(0, 575, __pyx_L1_error) + + /* "View.MemoryView":573 + * @property + * def strides(self): + * if self.view.strides == NULL: # <<<<<<<<<<<<<< + * + * raise ValueError, "Buffer view does not expose strides" + */ + } + + /* "View.MemoryView":577 + * raise ValueError, "Buffer view does not expose strides" + * + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + { /* enter inner scope */ + __pyx_t_2 = PyList_New(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 577, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = (__pyx_v_self->view.strides + __pyx_v_self->view.ndim); + for (__pyx_t_5 = __pyx_v_self->view.strides; __pyx_t_5 < __pyx_t_4; __pyx_t_5++) { + __pyx_t_3 = __pyx_t_5; + __pyx_8genexpr1__pyx_v_stride = (__pyx_t_3[0]); + __pyx_t_6 = PyInt_FromSsize_t(__pyx_8genexpr1__pyx_v_stride); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 577, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_2, (PyObject*)__pyx_t_6))) __PYX_ERR(0, 577, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + } /* exit inner scope */ + __pyx_t_6 = PyList_AsTuple(((PyObject*)__pyx_t_2)); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 577, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_6; + __pyx_t_6 = 0; + goto __pyx_L0; + + /* "View.MemoryView":571 + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def strides(self): + * if self.view.strides == NULL: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("View.MemoryView.memoryview.strides.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":579 + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def suboffsets(self): + * if self.view.suboffsets == NULL: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_10suboffsets_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_10suboffsets_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_10suboffsets___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_10suboffsets___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_8genexpr2__pyx_v_suboffset; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + Py_ssize_t *__pyx_t_5; + PyObject *__pyx_t_6 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":581 + * @property + * def suboffsets(self): + * if self.view.suboffsets == NULL: # <<<<<<<<<<<<<< + * return (-1,) * self.view.ndim + * + */ + __pyx_t_1 = (__pyx_v_self->view.suboffsets == NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":582 + * def suboffsets(self): + * if self.view.suboffsets == NULL: + * return (-1,) * self.view.ndim # <<<<<<<<<<<<<< + * + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PySequence_Multiply(__pyx_tuple__4, __pyx_v_self->view.ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 582, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":581 + * @property + * def suboffsets(self): + * if self.view.suboffsets == NULL: # <<<<<<<<<<<<<< + * return (-1,) * self.view.ndim + * + */ + } + + /* "View.MemoryView":584 + * return (-1,) * self.view.ndim + * + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + { /* enter inner scope */ + __pyx_t_2 = PyList_New(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 584, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = (__pyx_v_self->view.suboffsets + __pyx_v_self->view.ndim); + for (__pyx_t_5 = __pyx_v_self->view.suboffsets; __pyx_t_5 < __pyx_t_4; __pyx_t_5++) { + __pyx_t_3 = __pyx_t_5; + __pyx_8genexpr2__pyx_v_suboffset = (__pyx_t_3[0]); + __pyx_t_6 = PyInt_FromSsize_t(__pyx_8genexpr2__pyx_v_suboffset); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 584, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_2, (PyObject*)__pyx_t_6))) __PYX_ERR(0, 584, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + } /* exit inner scope */ + __pyx_t_6 = PyList_AsTuple(((PyObject*)__pyx_t_2)); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 584, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_6; + __pyx_t_6 = 0; + goto __pyx_L0; + + /* "View.MemoryView":579 + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def suboffsets(self): + * if self.view.suboffsets == NULL: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("View.MemoryView.memoryview.suboffsets.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":586 + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def ndim(self): + * return self.view.ndim + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4ndim_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4ndim_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_4ndim___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4ndim___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":588 + * @property + * def ndim(self): + * return self.view.ndim # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_self->view.ndim); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 588, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":586 + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def ndim(self): + * return self.view.ndim + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.ndim.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":590 + * return self.view.ndim + * + * @property # <<<<<<<<<<<<<< + * def itemsize(self): + * return self.view.itemsize + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_8itemsize_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_8itemsize_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_8itemsize___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_8itemsize___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":592 + * @property + * def itemsize(self): + * return self.view.itemsize # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyInt_FromSsize_t(__pyx_v_self->view.itemsize); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 592, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":590 + * return self.view.ndim + * + * @property # <<<<<<<<<<<<<< + * def itemsize(self): + * return self.view.itemsize + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.itemsize.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":594 + * return self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def nbytes(self): + * return self.size * self.view.itemsize + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_6nbytes_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_6nbytes_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_6nbytes___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_6nbytes___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":596 + * @property + * def nbytes(self): + * return self.size * self.view.itemsize # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_size); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 596, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = PyInt_FromSsize_t(__pyx_v_self->view.itemsize); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 596, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyNumber_Multiply(__pyx_t_1, __pyx_t_2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 596, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_3; + __pyx_t_3 = 0; + goto __pyx_L0; + + /* "View.MemoryView":594 + * return self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def nbytes(self): + * return self.size * self.view.itemsize + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.nbytes.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":598 + * return self.size * self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def size(self): + * if self._size is None: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4size_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4size_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_4size___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4size___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_v_result = NULL; + PyObject *__pyx_v_length = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + PyObject *__pyx_t_5 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":600 + * @property + * def size(self): + * if self._size is None: # <<<<<<<<<<<<<< + * result = 1 + * + */ + __pyx_t_1 = (__pyx_v_self->_size == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":601 + * def size(self): + * if self._size is None: + * result = 1 # <<<<<<<<<<<<<< + * + * for length in self.view.shape[:self.view.ndim]: + */ + __Pyx_INCREF(__pyx_int_1); + __pyx_v_result = __pyx_int_1; + + /* "View.MemoryView":603 + * result = 1 + * + * for length in self.view.shape[:self.view.ndim]: # <<<<<<<<<<<<<< + * result *= length + * + */ + __pyx_t_3 = (__pyx_v_self->view.shape + __pyx_v_self->view.ndim); + for (__pyx_t_4 = __pyx_v_self->view.shape; __pyx_t_4 < __pyx_t_3; __pyx_t_4++) { + __pyx_t_2 = __pyx_t_4; + __pyx_t_5 = PyInt_FromSsize_t((__pyx_t_2[0])); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 603, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_XDECREF_SET(__pyx_v_length, __pyx_t_5); + __pyx_t_5 = 0; + + /* "View.MemoryView":604 + * + * for length in self.view.shape[:self.view.ndim]: + * result *= length # <<<<<<<<<<<<<< + * + * self._size = result + */ + __pyx_t_5 = PyNumber_InPlaceMultiply(__pyx_v_result, __pyx_v_length); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 604, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF_SET(__pyx_v_result, __pyx_t_5); + __pyx_t_5 = 0; + } + + /* "View.MemoryView":606 + * result *= length + * + * self._size = result # <<<<<<<<<<<<<< + * + * return self._size + */ + __Pyx_INCREF(__pyx_v_result); + __Pyx_GIVEREF(__pyx_v_result); + __Pyx_GOTREF(__pyx_v_self->_size); + __Pyx_DECREF(__pyx_v_self->_size); + __pyx_v_self->_size = __pyx_v_result; + + /* "View.MemoryView":600 + * @property + * def size(self): + * if self._size is None: # <<<<<<<<<<<<<< + * result = 1 + * + */ + } + + /* "View.MemoryView":608 + * self._size = result + * + * return self._size # <<<<<<<<<<<<<< + * + * def __len__(self): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->_size); + __pyx_r = __pyx_v_self->_size; + goto __pyx_L0; + + /* "View.MemoryView":598 + * return self.size * self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def size(self): + * if self._size is None: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.memoryview.size.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_result); + __Pyx_XDECREF(__pyx_v_length); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":610 + * return self._size + * + * def __len__(self): # <<<<<<<<<<<<<< + * if self.view.ndim >= 1: + * return self.view.shape[0] + */ + +/* Python wrapper */ +static Py_ssize_t __pyx_memoryview___len__(PyObject *__pyx_v_self); /*proto*/ +static Py_ssize_t __pyx_memoryview___len__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + Py_ssize_t __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__len__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_10__len__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static Py_ssize_t __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_10__len__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_r; + int __pyx_t_1; + + /* "View.MemoryView":611 + * + * def __len__(self): + * if self.view.ndim >= 1: # <<<<<<<<<<<<<< + * return self.view.shape[0] + * + */ + __pyx_t_1 = (__pyx_v_self->view.ndim >= 1); + if (__pyx_t_1) { + + /* "View.MemoryView":612 + * def __len__(self): + * if self.view.ndim >= 1: + * return self.view.shape[0] # <<<<<<<<<<<<<< + * + * return 0 + */ + __pyx_r = (__pyx_v_self->view.shape[0]); + goto __pyx_L0; + + /* "View.MemoryView":611 + * + * def __len__(self): + * if self.view.ndim >= 1: # <<<<<<<<<<<<<< + * return self.view.shape[0] + * + */ + } + + /* "View.MemoryView":614 + * return self.view.shape[0] + * + * return 0 # <<<<<<<<<<<<<< + * + * def __repr__(self): + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":610 + * return self._size + * + * def __len__(self): # <<<<<<<<<<<<<< + * if self.view.ndim >= 1: + * return self.view.shape[0] + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":616 + * return 0 + * + * def __repr__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__, + * id(self)) + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview___repr__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_memoryview___repr__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__repr__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_12__repr__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_12__repr__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__repr__", 1); + + /* "View.MemoryView":617 + * + * def __repr__(self): + * return "" % (self.base.__class__.__name__, # <<<<<<<<<<<<<< + * id(self)) + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_base); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_class); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_name_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":618 + * def __repr__(self): + * return "" % (self.base.__class__.__name__, + * id(self)) # <<<<<<<<<<<<<< + * + * def __str__(self): + */ + __pyx_t_2 = __Pyx_PyObject_CallOneArg(__pyx_builtin_id, ((PyObject *)__pyx_v_self)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 618, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + + /* "View.MemoryView":617 + * + * def __repr__(self): + * return "" % (self.base.__class__.__name__, # <<<<<<<<<<<<<< + * id(self)) + * + */ + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_1)) __PYX_ERR(0, 617, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_2)) __PYX_ERR(0, 617, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyString_Format(__pyx_kp_s_MemoryView_of_r_at_0x_x, __pyx_t_3); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":616 + * return 0 + * + * def __repr__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__, + * id(self)) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.__repr__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":620 + * id(self)) + * + * def __str__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__,) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview___str__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_memoryview___str__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__str__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_14__str__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_14__str__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__str__", 1); + + /* "View.MemoryView":621 + * + * def __str__(self): + * return "" % (self.base.__class__.__name__,) # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_base); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_class); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_name_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = PyTuple_New(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_t_1)) __PYX_ERR(0, 621, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_MemoryView_of_r_object, __pyx_t_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":620 + * id(self)) + * + * def __str__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__,) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.__str__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":624 + * + * + * def is_c_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_is_c_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_is_c_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("is_c_contig (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("is_c_contig", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "is_c_contig", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_16is_c_contig(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_16is_c_contig(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice *__pyx_v_mslice; + __Pyx_memviewslice __pyx_v_tmp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("is_c_contig", 1); + + /* "View.MemoryView":627 + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) # <<<<<<<<<<<<<< + * return slice_is_contig(mslice[0], 'C', self.view.ndim) + * + */ + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(__pyx_v_self, (&__pyx_v_tmp)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(0, 627, __pyx_L1_error) + __pyx_v_mslice = __pyx_t_1; + + /* "View.MemoryView":628 + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) + * return slice_is_contig(mslice[0], 'C', self.view.ndim) # <<<<<<<<<<<<<< + * + * def is_f_contig(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_memviewslice_is_contig((__pyx_v_mslice[0]), 'C', __pyx_v_self->view.ndim)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 628, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":624 + * + * + * def is_c_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.is_c_contig", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":630 + * return slice_is_contig(mslice[0], 'C', self.view.ndim) + * + * def is_f_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_is_f_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_is_f_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("is_f_contig (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("is_f_contig", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "is_f_contig", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_18is_f_contig(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_18is_f_contig(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice *__pyx_v_mslice; + __Pyx_memviewslice __pyx_v_tmp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("is_f_contig", 1); + + /* "View.MemoryView":633 + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) # <<<<<<<<<<<<<< + * return slice_is_contig(mslice[0], 'F', self.view.ndim) + * + */ + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(__pyx_v_self, (&__pyx_v_tmp)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(0, 633, __pyx_L1_error) + __pyx_v_mslice = __pyx_t_1; + + /* "View.MemoryView":634 + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) + * return slice_is_contig(mslice[0], 'F', self.view.ndim) # <<<<<<<<<<<<<< + * + * def copy(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_memviewslice_is_contig((__pyx_v_mslice[0]), 'F', __pyx_v_self->view.ndim)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 634, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":630 + * return slice_is_contig(mslice[0], 'C', self.view.ndim) + * + * def is_f_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.is_f_contig", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":636 + * return slice_is_contig(mslice[0], 'F', self.view.ndim) + * + * def copy(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice mslice + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_copy(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_copy(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("copy (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("copy", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "copy", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_20copy(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_20copy(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice __pyx_v_mslice; + int __pyx_v_flags; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("copy", 1); + + /* "View.MemoryView":638 + * def copy(self): + * cdef __Pyx_memviewslice mslice + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS # <<<<<<<<<<<<<< + * + * slice_copy(self, &mslice) + */ + __pyx_v_flags = (__pyx_v_self->flags & (~PyBUF_F_CONTIGUOUS)); + + /* "View.MemoryView":640 + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS + * + * slice_copy(self, &mslice) # <<<<<<<<<<<<<< + * mslice = slice_copy_contig(&mslice, "c", self.view.ndim, + * self.view.itemsize, + */ + __pyx_memoryview_slice_copy(__pyx_v_self, (&__pyx_v_mslice)); + + /* "View.MemoryView":641 + * + * slice_copy(self, &mslice) + * mslice = slice_copy_contig(&mslice, "c", self.view.ndim, # <<<<<<<<<<<<<< + * self.view.itemsize, + * flags|PyBUF_C_CONTIGUOUS, + */ + __pyx_t_1 = __pyx_memoryview_copy_new_contig((&__pyx_v_mslice), ((char *)"c"), __pyx_v_self->view.ndim, __pyx_v_self->view.itemsize, (__pyx_v_flags | PyBUF_C_CONTIGUOUS), __pyx_v_self->dtype_is_object); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 641, __pyx_L1_error) + __pyx_v_mslice = __pyx_t_1; + + /* "View.MemoryView":646 + * self.dtype_is_object) + * + * return memoryview_copy_from_slice(self, &mslice) # <<<<<<<<<<<<<< + * + * def copy_fortran(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_memoryview_copy_object_from_slice(__pyx_v_self, (&__pyx_v_mslice)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 646, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":636 + * return slice_is_contig(mslice[0], 'F', self.view.ndim) + * + * def copy(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice mslice + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.copy", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":648 + * return memoryview_copy_from_slice(self, &mslice) + * + * def copy_fortran(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice src, dst + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_copy_fortran(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_copy_fortran(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("copy_fortran (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("copy_fortran", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "copy_fortran", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_22copy_fortran(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_22copy_fortran(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice __pyx_v_src; + __Pyx_memviewslice __pyx_v_dst; + int __pyx_v_flags; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("copy_fortran", 1); + + /* "View.MemoryView":650 + * def copy_fortran(self): + * cdef __Pyx_memviewslice src, dst + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS # <<<<<<<<<<<<<< + * + * slice_copy(self, &src) + */ + __pyx_v_flags = (__pyx_v_self->flags & (~PyBUF_C_CONTIGUOUS)); + + /* "View.MemoryView":652 + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS + * + * slice_copy(self, &src) # <<<<<<<<<<<<<< + * dst = slice_copy_contig(&src, "fortran", self.view.ndim, + * self.view.itemsize, + */ + __pyx_memoryview_slice_copy(__pyx_v_self, (&__pyx_v_src)); + + /* "View.MemoryView":653 + * + * slice_copy(self, &src) + * dst = slice_copy_contig(&src, "fortran", self.view.ndim, # <<<<<<<<<<<<<< + * self.view.itemsize, + * flags|PyBUF_F_CONTIGUOUS, + */ + __pyx_t_1 = __pyx_memoryview_copy_new_contig((&__pyx_v_src), ((char *)"fortran"), __pyx_v_self->view.ndim, __pyx_v_self->view.itemsize, (__pyx_v_flags | PyBUF_F_CONTIGUOUS), __pyx_v_self->dtype_is_object); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 653, __pyx_L1_error) + __pyx_v_dst = __pyx_t_1; + + /* "View.MemoryView":658 + * self.dtype_is_object) + * + * return memoryview_copy_from_slice(self, &dst) # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_memoryview_copy_object_from_slice(__pyx_v_self, (&__pyx_v_dst)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 658, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":648 + * return memoryview_copy_from_slice(self, &mslice) + * + * def copy_fortran(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice src, dst + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.copy_fortran", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryview_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryview_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_memoryview___reduce_cython__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryview___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(0, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryview_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryview_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(0, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.memoryview.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_memoryview_2__setstate_cython__(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryview_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(0, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":662 + * + * @cname('__pyx_memoryview_new') + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): # <<<<<<<<<<<<<< + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo + */ + +static PyObject *__pyx_memoryview_new(PyObject *__pyx_v_o, int __pyx_v_flags, int __pyx_v_dtype_is_object, __Pyx_TypeInfo *__pyx_v_typeinfo) { + struct __pyx_memoryview_obj *__pyx_v_result = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_cwrapper", 1); + + /* "View.MemoryView":663 + * @cname('__pyx_memoryview_new') + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): + * cdef memoryview result = memoryview(o, flags, dtype_is_object) # <<<<<<<<<<<<<< + * result.typeinfo = typeinfo + * return result + */ + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_flags); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_v_dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_v_o); + __Pyx_GIVEREF(__pyx_v_o); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_v_o)) __PYX_ERR(0, 663, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1)) __PYX_ERR(0, 663, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_t_2)) __PYX_ERR(0, 663, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_Call(((PyObject *)__pyx_memoryview_type), __pyx_t_3, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_v_result = ((struct __pyx_memoryview_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":664 + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo # <<<<<<<<<<<<<< + * return result + * + */ + __pyx_v_result->typeinfo = __pyx_v_typeinfo; + + /* "View.MemoryView":665 + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo + * return result # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_check') + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = ((PyObject *)__pyx_v_result); + goto __pyx_L0; + + /* "View.MemoryView":662 + * + * @cname('__pyx_memoryview_new') + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): # <<<<<<<<<<<<<< + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview_cwrapper", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":668 + * + * @cname('__pyx_memoryview_check') + * cdef inline bint memoryview_check(object o) noexcept: # <<<<<<<<<<<<<< + * return isinstance(o, memoryview) + * + */ + +static CYTHON_INLINE int __pyx_memoryview_check(PyObject *__pyx_v_o) { + int __pyx_r; + int __pyx_t_1; + + /* "View.MemoryView":669 + * @cname('__pyx_memoryview_check') + * cdef inline bint memoryview_check(object o) noexcept: + * return isinstance(o, memoryview) # <<<<<<<<<<<<<< + * + * cdef tuple _unellipsify(object index, int ndim): + */ + __pyx_t_1 = __Pyx_TypeCheck(__pyx_v_o, __pyx_memoryview_type); + __pyx_r = __pyx_t_1; + goto __pyx_L0; + + /* "View.MemoryView":668 + * + * @cname('__pyx_memoryview_check') + * cdef inline bint memoryview_check(object o) noexcept: # <<<<<<<<<<<<<< + * return isinstance(o, memoryview) + * + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":671 + * return isinstance(o, memoryview) + * + * cdef tuple _unellipsify(object index, int ndim): # <<<<<<<<<<<<<< + * """ + * Replace all ellipses with full slices and fill incomplete indices with + */ + +static PyObject *_unellipsify(PyObject *__pyx_v_index, int __pyx_v_ndim) { + Py_ssize_t __pyx_v_idx; + PyObject *__pyx_v_tup = NULL; + PyObject *__pyx_v_result = NULL; + int __pyx_v_have_slices; + int __pyx_v_seen_ellipsis; + PyObject *__pyx_v_item = NULL; + Py_ssize_t __pyx_v_nslices; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + Py_ssize_t __pyx_t_4; + Py_ssize_t __pyx_t_5; + Py_UCS4 __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("_unellipsify", 1); + + /* "View.MemoryView":677 + * """ + * cdef Py_ssize_t idx + * tup = index if isinstance(index, tuple) else (index,) # <<<<<<<<<<<<<< + * + * result = [slice(None)] * ndim + */ + __pyx_t_2 = PyTuple_Check(__pyx_v_index); + if (__pyx_t_2) { + __Pyx_INCREF(((PyObject*)__pyx_v_index)); + __pyx_t_1 = __pyx_v_index; + } else { + __pyx_t_3 = PyTuple_New(1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 677, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_v_index); + __Pyx_GIVEREF(__pyx_v_index); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_v_index)) __PYX_ERR(0, 677, __pyx_L1_error); + __pyx_t_1 = __pyx_t_3; + __pyx_t_3 = 0; + } + __pyx_v_tup = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":679 + * tup = index if isinstance(index, tuple) else (index,) + * + * result = [slice(None)] * ndim # <<<<<<<<<<<<<< + * have_slices = False + * seen_ellipsis = False + */ + __pyx_t_1 = PyList_New(1 * ((__pyx_v_ndim<0) ? 0:__pyx_v_ndim)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 679, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + { Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < __pyx_v_ndim; __pyx_temp++) { + __Pyx_INCREF(__pyx_slice__5); + __Pyx_GIVEREF(__pyx_slice__5); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, __pyx_temp, __pyx_slice__5)) __PYX_ERR(0, 679, __pyx_L1_error); + } + } + __pyx_v_result = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":680 + * + * result = [slice(None)] * ndim + * have_slices = False # <<<<<<<<<<<<<< + * seen_ellipsis = False + * idx = 0 + */ + __pyx_v_have_slices = 0; + + /* "View.MemoryView":681 + * result = [slice(None)] * ndim + * have_slices = False + * seen_ellipsis = False # <<<<<<<<<<<<<< + * idx = 0 + * for item in tup: + */ + __pyx_v_seen_ellipsis = 0; + + /* "View.MemoryView":682 + * have_slices = False + * seen_ellipsis = False + * idx = 0 # <<<<<<<<<<<<<< + * for item in tup: + * if item is Ellipsis: + */ + __pyx_v_idx = 0; + + /* "View.MemoryView":683 + * seen_ellipsis = False + * idx = 0 + * for item in tup: # <<<<<<<<<<<<<< + * if item is Ellipsis: + * if not seen_ellipsis: + */ + if (unlikely(__pyx_v_tup == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not iterable"); + __PYX_ERR(0, 683, __pyx_L1_error) + } + __pyx_t_1 = __pyx_v_tup; __Pyx_INCREF(__pyx_t_1); + __pyx_t_4 = 0; + for (;;) { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_1); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 683, __pyx_L1_error) + #endif + if (__pyx_t_4 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_3 = PyTuple_GET_ITEM(__pyx_t_1, __pyx_t_4); __Pyx_INCREF(__pyx_t_3); __pyx_t_4++; if (unlikely((0 < 0))) __PYX_ERR(0, 683, __pyx_L1_error) + #else + __pyx_t_3 = __Pyx_PySequence_ITEM(__pyx_t_1, __pyx_t_4); __pyx_t_4++; if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 683, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + #endif + __Pyx_XDECREF_SET(__pyx_v_item, __pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":684 + * idx = 0 + * for item in tup: + * if item is Ellipsis: # <<<<<<<<<<<<<< + * if not seen_ellipsis: + * idx += ndim - len(tup) + */ + __pyx_t_2 = (__pyx_v_item == __pyx_builtin_Ellipsis); + if (__pyx_t_2) { + + /* "View.MemoryView":685 + * for item in tup: + * if item is Ellipsis: + * if not seen_ellipsis: # <<<<<<<<<<<<<< + * idx += ndim - len(tup) + * seen_ellipsis = True + */ + __pyx_t_2 = (!__pyx_v_seen_ellipsis); + if (__pyx_t_2) { + + /* "View.MemoryView":686 + * if item is Ellipsis: + * if not seen_ellipsis: + * idx += ndim - len(tup) # <<<<<<<<<<<<<< + * seen_ellipsis = True + * have_slices = True + */ + if (unlikely(__pyx_v_tup == Py_None)) { + PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); + __PYX_ERR(0, 686, __pyx_L1_error) + } + __pyx_t_5 = __Pyx_PyTuple_GET_SIZE(__pyx_v_tup); if (unlikely(__pyx_t_5 == ((Py_ssize_t)-1))) __PYX_ERR(0, 686, __pyx_L1_error) + __pyx_v_idx = (__pyx_v_idx + (__pyx_v_ndim - __pyx_t_5)); + + /* "View.MemoryView":687 + * if not seen_ellipsis: + * idx += ndim - len(tup) + * seen_ellipsis = True # <<<<<<<<<<<<<< + * have_slices = True + * else: + */ + __pyx_v_seen_ellipsis = 1; + + /* "View.MemoryView":685 + * for item in tup: + * if item is Ellipsis: + * if not seen_ellipsis: # <<<<<<<<<<<<<< + * idx += ndim - len(tup) + * seen_ellipsis = True + */ + } + + /* "View.MemoryView":688 + * idx += ndim - len(tup) + * seen_ellipsis = True + * have_slices = True # <<<<<<<<<<<<<< + * else: + * if isinstance(item, slice): + */ + __pyx_v_have_slices = 1; + + /* "View.MemoryView":684 + * idx = 0 + * for item in tup: + * if item is Ellipsis: # <<<<<<<<<<<<<< + * if not seen_ellipsis: + * idx += ndim - len(tup) + */ + goto __pyx_L5; + } + + /* "View.MemoryView":690 + * have_slices = True + * else: + * if isinstance(item, slice): # <<<<<<<<<<<<<< + * have_slices = True + * elif not PyIndex_Check(item): + */ + /*else*/ { + __pyx_t_2 = PySlice_Check(__pyx_v_item); + if (__pyx_t_2) { + + /* "View.MemoryView":691 + * else: + * if isinstance(item, slice): + * have_slices = True # <<<<<<<<<<<<<< + * elif not PyIndex_Check(item): + * raise TypeError, f"Cannot index with type '{type(item)}'" + */ + __pyx_v_have_slices = 1; + + /* "View.MemoryView":690 + * have_slices = True + * else: + * if isinstance(item, slice): # <<<<<<<<<<<<<< + * have_slices = True + * elif not PyIndex_Check(item): + */ + goto __pyx_L7; + } + + /* "View.MemoryView":692 + * if isinstance(item, slice): + * have_slices = True + * elif not PyIndex_Check(item): # <<<<<<<<<<<<<< + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item + */ + __pyx_t_2 = (!(PyIndex_Check(__pyx_v_item) != 0)); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":693 + * have_slices = True + * elif not PyIndex_Check(item): + * raise TypeError, f"Cannot index with type '{type(item)}'" # <<<<<<<<<<<<<< + * result[idx] = item + * idx += 1 + */ + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 693, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = 0; + __pyx_t_6 = 127; + __Pyx_INCREF(__pyx_kp_u_Cannot_index_with_type); + __pyx_t_5 += 24; + __Pyx_GIVEREF(__pyx_kp_u_Cannot_index_with_type); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_kp_u_Cannot_index_with_type); + __pyx_t_7 = __Pyx_PyObject_FormatSimple(((PyObject *)Py_TYPE(__pyx_v_item)), __pyx_empty_unicode); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 693, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_7) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_7) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_7); + __pyx_t_7 = 0; + __Pyx_INCREF(__pyx_kp_u__6); + __pyx_t_5 += 1; + __Pyx_GIVEREF(__pyx_kp_u__6); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_kp_u__6); + __pyx_t_7 = __Pyx_PyUnicode_Join(__pyx_t_3, 3, __pyx_t_5, __pyx_t_6); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 693, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_t_7, 0, 0); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __PYX_ERR(0, 693, __pyx_L1_error) + + /* "View.MemoryView":692 + * if isinstance(item, slice): + * have_slices = True + * elif not PyIndex_Check(item): # <<<<<<<<<<<<<< + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item + */ + } + __pyx_L7:; + + /* "View.MemoryView":694 + * elif not PyIndex_Check(item): + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item # <<<<<<<<<<<<<< + * idx += 1 + * + */ + if (unlikely((__Pyx_SetItemInt(__pyx_v_result, __pyx_v_idx, __pyx_v_item, Py_ssize_t, 1, PyInt_FromSsize_t, 1, 1, 1) < 0))) __PYX_ERR(0, 694, __pyx_L1_error) + } + __pyx_L5:; + + /* "View.MemoryView":695 + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item + * idx += 1 # <<<<<<<<<<<<<< + * + * nslices = ndim - idx + */ + __pyx_v_idx = (__pyx_v_idx + 1); + + /* "View.MemoryView":683 + * seen_ellipsis = False + * idx = 0 + * for item in tup: # <<<<<<<<<<<<<< + * if item is Ellipsis: + * if not seen_ellipsis: + */ + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "View.MemoryView":697 + * idx += 1 + * + * nslices = ndim - idx # <<<<<<<<<<<<<< + * return have_slices or nslices, tuple(result) + * + */ + __pyx_v_nslices = (__pyx_v_ndim - __pyx_v_idx); + + /* "View.MemoryView":698 + * + * nslices = ndim - idx + * return have_slices or nslices, tuple(result) # <<<<<<<<<<<<<< + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + */ + __Pyx_XDECREF(__pyx_r); + if (!__pyx_v_have_slices) { + } else { + __pyx_t_7 = __Pyx_PyBool_FromLong(__pyx_v_have_slices); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_1 = __pyx_t_7; + __pyx_t_7 = 0; + goto __pyx_L9_bool_binop_done; + } + __pyx_t_7 = PyInt_FromSsize_t(__pyx_v_nslices); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_1 = __pyx_t_7; + __pyx_t_7 = 0; + __pyx_L9_bool_binop_done:; + __pyx_t_7 = PyList_AsTuple(__pyx_v_result); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_1)) __PYX_ERR(0, 698, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_7); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_7)) __PYX_ERR(0, 698, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_7 = 0; + __pyx_r = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; + goto __pyx_L0; + + /* "View.MemoryView":671 + * return isinstance(o, memoryview) + * + * cdef tuple _unellipsify(object index, int ndim): # <<<<<<<<<<<<<< + * """ + * Replace all ellipses with full slices and fill incomplete indices with + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("View.MemoryView._unellipsify", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_tup); + __Pyx_XDECREF(__pyx_v_result); + __Pyx_XDECREF(__pyx_v_item); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":700 + * return have_slices or nslices, tuple(result) + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: # <<<<<<<<<<<<<< + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: + */ + +static int assert_direct_dimensions(Py_ssize_t *__pyx_v_suboffsets, int __pyx_v_ndim) { + Py_ssize_t __pyx_v_suboffset; + int __pyx_r; + Py_ssize_t *__pyx_t_1; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + int __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + + /* "View.MemoryView":701 + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + * for suboffset in suboffsets[:ndim]: # <<<<<<<<<<<<<< + * if suboffset >= 0: + * raise ValueError, "Indirect dimensions not supported" + */ + __pyx_t_2 = (__pyx_v_suboffsets + __pyx_v_ndim); + for (__pyx_t_3 = __pyx_v_suboffsets; __pyx_t_3 < __pyx_t_2; __pyx_t_3++) { + __pyx_t_1 = __pyx_t_3; + __pyx_v_suboffset = (__pyx_t_1[0]); + + /* "View.MemoryView":702 + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * raise ValueError, "Indirect dimensions not supported" + * return 0 # return type just used as an error flag + */ + __pyx_t_4 = (__pyx_v_suboffset >= 0); + if (unlikely(__pyx_t_4)) { + + /* "View.MemoryView":703 + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: + * raise ValueError, "Indirect dimensions not supported" # <<<<<<<<<<<<<< + * return 0 # return type just used as an error flag + * + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Indirect_dimensions_not_supporte, 0, 0); + __PYX_ERR(0, 703, __pyx_L1_error) + + /* "View.MemoryView":702 + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * raise ValueError, "Indirect dimensions not supported" + * return 0 # return type just used as an error flag + */ + } + } + + /* "View.MemoryView":704 + * if suboffset >= 0: + * raise ValueError, "Indirect dimensions not supported" + * return 0 # return type just used as an error flag # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":700 + * return have_slices or nslices, tuple(result) + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: # <<<<<<<<<<<<<< + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.assert_direct_dimensions", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":711 + * + * @cname('__pyx_memview_slice') + * cdef memoryview memview_slice(memoryview memview, object indices): # <<<<<<<<<<<<<< + * cdef int new_ndim = 0, suboffset_dim = -1, dim + * cdef bint negative_step + */ + +static struct __pyx_memoryview_obj *__pyx_memview_slice(struct __pyx_memoryview_obj *__pyx_v_memview, PyObject *__pyx_v_indices) { + int __pyx_v_new_ndim; + int __pyx_v_suboffset_dim; + int __pyx_v_dim; + __Pyx_memviewslice __pyx_v_src; + __Pyx_memviewslice __pyx_v_dst; + __Pyx_memviewslice *__pyx_v_p_src; + struct __pyx_memoryviewslice_obj *__pyx_v_memviewsliceobj = 0; + __Pyx_memviewslice *__pyx_v_p_dst; + int *__pyx_v_p_suboffset_dim; + Py_ssize_t __pyx_v_start; + Py_ssize_t __pyx_v_stop; + Py_ssize_t __pyx_v_step; + Py_ssize_t __pyx_v_cindex; + int __pyx_v_have_start; + int __pyx_v_have_stop; + int __pyx_v_have_step; + PyObject *__pyx_v_index = NULL; + struct __pyx_memoryview_obj *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + struct __pyx_memoryview_obj *__pyx_t_3; + char *__pyx_t_4; + int __pyx_t_5; + Py_ssize_t __pyx_t_6; + PyObject *(*__pyx_t_7)(PyObject *); + PyObject *__pyx_t_8 = NULL; + Py_ssize_t __pyx_t_9; + int __pyx_t_10; + Py_ssize_t __pyx_t_11; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memview_slice", 1); + + /* "View.MemoryView":712 + * @cname('__pyx_memview_slice') + * cdef memoryview memview_slice(memoryview memview, object indices): + * cdef int new_ndim = 0, suboffset_dim = -1, dim # <<<<<<<<<<<<<< + * cdef bint negative_step + * cdef __Pyx_memviewslice src, dst + */ + __pyx_v_new_ndim = 0; + __pyx_v_suboffset_dim = -1; + + /* "View.MemoryView":719 + * + * + * memset(&dst, 0, sizeof(dst)) # <<<<<<<<<<<<<< + * + * cdef _memoryviewslice memviewsliceobj + */ + (void)(memset((&__pyx_v_dst), 0, (sizeof(__pyx_v_dst)))); + + /* "View.MemoryView":723 + * cdef _memoryviewslice memviewsliceobj + * + * assert memview.view.ndim > 0 # <<<<<<<<<<<<<< + * + * if isinstance(memview, _memoryviewslice): + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_1 = (__pyx_v_memview->view.ndim > 0); + if (unlikely(!__pyx_t_1)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(0, 723, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(0, 723, __pyx_L1_error) + #endif + + /* "View.MemoryView":725 + * assert memview.view.ndim > 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * memviewsliceobj = memview + * p_src = &memviewsliceobj.from_slice + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":726 + * + * if isinstance(memview, _memoryviewslice): + * memviewsliceobj = memview # <<<<<<<<<<<<<< + * p_src = &memviewsliceobj.from_slice + * else: + */ + if (!(likely(((((PyObject *)__pyx_v_memview)) == Py_None) || likely(__Pyx_TypeTest(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type))))) __PYX_ERR(0, 726, __pyx_L1_error) + __pyx_t_2 = ((PyObject *)__pyx_v_memview); + __Pyx_INCREF(__pyx_t_2); + __pyx_v_memviewsliceobj = ((struct __pyx_memoryviewslice_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":727 + * if isinstance(memview, _memoryviewslice): + * memviewsliceobj = memview + * p_src = &memviewsliceobj.from_slice # <<<<<<<<<<<<<< + * else: + * slice_copy(memview, &src) + */ + __pyx_v_p_src = (&__pyx_v_memviewsliceobj->from_slice); + + /* "View.MemoryView":725 + * assert memview.view.ndim > 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * memviewsliceobj = memview + * p_src = &memviewsliceobj.from_slice + */ + goto __pyx_L3; + } + + /* "View.MemoryView":729 + * p_src = &memviewsliceobj.from_slice + * else: + * slice_copy(memview, &src) # <<<<<<<<<<<<<< + * p_src = &src + * + */ + /*else*/ { + __pyx_memoryview_slice_copy(__pyx_v_memview, (&__pyx_v_src)); + + /* "View.MemoryView":730 + * else: + * slice_copy(memview, &src) + * p_src = &src # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_p_src = (&__pyx_v_src); + } + __pyx_L3:; + + /* "View.MemoryView":736 + * + * + * dst.memview = p_src.memview # <<<<<<<<<<<<<< + * dst.data = p_src.data + * + */ + __pyx_t_3 = __pyx_v_p_src->memview; + __pyx_v_dst.memview = __pyx_t_3; + + /* "View.MemoryView":737 + * + * dst.memview = p_src.memview + * dst.data = p_src.data # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_4 = __pyx_v_p_src->data; + __pyx_v_dst.data = __pyx_t_4; + + /* "View.MemoryView":742 + * + * + * cdef __Pyx_memviewslice *p_dst = &dst # <<<<<<<<<<<<<< + * cdef int *p_suboffset_dim = &suboffset_dim + * cdef Py_ssize_t start, stop, step, cindex + */ + __pyx_v_p_dst = (&__pyx_v_dst); + + /* "View.MemoryView":743 + * + * cdef __Pyx_memviewslice *p_dst = &dst + * cdef int *p_suboffset_dim = &suboffset_dim # <<<<<<<<<<<<<< + * cdef Py_ssize_t start, stop, step, cindex + * cdef bint have_start, have_stop, have_step + */ + __pyx_v_p_suboffset_dim = (&__pyx_v_suboffset_dim); + + /* "View.MemoryView":747 + * cdef bint have_start, have_stop, have_step + * + * for dim, index in enumerate(indices): # <<<<<<<<<<<<<< + * if PyIndex_Check(index): + * cindex = index + */ + __pyx_t_5 = 0; + if (likely(PyList_CheckExact(__pyx_v_indices)) || PyTuple_CheckExact(__pyx_v_indices)) { + __pyx_t_2 = __pyx_v_indices; __Pyx_INCREF(__pyx_t_2); + __pyx_t_6 = 0; + __pyx_t_7 = NULL; + } else { + __pyx_t_6 = -1; __pyx_t_2 = PyObject_GetIter(__pyx_v_indices); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 747, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_7 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_2); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 747, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_7)) { + if (likely(PyList_CheckExact(__pyx_t_2))) { + { + Py_ssize_t __pyx_temp = __Pyx_PyList_GET_SIZE(__pyx_t_2); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 747, __pyx_L1_error) + #endif + if (__pyx_t_6 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_8 = PyList_GET_ITEM(__pyx_t_2, __pyx_t_6); __Pyx_INCREF(__pyx_t_8); __pyx_t_6++; if (unlikely((0 < 0))) __PYX_ERR(0, 747, __pyx_L1_error) + #else + __pyx_t_8 = __Pyx_PySequence_ITEM(__pyx_t_2, __pyx_t_6); __pyx_t_6++; if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 747, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + #endif + } else { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_2); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 747, __pyx_L1_error) + #endif + if (__pyx_t_6 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_8 = PyTuple_GET_ITEM(__pyx_t_2, __pyx_t_6); __Pyx_INCREF(__pyx_t_8); __pyx_t_6++; if (unlikely((0 < 0))) __PYX_ERR(0, 747, __pyx_L1_error) + #else + __pyx_t_8 = __Pyx_PySequence_ITEM(__pyx_t_2, __pyx_t_6); __pyx_t_6++; if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 747, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + #endif + } + } else { + __pyx_t_8 = __pyx_t_7(__pyx_t_2); + if (unlikely(!__pyx_t_8)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(0, 747, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_8); + } + __Pyx_XDECREF_SET(__pyx_v_index, __pyx_t_8); + __pyx_t_8 = 0; + __pyx_v_dim = __pyx_t_5; + __pyx_t_5 = (__pyx_t_5 + 1); + + /* "View.MemoryView":748 + * + * for dim, index in enumerate(indices): + * if PyIndex_Check(index): # <<<<<<<<<<<<<< + * cindex = index + * slice_memviewslice( + */ + __pyx_t_1 = (PyIndex_Check(__pyx_v_index) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":749 + * for dim, index in enumerate(indices): + * if PyIndex_Check(index): + * cindex = index # <<<<<<<<<<<<<< + * slice_memviewslice( + * p_dst, p_src.shape[dim], p_src.strides[dim], p_src.suboffsets[dim], + */ + __pyx_t_9 = __Pyx_PyIndex_AsSsize_t(__pyx_v_index); if (unlikely((__pyx_t_9 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 749, __pyx_L1_error) + __pyx_v_cindex = __pyx_t_9; + + /* "View.MemoryView":750 + * if PyIndex_Check(index): + * cindex = index + * slice_memviewslice( # <<<<<<<<<<<<<< + * p_dst, p_src.shape[dim], p_src.strides[dim], p_src.suboffsets[dim], + * dim, new_ndim, p_suboffset_dim, + */ + __pyx_t_10 = __pyx_memoryview_slice_memviewslice(__pyx_v_p_dst, (__pyx_v_p_src->shape[__pyx_v_dim]), (__pyx_v_p_src->strides[__pyx_v_dim]), (__pyx_v_p_src->suboffsets[__pyx_v_dim]), __pyx_v_dim, __pyx_v_new_ndim, __pyx_v_p_suboffset_dim, __pyx_v_cindex, 0, 0, 0, 0, 0, 0); if (unlikely(__pyx_t_10 == ((int)-1))) __PYX_ERR(0, 750, __pyx_L1_error) + + /* "View.MemoryView":748 + * + * for dim, index in enumerate(indices): + * if PyIndex_Check(index): # <<<<<<<<<<<<<< + * cindex = index + * slice_memviewslice( + */ + goto __pyx_L6; + } + + /* "View.MemoryView":756 + * 0, 0, 0, # have_{start,stop,step} + * False) + * elif index is None: # <<<<<<<<<<<<<< + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 + */ + __pyx_t_1 = (__pyx_v_index == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":757 + * False) + * elif index is None: + * p_dst.shape[new_ndim] = 1 # <<<<<<<<<<<<<< + * p_dst.strides[new_ndim] = 0 + * p_dst.suboffsets[new_ndim] = -1 + */ + (__pyx_v_p_dst->shape[__pyx_v_new_ndim]) = 1; + + /* "View.MemoryView":758 + * elif index is None: + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 # <<<<<<<<<<<<<< + * p_dst.suboffsets[new_ndim] = -1 + * new_ndim += 1 + */ + (__pyx_v_p_dst->strides[__pyx_v_new_ndim]) = 0; + + /* "View.MemoryView":759 + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 + * p_dst.suboffsets[new_ndim] = -1 # <<<<<<<<<<<<<< + * new_ndim += 1 + * else: + */ + (__pyx_v_p_dst->suboffsets[__pyx_v_new_ndim]) = -1L; + + /* "View.MemoryView":760 + * p_dst.strides[new_ndim] = 0 + * p_dst.suboffsets[new_ndim] = -1 + * new_ndim += 1 # <<<<<<<<<<<<<< + * else: + * start = index.start or 0 + */ + __pyx_v_new_ndim = (__pyx_v_new_ndim + 1); + + /* "View.MemoryView":756 + * 0, 0, 0, # have_{start,stop,step} + * False) + * elif index is None: # <<<<<<<<<<<<<< + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 + */ + goto __pyx_L6; + } + + /* "View.MemoryView":762 + * new_ndim += 1 + * else: + * start = index.start or 0 # <<<<<<<<<<<<<< + * stop = index.stop or 0 + * step = index.step or 0 + */ + /*else*/ { + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_start); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 762, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_t_8); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(0, 762, __pyx_L1_error) + if (!__pyx_t_1) { + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } else { + __pyx_t_11 = __Pyx_PyIndex_AsSsize_t(__pyx_t_8); if (unlikely((__pyx_t_11 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 762, __pyx_L1_error) + __pyx_t_9 = __pyx_t_11; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L7_bool_binop_done; + } + __pyx_t_9 = 0; + __pyx_L7_bool_binop_done:; + __pyx_v_start = __pyx_t_9; + + /* "View.MemoryView":763 + * else: + * start = index.start or 0 + * stop = index.stop or 0 # <<<<<<<<<<<<<< + * step = index.step or 0 + * + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_stop); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 763, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_t_8); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(0, 763, __pyx_L1_error) + if (!__pyx_t_1) { + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } else { + __pyx_t_11 = __Pyx_PyIndex_AsSsize_t(__pyx_t_8); if (unlikely((__pyx_t_11 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 763, __pyx_L1_error) + __pyx_t_9 = __pyx_t_11; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L9_bool_binop_done; + } + __pyx_t_9 = 0; + __pyx_L9_bool_binop_done:; + __pyx_v_stop = __pyx_t_9; + + /* "View.MemoryView":764 + * start = index.start or 0 + * stop = index.stop or 0 + * step = index.step or 0 # <<<<<<<<<<<<<< + * + * have_start = index.start is not None + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_step); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 764, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_t_8); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(0, 764, __pyx_L1_error) + if (!__pyx_t_1) { + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } else { + __pyx_t_11 = __Pyx_PyIndex_AsSsize_t(__pyx_t_8); if (unlikely((__pyx_t_11 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 764, __pyx_L1_error) + __pyx_t_9 = __pyx_t_11; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L11_bool_binop_done; + } + __pyx_t_9 = 0; + __pyx_L11_bool_binop_done:; + __pyx_v_step = __pyx_t_9; + + /* "View.MemoryView":766 + * step = index.step or 0 + * + * have_start = index.start is not None # <<<<<<<<<<<<<< + * have_stop = index.stop is not None + * have_step = index.step is not None + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_start); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 766, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = (__pyx_t_8 != Py_None); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_v_have_start = __pyx_t_1; + + /* "View.MemoryView":767 + * + * have_start = index.start is not None + * have_stop = index.stop is not None # <<<<<<<<<<<<<< + * have_step = index.step is not None + * + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_stop); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 767, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = (__pyx_t_8 != Py_None); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_v_have_stop = __pyx_t_1; + + /* "View.MemoryView":768 + * have_start = index.start is not None + * have_stop = index.stop is not None + * have_step = index.step is not None # <<<<<<<<<<<<<< + * + * slice_memviewslice( + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_step); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 768, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = (__pyx_t_8 != Py_None); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_v_have_step = __pyx_t_1; + + /* "View.MemoryView":770 + * have_step = index.step is not None + * + * slice_memviewslice( # <<<<<<<<<<<<<< + * p_dst, p_src.shape[dim], p_src.strides[dim], p_src.suboffsets[dim], + * dim, new_ndim, p_suboffset_dim, + */ + __pyx_t_10 = __pyx_memoryview_slice_memviewslice(__pyx_v_p_dst, (__pyx_v_p_src->shape[__pyx_v_dim]), (__pyx_v_p_src->strides[__pyx_v_dim]), (__pyx_v_p_src->suboffsets[__pyx_v_dim]), __pyx_v_dim, __pyx_v_new_ndim, __pyx_v_p_suboffset_dim, __pyx_v_start, __pyx_v_stop, __pyx_v_step, __pyx_v_have_start, __pyx_v_have_stop, __pyx_v_have_step, 1); if (unlikely(__pyx_t_10 == ((int)-1))) __PYX_ERR(0, 770, __pyx_L1_error) + + /* "View.MemoryView":776 + * have_start, have_stop, have_step, + * True) + * new_ndim += 1 # <<<<<<<<<<<<<< + * + * if isinstance(memview, _memoryviewslice): + */ + __pyx_v_new_ndim = (__pyx_v_new_ndim + 1); + } + __pyx_L6:; + + /* "View.MemoryView":747 + * cdef bint have_start, have_stop, have_step + * + * for dim, index in enumerate(indices): # <<<<<<<<<<<<<< + * if PyIndex_Check(index): + * cindex = index + */ + } + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":778 + * new_ndim += 1 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":779 + * + * if isinstance(memview, _memoryviewslice): + * return memoryview_fromslice(dst, new_ndim, # <<<<<<<<<<<<<< + * memviewsliceobj.to_object_func, + * memviewsliceobj.to_dtype_func, + */ + __Pyx_XDECREF((PyObject *)__pyx_r); + + /* "View.MemoryView":780 + * if isinstance(memview, _memoryviewslice): + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, # <<<<<<<<<<<<<< + * memviewsliceobj.to_dtype_func, + * memview.dtype_is_object) + */ + if (unlikely(!__pyx_v_memviewsliceobj)) { __Pyx_RaiseUnboundLocalError("memviewsliceobj"); __PYX_ERR(0, 780, __pyx_L1_error) } + + /* "View.MemoryView":781 + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, + * memviewsliceobj.to_dtype_func, # <<<<<<<<<<<<<< + * memview.dtype_is_object) + * else: + */ + if (unlikely(!__pyx_v_memviewsliceobj)) { __Pyx_RaiseUnboundLocalError("memviewsliceobj"); __PYX_ERR(0, 781, __pyx_L1_error) } + + /* "View.MemoryView":779 + * + * if isinstance(memview, _memoryviewslice): + * return memoryview_fromslice(dst, new_ndim, # <<<<<<<<<<<<<< + * memviewsliceobj.to_object_func, + * memviewsliceobj.to_dtype_func, + */ + __pyx_t_2 = __pyx_memoryview_fromslice(__pyx_v_dst, __pyx_v_new_ndim, __pyx_v_memviewsliceobj->to_object_func, __pyx_v_memviewsliceobj->to_dtype_func, __pyx_v_memview->dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 779, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (!(likely(((__pyx_t_2) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_2, __pyx_memoryview_type))))) __PYX_ERR(0, 779, __pyx_L1_error) + __pyx_r = ((struct __pyx_memoryview_obj *)__pyx_t_2); + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":778 + * new_ndim += 1 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, + */ + } + + /* "View.MemoryView":784 + * memview.dtype_is_object) + * else: + * return memoryview_fromslice(dst, new_ndim, NULL, NULL, # <<<<<<<<<<<<<< + * memview.dtype_is_object) + * + */ + /*else*/ { + __Pyx_XDECREF((PyObject *)__pyx_r); + + /* "View.MemoryView":785 + * else: + * return memoryview_fromslice(dst, new_ndim, NULL, NULL, + * memview.dtype_is_object) # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = __pyx_memoryview_fromslice(__pyx_v_dst, __pyx_v_new_ndim, NULL, NULL, __pyx_v_memview->dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 784, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + + /* "View.MemoryView":784 + * memview.dtype_is_object) + * else: + * return memoryview_fromslice(dst, new_ndim, NULL, NULL, # <<<<<<<<<<<<<< + * memview.dtype_is_object) + * + */ + if (!(likely(((__pyx_t_2) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_2, __pyx_memoryview_type))))) __PYX_ERR(0, 784, __pyx_L1_error) + __pyx_r = ((struct __pyx_memoryview_obj *)__pyx_t_2); + __pyx_t_2 = 0; + goto __pyx_L0; + } + + /* "View.MemoryView":711 + * + * @cname('__pyx_memview_slice') + * cdef memoryview memview_slice(memoryview memview, object indices): # <<<<<<<<<<<<<< + * cdef int new_ndim = 0, suboffset_dim = -1, dim + * cdef bint negative_step + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("View.MemoryView.memview_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_memviewsliceobj); + __Pyx_XDECREF(__pyx_v_index); + __Pyx_XGIVEREF((PyObject *)__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":793 + * + * @cname('__pyx_memoryview_slice_memviewslice') + * cdef int slice_memviewslice( # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * Py_ssize_t shape, Py_ssize_t stride, Py_ssize_t suboffset, + */ + +static int __pyx_memoryview_slice_memviewslice(__Pyx_memviewslice *__pyx_v_dst, Py_ssize_t __pyx_v_shape, Py_ssize_t __pyx_v_stride, Py_ssize_t __pyx_v_suboffset, int __pyx_v_dim, int __pyx_v_new_ndim, int *__pyx_v_suboffset_dim, Py_ssize_t __pyx_v_start, Py_ssize_t __pyx_v_stop, Py_ssize_t __pyx_v_step, int __pyx_v_have_start, int __pyx_v_have_stop, int __pyx_v_have_step, int __pyx_v_is_slice) { + Py_ssize_t __pyx_v_new_shape; + int __pyx_v_negative_step; + int __pyx_r; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":813 + * cdef bint negative_step + * + * if not is_slice: # <<<<<<<<<<<<<< + * + * if start < 0: + */ + __pyx_t_1 = (!__pyx_v_is_slice); + if (__pyx_t_1) { + + /* "View.MemoryView":815 + * if not is_slice: + * + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if not 0 <= start < shape: + */ + __pyx_t_1 = (__pyx_v_start < 0); + if (__pyx_t_1) { + + /* "View.MemoryView":816 + * + * if start < 0: + * start += shape # <<<<<<<<<<<<<< + * if not 0 <= start < shape: + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) + */ + __pyx_v_start = (__pyx_v_start + __pyx_v_shape); + + /* "View.MemoryView":815 + * if not is_slice: + * + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if not 0 <= start < shape: + */ + } + + /* "View.MemoryView":817 + * if start < 0: + * start += shape + * if not 0 <= start < shape: # <<<<<<<<<<<<<< + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) + * else: + */ + __pyx_t_1 = (0 <= __pyx_v_start); + if (__pyx_t_1) { + __pyx_t_1 = (__pyx_v_start < __pyx_v_shape); + } + __pyx_t_2 = (!__pyx_t_1); + if (__pyx_t_2) { + + /* "View.MemoryView":818 + * start += shape + * if not 0 <= start < shape: + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) # <<<<<<<<<<<<<< + * else: + * + */ + __pyx_t_3 = __pyx_memoryview_err_dim(PyExc_IndexError, __pyx_kp_s_Index_out_of_bounds_axis_d, __pyx_v_dim); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(0, 818, __pyx_L1_error) + + /* "View.MemoryView":817 + * if start < 0: + * start += shape + * if not 0 <= start < shape: # <<<<<<<<<<<<<< + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) + * else: + */ + } + + /* "View.MemoryView":813 + * cdef bint negative_step + * + * if not is_slice: # <<<<<<<<<<<<<< + * + * if start < 0: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":821 + * else: + * + * if have_step: # <<<<<<<<<<<<<< + * negative_step = step < 0 + * if step == 0: + */ + /*else*/ { + __pyx_t_2 = (__pyx_v_have_step != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":822 + * + * if have_step: + * negative_step = step < 0 # <<<<<<<<<<<<<< + * if step == 0: + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + */ + __pyx_v_negative_step = (__pyx_v_step < 0); + + /* "View.MemoryView":823 + * if have_step: + * negative_step = step < 0 + * if step == 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + * else: + */ + __pyx_t_2 = (__pyx_v_step == 0); + if (__pyx_t_2) { + + /* "View.MemoryView":824 + * negative_step = step < 0 + * if step == 0: + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) # <<<<<<<<<<<<<< + * else: + * negative_step = False + */ + __pyx_t_3 = __pyx_memoryview_err_dim(PyExc_ValueError, __pyx_kp_s_Step_may_not_be_zero_axis_d, __pyx_v_dim); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(0, 824, __pyx_L1_error) + + /* "View.MemoryView":823 + * if have_step: + * negative_step = step < 0 + * if step == 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + * else: + */ + } + + /* "View.MemoryView":821 + * else: + * + * if have_step: # <<<<<<<<<<<<<< + * negative_step = step < 0 + * if step == 0: + */ + goto __pyx_L6; + } + + /* "View.MemoryView":826 + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + * else: + * negative_step = False # <<<<<<<<<<<<<< + * step = 1 + * + */ + /*else*/ { + __pyx_v_negative_step = 0; + + /* "View.MemoryView":827 + * else: + * negative_step = False + * step = 1 # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_step = 1; + } + __pyx_L6:; + + /* "View.MemoryView":830 + * + * + * if have_start: # <<<<<<<<<<<<<< + * if start < 0: + * start += shape + */ + __pyx_t_2 = (__pyx_v_have_start != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":831 + * + * if have_start: + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if start < 0: + */ + __pyx_t_2 = (__pyx_v_start < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":832 + * if have_start: + * if start < 0: + * start += shape # <<<<<<<<<<<<<< + * if start < 0: + * start = 0 + */ + __pyx_v_start = (__pyx_v_start + __pyx_v_shape); + + /* "View.MemoryView":833 + * if start < 0: + * start += shape + * if start < 0: # <<<<<<<<<<<<<< + * start = 0 + * elif start >= shape: + */ + __pyx_t_2 = (__pyx_v_start < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":834 + * start += shape + * if start < 0: + * start = 0 # <<<<<<<<<<<<<< + * elif start >= shape: + * if negative_step: + */ + __pyx_v_start = 0; + + /* "View.MemoryView":833 + * if start < 0: + * start += shape + * if start < 0: # <<<<<<<<<<<<<< + * start = 0 + * elif start >= shape: + */ + } + + /* "View.MemoryView":831 + * + * if have_start: + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if start < 0: + */ + goto __pyx_L9; + } + + /* "View.MemoryView":835 + * if start < 0: + * start = 0 + * elif start >= shape: # <<<<<<<<<<<<<< + * if negative_step: + * start = shape - 1 + */ + __pyx_t_2 = (__pyx_v_start >= __pyx_v_shape); + if (__pyx_t_2) { + + /* "View.MemoryView":836 + * start = 0 + * elif start >= shape: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + if (__pyx_v_negative_step) { + + /* "View.MemoryView":837 + * elif start >= shape: + * if negative_step: + * start = shape - 1 # <<<<<<<<<<<<<< + * else: + * start = shape + */ + __pyx_v_start = (__pyx_v_shape - 1); + + /* "View.MemoryView":836 + * start = 0 + * elif start >= shape: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + goto __pyx_L11; + } + + /* "View.MemoryView":839 + * start = shape - 1 + * else: + * start = shape # <<<<<<<<<<<<<< + * else: + * if negative_step: + */ + /*else*/ { + __pyx_v_start = __pyx_v_shape; + } + __pyx_L11:; + + /* "View.MemoryView":835 + * if start < 0: + * start = 0 + * elif start >= shape: # <<<<<<<<<<<<<< + * if negative_step: + * start = shape - 1 + */ + } + __pyx_L9:; + + /* "View.MemoryView":830 + * + * + * if have_start: # <<<<<<<<<<<<<< + * if start < 0: + * start += shape + */ + goto __pyx_L8; + } + + /* "View.MemoryView":841 + * start = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + /*else*/ { + if (__pyx_v_negative_step) { + + /* "View.MemoryView":842 + * else: + * if negative_step: + * start = shape - 1 # <<<<<<<<<<<<<< + * else: + * start = 0 + */ + __pyx_v_start = (__pyx_v_shape - 1); + + /* "View.MemoryView":841 + * start = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + goto __pyx_L12; + } + + /* "View.MemoryView":844 + * start = shape - 1 + * else: + * start = 0 # <<<<<<<<<<<<<< + * + * if have_stop: + */ + /*else*/ { + __pyx_v_start = 0; + } + __pyx_L12:; + } + __pyx_L8:; + + /* "View.MemoryView":846 + * start = 0 + * + * if have_stop: # <<<<<<<<<<<<<< + * if stop < 0: + * stop += shape + */ + __pyx_t_2 = (__pyx_v_have_stop != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":847 + * + * if have_stop: + * if stop < 0: # <<<<<<<<<<<<<< + * stop += shape + * if stop < 0: + */ + __pyx_t_2 = (__pyx_v_stop < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":848 + * if have_stop: + * if stop < 0: + * stop += shape # <<<<<<<<<<<<<< + * if stop < 0: + * stop = 0 + */ + __pyx_v_stop = (__pyx_v_stop + __pyx_v_shape); + + /* "View.MemoryView":849 + * if stop < 0: + * stop += shape + * if stop < 0: # <<<<<<<<<<<<<< + * stop = 0 + * elif stop > shape: + */ + __pyx_t_2 = (__pyx_v_stop < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":850 + * stop += shape + * if stop < 0: + * stop = 0 # <<<<<<<<<<<<<< + * elif stop > shape: + * stop = shape + */ + __pyx_v_stop = 0; + + /* "View.MemoryView":849 + * if stop < 0: + * stop += shape + * if stop < 0: # <<<<<<<<<<<<<< + * stop = 0 + * elif stop > shape: + */ + } + + /* "View.MemoryView":847 + * + * if have_stop: + * if stop < 0: # <<<<<<<<<<<<<< + * stop += shape + * if stop < 0: + */ + goto __pyx_L14; + } + + /* "View.MemoryView":851 + * if stop < 0: + * stop = 0 + * elif stop > shape: # <<<<<<<<<<<<<< + * stop = shape + * else: + */ + __pyx_t_2 = (__pyx_v_stop > __pyx_v_shape); + if (__pyx_t_2) { + + /* "View.MemoryView":852 + * stop = 0 + * elif stop > shape: + * stop = shape # <<<<<<<<<<<<<< + * else: + * if negative_step: + */ + __pyx_v_stop = __pyx_v_shape; + + /* "View.MemoryView":851 + * if stop < 0: + * stop = 0 + * elif stop > shape: # <<<<<<<<<<<<<< + * stop = shape + * else: + */ + } + __pyx_L14:; + + /* "View.MemoryView":846 + * start = 0 + * + * if have_stop: # <<<<<<<<<<<<<< + * if stop < 0: + * stop += shape + */ + goto __pyx_L13; + } + + /* "View.MemoryView":854 + * stop = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * stop = -1 + * else: + */ + /*else*/ { + if (__pyx_v_negative_step) { + + /* "View.MemoryView":855 + * else: + * if negative_step: + * stop = -1 # <<<<<<<<<<<<<< + * else: + * stop = shape + */ + __pyx_v_stop = -1L; + + /* "View.MemoryView":854 + * stop = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * stop = -1 + * else: + */ + goto __pyx_L16; + } + + /* "View.MemoryView":857 + * stop = -1 + * else: + * stop = shape # <<<<<<<<<<<<<< + * + * + */ + /*else*/ { + __pyx_v_stop = __pyx_v_shape; + } + __pyx_L16:; + } + __pyx_L13:; + + /* "View.MemoryView":861 + * + * with cython.cdivision(True): + * new_shape = (stop - start) // step # <<<<<<<<<<<<<< + * + * if (stop - start) - step * new_shape: + */ + __pyx_v_new_shape = ((__pyx_v_stop - __pyx_v_start) / __pyx_v_step); + + /* "View.MemoryView":863 + * new_shape = (stop - start) // step + * + * if (stop - start) - step * new_shape: # <<<<<<<<<<<<<< + * new_shape += 1 + * + */ + __pyx_t_2 = (((__pyx_v_stop - __pyx_v_start) - (__pyx_v_step * __pyx_v_new_shape)) != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":864 + * + * if (stop - start) - step * new_shape: + * new_shape += 1 # <<<<<<<<<<<<<< + * + * if new_shape < 0: + */ + __pyx_v_new_shape = (__pyx_v_new_shape + 1); + + /* "View.MemoryView":863 + * new_shape = (stop - start) // step + * + * if (stop - start) - step * new_shape: # <<<<<<<<<<<<<< + * new_shape += 1 + * + */ + } + + /* "View.MemoryView":866 + * new_shape += 1 + * + * if new_shape < 0: # <<<<<<<<<<<<<< + * new_shape = 0 + * + */ + __pyx_t_2 = (__pyx_v_new_shape < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":867 + * + * if new_shape < 0: + * new_shape = 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_new_shape = 0; + + /* "View.MemoryView":866 + * new_shape += 1 + * + * if new_shape < 0: # <<<<<<<<<<<<<< + * new_shape = 0 + * + */ + } + + /* "View.MemoryView":870 + * + * + * dst.strides[new_ndim] = stride * step # <<<<<<<<<<<<<< + * dst.shape[new_ndim] = new_shape + * dst.suboffsets[new_ndim] = suboffset + */ + (__pyx_v_dst->strides[__pyx_v_new_ndim]) = (__pyx_v_stride * __pyx_v_step); + + /* "View.MemoryView":871 + * + * dst.strides[new_ndim] = stride * step + * dst.shape[new_ndim] = new_shape # <<<<<<<<<<<<<< + * dst.suboffsets[new_ndim] = suboffset + * + */ + (__pyx_v_dst->shape[__pyx_v_new_ndim]) = __pyx_v_new_shape; + + /* "View.MemoryView":872 + * dst.strides[new_ndim] = stride * step + * dst.shape[new_ndim] = new_shape + * dst.suboffsets[new_ndim] = suboffset # <<<<<<<<<<<<<< + * + * + */ + (__pyx_v_dst->suboffsets[__pyx_v_new_ndim]) = __pyx_v_suboffset; + } + __pyx_L3:; + + /* "View.MemoryView":875 + * + * + * if suboffset_dim[0] < 0: # <<<<<<<<<<<<<< + * dst.data += start * stride + * else: + */ + __pyx_t_2 = ((__pyx_v_suboffset_dim[0]) < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":876 + * + * if suboffset_dim[0] < 0: + * dst.data += start * stride # <<<<<<<<<<<<<< + * else: + * dst.suboffsets[suboffset_dim[0]] += start * stride + */ + __pyx_v_dst->data = (__pyx_v_dst->data + (__pyx_v_start * __pyx_v_stride)); + + /* "View.MemoryView":875 + * + * + * if suboffset_dim[0] < 0: # <<<<<<<<<<<<<< + * dst.data += start * stride + * else: + */ + goto __pyx_L19; + } + + /* "View.MemoryView":878 + * dst.data += start * stride + * else: + * dst.suboffsets[suboffset_dim[0]] += start * stride # <<<<<<<<<<<<<< + * + * if suboffset >= 0: + */ + /*else*/ { + __pyx_t_3 = (__pyx_v_suboffset_dim[0]); + (__pyx_v_dst->suboffsets[__pyx_t_3]) = ((__pyx_v_dst->suboffsets[__pyx_t_3]) + (__pyx_v_start * __pyx_v_stride)); + } + __pyx_L19:; + + /* "View.MemoryView":880 + * dst.suboffsets[suboffset_dim[0]] += start * stride + * + * if suboffset >= 0: # <<<<<<<<<<<<<< + * if not is_slice: + * if new_ndim == 0: + */ + __pyx_t_2 = (__pyx_v_suboffset >= 0); + if (__pyx_t_2) { + + /* "View.MemoryView":881 + * + * if suboffset >= 0: + * if not is_slice: # <<<<<<<<<<<<<< + * if new_ndim == 0: + * dst.data = ( dst.data)[0] + suboffset + */ + __pyx_t_2 = (!__pyx_v_is_slice); + if (__pyx_t_2) { + + /* "View.MemoryView":882 + * if suboffset >= 0: + * if not is_slice: + * if new_ndim == 0: # <<<<<<<<<<<<<< + * dst.data = ( dst.data)[0] + suboffset + * else: + */ + __pyx_t_2 = (__pyx_v_new_ndim == 0); + if (__pyx_t_2) { + + /* "View.MemoryView":883 + * if not is_slice: + * if new_ndim == 0: + * dst.data = ( dst.data)[0] + suboffset # <<<<<<<<<<<<<< + * else: + * _err_dim(PyExc_IndexError, "All dimensions preceding dimension %d " + */ + __pyx_v_dst->data = ((((char **)__pyx_v_dst->data)[0]) + __pyx_v_suboffset); + + /* "View.MemoryView":882 + * if suboffset >= 0: + * if not is_slice: + * if new_ndim == 0: # <<<<<<<<<<<<<< + * dst.data = ( dst.data)[0] + suboffset + * else: + */ + goto __pyx_L22; + } + + /* "View.MemoryView":885 + * dst.data = ( dst.data)[0] + suboffset + * else: + * _err_dim(PyExc_IndexError, "All dimensions preceding dimension %d " # <<<<<<<<<<<<<< + * "must be indexed and not sliced", dim) + * else: + */ + /*else*/ { + + /* "View.MemoryView":886 + * else: + * _err_dim(PyExc_IndexError, "All dimensions preceding dimension %d " + * "must be indexed and not sliced", dim) # <<<<<<<<<<<<<< + * else: + * suboffset_dim[0] = new_ndim + */ + __pyx_t_3 = __pyx_memoryview_err_dim(PyExc_IndexError, __pyx_kp_s_All_dimensions_preceding_dimensi, __pyx_v_dim); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(0, 885, __pyx_L1_error) + } + __pyx_L22:; + + /* "View.MemoryView":881 + * + * if suboffset >= 0: + * if not is_slice: # <<<<<<<<<<<<<< + * if new_ndim == 0: + * dst.data = ( dst.data)[0] + suboffset + */ + goto __pyx_L21; + } + + /* "View.MemoryView":888 + * "must be indexed and not sliced", dim) + * else: + * suboffset_dim[0] = new_ndim # <<<<<<<<<<<<<< + * + * return 0 + */ + /*else*/ { + (__pyx_v_suboffset_dim[0]) = __pyx_v_new_ndim; + } + __pyx_L21:; + + /* "View.MemoryView":880 + * dst.suboffsets[suboffset_dim[0]] += start * stride + * + * if suboffset >= 0: # <<<<<<<<<<<<<< + * if not is_slice: + * if new_ndim == 0: + */ + } + + /* "View.MemoryView":890 + * suboffset_dim[0] = new_ndim + * + * return 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":793 + * + * @cname('__pyx_memoryview_slice_memviewslice') + * cdef int slice_memviewslice( # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * Py_ssize_t shape, Py_ssize_t stride, Py_ssize_t suboffset, + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.slice_memviewslice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":896 + * + * @cname('__pyx_pybuffer_index') + * cdef char *pybuffer_index(Py_buffer *view, char *bufp, Py_ssize_t index, # <<<<<<<<<<<<<< + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 + */ + +static char *__pyx_pybuffer_index(Py_buffer *__pyx_v_view, char *__pyx_v_bufp, Py_ssize_t __pyx_v_index, Py_ssize_t __pyx_v_dim) { + Py_ssize_t __pyx_v_shape; + Py_ssize_t __pyx_v_stride; + Py_ssize_t __pyx_v_suboffset; + Py_ssize_t __pyx_v_itemsize; + char *__pyx_v_resultp; + char *__pyx_r; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + Py_UCS4 __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("pybuffer_index", 1); + + /* "View.MemoryView":898 + * cdef char *pybuffer_index(Py_buffer *view, char *bufp, Py_ssize_t index, + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 # <<<<<<<<<<<<<< + * cdef Py_ssize_t itemsize = view.itemsize + * cdef char *resultp + */ + __pyx_v_suboffset = -1L; + + /* "View.MemoryView":899 + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 + * cdef Py_ssize_t itemsize = view.itemsize # <<<<<<<<<<<<<< + * cdef char *resultp + * + */ + __pyx_t_1 = __pyx_v_view->itemsize; + __pyx_v_itemsize = __pyx_t_1; + + /* "View.MemoryView":902 + * cdef char *resultp + * + * if view.ndim == 0: # <<<<<<<<<<<<<< + * shape = view.len // itemsize + * stride = itemsize + */ + __pyx_t_2 = (__pyx_v_view->ndim == 0); + if (__pyx_t_2) { + + /* "View.MemoryView":903 + * + * if view.ndim == 0: + * shape = view.len // itemsize # <<<<<<<<<<<<<< + * stride = itemsize + * else: + */ + if (unlikely(__pyx_v_itemsize == 0)) { + PyErr_SetString(PyExc_ZeroDivisionError, "integer division or modulo by zero"); + __PYX_ERR(0, 903, __pyx_L1_error) + } + else if (sizeof(Py_ssize_t) == sizeof(long) && (!(((Py_ssize_t)-1) > 0)) && unlikely(__pyx_v_itemsize == (Py_ssize_t)-1) && unlikely(__Pyx_UNARY_NEG_WOULD_OVERFLOW(__pyx_v_view->len))) { + PyErr_SetString(PyExc_OverflowError, "value too large to perform division"); + __PYX_ERR(0, 903, __pyx_L1_error) + } + __pyx_v_shape = __Pyx_div_Py_ssize_t(__pyx_v_view->len, __pyx_v_itemsize); + + /* "View.MemoryView":904 + * if view.ndim == 0: + * shape = view.len // itemsize + * stride = itemsize # <<<<<<<<<<<<<< + * else: + * shape = view.shape[dim] + */ + __pyx_v_stride = __pyx_v_itemsize; + + /* "View.MemoryView":902 + * cdef char *resultp + * + * if view.ndim == 0: # <<<<<<<<<<<<<< + * shape = view.len // itemsize + * stride = itemsize + */ + goto __pyx_L3; + } + + /* "View.MemoryView":906 + * stride = itemsize + * else: + * shape = view.shape[dim] # <<<<<<<<<<<<<< + * stride = view.strides[dim] + * if view.suboffsets != NULL: + */ + /*else*/ { + __pyx_v_shape = (__pyx_v_view->shape[__pyx_v_dim]); + + /* "View.MemoryView":907 + * else: + * shape = view.shape[dim] + * stride = view.strides[dim] # <<<<<<<<<<<<<< + * if view.suboffsets != NULL: + * suboffset = view.suboffsets[dim] + */ + __pyx_v_stride = (__pyx_v_view->strides[__pyx_v_dim]); + + /* "View.MemoryView":908 + * shape = view.shape[dim] + * stride = view.strides[dim] + * if view.suboffsets != NULL: # <<<<<<<<<<<<<< + * suboffset = view.suboffsets[dim] + * + */ + __pyx_t_2 = (__pyx_v_view->suboffsets != NULL); + if (__pyx_t_2) { + + /* "View.MemoryView":909 + * stride = view.strides[dim] + * if view.suboffsets != NULL: + * suboffset = view.suboffsets[dim] # <<<<<<<<<<<<<< + * + * if index < 0: + */ + __pyx_v_suboffset = (__pyx_v_view->suboffsets[__pyx_v_dim]); + + /* "View.MemoryView":908 + * shape = view.shape[dim] + * stride = view.strides[dim] + * if view.suboffsets != NULL: # <<<<<<<<<<<<<< + * suboffset = view.suboffsets[dim] + * + */ + } + } + __pyx_L3:; + + /* "View.MemoryView":911 + * suboffset = view.suboffsets[dim] + * + * if index < 0: # <<<<<<<<<<<<<< + * index += view.shape[dim] + * if index < 0: + */ + __pyx_t_2 = (__pyx_v_index < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":912 + * + * if index < 0: + * index += view.shape[dim] # <<<<<<<<<<<<<< + * if index < 0: + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + */ + __pyx_v_index = (__pyx_v_index + (__pyx_v_view->shape[__pyx_v_dim])); + + /* "View.MemoryView":913 + * if index < 0: + * index += view.shape[dim] + * if index < 0: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + __pyx_t_2 = (__pyx_v_index < 0); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":914 + * index += view.shape[dim] + * if index < 0: + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" # <<<<<<<<<<<<<< + * + * if index >= shape: + */ + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 914, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = 0; + __pyx_t_4 = 127; + __Pyx_INCREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_1 += 37; + __Pyx_GIVEREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_5 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_dim, 0, ' ', 'd'); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 914, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_5); + __Pyx_GIVEREF(__pyx_t_5); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_5); + __pyx_t_5 = 0; + __Pyx_INCREF(__pyx_kp_u__7); + __pyx_t_1 += 1; + __Pyx_GIVEREF(__pyx_kp_u__7); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_kp_u__7); + __pyx_t_5 = __Pyx_PyUnicode_Join(__pyx_t_3, 3, __pyx_t_1, __pyx_t_4); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 914, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_builtin_IndexError, __pyx_t_5, 0, 0); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __PYX_ERR(0, 914, __pyx_L1_error) + + /* "View.MemoryView":913 + * if index < 0: + * index += view.shape[dim] + * if index < 0: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + } + + /* "View.MemoryView":911 + * suboffset = view.suboffsets[dim] + * + * if index < 0: # <<<<<<<<<<<<<< + * index += view.shape[dim] + * if index < 0: + */ + } + + /* "View.MemoryView":916 + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + * if index >= shape: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + __pyx_t_2 = (__pyx_v_index >= __pyx_v_shape); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":917 + * + * if index >= shape: + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" # <<<<<<<<<<<<<< + * + * resultp = bufp + index * stride + */ + __pyx_t_5 = PyTuple_New(3); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 917, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 = 0; + __pyx_t_4 = 127; + __Pyx_INCREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_1 += 37; + __Pyx_GIVEREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_3 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_dim, 0, ' ', 'd'); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 917, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_3); + PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_3); + __pyx_t_3 = 0; + __Pyx_INCREF(__pyx_kp_u__7); + __pyx_t_1 += 1; + __Pyx_GIVEREF(__pyx_kp_u__7); + PyTuple_SET_ITEM(__pyx_t_5, 2, __pyx_kp_u__7); + __pyx_t_3 = __Pyx_PyUnicode_Join(__pyx_t_5, 3, __pyx_t_1, __pyx_t_4); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 917, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_Raise(__pyx_builtin_IndexError, __pyx_t_3, 0, 0); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __PYX_ERR(0, 917, __pyx_L1_error) + + /* "View.MemoryView":916 + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + * if index >= shape: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + } + + /* "View.MemoryView":919 + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + * resultp = bufp + index * stride # <<<<<<<<<<<<<< + * if suboffset >= 0: + * resultp = ( resultp)[0] + suboffset + */ + __pyx_v_resultp = (__pyx_v_bufp + (__pyx_v_index * __pyx_v_stride)); + + /* "View.MemoryView":920 + * + * resultp = bufp + index * stride + * if suboffset >= 0: # <<<<<<<<<<<<<< + * resultp = ( resultp)[0] + suboffset + * + */ + __pyx_t_2 = (__pyx_v_suboffset >= 0); + if (__pyx_t_2) { + + /* "View.MemoryView":921 + * resultp = bufp + index * stride + * if suboffset >= 0: + * resultp = ( resultp)[0] + suboffset # <<<<<<<<<<<<<< + * + * return resultp + */ + __pyx_v_resultp = ((((char **)__pyx_v_resultp)[0]) + __pyx_v_suboffset); + + /* "View.MemoryView":920 + * + * resultp = bufp + index * stride + * if suboffset >= 0: # <<<<<<<<<<<<<< + * resultp = ( resultp)[0] + suboffset + * + */ + } + + /* "View.MemoryView":923 + * resultp = ( resultp)[0] + suboffset + * + * return resultp # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = __pyx_v_resultp; + goto __pyx_L0; + + /* "View.MemoryView":896 + * + * @cname('__pyx_pybuffer_index') + * cdef char *pybuffer_index(Py_buffer *view, char *bufp, Py_ssize_t index, # <<<<<<<<<<<<<< + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.pybuffer_index", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":929 + * + * @cname('__pyx_memslice_transpose') + * cdef int transpose_memslice(__Pyx_memviewslice *memslice) except -1 nogil: # <<<<<<<<<<<<<< + * cdef int ndim = memslice.memview.view.ndim + * + */ + +static int __pyx_memslice_transpose(__Pyx_memviewslice *__pyx_v_memslice) { + int __pyx_v_ndim; + Py_ssize_t *__pyx_v_shape; + Py_ssize_t *__pyx_v_strides; + int __pyx_v_i; + int __pyx_v_j; + int __pyx_r; + int __pyx_t_1; + Py_ssize_t *__pyx_t_2; + long __pyx_t_3; + long __pyx_t_4; + Py_ssize_t __pyx_t_5; + Py_ssize_t __pyx_t_6; + int __pyx_t_7; + int __pyx_t_8; + int __pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":930 + * @cname('__pyx_memslice_transpose') + * cdef int transpose_memslice(__Pyx_memviewslice *memslice) except -1 nogil: + * cdef int ndim = memslice.memview.view.ndim # <<<<<<<<<<<<<< + * + * cdef Py_ssize_t *shape = memslice.shape + */ + __pyx_t_1 = __pyx_v_memslice->memview->view.ndim; + __pyx_v_ndim = __pyx_t_1; + + /* "View.MemoryView":932 + * cdef int ndim = memslice.memview.view.ndim + * + * cdef Py_ssize_t *shape = memslice.shape # <<<<<<<<<<<<<< + * cdef Py_ssize_t *strides = memslice.strides + * + */ + __pyx_t_2 = __pyx_v_memslice->shape; + __pyx_v_shape = __pyx_t_2; + + /* "View.MemoryView":933 + * + * cdef Py_ssize_t *shape = memslice.shape + * cdef Py_ssize_t *strides = memslice.strides # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = __pyx_v_memslice->strides; + __pyx_v_strides = __pyx_t_2; + + /* "View.MemoryView":937 + * + * cdef int i, j + * for i in range(ndim // 2): # <<<<<<<<<<<<<< + * j = ndim - 1 - i + * strides[i], strides[j] = strides[j], strides[i] + */ + __pyx_t_3 = __Pyx_div_long(__pyx_v_ndim, 2); + __pyx_t_4 = __pyx_t_3; + for (__pyx_t_1 = 0; __pyx_t_1 < __pyx_t_4; __pyx_t_1+=1) { + __pyx_v_i = __pyx_t_1; + + /* "View.MemoryView":938 + * cdef int i, j + * for i in range(ndim // 2): + * j = ndim - 1 - i # <<<<<<<<<<<<<< + * strides[i], strides[j] = strides[j], strides[i] + * shape[i], shape[j] = shape[j], shape[i] + */ + __pyx_v_j = ((__pyx_v_ndim - 1) - __pyx_v_i); + + /* "View.MemoryView":939 + * for i in range(ndim // 2): + * j = ndim - 1 - i + * strides[i], strides[j] = strides[j], strides[i] # <<<<<<<<<<<<<< + * shape[i], shape[j] = shape[j], shape[i] + * + */ + __pyx_t_5 = (__pyx_v_strides[__pyx_v_j]); + __pyx_t_6 = (__pyx_v_strides[__pyx_v_i]); + (__pyx_v_strides[__pyx_v_i]) = __pyx_t_5; + (__pyx_v_strides[__pyx_v_j]) = __pyx_t_6; + + /* "View.MemoryView":940 + * j = ndim - 1 - i + * strides[i], strides[j] = strides[j], strides[i] + * shape[i], shape[j] = shape[j], shape[i] # <<<<<<<<<<<<<< + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: + */ + __pyx_t_6 = (__pyx_v_shape[__pyx_v_j]); + __pyx_t_5 = (__pyx_v_shape[__pyx_v_i]); + (__pyx_v_shape[__pyx_v_i]) = __pyx_t_6; + (__pyx_v_shape[__pyx_v_j]) = __pyx_t_5; + + /* "View.MemoryView":942 + * shape[i], shape[j] = shape[j], shape[i] + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: # <<<<<<<<<<<<<< + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") + * + */ + __pyx_t_8 = ((__pyx_v_memslice->suboffsets[__pyx_v_i]) >= 0); + if (!__pyx_t_8) { + } else { + __pyx_t_7 = __pyx_t_8; + goto __pyx_L6_bool_binop_done; + } + __pyx_t_8 = ((__pyx_v_memslice->suboffsets[__pyx_v_j]) >= 0); + __pyx_t_7 = __pyx_t_8; + __pyx_L6_bool_binop_done:; + if (__pyx_t_7) { + + /* "View.MemoryView":943 + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") # <<<<<<<<<<<<<< + * + * return 0 + */ + __pyx_t_9 = __pyx_memoryview_err(PyExc_ValueError, __pyx_kp_s_Cannot_transpose_memoryview_with); if (unlikely(__pyx_t_9 == ((int)-1))) __PYX_ERR(0, 943, __pyx_L1_error) + + /* "View.MemoryView":942 + * shape[i], shape[j] = shape[j], shape[i] + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: # <<<<<<<<<<<<<< + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") + * + */ + } + } + + /* "View.MemoryView":945 + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") + * + * return 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":929 + * + * @cname('__pyx_memslice_transpose') + * cdef int transpose_memslice(__Pyx_memviewslice *memslice) except -1 nogil: # <<<<<<<<<<<<<< + * cdef int ndim = memslice.memview.view.ndim + * + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.transpose_memslice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":963 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + */ + +/* Python wrapper */ +static void __pyx_memoryviewslice___dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_memoryviewslice___dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_memoryviewslice___pyx_pf_15View_dot_MemoryView_16_memoryviewslice___dealloc__(((struct __pyx_memoryviewslice_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_memoryviewslice___pyx_pf_15View_dot_MemoryView_16_memoryviewslice___dealloc__(struct __pyx_memoryviewslice_obj *__pyx_v_self) { + + /* "View.MemoryView":964 + * + * def __dealloc__(self): + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) # <<<<<<<<<<<<<< + * + * cdef convert_item_to_object(self, char *itemp): + */ + __PYX_XCLEAR_MEMVIEW((&__pyx_v_self->from_slice), 1); + + /* "View.MemoryView":963 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + */ + + /* function exit code */ +} + +/* "View.MemoryView":966 + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * if self.to_object_func != NULL: + * return self.to_object_func(itemp) + */ + +static PyObject *__pyx_memoryviewslice_convert_item_to_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("convert_item_to_object", 1); + + /* "View.MemoryView":967 + * + * cdef convert_item_to_object(self, char *itemp): + * if self.to_object_func != NULL: # <<<<<<<<<<<<<< + * return self.to_object_func(itemp) + * else: + */ + __pyx_t_1 = (__pyx_v_self->to_object_func != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":968 + * cdef convert_item_to_object(self, char *itemp): + * if self.to_object_func != NULL: + * return self.to_object_func(itemp) # <<<<<<<<<<<<<< + * else: + * return memoryview.convert_item_to_object(self, itemp) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_v_self->to_object_func(__pyx_v_itemp); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 968, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":967 + * + * cdef convert_item_to_object(self, char *itemp): + * if self.to_object_func != NULL: # <<<<<<<<<<<<<< + * return self.to_object_func(itemp) + * else: + */ + } + + /* "View.MemoryView":970 + * return self.to_object_func(itemp) + * else: + * return memoryview.convert_item_to_object(self, itemp) # <<<<<<<<<<<<<< + * + * cdef assign_item_from_object(self, char *itemp, object value): + */ + /*else*/ { + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_memoryview_convert_item_to_object(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v_itemp); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 970, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + } + + /* "View.MemoryView":966 + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * if self.to_object_func != NULL: + * return self.to_object_func(itemp) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.convert_item_to_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":972 + * return memoryview.convert_item_to_object(self, itemp) + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * if self.to_dtype_func != NULL: + * self.to_dtype_func(itemp, value) + */ + +static PyObject *__pyx_memoryviewslice_assign_item_from_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("assign_item_from_object", 1); + + /* "View.MemoryView":973 + * + * cdef assign_item_from_object(self, char *itemp, object value): + * if self.to_dtype_func != NULL: # <<<<<<<<<<<<<< + * self.to_dtype_func(itemp, value) + * else: + */ + __pyx_t_1 = (__pyx_v_self->to_dtype_func != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":974 + * cdef assign_item_from_object(self, char *itemp, object value): + * if self.to_dtype_func != NULL: + * self.to_dtype_func(itemp, value) # <<<<<<<<<<<<<< + * else: + * memoryview.assign_item_from_object(self, itemp, value) + */ + __pyx_t_2 = __pyx_v_self->to_dtype_func(__pyx_v_itemp, __pyx_v_value); if (unlikely(__pyx_t_2 == ((int)0))) __PYX_ERR(0, 974, __pyx_L1_error) + + /* "View.MemoryView":973 + * + * cdef assign_item_from_object(self, char *itemp, object value): + * if self.to_dtype_func != NULL: # <<<<<<<<<<<<<< + * self.to_dtype_func(itemp, value) + * else: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":976 + * self.to_dtype_func(itemp, value) + * else: + * memoryview.assign_item_from_object(self, itemp, value) # <<<<<<<<<<<<<< + * + * cdef _get_base(self): + */ + /*else*/ { + __pyx_t_3 = __pyx_memoryview_assign_item_from_object(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v_itemp, __pyx_v_value); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 976, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_L3:; + + /* "View.MemoryView":972 + * return memoryview.convert_item_to_object(self, itemp) + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * if self.to_dtype_func != NULL: + * self.to_dtype_func(itemp, value) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.assign_item_from_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":978 + * memoryview.assign_item_from_object(self, itemp, value) + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.from_object + * + */ + +static PyObject *__pyx_memoryviewslice__get_base(struct __pyx_memoryviewslice_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("_get_base", 1); + + /* "View.MemoryView":979 + * + * cdef _get_base(self): + * return self.from_object # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->from_object); + __pyx_r = __pyx_v_self->from_object; + goto __pyx_L0; + + /* "View.MemoryView":978 + * memoryview.assign_item_from_object(self, itemp, value) + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.from_object + * + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryviewslice_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryviewslice_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_memoryviewslice___reduce_cython__(((struct __pyx_memoryviewslice_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryviewslice___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(0, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryviewslice_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryviewslice_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(0, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_memoryviewslice_2__setstate_cython__(((struct __pyx_memoryviewslice_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryviewslice_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(0, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":999 + * + * @cname('__pyx_memoryview_fromslice') + * cdef memoryview_fromslice(__Pyx_memviewslice memviewslice, # <<<<<<<<<<<<<< + * int ndim, + * object (*to_object_func)(char *), + */ + +static PyObject *__pyx_memoryview_fromslice(__Pyx_memviewslice __pyx_v_memviewslice, int __pyx_v_ndim, PyObject *(*__pyx_v_to_object_func)(char *), int (*__pyx_v_to_dtype_func)(char *, PyObject *), int __pyx_v_dtype_is_object) { + struct __pyx_memoryviewslice_obj *__pyx_v_result = 0; + Py_ssize_t __pyx_v_suboffset; + PyObject *__pyx_v_length = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + __Pyx_TypeInfo *__pyx_t_4; + Py_buffer __pyx_t_5; + Py_ssize_t *__pyx_t_6; + Py_ssize_t *__pyx_t_7; + Py_ssize_t *__pyx_t_8; + Py_ssize_t __pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_fromslice", 1); + + /* "View.MemoryView":1007 + * cdef _memoryviewslice result + * + * if memviewslice.memview == Py_None: # <<<<<<<<<<<<<< + * return None + * + */ + __pyx_t_1 = (((PyObject *)__pyx_v_memviewslice.memview) == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":1008 + * + * if memviewslice.memview == Py_None: + * return None # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "View.MemoryView":1007 + * cdef _memoryviewslice result + * + * if memviewslice.memview == Py_None: # <<<<<<<<<<<<<< + * return None + * + */ + } + + /* "View.MemoryView":1013 + * + * + * result = _memoryviewslice.__new__(_memoryviewslice, None, 0, dtype_is_object) # <<<<<<<<<<<<<< + * + * result.from_slice = memviewslice + */ + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_v_dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 1013, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 1013, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(Py_None); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, Py_None)) __PYX_ERR(0, 1013, __pyx_L1_error); + __Pyx_INCREF(__pyx_int_0); + __Pyx_GIVEREF(__pyx_int_0); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_int_0)) __PYX_ERR(0, 1013, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_t_2)) __PYX_ERR(0, 1013, __pyx_L1_error); + __pyx_t_2 = 0; + __pyx_t_2 = ((PyObject *)__pyx_tp_new__memoryviewslice(((PyTypeObject *)__pyx_memoryviewslice_type), __pyx_t_3, NULL)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 1013, __pyx_L1_error) + __Pyx_GOTREF((PyObject *)__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_v_result = ((struct __pyx_memoryviewslice_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":1015 + * result = _memoryviewslice.__new__(_memoryviewslice, None, 0, dtype_is_object) + * + * result.from_slice = memviewslice # <<<<<<<<<<<<<< + * __PYX_INC_MEMVIEW(&memviewslice, 1) + * + */ + __pyx_v_result->from_slice = __pyx_v_memviewslice; + + /* "View.MemoryView":1016 + * + * result.from_slice = memviewslice + * __PYX_INC_MEMVIEW(&memviewslice, 1) # <<<<<<<<<<<<<< + * + * result.from_object = ( memviewslice.memview)._get_base() + */ + __PYX_INC_MEMVIEW((&__pyx_v_memviewslice), 1); + + /* "View.MemoryView":1018 + * __PYX_INC_MEMVIEW(&memviewslice, 1) + * + * result.from_object = ( memviewslice.memview)._get_base() # <<<<<<<<<<<<<< + * result.typeinfo = memviewslice.memview.typeinfo + * + */ + __pyx_t_2 = ((struct __pyx_vtabstruct_memoryview *)((struct __pyx_memoryview_obj *)__pyx_v_memviewslice.memview)->__pyx_vtab)->_get_base(((struct __pyx_memoryview_obj *)__pyx_v_memviewslice.memview)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 1018, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + __Pyx_GOTREF(__pyx_v_result->from_object); + __Pyx_DECREF(__pyx_v_result->from_object); + __pyx_v_result->from_object = __pyx_t_2; + __pyx_t_2 = 0; + + /* "View.MemoryView":1019 + * + * result.from_object = ( memviewslice.memview)._get_base() + * result.typeinfo = memviewslice.memview.typeinfo # <<<<<<<<<<<<<< + * + * result.view = memviewslice.memview.view + */ + __pyx_t_4 = __pyx_v_memviewslice.memview->typeinfo; + __pyx_v_result->__pyx_base.typeinfo = __pyx_t_4; + + /* "View.MemoryView":1021 + * result.typeinfo = memviewslice.memview.typeinfo + * + * result.view = memviewslice.memview.view # <<<<<<<<<<<<<< + * result.view.buf = memviewslice.data + * result.view.ndim = ndim + */ + __pyx_t_5 = __pyx_v_memviewslice.memview->view; + __pyx_v_result->__pyx_base.view = __pyx_t_5; + + /* "View.MemoryView":1022 + * + * result.view = memviewslice.memview.view + * result.view.buf = memviewslice.data # <<<<<<<<<<<<<< + * result.view.ndim = ndim + * (<__pyx_buffer *> &result.view).obj = Py_None + */ + __pyx_v_result->__pyx_base.view.buf = ((void *)__pyx_v_memviewslice.data); + + /* "View.MemoryView":1023 + * result.view = memviewslice.memview.view + * result.view.buf = memviewslice.data + * result.view.ndim = ndim # <<<<<<<<<<<<<< + * (<__pyx_buffer *> &result.view).obj = Py_None + * Py_INCREF(Py_None) + */ + __pyx_v_result->__pyx_base.view.ndim = __pyx_v_ndim; + + /* "View.MemoryView":1024 + * result.view.buf = memviewslice.data + * result.view.ndim = ndim + * (<__pyx_buffer *> &result.view).obj = Py_None # <<<<<<<<<<<<<< + * Py_INCREF(Py_None) + * + */ + ((Py_buffer *)(&__pyx_v_result->__pyx_base.view))->obj = Py_None; + + /* "View.MemoryView":1025 + * result.view.ndim = ndim + * (<__pyx_buffer *> &result.view).obj = Py_None + * Py_INCREF(Py_None) # <<<<<<<<<<<<<< + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: + */ + Py_INCREF(Py_None); + + /* "View.MemoryView":1027 + * Py_INCREF(Py_None) + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: # <<<<<<<<<<<<<< + * result.flags = PyBUF_RECORDS + * else: + */ + __pyx_t_1 = ((((struct __pyx_memoryview_obj *)__pyx_v_memviewslice.memview)->flags & PyBUF_WRITABLE) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":1028 + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: + * result.flags = PyBUF_RECORDS # <<<<<<<<<<<<<< + * else: + * result.flags = PyBUF_RECORDS_RO + */ + __pyx_v_result->__pyx_base.flags = PyBUF_RECORDS; + + /* "View.MemoryView":1027 + * Py_INCREF(Py_None) + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: # <<<<<<<<<<<<<< + * result.flags = PyBUF_RECORDS + * else: + */ + goto __pyx_L4; + } + + /* "View.MemoryView":1030 + * result.flags = PyBUF_RECORDS + * else: + * result.flags = PyBUF_RECORDS_RO # <<<<<<<<<<<<<< + * + * result.view.shape = result.from_slice.shape + */ + /*else*/ { + __pyx_v_result->__pyx_base.flags = PyBUF_RECORDS_RO; + } + __pyx_L4:; + + /* "View.MemoryView":1032 + * result.flags = PyBUF_RECORDS_RO + * + * result.view.shape = result.from_slice.shape # <<<<<<<<<<<<<< + * result.view.strides = result.from_slice.strides + * + */ + __pyx_v_result->__pyx_base.view.shape = ((Py_ssize_t *)__pyx_v_result->from_slice.shape); + + /* "View.MemoryView":1033 + * + * result.view.shape = result.from_slice.shape + * result.view.strides = result.from_slice.strides # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_result->__pyx_base.view.strides = ((Py_ssize_t *)__pyx_v_result->from_slice.strides); + + /* "View.MemoryView":1036 + * + * + * result.view.suboffsets = NULL # <<<<<<<<<<<<<< + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: + */ + __pyx_v_result->__pyx_base.view.suboffsets = NULL; + + /* "View.MemoryView":1037 + * + * result.view.suboffsets = NULL + * for suboffset in result.from_slice.suboffsets[:ndim]: # <<<<<<<<<<<<<< + * if suboffset >= 0: + * result.view.suboffsets = result.from_slice.suboffsets + */ + __pyx_t_7 = (__pyx_v_result->from_slice.suboffsets + __pyx_v_ndim); + for (__pyx_t_8 = __pyx_v_result->from_slice.suboffsets; __pyx_t_8 < __pyx_t_7; __pyx_t_8++) { + __pyx_t_6 = __pyx_t_8; + __pyx_v_suboffset = (__pyx_t_6[0]); + + /* "View.MemoryView":1038 + * result.view.suboffsets = NULL + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * result.view.suboffsets = result.from_slice.suboffsets + * break + */ + __pyx_t_1 = (__pyx_v_suboffset >= 0); + if (__pyx_t_1) { + + /* "View.MemoryView":1039 + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: + * result.view.suboffsets = result.from_slice.suboffsets # <<<<<<<<<<<<<< + * break + * + */ + __pyx_v_result->__pyx_base.view.suboffsets = ((Py_ssize_t *)__pyx_v_result->from_slice.suboffsets); + + /* "View.MemoryView":1040 + * if suboffset >= 0: + * result.view.suboffsets = result.from_slice.suboffsets + * break # <<<<<<<<<<<<<< + * + * result.view.len = result.view.itemsize + */ + goto __pyx_L6_break; + + /* "View.MemoryView":1038 + * result.view.suboffsets = NULL + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * result.view.suboffsets = result.from_slice.suboffsets + * break + */ + } + } + __pyx_L6_break:; + + /* "View.MemoryView":1042 + * break + * + * result.view.len = result.view.itemsize # <<<<<<<<<<<<<< + * for length in result.view.shape[:ndim]: + * result.view.len *= length + */ + __pyx_t_9 = __pyx_v_result->__pyx_base.view.itemsize; + __pyx_v_result->__pyx_base.view.len = __pyx_t_9; + + /* "View.MemoryView":1043 + * + * result.view.len = result.view.itemsize + * for length in result.view.shape[:ndim]: # <<<<<<<<<<<<<< + * result.view.len *= length + * + */ + __pyx_t_7 = (__pyx_v_result->__pyx_base.view.shape + __pyx_v_ndim); + for (__pyx_t_8 = __pyx_v_result->__pyx_base.view.shape; __pyx_t_8 < __pyx_t_7; __pyx_t_8++) { + __pyx_t_6 = __pyx_t_8; + __pyx_t_2 = PyInt_FromSsize_t((__pyx_t_6[0])); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 1043, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_XDECREF_SET(__pyx_v_length, __pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":1044 + * result.view.len = result.view.itemsize + * for length in result.view.shape[:ndim]: + * result.view.len *= length # <<<<<<<<<<<<<< + * + * result.to_object_func = to_object_func + */ + __pyx_t_2 = PyInt_FromSsize_t(__pyx_v_result->__pyx_base.view.len); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 1044, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyNumber_InPlaceMultiply(__pyx_t_2, __pyx_v_length); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 1044, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_9 = __Pyx_PyIndex_AsSsize_t(__pyx_t_3); if (unlikely((__pyx_t_9 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 1044, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_v_result->__pyx_base.view.len = __pyx_t_9; + } + + /* "View.MemoryView":1046 + * result.view.len *= length + * + * result.to_object_func = to_object_func # <<<<<<<<<<<<<< + * result.to_dtype_func = to_dtype_func + * + */ + __pyx_v_result->to_object_func = __pyx_v_to_object_func; + + /* "View.MemoryView":1047 + * + * result.to_object_func = to_object_func + * result.to_dtype_func = to_dtype_func # <<<<<<<<<<<<<< + * + * return result + */ + __pyx_v_result->to_dtype_func = __pyx_v_to_dtype_func; + + /* "View.MemoryView":1049 + * result.to_dtype_func = to_dtype_func + * + * return result # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_get_slice_from_memoryview') + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = ((PyObject *)__pyx_v_result); + goto __pyx_L0; + + /* "View.MemoryView":999 + * + * @cname('__pyx_memoryview_fromslice') + * cdef memoryview_fromslice(__Pyx_memviewslice memviewslice, # <<<<<<<<<<<<<< + * int ndim, + * object (*to_object_func)(char *), + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview_fromslice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XDECREF(__pyx_v_length); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1052 + * + * @cname('__pyx_memoryview_get_slice_from_memoryview') + * cdef __Pyx_memviewslice *get_slice_from_memview(memoryview memview, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + */ + +static __Pyx_memviewslice *__pyx_memoryview_get_slice_from_memoryview(struct __pyx_memoryview_obj *__pyx_v_memview, __Pyx_memviewslice *__pyx_v_mslice) { + struct __pyx_memoryviewslice_obj *__pyx_v_obj = 0; + __Pyx_memviewslice *__pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_slice_from_memview", 1); + + /* "View.MemoryView":1055 + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * obj = memview + * return &obj.from_slice + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":1056 + * cdef _memoryviewslice obj + * if isinstance(memview, _memoryviewslice): + * obj = memview # <<<<<<<<<<<<<< + * return &obj.from_slice + * else: + */ + if (!(likely(((((PyObject *)__pyx_v_memview)) == Py_None) || likely(__Pyx_TypeTest(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type))))) __PYX_ERR(0, 1056, __pyx_L1_error) + __pyx_t_2 = ((PyObject *)__pyx_v_memview); + __Pyx_INCREF(__pyx_t_2); + __pyx_v_obj = ((struct __pyx_memoryviewslice_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":1057 + * if isinstance(memview, _memoryviewslice): + * obj = memview + * return &obj.from_slice # <<<<<<<<<<<<<< + * else: + * slice_copy(memview, mslice) + */ + __pyx_r = (&__pyx_v_obj->from_slice); + goto __pyx_L0; + + /* "View.MemoryView":1055 + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * obj = memview + * return &obj.from_slice + */ + } + + /* "View.MemoryView":1059 + * return &obj.from_slice + * else: + * slice_copy(memview, mslice) # <<<<<<<<<<<<<< + * return mslice + * + */ + /*else*/ { + __pyx_memoryview_slice_copy(__pyx_v_memview, __pyx_v_mslice); + + /* "View.MemoryView":1060 + * else: + * slice_copy(memview, mslice) + * return mslice # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_slice_copy') + */ + __pyx_r = __pyx_v_mslice; + goto __pyx_L0; + } + + /* "View.MemoryView":1052 + * + * @cname('__pyx_memoryview_get_slice_from_memoryview') + * cdef __Pyx_memviewslice *get_slice_from_memview(memoryview memview, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.get_slice_from_memview", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_obj); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1063 + * + * @cname('__pyx_memoryview_slice_copy') + * cdef void slice_copy(memoryview memview, __Pyx_memviewslice *dst) noexcept: # <<<<<<<<<<<<<< + * cdef int dim + * cdef (Py_ssize_t*) shape, strides, suboffsets + */ + +static void __pyx_memoryview_slice_copy(struct __pyx_memoryview_obj *__pyx_v_memview, __Pyx_memviewslice *__pyx_v_dst) { + int __pyx_v_dim; + Py_ssize_t *__pyx_v_shape; + Py_ssize_t *__pyx_v_strides; + Py_ssize_t *__pyx_v_suboffsets; + Py_ssize_t *__pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + Py_ssize_t __pyx_t_5; + int __pyx_t_6; + + /* "View.MemoryView":1067 + * cdef (Py_ssize_t*) shape, strides, suboffsets + * + * shape = memview.view.shape # <<<<<<<<<<<<<< + * strides = memview.view.strides + * suboffsets = memview.view.suboffsets + */ + __pyx_t_1 = __pyx_v_memview->view.shape; + __pyx_v_shape = __pyx_t_1; + + /* "View.MemoryView":1068 + * + * shape = memview.view.shape + * strides = memview.view.strides # <<<<<<<<<<<<<< + * suboffsets = memview.view.suboffsets + * + */ + __pyx_t_1 = __pyx_v_memview->view.strides; + __pyx_v_strides = __pyx_t_1; + + /* "View.MemoryView":1069 + * shape = memview.view.shape + * strides = memview.view.strides + * suboffsets = memview.view.suboffsets # <<<<<<<<<<<<<< + * + * dst.memview = <__pyx_memoryview *> memview + */ + __pyx_t_1 = __pyx_v_memview->view.suboffsets; + __pyx_v_suboffsets = __pyx_t_1; + + /* "View.MemoryView":1071 + * suboffsets = memview.view.suboffsets + * + * dst.memview = <__pyx_memoryview *> memview # <<<<<<<<<<<<<< + * dst.data = memview.view.buf + * + */ + __pyx_v_dst->memview = ((struct __pyx_memoryview_obj *)__pyx_v_memview); + + /* "View.MemoryView":1072 + * + * dst.memview = <__pyx_memoryview *> memview + * dst.data = memview.view.buf # <<<<<<<<<<<<<< + * + * for dim in range(memview.view.ndim): + */ + __pyx_v_dst->data = ((char *)__pyx_v_memview->view.buf); + + /* "View.MemoryView":1074 + * dst.data = memview.view.buf + * + * for dim in range(memview.view.ndim): # <<<<<<<<<<<<<< + * dst.shape[dim] = shape[dim] + * dst.strides[dim] = strides[dim] + */ + __pyx_t_2 = __pyx_v_memview->view.ndim; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_dim = __pyx_t_4; + + /* "View.MemoryView":1075 + * + * for dim in range(memview.view.ndim): + * dst.shape[dim] = shape[dim] # <<<<<<<<<<<<<< + * dst.strides[dim] = strides[dim] + * dst.suboffsets[dim] = suboffsets[dim] if suboffsets else -1 + */ + (__pyx_v_dst->shape[__pyx_v_dim]) = (__pyx_v_shape[__pyx_v_dim]); + + /* "View.MemoryView":1076 + * for dim in range(memview.view.ndim): + * dst.shape[dim] = shape[dim] + * dst.strides[dim] = strides[dim] # <<<<<<<<<<<<<< + * dst.suboffsets[dim] = suboffsets[dim] if suboffsets else -1 + * + */ + (__pyx_v_dst->strides[__pyx_v_dim]) = (__pyx_v_strides[__pyx_v_dim]); + + /* "View.MemoryView":1077 + * dst.shape[dim] = shape[dim] + * dst.strides[dim] = strides[dim] + * dst.suboffsets[dim] = suboffsets[dim] if suboffsets else -1 # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_copy_object') + */ + __pyx_t_6 = (__pyx_v_suboffsets != 0); + if (__pyx_t_6) { + __pyx_t_5 = (__pyx_v_suboffsets[__pyx_v_dim]); + } else { + __pyx_t_5 = -1L; + } + (__pyx_v_dst->suboffsets[__pyx_v_dim]) = __pyx_t_5; + } + + /* "View.MemoryView":1063 + * + * @cname('__pyx_memoryview_slice_copy') + * cdef void slice_copy(memoryview memview, __Pyx_memviewslice *dst) noexcept: # <<<<<<<<<<<<<< + * cdef int dim + * cdef (Py_ssize_t*) shape, strides, suboffsets + */ + + /* function exit code */ +} + +/* "View.MemoryView":1080 + * + * @cname('__pyx_memoryview_copy_object') + * cdef memoryview_copy(memoryview memview): # <<<<<<<<<<<<<< + * "Create a new memoryview object" + * cdef __Pyx_memviewslice memviewslice + */ + +static PyObject *__pyx_memoryview_copy_object(struct __pyx_memoryview_obj *__pyx_v_memview) { + __Pyx_memviewslice __pyx_v_memviewslice; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_copy", 1); + + /* "View.MemoryView":1083 + * "Create a new memoryview object" + * cdef __Pyx_memviewslice memviewslice + * slice_copy(memview, &memviewslice) # <<<<<<<<<<<<<< + * return memoryview_copy_from_slice(memview, &memviewslice) + * + */ + __pyx_memoryview_slice_copy(__pyx_v_memview, (&__pyx_v_memviewslice)); + + /* "View.MemoryView":1084 + * cdef __Pyx_memviewslice memviewslice + * slice_copy(memview, &memviewslice) + * return memoryview_copy_from_slice(memview, &memviewslice) # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_copy_object_from_slice') + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __pyx_memoryview_copy_object_from_slice(__pyx_v_memview, (&__pyx_v_memviewslice)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 1084, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":1080 + * + * @cname('__pyx_memoryview_copy_object') + * cdef memoryview_copy(memoryview memview): # <<<<<<<<<<<<<< + * "Create a new memoryview object" + * cdef __Pyx_memviewslice memviewslice + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview_copy", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1087 + * + * @cname('__pyx_memoryview_copy_object_from_slice') + * cdef memoryview_copy_from_slice(memoryview memview, __Pyx_memviewslice *memviewslice): # <<<<<<<<<<<<<< + * """ + * Create a new memoryview object from a given memoryview object and slice. + */ + +static PyObject *__pyx_memoryview_copy_object_from_slice(struct __pyx_memoryview_obj *__pyx_v_memview, __Pyx_memviewslice *__pyx_v_memviewslice) { + PyObject *(*__pyx_v_to_object_func)(char *); + int (*__pyx_v_to_dtype_func)(char *, PyObject *); + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *(*__pyx_t_2)(char *); + int (*__pyx_t_3)(char *, PyObject *); + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_copy_from_slice", 1); + + /* "View.MemoryView":1094 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * to_object_func = (<_memoryviewslice> memview).to_object_func + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":1095 + * + * if isinstance(memview, _memoryviewslice): + * to_object_func = (<_memoryviewslice> memview).to_object_func # <<<<<<<<<<<<<< + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + * else: + */ + __pyx_t_2 = ((struct __pyx_memoryviewslice_obj *)__pyx_v_memview)->to_object_func; + __pyx_v_to_object_func = __pyx_t_2; + + /* "View.MemoryView":1096 + * if isinstance(memview, _memoryviewslice): + * to_object_func = (<_memoryviewslice> memview).to_object_func + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func # <<<<<<<<<<<<<< + * else: + * to_object_func = NULL + */ + __pyx_t_3 = ((struct __pyx_memoryviewslice_obj *)__pyx_v_memview)->to_dtype_func; + __pyx_v_to_dtype_func = __pyx_t_3; + + /* "View.MemoryView":1094 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * to_object_func = (<_memoryviewslice> memview).to_object_func + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1098 + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + * else: + * to_object_func = NULL # <<<<<<<<<<<<<< + * to_dtype_func = NULL + * + */ + /*else*/ { + __pyx_v_to_object_func = NULL; + + /* "View.MemoryView":1099 + * else: + * to_object_func = NULL + * to_dtype_func = NULL # <<<<<<<<<<<<<< + * + * return memoryview_fromslice(memviewslice[0], memview.view.ndim, + */ + __pyx_v_to_dtype_func = NULL; + } + __pyx_L3:; + + /* "View.MemoryView":1101 + * to_dtype_func = NULL + * + * return memoryview_fromslice(memviewslice[0], memview.view.ndim, # <<<<<<<<<<<<<< + * to_object_func, to_dtype_func, + * memview.dtype_is_object) + */ + __Pyx_XDECREF(__pyx_r); + + /* "View.MemoryView":1103 + * return memoryview_fromslice(memviewslice[0], memview.view.ndim, + * to_object_func, to_dtype_func, + * memview.dtype_is_object) # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_4 = __pyx_memoryview_fromslice((__pyx_v_memviewslice[0]), __pyx_v_memview->view.ndim, __pyx_v_to_object_func, __pyx_v_to_dtype_func, __pyx_v_memview->dtype_is_object); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 1101, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_r = __pyx_t_4; + __pyx_t_4 = 0; + goto __pyx_L0; + + /* "View.MemoryView":1087 + * + * @cname('__pyx_memoryview_copy_object_from_slice') + * cdef memoryview_copy_from_slice(memoryview memview, __Pyx_memviewslice *memviewslice): # <<<<<<<<<<<<<< + * """ + * Create a new memoryview object from a given memoryview object and slice. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.memoryview_copy_from_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1109 + * + * + * cdef Py_ssize_t abs_py_ssize_t(Py_ssize_t arg) noexcept nogil: # <<<<<<<<<<<<<< + * return -arg if arg < 0 else arg + * + */ + +static Py_ssize_t abs_py_ssize_t(Py_ssize_t __pyx_v_arg) { + Py_ssize_t __pyx_r; + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + + /* "View.MemoryView":1110 + * + * cdef Py_ssize_t abs_py_ssize_t(Py_ssize_t arg) noexcept nogil: + * return -arg if arg < 0 else arg # <<<<<<<<<<<<<< + * + * @cname('__pyx_get_best_slice_order') + */ + __pyx_t_2 = (__pyx_v_arg < 0); + if (__pyx_t_2) { + __pyx_t_1 = (-__pyx_v_arg); + } else { + __pyx_t_1 = __pyx_v_arg; + } + __pyx_r = __pyx_t_1; + goto __pyx_L0; + + /* "View.MemoryView":1109 + * + * + * cdef Py_ssize_t abs_py_ssize_t(Py_ssize_t arg) noexcept nogil: # <<<<<<<<<<<<<< + * return -arg if arg < 0 else arg + * + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1113 + * + * @cname('__pyx_get_best_slice_order') + * cdef char get_best_order(__Pyx_memviewslice *mslice, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * """ + * Figure out the best memory access order for a given slice. + */ + +static char __pyx_get_best_slice_order(__Pyx_memviewslice *__pyx_v_mslice, int __pyx_v_ndim) { + int __pyx_v_i; + Py_ssize_t __pyx_v_c_stride; + Py_ssize_t __pyx_v_f_stride; + char __pyx_r; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + + /* "View.MemoryView":1118 + * """ + * cdef int i + * cdef Py_ssize_t c_stride = 0 # <<<<<<<<<<<<<< + * cdef Py_ssize_t f_stride = 0 + * + */ + __pyx_v_c_stride = 0; + + /* "View.MemoryView":1119 + * cdef int i + * cdef Py_ssize_t c_stride = 0 + * cdef Py_ssize_t f_stride = 0 # <<<<<<<<<<<<<< + * + * for i in range(ndim - 1, -1, -1): + */ + __pyx_v_f_stride = 0; + + /* "View.MemoryView":1121 + * cdef Py_ssize_t f_stride = 0 + * + * for i in range(ndim - 1, -1, -1): # <<<<<<<<<<<<<< + * if mslice.shape[i] > 1: + * c_stride = mslice.strides[i] + */ + for (__pyx_t_1 = (__pyx_v_ndim - 1); __pyx_t_1 > -1; __pyx_t_1-=1) { + __pyx_v_i = __pyx_t_1; + + /* "View.MemoryView":1122 + * + * for i in range(ndim - 1, -1, -1): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * c_stride = mslice.strides[i] + * break + */ + __pyx_t_2 = ((__pyx_v_mslice->shape[__pyx_v_i]) > 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1123 + * for i in range(ndim - 1, -1, -1): + * if mslice.shape[i] > 1: + * c_stride = mslice.strides[i] # <<<<<<<<<<<<<< + * break + * + */ + __pyx_v_c_stride = (__pyx_v_mslice->strides[__pyx_v_i]); + + /* "View.MemoryView":1124 + * if mslice.shape[i] > 1: + * c_stride = mslice.strides[i] + * break # <<<<<<<<<<<<<< + * + * for i in range(ndim): + */ + goto __pyx_L4_break; + + /* "View.MemoryView":1122 + * + * for i in range(ndim - 1, -1, -1): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * c_stride = mslice.strides[i] + * break + */ + } + } + __pyx_L4_break:; + + /* "View.MemoryView":1126 + * break + * + * for i in range(ndim): # <<<<<<<<<<<<<< + * if mslice.shape[i] > 1: + * f_stride = mslice.strides[i] + */ + __pyx_t_1 = __pyx_v_ndim; + __pyx_t_3 = __pyx_t_1; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1127 + * + * for i in range(ndim): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * f_stride = mslice.strides[i] + * break + */ + __pyx_t_2 = ((__pyx_v_mslice->shape[__pyx_v_i]) > 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1128 + * for i in range(ndim): + * if mslice.shape[i] > 1: + * f_stride = mslice.strides[i] # <<<<<<<<<<<<<< + * break + * + */ + __pyx_v_f_stride = (__pyx_v_mslice->strides[__pyx_v_i]); + + /* "View.MemoryView":1129 + * if mslice.shape[i] > 1: + * f_stride = mslice.strides[i] + * break # <<<<<<<<<<<<<< + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): + */ + goto __pyx_L7_break; + + /* "View.MemoryView":1127 + * + * for i in range(ndim): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * f_stride = mslice.strides[i] + * break + */ + } + } + __pyx_L7_break:; + + /* "View.MemoryView":1131 + * break + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): # <<<<<<<<<<<<<< + * return 'C' + * else: + */ + __pyx_t_2 = (abs_py_ssize_t(__pyx_v_c_stride) <= abs_py_ssize_t(__pyx_v_f_stride)); + if (__pyx_t_2) { + + /* "View.MemoryView":1132 + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): + * return 'C' # <<<<<<<<<<<<<< + * else: + * return 'F' + */ + __pyx_r = 'C'; + goto __pyx_L0; + + /* "View.MemoryView":1131 + * break + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): # <<<<<<<<<<<<<< + * return 'C' + * else: + */ + } + + /* "View.MemoryView":1134 + * return 'C' + * else: + * return 'F' # <<<<<<<<<<<<<< + * + * @cython.cdivision(True) + */ + /*else*/ { + __pyx_r = 'F'; + goto __pyx_L0; + } + + /* "View.MemoryView":1113 + * + * @cname('__pyx_get_best_slice_order') + * cdef char get_best_order(__Pyx_memviewslice *mslice, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * """ + * Figure out the best memory access order for a given slice. + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1137 + * + * @cython.cdivision(True) + * cdef void _copy_strided_to_strided(char *src_data, Py_ssize_t *src_strides, # <<<<<<<<<<<<<< + * char *dst_data, Py_ssize_t *dst_strides, + * Py_ssize_t *src_shape, Py_ssize_t *dst_shape, + */ + +static void _copy_strided_to_strided(char *__pyx_v_src_data, Py_ssize_t *__pyx_v_src_strides, char *__pyx_v_dst_data, Py_ssize_t *__pyx_v_dst_strides, Py_ssize_t *__pyx_v_src_shape, Py_ssize_t *__pyx_v_dst_shape, int __pyx_v_ndim, size_t __pyx_v_itemsize) { + CYTHON_UNUSED Py_ssize_t __pyx_v_i; + CYTHON_UNUSED Py_ssize_t __pyx_v_src_extent; + Py_ssize_t __pyx_v_dst_extent; + Py_ssize_t __pyx_v_src_stride; + Py_ssize_t __pyx_v_dst_stride; + int __pyx_t_1; + int __pyx_t_2; + Py_ssize_t __pyx_t_3; + Py_ssize_t __pyx_t_4; + Py_ssize_t __pyx_t_5; + + /* "View.MemoryView":1144 + * + * cdef Py_ssize_t i + * cdef Py_ssize_t src_extent = src_shape[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t dst_extent = dst_shape[0] + * cdef Py_ssize_t src_stride = src_strides[0] + */ + __pyx_v_src_extent = (__pyx_v_src_shape[0]); + + /* "View.MemoryView":1145 + * cdef Py_ssize_t i + * cdef Py_ssize_t src_extent = src_shape[0] + * cdef Py_ssize_t dst_extent = dst_shape[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t src_stride = src_strides[0] + * cdef Py_ssize_t dst_stride = dst_strides[0] + */ + __pyx_v_dst_extent = (__pyx_v_dst_shape[0]); + + /* "View.MemoryView":1146 + * cdef Py_ssize_t src_extent = src_shape[0] + * cdef Py_ssize_t dst_extent = dst_shape[0] + * cdef Py_ssize_t src_stride = src_strides[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t dst_stride = dst_strides[0] + * + */ + __pyx_v_src_stride = (__pyx_v_src_strides[0]); + + /* "View.MemoryView":1147 + * cdef Py_ssize_t dst_extent = dst_shape[0] + * cdef Py_ssize_t src_stride = src_strides[0] + * cdef Py_ssize_t dst_stride = dst_strides[0] # <<<<<<<<<<<<<< + * + * if ndim == 1: + */ + __pyx_v_dst_stride = (__pyx_v_dst_strides[0]); + + /* "View.MemoryView":1149 + * cdef Py_ssize_t dst_stride = dst_strides[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): + */ + __pyx_t_1 = (__pyx_v_ndim == 1); + if (__pyx_t_1) { + + /* "View.MemoryView":1150 + * + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and # <<<<<<<<<<<<<< + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) + */ + __pyx_t_2 = (__pyx_v_src_stride > 0); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L5_bool_binop_done; + } + __pyx_t_2 = (__pyx_v_dst_stride > 0); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L5_bool_binop_done; + } + + /* "View.MemoryView":1151 + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): # <<<<<<<<<<<<<< + * memcpy(dst_data, src_data, itemsize * dst_extent) + * else: + */ + __pyx_t_2 = (((size_t)__pyx_v_src_stride) == __pyx_v_itemsize); + if (__pyx_t_2) { + __pyx_t_2 = (__pyx_v_itemsize == ((size_t)__pyx_v_dst_stride)); + } + __pyx_t_1 = __pyx_t_2; + __pyx_L5_bool_binop_done:; + + /* "View.MemoryView":1150 + * + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and # <<<<<<<<<<<<<< + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) + */ + if (__pyx_t_1) { + + /* "View.MemoryView":1152 + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) # <<<<<<<<<<<<<< + * else: + * for i in range(dst_extent): + */ + (void)(memcpy(__pyx_v_dst_data, __pyx_v_src_data, (__pyx_v_itemsize * __pyx_v_dst_extent))); + + /* "View.MemoryView":1150 + * + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and # <<<<<<<<<<<<<< + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) + */ + goto __pyx_L4; + } + + /* "View.MemoryView":1154 + * memcpy(dst_data, src_data, itemsize * dst_extent) + * else: + * for i in range(dst_extent): # <<<<<<<<<<<<<< + * memcpy(dst_data, src_data, itemsize) + * src_data += src_stride + */ + /*else*/ { + __pyx_t_3 = __pyx_v_dst_extent; + __pyx_t_4 = __pyx_t_3; + for (__pyx_t_5 = 0; __pyx_t_5 < __pyx_t_4; __pyx_t_5+=1) { + __pyx_v_i = __pyx_t_5; + + /* "View.MemoryView":1155 + * else: + * for i in range(dst_extent): + * memcpy(dst_data, src_data, itemsize) # <<<<<<<<<<<<<< + * src_data += src_stride + * dst_data += dst_stride + */ + (void)(memcpy(__pyx_v_dst_data, __pyx_v_src_data, __pyx_v_itemsize)); + + /* "View.MemoryView":1156 + * for i in range(dst_extent): + * memcpy(dst_data, src_data, itemsize) + * src_data += src_stride # <<<<<<<<<<<<<< + * dst_data += dst_stride + * else: + */ + __pyx_v_src_data = (__pyx_v_src_data + __pyx_v_src_stride); + + /* "View.MemoryView":1157 + * memcpy(dst_data, src_data, itemsize) + * src_data += src_stride + * dst_data += dst_stride # <<<<<<<<<<<<<< + * else: + * for i in range(dst_extent): + */ + __pyx_v_dst_data = (__pyx_v_dst_data + __pyx_v_dst_stride); + } + } + __pyx_L4:; + + /* "View.MemoryView":1149 + * cdef Py_ssize_t dst_stride = dst_strides[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1159 + * dst_data += dst_stride + * else: + * for i in range(dst_extent): # <<<<<<<<<<<<<< + * _copy_strided_to_strided(src_data, src_strides + 1, + * dst_data, dst_strides + 1, + */ + /*else*/ { + __pyx_t_3 = __pyx_v_dst_extent; + __pyx_t_4 = __pyx_t_3; + for (__pyx_t_5 = 0; __pyx_t_5 < __pyx_t_4; __pyx_t_5+=1) { + __pyx_v_i = __pyx_t_5; + + /* "View.MemoryView":1160 + * else: + * for i in range(dst_extent): + * _copy_strided_to_strided(src_data, src_strides + 1, # <<<<<<<<<<<<<< + * dst_data, dst_strides + 1, + * src_shape + 1, dst_shape + 1, + */ + _copy_strided_to_strided(__pyx_v_src_data, (__pyx_v_src_strides + 1), __pyx_v_dst_data, (__pyx_v_dst_strides + 1), (__pyx_v_src_shape + 1), (__pyx_v_dst_shape + 1), (__pyx_v_ndim - 1), __pyx_v_itemsize); + + /* "View.MemoryView":1164 + * src_shape + 1, dst_shape + 1, + * ndim - 1, itemsize) + * src_data += src_stride # <<<<<<<<<<<<<< + * dst_data += dst_stride + * + */ + __pyx_v_src_data = (__pyx_v_src_data + __pyx_v_src_stride); + + /* "View.MemoryView":1165 + * ndim - 1, itemsize) + * src_data += src_stride + * dst_data += dst_stride # <<<<<<<<<<<<<< + * + * cdef void copy_strided_to_strided(__Pyx_memviewslice *src, + */ + __pyx_v_dst_data = (__pyx_v_dst_data + __pyx_v_dst_stride); + } + } + __pyx_L3:; + + /* "View.MemoryView":1137 + * + * @cython.cdivision(True) + * cdef void _copy_strided_to_strided(char *src_data, Py_ssize_t *src_strides, # <<<<<<<<<<<<<< + * char *dst_data, Py_ssize_t *dst_strides, + * Py_ssize_t *src_shape, Py_ssize_t *dst_shape, + */ + + /* function exit code */ +} + +/* "View.MemoryView":1167 + * dst_data += dst_stride + * + * cdef void copy_strided_to_strided(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * int ndim, size_t itemsize) noexcept nogil: + */ + +static void copy_strided_to_strided(__Pyx_memviewslice *__pyx_v_src, __Pyx_memviewslice *__pyx_v_dst, int __pyx_v_ndim, size_t __pyx_v_itemsize) { + + /* "View.MemoryView":1170 + * __Pyx_memviewslice *dst, + * int ndim, size_t itemsize) noexcept nogil: + * _copy_strided_to_strided(src.data, src.strides, dst.data, dst.strides, # <<<<<<<<<<<<<< + * src.shape, dst.shape, ndim, itemsize) + * + */ + _copy_strided_to_strided(__pyx_v_src->data, __pyx_v_src->strides, __pyx_v_dst->data, __pyx_v_dst->strides, __pyx_v_src->shape, __pyx_v_dst->shape, __pyx_v_ndim, __pyx_v_itemsize); + + /* "View.MemoryView":1167 + * dst_data += dst_stride + * + * cdef void copy_strided_to_strided(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * int ndim, size_t itemsize) noexcept nogil: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1174 + * + * @cname('__pyx_memoryview_slice_get_size') + * cdef Py_ssize_t slice_get_size(__Pyx_memviewslice *src, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * "Return the size of the memory occupied by the slice in number of bytes" + * cdef Py_ssize_t shape, size = src.memview.view.itemsize + */ + +static Py_ssize_t __pyx_memoryview_slice_get_size(__Pyx_memviewslice *__pyx_v_src, int __pyx_v_ndim) { + Py_ssize_t __pyx_v_shape; + Py_ssize_t __pyx_v_size; + Py_ssize_t __pyx_r; + Py_ssize_t __pyx_t_1; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + + /* "View.MemoryView":1176 + * cdef Py_ssize_t slice_get_size(__Pyx_memviewslice *src, int ndim) noexcept nogil: + * "Return the size of the memory occupied by the slice in number of bytes" + * cdef Py_ssize_t shape, size = src.memview.view.itemsize # <<<<<<<<<<<<<< + * + * for shape in src.shape[:ndim]: + */ + __pyx_t_1 = __pyx_v_src->memview->view.itemsize; + __pyx_v_size = __pyx_t_1; + + /* "View.MemoryView":1178 + * cdef Py_ssize_t shape, size = src.memview.view.itemsize + * + * for shape in src.shape[:ndim]: # <<<<<<<<<<<<<< + * size *= shape + * + */ + __pyx_t_3 = (__pyx_v_src->shape + __pyx_v_ndim); + for (__pyx_t_4 = __pyx_v_src->shape; __pyx_t_4 < __pyx_t_3; __pyx_t_4++) { + __pyx_t_2 = __pyx_t_4; + __pyx_v_shape = (__pyx_t_2[0]); + + /* "View.MemoryView":1179 + * + * for shape in src.shape[:ndim]: + * size *= shape # <<<<<<<<<<<<<< + * + * return size + */ + __pyx_v_size = (__pyx_v_size * __pyx_v_shape); + } + + /* "View.MemoryView":1181 + * size *= shape + * + * return size # <<<<<<<<<<<<<< + * + * @cname('__pyx_fill_contig_strides_array') + */ + __pyx_r = __pyx_v_size; + goto __pyx_L0; + + /* "View.MemoryView":1174 + * + * @cname('__pyx_memoryview_slice_get_size') + * cdef Py_ssize_t slice_get_size(__Pyx_memviewslice *src, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * "Return the size of the memory occupied by the slice in number of bytes" + * cdef Py_ssize_t shape, size = src.memview.view.itemsize + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1184 + * + * @cname('__pyx_fill_contig_strides_array') + * cdef Py_ssize_t fill_contig_strides_array( # <<<<<<<<<<<<<< + * Py_ssize_t *shape, Py_ssize_t *strides, Py_ssize_t stride, + * int ndim, char order) noexcept nogil: + */ + +static Py_ssize_t __pyx_fill_contig_strides_array(Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, Py_ssize_t __pyx_v_stride, int __pyx_v_ndim, char __pyx_v_order) { + int __pyx_v_idx; + Py_ssize_t __pyx_r; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + + /* "View.MemoryView":1193 + * cdef int idx + * + * if order == 'F': # <<<<<<<<<<<<<< + * for idx in range(ndim): + * strides[idx] = stride + */ + __pyx_t_1 = (__pyx_v_order == 'F'); + if (__pyx_t_1) { + + /* "View.MemoryView":1194 + * + * if order == 'F': + * for idx in range(ndim): # <<<<<<<<<<<<<< + * strides[idx] = stride + * stride *= shape[idx] + */ + __pyx_t_2 = __pyx_v_ndim; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_idx = __pyx_t_4; + + /* "View.MemoryView":1195 + * if order == 'F': + * for idx in range(ndim): + * strides[idx] = stride # <<<<<<<<<<<<<< + * stride *= shape[idx] + * else: + */ + (__pyx_v_strides[__pyx_v_idx]) = __pyx_v_stride; + + /* "View.MemoryView":1196 + * for idx in range(ndim): + * strides[idx] = stride + * stride *= shape[idx] # <<<<<<<<<<<<<< + * else: + * for idx in range(ndim - 1, -1, -1): + */ + __pyx_v_stride = (__pyx_v_stride * (__pyx_v_shape[__pyx_v_idx])); + } + + /* "View.MemoryView":1193 + * cdef int idx + * + * if order == 'F': # <<<<<<<<<<<<<< + * for idx in range(ndim): + * strides[idx] = stride + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1198 + * stride *= shape[idx] + * else: + * for idx in range(ndim - 1, -1, -1): # <<<<<<<<<<<<<< + * strides[idx] = stride + * stride *= shape[idx] + */ + /*else*/ { + for (__pyx_t_2 = (__pyx_v_ndim - 1); __pyx_t_2 > -1; __pyx_t_2-=1) { + __pyx_v_idx = __pyx_t_2; + + /* "View.MemoryView":1199 + * else: + * for idx in range(ndim - 1, -1, -1): + * strides[idx] = stride # <<<<<<<<<<<<<< + * stride *= shape[idx] + * + */ + (__pyx_v_strides[__pyx_v_idx]) = __pyx_v_stride; + + /* "View.MemoryView":1200 + * for idx in range(ndim - 1, -1, -1): + * strides[idx] = stride + * stride *= shape[idx] # <<<<<<<<<<<<<< + * + * return stride + */ + __pyx_v_stride = (__pyx_v_stride * (__pyx_v_shape[__pyx_v_idx])); + } + } + __pyx_L3:; + + /* "View.MemoryView":1202 + * stride *= shape[idx] + * + * return stride # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_copy_data_to_temp') + */ + __pyx_r = __pyx_v_stride; + goto __pyx_L0; + + /* "View.MemoryView":1184 + * + * @cname('__pyx_fill_contig_strides_array') + * cdef Py_ssize_t fill_contig_strides_array( # <<<<<<<<<<<<<< + * Py_ssize_t *shape, Py_ssize_t *strides, Py_ssize_t stride, + * int ndim, char order) noexcept nogil: + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1205 + * + * @cname('__pyx_memoryview_copy_data_to_temp') + * cdef void *copy_data_to_temp(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *tmpslice, + * char order, + */ + +static void *__pyx_memoryview_copy_data_to_temp(__Pyx_memviewslice *__pyx_v_src, __Pyx_memviewslice *__pyx_v_tmpslice, char __pyx_v_order, int __pyx_v_ndim) { + int __pyx_v_i; + void *__pyx_v_result; + size_t __pyx_v_itemsize; + size_t __pyx_v_size; + void *__pyx_r; + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + struct __pyx_memoryview_obj *__pyx_t_4; + int __pyx_t_5; + int __pyx_t_6; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":1216 + * cdef void *result + * + * cdef size_t itemsize = src.memview.view.itemsize # <<<<<<<<<<<<<< + * cdef size_t size = slice_get_size(src, ndim) + * + */ + __pyx_t_1 = __pyx_v_src->memview->view.itemsize; + __pyx_v_itemsize = __pyx_t_1; + + /* "View.MemoryView":1217 + * + * cdef size_t itemsize = src.memview.view.itemsize + * cdef size_t size = slice_get_size(src, ndim) # <<<<<<<<<<<<<< + * + * result = malloc(size) + */ + __pyx_v_size = __pyx_memoryview_slice_get_size(__pyx_v_src, __pyx_v_ndim); + + /* "View.MemoryView":1219 + * cdef size_t size = slice_get_size(src, ndim) + * + * result = malloc(size) # <<<<<<<<<<<<<< + * if not result: + * _err_no_memory() + */ + __pyx_v_result = malloc(__pyx_v_size); + + /* "View.MemoryView":1220 + * + * result = malloc(size) + * if not result: # <<<<<<<<<<<<<< + * _err_no_memory() + * + */ + __pyx_t_2 = (!(__pyx_v_result != 0)); + if (__pyx_t_2) { + + /* "View.MemoryView":1221 + * result = malloc(size) + * if not result: + * _err_no_memory() # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_3 = __pyx_memoryview_err_no_memory(); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(0, 1221, __pyx_L1_error) + + /* "View.MemoryView":1220 + * + * result = malloc(size) + * if not result: # <<<<<<<<<<<<<< + * _err_no_memory() + * + */ + } + + /* "View.MemoryView":1224 + * + * + * tmpslice.data = result # <<<<<<<<<<<<<< + * tmpslice.memview = src.memview + * for i in range(ndim): + */ + __pyx_v_tmpslice->data = ((char *)__pyx_v_result); + + /* "View.MemoryView":1225 + * + * tmpslice.data = result + * tmpslice.memview = src.memview # <<<<<<<<<<<<<< + * for i in range(ndim): + * tmpslice.shape[i] = src.shape[i] + */ + __pyx_t_4 = __pyx_v_src->memview; + __pyx_v_tmpslice->memview = __pyx_t_4; + + /* "View.MemoryView":1226 + * tmpslice.data = result + * tmpslice.memview = src.memview + * for i in range(ndim): # <<<<<<<<<<<<<< + * tmpslice.shape[i] = src.shape[i] + * tmpslice.suboffsets[i] = -1 + */ + __pyx_t_3 = __pyx_v_ndim; + __pyx_t_5 = __pyx_t_3; + for (__pyx_t_6 = 0; __pyx_t_6 < __pyx_t_5; __pyx_t_6+=1) { + __pyx_v_i = __pyx_t_6; + + /* "View.MemoryView":1227 + * tmpslice.memview = src.memview + * for i in range(ndim): + * tmpslice.shape[i] = src.shape[i] # <<<<<<<<<<<<<< + * tmpslice.suboffsets[i] = -1 + * + */ + (__pyx_v_tmpslice->shape[__pyx_v_i]) = (__pyx_v_src->shape[__pyx_v_i]); + + /* "View.MemoryView":1228 + * for i in range(ndim): + * tmpslice.shape[i] = src.shape[i] + * tmpslice.suboffsets[i] = -1 # <<<<<<<<<<<<<< + * + * fill_contig_strides_array(&tmpslice.shape[0], &tmpslice.strides[0], itemsize, ndim, order) + */ + (__pyx_v_tmpslice->suboffsets[__pyx_v_i]) = -1L; + } + + /* "View.MemoryView":1230 + * tmpslice.suboffsets[i] = -1 + * + * fill_contig_strides_array(&tmpslice.shape[0], &tmpslice.strides[0], itemsize, ndim, order) # <<<<<<<<<<<<<< + * + * + */ + (void)(__pyx_fill_contig_strides_array((&(__pyx_v_tmpslice->shape[0])), (&(__pyx_v_tmpslice->strides[0])), __pyx_v_itemsize, __pyx_v_ndim, __pyx_v_order)); + + /* "View.MemoryView":1233 + * + * + * for i in range(ndim): # <<<<<<<<<<<<<< + * if tmpslice.shape[i] == 1: + * tmpslice.strides[i] = 0 + */ + __pyx_t_3 = __pyx_v_ndim; + __pyx_t_5 = __pyx_t_3; + for (__pyx_t_6 = 0; __pyx_t_6 < __pyx_t_5; __pyx_t_6+=1) { + __pyx_v_i = __pyx_t_6; + + /* "View.MemoryView":1234 + * + * for i in range(ndim): + * if tmpslice.shape[i] == 1: # <<<<<<<<<<<<<< + * tmpslice.strides[i] = 0 + * + */ + __pyx_t_2 = ((__pyx_v_tmpslice->shape[__pyx_v_i]) == 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1235 + * for i in range(ndim): + * if tmpslice.shape[i] == 1: + * tmpslice.strides[i] = 0 # <<<<<<<<<<<<<< + * + * if slice_is_contig(src[0], order, ndim): + */ + (__pyx_v_tmpslice->strides[__pyx_v_i]) = 0; + + /* "View.MemoryView":1234 + * + * for i in range(ndim): + * if tmpslice.shape[i] == 1: # <<<<<<<<<<<<<< + * tmpslice.strides[i] = 0 + * + */ + } + } + + /* "View.MemoryView":1237 + * tmpslice.strides[i] = 0 + * + * if slice_is_contig(src[0], order, ndim): # <<<<<<<<<<<<<< + * memcpy(result, src.data, size) + * else: + */ + __pyx_t_2 = __pyx_memviewslice_is_contig((__pyx_v_src[0]), __pyx_v_order, __pyx_v_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1238 + * + * if slice_is_contig(src[0], order, ndim): + * memcpy(result, src.data, size) # <<<<<<<<<<<<<< + * else: + * copy_strided_to_strided(src, tmpslice, ndim, itemsize) + */ + (void)(memcpy(__pyx_v_result, __pyx_v_src->data, __pyx_v_size)); + + /* "View.MemoryView":1237 + * tmpslice.strides[i] = 0 + * + * if slice_is_contig(src[0], order, ndim): # <<<<<<<<<<<<<< + * memcpy(result, src.data, size) + * else: + */ + goto __pyx_L9; + } + + /* "View.MemoryView":1240 + * memcpy(result, src.data, size) + * else: + * copy_strided_to_strided(src, tmpslice, ndim, itemsize) # <<<<<<<<<<<<<< + * + * return result + */ + /*else*/ { + copy_strided_to_strided(__pyx_v_src, __pyx_v_tmpslice, __pyx_v_ndim, __pyx_v_itemsize); + } + __pyx_L9:; + + /* "View.MemoryView":1242 + * copy_strided_to_strided(src, tmpslice, ndim, itemsize) + * + * return result # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = __pyx_v_result; + goto __pyx_L0; + + /* "View.MemoryView":1205 + * + * @cname('__pyx_memoryview_copy_data_to_temp') + * cdef void *copy_data_to_temp(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *tmpslice, + * char order, + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.copy_data_to_temp", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1247 + * + * @cname('__pyx_memoryview_err_extents') + * cdef int _err_extents(int i, Py_ssize_t extent1, # <<<<<<<<<<<<<< + * Py_ssize_t extent2) except -1 with gil: + * raise ValueError, f"got differing extents in dimension {i} (got {extent1} and {extent2})" + */ + +static int __pyx_memoryview_err_extents(int __pyx_v_i, Py_ssize_t __pyx_v_extent1, Py_ssize_t __pyx_v_extent2) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + Py_ssize_t __pyx_t_2; + Py_UCS4 __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_RefNannySetupContext("_err_extents", 0); + + /* "View.MemoryView":1249 + * cdef int _err_extents(int i, Py_ssize_t extent1, + * Py_ssize_t extent2) except -1 with gil: + * raise ValueError, f"got differing extents in dimension {i} (got {extent1} and {extent2})" # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_err_dim') + */ + __pyx_t_1 = PyTuple_New(7); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = 0; + __pyx_t_3 = 127; + __Pyx_INCREF(__pyx_kp_u_got_differing_extents_in_dimensi); + __pyx_t_2 += 35; + __Pyx_GIVEREF(__pyx_kp_u_got_differing_extents_in_dimensi); + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_kp_u_got_differing_extents_in_dimensi); + __pyx_t_4 = __Pyx_PyUnicode_From_int(__pyx_v_i, 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_2 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_t_4); + __pyx_t_4 = 0; + __Pyx_INCREF(__pyx_kp_u_got); + __pyx_t_2 += 6; + __Pyx_GIVEREF(__pyx_kp_u_got); + PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_kp_u_got); + __pyx_t_4 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_extent1, 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_2 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_1, 3, __pyx_t_4); + __pyx_t_4 = 0; + __Pyx_INCREF(__pyx_kp_u_and); + __pyx_t_2 += 5; + __Pyx_GIVEREF(__pyx_kp_u_and); + PyTuple_SET_ITEM(__pyx_t_1, 4, __pyx_kp_u_and); + __pyx_t_4 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_extent2, 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_2 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_1, 5, __pyx_t_4); + __pyx_t_4 = 0; + __Pyx_INCREF(__pyx_kp_u__7); + __pyx_t_2 += 1; + __Pyx_GIVEREF(__pyx_kp_u__7); + PyTuple_SET_ITEM(__pyx_t_1, 6, __pyx_kp_u__7); + __pyx_t_4 = __Pyx_PyUnicode_Join(__pyx_t_1, 7, __pyx_t_2, __pyx_t_3); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_t_4, 0, 0); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __PYX_ERR(0, 1249, __pyx_L1_error) + + /* "View.MemoryView":1247 + * + * @cname('__pyx_memoryview_err_extents') + * cdef int _err_extents(int i, Py_ssize_t extent1, # <<<<<<<<<<<<<< + * Py_ssize_t extent2) except -1 with gil: + * raise ValueError, f"got differing extents in dimension {i} (got {extent1} and {extent2})" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView._err_extents", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __Pyx_RefNannyFinishContext(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1252 + * + * @cname('__pyx_memoryview_err_dim') + * cdef int _err_dim(PyObject *error, str msg, int dim) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg % dim + * + */ + +static int __pyx_memoryview_err_dim(PyObject *__pyx_v_error, PyObject *__pyx_v_msg, int __pyx_v_dim) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_RefNannySetupContext("_err_dim", 0); + __Pyx_INCREF(__pyx_v_msg); + + /* "View.MemoryView":1253 + * @cname('__pyx_memoryview_err_dim') + * cdef int _err_dim(PyObject *error, str msg, int dim) except -1 with gil: + * raise error, msg % dim # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_err') + */ + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_dim); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 1253, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyString_FormatSafe(__pyx_v_msg, __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 1253, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(((PyObject *)__pyx_v_error), __pyx_t_2, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 1253, __pyx_L1_error) + + /* "View.MemoryView":1252 + * + * @cname('__pyx_memoryview_err_dim') + * cdef int _err_dim(PyObject *error, str msg, int dim) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg % dim + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView._err_dim", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __Pyx_XDECREF(__pyx_v_msg); + __Pyx_RefNannyFinishContext(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1256 + * + * @cname('__pyx_memoryview_err') + * cdef int _err(PyObject *error, str msg) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg + * + */ + +static int __pyx_memoryview_err(PyObject *__pyx_v_error, PyObject *__pyx_v_msg) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_RefNannySetupContext("_err", 0); + __Pyx_INCREF(__pyx_v_msg); + + /* "View.MemoryView":1257 + * @cname('__pyx_memoryview_err') + * cdef int _err(PyObject *error, str msg) except -1 with gil: + * raise error, msg # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_err_no_memory') + */ + __Pyx_Raise(((PyObject *)__pyx_v_error), __pyx_v_msg, 0, 0); + __PYX_ERR(0, 1257, __pyx_L1_error) + + /* "View.MemoryView":1256 + * + * @cname('__pyx_memoryview_err') + * cdef int _err(PyObject *error, str msg) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._err", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __Pyx_XDECREF(__pyx_v_msg); + __Pyx_RefNannyFinishContext(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1260 + * + * @cname('__pyx_memoryview_err_no_memory') + * cdef int _err_no_memory() except -1 with gil: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + +static int __pyx_memoryview_err_no_memory(void) { + int __pyx_r; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + + /* "View.MemoryView":1261 + * @cname('__pyx_memoryview_err_no_memory') + * cdef int _err_no_memory() except -1 with gil: + * raise MemoryError # <<<<<<<<<<<<<< + * + * + */ + PyErr_NoMemory(); __PYX_ERR(0, 1261, __pyx_L1_error) + + /* "View.MemoryView":1260 + * + * @cname('__pyx_memoryview_err_no_memory') + * cdef int _err_no_memory() except -1 with gil: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._err_no_memory", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1265 + * + * @cname('__pyx_memoryview_copy_contents') + * cdef int memoryview_copy_contents(__Pyx_memviewslice src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice dst, + * int src_ndim, int dst_ndim, + */ + +static int __pyx_memoryview_copy_contents(__Pyx_memviewslice __pyx_v_src, __Pyx_memviewslice __pyx_v_dst, int __pyx_v_src_ndim, int __pyx_v_dst_ndim, int __pyx_v_dtype_is_object) { + void *__pyx_v_tmpdata; + size_t __pyx_v_itemsize; + int __pyx_v_i; + char __pyx_v_order; + int __pyx_v_broadcasting; + int __pyx_v_direct_copy; + __Pyx_memviewslice __pyx_v_tmp; + int __pyx_v_ndim; + int __pyx_r; + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + int __pyx_t_5; + int __pyx_t_6; + void *__pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":1273 + * Check for overlapping memory and verify the shapes. + * """ + * cdef void *tmpdata = NULL # <<<<<<<<<<<<<< + * cdef size_t itemsize = src.memview.view.itemsize + * cdef int i + */ + __pyx_v_tmpdata = NULL; + + /* "View.MemoryView":1274 + * """ + * cdef void *tmpdata = NULL + * cdef size_t itemsize = src.memview.view.itemsize # <<<<<<<<<<<<<< + * cdef int i + * cdef char order = get_best_order(&src, src_ndim) + */ + __pyx_t_1 = __pyx_v_src.memview->view.itemsize; + __pyx_v_itemsize = __pyx_t_1; + + /* "View.MemoryView":1276 + * cdef size_t itemsize = src.memview.view.itemsize + * cdef int i + * cdef char order = get_best_order(&src, src_ndim) # <<<<<<<<<<<<<< + * cdef bint broadcasting = False + * cdef bint direct_copy = False + */ + __pyx_v_order = __pyx_get_best_slice_order((&__pyx_v_src), __pyx_v_src_ndim); + + /* "View.MemoryView":1277 + * cdef int i + * cdef char order = get_best_order(&src, src_ndim) + * cdef bint broadcasting = False # <<<<<<<<<<<<<< + * cdef bint direct_copy = False + * cdef __Pyx_memviewslice tmp + */ + __pyx_v_broadcasting = 0; + + /* "View.MemoryView":1278 + * cdef char order = get_best_order(&src, src_ndim) + * cdef bint broadcasting = False + * cdef bint direct_copy = False # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice tmp + * + */ + __pyx_v_direct_copy = 0; + + /* "View.MemoryView":1281 + * cdef __Pyx_memviewslice tmp + * + * if src_ndim < dst_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: + */ + __pyx_t_2 = (__pyx_v_src_ndim < __pyx_v_dst_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1282 + * + * if src_ndim < dst_ndim: + * broadcast_leading(&src, src_ndim, dst_ndim) # <<<<<<<<<<<<<< + * elif dst_ndim < src_ndim: + * broadcast_leading(&dst, dst_ndim, src_ndim) + */ + __pyx_memoryview_broadcast_leading((&__pyx_v_src), __pyx_v_src_ndim, __pyx_v_dst_ndim); + + /* "View.MemoryView":1281 + * cdef __Pyx_memviewslice tmp + * + * if src_ndim < dst_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1283 + * if src_ndim < dst_ndim: + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&dst, dst_ndim, src_ndim) + * + */ + __pyx_t_2 = (__pyx_v_dst_ndim < __pyx_v_src_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1284 + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: + * broadcast_leading(&dst, dst_ndim, src_ndim) # <<<<<<<<<<<<<< + * + * cdef int ndim = max(src_ndim, dst_ndim) + */ + __pyx_memoryview_broadcast_leading((&__pyx_v_dst), __pyx_v_dst_ndim, __pyx_v_src_ndim); + + /* "View.MemoryView":1283 + * if src_ndim < dst_ndim: + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&dst, dst_ndim, src_ndim) + * + */ + } + __pyx_L3:; + + /* "View.MemoryView":1286 + * broadcast_leading(&dst, dst_ndim, src_ndim) + * + * cdef int ndim = max(src_ndim, dst_ndim) # <<<<<<<<<<<<<< + * + * for i in range(ndim): + */ + __pyx_t_3 = __pyx_v_dst_ndim; + __pyx_t_4 = __pyx_v_src_ndim; + __pyx_t_2 = (__pyx_t_3 > __pyx_t_4); + if (__pyx_t_2) { + __pyx_t_5 = __pyx_t_3; + } else { + __pyx_t_5 = __pyx_t_4; + } + __pyx_v_ndim = __pyx_t_5; + + /* "View.MemoryView":1288 + * cdef int ndim = max(src_ndim, dst_ndim) + * + * for i in range(ndim): # <<<<<<<<<<<<<< + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: + */ + __pyx_t_5 = __pyx_v_ndim; + __pyx_t_3 = __pyx_t_5; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1289 + * + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: # <<<<<<<<<<<<<< + * if src.shape[i] == 1: + * broadcasting = True + */ + __pyx_t_2 = ((__pyx_v_src.shape[__pyx_v_i]) != (__pyx_v_dst.shape[__pyx_v_i])); + if (__pyx_t_2) { + + /* "View.MemoryView":1290 + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: # <<<<<<<<<<<<<< + * broadcasting = True + * src.strides[i] = 0 + */ + __pyx_t_2 = ((__pyx_v_src.shape[__pyx_v_i]) == 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1291 + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: + * broadcasting = True # <<<<<<<<<<<<<< + * src.strides[i] = 0 + * else: + */ + __pyx_v_broadcasting = 1; + + /* "View.MemoryView":1292 + * if src.shape[i] == 1: + * broadcasting = True + * src.strides[i] = 0 # <<<<<<<<<<<<<< + * else: + * _err_extents(i, dst.shape[i], src.shape[i]) + */ + (__pyx_v_src.strides[__pyx_v_i]) = 0; + + /* "View.MemoryView":1290 + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: # <<<<<<<<<<<<<< + * broadcasting = True + * src.strides[i] = 0 + */ + goto __pyx_L7; + } + + /* "View.MemoryView":1294 + * src.strides[i] = 0 + * else: + * _err_extents(i, dst.shape[i], src.shape[i]) # <<<<<<<<<<<<<< + * + * if src.suboffsets[i] >= 0: + */ + /*else*/ { + __pyx_t_6 = __pyx_memoryview_err_extents(__pyx_v_i, (__pyx_v_dst.shape[__pyx_v_i]), (__pyx_v_src.shape[__pyx_v_i])); if (unlikely(__pyx_t_6 == ((int)-1))) __PYX_ERR(0, 1294, __pyx_L1_error) + } + __pyx_L7:; + + /* "View.MemoryView":1289 + * + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: # <<<<<<<<<<<<<< + * if src.shape[i] == 1: + * broadcasting = True + */ + } + + /* "View.MemoryView":1296 + * _err_extents(i, dst.shape[i], src.shape[i]) + * + * if src.suboffsets[i] >= 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + */ + __pyx_t_2 = ((__pyx_v_src.suboffsets[__pyx_v_i]) >= 0); + if (__pyx_t_2) { + + /* "View.MemoryView":1297 + * + * if src.suboffsets[i] >= 0: + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) # <<<<<<<<<<<<<< + * + * if slices_overlap(&src, &dst, ndim, itemsize): + */ + __pyx_t_6 = __pyx_memoryview_err_dim(PyExc_ValueError, __pyx_kp_s_Dimension_d_is_not_direct, __pyx_v_i); if (unlikely(__pyx_t_6 == ((int)-1))) __PYX_ERR(0, 1297, __pyx_L1_error) + + /* "View.MemoryView":1296 + * _err_extents(i, dst.shape[i], src.shape[i]) + * + * if src.suboffsets[i] >= 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + */ + } + } + + /* "View.MemoryView":1299 + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + * if slices_overlap(&src, &dst, ndim, itemsize): # <<<<<<<<<<<<<< + * + * if not slice_is_contig(src, order, ndim): + */ + __pyx_t_2 = __pyx_slices_overlap((&__pyx_v_src), (&__pyx_v_dst), __pyx_v_ndim, __pyx_v_itemsize); + if (__pyx_t_2) { + + /* "View.MemoryView":1301 + * if slices_overlap(&src, &dst, ndim, itemsize): + * + * if not slice_is_contig(src, order, ndim): # <<<<<<<<<<<<<< + * order = get_best_order(&dst, ndim) + * + */ + __pyx_t_2 = (!__pyx_memviewslice_is_contig(__pyx_v_src, __pyx_v_order, __pyx_v_ndim)); + if (__pyx_t_2) { + + /* "View.MemoryView":1302 + * + * if not slice_is_contig(src, order, ndim): + * order = get_best_order(&dst, ndim) # <<<<<<<<<<<<<< + * + * tmpdata = copy_data_to_temp(&src, &tmp, order, ndim) + */ + __pyx_v_order = __pyx_get_best_slice_order((&__pyx_v_dst), __pyx_v_ndim); + + /* "View.MemoryView":1301 + * if slices_overlap(&src, &dst, ndim, itemsize): + * + * if not slice_is_contig(src, order, ndim): # <<<<<<<<<<<<<< + * order = get_best_order(&dst, ndim) + * + */ + } + + /* "View.MemoryView":1304 + * order = get_best_order(&dst, ndim) + * + * tmpdata = copy_data_to_temp(&src, &tmp, order, ndim) # <<<<<<<<<<<<<< + * src = tmp + * + */ + __pyx_t_7 = __pyx_memoryview_copy_data_to_temp((&__pyx_v_src), (&__pyx_v_tmp), __pyx_v_order, __pyx_v_ndim); if (unlikely(__pyx_t_7 == ((void *)NULL))) __PYX_ERR(0, 1304, __pyx_L1_error) + __pyx_v_tmpdata = __pyx_t_7; + + /* "View.MemoryView":1305 + * + * tmpdata = copy_data_to_temp(&src, &tmp, order, ndim) + * src = tmp # <<<<<<<<<<<<<< + * + * if not broadcasting: + */ + __pyx_v_src = __pyx_v_tmp; + + /* "View.MemoryView":1299 + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + * if slices_overlap(&src, &dst, ndim, itemsize): # <<<<<<<<<<<<<< + * + * if not slice_is_contig(src, order, ndim): + */ + } + + /* "View.MemoryView":1307 + * src = tmp + * + * if not broadcasting: # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = (!__pyx_v_broadcasting); + if (__pyx_t_2) { + + /* "View.MemoryView":1310 + * + * + * if slice_is_contig(src, 'C', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): + */ + __pyx_t_2 = __pyx_memviewslice_is_contig(__pyx_v_src, 'C', __pyx_v_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1311 + * + * if slice_is_contig(src, 'C', ndim): + * direct_copy = slice_is_contig(dst, 'C', ndim) # <<<<<<<<<<<<<< + * elif slice_is_contig(src, 'F', ndim): + * direct_copy = slice_is_contig(dst, 'F', ndim) + */ + __pyx_v_direct_copy = __pyx_memviewslice_is_contig(__pyx_v_dst, 'C', __pyx_v_ndim); + + /* "View.MemoryView":1310 + * + * + * if slice_is_contig(src, 'C', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): + */ + goto __pyx_L12; + } + + /* "View.MemoryView":1312 + * if slice_is_contig(src, 'C', ndim): + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + */ + __pyx_t_2 = __pyx_memviewslice_is_contig(__pyx_v_src, 'F', __pyx_v_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1313 + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): + * direct_copy = slice_is_contig(dst, 'F', ndim) # <<<<<<<<<<<<<< + * + * if direct_copy: + */ + __pyx_v_direct_copy = __pyx_memviewslice_is_contig(__pyx_v_dst, 'F', __pyx_v_ndim); + + /* "View.MemoryView":1312 + * if slice_is_contig(src, 'C', ndim): + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + */ + } + __pyx_L12:; + + /* "View.MemoryView":1315 + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + * if direct_copy: # <<<<<<<<<<<<<< + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + */ + if (__pyx_v_direct_copy) { + + /* "View.MemoryView":1317 + * if direct_copy: + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) # <<<<<<<<<<<<<< + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 0); + + /* "View.MemoryView":1318 + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) # <<<<<<<<<<<<<< + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * free(tmpdata) + */ + (void)(memcpy(__pyx_v_dst.data, __pyx_v_src.data, __pyx_memoryview_slice_get_size((&__pyx_v_src), __pyx_v_ndim))); + + /* "View.MemoryView":1319 + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) # <<<<<<<<<<<<<< + * free(tmpdata) + * return 0 + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 1); + + /* "View.MemoryView":1320 + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * free(tmpdata) # <<<<<<<<<<<<<< + * return 0 + * + */ + free(__pyx_v_tmpdata); + + /* "View.MemoryView":1321 + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * free(tmpdata) + * return 0 # <<<<<<<<<<<<<< + * + * if order == 'F' == get_best_order(&dst, ndim): + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":1315 + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + * if direct_copy: # <<<<<<<<<<<<<< + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + */ + } + + /* "View.MemoryView":1307 + * src = tmp + * + * if not broadcasting: # <<<<<<<<<<<<<< + * + * + */ + } + + /* "View.MemoryView":1323 + * return 0 + * + * if order == 'F' == get_best_order(&dst, ndim): # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = (__pyx_v_order == 'F'); + if (__pyx_t_2) { + __pyx_t_2 = ('F' == __pyx_get_best_slice_order((&__pyx_v_dst), __pyx_v_ndim)); + } + if (__pyx_t_2) { + + /* "View.MemoryView":1326 + * + * + * transpose_memslice(&src) # <<<<<<<<<<<<<< + * transpose_memslice(&dst) + * + */ + __pyx_t_5 = __pyx_memslice_transpose((&__pyx_v_src)); if (unlikely(__pyx_t_5 == ((int)-1))) __PYX_ERR(0, 1326, __pyx_L1_error) + + /* "View.MemoryView":1327 + * + * transpose_memslice(&src) + * transpose_memslice(&dst) # <<<<<<<<<<<<<< + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + */ + __pyx_t_5 = __pyx_memslice_transpose((&__pyx_v_dst)); if (unlikely(__pyx_t_5 == ((int)-1))) __PYX_ERR(0, 1327, __pyx_L1_error) + + /* "View.MemoryView":1323 + * return 0 + * + * if order == 'F' == get_best_order(&dst, ndim): # <<<<<<<<<<<<<< + * + * + */ + } + + /* "View.MemoryView":1329 + * transpose_memslice(&dst) + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) # <<<<<<<<<<<<<< + * copy_strided_to_strided(&src, &dst, ndim, itemsize) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 0); + + /* "View.MemoryView":1330 + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * copy_strided_to_strided(&src, &dst, ndim, itemsize) # <<<<<<<<<<<<<< + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * + */ + copy_strided_to_strided((&__pyx_v_src), (&__pyx_v_dst), __pyx_v_ndim, __pyx_v_itemsize); + + /* "View.MemoryView":1331 + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * copy_strided_to_strided(&src, &dst, ndim, itemsize) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) # <<<<<<<<<<<<<< + * + * free(tmpdata) + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 1); + + /* "View.MemoryView":1333 + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * + * free(tmpdata) # <<<<<<<<<<<<<< + * return 0 + * + */ + free(__pyx_v_tmpdata); + + /* "View.MemoryView":1334 + * + * free(tmpdata) + * return 0 # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_broadcast_leading') + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":1265 + * + * @cname('__pyx_memoryview_copy_contents') + * cdef int memoryview_copy_contents(__Pyx_memviewslice src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice dst, + * int src_ndim, int dst_ndim, + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.memoryview_copy_contents", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1337 + * + * @cname('__pyx_memoryview_broadcast_leading') + * cdef void broadcast_leading(__Pyx_memviewslice *mslice, # <<<<<<<<<<<<<< + * int ndim, + * int ndim_other) noexcept nogil: + */ + +static void __pyx_memoryview_broadcast_leading(__Pyx_memviewslice *__pyx_v_mslice, int __pyx_v_ndim, int __pyx_v_ndim_other) { + int __pyx_v_i; + int __pyx_v_offset; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + + /* "View.MemoryView":1341 + * int ndim_other) noexcept nogil: + * cdef int i + * cdef int offset = ndim_other - ndim # <<<<<<<<<<<<<< + * + * for i in range(ndim - 1, -1, -1): + */ + __pyx_v_offset = (__pyx_v_ndim_other - __pyx_v_ndim); + + /* "View.MemoryView":1343 + * cdef int offset = ndim_other - ndim + * + * for i in range(ndim - 1, -1, -1): # <<<<<<<<<<<<<< + * mslice.shape[i + offset] = mslice.shape[i] + * mslice.strides[i + offset] = mslice.strides[i] + */ + for (__pyx_t_1 = (__pyx_v_ndim - 1); __pyx_t_1 > -1; __pyx_t_1-=1) { + __pyx_v_i = __pyx_t_1; + + /* "View.MemoryView":1344 + * + * for i in range(ndim - 1, -1, -1): + * mslice.shape[i + offset] = mslice.shape[i] # <<<<<<<<<<<<<< + * mslice.strides[i + offset] = mslice.strides[i] + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] + */ + (__pyx_v_mslice->shape[(__pyx_v_i + __pyx_v_offset)]) = (__pyx_v_mslice->shape[__pyx_v_i]); + + /* "View.MemoryView":1345 + * for i in range(ndim - 1, -1, -1): + * mslice.shape[i + offset] = mslice.shape[i] + * mslice.strides[i + offset] = mslice.strides[i] # <<<<<<<<<<<<<< + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] + * + */ + (__pyx_v_mslice->strides[(__pyx_v_i + __pyx_v_offset)]) = (__pyx_v_mslice->strides[__pyx_v_i]); + + /* "View.MemoryView":1346 + * mslice.shape[i + offset] = mslice.shape[i] + * mslice.strides[i + offset] = mslice.strides[i] + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] # <<<<<<<<<<<<<< + * + * for i in range(offset): + */ + (__pyx_v_mslice->suboffsets[(__pyx_v_i + __pyx_v_offset)]) = (__pyx_v_mslice->suboffsets[__pyx_v_i]); + } + + /* "View.MemoryView":1348 + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] + * + * for i in range(offset): # <<<<<<<<<<<<<< + * mslice.shape[i] = 1 + * mslice.strides[i] = mslice.strides[0] + */ + __pyx_t_1 = __pyx_v_offset; + __pyx_t_2 = __pyx_t_1; + for (__pyx_t_3 = 0; __pyx_t_3 < __pyx_t_2; __pyx_t_3+=1) { + __pyx_v_i = __pyx_t_3; + + /* "View.MemoryView":1349 + * + * for i in range(offset): + * mslice.shape[i] = 1 # <<<<<<<<<<<<<< + * mslice.strides[i] = mslice.strides[0] + * mslice.suboffsets[i] = -1 + */ + (__pyx_v_mslice->shape[__pyx_v_i]) = 1; + + /* "View.MemoryView":1350 + * for i in range(offset): + * mslice.shape[i] = 1 + * mslice.strides[i] = mslice.strides[0] # <<<<<<<<<<<<<< + * mslice.suboffsets[i] = -1 + * + */ + (__pyx_v_mslice->strides[__pyx_v_i]) = (__pyx_v_mslice->strides[0]); + + /* "View.MemoryView":1351 + * mslice.shape[i] = 1 + * mslice.strides[i] = mslice.strides[0] + * mslice.suboffsets[i] = -1 # <<<<<<<<<<<<<< + * + * + */ + (__pyx_v_mslice->suboffsets[__pyx_v_i]) = -1L; + } + + /* "View.MemoryView":1337 + * + * @cname('__pyx_memoryview_broadcast_leading') + * cdef void broadcast_leading(__Pyx_memviewslice *mslice, # <<<<<<<<<<<<<< + * int ndim, + * int ndim_other) noexcept nogil: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1359 + * + * @cname('__pyx_memoryview_refcount_copying') + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: # <<<<<<<<<<<<<< + * + * if dtype_is_object: + */ + +static void __pyx_memoryview_refcount_copying(__Pyx_memviewslice *__pyx_v_dst, int __pyx_v_dtype_is_object, int __pyx_v_ndim, int __pyx_v_inc) { + + /* "View.MemoryView":1361 + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: + * + * if dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice_with_gil(dst.data, dst.shape, dst.strides, ndim, inc) + * + */ + if (__pyx_v_dtype_is_object) { + + /* "View.MemoryView":1362 + * + * if dtype_is_object: + * refcount_objects_in_slice_with_gil(dst.data, dst.shape, dst.strides, ndim, inc) # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_refcount_objects_in_slice_with_gil') + */ + __pyx_memoryview_refcount_objects_in_slice_with_gil(__pyx_v_dst->data, __pyx_v_dst->shape, __pyx_v_dst->strides, __pyx_v_ndim, __pyx_v_inc); + + /* "View.MemoryView":1361 + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: + * + * if dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice_with_gil(dst.data, dst.shape, dst.strides, ndim, inc) + * + */ + } + + /* "View.MemoryView":1359 + * + * @cname('__pyx_memoryview_refcount_copying') + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: # <<<<<<<<<<<<<< + * + * if dtype_is_object: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1365 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice_with_gil') + * cdef void refcount_objects_in_slice_with_gil(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * bint inc) noexcept with gil: + */ + +static void __pyx_memoryview_refcount_objects_in_slice_with_gil(char *__pyx_v_data, Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, int __pyx_v_ndim, int __pyx_v_inc) { + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + + /* "View.MemoryView":1368 + * Py_ssize_t *strides, int ndim, + * bint inc) noexcept with gil: + * refcount_objects_in_slice(data, shape, strides, ndim, inc) # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_refcount_objects_in_slice') + */ + __pyx_memoryview_refcount_objects_in_slice(__pyx_v_data, __pyx_v_shape, __pyx_v_strides, __pyx_v_ndim, __pyx_v_inc); + + /* "View.MemoryView":1365 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice_with_gil') + * cdef void refcount_objects_in_slice_with_gil(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * bint inc) noexcept with gil: + */ + + /* function exit code */ + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif +} + +/* "View.MemoryView":1371 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice') + * cdef void refcount_objects_in_slice(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, bint inc) noexcept: + * cdef Py_ssize_t i + */ + +static void __pyx_memoryview_refcount_objects_in_slice(char *__pyx_v_data, Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, int __pyx_v_ndim, int __pyx_v_inc) { + CYTHON_UNUSED Py_ssize_t __pyx_v_i; + Py_ssize_t __pyx_v_stride; + Py_ssize_t __pyx_t_1; + Py_ssize_t __pyx_t_2; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + + /* "View.MemoryView":1374 + * Py_ssize_t *strides, int ndim, bint inc) noexcept: + * cdef Py_ssize_t i + * cdef Py_ssize_t stride = strides[0] # <<<<<<<<<<<<<< + * + * for i in range(shape[0]): + */ + __pyx_v_stride = (__pyx_v_strides[0]); + + /* "View.MemoryView":1376 + * cdef Py_ssize_t stride = strides[0] + * + * for i in range(shape[0]): # <<<<<<<<<<<<<< + * if ndim == 1: + * if inc: + */ + __pyx_t_1 = (__pyx_v_shape[0]); + __pyx_t_2 = __pyx_t_1; + for (__pyx_t_3 = 0; __pyx_t_3 < __pyx_t_2; __pyx_t_3+=1) { + __pyx_v_i = __pyx_t_3; + + /* "View.MemoryView":1377 + * + * for i in range(shape[0]): + * if ndim == 1: # <<<<<<<<<<<<<< + * if inc: + * Py_INCREF(( data)[0]) + */ + __pyx_t_4 = (__pyx_v_ndim == 1); + if (__pyx_t_4) { + + /* "View.MemoryView":1378 + * for i in range(shape[0]): + * if ndim == 1: + * if inc: # <<<<<<<<<<<<<< + * Py_INCREF(( data)[0]) + * else: + */ + if (__pyx_v_inc) { + + /* "View.MemoryView":1379 + * if ndim == 1: + * if inc: + * Py_INCREF(( data)[0]) # <<<<<<<<<<<<<< + * else: + * Py_DECREF(( data)[0]) + */ + Py_INCREF((((PyObject **)__pyx_v_data)[0])); + + /* "View.MemoryView":1378 + * for i in range(shape[0]): + * if ndim == 1: + * if inc: # <<<<<<<<<<<<<< + * Py_INCREF(( data)[0]) + * else: + */ + goto __pyx_L6; + } + + /* "View.MemoryView":1381 + * Py_INCREF(( data)[0]) + * else: + * Py_DECREF(( data)[0]) # <<<<<<<<<<<<<< + * else: + * refcount_objects_in_slice(data, shape + 1, strides + 1, ndim - 1, inc) + */ + /*else*/ { + Py_DECREF((((PyObject **)__pyx_v_data)[0])); + } + __pyx_L6:; + + /* "View.MemoryView":1377 + * + * for i in range(shape[0]): + * if ndim == 1: # <<<<<<<<<<<<<< + * if inc: + * Py_INCREF(( data)[0]) + */ + goto __pyx_L5; + } + + /* "View.MemoryView":1383 + * Py_DECREF(( data)[0]) + * else: + * refcount_objects_in_slice(data, shape + 1, strides + 1, ndim - 1, inc) # <<<<<<<<<<<<<< + * + * data += stride + */ + /*else*/ { + __pyx_memoryview_refcount_objects_in_slice(__pyx_v_data, (__pyx_v_shape + 1), (__pyx_v_strides + 1), (__pyx_v_ndim - 1), __pyx_v_inc); + } + __pyx_L5:; + + /* "View.MemoryView":1385 + * refcount_objects_in_slice(data, shape + 1, strides + 1, ndim - 1, inc) + * + * data += stride # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_data = (__pyx_v_data + __pyx_v_stride); + } + + /* "View.MemoryView":1371 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice') + * cdef void refcount_objects_in_slice(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, bint inc) noexcept: + * cdef Py_ssize_t i + */ + + /* function exit code */ +} + +/* "View.MemoryView":1391 + * + * @cname('__pyx_memoryview_slice_assign_scalar') + * cdef void slice_assign_scalar(__Pyx_memviewslice *dst, int ndim, # <<<<<<<<<<<<<< + * size_t itemsize, void *item, + * bint dtype_is_object) noexcept nogil: + */ + +static void __pyx_memoryview_slice_assign_scalar(__Pyx_memviewslice *__pyx_v_dst, int __pyx_v_ndim, size_t __pyx_v_itemsize, void *__pyx_v_item, int __pyx_v_dtype_is_object) { + + /* "View.MemoryView":1394 + * size_t itemsize, void *item, + * bint dtype_is_object) noexcept nogil: + * refcount_copying(dst, dtype_is_object, ndim, inc=False) # <<<<<<<<<<<<<< + * _slice_assign_scalar(dst.data, dst.shape, dst.strides, ndim, itemsize, item) + * refcount_copying(dst, dtype_is_object, ndim, inc=True) + */ + __pyx_memoryview_refcount_copying(__pyx_v_dst, __pyx_v_dtype_is_object, __pyx_v_ndim, 0); + + /* "View.MemoryView":1395 + * bint dtype_is_object) noexcept nogil: + * refcount_copying(dst, dtype_is_object, ndim, inc=False) + * _slice_assign_scalar(dst.data, dst.shape, dst.strides, ndim, itemsize, item) # <<<<<<<<<<<<<< + * refcount_copying(dst, dtype_is_object, ndim, inc=True) + * + */ + __pyx_memoryview__slice_assign_scalar(__pyx_v_dst->data, __pyx_v_dst->shape, __pyx_v_dst->strides, __pyx_v_ndim, __pyx_v_itemsize, __pyx_v_item); + + /* "View.MemoryView":1396 + * refcount_copying(dst, dtype_is_object, ndim, inc=False) + * _slice_assign_scalar(dst.data, dst.shape, dst.strides, ndim, itemsize, item) + * refcount_copying(dst, dtype_is_object, ndim, inc=True) # <<<<<<<<<<<<<< + * + * + */ + __pyx_memoryview_refcount_copying(__pyx_v_dst, __pyx_v_dtype_is_object, __pyx_v_ndim, 1); + + /* "View.MemoryView":1391 + * + * @cname('__pyx_memoryview_slice_assign_scalar') + * cdef void slice_assign_scalar(__Pyx_memviewslice *dst, int ndim, # <<<<<<<<<<<<<< + * size_t itemsize, void *item, + * bint dtype_is_object) noexcept nogil: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1400 + * + * @cname('__pyx_memoryview__slice_assign_scalar') + * cdef void _slice_assign_scalar(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * size_t itemsize, void *item) noexcept nogil: + */ + +static void __pyx_memoryview__slice_assign_scalar(char *__pyx_v_data, Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, int __pyx_v_ndim, size_t __pyx_v_itemsize, void *__pyx_v_item) { + CYTHON_UNUSED Py_ssize_t __pyx_v_i; + Py_ssize_t __pyx_v_stride; + Py_ssize_t __pyx_v_extent; + int __pyx_t_1; + Py_ssize_t __pyx_t_2; + Py_ssize_t __pyx_t_3; + Py_ssize_t __pyx_t_4; + + /* "View.MemoryView":1404 + * size_t itemsize, void *item) noexcept nogil: + * cdef Py_ssize_t i + * cdef Py_ssize_t stride = strides[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t extent = shape[0] + * + */ + __pyx_v_stride = (__pyx_v_strides[0]); + + /* "View.MemoryView":1405 + * cdef Py_ssize_t i + * cdef Py_ssize_t stride = strides[0] + * cdef Py_ssize_t extent = shape[0] # <<<<<<<<<<<<<< + * + * if ndim == 1: + */ + __pyx_v_extent = (__pyx_v_shape[0]); + + /* "View.MemoryView":1407 + * cdef Py_ssize_t extent = shape[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * for i in range(extent): + * memcpy(data, item, itemsize) + */ + __pyx_t_1 = (__pyx_v_ndim == 1); + if (__pyx_t_1) { + + /* "View.MemoryView":1408 + * + * if ndim == 1: + * for i in range(extent): # <<<<<<<<<<<<<< + * memcpy(data, item, itemsize) + * data += stride + */ + __pyx_t_2 = __pyx_v_extent; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1409 + * if ndim == 1: + * for i in range(extent): + * memcpy(data, item, itemsize) # <<<<<<<<<<<<<< + * data += stride + * else: + */ + (void)(memcpy(__pyx_v_data, __pyx_v_item, __pyx_v_itemsize)); + + /* "View.MemoryView":1410 + * for i in range(extent): + * memcpy(data, item, itemsize) + * data += stride # <<<<<<<<<<<<<< + * else: + * for i in range(extent): + */ + __pyx_v_data = (__pyx_v_data + __pyx_v_stride); + } + + /* "View.MemoryView":1407 + * cdef Py_ssize_t extent = shape[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * for i in range(extent): + * memcpy(data, item, itemsize) + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1412 + * data += stride + * else: + * for i in range(extent): # <<<<<<<<<<<<<< + * _slice_assign_scalar(data, shape + 1, strides + 1, ndim - 1, itemsize, item) + * data += stride + */ + /*else*/ { + __pyx_t_2 = __pyx_v_extent; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1413 + * else: + * for i in range(extent): + * _slice_assign_scalar(data, shape + 1, strides + 1, ndim - 1, itemsize, item) # <<<<<<<<<<<<<< + * data += stride + * + */ + __pyx_memoryview__slice_assign_scalar(__pyx_v_data, (__pyx_v_shape + 1), (__pyx_v_strides + 1), (__pyx_v_ndim - 1), __pyx_v_itemsize, __pyx_v_item); + + /* "View.MemoryView":1414 + * for i in range(extent): + * _slice_assign_scalar(data, shape + 1, strides + 1, ndim - 1, itemsize, item) + * data += stride # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_data = (__pyx_v_data + __pyx_v_stride); + } + } + __pyx_L3:; + + /* "View.MemoryView":1400 + * + * @cname('__pyx_memoryview__slice_assign_scalar') + * cdef void _slice_assign_scalar(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * size_t itemsize, void *item) noexcept nogil: + */ + + /* function exit code */ +} + +/* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_1__pyx_unpickle_Enum(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_15View_dot_MemoryView_1__pyx_unpickle_Enum = {"__pyx_unpickle_Enum", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15View_dot_MemoryView_1__pyx_unpickle_Enum, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15View_dot_MemoryView_1__pyx_unpickle_Enum(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v___pyx_type = 0; + long __pyx_v___pyx_checksum; + PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__pyx_unpickle_Enum (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_type,&__pyx_n_s_pyx_checksum,&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_type)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 1, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_checksum)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 1, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle_Enum", 1, 3, 3, 1); __PYX_ERR(0, 1, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 1, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle_Enum", 1, 3, 3, 2); __PYX_ERR(0, 1, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__pyx_unpickle_Enum") < 0)) __PYX_ERR(0, 1, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + } + __pyx_v___pyx_type = values[0]; + __pyx_v___pyx_checksum = __Pyx_PyInt_As_long(values[1]); if (unlikely((__pyx_v___pyx_checksum == (long)-1) && PyErr_Occurred())) __PYX_ERR(0, 1, __pyx_L3_error) + __pyx_v___pyx_state = values[2]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle_Enum", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 1, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.__pyx_unpickle_Enum", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15View_dot_MemoryView___pyx_unpickle_Enum(__pyx_self, __pyx_v___pyx_type, __pyx_v___pyx_checksum, __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView___pyx_unpickle_Enum(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v___pyx_type, long __pyx_v___pyx_checksum, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_v___pyx_PickleError = 0; + PyObject *__pyx_v___pyx_result = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_unpickle_Enum", 1); + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + */ + __pyx_t_1 = __Pyx_PyInt_From_long(__pyx_v___pyx_checksum); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 4, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = (__Pyx_PySequence_ContainsTF(__pyx_t_1, __pyx_tuple__8, Py_NE)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 4, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (__pyx_t_2) { + + /* "(tree fragment)":5 + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): + * from pickle import PickleError as __pyx_PickleError # <<<<<<<<<<<<<< + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) + */ + __pyx_t_1 = PyList_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_s_PickleError); + __Pyx_GIVEREF(__pyx_n_s_PickleError); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_s_PickleError)) __PYX_ERR(0, 5, __pyx_L1_error); + __pyx_t_3 = __Pyx_Import(__pyx_n_s_pickle, __pyx_t_1, 0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_ImportFrom(__pyx_t_3, __pyx_n_s_PickleError); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_t_1); + __pyx_v___pyx_PickleError = __pyx_t_1; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "(tree fragment)":6 + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum # <<<<<<<<<<<<<< + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: + */ + __pyx_t_3 = __Pyx_PyInt_From_long(__pyx_v___pyx_checksum); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_Incompatible_checksums_0x_x_vs_0, __pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_v___pyx_PickleError, __pyx_t_1, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 6, __pyx_L1_error) + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + */ + } + + /* "(tree fragment)":7 + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) # <<<<<<<<<<<<<< + * if __pyx_state is not None: + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_MemviewEnum_type), __pyx_n_s_new); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 7, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = NULL; + __pyx_t_5 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_5 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_4, __pyx_v___pyx_type}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_5, 1+__pyx_t_5); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 7, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_v___pyx_result = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":8 + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + */ + __pyx_t_2 = (__pyx_v___pyx_state != Py_None); + if (__pyx_t_2) { + + /* "(tree fragment)":9 + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) # <<<<<<<<<<<<<< + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + */ + if (!(likely(PyTuple_CheckExact(__pyx_v___pyx_state))||((__pyx_v___pyx_state) == Py_None) || __Pyx_RaiseUnexpectedTypeError("tuple", __pyx_v___pyx_state))) __PYX_ERR(0, 9, __pyx_L1_error) + __pyx_t_1 = __pyx_unpickle_Enum__set_state(((struct __pyx_MemviewEnum_obj *)__pyx_v___pyx_result), ((PyObject*)__pyx_v___pyx_state)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 9, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":8 + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + */ + } + + /* "(tree fragment)":10 + * if __pyx_state is not None: + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result # <<<<<<<<<<<<<< + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v___pyx_result); + __pyx_r = __pyx_v___pyx_result; + goto __pyx_L0; + + /* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.__pyx_unpickle_Enum", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v___pyx_PickleError); + __Pyx_XDECREF(__pyx_v___pyx_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":11 + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): # <<<<<<<<<<<<<< + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + */ + +static PyObject *__pyx_unpickle_Enum__set_state(struct __pyx_MemviewEnum_obj *__pyx_v___pyx_result, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + int __pyx_t_8; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_unpickle_Enum__set_state", 1); + + /* "(tree fragment)":12 + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] # <<<<<<<<<<<<<< + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + * __pyx_result.__dict__.update(__pyx_state[1]) + */ + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(0, 12, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 12, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + __Pyx_GOTREF(__pyx_v___pyx_result->name); + __Pyx_DECREF(__pyx_v___pyx_result->name); + __pyx_v___pyx_result->name = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":13 + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): # <<<<<<<<<<<<<< + * __pyx_result.__dict__.update(__pyx_state[1]) + */ + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); + __PYX_ERR(0, 13, __pyx_L1_error) + } + __pyx_t_3 = __Pyx_PyTuple_GET_SIZE(__pyx_v___pyx_state); if (unlikely(__pyx_t_3 == ((Py_ssize_t)-1))) __PYX_ERR(0, 13, __pyx_L1_error) + __pyx_t_4 = (__pyx_t_3 > 1); + if (__pyx_t_4) { + } else { + __pyx_t_2 = __pyx_t_4; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_4 = __Pyx_HasAttr(((PyObject *)__pyx_v___pyx_result), __pyx_n_s_dict); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(0, 13, __pyx_L1_error) + __pyx_t_2 = __pyx_t_4; + __pyx_L4_bool_binop_done:; + if (__pyx_t_2) { + + /* "(tree fragment)":14 + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + * __pyx_result.__dict__.update(__pyx_state[1]) # <<<<<<<<<<<<<< + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v___pyx_result), __pyx_n_s_dict); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_update); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(0, 14, __pyx_L1_error) + } + __pyx_t_5 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_7 = NULL; + __pyx_t_8 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_6))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_6); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_6); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_6, function); + __pyx_t_8 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_7, __pyx_t_5}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_6, __pyx_callargs+1-__pyx_t_8, 1+__pyx_t_8); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":13 + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): # <<<<<<<<<<<<<< + * __pyx_result.__dict__.update(__pyx_state[1]) + */ + } + + /* "(tree fragment)":11 + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): # <<<<<<<<<<<<<< + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("View.MemoryView.__pyx_unpickle_Enum__set_state", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "selfdrive/modeld/runners/runmodel_pyx.pyx":15 + * + * cdef class RunModel: + * def __dealloc__(self): # <<<<<<<<<<<<<< + * del self.model + * + */ + +/* Python wrapper */ +static void __pyx_pw_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_1__dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_pw_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_1__dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_pf_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel___dealloc__(((struct __pyx_obj_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_pf_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel___dealloc__(struct __pyx_obj_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel *__pyx_v_self) { + + /* "selfdrive/modeld/runners/runmodel_pyx.pyx":16 + * cdef class RunModel: + * def __dealloc__(self): + * del self.model # <<<<<<<<<<<<<< + * + * def addInput(self, string name, float[:] buffer): + */ + delete __pyx_v_self->model; + + /* "selfdrive/modeld/runners/runmodel_pyx.pyx":15 + * + * cdef class RunModel: + * def __dealloc__(self): # <<<<<<<<<<<<<< + * del self.model + * + */ + + /* function exit code */ +} + +/* "selfdrive/modeld/runners/runmodel_pyx.pyx":18 + * del self.model + * + * def addInput(self, string name, float[:] buffer): # <<<<<<<<<<<<<< + * if buffer is not None: + * self.model.addInput(name, &buffer[0], len(buffer)) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_3addInput(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_3addInput = {"addInput", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_3addInput, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_3addInput(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + std::string __pyx_v_name; + __Pyx_memviewslice __pyx_v_buffer = { 0, 0, { 0 }, { 0 }, { 0 } }; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[2] = {0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("addInput (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_name,&__pyx_n_s_buffer,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_name)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 18, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_buffer)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 18, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("addInput", 1, 2, 2, 1); __PYX_ERR(1, 18, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "addInput") < 0)) __PYX_ERR(1, 18, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 2)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + } + __pyx_v_name = __pyx_convert_string_from_py_std__in_string(values[0]); if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 18, __pyx_L3_error) + __pyx_v_buffer = __Pyx_PyObject_to_MemoryviewSlice_ds_float(values[1], PyBUF_WRITABLE); if (unlikely(!__pyx_v_buffer.memview)) __PYX_ERR(1, 18, __pyx_L3_error) + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("addInput", 1, 2, 2, __pyx_nargs); __PYX_ERR(1, 18, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __PYX_XCLEAR_MEMVIEW(&__pyx_v_buffer, 1); + __Pyx_AddTraceback("selfdrive.modeld.runners.runmodel_pyx.RunModel.addInput", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_2addInput(((struct __pyx_obj_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel *)__pyx_v_self), __PYX_STD_MOVE_IF_SUPPORTED(__pyx_v_name), __pyx_v_buffer); + + /* function exit code */ + __PYX_XCLEAR_MEMVIEW(&__pyx_v_buffer, 1); + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_2addInput(struct __pyx_obj_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel *__pyx_v_self, std::string __pyx_v_name, __Pyx_memviewslice __pyx_v_buffer) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + Py_ssize_t __pyx_t_2; + int __pyx_t_3; + Py_ssize_t __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("addInput", 1); + + /* "selfdrive/modeld/runners/runmodel_pyx.pyx":19 + * + * def addInput(self, string name, float[:] buffer): + * if buffer is not None: # <<<<<<<<<<<<<< + * self.model.addInput(name, &buffer[0], len(buffer)) + * else: + */ + __pyx_t_1 = (((PyObject *) __pyx_v_buffer.memview) != Py_None); + if (__pyx_t_1) { + + /* "selfdrive/modeld/runners/runmodel_pyx.pyx":20 + * def addInput(self, string name, float[:] buffer): + * if buffer is not None: + * self.model.addInput(name, &buffer[0], len(buffer)) # <<<<<<<<<<<<<< + * else: + * self.model.addInput(name, NULL, 0) + */ + __pyx_t_2 = 0; + __pyx_t_3 = -1; + if (__pyx_t_2 < 0) { + __pyx_t_2 += __pyx_v_buffer.shape[0]; + if (unlikely(__pyx_t_2 < 0)) __pyx_t_3 = 0; + } else if (unlikely(__pyx_t_2 >= __pyx_v_buffer.shape[0])) __pyx_t_3 = 0; + if (unlikely(__pyx_t_3 != -1)) { + __Pyx_RaiseBufferIndexError(__pyx_t_3); + __PYX_ERR(1, 20, __pyx_L1_error) + } + __pyx_t_4 = __Pyx_MemoryView_Len(__pyx_v_buffer); + __pyx_v_self->model->addInput(__pyx_v_name, (&(*((float *) ( /* dim=0 */ (__pyx_v_buffer.data + __pyx_t_2 * __pyx_v_buffer.strides[0]) )))), __pyx_t_4); + + /* "selfdrive/modeld/runners/runmodel_pyx.pyx":19 + * + * def addInput(self, string name, float[:] buffer): + * if buffer is not None: # <<<<<<<<<<<<<< + * self.model.addInput(name, &buffer[0], len(buffer)) + * else: + */ + goto __pyx_L3; + } + + /* "selfdrive/modeld/runners/runmodel_pyx.pyx":22 + * self.model.addInput(name, &buffer[0], len(buffer)) + * else: + * self.model.addInput(name, NULL, 0) # <<<<<<<<<<<<<< + * + * def setInputBuffer(self, string name, float[:] buffer): + */ + /*else*/ { + __pyx_v_self->model->addInput(__pyx_v_name, NULL, 0); + } + __pyx_L3:; + + /* "selfdrive/modeld/runners/runmodel_pyx.pyx":18 + * del self.model + * + * def addInput(self, string name, float[:] buffer): # <<<<<<<<<<<<<< + * if buffer is not None: + * self.model.addInput(name, &buffer[0], len(buffer)) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("selfdrive.modeld.runners.runmodel_pyx.RunModel.addInput", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "selfdrive/modeld/runners/runmodel_pyx.pyx":24 + * self.model.addInput(name, NULL, 0) + * + * def setInputBuffer(self, string name, float[:] buffer): # <<<<<<<<<<<<<< + * if buffer is not None: + * self.model.setInputBuffer(name, &buffer[0], len(buffer)) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_5setInputBuffer(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_5setInputBuffer = {"setInputBuffer", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_5setInputBuffer, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_5setInputBuffer(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + std::string __pyx_v_name; + __Pyx_memviewslice __pyx_v_buffer = { 0, 0, { 0 }, { 0 }, { 0 } }; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[2] = {0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("setInputBuffer (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_name,&__pyx_n_s_buffer,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_name)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 24, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_buffer)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 24, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("setInputBuffer", 1, 2, 2, 1); __PYX_ERR(1, 24, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "setInputBuffer") < 0)) __PYX_ERR(1, 24, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 2)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + } + __pyx_v_name = __pyx_convert_string_from_py_std__in_string(values[0]); if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 24, __pyx_L3_error) + __pyx_v_buffer = __Pyx_PyObject_to_MemoryviewSlice_ds_float(values[1], PyBUF_WRITABLE); if (unlikely(!__pyx_v_buffer.memview)) __PYX_ERR(1, 24, __pyx_L3_error) + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("setInputBuffer", 1, 2, 2, __pyx_nargs); __PYX_ERR(1, 24, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __PYX_XCLEAR_MEMVIEW(&__pyx_v_buffer, 1); + __Pyx_AddTraceback("selfdrive.modeld.runners.runmodel_pyx.RunModel.setInputBuffer", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_4setInputBuffer(((struct __pyx_obj_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel *)__pyx_v_self), __PYX_STD_MOVE_IF_SUPPORTED(__pyx_v_name), __pyx_v_buffer); + + /* function exit code */ + __PYX_XCLEAR_MEMVIEW(&__pyx_v_buffer, 1); + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_4setInputBuffer(struct __pyx_obj_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel *__pyx_v_self, std::string __pyx_v_name, __Pyx_memviewslice __pyx_v_buffer) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + Py_ssize_t __pyx_t_2; + int __pyx_t_3; + Py_ssize_t __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("setInputBuffer", 1); + + /* "selfdrive/modeld/runners/runmodel_pyx.pyx":25 + * + * def setInputBuffer(self, string name, float[:] buffer): + * if buffer is not None: # <<<<<<<<<<<<<< + * self.model.setInputBuffer(name, &buffer[0], len(buffer)) + * else: + */ + __pyx_t_1 = (((PyObject *) __pyx_v_buffer.memview) != Py_None); + if (__pyx_t_1) { + + /* "selfdrive/modeld/runners/runmodel_pyx.pyx":26 + * def setInputBuffer(self, string name, float[:] buffer): + * if buffer is not None: + * self.model.setInputBuffer(name, &buffer[0], len(buffer)) # <<<<<<<<<<<<<< + * else: + * self.model.setInputBuffer(name, NULL, 0) + */ + __pyx_t_2 = 0; + __pyx_t_3 = -1; + if (__pyx_t_2 < 0) { + __pyx_t_2 += __pyx_v_buffer.shape[0]; + if (unlikely(__pyx_t_2 < 0)) __pyx_t_3 = 0; + } else if (unlikely(__pyx_t_2 >= __pyx_v_buffer.shape[0])) __pyx_t_3 = 0; + if (unlikely(__pyx_t_3 != -1)) { + __Pyx_RaiseBufferIndexError(__pyx_t_3); + __PYX_ERR(1, 26, __pyx_L1_error) + } + __pyx_t_4 = __Pyx_MemoryView_Len(__pyx_v_buffer); + __pyx_v_self->model->setInputBuffer(__pyx_v_name, (&(*((float *) ( /* dim=0 */ (__pyx_v_buffer.data + __pyx_t_2 * __pyx_v_buffer.strides[0]) )))), __pyx_t_4); + + /* "selfdrive/modeld/runners/runmodel_pyx.pyx":25 + * + * def setInputBuffer(self, string name, float[:] buffer): + * if buffer is not None: # <<<<<<<<<<<<<< + * self.model.setInputBuffer(name, &buffer[0], len(buffer)) + * else: + */ + goto __pyx_L3; + } + + /* "selfdrive/modeld/runners/runmodel_pyx.pyx":28 + * self.model.setInputBuffer(name, &buffer[0], len(buffer)) + * else: + * self.model.setInputBuffer(name, NULL, 0) # <<<<<<<<<<<<<< + * + * def getCLBuffer(self, string name): + */ + /*else*/ { + __pyx_v_self->model->setInputBuffer(__pyx_v_name, NULL, 0); + } + __pyx_L3:; + + /* "selfdrive/modeld/runners/runmodel_pyx.pyx":24 + * self.model.addInput(name, NULL, 0) + * + * def setInputBuffer(self, string name, float[:] buffer): # <<<<<<<<<<<<<< + * if buffer is not None: + * self.model.setInputBuffer(name, &buffer[0], len(buffer)) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("selfdrive.modeld.runners.runmodel_pyx.RunModel.setInputBuffer", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "selfdrive/modeld/runners/runmodel_pyx.pyx":30 + * self.model.setInputBuffer(name, NULL, 0) + * + * def getCLBuffer(self, string name): # <<<<<<<<<<<<<< + * cdef void * cl_buf = self.model.getCLBuffer(name) + * if not cl_buf: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_7getCLBuffer(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_7getCLBuffer = {"getCLBuffer", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_7getCLBuffer, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_7getCLBuffer(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + std::string __pyx_v_name; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("getCLBuffer (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_name,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_name)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 30, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "getCLBuffer") < 0)) __PYX_ERR(1, 30, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v_name = __pyx_convert_string_from_py_std__in_string(values[0]); if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 30, __pyx_L3_error) + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("getCLBuffer", 1, 1, 1, __pyx_nargs); __PYX_ERR(1, 30, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("selfdrive.modeld.runners.runmodel_pyx.RunModel.getCLBuffer", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_6getCLBuffer(((struct __pyx_obj_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel *)__pyx_v_self), __PYX_STD_MOVE_IF_SUPPORTED(__pyx_v_name)); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_6getCLBuffer(struct __pyx_obj_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel *__pyx_v_self, std::string __pyx_v_name) { + void *__pyx_v_cl_buf; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("getCLBuffer", 1); + + /* "selfdrive/modeld/runners/runmodel_pyx.pyx":31 + * + * def getCLBuffer(self, string name): + * cdef void * cl_buf = self.model.getCLBuffer(name) # <<<<<<<<<<<<<< + * if not cl_buf: + * return None + */ + __pyx_v_cl_buf = __pyx_v_self->model->getCLBuffer(__pyx_v_name); + + /* "selfdrive/modeld/runners/runmodel_pyx.pyx":32 + * def getCLBuffer(self, string name): + * cdef void * cl_buf = self.model.getCLBuffer(name) + * if not cl_buf: # <<<<<<<<<<<<<< + * return None + * return CLMem.create(cl_buf) + */ + __pyx_t_1 = (!(__pyx_v_cl_buf != 0)); + if (__pyx_t_1) { + + /* "selfdrive/modeld/runners/runmodel_pyx.pyx":33 + * cdef void * cl_buf = self.model.getCLBuffer(name) + * if not cl_buf: + * return None # <<<<<<<<<<<<<< + * return CLMem.create(cl_buf) + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "selfdrive/modeld/runners/runmodel_pyx.pyx":32 + * def getCLBuffer(self, string name): + * cdef void * cl_buf = self.model.getCLBuffer(name) + * if not cl_buf: # <<<<<<<<<<<<<< + * return None + * return CLMem.create(cl_buf) + */ + } + + /* "selfdrive/modeld/runners/runmodel_pyx.pyx":34 + * if not cl_buf: + * return None + * return CLMem.create(cl_buf) # <<<<<<<<<<<<<< + * + * def execute(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_vtabptr_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem->create(__pyx_v_cl_buf); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 34, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "selfdrive/modeld/runners/runmodel_pyx.pyx":30 + * self.model.setInputBuffer(name, NULL, 0) + * + * def getCLBuffer(self, string name): # <<<<<<<<<<<<<< + * cdef void * cl_buf = self.model.getCLBuffer(name) + * if not cl_buf: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("selfdrive.modeld.runners.runmodel_pyx.RunModel.getCLBuffer", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "selfdrive/modeld/runners/runmodel_pyx.pyx":36 + * return CLMem.create(cl_buf) + * + * def execute(self): # <<<<<<<<<<<<<< + * self.model.execute() + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_9execute(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_9execute = {"execute", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_9execute, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_9execute(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("execute (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("execute", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "execute", 0))) return NULL; + __pyx_r = __pyx_pf_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_8execute(((struct __pyx_obj_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_8execute(struct __pyx_obj_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("execute", 1); + + /* "selfdrive/modeld/runners/runmodel_pyx.pyx":37 + * + * def execute(self): + * self.model.execute() # <<<<<<<<<<<<<< + */ + __pyx_v_self->model->execute(); + + /* "selfdrive/modeld/runners/runmodel_pyx.pyx":36 + * return CLMem.create(cl_buf) + * + * def execute(self): # <<<<<<<<<<<<<< + * self.model.execute() + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.model cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_11__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_11__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_11__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_11__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_10__reduce_cython__(((struct __pyx_obj_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_10__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "self.model cannot be converted to a Python object for pickling" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "self.model cannot be converted to a Python object for pickling" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_self_model_cannot_be_converted_t, 0, 0); + __PYX_ERR(0, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.model cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("selfdrive.modeld.runners.runmodel_pyx.RunModel.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.model cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.model cannot be converted to a Python object for pickling" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_13__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_13__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_13__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_13__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(0, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("selfdrive.modeld.runners.runmodel_pyx.RunModel.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_12__setstate_cython__(((struct __pyx_obj_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_12__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "self.model cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "self.model cannot be converted to a Python object for pickling" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_self_model_cannot_be_converted_t, 0, 0); + __PYX_ERR(0, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.model cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.model cannot be converted to a Python object for pickling" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("selfdrive.modeld.runners.runmodel_pyx.RunModel.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_tp_new_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + return o; +} + +static void __pyx_tp_dealloc_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel(PyObject *o) { + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_pw_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_1__dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} + +static PyMethodDef __pyx_methods_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel[] = { + {"addInput", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_3addInput, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"setInputBuffer", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_5setInputBuffer, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"getCLBuffer", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_7getCLBuffer, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"execute", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_9execute, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_11__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_13__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel}, + {Py_tp_methods, (void *)__pyx_methods_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel}, + {Py_tp_new, (void *)__pyx_tp_new_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel}, + {0, 0}, +}; +static PyType_Spec __pyx_type_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel_spec = { + "selfdrive.modeld.runners.runmodel_pyx.RunModel", + sizeof(struct __pyx_obj_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, + __pyx_type_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel_slots, +}; +#else + +static PyTypeObject __pyx_type_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel = { + PyVarObject_HEAD_INIT(0, 0) + "selfdrive.modeld.runners.runmodel_pyx.""RunModel", /*tp_name*/ + sizeof(struct __pyx_obj_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE, /*tp_flags*/ + 0, /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif +static struct __pyx_vtabstruct_array __pyx_vtable_array; + +static PyObject *__pyx_tp_new_array(PyTypeObject *t, PyObject *a, PyObject *k) { + struct __pyx_array_obj *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_array_obj *)o); + p->__pyx_vtab = __pyx_vtabptr_array; + p->mode = ((PyObject*)Py_None); Py_INCREF(Py_None); + p->_format = ((PyObject*)Py_None); Py_INCREF(Py_None); + if (unlikely(__pyx_array___cinit__(o, a, k) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static void __pyx_tp_dealloc_array(PyObject *o) { + struct __pyx_array_obj *p = (struct __pyx_array_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_array) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_array___dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + Py_CLEAR(p->mode); + Py_CLEAR(p->_format); + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} +static PyObject *__pyx_sq_item_array(PyObject *o, Py_ssize_t i) { + PyObject *r; + PyObject *x = PyInt_FromSsize_t(i); if(!x) return 0; + r = Py_TYPE(o)->tp_as_mapping->mp_subscript(o, x); + Py_DECREF(x); + return r; +} + +static int __pyx_mp_ass_subscript_array(PyObject *o, PyObject *i, PyObject *v) { + if (v) { + return __pyx_array___setitem__(o, i, v); + } + else { + __Pyx_TypeName o_type_name; + o_type_name = __Pyx_PyType_GetName(Py_TYPE(o)); + PyErr_Format(PyExc_NotImplementedError, + "Subscript deletion not supported by " __Pyx_FMT_TYPENAME, o_type_name); + __Pyx_DECREF_TypeName(o_type_name); + return -1; + } +} + +static PyObject *__pyx_tp_getattro_array(PyObject *o, PyObject *n) { + PyObject *v = __Pyx_PyObject_GenericGetAttr(o, n); + if (!v && PyErr_ExceptionMatches(PyExc_AttributeError)) { + PyErr_Clear(); + v = __pyx_array___getattr__(o, n); + } + return v; +} + +static PyObject *__pyx_getprop___pyx_array_memview(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_5array_7memview_1__get__(o); +} + +static PyMethodDef __pyx_methods_array[] = { + {"__getattr__", (PyCFunction)__pyx_array___getattr__, METH_O|METH_COEXIST, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_array_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_array_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; + +static struct PyGetSetDef __pyx_getsets_array[] = { + {(char *)"memview", __pyx_getprop___pyx_array_memview, 0, (char *)0, 0}, + {0, 0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +#if !CYTHON_COMPILING_IN_LIMITED_API + +static PyBufferProcs __pyx_tp_as_buffer_array = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_array_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; +#endif +static PyType_Slot __pyx_type___pyx_array_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_array}, + {Py_sq_length, (void *)__pyx_array___len__}, + {Py_sq_item, (void *)__pyx_sq_item_array}, + {Py_mp_length, (void *)__pyx_array___len__}, + {Py_mp_subscript, (void *)__pyx_array___getitem__}, + {Py_mp_ass_subscript, (void *)__pyx_mp_ass_subscript_array}, + {Py_tp_getattro, (void *)__pyx_tp_getattro_array}, + #if defined(Py_bf_getbuffer) + {Py_bf_getbuffer, (void *)__pyx_array_getbuffer}, + #endif + {Py_tp_methods, (void *)__pyx_methods_array}, + {Py_tp_getset, (void *)__pyx_getsets_array}, + {Py_tp_new, (void *)__pyx_tp_new_array}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_array_spec = { + "selfdrive.modeld.runners.runmodel_pyx.array", + sizeof(struct __pyx_array_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_SEQUENCE, + __pyx_type___pyx_array_slots, +}; +#else + +static PySequenceMethods __pyx_tp_as_sequence_array = { + __pyx_array___len__, /*sq_length*/ + 0, /*sq_concat*/ + 0, /*sq_repeat*/ + __pyx_sq_item_array, /*sq_item*/ + 0, /*sq_slice*/ + 0, /*sq_ass_item*/ + 0, /*sq_ass_slice*/ + 0, /*sq_contains*/ + 0, /*sq_inplace_concat*/ + 0, /*sq_inplace_repeat*/ +}; + +static PyMappingMethods __pyx_tp_as_mapping_array = { + __pyx_array___len__, /*mp_length*/ + __pyx_array___getitem__, /*mp_subscript*/ + __pyx_mp_ass_subscript_array, /*mp_ass_subscript*/ +}; + +static PyBufferProcs __pyx_tp_as_buffer_array = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_array_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; + +static PyTypeObject __pyx_type___pyx_array = { + PyVarObject_HEAD_INIT(0, 0) + "selfdrive.modeld.runners.runmodel_pyx.""array", /*tp_name*/ + sizeof(struct __pyx_array_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_array, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + &__pyx_tp_as_sequence_array, /*tp_as_sequence*/ + &__pyx_tp_as_mapping_array, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + __pyx_tp_getattro_array, /*tp_getattro*/ + 0, /*tp_setattro*/ + &__pyx_tp_as_buffer_array, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_SEQUENCE, /*tp_flags*/ + 0, /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_array, /*tp_methods*/ + 0, /*tp_members*/ + __pyx_getsets_array, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_array, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyObject *__pyx_tp_new_Enum(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { + struct __pyx_MemviewEnum_obj *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_MemviewEnum_obj *)o); + p->name = Py_None; Py_INCREF(Py_None); + return o; +} + +static void __pyx_tp_dealloc_Enum(PyObject *o) { + struct __pyx_MemviewEnum_obj *p = (struct __pyx_MemviewEnum_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_Enum) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + Py_CLEAR(p->name); + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} + +static int __pyx_tp_traverse_Enum(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_MemviewEnum_obj *p = (struct __pyx_MemviewEnum_obj *)o; + if (p->name) { + e = (*v)(p->name, a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear_Enum(PyObject *o) { + PyObject* tmp; + struct __pyx_MemviewEnum_obj *p = (struct __pyx_MemviewEnum_obj *)o; + tmp = ((PyObject*)p->name); + p->name = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + return 0; +} + +static PyObject *__pyx_specialmethod___pyx_MemviewEnum___repr__(PyObject *self, CYTHON_UNUSED PyObject *arg) { + return __pyx_MemviewEnum___repr__(self); +} + +static PyMethodDef __pyx_methods_Enum[] = { + {"__repr__", (PyCFunction)__pyx_specialmethod___pyx_MemviewEnum___repr__, METH_NOARGS|METH_COEXIST, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_MemviewEnum_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_MemviewEnum_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type___pyx_MemviewEnum_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_Enum}, + {Py_tp_repr, (void *)__pyx_MemviewEnum___repr__}, + {Py_tp_traverse, (void *)__pyx_tp_traverse_Enum}, + {Py_tp_clear, (void *)__pyx_tp_clear_Enum}, + {Py_tp_methods, (void *)__pyx_methods_Enum}, + {Py_tp_init, (void *)__pyx_MemviewEnum___init__}, + {Py_tp_new, (void *)__pyx_tp_new_Enum}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_MemviewEnum_spec = { + "selfdrive.modeld.runners.runmodel_pyx.Enum", + sizeof(struct __pyx_MemviewEnum_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, + __pyx_type___pyx_MemviewEnum_slots, +}; +#else + +static PyTypeObject __pyx_type___pyx_MemviewEnum = { + PyVarObject_HEAD_INIT(0, 0) + "selfdrive.modeld.runners.runmodel_pyx.""Enum", /*tp_name*/ + sizeof(struct __pyx_MemviewEnum_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_Enum, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + __pyx_MemviewEnum___repr__, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, /*tp_flags*/ + 0, /*tp_doc*/ + __pyx_tp_traverse_Enum, /*tp_traverse*/ + __pyx_tp_clear_Enum, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_Enum, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + __pyx_MemviewEnum___init__, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_Enum, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif +static struct __pyx_vtabstruct_memoryview __pyx_vtable_memoryview; + +static PyObject *__pyx_tp_new_memoryview(PyTypeObject *t, PyObject *a, PyObject *k) { + struct __pyx_memoryview_obj *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_memoryview_obj *)o); + p->__pyx_vtab = __pyx_vtabptr_memoryview; + p->obj = Py_None; Py_INCREF(Py_None); + p->_size = Py_None; Py_INCREF(Py_None); + p->_array_interface = Py_None; Py_INCREF(Py_None); + p->view.obj = NULL; + if (unlikely(__pyx_memoryview___cinit__(o, a, k) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static void __pyx_tp_dealloc_memoryview(PyObject *o) { + struct __pyx_memoryview_obj *p = (struct __pyx_memoryview_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_memoryview) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_memoryview___dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + Py_CLEAR(p->obj); + Py_CLEAR(p->_size); + Py_CLEAR(p->_array_interface); + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} + +static int __pyx_tp_traverse_memoryview(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_memoryview_obj *p = (struct __pyx_memoryview_obj *)o; + if (p->obj) { + e = (*v)(p->obj, a); if (e) return e; + } + if (p->_size) { + e = (*v)(p->_size, a); if (e) return e; + } + if (p->_array_interface) { + e = (*v)(p->_array_interface, a); if (e) return e; + } + if (p->view.obj) { + e = (*v)(p->view.obj, a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear_memoryview(PyObject *o) { + PyObject* tmp; + struct __pyx_memoryview_obj *p = (struct __pyx_memoryview_obj *)o; + tmp = ((PyObject*)p->obj); + p->obj = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + tmp = ((PyObject*)p->_size); + p->_size = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + tmp = ((PyObject*)p->_array_interface); + p->_array_interface = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + Py_CLEAR(p->view.obj); + return 0; +} +static PyObject *__pyx_sq_item_memoryview(PyObject *o, Py_ssize_t i) { + PyObject *r; + PyObject *x = PyInt_FromSsize_t(i); if(!x) return 0; + r = Py_TYPE(o)->tp_as_mapping->mp_subscript(o, x); + Py_DECREF(x); + return r; +} + +static int __pyx_mp_ass_subscript_memoryview(PyObject *o, PyObject *i, PyObject *v) { + if (v) { + return __pyx_memoryview___setitem__(o, i, v); + } + else { + __Pyx_TypeName o_type_name; + o_type_name = __Pyx_PyType_GetName(Py_TYPE(o)); + PyErr_Format(PyExc_NotImplementedError, + "Subscript deletion not supported by " __Pyx_FMT_TYPENAME, o_type_name); + __Pyx_DECREF_TypeName(o_type_name); + return -1; + } +} + +static PyObject *__pyx_getprop___pyx_memoryview_T(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_1T_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_base(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_4base_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_shape(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_5shape_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_strides(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_7strides_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_suboffsets(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_10suboffsets_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_ndim(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_4ndim_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_itemsize(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_8itemsize_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_nbytes(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_6nbytes_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_size(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_4size_1__get__(o); +} + +static PyObject *__pyx_specialmethod___pyx_memoryview___repr__(PyObject *self, CYTHON_UNUSED PyObject *arg) { + return __pyx_memoryview___repr__(self); +} + +static PyMethodDef __pyx_methods_memoryview[] = { + {"__repr__", (PyCFunction)__pyx_specialmethod___pyx_memoryview___repr__, METH_NOARGS|METH_COEXIST, 0}, + {"is_c_contig", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_is_c_contig, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"is_f_contig", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_is_f_contig, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"copy", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_copy, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"copy_fortran", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_copy_fortran, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryview_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryview_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; + +static struct PyGetSetDef __pyx_getsets_memoryview[] = { + {(char *)"T", __pyx_getprop___pyx_memoryview_T, 0, (char *)0, 0}, + {(char *)"base", __pyx_getprop___pyx_memoryview_base, 0, (char *)0, 0}, + {(char *)"shape", __pyx_getprop___pyx_memoryview_shape, 0, (char *)0, 0}, + {(char *)"strides", __pyx_getprop___pyx_memoryview_strides, 0, (char *)0, 0}, + {(char *)"suboffsets", __pyx_getprop___pyx_memoryview_suboffsets, 0, (char *)0, 0}, + {(char *)"ndim", __pyx_getprop___pyx_memoryview_ndim, 0, (char *)0, 0}, + {(char *)"itemsize", __pyx_getprop___pyx_memoryview_itemsize, 0, (char *)0, 0}, + {(char *)"nbytes", __pyx_getprop___pyx_memoryview_nbytes, 0, (char *)0, 0}, + {(char *)"size", __pyx_getprop___pyx_memoryview_size, 0, (char *)0, 0}, + {0, 0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +#if !CYTHON_COMPILING_IN_LIMITED_API + +static PyBufferProcs __pyx_tp_as_buffer_memoryview = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_memoryview_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; +#endif +static PyType_Slot __pyx_type___pyx_memoryview_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_memoryview}, + {Py_tp_repr, (void *)__pyx_memoryview___repr__}, + {Py_sq_length, (void *)__pyx_memoryview___len__}, + {Py_sq_item, (void *)__pyx_sq_item_memoryview}, + {Py_mp_length, (void *)__pyx_memoryview___len__}, + {Py_mp_subscript, (void *)__pyx_memoryview___getitem__}, + {Py_mp_ass_subscript, (void *)__pyx_mp_ass_subscript_memoryview}, + {Py_tp_str, (void *)__pyx_memoryview___str__}, + #if defined(Py_bf_getbuffer) + {Py_bf_getbuffer, (void *)__pyx_memoryview_getbuffer}, + #endif + {Py_tp_traverse, (void *)__pyx_tp_traverse_memoryview}, + {Py_tp_clear, (void *)__pyx_tp_clear_memoryview}, + {Py_tp_methods, (void *)__pyx_methods_memoryview}, + {Py_tp_getset, (void *)__pyx_getsets_memoryview}, + {Py_tp_new, (void *)__pyx_tp_new_memoryview}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_memoryview_spec = { + "selfdrive.modeld.runners.runmodel_pyx.memoryview", + sizeof(struct __pyx_memoryview_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, + __pyx_type___pyx_memoryview_slots, +}; +#else + +static PySequenceMethods __pyx_tp_as_sequence_memoryview = { + __pyx_memoryview___len__, /*sq_length*/ + 0, /*sq_concat*/ + 0, /*sq_repeat*/ + __pyx_sq_item_memoryview, /*sq_item*/ + 0, /*sq_slice*/ + 0, /*sq_ass_item*/ + 0, /*sq_ass_slice*/ + 0, /*sq_contains*/ + 0, /*sq_inplace_concat*/ + 0, /*sq_inplace_repeat*/ +}; + +static PyMappingMethods __pyx_tp_as_mapping_memoryview = { + __pyx_memoryview___len__, /*mp_length*/ + __pyx_memoryview___getitem__, /*mp_subscript*/ + __pyx_mp_ass_subscript_memoryview, /*mp_ass_subscript*/ +}; + +static PyBufferProcs __pyx_tp_as_buffer_memoryview = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_memoryview_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; + +static PyTypeObject __pyx_type___pyx_memoryview = { + PyVarObject_HEAD_INIT(0, 0) + "selfdrive.modeld.runners.runmodel_pyx.""memoryview", /*tp_name*/ + sizeof(struct __pyx_memoryview_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_memoryview, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + __pyx_memoryview___repr__, /*tp_repr*/ + 0, /*tp_as_number*/ + &__pyx_tp_as_sequence_memoryview, /*tp_as_sequence*/ + &__pyx_tp_as_mapping_memoryview, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + __pyx_memoryview___str__, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + &__pyx_tp_as_buffer_memoryview, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, /*tp_flags*/ + 0, /*tp_doc*/ + __pyx_tp_traverse_memoryview, /*tp_traverse*/ + __pyx_tp_clear_memoryview, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_memoryview, /*tp_methods*/ + 0, /*tp_members*/ + __pyx_getsets_memoryview, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_memoryview, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif +static struct __pyx_vtabstruct__memoryviewslice __pyx_vtable__memoryviewslice; + +static PyObject *__pyx_tp_new__memoryviewslice(PyTypeObject *t, PyObject *a, PyObject *k) { + struct __pyx_memoryviewslice_obj *p; + PyObject *o = __pyx_tp_new_memoryview(t, a, k); + if (unlikely(!o)) return 0; + p = ((struct __pyx_memoryviewslice_obj *)o); + p->__pyx_base.__pyx_vtab = (struct __pyx_vtabstruct_memoryview*)__pyx_vtabptr__memoryviewslice; + new((void*)&(p->from_slice)) __Pyx_memviewslice(); + p->from_object = Py_None; Py_INCREF(Py_None); + p->from_slice.memview = NULL; + return o; +} + +static void __pyx_tp_dealloc__memoryviewslice(PyObject *o) { + struct __pyx_memoryviewslice_obj *p = (struct __pyx_memoryviewslice_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc__memoryviewslice) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_memoryviewslice___dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + __Pyx_call_destructor(p->from_slice); + Py_CLEAR(p->from_object); + PyObject_GC_Track(o); + __pyx_tp_dealloc_memoryview(o); +} + +static int __pyx_tp_traverse__memoryviewslice(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_memoryviewslice_obj *p = (struct __pyx_memoryviewslice_obj *)o; + e = __pyx_tp_traverse_memoryview(o, v, a); if (e) return e; + if (p->from_object) { + e = (*v)(p->from_object, a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear__memoryviewslice(PyObject *o) { + PyObject* tmp; + struct __pyx_memoryviewslice_obj *p = (struct __pyx_memoryviewslice_obj *)o; + __pyx_tp_clear_memoryview(o); + tmp = ((PyObject*)p->from_object); + p->from_object = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + __PYX_XCLEAR_MEMVIEW(&p->from_slice, 1); + return 0; +} + +static PyMethodDef __pyx_methods__memoryviewslice[] = { + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryviewslice_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryviewslice_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type___pyx_memoryviewslice_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc__memoryviewslice}, + {Py_tp_doc, (void *)PyDoc_STR("Internal class for passing memoryview slices to Python")}, + {Py_tp_traverse, (void *)__pyx_tp_traverse__memoryviewslice}, + {Py_tp_clear, (void *)__pyx_tp_clear__memoryviewslice}, + {Py_tp_methods, (void *)__pyx_methods__memoryviewslice}, + {Py_tp_new, (void *)__pyx_tp_new__memoryviewslice}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_memoryviewslice_spec = { + "selfdrive.modeld.runners.runmodel_pyx._memoryviewslice", + sizeof(struct __pyx_memoryviewslice_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_SEQUENCE, + __pyx_type___pyx_memoryviewslice_slots, +}; +#else + +static PyTypeObject __pyx_type___pyx_memoryviewslice = { + PyVarObject_HEAD_INIT(0, 0) + "selfdrive.modeld.runners.runmodel_pyx.""_memoryviewslice", /*tp_name*/ + sizeof(struct __pyx_memoryviewslice_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc__memoryviewslice, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + #if CYTHON_COMPILING_IN_PYPY || 0 + __pyx_memoryview___repr__, /*tp_repr*/ + #else + 0, /*tp_repr*/ + #endif + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + #if CYTHON_COMPILING_IN_PYPY || 0 + __pyx_memoryview___str__, /*tp_str*/ + #else + 0, /*tp_str*/ + #endif + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_SEQUENCE, /*tp_flags*/ + PyDoc_STR("Internal class for passing memoryview slices to Python"), /*tp_doc*/ + __pyx_tp_traverse__memoryviewslice, /*tp_traverse*/ + __pyx_tp_clear__memoryviewslice, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods__memoryviewslice, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new__memoryviewslice, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyMethodDef __pyx_methods[] = { + {0, 0, 0, 0} +}; +#ifndef CYTHON_SMALL_CODE +#if defined(__clang__) + #define CYTHON_SMALL_CODE +#elif defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 3)) + #define CYTHON_SMALL_CODE __attribute__((cold)) +#else + #define CYTHON_SMALL_CODE +#endif +#endif +/* #### Code section: pystring_table ### */ + +static int __Pyx_CreateStringTabAndInitStrings(void) { + __Pyx_StringTabEntry __pyx_string_tab[] = { + {&__pyx_kp_u_, __pyx_k_, sizeof(__pyx_k_), 0, 1, 0, 0}, + {&__pyx_n_s_ASCII, __pyx_k_ASCII, sizeof(__pyx_k_ASCII), 0, 0, 1, 1}, + {&__pyx_kp_s_All_dimensions_preceding_dimensi, __pyx_k_All_dimensions_preceding_dimensi, sizeof(__pyx_k_All_dimensions_preceding_dimensi), 0, 0, 1, 0}, + {&__pyx_n_s_AssertionError, __pyx_k_AssertionError, sizeof(__pyx_k_AssertionError), 0, 0, 1, 1}, + {&__pyx_kp_s_Buffer_view_does_not_expose_stri, __pyx_k_Buffer_view_does_not_expose_stri, sizeof(__pyx_k_Buffer_view_does_not_expose_stri), 0, 0, 1, 0}, + {&__pyx_n_s_CPU, __pyx_k_CPU, sizeof(__pyx_k_CPU), 0, 0, 1, 1}, + {&__pyx_kp_s_Can_only_create_a_buffer_that_is, __pyx_k_Can_only_create_a_buffer_that_is, sizeof(__pyx_k_Can_only_create_a_buffer_that_is), 0, 0, 1, 0}, + {&__pyx_kp_s_Cannot_assign_to_read_only_memor, __pyx_k_Cannot_assign_to_read_only_memor, sizeof(__pyx_k_Cannot_assign_to_read_only_memor), 0, 0, 1, 0}, + {&__pyx_kp_s_Cannot_create_writable_memory_vi, __pyx_k_Cannot_create_writable_memory_vi, sizeof(__pyx_k_Cannot_create_writable_memory_vi), 0, 0, 1, 0}, + {&__pyx_kp_u_Cannot_index_with_type, __pyx_k_Cannot_index_with_type, sizeof(__pyx_k_Cannot_index_with_type), 0, 1, 0, 0}, + {&__pyx_kp_s_Cannot_transpose_memoryview_with, __pyx_k_Cannot_transpose_memoryview_with, sizeof(__pyx_k_Cannot_transpose_memoryview_with), 0, 0, 1, 0}, + {&__pyx_n_s_DSP, __pyx_k_DSP, sizeof(__pyx_k_DSP), 0, 0, 1, 1}, + {&__pyx_kp_s_Dimension_d_is_not_direct, __pyx_k_Dimension_d_is_not_direct, sizeof(__pyx_k_Dimension_d_is_not_direct), 0, 0, 1, 0}, + {&__pyx_n_s_Ellipsis, __pyx_k_Ellipsis, sizeof(__pyx_k_Ellipsis), 0, 0, 1, 1}, + {&__pyx_kp_s_Empty_shape_tuple_for_cython_arr, __pyx_k_Empty_shape_tuple_for_cython_arr, sizeof(__pyx_k_Empty_shape_tuple_for_cython_arr), 0, 0, 1, 0}, + {&__pyx_n_s_GPU, __pyx_k_GPU, sizeof(__pyx_k_GPU), 0, 0, 1, 1}, + {&__pyx_kp_s_Incompatible_checksums_0x_x_vs_0, __pyx_k_Incompatible_checksums_0x_x_vs_0, sizeof(__pyx_k_Incompatible_checksums_0x_x_vs_0), 0, 0, 1, 0}, + {&__pyx_n_s_IndexError, __pyx_k_IndexError, sizeof(__pyx_k_IndexError), 0, 0, 1, 1}, + {&__pyx_kp_s_Index_out_of_bounds_axis_d, __pyx_k_Index_out_of_bounds_axis_d, sizeof(__pyx_k_Index_out_of_bounds_axis_d), 0, 0, 1, 0}, + {&__pyx_kp_s_Indirect_dimensions_not_supporte, __pyx_k_Indirect_dimensions_not_supporte, sizeof(__pyx_k_Indirect_dimensions_not_supporte), 0, 0, 1, 0}, + {&__pyx_kp_u_Invalid_mode_expected_c_or_fortr, __pyx_k_Invalid_mode_expected_c_or_fortr, sizeof(__pyx_k_Invalid_mode_expected_c_or_fortr), 0, 1, 0, 0}, + {&__pyx_kp_u_Invalid_shape_in_axis, __pyx_k_Invalid_shape_in_axis, sizeof(__pyx_k_Invalid_shape_in_axis), 0, 1, 0, 0}, + {&__pyx_n_s_MemoryError, __pyx_k_MemoryError, sizeof(__pyx_k_MemoryError), 0, 0, 1, 1}, + {&__pyx_kp_s_MemoryView_of_r_at_0x_x, __pyx_k_MemoryView_of_r_at_0x_x, sizeof(__pyx_k_MemoryView_of_r_at_0x_x), 0, 0, 1, 0}, + {&__pyx_kp_s_MemoryView_of_r_object, __pyx_k_MemoryView_of_r_object, sizeof(__pyx_k_MemoryView_of_r_object), 0, 0, 1, 0}, + {&__pyx_n_b_O, __pyx_k_O, sizeof(__pyx_k_O), 0, 0, 0, 1}, + {&__pyx_kp_u_Out_of_bounds_on_buffer_access_a, __pyx_k_Out_of_bounds_on_buffer_access_a, sizeof(__pyx_k_Out_of_bounds_on_buffer_access_a), 0, 1, 0, 0}, + {&__pyx_n_s_PickleError, __pyx_k_PickleError, sizeof(__pyx_k_PickleError), 0, 0, 1, 1}, + {&__pyx_n_s_RunModel, __pyx_k_RunModel, sizeof(__pyx_k_RunModel), 0, 0, 1, 1}, + {&__pyx_n_s_RunModel___reduce_cython, __pyx_k_RunModel___reduce_cython, sizeof(__pyx_k_RunModel___reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_RunModel___setstate_cython, __pyx_k_RunModel___setstate_cython, sizeof(__pyx_k_RunModel___setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_RunModel_addInput, __pyx_k_RunModel_addInput, sizeof(__pyx_k_RunModel_addInput), 0, 0, 1, 1}, + {&__pyx_n_s_RunModel_execute, __pyx_k_RunModel_execute, sizeof(__pyx_k_RunModel_execute), 0, 0, 1, 1}, + {&__pyx_n_s_RunModel_getCLBuffer, __pyx_k_RunModel_getCLBuffer, sizeof(__pyx_k_RunModel_getCLBuffer), 0, 0, 1, 1}, + {&__pyx_n_s_RunModel_setInputBuffer, __pyx_k_RunModel_setInputBuffer, sizeof(__pyx_k_RunModel_setInputBuffer), 0, 0, 1, 1}, + {&__pyx_n_s_Runtime, __pyx_k_Runtime, sizeof(__pyx_k_Runtime), 0, 0, 1, 1}, + {&__pyx_n_s_Sequence, __pyx_k_Sequence, sizeof(__pyx_k_Sequence), 0, 0, 1, 1}, + {&__pyx_kp_s_Step_may_not_be_zero_axis_d, __pyx_k_Step_may_not_be_zero_axis_d, sizeof(__pyx_k_Step_may_not_be_zero_axis_d), 0, 0, 1, 0}, + {&__pyx_n_s_TypeError, __pyx_k_TypeError, sizeof(__pyx_k_TypeError), 0, 0, 1, 1}, + {&__pyx_kp_s_Unable_to_convert_item_to_object, __pyx_k_Unable_to_convert_item_to_object, sizeof(__pyx_k_Unable_to_convert_item_to_object), 0, 0, 1, 0}, + {&__pyx_n_s_ValueError, __pyx_k_ValueError, sizeof(__pyx_k_ValueError), 0, 0, 1, 1}, + {&__pyx_n_s_View_MemoryView, __pyx_k_View_MemoryView, sizeof(__pyx_k_View_MemoryView), 0, 0, 1, 1}, + {&__pyx_kp_u__2, __pyx_k__2, sizeof(__pyx_k__2), 0, 1, 0, 0}, + {&__pyx_n_s__3, __pyx_k__3, sizeof(__pyx_k__3), 0, 0, 1, 1}, + {&__pyx_n_s__30, __pyx_k__30, sizeof(__pyx_k__30), 0, 0, 1, 1}, + {&__pyx_kp_u__6, __pyx_k__6, sizeof(__pyx_k__6), 0, 1, 0, 0}, + {&__pyx_kp_u__7, __pyx_k__7, sizeof(__pyx_k__7), 0, 1, 0, 0}, + {&__pyx_n_s_abc, __pyx_k_abc, sizeof(__pyx_k_abc), 0, 0, 1, 1}, + {&__pyx_n_s_addInput, __pyx_k_addInput, sizeof(__pyx_k_addInput), 0, 0, 1, 1}, + {&__pyx_n_s_allocate_buffer, __pyx_k_allocate_buffer, sizeof(__pyx_k_allocate_buffer), 0, 0, 1, 1}, + {&__pyx_kp_u_and, __pyx_k_and, sizeof(__pyx_k_and), 0, 1, 0, 0}, + {&__pyx_n_s_asyncio_coroutines, __pyx_k_asyncio_coroutines, sizeof(__pyx_k_asyncio_coroutines), 0, 0, 1, 1}, + {&__pyx_n_s_base, __pyx_k_base, sizeof(__pyx_k_base), 0, 0, 1, 1}, + {&__pyx_n_s_buffer, __pyx_k_buffer, sizeof(__pyx_k_buffer), 0, 0, 1, 1}, + {&__pyx_n_s_c, __pyx_k_c, sizeof(__pyx_k_c), 0, 0, 1, 1}, + {&__pyx_n_u_c, __pyx_k_c, sizeof(__pyx_k_c), 0, 1, 0, 1}, + {&__pyx_n_s_cl_buf, __pyx_k_cl_buf, sizeof(__pyx_k_cl_buf), 0, 0, 1, 1}, + {&__pyx_n_s_class, __pyx_k_class, sizeof(__pyx_k_class), 0, 0, 1, 1}, + {&__pyx_n_s_class_getitem, __pyx_k_class_getitem, sizeof(__pyx_k_class_getitem), 0, 0, 1, 1}, + {&__pyx_n_s_cline_in_traceback, __pyx_k_cline_in_traceback, sizeof(__pyx_k_cline_in_traceback), 0, 0, 1, 1}, + {&__pyx_n_s_collections, __pyx_k_collections, sizeof(__pyx_k_collections), 0, 0, 1, 1}, + {&__pyx_kp_s_collections_abc, __pyx_k_collections_abc, sizeof(__pyx_k_collections_abc), 0, 0, 1, 0}, + {&__pyx_kp_s_contiguous_and_direct, __pyx_k_contiguous_and_direct, sizeof(__pyx_k_contiguous_and_direct), 0, 0, 1, 0}, + {&__pyx_kp_s_contiguous_and_indirect, __pyx_k_contiguous_and_indirect, sizeof(__pyx_k_contiguous_and_indirect), 0, 0, 1, 0}, + {&__pyx_n_s_count, __pyx_k_count, sizeof(__pyx_k_count), 0, 0, 1, 1}, + {&__pyx_n_s_dict, __pyx_k_dict, sizeof(__pyx_k_dict), 0, 0, 1, 1}, + {&__pyx_kp_u_disable, __pyx_k_disable, sizeof(__pyx_k_disable), 0, 1, 0, 0}, + {&__pyx_n_s_doc, __pyx_k_doc, sizeof(__pyx_k_doc), 0, 0, 1, 1}, + {&__pyx_n_s_dtype_is_object, __pyx_k_dtype_is_object, sizeof(__pyx_k_dtype_is_object), 0, 0, 1, 1}, + {&__pyx_kp_u_enable, __pyx_k_enable, sizeof(__pyx_k_enable), 0, 1, 0, 0}, + {&__pyx_n_s_encode, __pyx_k_encode, sizeof(__pyx_k_encode), 0, 0, 1, 1}, + {&__pyx_n_s_enumerate, __pyx_k_enumerate, sizeof(__pyx_k_enumerate), 0, 0, 1, 1}, + {&__pyx_n_s_error, __pyx_k_error, sizeof(__pyx_k_error), 0, 0, 1, 1}, + {&__pyx_n_s_execute, __pyx_k_execute, sizeof(__pyx_k_execute), 0, 0, 1, 1}, + {&__pyx_n_s_flags, __pyx_k_flags, sizeof(__pyx_k_flags), 0, 0, 1, 1}, + {&__pyx_n_s_format, __pyx_k_format, sizeof(__pyx_k_format), 0, 0, 1, 1}, + {&__pyx_n_s_fortran, __pyx_k_fortran, sizeof(__pyx_k_fortran), 0, 0, 1, 1}, + {&__pyx_n_u_fortran, __pyx_k_fortran, sizeof(__pyx_k_fortran), 0, 1, 0, 1}, + {&__pyx_kp_u_gc, __pyx_k_gc, sizeof(__pyx_k_gc), 0, 1, 0, 0}, + {&__pyx_n_s_getCLBuffer, __pyx_k_getCLBuffer, sizeof(__pyx_k_getCLBuffer), 0, 0, 1, 1}, + {&__pyx_n_s_getstate, __pyx_k_getstate, sizeof(__pyx_k_getstate), 0, 0, 1, 1}, + {&__pyx_kp_u_got, __pyx_k_got, sizeof(__pyx_k_got), 0, 1, 0, 0}, + {&__pyx_kp_u_got_differing_extents_in_dimensi, __pyx_k_got_differing_extents_in_dimensi, sizeof(__pyx_k_got_differing_extents_in_dimensi), 0, 1, 0, 0}, + {&__pyx_n_s_id, __pyx_k_id, sizeof(__pyx_k_id), 0, 0, 1, 1}, + {&__pyx_n_s_import, __pyx_k_import, sizeof(__pyx_k_import), 0, 0, 1, 1}, + {&__pyx_n_s_index, __pyx_k_index, sizeof(__pyx_k_index), 0, 0, 1, 1}, + {&__pyx_n_s_init_subclass, __pyx_k_init_subclass, sizeof(__pyx_k_init_subclass), 0, 0, 1, 1}, + {&__pyx_n_s_initializing, __pyx_k_initializing, sizeof(__pyx_k_initializing), 0, 0, 1, 1}, + {&__pyx_n_s_is_coroutine, __pyx_k_is_coroutine, sizeof(__pyx_k_is_coroutine), 0, 0, 1, 1}, + {&__pyx_kp_u_isenabled, __pyx_k_isenabled, sizeof(__pyx_k_isenabled), 0, 1, 0, 0}, + {&__pyx_n_s_itemsize, __pyx_k_itemsize, sizeof(__pyx_k_itemsize), 0, 0, 1, 1}, + {&__pyx_kp_s_itemsize_0_for_cython_array, __pyx_k_itemsize_0_for_cython_array, sizeof(__pyx_k_itemsize_0_for_cython_array), 0, 0, 1, 0}, + {&__pyx_n_s_main, __pyx_k_main, sizeof(__pyx_k_main), 0, 0, 1, 1}, + {&__pyx_n_s_memview, __pyx_k_memview, sizeof(__pyx_k_memview), 0, 0, 1, 1}, + {&__pyx_n_s_metaclass, __pyx_k_metaclass, sizeof(__pyx_k_metaclass), 0, 0, 1, 1}, + {&__pyx_n_s_mode, __pyx_k_mode, sizeof(__pyx_k_mode), 0, 0, 1, 1}, + {&__pyx_n_s_module, __pyx_k_module, sizeof(__pyx_k_module), 0, 0, 1, 1}, + {&__pyx_n_s_name, __pyx_k_name, sizeof(__pyx_k_name), 0, 0, 1, 1}, + {&__pyx_n_s_name_2, __pyx_k_name_2, sizeof(__pyx_k_name_2), 0, 0, 1, 1}, + {&__pyx_n_s_ndim, __pyx_k_ndim, sizeof(__pyx_k_ndim), 0, 0, 1, 1}, + {&__pyx_n_s_new, __pyx_k_new, sizeof(__pyx_k_new), 0, 0, 1, 1}, + {&__pyx_kp_s_no_default___reduce___due_to_non, __pyx_k_no_default___reduce___due_to_non, sizeof(__pyx_k_no_default___reduce___due_to_non), 0, 0, 1, 0}, + {&__pyx_n_s_obj, __pyx_k_obj, sizeof(__pyx_k_obj), 0, 0, 1, 1}, + {&__pyx_n_s_pack, __pyx_k_pack, sizeof(__pyx_k_pack), 0, 0, 1, 1}, + {&__pyx_n_s_pickle, __pyx_k_pickle, sizeof(__pyx_k_pickle), 0, 0, 1, 1}, + {&__pyx_n_s_prepare, __pyx_k_prepare, sizeof(__pyx_k_prepare), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_PickleError, __pyx_k_pyx_PickleError, sizeof(__pyx_k_pyx_PickleError), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_checksum, __pyx_k_pyx_checksum, sizeof(__pyx_k_pyx_checksum), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_result, __pyx_k_pyx_result, sizeof(__pyx_k_pyx_result), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_state, __pyx_k_pyx_state, sizeof(__pyx_k_pyx_state), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_type, __pyx_k_pyx_type, sizeof(__pyx_k_pyx_type), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_unpickle_Enum, __pyx_k_pyx_unpickle_Enum, sizeof(__pyx_k_pyx_unpickle_Enum), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_vtable, __pyx_k_pyx_vtable, sizeof(__pyx_k_pyx_vtable), 0, 0, 1, 1}, + {&__pyx_n_s_qualname, __pyx_k_qualname, sizeof(__pyx_k_qualname), 0, 0, 1, 1}, + {&__pyx_n_s_range, __pyx_k_range, sizeof(__pyx_k_range), 0, 0, 1, 1}, + {&__pyx_n_s_reduce, __pyx_k_reduce, sizeof(__pyx_k_reduce), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_cython, __pyx_k_reduce_cython, sizeof(__pyx_k_reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_ex, __pyx_k_reduce_ex, sizeof(__pyx_k_reduce_ex), 0, 0, 1, 1}, + {&__pyx_n_s_register, __pyx_k_register, sizeof(__pyx_k_register), 0, 0, 1, 1}, + {&__pyx_n_s_self, __pyx_k_self, sizeof(__pyx_k_self), 0, 0, 1, 1}, + {&__pyx_kp_s_self_model_cannot_be_converted_t, __pyx_k_self_model_cannot_be_converted_t, sizeof(__pyx_k_self_model_cannot_be_converted_t), 0, 0, 1, 0}, + {&__pyx_n_s_selfdrive_modeld_runners_runmode, __pyx_k_selfdrive_modeld_runners_runmode, sizeof(__pyx_k_selfdrive_modeld_runners_runmode), 0, 0, 1, 1}, + {&__pyx_kp_s_selfdrive_modeld_runners_runmode_2, __pyx_k_selfdrive_modeld_runners_runmode_2, sizeof(__pyx_k_selfdrive_modeld_runners_runmode_2), 0, 0, 1, 0}, + {&__pyx_n_s_setInputBuffer, __pyx_k_setInputBuffer, sizeof(__pyx_k_setInputBuffer), 0, 0, 1, 1}, + {&__pyx_n_s_set_name, __pyx_k_set_name, sizeof(__pyx_k_set_name), 0, 0, 1, 1}, + {&__pyx_n_s_setstate, __pyx_k_setstate, sizeof(__pyx_k_setstate), 0, 0, 1, 1}, + {&__pyx_n_s_setstate_cython, __pyx_k_setstate_cython, sizeof(__pyx_k_setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_shape, __pyx_k_shape, sizeof(__pyx_k_shape), 0, 0, 1, 1}, + {&__pyx_n_s_size, __pyx_k_size, sizeof(__pyx_k_size), 0, 0, 1, 1}, + {&__pyx_n_s_spec, __pyx_k_spec, sizeof(__pyx_k_spec), 0, 0, 1, 1}, + {&__pyx_n_s_start, __pyx_k_start, sizeof(__pyx_k_start), 0, 0, 1, 1}, + {&__pyx_n_s_step, __pyx_k_step, sizeof(__pyx_k_step), 0, 0, 1, 1}, + {&__pyx_n_s_stop, __pyx_k_stop, sizeof(__pyx_k_stop), 0, 0, 1, 1}, + {&__pyx_kp_s_strided_and_direct, __pyx_k_strided_and_direct, sizeof(__pyx_k_strided_and_direct), 0, 0, 1, 0}, + {&__pyx_kp_s_strided_and_direct_or_indirect, __pyx_k_strided_and_direct_or_indirect, sizeof(__pyx_k_strided_and_direct_or_indirect), 0, 0, 1, 0}, + {&__pyx_kp_s_strided_and_indirect, __pyx_k_strided_and_indirect, sizeof(__pyx_k_strided_and_indirect), 0, 0, 1, 0}, + {&__pyx_kp_s_stringsource, __pyx_k_stringsource, sizeof(__pyx_k_stringsource), 0, 0, 1, 0}, + {&__pyx_n_s_struct, __pyx_k_struct, sizeof(__pyx_k_struct), 0, 0, 1, 1}, + {&__pyx_n_s_super, __pyx_k_super, sizeof(__pyx_k_super), 0, 0, 1, 1}, + {&__pyx_n_s_sys, __pyx_k_sys, sizeof(__pyx_k_sys), 0, 0, 1, 1}, + {&__pyx_n_s_test, __pyx_k_test, sizeof(__pyx_k_test), 0, 0, 1, 1}, + {&__pyx_kp_s_unable_to_allocate_array_data, __pyx_k_unable_to_allocate_array_data, sizeof(__pyx_k_unable_to_allocate_array_data), 0, 0, 1, 0}, + {&__pyx_kp_s_unable_to_allocate_shape_and_str, __pyx_k_unable_to_allocate_shape_and_str, sizeof(__pyx_k_unable_to_allocate_shape_and_str), 0, 0, 1, 0}, + {&__pyx_n_s_unpack, __pyx_k_unpack, sizeof(__pyx_k_unpack), 0, 0, 1, 1}, + {&__pyx_n_s_update, __pyx_k_update, sizeof(__pyx_k_update), 0, 0, 1, 1}, + {&__pyx_n_s_version_info, __pyx_k_version_info, sizeof(__pyx_k_version_info), 0, 0, 1, 1}, + {0, 0, 0, 0, 0, 0, 0} + }; + return __Pyx_InitStrings(__pyx_string_tab); +} +/* #### Code section: cached_builtins ### */ +static CYTHON_SMALL_CODE int __Pyx_InitCachedBuiltins(void) { + __pyx_builtin_TypeError = __Pyx_GetBuiltinName(__pyx_n_s_TypeError); if (!__pyx_builtin_TypeError) __PYX_ERR(0, 2, __pyx_L1_error) + __pyx_builtin___import__ = __Pyx_GetBuiltinName(__pyx_n_s_import); if (!__pyx_builtin___import__) __PYX_ERR(0, 100, __pyx_L1_error) + __pyx_builtin_ValueError = __Pyx_GetBuiltinName(__pyx_n_s_ValueError); if (!__pyx_builtin_ValueError) __PYX_ERR(0, 141, __pyx_L1_error) + __pyx_builtin_MemoryError = __Pyx_GetBuiltinName(__pyx_n_s_MemoryError); if (!__pyx_builtin_MemoryError) __PYX_ERR(0, 156, __pyx_L1_error) + __pyx_builtin_enumerate = __Pyx_GetBuiltinName(__pyx_n_s_enumerate); if (!__pyx_builtin_enumerate) __PYX_ERR(0, 159, __pyx_L1_error) + __pyx_builtin_range = __Pyx_GetBuiltinName(__pyx_n_s_range); if (!__pyx_builtin_range) __PYX_ERR(0, 261, __pyx_L1_error) + __pyx_builtin_AssertionError = __Pyx_GetBuiltinName(__pyx_n_s_AssertionError); if (!__pyx_builtin_AssertionError) __PYX_ERR(0, 373, __pyx_L1_error) + __pyx_builtin_Ellipsis = __Pyx_GetBuiltinName(__pyx_n_s_Ellipsis); if (!__pyx_builtin_Ellipsis) __PYX_ERR(0, 408, __pyx_L1_error) + __pyx_builtin_id = __Pyx_GetBuiltinName(__pyx_n_s_id); if (!__pyx_builtin_id) __PYX_ERR(0, 618, __pyx_L1_error) + __pyx_builtin_IndexError = __Pyx_GetBuiltinName(__pyx_n_s_IndexError); if (!__pyx_builtin_IndexError) __PYX_ERR(0, 914, __pyx_L1_error) + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: cached_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_InitCachedConstants", 0); + + /* "View.MemoryView":582 + * def suboffsets(self): + * if self.view.suboffsets == NULL: + * return (-1,) * self.view.ndim # <<<<<<<<<<<<<< + * + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + */ + __pyx_tuple__4 = PyTuple_New(1); if (unlikely(!__pyx_tuple__4)) __PYX_ERR(0, 582, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__4); + __Pyx_INCREF(__pyx_int_neg_1); + __Pyx_GIVEREF(__pyx_int_neg_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_tuple__4, 0, __pyx_int_neg_1)) __PYX_ERR(0, 582, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_tuple__4); + + /* "View.MemoryView":679 + * tup = index if isinstance(index, tuple) else (index,) + * + * result = [slice(None)] * ndim # <<<<<<<<<<<<<< + * have_slices = False + * seen_ellipsis = False + */ + __pyx_slice__5 = PySlice_New(Py_None, Py_None, Py_None); if (unlikely(!__pyx_slice__5)) __PYX_ERR(0, 679, __pyx_L1_error) + __Pyx_GOTREF(__pyx_slice__5); + __Pyx_GIVEREF(__pyx_slice__5); + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + */ + __pyx_tuple__8 = PyTuple_Pack(3, __pyx_int_136983863, __pyx_int_112105877, __pyx_int_184977713); if (unlikely(!__pyx_tuple__8)) __PYX_ERR(0, 4, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__8); + __Pyx_GIVEREF(__pyx_tuple__8); + + /* "View.MemoryView":100 + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: + * if __import__("sys").version_info >= (3, 3): # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + */ + __pyx_tuple__9 = PyTuple_Pack(1, __pyx_n_s_sys); if (unlikely(!__pyx_tuple__9)) __PYX_ERR(0, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__9); + __Pyx_GIVEREF(__pyx_tuple__9); + __pyx_tuple__10 = PyTuple_Pack(2, __pyx_int_3, __pyx_int_3); if (unlikely(!__pyx_tuple__10)) __PYX_ERR(0, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__10); + __Pyx_GIVEREF(__pyx_tuple__10); + + /* "View.MemoryView":101 + * try: + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence # <<<<<<<<<<<<<< + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence + */ + __pyx_tuple__11 = PyTuple_Pack(1, __pyx_kp_s_collections_abc); if (unlikely(!__pyx_tuple__11)) __PYX_ERR(0, 101, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__11); + __Pyx_GIVEREF(__pyx_tuple__11); + + /* "View.MemoryView":103 + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence # <<<<<<<<<<<<<< + * except: + * + */ + __pyx_tuple__12 = PyTuple_Pack(1, __pyx_n_s_collections); if (unlikely(!__pyx_tuple__12)) __PYX_ERR(0, 103, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__12); + __Pyx_GIVEREF(__pyx_tuple__12); + + /* "View.MemoryView":309 + * return self.name + * + * cdef generic = Enum("") # <<<<<<<<<<<<<< + * cdef strided = Enum("") # default + * cdef indirect = Enum("") + */ + __pyx_tuple__13 = PyTuple_Pack(1, __pyx_kp_s_strided_and_direct_or_indirect); if (unlikely(!__pyx_tuple__13)) __PYX_ERR(0, 309, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__13); + __Pyx_GIVEREF(__pyx_tuple__13); + + /* "View.MemoryView":310 + * + * cdef generic = Enum("") + * cdef strided = Enum("") # default # <<<<<<<<<<<<<< + * cdef indirect = Enum("") + * + */ + __pyx_tuple__14 = PyTuple_Pack(1, __pyx_kp_s_strided_and_direct); if (unlikely(!__pyx_tuple__14)) __PYX_ERR(0, 310, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__14); + __Pyx_GIVEREF(__pyx_tuple__14); + + /* "View.MemoryView":311 + * cdef generic = Enum("") + * cdef strided = Enum("") # default + * cdef indirect = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_tuple__15 = PyTuple_Pack(1, __pyx_kp_s_strided_and_indirect); if (unlikely(!__pyx_tuple__15)) __PYX_ERR(0, 311, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__15); + __Pyx_GIVEREF(__pyx_tuple__15); + + /* "View.MemoryView":314 + * + * + * cdef contiguous = Enum("") # <<<<<<<<<<<<<< + * cdef indirect_contiguous = Enum("") + * + */ + __pyx_tuple__16 = PyTuple_Pack(1, __pyx_kp_s_contiguous_and_direct); if (unlikely(!__pyx_tuple__16)) __PYX_ERR(0, 314, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__16); + __Pyx_GIVEREF(__pyx_tuple__16); + + /* "View.MemoryView":315 + * + * cdef contiguous = Enum("") + * cdef indirect_contiguous = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_tuple__17 = PyTuple_Pack(1, __pyx_kp_s_contiguous_and_indirect); if (unlikely(!__pyx_tuple__17)) __PYX_ERR(0, 315, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__17); + __Pyx_GIVEREF(__pyx_tuple__17); + + /* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + __pyx_tuple__18 = PyTuple_Pack(5, __pyx_n_s_pyx_type, __pyx_n_s_pyx_checksum, __pyx_n_s_pyx_state, __pyx_n_s_pyx_PickleError, __pyx_n_s_pyx_result); if (unlikely(!__pyx_tuple__18)) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__18); + __Pyx_GIVEREF(__pyx_tuple__18); + __pyx_codeobj__19 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__18, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_pyx_unpickle_Enum, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__19)) __PYX_ERR(0, 1, __pyx_L1_error) + + /* "selfdrive/modeld/runners/runmodel_pyx.pyx":18 + * del self.model + * + * def addInput(self, string name, float[:] buffer): # <<<<<<<<<<<<<< + * if buffer is not None: + * self.model.addInput(name, &buffer[0], len(buffer)) + */ + __pyx_tuple__20 = PyTuple_Pack(3, __pyx_n_s_self, __pyx_n_s_name, __pyx_n_s_buffer); if (unlikely(!__pyx_tuple__20)) __PYX_ERR(1, 18, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__20); + __Pyx_GIVEREF(__pyx_tuple__20); + __pyx_codeobj__21 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__20, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_selfdrive_modeld_runners_runmode_2, __pyx_n_s_addInput, 18, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__21)) __PYX_ERR(1, 18, __pyx_L1_error) + + /* "selfdrive/modeld/runners/runmodel_pyx.pyx":24 + * self.model.addInput(name, NULL, 0) + * + * def setInputBuffer(self, string name, float[:] buffer): # <<<<<<<<<<<<<< + * if buffer is not None: + * self.model.setInputBuffer(name, &buffer[0], len(buffer)) + */ + __pyx_codeobj__22 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__20, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_selfdrive_modeld_runners_runmode_2, __pyx_n_s_setInputBuffer, 24, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__22)) __PYX_ERR(1, 24, __pyx_L1_error) + + /* "selfdrive/modeld/runners/runmodel_pyx.pyx":30 + * self.model.setInputBuffer(name, NULL, 0) + * + * def getCLBuffer(self, string name): # <<<<<<<<<<<<<< + * cdef void * cl_buf = self.model.getCLBuffer(name) + * if not cl_buf: + */ + __pyx_tuple__23 = PyTuple_Pack(3, __pyx_n_s_self, __pyx_n_s_name, __pyx_n_s_cl_buf); if (unlikely(!__pyx_tuple__23)) __PYX_ERR(1, 30, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__23); + __Pyx_GIVEREF(__pyx_tuple__23); + __pyx_codeobj__24 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 3, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__23, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_selfdrive_modeld_runners_runmode_2, __pyx_n_s_getCLBuffer, 30, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__24)) __PYX_ERR(1, 30, __pyx_L1_error) + + /* "selfdrive/modeld/runners/runmodel_pyx.pyx":36 + * return CLMem.create(cl_buf) + * + * def execute(self): # <<<<<<<<<<<<<< + * self.model.execute() + */ + __pyx_tuple__25 = PyTuple_Pack(1, __pyx_n_s_self); if (unlikely(!__pyx_tuple__25)) __PYX_ERR(1, 36, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__25); + __Pyx_GIVEREF(__pyx_tuple__25); + __pyx_codeobj__26 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__25, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_selfdrive_modeld_runners_runmode_2, __pyx_n_s_execute, 36, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__26)) __PYX_ERR(1, 36, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.model cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_codeobj__27 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__25, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__27)) __PYX_ERR(0, 1, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.model cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.model cannot be converted to a Python object for pickling" + */ + __pyx_tuple__28 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_pyx_state); if (unlikely(!__pyx_tuple__28)) __PYX_ERR(0, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__28); + __Pyx_GIVEREF(__pyx_tuple__28); + __pyx_codeobj__29 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__28, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__29)) __PYX_ERR(0, 3, __pyx_L1_error) + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_RefNannyFinishContext(); + return -1; +} +/* #### Code section: init_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitConstants(void) { + if (__Pyx_CreateStringTabAndInitStrings() < 0) __PYX_ERR(1, 1, __pyx_L1_error); + __pyx_int_0 = PyInt_FromLong(0); if (unlikely(!__pyx_int_0)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_int_1 = PyInt_FromLong(1); if (unlikely(!__pyx_int_1)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_int_3 = PyInt_FromLong(3); if (unlikely(!__pyx_int_3)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_int_112105877 = PyInt_FromLong(112105877L); if (unlikely(!__pyx_int_112105877)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_int_136983863 = PyInt_FromLong(136983863L); if (unlikely(!__pyx_int_136983863)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_int_184977713 = PyInt_FromLong(184977713L); if (unlikely(!__pyx_int_184977713)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_int_neg_1 = PyInt_FromLong(-1); if (unlikely(!__pyx_int_neg_1)) __PYX_ERR(1, 1, __pyx_L1_error) + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: init_globals ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitGlobals(void) { + /* AssertionsEnabled.init */ + if (likely(__Pyx_init_assertions_enabled() == 0)); else + +if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L1_error) + + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: init_module ### */ + +static CYTHON_SMALL_CODE int __Pyx_modinit_global_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_import_code(void); /*proto*/ + +static int __Pyx_modinit_global_init_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_global_init_code", 0); + /*--- Global init code ---*/ + __pyx_collections_abc_Sequence = Py_None; Py_INCREF(Py_None); + generic = Py_None; Py_INCREF(Py_None); + strided = Py_None; Py_INCREF(Py_None); + indirect = Py_None; Py_INCREF(Py_None); + contiguous = Py_None; Py_INCREF(Py_None); + indirect_contiguous = Py_None; Py_INCREF(Py_None); + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_variable_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_export_code", 0); + /*--- Variable export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_export_code", 0); + /*--- Function export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_type_init_code(void) { + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_modinit_type_init_code", 0); + /*--- Type init code ---*/ + #if CYTHON_USE_TYPE_SPECS + __pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel_spec, NULL); if (unlikely(!__pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel)) __PYX_ERR(1, 14, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel_spec, __pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel) < 0) __PYX_ERR(1, 14, __pyx_L1_error) + #else + __pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel = &__pyx_type_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel) < 0) __PYX_ERR(1, 14, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel->tp_dictoffset && __pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_RunModel, (PyObject *) __pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel) < 0) __PYX_ERR(1, 14, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel) < 0) __PYX_ERR(1, 14, __pyx_L1_error) + #endif + __pyx_vtabptr_array = &__pyx_vtable_array; + __pyx_vtable_array.get_memview = (PyObject *(*)(struct __pyx_array_obj *))__pyx_array_get_memview; + #if CYTHON_USE_TYPE_SPECS + __pyx_array_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_array_spec, NULL); if (unlikely(!__pyx_array_type)) __PYX_ERR(0, 114, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + __pyx_array_type->tp_as_buffer = &__pyx_tp_as_buffer_array; + if (!__pyx_array_type->tp_as_buffer->bf_releasebuffer && __pyx_array_type->tp_base->tp_as_buffer && __pyx_array_type->tp_base->tp_as_buffer->bf_releasebuffer) { + __pyx_array_type->tp_as_buffer->bf_releasebuffer = __pyx_array_type->tp_base->tp_as_buffer->bf_releasebuffer; + } + #elif defined(Py_bf_getbuffer) && defined(Py_bf_releasebuffer) + /* PY_VERSION_HEX >= 0x03090000 || Py_LIMITED_API >= 0x030B0000 */ + #elif defined(_MSC_VER) + #pragma message ("The buffer protocol is not supported in the Limited C-API < 3.11.") + #else + #warning "The buffer protocol is not supported in the Limited C-API < 3.11." + #endif + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_array_spec, __pyx_array_type) < 0) __PYX_ERR(0, 114, __pyx_L1_error) + #else + __pyx_array_type = &__pyx_type___pyx_array; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_array_type) < 0) __PYX_ERR(0, 114, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_array_type->tp_print = 0; + #endif + if (__Pyx_SetVtable(__pyx_array_type, __pyx_vtabptr_array) < 0) __PYX_ERR(0, 114, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_array_type) < 0) __PYX_ERR(0, 114, __pyx_L1_error) + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_array_type) < 0) __PYX_ERR(0, 114, __pyx_L1_error) + #endif + #if CYTHON_USE_TYPE_SPECS + __pyx_MemviewEnum_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_MemviewEnum_spec, NULL); if (unlikely(!__pyx_MemviewEnum_type)) __PYX_ERR(0, 302, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_MemviewEnum_spec, __pyx_MemviewEnum_type) < 0) __PYX_ERR(0, 302, __pyx_L1_error) + #else + __pyx_MemviewEnum_type = &__pyx_type___pyx_MemviewEnum; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_MemviewEnum_type) < 0) __PYX_ERR(0, 302, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_MemviewEnum_type->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_MemviewEnum_type->tp_dictoffset && __pyx_MemviewEnum_type->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_MemviewEnum_type->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_MemviewEnum_type) < 0) __PYX_ERR(0, 302, __pyx_L1_error) + #endif + __pyx_vtabptr_memoryview = &__pyx_vtable_memoryview; + __pyx_vtable_memoryview.get_item_pointer = (char *(*)(struct __pyx_memoryview_obj *, PyObject *))__pyx_memoryview_get_item_pointer; + __pyx_vtable_memoryview.is_slice = (PyObject *(*)(struct __pyx_memoryview_obj *, PyObject *))__pyx_memoryview_is_slice; + __pyx_vtable_memoryview.setitem_slice_assignment = (PyObject *(*)(struct __pyx_memoryview_obj *, PyObject *, PyObject *))__pyx_memoryview_setitem_slice_assignment; + __pyx_vtable_memoryview.setitem_slice_assign_scalar = (PyObject *(*)(struct __pyx_memoryview_obj *, struct __pyx_memoryview_obj *, PyObject *))__pyx_memoryview_setitem_slice_assign_scalar; + __pyx_vtable_memoryview.setitem_indexed = (PyObject *(*)(struct __pyx_memoryview_obj *, PyObject *, PyObject *))__pyx_memoryview_setitem_indexed; + __pyx_vtable_memoryview.convert_item_to_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *))__pyx_memoryview_convert_item_to_object; + __pyx_vtable_memoryview.assign_item_from_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *, PyObject *))__pyx_memoryview_assign_item_from_object; + __pyx_vtable_memoryview._get_base = (PyObject *(*)(struct __pyx_memoryview_obj *))__pyx_memoryview__get_base; + #if CYTHON_USE_TYPE_SPECS + __pyx_memoryview_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_memoryview_spec, NULL); if (unlikely(!__pyx_memoryview_type)) __PYX_ERR(0, 337, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + __pyx_memoryview_type->tp_as_buffer = &__pyx_tp_as_buffer_memoryview; + if (!__pyx_memoryview_type->tp_as_buffer->bf_releasebuffer && __pyx_memoryview_type->tp_base->tp_as_buffer && __pyx_memoryview_type->tp_base->tp_as_buffer->bf_releasebuffer) { + __pyx_memoryview_type->tp_as_buffer->bf_releasebuffer = __pyx_memoryview_type->tp_base->tp_as_buffer->bf_releasebuffer; + } + #elif defined(Py_bf_getbuffer) && defined(Py_bf_releasebuffer) + /* PY_VERSION_HEX >= 0x03090000 || Py_LIMITED_API >= 0x030B0000 */ + #elif defined(_MSC_VER) + #pragma message ("The buffer protocol is not supported in the Limited C-API < 3.11.") + #else + #warning "The buffer protocol is not supported in the Limited C-API < 3.11." + #endif + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_memoryview_spec, __pyx_memoryview_type) < 0) __PYX_ERR(0, 337, __pyx_L1_error) + #else + __pyx_memoryview_type = &__pyx_type___pyx_memoryview; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_memoryview_type) < 0) __PYX_ERR(0, 337, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_memoryview_type->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_memoryview_type->tp_dictoffset && __pyx_memoryview_type->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_memoryview_type->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (__Pyx_SetVtable(__pyx_memoryview_type, __pyx_vtabptr_memoryview) < 0) __PYX_ERR(0, 337, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_memoryview_type) < 0) __PYX_ERR(0, 337, __pyx_L1_error) + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_memoryview_type) < 0) __PYX_ERR(0, 337, __pyx_L1_error) + #endif + __pyx_vtabptr__memoryviewslice = &__pyx_vtable__memoryviewslice; + __pyx_vtable__memoryviewslice.__pyx_base = *__pyx_vtabptr_memoryview; + __pyx_vtable__memoryviewslice.__pyx_base.convert_item_to_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *))__pyx_memoryviewslice_convert_item_to_object; + __pyx_vtable__memoryviewslice.__pyx_base.assign_item_from_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *, PyObject *))__pyx_memoryviewslice_assign_item_from_object; + __pyx_vtable__memoryviewslice.__pyx_base._get_base = (PyObject *(*)(struct __pyx_memoryview_obj *))__pyx_memoryviewslice__get_base; + #if CYTHON_USE_TYPE_SPECS + __pyx_t_1 = PyTuple_Pack(1, (PyObject *)__pyx_memoryview_type); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 952, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_memoryviewslice_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_memoryviewslice_spec, __pyx_t_1); + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_memoryviewslice_type)) __PYX_ERR(0, 952, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_memoryviewslice_spec, __pyx_memoryviewslice_type) < 0) __PYX_ERR(0, 952, __pyx_L1_error) + #else + __pyx_memoryviewslice_type = &__pyx_type___pyx_memoryviewslice; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + __pyx_memoryviewslice_type->tp_base = __pyx_memoryview_type; + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_memoryviewslice_type) < 0) __PYX_ERR(0, 952, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_memoryviewslice_type->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_memoryviewslice_type->tp_dictoffset && __pyx_memoryviewslice_type->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_memoryviewslice_type->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (__Pyx_SetVtable(__pyx_memoryviewslice_type, __pyx_vtabptr__memoryviewslice) < 0) __PYX_ERR(0, 952, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_memoryviewslice_type) < 0) __PYX_ERR(0, 952, __pyx_L1_error) + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_memoryviewslice_type) < 0) __PYX_ERR(0, 952, __pyx_L1_error) + #endif + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_RefNannyFinishContext(); + return -1; +} + +static int __Pyx_modinit_type_import_code(void) { + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_modinit_type_import_code", 0); + /*--- Type import code ---*/ + __pyx_t_1 = PyImport_ImportModule("cereal.visionipc.visionipc_pyx"); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 7, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext = __Pyx_ImportType_3_0_8(__pyx_t_1, "cereal.visionipc.visionipc_pyx", "CLContext", sizeof(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_CLContext), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_CLContext),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext) __PYX_ERR(2, 7, __pyx_L1_error) + __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf = __Pyx_ImportType_3_0_8(__pyx_t_1, "cereal.visionipc.visionipc_pyx", "VisionBuf", sizeof(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf) __PYX_ERR(2, 11, __pyx_L1_error) + __pyx_vtabptr_6cereal_9visionipc_13visionipc_pyx_VisionBuf = (struct __pyx_vtabstruct_6cereal_9visionipc_13visionipc_pyx_VisionBuf*)__Pyx_GetVtable(__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf); if (unlikely(!__pyx_vtabptr_6cereal_9visionipc_13visionipc_pyx_VisionBuf)) __PYX_ERR(2, 11, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = PyImport_ImportModule("selfdrive.modeld.models.commonmodel_pyx"); if (unlikely(!__pyx_t_1)) __PYX_ERR(3, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext = __Pyx_ImportType_3_0_8(__pyx_t_1, "selfdrive.modeld.models.commonmodel_pyx", "CLContext", sizeof(struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext) __PYX_ERR(3, 6, __pyx_L1_error) + __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem = __Pyx_ImportType_3_0_8(__pyx_t_1, "selfdrive.modeld.models.commonmodel_pyx", "CLMem", sizeof(struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem) __PYX_ERR(3, 9, __pyx_L1_error) + __pyx_vtabptr_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem = (struct __pyx_vtabstruct_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem*)__Pyx_GetVtable(__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem); if (unlikely(!__pyx_vtabptr_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem)) __PYX_ERR(3, 9, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_RefNannyFinishContext(); + return -1; +} + +static int __Pyx_modinit_variable_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_import_code", 0); + /*--- Variable import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_import_code", 0); + /*--- Function import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + + +#if PY_MAJOR_VERSION >= 3 +#if CYTHON_PEP489_MULTI_PHASE_INIT +static PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def); /*proto*/ +static int __pyx_pymod_exec_runmodel_pyx(PyObject* module); /*proto*/ +static PyModuleDef_Slot __pyx_moduledef_slots[] = { + {Py_mod_create, (void*)__pyx_pymod_create}, + {Py_mod_exec, (void*)__pyx_pymod_exec_runmodel_pyx}, + {0, NULL} +}; +#endif + +#ifdef __cplusplus +namespace { + struct PyModuleDef __pyx_moduledef = + #else + static struct PyModuleDef __pyx_moduledef = + #endif + { + PyModuleDef_HEAD_INIT, + "runmodel_pyx", + 0, /* m_doc */ + #if CYTHON_PEP489_MULTI_PHASE_INIT + 0, /* m_size */ + #elif CYTHON_USE_MODULE_STATE + sizeof(__pyx_mstate), /* m_size */ + #else + -1, /* m_size */ + #endif + __pyx_methods /* m_methods */, + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_moduledef_slots, /* m_slots */ + #else + NULL, /* m_reload */ + #endif + #if CYTHON_USE_MODULE_STATE + __pyx_m_traverse, /* m_traverse */ + __pyx_m_clear, /* m_clear */ + NULL /* m_free */ + #else + NULL, /* m_traverse */ + NULL, /* m_clear */ + NULL /* m_free */ + #endif + }; + #ifdef __cplusplus +} /* anonymous namespace */ +#endif +#endif + +#ifndef CYTHON_NO_PYINIT_EXPORT +#define __Pyx_PyMODINIT_FUNC PyMODINIT_FUNC +#elif PY_MAJOR_VERSION < 3 +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" void +#else +#define __Pyx_PyMODINIT_FUNC void +#endif +#else +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" PyObject * +#else +#define __Pyx_PyMODINIT_FUNC PyObject * +#endif +#endif + + +#if PY_MAJOR_VERSION < 3 +__Pyx_PyMODINIT_FUNC initrunmodel_pyx(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC initrunmodel_pyx(void) +#else +__Pyx_PyMODINIT_FUNC PyInit_runmodel_pyx(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC PyInit_runmodel_pyx(void) +#if CYTHON_PEP489_MULTI_PHASE_INIT +{ + return PyModuleDef_Init(&__pyx_moduledef); +} +static CYTHON_SMALL_CODE int __Pyx_check_single_interpreter(void) { + #if PY_VERSION_HEX >= 0x030700A1 + static PY_INT64_T main_interpreter_id = -1; + PY_INT64_T current_id = PyInterpreterState_GetID(PyThreadState_Get()->interp); + if (main_interpreter_id == -1) { + main_interpreter_id = current_id; + return (unlikely(current_id == -1)) ? -1 : 0; + } else if (unlikely(main_interpreter_id != current_id)) + #else + static PyInterpreterState *main_interpreter = NULL; + PyInterpreterState *current_interpreter = PyThreadState_Get()->interp; + if (!main_interpreter) { + main_interpreter = current_interpreter; + } else if (unlikely(main_interpreter != current_interpreter)) + #endif + { + PyErr_SetString( + PyExc_ImportError, + "Interpreter change detected - this module can only be loaded into one interpreter per process."); + return -1; + } + return 0; +} +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *module, const char* from_name, const char* to_name, int allow_none) +#else +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *moddict, const char* from_name, const char* to_name, int allow_none) +#endif +{ + PyObject *value = PyObject_GetAttrString(spec, from_name); + int result = 0; + if (likely(value)) { + if (allow_none || value != Py_None) { +#if CYTHON_COMPILING_IN_LIMITED_API + result = PyModule_AddObject(module, to_name, value); +#else + result = PyDict_SetItemString(moddict, to_name, value); +#endif + } + Py_DECREF(value); + } else if (PyErr_ExceptionMatches(PyExc_AttributeError)) { + PyErr_Clear(); + } else { + result = -1; + } + return result; +} +static CYTHON_SMALL_CODE PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def) { + PyObject *module = NULL, *moddict, *modname; + CYTHON_UNUSED_VAR(def); + if (__Pyx_check_single_interpreter()) + return NULL; + if (__pyx_m) + return __Pyx_NewRef(__pyx_m); + modname = PyObject_GetAttrString(spec, "name"); + if (unlikely(!modname)) goto bad; + module = PyModule_NewObject(modname); + Py_DECREF(modname); + if (unlikely(!module)) goto bad; +#if CYTHON_COMPILING_IN_LIMITED_API + moddict = module; +#else + moddict = PyModule_GetDict(module); + if (unlikely(!moddict)) goto bad; +#endif + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "loader", "__loader__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "origin", "__file__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "parent", "__package__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "submodule_search_locations", "__path__", 0) < 0)) goto bad; + return module; +bad: + Py_XDECREF(module); + return NULL; +} + + +static CYTHON_SMALL_CODE int __pyx_pymod_exec_runmodel_pyx(PyObject *__pyx_pyinit_module) +#endif +#endif +{ + int stringtab_initialized = 0; + #if CYTHON_USE_MODULE_STATE + int pystate_addmodule_run = 0; + #endif + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + static PyThread_type_lock __pyx_t_8[8]; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannyDeclarations + #if CYTHON_PEP489_MULTI_PHASE_INIT + if (__pyx_m) { + if (__pyx_m == __pyx_pyinit_module) return 0; + PyErr_SetString(PyExc_RuntimeError, "Module 'runmodel_pyx' has already been imported. Re-initialisation is not supported."); + return -1; + } + #elif PY_MAJOR_VERSION >= 3 + if (__pyx_m) return __Pyx_NewRef(__pyx_m); + #endif + /*--- Module creation code ---*/ + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_m = __pyx_pyinit_module; + Py_INCREF(__pyx_m); + #else + #if PY_MAJOR_VERSION < 3 + __pyx_m = Py_InitModule4("runmodel_pyx", __pyx_methods, 0, 0, PYTHON_API_VERSION); Py_XINCREF(__pyx_m); + if (unlikely(!__pyx_m)) __PYX_ERR(1, 1, __pyx_L1_error) + #elif CYTHON_USE_MODULE_STATE + __pyx_t_1 = PyModule_Create(&__pyx_moduledef); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 1, __pyx_L1_error) + { + int add_module_result = PyState_AddModule(__pyx_t_1, &__pyx_moduledef); + __pyx_t_1 = 0; /* transfer ownership from __pyx_t_1 to "runmodel_pyx" pseudovariable */ + if (unlikely((add_module_result < 0))) __PYX_ERR(1, 1, __pyx_L1_error) + pystate_addmodule_run = 1; + } + #else + __pyx_m = PyModule_Create(&__pyx_moduledef); + if (unlikely(!__pyx_m)) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + #endif + CYTHON_UNUSED_VAR(__pyx_t_1); + __pyx_d = PyModule_GetDict(__pyx_m); if (unlikely(!__pyx_d)) __PYX_ERR(1, 1, __pyx_L1_error) + Py_INCREF(__pyx_d); + __pyx_b = __Pyx_PyImport_AddModuleRef(__Pyx_BUILTIN_MODULE_NAME); if (unlikely(!__pyx_b)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_cython_runtime = __Pyx_PyImport_AddModuleRef((const char *) "cython_runtime"); if (unlikely(!__pyx_cython_runtime)) __PYX_ERR(1, 1, __pyx_L1_error) + if (PyObject_SetAttrString(__pyx_m, "__builtins__", __pyx_b) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #if CYTHON_REFNANNY +__Pyx_RefNanny = __Pyx_RefNannyImportAPI("refnanny"); +if (!__Pyx_RefNanny) { + PyErr_Clear(); + __Pyx_RefNanny = __Pyx_RefNannyImportAPI("Cython.Runtime.refnanny"); + if (!__Pyx_RefNanny) + Py_FatalError("failed to import 'refnanny' module"); +} +#endif + __Pyx_RefNannySetupContext("__Pyx_PyMODINIT_FUNC PyInit_runmodel_pyx(void)", 0); + if (__Pyx_check_binary_version(__PYX_LIMITED_VERSION_HEX, __Pyx_get_runtime_version(), CYTHON_COMPILING_IN_LIMITED_API) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #ifdef __Pxy_PyFrame_Initialize_Offsets + __Pxy_PyFrame_Initialize_Offsets(); + #endif + __pyx_empty_tuple = PyTuple_New(0); if (unlikely(!__pyx_empty_tuple)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_empty_bytes = PyBytes_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_bytes)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_empty_unicode = PyUnicode_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_unicode)) __PYX_ERR(1, 1, __pyx_L1_error) + #ifdef __Pyx_CyFunction_USED + if (__pyx_CyFunction_init(__pyx_m) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_FusedFunction_USED + if (__pyx_FusedFunction_init(__pyx_m) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Coroutine_USED + if (__pyx_Coroutine_init(__pyx_m) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Generator_USED + if (__pyx_Generator_init(__pyx_m) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_AsyncGen_USED + if (__pyx_AsyncGen_init(__pyx_m) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_StopAsyncIteration_USED + if (__pyx_StopAsyncIteration_init(__pyx_m) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + /*--- Library function declarations ---*/ + /*--- Threads initialization code ---*/ + #if defined(WITH_THREAD) && PY_VERSION_HEX < 0x030700F0 && defined(__PYX_FORCE_INIT_THREADS) && __PYX_FORCE_INIT_THREADS + PyEval_InitThreads(); + #endif + /*--- Initialize various global constants etc. ---*/ + if (__Pyx_InitConstants() < 0) __PYX_ERR(1, 1, __pyx_L1_error) + stringtab_initialized = 1; + if (__Pyx_InitGlobals() < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #if PY_MAJOR_VERSION < 3 && (__PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT) + if (__Pyx_init_sys_getdefaultencoding_params() < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + if (__pyx_module_is_main_selfdrive__modeld__runners__runmodel_pyx) { + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_name_2, __pyx_n_s_main) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + } + #if PY_MAJOR_VERSION >= 3 + { + PyObject *modules = PyImport_GetModuleDict(); if (unlikely(!modules)) __PYX_ERR(1, 1, __pyx_L1_error) + if (!PyDict_GetItemString(modules, "selfdrive.modeld.runners.runmodel_pyx")) { + if (unlikely((PyDict_SetItemString(modules, "selfdrive.modeld.runners.runmodel_pyx", __pyx_m) < 0))) __PYX_ERR(1, 1, __pyx_L1_error) + } + } + #endif + /*--- Builtin init code ---*/ + if (__Pyx_InitCachedBuiltins() < 0) __PYX_ERR(1, 1, __pyx_L1_error) + /*--- Constants init code ---*/ + if (__Pyx_InitCachedConstants() < 0) __PYX_ERR(1, 1, __pyx_L1_error) + /*--- Global type/function init code ---*/ + (void)__Pyx_modinit_global_init_code(); + (void)__Pyx_modinit_variable_export_code(); + (void)__Pyx_modinit_function_export_code(); + if (unlikely((__Pyx_modinit_type_init_code() < 0))) __PYX_ERR(1, 1, __pyx_L1_error) + if (unlikely((__Pyx_modinit_type_import_code() < 0))) __PYX_ERR(1, 1, __pyx_L1_error) + (void)__Pyx_modinit_variable_import_code(); + (void)__Pyx_modinit_function_import_code(); + /*--- Execution code ---*/ + #if defined(__Pyx_Generator_USED) || defined(__Pyx_Coroutine_USED) + if (__Pyx_patch_abc() < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + + /* "View.MemoryView":99 + * + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: # <<<<<<<<<<<<<< + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "View.MemoryView":100 + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: + * if __import__("sys").version_info >= (3, 3): # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + */ + __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__9, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 100, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_version_info); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 100, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = PyObject_RichCompare(__pyx_t_5, __pyx_tuple__10, Py_GE); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 100, __pyx_L2_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_6 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 100, __pyx_L2_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (__pyx_t_6) { + + /* "View.MemoryView":101 + * try: + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence # <<<<<<<<<<<<<< + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence + */ + __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__11, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 101, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_abc); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 101, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_Sequence); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 101, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XGOTREF(__pyx_collections_abc_Sequence); + __Pyx_DECREF_SET(__pyx_collections_abc_Sequence, __pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + __pyx_t_4 = 0; + + /* "View.MemoryView":100 + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: + * if __import__("sys").version_info >= (3, 3): # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + */ + goto __pyx_L8; + } + + /* "View.MemoryView":103 + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence # <<<<<<<<<<<<<< + * except: + * + */ + /*else*/ { + __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__12, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 103, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_Sequence); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 103, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XGOTREF(__pyx_collections_abc_Sequence); + __Pyx_DECREF_SET(__pyx_collections_abc_Sequence, __pyx_t_5); + __Pyx_GIVEREF(__pyx_t_5); + __pyx_t_5 = 0; + } + __pyx_L8:; + + /* "View.MemoryView":99 + * + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: # <<<<<<<<<<<<<< + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L7_try_end; + __pyx_L2_error:; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "View.MemoryView":104 + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence + * except: # <<<<<<<<<<<<<< + * + * __pyx_collections_abc_Sequence = None + */ + /*except:*/ { + __Pyx_AddTraceback("View.MemoryView", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_4, &__pyx_t_7) < 0) __PYX_ERR(0, 104, __pyx_L4_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_4); + __Pyx_XGOTREF(__pyx_t_7); + + /* "View.MemoryView":106 + * except: + * + * __pyx_collections_abc_Sequence = None # <<<<<<<<<<<<<< + * + * + */ + __Pyx_INCREF(Py_None); + __Pyx_XGOTREF(__pyx_collections_abc_Sequence); + __Pyx_DECREF_SET(__pyx_collections_abc_Sequence, Py_None); + __Pyx_GIVEREF(Py_None); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + goto __pyx_L3_exception_handled; + } + + /* "View.MemoryView":99 + * + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: # <<<<<<<<<<<<<< + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + */ + __pyx_L4_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + goto __pyx_L1_error; + __pyx_L3_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + __pyx_L7_try_end:; + } + + /* "View.MemoryView":241 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_3, &__pyx_t_2, &__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_1); + /*try:*/ { + + /* "View.MemoryView":242 + * + * try: + * count = __pyx_collections_abc_Sequence.count # <<<<<<<<<<<<<< + * index = __pyx_collections_abc_Sequence.index + * except: + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_count); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 242, __pyx_L11_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict(__pyx_array_type, __pyx_n_s_count, __pyx_t_7) < 0) __PYX_ERR(0, 242, __pyx_L11_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_array_type); + + /* "View.MemoryView":243 + * try: + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index # <<<<<<<<<<<<<< + * except: + * pass + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_index); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 243, __pyx_L11_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict(__pyx_array_type, __pyx_n_s_index, __pyx_t_7) < 0) __PYX_ERR(0, 243, __pyx_L11_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_array_type); + + /* "View.MemoryView":241 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + } + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + goto __pyx_L16_try_end; + __pyx_L11_error:; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":244 + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + * except: # <<<<<<<<<<<<<< + * pass + * + */ + /*except:*/ { + __Pyx_ErrRestore(0,0,0); + goto __pyx_L12_exception_handled; + } + __pyx_L12_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_2, __pyx_t_1); + __pyx_L16_try_end:; + } + + /* "View.MemoryView":309 + * return self.name + * + * cdef generic = Enum("") # <<<<<<<<<<<<<< + * cdef strided = Enum("") # default + * cdef indirect = Enum("") + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__13, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 309, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(generic); + __Pyx_DECREF_SET(generic, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":310 + * + * cdef generic = Enum("") + * cdef strided = Enum("") # default # <<<<<<<<<<<<<< + * cdef indirect = Enum("") + * + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__14, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 310, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(strided); + __Pyx_DECREF_SET(strided, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":311 + * cdef generic = Enum("") + * cdef strided = Enum("") # default + * cdef indirect = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__15, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 311, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(indirect); + __Pyx_DECREF_SET(indirect, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":314 + * + * + * cdef contiguous = Enum("") # <<<<<<<<<<<<<< + * cdef indirect_contiguous = Enum("") + * + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__16, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 314, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(contiguous); + __Pyx_DECREF_SET(contiguous, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":315 + * + * cdef contiguous = Enum("") + * cdef indirect_contiguous = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__17, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 315, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(indirect_contiguous); + __Pyx_DECREF_SET(indirect_contiguous, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":323 + * + * + * cdef int __pyx_memoryview_thread_locks_used = 0 # <<<<<<<<<<<<<< + * cdef PyThread_type_lock[8] __pyx_memoryview_thread_locks = [ + * PyThread_allocate_lock(), + */ + __pyx_memoryview_thread_locks_used = 0; + + /* "View.MemoryView":324 + * + * cdef int __pyx_memoryview_thread_locks_used = 0 + * cdef PyThread_type_lock[8] __pyx_memoryview_thread_locks = [ # <<<<<<<<<<<<<< + * PyThread_allocate_lock(), + * PyThread_allocate_lock(), + */ + __pyx_t_8[0] = PyThread_allocate_lock(); + __pyx_t_8[1] = PyThread_allocate_lock(); + __pyx_t_8[2] = PyThread_allocate_lock(); + __pyx_t_8[3] = PyThread_allocate_lock(); + __pyx_t_8[4] = PyThread_allocate_lock(); + __pyx_t_8[5] = PyThread_allocate_lock(); + __pyx_t_8[6] = PyThread_allocate_lock(); + __pyx_t_8[7] = PyThread_allocate_lock(); + memcpy(&(__pyx_memoryview_thread_locks[0]), __pyx_t_8, sizeof(__pyx_memoryview_thread_locks[0]) * (8)); + + /* "View.MemoryView":982 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "View.MemoryView":983 + * + * try: + * count = __pyx_collections_abc_Sequence.count # <<<<<<<<<<<<<< + * index = __pyx_collections_abc_Sequence.index + * except: + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_count); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 983, __pyx_L17_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict(__pyx_memoryviewslice_type, __pyx_n_s_count, __pyx_t_7) < 0) __PYX_ERR(0, 983, __pyx_L17_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_memoryviewslice_type); + + /* "View.MemoryView":984 + * try: + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index # <<<<<<<<<<<<<< + * except: + * pass + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_index); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 984, __pyx_L17_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict(__pyx_memoryviewslice_type, __pyx_n_s_index, __pyx_t_7) < 0) __PYX_ERR(0, 984, __pyx_L17_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_memoryviewslice_type); + + /* "View.MemoryView":982 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L22_try_end; + __pyx_L17_error:; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":985 + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + * except: # <<<<<<<<<<<<<< + * pass + * + */ + /*except:*/ { + __Pyx_ErrRestore(0,0,0); + goto __pyx_L18_exception_handled; + } + __pyx_L18_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + __pyx_L22_try_end:; + } + + /* "View.MemoryView":988 + * pass + * + * try: # <<<<<<<<<<<<<< + * if __pyx_collections_abc_Sequence: + * + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_3, &__pyx_t_2, &__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_1); + /*try:*/ { + + /* "View.MemoryView":989 + * + * try: + * if __pyx_collections_abc_Sequence: # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_6 = __Pyx_PyObject_IsTrue(__pyx_collections_abc_Sequence); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 989, __pyx_L23_error) + if (__pyx_t_6) { + + /* "View.MemoryView":993 + * + * + * __pyx_collections_abc_Sequence.register(_memoryviewslice) # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence.register(array) + * except: + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_register); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 993, __pyx_L23_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_4 = __Pyx_PyObject_CallOneArg(__pyx_t_7, ((PyObject *)__pyx_memoryviewslice_type)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 993, __pyx_L23_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "View.MemoryView":994 + * + * __pyx_collections_abc_Sequence.register(_memoryviewslice) + * __pyx_collections_abc_Sequence.register(array) # <<<<<<<<<<<<<< + * except: + * pass # ignore failure, it's a minor issue + */ + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_register); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 994, __pyx_L23_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_7 = __Pyx_PyObject_CallOneArg(__pyx_t_4, ((PyObject *)__pyx_array_type)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 994, __pyx_L23_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":989 + * + * try: + * if __pyx_collections_abc_Sequence: # <<<<<<<<<<<<<< + * + * + */ + } + + /* "View.MemoryView":988 + * pass + * + * try: # <<<<<<<<<<<<<< + * if __pyx_collections_abc_Sequence: + * + */ + } + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + goto __pyx_L28_try_end; + __pyx_L23_error:; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":995 + * __pyx_collections_abc_Sequence.register(_memoryviewslice) + * __pyx_collections_abc_Sequence.register(array) + * except: # <<<<<<<<<<<<<< + * pass # ignore failure, it's a minor issue + * + */ + /*except:*/ { + __Pyx_ErrRestore(0,0,0); + goto __pyx_L24_exception_handled; + } + __pyx_L24_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_2, __pyx_t_1); + __pyx_L28_try_end:; + } + + /* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + __pyx_t_7 = PyCFunction_NewEx(&__pyx_mdef_15View_dot_MemoryView_1__pyx_unpickle_Enum, NULL, __pyx_n_s_View_MemoryView); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_pyx_unpickle_Enum, __pyx_t_7) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "selfdrive/modeld/runners/runmodel_pyx.pyx":9 + * from selfdrive.modeld.models.commonmodel_pyx cimport CLMem + * + * class Runtime: # <<<<<<<<<<<<<< + * CPU = USE_CPU_RUNTIME + * GPU = USE_GPU_RUNTIME + */ + __pyx_t_7 = __Pyx_Py3MetaclassPrepare((PyObject *) NULL, __pyx_empty_tuple, __pyx_n_s_Runtime, __pyx_n_s_Runtime, (PyObject *) NULL, __pyx_n_s_selfdrive_modeld_runners_runmode, (PyObject *) NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 9, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + + /* "selfdrive/modeld/runners/runmodel_pyx.pyx":10 + * + * class Runtime: + * CPU = USE_CPU_RUNTIME # <<<<<<<<<<<<<< + * GPU = USE_GPU_RUNTIME + * DSP = USE_DSP_RUNTIME + */ + __pyx_t_4 = __Pyx_PyInt_From_int(USE_CPU_RUNTIME); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 10, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (__Pyx_SetNameInClass(__pyx_t_7, __pyx_n_s_CPU, __pyx_t_4) < 0) __PYX_ERR(1, 10, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "selfdrive/modeld/runners/runmodel_pyx.pyx":11 + * class Runtime: + * CPU = USE_CPU_RUNTIME + * GPU = USE_GPU_RUNTIME # <<<<<<<<<<<<<< + * DSP = USE_DSP_RUNTIME + * + */ + __pyx_t_4 = __Pyx_PyInt_From_int(USE_GPU_RUNTIME); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 11, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (__Pyx_SetNameInClass(__pyx_t_7, __pyx_n_s_GPU, __pyx_t_4) < 0) __PYX_ERR(1, 11, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "selfdrive/modeld/runners/runmodel_pyx.pyx":12 + * CPU = USE_CPU_RUNTIME + * GPU = USE_GPU_RUNTIME + * DSP = USE_DSP_RUNTIME # <<<<<<<<<<<<<< + * + * cdef class RunModel: + */ + __pyx_t_4 = __Pyx_PyInt_From_int(USE_DSP_RUNTIME); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 12, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (__Pyx_SetNameInClass(__pyx_t_7, __pyx_n_s_DSP, __pyx_t_4) < 0) __PYX_ERR(1, 12, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "selfdrive/modeld/runners/runmodel_pyx.pyx":9 + * from selfdrive.modeld.models.commonmodel_pyx cimport CLMem + * + * class Runtime: # <<<<<<<<<<<<<< + * CPU = USE_CPU_RUNTIME + * GPU = USE_GPU_RUNTIME + */ + __pyx_t_4 = __Pyx_Py3ClassCreate(((PyObject*)&PyType_Type), __pyx_n_s_Runtime, __pyx_empty_tuple, __pyx_t_7, NULL, 0, 0); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 9, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_Runtime, __pyx_t_4) < 0) __PYX_ERR(1, 9, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "selfdrive/modeld/runners/runmodel_pyx.pyx":18 + * del self.model + * + * def addInput(self, string name, float[:] buffer): # <<<<<<<<<<<<<< + * if buffer is not None: + * self.model.addInput(name, &buffer[0], len(buffer)) + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_3addInput, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_RunModel_addInput, NULL, __pyx_n_s_selfdrive_modeld_runners_runmode, __pyx_d, ((PyObject *)__pyx_codeobj__21)); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 18, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel, __pyx_n_s_addInput, __pyx_t_7) < 0) __PYX_ERR(1, 18, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel); + + /* "selfdrive/modeld/runners/runmodel_pyx.pyx":24 + * self.model.addInput(name, NULL, 0) + * + * def setInputBuffer(self, string name, float[:] buffer): # <<<<<<<<<<<<<< + * if buffer is not None: + * self.model.setInputBuffer(name, &buffer[0], len(buffer)) + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_5setInputBuffer, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_RunModel_setInputBuffer, NULL, __pyx_n_s_selfdrive_modeld_runners_runmode, __pyx_d, ((PyObject *)__pyx_codeobj__22)); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 24, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel, __pyx_n_s_setInputBuffer, __pyx_t_7) < 0) __PYX_ERR(1, 24, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel); + + /* "selfdrive/modeld/runners/runmodel_pyx.pyx":30 + * self.model.setInputBuffer(name, NULL, 0) + * + * def getCLBuffer(self, string name): # <<<<<<<<<<<<<< + * cdef void * cl_buf = self.model.getCLBuffer(name) + * if not cl_buf: + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_7getCLBuffer, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_RunModel_getCLBuffer, NULL, __pyx_n_s_selfdrive_modeld_runners_runmode, __pyx_d, ((PyObject *)__pyx_codeobj__24)); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 30, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel, __pyx_n_s_getCLBuffer, __pyx_t_7) < 0) __PYX_ERR(1, 30, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel); + + /* "selfdrive/modeld/runners/runmodel_pyx.pyx":36 + * return CLMem.create(cl_buf) + * + * def execute(self): # <<<<<<<<<<<<<< + * self.model.execute() + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_9execute, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_RunModel_execute, NULL, __pyx_n_s_selfdrive_modeld_runners_runmode, __pyx_d, ((PyObject *)__pyx_codeobj__26)); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 36, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict((PyObject *)__pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel, __pyx_n_s_execute, __pyx_t_7) < 0) __PYX_ERR(1, 36, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel); + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "self.model cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_11__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_RunModel___reduce_cython, NULL, __pyx_n_s_selfdrive_modeld_runners_runmode, __pyx_d, ((PyObject *)__pyx_codeobj__27)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_7) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "self.model cannot be converted to a Python object for pickling" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "self.model cannot be converted to a Python object for pickling" + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_9selfdrive_6modeld_7runners_12runmodel_pyx_8RunModel_13__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_RunModel___setstate_cython, NULL, __pyx_n_s_selfdrive_modeld_runners_runmode, __pyx_d, ((PyObject *)__pyx_codeobj__29)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_7) < 0) __PYX_ERR(0, 3, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "selfdrive/modeld/runners/runmodel_pyx.pyx":1 + * # distutils: language = c++ # <<<<<<<<<<<<<< + * # cython: c_string_encoding=ascii + * + */ + __pyx_t_7 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_test, __pyx_t_7) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /*--- Wrapped vars code ---*/ + + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_7); + if (__pyx_m) { + if (__pyx_d && stringtab_initialized) { + __Pyx_AddTraceback("init selfdrive.modeld.runners.runmodel_pyx", __pyx_clineno, __pyx_lineno, __pyx_filename); + } + #if !CYTHON_USE_MODULE_STATE + Py_CLEAR(__pyx_m); + #else + Py_DECREF(__pyx_m); + if (pystate_addmodule_run) { + PyObject *tp, *value, *tb; + PyErr_Fetch(&tp, &value, &tb); + PyState_RemoveModule(&__pyx_moduledef); + PyErr_Restore(tp, value, tb); + } + #endif + } else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_ImportError, "init selfdrive.modeld.runners.runmodel_pyx"); + } + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + #if CYTHON_PEP489_MULTI_PHASE_INIT + return (__pyx_m != NULL) ? 0 : -1; + #elif PY_MAJOR_VERSION >= 3 + return __pyx_m; + #else + return; + #endif +} +/* #### Code section: cleanup_globals ### */ +/* #### Code section: cleanup_module ### */ +/* #### Code section: main_method ### */ +/* #### Code section: utility_code_pragmas ### */ +#ifdef _MSC_VER +#pragma warning( push ) +/* Warning 4127: conditional expression is constant + * Cython uses constant conditional expressions to allow in inline functions to be optimized at + * compile-time, so this warning is not useful + */ +#pragma warning( disable : 4127 ) +#endif + + + +/* #### Code section: utility_code_def ### */ + +/* --- Runtime support code --- */ +/* Refnanny */ +#if CYTHON_REFNANNY +static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname) { + PyObject *m = NULL, *p = NULL; + void *r = NULL; + m = PyImport_ImportModule(modname); + if (!m) goto end; + p = PyObject_GetAttrString(m, "RefNannyAPI"); + if (!p) goto end; + r = PyLong_AsVoidPtr(p); +end: + Py_XDECREF(p); + Py_XDECREF(m); + return (__Pyx_RefNannyAPIStruct *)r; +} +#endif + +/* PyErrExceptionMatches */ +#if CYTHON_FAST_THREAD_STATE +static int __Pyx_PyErr_ExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; i= 0x030C00A6 + PyObject *current_exception = tstate->current_exception; + if (unlikely(!current_exception)) return 0; + exc_type = (PyObject*) Py_TYPE(current_exception); + if (exc_type == err) return 1; +#else + exc_type = tstate->curexc_type; + if (exc_type == err) return 1; + if (unlikely(!exc_type)) return 0; +#endif + #if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(exc_type); + #endif + if (unlikely(PyTuple_Check(err))) { + result = __Pyx_PyErr_ExceptionMatchesTuple(exc_type, err); + } else { + result = __Pyx_PyErr_GivenExceptionMatches(exc_type, err); + } + #if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(exc_type); + #endif + return result; +} +#endif + +/* PyErrFetchRestore */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject *tmp_value; + assert(type == NULL || (value != NULL && type == (PyObject*) Py_TYPE(value))); + if (value) { + #if CYTHON_COMPILING_IN_CPYTHON + if (unlikely(((PyBaseExceptionObject*) value)->traceback != tb)) + #endif + PyException_SetTraceback(value, tb); + } + tmp_value = tstate->current_exception; + tstate->current_exception = value; + Py_XDECREF(tmp_value); + Py_XDECREF(type); + Py_XDECREF(tb); +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + tmp_type = tstate->curexc_type; + tmp_value = tstate->curexc_value; + tmp_tb = tstate->curexc_traceback; + tstate->curexc_type = type; + tstate->curexc_value = value; + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); +#endif +} +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject* exc_value; + exc_value = tstate->current_exception; + tstate->current_exception = 0; + *value = exc_value; + *type = NULL; + *tb = NULL; + if (exc_value) { + *type = (PyObject*) Py_TYPE(exc_value); + Py_INCREF(*type); + #if CYTHON_COMPILING_IN_CPYTHON + *tb = ((PyBaseExceptionObject*) exc_value)->traceback; + Py_XINCREF(*tb); + #else + *tb = PyException_GetTraceback(exc_value); + #endif + } +#else + *type = tstate->curexc_type; + *value = tstate->curexc_value; + *tb = tstate->curexc_traceback; + tstate->curexc_type = 0; + tstate->curexc_value = 0; + tstate->curexc_traceback = 0; +#endif +} +#endif + +/* PyObjectGetAttrStr */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name) { + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro)) + return tp->tp_getattro(obj, attr_name); +#if PY_MAJOR_VERSION < 3 + if (likely(tp->tp_getattr)) + return tp->tp_getattr(obj, PyString_AS_STRING(attr_name)); +#endif + return PyObject_GetAttr(obj, attr_name); +} +#endif + +/* PyObjectGetAttrStrNoError */ +#if __PYX_LIMITED_VERSION_HEX < 0x030d00A1 +static void __Pyx_PyObject_GetAttrStr_ClearAttributeError(void) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + if (likely(__Pyx_PyErr_ExceptionMatches(PyExc_AttributeError))) + __Pyx_PyErr_Clear(); +} +#endif +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name) { + PyObject *result; +#if __PYX_LIMITED_VERSION_HEX >= 0x030d00A1 + (void) PyObject_GetOptionalAttr(obj, attr_name, &result); + return result; +#else +#if CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_TYPE_SLOTS && PY_VERSION_HEX >= 0x030700B1 + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro == PyObject_GenericGetAttr)) { + return _PyObject_GenericGetAttrWithDict(obj, attr_name, NULL, 1); + } +#endif + result = __Pyx_PyObject_GetAttrStr(obj, attr_name); + if (unlikely(!result)) { + __Pyx_PyObject_GetAttrStr_ClearAttributeError(); + } + return result; +#endif +} + +/* GetBuiltinName */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name) { + PyObject* result = __Pyx_PyObject_GetAttrStrNoError(__pyx_b, name); + if (unlikely(!result) && !PyErr_Occurred()) { + PyErr_Format(PyExc_NameError, +#if PY_MAJOR_VERSION >= 3 + "name '%U' is not defined", name); +#else + "name '%.200s' is not defined", PyString_AS_STRING(name)); +#endif + } + return result; +} + +/* TupleAndListFromArray */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE void __Pyx_copy_object_array(PyObject *const *CYTHON_RESTRICT src, PyObject** CYTHON_RESTRICT dest, Py_ssize_t length) { + PyObject *v; + Py_ssize_t i; + for (i = 0; i < length; i++) { + v = dest[i] = src[i]; + Py_INCREF(v); + } +} +static CYTHON_INLINE PyObject * +__Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + Py_INCREF(__pyx_empty_tuple); + return __pyx_empty_tuple; + } + res = PyTuple_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyTupleObject*)res)->ob_item, n); + return res; +} +static CYTHON_INLINE PyObject * +__Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + return PyList_New(0); + } + res = PyList_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyListObject*)res)->ob_item, n); + return res; +} +#endif + +/* BytesEquals */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else + if (s1 == s2) { + return (equals == Py_EQ); + } else if (PyBytes_CheckExact(s1) & PyBytes_CheckExact(s2)) { + const char *ps1, *ps2; + Py_ssize_t length = PyBytes_GET_SIZE(s1); + if (length != PyBytes_GET_SIZE(s2)) + return (equals == Py_NE); + ps1 = PyBytes_AS_STRING(s1); + ps2 = PyBytes_AS_STRING(s2); + if (ps1[0] != ps2[0]) { + return (equals == Py_NE); + } else if (length == 1) { + return (equals == Py_EQ); + } else { + int result; +#if CYTHON_USE_UNICODE_INTERNALS && (PY_VERSION_HEX < 0x030B0000) + Py_hash_t hash1, hash2; + hash1 = ((PyBytesObject*)s1)->ob_shash; + hash2 = ((PyBytesObject*)s2)->ob_shash; + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + return (equals == Py_NE); + } +#endif + result = memcmp(ps1, ps2, (size_t)length); + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & PyBytes_CheckExact(s2)) { + return (equals == Py_NE); + } else if ((s2 == Py_None) & PyBytes_CheckExact(s1)) { + return (equals == Py_NE); + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +#endif +} + +/* UnicodeEquals */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else +#if PY_MAJOR_VERSION < 3 + PyObject* owned_ref = NULL; +#endif + int s1_is_unicode, s2_is_unicode; + if (s1 == s2) { + goto return_eq; + } + s1_is_unicode = PyUnicode_CheckExact(s1); + s2_is_unicode = PyUnicode_CheckExact(s2); +#if PY_MAJOR_VERSION < 3 + if ((s1_is_unicode & (!s2_is_unicode)) && PyString_CheckExact(s2)) { + owned_ref = PyUnicode_FromObject(s2); + if (unlikely(!owned_ref)) + return -1; + s2 = owned_ref; + s2_is_unicode = 1; + } else if ((s2_is_unicode & (!s1_is_unicode)) && PyString_CheckExact(s1)) { + owned_ref = PyUnicode_FromObject(s1); + if (unlikely(!owned_ref)) + return -1; + s1 = owned_ref; + s1_is_unicode = 1; + } else if (((!s2_is_unicode) & (!s1_is_unicode))) { + return __Pyx_PyBytes_Equals(s1, s2, equals); + } +#endif + if (s1_is_unicode & s2_is_unicode) { + Py_ssize_t length; + int kind; + void *data1, *data2; + if (unlikely(__Pyx_PyUnicode_READY(s1) < 0) || unlikely(__Pyx_PyUnicode_READY(s2) < 0)) + return -1; + length = __Pyx_PyUnicode_GET_LENGTH(s1); + if (length != __Pyx_PyUnicode_GET_LENGTH(s2)) { + goto return_ne; + } +#if CYTHON_USE_UNICODE_INTERNALS + { + Py_hash_t hash1, hash2; + #if CYTHON_PEP393_ENABLED + hash1 = ((PyASCIIObject*)s1)->hash; + hash2 = ((PyASCIIObject*)s2)->hash; + #else + hash1 = ((PyUnicodeObject*)s1)->hash; + hash2 = ((PyUnicodeObject*)s2)->hash; + #endif + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + goto return_ne; + } + } +#endif + kind = __Pyx_PyUnicode_KIND(s1); + if (kind != __Pyx_PyUnicode_KIND(s2)) { + goto return_ne; + } + data1 = __Pyx_PyUnicode_DATA(s1); + data2 = __Pyx_PyUnicode_DATA(s2); + if (__Pyx_PyUnicode_READ(kind, data1, 0) != __Pyx_PyUnicode_READ(kind, data2, 0)) { + goto return_ne; + } else if (length == 1) { + goto return_eq; + } else { + int result = memcmp(data1, data2, (size_t)(length * kind)); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & s2_is_unicode) { + goto return_ne; + } else if ((s2 == Py_None) & s1_is_unicode) { + goto return_ne; + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +return_eq: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ); +return_ne: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_NE); +#endif +} + +/* fastcall */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s) +{ + Py_ssize_t i, n = PyTuple_GET_SIZE(kwnames); + for (i = 0; i < n; i++) + { + if (s == PyTuple_GET_ITEM(kwnames, i)) return kwvalues[i]; + } + for (i = 0; i < n; i++) + { + int eq = __Pyx_PyUnicode_Equals(s, PyTuple_GET_ITEM(kwnames, i), Py_EQ); + if (unlikely(eq != 0)) { + if (unlikely(eq < 0)) return NULL; + return kwvalues[i]; + } + } + return NULL; +} +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 +CYTHON_UNUSED static PyObject *__Pyx_KwargsAsDict_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues) { + Py_ssize_t i, nkwargs = PyTuple_GET_SIZE(kwnames); + PyObject *dict; + dict = PyDict_New(); + if (unlikely(!dict)) + return NULL; + for (i=0; i= 3 + "%s() got multiple values for keyword argument '%U'", func_name, kw_name); + #else + "%s() got multiple values for keyword argument '%s'", func_name, + PyString_AsString(kw_name)); + #endif +} + +/* ParseKeywords */ +static int __Pyx_ParseOptionalKeywords( + PyObject *kwds, + PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, + PyObject *values[], + Py_ssize_t num_pos_args, + const char* function_name) +{ + PyObject *key = 0, *value = 0; + Py_ssize_t pos = 0; + PyObject*** name; + PyObject*** first_kw_arg = argnames + num_pos_args; + int kwds_is_tuple = CYTHON_METH_FASTCALL && likely(PyTuple_Check(kwds)); + while (1) { + Py_XDECREF(key); key = NULL; + Py_XDECREF(value); value = NULL; + if (kwds_is_tuple) { + Py_ssize_t size; +#if CYTHON_ASSUME_SAFE_MACROS + size = PyTuple_GET_SIZE(kwds); +#else + size = PyTuple_Size(kwds); + if (size < 0) goto bad; +#endif + if (pos >= size) break; +#if CYTHON_AVOID_BORROWED_REFS + key = __Pyx_PySequence_ITEM(kwds, pos); + if (!key) goto bad; +#elif CYTHON_ASSUME_SAFE_MACROS + key = PyTuple_GET_ITEM(kwds, pos); +#else + key = PyTuple_GetItem(kwds, pos); + if (!key) goto bad; +#endif + value = kwvalues[pos]; + pos++; + } + else + { + if (!PyDict_Next(kwds, &pos, &key, &value)) break; +#if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(key); +#endif + } + name = first_kw_arg; + while (*name && (**name != key)) name++; + if (*name) { + values[name-argnames] = value; +#if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(value); + Py_DECREF(key); +#endif + key = NULL; + value = NULL; + continue; + } +#if !CYTHON_AVOID_BORROWED_REFS + Py_INCREF(key); +#endif + Py_INCREF(value); + name = first_kw_arg; + #if PY_MAJOR_VERSION < 3 + if (likely(PyString_Check(key))) { + while (*name) { + if ((CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**name) == PyString_GET_SIZE(key)) + && _PyString_Eq(**name, key)) { + values[name-argnames] = value; +#if CYTHON_AVOID_BORROWED_REFS + value = NULL; +#endif + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + if ((**argname == key) || ( + (CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**argname) == PyString_GET_SIZE(key)) + && _PyString_Eq(**argname, key))) { + goto arg_passed_twice; + } + argname++; + } + } + } else + #endif + if (likely(PyUnicode_Check(key))) { + while (*name) { + int cmp = ( + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**name) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**name, key) + ); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) { + values[name-argnames] = value; +#if CYTHON_AVOID_BORROWED_REFS + value = NULL; +#endif + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + int cmp = (**argname == key) ? 0 : + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**argname) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**argname, key); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) goto arg_passed_twice; + argname++; + } + } + } else + goto invalid_keyword_type; + if (kwds2) { + if (unlikely(PyDict_SetItem(kwds2, key, value))) goto bad; + } else { + goto invalid_keyword; + } + } + Py_XDECREF(key); + Py_XDECREF(value); + return 0; +arg_passed_twice: + __Pyx_RaiseDoubleKeywordsError(function_name, key); + goto bad; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + goto bad; +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif +bad: + Py_XDECREF(key); + Py_XDECREF(value); + return -1; +} + +/* ArgTypeTest */ +static int __Pyx__ArgTypeTest(PyObject *obj, PyTypeObject *type, const char *name, int exact) +{ + __Pyx_TypeName type_name; + __Pyx_TypeName obj_type_name; + if (unlikely(!type)) { + PyErr_SetString(PyExc_SystemError, "Missing type object"); + return 0; + } + else if (exact) { + #if PY_MAJOR_VERSION == 2 + if ((type == &PyBaseString_Type) && likely(__Pyx_PyBaseString_CheckExact(obj))) return 1; + #endif + } + else { + if (likely(__Pyx_TypeCheck(obj, type))) return 1; + } + type_name = __Pyx_PyType_GetName(type); + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "Argument '%.200s' has incorrect type (expected " __Pyx_FMT_TYPENAME + ", got " __Pyx_FMT_TYPENAME ")", name, type_name, obj_type_name); + __Pyx_DECREF_TypeName(type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return 0; +} + +/* RaiseException */ +#if PY_MAJOR_VERSION < 3 +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + __Pyx_PyThreadState_declare + CYTHON_UNUSED_VAR(cause); + Py_XINCREF(type); + if (!value || value == Py_None) + value = NULL; + else + Py_INCREF(value); + if (!tb || tb == Py_None) + tb = NULL; + else { + Py_INCREF(tb); + if (!PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto raise_error; + } + } + if (PyType_Check(type)) { +#if CYTHON_COMPILING_IN_PYPY + if (!value) { + Py_INCREF(Py_None); + value = Py_None; + } +#endif + PyErr_NormalizeException(&type, &value, &tb); + } else { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto raise_error; + } + value = type; + type = (PyObject*) Py_TYPE(type); + Py_INCREF(type); + if (!PyType_IsSubtype((PyTypeObject *)type, (PyTypeObject *)PyExc_BaseException)) { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto raise_error; + } + } + __Pyx_PyThreadState_assign + __Pyx_ErrRestore(type, value, tb); + return; +raise_error: + Py_XDECREF(value); + Py_XDECREF(type); + Py_XDECREF(tb); + return; +} +#else +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + PyObject* owned_instance = NULL; + if (tb == Py_None) { + tb = 0; + } else if (tb && !PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto bad; + } + if (value == Py_None) + value = 0; + if (PyExceptionInstance_Check(type)) { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto bad; + } + value = type; + type = (PyObject*) Py_TYPE(value); + } else if (PyExceptionClass_Check(type)) { + PyObject *instance_class = NULL; + if (value && PyExceptionInstance_Check(value)) { + instance_class = (PyObject*) Py_TYPE(value); + if (instance_class != type) { + int is_subclass = PyObject_IsSubclass(instance_class, type); + if (!is_subclass) { + instance_class = NULL; + } else if (unlikely(is_subclass == -1)) { + goto bad; + } else { + type = instance_class; + } + } + } + if (!instance_class) { + PyObject *args; + if (!value) + args = PyTuple_New(0); + else if (PyTuple_Check(value)) { + Py_INCREF(value); + args = value; + } else + args = PyTuple_Pack(1, value); + if (!args) + goto bad; + owned_instance = PyObject_Call(type, args, NULL); + Py_DECREF(args); + if (!owned_instance) + goto bad; + value = owned_instance; + if (!PyExceptionInstance_Check(value)) { + PyErr_Format(PyExc_TypeError, + "calling %R should have returned an instance of " + "BaseException, not %R", + type, Py_TYPE(value)); + goto bad; + } + } + } else { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto bad; + } + if (cause) { + PyObject *fixed_cause; + if (cause == Py_None) { + fixed_cause = NULL; + } else if (PyExceptionClass_Check(cause)) { + fixed_cause = PyObject_CallObject(cause, NULL); + if (fixed_cause == NULL) + goto bad; + } else if (PyExceptionInstance_Check(cause)) { + fixed_cause = cause; + Py_INCREF(fixed_cause); + } else { + PyErr_SetString(PyExc_TypeError, + "exception causes must derive from " + "BaseException"); + goto bad; + } + PyException_SetCause(value, fixed_cause); + } + PyErr_SetObject(type, value); + if (tb) { + #if PY_VERSION_HEX >= 0x030C00A6 + PyException_SetTraceback(value, tb); + #elif CYTHON_FAST_THREAD_STATE + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject* tmp_tb = tstate->curexc_traceback; + if (tb != tmp_tb) { + Py_INCREF(tb); + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_tb); + } +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + PyErr_Fetch(&tmp_type, &tmp_value, &tmp_tb); + Py_INCREF(tb); + PyErr_Restore(tmp_type, tmp_value, tb); + Py_XDECREF(tmp_tb); +#endif + } +bad: + Py_XDECREF(owned_instance); + return; +} +#endif + +/* PyFunctionFastCall */ +#if CYTHON_FAST_PYCALL && !CYTHON_VECTORCALL +static PyObject* __Pyx_PyFunction_FastCallNoKw(PyCodeObject *co, PyObject **args, Py_ssize_t na, + PyObject *globals) { + PyFrameObject *f; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject **fastlocals; + Py_ssize_t i; + PyObject *result; + assert(globals != NULL); + /* XXX Perhaps we should create a specialized + PyFrame_New() that doesn't take locals, but does + take builtins without sanity checking them. + */ + assert(tstate != NULL); + f = PyFrame_New(tstate, co, globals, NULL); + if (f == NULL) { + return NULL; + } + fastlocals = __Pyx_PyFrame_GetLocalsplus(f); + for (i = 0; i < na; i++) { + Py_INCREF(*args); + fastlocals[i] = *args++; + } + result = PyEval_EvalFrameEx(f,0); + ++tstate->recursion_depth; + Py_DECREF(f); + --tstate->recursion_depth; + return result; +} +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs) { + PyCodeObject *co = (PyCodeObject *)PyFunction_GET_CODE(func); + PyObject *globals = PyFunction_GET_GLOBALS(func); + PyObject *argdefs = PyFunction_GET_DEFAULTS(func); + PyObject *closure; +#if PY_MAJOR_VERSION >= 3 + PyObject *kwdefs; +#endif + PyObject *kwtuple, **k; + PyObject **d; + Py_ssize_t nd; + Py_ssize_t nk; + PyObject *result; + assert(kwargs == NULL || PyDict_Check(kwargs)); + nk = kwargs ? PyDict_Size(kwargs) : 0; + #if PY_MAJOR_VERSION < 3 + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) { + return NULL; + } + #else + if (unlikely(Py_EnterRecursiveCall(" while calling a Python object"))) { + return NULL; + } + #endif + if ( +#if PY_MAJOR_VERSION >= 3 + co->co_kwonlyargcount == 0 && +#endif + likely(kwargs == NULL || nk == 0) && + co->co_flags == (CO_OPTIMIZED | CO_NEWLOCALS | CO_NOFREE)) { + if (argdefs == NULL && co->co_argcount == nargs) { + result = __Pyx_PyFunction_FastCallNoKw(co, args, nargs, globals); + goto done; + } + else if (nargs == 0 && argdefs != NULL + && co->co_argcount == Py_SIZE(argdefs)) { + /* function called with no arguments, but all parameters have + a default value: use default values as arguments .*/ + args = &PyTuple_GET_ITEM(argdefs, 0); + result =__Pyx_PyFunction_FastCallNoKw(co, args, Py_SIZE(argdefs), globals); + goto done; + } + } + if (kwargs != NULL) { + Py_ssize_t pos, i; + kwtuple = PyTuple_New(2 * nk); + if (kwtuple == NULL) { + result = NULL; + goto done; + } + k = &PyTuple_GET_ITEM(kwtuple, 0); + pos = i = 0; + while (PyDict_Next(kwargs, &pos, &k[i], &k[i+1])) { + Py_INCREF(k[i]); + Py_INCREF(k[i+1]); + i += 2; + } + nk = i / 2; + } + else { + kwtuple = NULL; + k = NULL; + } + closure = PyFunction_GET_CLOSURE(func); +#if PY_MAJOR_VERSION >= 3 + kwdefs = PyFunction_GET_KW_DEFAULTS(func); +#endif + if (argdefs != NULL) { + d = &PyTuple_GET_ITEM(argdefs, 0); + nd = Py_SIZE(argdefs); + } + else { + d = NULL; + nd = 0; + } +#if PY_MAJOR_VERSION >= 3 + result = PyEval_EvalCodeEx((PyObject*)co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, kwdefs, closure); +#else + result = PyEval_EvalCodeEx(co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, closure); +#endif + Py_XDECREF(kwtuple); +done: + Py_LeaveRecursiveCall(); + return result; +} +#endif + +/* PyObjectCall */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw) { + PyObject *result; + ternaryfunc call = Py_TYPE(func)->tp_call; + if (unlikely(!call)) + return PyObject_Call(func, arg, kw); + #if PY_MAJOR_VERSION < 3 + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + #else + if (unlikely(Py_EnterRecursiveCall(" while calling a Python object"))) + return NULL; + #endif + result = (*call)(func, arg, kw); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* PyObjectCallMethO */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg) { + PyObject *self, *result; + PyCFunction cfunc; + cfunc = __Pyx_CyOrPyCFunction_GET_FUNCTION(func); + self = __Pyx_CyOrPyCFunction_GET_SELF(func); + #if PY_MAJOR_VERSION < 3 + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + #else + if (unlikely(Py_EnterRecursiveCall(" while calling a Python object"))) + return NULL; + #endif + result = cfunc(self, arg); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* PyObjectFastCall */ +#if PY_VERSION_HEX < 0x03090000 || CYTHON_COMPILING_IN_LIMITED_API +static PyObject* __Pyx_PyObject_FastCall_fallback(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs) { + PyObject *argstuple; + PyObject *result = 0; + size_t i; + argstuple = PyTuple_New((Py_ssize_t)nargs); + if (unlikely(!argstuple)) return NULL; + for (i = 0; i < nargs; i++) { + Py_INCREF(args[i]); + if (__Pyx_PyTuple_SET_ITEM(argstuple, (Py_ssize_t)i, args[i]) < 0) goto bad; + } + result = __Pyx_PyObject_Call(func, argstuple, kwargs); + bad: + Py_DECREF(argstuple); + return result; +} +#endif +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t _nargs, PyObject *kwargs) { + Py_ssize_t nargs = __Pyx_PyVectorcall_NARGS(_nargs); +#if CYTHON_COMPILING_IN_CPYTHON + if (nargs == 0 && kwargs == NULL) { + if (__Pyx_CyOrPyCFunction_Check(func) && likely( __Pyx_CyOrPyCFunction_GET_FLAGS(func) & METH_NOARGS)) + return __Pyx_PyObject_CallMethO(func, NULL); + } + else if (nargs == 1 && kwargs == NULL) { + if (__Pyx_CyOrPyCFunction_Check(func) && likely( __Pyx_CyOrPyCFunction_GET_FLAGS(func) & METH_O)) + return __Pyx_PyObject_CallMethO(func, args[0]); + } +#endif + #if PY_VERSION_HEX < 0x030800B1 + #if CYTHON_FAST_PYCCALL + if (PyCFunction_Check(func)) { + if (kwargs) { + return _PyCFunction_FastCallDict(func, args, nargs, kwargs); + } else { + return _PyCFunction_FastCallKeywords(func, args, nargs, NULL); + } + } + #if PY_VERSION_HEX >= 0x030700A1 + if (!kwargs && __Pyx_IS_TYPE(func, &PyMethodDescr_Type)) { + return _PyMethodDescr_FastCallKeywords(func, args, nargs, NULL); + } + #endif + #endif + #if CYTHON_FAST_PYCALL + if (PyFunction_Check(func)) { + return __Pyx_PyFunction_FastCallDict(func, args, nargs, kwargs); + } + #endif + #endif + if (kwargs == NULL) { + #if CYTHON_VECTORCALL + #if PY_VERSION_HEX < 0x03090000 + vectorcallfunc f = _PyVectorcall_Function(func); + #else + vectorcallfunc f = PyVectorcall_Function(func); + #endif + if (f) { + return f(func, args, (size_t)nargs, NULL); + } + #elif defined(__Pyx_CyFunction_USED) && CYTHON_BACKPORT_VECTORCALL + if (__Pyx_CyFunction_CheckExact(func)) { + __pyx_vectorcallfunc f = __Pyx_CyFunction_func_vectorcall(func); + if (f) return f(func, args, (size_t)nargs, NULL); + } + #endif + } + if (nargs == 0) { + return __Pyx_PyObject_Call(func, __pyx_empty_tuple, kwargs); + } + #if PY_VERSION_HEX >= 0x03090000 && !CYTHON_COMPILING_IN_LIMITED_API + return PyObject_VectorcallDict(func, args, (size_t)nargs, kwargs); + #else + return __Pyx_PyObject_FastCall_fallback(func, args, (size_t)nargs, kwargs); + #endif +} + +/* RaiseUnexpectedTypeError */ +static int +__Pyx_RaiseUnexpectedTypeError(const char *expected, PyObject *obj) +{ + __Pyx_TypeName obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, "Expected %s, got " __Pyx_FMT_TYPENAME, + expected, obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return 0; +} + +/* CIntToDigits */ +static const char DIGIT_PAIRS_10[2*10*10+1] = { + "00010203040506070809" + "10111213141516171819" + "20212223242526272829" + "30313233343536373839" + "40414243444546474849" + "50515253545556575859" + "60616263646566676869" + "70717273747576777879" + "80818283848586878889" + "90919293949596979899" +}; +static const char DIGIT_PAIRS_8[2*8*8+1] = { + "0001020304050607" + "1011121314151617" + "2021222324252627" + "3031323334353637" + "4041424344454647" + "5051525354555657" + "6061626364656667" + "7071727374757677" +}; +static const char DIGITS_HEX[2*16+1] = { + "0123456789abcdef" + "0123456789ABCDEF" +}; + +/* BuildPyUnicode */ +static PyObject* __Pyx_PyUnicode_BuildFromAscii(Py_ssize_t ulength, char* chars, int clength, + int prepend_sign, char padding_char) { + PyObject *uval; + Py_ssize_t uoffset = ulength - clength; +#if CYTHON_USE_UNICODE_INTERNALS + Py_ssize_t i; +#if CYTHON_PEP393_ENABLED + void *udata; + uval = PyUnicode_New(ulength, 127); + if (unlikely(!uval)) return NULL; + udata = PyUnicode_DATA(uval); +#else + Py_UNICODE *udata; + uval = PyUnicode_FromUnicode(NULL, ulength); + if (unlikely(!uval)) return NULL; + udata = PyUnicode_AS_UNICODE(uval); +#endif + if (uoffset > 0) { + i = 0; + if (prepend_sign) { + __Pyx_PyUnicode_WRITE(PyUnicode_1BYTE_KIND, udata, 0, '-'); + i++; + } + for (; i < uoffset; i++) { + __Pyx_PyUnicode_WRITE(PyUnicode_1BYTE_KIND, udata, i, padding_char); + } + } + for (i=0; i < clength; i++) { + __Pyx_PyUnicode_WRITE(PyUnicode_1BYTE_KIND, udata, uoffset+i, chars[i]); + } +#else + { + PyObject *sign = NULL, *padding = NULL; + uval = NULL; + if (uoffset > 0) { + prepend_sign = !!prepend_sign; + if (uoffset > prepend_sign) { + padding = PyUnicode_FromOrdinal(padding_char); + if (likely(padding) && uoffset > prepend_sign + 1) { + PyObject *tmp; + PyObject *repeat = PyInt_FromSsize_t(uoffset - prepend_sign); + if (unlikely(!repeat)) goto done_or_error; + tmp = PyNumber_Multiply(padding, repeat); + Py_DECREF(repeat); + Py_DECREF(padding); + padding = tmp; + } + if (unlikely(!padding)) goto done_or_error; + } + if (prepend_sign) { + sign = PyUnicode_FromOrdinal('-'); + if (unlikely(!sign)) goto done_or_error; + } + } + uval = PyUnicode_DecodeASCII(chars, clength, NULL); + if (likely(uval) && padding) { + PyObject *tmp = PyNumber_Add(padding, uval); + Py_DECREF(uval); + uval = tmp; + } + if (likely(uval) && sign) { + PyObject *tmp = PyNumber_Add(sign, uval); + Py_DECREF(uval); + uval = tmp; + } +done_or_error: + Py_XDECREF(padding); + Py_XDECREF(sign); + } +#endif + return uval; +} + +/* CIntToPyUnicode */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_int(int value, Py_ssize_t width, char padding_char, char format_char) { + char digits[sizeof(int)*3+2]; + char *dpos, *end = digits + sizeof(int)*3+2; + const char *hex_digits = DIGITS_HEX; + Py_ssize_t length, ulength; + int prepend_sign, last_one_off; + int remaining; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (format_char == 'X') { + hex_digits += 16; + format_char = 'x'; + } + remaining = value; + last_one_off = 0; + dpos = end; + do { + int digit_pos; + switch (format_char) { + case 'o': + digit_pos = abs((int)(remaining % (8*8))); + remaining = (int) (remaining / (8*8)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_8 + digit_pos * 2, 2); + last_one_off = (digit_pos < 8); + break; + case 'd': + digit_pos = abs((int)(remaining % (10*10))); + remaining = (int) (remaining / (10*10)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_10 + digit_pos * 2, 2); + last_one_off = (digit_pos < 10); + break; + case 'x': + *(--dpos) = hex_digits[abs((int)(remaining % 16))]; + remaining = (int) (remaining / 16); + break; + default: + assert(0); + break; + } + } while (unlikely(remaining != 0)); + assert(!last_one_off || *dpos == '0'); + dpos += last_one_off; + length = end - dpos; + ulength = length; + prepend_sign = 0; + if (!is_unsigned && value <= neg_one) { + if (padding_char == ' ' || width <= length + 1) { + *(--dpos) = '-'; + ++length; + } else { + prepend_sign = 1; + } + ++ulength; + } + if (width > ulength) { + ulength = width; + } + if (ulength == 1) { + return PyUnicode_FromOrdinal(*dpos); + } + return __Pyx_PyUnicode_BuildFromAscii(ulength, dpos, (int) length, prepend_sign, padding_char); +} + +/* CIntToPyUnicode */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_Py_ssize_t(Py_ssize_t value, Py_ssize_t width, char padding_char, char format_char) { + char digits[sizeof(Py_ssize_t)*3+2]; + char *dpos, *end = digits + sizeof(Py_ssize_t)*3+2; + const char *hex_digits = DIGITS_HEX; + Py_ssize_t length, ulength; + int prepend_sign, last_one_off; + Py_ssize_t remaining; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const Py_ssize_t neg_one = (Py_ssize_t) -1, const_zero = (Py_ssize_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (format_char == 'X') { + hex_digits += 16; + format_char = 'x'; + } + remaining = value; + last_one_off = 0; + dpos = end; + do { + int digit_pos; + switch (format_char) { + case 'o': + digit_pos = abs((int)(remaining % (8*8))); + remaining = (Py_ssize_t) (remaining / (8*8)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_8 + digit_pos * 2, 2); + last_one_off = (digit_pos < 8); + break; + case 'd': + digit_pos = abs((int)(remaining % (10*10))); + remaining = (Py_ssize_t) (remaining / (10*10)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_10 + digit_pos * 2, 2); + last_one_off = (digit_pos < 10); + break; + case 'x': + *(--dpos) = hex_digits[abs((int)(remaining % 16))]; + remaining = (Py_ssize_t) (remaining / 16); + break; + default: + assert(0); + break; + } + } while (unlikely(remaining != 0)); + assert(!last_one_off || *dpos == '0'); + dpos += last_one_off; + length = end - dpos; + ulength = length; + prepend_sign = 0; + if (!is_unsigned && value <= neg_one) { + if (padding_char == ' ' || width <= length + 1) { + *(--dpos) = '-'; + ++length; + } else { + prepend_sign = 1; + } + ++ulength; + } + if (width > ulength) { + ulength = width; + } + if (ulength == 1) { + return PyUnicode_FromOrdinal(*dpos); + } + return __Pyx_PyUnicode_BuildFromAscii(ulength, dpos, (int) length, prepend_sign, padding_char); +} + +/* JoinPyUnicode */ +static PyObject* __Pyx_PyUnicode_Join(PyObject* value_tuple, Py_ssize_t value_count, Py_ssize_t result_ulength, + Py_UCS4 max_char) { +#if CYTHON_USE_UNICODE_INTERNALS && CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + PyObject *result_uval; + int result_ukind, kind_shift; + Py_ssize_t i, char_pos; + void *result_udata; + CYTHON_MAYBE_UNUSED_VAR(max_char); +#if CYTHON_PEP393_ENABLED + result_uval = PyUnicode_New(result_ulength, max_char); + if (unlikely(!result_uval)) return NULL; + result_ukind = (max_char <= 255) ? PyUnicode_1BYTE_KIND : (max_char <= 65535) ? PyUnicode_2BYTE_KIND : PyUnicode_4BYTE_KIND; + kind_shift = (result_ukind == PyUnicode_4BYTE_KIND) ? 2 : result_ukind - 1; + result_udata = PyUnicode_DATA(result_uval); +#else + result_uval = PyUnicode_FromUnicode(NULL, result_ulength); + if (unlikely(!result_uval)) return NULL; + result_ukind = sizeof(Py_UNICODE); + kind_shift = (result_ukind == 4) ? 2 : result_ukind - 1; + result_udata = PyUnicode_AS_UNICODE(result_uval); +#endif + assert(kind_shift == 2 || kind_shift == 1 || kind_shift == 0); + char_pos = 0; + for (i=0; i < value_count; i++) { + int ukind; + Py_ssize_t ulength; + void *udata; + PyObject *uval = PyTuple_GET_ITEM(value_tuple, i); + if (unlikely(__Pyx_PyUnicode_READY(uval))) + goto bad; + ulength = __Pyx_PyUnicode_GET_LENGTH(uval); + if (unlikely(!ulength)) + continue; + if (unlikely((PY_SSIZE_T_MAX >> kind_shift) - ulength < char_pos)) + goto overflow; + ukind = __Pyx_PyUnicode_KIND(uval); + udata = __Pyx_PyUnicode_DATA(uval); + if (!CYTHON_PEP393_ENABLED || ukind == result_ukind) { + memcpy((char *)result_udata + (char_pos << kind_shift), udata, (size_t) (ulength << kind_shift)); + } else { + #if PY_VERSION_HEX >= 0x030d0000 + if (unlikely(PyUnicode_CopyCharacters(result_uval, char_pos, uval, 0, ulength) < 0)) goto bad; + #elif CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030300F0 || defined(_PyUnicode_FastCopyCharacters) + _PyUnicode_FastCopyCharacters(result_uval, char_pos, uval, 0, ulength); + #else + Py_ssize_t j; + for (j=0; j < ulength; j++) { + Py_UCS4 uchar = __Pyx_PyUnicode_READ(ukind, udata, j); + __Pyx_PyUnicode_WRITE(result_ukind, result_udata, char_pos+j, uchar); + } + #endif + } + char_pos += ulength; + } + return result_uval; +overflow: + PyErr_SetString(PyExc_OverflowError, "join() result is too long for a Python string"); +bad: + Py_DECREF(result_uval); + return NULL; +#else + CYTHON_UNUSED_VAR(max_char); + CYTHON_UNUSED_VAR(result_ulength); + CYTHON_UNUSED_VAR(value_count); + return PyUnicode_Join(__pyx_empty_unicode, value_tuple); +#endif +} + +/* GetAttr */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr(PyObject *o, PyObject *n) { +#if CYTHON_USE_TYPE_SLOTS +#if PY_MAJOR_VERSION >= 3 + if (likely(PyUnicode_Check(n))) +#else + if (likely(PyString_Check(n))) +#endif + return __Pyx_PyObject_GetAttrStr(o, n); +#endif + return PyObject_GetAttr(o, n); +} + +/* GetItemInt */ +static PyObject *__Pyx_GetItemInt_Generic(PyObject *o, PyObject* j) { + PyObject *r; + if (unlikely(!j)) return NULL; + r = PyObject_GetItem(o, j); + Py_DECREF(j); + return r; +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_List_Fast(PyObject *o, Py_ssize_t i, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + Py_ssize_t wrapped_i = i; + if (wraparound & unlikely(i < 0)) { + wrapped_i += PyList_GET_SIZE(o); + } + if ((!boundscheck) || likely(__Pyx_is_valid_index(wrapped_i, PyList_GET_SIZE(o)))) { + PyObject *r = PyList_GET_ITEM(o, wrapped_i); + Py_INCREF(r); + return r; + } + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +#else + return PySequence_GetItem(o, i); +#endif +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Tuple_Fast(PyObject *o, Py_ssize_t i, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + Py_ssize_t wrapped_i = i; + if (wraparound & unlikely(i < 0)) { + wrapped_i += PyTuple_GET_SIZE(o); + } + if ((!boundscheck) || likely(__Pyx_is_valid_index(wrapped_i, PyTuple_GET_SIZE(o)))) { + PyObject *r = PyTuple_GET_ITEM(o, wrapped_i); + Py_INCREF(r); + return r; + } + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +#else + return PySequence_GetItem(o, i); +#endif +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Fast(PyObject *o, Py_ssize_t i, int is_list, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS && CYTHON_USE_TYPE_SLOTS + if (is_list || PyList_CheckExact(o)) { + Py_ssize_t n = ((!wraparound) | likely(i >= 0)) ? i : i + PyList_GET_SIZE(o); + if ((!boundscheck) || (likely(__Pyx_is_valid_index(n, PyList_GET_SIZE(o))))) { + PyObject *r = PyList_GET_ITEM(o, n); + Py_INCREF(r); + return r; + } + } + else if (PyTuple_CheckExact(o)) { + Py_ssize_t n = ((!wraparound) | likely(i >= 0)) ? i : i + PyTuple_GET_SIZE(o); + if ((!boundscheck) || likely(__Pyx_is_valid_index(n, PyTuple_GET_SIZE(o)))) { + PyObject *r = PyTuple_GET_ITEM(o, n); + Py_INCREF(r); + return r; + } + } else { + PyMappingMethods *mm = Py_TYPE(o)->tp_as_mapping; + PySequenceMethods *sm = Py_TYPE(o)->tp_as_sequence; + if (mm && mm->mp_subscript) { + PyObject *r, *key = PyInt_FromSsize_t(i); + if (unlikely(!key)) return NULL; + r = mm->mp_subscript(o, key); + Py_DECREF(key); + return r; + } + if (likely(sm && sm->sq_item)) { + if (wraparound && unlikely(i < 0) && likely(sm->sq_length)) { + Py_ssize_t l = sm->sq_length(o); + if (likely(l >= 0)) { + i += l; + } else { + if (!PyErr_ExceptionMatches(PyExc_OverflowError)) + return NULL; + PyErr_Clear(); + } + } + return sm->sq_item(o, i); + } + } +#else + if (is_list || !PyMapping_Check(o)) { + return PySequence_GetItem(o, i); + } +#endif + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +} + +/* PyObjectCallOneArg */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg) { + PyObject *args[2] = {NULL, arg}; + return __Pyx_PyObject_FastCall(func, args+1, 1 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* ObjectGetItem */ +#if CYTHON_USE_TYPE_SLOTS +static PyObject *__Pyx_PyObject_GetIndex(PyObject *obj, PyObject *index) { + PyObject *runerr = NULL; + Py_ssize_t key_value; + key_value = __Pyx_PyIndex_AsSsize_t(index); + if (likely(key_value != -1 || !(runerr = PyErr_Occurred()))) { + return __Pyx_GetItemInt_Fast(obj, key_value, 0, 1, 1); + } + if (PyErr_GivenExceptionMatches(runerr, PyExc_OverflowError)) { + __Pyx_TypeName index_type_name = __Pyx_PyType_GetName(Py_TYPE(index)); + PyErr_Clear(); + PyErr_Format(PyExc_IndexError, + "cannot fit '" __Pyx_FMT_TYPENAME "' into an index-sized integer", index_type_name); + __Pyx_DECREF_TypeName(index_type_name); + } + return NULL; +} +static PyObject *__Pyx_PyObject_GetItem_Slow(PyObject *obj, PyObject *key) { + __Pyx_TypeName obj_type_name; + if (likely(PyType_Check(obj))) { + PyObject *meth = __Pyx_PyObject_GetAttrStrNoError(obj, __pyx_n_s_class_getitem); + if (!meth) { + PyErr_Clear(); + } else { + PyObject *result = __Pyx_PyObject_CallOneArg(meth, key); + Py_DECREF(meth); + return result; + } + } + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "'" __Pyx_FMT_TYPENAME "' object is not subscriptable", obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return NULL; +} +static PyObject *__Pyx_PyObject_GetItem(PyObject *obj, PyObject *key) { + PyTypeObject *tp = Py_TYPE(obj); + PyMappingMethods *mm = tp->tp_as_mapping; + PySequenceMethods *sm = tp->tp_as_sequence; + if (likely(mm && mm->mp_subscript)) { + return mm->mp_subscript(obj, key); + } + if (likely(sm && sm->sq_item)) { + return __Pyx_PyObject_GetIndex(obj, key); + } + return __Pyx_PyObject_GetItem_Slow(obj, key); +} +#endif + +/* KeywordStringCheck */ +static int __Pyx_CheckKeywordStrings( + PyObject *kw, + const char* function_name, + int kw_allowed) +{ + PyObject* key = 0; + Py_ssize_t pos = 0; +#if CYTHON_COMPILING_IN_PYPY + if (!kw_allowed && PyDict_Next(kw, &pos, &key, 0)) + goto invalid_keyword; + return 1; +#else + if (CYTHON_METH_FASTCALL && likely(PyTuple_Check(kw))) { + Py_ssize_t kwsize; +#if CYTHON_ASSUME_SAFE_MACROS + kwsize = PyTuple_GET_SIZE(kw); +#else + kwsize = PyTuple_Size(kw); + if (kwsize < 0) return 0; +#endif + if (unlikely(kwsize == 0)) + return 1; + if (!kw_allowed) { +#if CYTHON_ASSUME_SAFE_MACROS + key = PyTuple_GET_ITEM(kw, 0); +#else + key = PyTuple_GetItem(kw, pos); + if (!key) return 0; +#endif + goto invalid_keyword; + } +#if PY_VERSION_HEX < 0x03090000 + for (pos = 0; pos < kwsize; pos++) { +#if CYTHON_ASSUME_SAFE_MACROS + key = PyTuple_GET_ITEM(kw, pos); +#else + key = PyTuple_GetItem(kw, pos); + if (!key) return 0; +#endif + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } +#endif + return 1; + } + while (PyDict_Next(kw, &pos, &key, 0)) { + #if PY_MAJOR_VERSION < 3 + if (unlikely(!PyString_Check(key))) + #endif + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } + if (!kw_allowed && unlikely(key)) + goto invalid_keyword; + return 1; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + return 0; +#endif +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif + return 0; +} + +/* DivInt[Py_ssize_t] */ +static CYTHON_INLINE Py_ssize_t __Pyx_div_Py_ssize_t(Py_ssize_t a, Py_ssize_t b) { + Py_ssize_t q = a / b; + Py_ssize_t r = a - q*b; + q -= ((r != 0) & ((r ^ b) < 0)); + return q; +} + +/* GetAttr3 */ +#if __PYX_LIMITED_VERSION_HEX < 0x030d00A1 +static PyObject *__Pyx_GetAttr3Default(PyObject *d) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + if (unlikely(!__Pyx_PyErr_ExceptionMatches(PyExc_AttributeError))) + return NULL; + __Pyx_PyErr_Clear(); + Py_INCREF(d); + return d; +} +#endif +static CYTHON_INLINE PyObject *__Pyx_GetAttr3(PyObject *o, PyObject *n, PyObject *d) { + PyObject *r; +#if __PYX_LIMITED_VERSION_HEX >= 0x030d00A1 + int res = PyObject_GetOptionalAttr(o, n, &r); + return (res != 0) ? r : __Pyx_NewRef(d); +#else + #if CYTHON_USE_TYPE_SLOTS + if (likely(PyString_Check(n))) { + r = __Pyx_PyObject_GetAttrStrNoError(o, n); + if (unlikely(!r) && likely(!PyErr_Occurred())) { + r = __Pyx_NewRef(d); + } + return r; + } + #endif + r = PyObject_GetAttr(o, n); + return (likely(r)) ? r : __Pyx_GetAttr3Default(d); +#endif +} + +/* PyDictVersioning */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + return likely(dict) ? __PYX_GET_DICT_VERSION(dict) : 0; +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj) { + PyObject **dictptr = NULL; + Py_ssize_t offset = Py_TYPE(obj)->tp_dictoffset; + if (offset) { +#if CYTHON_COMPILING_IN_CPYTHON + dictptr = (likely(offset > 0)) ? (PyObject **) ((char *)obj + offset) : _PyObject_GetDictPtr(obj); +#else + dictptr = _PyObject_GetDictPtr(obj); +#endif + } + return (dictptr && *dictptr) ? __PYX_GET_DICT_VERSION(*dictptr) : 0; +} +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + if (unlikely(!dict) || unlikely(tp_dict_version != __PYX_GET_DICT_VERSION(dict))) + return 0; + return obj_dict_version == __Pyx_get_object_dict_version(obj); +} +#endif + +/* GetModuleGlobalName */ +#if CYTHON_USE_DICT_VERSIONS +static PyObject *__Pyx__GetModuleGlobalName(PyObject *name, PY_UINT64_T *dict_version, PyObject **dict_cached_value) +#else +static CYTHON_INLINE PyObject *__Pyx__GetModuleGlobalName(PyObject *name) +#endif +{ + PyObject *result; +#if !CYTHON_AVOID_BORROWED_REFS +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030500A1 && PY_VERSION_HEX < 0x030d0000 + result = _PyDict_GetItem_KnownHash(__pyx_d, name, ((PyASCIIObject *) name)->hash); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } else if (unlikely(PyErr_Occurred())) { + return NULL; + } +#elif CYTHON_COMPILING_IN_LIMITED_API + if (unlikely(!__pyx_m)) { + return NULL; + } + result = PyObject_GetAttr(__pyx_m, name); + if (likely(result)) { + return result; + } +#else + result = PyDict_GetItem(__pyx_d, name); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } +#endif +#else + result = PyObject_GetItem(__pyx_d, name); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } + PyErr_Clear(); +#endif + return __Pyx_GetBuiltinName(name); +} + +/* RaiseTooManyValuesToUnpack */ +static CYTHON_INLINE void __Pyx_RaiseTooManyValuesError(Py_ssize_t expected) { + PyErr_Format(PyExc_ValueError, + "too many values to unpack (expected %" CYTHON_FORMAT_SSIZE_T "d)", expected); +} + +/* RaiseNeedMoreValuesToUnpack */ +static CYTHON_INLINE void __Pyx_RaiseNeedMoreValuesError(Py_ssize_t index) { + PyErr_Format(PyExc_ValueError, + "need more than %" CYTHON_FORMAT_SSIZE_T "d value%.1s to unpack", + index, (index == 1) ? "" : "s"); +} + +/* RaiseNoneIterError */ +static CYTHON_INLINE void __Pyx_RaiseNoneNotIterableError(void) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not iterable"); +} + +/* ExtTypeTest */ +static CYTHON_INLINE int __Pyx_TypeTest(PyObject *obj, PyTypeObject *type) { + __Pyx_TypeName obj_type_name; + __Pyx_TypeName type_name; + if (unlikely(!type)) { + PyErr_SetString(PyExc_SystemError, "Missing type object"); + return 0; + } + if (likely(__Pyx_TypeCheck(obj, type))) + return 1; + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + type_name = __Pyx_PyType_GetName(type); + PyErr_Format(PyExc_TypeError, + "Cannot convert " __Pyx_FMT_TYPENAME " to " __Pyx_FMT_TYPENAME, + obj_type_name, type_name); + __Pyx_DECREF_TypeName(obj_type_name); + __Pyx_DECREF_TypeName(type_name); + return 0; +} + +/* GetTopmostException */ +#if CYTHON_USE_EXC_INFO_STACK && CYTHON_FAST_THREAD_STATE +static _PyErr_StackItem * +__Pyx_PyErr_GetTopmostException(PyThreadState *tstate) +{ + _PyErr_StackItem *exc_info = tstate->exc_info; + while ((exc_info->exc_value == NULL || exc_info->exc_value == Py_None) && + exc_info->previous_item != NULL) + { + exc_info = exc_info->previous_item; + } + return exc_info; +} +#endif + +/* SaveResetException */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx__ExceptionSave(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { + #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 + _PyErr_StackItem *exc_info = __Pyx_PyErr_GetTopmostException(tstate); + PyObject *exc_value = exc_info->exc_value; + if (exc_value == NULL || exc_value == Py_None) { + *value = NULL; + *type = NULL; + *tb = NULL; + } else { + *value = exc_value; + Py_INCREF(*value); + *type = (PyObject*) Py_TYPE(exc_value); + Py_INCREF(*type); + *tb = PyException_GetTraceback(exc_value); + } + #elif CYTHON_USE_EXC_INFO_STACK + _PyErr_StackItem *exc_info = __Pyx_PyErr_GetTopmostException(tstate); + *type = exc_info->exc_type; + *value = exc_info->exc_value; + *tb = exc_info->exc_traceback; + Py_XINCREF(*type); + Py_XINCREF(*value); + Py_XINCREF(*tb); + #else + *type = tstate->exc_type; + *value = tstate->exc_value; + *tb = tstate->exc_traceback; + Py_XINCREF(*type); + Py_XINCREF(*value); + Py_XINCREF(*tb); + #endif +} +static CYTHON_INLINE void __Pyx__ExceptionReset(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb) { + #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 + _PyErr_StackItem *exc_info = tstate->exc_info; + PyObject *tmp_value = exc_info->exc_value; + exc_info->exc_value = value; + Py_XDECREF(tmp_value); + Py_XDECREF(type); + Py_XDECREF(tb); + #else + PyObject *tmp_type, *tmp_value, *tmp_tb; + #if CYTHON_USE_EXC_INFO_STACK + _PyErr_StackItem *exc_info = tstate->exc_info; + tmp_type = exc_info->exc_type; + tmp_value = exc_info->exc_value; + tmp_tb = exc_info->exc_traceback; + exc_info->exc_type = type; + exc_info->exc_value = value; + exc_info->exc_traceback = tb; + #else + tmp_type = tstate->exc_type; + tmp_value = tstate->exc_value; + tmp_tb = tstate->exc_traceback; + tstate->exc_type = type; + tstate->exc_value = value; + tstate->exc_traceback = tb; + #endif + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); + #endif +} +#endif + +/* GetException */ +#if CYTHON_FAST_THREAD_STATE +static int __Pyx__GetException(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) +#else +static int __Pyx_GetException(PyObject **type, PyObject **value, PyObject **tb) +#endif +{ + PyObject *local_type = NULL, *local_value, *local_tb = NULL; +#if CYTHON_FAST_THREAD_STATE + PyObject *tmp_type, *tmp_value, *tmp_tb; + #if PY_VERSION_HEX >= 0x030C00A6 + local_value = tstate->current_exception; + tstate->current_exception = 0; + if (likely(local_value)) { + local_type = (PyObject*) Py_TYPE(local_value); + Py_INCREF(local_type); + local_tb = PyException_GetTraceback(local_value); + } + #else + local_type = tstate->curexc_type; + local_value = tstate->curexc_value; + local_tb = tstate->curexc_traceback; + tstate->curexc_type = 0; + tstate->curexc_value = 0; + tstate->curexc_traceback = 0; + #endif +#else + PyErr_Fetch(&local_type, &local_value, &local_tb); +#endif + PyErr_NormalizeException(&local_type, &local_value, &local_tb); +#if CYTHON_FAST_THREAD_STATE && PY_VERSION_HEX >= 0x030C00A6 + if (unlikely(tstate->current_exception)) +#elif CYTHON_FAST_THREAD_STATE + if (unlikely(tstate->curexc_type)) +#else + if (unlikely(PyErr_Occurred())) +#endif + goto bad; + #if PY_MAJOR_VERSION >= 3 + if (local_tb) { + if (unlikely(PyException_SetTraceback(local_value, local_tb) < 0)) + goto bad; + } + #endif + Py_XINCREF(local_tb); + Py_XINCREF(local_type); + Py_XINCREF(local_value); + *type = local_type; + *value = local_value; + *tb = local_tb; +#if CYTHON_FAST_THREAD_STATE + #if CYTHON_USE_EXC_INFO_STACK + { + _PyErr_StackItem *exc_info = tstate->exc_info; + #if PY_VERSION_HEX >= 0x030B00a4 + tmp_value = exc_info->exc_value; + exc_info->exc_value = local_value; + tmp_type = NULL; + tmp_tb = NULL; + Py_XDECREF(local_type); + Py_XDECREF(local_tb); + #else + tmp_type = exc_info->exc_type; + tmp_value = exc_info->exc_value; + tmp_tb = exc_info->exc_traceback; + exc_info->exc_type = local_type; + exc_info->exc_value = local_value; + exc_info->exc_traceback = local_tb; + #endif + } + #else + tmp_type = tstate->exc_type; + tmp_value = tstate->exc_value; + tmp_tb = tstate->exc_traceback; + tstate->exc_type = local_type; + tstate->exc_value = local_value; + tstate->exc_traceback = local_tb; + #endif + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); +#else + PyErr_SetExcInfo(local_type, local_value, local_tb); +#endif + return 0; +bad: + *type = 0; + *value = 0; + *tb = 0; + Py_XDECREF(local_type); + Py_XDECREF(local_value); + Py_XDECREF(local_tb); + return -1; +} + +/* SwapException */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx__ExceptionSwap(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { + PyObject *tmp_type, *tmp_value, *tmp_tb; + #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 + _PyErr_StackItem *exc_info = tstate->exc_info; + tmp_value = exc_info->exc_value; + exc_info->exc_value = *value; + if (tmp_value == NULL || tmp_value == Py_None) { + Py_XDECREF(tmp_value); + tmp_value = NULL; + tmp_type = NULL; + tmp_tb = NULL; + } else { + tmp_type = (PyObject*) Py_TYPE(tmp_value); + Py_INCREF(tmp_type); + #if CYTHON_COMPILING_IN_CPYTHON + tmp_tb = ((PyBaseExceptionObject*) tmp_value)->traceback; + Py_XINCREF(tmp_tb); + #else + tmp_tb = PyException_GetTraceback(tmp_value); + #endif + } + #elif CYTHON_USE_EXC_INFO_STACK + _PyErr_StackItem *exc_info = tstate->exc_info; + tmp_type = exc_info->exc_type; + tmp_value = exc_info->exc_value; + tmp_tb = exc_info->exc_traceback; + exc_info->exc_type = *type; + exc_info->exc_value = *value; + exc_info->exc_traceback = *tb; + #else + tmp_type = tstate->exc_type; + tmp_value = tstate->exc_value; + tmp_tb = tstate->exc_traceback; + tstate->exc_type = *type; + tstate->exc_value = *value; + tstate->exc_traceback = *tb; + #endif + *type = tmp_type; + *value = tmp_value; + *tb = tmp_tb; +} +#else +static CYTHON_INLINE void __Pyx_ExceptionSwap(PyObject **type, PyObject **value, PyObject **tb) { + PyObject *tmp_type, *tmp_value, *tmp_tb; + PyErr_GetExcInfo(&tmp_type, &tmp_value, &tmp_tb); + PyErr_SetExcInfo(*type, *value, *tb); + *type = tmp_type; + *value = tmp_value; + *tb = tmp_tb; +} +#endif + +/* Import */ +static PyObject *__Pyx_Import(PyObject *name, PyObject *from_list, int level) { + PyObject *module = 0; + PyObject *empty_dict = 0; + PyObject *empty_list = 0; + #if PY_MAJOR_VERSION < 3 + PyObject *py_import; + py_import = __Pyx_PyObject_GetAttrStr(__pyx_b, __pyx_n_s_import); + if (unlikely(!py_import)) + goto bad; + if (!from_list) { + empty_list = PyList_New(0); + if (unlikely(!empty_list)) + goto bad; + from_list = empty_list; + } + #endif + empty_dict = PyDict_New(); + if (unlikely(!empty_dict)) + goto bad; + { + #if PY_MAJOR_VERSION >= 3 + if (level == -1) { + if (strchr(__Pyx_MODULE_NAME, '.') != NULL) { + module = PyImport_ImportModuleLevelObject( + name, __pyx_d, empty_dict, from_list, 1); + if (unlikely(!module)) { + if (unlikely(!PyErr_ExceptionMatches(PyExc_ImportError))) + goto bad; + PyErr_Clear(); + } + } + level = 0; + } + #endif + if (!module) { + #if PY_MAJOR_VERSION < 3 + PyObject *py_level = PyInt_FromLong(level); + if (unlikely(!py_level)) + goto bad; + module = PyObject_CallFunctionObjArgs(py_import, + name, __pyx_d, empty_dict, from_list, py_level, (PyObject *)NULL); + Py_DECREF(py_level); + #else + module = PyImport_ImportModuleLevelObject( + name, __pyx_d, empty_dict, from_list, level); + #endif + } + } +bad: + Py_XDECREF(empty_dict); + Py_XDECREF(empty_list); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_import); + #endif + return module; +} + +/* ImportDottedModule */ +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx__ImportDottedModule_Error(PyObject *name, PyObject *parts_tuple, Py_ssize_t count) { + PyObject *partial_name = NULL, *slice = NULL, *sep = NULL; + if (unlikely(PyErr_Occurred())) { + PyErr_Clear(); + } + if (likely(PyTuple_GET_SIZE(parts_tuple) == count)) { + partial_name = name; + } else { + slice = PySequence_GetSlice(parts_tuple, 0, count); + if (unlikely(!slice)) + goto bad; + sep = PyUnicode_FromStringAndSize(".", 1); + if (unlikely(!sep)) + goto bad; + partial_name = PyUnicode_Join(sep, slice); + } + PyErr_Format( +#if PY_MAJOR_VERSION < 3 + PyExc_ImportError, + "No module named '%s'", PyString_AS_STRING(partial_name)); +#else +#if PY_VERSION_HEX >= 0x030600B1 + PyExc_ModuleNotFoundError, +#else + PyExc_ImportError, +#endif + "No module named '%U'", partial_name); +#endif +bad: + Py_XDECREF(sep); + Py_XDECREF(slice); + Py_XDECREF(partial_name); + return NULL; +} +#endif +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx__ImportDottedModule_Lookup(PyObject *name) { + PyObject *imported_module; +#if PY_VERSION_HEX < 0x030700A1 || (CYTHON_COMPILING_IN_PYPY && PYPY_VERSION_NUM < 0x07030400) + PyObject *modules = PyImport_GetModuleDict(); + if (unlikely(!modules)) + return NULL; + imported_module = __Pyx_PyDict_GetItemStr(modules, name); + Py_XINCREF(imported_module); +#else + imported_module = PyImport_GetModule(name); +#endif + return imported_module; +} +#endif +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_ImportDottedModule_WalkParts(PyObject *module, PyObject *name, PyObject *parts_tuple) { + Py_ssize_t i, nparts; + nparts = PyTuple_GET_SIZE(parts_tuple); + for (i=1; i < nparts && module; i++) { + PyObject *part, *submodule; +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + part = PyTuple_GET_ITEM(parts_tuple, i); +#else + part = PySequence_ITEM(parts_tuple, i); +#endif + submodule = __Pyx_PyObject_GetAttrStrNoError(module, part); +#if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(part); +#endif + Py_DECREF(module); + module = submodule; + } + if (unlikely(!module)) { + return __Pyx__ImportDottedModule_Error(name, parts_tuple, i); + } + return module; +} +#endif +static PyObject *__Pyx__ImportDottedModule(PyObject *name, PyObject *parts_tuple) { +#if PY_MAJOR_VERSION < 3 + PyObject *module, *from_list, *star = __pyx_n_s__3; + CYTHON_UNUSED_VAR(parts_tuple); + from_list = PyList_New(1); + if (unlikely(!from_list)) + return NULL; + Py_INCREF(star); + PyList_SET_ITEM(from_list, 0, star); + module = __Pyx_Import(name, from_list, 0); + Py_DECREF(from_list); + return module; +#else + PyObject *imported_module; + PyObject *module = __Pyx_Import(name, NULL, 0); + if (!parts_tuple || unlikely(!module)) + return module; + imported_module = __Pyx__ImportDottedModule_Lookup(name); + if (likely(imported_module)) { + Py_DECREF(module); + return imported_module; + } + PyErr_Clear(); + return __Pyx_ImportDottedModule_WalkParts(module, name, parts_tuple); +#endif +} +static PyObject *__Pyx_ImportDottedModule(PyObject *name, PyObject *parts_tuple) { +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030400B1 + PyObject *module = __Pyx__ImportDottedModule_Lookup(name); + if (likely(module)) { + PyObject *spec = __Pyx_PyObject_GetAttrStrNoError(module, __pyx_n_s_spec); + if (likely(spec)) { + PyObject *unsafe = __Pyx_PyObject_GetAttrStrNoError(spec, __pyx_n_s_initializing); + if (likely(!unsafe || !__Pyx_PyObject_IsTrue(unsafe))) { + Py_DECREF(spec); + spec = NULL; + } + Py_XDECREF(unsafe); + } + if (likely(!spec)) { + PyErr_Clear(); + return module; + } + Py_DECREF(spec); + Py_DECREF(module); + } else if (PyErr_Occurred()) { + PyErr_Clear(); + } +#endif + return __Pyx__ImportDottedModule(name, parts_tuple); +} + +/* FastTypeChecks */ +#if CYTHON_COMPILING_IN_CPYTHON +static int __Pyx_InBases(PyTypeObject *a, PyTypeObject *b) { + while (a) { + a = __Pyx_PyType_GetSlot(a, tp_base, PyTypeObject*); + if (a == b) + return 1; + } + return b == &PyBaseObject_Type; +} +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (a == b) return 1; + mro = a->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + if (PyTuple_GET_ITEM(mro, i) == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(a, b); +} +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (cls == a || cls == b) return 1; + mro = cls->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + PyObject *base = PyTuple_GET_ITEM(mro, i); + if (base == (PyObject *)a || base == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(cls, a) || __Pyx_InBases(cls, b); +} +#if PY_MAJOR_VERSION == 2 +static int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject* exc_type2) { + PyObject *exception, *value, *tb; + int res; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&exception, &value, &tb); + res = exc_type1 ? PyObject_IsSubclass(err, exc_type1) : 0; + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + if (!res) { + res = PyObject_IsSubclass(err, exc_type2); + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + } + __Pyx_ErrRestore(exception, value, tb); + return res; +} +#else +static CYTHON_INLINE int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject *exc_type2) { + if (exc_type1) { + return __Pyx_IsAnySubtype2((PyTypeObject*)err, (PyTypeObject*)exc_type1, (PyTypeObject*)exc_type2); + } else { + return __Pyx_IsSubtype((PyTypeObject*)err, (PyTypeObject*)exc_type2); + } +} +#endif +static int __Pyx_PyErr_GivenExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + assert(PyExceptionClass_Check(exc_type)); + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; itp_as_sequence && type->tp_as_sequence->sq_repeat)) { + return type->tp_as_sequence->sq_repeat(seq, mul); + } else +#endif + { + return __Pyx_PySequence_Multiply_Generic(seq, mul); + } +} + +/* SetItemInt */ +static int __Pyx_SetItemInt_Generic(PyObject *o, PyObject *j, PyObject *v) { + int r; + if (unlikely(!j)) return -1; + r = PyObject_SetItem(o, j, v); + Py_DECREF(j); + return r; +} +static CYTHON_INLINE int __Pyx_SetItemInt_Fast(PyObject *o, Py_ssize_t i, PyObject *v, int is_list, + CYTHON_NCP_UNUSED int wraparound, CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS && CYTHON_USE_TYPE_SLOTS + if (is_list || PyList_CheckExact(o)) { + Py_ssize_t n = (!wraparound) ? i : ((likely(i >= 0)) ? i : i + PyList_GET_SIZE(o)); + if ((!boundscheck) || likely(__Pyx_is_valid_index(n, PyList_GET_SIZE(o)))) { + PyObject* old = PyList_GET_ITEM(o, n); + Py_INCREF(v); + PyList_SET_ITEM(o, n, v); + Py_DECREF(old); + return 1; + } + } else { + PyMappingMethods *mm = Py_TYPE(o)->tp_as_mapping; + PySequenceMethods *sm = Py_TYPE(o)->tp_as_sequence; + if (mm && mm->mp_ass_subscript) { + int r; + PyObject *key = PyInt_FromSsize_t(i); + if (unlikely(!key)) return -1; + r = mm->mp_ass_subscript(o, key, v); + Py_DECREF(key); + return r; + } + if (likely(sm && sm->sq_ass_item)) { + if (wraparound && unlikely(i < 0) && likely(sm->sq_length)) { + Py_ssize_t l = sm->sq_length(o); + if (likely(l >= 0)) { + i += l; + } else { + if (!PyErr_ExceptionMatches(PyExc_OverflowError)) + return -1; + PyErr_Clear(); + } + } + return sm->sq_ass_item(o, i, v); + } + } +#else + if (is_list || !PyMapping_Check(o)) + { + return PySequence_SetItem(o, i, v); + } +#endif + return __Pyx_SetItemInt_Generic(o, PyInt_FromSsize_t(i), v); +} + +/* RaiseUnboundLocalError */ +static CYTHON_INLINE void __Pyx_RaiseUnboundLocalError(const char *varname) { + PyErr_Format(PyExc_UnboundLocalError, "local variable '%s' referenced before assignment", varname); +} + +/* DivInt[long] */ +static CYTHON_INLINE long __Pyx_div_long(long a, long b) { + long q = a / b; + long r = a - q*b; + q -= ((r != 0) & ((r ^ b) < 0)); + return q; +} + +/* ImportFrom */ +static PyObject* __Pyx_ImportFrom(PyObject* module, PyObject* name) { + PyObject* value = __Pyx_PyObject_GetAttrStr(module, name); + if (unlikely(!value) && PyErr_ExceptionMatches(PyExc_AttributeError)) { + const char* module_name_str = 0; + PyObject* module_name = 0; + PyObject* module_dot = 0; + PyObject* full_name = 0; + PyErr_Clear(); + module_name_str = PyModule_GetName(module); + if (unlikely(!module_name_str)) { goto modbad; } + module_name = PyUnicode_FromString(module_name_str); + if (unlikely(!module_name)) { goto modbad; } + module_dot = PyUnicode_Concat(module_name, __pyx_kp_u__2); + if (unlikely(!module_dot)) { goto modbad; } + full_name = PyUnicode_Concat(module_dot, name); + if (unlikely(!full_name)) { goto modbad; } + #if PY_VERSION_HEX < 0x030700A1 || (CYTHON_COMPILING_IN_PYPY && PYPY_VERSION_NUM < 0x07030400) + { + PyObject *modules = PyImport_GetModuleDict(); + if (unlikely(!modules)) + goto modbad; + value = PyObject_GetItem(modules, full_name); + } + #else + value = PyImport_GetModule(full_name); + #endif + modbad: + Py_XDECREF(full_name); + Py_XDECREF(module_dot); + Py_XDECREF(module_name); + } + if (unlikely(!value)) { + PyErr_Format(PyExc_ImportError, + #if PY_MAJOR_VERSION < 3 + "cannot import name %.230s", PyString_AS_STRING(name)); + #else + "cannot import name %S", name); + #endif + } + return value; +} + +/* HasAttr */ +#if __PYX_LIMITED_VERSION_HEX < 0x030d00A1 +static CYTHON_INLINE int __Pyx_HasAttr(PyObject *o, PyObject *n) { + PyObject *r; + if (unlikely(!__Pyx_PyBaseString_Check(n))) { + PyErr_SetString(PyExc_TypeError, + "hasattr(): attribute name must be string"); + return -1; + } + r = __Pyx_GetAttr(o, n); + if (!r) { + PyErr_Clear(); + return 0; + } else { + Py_DECREF(r); + return 1; + } +} +#endif + +/* BufferIndexError */ +static void __Pyx_RaiseBufferIndexError(int axis) { + PyErr_Format(PyExc_IndexError, + "Out of bounds on buffer access (axis %d)", axis); +} + +/* PyObject_GenericGetAttrNoDict */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject *__Pyx_RaiseGenericGetAttributeError(PyTypeObject *tp, PyObject *attr_name) { + __Pyx_TypeName type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, attr_name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(attr_name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name) { + PyObject *descr; + PyTypeObject *tp = Py_TYPE(obj); + if (unlikely(!PyString_Check(attr_name))) { + return PyObject_GenericGetAttr(obj, attr_name); + } + assert(!tp->tp_dictoffset); + descr = _PyType_Lookup(tp, attr_name); + if (unlikely(!descr)) { + return __Pyx_RaiseGenericGetAttributeError(tp, attr_name); + } + Py_INCREF(descr); + #if PY_MAJOR_VERSION < 3 + if (likely(PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_HAVE_CLASS))) + #endif + { + descrgetfunc f = Py_TYPE(descr)->tp_descr_get; + if (unlikely(f)) { + PyObject *res = f(descr, obj, (PyObject *)tp); + Py_DECREF(descr); + return res; + } + } + return descr; +} +#endif + +/* PyObject_GenericGetAttr */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name) { + if (unlikely(Py_TYPE(obj)->tp_dictoffset)) { + return PyObject_GenericGetAttr(obj, attr_name); + } + return __Pyx_PyObject_GenericGetAttrNoDict(obj, attr_name); +} +#endif + +/* FixUpExtensionType */ +#if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type) { +#if PY_VERSION_HEX > 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + CYTHON_UNUSED_VAR(spec); + CYTHON_UNUSED_VAR(type); +#else + const PyType_Slot *slot = spec->slots; + while (slot && slot->slot && slot->slot != Py_tp_members) + slot++; + if (slot && slot->slot == Py_tp_members) { + int changed = 0; +#if !(PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON) + const +#endif + PyMemberDef *memb = (PyMemberDef*) slot->pfunc; + while (memb && memb->name) { + if (memb->name[0] == '_' && memb->name[1] == '_') { +#if PY_VERSION_HEX < 0x030900b1 + if (strcmp(memb->name, "__weaklistoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_weaklistoffset = memb->offset; + changed = 1; + } + else if (strcmp(memb->name, "__dictoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_dictoffset = memb->offset; + changed = 1; + } +#if CYTHON_METH_FASTCALL + else if (strcmp(memb->name, "__vectorcalloffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); +#if PY_VERSION_HEX >= 0x030800b4 + type->tp_vectorcall_offset = memb->offset; +#else + type->tp_print = (printfunc) memb->offset; +#endif + changed = 1; + } +#endif +#else + if ((0)); +#endif +#if PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON + else if (strcmp(memb->name, "__module__") == 0) { + PyObject *descr; + assert(memb->type == T_OBJECT); + assert(memb->flags == 0 || memb->flags == READONLY); + descr = PyDescr_NewMember(type, memb); + if (unlikely(!descr)) + return -1; + if (unlikely(PyDict_SetItem(type->tp_dict, PyDescr_NAME(descr), descr) < 0)) { + Py_DECREF(descr); + return -1; + } + Py_DECREF(descr); + changed = 1; + } +#endif + } + memb++; + } + if (changed) + PyType_Modified(type); + } +#endif + return 0; +} +#endif + +/* PyObjectCallNoArg */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func) { + PyObject *arg[2] = {NULL, NULL}; + return __Pyx_PyObject_FastCall(func, arg + 1, 0 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* PyObjectGetMethod */ +static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method) { + PyObject *attr; +#if CYTHON_UNPACK_METHODS && CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_PYTYPE_LOOKUP + __Pyx_TypeName type_name; + PyTypeObject *tp = Py_TYPE(obj); + PyObject *descr; + descrgetfunc f = NULL; + PyObject **dictptr, *dict; + int meth_found = 0; + assert (*method == NULL); + if (unlikely(tp->tp_getattro != PyObject_GenericGetAttr)) { + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; + } + if (unlikely(tp->tp_dict == NULL) && unlikely(PyType_Ready(tp) < 0)) { + return 0; + } + descr = _PyType_Lookup(tp, name); + if (likely(descr != NULL)) { + Py_INCREF(descr); +#if defined(Py_TPFLAGS_METHOD_DESCRIPTOR) && Py_TPFLAGS_METHOD_DESCRIPTOR + if (__Pyx_PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_METHOD_DESCRIPTOR)) +#elif PY_MAJOR_VERSION >= 3 + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type))) + #endif +#else + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr))) + #endif +#endif + { + meth_found = 1; + } else { + f = Py_TYPE(descr)->tp_descr_get; + if (f != NULL && PyDescr_IsData(descr)) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + } + } + dictptr = _PyObject_GetDictPtr(obj); + if (dictptr != NULL && (dict = *dictptr) != NULL) { + Py_INCREF(dict); + attr = __Pyx_PyDict_GetItemStr(dict, name); + if (attr != NULL) { + Py_INCREF(attr); + Py_DECREF(dict); + Py_XDECREF(descr); + goto try_unpack; + } + Py_DECREF(dict); + } + if (meth_found) { + *method = descr; + return 1; + } + if (f != NULL) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + if (likely(descr != NULL)) { + *method = descr; + return 0; + } + type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return 0; +#else + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; +#endif +try_unpack: +#if CYTHON_UNPACK_METHODS + if (likely(attr) && PyMethod_Check(attr) && likely(PyMethod_GET_SELF(attr) == obj)) { + PyObject *function = PyMethod_GET_FUNCTION(attr); + Py_INCREF(function); + Py_DECREF(attr); + *method = function; + return 1; + } +#endif + *method = attr; + return 0; +} + +/* PyObjectCallMethod0 */ +static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name) { + PyObject *method = NULL, *result = NULL; + int is_method = __Pyx_PyObject_GetMethod(obj, method_name, &method); + if (likely(is_method)) { + result = __Pyx_PyObject_CallOneArg(method, obj); + Py_DECREF(method); + return result; + } + if (unlikely(!method)) goto bad; + result = __Pyx_PyObject_CallNoArg(method); + Py_DECREF(method); +bad: + return result; +} + +/* ValidateBasesTuple */ +#if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases) { + Py_ssize_t i, n; +#if CYTHON_ASSUME_SAFE_MACROS + n = PyTuple_GET_SIZE(bases); +#else + n = PyTuple_Size(bases); + if (n < 0) return -1; +#endif + for (i = 1; i < n; i++) + { +#if CYTHON_AVOID_BORROWED_REFS + PyObject *b0 = PySequence_GetItem(bases, i); + if (!b0) return -1; +#elif CYTHON_ASSUME_SAFE_MACROS + PyObject *b0 = PyTuple_GET_ITEM(bases, i); +#else + PyObject *b0 = PyTuple_GetItem(bases, i); + if (!b0) return -1; +#endif + PyTypeObject *b; +#if PY_MAJOR_VERSION < 3 + if (PyClass_Check(b0)) + { + PyErr_Format(PyExc_TypeError, "base class '%.200s' is an old-style class", + PyString_AS_STRING(((PyClassObject*)b0)->cl_name)); +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + return -1; + } +#endif + b = (PyTypeObject*) b0; + if (!__Pyx_PyType_HasFeature(b, Py_TPFLAGS_HEAPTYPE)) + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "base class '" __Pyx_FMT_TYPENAME "' is not a heap type", b_name); + __Pyx_DECREF_TypeName(b_name); +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + return -1; + } + if (dictoffset == 0) + { + Py_ssize_t b_dictoffset = 0; +#if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + b_dictoffset = b->tp_dictoffset; +#else + PyObject *py_b_dictoffset = PyObject_GetAttrString((PyObject*)b, "__dictoffset__"); + if (!py_b_dictoffset) goto dictoffset_return; + b_dictoffset = PyLong_AsSsize_t(py_b_dictoffset); + Py_DECREF(py_b_dictoffset); + if (b_dictoffset == -1 && PyErr_Occurred()) goto dictoffset_return; +#endif + if (b_dictoffset) { + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "extension type '%.200s' has no __dict__ slot, " + "but base type '" __Pyx_FMT_TYPENAME "' has: " + "either add 'cdef dict __dict__' to the extension type " + "or add '__slots__ = [...]' to the base type", + type_name, b_name); + __Pyx_DECREF_TypeName(b_name); + } +#if !(CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY) + dictoffset_return: +#endif +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + return -1; + } + } +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + } + return 0; +} +#endif + +/* PyType_Ready */ +static int __Pyx_PyType_Ready(PyTypeObject *t) { +#if CYTHON_USE_TYPE_SPECS || !(CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API) || defined(PYSTON_MAJOR_VERSION) + (void)__Pyx_PyObject_CallMethod0; +#if CYTHON_USE_TYPE_SPECS + (void)__Pyx_validate_bases_tuple; +#endif + return PyType_Ready(t); +#else + int r; + PyObject *bases = __Pyx_PyType_GetSlot(t, tp_bases, PyObject*); + if (bases && unlikely(__Pyx_validate_bases_tuple(t->tp_name, t->tp_dictoffset, bases) == -1)) + return -1; +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + { + int gc_was_enabled; + #if PY_VERSION_HEX >= 0x030A00b1 + gc_was_enabled = PyGC_Disable(); + (void)__Pyx_PyObject_CallMethod0; + #else + PyObject *ret, *py_status; + PyObject *gc = NULL; + #if PY_VERSION_HEX >= 0x030700a1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM+0 >= 0x07030400) + gc = PyImport_GetModule(__pyx_kp_u_gc); + #endif + if (unlikely(!gc)) gc = PyImport_Import(__pyx_kp_u_gc); + if (unlikely(!gc)) return -1; + py_status = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_isenabled); + if (unlikely(!py_status)) { + Py_DECREF(gc); + return -1; + } + gc_was_enabled = __Pyx_PyObject_IsTrue(py_status); + Py_DECREF(py_status); + if (gc_was_enabled > 0) { + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_disable); + if (unlikely(!ret)) { + Py_DECREF(gc); + return -1; + } + Py_DECREF(ret); + } else if (unlikely(gc_was_enabled == -1)) { + Py_DECREF(gc); + return -1; + } + #endif + t->tp_flags |= Py_TPFLAGS_HEAPTYPE; +#if PY_VERSION_HEX >= 0x030A0000 + t->tp_flags |= Py_TPFLAGS_IMMUTABLETYPE; +#endif +#else + (void)__Pyx_PyObject_CallMethod0; +#endif + r = PyType_Ready(t); +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + t->tp_flags &= ~Py_TPFLAGS_HEAPTYPE; + #if PY_VERSION_HEX >= 0x030A00b1 + if (gc_was_enabled) + PyGC_Enable(); + #else + if (gc_was_enabled) { + PyObject *tp, *v, *tb; + PyErr_Fetch(&tp, &v, &tb); + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_enable); + if (likely(ret || r == -1)) { + Py_XDECREF(ret); + PyErr_Restore(tp, v, tb); + } else { + Py_XDECREF(tp); + Py_XDECREF(v); + Py_XDECREF(tb); + r = -1; + } + } + Py_DECREF(gc); + #endif + } +#endif + return r; +#endif +} + +/* SetupReduce */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce_is_named(PyObject* meth, PyObject* name) { + int ret; + PyObject *name_attr; + name_attr = __Pyx_PyObject_GetAttrStrNoError(meth, __pyx_n_s_name_2); + if (likely(name_attr)) { + ret = PyObject_RichCompareBool(name_attr, name, Py_EQ); + } else { + ret = -1; + } + if (unlikely(ret < 0)) { + PyErr_Clear(); + ret = 0; + } + Py_XDECREF(name_attr); + return ret; +} +static int __Pyx_setup_reduce(PyObject* type_obj) { + int ret = 0; + PyObject *object_reduce = NULL; + PyObject *object_getstate = NULL; + PyObject *object_reduce_ex = NULL; + PyObject *reduce = NULL; + PyObject *reduce_ex = NULL; + PyObject *reduce_cython = NULL; + PyObject *setstate = NULL; + PyObject *setstate_cython = NULL; + PyObject *getstate = NULL; +#if CYTHON_USE_PYTYPE_LOOKUP + getstate = _PyType_Lookup((PyTypeObject*)type_obj, __pyx_n_s_getstate); +#else + getstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_getstate); + if (!getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (getstate) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_getstate = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_getstate); +#else + object_getstate = __Pyx_PyObject_GetAttrStrNoError((PyObject*)&PyBaseObject_Type, __pyx_n_s_getstate); + if (!object_getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (object_getstate != getstate) { + goto __PYX_GOOD; + } + } +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce_ex = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#else + object_reduce_ex = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#endif + reduce_ex = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce_ex); if (unlikely(!reduce_ex)) goto __PYX_BAD; + if (reduce_ex == object_reduce_ex) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#else + object_reduce = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#endif + reduce = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce); if (unlikely(!reduce)) goto __PYX_BAD; + if (reduce == object_reduce || __Pyx_setup_reduce_is_named(reduce, __pyx_n_s_reduce_cython)) { + reduce_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_reduce_cython); + if (likely(reduce_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce, reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (reduce == object_reduce || PyErr_Occurred()) { + goto __PYX_BAD; + } + setstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate); + if (!setstate) PyErr_Clear(); + if (!setstate || __Pyx_setup_reduce_is_named(setstate, __pyx_n_s_setstate_cython)) { + setstate_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate_cython); + if (likely(setstate_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate, setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (!setstate || PyErr_Occurred()) { + goto __PYX_BAD; + } + } + PyType_Modified((PyTypeObject*)type_obj); + } + } + goto __PYX_GOOD; +__PYX_BAD: + if (!PyErr_Occurred()) { + __Pyx_TypeName type_obj_name = + __Pyx_PyType_GetName((PyTypeObject*)type_obj); + PyErr_Format(PyExc_RuntimeError, + "Unable to initialize pickling for " __Pyx_FMT_TYPENAME, type_obj_name); + __Pyx_DECREF_TypeName(type_obj_name); + } + ret = -1; +__PYX_GOOD: +#if !CYTHON_USE_PYTYPE_LOOKUP + Py_XDECREF(object_reduce); + Py_XDECREF(object_reduce_ex); + Py_XDECREF(object_getstate); + Py_XDECREF(getstate); +#endif + Py_XDECREF(reduce); + Py_XDECREF(reduce_ex); + Py_XDECREF(reduce_cython); + Py_XDECREF(setstate); + Py_XDECREF(setstate_cython); + return ret; +} +#endif + +/* SetVTable */ +static int __Pyx_SetVtable(PyTypeObject *type, void *vtable) { + PyObject *ob = PyCapsule_New(vtable, 0, 0); + if (unlikely(!ob)) + goto bad; +#if CYTHON_COMPILING_IN_LIMITED_API + if (unlikely(PyObject_SetAttr((PyObject *) type, __pyx_n_s_pyx_vtable, ob) < 0)) +#else + if (unlikely(PyDict_SetItem(type->tp_dict, __pyx_n_s_pyx_vtable, ob) < 0)) +#endif + goto bad; + Py_DECREF(ob); + return 0; +bad: + Py_XDECREF(ob); + return -1; +} + +/* GetVTable */ +static void* __Pyx_GetVtable(PyTypeObject *type) { + void* ptr; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *ob = PyObject_GetAttr((PyObject *)type, __pyx_n_s_pyx_vtable); +#else + PyObject *ob = PyObject_GetItem(type->tp_dict, __pyx_n_s_pyx_vtable); +#endif + if (!ob) + goto bad; + ptr = PyCapsule_GetPointer(ob, 0); + if (!ptr && !PyErr_Occurred()) + PyErr_SetString(PyExc_RuntimeError, "invalid vtable found for imported type"); + Py_DECREF(ob); + return ptr; +bad: + Py_XDECREF(ob); + return NULL; +} + +/* MergeVTables */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_MergeVtables(PyTypeObject *type) { + int i; + void** base_vtables; + __Pyx_TypeName tp_base_name; + __Pyx_TypeName base_name; + void* unknown = (void*)-1; + PyObject* bases = type->tp_bases; + int base_depth = 0; + { + PyTypeObject* base = type->tp_base; + while (base) { + base_depth += 1; + base = base->tp_base; + } + } + base_vtables = (void**) malloc(sizeof(void*) * (size_t)(base_depth + 1)); + base_vtables[0] = unknown; + for (i = 1; i < PyTuple_GET_SIZE(bases); i++) { + void* base_vtable = __Pyx_GetVtable(((PyTypeObject*)PyTuple_GET_ITEM(bases, i))); + if (base_vtable != NULL) { + int j; + PyTypeObject* base = type->tp_base; + for (j = 0; j < base_depth; j++) { + if (base_vtables[j] == unknown) { + base_vtables[j] = __Pyx_GetVtable(base); + base_vtables[j + 1] = unknown; + } + if (base_vtables[j] == base_vtable) { + break; + } else if (base_vtables[j] == NULL) { + goto bad; + } + base = base->tp_base; + } + } + } + PyErr_Clear(); + free(base_vtables); + return 0; +bad: + tp_base_name = __Pyx_PyType_GetName(type->tp_base); + base_name = __Pyx_PyType_GetName((PyTypeObject*)PyTuple_GET_ITEM(bases, i)); + PyErr_Format(PyExc_TypeError, + "multiple bases have vtable conflict: '" __Pyx_FMT_TYPENAME "' and '" __Pyx_FMT_TYPENAME "'", tp_base_name, base_name); + __Pyx_DECREF_TypeName(tp_base_name); + __Pyx_DECREF_TypeName(base_name); + free(base_vtables); + return -1; +} +#endif + +/* TypeImport */ +#ifndef __PYX_HAVE_RT_ImportType_3_0_8 +#define __PYX_HAVE_RT_ImportType_3_0_8 +static PyTypeObject *__Pyx_ImportType_3_0_8(PyObject *module, const char *module_name, const char *class_name, + size_t size, size_t alignment, enum __Pyx_ImportType_CheckSize_3_0_8 check_size) +{ + PyObject *result = 0; + char warning[200]; + Py_ssize_t basicsize; + Py_ssize_t itemsize; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *py_basicsize; + PyObject *py_itemsize; +#endif + result = PyObject_GetAttrString(module, class_name); + if (!result) + goto bad; + if (!PyType_Check(result)) { + PyErr_Format(PyExc_TypeError, + "%.200s.%.200s is not a type object", + module_name, class_name); + goto bad; + } +#if !CYTHON_COMPILING_IN_LIMITED_API + basicsize = ((PyTypeObject *)result)->tp_basicsize; + itemsize = ((PyTypeObject *)result)->tp_itemsize; +#else + py_basicsize = PyObject_GetAttrString(result, "__basicsize__"); + if (!py_basicsize) + goto bad; + basicsize = PyLong_AsSsize_t(py_basicsize); + Py_DECREF(py_basicsize); + py_basicsize = 0; + if (basicsize == (Py_ssize_t)-1 && PyErr_Occurred()) + goto bad; + py_itemsize = PyObject_GetAttrString(result, "__itemsize__"); + if (!py_itemsize) + goto bad; + itemsize = PyLong_AsSsize_t(py_itemsize); + Py_DECREF(py_itemsize); + py_itemsize = 0; + if (itemsize == (Py_ssize_t)-1 && PyErr_Occurred()) + goto bad; +#endif + if (itemsize) { + if (size % alignment) { + alignment = size % alignment; + } + if (itemsize < (Py_ssize_t)alignment) + itemsize = (Py_ssize_t)alignment; + } + if ((size_t)(basicsize + itemsize) < size) { + PyErr_Format(PyExc_ValueError, + "%.200s.%.200s size changed, may indicate binary incompatibility. " + "Expected %zd from C header, got %zd from PyObject", + module_name, class_name, size, basicsize+itemsize); + goto bad; + } + if (check_size == __Pyx_ImportType_CheckSize_Error_3_0_8 && + ((size_t)basicsize > size || (size_t)(basicsize + itemsize) < size)) { + PyErr_Format(PyExc_ValueError, + "%.200s.%.200s size changed, may indicate binary incompatibility. " + "Expected %zd from C header, got %zd-%zd from PyObject", + module_name, class_name, size, basicsize, basicsize+itemsize); + goto bad; + } + else if (check_size == __Pyx_ImportType_CheckSize_Warn_3_0_8 && (size_t)basicsize > size) { + PyOS_snprintf(warning, sizeof(warning), + "%s.%s size changed, may indicate binary incompatibility. " + "Expected %zd from C header, got %zd from PyObject", + module_name, class_name, size, basicsize); + if (PyErr_WarnEx(NULL, warning, 0) < 0) goto bad; + } + return (PyTypeObject *)result; +bad: + Py_XDECREF(result); + return NULL; +} +#endif + +/* CalculateMetaclass */ +static PyObject *__Pyx_CalculateMetaclass(PyTypeObject *metaclass, PyObject *bases) { + Py_ssize_t i, nbases; +#if CYTHON_ASSUME_SAFE_MACROS + nbases = PyTuple_GET_SIZE(bases); +#else + nbases = PyTuple_Size(bases); + if (nbases < 0) return NULL; +#endif + for (i=0; i < nbases; i++) { + PyTypeObject *tmptype; +#if CYTHON_ASSUME_SAFE_MACROS + PyObject *tmp = PyTuple_GET_ITEM(bases, i); +#else + PyObject *tmp = PyTuple_GetItem(bases, i); + if (!tmp) return NULL; +#endif + tmptype = Py_TYPE(tmp); +#if PY_MAJOR_VERSION < 3 + if (tmptype == &PyClass_Type) + continue; +#endif + if (!metaclass) { + metaclass = tmptype; + continue; + } + if (PyType_IsSubtype(metaclass, tmptype)) + continue; + if (PyType_IsSubtype(tmptype, metaclass)) { + metaclass = tmptype; + continue; + } + PyErr_SetString(PyExc_TypeError, + "metaclass conflict: " + "the metaclass of a derived class " + "must be a (non-strict) subclass " + "of the metaclasses of all its bases"); + return NULL; + } + if (!metaclass) { +#if PY_MAJOR_VERSION < 3 + metaclass = &PyClass_Type; +#else + metaclass = &PyType_Type; +#endif + } + Py_INCREF((PyObject*) metaclass); + return (PyObject*) metaclass; +} + +/* PyObjectCall2Args */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call2Args(PyObject* function, PyObject* arg1, PyObject* arg2) { + PyObject *args[3] = {NULL, arg1, arg2}; + return __Pyx_PyObject_FastCall(function, args+1, 2 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* PyObjectLookupSpecial */ +#if CYTHON_USE_PYTYPE_LOOKUP && CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx__PyObject_LookupSpecial(PyObject* obj, PyObject* attr_name, int with_error) { + PyObject *res; + PyTypeObject *tp = Py_TYPE(obj); +#if PY_MAJOR_VERSION < 3 + if (unlikely(PyInstance_Check(obj))) + return with_error ? __Pyx_PyObject_GetAttrStr(obj, attr_name) : __Pyx_PyObject_GetAttrStrNoError(obj, attr_name); +#endif + res = _PyType_Lookup(tp, attr_name); + if (likely(res)) { + descrgetfunc f = Py_TYPE(res)->tp_descr_get; + if (!f) { + Py_INCREF(res); + } else { + res = f(res, obj, (PyObject *)tp); + } + } else if (with_error) { + PyErr_SetObject(PyExc_AttributeError, attr_name); + } + return res; +} +#endif + +/* Py3ClassCreate */ +static PyObject *__Pyx_Py3MetaclassPrepare(PyObject *metaclass, PyObject *bases, PyObject *name, + PyObject *qualname, PyObject *mkw, PyObject *modname, PyObject *doc) { + PyObject *ns; + if (metaclass) { + PyObject *prep = __Pyx_PyObject_GetAttrStrNoError(metaclass, __pyx_n_s_prepare); + if (prep) { + PyObject *pargs[3] = {NULL, name, bases}; + ns = __Pyx_PyObject_FastCallDict(prep, pargs+1, 2 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET, mkw); + Py_DECREF(prep); + } else { + if (unlikely(PyErr_Occurred())) + return NULL; + ns = PyDict_New(); + } + } else { + ns = PyDict_New(); + } + if (unlikely(!ns)) + return NULL; + if (unlikely(PyObject_SetItem(ns, __pyx_n_s_module, modname) < 0)) goto bad; +#if PY_VERSION_HEX >= 0x03030000 + if (unlikely(PyObject_SetItem(ns, __pyx_n_s_qualname, qualname) < 0)) goto bad; +#else + CYTHON_MAYBE_UNUSED_VAR(qualname); +#endif + if (unlikely(doc && PyObject_SetItem(ns, __pyx_n_s_doc, doc) < 0)) goto bad; + return ns; +bad: + Py_DECREF(ns); + return NULL; +} +#if PY_VERSION_HEX < 0x030600A4 && CYTHON_PEP487_INIT_SUBCLASS +static int __Pyx_SetNamesPEP487(PyObject *type_obj) { + PyTypeObject *type = (PyTypeObject*) type_obj; + PyObject *names_to_set, *key, *value, *set_name, *tmp; + Py_ssize_t i = 0; +#if CYTHON_USE_TYPE_SLOTS + names_to_set = PyDict_Copy(type->tp_dict); +#else + { + PyObject *d = PyObject_GetAttr(type_obj, __pyx_n_s_dict); + names_to_set = NULL; + if (likely(d)) { + PyObject *names_to_set = PyDict_New(); + int ret = likely(names_to_set) ? PyDict_Update(names_to_set, d) : -1; + Py_DECREF(d); + if (unlikely(ret < 0)) + Py_CLEAR(names_to_set); + } + } +#endif + if (unlikely(names_to_set == NULL)) + goto bad; + while (PyDict_Next(names_to_set, &i, &key, &value)) { + set_name = __Pyx_PyObject_LookupSpecialNoError(value, __pyx_n_s_set_name); + if (unlikely(set_name != NULL)) { + tmp = __Pyx_PyObject_Call2Args(set_name, type_obj, key); + Py_DECREF(set_name); + if (unlikely(tmp == NULL)) { + __Pyx_TypeName value_type_name = + __Pyx_PyType_GetName(Py_TYPE(value)); + __Pyx_TypeName type_name = __Pyx_PyType_GetName(type); + PyErr_Format(PyExc_RuntimeError, +#if PY_MAJOR_VERSION >= 3 + "Error calling __set_name__ on '" __Pyx_FMT_TYPENAME "' instance %R " "in '" __Pyx_FMT_TYPENAME "'", + value_type_name, key, type_name); +#else + "Error calling __set_name__ on '" __Pyx_FMT_TYPENAME "' instance %.100s in '" __Pyx_FMT_TYPENAME "'", + value_type_name, + PyString_Check(key) ? PyString_AS_STRING(key) : "?", + type_name); +#endif + goto bad; + } else { + Py_DECREF(tmp); + } + } + else if (unlikely(PyErr_Occurred())) { + goto bad; + } + } + Py_DECREF(names_to_set); + return 0; +bad: + Py_XDECREF(names_to_set); + return -1; +} +static PyObject *__Pyx_InitSubclassPEP487(PyObject *type_obj, PyObject *mkw) { +#if CYTHON_USE_TYPE_SLOTS && CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + PyTypeObject *type = (PyTypeObject*) type_obj; + PyObject *mro = type->tp_mro; + Py_ssize_t i, nbases; + if (unlikely(!mro)) goto done; + (void) &__Pyx_GetBuiltinName; + Py_INCREF(mro); + nbases = PyTuple_GET_SIZE(mro); + assert(PyTuple_GET_ITEM(mro, 0) == type_obj); + for (i = 1; i < nbases-1; i++) { + PyObject *base, *dict, *meth; + base = PyTuple_GET_ITEM(mro, i); + dict = ((PyTypeObject *)base)->tp_dict; + meth = __Pyx_PyDict_GetItemStrWithError(dict, __pyx_n_s_init_subclass); + if (unlikely(meth)) { + descrgetfunc f = Py_TYPE(meth)->tp_descr_get; + PyObject *res; + Py_INCREF(meth); + if (likely(f)) { + res = f(meth, NULL, type_obj); + Py_DECREF(meth); + if (unlikely(!res)) goto bad; + meth = res; + } + res = __Pyx_PyObject_FastCallDict(meth, NULL, 0, mkw); + Py_DECREF(meth); + if (unlikely(!res)) goto bad; + Py_DECREF(res); + goto done; + } else if (unlikely(PyErr_Occurred())) { + goto bad; + } + } +done: + Py_XDECREF(mro); + return type_obj; +bad: + Py_XDECREF(mro); + Py_DECREF(type_obj); + return NULL; +#else + PyObject *super_type, *super, *func, *res; +#if CYTHON_COMPILING_IN_PYPY && !defined(PySuper_Type) + super_type = __Pyx_GetBuiltinName(__pyx_n_s_super); +#else + super_type = (PyObject*) &PySuper_Type; + (void) &__Pyx_GetBuiltinName; +#endif + super = likely(super_type) ? __Pyx_PyObject_Call2Args(super_type, type_obj, type_obj) : NULL; +#if CYTHON_COMPILING_IN_PYPY && !defined(PySuper_Type) + Py_XDECREF(super_type); +#endif + if (unlikely(!super)) { + Py_CLEAR(type_obj); + goto done; + } + func = __Pyx_PyObject_GetAttrStrNoError(super, __pyx_n_s_init_subclass); + Py_DECREF(super); + if (likely(!func)) { + if (unlikely(PyErr_Occurred())) + Py_CLEAR(type_obj); + goto done; + } + res = __Pyx_PyObject_FastCallDict(func, NULL, 0, mkw); + Py_DECREF(func); + if (unlikely(!res)) + Py_CLEAR(type_obj); + Py_XDECREF(res); +done: + return type_obj; +#endif +} +#endif +static PyObject *__Pyx_Py3ClassCreate(PyObject *metaclass, PyObject *name, PyObject *bases, + PyObject *dict, PyObject *mkw, + int calculate_metaclass, int allow_py2_metaclass) { + PyObject *result; + PyObject *owned_metaclass = NULL; + PyObject *margs[4] = {NULL, name, bases, dict}; + if (allow_py2_metaclass) { + owned_metaclass = PyObject_GetItem(dict, __pyx_n_s_metaclass); + if (owned_metaclass) { + metaclass = owned_metaclass; + } else if (likely(PyErr_ExceptionMatches(PyExc_KeyError))) { + PyErr_Clear(); + } else { + return NULL; + } + } + if (calculate_metaclass && (!metaclass || PyType_Check(metaclass))) { + metaclass = __Pyx_CalculateMetaclass((PyTypeObject*) metaclass, bases); + Py_XDECREF(owned_metaclass); + if (unlikely(!metaclass)) + return NULL; + owned_metaclass = metaclass; + } + result = __Pyx_PyObject_FastCallDict(metaclass, margs+1, 3 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET, +#if PY_VERSION_HEX < 0x030600A4 + (metaclass == (PyObject*)&PyType_Type) ? NULL : mkw +#else + mkw +#endif + ); + Py_XDECREF(owned_metaclass); +#if PY_VERSION_HEX < 0x030600A4 && CYTHON_PEP487_INIT_SUBCLASS + if (likely(result) && likely(PyType_Check(result))) { + if (unlikely(__Pyx_SetNamesPEP487(result) < 0)) { + Py_CLEAR(result); + } else { + result = __Pyx_InitSubclassPEP487(result, mkw); + } + } +#else + (void) &__Pyx_GetBuiltinName; +#endif + return result; +} + +/* FetchSharedCythonModule */ +static PyObject *__Pyx_FetchSharedCythonABIModule(void) { + return __Pyx_PyImport_AddModuleRef((char*) __PYX_ABI_MODULE_NAME); +} + +/* FetchCommonType */ +static int __Pyx_VerifyCachedType(PyObject *cached_type, + const char *name, + Py_ssize_t basicsize, + Py_ssize_t expected_basicsize) { + if (!PyType_Check(cached_type)) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s is not a type object", name); + return -1; + } + if (basicsize != expected_basicsize) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s has the wrong size, try recompiling", + name); + return -1; + } + return 0; +} +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type) { + PyObject* abi_module; + const char* object_name; + PyTypeObject *cached_type = NULL; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + object_name = strrchr(type->tp_name, '.'); + object_name = object_name ? object_name+1 : type->tp_name; + cached_type = (PyTypeObject*) PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + if (__Pyx_VerifyCachedType( + (PyObject *)cached_type, + object_name, + cached_type->tp_basicsize, + type->tp_basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + if (PyType_Ready(type) < 0) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, (PyObject *)type) < 0) + goto bad; + Py_INCREF(type); + cached_type = type; +done: + Py_DECREF(abi_module); + return cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#else +static PyTypeObject *__Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases) { + PyObject *abi_module, *cached_type = NULL; + const char* object_name = strrchr(spec->name, '.'); + object_name = object_name ? object_name+1 : spec->name; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + cached_type = PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + Py_ssize_t basicsize; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *py_basicsize; + py_basicsize = PyObject_GetAttrString(cached_type, "__basicsize__"); + if (unlikely(!py_basicsize)) goto bad; + basicsize = PyLong_AsSsize_t(py_basicsize); + Py_DECREF(py_basicsize); + py_basicsize = 0; + if (unlikely(basicsize == (Py_ssize_t)-1) && PyErr_Occurred()) goto bad; +#else + basicsize = likely(PyType_Check(cached_type)) ? ((PyTypeObject*) cached_type)->tp_basicsize : -1; +#endif + if (__Pyx_VerifyCachedType( + cached_type, + object_name, + basicsize, + spec->basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + CYTHON_UNUSED_VAR(module); + cached_type = __Pyx_PyType_FromModuleAndSpec(abi_module, spec, bases); + if (unlikely(!cached_type)) goto bad; + if (unlikely(__Pyx_fix_up_extension_type_from_spec(spec, (PyTypeObject *) cached_type) < 0)) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, cached_type) < 0) goto bad; +done: + Py_DECREF(abi_module); + assert(cached_type == NULL || PyType_Check(cached_type)); + return (PyTypeObject *) cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#endif + +/* PyVectorcallFastCallDict */ +#if CYTHON_METH_FASTCALL +static PyObject *__Pyx_PyVectorcall_FastCallDict_kw(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + PyObject *res = NULL; + PyObject *kwnames; + PyObject **newargs; + PyObject **kwvalues; + Py_ssize_t i, pos; + size_t j; + PyObject *key, *value; + unsigned long keys_are_strings; + Py_ssize_t nkw = PyDict_GET_SIZE(kw); + newargs = (PyObject **)PyMem_Malloc((nargs + (size_t)nkw) * sizeof(args[0])); + if (unlikely(newargs == NULL)) { + PyErr_NoMemory(); + return NULL; + } + for (j = 0; j < nargs; j++) newargs[j] = args[j]; + kwnames = PyTuple_New(nkw); + if (unlikely(kwnames == NULL)) { + PyMem_Free(newargs); + return NULL; + } + kwvalues = newargs + nargs; + pos = i = 0; + keys_are_strings = Py_TPFLAGS_UNICODE_SUBCLASS; + while (PyDict_Next(kw, &pos, &key, &value)) { + keys_are_strings &= Py_TYPE(key)->tp_flags; + Py_INCREF(key); + Py_INCREF(value); + PyTuple_SET_ITEM(kwnames, i, key); + kwvalues[i] = value; + i++; + } + if (unlikely(!keys_are_strings)) { + PyErr_SetString(PyExc_TypeError, "keywords must be strings"); + goto cleanup; + } + res = vc(func, newargs, nargs, kwnames); +cleanup: + Py_DECREF(kwnames); + for (i = 0; i < nkw; i++) + Py_DECREF(kwvalues[i]); + PyMem_Free(newargs); + return res; +} +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + if (likely(kw == NULL) || PyDict_GET_SIZE(kw) == 0) { + return vc(func, args, nargs, NULL); + } + return __Pyx_PyVectorcall_FastCallDict_kw(func, vc, args, nargs, kw); +} +#endif + +/* CythonFunctionShared */ +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc) { + if (__Pyx_CyFunction_Check(func)) { + return PyCFunction_GetFunction(((__pyx_CyFunctionObject*)func)->func) == (PyCFunction) cfunc; + } else if (PyCFunction_Check(func)) { + return PyCFunction_GetFunction(func) == (PyCFunction) cfunc; + } + return 0; +} +#else +static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc) { + return __Pyx_CyOrPyCFunction_Check(func) && __Pyx_CyOrPyCFunction_GET_FUNCTION(func) == (PyCFunction) cfunc; +} +#endif +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj) { +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + __Pyx_Py_XDECREF_SET( + __Pyx_CyFunction_GetClassObj(f), + ((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#else + __Pyx_Py_XDECREF_SET( + ((PyCMethodObject *) (f))->mm_class, + (PyTypeObject*)((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#endif +} +static PyObject * +__Pyx_CyFunction_get_doc(__pyx_CyFunctionObject *op, void *closure) +{ + CYTHON_UNUSED_VAR(closure); + if (unlikely(op->func_doc == NULL)) { +#if CYTHON_COMPILING_IN_LIMITED_API + op->func_doc = PyObject_GetAttrString(op->func, "__doc__"); + if (unlikely(!op->func_doc)) return NULL; +#else + if (((PyCFunctionObject*)op)->m_ml->ml_doc) { +#if PY_MAJOR_VERSION >= 3 + op->func_doc = PyUnicode_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#else + op->func_doc = PyString_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#endif + if (unlikely(op->func_doc == NULL)) + return NULL; + } else { + Py_INCREF(Py_None); + return Py_None; + } +#endif + } + Py_INCREF(op->func_doc); + return op->func_doc; +} +static int +__Pyx_CyFunction_set_doc(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (value == NULL) { + value = Py_None; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_doc, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_name(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_name == NULL)) { +#if CYTHON_COMPILING_IN_LIMITED_API + op->func_name = PyObject_GetAttrString(op->func, "__name__"); +#elif PY_MAJOR_VERSION >= 3 + op->func_name = PyUnicode_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#else + op->func_name = PyString_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#endif + if (unlikely(op->func_name == NULL)) + return NULL; + } + Py_INCREF(op->func_name); + return op->func_name; +} +static int +__Pyx_CyFunction_set_name(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__name__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_name, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_qualname(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_qualname); + return op->func_qualname; +} +static int +__Pyx_CyFunction_set_qualname(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__qualname__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_qualname, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_dict(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_dict == NULL)) { + op->func_dict = PyDict_New(); + if (unlikely(op->func_dict == NULL)) + return NULL; + } + Py_INCREF(op->func_dict); + return op->func_dict; +} +static int +__Pyx_CyFunction_set_dict(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(value == NULL)) { + PyErr_SetString(PyExc_TypeError, + "function's dictionary may not be deleted"); + return -1; + } + if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "setting function's dictionary to a non-dict"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_dict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_globals(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_globals); + return op->func_globals; +} +static PyObject * +__Pyx_CyFunction_get_closure(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(op); + CYTHON_UNUSED_VAR(context); + Py_INCREF(Py_None); + return Py_None; +} +static PyObject * +__Pyx_CyFunction_get_code(__pyx_CyFunctionObject *op, void *context) +{ + PyObject* result = (op->func_code) ? op->func_code : Py_None; + CYTHON_UNUSED_VAR(context); + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_init_defaults(__pyx_CyFunctionObject *op) { + int result = 0; + PyObject *res = op->defaults_getter((PyObject *) op); + if (unlikely(!res)) + return -1; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + op->defaults_tuple = PyTuple_GET_ITEM(res, 0); + Py_INCREF(op->defaults_tuple); + op->defaults_kwdict = PyTuple_GET_ITEM(res, 1); + Py_INCREF(op->defaults_kwdict); + #else + op->defaults_tuple = __Pyx_PySequence_ITEM(res, 0); + if (unlikely(!op->defaults_tuple)) result = -1; + else { + op->defaults_kwdict = __Pyx_PySequence_ITEM(res, 1); + if (unlikely(!op->defaults_kwdict)) result = -1; + } + #endif + Py_DECREF(res); + return result; +} +static int +__Pyx_CyFunction_set_defaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyTuple_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__defaults__ must be set to a tuple object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__defaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_tuple, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_defaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_tuple; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_tuple; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_kwdefaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__kwdefaults__ must be set to a dict object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__kwdefaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_kwdict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_kwdefaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_kwdict; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_kwdict; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_annotations(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value || value == Py_None) { + value = NULL; + } else if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__annotations__ must be set to a dict object"); + return -1; + } + Py_XINCREF(value); + __Pyx_Py_XDECREF_SET(op->func_annotations, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_annotations(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->func_annotations; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + result = PyDict_New(); + if (unlikely(!result)) return NULL; + op->func_annotations = result; + } + Py_INCREF(result); + return result; +} +static PyObject * +__Pyx_CyFunction_get_is_coroutine(__pyx_CyFunctionObject *op, void *context) { + int is_coroutine; + CYTHON_UNUSED_VAR(context); + if (op->func_is_coroutine) { + return __Pyx_NewRef(op->func_is_coroutine); + } + is_coroutine = op->flags & __Pyx_CYFUNCTION_COROUTINE; +#if PY_VERSION_HEX >= 0x03050000 + if (is_coroutine) { + PyObject *module, *fromlist, *marker = __pyx_n_s_is_coroutine; + fromlist = PyList_New(1); + if (unlikely(!fromlist)) return NULL; + Py_INCREF(marker); +#if CYTHON_ASSUME_SAFE_MACROS + PyList_SET_ITEM(fromlist, 0, marker); +#else + if (unlikely(PyList_SetItem(fromlist, 0, marker) < 0)) { + Py_DECREF(marker); + Py_DECREF(fromlist); + return NULL; + } +#endif + module = PyImport_ImportModuleLevelObject(__pyx_n_s_asyncio_coroutines, NULL, NULL, fromlist, 0); + Py_DECREF(fromlist); + if (unlikely(!module)) goto ignore; + op->func_is_coroutine = __Pyx_PyObject_GetAttrStr(module, marker); + Py_DECREF(module); + if (likely(op->func_is_coroutine)) { + return __Pyx_NewRef(op->func_is_coroutine); + } +ignore: + PyErr_Clear(); + } +#endif + op->func_is_coroutine = __Pyx_PyBool_FromLong(is_coroutine); + return __Pyx_NewRef(op->func_is_coroutine); +} +#if CYTHON_COMPILING_IN_LIMITED_API +static PyObject * +__Pyx_CyFunction_get_module(__pyx_CyFunctionObject *op, void *context) { + CYTHON_UNUSED_VAR(context); + return PyObject_GetAttrString(op->func, "__module__"); +} +static int +__Pyx_CyFunction_set_module(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + return PyObject_SetAttrString(op->func, "__module__", value); +} +#endif +static PyGetSetDef __pyx_CyFunction_getsets[] = { + {(char *) "func_doc", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "__doc__", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "func_name", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__name__", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__qualname__", (getter)__Pyx_CyFunction_get_qualname, (setter)__Pyx_CyFunction_set_qualname, 0, 0}, + {(char *) "func_dict", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "__dict__", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "func_globals", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "__globals__", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "func_closure", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "__closure__", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "func_code", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "__code__", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "func_defaults", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__defaults__", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__kwdefaults__", (getter)__Pyx_CyFunction_get_kwdefaults, (setter)__Pyx_CyFunction_set_kwdefaults, 0, 0}, + {(char *) "__annotations__", (getter)__Pyx_CyFunction_get_annotations, (setter)__Pyx_CyFunction_set_annotations, 0, 0}, + {(char *) "_is_coroutine", (getter)__Pyx_CyFunction_get_is_coroutine, 0, 0, 0}, +#if CYTHON_COMPILING_IN_LIMITED_API + {"__module__", (getter)__Pyx_CyFunction_get_module, (setter)__Pyx_CyFunction_set_module, 0, 0}, +#endif + {0, 0, 0, 0, 0} +}; +static PyMemberDef __pyx_CyFunction_members[] = { +#if !CYTHON_COMPILING_IN_LIMITED_API + {(char *) "__module__", T_OBJECT, offsetof(PyCFunctionObject, m_module), 0, 0}, +#endif +#if CYTHON_USE_TYPE_SPECS + {(char *) "__dictoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_dict), READONLY, 0}, +#if CYTHON_METH_FASTCALL +#if CYTHON_BACKPORT_VECTORCALL + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_vectorcall), READONLY, 0}, +#else +#if !CYTHON_COMPILING_IN_LIMITED_API + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(PyCFunctionObject, vectorcall), READONLY, 0}, +#endif +#endif +#endif +#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_weakreflist), READONLY, 0}, +#else + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(PyCFunctionObject, m_weakreflist), READONLY, 0}, +#endif +#endif + {0, 0, 0, 0, 0} +}; +static PyObject * +__Pyx_CyFunction_reduce(__pyx_CyFunctionObject *m, PyObject *args) +{ + CYTHON_UNUSED_VAR(args); +#if PY_MAJOR_VERSION >= 3 + Py_INCREF(m->func_qualname); + return m->func_qualname; +#else + return PyString_FromString(((PyCFunctionObject*)m)->m_ml->ml_name); +#endif +} +static PyMethodDef __pyx_CyFunction_methods[] = { + {"__reduce__", (PyCFunction)__Pyx_CyFunction_reduce, METH_VARARGS, 0}, + {0, 0, 0, 0} +}; +#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API +#define __Pyx_CyFunction_weakreflist(cyfunc) ((cyfunc)->func_weakreflist) +#else +#define __Pyx_CyFunction_weakreflist(cyfunc) (((PyCFunctionObject*)cyfunc)->m_weakreflist) +#endif +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject *op, PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { +#if !CYTHON_COMPILING_IN_LIMITED_API + PyCFunctionObject *cf = (PyCFunctionObject*) op; +#endif + if (unlikely(op == NULL)) + return NULL; +#if CYTHON_COMPILING_IN_LIMITED_API + op->func = PyCFunction_NewEx(ml, (PyObject*)op, module); + if (unlikely(!op->func)) return NULL; +#endif + op->flags = flags; + __Pyx_CyFunction_weakreflist(op) = NULL; +#if !CYTHON_COMPILING_IN_LIMITED_API + cf->m_ml = ml; + cf->m_self = (PyObject *) op; +#endif + Py_XINCREF(closure); + op->func_closure = closure; +#if !CYTHON_COMPILING_IN_LIMITED_API + Py_XINCREF(module); + cf->m_module = module; +#endif + op->func_dict = NULL; + op->func_name = NULL; + Py_INCREF(qualname); + op->func_qualname = qualname; + op->func_doc = NULL; +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + op->func_classobj = NULL; +#else + ((PyCMethodObject*)op)->mm_class = NULL; +#endif + op->func_globals = globals; + Py_INCREF(op->func_globals); + Py_XINCREF(code); + op->func_code = code; + op->defaults_pyobjects = 0; + op->defaults_size = 0; + op->defaults = NULL; + op->defaults_tuple = NULL; + op->defaults_kwdict = NULL; + op->defaults_getter = NULL; + op->func_annotations = NULL; + op->func_is_coroutine = NULL; +#if CYTHON_METH_FASTCALL + switch (ml->ml_flags & (METH_VARARGS | METH_FASTCALL | METH_NOARGS | METH_O | METH_KEYWORDS | METH_METHOD)) { + case METH_NOARGS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_NOARGS; + break; + case METH_O: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_O; + break; + case METH_METHOD | METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD; + break; + case METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS; + break; + case METH_VARARGS | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = NULL; + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + Py_DECREF(op); + return NULL; + } +#endif + return (PyObject *) op; +} +static int +__Pyx_CyFunction_clear(__pyx_CyFunctionObject *m) +{ + Py_CLEAR(m->func_closure); +#if CYTHON_COMPILING_IN_LIMITED_API + Py_CLEAR(m->func); +#else + Py_CLEAR(((PyCFunctionObject*)m)->m_module); +#endif + Py_CLEAR(m->func_dict); + Py_CLEAR(m->func_name); + Py_CLEAR(m->func_qualname); + Py_CLEAR(m->func_doc); + Py_CLEAR(m->func_globals); + Py_CLEAR(m->func_code); +#if !CYTHON_COMPILING_IN_LIMITED_API +#if PY_VERSION_HEX < 0x030900B1 + Py_CLEAR(__Pyx_CyFunction_GetClassObj(m)); +#else + { + PyObject *cls = (PyObject*) ((PyCMethodObject *) (m))->mm_class; + ((PyCMethodObject *) (m))->mm_class = NULL; + Py_XDECREF(cls); + } +#endif +#endif + Py_CLEAR(m->defaults_tuple); + Py_CLEAR(m->defaults_kwdict); + Py_CLEAR(m->func_annotations); + Py_CLEAR(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_XDECREF(pydefaults[i]); + PyObject_Free(m->defaults); + m->defaults = NULL; + } + return 0; +} +static void __Pyx__CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + if (__Pyx_CyFunction_weakreflist(m) != NULL) + PyObject_ClearWeakRefs((PyObject *) m); + __Pyx_CyFunction_clear(m); + __Pyx_PyHeapTypeObject_GC_Del(m); +} +static void __Pyx_CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + PyObject_GC_UnTrack(m); + __Pyx__CyFunction_dealloc(m); +} +static int __Pyx_CyFunction_traverse(__pyx_CyFunctionObject *m, visitproc visit, void *arg) +{ + Py_VISIT(m->func_closure); +#if CYTHON_COMPILING_IN_LIMITED_API + Py_VISIT(m->func); +#else + Py_VISIT(((PyCFunctionObject*)m)->m_module); +#endif + Py_VISIT(m->func_dict); + Py_VISIT(m->func_name); + Py_VISIT(m->func_qualname); + Py_VISIT(m->func_doc); + Py_VISIT(m->func_globals); + Py_VISIT(m->func_code); +#if !CYTHON_COMPILING_IN_LIMITED_API + Py_VISIT(__Pyx_CyFunction_GetClassObj(m)); +#endif + Py_VISIT(m->defaults_tuple); + Py_VISIT(m->defaults_kwdict); + Py_VISIT(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_VISIT(pydefaults[i]); + } + return 0; +} +static PyObject* +__Pyx_CyFunction_repr(__pyx_CyFunctionObject *op) +{ +#if PY_MAJOR_VERSION >= 3 + return PyUnicode_FromFormat("", + op->func_qualname, (void *)op); +#else + return PyString_FromFormat("", + PyString_AsString(op->func_qualname), (void *)op); +#endif +} +static PyObject * __Pyx_CyFunction_CallMethod(PyObject *func, PyObject *self, PyObject *arg, PyObject *kw) { +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *f = ((__pyx_CyFunctionObject*)func)->func; + PyObject *py_name = NULL; + PyCFunction meth; + int flags; + meth = PyCFunction_GetFunction(f); + if (unlikely(!meth)) return NULL; + flags = PyCFunction_GetFlags(f); + if (unlikely(flags < 0)) return NULL; +#else + PyCFunctionObject* f = (PyCFunctionObject*)func; + PyCFunction meth = f->m_ml->ml_meth; + int flags = f->m_ml->ml_flags; +#endif + Py_ssize_t size; + switch (flags & (METH_VARARGS | METH_KEYWORDS | METH_NOARGS | METH_O)) { + case METH_VARARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) + return (*meth)(self, arg); + break; + case METH_VARARGS | METH_KEYWORDS: + return (*(PyCFunctionWithKeywords)(void*)meth)(self, arg, kw); + case METH_NOARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { +#if CYTHON_ASSUME_SAFE_MACROS + size = PyTuple_GET_SIZE(arg); +#else + size = PyTuple_Size(arg); + if (unlikely(size < 0)) return NULL; +#endif + if (likely(size == 0)) + return (*meth)(self, NULL); +#if CYTHON_COMPILING_IN_LIMITED_API + py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); + if (!py_name) return NULL; + PyErr_Format(PyExc_TypeError, + "%.200S() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + py_name, size); + Py_DECREF(py_name); +#else + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); +#endif + return NULL; + } + break; + case METH_O: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { +#if CYTHON_ASSUME_SAFE_MACROS + size = PyTuple_GET_SIZE(arg); +#else + size = PyTuple_Size(arg); + if (unlikely(size < 0)) return NULL; +#endif + if (likely(size == 1)) { + PyObject *result, *arg0; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + arg0 = PyTuple_GET_ITEM(arg, 0); + #else + arg0 = __Pyx_PySequence_ITEM(arg, 0); if (unlikely(!arg0)) return NULL; + #endif + result = (*meth)(self, arg0); + #if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(arg0); + #endif + return result; + } +#if CYTHON_COMPILING_IN_LIMITED_API + py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); + if (!py_name) return NULL; + PyErr_Format(PyExc_TypeError, + "%.200S() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + py_name, size); + Py_DECREF(py_name); +#else + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); +#endif + return NULL; + } + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + return NULL; + } +#if CYTHON_COMPILING_IN_LIMITED_API + py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); + if (!py_name) return NULL; + PyErr_Format(PyExc_TypeError, "%.200S() takes no keyword arguments", + py_name); + Py_DECREF(py_name); +#else + PyErr_Format(PyExc_TypeError, "%.200s() takes no keyword arguments", + f->m_ml->ml_name); +#endif + return NULL; +} +static CYTHON_INLINE PyObject *__Pyx_CyFunction_Call(PyObject *func, PyObject *arg, PyObject *kw) { + PyObject *self, *result; +#if CYTHON_COMPILING_IN_LIMITED_API + self = PyCFunction_GetSelf(((__pyx_CyFunctionObject*)func)->func); + if (unlikely(!self) && PyErr_Occurred()) return NULL; +#else + self = ((PyCFunctionObject*)func)->m_self; +#endif + result = __Pyx_CyFunction_CallMethod(func, self, arg, kw); + return result; +} +static PyObject *__Pyx_CyFunction_CallAsMethod(PyObject *func, PyObject *args, PyObject *kw) { + PyObject *result; + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *) func; +#if CYTHON_METH_FASTCALL + __pyx_vectorcallfunc vc = __Pyx_CyFunction_func_vectorcall(cyfunc); + if (vc) { +#if CYTHON_ASSUME_SAFE_MACROS + return __Pyx_PyVectorcall_FastCallDict(func, vc, &PyTuple_GET_ITEM(args, 0), (size_t)PyTuple_GET_SIZE(args), kw); +#else + (void) &__Pyx_PyVectorcall_FastCallDict; + return PyVectorcall_Call(func, args, kw); +#endif + } +#endif + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + Py_ssize_t argc; + PyObject *new_args; + PyObject *self; +#if CYTHON_ASSUME_SAFE_MACROS + argc = PyTuple_GET_SIZE(args); +#else + argc = PyTuple_Size(args); + if (unlikely(!argc) < 0) return NULL; +#endif + new_args = PyTuple_GetSlice(args, 1, argc); + if (unlikely(!new_args)) + return NULL; + self = PyTuple_GetItem(args, 0); + if (unlikely(!self)) { + Py_DECREF(new_args); +#if PY_MAJOR_VERSION > 2 + PyErr_Format(PyExc_TypeError, + "unbound method %.200S() needs an argument", + cyfunc->func_qualname); +#else + PyErr_SetString(PyExc_TypeError, + "unbound method needs an argument"); +#endif + return NULL; + } + result = __Pyx_CyFunction_CallMethod(func, self, new_args, kw); + Py_DECREF(new_args); + } else { + result = __Pyx_CyFunction_Call(func, args, kw); + } + return result; +} +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE int __Pyx_CyFunction_Vectorcall_CheckArgs(__pyx_CyFunctionObject *cyfunc, Py_ssize_t nargs, PyObject *kwnames) +{ + int ret = 0; + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + if (unlikely(nargs < 1)) { + PyErr_Format(PyExc_TypeError, "%.200s() needs an argument", + ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + ret = 1; + } + if (unlikely(kwnames) && unlikely(PyTuple_GET_SIZE(kwnames))) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no keyword arguments", ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + return ret; +} +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 0)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, NULL); +} +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 1)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, args[0]); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((_PyCFunctionFastWithKeywords)(void(*)(void))def->ml_meth)(self, args, nargs, kwnames); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; + PyTypeObject *cls = (PyTypeObject *) __Pyx_CyFunction_GetClassObj(cyfunc); +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((__Pyx_PyCMethod)(void(*)(void))def->ml_meth)(self, cls, args, (size_t)nargs, kwnames); +} +#endif +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_CyFunctionType_slots[] = { + {Py_tp_dealloc, (void *)__Pyx_CyFunction_dealloc}, + {Py_tp_repr, (void *)__Pyx_CyFunction_repr}, + {Py_tp_call, (void *)__Pyx_CyFunction_CallAsMethod}, + {Py_tp_traverse, (void *)__Pyx_CyFunction_traverse}, + {Py_tp_clear, (void *)__Pyx_CyFunction_clear}, + {Py_tp_methods, (void *)__pyx_CyFunction_methods}, + {Py_tp_members, (void *)__pyx_CyFunction_members}, + {Py_tp_getset, (void *)__pyx_CyFunction_getsets}, + {Py_tp_descr_get, (void *)__Pyx_PyMethod_New}, + {0, 0}, +}; +static PyType_Spec __pyx_CyFunctionType_spec = { + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#if (defined(_Py_TPFLAGS_HAVE_VECTORCALL) && CYTHON_METH_FASTCALL) + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + __pyx_CyFunctionType_slots +}; +#else +static PyTypeObject __pyx_CyFunctionType_type = { + PyVarObject_HEAD_INIT(0, 0) + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, + (destructor) __Pyx_CyFunction_dealloc, +#if !CYTHON_METH_FASTCALL + 0, +#elif CYTHON_BACKPORT_VECTORCALL + (printfunc)offsetof(__pyx_CyFunctionObject, func_vectorcall), +#else + offsetof(PyCFunctionObject, vectorcall), +#endif + 0, + 0, +#if PY_MAJOR_VERSION < 3 + 0, +#else + 0, +#endif + (reprfunc) __Pyx_CyFunction_repr, + 0, + 0, + 0, + 0, + __Pyx_CyFunction_CallAsMethod, + 0, + 0, + 0, + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#if defined(_Py_TPFLAGS_HAVE_VECTORCALL) && CYTHON_METH_FASTCALL + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + 0, + (traverseproc) __Pyx_CyFunction_traverse, + (inquiry) __Pyx_CyFunction_clear, + 0, +#if PY_VERSION_HEX < 0x030500A0 + offsetof(__pyx_CyFunctionObject, func_weakreflist), +#else + offsetof(PyCFunctionObject, m_weakreflist), +#endif + 0, + 0, + __pyx_CyFunction_methods, + __pyx_CyFunction_members, + __pyx_CyFunction_getsets, + 0, + 0, + __Pyx_PyMethod_New, + 0, + offsetof(__pyx_CyFunctionObject, func_dict), + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, +#if PY_VERSION_HEX >= 0x030400a1 + 0, +#endif +#if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, +#endif +#if __PYX_NEED_TP_PRINT_SLOT + 0, +#endif +#if PY_VERSION_HEX >= 0x030C0000 + 0, +#endif +#if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, +#endif +}; +#endif +static int __pyx_CyFunction_init(PyObject *module) { +#if CYTHON_USE_TYPE_SPECS + __pyx_CyFunctionType = __Pyx_FetchCommonTypeFromSpec(module, &__pyx_CyFunctionType_spec, NULL); +#else + CYTHON_UNUSED_VAR(module); + __pyx_CyFunctionType = __Pyx_FetchCommonType(&__pyx_CyFunctionType_type); +#endif + if (unlikely(__pyx_CyFunctionType == NULL)) { + return -1; + } + return 0; +} +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *func, size_t size, int pyobjects) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults = PyObject_Malloc(size); + if (unlikely(!m->defaults)) + return PyErr_NoMemory(); + memset(m->defaults, 0, size); + m->defaults_pyobjects = pyobjects; + m->defaults_size = size; + return m->defaults; +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *func, PyObject *tuple) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_tuple = tuple; + Py_INCREF(tuple); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_kwdict = dict; + Py_INCREF(dict); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->func_annotations = dict; + Py_INCREF(dict); +} + +/* CythonFunction */ +static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { + PyObject *op = __Pyx_CyFunction_Init( + PyObject_GC_New(__pyx_CyFunctionObject, __pyx_CyFunctionType), + ml, flags, qualname, closure, module, globals, code + ); + if (likely(op)) { + PyObject_GC_Track(op); + } + return op; +} + +/* CLineInTraceback */ +#ifndef CYTHON_CLINE_IN_TRACEBACK +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line) { + PyObject *use_cline; + PyObject *ptype, *pvalue, *ptraceback; +#if CYTHON_COMPILING_IN_CPYTHON + PyObject **cython_runtime_dict; +#endif + CYTHON_MAYBE_UNUSED_VAR(tstate); + if (unlikely(!__pyx_cython_runtime)) { + return c_line; + } + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); +#if CYTHON_COMPILING_IN_CPYTHON + cython_runtime_dict = _PyObject_GetDictPtr(__pyx_cython_runtime); + if (likely(cython_runtime_dict)) { + __PYX_PY_DICT_LOOKUP_IF_MODIFIED( + use_cline, *cython_runtime_dict, + __Pyx_PyDict_GetItemStr(*cython_runtime_dict, __pyx_n_s_cline_in_traceback)) + } else +#endif + { + PyObject *use_cline_obj = __Pyx_PyObject_GetAttrStrNoError(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback); + if (use_cline_obj) { + use_cline = PyObject_Not(use_cline_obj) ? Py_False : Py_True; + Py_DECREF(use_cline_obj); + } else { + PyErr_Clear(); + use_cline = NULL; + } + } + if (!use_cline) { + c_line = 0; + (void) PyObject_SetAttr(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback, Py_False); + } + else if (use_cline == Py_False || (use_cline != Py_True && PyObject_Not(use_cline) != 0)) { + c_line = 0; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + return c_line; +} +#endif + +/* CodeObjectCache */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line) { + int start = 0, mid = 0, end = count - 1; + if (end >= 0 && code_line > entries[end].code_line) { + return count; + } + while (start < end) { + mid = start + (end - start) / 2; + if (code_line < entries[mid].code_line) { + end = mid; + } else if (code_line > entries[mid].code_line) { + start = mid + 1; + } else { + return mid; + } + } + if (code_line <= entries[mid].code_line) { + return mid; + } else { + return mid + 1; + } +} +static PyCodeObject *__pyx_find_code_object(int code_line) { + PyCodeObject* code_object; + int pos; + if (unlikely(!code_line) || unlikely(!__pyx_code_cache.entries)) { + return NULL; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if (unlikely(pos >= __pyx_code_cache.count) || unlikely(__pyx_code_cache.entries[pos].code_line != code_line)) { + return NULL; + } + code_object = __pyx_code_cache.entries[pos].code_object; + Py_INCREF(code_object); + return code_object; +} +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object) { + int pos, i; + __Pyx_CodeObjectCacheEntry* entries = __pyx_code_cache.entries; + if (unlikely(!code_line)) { + return; + } + if (unlikely(!entries)) { + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Malloc(64*sizeof(__Pyx_CodeObjectCacheEntry)); + if (likely(entries)) { + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = 64; + __pyx_code_cache.count = 1; + entries[0].code_line = code_line; + entries[0].code_object = code_object; + Py_INCREF(code_object); + } + return; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if ((pos < __pyx_code_cache.count) && unlikely(__pyx_code_cache.entries[pos].code_line == code_line)) { + PyCodeObject* tmp = entries[pos].code_object; + entries[pos].code_object = code_object; + Py_DECREF(tmp); + return; + } + if (__pyx_code_cache.count == __pyx_code_cache.max_count) { + int new_max = __pyx_code_cache.max_count + 64; + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Realloc( + __pyx_code_cache.entries, ((size_t)new_max) * sizeof(__Pyx_CodeObjectCacheEntry)); + if (unlikely(!entries)) { + return; + } + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = new_max; + } + for (i=__pyx_code_cache.count; i>pos; i--) { + entries[i] = entries[i-1]; + } + entries[pos].code_line = code_line; + entries[pos].code_object = code_object; + __pyx_code_cache.count++; + Py_INCREF(code_object); +} +#endif + +/* AddTraceback */ +#include "compile.h" +#include "frameobject.h" +#include "traceback.h" +#if PY_VERSION_HEX >= 0x030b00a6 && !CYTHON_COMPILING_IN_LIMITED_API + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static PyObject *__Pyx_PyCode_Replace_For_AddTraceback(PyObject *code, PyObject *scratch_dict, + PyObject *firstlineno, PyObject *name) { + PyObject *replace = NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "co_firstlineno", firstlineno))) return NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "co_name", name))) return NULL; + replace = PyObject_GetAttrString(code, "replace"); + if (likely(replace)) { + PyObject *result; + result = PyObject_Call(replace, __pyx_empty_tuple, scratch_dict); + Py_DECREF(replace); + return result; + } + PyErr_Clear(); + #if __PYX_LIMITED_VERSION_HEX < 0x030780000 + { + PyObject *compiled = NULL, *result = NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "code", code))) return NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "type", (PyObject*)(&PyType_Type)))) return NULL; + compiled = Py_CompileString( + "out = type(code)(\n" + " code.co_argcount, code.co_kwonlyargcount, code.co_nlocals, code.co_stacksize,\n" + " code.co_flags, code.co_code, code.co_consts, code.co_names,\n" + " code.co_varnames, code.co_filename, co_name, co_firstlineno,\n" + " code.co_lnotab)\n", "", Py_file_input); + if (!compiled) return NULL; + result = PyEval_EvalCode(compiled, scratch_dict, scratch_dict); + Py_DECREF(compiled); + if (!result) PyErr_Print(); + Py_DECREF(result); + result = PyDict_GetItemString(scratch_dict, "out"); + if (result) Py_INCREF(result); + return result; + } + #else + return NULL; + #endif +} +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + PyObject *code_object = NULL, *py_py_line = NULL, *py_funcname = NULL, *dict = NULL; + PyObject *replace = NULL, *getframe = NULL, *frame = NULL; + PyObject *exc_type, *exc_value, *exc_traceback; + int success = 0; + if (c_line) { + (void) __pyx_cfilenm; + (void) __Pyx_CLineForTraceback(__Pyx_PyThreadState_Current, c_line); + } + PyErr_Fetch(&exc_type, &exc_value, &exc_traceback); + code_object = Py_CompileString("_getframe()", filename, Py_eval_input); + if (unlikely(!code_object)) goto bad; + py_py_line = PyLong_FromLong(py_line); + if (unlikely(!py_py_line)) goto bad; + py_funcname = PyUnicode_FromString(funcname); + if (unlikely(!py_funcname)) goto bad; + dict = PyDict_New(); + if (unlikely(!dict)) goto bad; + { + PyObject *old_code_object = code_object; + code_object = __Pyx_PyCode_Replace_For_AddTraceback(code_object, dict, py_py_line, py_funcname); + Py_DECREF(old_code_object); + } + if (unlikely(!code_object)) goto bad; + getframe = PySys_GetObject("_getframe"); + if (unlikely(!getframe)) goto bad; + if (unlikely(PyDict_SetItemString(dict, "_getframe", getframe))) goto bad; + frame = PyEval_EvalCode(code_object, dict, dict); + if (unlikely(!frame) || frame == Py_None) goto bad; + success = 1; + bad: + PyErr_Restore(exc_type, exc_value, exc_traceback); + Py_XDECREF(code_object); + Py_XDECREF(py_py_line); + Py_XDECREF(py_funcname); + Py_XDECREF(dict); + Py_XDECREF(replace); + if (success) { + PyTraceBack_Here( + (struct _frame*)frame); + } + Py_XDECREF(frame); +} +#else +static PyCodeObject* __Pyx_CreateCodeObjectForTraceback( + const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = NULL; + PyObject *py_funcname = NULL; + #if PY_MAJOR_VERSION < 3 + PyObject *py_srcfile = NULL; + py_srcfile = PyString_FromString(filename); + if (!py_srcfile) goto bad; + #endif + if (c_line) { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + #else + py_funcname = PyUnicode_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + funcname = PyUnicode_AsUTF8(py_funcname); + if (!funcname) goto bad; + #endif + } + else { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromString(funcname); + if (!py_funcname) goto bad; + #endif + } + #if PY_MAJOR_VERSION < 3 + py_code = __Pyx_PyCode_New( + 0, + 0, + 0, + 0, + 0, + 0, + __pyx_empty_bytes, /*PyObject *code,*/ + __pyx_empty_tuple, /*PyObject *consts,*/ + __pyx_empty_tuple, /*PyObject *names,*/ + __pyx_empty_tuple, /*PyObject *varnames,*/ + __pyx_empty_tuple, /*PyObject *freevars,*/ + __pyx_empty_tuple, /*PyObject *cellvars,*/ + py_srcfile, /*PyObject *filename,*/ + py_funcname, /*PyObject *name,*/ + py_line, + __pyx_empty_bytes /*PyObject *lnotab*/ + ); + Py_DECREF(py_srcfile); + #else + py_code = PyCode_NewEmpty(filename, funcname, py_line); + #endif + Py_XDECREF(py_funcname); + return py_code; +bad: + Py_XDECREF(py_funcname); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_srcfile); + #endif + return NULL; +} +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = 0; + PyFrameObject *py_frame = 0; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject *ptype, *pvalue, *ptraceback; + if (c_line) { + c_line = __Pyx_CLineForTraceback(tstate, c_line); + } + py_code = __pyx_find_code_object(c_line ? -c_line : py_line); + if (!py_code) { + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); + py_code = __Pyx_CreateCodeObjectForTraceback( + funcname, c_line, py_line, filename); + if (!py_code) { + /* If the code object creation fails, then we should clear the + fetched exception references and propagate the new exception */ + Py_XDECREF(ptype); + Py_XDECREF(pvalue); + Py_XDECREF(ptraceback); + goto bad; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + __pyx_insert_code_object(c_line ? -c_line : py_line, py_code); + } + py_frame = PyFrame_New( + tstate, /*PyThreadState *tstate,*/ + py_code, /*PyCodeObject *code,*/ + __pyx_d, /*PyObject *globals,*/ + 0 /*PyObject *locals*/ + ); + if (!py_frame) goto bad; + __Pyx_PyFrame_SetLineNumber(py_frame, py_line); + PyTraceBack_Here(py_frame); +bad: + Py_XDECREF(py_code); + Py_XDECREF(py_frame); +} +#endif + +#if PY_MAJOR_VERSION < 3 +static int __Pyx_GetBuffer(PyObject *obj, Py_buffer *view, int flags) { + __Pyx_TypeName obj_type_name; + if (PyObject_CheckBuffer(obj)) return PyObject_GetBuffer(obj, view, flags); + if (__Pyx_TypeCheck(obj, __pyx_array_type)) return __pyx_array_getbuffer(obj, view, flags); + if (__Pyx_TypeCheck(obj, __pyx_memoryview_type)) return __pyx_memoryview_getbuffer(obj, view, flags); + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "'" __Pyx_FMT_TYPENAME "' does not have the buffer interface", + obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return -1; +} +static void __Pyx_ReleaseBuffer(Py_buffer *view) { + PyObject *obj = view->obj; + if (!obj) return; + if (PyObject_CheckBuffer(obj)) { + PyBuffer_Release(view); + return; + } + if ((0)) {} + view->obj = NULL; + Py_DECREF(obj); +} +#endif + + +/* MemviewSliceIsContig */ +static int +__pyx_memviewslice_is_contig(const __Pyx_memviewslice mvs, char order, int ndim) +{ + int i, index, step, start; + Py_ssize_t itemsize = mvs.memview->view.itemsize; + if (order == 'F') { + step = 1; + start = 0; + } else { + step = -1; + start = ndim - 1; + } + for (i = 0; i < ndim; i++) { + index = start + step * i; + if (mvs.suboffsets[index] >= 0 || mvs.strides[index] != itemsize) + return 0; + itemsize *= mvs.shape[index]; + } + return 1; +} + +/* OverlappingSlices */ +static void +__pyx_get_array_memory_extents(__Pyx_memviewslice *slice, + void **out_start, void **out_end, + int ndim, size_t itemsize) +{ + char *start, *end; + int i; + start = end = slice->data; + for (i = 0; i < ndim; i++) { + Py_ssize_t stride = slice->strides[i]; + Py_ssize_t extent = slice->shape[i]; + if (extent == 0) { + *out_start = *out_end = start; + return; + } else { + if (stride > 0) + end += stride * (extent - 1); + else + start += stride * (extent - 1); + } + } + *out_start = start; + *out_end = end + itemsize; +} +static int +__pyx_slices_overlap(__Pyx_memviewslice *slice1, + __Pyx_memviewslice *slice2, + int ndim, size_t itemsize) +{ + void *start1, *end1, *start2, *end2; + __pyx_get_array_memory_extents(slice1, &start1, &end1, ndim, itemsize); + __pyx_get_array_memory_extents(slice2, &start2, &end2, ndim, itemsize); + return (start1 < end2) && (start2 < end1); +} + +/* IsLittleEndian */ +static CYTHON_INLINE int __Pyx_Is_Little_Endian(void) +{ + union { + uint32_t u32; + uint8_t u8[4]; + } S; + S.u32 = 0x01020304; + return S.u8[0] == 4; +} + +/* BufferFormatCheck */ +static void __Pyx_BufFmt_Init(__Pyx_BufFmt_Context* ctx, + __Pyx_BufFmt_StackElem* stack, + __Pyx_TypeInfo* type) { + stack[0].field = &ctx->root; + stack[0].parent_offset = 0; + ctx->root.type = type; + ctx->root.name = "buffer dtype"; + ctx->root.offset = 0; + ctx->head = stack; + ctx->head->field = &ctx->root; + ctx->fmt_offset = 0; + ctx->head->parent_offset = 0; + ctx->new_packmode = '@'; + ctx->enc_packmode = '@'; + ctx->new_count = 1; + ctx->enc_count = 0; + ctx->enc_type = 0; + ctx->is_complex = 0; + ctx->is_valid_array = 0; + ctx->struct_alignment = 0; + while (type->typegroup == 'S') { + ++ctx->head; + ctx->head->field = type->fields; + ctx->head->parent_offset = 0; + type = type->fields->type; + } +} +static int __Pyx_BufFmt_ParseNumber(const char** ts) { + int count; + const char* t = *ts; + if (*t < '0' || *t > '9') { + return -1; + } else { + count = *t++ - '0'; + while (*t >= '0' && *t <= '9') { + count *= 10; + count += *t++ - '0'; + } + } + *ts = t; + return count; +} +static int __Pyx_BufFmt_ExpectNumber(const char **ts) { + int number = __Pyx_BufFmt_ParseNumber(ts); + if (number == -1) + PyErr_Format(PyExc_ValueError,\ + "Does not understand character buffer dtype format string ('%c')", **ts); + return number; +} +static void __Pyx_BufFmt_RaiseUnexpectedChar(char ch) { + PyErr_Format(PyExc_ValueError, + "Unexpected format string character: '%c'", ch); +} +static const char* __Pyx_BufFmt_DescribeTypeChar(char ch, int is_complex) { + switch (ch) { + case '?': return "'bool'"; + case 'c': return "'char'"; + case 'b': return "'signed char'"; + case 'B': return "'unsigned char'"; + case 'h': return "'short'"; + case 'H': return "'unsigned short'"; + case 'i': return "'int'"; + case 'I': return "'unsigned int'"; + case 'l': return "'long'"; + case 'L': return "'unsigned long'"; + case 'q': return "'long long'"; + case 'Q': return "'unsigned long long'"; + case 'f': return (is_complex ? "'complex float'" : "'float'"); + case 'd': return (is_complex ? "'complex double'" : "'double'"); + case 'g': return (is_complex ? "'complex long double'" : "'long double'"); + case 'T': return "a struct"; + case 'O': return "Python object"; + case 'P': return "a pointer"; + case 's': case 'p': return "a string"; + case 0: return "end"; + default: return "unparsable format string"; + } +} +static size_t __Pyx_BufFmt_TypeCharToStandardSize(char ch, int is_complex) { + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return 2; + case 'i': case 'I': case 'l': case 'L': return 4; + case 'q': case 'Q': return 8; + case 'f': return (is_complex ? 8 : 4); + case 'd': return (is_complex ? 16 : 8); + case 'g': { + PyErr_SetString(PyExc_ValueError, "Python does not define a standard format string size for long double ('g').."); + return 0; + } + case 'O': case 'P': return sizeof(void*); + default: + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } +} +static size_t __Pyx_BufFmt_TypeCharToNativeSize(char ch, int is_complex) { + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return sizeof(short); + case 'i': case 'I': return sizeof(int); + case 'l': case 'L': return sizeof(long); + #ifdef HAVE_LONG_LONG + case 'q': case 'Q': return sizeof(PY_LONG_LONG); + #endif + case 'f': return sizeof(float) * (is_complex ? 2 : 1); + case 'd': return sizeof(double) * (is_complex ? 2 : 1); + case 'g': return sizeof(long double) * (is_complex ? 2 : 1); + case 'O': case 'P': return sizeof(void*); + default: { + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } + } +} +typedef struct { char c; short x; } __Pyx_st_short; +typedef struct { char c; int x; } __Pyx_st_int; +typedef struct { char c; long x; } __Pyx_st_long; +typedef struct { char c; float x; } __Pyx_st_float; +typedef struct { char c; double x; } __Pyx_st_double; +typedef struct { char c; long double x; } __Pyx_st_longdouble; +typedef struct { char c; void *x; } __Pyx_st_void_p; +#ifdef HAVE_LONG_LONG +typedef struct { char c; PY_LONG_LONG x; } __Pyx_st_longlong; +#endif +static size_t __Pyx_BufFmt_TypeCharToAlignment(char ch, int is_complex) { + CYTHON_UNUSED_VAR(is_complex); + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return sizeof(__Pyx_st_short) - sizeof(short); + case 'i': case 'I': return sizeof(__Pyx_st_int) - sizeof(int); + case 'l': case 'L': return sizeof(__Pyx_st_long) - sizeof(long); +#ifdef HAVE_LONG_LONG + case 'q': case 'Q': return sizeof(__Pyx_st_longlong) - sizeof(PY_LONG_LONG); +#endif + case 'f': return sizeof(__Pyx_st_float) - sizeof(float); + case 'd': return sizeof(__Pyx_st_double) - sizeof(double); + case 'g': return sizeof(__Pyx_st_longdouble) - sizeof(long double); + case 'P': case 'O': return sizeof(__Pyx_st_void_p) - sizeof(void*); + default: + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } +} +/* These are for computing the padding at the end of the struct to align + on the first member of the struct. This will probably the same as above, + but we don't have any guarantees. + */ +typedef struct { short x; char c; } __Pyx_pad_short; +typedef struct { int x; char c; } __Pyx_pad_int; +typedef struct { long x; char c; } __Pyx_pad_long; +typedef struct { float x; char c; } __Pyx_pad_float; +typedef struct { double x; char c; } __Pyx_pad_double; +typedef struct { long double x; char c; } __Pyx_pad_longdouble; +typedef struct { void *x; char c; } __Pyx_pad_void_p; +#ifdef HAVE_LONG_LONG +typedef struct { PY_LONG_LONG x; char c; } __Pyx_pad_longlong; +#endif +static size_t __Pyx_BufFmt_TypeCharToPadding(char ch, int is_complex) { + CYTHON_UNUSED_VAR(is_complex); + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return sizeof(__Pyx_pad_short) - sizeof(short); + case 'i': case 'I': return sizeof(__Pyx_pad_int) - sizeof(int); + case 'l': case 'L': return sizeof(__Pyx_pad_long) - sizeof(long); +#ifdef HAVE_LONG_LONG + case 'q': case 'Q': return sizeof(__Pyx_pad_longlong) - sizeof(PY_LONG_LONG); +#endif + case 'f': return sizeof(__Pyx_pad_float) - sizeof(float); + case 'd': return sizeof(__Pyx_pad_double) - sizeof(double); + case 'g': return sizeof(__Pyx_pad_longdouble) - sizeof(long double); + case 'P': case 'O': return sizeof(__Pyx_pad_void_p) - sizeof(void*); + default: + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } +} +static char __Pyx_BufFmt_TypeCharToGroup(char ch, int is_complex) { + switch (ch) { + case 'c': + return 'H'; + case 'b': case 'h': case 'i': + case 'l': case 'q': case 's': case 'p': + return 'I'; + case '?': case 'B': case 'H': case 'I': case 'L': case 'Q': + return 'U'; + case 'f': case 'd': case 'g': + return (is_complex ? 'C' : 'R'); + case 'O': + return 'O'; + case 'P': + return 'P'; + default: { + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } + } +} +static void __Pyx_BufFmt_RaiseExpected(__Pyx_BufFmt_Context* ctx) { + if (ctx->head == NULL || ctx->head->field == &ctx->root) { + const char* expected; + const char* quote; + if (ctx->head == NULL) { + expected = "end"; + quote = ""; + } else { + expected = ctx->head->field->type->name; + quote = "'"; + } + PyErr_Format(PyExc_ValueError, + "Buffer dtype mismatch, expected %s%s%s but got %s", + quote, expected, quote, + __Pyx_BufFmt_DescribeTypeChar(ctx->enc_type, ctx->is_complex)); + } else { + __Pyx_StructField* field = ctx->head->field; + __Pyx_StructField* parent = (ctx->head - 1)->field; + PyErr_Format(PyExc_ValueError, + "Buffer dtype mismatch, expected '%s' but got %s in '%s.%s'", + field->type->name, __Pyx_BufFmt_DescribeTypeChar(ctx->enc_type, ctx->is_complex), + parent->type->name, field->name); + } +} +static int __Pyx_BufFmt_ProcessTypeChunk(__Pyx_BufFmt_Context* ctx) { + char group; + size_t size, offset, arraysize = 1; + if (ctx->enc_type == 0) return 0; + if (ctx->head->field->type->arraysize[0]) { + int i, ndim = 0; + if (ctx->enc_type == 's' || ctx->enc_type == 'p') { + ctx->is_valid_array = ctx->head->field->type->ndim == 1; + ndim = 1; + if (ctx->enc_count != ctx->head->field->type->arraysize[0]) { + PyErr_Format(PyExc_ValueError, + "Expected a dimension of size %zu, got %zu", + ctx->head->field->type->arraysize[0], ctx->enc_count); + return -1; + } + } + if (!ctx->is_valid_array) { + PyErr_Format(PyExc_ValueError, "Expected %d dimensions, got %d", + ctx->head->field->type->ndim, ndim); + return -1; + } + for (i = 0; i < ctx->head->field->type->ndim; i++) { + arraysize *= ctx->head->field->type->arraysize[i]; + } + ctx->is_valid_array = 0; + ctx->enc_count = 1; + } + group = __Pyx_BufFmt_TypeCharToGroup(ctx->enc_type, ctx->is_complex); + do { + __Pyx_StructField* field = ctx->head->field; + __Pyx_TypeInfo* type = field->type; + if (ctx->enc_packmode == '@' || ctx->enc_packmode == '^') { + size = __Pyx_BufFmt_TypeCharToNativeSize(ctx->enc_type, ctx->is_complex); + } else { + size = __Pyx_BufFmt_TypeCharToStandardSize(ctx->enc_type, ctx->is_complex); + } + if (ctx->enc_packmode == '@') { + size_t align_at = __Pyx_BufFmt_TypeCharToAlignment(ctx->enc_type, ctx->is_complex); + size_t align_mod_offset; + if (align_at == 0) return -1; + align_mod_offset = ctx->fmt_offset % align_at; + if (align_mod_offset > 0) ctx->fmt_offset += align_at - align_mod_offset; + if (ctx->struct_alignment == 0) + ctx->struct_alignment = __Pyx_BufFmt_TypeCharToPadding(ctx->enc_type, + ctx->is_complex); + } + if (type->size != size || type->typegroup != group) { + if (type->typegroup == 'C' && type->fields != NULL) { + size_t parent_offset = ctx->head->parent_offset + field->offset; + ++ctx->head; + ctx->head->field = type->fields; + ctx->head->parent_offset = parent_offset; + continue; + } + if ((type->typegroup == 'H' || group == 'H') && type->size == size) { + } else { + __Pyx_BufFmt_RaiseExpected(ctx); + return -1; + } + } + offset = ctx->head->parent_offset + field->offset; + if (ctx->fmt_offset != offset) { + PyErr_Format(PyExc_ValueError, + "Buffer dtype mismatch; next field is at offset %" CYTHON_FORMAT_SSIZE_T "d but %" CYTHON_FORMAT_SSIZE_T "d expected", + (Py_ssize_t)ctx->fmt_offset, (Py_ssize_t)offset); + return -1; + } + ctx->fmt_offset += size; + if (arraysize) + ctx->fmt_offset += (arraysize - 1) * size; + --ctx->enc_count; + while (1) { + if (field == &ctx->root) { + ctx->head = NULL; + if (ctx->enc_count != 0) { + __Pyx_BufFmt_RaiseExpected(ctx); + return -1; + } + break; + } + ctx->head->field = ++field; + if (field->type == NULL) { + --ctx->head; + field = ctx->head->field; + continue; + } else if (field->type->typegroup == 'S') { + size_t parent_offset = ctx->head->parent_offset + field->offset; + if (field->type->fields->type == NULL) continue; + field = field->type->fields; + ++ctx->head; + ctx->head->field = field; + ctx->head->parent_offset = parent_offset; + break; + } else { + break; + } + } + } while (ctx->enc_count); + ctx->enc_type = 0; + ctx->is_complex = 0; + return 0; +} +static int +__pyx_buffmt_parse_array(__Pyx_BufFmt_Context* ctx, const char** tsp) +{ + const char *ts = *tsp; + int i = 0, number, ndim; + ++ts; + if (ctx->new_count != 1) { + PyErr_SetString(PyExc_ValueError, + "Cannot handle repeated arrays in format string"); + return -1; + } + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return -1; + ndim = ctx->head->field->type->ndim; + while (*ts && *ts != ')') { + switch (*ts) { + case ' ': case '\f': case '\r': case '\n': case '\t': case '\v': continue; + default: break; + } + number = __Pyx_BufFmt_ExpectNumber(&ts); + if (number == -1) return -1; + if (i < ndim && (size_t) number != ctx->head->field->type->arraysize[i]) { + PyErr_Format(PyExc_ValueError, + "Expected a dimension of size %zu, got %d", + ctx->head->field->type->arraysize[i], number); + return -1; + } + if (*ts != ',' && *ts != ')') { + PyErr_Format(PyExc_ValueError, + "Expected a comma in format string, got '%c'", *ts); + return -1; + } + if (*ts == ',') ts++; + i++; + } + if (i != ndim) { + PyErr_Format(PyExc_ValueError, "Expected %d dimension(s), got %d", + ctx->head->field->type->ndim, i); + return -1; + } + if (!*ts) { + PyErr_SetString(PyExc_ValueError, + "Unexpected end of format string, expected ')'"); + return -1; + } + ctx->is_valid_array = 1; + ctx->new_count = 1; + *tsp = ++ts; + return 0; +} +static const char* __Pyx_BufFmt_CheckString(__Pyx_BufFmt_Context* ctx, const char* ts) { + int got_Z = 0; + while (1) { + switch(*ts) { + case 0: + if (ctx->enc_type != 0 && ctx->head == NULL) { + __Pyx_BufFmt_RaiseExpected(ctx); + return NULL; + } + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + if (ctx->head != NULL) { + __Pyx_BufFmt_RaiseExpected(ctx); + return NULL; + } + return ts; + case ' ': + case '\r': + case '\n': + ++ts; + break; + case '<': + if (!__Pyx_Is_Little_Endian()) { + PyErr_SetString(PyExc_ValueError, "Little-endian buffer not supported on big-endian compiler"); + return NULL; + } + ctx->new_packmode = '='; + ++ts; + break; + case '>': + case '!': + if (__Pyx_Is_Little_Endian()) { + PyErr_SetString(PyExc_ValueError, "Big-endian buffer not supported on little-endian compiler"); + return NULL; + } + ctx->new_packmode = '='; + ++ts; + break; + case '=': + case '@': + case '^': + ctx->new_packmode = *ts++; + break; + case 'T': + { + const char* ts_after_sub; + size_t i, struct_count = ctx->new_count; + size_t struct_alignment = ctx->struct_alignment; + ctx->new_count = 1; + ++ts; + if (*ts != '{') { + PyErr_SetString(PyExc_ValueError, "Buffer acquisition: Expected '{' after 'T'"); + return NULL; + } + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->enc_type = 0; + ctx->enc_count = 0; + ctx->struct_alignment = 0; + ++ts; + ts_after_sub = ts; + for (i = 0; i != struct_count; ++i) { + ts_after_sub = __Pyx_BufFmt_CheckString(ctx, ts); + if (!ts_after_sub) return NULL; + } + ts = ts_after_sub; + if (struct_alignment) ctx->struct_alignment = struct_alignment; + } + break; + case '}': + { + size_t alignment = ctx->struct_alignment; + ++ts; + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->enc_type = 0; + if (alignment && ctx->fmt_offset % alignment) { + ctx->fmt_offset += alignment - (ctx->fmt_offset % alignment); + } + } + return ts; + case 'x': + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->fmt_offset += ctx->new_count; + ctx->new_count = 1; + ctx->enc_count = 0; + ctx->enc_type = 0; + ctx->enc_packmode = ctx->new_packmode; + ++ts; + break; + case 'Z': + got_Z = 1; + ++ts; + if (*ts != 'f' && *ts != 'd' && *ts != 'g') { + __Pyx_BufFmt_RaiseUnexpectedChar('Z'); + return NULL; + } + CYTHON_FALLTHROUGH; + case '?': case 'c': case 'b': case 'B': case 'h': case 'H': case 'i': case 'I': + case 'l': case 'L': case 'q': case 'Q': + case 'f': case 'd': case 'g': + case 'O': case 'p': + if ((ctx->enc_type == *ts) && (got_Z == ctx->is_complex) && + (ctx->enc_packmode == ctx->new_packmode) && (!ctx->is_valid_array)) { + ctx->enc_count += ctx->new_count; + ctx->new_count = 1; + got_Z = 0; + ++ts; + break; + } + CYTHON_FALLTHROUGH; + case 's': + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->enc_count = ctx->new_count; + ctx->enc_packmode = ctx->new_packmode; + ctx->enc_type = *ts; + ctx->is_complex = got_Z; + ++ts; + ctx->new_count = 1; + got_Z = 0; + break; + case ':': + ++ts; + while(*ts != ':') ++ts; + ++ts; + break; + case '(': + if (__pyx_buffmt_parse_array(ctx, &ts) < 0) return NULL; + break; + default: + { + int number = __Pyx_BufFmt_ExpectNumber(&ts); + if (number == -1) return NULL; + ctx->new_count = (size_t)number; + } + } + } +} + +/* TypeInfoCompare */ + static int +__pyx_typeinfo_cmp(__Pyx_TypeInfo *a, __Pyx_TypeInfo *b) +{ + int i; + if (!a || !b) + return 0; + if (a == b) + return 1; + if (a->size != b->size || a->typegroup != b->typegroup || + a->is_unsigned != b->is_unsigned || a->ndim != b->ndim) { + if (a->typegroup == 'H' || b->typegroup == 'H') { + return a->size == b->size; + } else { + return 0; + } + } + if (a->ndim) { + for (i = 0; i < a->ndim; i++) + if (a->arraysize[i] != b->arraysize[i]) + return 0; + } + if (a->typegroup == 'S') { + if (a->flags != b->flags) + return 0; + if (a->fields || b->fields) { + if (!(a->fields && b->fields)) + return 0; + for (i = 0; a->fields[i].type && b->fields[i].type; i++) { + __Pyx_StructField *field_a = a->fields + i; + __Pyx_StructField *field_b = b->fields + i; + if (field_a->offset != field_b->offset || + !__pyx_typeinfo_cmp(field_a->type, field_b->type)) + return 0; + } + return !a->fields[i].type && !b->fields[i].type; + } + } + return 1; +} + +/* MemviewSliceValidateAndInit */ + static int +__pyx_check_strides(Py_buffer *buf, int dim, int ndim, int spec) +{ + if (buf->shape[dim] <= 1) + return 1; + if (buf->strides) { + if (spec & __Pyx_MEMVIEW_CONTIG) { + if (spec & (__Pyx_MEMVIEW_PTR|__Pyx_MEMVIEW_FULL)) { + if (unlikely(buf->strides[dim] != sizeof(void *))) { + PyErr_Format(PyExc_ValueError, + "Buffer is not indirectly contiguous " + "in dimension %d.", dim); + goto fail; + } + } else if (unlikely(buf->strides[dim] != buf->itemsize)) { + PyErr_SetString(PyExc_ValueError, + "Buffer and memoryview are not contiguous " + "in the same dimension."); + goto fail; + } + } + if (spec & __Pyx_MEMVIEW_FOLLOW) { + Py_ssize_t stride = buf->strides[dim]; + if (stride < 0) + stride = -stride; + if (unlikely(stride < buf->itemsize)) { + PyErr_SetString(PyExc_ValueError, + "Buffer and memoryview are not contiguous " + "in the same dimension."); + goto fail; + } + } + } else { + if (unlikely(spec & __Pyx_MEMVIEW_CONTIG && dim != ndim - 1)) { + PyErr_Format(PyExc_ValueError, + "C-contiguous buffer is not contiguous in " + "dimension %d", dim); + goto fail; + } else if (unlikely(spec & (__Pyx_MEMVIEW_PTR))) { + PyErr_Format(PyExc_ValueError, + "C-contiguous buffer is not indirect in " + "dimension %d", dim); + goto fail; + } else if (unlikely(buf->suboffsets)) { + PyErr_SetString(PyExc_ValueError, + "Buffer exposes suboffsets but no strides"); + goto fail; + } + } + return 1; +fail: + return 0; +} +static int +__pyx_check_suboffsets(Py_buffer *buf, int dim, int ndim, int spec) +{ + CYTHON_UNUSED_VAR(ndim); + if (spec & __Pyx_MEMVIEW_DIRECT) { + if (unlikely(buf->suboffsets && buf->suboffsets[dim] >= 0)) { + PyErr_Format(PyExc_ValueError, + "Buffer not compatible with direct access " + "in dimension %d.", dim); + goto fail; + } + } + if (spec & __Pyx_MEMVIEW_PTR) { + if (unlikely(!buf->suboffsets || (buf->suboffsets[dim] < 0))) { + PyErr_Format(PyExc_ValueError, + "Buffer is not indirectly accessible " + "in dimension %d.", dim); + goto fail; + } + } + return 1; +fail: + return 0; +} +static int +__pyx_verify_contig(Py_buffer *buf, int ndim, int c_or_f_flag) +{ + int i; + if (c_or_f_flag & __Pyx_IS_F_CONTIG) { + Py_ssize_t stride = 1; + for (i = 0; i < ndim; i++) { + if (unlikely(stride * buf->itemsize != buf->strides[i] && buf->shape[i] > 1)) { + PyErr_SetString(PyExc_ValueError, + "Buffer not fortran contiguous."); + goto fail; + } + stride = stride * buf->shape[i]; + } + } else if (c_or_f_flag & __Pyx_IS_C_CONTIG) { + Py_ssize_t stride = 1; + for (i = ndim - 1; i >- 1; i--) { + if (unlikely(stride * buf->itemsize != buf->strides[i] && buf->shape[i] > 1)) { + PyErr_SetString(PyExc_ValueError, + "Buffer not C contiguous."); + goto fail; + } + stride = stride * buf->shape[i]; + } + } + return 1; +fail: + return 0; +} +static int __Pyx_ValidateAndInit_memviewslice( + int *axes_specs, + int c_or_f_flag, + int buf_flags, + int ndim, + __Pyx_TypeInfo *dtype, + __Pyx_BufFmt_StackElem stack[], + __Pyx_memviewslice *memviewslice, + PyObject *original_obj) +{ + struct __pyx_memoryview_obj *memview, *new_memview; + __Pyx_RefNannyDeclarations + Py_buffer *buf; + int i, spec = 0, retval = -1; + __Pyx_BufFmt_Context ctx; + int from_memoryview = __pyx_memoryview_check(original_obj); + __Pyx_RefNannySetupContext("ValidateAndInit_memviewslice", 0); + if (from_memoryview && __pyx_typeinfo_cmp(dtype, ((struct __pyx_memoryview_obj *) + original_obj)->typeinfo)) { + memview = (struct __pyx_memoryview_obj *) original_obj; + new_memview = NULL; + } else { + memview = (struct __pyx_memoryview_obj *) __pyx_memoryview_new( + original_obj, buf_flags, 0, dtype); + new_memview = memview; + if (unlikely(!memview)) + goto fail; + } + buf = &memview->view; + if (unlikely(buf->ndim != ndim)) { + PyErr_Format(PyExc_ValueError, + "Buffer has wrong number of dimensions (expected %d, got %d)", + ndim, buf->ndim); + goto fail; + } + if (new_memview) { + __Pyx_BufFmt_Init(&ctx, stack, dtype); + if (unlikely(!__Pyx_BufFmt_CheckString(&ctx, buf->format))) goto fail; + } + if (unlikely((unsigned) buf->itemsize != dtype->size)) { + PyErr_Format(PyExc_ValueError, + "Item size of buffer (%" CYTHON_FORMAT_SSIZE_T "u byte%s) " + "does not match size of '%s' (%" CYTHON_FORMAT_SSIZE_T "u byte%s)", + buf->itemsize, + (buf->itemsize > 1) ? "s" : "", + dtype->name, + dtype->size, + (dtype->size > 1) ? "s" : ""); + goto fail; + } + if (buf->len > 0) { + for (i = 0; i < ndim; i++) { + spec = axes_specs[i]; + if (unlikely(!__pyx_check_strides(buf, i, ndim, spec))) + goto fail; + if (unlikely(!__pyx_check_suboffsets(buf, i, ndim, spec))) + goto fail; + } + if (unlikely(buf->strides && !__pyx_verify_contig(buf, ndim, c_or_f_flag))) + goto fail; + } + if (unlikely(__Pyx_init_memviewslice(memview, ndim, memviewslice, + new_memview != NULL) == -1)) { + goto fail; + } + retval = 0; + goto no_fail; +fail: + Py_XDECREF(new_memview); + retval = -1; +no_fail: + __Pyx_RefNannyFinishContext(); + return retval; +} + +/* ObjectToMemviewSlice */ + static CYTHON_INLINE __Pyx_memviewslice __Pyx_PyObject_to_MemoryviewSlice_ds_float(PyObject *obj, int writable_flag) { + __Pyx_memviewslice result = { 0, 0, { 0 }, { 0 }, { 0 } }; + __Pyx_BufFmt_StackElem stack[1]; + int axes_specs[] = { (__Pyx_MEMVIEW_DIRECT | __Pyx_MEMVIEW_STRIDED) }; + int retcode; + if (obj == Py_None) { + result.memview = (struct __pyx_memoryview_obj *) Py_None; + return result; + } + retcode = __Pyx_ValidateAndInit_memviewslice(axes_specs, 0, + PyBUF_RECORDS_RO | writable_flag, 1, + &__Pyx_TypeInfo_float, stack, + &result, obj); + if (unlikely(retcode == -1)) + goto __pyx_fail; + return result; +__pyx_fail: + result.memview = NULL; + result.data = NULL; + return result; +} + +/* MemviewDtypeToObject */ + static CYTHON_INLINE PyObject *__pyx_memview_get_float(const char *itemp) { + return (PyObject *) PyFloat_FromDouble(*(float *) itemp); +} +static CYTHON_INLINE int __pyx_memview_set_float(const char *itemp, PyObject *obj) { + float value = __pyx_PyFloat_AsFloat(obj); + if (unlikely((value == (float)-1) && PyErr_Occurred())) + return 0; + *(float *) itemp = value; + return 1; +} + +/* MemviewSliceCopyTemplate */ + static __Pyx_memviewslice +__pyx_memoryview_copy_new_contig(const __Pyx_memviewslice *from_mvs, + const char *mode, int ndim, + size_t sizeof_dtype, int contig_flag, + int dtype_is_object) +{ + __Pyx_RefNannyDeclarations + int i; + __Pyx_memviewslice new_mvs = { 0, 0, { 0 }, { 0 }, { 0 } }; + struct __pyx_memoryview_obj *from_memview = from_mvs->memview; + Py_buffer *buf = &from_memview->view; + PyObject *shape_tuple = NULL; + PyObject *temp_int = NULL; + struct __pyx_array_obj *array_obj = NULL; + struct __pyx_memoryview_obj *memview_obj = NULL; + __Pyx_RefNannySetupContext("__pyx_memoryview_copy_new_contig", 0); + for (i = 0; i < ndim; i++) { + if (unlikely(from_mvs->suboffsets[i] >= 0)) { + PyErr_Format(PyExc_ValueError, "Cannot copy memoryview slice with " + "indirect dimensions (axis %d)", i); + goto fail; + } + } + shape_tuple = PyTuple_New(ndim); + if (unlikely(!shape_tuple)) { + goto fail; + } + __Pyx_GOTREF(shape_tuple); + for(i = 0; i < ndim; i++) { + temp_int = PyInt_FromSsize_t(from_mvs->shape[i]); + if(unlikely(!temp_int)) { + goto fail; + } else { + PyTuple_SET_ITEM(shape_tuple, i, temp_int); + temp_int = NULL; + } + } + array_obj = __pyx_array_new(shape_tuple, sizeof_dtype, buf->format, (char *) mode, NULL); + if (unlikely(!array_obj)) { + goto fail; + } + __Pyx_GOTREF(array_obj); + memview_obj = (struct __pyx_memoryview_obj *) __pyx_memoryview_new( + (PyObject *) array_obj, contig_flag, + dtype_is_object, + from_mvs->memview->typeinfo); + if (unlikely(!memview_obj)) + goto fail; + if (unlikely(__Pyx_init_memviewslice(memview_obj, ndim, &new_mvs, 1) < 0)) + goto fail; + if (unlikely(__pyx_memoryview_copy_contents(*from_mvs, new_mvs, ndim, ndim, + dtype_is_object) < 0)) + goto fail; + goto no_fail; +fail: + __Pyx_XDECREF(new_mvs.memview); + new_mvs.memview = NULL; + new_mvs.data = NULL; +no_fail: + __Pyx_XDECREF(shape_tuple); + __Pyx_XDECREF(temp_int); + __Pyx_XDECREF(array_obj); + __Pyx_RefNannyFinishContext(); + return new_mvs; +} + +/* MemviewSliceInit */ + static int +__Pyx_init_memviewslice(struct __pyx_memoryview_obj *memview, + int ndim, + __Pyx_memviewslice *memviewslice, + int memview_is_new_reference) +{ + __Pyx_RefNannyDeclarations + int i, retval=-1; + Py_buffer *buf = &memview->view; + __Pyx_RefNannySetupContext("init_memviewslice", 0); + if (unlikely(memviewslice->memview || memviewslice->data)) { + PyErr_SetString(PyExc_ValueError, + "memviewslice is already initialized!"); + goto fail; + } + if (buf->strides) { + for (i = 0; i < ndim; i++) { + memviewslice->strides[i] = buf->strides[i]; + } + } else { + Py_ssize_t stride = buf->itemsize; + for (i = ndim - 1; i >= 0; i--) { + memviewslice->strides[i] = stride; + stride *= buf->shape[i]; + } + } + for (i = 0; i < ndim; i++) { + memviewslice->shape[i] = buf->shape[i]; + if (buf->suboffsets) { + memviewslice->suboffsets[i] = buf->suboffsets[i]; + } else { + memviewslice->suboffsets[i] = -1; + } + } + memviewslice->memview = memview; + memviewslice->data = (char *)buf->buf; + if (__pyx_add_acquisition_count(memview) == 0 && !memview_is_new_reference) { + Py_INCREF(memview); + } + retval = 0; + goto no_fail; +fail: + memviewslice->memview = 0; + memviewslice->data = 0; + retval = -1; +no_fail: + __Pyx_RefNannyFinishContext(); + return retval; +} +#ifndef Py_NO_RETURN +#define Py_NO_RETURN +#endif +static void __pyx_fatalerror(const char *fmt, ...) Py_NO_RETURN { + va_list vargs; + char msg[200]; +#if PY_VERSION_HEX >= 0x030A0000 || defined(HAVE_STDARG_PROTOTYPES) + va_start(vargs, fmt); +#else + va_start(vargs); +#endif + vsnprintf(msg, 200, fmt, vargs); + va_end(vargs); + Py_FatalError(msg); +} +static CYTHON_INLINE int +__pyx_add_acquisition_count_locked(__pyx_atomic_int_type *acquisition_count, + PyThread_type_lock lock) +{ + int result; + PyThread_acquire_lock(lock, 1); + result = (*acquisition_count)++; + PyThread_release_lock(lock); + return result; +} +static CYTHON_INLINE int +__pyx_sub_acquisition_count_locked(__pyx_atomic_int_type *acquisition_count, + PyThread_type_lock lock) +{ + int result; + PyThread_acquire_lock(lock, 1); + result = (*acquisition_count)--; + PyThread_release_lock(lock); + return result; +} +static CYTHON_INLINE void +__Pyx_INC_MEMVIEW(__Pyx_memviewslice *memslice, int have_gil, int lineno) +{ + __pyx_nonatomic_int_type old_acquisition_count; + struct __pyx_memoryview_obj *memview = memslice->memview; + if (unlikely(!memview || (PyObject *) memview == Py_None)) { + return; + } + old_acquisition_count = __pyx_add_acquisition_count(memview); + if (unlikely(old_acquisition_count <= 0)) { + if (likely(old_acquisition_count == 0)) { + if (have_gil) { + Py_INCREF((PyObject *) memview); + } else { + PyGILState_STATE _gilstate = PyGILState_Ensure(); + Py_INCREF((PyObject *) memview); + PyGILState_Release(_gilstate); + } + } else { + __pyx_fatalerror("Acquisition count is %d (line %d)", + old_acquisition_count+1, lineno); + } + } +} +static CYTHON_INLINE void __Pyx_XCLEAR_MEMVIEW(__Pyx_memviewslice *memslice, + int have_gil, int lineno) { + __pyx_nonatomic_int_type old_acquisition_count; + struct __pyx_memoryview_obj *memview = memslice->memview; + if (unlikely(!memview || (PyObject *) memview == Py_None)) { + memslice->memview = NULL; + return; + } + old_acquisition_count = __pyx_sub_acquisition_count(memview); + memslice->data = NULL; + if (likely(old_acquisition_count > 1)) { + memslice->memview = NULL; + } else if (likely(old_acquisition_count == 1)) { + if (have_gil) { + Py_CLEAR(memslice->memview); + } else { + PyGILState_STATE _gilstate = PyGILState_Ensure(); + Py_CLEAR(memslice->memview); + PyGILState_Release(_gilstate); + } + } else { + __pyx_fatalerror("Acquisition count is %d (line %d)", + old_acquisition_count-1, lineno); + } +} + +/* CIntToPy */ + static CYTHON_INLINE PyObject* __Pyx_PyInt_From_int(int value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(int) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(int) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(int) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(int) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(int) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; +#if !CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030d0000 + return _PyLong_FromByteArray(bytes, sizeof(int), + little, !is_unsigned); +#else + PyObject *from_bytes, *result = NULL; + PyObject *py_bytes = NULL, *arg_tuple = NULL, *kwds = NULL, *order_str = NULL; + from_bytes = PyObject_GetAttrString((PyObject*)&PyLong_Type, "from_bytes"); + if (!from_bytes) return NULL; + py_bytes = PyBytes_FromStringAndSize((char*)bytes, sizeof(int)); + if (!py_bytes) goto limited_bad; + order_str = PyUnicode_FromString(little ? "little" : "big"); + if (!order_str) goto limited_bad; + arg_tuple = PyTuple_Pack(2, py_bytes, order_str); + if (!arg_tuple) goto limited_bad; + if (!is_unsigned) { + kwds = PyDict_New(); + if (!kwds) goto limited_bad; + if (PyDict_SetItemString(kwds, "signed", __Pyx_NewRef(Py_True))) goto limited_bad; + } + result = PyObject_Call(from_bytes, arg_tuple, kwds); + limited_bad: + Py_XDECREF(kwds); + Py_XDECREF(arg_tuple); + Py_XDECREF(order_str); + Py_XDECREF(py_bytes); + Py_XDECREF(from_bytes); + return result; +#endif + } +} + +/* CIntFromPyVerify */ + #define __PYX_VERIFY_RETURN_INT(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 0) +#define __PYX_VERIFY_RETURN_INT_EXC(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 1) +#define __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, exc)\ + {\ + func_type value = func_value;\ + if (sizeof(target_type) < sizeof(func_type)) {\ + if (unlikely(value != (func_type) (target_type) value)) {\ + func_type zero = 0;\ + if (exc && unlikely(value == (func_type)-1 && PyErr_Occurred()))\ + return (target_type) -1;\ + if (is_unsigned && unlikely(value < zero))\ + goto raise_neg_overflow;\ + else\ + goto raise_overflow;\ + }\ + }\ + return (target_type) value;\ + } + +/* CIntFromPy */ + static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(int) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(int, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (int) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 2 * PyLong_SHIFT)) { + return (int) (((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 3 * PyLong_SHIFT)) { + return (int) (((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 4 * PyLong_SHIFT)) { + return (int) (((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(int) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(int) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) ((((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) ((((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) ((((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(int) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + int val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (int) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (int) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (int) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (int) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(int) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(int) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((int) 1) << (sizeof(int) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (int) -1; + } + } else { + int val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (int) -1; + val = __Pyx_PyInt_As_int(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to int"); + return (int) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to int"); + return (int) -1; +} + +/* CIntFromPy */ + static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(long) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(long, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (long) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 2 * PyLong_SHIFT)) { + return (long) (((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 3 * PyLong_SHIFT)) { + return (long) (((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 4 * PyLong_SHIFT)) { + return (long) (((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(long) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(long) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) ((((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) ((((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) ((((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(long) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + long val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (long) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (long) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (long) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (long) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(long) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(long) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((long) 1) << (sizeof(long) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (long) -1; + } + } else { + long val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (long) -1; + val = __Pyx_PyInt_As_long(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to long"); + return (long) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to long"); + return (long) -1; +} + +/* CIntToPy */ + static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(long) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(long) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(long) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; +#if !CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030d0000 + return _PyLong_FromByteArray(bytes, sizeof(long), + little, !is_unsigned); +#else + PyObject *from_bytes, *result = NULL; + PyObject *py_bytes = NULL, *arg_tuple = NULL, *kwds = NULL, *order_str = NULL; + from_bytes = PyObject_GetAttrString((PyObject*)&PyLong_Type, "from_bytes"); + if (!from_bytes) return NULL; + py_bytes = PyBytes_FromStringAndSize((char*)bytes, sizeof(long)); + if (!py_bytes) goto limited_bad; + order_str = PyUnicode_FromString(little ? "little" : "big"); + if (!order_str) goto limited_bad; + arg_tuple = PyTuple_Pack(2, py_bytes, order_str); + if (!arg_tuple) goto limited_bad; + if (!is_unsigned) { + kwds = PyDict_New(); + if (!kwds) goto limited_bad; + if (PyDict_SetItemString(kwds, "signed", __Pyx_NewRef(Py_True))) goto limited_bad; + } + result = PyObject_Call(from_bytes, arg_tuple, kwds); + limited_bad: + Py_XDECREF(kwds); + Py_XDECREF(arg_tuple); + Py_XDECREF(order_str); + Py_XDECREF(py_bytes); + Py_XDECREF(from_bytes); + return result; +#endif + } +} + +/* CIntFromPy */ + static CYTHON_INLINE char __Pyx_PyInt_As_char(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const char neg_one = (char) -1, const_zero = (char) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(char) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(char, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (char) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(char, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(char) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) >= 2 * PyLong_SHIFT)) { + return (char) (((((char)digits[1]) << PyLong_SHIFT) | (char)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(char) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) >= 3 * PyLong_SHIFT)) { + return (char) (((((((char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(char) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) >= 4 * PyLong_SHIFT)) { + return (char) (((((((((char)digits[3]) << PyLong_SHIFT) | (char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (char) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(char) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(char, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(char) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(char, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(char, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(char) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 2 * PyLong_SHIFT)) { + return (char) (((char)-1)*(((((char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(char) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 2 * PyLong_SHIFT)) { + return (char) ((((((char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(char) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 3 * PyLong_SHIFT)) { + return (char) (((char)-1)*(((((((char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(char) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 3 * PyLong_SHIFT)) { + return (char) ((((((((char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(char) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 4 * PyLong_SHIFT)) { + return (char) (((char)-1)*(((((((((char)digits[3]) << PyLong_SHIFT) | (char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(char) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 4 * PyLong_SHIFT)) { + return (char) ((((((((((char)digits[3]) << PyLong_SHIFT) | (char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(char) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(char, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(char) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(char, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + char val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (char) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (char) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (char) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (char) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (char) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(char) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((char) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(char) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((char) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((char) 1) << (sizeof(char) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (char) -1; + } + } else { + char val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (char) -1; + val = __Pyx_PyInt_As_char(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to char"); + return (char) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to char"); + return (char) -1; +} + +/* FormatTypeName */ + #if CYTHON_COMPILING_IN_LIMITED_API +static __Pyx_TypeName +__Pyx_PyType_GetName(PyTypeObject* tp) +{ + PyObject *name = __Pyx_PyObject_GetAttrStr((PyObject *)tp, + __pyx_n_s_name_2); + if (unlikely(name == NULL) || unlikely(!PyUnicode_Check(name))) { + PyErr_Clear(); + Py_XDECREF(name); + name = __Pyx_NewRef(__pyx_n_s__30); + } + return name; +} +#endif + +/* CheckBinaryVersion */ + static unsigned long __Pyx_get_runtime_version(void) { +#if __PYX_LIMITED_VERSION_HEX >= 0x030B00A4 + return Py_Version & ~0xFFUL; +#else + const char* rt_version = Py_GetVersion(); + unsigned long version = 0; + unsigned long factor = 0x01000000UL; + unsigned int digit = 0; + int i = 0; + while (factor) { + while ('0' <= rt_version[i] && rt_version[i] <= '9') { + digit = digit * 10 + (unsigned int) (rt_version[i] - '0'); + ++i; + } + version += factor * digit; + if (rt_version[i] != '.') + break; + digit = 0; + factor >>= 8; + ++i; + } + return version; +#endif +} +static int __Pyx_check_binary_version(unsigned long ct_version, unsigned long rt_version, int allow_newer) { + const unsigned long MAJOR_MINOR = 0xFFFF0000UL; + if ((rt_version & MAJOR_MINOR) == (ct_version & MAJOR_MINOR)) + return 0; + if (likely(allow_newer && (rt_version & MAJOR_MINOR) > (ct_version & MAJOR_MINOR))) + return 1; + { + char message[200]; + PyOS_snprintf(message, sizeof(message), + "compile time Python version %d.%d " + "of module '%.100s' " + "%s " + "runtime version %d.%d", + (int) (ct_version >> 24), (int) ((ct_version >> 16) & 0xFF), + __Pyx_MODULE_NAME, + (allow_newer) ? "was newer than" : "does not match", + (int) (rt_version >> 24), (int) ((rt_version >> 16) & 0xFF) + ); + return PyErr_WarnEx(NULL, message, 1); + } +} + +/* InitStrings */ + #if PY_MAJOR_VERSION >= 3 +static int __Pyx_InitString(__Pyx_StringTabEntry t, PyObject **str) { + if (t.is_unicode | t.is_str) { + if (t.intern) { + *str = PyUnicode_InternFromString(t.s); + } else if (t.encoding) { + *str = PyUnicode_Decode(t.s, t.n - 1, t.encoding, NULL); + } else { + *str = PyUnicode_FromStringAndSize(t.s, t.n - 1); + } + } else { + *str = PyBytes_FromStringAndSize(t.s, t.n - 1); + } + if (!*str) + return -1; + if (PyObject_Hash(*str) == -1) + return -1; + return 0; +} +#endif +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t) { + while (t->p) { + #if PY_MAJOR_VERSION >= 3 + __Pyx_InitString(*t, t->p); + #else + if (t->is_unicode) { + *t->p = PyUnicode_DecodeUTF8(t->s, t->n - 1, NULL); + } else if (t->intern) { + *t->p = PyString_InternFromString(t->s); + } else { + *t->p = PyString_FromStringAndSize(t->s, t->n - 1); + } + if (!*t->p) + return -1; + if (PyObject_Hash(*t->p) == -1) + return -1; + #endif + ++t; + } + return 0; +} + +#include +static CYTHON_INLINE Py_ssize_t __Pyx_ssize_strlen(const char *s) { + size_t len = strlen(s); + if (unlikely(len > (size_t) PY_SSIZE_T_MAX)) { + PyErr_SetString(PyExc_OverflowError, "byte string is too long"); + return -1; + } + return (Py_ssize_t) len; +} +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char* c_str) { + Py_ssize_t len = __Pyx_ssize_strlen(c_str); + if (unlikely(len < 0)) return NULL; + return __Pyx_PyUnicode_FromStringAndSize(c_str, len); +} +static CYTHON_INLINE PyObject* __Pyx_PyByteArray_FromString(const char* c_str) { + Py_ssize_t len = __Pyx_ssize_strlen(c_str); + if (unlikely(len < 0)) return NULL; + return PyByteArray_FromStringAndSize(c_str, len); +} +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject* o) { + Py_ssize_t ignore; + return __Pyx_PyObject_AsStringAndSize(o, &ignore); +} +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +#if !CYTHON_PEP393_ENABLED +static const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + char* defenc_c; + PyObject* defenc = _PyUnicode_AsDefaultEncodedString(o, NULL); + if (!defenc) return NULL; + defenc_c = PyBytes_AS_STRING(defenc); +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + { + char* end = defenc_c + PyBytes_GET_SIZE(defenc); + char* c; + for (c = defenc_c; c < end; c++) { + if ((unsigned char) (*c) >= 128) { + PyUnicode_AsASCIIString(o); + return NULL; + } + } + } +#endif + *length = PyBytes_GET_SIZE(defenc); + return defenc_c; +} +#else +static CYTHON_INLINE const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + if (unlikely(__Pyx_PyUnicode_READY(o) == -1)) return NULL; +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + if (likely(PyUnicode_IS_ASCII(o))) { + *length = PyUnicode_GET_LENGTH(o); + return PyUnicode_AsUTF8(o); + } else { + PyUnicode_AsASCIIString(o); + return NULL; + } +#else + return PyUnicode_AsUTF8AndSize(o, length); +#endif +} +#endif +#endif +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject* o, Py_ssize_t *length) { +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT + if ( +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + __Pyx_sys_getdefaultencoding_not_ascii && +#endif + PyUnicode_Check(o)) { + return __Pyx_PyUnicode_AsStringAndSize(o, length); + } else +#endif +#if (!CYTHON_COMPILING_IN_PYPY && !CYTHON_COMPILING_IN_LIMITED_API) || (defined(PyByteArray_AS_STRING) && defined(PyByteArray_GET_SIZE)) + if (PyByteArray_Check(o)) { + *length = PyByteArray_GET_SIZE(o); + return PyByteArray_AS_STRING(o); + } else +#endif + { + char* result; + int r = PyBytes_AsStringAndSize(o, &result, length); + if (unlikely(r < 0)) { + return NULL; + } else { + return result; + } + } +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject* x) { + int is_true = x == Py_True; + if (is_true | (x == Py_False) | (x == Py_None)) return is_true; + else return PyObject_IsTrue(x); +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject* x) { + int retval; + if (unlikely(!x)) return -1; + retval = __Pyx_PyObject_IsTrue(x); + Py_DECREF(x); + return retval; +} +static PyObject* __Pyx_PyNumber_IntOrLongWrongResultType(PyObject* result, const char* type_name) { + __Pyx_TypeName result_type_name = __Pyx_PyType_GetName(Py_TYPE(result)); +#if PY_MAJOR_VERSION >= 3 + if (PyLong_Check(result)) { + if (PyErr_WarnFormat(PyExc_DeprecationWarning, 1, + "__int__ returned non-int (type " __Pyx_FMT_TYPENAME "). " + "The ability to return an instance of a strict subclass of int is deprecated, " + "and may be removed in a future version of Python.", + result_type_name)) { + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; + } + __Pyx_DECREF_TypeName(result_type_name); + return result; + } +#endif + PyErr_Format(PyExc_TypeError, + "__%.4s__ returned non-%.4s (type " __Pyx_FMT_TYPENAME ")", + type_name, type_name, result_type_name); + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x) { +#if CYTHON_USE_TYPE_SLOTS + PyNumberMethods *m; +#endif + const char *name = NULL; + PyObject *res = NULL; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x) || PyLong_Check(x))) +#else + if (likely(PyLong_Check(x))) +#endif + return __Pyx_NewRef(x); +#if CYTHON_USE_TYPE_SLOTS + m = Py_TYPE(x)->tp_as_number; + #if PY_MAJOR_VERSION < 3 + if (m && m->nb_int) { + name = "int"; + res = m->nb_int(x); + } + else if (m && m->nb_long) { + name = "long"; + res = m->nb_long(x); + } + #else + if (likely(m && m->nb_int)) { + name = "int"; + res = m->nb_int(x); + } + #endif +#else + if (!PyBytes_CheckExact(x) && !PyUnicode_CheckExact(x)) { + res = PyNumber_Int(x); + } +#endif + if (likely(res)) { +#if PY_MAJOR_VERSION < 3 + if (unlikely(!PyInt_Check(res) && !PyLong_Check(res))) { +#else + if (unlikely(!PyLong_CheckExact(res))) { +#endif + return __Pyx_PyNumber_IntOrLongWrongResultType(res, name); + } + } + else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_TypeError, + "an integer is required"); + } + return res; +} +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject* b) { + Py_ssize_t ival; + PyObject *x; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_CheckExact(b))) { + if (sizeof(Py_ssize_t) >= sizeof(long)) + return PyInt_AS_LONG(b); + else + return PyInt_AsSsize_t(b); + } +#endif + if (likely(PyLong_CheckExact(b))) { + #if CYTHON_USE_PYLONG_INTERNALS + if (likely(__Pyx_PyLong_IsCompact(b))) { + return __Pyx_PyLong_CompactValue(b); + } else { + const digit* digits = __Pyx_PyLong_Digits(b); + const Py_ssize_t size = __Pyx_PyLong_SignedDigitCount(b); + switch (size) { + case 2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return (Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + } + } + #endif + return PyLong_AsSsize_t(b); + } + x = PyNumber_Index(b); + if (!x) return -1; + ival = PyInt_AsSsize_t(x); + Py_DECREF(x); + return ival; +} +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject* o) { + if (sizeof(Py_hash_t) == sizeof(Py_ssize_t)) { + return (Py_hash_t) __Pyx_PyIndex_AsSsize_t(o); +#if PY_MAJOR_VERSION < 3 + } else if (likely(PyInt_CheckExact(o))) { + return PyInt_AS_LONG(o); +#endif + } else { + Py_ssize_t ival; + PyObject *x; + x = PyNumber_Index(o); + if (!x) return -1; + ival = PyInt_AsLong(x); + Py_DECREF(x); + return ival; + } +} +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b) { + return b ? __Pyx_NewRef(Py_True) : __Pyx_NewRef(Py_False); +} +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t ival) { + return PyInt_FromSize_t(ival); +} + + +/* #### Code section: utility_code_pragmas_end ### */ +#ifdef _MSC_VER +#pragma warning( pop ) +#endif + + + +/* #### Code section: end ### */ +#endif /* Py_PYTHON_H */ diff --git a/selfdrive/modeld/runners/runmodel_pyx.so b/selfdrive/modeld/runners/runmodel_pyx.so new file mode 100755 index 0000000..c32588f Binary files /dev/null and b/selfdrive/modeld/runners/runmodel_pyx.so differ diff --git a/selfdrive/modeld/runners/snpemodel.cc b/selfdrive/modeld/runners/snpemodel.cc deleted file mode 100644 index 15c1db0..0000000 --- a/selfdrive/modeld/runners/snpemodel.cc +++ /dev/null @@ -1,116 +0,0 @@ -#pragma clang diagnostic ignored "-Wexceptions" - -#include "selfdrive/modeld/runners/snpemodel.h" - -#include -#include -#include -#include -#include - -#include "common/util.h" -#include "common/timing.h" - -void PrintErrorStringAndExit() { - std::cerr << zdl::DlSystem::getLastErrorString() << std::endl; - std::exit(EXIT_FAILURE); -} - -SNPEModel::SNPEModel(const std::string path, float *_output, size_t _output_size, int runtime, bool _use_tf8, cl_context context) { - output = _output; - output_size = _output_size; - use_tf8 = _use_tf8; - -#ifdef QCOM2 - if (runtime == USE_GPU_RUNTIME) { - snpe_runtime = zdl::DlSystem::Runtime_t::GPU; - } else if (runtime == USE_DSP_RUNTIME) { - snpe_runtime = zdl::DlSystem::Runtime_t::DSP; - } else { - snpe_runtime = zdl::DlSystem::Runtime_t::CPU; - } - assert(zdl::SNPE::SNPEFactory::isRuntimeAvailable(snpe_runtime)); -#endif - model_data = util::read_file(path); - assert(model_data.size() > 0); - - // load model - std::unique_ptr container = zdl::DlContainer::IDlContainer::open((uint8_t*)model_data.data(), model_data.size()); - if (!container) { PrintErrorStringAndExit(); } - LOGW("loaded model with size: %lu", model_data.size()); - - // create model runner - zdl::SNPE::SNPEBuilder snpe_builder(container.get()); - while (!snpe) { -#ifdef QCOM2 - snpe = snpe_builder.setOutputLayers({}) - .setRuntimeProcessor(snpe_runtime) - .setUseUserSuppliedBuffers(true) - .setPerformanceProfile(zdl::DlSystem::PerformanceProfile_t::HIGH_PERFORMANCE) - .build(); -#else - snpe = snpe_builder.setOutputLayers({}) - .setUseUserSuppliedBuffers(true) - .setPerformanceProfile(zdl::DlSystem::PerformanceProfile_t::HIGH_PERFORMANCE) - .build(); -#endif - if (!snpe) std::cerr << zdl::DlSystem::getLastErrorString() << std::endl; - } - - // create output buffer - zdl::DlSystem::UserBufferEncodingFloat ub_encoding_float; - zdl::DlSystem::IUserBufferFactory &ub_factory = zdl::SNPE::SNPEFactory::getUserBufferFactory(); - - const auto &output_tensor_names_opt = snpe->getOutputTensorNames(); - if (!output_tensor_names_opt) throw std::runtime_error("Error obtaining output tensor names"); - const auto &output_tensor_names = *output_tensor_names_opt; - assert(output_tensor_names.size() == 1); - const char *output_tensor_name = output_tensor_names.at(0); - const zdl::DlSystem::TensorShape &buffer_shape = snpe->getInputOutputBufferAttributes(output_tensor_name)->getDims(); - if (output_size != 0) { - assert(output_size == buffer_shape[1]); - } else { - output_size = buffer_shape[1]; - } - std::vector output_strides = {output_size * sizeof(float), sizeof(float)}; - output_buffer = ub_factory.createUserBuffer(output, output_size * sizeof(float), output_strides, &ub_encoding_float); - output_map.add(output_tensor_name, output_buffer.get()); -} - -void SNPEModel::addInput(const std::string name, float *buffer, int size) { - const int idx = inputs.size(); - const auto &input_tensor_names_opt = snpe->getInputTensorNames(); - if (!input_tensor_names_opt) throw std::runtime_error("Error obtaining input tensor names"); - const auto &input_tensor_names = *input_tensor_names_opt; - const char *input_tensor_name = input_tensor_names.at(idx); - const bool input_tf8 = use_tf8 && strcmp(input_tensor_name, "input_img") == 0; // TODO: This is a terrible hack, get rid of this name check both here and in onnx_runner.py - LOGW("adding index %d: %s", idx, input_tensor_name); - - zdl::DlSystem::UserBufferEncodingFloat ub_encoding_float; - zdl::DlSystem::UserBufferEncodingTf8 ub_encoding_tf8(0, 1./255); // network takes 0-1 - zdl::DlSystem::IUserBufferFactory &ub_factory = zdl::SNPE::SNPEFactory::getUserBufferFactory(); - zdl::DlSystem::UserBufferEncoding *input_encoding = input_tf8 ? (zdl::DlSystem::UserBufferEncoding*)&ub_encoding_tf8 : (zdl::DlSystem::UserBufferEncoding*)&ub_encoding_float; - - const auto &buffer_shape_opt = snpe->getInputDimensions(input_tensor_name); - const zdl::DlSystem::TensorShape &buffer_shape = *buffer_shape_opt; - size_t size_of_input = input_tf8 ? sizeof(uint8_t) : sizeof(float); - std::vector strides(buffer_shape.rank()); - strides[strides.size() - 1] = size_of_input; - size_t product = 1; - for (size_t i = 0; i < buffer_shape.rank(); i++) product *= buffer_shape[i]; - size_t stride = strides[strides.size() - 1]; - for (size_t i = buffer_shape.rank() - 1; i > 0; i--) { - stride *= buffer_shape[i]; - strides[i-1] = stride; - } - - auto input_buffer = ub_factory.createUserBuffer(buffer, product*size_of_input, strides, input_encoding); - input_map.add(input_tensor_name, input_buffer.get()); - inputs.push_back(std::unique_ptr(new SNPEModelInput(name, buffer, size, std::move(input_buffer)))); -} - -void SNPEModel::execute() { - if (!snpe->execute(input_map, output_map)) { - PrintErrorStringAndExit(); - } -} diff --git a/selfdrive/modeld/runners/snpemodel.h b/selfdrive/modeld/runners/snpemodel.h deleted file mode 100644 index 86b2c86..0000000 --- a/selfdrive/modeld/runners/snpemodel.h +++ /dev/null @@ -1,52 +0,0 @@ -#pragma once -#pragma clang diagnostic ignored "-Wdeprecated-declarations" - -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include "selfdrive/modeld/runners/runmodel.h" - -struct SNPEModelInput : public ModelInput { - std::unique_ptr snpe_buffer; - - SNPEModelInput(const std::string _name, float *_buffer, int _size, std::unique_ptr _snpe_buffer) : ModelInput(_name, _buffer, _size), snpe_buffer(std::move(_snpe_buffer)) {} - void setBuffer(float *_buffer, int _size) { - ModelInput::setBuffer(_buffer, _size); - assert(snpe_buffer->setBufferAddress(_buffer) == true); - } -}; - -class SNPEModel : public RunModel { -public: - SNPEModel(const std::string path, float *_output, size_t _output_size, int runtime, bool use_tf8 = false, cl_context context = NULL); - void addInput(const std::string name, float *buffer, int size); - void execute(); - -private: - std::string model_data; - -#ifdef QCOM2 - zdl::DlSystem::Runtime_t snpe_runtime; -#endif - - // snpe model stuff - std::unique_ptr snpe; - zdl::DlSystem::UserBufferMap input_map; - zdl::DlSystem::UserBufferMap output_map; - std::unique_ptr output_buffer; - - bool use_tf8; - float *output; - size_t output_size; -}; diff --git a/selfdrive/modeld/runners/snpemodel_pyx.cpp b/selfdrive/modeld/runners/snpemodel_pyx.cpp new file mode 100644 index 0000000..965b680 --- /dev/null +++ b/selfdrive/modeld/runners/snpemodel_pyx.cpp @@ -0,0 +1,27817 @@ +/* Generated by Cython 3.0.8 */ + +/* BEGIN: Cython Metadata +{ + "distutils": { + "depends": [ + "cereal/visionipc/visionbuf.h", + "cereal/visionipc/visionipc.h", + "cereal/visionipc/visionipc_client.h", + "cereal/visionipc/visionipc_server.h", + "selfdrive/modeld/runners/runmodel.h", + "selfdrive/modeld/runners/snpemodel.h" + ], + "language": "c++", + "name": "selfdrive.modeld.runners.snpemodel_pyx", + "sources": [ + "/data/openpilot/selfdrive/modeld/runners/snpemodel_pyx.pyx" + ] + }, + "module_name": "selfdrive.modeld.runners.snpemodel_pyx" +} +END: Cython Metadata */ + +#ifndef PY_SSIZE_T_CLEAN +#define PY_SSIZE_T_CLEAN +#endif /* PY_SSIZE_T_CLEAN */ +#if defined(CYTHON_LIMITED_API) && 0 + #ifndef Py_LIMITED_API + #if CYTHON_LIMITED_API+0 > 0x03030000 + #define Py_LIMITED_API CYTHON_LIMITED_API + #else + #define Py_LIMITED_API 0x03030000 + #endif + #endif +#endif + +#include "Python.h" +#ifndef Py_PYTHON_H + #error Python headers needed to compile C extensions, please install development version of Python. +#elif PY_VERSION_HEX < 0x02070000 || (0x03000000 <= PY_VERSION_HEX && PY_VERSION_HEX < 0x03030000) + #error Cython requires Python 2.7+ or Python 3.3+. +#else +#if defined(CYTHON_LIMITED_API) && CYTHON_LIMITED_API +#define __PYX_EXTRA_ABI_MODULE_NAME "limited" +#else +#define __PYX_EXTRA_ABI_MODULE_NAME "" +#endif +#define CYTHON_ABI "3_0_8" __PYX_EXTRA_ABI_MODULE_NAME +#define __PYX_ABI_MODULE_NAME "_cython_" CYTHON_ABI +#define __PYX_TYPE_MODULE_PREFIX __PYX_ABI_MODULE_NAME "." +#define CYTHON_HEX_VERSION 0x030008F0 +#define CYTHON_FUTURE_DIVISION 1 +#include +#ifndef offsetof + #define offsetof(type, member) ( (size_t) & ((type*)0) -> member ) +#endif +#if !defined(_WIN32) && !defined(WIN32) && !defined(MS_WINDOWS) + #ifndef __stdcall + #define __stdcall + #endif + #ifndef __cdecl + #define __cdecl + #endif + #ifndef __fastcall + #define __fastcall + #endif +#endif +#ifndef DL_IMPORT + #define DL_IMPORT(t) t +#endif +#ifndef DL_EXPORT + #define DL_EXPORT(t) t +#endif +#define __PYX_COMMA , +#ifndef HAVE_LONG_LONG + #define HAVE_LONG_LONG +#endif +#ifndef PY_LONG_LONG + #define PY_LONG_LONG LONG_LONG +#endif +#ifndef Py_HUGE_VAL + #define Py_HUGE_VAL HUGE_VAL +#endif +#define __PYX_LIMITED_VERSION_HEX PY_VERSION_HEX +#if defined(GRAALVM_PYTHON) + /* For very preliminary testing purposes. Most variables are set the same as PyPy. + The existence of this section does not imply that anything works or is even tested */ + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 1 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(PYPY_VERSION) + #define CYTHON_COMPILING_IN_PYPY 1 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #ifndef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #endif + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #if PY_VERSION_HEX < 0x03090000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE (PY_VERSION_HEX >= 0x030400a1 && PYPY_VERSION_NUM >= 0x07030C00) + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(CYTHON_LIMITED_API) + #ifdef Py_LIMITED_API + #undef __PYX_LIMITED_VERSION_HEX + #define __PYX_LIMITED_VERSION_HEX Py_LIMITED_API + #endif + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 1 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_CLINE_IN_TRACEBACK + #define CYTHON_CLINE_IN_TRACEBACK 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 1 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #endif + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 1 + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(Py_GIL_DISABLED) || defined(Py_NOGIL) + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 1 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #ifndef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 +#else + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 1 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #ifndef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #endif + #ifndef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 1 + #endif + #if PY_MAJOR_VERSION < 3 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #ifndef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 1 + #endif + #ifndef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 1 + #endif + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #if PY_VERSION_HEX < 0x030300F0 || PY_VERSION_HEX >= 0x030B00A2 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #elif !defined(CYTHON_USE_UNICODE_WRITER) + #define CYTHON_USE_UNICODE_WRITER 1 + #endif + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #ifndef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 1 + #endif + #ifndef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL (PY_MAJOR_VERSION < 3 || PY_VERSION_HEX >= 0x03060000 && PY_VERSION_HEX < 0x030C00A6) + #endif + #ifndef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL (PY_VERSION_HEX >= 0x030700A1) + #endif + #ifndef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 1 + #endif + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #endif + #if PY_VERSION_HEX < 0x030400a1 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #elif !defined(CYTHON_USE_TP_FINALIZE) + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #if PY_VERSION_HEX < 0x030600B1 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #elif !defined(CYTHON_USE_DICT_VERSIONS) + #define CYTHON_USE_DICT_VERSIONS (PY_VERSION_HEX < 0x030C00A5) + #endif + #if PY_VERSION_HEX < 0x030700A3 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #elif !defined(CYTHON_USE_EXC_INFO_STACK) + #define CYTHON_USE_EXC_INFO_STACK 1 + #endif + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 1 + #endif +#endif +#if !defined(CYTHON_FAST_PYCCALL) +#define CYTHON_FAST_PYCCALL (CYTHON_FAST_PYCALL && PY_VERSION_HEX >= 0x030600B1) +#endif +#if !defined(CYTHON_VECTORCALL) +#define CYTHON_VECTORCALL (CYTHON_FAST_PYCCALL && PY_VERSION_HEX >= 0x030800B1) +#endif +#define CYTHON_BACKPORT_VECTORCALL (CYTHON_METH_FASTCALL && PY_VERSION_HEX < 0x030800B1) +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_MAJOR_VERSION < 3 + #include "longintrepr.h" + #endif + #undef SHIFT + #undef BASE + #undef MASK + #ifdef SIZEOF_VOID_P + enum { __pyx_check_sizeof_voidp = 1 / (int)(SIZEOF_VOID_P == sizeof(void*)) }; + #endif +#endif +#ifndef __has_attribute + #define __has_attribute(x) 0 +#endif +#ifndef __has_cpp_attribute + #define __has_cpp_attribute(x) 0 +#endif +#ifndef CYTHON_RESTRICT + #if defined(__GNUC__) + #define CYTHON_RESTRICT __restrict__ + #elif defined(_MSC_VER) && _MSC_VER >= 1400 + #define CYTHON_RESTRICT __restrict + #elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define CYTHON_RESTRICT restrict + #else + #define CYTHON_RESTRICT + #endif +#endif +#ifndef CYTHON_UNUSED + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(maybe_unused) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(maybe_unused) + #define CYTHON_UNUSED [[maybe_unused]] + #endif + #endif + #endif +#endif +#ifndef CYTHON_UNUSED +# if defined(__GNUC__) +# if !(defined(__cplusplus)) || (__GNUC__ > 3 || (__GNUC__ == 3 && __GNUC_MINOR__ >= 4)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +# elif defined(__ICC) || (defined(__INTEL_COMPILER) && !defined(_MSC_VER)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +#endif +#ifndef CYTHON_UNUSED_VAR +# if defined(__cplusplus) + template void CYTHON_UNUSED_VAR( const T& ) { } +# else +# define CYTHON_UNUSED_VAR(x) (void)(x) +# endif +#endif +#ifndef CYTHON_MAYBE_UNUSED_VAR + #define CYTHON_MAYBE_UNUSED_VAR(x) CYTHON_UNUSED_VAR(x) +#endif +#ifndef CYTHON_NCP_UNUSED +# if CYTHON_COMPILING_IN_CPYTHON +# define CYTHON_NCP_UNUSED +# else +# define CYTHON_NCP_UNUSED CYTHON_UNUSED +# endif +#endif +#ifndef CYTHON_USE_CPP_STD_MOVE + #if defined(__cplusplus) && (\ + __cplusplus >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1600)) + #define CYTHON_USE_CPP_STD_MOVE 1 + #else + #define CYTHON_USE_CPP_STD_MOVE 0 + #endif +#endif +#define __Pyx_void_to_None(void_result) ((void)(void_result), Py_INCREF(Py_None), Py_None) +#ifdef _MSC_VER + #ifndef _MSC_STDINT_H_ + #if _MSC_VER < 1300 + typedef unsigned char uint8_t; + typedef unsigned short uint16_t; + typedef unsigned int uint32_t; + #else + typedef unsigned __int8 uint8_t; + typedef unsigned __int16 uint16_t; + typedef unsigned __int32 uint32_t; + #endif + #endif + #if _MSC_VER < 1300 + #ifdef _WIN64 + typedef unsigned long long __pyx_uintptr_t; + #else + typedef unsigned int __pyx_uintptr_t; + #endif + #else + #ifdef _WIN64 + typedef unsigned __int64 __pyx_uintptr_t; + #else + typedef unsigned __int32 __pyx_uintptr_t; + #endif + #endif +#else + #include + typedef uintptr_t __pyx_uintptr_t; +#endif +#ifndef CYTHON_FALLTHROUGH + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(fallthrough) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(fallthrough) + #define CYTHON_FALLTHROUGH [[fallthrough]] + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_cpp_attribute(clang::fallthrough) + #define CYTHON_FALLTHROUGH [[clang::fallthrough]] + #elif __has_cpp_attribute(gnu::fallthrough) + #define CYTHON_FALLTHROUGH [[gnu::fallthrough]] + #endif + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_attribute(fallthrough) + #define CYTHON_FALLTHROUGH __attribute__((fallthrough)) + #else + #define CYTHON_FALLTHROUGH + #endif + #endif + #if defined(__clang__) && defined(__apple_build_version__) + #if __apple_build_version__ < 7000000 + #undef CYTHON_FALLTHROUGH + #define CYTHON_FALLTHROUGH + #endif + #endif +#endif +#ifdef __cplusplus + template + struct __PYX_IS_UNSIGNED_IMPL {static const bool value = T(0) < T(-1);}; + #define __PYX_IS_UNSIGNED(type) (__PYX_IS_UNSIGNED_IMPL::value) +#else + #define __PYX_IS_UNSIGNED(type) (((type)-1) > 0) +#endif +#if CYTHON_COMPILING_IN_PYPY == 1 + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x030A0000) +#else + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x03090000) +#endif +#define __PYX_REINTERPRET_FUNCION(func_pointer, other_pointer) ((func_pointer)(void(*)(void))(other_pointer)) + +#ifndef __cplusplus + #error "Cython files generated with the C++ option must be compiled with a C++ compiler." +#endif +#ifndef CYTHON_INLINE + #if defined(__clang__) + #define CYTHON_INLINE __inline__ __attribute__ ((__unused__)) + #else + #define CYTHON_INLINE inline + #endif +#endif +template +void __Pyx_call_destructor(T& x) { + x.~T(); +} +template +class __Pyx_FakeReference { + public: + __Pyx_FakeReference() : ptr(NULL) { } + __Pyx_FakeReference(const T& ref) : ptr(const_cast(&ref)) { } + T *operator->() { return ptr; } + T *operator&() { return ptr; } + operator T&() { return *ptr; } + template bool operator ==(const U& other) const { return *ptr == other; } + template bool operator !=(const U& other) const { return *ptr != other; } + template bool operator==(const __Pyx_FakeReference& other) const { return *ptr == *other.ptr; } + template bool operator!=(const __Pyx_FakeReference& other) const { return *ptr != *other.ptr; } + private: + T *ptr; +}; + +#define __PYX_BUILD_PY_SSIZE_T "n" +#define CYTHON_FORMAT_SSIZE_T "z" +#if PY_MAJOR_VERSION < 3 + #define __Pyx_BUILTIN_MODULE_NAME "__builtin__" + #define __Pyx_DefaultClassType PyClass_Type + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a+k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_BUILTIN_MODULE_NAME "builtins" + #define __Pyx_DefaultClassType PyType_Type +#if CYTHON_COMPILING_IN_LIMITED_API + static CYTHON_INLINE PyObject* __Pyx_PyCode_New(int a, int p, int k, int l, int s, int f, + PyObject *code, PyObject *c, PyObject* n, PyObject *v, + PyObject *fv, PyObject *cell, PyObject* fn, + PyObject *name, int fline, PyObject *lnos) { + PyObject *exception_table = NULL; + PyObject *types_module=NULL, *code_type=NULL, *result=NULL; + #if __PYX_LIMITED_VERSION_HEX < 0x030B0000 + PyObject *version_info; + PyObject *py_minor_version = NULL; + #endif + long minor_version = 0; + PyObject *type, *value, *traceback; + PyErr_Fetch(&type, &value, &traceback); + #if __PYX_LIMITED_VERSION_HEX >= 0x030B0000 + minor_version = 11; + #else + if (!(version_info = PySys_GetObject("version_info"))) goto end; + if (!(py_minor_version = PySequence_GetItem(version_info, 1))) goto end; + minor_version = PyLong_AsLong(py_minor_version); + Py_DECREF(py_minor_version); + if (minor_version == -1 && PyErr_Occurred()) goto end; + #endif + if (!(types_module = PyImport_ImportModule("types"))) goto end; + if (!(code_type = PyObject_GetAttrString(types_module, "CodeType"))) goto end; + if (minor_version <= 7) { + (void)p; + result = PyObject_CallFunction(code_type, "iiiiiOOOOOOiOO", a, k, l, s, f, code, + c, n, v, fn, name, fline, lnos, fv, cell); + } else if (minor_version <= 10) { + result = PyObject_CallFunction(code_type, "iiiiiiOOOOOOiOO", a,p, k, l, s, f, code, + c, n, v, fn, name, fline, lnos, fv, cell); + } else { + if (!(exception_table = PyBytes_FromStringAndSize(NULL, 0))) goto end; + result = PyObject_CallFunction(code_type, "iiiiiiOOOOOOOiOO", a,p, k, l, s, f, code, + c, n, v, fn, name, name, fline, lnos, exception_table, fv, cell); + } + end: + Py_XDECREF(code_type); + Py_XDECREF(exception_table); + Py_XDECREF(types_module); + if (type) { + PyErr_Restore(type, value, traceback); + } + return result; + } + #ifndef CO_OPTIMIZED + #define CO_OPTIMIZED 0x0001 + #endif + #ifndef CO_NEWLOCALS + #define CO_NEWLOCALS 0x0002 + #endif + #ifndef CO_VARARGS + #define CO_VARARGS 0x0004 + #endif + #ifndef CO_VARKEYWORDS + #define CO_VARKEYWORDS 0x0008 + #endif + #ifndef CO_ASYNC_GENERATOR + #define CO_ASYNC_GENERATOR 0x0200 + #endif + #ifndef CO_GENERATOR + #define CO_GENERATOR 0x0020 + #endif + #ifndef CO_COROUTINE + #define CO_COROUTINE 0x0080 + #endif +#elif PY_VERSION_HEX >= 0x030B0000 + static CYTHON_INLINE PyCodeObject* __Pyx_PyCode_New(int a, int p, int k, int l, int s, int f, + PyObject *code, PyObject *c, PyObject* n, PyObject *v, + PyObject *fv, PyObject *cell, PyObject* fn, + PyObject *name, int fline, PyObject *lnos) { + PyCodeObject *result; + PyObject *empty_bytes = PyBytes_FromStringAndSize("", 0); + if (!empty_bytes) return NULL; + result = + #if PY_VERSION_HEX >= 0x030C0000 + PyUnstable_Code_NewWithPosOnlyArgs + #else + PyCode_NewWithPosOnlyArgs + #endif + (a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, name, fline, lnos, empty_bytes); + Py_DECREF(empty_bytes); + return result; + } +#elif PY_VERSION_HEX >= 0x030800B2 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_NewWithPosOnlyArgs(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#endif +#endif +#if PY_VERSION_HEX >= 0x030900A4 || defined(Py_IS_TYPE) + #define __Pyx_IS_TYPE(ob, type) Py_IS_TYPE(ob, type) +#else + #define __Pyx_IS_TYPE(ob, type) (((const PyObject*)ob)->ob_type == (type)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_Is) + #define __Pyx_Py_Is(x, y) Py_Is(x, y) +#else + #define __Pyx_Py_Is(x, y) ((x) == (y)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsNone) + #define __Pyx_Py_IsNone(ob) Py_IsNone(ob) +#else + #define __Pyx_Py_IsNone(ob) __Pyx_Py_Is((ob), Py_None) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsTrue) + #define __Pyx_Py_IsTrue(ob) Py_IsTrue(ob) +#else + #define __Pyx_Py_IsTrue(ob) __Pyx_Py_Is((ob), Py_True) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsFalse) + #define __Pyx_Py_IsFalse(ob) Py_IsFalse(ob) +#else + #define __Pyx_Py_IsFalse(ob) __Pyx_Py_Is((ob), Py_False) +#endif +#define __Pyx_NoneAsNull(obj) (__Pyx_Py_IsNone(obj) ? NULL : (obj)) +#if PY_VERSION_HEX >= 0x030900F0 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_GC_IsFinalized(o) PyObject_GC_IsFinalized(o) +#else + #define __Pyx_PyObject_GC_IsFinalized(o) _PyGC_FINALIZED(o) +#endif +#ifndef CO_COROUTINE + #define CO_COROUTINE 0x80 +#endif +#ifndef CO_ASYNC_GENERATOR + #define CO_ASYNC_GENERATOR 0x200 +#endif +#ifndef Py_TPFLAGS_CHECKTYPES + #define Py_TPFLAGS_CHECKTYPES 0 +#endif +#ifndef Py_TPFLAGS_HAVE_INDEX + #define Py_TPFLAGS_HAVE_INDEX 0 +#endif +#ifndef Py_TPFLAGS_HAVE_NEWBUFFER + #define Py_TPFLAGS_HAVE_NEWBUFFER 0 +#endif +#ifndef Py_TPFLAGS_HAVE_FINALIZE + #define Py_TPFLAGS_HAVE_FINALIZE 0 +#endif +#ifndef Py_TPFLAGS_SEQUENCE + #define Py_TPFLAGS_SEQUENCE 0 +#endif +#ifndef Py_TPFLAGS_MAPPING + #define Py_TPFLAGS_MAPPING 0 +#endif +#ifndef METH_STACKLESS + #define METH_STACKLESS 0 +#endif +#if PY_VERSION_HEX <= 0x030700A3 || !defined(METH_FASTCALL) + #ifndef METH_FASTCALL + #define METH_FASTCALL 0x80 + #endif + typedef PyObject *(*__Pyx_PyCFunctionFast) (PyObject *self, PyObject *const *args, Py_ssize_t nargs); + typedef PyObject *(*__Pyx_PyCFunctionFastWithKeywords) (PyObject *self, PyObject *const *args, + Py_ssize_t nargs, PyObject *kwnames); +#else + #define __Pyx_PyCFunctionFast _PyCFunctionFast + #define __Pyx_PyCFunctionFastWithKeywords _PyCFunctionFastWithKeywords +#endif +#if CYTHON_METH_FASTCALL + #define __Pyx_METH_FASTCALL METH_FASTCALL + #define __Pyx_PyCFunction_FastCall __Pyx_PyCFunctionFast + #define __Pyx_PyCFunction_FastCallWithKeywords __Pyx_PyCFunctionFastWithKeywords +#else + #define __Pyx_METH_FASTCALL METH_VARARGS + #define __Pyx_PyCFunction_FastCall PyCFunction + #define __Pyx_PyCFunction_FastCallWithKeywords PyCFunctionWithKeywords +#endif +#if CYTHON_VECTORCALL + #define __pyx_vectorcallfunc vectorcallfunc + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET PY_VECTORCALL_ARGUMENTS_OFFSET + #define __Pyx_PyVectorcall_NARGS(n) PyVectorcall_NARGS((size_t)(n)) +#elif CYTHON_BACKPORT_VECTORCALL + typedef PyObject *(*__pyx_vectorcallfunc)(PyObject *callable, PyObject *const *args, + size_t nargsf, PyObject *kwnames); + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET ((size_t)1 << (8 * sizeof(size_t) - 1)) + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(((size_t)(n)) & ~__Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET)) +#else + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET 0 + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(n)) +#endif +#if PY_MAJOR_VERSION >= 0x030900B1 +#define __Pyx_PyCFunction_CheckExact(func) PyCFunction_CheckExact(func) +#else +#define __Pyx_PyCFunction_CheckExact(func) PyCFunction_Check(func) +#endif +#define __Pyx_CyOrPyCFunction_Check(func) PyCFunction_Check(func) +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_CyOrPyCFunction_GET_FUNCTION(func) (((PyCFunctionObject*)(func))->m_ml->ml_meth) +#elif !CYTHON_COMPILING_IN_LIMITED_API +#define __Pyx_CyOrPyCFunction_GET_FUNCTION(func) PyCFunction_GET_FUNCTION(func) +#endif +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_CyOrPyCFunction_GET_FLAGS(func) (((PyCFunctionObject*)(func))->m_ml->ml_flags) +static CYTHON_INLINE PyObject* __Pyx_CyOrPyCFunction_GET_SELF(PyObject *func) { + return (__Pyx_CyOrPyCFunction_GET_FLAGS(func) & METH_STATIC) ? NULL : ((PyCFunctionObject*)func)->m_self; +} +#endif +static CYTHON_INLINE int __Pyx__IsSameCFunction(PyObject *func, void *cfunc) { +#if CYTHON_COMPILING_IN_LIMITED_API + return PyCFunction_Check(func) && PyCFunction_GetFunction(func) == (PyCFunction) cfunc; +#else + return PyCFunction_Check(func) && PyCFunction_GET_FUNCTION(func) == (PyCFunction) cfunc; +#endif +} +#define __Pyx_IsSameCFunction(func, cfunc) __Pyx__IsSameCFunction(func, cfunc) +#if __PYX_LIMITED_VERSION_HEX < 0x030900B1 + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) ((void)m, PyType_FromSpecWithBases(s, b)) + typedef PyObject *(*__Pyx_PyCMethod)(PyObject *, PyTypeObject *, PyObject *const *, size_t, PyObject *); +#else + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) PyType_FromModuleAndSpec(m, s, b) + #define __Pyx_PyCMethod PyCMethod +#endif +#ifndef METH_METHOD + #define METH_METHOD 0x200 +#endif +#if CYTHON_COMPILING_IN_PYPY && !defined(PyObject_Malloc) + #define PyObject_Malloc(s) PyMem_Malloc(s) + #define PyObject_Free(p) PyMem_Free(p) + #define PyObject_Realloc(p) PyMem_Realloc(p) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) +#else + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) (frame)->f_lineno = (lineno) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyThreadState_Current PyThreadState_Get() +#elif !CYTHON_FAST_THREAD_STATE + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#elif PY_VERSION_HEX >= 0x030d00A1 + #define __Pyx_PyThreadState_Current PyThreadState_GetUnchecked() +#elif PY_VERSION_HEX >= 0x03060000 + #define __Pyx_PyThreadState_Current _PyThreadState_UncheckedGet() +#elif PY_VERSION_HEX >= 0x03000000 + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#else + #define __Pyx_PyThreadState_Current _PyThreadState_Current +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE void *__Pyx_PyModule_GetState(PyObject *op) +{ + void *result; + result = PyModule_GetState(op); + if (!result) + Py_FatalError("Couldn't find the module state"); + return result; +} +#endif +#define __Pyx_PyObject_GetSlot(obj, name, func_ctype) __Pyx_PyType_GetSlot(Py_TYPE(obj), name, func_ctype) +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((func_ctype) PyType_GetSlot((type), Py_##name)) +#else + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((type)->name) +#endif +#if PY_VERSION_HEX < 0x030700A2 && !defined(PyThread_tss_create) && !defined(Py_tss_NEEDS_INIT) +#include "pythread.h" +#define Py_tss_NEEDS_INIT 0 +typedef int Py_tss_t; +static CYTHON_INLINE int PyThread_tss_create(Py_tss_t *key) { + *key = PyThread_create_key(); + return 0; +} +static CYTHON_INLINE Py_tss_t * PyThread_tss_alloc(void) { + Py_tss_t *key = (Py_tss_t *)PyObject_Malloc(sizeof(Py_tss_t)); + *key = Py_tss_NEEDS_INIT; + return key; +} +static CYTHON_INLINE void PyThread_tss_free(Py_tss_t *key) { + PyObject_Free(key); +} +static CYTHON_INLINE int PyThread_tss_is_created(Py_tss_t *key) { + return *key != Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE void PyThread_tss_delete(Py_tss_t *key) { + PyThread_delete_key(*key); + *key = Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE int PyThread_tss_set(Py_tss_t *key, void *value) { + return PyThread_set_key_value(*key, value); +} +static CYTHON_INLINE void * PyThread_tss_get(Py_tss_t *key) { + return PyThread_get_key_value(*key); +} +#endif +#if PY_MAJOR_VERSION < 3 + #if CYTHON_COMPILING_IN_PYPY + #if PYPY_VERSION_NUM < 0x07030600 + #if defined(__cplusplus) && __cplusplus >= 201402L + [[deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")]] + #elif defined(__GNUC__) || defined(__clang__) + __attribute__ ((__deprecated__("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6"))) + #elif defined(_MSC_VER) + __declspec(deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")) + #endif + static CYTHON_INLINE int PyGILState_Check(void) { + return 0; + } + #else // PYPY_VERSION_NUM < 0x07030600 + #endif // PYPY_VERSION_NUM < 0x07030600 + #else + static CYTHON_INLINE int PyGILState_Check(void) { + PyThreadState * tstate = _PyThreadState_Current; + return tstate && (tstate == PyGILState_GetThisThreadState()); + } + #endif +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030d0000 || defined(_PyDict_NewPresized) +#define __Pyx_PyDict_NewPresized(n) ((n <= 8) ? PyDict_New() : _PyDict_NewPresized(n)) +#else +#define __Pyx_PyDict_NewPresized(n) PyDict_New() +#endif +#if PY_MAJOR_VERSION >= 3 || CYTHON_FUTURE_DIVISION + #define __Pyx_PyNumber_Divide(x,y) PyNumber_TrueDivide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceTrueDivide(x,y) +#else + #define __Pyx_PyNumber_Divide(x,y) PyNumber_Divide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceDivide(x,y) +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX > 0x030600B4 && PY_VERSION_HEX < 0x030d0000 && CYTHON_USE_UNICODE_INTERNALS +#define __Pyx_PyDict_GetItemStrWithError(dict, name) _PyDict_GetItem_KnownHash(dict, name, ((PyASCIIObject *) name)->hash) +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStr(PyObject *dict, PyObject *name) { + PyObject *res = __Pyx_PyDict_GetItemStrWithError(dict, name); + if (res == NULL) PyErr_Clear(); + return res; +} +#elif PY_MAJOR_VERSION >= 3 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07020000) +#define __Pyx_PyDict_GetItemStrWithError PyDict_GetItemWithError +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#else +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStrWithError(PyObject *dict, PyObject *name) { +#if CYTHON_COMPILING_IN_PYPY + return PyDict_GetItem(dict, name); +#else + PyDictEntry *ep; + PyDictObject *mp = (PyDictObject*) dict; + long hash = ((PyStringObject *) name)->ob_shash; + assert(hash != -1); + ep = (mp->ma_lookup)(mp, name, hash); + if (ep == NULL) { + return NULL; + } + return ep->me_value; +#endif +} +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#endif +#if CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyType_GetFlags(tp) (((PyTypeObject *)tp)->tp_flags) + #define __Pyx_PyType_HasFeature(type, feature) ((__Pyx_PyType_GetFlags(type) & (feature)) != 0) + #define __Pyx_PyObject_GetIterNextFunc(obj) (Py_TYPE(obj)->tp_iternext) +#else + #define __Pyx_PyType_GetFlags(tp) (PyType_GetFlags((PyTypeObject *)tp)) + #define __Pyx_PyType_HasFeature(type, feature) PyType_HasFeature(type, feature) + #define __Pyx_PyObject_GetIterNextFunc(obj) PyIter_Next +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_SetItemOnTypeDict(tp, k, v) PyObject_GenericSetAttr((PyObject*)tp, k, v) +#else + #define __Pyx_SetItemOnTypeDict(tp, k, v) PyDict_SetItem(tp->tp_dict, k, v) +#endif +#if CYTHON_USE_TYPE_SPECS && PY_VERSION_HEX >= 0x03080000 +#define __Pyx_PyHeapTypeObject_GC_Del(obj) {\ + PyTypeObject *type = Py_TYPE((PyObject*)obj);\ + assert(__Pyx_PyType_HasFeature(type, Py_TPFLAGS_HEAPTYPE));\ + PyObject_GC_Del(obj);\ + Py_DECREF(type);\ +} +#else +#define __Pyx_PyHeapTypeObject_GC_Del(obj) PyObject_GC_Del(obj) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define CYTHON_PEP393_ENABLED 1 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GetLength(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_ReadChar(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((void)u, 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((void)u, (0)) + #define __Pyx_PyUnicode_DATA(u) ((void*)u) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)k, PyUnicode_ReadChar((PyObject*)(d), i)) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GetLength(u)) +#elif PY_VERSION_HEX > 0x03030000 && defined(PyUnicode_KIND) + #define CYTHON_PEP393_ENABLED 1 + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_READY(op) (0) + #else + #define __Pyx_PyUnicode_READY(op) (likely(PyUnicode_IS_READY(op)) ?\ + 0 : _PyUnicode_Ready((PyObject *)(op))) + #endif + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_LENGTH(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_READ_CHAR(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) PyUnicode_MAX_CHAR_VALUE(u) + #define __Pyx_PyUnicode_KIND(u) ((int)PyUnicode_KIND(u)) + #define __Pyx_PyUnicode_DATA(u) PyUnicode_DATA(u) + #define __Pyx_PyUnicode_READ(k, d, i) PyUnicode_READ(k, d, i) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) PyUnicode_WRITE(k, d, i, (Py_UCS4) ch) + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_LENGTH(u)) + #else + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x03090000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : ((PyCompactUnicodeObject *)(u))->wstr_length)) + #else + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : PyUnicode_GET_SIZE(u))) + #endif + #endif +#else + #define CYTHON_PEP393_ENABLED 0 + #define PyUnicode_1BYTE_KIND 1 + #define PyUnicode_2BYTE_KIND 2 + #define PyUnicode_4BYTE_KIND 4 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_SIZE(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) ((Py_UCS4)(PyUnicode_AS_UNICODE(u)[i])) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((sizeof(Py_UNICODE) == 2) ? 65535U : 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((int)sizeof(Py_UNICODE)) + #define __Pyx_PyUnicode_DATA(u) ((void*)PyUnicode_AS_UNICODE(u)) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)(k), (Py_UCS4)(((Py_UNICODE*)d)[i])) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) (((void)(k)), ((Py_UNICODE*)d)[i] = (Py_UNICODE) ch) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_SIZE(u)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyUnicode_Concat(a, b) PyNumber_Add(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) PyNumber_Add(a, b) +#else + #define __Pyx_PyUnicode_Concat(a, b) PyUnicode_Concat(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) ((unlikely((a) == Py_None) || unlikely((b) == Py_None)) ?\ + PyNumber_Add(a, b) : __Pyx_PyUnicode_Concat(a, b)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #if !defined(PyUnicode_DecodeUnicodeEscape) + #define PyUnicode_DecodeUnicodeEscape(s, size, errors) PyUnicode_Decode(s, size, "unicode_escape", errors) + #endif + #if !defined(PyUnicode_Contains) || (PY_MAJOR_VERSION == 2 && PYPY_VERSION_NUM < 0x07030500) + #undef PyUnicode_Contains + #define PyUnicode_Contains(u, s) PySequence_Contains(u, s) + #endif + #if !defined(PyByteArray_Check) + #define PyByteArray_Check(obj) PyObject_TypeCheck(obj, &PyByteArray_Type) + #endif + #if !defined(PyObject_Format) + #define PyObject_Format(obj, fmt) PyObject_CallMethod(obj, "__format__", "O", fmt) + #endif +#endif +#define __Pyx_PyString_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyString_Check(b) && !PyString_CheckExact(b)))) ? PyNumber_Remainder(a, b) : __Pyx_PyString_Format(a, b)) +#define __Pyx_PyUnicode_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyUnicode_Check(b) && !PyUnicode_CheckExact(b)))) ? PyNumber_Remainder(a, b) : PyUnicode_Format(a, b)) +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyString_Format(a, b) PyUnicode_Format(a, b) +#else + #define __Pyx_PyString_Format(a, b) PyString_Format(a, b) +#endif +#if PY_MAJOR_VERSION < 3 && !defined(PyObject_ASCII) + #define PyObject_ASCII(o) PyObject_Repr(o) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBaseString_Type PyUnicode_Type + #define PyStringObject PyUnicodeObject + #define PyString_Type PyUnicode_Type + #define PyString_Check PyUnicode_Check + #define PyString_CheckExact PyUnicode_CheckExact +#ifndef PyObject_Unicode + #define PyObject_Unicode PyObject_Str +#endif +#endif +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyBaseString_Check(obj) PyUnicode_Check(obj) + #define __Pyx_PyBaseString_CheckExact(obj) PyUnicode_CheckExact(obj) +#else + #define __Pyx_PyBaseString_Check(obj) (PyString_Check(obj) || PyUnicode_Check(obj)) + #define __Pyx_PyBaseString_CheckExact(obj) (PyString_CheckExact(obj) || PyUnicode_CheckExact(obj)) +#endif +#if CYTHON_COMPILING_IN_CPYTHON + #define __Pyx_PySequence_ListKeepNew(obj)\ + (likely(PyList_CheckExact(obj) && Py_REFCNT(obj) == 1) ? __Pyx_NewRef(obj) : PySequence_List(obj)) +#else + #define __Pyx_PySequence_ListKeepNew(obj) PySequence_List(obj) +#endif +#ifndef PySet_CheckExact + #define PySet_CheckExact(obj) __Pyx_IS_TYPE(obj, &PySet_Type) +#endif +#if PY_VERSION_HEX >= 0x030900A4 + #define __Pyx_SET_REFCNT(obj, refcnt) Py_SET_REFCNT(obj, refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SET_SIZE(obj, size) +#else + #define __Pyx_SET_REFCNT(obj, refcnt) Py_REFCNT(obj) = (refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SIZE(obj) = (size) +#endif +#if CYTHON_ASSUME_SAFE_MACROS + #define __Pyx_PySequence_ITEM(o, i) PySequence_ITEM(o, i) + #define __Pyx_PySequence_SIZE(seq) Py_SIZE(seq) + #define __Pyx_PyTuple_SET_ITEM(o, i, v) (PyTuple_SET_ITEM(o, i, v), (0)) + #define __Pyx_PyList_SET_ITEM(o, i, v) (PyList_SET_ITEM(o, i, v), (0)) + #define __Pyx_PyTuple_GET_SIZE(o) PyTuple_GET_SIZE(o) + #define __Pyx_PyList_GET_SIZE(o) PyList_GET_SIZE(o) + #define __Pyx_PySet_GET_SIZE(o) PySet_GET_SIZE(o) + #define __Pyx_PyBytes_GET_SIZE(o) PyBytes_GET_SIZE(o) + #define __Pyx_PyByteArray_GET_SIZE(o) PyByteArray_GET_SIZE(o) +#else + #define __Pyx_PySequence_ITEM(o, i) PySequence_GetItem(o, i) + #define __Pyx_PySequence_SIZE(seq) PySequence_Size(seq) + #define __Pyx_PyTuple_SET_ITEM(o, i, v) PyTuple_SetItem(o, i, v) + #define __Pyx_PyList_SET_ITEM(o, i, v) PyList_SetItem(o, i, v) + #define __Pyx_PyTuple_GET_SIZE(o) PyTuple_Size(o) + #define __Pyx_PyList_GET_SIZE(o) PyList_Size(o) + #define __Pyx_PySet_GET_SIZE(o) PySet_Size(o) + #define __Pyx_PyBytes_GET_SIZE(o) PyBytes_Size(o) + #define __Pyx_PyByteArray_GET_SIZE(o) PyByteArray_Size(o) +#endif +#if PY_VERSION_HEX >= 0x030d00A1 + #define __Pyx_PyImport_AddModuleRef(name) PyImport_AddModuleRef(name) +#else + static CYTHON_INLINE PyObject *__Pyx_PyImport_AddModuleRef(const char *name) { + PyObject *module = PyImport_AddModule(name); + Py_XINCREF(module); + return module; + } +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyIntObject PyLongObject + #define PyInt_Type PyLong_Type + #define PyInt_Check(op) PyLong_Check(op) + #define PyInt_CheckExact(op) PyLong_CheckExact(op) + #define __Pyx_Py3Int_Check(op) PyLong_Check(op) + #define __Pyx_Py3Int_CheckExact(op) PyLong_CheckExact(op) + #define PyInt_FromString PyLong_FromString + #define PyInt_FromUnicode PyLong_FromUnicode + #define PyInt_FromLong PyLong_FromLong + #define PyInt_FromSize_t PyLong_FromSize_t + #define PyInt_FromSsize_t PyLong_FromSsize_t + #define PyInt_AsLong PyLong_AsLong + #define PyInt_AS_LONG PyLong_AS_LONG + #define PyInt_AsSsize_t PyLong_AsSsize_t + #define PyInt_AsUnsignedLongMask PyLong_AsUnsignedLongMask + #define PyInt_AsUnsignedLongLongMask PyLong_AsUnsignedLongLongMask + #define PyNumber_Int PyNumber_Long +#else + #define __Pyx_Py3Int_Check(op) (PyLong_Check(op) || PyInt_Check(op)) + #define __Pyx_Py3Int_CheckExact(op) (PyLong_CheckExact(op) || PyInt_CheckExact(op)) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBoolObject PyLongObject +#endif +#if PY_MAJOR_VERSION >= 3 && CYTHON_COMPILING_IN_PYPY + #ifndef PyUnicode_InternFromString + #define PyUnicode_InternFromString(s) PyUnicode_FromString(s) + #endif +#endif +#if PY_VERSION_HEX < 0x030200A4 + typedef long Py_hash_t; + #define __Pyx_PyInt_FromHash_t PyInt_FromLong + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsHash_t +#else + #define __Pyx_PyInt_FromHash_t PyInt_FromSsize_t + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsSsize_t +#endif +#if CYTHON_USE_ASYNC_SLOTS + #if PY_VERSION_HEX >= 0x030500B1 + #define __Pyx_PyAsyncMethodsStruct PyAsyncMethods + #define __Pyx_PyType_AsAsync(obj) (Py_TYPE(obj)->tp_as_async) + #else + #define __Pyx_PyType_AsAsync(obj) ((__Pyx_PyAsyncMethodsStruct*) (Py_TYPE(obj)->tp_reserved)) + #endif +#else + #define __Pyx_PyType_AsAsync(obj) NULL +#endif +#ifndef __Pyx_PyAsyncMethodsStruct + typedef struct { + unaryfunc am_await; + unaryfunc am_aiter; + unaryfunc am_anext; + } __Pyx_PyAsyncMethodsStruct; +#endif + +#if defined(_WIN32) || defined(WIN32) || defined(MS_WINDOWS) + #if !defined(_USE_MATH_DEFINES) + #define _USE_MATH_DEFINES + #endif +#endif +#include +#ifdef NAN +#define __PYX_NAN() ((float) NAN) +#else +static CYTHON_INLINE float __PYX_NAN() { + float value; + memset(&value, 0xFF, sizeof(value)); + return value; +} +#endif +#if defined(__CYGWIN__) && defined(_LDBL_EQ_DBL) +#define __Pyx_truncl trunc +#else +#define __Pyx_truncl truncl +#endif + +#define __PYX_MARK_ERR_POS(f_index, lineno) \ + { __pyx_filename = __pyx_f[f_index]; (void)__pyx_filename; __pyx_lineno = lineno; (void)__pyx_lineno; __pyx_clineno = __LINE__; (void)__pyx_clineno; } +#define __PYX_ERR(f_index, lineno, Ln_error) \ + { __PYX_MARK_ERR_POS(f_index, lineno) goto Ln_error; } + +#ifdef CYTHON_EXTERN_C + #undef __PYX_EXTERN_C + #define __PYX_EXTERN_C CYTHON_EXTERN_C +#elif defined(__PYX_EXTERN_C) + #ifdef _MSC_VER + #pragma message ("Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead.") + #else + #warning Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead. + #endif +#else + #define __PYX_EXTERN_C extern "C++" +#endif + +#define __PYX_HAVE__selfdrive__modeld__runners__snpemodel_pyx +#define __PYX_HAVE_API__selfdrive__modeld__runners__snpemodel_pyx +/* Early includes */ +#include +#include +#include "ios" +#include "new" +#include "stdexcept" +#include "typeinfo" +#include +#include + + #if __cplusplus >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1600) + // move should be defined for these versions of MSVC, but __cplusplus isn't set usefully + #include + + namespace cython_std { + template typename std::remove_reference::type&& move(T& t) noexcept { return std::move(t); } + template typename std::remove_reference::type&& move(T&& t) noexcept { return std::move(t); } + } + + #endif + +#include +#include +#include "cereal/visionipc/visionbuf.h" +#include "cereal/visionipc/visionipc.h" +#include "cereal/visionipc/visionipc_server.h" +#include "cereal/visionipc/visionipc_client.h" +#include "selfdrive/modeld/runners/snpemodel.h" +#include "selfdrive/modeld/runners/runmodel.h" +#include "pythread.h" +#include +#ifdef _OPENMP +#include +#endif /* _OPENMP */ + +#if defined(PYREX_WITHOUT_ASSERTIONS) && !defined(CYTHON_WITHOUT_ASSERTIONS) +#define CYTHON_WITHOUT_ASSERTIONS +#endif + +typedef struct {PyObject **p; const char *s; const Py_ssize_t n; const char* encoding; + const char is_unicode; const char is_str; const char intern; } __Pyx_StringTabEntry; + +#define __PYX_DEFAULT_STRING_ENCODING_IS_ASCII 1 +#define __PYX_DEFAULT_STRING_ENCODING_IS_UTF8 0 +#define __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT (PY_MAJOR_VERSION >= 3 && __PYX_DEFAULT_STRING_ENCODING_IS_UTF8) +#define __PYX_DEFAULT_STRING_ENCODING "ascii" +#define __Pyx_PyObject_FromString __Pyx_PyBytes_FromString +#define __Pyx_PyObject_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#define __Pyx_uchar_cast(c) ((unsigned char)c) +#define __Pyx_long_cast(x) ((long)x) +#define __Pyx_fits_Py_ssize_t(v, type, is_signed) (\ + (sizeof(type) < sizeof(Py_ssize_t)) ||\ + (sizeof(type) > sizeof(Py_ssize_t) &&\ + likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX) &&\ + (!is_signed || likely(v > (type)PY_SSIZE_T_MIN ||\ + v == (type)PY_SSIZE_T_MIN))) ||\ + (sizeof(type) == sizeof(Py_ssize_t) &&\ + (is_signed || likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX))) ) +static CYTHON_INLINE int __Pyx_is_valid_index(Py_ssize_t i, Py_ssize_t limit) { + return (size_t) i < (size_t) limit; +} +#if defined (__cplusplus) && __cplusplus >= 201103L + #include + #define __Pyx_sst_abs(value) std::abs(value) +#elif SIZEOF_INT >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) abs(value) +#elif SIZEOF_LONG >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) labs(value) +#elif defined (_MSC_VER) + #define __Pyx_sst_abs(value) ((Py_ssize_t)_abs64(value)) +#elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define __Pyx_sst_abs(value) llabs(value) +#elif defined (__GNUC__) + #define __Pyx_sst_abs(value) __builtin_llabs(value) +#else + #define __Pyx_sst_abs(value) ((value<0) ? -value : value) +#endif +static CYTHON_INLINE Py_ssize_t __Pyx_ssize_strlen(const char *s); +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject*); +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject*, Py_ssize_t* length); +static CYTHON_INLINE PyObject* __Pyx_PyByteArray_FromString(const char*); +#define __Pyx_PyByteArray_FromStringAndSize(s, l) PyByteArray_FromStringAndSize((const char*)s, l) +#define __Pyx_PyBytes_FromString PyBytes_FromString +#define __Pyx_PyBytes_FromStringAndSize PyBytes_FromStringAndSize +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char*); +#if PY_MAJOR_VERSION < 3 + #define __Pyx_PyStr_FromString __Pyx_PyBytes_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#else + #define __Pyx_PyStr_FromString __Pyx_PyUnicode_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyUnicode_FromStringAndSize +#endif +#define __Pyx_PyBytes_AsWritableString(s) ((char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableSString(s) ((signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableUString(s) ((unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsString(s) ((const char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsSString(s) ((const signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsUString(s) ((const unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyObject_AsWritableString(s) ((char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableSString(s) ((signed char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableUString(s) ((unsigned char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsSString(s) ((const signed char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsUString(s) ((const unsigned char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_FromCString(s) __Pyx_PyObject_FromString((const char*)s) +#define __Pyx_PyBytes_FromCString(s) __Pyx_PyBytes_FromString((const char*)s) +#define __Pyx_PyByteArray_FromCString(s) __Pyx_PyByteArray_FromString((const char*)s) +#define __Pyx_PyStr_FromCString(s) __Pyx_PyStr_FromString((const char*)s) +#define __Pyx_PyUnicode_FromCString(s) __Pyx_PyUnicode_FromString((const char*)s) +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const wchar_t *u) +{ + const wchar_t *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#else +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const Py_UNICODE *u) +{ + const Py_UNICODE *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#endif +#define __Pyx_PyUnicode_FromOrdinal(o) PyUnicode_FromOrdinal((int)o) +#define __Pyx_PyUnicode_FromUnicode(u) PyUnicode_FromUnicode(u, __Pyx_Py_UNICODE_strlen(u)) +#define __Pyx_PyUnicode_FromUnicodeAndLength PyUnicode_FromUnicode +#define __Pyx_PyUnicode_AsUnicode PyUnicode_AsUnicode +#define __Pyx_NewRef(obj) (Py_INCREF(obj), obj) +#define __Pyx_Owned_Py_None(b) __Pyx_NewRef(Py_None) +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b); +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject*); +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject*); +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x); +#define __Pyx_PySequence_Tuple(obj)\ + (likely(PyTuple_CheckExact(obj)) ? __Pyx_NewRef(obj) : PySequence_Tuple(obj)) +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject*); +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t); +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject*); +#if CYTHON_ASSUME_SAFE_MACROS +#define __pyx_PyFloat_AsDouble(x) (PyFloat_CheckExact(x) ? PyFloat_AS_DOUBLE(x) : PyFloat_AsDouble(x)) +#else +#define __pyx_PyFloat_AsDouble(x) PyFloat_AsDouble(x) +#endif +#define __pyx_PyFloat_AsFloat(x) ((float) __pyx_PyFloat_AsDouble(x)) +#if PY_MAJOR_VERSION >= 3 +#define __Pyx_PyNumber_Int(x) (PyLong_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Long(x)) +#else +#define __Pyx_PyNumber_Int(x) (PyInt_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Int(x)) +#endif +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_VERSION_HEX >= 0x030C00A7 + #ifndef _PyLong_SIGN_MASK + #define _PyLong_SIGN_MASK 3 + #endif + #ifndef _PyLong_NON_SIZE_BITS + #define _PyLong_NON_SIZE_BITS 3 + #endif + #define __Pyx_PyLong_Sign(x) (((PyLongObject*)x)->long_value.lv_tag & _PyLong_SIGN_MASK) + #define __Pyx_PyLong_IsNeg(x) ((__Pyx_PyLong_Sign(x) & 2) != 0) + #define __Pyx_PyLong_IsNonNeg(x) (!__Pyx_PyLong_IsNeg(x)) + #define __Pyx_PyLong_IsZero(x) (__Pyx_PyLong_Sign(x) & 1) + #define __Pyx_PyLong_IsPos(x) (__Pyx_PyLong_Sign(x) == 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) (__Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) ((Py_ssize_t) (((PyLongObject*)x)->long_value.lv_tag >> _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_SignedDigitCount(x)\ + ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * __Pyx_PyLong_DigitCount(x)) + #if defined(PyUnstable_Long_IsCompact) && defined(PyUnstable_Long_CompactValue) + #define __Pyx_PyLong_IsCompact(x) PyUnstable_Long_IsCompact((PyLongObject*) x) + #define __Pyx_PyLong_CompactValue(x) PyUnstable_Long_CompactValue((PyLongObject*) x) + #else + #define __Pyx_PyLong_IsCompact(x) (((PyLongObject*)x)->long_value.lv_tag < (2 << _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_CompactValue(x) ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * (Py_ssize_t) __Pyx_PyLong_Digits(x)[0]) + #endif + typedef Py_ssize_t __Pyx_compact_pylong; + typedef size_t __Pyx_compact_upylong; + #else + #define __Pyx_PyLong_IsNeg(x) (Py_SIZE(x) < 0) + #define __Pyx_PyLong_IsNonNeg(x) (Py_SIZE(x) >= 0) + #define __Pyx_PyLong_IsZero(x) (Py_SIZE(x) == 0) + #define __Pyx_PyLong_IsPos(x) (Py_SIZE(x) > 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) ((Py_SIZE(x) == 0) ? 0 : __Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) __Pyx_sst_abs(Py_SIZE(x)) + #define __Pyx_PyLong_SignedDigitCount(x) Py_SIZE(x) + #define __Pyx_PyLong_IsCompact(x) (Py_SIZE(x) == 0 || Py_SIZE(x) == 1 || Py_SIZE(x) == -1) + #define __Pyx_PyLong_CompactValue(x)\ + ((Py_SIZE(x) == 0) ? (sdigit) 0 : ((Py_SIZE(x) < 0) ? -(sdigit)__Pyx_PyLong_Digits(x)[0] : (sdigit)__Pyx_PyLong_Digits(x)[0])) + typedef sdigit __Pyx_compact_pylong; + typedef digit __Pyx_compact_upylong; + #endif + #if PY_VERSION_HEX >= 0x030C00A5 + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->long_value.ob_digit) + #else + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->ob_digit) + #endif +#endif +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII +#include +static int __Pyx_sys_getdefaultencoding_not_ascii; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + PyObject* ascii_chars_u = NULL; + PyObject* ascii_chars_b = NULL; + const char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + if (strcmp(default_encoding_c, "ascii") == 0) { + __Pyx_sys_getdefaultencoding_not_ascii = 0; + } else { + char ascii_chars[128]; + int c; + for (c = 0; c < 128; c++) { + ascii_chars[c] = (char) c; + } + __Pyx_sys_getdefaultencoding_not_ascii = 1; + ascii_chars_u = PyUnicode_DecodeASCII(ascii_chars, 128, NULL); + if (!ascii_chars_u) goto bad; + ascii_chars_b = PyUnicode_AsEncodedString(ascii_chars_u, default_encoding_c, NULL); + if (!ascii_chars_b || !PyBytes_Check(ascii_chars_b) || memcmp(ascii_chars, PyBytes_AS_STRING(ascii_chars_b), 128) != 0) { + PyErr_Format( + PyExc_ValueError, + "This module compiled with c_string_encoding=ascii, but default encoding '%.200s' is not a superset of ascii.", + default_encoding_c); + goto bad; + } + Py_DECREF(ascii_chars_u); + Py_DECREF(ascii_chars_b); + } + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + Py_XDECREF(ascii_chars_u); + Py_XDECREF(ascii_chars_b); + return -1; +} +#endif +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT && PY_MAJOR_VERSION >= 3 +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_DecodeUTF8(c_str, size, NULL) +#else +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_Decode(c_str, size, __PYX_DEFAULT_STRING_ENCODING, NULL) +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +#include +static char* __PYX_DEFAULT_STRING_ENCODING; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) (const char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + __PYX_DEFAULT_STRING_ENCODING = (char*) malloc(strlen(default_encoding_c) + 1); + if (!__PYX_DEFAULT_STRING_ENCODING) goto bad; + strcpy(__PYX_DEFAULT_STRING_ENCODING, default_encoding_c); + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + return -1; +} +#endif +#endif + + +/* Test for GCC > 2.95 */ +#if defined(__GNUC__) && (__GNUC__ > 2 || (__GNUC__ == 2 && (__GNUC_MINOR__ > 95))) + #define likely(x) __builtin_expect(!!(x), 1) + #define unlikely(x) __builtin_expect(!!(x), 0) +#else /* !__GNUC__ or GCC < 2.95 */ + #define likely(x) (x) + #define unlikely(x) (x) +#endif /* __GNUC__ */ +static CYTHON_INLINE void __Pyx_pretend_to_initialize(void* ptr) { (void)ptr; } + +#if !CYTHON_USE_MODULE_STATE +static PyObject *__pyx_m = NULL; +#endif +static int __pyx_lineno; +static int __pyx_clineno = 0; +static const char * __pyx_cfilenm = __FILE__; +static const char *__pyx_filename; + +/* #### Code section: filename_table ### */ + +static const char *__pyx_f[] = { + "", + "selfdrive/modeld/runners/snpemodel_pyx.pyx", + "cereal/visionipc/visionipc_pyx.pxd", + "selfdrive/modeld/models/commonmodel_pyx.pxd", +}; +/* #### Code section: utility_code_proto_before_types ### */ +/* ForceInitThreads.proto */ +#ifndef __PYX_FORCE_INIT_THREADS + #define __PYX_FORCE_INIT_THREADS 0 +#endif + +/* NoFastGil.proto */ +#define __Pyx_PyGILState_Ensure PyGILState_Ensure +#define __Pyx_PyGILState_Release PyGILState_Release +#define __Pyx_FastGIL_Remember() +#define __Pyx_FastGIL_Forget() +#define __Pyx_FastGilFuncInit() + +/* BufferFormatStructs.proto */ +struct __Pyx_StructField_; +#define __PYX_BUF_FLAGS_PACKED_STRUCT (1 << 0) +typedef struct { + const char* name; + struct __Pyx_StructField_* fields; + size_t size; + size_t arraysize[8]; + int ndim; + char typegroup; + char is_unsigned; + int flags; +} __Pyx_TypeInfo; +typedef struct __Pyx_StructField_ { + __Pyx_TypeInfo* type; + const char* name; + size_t offset; +} __Pyx_StructField; +typedef struct { + __Pyx_StructField* field; + size_t parent_offset; +} __Pyx_BufFmt_StackElem; +typedef struct { + __Pyx_StructField root; + __Pyx_BufFmt_StackElem* head; + size_t fmt_offset; + size_t new_count, enc_count; + size_t struct_alignment; + int is_complex; + char enc_type; + char new_packmode; + char enc_packmode; + char is_valid_array; +} __Pyx_BufFmt_Context; + +/* Atomics.proto */ +#include +#ifndef CYTHON_ATOMICS + #define CYTHON_ATOMICS 1 +#endif +#define __PYX_CYTHON_ATOMICS_ENABLED() CYTHON_ATOMICS +#define __pyx_atomic_int_type int +#define __pyx_nonatomic_int_type int +#if CYTHON_ATOMICS && (defined(__STDC_VERSION__) &&\ + (__STDC_VERSION__ >= 201112L) &&\ + !defined(__STDC_NO_ATOMICS__)) + #include +#elif CYTHON_ATOMICS && (defined(__cplusplus) && (\ + (__cplusplus >= 201103L) ||\ + (defined(_MSC_VER) && _MSC_VER >= 1700))) + #include +#endif +#if CYTHON_ATOMICS && (defined(__STDC_VERSION__) &&\ + (__STDC_VERSION__ >= 201112L) &&\ + !defined(__STDC_NO_ATOMICS__) &&\ + ATOMIC_INT_LOCK_FREE == 2) + #undef __pyx_atomic_int_type + #define __pyx_atomic_int_type atomic_int + #define __pyx_atomic_incr_aligned(value) atomic_fetch_add_explicit(value, 1, memory_order_relaxed) + #define __pyx_atomic_decr_aligned(value) atomic_fetch_sub_explicit(value, 1, memory_order_acq_rel) + #if defined(__PYX_DEBUG_ATOMICS) && defined(_MSC_VER) + #pragma message ("Using standard C atomics") + #elif defined(__PYX_DEBUG_ATOMICS) + #warning "Using standard C atomics" + #endif +#elif CYTHON_ATOMICS && (defined(__cplusplus) && (\ + (__cplusplus >= 201103L) ||\ +\ + (defined(_MSC_VER) && _MSC_VER >= 1700)) &&\ + ATOMIC_INT_LOCK_FREE == 2) + #undef __pyx_atomic_int_type + #define __pyx_atomic_int_type std::atomic_int + #define __pyx_atomic_incr_aligned(value) std::atomic_fetch_add_explicit(value, 1, std::memory_order_relaxed) + #define __pyx_atomic_decr_aligned(value) std::atomic_fetch_sub_explicit(value, 1, std::memory_order_acq_rel) + #if defined(__PYX_DEBUG_ATOMICS) && defined(_MSC_VER) + #pragma message ("Using standard C++ atomics") + #elif defined(__PYX_DEBUG_ATOMICS) + #warning "Using standard C++ atomics" + #endif +#elif CYTHON_ATOMICS && (__GNUC__ >= 5 || (__GNUC__ == 4 &&\ + (__GNUC_MINOR__ > 1 ||\ + (__GNUC_MINOR__ == 1 && __GNUC_PATCHLEVEL__ >= 2)))) + #define __pyx_atomic_incr_aligned(value) __sync_fetch_and_add(value, 1) + #define __pyx_atomic_decr_aligned(value) __sync_fetch_and_sub(value, 1) + #ifdef __PYX_DEBUG_ATOMICS + #warning "Using GNU atomics" + #endif +#elif CYTHON_ATOMICS && defined(_MSC_VER) + #include + #undef __pyx_atomic_int_type + #define __pyx_atomic_int_type long + #undef __pyx_nonatomic_int_type + #define __pyx_nonatomic_int_type long + #pragma intrinsic (_InterlockedExchangeAdd) + #define __pyx_atomic_incr_aligned(value) _InterlockedExchangeAdd(value, 1) + #define __pyx_atomic_decr_aligned(value) _InterlockedExchangeAdd(value, -1) + #ifdef __PYX_DEBUG_ATOMICS + #pragma message ("Using MSVC atomics") + #endif +#else + #undef CYTHON_ATOMICS + #define CYTHON_ATOMICS 0 + #ifdef __PYX_DEBUG_ATOMICS + #warning "Not using atomics" + #endif +#endif +#if CYTHON_ATOMICS + #define __pyx_add_acquisition_count(memview)\ + __pyx_atomic_incr_aligned(__pyx_get_slice_count_pointer(memview)) + #define __pyx_sub_acquisition_count(memview)\ + __pyx_atomic_decr_aligned(__pyx_get_slice_count_pointer(memview)) +#else + #define __pyx_add_acquisition_count(memview)\ + __pyx_add_acquisition_count_locked(__pyx_get_slice_count_pointer(memview), memview->lock) + #define __pyx_sub_acquisition_count(memview)\ + __pyx_sub_acquisition_count_locked(__pyx_get_slice_count_pointer(memview), memview->lock) +#endif + +/* MemviewSliceStruct.proto */ +struct __pyx_memoryview_obj; +typedef struct { + struct __pyx_memoryview_obj *memview; + char *data; + Py_ssize_t shape[8]; + Py_ssize_t strides[8]; + Py_ssize_t suboffsets[8]; +} __Pyx_memviewslice; +#define __Pyx_MemoryView_Len(m) (m.shape[0]) + +/* #### Code section: numeric_typedefs ### */ +/* #### Code section: complex_type_declarations ### */ +/* #### Code section: type_declarations ### */ + +/*--- Type declarations ---*/ +struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_CLContext; +struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf; +struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext; +struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem; +struct __pyx_obj_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel; +struct __pyx_obj_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel; +struct __pyx_array_obj; +struct __pyx_MemviewEnum_obj; +struct __pyx_memoryview_obj; +struct __pyx_memoryviewslice_obj; + +/* "cereal/visionipc/visionipc_pyx.pxd":7 + * from .visionipc cimport cl_device_id, cl_context + * + * cdef class CLContext: # <<<<<<<<<<<<<< + * cdef cl_device_id device_id + * cdef cl_context context + */ +struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_CLContext { + PyObject_HEAD + cl_device_id device_id; + cl_context context; +}; + + +/* "cereal/visionipc/visionipc_pyx.pxd":11 + * cdef cl_context context + * + * cdef class VisionBuf: # <<<<<<<<<<<<<< + * cdef cppVisionBuf * buf + * + */ +struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf { + PyObject_HEAD + struct __pyx_vtabstruct_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_vtab; + VisionBuf *buf; +}; + + +/* "selfdrive/modeld/models/commonmodel_pyx.pxd":6 + * from cereal.visionipc.visionipc_pyx cimport CLContext as BaseCLContext + * + * cdef class CLContext(BaseCLContext): # <<<<<<<<<<<<<< + * pass + * + */ +struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext { + struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_CLContext __pyx_base; +}; + + +/* "selfdrive/modeld/models/commonmodel_pyx.pxd":9 + * pass + * + * cdef class CLMem: # <<<<<<<<<<<<<< + * cdef cl_mem * mem + * + */ +struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem { + PyObject_HEAD + struct __pyx_vtabstruct_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem *__pyx_vtab; + cl_mem *mem; +}; + + +/* "selfdrive/modeld/runners/runmodel_pyx.pxd":5 + * from .runmodel cimport RunModel as cppRunModel + * + * cdef class RunModel: # <<<<<<<<<<<<<< + * cdef cppRunModel * model + */ +struct __pyx_obj_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel { + PyObject_HEAD + RunModel *model; +}; + + +/* "selfdrive/modeld/runners/snpemodel_pyx.pyx":15 + * os.environ['ADSP_LIBRARY_PATH'] = "/data/pythonpath/third_party/snpe/dsp/" + * + * cdef class SNPEModel(RunModel): # <<<<<<<<<<<<<< + * def __cinit__(self, string path, float[:] output, int runtime, bool use_tf8, CLContext context): + * self.model = new cppSNPEModel(path, &output[0], len(output), runtime, use_tf8, context.context) + */ +struct __pyx_obj_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel { + struct __pyx_obj_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel __pyx_base; +}; + + +/* "View.MemoryView":114 + * @cython.collection_type("sequence") + * @cname("__pyx_array") + * cdef class array: # <<<<<<<<<<<<<< + * + * cdef: + */ +struct __pyx_array_obj { + PyObject_HEAD + struct __pyx_vtabstruct_array *__pyx_vtab; + char *data; + Py_ssize_t len; + char *format; + int ndim; + Py_ssize_t *_shape; + Py_ssize_t *_strides; + Py_ssize_t itemsize; + PyObject *mode; + PyObject *_format; + void (*callback_free_data)(void *); + int free_data; + int dtype_is_object; +}; + + +/* "View.MemoryView":302 + * + * @cname('__pyx_MemviewEnum') + * cdef class Enum(object): # <<<<<<<<<<<<<< + * cdef object name + * def __init__(self, name): + */ +struct __pyx_MemviewEnum_obj { + PyObject_HEAD + PyObject *name; +}; + + +/* "View.MemoryView":337 + * + * @cname('__pyx_memoryview') + * cdef class memoryview: # <<<<<<<<<<<<<< + * + * cdef object obj + */ +struct __pyx_memoryview_obj { + PyObject_HEAD + struct __pyx_vtabstruct_memoryview *__pyx_vtab; + PyObject *obj; + PyObject *_size; + PyObject *_array_interface; + PyThread_type_lock lock; + __pyx_atomic_int_type acquisition_count; + Py_buffer view; + int flags; + int dtype_is_object; + __Pyx_TypeInfo *typeinfo; +}; + + +/* "View.MemoryView":952 + * @cython.collection_type("sequence") + * @cname('__pyx_memoryviewslice') + * cdef class _memoryviewslice(memoryview): # <<<<<<<<<<<<<< + * "Internal class for passing memoryview slices to Python" + * + */ +struct __pyx_memoryviewslice_obj { + struct __pyx_memoryview_obj __pyx_base; + __Pyx_memviewslice from_slice; + PyObject *from_object; + PyObject *(*to_object_func)(char *); + int (*to_dtype_func)(char *, PyObject *); +}; + + + +/* "cereal/visionipc/visionipc_pyx.pxd":11 + * cdef cl_context context + * + * cdef class VisionBuf: # <<<<<<<<<<<<<< + * cdef cppVisionBuf * buf + * + */ + +struct __pyx_vtabstruct_6cereal_9visionipc_13visionipc_pyx_VisionBuf { + PyObject *(*create)(VisionBuf *); +}; +static struct __pyx_vtabstruct_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_vtabptr_6cereal_9visionipc_13visionipc_pyx_VisionBuf; + + +/* "selfdrive/modeld/models/commonmodel_pyx.pxd":9 + * pass + * + * cdef class CLMem: # <<<<<<<<<<<<<< + * cdef cl_mem * mem + * + */ + +struct __pyx_vtabstruct_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem { + PyObject *(*create)(void *); +}; +static struct __pyx_vtabstruct_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem *__pyx_vtabptr_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem; + + +/* "View.MemoryView":114 + * @cython.collection_type("sequence") + * @cname("__pyx_array") + * cdef class array: # <<<<<<<<<<<<<< + * + * cdef: + */ + +struct __pyx_vtabstruct_array { + PyObject *(*get_memview)(struct __pyx_array_obj *); +}; +static struct __pyx_vtabstruct_array *__pyx_vtabptr_array; + + +/* "View.MemoryView":337 + * + * @cname('__pyx_memoryview') + * cdef class memoryview: # <<<<<<<<<<<<<< + * + * cdef object obj + */ + +struct __pyx_vtabstruct_memoryview { + char *(*get_item_pointer)(struct __pyx_memoryview_obj *, PyObject *); + PyObject *(*is_slice)(struct __pyx_memoryview_obj *, PyObject *); + PyObject *(*setitem_slice_assignment)(struct __pyx_memoryview_obj *, PyObject *, PyObject *); + PyObject *(*setitem_slice_assign_scalar)(struct __pyx_memoryview_obj *, struct __pyx_memoryview_obj *, PyObject *); + PyObject *(*setitem_indexed)(struct __pyx_memoryview_obj *, PyObject *, PyObject *); + PyObject *(*convert_item_to_object)(struct __pyx_memoryview_obj *, char *); + PyObject *(*assign_item_from_object)(struct __pyx_memoryview_obj *, char *, PyObject *); + PyObject *(*_get_base)(struct __pyx_memoryview_obj *); +}; +static struct __pyx_vtabstruct_memoryview *__pyx_vtabptr_memoryview; + + +/* "View.MemoryView":952 + * @cython.collection_type("sequence") + * @cname('__pyx_memoryviewslice') + * cdef class _memoryviewslice(memoryview): # <<<<<<<<<<<<<< + * "Internal class for passing memoryview slices to Python" + * + */ + +struct __pyx_vtabstruct__memoryviewslice { + struct __pyx_vtabstruct_memoryview __pyx_base; +}; +static struct __pyx_vtabstruct__memoryviewslice *__pyx_vtabptr__memoryviewslice; +/* #### Code section: utility_code_proto ### */ + +/* --- Runtime support code (head) --- */ +/* Refnanny.proto */ +#ifndef CYTHON_REFNANNY + #define CYTHON_REFNANNY 0 +#endif +#if CYTHON_REFNANNY + typedef struct { + void (*INCREF)(void*, PyObject*, Py_ssize_t); + void (*DECREF)(void*, PyObject*, Py_ssize_t); + void (*GOTREF)(void*, PyObject*, Py_ssize_t); + void (*GIVEREF)(void*, PyObject*, Py_ssize_t); + void* (*SetupContext)(const char*, Py_ssize_t, const char*); + void (*FinishContext)(void**); + } __Pyx_RefNannyAPIStruct; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNanny = NULL; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname); + #define __Pyx_RefNannyDeclarations void *__pyx_refnanny = NULL; +#ifdef WITH_THREAD + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + if (acquire_gil) {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + PyGILState_Release(__pyx_gilstate_save);\ + } else {\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + } + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } +#else + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__)) + #define __Pyx_RefNannyFinishContextNogil() __Pyx_RefNannyFinishContext() +#endif + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } + #define __Pyx_RefNannyFinishContext()\ + __Pyx_RefNanny->FinishContext(&__pyx_refnanny) + #define __Pyx_INCREF(r) __Pyx_RefNanny->INCREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_DECREF(r) __Pyx_RefNanny->DECREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GOTREF(r) __Pyx_RefNanny->GOTREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GIVEREF(r) __Pyx_RefNanny->GIVEREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_XINCREF(r) do { if((r) == NULL); else {__Pyx_INCREF(r); }} while(0) + #define __Pyx_XDECREF(r) do { if((r) == NULL); else {__Pyx_DECREF(r); }} while(0) + #define __Pyx_XGOTREF(r) do { if((r) == NULL); else {__Pyx_GOTREF(r); }} while(0) + #define __Pyx_XGIVEREF(r) do { if((r) == NULL); else {__Pyx_GIVEREF(r);}} while(0) +#else + #define __Pyx_RefNannyDeclarations + #define __Pyx_RefNannySetupContext(name, acquire_gil) + #define __Pyx_RefNannyFinishContextNogil() + #define __Pyx_RefNannyFinishContext() + #define __Pyx_INCREF(r) Py_INCREF(r) + #define __Pyx_DECREF(r) Py_DECREF(r) + #define __Pyx_GOTREF(r) + #define __Pyx_GIVEREF(r) + #define __Pyx_XINCREF(r) Py_XINCREF(r) + #define __Pyx_XDECREF(r) Py_XDECREF(r) + #define __Pyx_XGOTREF(r) + #define __Pyx_XGIVEREF(r) +#endif +#define __Pyx_Py_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; Py_XDECREF(tmp);\ + } while (0) +#define __Pyx_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_XDECREF(tmp);\ + } while (0) +#define __Pyx_DECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_DECREF(tmp);\ + } while (0) +#define __Pyx_CLEAR(r) do { PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);} while(0) +#define __Pyx_XCLEAR(r) do { if((r) != NULL) {PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);}} while(0) + +/* PyErrExceptionMatches.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_ExceptionMatches(err) __Pyx_PyErr_ExceptionMatchesInState(__pyx_tstate, err) +static CYTHON_INLINE int __Pyx_PyErr_ExceptionMatchesInState(PyThreadState* tstate, PyObject* err); +#else +#define __Pyx_PyErr_ExceptionMatches(err) PyErr_ExceptionMatches(err) +#endif + +/* PyThreadStateGet.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyThreadState_declare PyThreadState *__pyx_tstate; +#define __Pyx_PyThreadState_assign __pyx_tstate = __Pyx_PyThreadState_Current; +#if PY_VERSION_HEX >= 0x030C00A6 +#define __Pyx_PyErr_Occurred() (__pyx_tstate->current_exception != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->current_exception ? (PyObject*) Py_TYPE(__pyx_tstate->current_exception) : (PyObject*) NULL) +#else +#define __Pyx_PyErr_Occurred() (__pyx_tstate->curexc_type != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->curexc_type) +#endif +#else +#define __Pyx_PyThreadState_declare +#define __Pyx_PyThreadState_assign +#define __Pyx_PyErr_Occurred() (PyErr_Occurred() != NULL) +#define __Pyx_PyErr_CurrentExceptionType() PyErr_Occurred() +#endif + +/* PyErrFetchRestore.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_Clear() __Pyx_ErrRestore(NULL, NULL, NULL) +#define __Pyx_ErrRestoreWithState(type, value, tb) __Pyx_ErrRestoreInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) __Pyx_ErrFetchInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) __Pyx_ErrRestoreInState(__pyx_tstate, type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) __Pyx_ErrFetchInState(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb); +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A6 +#define __Pyx_PyErr_SetNone(exc) (Py_INCREF(exc), __Pyx_ErrRestore((exc), NULL, NULL)) +#else +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#endif +#else +#define __Pyx_PyErr_Clear() PyErr_Clear() +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#define __Pyx_ErrRestoreWithState(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestoreInState(tstate, type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchInState(tstate, type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) PyErr_Fetch(type, value, tb) +#endif + +/* PyObjectGetAttrStr.proto */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GetAttrStr(o,n) PyObject_GetAttr(o,n) +#endif + +/* PyObjectGetAttrStrNoError.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name); + +/* GetBuiltinName.proto */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name); + +/* TupleAndListFromArray.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n); +static CYTHON_INLINE PyObject* __Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n); +#endif + +/* IncludeStringH.proto */ +#include + +/* BytesEquals.proto */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals); + +/* UnicodeEquals.proto */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals); + +/* fastcall.proto */ +#if CYTHON_AVOID_BORROWED_REFS + #define __Pyx_Arg_VARARGS(args, i) PySequence_GetItem(args, i) +#elif CYTHON_ASSUME_SAFE_MACROS + #define __Pyx_Arg_VARARGS(args, i) PyTuple_GET_ITEM(args, i) +#else + #define __Pyx_Arg_VARARGS(args, i) PyTuple_GetItem(args, i) +#endif +#if CYTHON_AVOID_BORROWED_REFS + #define __Pyx_Arg_NewRef_VARARGS(arg) __Pyx_NewRef(arg) + #define __Pyx_Arg_XDECREF_VARARGS(arg) Py_XDECREF(arg) +#else + #define __Pyx_Arg_NewRef_VARARGS(arg) arg + #define __Pyx_Arg_XDECREF_VARARGS(arg) +#endif +#define __Pyx_NumKwargs_VARARGS(kwds) PyDict_Size(kwds) +#define __Pyx_KwValues_VARARGS(args, nargs) NULL +#define __Pyx_GetKwValue_VARARGS(kw, kwvalues, s) __Pyx_PyDict_GetItemStrWithError(kw, s) +#define __Pyx_KwargsAsDict_VARARGS(kw, kwvalues) PyDict_Copy(kw) +#if CYTHON_METH_FASTCALL + #define __Pyx_Arg_FASTCALL(args, i) args[i] + #define __Pyx_NumKwargs_FASTCALL(kwds) PyTuple_GET_SIZE(kwds) + #define __Pyx_KwValues_FASTCALL(args, nargs) ((args) + (nargs)) + static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 + CYTHON_UNUSED static PyObject *__Pyx_KwargsAsDict_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues); + #else + #define __Pyx_KwargsAsDict_FASTCALL(kw, kwvalues) _PyStack_AsDict(kwvalues, kw) + #endif + #define __Pyx_Arg_NewRef_FASTCALL(arg) arg /* no-op, __Pyx_Arg_FASTCALL is direct and this needs + to have the same reference counting */ + #define __Pyx_Arg_XDECREF_FASTCALL(arg) +#else + #define __Pyx_Arg_FASTCALL __Pyx_Arg_VARARGS + #define __Pyx_NumKwargs_FASTCALL __Pyx_NumKwargs_VARARGS + #define __Pyx_KwValues_FASTCALL __Pyx_KwValues_VARARGS + #define __Pyx_GetKwValue_FASTCALL __Pyx_GetKwValue_VARARGS + #define __Pyx_KwargsAsDict_FASTCALL __Pyx_KwargsAsDict_VARARGS + #define __Pyx_Arg_NewRef_FASTCALL(arg) __Pyx_Arg_NewRef_VARARGS(arg) + #define __Pyx_Arg_XDECREF_FASTCALL(arg) __Pyx_Arg_XDECREF_VARARGS(arg) +#endif +#if CYTHON_COMPILING_IN_CPYTHON && CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_VARARGS(args, start), stop - start) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_FASTCALL(args, start), stop - start) +#else +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) PyTuple_GetSlice(args, start, stop) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) PyTuple_GetSlice(args, start, stop) +#endif + +/* RaiseArgTupleInvalid.proto */ +static void __Pyx_RaiseArgtupleInvalid(const char* func_name, int exact, + Py_ssize_t num_min, Py_ssize_t num_max, Py_ssize_t num_found); + +/* RaiseDoubleKeywords.proto */ +static void __Pyx_RaiseDoubleKeywordsError(const char* func_name, PyObject* kw_name); + +/* ParseKeywords.proto */ +static int __Pyx_ParseOptionalKeywords(PyObject *kwds, PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, PyObject *values[], Py_ssize_t num_pos_args, + const char* function_name); + +/* ArgTypeTest.proto */ +#define __Pyx_ArgTypeTest(obj, type, none_allowed, name, exact)\ + ((likely(__Pyx_IS_TYPE(obj, type) | (none_allowed && (obj == Py_None)))) ? 1 :\ + __Pyx__ArgTypeTest(obj, type, name, exact)) +static int __Pyx__ArgTypeTest(PyObject *obj, PyTypeObject *type, const char *name, int exact); + +/* RaiseException.proto */ +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause); + +/* PyFunctionFastCall.proto */ +#if CYTHON_FAST_PYCALL +#if !CYTHON_VECTORCALL +#define __Pyx_PyFunction_FastCall(func, args, nargs)\ + __Pyx_PyFunction_FastCallDict((func), (args), (nargs), NULL) +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs); +#endif +#define __Pyx_BUILD_ASSERT_EXPR(cond)\ + (sizeof(char [1 - 2*!(cond)]) - 1) +#ifndef Py_MEMBER_SIZE +#define Py_MEMBER_SIZE(type, member) sizeof(((type *)0)->member) +#endif +#if !CYTHON_VECTORCALL +#if PY_VERSION_HEX >= 0x03080000 + #include "frameobject.h" +#if PY_VERSION_HEX >= 0x030b00a6 && !CYTHON_COMPILING_IN_LIMITED_API + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif + #define __Pxy_PyFrame_Initialize_Offsets() + #define __Pyx_PyFrame_GetLocalsplus(frame) ((frame)->f_localsplus) +#else + static size_t __pyx_pyframe_localsplus_offset = 0; + #include "frameobject.h" + #define __Pxy_PyFrame_Initialize_Offsets()\ + ((void)__Pyx_BUILD_ASSERT_EXPR(sizeof(PyFrameObject) == offsetof(PyFrameObject, f_localsplus) + Py_MEMBER_SIZE(PyFrameObject, f_localsplus)),\ + (void)(__pyx_pyframe_localsplus_offset = ((size_t)PyFrame_Type.tp_basicsize) - Py_MEMBER_SIZE(PyFrameObject, f_localsplus))) + #define __Pyx_PyFrame_GetLocalsplus(frame)\ + (assert(__pyx_pyframe_localsplus_offset), (PyObject **)(((char *)(frame)) + __pyx_pyframe_localsplus_offset)) +#endif +#endif +#endif + +/* PyObjectCall.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw); +#else +#define __Pyx_PyObject_Call(func, arg, kw) PyObject_Call(func, arg, kw) +#endif + +/* PyObjectCallMethO.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg); +#endif + +/* PyObjectFastCall.proto */ +#define __Pyx_PyObject_FastCall(func, args, nargs) __Pyx_PyObject_FastCallDict(func, args, (size_t)(nargs), NULL) +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs); + +/* RaiseUnexpectedTypeError.proto */ +static int __Pyx_RaiseUnexpectedTypeError(const char *expected, PyObject *obj); + +/* GCCDiagnostics.proto */ +#if !defined(__INTEL_COMPILER) && defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 6)) +#define __Pyx_HAS_GCC_DIAGNOSTIC +#endif + +/* BuildPyUnicode.proto */ +static PyObject* __Pyx_PyUnicode_BuildFromAscii(Py_ssize_t ulength, char* chars, int clength, + int prepend_sign, char padding_char); + +/* CIntToPyUnicode.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_int(int value, Py_ssize_t width, char padding_char, char format_char); + +/* CIntToPyUnicode.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_Py_ssize_t(Py_ssize_t value, Py_ssize_t width, char padding_char, char format_char); + +/* JoinPyUnicode.proto */ +static PyObject* __Pyx_PyUnicode_Join(PyObject* value_tuple, Py_ssize_t value_count, Py_ssize_t result_ulength, + Py_UCS4 max_char); + +/* StrEquals.proto */ +#if PY_MAJOR_VERSION >= 3 +#define __Pyx_PyString_Equals __Pyx_PyUnicode_Equals +#else +#define __Pyx_PyString_Equals __Pyx_PyBytes_Equals +#endif + +/* PyObjectFormatSimple.proto */ +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + PyObject_Format(s, f)) +#elif PY_MAJOR_VERSION < 3 + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + likely(PyString_CheckExact(s)) ? PyUnicode_FromEncodedObject(s, NULL, "strict") :\ + PyObject_Format(s, f)) +#elif CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + likely(PyLong_CheckExact(s)) ? PyLong_Type.tp_repr(s) :\ + likely(PyFloat_CheckExact(s)) ? PyFloat_Type.tp_repr(s) :\ + PyObject_Format(s, f)) +#else + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + PyObject_Format(s, f)) +#endif + +CYTHON_UNUSED static int __pyx_array_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +static PyObject *__pyx_array_get_memview(struct __pyx_array_obj *); /*proto*/ +/* GetAttr.proto */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr(PyObject *, PyObject *); + +/* GetItemInt.proto */ +#define __Pyx_GetItemInt(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_Fast(o, (Py_ssize_t)i, is_list, wraparound, boundscheck) :\ + (is_list ? (PyErr_SetString(PyExc_IndexError, "list index out of range"), (PyObject*)NULL) :\ + __Pyx_GetItemInt_Generic(o, to_py_func(i)))) +#define __Pyx_GetItemInt_List(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_List_Fast(o, (Py_ssize_t)i, wraparound, boundscheck) :\ + (PyErr_SetString(PyExc_IndexError, "list index out of range"), (PyObject*)NULL)) +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_List_Fast(PyObject *o, Py_ssize_t i, + int wraparound, int boundscheck); +#define __Pyx_GetItemInt_Tuple(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_Tuple_Fast(o, (Py_ssize_t)i, wraparound, boundscheck) :\ + (PyErr_SetString(PyExc_IndexError, "tuple index out of range"), (PyObject*)NULL)) +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Tuple_Fast(PyObject *o, Py_ssize_t i, + int wraparound, int boundscheck); +static PyObject *__Pyx_GetItemInt_Generic(PyObject *o, PyObject* j); +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Fast(PyObject *o, Py_ssize_t i, + int is_list, int wraparound, int boundscheck); + +/* PyObjectCallOneArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg); + +/* ObjectGetItem.proto */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject *__Pyx_PyObject_GetItem(PyObject *obj, PyObject *key); +#else +#define __Pyx_PyObject_GetItem(obj, key) PyObject_GetItem(obj, key) +#endif + +/* KeywordStringCheck.proto */ +static int __Pyx_CheckKeywordStrings(PyObject *kw, const char* function_name, int kw_allowed); + +/* DivInt[Py_ssize_t].proto */ +static CYTHON_INLINE Py_ssize_t __Pyx_div_Py_ssize_t(Py_ssize_t, Py_ssize_t); + +/* UnaryNegOverflows.proto */ +#define __Pyx_UNARY_NEG_WOULD_OVERFLOW(x)\ + (((x) < 0) & ((unsigned long)(x) == 0-(unsigned long)(x))) + +/* GetAttr3.proto */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr3(PyObject *, PyObject *, PyObject *); + +/* PyDictVersioning.proto */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +#define __PYX_DICT_VERSION_INIT ((PY_UINT64_T) -1) +#define __PYX_GET_DICT_VERSION(dict) (((PyDictObject*)(dict))->ma_version_tag) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var)\ + (version_var) = __PYX_GET_DICT_VERSION(dict);\ + (cache_var) = (value); +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + if (likely(__PYX_GET_DICT_VERSION(DICT) == __pyx_dict_version)) {\ + (VAR) = __pyx_dict_cached_value;\ + } else {\ + (VAR) = __pyx_dict_cached_value = (LOOKUP);\ + __pyx_dict_version = __PYX_GET_DICT_VERSION(DICT);\ + }\ +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj); +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj); +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version); +#else +#define __PYX_GET_DICT_VERSION(dict) (0) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var) +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) (VAR) = (LOOKUP); +#endif + +/* GetModuleGlobalName.proto */ +#if CYTHON_USE_DICT_VERSIONS +#define __Pyx_GetModuleGlobalName(var, name) do {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + (var) = (likely(__pyx_dict_version == __PYX_GET_DICT_VERSION(__pyx_d))) ?\ + (likely(__pyx_dict_cached_value) ? __Pyx_NewRef(__pyx_dict_cached_value) : __Pyx_GetBuiltinName(name)) :\ + __Pyx__GetModuleGlobalName(name, &__pyx_dict_version, &__pyx_dict_cached_value);\ +} while(0) +#define __Pyx_GetModuleGlobalNameUncached(var, name) do {\ + PY_UINT64_T __pyx_dict_version;\ + PyObject *__pyx_dict_cached_value;\ + (var) = __Pyx__GetModuleGlobalName(name, &__pyx_dict_version, &__pyx_dict_cached_value);\ +} while(0) +static PyObject *__Pyx__GetModuleGlobalName(PyObject *name, PY_UINT64_T *dict_version, PyObject **dict_cached_value); +#else +#define __Pyx_GetModuleGlobalName(var, name) (var) = __Pyx__GetModuleGlobalName(name) +#define __Pyx_GetModuleGlobalNameUncached(var, name) (var) = __Pyx__GetModuleGlobalName(name) +static CYTHON_INLINE PyObject *__Pyx__GetModuleGlobalName(PyObject *name); +#endif + +/* AssertionsEnabled.proto */ +#if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX < 0x02070600 && !defined(Py_OptimizeFlag) + #define __Pyx_init_assertions_enabled() (0) + #define __pyx_assertions_enabled() (1) +#elif CYTHON_COMPILING_IN_LIMITED_API || (CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030C0000) + static int __pyx_assertions_enabled_flag; + #define __pyx_assertions_enabled() (__pyx_assertions_enabled_flag) + static int __Pyx_init_assertions_enabled(void) { + PyObject *builtins, *debug, *debug_str; + int flag; + builtins = PyEval_GetBuiltins(); + if (!builtins) goto bad; + debug_str = PyUnicode_FromStringAndSize("__debug__", 9); + if (!debug_str) goto bad; + debug = PyObject_GetItem(builtins, debug_str); + Py_DECREF(debug_str); + if (!debug) goto bad; + flag = PyObject_IsTrue(debug); + Py_DECREF(debug); + if (flag == -1) goto bad; + __pyx_assertions_enabled_flag = flag; + return 0; + bad: + __pyx_assertions_enabled_flag = 1; + return -1; + } +#else + #define __Pyx_init_assertions_enabled() (0) + #define __pyx_assertions_enabled() (!Py_OptimizeFlag) +#endif + +/* RaiseTooManyValuesToUnpack.proto */ +static CYTHON_INLINE void __Pyx_RaiseTooManyValuesError(Py_ssize_t expected); + +/* RaiseNeedMoreValuesToUnpack.proto */ +static CYTHON_INLINE void __Pyx_RaiseNeedMoreValuesError(Py_ssize_t index); + +/* RaiseNoneIterError.proto */ +static CYTHON_INLINE void __Pyx_RaiseNoneNotIterableError(void); + +/* ExtTypeTest.proto */ +static CYTHON_INLINE int __Pyx_TypeTest(PyObject *obj, PyTypeObject *type); + +/* GetTopmostException.proto */ +#if CYTHON_USE_EXC_INFO_STACK && CYTHON_FAST_THREAD_STATE +static _PyErr_StackItem * __Pyx_PyErr_GetTopmostException(PyThreadState *tstate); +#endif + +/* SaveResetException.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_ExceptionSave(type, value, tb) __Pyx__ExceptionSave(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx__ExceptionSave(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#define __Pyx_ExceptionReset(type, value, tb) __Pyx__ExceptionReset(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx__ExceptionReset(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb); +#else +#define __Pyx_ExceptionSave(type, value, tb) PyErr_GetExcInfo(type, value, tb) +#define __Pyx_ExceptionReset(type, value, tb) PyErr_SetExcInfo(type, value, tb) +#endif + +/* GetException.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_GetException(type, value, tb) __Pyx__GetException(__pyx_tstate, type, value, tb) +static int __Pyx__GetException(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#else +static int __Pyx_GetException(PyObject **type, PyObject **value, PyObject **tb); +#endif + +/* SwapException.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_ExceptionSwap(type, value, tb) __Pyx__ExceptionSwap(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx__ExceptionSwap(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#else +static CYTHON_INLINE void __Pyx_ExceptionSwap(PyObject **type, PyObject **value, PyObject **tb); +#endif + +/* Import.proto */ +static PyObject *__Pyx_Import(PyObject *name, PyObject *from_list, int level); + +/* ImportDottedModule.proto */ +static PyObject *__Pyx_ImportDottedModule(PyObject *name, PyObject *parts_tuple); +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_ImportDottedModule_WalkParts(PyObject *module, PyObject *name, PyObject *parts_tuple); +#endif + +/* FastTypeChecks.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_TypeCheck(obj, type) __Pyx_IsSubtype(Py_TYPE(obj), (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) __Pyx_IsAnySubtype2(Py_TYPE(obj), (PyTypeObject *)type1, (PyTypeObject *)type2) +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches(PyObject *err, PyObject *type); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches2(PyObject *err, PyObject *type1, PyObject *type2); +#else +#define __Pyx_TypeCheck(obj, type) PyObject_TypeCheck(obj, (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) (PyObject_TypeCheck(obj, (PyTypeObject *)type1) || PyObject_TypeCheck(obj, (PyTypeObject *)type2)) +#define __Pyx_PyErr_GivenExceptionMatches(err, type) PyErr_GivenExceptionMatches(err, type) +#define __Pyx_PyErr_GivenExceptionMatches2(err, type1, type2) (PyErr_GivenExceptionMatches(err, type1) || PyErr_GivenExceptionMatches(err, type2)) +#endif +#define __Pyx_PyErr_ExceptionMatches2(err1, err2) __Pyx_PyErr_GivenExceptionMatches2(__Pyx_PyErr_CurrentExceptionType(), err1, err2) +#define __Pyx_PyException_Check(obj) __Pyx_TypeCheck(obj, PyExc_Exception) + +CYTHON_UNUSED static int __pyx_memoryview_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +/* ListCompAppend.proto */ +#if CYTHON_USE_PYLIST_INTERNALS && CYTHON_ASSUME_SAFE_MACROS +static CYTHON_INLINE int __Pyx_ListComp_Append(PyObject* list, PyObject* x) { + PyListObject* L = (PyListObject*) list; + Py_ssize_t len = Py_SIZE(list); + if (likely(L->allocated > len)) { + Py_INCREF(x); + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 + L->ob_item[len] = x; + #else + PyList_SET_ITEM(list, len, x); + #endif + __Pyx_SET_SIZE(list, len + 1); + return 0; + } + return PyList_Append(list, x); +} +#else +#define __Pyx_ListComp_Append(L,x) PyList_Append(L,x) +#endif + +/* PySequenceMultiply.proto */ +#define __Pyx_PySequence_Multiply_Left(mul, seq) __Pyx_PySequence_Multiply(seq, mul) +static CYTHON_INLINE PyObject* __Pyx_PySequence_Multiply(PyObject *seq, Py_ssize_t mul); + +/* SetItemInt.proto */ +#define __Pyx_SetItemInt(o, i, v, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_SetItemInt_Fast(o, (Py_ssize_t)i, v, is_list, wraparound, boundscheck) :\ + (is_list ? (PyErr_SetString(PyExc_IndexError, "list assignment index out of range"), -1) :\ + __Pyx_SetItemInt_Generic(o, to_py_func(i), v))) +static int __Pyx_SetItemInt_Generic(PyObject *o, PyObject *j, PyObject *v); +static CYTHON_INLINE int __Pyx_SetItemInt_Fast(PyObject *o, Py_ssize_t i, PyObject *v, + int is_list, int wraparound, int boundscheck); + +/* RaiseUnboundLocalError.proto */ +static CYTHON_INLINE void __Pyx_RaiseUnboundLocalError(const char *varname); + +/* DivInt[long].proto */ +static CYTHON_INLINE long __Pyx_div_long(long, long); + +/* PySequenceContains.proto */ +static CYTHON_INLINE int __Pyx_PySequence_ContainsTF(PyObject* item, PyObject* seq, int eq) { + int result = PySequence_Contains(seq, item); + return unlikely(result < 0) ? result : (result == (eq == Py_EQ)); +} + +/* ImportFrom.proto */ +static PyObject* __Pyx_ImportFrom(PyObject* module, PyObject* name); + +/* HasAttr.proto */ +#if __PYX_LIMITED_VERSION_HEX >= 0x030d00A1 +#define __Pyx_HasAttr(o, n) PyObject_HasAttrWithError(o, n) +#else +static CYTHON_INLINE int __Pyx_HasAttr(PyObject *, PyObject *); +#endif + +/* MoveIfSupported.proto */ +#if CYTHON_USE_CPP_STD_MOVE + #include + #define __PYX_STD_MOVE_IF_SUPPORTED(x) std::move(x) +#else + #define __PYX_STD_MOVE_IF_SUPPORTED(x) x +#endif + +/* BufferIndexError.proto */ +static void __Pyx_RaiseBufferIndexError(int axis); + +/* PyObject_GenericGetAttrNoDict.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttrNoDict PyObject_GenericGetAttr +#endif + +/* PyObject_GenericGetAttr.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttr PyObject_GenericGetAttr +#endif + +/* TypeImport.proto */ +#ifndef __PYX_HAVE_RT_ImportType_proto_3_0_8 +#define __PYX_HAVE_RT_ImportType_proto_3_0_8 +#if defined (__STDC_VERSION__) && __STDC_VERSION__ >= 201112L +#include +#endif +#if (defined (__STDC_VERSION__) && __STDC_VERSION__ >= 201112L) || __cplusplus >= 201103L +#define __PYX_GET_STRUCT_ALIGNMENT_3_0_8(s) alignof(s) +#else +#define __PYX_GET_STRUCT_ALIGNMENT_3_0_8(s) sizeof(void*) +#endif +enum __Pyx_ImportType_CheckSize_3_0_8 { + __Pyx_ImportType_CheckSize_Error_3_0_8 = 0, + __Pyx_ImportType_CheckSize_Warn_3_0_8 = 1, + __Pyx_ImportType_CheckSize_Ignore_3_0_8 = 2 +}; +static PyTypeObject *__Pyx_ImportType_3_0_8(PyObject* module, const char *module_name, const char *class_name, size_t size, size_t alignment, enum __Pyx_ImportType_CheckSize_3_0_8 check_size); +#endif + +/* IncludeStructmemberH.proto */ +#include + +/* FixUpExtensionType.proto */ +#if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type); +#endif + +/* PyObjectCallNoArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func); + +/* PyObjectGetMethod.proto */ +static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method); + +/* PyObjectCallMethod0.proto */ +static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name); + +/* ValidateBasesTuple.proto */ +#if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases); +#endif + +/* PyType_Ready.proto */ +CYTHON_UNUSED static int __Pyx_PyType_Ready(PyTypeObject *t); + +/* SetupReduce.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce(PyObject* type_obj); +#endif + +/* SetVTable.proto */ +static int __Pyx_SetVtable(PyTypeObject* typeptr , void* vtable); + +/* GetVTable.proto */ +static void* __Pyx_GetVtable(PyTypeObject *type); + +/* MergeVTables.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_MergeVtables(PyTypeObject *type); +#endif + +/* FetchSharedCythonModule.proto */ +static PyObject *__Pyx_FetchSharedCythonABIModule(void); + +/* FetchCommonType.proto */ +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type); +#else +static PyTypeObject* __Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases); +#endif + +/* PyMethodNew.proto */ +#if CYTHON_COMPILING_IN_LIMITED_API +static PyObject *__Pyx_PyMethod_New(PyObject *func, PyObject *self, PyObject *typ) { + PyObject *typesModule=NULL, *methodType=NULL, *result=NULL; + CYTHON_UNUSED_VAR(typ); + if (!self) + return __Pyx_NewRef(func); + typesModule = PyImport_ImportModule("types"); + if (!typesModule) return NULL; + methodType = PyObject_GetAttrString(typesModule, "MethodType"); + Py_DECREF(typesModule); + if (!methodType) return NULL; + result = PyObject_CallFunctionObjArgs(methodType, func, self, NULL); + Py_DECREF(methodType); + return result; +} +#elif PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_PyMethod_New(PyObject *func, PyObject *self, PyObject *typ) { + CYTHON_UNUSED_VAR(typ); + if (!self) + return __Pyx_NewRef(func); + return PyMethod_New(func, self); +} +#else + #define __Pyx_PyMethod_New PyMethod_New +#endif + +/* PyVectorcallFastCallDict.proto */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw); +#endif + +/* CythonFunctionShared.proto */ +#define __Pyx_CyFunction_USED +#define __Pyx_CYFUNCTION_STATICMETHOD 0x01 +#define __Pyx_CYFUNCTION_CLASSMETHOD 0x02 +#define __Pyx_CYFUNCTION_CCLASS 0x04 +#define __Pyx_CYFUNCTION_COROUTINE 0x08 +#define __Pyx_CyFunction_GetClosure(f)\ + (((__pyx_CyFunctionObject *) (f))->func_closure) +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_CyFunction_GetClassObj(f)\ + (((__pyx_CyFunctionObject *) (f))->func_classobj) +#else + #define __Pyx_CyFunction_GetClassObj(f)\ + ((PyObject*) ((PyCMethodObject *) (f))->mm_class) +#endif +#define __Pyx_CyFunction_SetClassObj(f, classobj)\ + __Pyx__CyFunction_SetClassObj((__pyx_CyFunctionObject *) (f), (classobj)) +#define __Pyx_CyFunction_Defaults(type, f)\ + ((type *)(((__pyx_CyFunctionObject *) (f))->defaults)) +#define __Pyx_CyFunction_SetDefaultsGetter(f, g)\ + ((__pyx_CyFunctionObject *) (f))->defaults_getter = (g) +typedef struct { +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject_HEAD + PyObject *func; +#elif PY_VERSION_HEX < 0x030900B1 + PyCFunctionObject func; +#else + PyCMethodObject func; +#endif +#if CYTHON_BACKPORT_VECTORCALL + __pyx_vectorcallfunc func_vectorcall; +#endif +#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API + PyObject *func_weakreflist; +#endif + PyObject *func_dict; + PyObject *func_name; + PyObject *func_qualname; + PyObject *func_doc; + PyObject *func_globals; + PyObject *func_code; + PyObject *func_closure; +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + PyObject *func_classobj; +#endif + void *defaults; + int defaults_pyobjects; + size_t defaults_size; + int flags; + PyObject *defaults_tuple; + PyObject *defaults_kwdict; + PyObject *(*defaults_getter)(PyObject *); + PyObject *func_annotations; + PyObject *func_is_coroutine; +} __pyx_CyFunctionObject; +#undef __Pyx_CyOrPyCFunction_Check +#define __Pyx_CyFunction_Check(obj) __Pyx_TypeCheck(obj, __pyx_CyFunctionType) +#define __Pyx_CyOrPyCFunction_Check(obj) __Pyx_TypeCheck2(obj, __pyx_CyFunctionType, &PyCFunction_Type) +#define __Pyx_CyFunction_CheckExact(obj) __Pyx_IS_TYPE(obj, __pyx_CyFunctionType) +static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc); +#undef __Pyx_IsSameCFunction +#define __Pyx_IsSameCFunction(func, cfunc) __Pyx__IsSameCyOrCFunction(func, cfunc) +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject* op, PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj); +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *m, + size_t size, + int pyobjects); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *m, + PyObject *tuple); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *m, + PyObject *dict); +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *m, + PyObject *dict); +static int __pyx_CyFunction_init(PyObject *module); +#if CYTHON_METH_FASTCALL +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +#if CYTHON_BACKPORT_VECTORCALL +#define __Pyx_CyFunction_func_vectorcall(f) (((__pyx_CyFunctionObject*)f)->func_vectorcall) +#else +#define __Pyx_CyFunction_func_vectorcall(f) (((PyCFunctionObject*)f)->vectorcall) +#endif +#endif + +/* CythonFunction.proto */ +static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); + +/* CLineInTraceback.proto */ +#ifdef CYTHON_CLINE_IN_TRACEBACK +#define __Pyx_CLineForTraceback(tstate, c_line) (((CYTHON_CLINE_IN_TRACEBACK)) ? c_line : 0) +#else +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line); +#endif + +/* CodeObjectCache.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +typedef struct { + PyCodeObject* code_object; + int code_line; +} __Pyx_CodeObjectCacheEntry; +struct __Pyx_CodeObjectCache { + int count; + int max_count; + __Pyx_CodeObjectCacheEntry* entries; +}; +static struct __Pyx_CodeObjectCache __pyx_code_cache = {0,0,NULL}; +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line); +static PyCodeObject *__pyx_find_code_object(int code_line); +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object); +#endif + +/* AddTraceback.proto */ +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename); + +#if PY_MAJOR_VERSION < 3 + static int __Pyx_GetBuffer(PyObject *obj, Py_buffer *view, int flags); + static void __Pyx_ReleaseBuffer(Py_buffer *view); +#else + #define __Pyx_GetBuffer PyObject_GetBuffer + #define __Pyx_ReleaseBuffer PyBuffer_Release +#endif + + +/* BufferStructDeclare.proto */ +typedef struct { + Py_ssize_t shape, strides, suboffsets; +} __Pyx_Buf_DimInfo; +typedef struct { + size_t refcount; + Py_buffer pybuffer; +} __Pyx_Buffer; +typedef struct { + __Pyx_Buffer *rcbuffer; + char *data; + __Pyx_Buf_DimInfo diminfo[8]; +} __Pyx_LocalBuf_ND; + +/* MemviewSliceIsContig.proto */ +static int __pyx_memviewslice_is_contig(const __Pyx_memviewslice mvs, char order, int ndim); + +/* OverlappingSlices.proto */ +static int __pyx_slices_overlap(__Pyx_memviewslice *slice1, + __Pyx_memviewslice *slice2, + int ndim, size_t itemsize); + +/* IsLittleEndian.proto */ +static CYTHON_INLINE int __Pyx_Is_Little_Endian(void); + +/* BufferFormatCheck.proto */ +static const char* __Pyx_BufFmt_CheckString(__Pyx_BufFmt_Context* ctx, const char* ts); +static void __Pyx_BufFmt_Init(__Pyx_BufFmt_Context* ctx, + __Pyx_BufFmt_StackElem* stack, + __Pyx_TypeInfo* type); + +/* TypeInfoCompare.proto */ +static int __pyx_typeinfo_cmp(__Pyx_TypeInfo *a, __Pyx_TypeInfo *b); + +/* MemviewSliceValidateAndInit.proto */ +static int __Pyx_ValidateAndInit_memviewslice( + int *axes_specs, + int c_or_f_flag, + int buf_flags, + int ndim, + __Pyx_TypeInfo *dtype, + __Pyx_BufFmt_StackElem stack[], + __Pyx_memviewslice *memviewslice, + PyObject *original_obj); + +/* ObjectToMemviewSlice.proto */ +static CYTHON_INLINE __Pyx_memviewslice __Pyx_PyObject_to_MemoryviewSlice_ds_float(PyObject *, int writable_flag); + +/* MemviewDtypeToObject.proto */ +static CYTHON_INLINE PyObject *__pyx_memview_get_float(const char *itemp); +static CYTHON_INLINE int __pyx_memview_set_float(const char *itemp, PyObject *obj); + +/* MemviewSliceCopyTemplate.proto */ +static __Pyx_memviewslice +__pyx_memoryview_copy_new_contig(const __Pyx_memviewslice *from_mvs, + const char *mode, int ndim, + size_t sizeof_dtype, int contig_flag, + int dtype_is_object); + +/* MemviewSliceInit.proto */ +#define __Pyx_BUF_MAX_NDIMS %(BUF_MAX_NDIMS)d +#define __Pyx_MEMVIEW_DIRECT 1 +#define __Pyx_MEMVIEW_PTR 2 +#define __Pyx_MEMVIEW_FULL 4 +#define __Pyx_MEMVIEW_CONTIG 8 +#define __Pyx_MEMVIEW_STRIDED 16 +#define __Pyx_MEMVIEW_FOLLOW 32 +#define __Pyx_IS_C_CONTIG 1 +#define __Pyx_IS_F_CONTIG 2 +static int __Pyx_init_memviewslice( + struct __pyx_memoryview_obj *memview, + int ndim, + __Pyx_memviewslice *memviewslice, + int memview_is_new_reference); +static CYTHON_INLINE int __pyx_add_acquisition_count_locked( + __pyx_atomic_int_type *acquisition_count, PyThread_type_lock lock); +static CYTHON_INLINE int __pyx_sub_acquisition_count_locked( + __pyx_atomic_int_type *acquisition_count, PyThread_type_lock lock); +#define __pyx_get_slice_count_pointer(memview) (&memview->acquisition_count) +#define __PYX_INC_MEMVIEW(slice, have_gil) __Pyx_INC_MEMVIEW(slice, have_gil, __LINE__) +#define __PYX_XCLEAR_MEMVIEW(slice, have_gil) __Pyx_XCLEAR_MEMVIEW(slice, have_gil, __LINE__) +static CYTHON_INLINE void __Pyx_INC_MEMVIEW(__Pyx_memviewslice *, int, int); +static CYTHON_INLINE void __Pyx_XCLEAR_MEMVIEW(__Pyx_memviewslice *, int, int); + +/* CIntFromPy.proto */ +static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *); + +/* CppExceptionConversion.proto */ +#ifndef __Pyx_CppExn2PyErr +#include +#include +#include +#include +static void __Pyx_CppExn2PyErr() { + try { + if (PyErr_Occurred()) + ; // let the latest Python exn pass through and ignore the current one + else + throw; + } catch (const std::bad_alloc& exn) { + PyErr_SetString(PyExc_MemoryError, exn.what()); + } catch (const std::bad_cast& exn) { + PyErr_SetString(PyExc_TypeError, exn.what()); + } catch (const std::bad_typeid& exn) { + PyErr_SetString(PyExc_TypeError, exn.what()); + } catch (const std::domain_error& exn) { + PyErr_SetString(PyExc_ValueError, exn.what()); + } catch (const std::invalid_argument& exn) { + PyErr_SetString(PyExc_ValueError, exn.what()); + } catch (const std::ios_base::failure& exn) { + PyErr_SetString(PyExc_IOError, exn.what()); + } catch (const std::out_of_range& exn) { + PyErr_SetString(PyExc_IndexError, exn.what()); + } catch (const std::overflow_error& exn) { + PyErr_SetString(PyExc_OverflowError, exn.what()); + } catch (const std::range_error& exn) { + PyErr_SetString(PyExc_ArithmeticError, exn.what()); + } catch (const std::underflow_error& exn) { + PyErr_SetString(PyExc_ArithmeticError, exn.what()); + } catch (const std::exception& exn) { + PyErr_SetString(PyExc_RuntimeError, exn.what()); + } + catch (...) + { + PyErr_SetString(PyExc_RuntimeError, "Unknown exception"); + } +} +#endif + +/* None.proto */ +#include + +/* CIntFromPy.proto */ +static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_int(int value); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value); + +/* CIntFromPy.proto */ +static CYTHON_INLINE char __Pyx_PyInt_As_char(PyObject *); + +/* FormatTypeName.proto */ +#if CYTHON_COMPILING_IN_LIMITED_API +typedef PyObject *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%U" +static __Pyx_TypeName __Pyx_PyType_GetName(PyTypeObject* tp); +#define __Pyx_DECREF_TypeName(obj) Py_XDECREF(obj) +#else +typedef const char *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%.200s" +#define __Pyx_PyType_GetName(tp) ((tp)->tp_name) +#define __Pyx_DECREF_TypeName(obj) +#endif + +/* CheckBinaryVersion.proto */ +static unsigned long __Pyx_get_runtime_version(void); +static int __Pyx_check_binary_version(unsigned long ct_version, unsigned long rt_version, int allow_newer); + +/* InitStrings.proto */ +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t); + +/* #### Code section: module_declarations ### */ +static PyObject *__pyx_array_get_memview(struct __pyx_array_obj *__pyx_v_self); /* proto*/ +static char *__pyx_memoryview_get_item_pointer(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index); /* proto*/ +static PyObject *__pyx_memoryview_is_slice(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj); /* proto*/ +static PyObject *__pyx_memoryview_setitem_slice_assignment(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_dst, PyObject *__pyx_v_src); /* proto*/ +static PyObject *__pyx_memoryview_setitem_slice_assign_scalar(struct __pyx_memoryview_obj *__pyx_v_self, struct __pyx_memoryview_obj *__pyx_v_dst, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryview_setitem_indexed(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryview_convert_item_to_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp); /* proto*/ +static PyObject *__pyx_memoryview_assign_item_from_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryview__get_base(struct __pyx_memoryview_obj *__pyx_v_self); /* proto*/ +static PyObject *__pyx_memoryviewslice_convert_item_to_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp); /* proto*/ +static PyObject *__pyx_memoryviewslice_assign_item_from_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryviewslice__get_base(struct __pyx_memoryviewslice_obj *__pyx_v_self); /* proto*/ + +/* Module declarations from "libcpp" */ + +/* Module declarations from "libc.string" */ + +/* Module declarations from "libcpp.string" */ + +/* Module declarations from "libcpp.vector" */ + +/* Module declarations from "libcpp.utility" */ + +/* Module declarations from "libcpp.set" */ + +/* Module declarations from "libc.stdint" */ + +/* Module declarations from "cereal.visionipc.visionipc" */ + +/* Module declarations from "selfdrive.modeld.runners.snpemodel" */ + +/* Module declarations from "cereal.visionipc.visionipc_pyx" */ + +/* Module declarations from "selfdrive.modeld.models.commonmodel_pyx" */ + +/* Module declarations from "selfdrive.modeld.runners.runmodel" */ + +/* Module declarations from "selfdrive.modeld.runners.runmodel_pyx" */ + +/* Module declarations from "selfdrive.modeld.runners.snpemodel_pyx" */ +static PyObject *__pyx_collections_abc_Sequence = 0; +static PyObject *generic = 0; +static PyObject *strided = 0; +static PyObject *indirect = 0; +static PyObject *contiguous = 0; +static PyObject *indirect_contiguous = 0; +static int __pyx_memoryview_thread_locks_used; +static PyThread_type_lock __pyx_memoryview_thread_locks[8]; +static std::string __pyx_convert_string_from_py_std__in_string(PyObject *); /*proto*/ +static int __pyx_array_allocate_buffer(struct __pyx_array_obj *); /*proto*/ +static struct __pyx_array_obj *__pyx_array_new(PyObject *, Py_ssize_t, char *, char *, char *); /*proto*/ +static PyObject *__pyx_memoryview_new(PyObject *, int, int, __Pyx_TypeInfo *); /*proto*/ +static CYTHON_INLINE int __pyx_memoryview_check(PyObject *); /*proto*/ +static PyObject *_unellipsify(PyObject *, int); /*proto*/ +static int assert_direct_dimensions(Py_ssize_t *, int); /*proto*/ +static struct __pyx_memoryview_obj *__pyx_memview_slice(struct __pyx_memoryview_obj *, PyObject *); /*proto*/ +static int __pyx_memoryview_slice_memviewslice(__Pyx_memviewslice *, Py_ssize_t, Py_ssize_t, Py_ssize_t, int, int, int *, Py_ssize_t, Py_ssize_t, Py_ssize_t, int, int, int, int); /*proto*/ +static char *__pyx_pybuffer_index(Py_buffer *, char *, Py_ssize_t, Py_ssize_t); /*proto*/ +static int __pyx_memslice_transpose(__Pyx_memviewslice *); /*proto*/ +static PyObject *__pyx_memoryview_fromslice(__Pyx_memviewslice, int, PyObject *(*)(char *), int (*)(char *, PyObject *), int); /*proto*/ +static __Pyx_memviewslice *__pyx_memoryview_get_slice_from_memoryview(struct __pyx_memoryview_obj *, __Pyx_memviewslice *); /*proto*/ +static void __pyx_memoryview_slice_copy(struct __pyx_memoryview_obj *, __Pyx_memviewslice *); /*proto*/ +static PyObject *__pyx_memoryview_copy_object(struct __pyx_memoryview_obj *); /*proto*/ +static PyObject *__pyx_memoryview_copy_object_from_slice(struct __pyx_memoryview_obj *, __Pyx_memviewslice *); /*proto*/ +static Py_ssize_t abs_py_ssize_t(Py_ssize_t); /*proto*/ +static char __pyx_get_best_slice_order(__Pyx_memviewslice *, int); /*proto*/ +static void _copy_strided_to_strided(char *, Py_ssize_t *, char *, Py_ssize_t *, Py_ssize_t *, Py_ssize_t *, int, size_t); /*proto*/ +static void copy_strided_to_strided(__Pyx_memviewslice *, __Pyx_memviewslice *, int, size_t); /*proto*/ +static Py_ssize_t __pyx_memoryview_slice_get_size(__Pyx_memviewslice *, int); /*proto*/ +static Py_ssize_t __pyx_fill_contig_strides_array(Py_ssize_t *, Py_ssize_t *, Py_ssize_t, int, char); /*proto*/ +static void *__pyx_memoryview_copy_data_to_temp(__Pyx_memviewslice *, __Pyx_memviewslice *, char, int); /*proto*/ +static int __pyx_memoryview_err_extents(int, Py_ssize_t, Py_ssize_t); /*proto*/ +static int __pyx_memoryview_err_dim(PyObject *, PyObject *, int); /*proto*/ +static int __pyx_memoryview_err(PyObject *, PyObject *); /*proto*/ +static int __pyx_memoryview_err_no_memory(void); /*proto*/ +static int __pyx_memoryview_copy_contents(__Pyx_memviewslice, __Pyx_memviewslice, int, int, int); /*proto*/ +static void __pyx_memoryview_broadcast_leading(__Pyx_memviewslice *, int, int); /*proto*/ +static void __pyx_memoryview_refcount_copying(__Pyx_memviewslice *, int, int, int); /*proto*/ +static void __pyx_memoryview_refcount_objects_in_slice_with_gil(char *, Py_ssize_t *, Py_ssize_t *, int, int); /*proto*/ +static void __pyx_memoryview_refcount_objects_in_slice(char *, Py_ssize_t *, Py_ssize_t *, int, int); /*proto*/ +static void __pyx_memoryview_slice_assign_scalar(__Pyx_memviewslice *, int, size_t, void *, int); /*proto*/ +static void __pyx_memoryview__slice_assign_scalar(char *, Py_ssize_t *, Py_ssize_t *, int, size_t, void *); /*proto*/ +static PyObject *__pyx_unpickle_Enum__set_state(struct __pyx_MemviewEnum_obj *, PyObject *); /*proto*/ +/* #### Code section: typeinfo ### */ +static __Pyx_TypeInfo __Pyx_TypeInfo_float = { "float", NULL, sizeof(float), { 0 }, 0, 'R', 0, 0 }; +/* #### Code section: before_global_var ### */ +#define __Pyx_MODULE_NAME "selfdrive.modeld.runners.snpemodel_pyx" +extern int __pyx_module_is_main_selfdrive__modeld__runners__snpemodel_pyx; +int __pyx_module_is_main_selfdrive__modeld__runners__snpemodel_pyx = 0; + +/* Implementation of "selfdrive.modeld.runners.snpemodel_pyx" */ +/* #### Code section: global_var ### */ +static PyObject *__pyx_builtin_TypeError; +static PyObject *__pyx_builtin___import__; +static PyObject *__pyx_builtin_ValueError; +static PyObject *__pyx_builtin_MemoryError; +static PyObject *__pyx_builtin_enumerate; +static PyObject *__pyx_builtin_range; +static PyObject *__pyx_builtin_AssertionError; +static PyObject *__pyx_builtin_Ellipsis; +static PyObject *__pyx_builtin_id; +static PyObject *__pyx_builtin_IndexError; +/* #### Code section: string_decls ### */ +static const char __pyx_k_[] = ": "; +static const char __pyx_k_O[] = "O"; +static const char __pyx_k_c[] = "c"; +static const char __pyx_k__2[] = "."; +static const char __pyx_k__3[] = "*"; +static const char __pyx_k__6[] = "'"; +static const char __pyx_k__7[] = ")"; +static const char __pyx_k_gc[] = "gc"; +static const char __pyx_k_id[] = "id"; +static const char __pyx_k_os[] = "os"; +static const char __pyx_k__24[] = "?"; +static const char __pyx_k_abc[] = "abc"; +static const char __pyx_k_and[] = " and "; +static const char __pyx_k_got[] = " (got "; +static const char __pyx_k_new[] = "__new__"; +static const char __pyx_k_obj[] = "obj"; +static const char __pyx_k_sys[] = "sys"; +static const char __pyx_k_base[] = "base"; +static const char __pyx_k_dict[] = "__dict__"; +static const char __pyx_k_main[] = "__main__"; +static const char __pyx_k_mode[] = "mode"; +static const char __pyx_k_name[] = "name"; +static const char __pyx_k_ndim[] = "ndim"; +static const char __pyx_k_pack[] = "pack"; +static const char __pyx_k_path[] = "path"; +static const char __pyx_k_self[] = "self"; +static const char __pyx_k_size[] = "size"; +static const char __pyx_k_spec[] = "__spec__"; +static const char __pyx_k_step[] = "step"; +static const char __pyx_k_stop[] = "stop"; +static const char __pyx_k_test[] = "__test__"; +static const char __pyx_k_ASCII[] = "ASCII"; +static const char __pyx_k_class[] = "__class__"; +static const char __pyx_k_count[] = "count"; +static const char __pyx_k_error[] = "error"; +static const char __pyx_k_flags[] = "flags"; +static const char __pyx_k_index[] = "index"; +static const char __pyx_k_range[] = "range"; +static const char __pyx_k_shape[] = "shape"; +static const char __pyx_k_start[] = "start"; +static const char __pyx_k_enable[] = "enable"; +static const char __pyx_k_encode[] = "encode"; +static const char __pyx_k_format[] = "format"; +static const char __pyx_k_import[] = "__import__"; +static const char __pyx_k_name_2[] = "__name__"; +static const char __pyx_k_output[] = "output"; +static const char __pyx_k_pickle[] = "pickle"; +static const char __pyx_k_reduce[] = "__reduce__"; +static const char __pyx_k_struct[] = "struct"; +static const char __pyx_k_unpack[] = "unpack"; +static const char __pyx_k_update[] = "update"; +static const char __pyx_k_context[] = "context"; +static const char __pyx_k_disable[] = "disable"; +static const char __pyx_k_environ[] = "environ"; +static const char __pyx_k_fortran[] = "fortran"; +static const char __pyx_k_memview[] = "memview"; +static const char __pyx_k_runtime[] = "runtime"; +static const char __pyx_k_use_tf8[] = "use_tf8"; +static const char __pyx_k_Ellipsis[] = "Ellipsis"; +static const char __pyx_k_Sequence[] = "Sequence"; +static const char __pyx_k_getstate[] = "__getstate__"; +static const char __pyx_k_itemsize[] = "itemsize"; +static const char __pyx_k_pyx_type[] = "__pyx_type"; +static const char __pyx_k_register[] = "register"; +static const char __pyx_k_setstate[] = "__setstate__"; +static const char __pyx_k_SNPEModel[] = "SNPEModel"; +static const char __pyx_k_TypeError[] = "TypeError"; +static const char __pyx_k_enumerate[] = "enumerate"; +static const char __pyx_k_isenabled[] = "isenabled"; +static const char __pyx_k_pyx_state[] = "__pyx_state"; +static const char __pyx_k_reduce_ex[] = "__reduce_ex__"; +static const char __pyx_k_IndexError[] = "IndexError"; +static const char __pyx_k_ValueError[] = "ValueError"; +static const char __pyx_k_pyx_result[] = "__pyx_result"; +static const char __pyx_k_pyx_vtable[] = "__pyx_vtable__"; +static const char __pyx_k_MemoryError[] = "MemoryError"; +static const char __pyx_k_PickleError[] = "PickleError"; +static const char __pyx_k_collections[] = "collections"; +static const char __pyx_k_initializing[] = "_initializing"; +static const char __pyx_k_is_coroutine[] = "_is_coroutine"; +static const char __pyx_k_pyx_checksum[] = "__pyx_checksum"; +static const char __pyx_k_stringsource[] = ""; +static const char __pyx_k_version_info[] = "version_info"; +static const char __pyx_k_class_getitem[] = "__class_getitem__"; +static const char __pyx_k_reduce_cython[] = "__reduce_cython__"; +static const char __pyx_k_AssertionError[] = "AssertionError"; +static const char __pyx_k_View_MemoryView[] = "View.MemoryView"; +static const char __pyx_k_allocate_buffer[] = "allocate_buffer"; +static const char __pyx_k_collections_abc[] = "collections.abc"; +static const char __pyx_k_dtype_is_object[] = "dtype_is_object"; +static const char __pyx_k_pyx_PickleError[] = "__pyx_PickleError"; +static const char __pyx_k_setstate_cython[] = "__setstate_cython__"; +static const char __pyx_k_ADSP_LIBRARY_PATH[] = "ADSP_LIBRARY_PATH"; +static const char __pyx_k_pyx_unpickle_Enum[] = "__pyx_unpickle_Enum"; +static const char __pyx_k_asyncio_coroutines[] = "asyncio.coroutines"; +static const char __pyx_k_cline_in_traceback[] = "cline_in_traceback"; +static const char __pyx_k_strided_and_direct[] = ""; +static const char __pyx_k_strided_and_indirect[] = ""; +static const char __pyx_k_Invalid_shape_in_axis[] = "Invalid shape in axis "; +static const char __pyx_k_contiguous_and_direct[] = ""; +static const char __pyx_k_Cannot_index_with_type[] = "Cannot index with type '"; +static const char __pyx_k_MemoryView_of_r_object[] = ""; +static const char __pyx_k_MemoryView_of_r_at_0x_x[] = ""; +static const char __pyx_k_contiguous_and_indirect[] = ""; +static const char __pyx_k_Dimension_d_is_not_direct[] = "Dimension %d is not direct"; +static const char __pyx_k_SNPEModel___reduce_cython[] = "SNPEModel.__reduce_cython__"; +static const char __pyx_k_Index_out_of_bounds_axis_d[] = "Index out of bounds (axis %d)"; +static const char __pyx_k_SNPEModel___setstate_cython[] = "SNPEModel.__setstate_cython__"; +static const char __pyx_k_Step_may_not_be_zero_axis_d[] = "Step may not be zero (axis %d)"; +static const char __pyx_k_itemsize_0_for_cython_array[] = "itemsize <= 0 for cython.array"; +static const char __pyx_k_unable_to_allocate_array_data[] = "unable to allocate array data."; +static const char __pyx_k_strided_and_direct_or_indirect[] = ""; +static const char __pyx_k_data_pythonpath_third_party_snp[] = "/data/pythonpath/third_party/snpe/dsp/"; +static const char __pyx_k_All_dimensions_preceding_dimensi[] = "All dimensions preceding dimension %d must be indexed and not sliced"; +static const char __pyx_k_Buffer_view_does_not_expose_stri[] = "Buffer view does not expose strides"; +static const char __pyx_k_Can_only_create_a_buffer_that_is[] = "Can only create a buffer that is contiguous in memory."; +static const char __pyx_k_Cannot_assign_to_read_only_memor[] = "Cannot assign to read-only memoryview"; +static const char __pyx_k_Cannot_create_writable_memory_vi[] = "Cannot create writable memory view from read-only memoryview"; +static const char __pyx_k_Cannot_transpose_memoryview_with[] = "Cannot transpose memoryview with indirect dimensions"; +static const char __pyx_k_Empty_shape_tuple_for_cython_arr[] = "Empty shape tuple for cython.array"; +static const char __pyx_k_Incompatible_checksums_0x_x_vs_0[] = "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))"; +static const char __pyx_k_Indirect_dimensions_not_supporte[] = "Indirect dimensions not supported"; +static const char __pyx_k_Invalid_mode_expected_c_or_fortr[] = "Invalid mode, expected 'c' or 'fortran', got "; +static const char __pyx_k_Out_of_bounds_on_buffer_access_a[] = "Out of bounds on buffer access (axis "; +static const char __pyx_k_Unable_to_convert_item_to_object[] = "Unable to convert item to object"; +static const char __pyx_k_got_differing_extents_in_dimensi[] = "got differing extents in dimension "; +static const char __pyx_k_no_default___reduce___due_to_non[] = "no default __reduce__ due to non-trivial __cinit__"; +static const char __pyx_k_selfdrive_modeld_runners_snpemod[] = "selfdrive.modeld.runners.snpemodel_pyx"; +static const char __pyx_k_unable_to_allocate_shape_and_str[] = "unable to allocate shape and strides."; +/* #### Code section: decls ### */ +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array___cinit__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_shape, Py_ssize_t __pyx_v_itemsize, PyObject *__pyx_v_format, PyObject *__pyx_v_mode, int __pyx_v_allocate_buffer); /* proto */ +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_2__getbuffer__(struct __pyx_array_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /* proto */ +static void __pyx_array___pyx_pf_15View_dot_MemoryView_5array_4__dealloc__(struct __pyx_array_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_5array_7memview___get__(struct __pyx_array_obj *__pyx_v_self); /* proto */ +static Py_ssize_t __pyx_array___pyx_pf_15View_dot_MemoryView_5array_6__len__(struct __pyx_array_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_8__getattr__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_attr); /* proto */ +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_10__getitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item); /* proto */ +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_12__setitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value); /* proto */ +static PyObject *__pyx_pf___pyx_array___reduce_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_array_2__setstate_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum___init__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v_name); /* proto */ +static PyObject *__pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum_2__repr__(struct __pyx_MemviewEnum_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_MemviewEnum___reduce_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_MemviewEnum_2__setstate_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview___cinit__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj, int __pyx_v_flags, int __pyx_v_dtype_is_object); /* proto */ +static void __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_2__dealloc__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_4__getitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index); /* proto */ +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_6__setitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value); /* proto */ +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_8__getbuffer__(struct __pyx_memoryview_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_1T___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4base___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_5shape___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_7strides___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_10suboffsets___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4ndim___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_8itemsize___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_6nbytes___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4size___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static Py_ssize_t __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_10__len__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_12__repr__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_14__str__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_16is_c_contig(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_18is_f_contig(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_20copy(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_22copy_fortran(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryview___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryview_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static void __pyx_memoryviewslice___pyx_pf_15View_dot_MemoryView_16_memoryviewslice___dealloc__(struct __pyx_memoryviewslice_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryviewslice___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryviewslice_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView___pyx_unpickle_Enum(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v___pyx_type, long __pyx_v___pyx_checksum, PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_pf_9selfdrive_6modeld_7runners_13snpemodel_pyx_9SNPEModel___cinit__(struct __pyx_obj_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel *__pyx_v_self, std::string __pyx_v_path, __Pyx_memviewslice __pyx_v_output, int __pyx_v_runtime, bool __pyx_v_use_tf8, struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext *__pyx_v_context); /* proto */ +static PyObject *__pyx_pf_9selfdrive_6modeld_7runners_13snpemodel_pyx_9SNPEModel_2__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_9selfdrive_6modeld_7runners_13snpemodel_pyx_9SNPEModel_4__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_tp_new_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_array(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_Enum(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_memoryview(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new__memoryviewslice(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +/* #### Code section: late_includes ### */ +/* #### Code section: module_state ### */ +typedef struct { + PyObject *__pyx_d; + PyObject *__pyx_b; + PyObject *__pyx_cython_runtime; + PyObject *__pyx_empty_tuple; + PyObject *__pyx_empty_bytes; + PyObject *__pyx_empty_unicode; + #ifdef __Pyx_CyFunction_USED + PyTypeObject *__pyx_CyFunctionType; + #endif + #ifdef __Pyx_FusedFunction_USED + PyTypeObject *__pyx_FusedFunctionType; + #endif + #ifdef __Pyx_Generator_USED + PyTypeObject *__pyx_GeneratorType; + #endif + #ifdef __Pyx_IterableCoroutine_USED + PyTypeObject *__pyx_IterableCoroutineType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineAwaitType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineType; + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + PyTypeObject *__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext; + PyTypeObject *__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf; + #if CYTHON_USE_MODULE_STATE + #endif + PyTypeObject *__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext; + PyTypeObject *__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem; + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + PyTypeObject *__pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel; + #if CYTHON_USE_MODULE_STATE + PyObject *__pyx_type_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel; + PyObject *__pyx_type___pyx_array; + PyObject *__pyx_type___pyx_MemviewEnum; + PyObject *__pyx_type___pyx_memoryview; + PyObject *__pyx_type___pyx_memoryviewslice; + #endif + PyTypeObject *__pyx_ptype_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel; + PyTypeObject *__pyx_array_type; + PyTypeObject *__pyx_MemviewEnum_type; + PyTypeObject *__pyx_memoryview_type; + PyTypeObject *__pyx_memoryviewslice_type; + PyObject *__pyx_kp_u_; + PyObject *__pyx_n_s_ADSP_LIBRARY_PATH; + PyObject *__pyx_n_s_ASCII; + PyObject *__pyx_kp_s_All_dimensions_preceding_dimensi; + PyObject *__pyx_n_s_AssertionError; + PyObject *__pyx_kp_s_Buffer_view_does_not_expose_stri; + PyObject *__pyx_kp_s_Can_only_create_a_buffer_that_is; + PyObject *__pyx_kp_s_Cannot_assign_to_read_only_memor; + PyObject *__pyx_kp_s_Cannot_create_writable_memory_vi; + PyObject *__pyx_kp_u_Cannot_index_with_type; + PyObject *__pyx_kp_s_Cannot_transpose_memoryview_with; + PyObject *__pyx_kp_s_Dimension_d_is_not_direct; + PyObject *__pyx_n_s_Ellipsis; + PyObject *__pyx_kp_s_Empty_shape_tuple_for_cython_arr; + PyObject *__pyx_kp_s_Incompatible_checksums_0x_x_vs_0; + PyObject *__pyx_n_s_IndexError; + PyObject *__pyx_kp_s_Index_out_of_bounds_axis_d; + PyObject *__pyx_kp_s_Indirect_dimensions_not_supporte; + PyObject *__pyx_kp_u_Invalid_mode_expected_c_or_fortr; + PyObject *__pyx_kp_u_Invalid_shape_in_axis; + PyObject *__pyx_n_s_MemoryError; + PyObject *__pyx_kp_s_MemoryView_of_r_at_0x_x; + PyObject *__pyx_kp_s_MemoryView_of_r_object; + PyObject *__pyx_n_b_O; + PyObject *__pyx_kp_u_Out_of_bounds_on_buffer_access_a; + PyObject *__pyx_n_s_PickleError; + PyObject *__pyx_n_s_SNPEModel; + PyObject *__pyx_n_s_SNPEModel___reduce_cython; + PyObject *__pyx_n_s_SNPEModel___setstate_cython; + PyObject *__pyx_n_s_Sequence; + PyObject *__pyx_kp_s_Step_may_not_be_zero_axis_d; + PyObject *__pyx_n_s_TypeError; + PyObject *__pyx_kp_s_Unable_to_convert_item_to_object; + PyObject *__pyx_n_s_ValueError; + PyObject *__pyx_n_s_View_MemoryView; + PyObject *__pyx_kp_u__2; + PyObject *__pyx_n_s__24; + PyObject *__pyx_n_s__3; + PyObject *__pyx_kp_u__6; + PyObject *__pyx_kp_u__7; + PyObject *__pyx_n_s_abc; + PyObject *__pyx_n_s_allocate_buffer; + PyObject *__pyx_kp_u_and; + PyObject *__pyx_n_s_asyncio_coroutines; + PyObject *__pyx_n_s_base; + PyObject *__pyx_n_s_c; + PyObject *__pyx_n_u_c; + PyObject *__pyx_n_s_class; + PyObject *__pyx_n_s_class_getitem; + PyObject *__pyx_n_s_cline_in_traceback; + PyObject *__pyx_n_s_collections; + PyObject *__pyx_kp_s_collections_abc; + PyObject *__pyx_n_s_context; + PyObject *__pyx_kp_s_contiguous_and_direct; + PyObject *__pyx_kp_s_contiguous_and_indirect; + PyObject *__pyx_n_s_count; + PyObject *__pyx_kp_s_data_pythonpath_third_party_snp; + PyObject *__pyx_n_s_dict; + PyObject *__pyx_kp_u_disable; + PyObject *__pyx_n_s_dtype_is_object; + PyObject *__pyx_kp_u_enable; + PyObject *__pyx_n_s_encode; + PyObject *__pyx_n_s_enumerate; + PyObject *__pyx_n_s_environ; + PyObject *__pyx_n_s_error; + PyObject *__pyx_n_s_flags; + PyObject *__pyx_n_s_format; + PyObject *__pyx_n_s_fortran; + PyObject *__pyx_n_u_fortran; + PyObject *__pyx_kp_u_gc; + PyObject *__pyx_n_s_getstate; + PyObject *__pyx_kp_u_got; + PyObject *__pyx_kp_u_got_differing_extents_in_dimensi; + PyObject *__pyx_n_s_id; + PyObject *__pyx_n_s_import; + PyObject *__pyx_n_s_index; + PyObject *__pyx_n_s_initializing; + PyObject *__pyx_n_s_is_coroutine; + PyObject *__pyx_kp_u_isenabled; + PyObject *__pyx_n_s_itemsize; + PyObject *__pyx_kp_s_itemsize_0_for_cython_array; + PyObject *__pyx_n_s_main; + PyObject *__pyx_n_s_memview; + PyObject *__pyx_n_s_mode; + PyObject *__pyx_n_s_name; + PyObject *__pyx_n_s_name_2; + PyObject *__pyx_n_s_ndim; + PyObject *__pyx_n_s_new; + PyObject *__pyx_kp_s_no_default___reduce___due_to_non; + PyObject *__pyx_n_s_obj; + PyObject *__pyx_n_s_os; + PyObject *__pyx_n_s_output; + PyObject *__pyx_n_s_pack; + PyObject *__pyx_n_s_path; + PyObject *__pyx_n_s_pickle; + PyObject *__pyx_n_s_pyx_PickleError; + PyObject *__pyx_n_s_pyx_checksum; + PyObject *__pyx_n_s_pyx_result; + PyObject *__pyx_n_s_pyx_state; + PyObject *__pyx_n_s_pyx_type; + PyObject *__pyx_n_s_pyx_unpickle_Enum; + PyObject *__pyx_n_s_pyx_vtable; + PyObject *__pyx_n_s_range; + PyObject *__pyx_n_s_reduce; + PyObject *__pyx_n_s_reduce_cython; + PyObject *__pyx_n_s_reduce_ex; + PyObject *__pyx_n_s_register; + PyObject *__pyx_n_s_runtime; + PyObject *__pyx_n_s_self; + PyObject *__pyx_n_s_selfdrive_modeld_runners_snpemod; + PyObject *__pyx_n_s_setstate; + PyObject *__pyx_n_s_setstate_cython; + PyObject *__pyx_n_s_shape; + PyObject *__pyx_n_s_size; + PyObject *__pyx_n_s_spec; + PyObject *__pyx_n_s_start; + PyObject *__pyx_n_s_step; + PyObject *__pyx_n_s_stop; + PyObject *__pyx_kp_s_strided_and_direct; + PyObject *__pyx_kp_s_strided_and_direct_or_indirect; + PyObject *__pyx_kp_s_strided_and_indirect; + PyObject *__pyx_kp_s_stringsource; + PyObject *__pyx_n_s_struct; + PyObject *__pyx_n_s_sys; + PyObject *__pyx_n_s_test; + PyObject *__pyx_kp_s_unable_to_allocate_array_data; + PyObject *__pyx_kp_s_unable_to_allocate_shape_and_str; + PyObject *__pyx_n_s_unpack; + PyObject *__pyx_n_s_update; + PyObject *__pyx_n_s_use_tf8; + PyObject *__pyx_n_s_version_info; + PyObject *__pyx_int_0; + PyObject *__pyx_int_1; + PyObject *__pyx_int_3; + PyObject *__pyx_int_112105877; + PyObject *__pyx_int_136983863; + PyObject *__pyx_int_184977713; + PyObject *__pyx_int_neg_1; + PyObject *__pyx_slice__5; + PyObject *__pyx_tuple__4; + PyObject *__pyx_tuple__8; + PyObject *__pyx_tuple__9; + PyObject *__pyx_tuple__10; + PyObject *__pyx_tuple__11; + PyObject *__pyx_tuple__12; + PyObject *__pyx_tuple__13; + PyObject *__pyx_tuple__14; + PyObject *__pyx_tuple__15; + PyObject *__pyx_tuple__16; + PyObject *__pyx_tuple__17; + PyObject *__pyx_tuple__18; + PyObject *__pyx_tuple__20; + PyObject *__pyx_tuple__22; + PyObject *__pyx_codeobj__19; + PyObject *__pyx_codeobj__21; + PyObject *__pyx_codeobj__23; +} __pyx_mstate; + +#if CYTHON_USE_MODULE_STATE +#ifdef __cplusplus +namespace { + extern struct PyModuleDef __pyx_moduledef; +} /* anonymous namespace */ +#else +static struct PyModuleDef __pyx_moduledef; +#endif + +#define __pyx_mstate(o) ((__pyx_mstate *)__Pyx_PyModule_GetState(o)) + +#define __pyx_mstate_global (__pyx_mstate(PyState_FindModule(&__pyx_moduledef))) + +#define __pyx_m (PyState_FindModule(&__pyx_moduledef)) +#else +static __pyx_mstate __pyx_mstate_global_static = +#ifdef __cplusplus + {}; +#else + {0}; +#endif +static __pyx_mstate *__pyx_mstate_global = &__pyx_mstate_global_static; +#endif +/* #### Code section: module_state_clear ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_clear(PyObject *m) { + __pyx_mstate *clear_module_state = __pyx_mstate(m); + if (!clear_module_state) return 0; + Py_CLEAR(clear_module_state->__pyx_d); + Py_CLEAR(clear_module_state->__pyx_b); + Py_CLEAR(clear_module_state->__pyx_cython_runtime); + Py_CLEAR(clear_module_state->__pyx_empty_tuple); + Py_CLEAR(clear_module_state->__pyx_empty_bytes); + Py_CLEAR(clear_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_CLEAR(clear_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_CLEAR(clear_module_state->__pyx_FusedFunctionType); + #endif + Py_CLEAR(clear_module_state->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext); + Py_CLEAR(clear_module_state->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf); + Py_CLEAR(clear_module_state->__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext); + Py_CLEAR(clear_module_state->__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem); + Py_CLEAR(clear_module_state->__pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel); + Py_CLEAR(clear_module_state->__pyx_ptype_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel); + Py_CLEAR(clear_module_state->__pyx_type_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel); + Py_CLEAR(clear_module_state->__pyx_array_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_array); + Py_CLEAR(clear_module_state->__pyx_MemviewEnum_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_MemviewEnum); + Py_CLEAR(clear_module_state->__pyx_memoryview_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_memoryview); + Py_CLEAR(clear_module_state->__pyx_memoryviewslice_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_memoryviewslice); + Py_CLEAR(clear_module_state->__pyx_kp_u_); + Py_CLEAR(clear_module_state->__pyx_n_s_ADSP_LIBRARY_PATH); + Py_CLEAR(clear_module_state->__pyx_n_s_ASCII); + Py_CLEAR(clear_module_state->__pyx_kp_s_All_dimensions_preceding_dimensi); + Py_CLEAR(clear_module_state->__pyx_n_s_AssertionError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Buffer_view_does_not_expose_stri); + Py_CLEAR(clear_module_state->__pyx_kp_s_Can_only_create_a_buffer_that_is); + Py_CLEAR(clear_module_state->__pyx_kp_s_Cannot_assign_to_read_only_memor); + Py_CLEAR(clear_module_state->__pyx_kp_s_Cannot_create_writable_memory_vi); + Py_CLEAR(clear_module_state->__pyx_kp_u_Cannot_index_with_type); + Py_CLEAR(clear_module_state->__pyx_kp_s_Cannot_transpose_memoryview_with); + Py_CLEAR(clear_module_state->__pyx_kp_s_Dimension_d_is_not_direct); + Py_CLEAR(clear_module_state->__pyx_n_s_Ellipsis); + Py_CLEAR(clear_module_state->__pyx_kp_s_Empty_shape_tuple_for_cython_arr); + Py_CLEAR(clear_module_state->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0); + Py_CLEAR(clear_module_state->__pyx_n_s_IndexError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Index_out_of_bounds_axis_d); + Py_CLEAR(clear_module_state->__pyx_kp_s_Indirect_dimensions_not_supporte); + Py_CLEAR(clear_module_state->__pyx_kp_u_Invalid_mode_expected_c_or_fortr); + Py_CLEAR(clear_module_state->__pyx_kp_u_Invalid_shape_in_axis); + Py_CLEAR(clear_module_state->__pyx_n_s_MemoryError); + Py_CLEAR(clear_module_state->__pyx_kp_s_MemoryView_of_r_at_0x_x); + Py_CLEAR(clear_module_state->__pyx_kp_s_MemoryView_of_r_object); + Py_CLEAR(clear_module_state->__pyx_n_b_O); + Py_CLEAR(clear_module_state->__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + Py_CLEAR(clear_module_state->__pyx_n_s_PickleError); + Py_CLEAR(clear_module_state->__pyx_n_s_SNPEModel); + Py_CLEAR(clear_module_state->__pyx_n_s_SNPEModel___reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_SNPEModel___setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_Sequence); + Py_CLEAR(clear_module_state->__pyx_kp_s_Step_may_not_be_zero_axis_d); + Py_CLEAR(clear_module_state->__pyx_n_s_TypeError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Unable_to_convert_item_to_object); + Py_CLEAR(clear_module_state->__pyx_n_s_ValueError); + Py_CLEAR(clear_module_state->__pyx_n_s_View_MemoryView); + Py_CLEAR(clear_module_state->__pyx_kp_u__2); + Py_CLEAR(clear_module_state->__pyx_n_s__24); + Py_CLEAR(clear_module_state->__pyx_n_s__3); + Py_CLEAR(clear_module_state->__pyx_kp_u__6); + Py_CLEAR(clear_module_state->__pyx_kp_u__7); + Py_CLEAR(clear_module_state->__pyx_n_s_abc); + Py_CLEAR(clear_module_state->__pyx_n_s_allocate_buffer); + Py_CLEAR(clear_module_state->__pyx_kp_u_and); + Py_CLEAR(clear_module_state->__pyx_n_s_asyncio_coroutines); + Py_CLEAR(clear_module_state->__pyx_n_s_base); + Py_CLEAR(clear_module_state->__pyx_n_s_c); + Py_CLEAR(clear_module_state->__pyx_n_u_c); + Py_CLEAR(clear_module_state->__pyx_n_s_class); + Py_CLEAR(clear_module_state->__pyx_n_s_class_getitem); + Py_CLEAR(clear_module_state->__pyx_n_s_cline_in_traceback); + Py_CLEAR(clear_module_state->__pyx_n_s_collections); + Py_CLEAR(clear_module_state->__pyx_kp_s_collections_abc); + Py_CLEAR(clear_module_state->__pyx_n_s_context); + Py_CLEAR(clear_module_state->__pyx_kp_s_contiguous_and_direct); + Py_CLEAR(clear_module_state->__pyx_kp_s_contiguous_and_indirect); + Py_CLEAR(clear_module_state->__pyx_n_s_count); + Py_CLEAR(clear_module_state->__pyx_kp_s_data_pythonpath_third_party_snp); + Py_CLEAR(clear_module_state->__pyx_n_s_dict); + Py_CLEAR(clear_module_state->__pyx_kp_u_disable); + Py_CLEAR(clear_module_state->__pyx_n_s_dtype_is_object); + Py_CLEAR(clear_module_state->__pyx_kp_u_enable); + Py_CLEAR(clear_module_state->__pyx_n_s_encode); + Py_CLEAR(clear_module_state->__pyx_n_s_enumerate); + Py_CLEAR(clear_module_state->__pyx_n_s_environ); + Py_CLEAR(clear_module_state->__pyx_n_s_error); + Py_CLEAR(clear_module_state->__pyx_n_s_flags); + Py_CLEAR(clear_module_state->__pyx_n_s_format); + Py_CLEAR(clear_module_state->__pyx_n_s_fortran); + Py_CLEAR(clear_module_state->__pyx_n_u_fortran); + Py_CLEAR(clear_module_state->__pyx_kp_u_gc); + Py_CLEAR(clear_module_state->__pyx_n_s_getstate); + Py_CLEAR(clear_module_state->__pyx_kp_u_got); + Py_CLEAR(clear_module_state->__pyx_kp_u_got_differing_extents_in_dimensi); + Py_CLEAR(clear_module_state->__pyx_n_s_id); + Py_CLEAR(clear_module_state->__pyx_n_s_import); + Py_CLEAR(clear_module_state->__pyx_n_s_index); + Py_CLEAR(clear_module_state->__pyx_n_s_initializing); + Py_CLEAR(clear_module_state->__pyx_n_s_is_coroutine); + Py_CLEAR(clear_module_state->__pyx_kp_u_isenabled); + Py_CLEAR(clear_module_state->__pyx_n_s_itemsize); + Py_CLEAR(clear_module_state->__pyx_kp_s_itemsize_0_for_cython_array); + Py_CLEAR(clear_module_state->__pyx_n_s_main); + Py_CLEAR(clear_module_state->__pyx_n_s_memview); + Py_CLEAR(clear_module_state->__pyx_n_s_mode); + Py_CLEAR(clear_module_state->__pyx_n_s_name); + Py_CLEAR(clear_module_state->__pyx_n_s_name_2); + Py_CLEAR(clear_module_state->__pyx_n_s_ndim); + Py_CLEAR(clear_module_state->__pyx_n_s_new); + Py_CLEAR(clear_module_state->__pyx_kp_s_no_default___reduce___due_to_non); + Py_CLEAR(clear_module_state->__pyx_n_s_obj); + Py_CLEAR(clear_module_state->__pyx_n_s_os); + Py_CLEAR(clear_module_state->__pyx_n_s_output); + Py_CLEAR(clear_module_state->__pyx_n_s_pack); + Py_CLEAR(clear_module_state->__pyx_n_s_path); + Py_CLEAR(clear_module_state->__pyx_n_s_pickle); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_PickleError); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_checksum); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_result); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_state); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_type); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_unpickle_Enum); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_vtable); + Py_CLEAR(clear_module_state->__pyx_n_s_range); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_ex); + Py_CLEAR(clear_module_state->__pyx_n_s_register); + Py_CLEAR(clear_module_state->__pyx_n_s_runtime); + Py_CLEAR(clear_module_state->__pyx_n_s_self); + Py_CLEAR(clear_module_state->__pyx_n_s_selfdrive_modeld_runners_snpemod); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_shape); + Py_CLEAR(clear_module_state->__pyx_n_s_size); + Py_CLEAR(clear_module_state->__pyx_n_s_spec); + Py_CLEAR(clear_module_state->__pyx_n_s_start); + Py_CLEAR(clear_module_state->__pyx_n_s_step); + Py_CLEAR(clear_module_state->__pyx_n_s_stop); + Py_CLEAR(clear_module_state->__pyx_kp_s_strided_and_direct); + Py_CLEAR(clear_module_state->__pyx_kp_s_strided_and_direct_or_indirect); + Py_CLEAR(clear_module_state->__pyx_kp_s_strided_and_indirect); + Py_CLEAR(clear_module_state->__pyx_kp_s_stringsource); + Py_CLEAR(clear_module_state->__pyx_n_s_struct); + Py_CLEAR(clear_module_state->__pyx_n_s_sys); + Py_CLEAR(clear_module_state->__pyx_n_s_test); + Py_CLEAR(clear_module_state->__pyx_kp_s_unable_to_allocate_array_data); + Py_CLEAR(clear_module_state->__pyx_kp_s_unable_to_allocate_shape_and_str); + Py_CLEAR(clear_module_state->__pyx_n_s_unpack); + Py_CLEAR(clear_module_state->__pyx_n_s_update); + Py_CLEAR(clear_module_state->__pyx_n_s_use_tf8); + Py_CLEAR(clear_module_state->__pyx_n_s_version_info); + Py_CLEAR(clear_module_state->__pyx_int_0); + Py_CLEAR(clear_module_state->__pyx_int_1); + Py_CLEAR(clear_module_state->__pyx_int_3); + Py_CLEAR(clear_module_state->__pyx_int_112105877); + Py_CLEAR(clear_module_state->__pyx_int_136983863); + Py_CLEAR(clear_module_state->__pyx_int_184977713); + Py_CLEAR(clear_module_state->__pyx_int_neg_1); + Py_CLEAR(clear_module_state->__pyx_slice__5); + Py_CLEAR(clear_module_state->__pyx_tuple__4); + Py_CLEAR(clear_module_state->__pyx_tuple__8); + Py_CLEAR(clear_module_state->__pyx_tuple__9); + Py_CLEAR(clear_module_state->__pyx_tuple__10); + Py_CLEAR(clear_module_state->__pyx_tuple__11); + Py_CLEAR(clear_module_state->__pyx_tuple__12); + Py_CLEAR(clear_module_state->__pyx_tuple__13); + Py_CLEAR(clear_module_state->__pyx_tuple__14); + Py_CLEAR(clear_module_state->__pyx_tuple__15); + Py_CLEAR(clear_module_state->__pyx_tuple__16); + Py_CLEAR(clear_module_state->__pyx_tuple__17); + Py_CLEAR(clear_module_state->__pyx_tuple__18); + Py_CLEAR(clear_module_state->__pyx_tuple__20); + Py_CLEAR(clear_module_state->__pyx_tuple__22); + Py_CLEAR(clear_module_state->__pyx_codeobj__19); + Py_CLEAR(clear_module_state->__pyx_codeobj__21); + Py_CLEAR(clear_module_state->__pyx_codeobj__23); + return 0; +} +#endif +/* #### Code section: module_state_traverse ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { + __pyx_mstate *traverse_module_state = __pyx_mstate(m); + if (!traverse_module_state) return 0; + Py_VISIT(traverse_module_state->__pyx_d); + Py_VISIT(traverse_module_state->__pyx_b); + Py_VISIT(traverse_module_state->__pyx_cython_runtime); + Py_VISIT(traverse_module_state->__pyx_empty_tuple); + Py_VISIT(traverse_module_state->__pyx_empty_bytes); + Py_VISIT(traverse_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_VISIT(traverse_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_VISIT(traverse_module_state->__pyx_FusedFunctionType); + #endif + Py_VISIT(traverse_module_state->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext); + Py_VISIT(traverse_module_state->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf); + Py_VISIT(traverse_module_state->__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext); + Py_VISIT(traverse_module_state->__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem); + Py_VISIT(traverse_module_state->__pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel); + Py_VISIT(traverse_module_state->__pyx_ptype_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel); + Py_VISIT(traverse_module_state->__pyx_type_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel); + Py_VISIT(traverse_module_state->__pyx_array_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_array); + Py_VISIT(traverse_module_state->__pyx_MemviewEnum_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_MemviewEnum); + Py_VISIT(traverse_module_state->__pyx_memoryview_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_memoryview); + Py_VISIT(traverse_module_state->__pyx_memoryviewslice_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_memoryviewslice); + Py_VISIT(traverse_module_state->__pyx_kp_u_); + Py_VISIT(traverse_module_state->__pyx_n_s_ADSP_LIBRARY_PATH); + Py_VISIT(traverse_module_state->__pyx_n_s_ASCII); + Py_VISIT(traverse_module_state->__pyx_kp_s_All_dimensions_preceding_dimensi); + Py_VISIT(traverse_module_state->__pyx_n_s_AssertionError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Buffer_view_does_not_expose_stri); + Py_VISIT(traverse_module_state->__pyx_kp_s_Can_only_create_a_buffer_that_is); + Py_VISIT(traverse_module_state->__pyx_kp_s_Cannot_assign_to_read_only_memor); + Py_VISIT(traverse_module_state->__pyx_kp_s_Cannot_create_writable_memory_vi); + Py_VISIT(traverse_module_state->__pyx_kp_u_Cannot_index_with_type); + Py_VISIT(traverse_module_state->__pyx_kp_s_Cannot_transpose_memoryview_with); + Py_VISIT(traverse_module_state->__pyx_kp_s_Dimension_d_is_not_direct); + Py_VISIT(traverse_module_state->__pyx_n_s_Ellipsis); + Py_VISIT(traverse_module_state->__pyx_kp_s_Empty_shape_tuple_for_cython_arr); + Py_VISIT(traverse_module_state->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0); + Py_VISIT(traverse_module_state->__pyx_n_s_IndexError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Index_out_of_bounds_axis_d); + Py_VISIT(traverse_module_state->__pyx_kp_s_Indirect_dimensions_not_supporte); + Py_VISIT(traverse_module_state->__pyx_kp_u_Invalid_mode_expected_c_or_fortr); + Py_VISIT(traverse_module_state->__pyx_kp_u_Invalid_shape_in_axis); + Py_VISIT(traverse_module_state->__pyx_n_s_MemoryError); + Py_VISIT(traverse_module_state->__pyx_kp_s_MemoryView_of_r_at_0x_x); + Py_VISIT(traverse_module_state->__pyx_kp_s_MemoryView_of_r_object); + Py_VISIT(traverse_module_state->__pyx_n_b_O); + Py_VISIT(traverse_module_state->__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + Py_VISIT(traverse_module_state->__pyx_n_s_PickleError); + Py_VISIT(traverse_module_state->__pyx_n_s_SNPEModel); + Py_VISIT(traverse_module_state->__pyx_n_s_SNPEModel___reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_SNPEModel___setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_Sequence); + Py_VISIT(traverse_module_state->__pyx_kp_s_Step_may_not_be_zero_axis_d); + Py_VISIT(traverse_module_state->__pyx_n_s_TypeError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Unable_to_convert_item_to_object); + Py_VISIT(traverse_module_state->__pyx_n_s_ValueError); + Py_VISIT(traverse_module_state->__pyx_n_s_View_MemoryView); + Py_VISIT(traverse_module_state->__pyx_kp_u__2); + Py_VISIT(traverse_module_state->__pyx_n_s__24); + Py_VISIT(traverse_module_state->__pyx_n_s__3); + Py_VISIT(traverse_module_state->__pyx_kp_u__6); + Py_VISIT(traverse_module_state->__pyx_kp_u__7); + Py_VISIT(traverse_module_state->__pyx_n_s_abc); + Py_VISIT(traverse_module_state->__pyx_n_s_allocate_buffer); + Py_VISIT(traverse_module_state->__pyx_kp_u_and); + Py_VISIT(traverse_module_state->__pyx_n_s_asyncio_coroutines); + Py_VISIT(traverse_module_state->__pyx_n_s_base); + Py_VISIT(traverse_module_state->__pyx_n_s_c); + Py_VISIT(traverse_module_state->__pyx_n_u_c); + Py_VISIT(traverse_module_state->__pyx_n_s_class); + Py_VISIT(traverse_module_state->__pyx_n_s_class_getitem); + Py_VISIT(traverse_module_state->__pyx_n_s_cline_in_traceback); + Py_VISIT(traverse_module_state->__pyx_n_s_collections); + Py_VISIT(traverse_module_state->__pyx_kp_s_collections_abc); + Py_VISIT(traverse_module_state->__pyx_n_s_context); + Py_VISIT(traverse_module_state->__pyx_kp_s_contiguous_and_direct); + Py_VISIT(traverse_module_state->__pyx_kp_s_contiguous_and_indirect); + Py_VISIT(traverse_module_state->__pyx_n_s_count); + Py_VISIT(traverse_module_state->__pyx_kp_s_data_pythonpath_third_party_snp); + Py_VISIT(traverse_module_state->__pyx_n_s_dict); + Py_VISIT(traverse_module_state->__pyx_kp_u_disable); + Py_VISIT(traverse_module_state->__pyx_n_s_dtype_is_object); + Py_VISIT(traverse_module_state->__pyx_kp_u_enable); + Py_VISIT(traverse_module_state->__pyx_n_s_encode); + Py_VISIT(traverse_module_state->__pyx_n_s_enumerate); + Py_VISIT(traverse_module_state->__pyx_n_s_environ); + Py_VISIT(traverse_module_state->__pyx_n_s_error); + Py_VISIT(traverse_module_state->__pyx_n_s_flags); + Py_VISIT(traverse_module_state->__pyx_n_s_format); + Py_VISIT(traverse_module_state->__pyx_n_s_fortran); + Py_VISIT(traverse_module_state->__pyx_n_u_fortran); + Py_VISIT(traverse_module_state->__pyx_kp_u_gc); + Py_VISIT(traverse_module_state->__pyx_n_s_getstate); + Py_VISIT(traverse_module_state->__pyx_kp_u_got); + Py_VISIT(traverse_module_state->__pyx_kp_u_got_differing_extents_in_dimensi); + Py_VISIT(traverse_module_state->__pyx_n_s_id); + Py_VISIT(traverse_module_state->__pyx_n_s_import); + Py_VISIT(traverse_module_state->__pyx_n_s_index); + Py_VISIT(traverse_module_state->__pyx_n_s_initializing); + Py_VISIT(traverse_module_state->__pyx_n_s_is_coroutine); + Py_VISIT(traverse_module_state->__pyx_kp_u_isenabled); + Py_VISIT(traverse_module_state->__pyx_n_s_itemsize); + Py_VISIT(traverse_module_state->__pyx_kp_s_itemsize_0_for_cython_array); + Py_VISIT(traverse_module_state->__pyx_n_s_main); + Py_VISIT(traverse_module_state->__pyx_n_s_memview); + Py_VISIT(traverse_module_state->__pyx_n_s_mode); + Py_VISIT(traverse_module_state->__pyx_n_s_name); + Py_VISIT(traverse_module_state->__pyx_n_s_name_2); + Py_VISIT(traverse_module_state->__pyx_n_s_ndim); + Py_VISIT(traverse_module_state->__pyx_n_s_new); + Py_VISIT(traverse_module_state->__pyx_kp_s_no_default___reduce___due_to_non); + Py_VISIT(traverse_module_state->__pyx_n_s_obj); + Py_VISIT(traverse_module_state->__pyx_n_s_os); + Py_VISIT(traverse_module_state->__pyx_n_s_output); + Py_VISIT(traverse_module_state->__pyx_n_s_pack); + Py_VISIT(traverse_module_state->__pyx_n_s_path); + Py_VISIT(traverse_module_state->__pyx_n_s_pickle); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_PickleError); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_checksum); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_result); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_state); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_type); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_unpickle_Enum); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_vtable); + Py_VISIT(traverse_module_state->__pyx_n_s_range); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_ex); + Py_VISIT(traverse_module_state->__pyx_n_s_register); + Py_VISIT(traverse_module_state->__pyx_n_s_runtime); + Py_VISIT(traverse_module_state->__pyx_n_s_self); + Py_VISIT(traverse_module_state->__pyx_n_s_selfdrive_modeld_runners_snpemod); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_shape); + Py_VISIT(traverse_module_state->__pyx_n_s_size); + Py_VISIT(traverse_module_state->__pyx_n_s_spec); + Py_VISIT(traverse_module_state->__pyx_n_s_start); + Py_VISIT(traverse_module_state->__pyx_n_s_step); + Py_VISIT(traverse_module_state->__pyx_n_s_stop); + Py_VISIT(traverse_module_state->__pyx_kp_s_strided_and_direct); + Py_VISIT(traverse_module_state->__pyx_kp_s_strided_and_direct_or_indirect); + Py_VISIT(traverse_module_state->__pyx_kp_s_strided_and_indirect); + Py_VISIT(traverse_module_state->__pyx_kp_s_stringsource); + Py_VISIT(traverse_module_state->__pyx_n_s_struct); + Py_VISIT(traverse_module_state->__pyx_n_s_sys); + Py_VISIT(traverse_module_state->__pyx_n_s_test); + Py_VISIT(traverse_module_state->__pyx_kp_s_unable_to_allocate_array_data); + Py_VISIT(traverse_module_state->__pyx_kp_s_unable_to_allocate_shape_and_str); + Py_VISIT(traverse_module_state->__pyx_n_s_unpack); + Py_VISIT(traverse_module_state->__pyx_n_s_update); + Py_VISIT(traverse_module_state->__pyx_n_s_use_tf8); + Py_VISIT(traverse_module_state->__pyx_n_s_version_info); + Py_VISIT(traverse_module_state->__pyx_int_0); + Py_VISIT(traverse_module_state->__pyx_int_1); + Py_VISIT(traverse_module_state->__pyx_int_3); + Py_VISIT(traverse_module_state->__pyx_int_112105877); + Py_VISIT(traverse_module_state->__pyx_int_136983863); + Py_VISIT(traverse_module_state->__pyx_int_184977713); + Py_VISIT(traverse_module_state->__pyx_int_neg_1); + Py_VISIT(traverse_module_state->__pyx_slice__5); + Py_VISIT(traverse_module_state->__pyx_tuple__4); + Py_VISIT(traverse_module_state->__pyx_tuple__8); + Py_VISIT(traverse_module_state->__pyx_tuple__9); + Py_VISIT(traverse_module_state->__pyx_tuple__10); + Py_VISIT(traverse_module_state->__pyx_tuple__11); + Py_VISIT(traverse_module_state->__pyx_tuple__12); + Py_VISIT(traverse_module_state->__pyx_tuple__13); + Py_VISIT(traverse_module_state->__pyx_tuple__14); + Py_VISIT(traverse_module_state->__pyx_tuple__15); + Py_VISIT(traverse_module_state->__pyx_tuple__16); + Py_VISIT(traverse_module_state->__pyx_tuple__17); + Py_VISIT(traverse_module_state->__pyx_tuple__18); + Py_VISIT(traverse_module_state->__pyx_tuple__20); + Py_VISIT(traverse_module_state->__pyx_tuple__22); + Py_VISIT(traverse_module_state->__pyx_codeobj__19); + Py_VISIT(traverse_module_state->__pyx_codeobj__21); + Py_VISIT(traverse_module_state->__pyx_codeobj__23); + return 0; +} +#endif +/* #### Code section: module_state_defines ### */ +#define __pyx_d __pyx_mstate_global->__pyx_d +#define __pyx_b __pyx_mstate_global->__pyx_b +#define __pyx_cython_runtime __pyx_mstate_global->__pyx_cython_runtime +#define __pyx_empty_tuple __pyx_mstate_global->__pyx_empty_tuple +#define __pyx_empty_bytes __pyx_mstate_global->__pyx_empty_bytes +#define __pyx_empty_unicode __pyx_mstate_global->__pyx_empty_unicode +#ifdef __Pyx_CyFunction_USED +#define __pyx_CyFunctionType __pyx_mstate_global->__pyx_CyFunctionType +#endif +#ifdef __Pyx_FusedFunction_USED +#define __pyx_FusedFunctionType __pyx_mstate_global->__pyx_FusedFunctionType +#endif +#ifdef __Pyx_Generator_USED +#define __pyx_GeneratorType __pyx_mstate_global->__pyx_GeneratorType +#endif +#ifdef __Pyx_IterableCoroutine_USED +#define __pyx_IterableCoroutineType __pyx_mstate_global->__pyx_IterableCoroutineType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineAwaitType __pyx_mstate_global->__pyx_CoroutineAwaitType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineType __pyx_mstate_global->__pyx_CoroutineType +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#define __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext __pyx_mstate_global->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext +#define __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf __pyx_mstate_global->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf +#if CYTHON_USE_MODULE_STATE +#endif +#define __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext __pyx_mstate_global->__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext +#define __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem __pyx_mstate_global->__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#define __pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel __pyx_mstate_global->__pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel +#if CYTHON_USE_MODULE_STATE +#define __pyx_type_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel __pyx_mstate_global->__pyx_type_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel +#define __pyx_type___pyx_array __pyx_mstate_global->__pyx_type___pyx_array +#define __pyx_type___pyx_MemviewEnum __pyx_mstate_global->__pyx_type___pyx_MemviewEnum +#define __pyx_type___pyx_memoryview __pyx_mstate_global->__pyx_type___pyx_memoryview +#define __pyx_type___pyx_memoryviewslice __pyx_mstate_global->__pyx_type___pyx_memoryviewslice +#endif +#define __pyx_ptype_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel __pyx_mstate_global->__pyx_ptype_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel +#define __pyx_array_type __pyx_mstate_global->__pyx_array_type +#define __pyx_MemviewEnum_type __pyx_mstate_global->__pyx_MemviewEnum_type +#define __pyx_memoryview_type __pyx_mstate_global->__pyx_memoryview_type +#define __pyx_memoryviewslice_type __pyx_mstate_global->__pyx_memoryviewslice_type +#define __pyx_kp_u_ __pyx_mstate_global->__pyx_kp_u_ +#define __pyx_n_s_ADSP_LIBRARY_PATH __pyx_mstate_global->__pyx_n_s_ADSP_LIBRARY_PATH +#define __pyx_n_s_ASCII __pyx_mstate_global->__pyx_n_s_ASCII +#define __pyx_kp_s_All_dimensions_preceding_dimensi __pyx_mstate_global->__pyx_kp_s_All_dimensions_preceding_dimensi +#define __pyx_n_s_AssertionError __pyx_mstate_global->__pyx_n_s_AssertionError +#define __pyx_kp_s_Buffer_view_does_not_expose_stri __pyx_mstate_global->__pyx_kp_s_Buffer_view_does_not_expose_stri +#define __pyx_kp_s_Can_only_create_a_buffer_that_is __pyx_mstate_global->__pyx_kp_s_Can_only_create_a_buffer_that_is +#define __pyx_kp_s_Cannot_assign_to_read_only_memor __pyx_mstate_global->__pyx_kp_s_Cannot_assign_to_read_only_memor +#define __pyx_kp_s_Cannot_create_writable_memory_vi __pyx_mstate_global->__pyx_kp_s_Cannot_create_writable_memory_vi +#define __pyx_kp_u_Cannot_index_with_type __pyx_mstate_global->__pyx_kp_u_Cannot_index_with_type +#define __pyx_kp_s_Cannot_transpose_memoryview_with __pyx_mstate_global->__pyx_kp_s_Cannot_transpose_memoryview_with +#define __pyx_kp_s_Dimension_d_is_not_direct __pyx_mstate_global->__pyx_kp_s_Dimension_d_is_not_direct +#define __pyx_n_s_Ellipsis __pyx_mstate_global->__pyx_n_s_Ellipsis +#define __pyx_kp_s_Empty_shape_tuple_for_cython_arr __pyx_mstate_global->__pyx_kp_s_Empty_shape_tuple_for_cython_arr +#define __pyx_kp_s_Incompatible_checksums_0x_x_vs_0 __pyx_mstate_global->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0 +#define __pyx_n_s_IndexError __pyx_mstate_global->__pyx_n_s_IndexError +#define __pyx_kp_s_Index_out_of_bounds_axis_d __pyx_mstate_global->__pyx_kp_s_Index_out_of_bounds_axis_d +#define __pyx_kp_s_Indirect_dimensions_not_supporte __pyx_mstate_global->__pyx_kp_s_Indirect_dimensions_not_supporte +#define __pyx_kp_u_Invalid_mode_expected_c_or_fortr __pyx_mstate_global->__pyx_kp_u_Invalid_mode_expected_c_or_fortr +#define __pyx_kp_u_Invalid_shape_in_axis __pyx_mstate_global->__pyx_kp_u_Invalid_shape_in_axis +#define __pyx_n_s_MemoryError __pyx_mstate_global->__pyx_n_s_MemoryError +#define __pyx_kp_s_MemoryView_of_r_at_0x_x __pyx_mstate_global->__pyx_kp_s_MemoryView_of_r_at_0x_x +#define __pyx_kp_s_MemoryView_of_r_object __pyx_mstate_global->__pyx_kp_s_MemoryView_of_r_object +#define __pyx_n_b_O __pyx_mstate_global->__pyx_n_b_O +#define __pyx_kp_u_Out_of_bounds_on_buffer_access_a __pyx_mstate_global->__pyx_kp_u_Out_of_bounds_on_buffer_access_a +#define __pyx_n_s_PickleError __pyx_mstate_global->__pyx_n_s_PickleError +#define __pyx_n_s_SNPEModel __pyx_mstate_global->__pyx_n_s_SNPEModel +#define __pyx_n_s_SNPEModel___reduce_cython __pyx_mstate_global->__pyx_n_s_SNPEModel___reduce_cython +#define __pyx_n_s_SNPEModel___setstate_cython __pyx_mstate_global->__pyx_n_s_SNPEModel___setstate_cython +#define __pyx_n_s_Sequence __pyx_mstate_global->__pyx_n_s_Sequence +#define __pyx_kp_s_Step_may_not_be_zero_axis_d __pyx_mstate_global->__pyx_kp_s_Step_may_not_be_zero_axis_d +#define __pyx_n_s_TypeError __pyx_mstate_global->__pyx_n_s_TypeError +#define __pyx_kp_s_Unable_to_convert_item_to_object __pyx_mstate_global->__pyx_kp_s_Unable_to_convert_item_to_object +#define __pyx_n_s_ValueError __pyx_mstate_global->__pyx_n_s_ValueError +#define __pyx_n_s_View_MemoryView __pyx_mstate_global->__pyx_n_s_View_MemoryView +#define __pyx_kp_u__2 __pyx_mstate_global->__pyx_kp_u__2 +#define __pyx_n_s__24 __pyx_mstate_global->__pyx_n_s__24 +#define __pyx_n_s__3 __pyx_mstate_global->__pyx_n_s__3 +#define __pyx_kp_u__6 __pyx_mstate_global->__pyx_kp_u__6 +#define __pyx_kp_u__7 __pyx_mstate_global->__pyx_kp_u__7 +#define __pyx_n_s_abc __pyx_mstate_global->__pyx_n_s_abc +#define __pyx_n_s_allocate_buffer __pyx_mstate_global->__pyx_n_s_allocate_buffer +#define __pyx_kp_u_and __pyx_mstate_global->__pyx_kp_u_and +#define __pyx_n_s_asyncio_coroutines __pyx_mstate_global->__pyx_n_s_asyncio_coroutines +#define __pyx_n_s_base __pyx_mstate_global->__pyx_n_s_base +#define __pyx_n_s_c __pyx_mstate_global->__pyx_n_s_c +#define __pyx_n_u_c __pyx_mstate_global->__pyx_n_u_c +#define __pyx_n_s_class __pyx_mstate_global->__pyx_n_s_class +#define __pyx_n_s_class_getitem __pyx_mstate_global->__pyx_n_s_class_getitem +#define __pyx_n_s_cline_in_traceback __pyx_mstate_global->__pyx_n_s_cline_in_traceback +#define __pyx_n_s_collections __pyx_mstate_global->__pyx_n_s_collections +#define __pyx_kp_s_collections_abc __pyx_mstate_global->__pyx_kp_s_collections_abc +#define __pyx_n_s_context __pyx_mstate_global->__pyx_n_s_context +#define __pyx_kp_s_contiguous_and_direct __pyx_mstate_global->__pyx_kp_s_contiguous_and_direct +#define __pyx_kp_s_contiguous_and_indirect __pyx_mstate_global->__pyx_kp_s_contiguous_and_indirect +#define __pyx_n_s_count __pyx_mstate_global->__pyx_n_s_count +#define __pyx_kp_s_data_pythonpath_third_party_snp __pyx_mstate_global->__pyx_kp_s_data_pythonpath_third_party_snp +#define __pyx_n_s_dict __pyx_mstate_global->__pyx_n_s_dict +#define __pyx_kp_u_disable __pyx_mstate_global->__pyx_kp_u_disable +#define __pyx_n_s_dtype_is_object __pyx_mstate_global->__pyx_n_s_dtype_is_object +#define __pyx_kp_u_enable __pyx_mstate_global->__pyx_kp_u_enable +#define __pyx_n_s_encode __pyx_mstate_global->__pyx_n_s_encode +#define __pyx_n_s_enumerate __pyx_mstate_global->__pyx_n_s_enumerate +#define __pyx_n_s_environ __pyx_mstate_global->__pyx_n_s_environ +#define __pyx_n_s_error __pyx_mstate_global->__pyx_n_s_error +#define __pyx_n_s_flags __pyx_mstate_global->__pyx_n_s_flags +#define __pyx_n_s_format __pyx_mstate_global->__pyx_n_s_format +#define __pyx_n_s_fortran __pyx_mstate_global->__pyx_n_s_fortran +#define __pyx_n_u_fortran __pyx_mstate_global->__pyx_n_u_fortran +#define __pyx_kp_u_gc __pyx_mstate_global->__pyx_kp_u_gc +#define __pyx_n_s_getstate __pyx_mstate_global->__pyx_n_s_getstate +#define __pyx_kp_u_got __pyx_mstate_global->__pyx_kp_u_got +#define __pyx_kp_u_got_differing_extents_in_dimensi __pyx_mstate_global->__pyx_kp_u_got_differing_extents_in_dimensi +#define __pyx_n_s_id __pyx_mstate_global->__pyx_n_s_id +#define __pyx_n_s_import __pyx_mstate_global->__pyx_n_s_import +#define __pyx_n_s_index __pyx_mstate_global->__pyx_n_s_index +#define __pyx_n_s_initializing __pyx_mstate_global->__pyx_n_s_initializing +#define __pyx_n_s_is_coroutine __pyx_mstate_global->__pyx_n_s_is_coroutine +#define __pyx_kp_u_isenabled __pyx_mstate_global->__pyx_kp_u_isenabled +#define __pyx_n_s_itemsize __pyx_mstate_global->__pyx_n_s_itemsize +#define __pyx_kp_s_itemsize_0_for_cython_array __pyx_mstate_global->__pyx_kp_s_itemsize_0_for_cython_array +#define __pyx_n_s_main __pyx_mstate_global->__pyx_n_s_main +#define __pyx_n_s_memview __pyx_mstate_global->__pyx_n_s_memview +#define __pyx_n_s_mode __pyx_mstate_global->__pyx_n_s_mode +#define __pyx_n_s_name __pyx_mstate_global->__pyx_n_s_name +#define __pyx_n_s_name_2 __pyx_mstate_global->__pyx_n_s_name_2 +#define __pyx_n_s_ndim __pyx_mstate_global->__pyx_n_s_ndim +#define __pyx_n_s_new __pyx_mstate_global->__pyx_n_s_new +#define __pyx_kp_s_no_default___reduce___due_to_non __pyx_mstate_global->__pyx_kp_s_no_default___reduce___due_to_non +#define __pyx_n_s_obj __pyx_mstate_global->__pyx_n_s_obj +#define __pyx_n_s_os __pyx_mstate_global->__pyx_n_s_os +#define __pyx_n_s_output __pyx_mstate_global->__pyx_n_s_output +#define __pyx_n_s_pack __pyx_mstate_global->__pyx_n_s_pack +#define __pyx_n_s_path __pyx_mstate_global->__pyx_n_s_path +#define __pyx_n_s_pickle __pyx_mstate_global->__pyx_n_s_pickle +#define __pyx_n_s_pyx_PickleError __pyx_mstate_global->__pyx_n_s_pyx_PickleError +#define __pyx_n_s_pyx_checksum __pyx_mstate_global->__pyx_n_s_pyx_checksum +#define __pyx_n_s_pyx_result __pyx_mstate_global->__pyx_n_s_pyx_result +#define __pyx_n_s_pyx_state __pyx_mstate_global->__pyx_n_s_pyx_state +#define __pyx_n_s_pyx_type __pyx_mstate_global->__pyx_n_s_pyx_type +#define __pyx_n_s_pyx_unpickle_Enum __pyx_mstate_global->__pyx_n_s_pyx_unpickle_Enum +#define __pyx_n_s_pyx_vtable __pyx_mstate_global->__pyx_n_s_pyx_vtable +#define __pyx_n_s_range __pyx_mstate_global->__pyx_n_s_range +#define __pyx_n_s_reduce __pyx_mstate_global->__pyx_n_s_reduce +#define __pyx_n_s_reduce_cython __pyx_mstate_global->__pyx_n_s_reduce_cython +#define __pyx_n_s_reduce_ex __pyx_mstate_global->__pyx_n_s_reduce_ex +#define __pyx_n_s_register __pyx_mstate_global->__pyx_n_s_register +#define __pyx_n_s_runtime __pyx_mstate_global->__pyx_n_s_runtime +#define __pyx_n_s_self __pyx_mstate_global->__pyx_n_s_self +#define __pyx_n_s_selfdrive_modeld_runners_snpemod __pyx_mstate_global->__pyx_n_s_selfdrive_modeld_runners_snpemod +#define __pyx_n_s_setstate __pyx_mstate_global->__pyx_n_s_setstate +#define __pyx_n_s_setstate_cython __pyx_mstate_global->__pyx_n_s_setstate_cython +#define __pyx_n_s_shape __pyx_mstate_global->__pyx_n_s_shape +#define __pyx_n_s_size __pyx_mstate_global->__pyx_n_s_size +#define __pyx_n_s_spec __pyx_mstate_global->__pyx_n_s_spec +#define __pyx_n_s_start __pyx_mstate_global->__pyx_n_s_start +#define __pyx_n_s_step __pyx_mstate_global->__pyx_n_s_step +#define __pyx_n_s_stop __pyx_mstate_global->__pyx_n_s_stop +#define __pyx_kp_s_strided_and_direct __pyx_mstate_global->__pyx_kp_s_strided_and_direct +#define __pyx_kp_s_strided_and_direct_or_indirect __pyx_mstate_global->__pyx_kp_s_strided_and_direct_or_indirect +#define __pyx_kp_s_strided_and_indirect __pyx_mstate_global->__pyx_kp_s_strided_and_indirect +#define __pyx_kp_s_stringsource __pyx_mstate_global->__pyx_kp_s_stringsource +#define __pyx_n_s_struct __pyx_mstate_global->__pyx_n_s_struct +#define __pyx_n_s_sys __pyx_mstate_global->__pyx_n_s_sys +#define __pyx_n_s_test __pyx_mstate_global->__pyx_n_s_test +#define __pyx_kp_s_unable_to_allocate_array_data __pyx_mstate_global->__pyx_kp_s_unable_to_allocate_array_data +#define __pyx_kp_s_unable_to_allocate_shape_and_str __pyx_mstate_global->__pyx_kp_s_unable_to_allocate_shape_and_str +#define __pyx_n_s_unpack __pyx_mstate_global->__pyx_n_s_unpack +#define __pyx_n_s_update __pyx_mstate_global->__pyx_n_s_update +#define __pyx_n_s_use_tf8 __pyx_mstate_global->__pyx_n_s_use_tf8 +#define __pyx_n_s_version_info __pyx_mstate_global->__pyx_n_s_version_info +#define __pyx_int_0 __pyx_mstate_global->__pyx_int_0 +#define __pyx_int_1 __pyx_mstate_global->__pyx_int_1 +#define __pyx_int_3 __pyx_mstate_global->__pyx_int_3 +#define __pyx_int_112105877 __pyx_mstate_global->__pyx_int_112105877 +#define __pyx_int_136983863 __pyx_mstate_global->__pyx_int_136983863 +#define __pyx_int_184977713 __pyx_mstate_global->__pyx_int_184977713 +#define __pyx_int_neg_1 __pyx_mstate_global->__pyx_int_neg_1 +#define __pyx_slice__5 __pyx_mstate_global->__pyx_slice__5 +#define __pyx_tuple__4 __pyx_mstate_global->__pyx_tuple__4 +#define __pyx_tuple__8 __pyx_mstate_global->__pyx_tuple__8 +#define __pyx_tuple__9 __pyx_mstate_global->__pyx_tuple__9 +#define __pyx_tuple__10 __pyx_mstate_global->__pyx_tuple__10 +#define __pyx_tuple__11 __pyx_mstate_global->__pyx_tuple__11 +#define __pyx_tuple__12 __pyx_mstate_global->__pyx_tuple__12 +#define __pyx_tuple__13 __pyx_mstate_global->__pyx_tuple__13 +#define __pyx_tuple__14 __pyx_mstate_global->__pyx_tuple__14 +#define __pyx_tuple__15 __pyx_mstate_global->__pyx_tuple__15 +#define __pyx_tuple__16 __pyx_mstate_global->__pyx_tuple__16 +#define __pyx_tuple__17 __pyx_mstate_global->__pyx_tuple__17 +#define __pyx_tuple__18 __pyx_mstate_global->__pyx_tuple__18 +#define __pyx_tuple__20 __pyx_mstate_global->__pyx_tuple__20 +#define __pyx_tuple__22 __pyx_mstate_global->__pyx_tuple__22 +#define __pyx_codeobj__19 __pyx_mstate_global->__pyx_codeobj__19 +#define __pyx_codeobj__21 __pyx_mstate_global->__pyx_codeobj__21 +#define __pyx_codeobj__23 __pyx_mstate_global->__pyx_codeobj__23 +/* #### Code section: module_code ### */ + +/* "string.from_py":13 + * + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: # <<<<<<<<<<<<<< + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + */ + +static std::string __pyx_convert_string_from_py_std__in_string(PyObject *__pyx_v_o) { + Py_ssize_t __pyx_v_length; + char const *__pyx_v_data; + std::string __pyx_r; + char const *__pyx_t_1; + std::string __pyx_t_2; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + + /* "string.from_py":14 + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: + * cdef Py_ssize_t length = 0 # <<<<<<<<<<<<<< + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + * return string(data, length) + */ + __pyx_v_length = 0; + + /* "string.from_py":15 + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) # <<<<<<<<<<<<<< + * return string(data, length) + * + */ + __pyx_t_1 = __Pyx_PyObject_AsStringAndSize(__pyx_v_o, (&__pyx_v_length)); if (unlikely(__pyx_t_1 == ((char const *)NULL))) __PYX_ERR(0, 15, __pyx_L1_error) + __pyx_v_data = __pyx_t_1; + + /* "string.from_py":16 + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + * return string(data, length) # <<<<<<<<<<<<<< + * + * + */ + try { + __pyx_t_2 = std::string(__pyx_v_data, __pyx_v_length); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(0, 16, __pyx_L1_error) + } + __pyx_r = __pyx_t_2; + goto __pyx_L0; + + /* "string.from_py":13 + * + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: # <<<<<<<<<<<<<< + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("string.from_py.__pyx_convert_string_from_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_pretend_to_initialize(&__pyx_r); + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":131 + * cdef bint dtype_is_object + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, # <<<<<<<<<<<<<< + * mode="c", bint allocate_buffer=True): + * + */ + +/* Python wrapper */ +static int __pyx_array___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_array___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_shape = 0; + Py_ssize_t __pyx_v_itemsize; + PyObject *__pyx_v_format = 0; + PyObject *__pyx_v_mode = 0; + int __pyx_v_allocate_buffer; + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[5] = {0,0,0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_shape,&__pyx_n_s_itemsize,&__pyx_n_s_format,&__pyx_n_s_mode,&__pyx_n_s_allocate_buffer,0}; + values[3] = __Pyx_Arg_NewRef_VARARGS(((PyObject *)__pyx_n_s_c)); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 5: values[4] = __Pyx_Arg_VARARGS(__pyx_args, 4); + CYTHON_FALLTHROUGH; + case 4: values[3] = __Pyx_Arg_VARARGS(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_shape)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 131, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_itemsize)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 131, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 3, 5, 1); __PYX_ERR(0, 131, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_format)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 131, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 3, 5, 2); __PYX_ERR(0, 131, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 3: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_mode); + if (value) { values[3] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 131, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 4: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_allocate_buffer); + if (value) { values[4] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 131, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(0, 131, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 5: values[4] = __Pyx_Arg_VARARGS(__pyx_args, 4); + CYTHON_FALLTHROUGH; + case 4: values[3] = __Pyx_Arg_VARARGS(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_shape = ((PyObject*)values[0]); + __pyx_v_itemsize = __Pyx_PyIndex_AsSsize_t(values[1]); if (unlikely((__pyx_v_itemsize == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 131, __pyx_L3_error) + __pyx_v_format = values[2]; + __pyx_v_mode = values[3]; + if (values[4]) { + __pyx_v_allocate_buffer = __Pyx_PyObject_IsTrue(values[4]); if (unlikely((__pyx_v_allocate_buffer == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 132, __pyx_L3_error) + } else { + + /* "View.MemoryView":132 + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, + * mode="c", bint allocate_buffer=True): # <<<<<<<<<<<<<< + * + * cdef int idx + */ + __pyx_v_allocate_buffer = ((int)1); + } + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 3, 5, __pyx_nargs); __PYX_ERR(0, 131, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.array.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_shape), (&PyTuple_Type), 1, "shape", 1))) __PYX_ERR(0, 131, __pyx_L1_error) + if (unlikely(((PyObject *)__pyx_v_format) == Py_None)) { + PyErr_Format(PyExc_TypeError, "Argument '%.200s' must not be None", "format"); __PYX_ERR(0, 131, __pyx_L1_error) + } + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array___cinit__(((struct __pyx_array_obj *)__pyx_v_self), __pyx_v_shape, __pyx_v_itemsize, __pyx_v_format, __pyx_v_mode, __pyx_v_allocate_buffer); + + /* "View.MemoryView":131 + * cdef bint dtype_is_object + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, # <<<<<<<<<<<<<< + * mode="c", bint allocate_buffer=True): + * + */ + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = -1; + __pyx_L0:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array___cinit__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_shape, Py_ssize_t __pyx_v_itemsize, PyObject *__pyx_v_format, PyObject *__pyx_v_mode, int __pyx_v_allocate_buffer) { + int __pyx_v_idx; + Py_ssize_t __pyx_v_dim; + char __pyx_v_order; + int __pyx_r; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + int __pyx_t_7; + char *__pyx_t_8; + Py_ssize_t __pyx_t_9; + Py_UCS4 __pyx_t_10; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__cinit__", 0); + __Pyx_INCREF(__pyx_v_format); + + /* "View.MemoryView":137 + * cdef Py_ssize_t dim + * + * self.ndim = len(shape) # <<<<<<<<<<<<<< + * self.itemsize = itemsize + * + */ + if (unlikely(__pyx_v_shape == Py_None)) { + PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); + __PYX_ERR(0, 137, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_PyTuple_GET_SIZE(__pyx_v_shape); if (unlikely(__pyx_t_1 == ((Py_ssize_t)-1))) __PYX_ERR(0, 137, __pyx_L1_error) + __pyx_v_self->ndim = ((int)__pyx_t_1); + + /* "View.MemoryView":138 + * + * self.ndim = len(shape) + * self.itemsize = itemsize # <<<<<<<<<<<<<< + * + * if not self.ndim: + */ + __pyx_v_self->itemsize = __pyx_v_itemsize; + + /* "View.MemoryView":140 + * self.itemsize = itemsize + * + * if not self.ndim: # <<<<<<<<<<<<<< + * raise ValueError, "Empty shape tuple for cython.array" + * + */ + __pyx_t_2 = (!(__pyx_v_self->ndim != 0)); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":141 + * + * if not self.ndim: + * raise ValueError, "Empty shape tuple for cython.array" # <<<<<<<<<<<<<< + * + * if itemsize <= 0: + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Empty_shape_tuple_for_cython_arr, 0, 0); + __PYX_ERR(0, 141, __pyx_L1_error) + + /* "View.MemoryView":140 + * self.itemsize = itemsize + * + * if not self.ndim: # <<<<<<<<<<<<<< + * raise ValueError, "Empty shape tuple for cython.array" + * + */ + } + + /* "View.MemoryView":143 + * raise ValueError, "Empty shape tuple for cython.array" + * + * if itemsize <= 0: # <<<<<<<<<<<<<< + * raise ValueError, "itemsize <= 0 for cython.array" + * + */ + __pyx_t_2 = (__pyx_v_itemsize <= 0); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":144 + * + * if itemsize <= 0: + * raise ValueError, "itemsize <= 0 for cython.array" # <<<<<<<<<<<<<< + * + * if not isinstance(format, bytes): + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_itemsize_0_for_cython_array, 0, 0); + __PYX_ERR(0, 144, __pyx_L1_error) + + /* "View.MemoryView":143 + * raise ValueError, "Empty shape tuple for cython.array" + * + * if itemsize <= 0: # <<<<<<<<<<<<<< + * raise ValueError, "itemsize <= 0 for cython.array" + * + */ + } + + /* "View.MemoryView":146 + * raise ValueError, "itemsize <= 0 for cython.array" + * + * if not isinstance(format, bytes): # <<<<<<<<<<<<<< + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string + */ + __pyx_t_2 = PyBytes_Check(__pyx_v_format); + __pyx_t_3 = (!__pyx_t_2); + if (__pyx_t_3) { + + /* "View.MemoryView":147 + * + * if not isinstance(format, bytes): + * format = format.encode('ASCII') # <<<<<<<<<<<<<< + * self._format = format # keep a reference to the byte string + * self.format = self._format + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_format, __pyx_n_s_encode); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 147, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = NULL; + __pyx_t_7 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_6 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_6)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_6); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_7 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_6, __pyx_n_s_ASCII}; + __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_7, 1+__pyx_t_7); + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 147, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + __Pyx_DECREF_SET(__pyx_v_format, __pyx_t_4); + __pyx_t_4 = 0; + + /* "View.MemoryView":146 + * raise ValueError, "itemsize <= 0 for cython.array" + * + * if not isinstance(format, bytes): # <<<<<<<<<<<<<< + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string + */ + } + + /* "View.MemoryView":148 + * if not isinstance(format, bytes): + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string # <<<<<<<<<<<<<< + * self.format = self._format + * + */ + if (!(likely(PyBytes_CheckExact(__pyx_v_format))||((__pyx_v_format) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_v_format))) __PYX_ERR(0, 148, __pyx_L1_error) + __pyx_t_4 = __pyx_v_format; + __Pyx_INCREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + __Pyx_GOTREF(__pyx_v_self->_format); + __Pyx_DECREF(__pyx_v_self->_format); + __pyx_v_self->_format = ((PyObject*)__pyx_t_4); + __pyx_t_4 = 0; + + /* "View.MemoryView":149 + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string + * self.format = self._format # <<<<<<<<<<<<<< + * + * + */ + if (unlikely(__pyx_v_self->_format == Py_None)) { + PyErr_SetString(PyExc_TypeError, "expected bytes, NoneType found"); + __PYX_ERR(0, 149, __pyx_L1_error) + } + __pyx_t_8 = __Pyx_PyBytes_AsWritableString(__pyx_v_self->_format); if (unlikely((!__pyx_t_8) && PyErr_Occurred())) __PYX_ERR(0, 149, __pyx_L1_error) + __pyx_v_self->format = __pyx_t_8; + + /* "View.MemoryView":152 + * + * + * self._shape = PyObject_Malloc(sizeof(Py_ssize_t)*self.ndim*2) # <<<<<<<<<<<<<< + * self._strides = self._shape + self.ndim + * + */ + __pyx_v_self->_shape = ((Py_ssize_t *)PyObject_Malloc((((sizeof(Py_ssize_t)) * __pyx_v_self->ndim) * 2))); + + /* "View.MemoryView":153 + * + * self._shape = PyObject_Malloc(sizeof(Py_ssize_t)*self.ndim*2) + * self._strides = self._shape + self.ndim # <<<<<<<<<<<<<< + * + * if not self._shape: + */ + __pyx_v_self->_strides = (__pyx_v_self->_shape + __pyx_v_self->ndim); + + /* "View.MemoryView":155 + * self._strides = self._shape + self.ndim + * + * if not self._shape: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate shape and strides." + * + */ + __pyx_t_3 = (!(__pyx_v_self->_shape != 0)); + if (unlikely(__pyx_t_3)) { + + /* "View.MemoryView":156 + * + * if not self._shape: + * raise MemoryError, "unable to allocate shape and strides." # <<<<<<<<<<<<<< + * + * + */ + __Pyx_Raise(__pyx_builtin_MemoryError, __pyx_kp_s_unable_to_allocate_shape_and_str, 0, 0); + __PYX_ERR(0, 156, __pyx_L1_error) + + /* "View.MemoryView":155 + * self._strides = self._shape + self.ndim + * + * if not self._shape: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate shape and strides." + * + */ + } + + /* "View.MemoryView":159 + * + * + * for idx, dim in enumerate(shape): # <<<<<<<<<<<<<< + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + */ + __pyx_t_7 = 0; + __pyx_t_4 = __pyx_v_shape; __Pyx_INCREF(__pyx_t_4); + __pyx_t_1 = 0; + for (;;) { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_4); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 159, __pyx_L1_error) + #endif + if (__pyx_t_1 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_5 = PyTuple_GET_ITEM(__pyx_t_4, __pyx_t_1); __Pyx_INCREF(__pyx_t_5); __pyx_t_1++; if (unlikely((0 < 0))) __PYX_ERR(0, 159, __pyx_L1_error) + #else + __pyx_t_5 = __Pyx_PySequence_ITEM(__pyx_t_4, __pyx_t_1); __pyx_t_1++; if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 159, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + #endif + __pyx_t_9 = __Pyx_PyIndex_AsSsize_t(__pyx_t_5); if (unlikely((__pyx_t_9 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 159, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_v_dim = __pyx_t_9; + __pyx_v_idx = __pyx_t_7; + __pyx_t_7 = (__pyx_t_7 + 1); + + /* "View.MemoryView":160 + * + * for idx, dim in enumerate(shape): + * if dim <= 0: # <<<<<<<<<<<<<< + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + * self._shape[idx] = dim + */ + __pyx_t_3 = (__pyx_v_dim <= 0); + if (unlikely(__pyx_t_3)) { + + /* "View.MemoryView":161 + * for idx, dim in enumerate(shape): + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." # <<<<<<<<<<<<<< + * self._shape[idx] = dim + * + */ + __pyx_t_5 = PyTuple_New(5); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_9 = 0; + __pyx_t_10 = 127; + __Pyx_INCREF(__pyx_kp_u_Invalid_shape_in_axis); + __pyx_t_9 += 22; + __Pyx_GIVEREF(__pyx_kp_u_Invalid_shape_in_axis); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_kp_u_Invalid_shape_in_axis); + __pyx_t_6 = __Pyx_PyUnicode_From_int(__pyx_v_idx, 0, ' ', 'd'); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_9 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_6); + __Pyx_GIVEREF(__pyx_t_6); + PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_6); + __pyx_t_6 = 0; + __Pyx_INCREF(__pyx_kp_u_); + __pyx_t_9 += 2; + __Pyx_GIVEREF(__pyx_kp_u_); + PyTuple_SET_ITEM(__pyx_t_5, 2, __pyx_kp_u_); + __pyx_t_6 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_dim, 0, ' ', 'd'); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_9 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_6); + __Pyx_GIVEREF(__pyx_t_6); + PyTuple_SET_ITEM(__pyx_t_5, 3, __pyx_t_6); + __pyx_t_6 = 0; + __Pyx_INCREF(__pyx_kp_u__2); + __pyx_t_9 += 1; + __Pyx_GIVEREF(__pyx_kp_u__2); + PyTuple_SET_ITEM(__pyx_t_5, 4, __pyx_kp_u__2); + __pyx_t_6 = __Pyx_PyUnicode_Join(__pyx_t_5, 5, __pyx_t_9, __pyx_t_10); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_t_6, 0, 0); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __PYX_ERR(0, 161, __pyx_L1_error) + + /* "View.MemoryView":160 + * + * for idx, dim in enumerate(shape): + * if dim <= 0: # <<<<<<<<<<<<<< + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + * self._shape[idx] = dim + */ + } + + /* "View.MemoryView":162 + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + * self._shape[idx] = dim # <<<<<<<<<<<<<< + * + * cdef char order + */ + (__pyx_v_self->_shape[__pyx_v_idx]) = __pyx_v_dim; + + /* "View.MemoryView":159 + * + * + * for idx, dim in enumerate(shape): # <<<<<<<<<<<<<< + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + */ + } + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "View.MemoryView":165 + * + * cdef char order + * if mode == 'c': # <<<<<<<<<<<<<< + * order = b'C' + * self.mode = u'c' + */ + __pyx_t_3 = (__Pyx_PyString_Equals(__pyx_v_mode, __pyx_n_s_c, Py_EQ)); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(0, 165, __pyx_L1_error) + if (__pyx_t_3) { + + /* "View.MemoryView":166 + * cdef char order + * if mode == 'c': + * order = b'C' # <<<<<<<<<<<<<< + * self.mode = u'c' + * elif mode == 'fortran': + */ + __pyx_v_order = 'C'; + + /* "View.MemoryView":167 + * if mode == 'c': + * order = b'C' + * self.mode = u'c' # <<<<<<<<<<<<<< + * elif mode == 'fortran': + * order = b'F' + */ + __Pyx_INCREF(__pyx_n_u_c); + __Pyx_GIVEREF(__pyx_n_u_c); + __Pyx_GOTREF(__pyx_v_self->mode); + __Pyx_DECREF(__pyx_v_self->mode); + __pyx_v_self->mode = __pyx_n_u_c; + + /* "View.MemoryView":165 + * + * cdef char order + * if mode == 'c': # <<<<<<<<<<<<<< + * order = b'C' + * self.mode = u'c' + */ + goto __pyx_L11; + } + + /* "View.MemoryView":168 + * order = b'C' + * self.mode = u'c' + * elif mode == 'fortran': # <<<<<<<<<<<<<< + * order = b'F' + * self.mode = u'fortran' + */ + __pyx_t_3 = (__Pyx_PyString_Equals(__pyx_v_mode, __pyx_n_s_fortran, Py_EQ)); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(0, 168, __pyx_L1_error) + if (likely(__pyx_t_3)) { + + /* "View.MemoryView":169 + * self.mode = u'c' + * elif mode == 'fortran': + * order = b'F' # <<<<<<<<<<<<<< + * self.mode = u'fortran' + * else: + */ + __pyx_v_order = 'F'; + + /* "View.MemoryView":170 + * elif mode == 'fortran': + * order = b'F' + * self.mode = u'fortran' # <<<<<<<<<<<<<< + * else: + * raise ValueError, f"Invalid mode, expected 'c' or 'fortran', got {mode}" + */ + __Pyx_INCREF(__pyx_n_u_fortran); + __Pyx_GIVEREF(__pyx_n_u_fortran); + __Pyx_GOTREF(__pyx_v_self->mode); + __Pyx_DECREF(__pyx_v_self->mode); + __pyx_v_self->mode = __pyx_n_u_fortran; + + /* "View.MemoryView":168 + * order = b'C' + * self.mode = u'c' + * elif mode == 'fortran': # <<<<<<<<<<<<<< + * order = b'F' + * self.mode = u'fortran' + */ + goto __pyx_L11; + } + + /* "View.MemoryView":172 + * self.mode = u'fortran' + * else: + * raise ValueError, f"Invalid mode, expected 'c' or 'fortran', got {mode}" # <<<<<<<<<<<<<< + * + * self.len = fill_contig_strides_array(self._shape, self._strides, itemsize, self.ndim, order) + */ + /*else*/ { + __pyx_t_4 = __Pyx_PyObject_FormatSimple(__pyx_v_mode, __pyx_empty_unicode); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 172, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_6 = __Pyx_PyUnicode_Concat(__pyx_kp_u_Invalid_mode_expected_c_or_fortr, __pyx_t_4); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 172, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_t_6, 0, 0); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __PYX_ERR(0, 172, __pyx_L1_error) + } + __pyx_L11:; + + /* "View.MemoryView":174 + * raise ValueError, f"Invalid mode, expected 'c' or 'fortran', got {mode}" + * + * self.len = fill_contig_strides_array(self._shape, self._strides, itemsize, self.ndim, order) # <<<<<<<<<<<<<< + * + * self.free_data = allocate_buffer + */ + __pyx_v_self->len = __pyx_fill_contig_strides_array(__pyx_v_self->_shape, __pyx_v_self->_strides, __pyx_v_itemsize, __pyx_v_self->ndim, __pyx_v_order); + + /* "View.MemoryView":176 + * self.len = fill_contig_strides_array(self._shape, self._strides, itemsize, self.ndim, order) + * + * self.free_data = allocate_buffer # <<<<<<<<<<<<<< + * self.dtype_is_object = format == b'O' + * + */ + __pyx_v_self->free_data = __pyx_v_allocate_buffer; + + /* "View.MemoryView":177 + * + * self.free_data = allocate_buffer + * self.dtype_is_object = format == b'O' # <<<<<<<<<<<<<< + * + * if allocate_buffer: + */ + __pyx_t_6 = PyObject_RichCompare(__pyx_v_format, __pyx_n_b_O, Py_EQ); __Pyx_XGOTREF(__pyx_t_6); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 177, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_IsTrue(__pyx_t_6); if (unlikely((__pyx_t_3 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 177, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __pyx_v_self->dtype_is_object = __pyx_t_3; + + /* "View.MemoryView":179 + * self.dtype_is_object = format == b'O' + * + * if allocate_buffer: # <<<<<<<<<<<<<< + * _allocate_buffer(self) + * + */ + if (__pyx_v_allocate_buffer) { + + /* "View.MemoryView":180 + * + * if allocate_buffer: + * _allocate_buffer(self) # <<<<<<<<<<<<<< + * + * @cname('getbuffer') + */ + __pyx_t_7 = __pyx_array_allocate_buffer(__pyx_v_self); if (unlikely(__pyx_t_7 == ((int)-1))) __PYX_ERR(0, 180, __pyx_L1_error) + + /* "View.MemoryView":179 + * self.dtype_is_object = format == b'O' + * + * if allocate_buffer: # <<<<<<<<<<<<<< + * _allocate_buffer(self) + * + */ + } + + /* "View.MemoryView":131 + * cdef bint dtype_is_object + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, # <<<<<<<<<<<<<< + * mode="c", bint allocate_buffer=True): + * + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("View.MemoryView.array.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_format); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":182 + * _allocate_buffer(self) + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + */ + +/* Python wrapper */ +CYTHON_UNUSED static int __pyx_array_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +CYTHON_UNUSED static int __pyx_array_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getbuffer__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_2__getbuffer__(((struct __pyx_array_obj *)__pyx_v_self), ((Py_buffer *)__pyx_v_info), ((int)__pyx_v_flags)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_2__getbuffer__(struct __pyx_array_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + int __pyx_v_bufmode; + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + char *__pyx_t_2; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + Py_ssize_t *__pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + if (unlikely(__pyx_v_info == NULL)) { + PyErr_SetString(PyExc_BufferError, "PyObject_GetBuffer: view==NULL argument is obsolete"); + return -1; + } + __Pyx_RefNannySetupContext("__getbuffer__", 0); + __pyx_v_info->obj = Py_None; __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(__pyx_v_info->obj); + + /* "View.MemoryView":184 + * @cname('getbuffer') + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 # <<<<<<<<<<<<<< + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": + */ + __pyx_v_bufmode = -1; + + /* "View.MemoryView":185 + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): # <<<<<<<<<<<<<< + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + */ + __pyx_t_1 = ((__pyx_v_flags & ((PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS) | PyBUF_ANY_CONTIGUOUS)) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":186 + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": # <<<<<<<<<<<<<< + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": + */ + __pyx_t_1 = (__Pyx_PyUnicode_Equals(__pyx_v_self->mode, __pyx_n_u_c, Py_EQ)); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(0, 186, __pyx_L1_error) + if (__pyx_t_1) { + + /* "View.MemoryView":187 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS # <<<<<<<<<<<<<< + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + */ + __pyx_v_bufmode = (PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS); + + /* "View.MemoryView":186 + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": # <<<<<<<<<<<<<< + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": + */ + goto __pyx_L4; + } + + /* "View.MemoryView":188 + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": # <<<<<<<<<<<<<< + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): + */ + __pyx_t_1 = (__Pyx_PyUnicode_Equals(__pyx_v_self->mode, __pyx_n_u_fortran, Py_EQ)); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(0, 188, __pyx_L1_error) + if (__pyx_t_1) { + + /* "View.MemoryView":189 + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS # <<<<<<<<<<<<<< + * if not (flags & bufmode): + * raise ValueError, "Can only create a buffer that is contiguous in memory." + */ + __pyx_v_bufmode = (PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS); + + /* "View.MemoryView":188 + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": # <<<<<<<<<<<<<< + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): + */ + } + __pyx_L4:; + + /* "View.MemoryView":190 + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): # <<<<<<<<<<<<<< + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data + */ + __pyx_t_1 = (!((__pyx_v_flags & __pyx_v_bufmode) != 0)); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":191 + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): + * raise ValueError, "Can only create a buffer that is contiguous in memory." # <<<<<<<<<<<<<< + * info.buf = self.data + * info.len = self.len + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Can_only_create_a_buffer_that_is, 0, 0); + __PYX_ERR(0, 191, __pyx_L1_error) + + /* "View.MemoryView":190 + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): # <<<<<<<<<<<<<< + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data + */ + } + + /* "View.MemoryView":185 + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): # <<<<<<<<<<<<<< + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + */ + } + + /* "View.MemoryView":192 + * if not (flags & bufmode): + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data # <<<<<<<<<<<<<< + * info.len = self.len + * + */ + __pyx_t_2 = __pyx_v_self->data; + __pyx_v_info->buf = __pyx_t_2; + + /* "View.MemoryView":193 + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data + * info.len = self.len # <<<<<<<<<<<<<< + * + * if flags & PyBUF_STRIDES: + */ + __pyx_t_3 = __pyx_v_self->len; + __pyx_v_info->len = __pyx_t_3; + + /* "View.MemoryView":195 + * info.len = self.len + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.ndim = self.ndim + * info.shape = self._shape + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_STRIDES) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":196 + * + * if flags & PyBUF_STRIDES: + * info.ndim = self.ndim # <<<<<<<<<<<<<< + * info.shape = self._shape + * info.strides = self._strides + */ + __pyx_t_4 = __pyx_v_self->ndim; + __pyx_v_info->ndim = __pyx_t_4; + + /* "View.MemoryView":197 + * if flags & PyBUF_STRIDES: + * info.ndim = self.ndim + * info.shape = self._shape # <<<<<<<<<<<<<< + * info.strides = self._strides + * else: + */ + __pyx_t_5 = __pyx_v_self->_shape; + __pyx_v_info->shape = __pyx_t_5; + + /* "View.MemoryView":198 + * info.ndim = self.ndim + * info.shape = self._shape + * info.strides = self._strides # <<<<<<<<<<<<<< + * else: + * info.ndim = 1 + */ + __pyx_t_5 = __pyx_v_self->_strides; + __pyx_v_info->strides = __pyx_t_5; + + /* "View.MemoryView":195 + * info.len = self.len + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.ndim = self.ndim + * info.shape = self._shape + */ + goto __pyx_L6; + } + + /* "View.MemoryView":200 + * info.strides = self._strides + * else: + * info.ndim = 1 # <<<<<<<<<<<<<< + * info.shape = &self.len if flags & PyBUF_ND else NULL + * info.strides = NULL + */ + /*else*/ { + __pyx_v_info->ndim = 1; + + /* "View.MemoryView":201 + * else: + * info.ndim = 1 + * info.shape = &self.len if flags & PyBUF_ND else NULL # <<<<<<<<<<<<<< + * info.strides = NULL + * + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_ND) != 0); + if (__pyx_t_1) { + __pyx_t_5 = (&__pyx_v_self->len); + } else { + __pyx_t_5 = NULL; + } + __pyx_v_info->shape = __pyx_t_5; + + /* "View.MemoryView":202 + * info.ndim = 1 + * info.shape = &self.len if flags & PyBUF_ND else NULL + * info.strides = NULL # <<<<<<<<<<<<<< + * + * info.suboffsets = NULL + */ + __pyx_v_info->strides = NULL; + } + __pyx_L6:; + + /* "View.MemoryView":204 + * info.strides = NULL + * + * info.suboffsets = NULL # <<<<<<<<<<<<<< + * info.itemsize = self.itemsize + * info.readonly = 0 + */ + __pyx_v_info->suboffsets = NULL; + + /* "View.MemoryView":205 + * + * info.suboffsets = NULL + * info.itemsize = self.itemsize # <<<<<<<<<<<<<< + * info.readonly = 0 + * info.format = self.format if flags & PyBUF_FORMAT else NULL + */ + __pyx_t_3 = __pyx_v_self->itemsize; + __pyx_v_info->itemsize = __pyx_t_3; + + /* "View.MemoryView":206 + * info.suboffsets = NULL + * info.itemsize = self.itemsize + * info.readonly = 0 # <<<<<<<<<<<<<< + * info.format = self.format if flags & PyBUF_FORMAT else NULL + * info.obj = self + */ + __pyx_v_info->readonly = 0; + + /* "View.MemoryView":207 + * info.itemsize = self.itemsize + * info.readonly = 0 + * info.format = self.format if flags & PyBUF_FORMAT else NULL # <<<<<<<<<<<<<< + * info.obj = self + * + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_FORMAT) != 0); + if (__pyx_t_1) { + __pyx_t_2 = __pyx_v_self->format; + } else { + __pyx_t_2 = NULL; + } + __pyx_v_info->format = __pyx_t_2; + + /* "View.MemoryView":208 + * info.readonly = 0 + * info.format = self.format if flags & PyBUF_FORMAT else NULL + * info.obj = self # <<<<<<<<<<<<<< + * + * def __dealloc__(array self): + */ + __Pyx_INCREF((PyObject *)__pyx_v_self); + __Pyx_GIVEREF((PyObject *)__pyx_v_self); + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); + __pyx_v_info->obj = ((PyObject *)__pyx_v_self); + + /* "View.MemoryView":182 + * _allocate_buffer(self) + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.array.__getbuffer__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + if (__pyx_v_info->obj != NULL) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + goto __pyx_L2; + __pyx_L0:; + if (__pyx_v_info->obj == Py_None) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + __pyx_L2:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":210 + * info.obj = self + * + * def __dealloc__(array self): # <<<<<<<<<<<<<< + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + */ + +/* Python wrapper */ +static void __pyx_array___dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_array___dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_array___pyx_pf_15View_dot_MemoryView_5array_4__dealloc__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_array___pyx_pf_15View_dot_MemoryView_5array_4__dealloc__(struct __pyx_array_obj *__pyx_v_self) { + int __pyx_t_1; + int __pyx_t_2; + + /* "View.MemoryView":211 + * + * def __dealloc__(array self): + * if self.callback_free_data != NULL: # <<<<<<<<<<<<<< + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + */ + __pyx_t_1 = (__pyx_v_self->callback_free_data != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":212 + * def __dealloc__(array self): + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) # <<<<<<<<<<<<<< + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: + */ + __pyx_v_self->callback_free_data(__pyx_v_self->data); + + /* "View.MemoryView":211 + * + * def __dealloc__(array self): + * if self.callback_free_data != NULL: # <<<<<<<<<<<<<< + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":213 + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: # <<<<<<<<<<<<<< + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + */ + if (__pyx_v_self->free_data) { + } else { + __pyx_t_1 = __pyx_v_self->free_data; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_2 = (__pyx_v_self->data != NULL); + __pyx_t_1 = __pyx_t_2; + __pyx_L4_bool_binop_done:; + if (__pyx_t_1) { + + /* "View.MemoryView":214 + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) + */ + if (__pyx_v_self->dtype_is_object) { + + /* "View.MemoryView":215 + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) # <<<<<<<<<<<<<< + * free(self.data) + * PyObject_Free(self._shape) + */ + __pyx_memoryview_refcount_objects_in_slice(__pyx_v_self->data, __pyx_v_self->_shape, __pyx_v_self->_strides, __pyx_v_self->ndim, 0); + + /* "View.MemoryView":214 + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) + */ + } + + /* "View.MemoryView":216 + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) # <<<<<<<<<<<<<< + * PyObject_Free(self._shape) + * + */ + free(__pyx_v_self->data); + + /* "View.MemoryView":213 + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: # <<<<<<<<<<<<<< + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + */ + } + __pyx_L3:; + + /* "View.MemoryView":217 + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) + * PyObject_Free(self._shape) # <<<<<<<<<<<<<< + * + * @property + */ + PyObject_Free(__pyx_v_self->_shape); + + /* "View.MemoryView":210 + * info.obj = self + * + * def __dealloc__(array self): # <<<<<<<<<<<<<< + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + */ + + /* function exit code */ +} + +/* "View.MemoryView":219 + * PyObject_Free(self._shape) + * + * @property # <<<<<<<<<<<<<< + * def memview(self): + * return self.get_memview() + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_5array_7memview_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_5array_7memview_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_5array_7memview___get__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_5array_7memview___get__(struct __pyx_array_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":221 + * @property + * def memview(self): + * return self.get_memview() # <<<<<<<<<<<<<< + * + * @cname('get_memview') + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = ((struct __pyx_vtabstruct_array *)__pyx_v_self->__pyx_vtab)->get_memview(__pyx_v_self); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 221, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":219 + * PyObject_Free(self._shape) + * + * @property # <<<<<<<<<<<<<< + * def memview(self): + * return self.get_memview() + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.array.memview.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":224 + * + * @cname('get_memview') + * cdef get_memview(self): # <<<<<<<<<<<<<< + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE + * return memoryview(self, flags, self.dtype_is_object) + */ + +static PyObject *__pyx_array_get_memview(struct __pyx_array_obj *__pyx_v_self) { + int __pyx_v_flags; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_memview", 1); + + /* "View.MemoryView":225 + * @cname('get_memview') + * cdef get_memview(self): + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE # <<<<<<<<<<<<<< + * return memoryview(self, flags, self.dtype_is_object) + * + */ + __pyx_v_flags = ((PyBUF_ANY_CONTIGUOUS | PyBUF_FORMAT) | PyBUF_WRITABLE); + + /* "View.MemoryView":226 + * cdef get_memview(self): + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE + * return memoryview(self, flags, self.dtype_is_object) # <<<<<<<<<<<<<< + * + * def __len__(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_flags); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_v_self->dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF((PyObject *)__pyx_v_self); + __Pyx_GIVEREF((PyObject *)__pyx_v_self); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, ((PyObject *)__pyx_v_self))) __PYX_ERR(0, 226, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1)) __PYX_ERR(0, 226, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_t_2)) __PYX_ERR(0, 226, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_Call(((PyObject *)__pyx_memoryview_type), __pyx_t_3, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":224 + * + * @cname('get_memview') + * cdef get_memview(self): # <<<<<<<<<<<<<< + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE + * return memoryview(self, flags, self.dtype_is_object) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.array.get_memview", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":228 + * return memoryview(self, flags, self.dtype_is_object) + * + * def __len__(self): # <<<<<<<<<<<<<< + * return self._shape[0] + * + */ + +/* Python wrapper */ +static Py_ssize_t __pyx_array___len__(PyObject *__pyx_v_self); /*proto*/ +static Py_ssize_t __pyx_array___len__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + Py_ssize_t __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__len__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_6__len__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static Py_ssize_t __pyx_array___pyx_pf_15View_dot_MemoryView_5array_6__len__(struct __pyx_array_obj *__pyx_v_self) { + Py_ssize_t __pyx_r; + + /* "View.MemoryView":229 + * + * def __len__(self): + * return self._shape[0] # <<<<<<<<<<<<<< + * + * def __getattr__(self, attr): + */ + __pyx_r = (__pyx_v_self->_shape[0]); + goto __pyx_L0; + + /* "View.MemoryView":228 + * return memoryview(self, flags, self.dtype_is_object) + * + * def __len__(self): # <<<<<<<<<<<<<< + * return self._shape[0] + * + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":231 + * return self._shape[0] + * + * def __getattr__(self, attr): # <<<<<<<<<<<<<< + * return getattr(self.memview, attr) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_array___getattr__(PyObject *__pyx_v_self, PyObject *__pyx_v_attr); /*proto*/ +static PyObject *__pyx_array___getattr__(PyObject *__pyx_v_self, PyObject *__pyx_v_attr) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getattr__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_8__getattr__(((struct __pyx_array_obj *)__pyx_v_self), ((PyObject *)__pyx_v_attr)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_8__getattr__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_attr) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__getattr__", 1); + + /* "View.MemoryView":232 + * + * def __getattr__(self, attr): + * return getattr(self.memview, attr) # <<<<<<<<<<<<<< + * + * def __getitem__(self, item): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_memview); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 232, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_GetAttr(__pyx_t_1, __pyx_v_attr); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 232, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":231 + * return self._shape[0] + * + * def __getattr__(self, attr): # <<<<<<<<<<<<<< + * return getattr(self.memview, attr) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.array.__getattr__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":234 + * return getattr(self.memview, attr) + * + * def __getitem__(self, item): # <<<<<<<<<<<<<< + * return self.memview[item] + * + */ + +/* Python wrapper */ +static PyObject *__pyx_array___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item); /*proto*/ +static PyObject *__pyx_array___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getitem__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_10__getitem__(((struct __pyx_array_obj *)__pyx_v_self), ((PyObject *)__pyx_v_item)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_10__getitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__getitem__", 1); + + /* "View.MemoryView":235 + * + * def __getitem__(self, item): + * return self.memview[item] # <<<<<<<<<<<<<< + * + * def __setitem__(self, item, value): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_memview); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 235, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_t_1, __pyx_v_item); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 235, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":234 + * return getattr(self.memview, attr) + * + * def __getitem__(self, item): # <<<<<<<<<<<<<< + * return self.memview[item] + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.array.__getitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":237 + * return self.memview[item] + * + * def __setitem__(self, item, value): # <<<<<<<<<<<<<< + * self.memview[item] = value + * + */ + +/* Python wrapper */ +static int __pyx_array___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value); /*proto*/ +static int __pyx_array___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setitem__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_12__setitem__(((struct __pyx_array_obj *)__pyx_v_self), ((PyObject *)__pyx_v_item), ((PyObject *)__pyx_v_value)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_12__setitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setitem__", 1); + + /* "View.MemoryView":238 + * + * def __setitem__(self, item, value): + * self.memview[item] = value # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_memview); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 238, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyObject_SetItem(__pyx_t_1, __pyx_v_item, __pyx_v_value) < 0))) __PYX_ERR(0, 238, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "View.MemoryView":237 + * return self.memview[item] + * + * def __setitem__(self, item, value): # <<<<<<<<<<<<<< + * self.memview[item] = value + * + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.array.__setitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_array_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_array_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_array___reduce_cython__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_array___reduce_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(0, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.array.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_array_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_array_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(0, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.array.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_array_2__setstate_cython__(((struct __pyx_array_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_array_2__setstate_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(0, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.array.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":248 + * + * @cname("__pyx_array_allocate_buffer") + * cdef int _allocate_buffer(array self) except -1: # <<<<<<<<<<<<<< + * + * + */ + +static int __pyx_array_allocate_buffer(struct __pyx_array_obj *__pyx_v_self) { + Py_ssize_t __pyx_v_i; + PyObject **__pyx_v_p; + int __pyx_r; + int __pyx_t_1; + Py_ssize_t __pyx_t_2; + Py_ssize_t __pyx_t_3; + Py_ssize_t __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + + /* "View.MemoryView":254 + * cdef PyObject **p + * + * self.free_data = True # <<<<<<<<<<<<<< + * self.data = malloc(self.len) + * if not self.data: + */ + __pyx_v_self->free_data = 1; + + /* "View.MemoryView":255 + * + * self.free_data = True + * self.data = malloc(self.len) # <<<<<<<<<<<<<< + * if not self.data: + * raise MemoryError, "unable to allocate array data." + */ + __pyx_v_self->data = ((char *)malloc(__pyx_v_self->len)); + + /* "View.MemoryView":256 + * self.free_data = True + * self.data = malloc(self.len) + * if not self.data: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate array data." + * + */ + __pyx_t_1 = (!(__pyx_v_self->data != 0)); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":257 + * self.data = malloc(self.len) + * if not self.data: + * raise MemoryError, "unable to allocate array data." # <<<<<<<<<<<<<< + * + * if self.dtype_is_object: + */ + __Pyx_Raise(__pyx_builtin_MemoryError, __pyx_kp_s_unable_to_allocate_array_data, 0, 0); + __PYX_ERR(0, 257, __pyx_L1_error) + + /* "View.MemoryView":256 + * self.free_data = True + * self.data = malloc(self.len) + * if not self.data: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate array data." + * + */ + } + + /* "View.MemoryView":259 + * raise MemoryError, "unable to allocate array data." + * + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * p = self.data + * for i in range(self.len // self.itemsize): + */ + if (__pyx_v_self->dtype_is_object) { + + /* "View.MemoryView":260 + * + * if self.dtype_is_object: + * p = self.data # <<<<<<<<<<<<<< + * for i in range(self.len // self.itemsize): + * p[i] = Py_None + */ + __pyx_v_p = ((PyObject **)__pyx_v_self->data); + + /* "View.MemoryView":261 + * if self.dtype_is_object: + * p = self.data + * for i in range(self.len // self.itemsize): # <<<<<<<<<<<<<< + * p[i] = Py_None + * Py_INCREF(Py_None) + */ + if (unlikely(__pyx_v_self->itemsize == 0)) { + PyErr_SetString(PyExc_ZeroDivisionError, "integer division or modulo by zero"); + __PYX_ERR(0, 261, __pyx_L1_error) + } + else if (sizeof(Py_ssize_t) == sizeof(long) && (!(((Py_ssize_t)-1) > 0)) && unlikely(__pyx_v_self->itemsize == (Py_ssize_t)-1) && unlikely(__Pyx_UNARY_NEG_WOULD_OVERFLOW(__pyx_v_self->len))) { + PyErr_SetString(PyExc_OverflowError, "value too large to perform division"); + __PYX_ERR(0, 261, __pyx_L1_error) + } + __pyx_t_2 = __Pyx_div_Py_ssize_t(__pyx_v_self->len, __pyx_v_self->itemsize); + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":262 + * p = self.data + * for i in range(self.len // self.itemsize): + * p[i] = Py_None # <<<<<<<<<<<<<< + * Py_INCREF(Py_None) + * return 0 + */ + (__pyx_v_p[__pyx_v_i]) = Py_None; + + /* "View.MemoryView":263 + * for i in range(self.len // self.itemsize): + * p[i] = Py_None + * Py_INCREF(Py_None) # <<<<<<<<<<<<<< + * return 0 + * + */ + Py_INCREF(Py_None); + } + + /* "View.MemoryView":259 + * raise MemoryError, "unable to allocate array data." + * + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * p = self.data + * for i in range(self.len // self.itemsize): + */ + } + + /* "View.MemoryView":264 + * p[i] = Py_None + * Py_INCREF(Py_None) + * return 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":248 + * + * @cname("__pyx_array_allocate_buffer") + * cdef int _allocate_buffer(array self) except -1: # <<<<<<<<<<<<<< + * + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._allocate_buffer", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":268 + * + * @cname("__pyx_array_new") + * cdef array array_cwrapper(tuple shape, Py_ssize_t itemsize, char *format, char *c_mode, char *buf): # <<<<<<<<<<<<<< + * cdef array result + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + */ + +static struct __pyx_array_obj *__pyx_array_new(PyObject *__pyx_v_shape, Py_ssize_t __pyx_v_itemsize, char *__pyx_v_format, char *__pyx_v_c_mode, char *__pyx_v_buf) { + struct __pyx_array_obj *__pyx_v_result = 0; + PyObject *__pyx_v_mode = 0; + struct __pyx_array_obj *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("array_cwrapper", 1); + + /* "View.MemoryView":270 + * cdef array array_cwrapper(tuple shape, Py_ssize_t itemsize, char *format, char *c_mode, char *buf): + * cdef array result + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. # <<<<<<<<<<<<<< + * + * if buf is NULL: + */ + __pyx_t_2 = ((__pyx_v_c_mode[0]) == 'f'); + if (__pyx_t_2) { + __Pyx_INCREF(__pyx_n_s_fortran); + __pyx_t_1 = __pyx_n_s_fortran; + } else { + __Pyx_INCREF(__pyx_n_s_c); + __pyx_t_1 = __pyx_n_s_c; + } + __pyx_v_mode = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":272 + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + * + * if buf is NULL: # <<<<<<<<<<<<<< + * result = array.__new__(array, shape, itemsize, format, mode) + * else: + */ + __pyx_t_2 = (__pyx_v_buf == NULL); + if (__pyx_t_2) { + + /* "View.MemoryView":273 + * + * if buf is NULL: + * result = array.__new__(array, shape, itemsize, format, mode) # <<<<<<<<<<<<<< + * else: + * result = array.__new__(array, shape, itemsize, format, mode, allocate_buffer=False) + */ + __pyx_t_1 = PyInt_FromSsize_t(__pyx_v_itemsize); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 273, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyBytes_FromString(__pyx_v_format); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 273, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PyTuple_New(4); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 273, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_INCREF(__pyx_v_shape); + __Pyx_GIVEREF(__pyx_v_shape); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_v_shape)) __PYX_ERR(0, 273, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_t_1)) __PYX_ERR(0, 273, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 2, __pyx_t_3)) __PYX_ERR(0, 273, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_mode); + __Pyx_GIVEREF(__pyx_v_mode); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 3, __pyx_v_mode)) __PYX_ERR(0, 273, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_3 = 0; + __pyx_t_3 = ((PyObject *)__pyx_tp_new_array(((PyTypeObject *)__pyx_array_type), __pyx_t_4, NULL)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 273, __pyx_L1_error) + __Pyx_GOTREF((PyObject *)__pyx_t_3); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_v_result = ((struct __pyx_array_obj *)__pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":272 + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + * + * if buf is NULL: # <<<<<<<<<<<<<< + * result = array.__new__(array, shape, itemsize, format, mode) + * else: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":275 + * result = array.__new__(array, shape, itemsize, format, mode) + * else: + * result = array.__new__(array, shape, itemsize, format, mode, allocate_buffer=False) # <<<<<<<<<<<<<< + * result.data = buf + * + */ + /*else*/ { + __pyx_t_3 = PyInt_FromSsize_t(__pyx_v_itemsize); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = __Pyx_PyBytes_FromString(__pyx_v_format); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_1 = PyTuple_New(4); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v_shape); + __Pyx_GIVEREF(__pyx_v_shape); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v_shape)) __PYX_ERR(0, 275, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_t_3)) __PYX_ERR(0, 275, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_4); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_t_4)) __PYX_ERR(0, 275, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_mode); + __Pyx_GIVEREF(__pyx_v_mode); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 3, __pyx_v_mode)) __PYX_ERR(0, 275, __pyx_L1_error); + __pyx_t_3 = 0; + __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem(__pyx_t_4, __pyx_n_s_allocate_buffer, Py_False) < 0) __PYX_ERR(0, 275, __pyx_L1_error) + __pyx_t_3 = ((PyObject *)__pyx_tp_new_array(((PyTypeObject *)__pyx_array_type), __pyx_t_1, __pyx_t_4)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 275, __pyx_L1_error) + __Pyx_GOTREF((PyObject *)__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_v_result = ((struct __pyx_array_obj *)__pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":276 + * else: + * result = array.__new__(array, shape, itemsize, format, mode, allocate_buffer=False) + * result.data = buf # <<<<<<<<<<<<<< + * + * return result + */ + __pyx_v_result->data = __pyx_v_buf; + } + __pyx_L3:; + + /* "View.MemoryView":278 + * result.data = buf + * + * return result # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF((PyObject *)__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = __pyx_v_result; + goto __pyx_L0; + + /* "View.MemoryView":268 + * + * @cname("__pyx_array_new") + * cdef array array_cwrapper(tuple shape, Py_ssize_t itemsize, char *format, char *c_mode, char *buf): # <<<<<<<<<<<<<< + * cdef array result + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.array_cwrapper", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XDECREF(__pyx_v_mode); + __Pyx_XGIVEREF((PyObject *)__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":304 + * cdef class Enum(object): + * cdef object name + * def __init__(self, name): # <<<<<<<<<<<<<< + * self.name = name + * def __repr__(self): + */ + +/* Python wrapper */ +static int __pyx_MemviewEnum___init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_MemviewEnum___init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_name = 0; + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__init__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_name,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_name)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 304, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__init__") < 0)) __PYX_ERR(0, 304, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + } + __pyx_v_name = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__init__", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 304, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.Enum.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum___init__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self), __pyx_v_name); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum___init__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v_name) { + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__init__", 1); + + /* "View.MemoryView":305 + * cdef object name + * def __init__(self, name): + * self.name = name # <<<<<<<<<<<<<< + * def __repr__(self): + * return self.name + */ + __Pyx_INCREF(__pyx_v_name); + __Pyx_GIVEREF(__pyx_v_name); + __Pyx_GOTREF(__pyx_v_self->name); + __Pyx_DECREF(__pyx_v_self->name); + __pyx_v_self->name = __pyx_v_name; + + /* "View.MemoryView":304 + * cdef class Enum(object): + * cdef object name + * def __init__(self, name): # <<<<<<<<<<<<<< + * self.name = name + * def __repr__(self): + */ + + /* function exit code */ + __pyx_r = 0; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":306 + * def __init__(self, name): + * self.name = name + * def __repr__(self): # <<<<<<<<<<<<<< + * return self.name + * + */ + +/* Python wrapper */ +static PyObject *__pyx_MemviewEnum___repr__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_MemviewEnum___repr__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__repr__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum_2__repr__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum_2__repr__(struct __pyx_MemviewEnum_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__repr__", 1); + + /* "View.MemoryView":307 + * self.name = name + * def __repr__(self): + * return self.name # <<<<<<<<<<<<<< + * + * cdef generic = Enum("") + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->name); + __pyx_r = __pyx_v_self->name; + goto __pyx_L0; + + /* "View.MemoryView":306 + * def __init__(self, name): + * self.name = name + * def __repr__(self): # <<<<<<<<<<<<<< + * return self.name + * + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * cdef tuple state + * cdef object _dict + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_MemviewEnum_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_MemviewEnum_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_MemviewEnum___reduce_cython__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_MemviewEnum___reduce_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self) { + PyObject *__pyx_v_state = 0; + PyObject *__pyx_v__dict = 0; + int __pyx_v_use_setstate; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":5 + * cdef object _dict + * cdef bint use_setstate + * state = (self.name,) # <<<<<<<<<<<<<< + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: + */ + __pyx_t_1 = PyTuple_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v_self->name); + __Pyx_GIVEREF(__pyx_v_self->name); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v_self->name)) __PYX_ERR(0, 5, __pyx_L1_error); + __pyx_v_state = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "(tree fragment)":6 + * cdef bint use_setstate + * state = (self.name,) + * _dict = getattr(self, '__dict__', None) # <<<<<<<<<<<<<< + * if _dict is not None: + * state += (_dict,) + */ + __pyx_t_1 = __Pyx_GetAttr3(((PyObject *)__pyx_v_self), __pyx_n_s_dict, Py_None); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v__dict = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":7 + * state = (self.name,) + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: # <<<<<<<<<<<<<< + * state += (_dict,) + * use_setstate = True + */ + __pyx_t_2 = (__pyx_v__dict != Py_None); + if (__pyx_t_2) { + + /* "(tree fragment)":8 + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: + * state += (_dict,) # <<<<<<<<<<<<<< + * use_setstate = True + * else: + */ + __pyx_t_1 = PyTuple_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 8, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v__dict); + __Pyx_GIVEREF(__pyx_v__dict); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v__dict)) __PYX_ERR(0, 8, __pyx_L1_error); + __pyx_t_3 = PyNumber_InPlaceAdd(__pyx_v_state, __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 8, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF_SET(__pyx_v_state, ((PyObject*)__pyx_t_3)); + __pyx_t_3 = 0; + + /* "(tree fragment)":9 + * if _dict is not None: + * state += (_dict,) + * use_setstate = True # <<<<<<<<<<<<<< + * else: + * use_setstate = self.name is not None + */ + __pyx_v_use_setstate = 1; + + /* "(tree fragment)":7 + * state = (self.name,) + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: # <<<<<<<<<<<<<< + * state += (_dict,) + * use_setstate = True + */ + goto __pyx_L3; + } + + /* "(tree fragment)":11 + * use_setstate = True + * else: + * use_setstate = self.name is not None # <<<<<<<<<<<<<< + * if use_setstate: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + */ + /*else*/ { + __pyx_t_2 = (__pyx_v_self->name != Py_None); + __pyx_v_use_setstate = __pyx_t_2; + } + __pyx_L3:; + + /* "(tree fragment)":12 + * else: + * use_setstate = self.name is not None + * if use_setstate: # <<<<<<<<<<<<<< + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + * else: + */ + if (__pyx_v_use_setstate) { + + /* "(tree fragment)":13 + * use_setstate = self.name is not None + * if use_setstate: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state # <<<<<<<<<<<<<< + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_pyx_unpickle_Enum); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = PyTuple_New(3); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_GIVEREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, ((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self))))) __PYX_ERR(0, 13, __pyx_L1_error); + __Pyx_INCREF(__pyx_int_136983863); + __Pyx_GIVEREF(__pyx_int_136983863); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_int_136983863)) __PYX_ERR(0, 13, __pyx_L1_error); + __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(Py_None); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 2, Py_None)) __PYX_ERR(0, 13, __pyx_L1_error); + __pyx_t_4 = PyTuple_New(3); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_3)) __PYX_ERR(0, 13, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_t_1)) __PYX_ERR(0, 13, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_state); + __Pyx_GIVEREF(__pyx_v_state); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 2, __pyx_v_state)) __PYX_ERR(0, 13, __pyx_L1_error); + __pyx_t_3 = 0; + __pyx_t_1 = 0; + __pyx_r = __pyx_t_4; + __pyx_t_4 = 0; + goto __pyx_L0; + + /* "(tree fragment)":12 + * else: + * use_setstate = self.name is not None + * if use_setstate: # <<<<<<<<<<<<<< + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + * else: + */ + } + + /* "(tree fragment)":15 + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * __pyx_unpickle_Enum__set_state(self, __pyx_state) + */ + /*else*/ { + __Pyx_XDECREF(__pyx_r); + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_pyx_unpickle_Enum); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_1 = PyTuple_New(3); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_GIVEREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, ((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self))))) __PYX_ERR(0, 15, __pyx_L1_error); + __Pyx_INCREF(__pyx_int_136983863); + __Pyx_GIVEREF(__pyx_int_136983863); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_int_136983863)) __PYX_ERR(0, 15, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_state); + __Pyx_GIVEREF(__pyx_v_state); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_v_state)) __PYX_ERR(0, 15, __pyx_L1_error); + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_4); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_4)) __PYX_ERR(0, 15, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1)) __PYX_ERR(0, 15, __pyx_L1_error); + __pyx_t_4 = 0; + __pyx_t_1 = 0; + __pyx_r = __pyx_t_3; + __pyx_t_3 = 0; + goto __pyx_L0; + } + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * cdef tuple state + * cdef object _dict + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.Enum.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_state); + __Pyx_XDECREF(__pyx_v__dict); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":16 + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state(self, __pyx_state) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_MemviewEnum_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_MemviewEnum_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 16, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(0, 16, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 16, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.Enum.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_MemviewEnum_2__setstate_cython__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_MemviewEnum_2__setstate_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":17 + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + * def __setstate_cython__(self, __pyx_state): + * __pyx_unpickle_Enum__set_state(self, __pyx_state) # <<<<<<<<<<<<<< + */ + if (!(likely(PyTuple_CheckExact(__pyx_v___pyx_state))||((__pyx_v___pyx_state) == Py_None) || __Pyx_RaiseUnexpectedTypeError("tuple", __pyx_v___pyx_state))) __PYX_ERR(0, 17, __pyx_L1_error) + __pyx_t_1 = __pyx_unpickle_Enum__set_state(__pyx_v_self, ((PyObject*)__pyx_v___pyx_state)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 17, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":16 + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state(self, __pyx_state) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.Enum.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":349 + * cdef __Pyx_TypeInfo *typeinfo + * + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): # <<<<<<<<<<<<<< + * self.obj = obj + * self.flags = flags + */ + +/* Python wrapper */ +static int __pyx_memoryview___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_memoryview___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_obj = 0; + int __pyx_v_flags; + int __pyx_v_dtype_is_object; + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_obj,&__pyx_n_s_flags,&__pyx_n_s_dtype_is_object,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_obj)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 349, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_flags)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 349, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 2, 3, 1); __PYX_ERR(0, 349, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_dtype_is_object); + if (value) { values[2] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 349, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(0, 349, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_obj = values[0]; + __pyx_v_flags = __Pyx_PyInt_As_int(values[1]); if (unlikely((__pyx_v_flags == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 349, __pyx_L3_error) + if (values[2]) { + __pyx_v_dtype_is_object = __Pyx_PyObject_IsTrue(values[2]); if (unlikely((__pyx_v_dtype_is_object == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 349, __pyx_L3_error) + } else { + __pyx_v_dtype_is_object = ((int)0); + } + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 2, 3, __pyx_nargs); __PYX_ERR(0, 349, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.memoryview.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview___cinit__(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v_obj, __pyx_v_flags, __pyx_v_dtype_is_object); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview___cinit__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj, int __pyx_v_flags, int __pyx_v_dtype_is_object) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + Py_intptr_t __pyx_t_4; + size_t __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__cinit__", 1); + + /* "View.MemoryView":350 + * + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): + * self.obj = obj # <<<<<<<<<<<<<< + * self.flags = flags + * if type(self) is memoryview or obj is not None: + */ + __Pyx_INCREF(__pyx_v_obj); + __Pyx_GIVEREF(__pyx_v_obj); + __Pyx_GOTREF(__pyx_v_self->obj); + __Pyx_DECREF(__pyx_v_self->obj); + __pyx_v_self->obj = __pyx_v_obj; + + /* "View.MemoryView":351 + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): + * self.obj = obj + * self.flags = flags # <<<<<<<<<<<<<< + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) + */ + __pyx_v_self->flags = __pyx_v_flags; + + /* "View.MemoryView":352 + * self.obj = obj + * self.flags = flags + * if type(self) is memoryview or obj is not None: # <<<<<<<<<<<<<< + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: + */ + __pyx_t_2 = (((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self))) == ((PyObject *)__pyx_memoryview_type)); + if (!__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_2 = (__pyx_v_obj != Py_None); + __pyx_t_1 = __pyx_t_2; + __pyx_L4_bool_binop_done:; + if (__pyx_t_1) { + + /* "View.MemoryView":353 + * self.flags = flags + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) # <<<<<<<<<<<<<< + * if self.view.obj == NULL: + * (<__pyx_buffer *> &self.view).obj = Py_None + */ + __pyx_t_3 = __Pyx_GetBuffer(__pyx_v_obj, (&__pyx_v_self->view), __pyx_v_flags); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(0, 353, __pyx_L1_error) + + /* "View.MemoryView":354 + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: # <<<<<<<<<<<<<< + * (<__pyx_buffer *> &self.view).obj = Py_None + * Py_INCREF(Py_None) + */ + __pyx_t_1 = (((PyObject *)__pyx_v_self->view.obj) == NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":355 + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: + * (<__pyx_buffer *> &self.view).obj = Py_None # <<<<<<<<<<<<<< + * Py_INCREF(Py_None) + * + */ + ((Py_buffer *)(&__pyx_v_self->view))->obj = Py_None; + + /* "View.MemoryView":356 + * if self.view.obj == NULL: + * (<__pyx_buffer *> &self.view).obj = Py_None + * Py_INCREF(Py_None) # <<<<<<<<<<<<<< + * + * if not __PYX_CYTHON_ATOMICS_ENABLED(): + */ + Py_INCREF(Py_None); + + /* "View.MemoryView":354 + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: # <<<<<<<<<<<<<< + * (<__pyx_buffer *> &self.view).obj = Py_None + * Py_INCREF(Py_None) + */ + } + + /* "View.MemoryView":352 + * self.obj = obj + * self.flags = flags + * if type(self) is memoryview or obj is not None: # <<<<<<<<<<<<<< + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: + */ + } + + /* "View.MemoryView":358 + * Py_INCREF(Py_None) + * + * if not __PYX_CYTHON_ATOMICS_ENABLED(): # <<<<<<<<<<<<<< + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: + */ + __pyx_t_1 = (!__PYX_CYTHON_ATOMICS_ENABLED()); + if (__pyx_t_1) { + + /* "View.MemoryView":360 + * if not __PYX_CYTHON_ATOMICS_ENABLED(): + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: # <<<<<<<<<<<<<< + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + */ + __pyx_t_1 = (__pyx_memoryview_thread_locks_used < 8); + if (__pyx_t_1) { + + /* "View.MemoryView":361 + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: + */ + __pyx_v_self->lock = (__pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used]); + + /* "View.MemoryView":362 + * if __pyx_memoryview_thread_locks_used < 8: + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 # <<<<<<<<<<<<<< + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() + */ + __pyx_memoryview_thread_locks_used = (__pyx_memoryview_thread_locks_used + 1); + + /* "View.MemoryView":360 + * if not __PYX_CYTHON_ATOMICS_ENABLED(): + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: # <<<<<<<<<<<<<< + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + */ + } + + /* "View.MemoryView":363 + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: # <<<<<<<<<<<<<< + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: + */ + __pyx_t_1 = (__pyx_v_self->lock == NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":364 + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() # <<<<<<<<<<<<<< + * if self.lock is NULL: + * raise MemoryError + */ + __pyx_v_self->lock = PyThread_allocate_lock(); + + /* "View.MemoryView":365 + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + __pyx_t_1 = (__pyx_v_self->lock == NULL); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":366 + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: + * raise MemoryError # <<<<<<<<<<<<<< + * + * if flags & PyBUF_FORMAT: + */ + PyErr_NoMemory(); __PYX_ERR(0, 366, __pyx_L1_error) + + /* "View.MemoryView":365 + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + } + + /* "View.MemoryView":363 + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: # <<<<<<<<<<<<<< + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: + */ + } + + /* "View.MemoryView":358 + * Py_INCREF(Py_None) + * + * if not __PYX_CYTHON_ATOMICS_ENABLED(): # <<<<<<<<<<<<<< + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: + */ + } + + /* "View.MemoryView":368 + * raise MemoryError + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_FORMAT) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":369 + * + * if flags & PyBUF_FORMAT: + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') # <<<<<<<<<<<<<< + * else: + * self.dtype_is_object = dtype_is_object + */ + __pyx_t_2 = ((__pyx_v_self->view.format[0]) == 'O'); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L12_bool_binop_done; + } + __pyx_t_2 = ((__pyx_v_self->view.format[1]) == '\x00'); + __pyx_t_1 = __pyx_t_2; + __pyx_L12_bool_binop_done:; + __pyx_v_self->dtype_is_object = __pyx_t_1; + + /* "View.MemoryView":368 + * raise MemoryError + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') + * else: + */ + goto __pyx_L11; + } + + /* "View.MemoryView":371 + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') + * else: + * self.dtype_is_object = dtype_is_object # <<<<<<<<<<<<<< + * + * assert (&self.acquisition_count) % sizeof(__pyx_atomic_int_type) == 0 + */ + /*else*/ { + __pyx_v_self->dtype_is_object = __pyx_v_dtype_is_object; + } + __pyx_L11:; + + /* "View.MemoryView":373 + * self.dtype_is_object = dtype_is_object + * + * assert (&self.acquisition_count) % sizeof(__pyx_atomic_int_type) == 0 # <<<<<<<<<<<<<< + * self.typeinfo = NULL + * + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_4 = ((Py_intptr_t)((void *)(&__pyx_v_self->acquisition_count))); + __pyx_t_5 = (sizeof(__pyx_atomic_int_type)); + if (unlikely(__pyx_t_5 == 0)) { + PyErr_SetString(PyExc_ZeroDivisionError, "integer division or modulo by zero"); + __PYX_ERR(0, 373, __pyx_L1_error) + } + __pyx_t_1 = ((__pyx_t_4 % __pyx_t_5) == 0); + if (unlikely(!__pyx_t_1)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(0, 373, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(0, 373, __pyx_L1_error) + #endif + + /* "View.MemoryView":374 + * + * assert (&self.acquisition_count) % sizeof(__pyx_atomic_int_type) == 0 + * self.typeinfo = NULL # <<<<<<<<<<<<<< + * + * def __dealloc__(memoryview self): + */ + __pyx_v_self->typeinfo = NULL; + + /* "View.MemoryView":349 + * cdef __Pyx_TypeInfo *typeinfo + * + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): # <<<<<<<<<<<<<< + * self.obj = obj + * self.flags = flags + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":376 + * self.typeinfo = NULL + * + * def __dealloc__(memoryview self): # <<<<<<<<<<<<<< + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + */ + +/* Python wrapper */ +static void __pyx_memoryview___dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_memoryview___dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_2__dealloc__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_2__dealloc__(struct __pyx_memoryview_obj *__pyx_v_self) { + int __pyx_v_i; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + PyThread_type_lock __pyx_t_5; + PyThread_type_lock __pyx_t_6; + + /* "View.MemoryView":377 + * + * def __dealloc__(memoryview self): + * if self.obj is not None: # <<<<<<<<<<<<<< + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + */ + __pyx_t_1 = (__pyx_v_self->obj != Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":378 + * def __dealloc__(memoryview self): + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) # <<<<<<<<<<<<<< + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + * + */ + __Pyx_ReleaseBuffer((&__pyx_v_self->view)); + + /* "View.MemoryView":377 + * + * def __dealloc__(memoryview self): + * if self.obj is not None: # <<<<<<<<<<<<<< + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":379 + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: # <<<<<<<<<<<<<< + * + * (<__pyx_buffer *> &self.view).obj = NULL + */ + __pyx_t_1 = (((Py_buffer *)(&__pyx_v_self->view))->obj == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":381 + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + * + * (<__pyx_buffer *> &self.view).obj = NULL # <<<<<<<<<<<<<< + * Py_DECREF(Py_None) + * + */ + ((Py_buffer *)(&__pyx_v_self->view))->obj = NULL; + + /* "View.MemoryView":382 + * + * (<__pyx_buffer *> &self.view).obj = NULL + * Py_DECREF(Py_None) # <<<<<<<<<<<<<< + * + * cdef int i + */ + Py_DECREF(Py_None); + + /* "View.MemoryView":379 + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: # <<<<<<<<<<<<<< + * + * (<__pyx_buffer *> &self.view).obj = NULL + */ + } + __pyx_L3:; + + /* "View.MemoryView":386 + * cdef int i + * global __pyx_memoryview_thread_locks_used + * if self.lock != NULL: # <<<<<<<<<<<<<< + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: + */ + __pyx_t_1 = (__pyx_v_self->lock != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":387 + * global __pyx_memoryview_thread_locks_used + * if self.lock != NULL: + * for i in range(__pyx_memoryview_thread_locks_used): # <<<<<<<<<<<<<< + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 + */ + __pyx_t_2 = __pyx_memoryview_thread_locks_used; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":388 + * if self.lock != NULL: + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: + */ + __pyx_t_1 = ((__pyx_memoryview_thread_locks[__pyx_v_i]) == __pyx_v_self->lock); + if (__pyx_t_1) { + + /* "View.MemoryView":389 + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 # <<<<<<<<<<<<<< + * if i != __pyx_memoryview_thread_locks_used: + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + */ + __pyx_memoryview_thread_locks_used = (__pyx_memoryview_thread_locks_used - 1); + + /* "View.MemoryView":390 + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + */ + __pyx_t_1 = (__pyx_v_i != __pyx_memoryview_thread_locks_used); + if (__pyx_t_1) { + + /* "View.MemoryView":392 + * if i != __pyx_memoryview_thread_locks_used: + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) # <<<<<<<<<<<<<< + * break + * else: + */ + __pyx_t_5 = (__pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used]); + __pyx_t_6 = (__pyx_memoryview_thread_locks[__pyx_v_i]); + + /* "View.MemoryView":391 + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + * break + */ + (__pyx_memoryview_thread_locks[__pyx_v_i]) = __pyx_t_5; + (__pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used]) = __pyx_t_6; + + /* "View.MemoryView":390 + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + */ + } + + /* "View.MemoryView":393 + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + * break # <<<<<<<<<<<<<< + * else: + * PyThread_free_lock(self.lock) + */ + goto __pyx_L6_break; + + /* "View.MemoryView":388 + * if self.lock != NULL: + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: + */ + } + } + /*else*/ { + + /* "View.MemoryView":395 + * break + * else: + * PyThread_free_lock(self.lock) # <<<<<<<<<<<<<< + * + * cdef char *get_item_pointer(memoryview self, object index) except NULL: + */ + PyThread_free_lock(__pyx_v_self->lock); + } + __pyx_L6_break:; + + /* "View.MemoryView":386 + * cdef int i + * global __pyx_memoryview_thread_locks_used + * if self.lock != NULL: # <<<<<<<<<<<<<< + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: + */ + } + + /* "View.MemoryView":376 + * self.typeinfo = NULL + * + * def __dealloc__(memoryview self): # <<<<<<<<<<<<<< + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + */ + + /* function exit code */ +} + +/* "View.MemoryView":397 + * PyThread_free_lock(self.lock) + * + * cdef char *get_item_pointer(memoryview self, object index) except NULL: # <<<<<<<<<<<<<< + * cdef Py_ssize_t dim + * cdef char *itemp = self.view.buf + */ + +static char *__pyx_memoryview_get_item_pointer(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index) { + Py_ssize_t __pyx_v_dim; + char *__pyx_v_itemp; + PyObject *__pyx_v_idx = NULL; + char *__pyx_r; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + Py_ssize_t __pyx_t_3; + PyObject *(*__pyx_t_4)(PyObject *); + PyObject *__pyx_t_5 = NULL; + Py_ssize_t __pyx_t_6; + char *__pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_item_pointer", 1); + + /* "View.MemoryView":399 + * cdef char *get_item_pointer(memoryview self, object index) except NULL: + * cdef Py_ssize_t dim + * cdef char *itemp = self.view.buf # <<<<<<<<<<<<<< + * + * for dim, idx in enumerate(index): + */ + __pyx_v_itemp = ((char *)__pyx_v_self->view.buf); + + /* "View.MemoryView":401 + * cdef char *itemp = self.view.buf + * + * for dim, idx in enumerate(index): # <<<<<<<<<<<<<< + * itemp = pybuffer_index(&self.view, itemp, idx, dim) + * + */ + __pyx_t_1 = 0; + if (likely(PyList_CheckExact(__pyx_v_index)) || PyTuple_CheckExact(__pyx_v_index)) { + __pyx_t_2 = __pyx_v_index; __Pyx_INCREF(__pyx_t_2); + __pyx_t_3 = 0; + __pyx_t_4 = NULL; + } else { + __pyx_t_3 = -1; __pyx_t_2 = PyObject_GetIter(__pyx_v_index); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 401, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_2); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 401, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_4)) { + if (likely(PyList_CheckExact(__pyx_t_2))) { + { + Py_ssize_t __pyx_temp = __Pyx_PyList_GET_SIZE(__pyx_t_2); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 401, __pyx_L1_error) + #endif + if (__pyx_t_3 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_5 = PyList_GET_ITEM(__pyx_t_2, __pyx_t_3); __Pyx_INCREF(__pyx_t_5); __pyx_t_3++; if (unlikely((0 < 0))) __PYX_ERR(0, 401, __pyx_L1_error) + #else + __pyx_t_5 = __Pyx_PySequence_ITEM(__pyx_t_2, __pyx_t_3); __pyx_t_3++; if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 401, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + #endif + } else { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_2); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 401, __pyx_L1_error) + #endif + if (__pyx_t_3 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_5 = PyTuple_GET_ITEM(__pyx_t_2, __pyx_t_3); __Pyx_INCREF(__pyx_t_5); __pyx_t_3++; if (unlikely((0 < 0))) __PYX_ERR(0, 401, __pyx_L1_error) + #else + __pyx_t_5 = __Pyx_PySequence_ITEM(__pyx_t_2, __pyx_t_3); __pyx_t_3++; if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 401, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + #endif + } + } else { + __pyx_t_5 = __pyx_t_4(__pyx_t_2); + if (unlikely(!__pyx_t_5)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(0, 401, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_5); + } + __Pyx_XDECREF_SET(__pyx_v_idx, __pyx_t_5); + __pyx_t_5 = 0; + __pyx_v_dim = __pyx_t_1; + __pyx_t_1 = (__pyx_t_1 + 1); + + /* "View.MemoryView":402 + * + * for dim, idx in enumerate(index): + * itemp = pybuffer_index(&self.view, itemp, idx, dim) # <<<<<<<<<<<<<< + * + * return itemp + */ + __pyx_t_6 = __Pyx_PyIndex_AsSsize_t(__pyx_v_idx); if (unlikely((__pyx_t_6 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 402, __pyx_L1_error) + __pyx_t_7 = __pyx_pybuffer_index((&__pyx_v_self->view), __pyx_v_itemp, __pyx_t_6, __pyx_v_dim); if (unlikely(__pyx_t_7 == ((char *)NULL))) __PYX_ERR(0, 402, __pyx_L1_error) + __pyx_v_itemp = __pyx_t_7; + + /* "View.MemoryView":401 + * cdef char *itemp = self.view.buf + * + * for dim, idx in enumerate(index): # <<<<<<<<<<<<<< + * itemp = pybuffer_index(&self.view, itemp, idx, dim) + * + */ + } + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":404 + * itemp = pybuffer_index(&self.view, itemp, idx, dim) + * + * return itemp # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = __pyx_v_itemp; + goto __pyx_L0; + + /* "View.MemoryView":397 + * PyThread_free_lock(self.lock) + * + * cdef char *get_item_pointer(memoryview self, object index) except NULL: # <<<<<<<<<<<<<< + * cdef Py_ssize_t dim + * cdef char *itemp = self.view.buf + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.memoryview.get_item_pointer", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_idx); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":407 + * + * + * def __getitem__(memoryview self, object index): # <<<<<<<<<<<<<< + * if index is Ellipsis: + * return self + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index); /*proto*/ +static PyObject *__pyx_memoryview___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getitem__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_4__getitem__(((struct __pyx_memoryview_obj *)__pyx_v_self), ((PyObject *)__pyx_v_index)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_4__getitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index) { + PyObject *__pyx_v_have_slices = NULL; + PyObject *__pyx_v_indices = NULL; + char *__pyx_v_itemp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + char *__pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__getitem__", 1); + + /* "View.MemoryView":408 + * + * def __getitem__(memoryview self, object index): + * if index is Ellipsis: # <<<<<<<<<<<<<< + * return self + * + */ + __pyx_t_1 = (__pyx_v_index == __pyx_builtin_Ellipsis); + if (__pyx_t_1) { + + /* "View.MemoryView":409 + * def __getitem__(memoryview self, object index): + * if index is Ellipsis: + * return self # <<<<<<<<<<<<<< + * + * have_slices, indices = _unellipsify(index, self.view.ndim) + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_self); + __pyx_r = ((PyObject *)__pyx_v_self); + goto __pyx_L0; + + /* "View.MemoryView":408 + * + * def __getitem__(memoryview self, object index): + * if index is Ellipsis: # <<<<<<<<<<<<<< + * return self + * + */ + } + + /* "View.MemoryView":411 + * return self + * + * have_slices, indices = _unellipsify(index, self.view.ndim) # <<<<<<<<<<<<<< + * + * cdef char *itemp + */ + __pyx_t_2 = _unellipsify(__pyx_v_index, __pyx_v_self->view.ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 411, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (likely(__pyx_t_2 != Py_None)) { + PyObject* sequence = __pyx_t_2; + Py_ssize_t size = __Pyx_PySequence_SIZE(sequence); + if (unlikely(size != 2)) { + if (size > 2) __Pyx_RaiseTooManyValuesError(2); + else if (size >= 0) __Pyx_RaiseNeedMoreValuesError(size); + __PYX_ERR(0, 411, __pyx_L1_error) + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_3 = PyTuple_GET_ITEM(sequence, 0); + __pyx_t_4 = PyTuple_GET_ITEM(sequence, 1); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(__pyx_t_4); + #else + __pyx_t_3 = PySequence_ITEM(sequence, 0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 411, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PySequence_ITEM(sequence, 1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 411, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } else { + __Pyx_RaiseNoneNotIterableError(); __PYX_ERR(0, 411, __pyx_L1_error) + } + __pyx_v_have_slices = __pyx_t_3; + __pyx_t_3 = 0; + __pyx_v_indices = __pyx_t_4; + __pyx_t_4 = 0; + + /* "View.MemoryView":414 + * + * cdef char *itemp + * if have_slices: # <<<<<<<<<<<<<< + * return memview_slice(self, indices) + * else: + */ + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_v_have_slices); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(0, 414, __pyx_L1_error) + if (__pyx_t_1) { + + /* "View.MemoryView":415 + * cdef char *itemp + * if have_slices: + * return memview_slice(self, indices) # <<<<<<<<<<<<<< + * else: + * itemp = self.get_item_pointer(indices) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = ((PyObject *)__pyx_memview_slice(__pyx_v_self, __pyx_v_indices)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 415, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":414 + * + * cdef char *itemp + * if have_slices: # <<<<<<<<<<<<<< + * return memview_slice(self, indices) + * else: + */ + } + + /* "View.MemoryView":417 + * return memview_slice(self, indices) + * else: + * itemp = self.get_item_pointer(indices) # <<<<<<<<<<<<<< + * return self.convert_item_to_object(itemp) + * + */ + /*else*/ { + __pyx_t_5 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->get_item_pointer(__pyx_v_self, __pyx_v_indices); if (unlikely(__pyx_t_5 == ((char *)NULL))) __PYX_ERR(0, 417, __pyx_L1_error) + __pyx_v_itemp = __pyx_t_5; + + /* "View.MemoryView":418 + * else: + * itemp = self.get_item_pointer(indices) + * return self.convert_item_to_object(itemp) # <<<<<<<<<<<<<< + * + * def __setitem__(memoryview self, object index, object value): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->convert_item_to_object(__pyx_v_self, __pyx_v_itemp); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 418, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + } + + /* "View.MemoryView":407 + * + * + * def __getitem__(memoryview self, object index): # <<<<<<<<<<<<<< + * if index is Ellipsis: + * return self + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.memoryview.__getitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_have_slices); + __Pyx_XDECREF(__pyx_v_indices); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":420 + * return self.convert_item_to_object(itemp) + * + * def __setitem__(memoryview self, object index, object value): # <<<<<<<<<<<<<< + * if self.view.readonly: + * raise TypeError, "Cannot assign to read-only memoryview" + */ + +/* Python wrapper */ +static int __pyx_memoryview___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value); /*proto*/ +static int __pyx_memoryview___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setitem__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_6__setitem__(((struct __pyx_memoryview_obj *)__pyx_v_self), ((PyObject *)__pyx_v_index), ((PyObject *)__pyx_v_value)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_6__setitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value) { + PyObject *__pyx_v_have_slices = NULL; + PyObject *__pyx_v_obj = NULL; + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setitem__", 0); + __Pyx_INCREF(__pyx_v_index); + + /* "View.MemoryView":421 + * + * def __setitem__(memoryview self, object index, object value): + * if self.view.readonly: # <<<<<<<<<<<<<< + * raise TypeError, "Cannot assign to read-only memoryview" + * + */ + if (unlikely(__pyx_v_self->view.readonly)) { + + /* "View.MemoryView":422 + * def __setitem__(memoryview self, object index, object value): + * if self.view.readonly: + * raise TypeError, "Cannot assign to read-only memoryview" # <<<<<<<<<<<<<< + * + * have_slices, index = _unellipsify(index, self.view.ndim) + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_Cannot_assign_to_read_only_memor, 0, 0); + __PYX_ERR(0, 422, __pyx_L1_error) + + /* "View.MemoryView":421 + * + * def __setitem__(memoryview self, object index, object value): + * if self.view.readonly: # <<<<<<<<<<<<<< + * raise TypeError, "Cannot assign to read-only memoryview" + * + */ + } + + /* "View.MemoryView":424 + * raise TypeError, "Cannot assign to read-only memoryview" + * + * have_slices, index = _unellipsify(index, self.view.ndim) # <<<<<<<<<<<<<< + * + * if have_slices: + */ + __pyx_t_1 = _unellipsify(__pyx_v_index, __pyx_v_self->view.ndim); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 424, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (likely(__pyx_t_1 != Py_None)) { + PyObject* sequence = __pyx_t_1; + Py_ssize_t size = __Pyx_PySequence_SIZE(sequence); + if (unlikely(size != 2)) { + if (size > 2) __Pyx_RaiseTooManyValuesError(2); + else if (size >= 0) __Pyx_RaiseNeedMoreValuesError(size); + __PYX_ERR(0, 424, __pyx_L1_error) + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_2 = PyTuple_GET_ITEM(sequence, 0); + __pyx_t_3 = PyTuple_GET_ITEM(sequence, 1); + __Pyx_INCREF(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + #else + __pyx_t_2 = PySequence_ITEM(sequence, 0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 424, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PySequence_ITEM(sequence, 1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 424, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + #endif + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } else { + __Pyx_RaiseNoneNotIterableError(); __PYX_ERR(0, 424, __pyx_L1_error) + } + __pyx_v_have_slices = __pyx_t_2; + __pyx_t_2 = 0; + __Pyx_DECREF_SET(__pyx_v_index, __pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":426 + * have_slices, index = _unellipsify(index, self.view.ndim) + * + * if have_slices: # <<<<<<<<<<<<<< + * obj = self.is_slice(value) + * if obj: + */ + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_v_have_slices); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 426, __pyx_L1_error) + if (__pyx_t_4) { + + /* "View.MemoryView":427 + * + * if have_slices: + * obj = self.is_slice(value) # <<<<<<<<<<<<<< + * if obj: + * self.setitem_slice_assignment(self[index], obj) + */ + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->is_slice(__pyx_v_self, __pyx_v_value); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 427, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_obj = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":428 + * if have_slices: + * obj = self.is_slice(value) + * if obj: # <<<<<<<<<<<<<< + * self.setitem_slice_assignment(self[index], obj) + * else: + */ + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_v_obj); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 428, __pyx_L1_error) + if (__pyx_t_4) { + + /* "View.MemoryView":429 + * obj = self.is_slice(value) + * if obj: + * self.setitem_slice_assignment(self[index], obj) # <<<<<<<<<<<<<< + * else: + * self.setitem_slice_assign_scalar(self[index], value) + */ + __pyx_t_1 = __Pyx_PyObject_GetItem(((PyObject *)__pyx_v_self), __pyx_v_index); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 429, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->setitem_slice_assignment(__pyx_v_self, __pyx_t_1, __pyx_v_obj); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 429, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "View.MemoryView":428 + * if have_slices: + * obj = self.is_slice(value) + * if obj: # <<<<<<<<<<<<<< + * self.setitem_slice_assignment(self[index], obj) + * else: + */ + goto __pyx_L5; + } + + /* "View.MemoryView":431 + * self.setitem_slice_assignment(self[index], obj) + * else: + * self.setitem_slice_assign_scalar(self[index], value) # <<<<<<<<<<<<<< + * else: + * self.setitem_indexed(index, value) + */ + /*else*/ { + __pyx_t_3 = __Pyx_PyObject_GetItem(((PyObject *)__pyx_v_self), __pyx_v_index); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 431, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (!(likely(((__pyx_t_3) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_3, __pyx_memoryview_type))))) __PYX_ERR(0, 431, __pyx_L1_error) + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->setitem_slice_assign_scalar(__pyx_v_self, ((struct __pyx_memoryview_obj *)__pyx_t_3), __pyx_v_value); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 431, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_L5:; + + /* "View.MemoryView":426 + * have_slices, index = _unellipsify(index, self.view.ndim) + * + * if have_slices: # <<<<<<<<<<<<<< + * obj = self.is_slice(value) + * if obj: + */ + goto __pyx_L4; + } + + /* "View.MemoryView":433 + * self.setitem_slice_assign_scalar(self[index], value) + * else: + * self.setitem_indexed(index, value) # <<<<<<<<<<<<<< + * + * cdef is_slice(self, obj): + */ + /*else*/ { + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->setitem_indexed(__pyx_v_self, __pyx_v_index, __pyx_v_value); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 433, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_L4:; + + /* "View.MemoryView":420 + * return self.convert_item_to_object(itemp) + * + * def __setitem__(memoryview self, object index, object value): # <<<<<<<<<<<<<< + * if self.view.readonly: + * raise TypeError, "Cannot assign to read-only memoryview" + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.__setitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_have_slices); + __Pyx_XDECREF(__pyx_v_obj); + __Pyx_XDECREF(__pyx_v_index); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":435 + * self.setitem_indexed(index, value) + * + * cdef is_slice(self, obj): # <<<<<<<<<<<<<< + * if not isinstance(obj, memoryview): + * try: + */ + +static PyObject *__pyx_memoryview_is_slice(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("is_slice", 0); + __Pyx_INCREF(__pyx_v_obj); + + /* "View.MemoryView":436 + * + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): # <<<<<<<<<<<<<< + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + */ + __pyx_t_1 = __Pyx_TypeCheck(__pyx_v_obj, __pyx_memoryview_type); + __pyx_t_2 = (!__pyx_t_1); + if (__pyx_t_2) { + + /* "View.MemoryView":437 + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): + * try: # <<<<<<<<<<<<<< + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_3, &__pyx_t_4, &__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_4); + __Pyx_XGOTREF(__pyx_t_5); + /*try:*/ { + + /* "View.MemoryView":438 + * if not isinstance(obj, memoryview): + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, # <<<<<<<<<<<<<< + * self.dtype_is_object) + * except TypeError: + */ + __pyx_t_6 = __Pyx_PyInt_From_int(((__pyx_v_self->flags & (~PyBUF_WRITABLE)) | PyBUF_ANY_CONTIGUOUS)); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 438, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_6); + + /* "View.MemoryView":439 + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) # <<<<<<<<<<<<<< + * except TypeError: + * return None + */ + __pyx_t_7 = __Pyx_PyBool_FromLong(__pyx_v_self->dtype_is_object); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 439, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_7); + + /* "View.MemoryView":438 + * if not isinstance(obj, memoryview): + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, # <<<<<<<<<<<<<< + * self.dtype_is_object) + * except TypeError: + */ + __pyx_t_8 = PyTuple_New(3); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 438, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_INCREF(__pyx_v_obj); + __Pyx_GIVEREF(__pyx_v_obj); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_8, 0, __pyx_v_obj)) __PYX_ERR(0, 438, __pyx_L4_error); + __Pyx_GIVEREF(__pyx_t_6); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_8, 1, __pyx_t_6)) __PYX_ERR(0, 438, __pyx_L4_error); + __Pyx_GIVEREF(__pyx_t_7); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_8, 2, __pyx_t_7)) __PYX_ERR(0, 438, __pyx_L4_error); + __pyx_t_6 = 0; + __pyx_t_7 = 0; + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_memoryview_type), __pyx_t_8, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 438, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_DECREF_SET(__pyx_v_obj, __pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":437 + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): + * try: # <<<<<<<<<<<<<< + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + */ + } + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + goto __pyx_L9_try_end; + __pyx_L4_error:; + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + + /* "View.MemoryView":440 + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + * except TypeError: # <<<<<<<<<<<<<< + * return None + * + */ + __pyx_t_9 = __Pyx_PyErr_ExceptionMatches(__pyx_builtin_TypeError); + if (__pyx_t_9) { + __Pyx_AddTraceback("View.MemoryView.memoryview.is_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_7, &__pyx_t_8, &__pyx_t_6) < 0) __PYX_ERR(0, 440, __pyx_L6_except_error) + __Pyx_XGOTREF(__pyx_t_7); + __Pyx_XGOTREF(__pyx_t_8); + __Pyx_XGOTREF(__pyx_t_6); + + /* "View.MemoryView":441 + * self.dtype_is_object) + * except TypeError: + * return None # <<<<<<<<<<<<<< + * + * return obj + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L7_except_return; + } + goto __pyx_L6_except_error; + + /* "View.MemoryView":437 + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): + * try: # <<<<<<<<<<<<<< + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + */ + __pyx_L6_except_error:; + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_XGIVEREF(__pyx_t_5); + __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_4, __pyx_t_5); + goto __pyx_L1_error; + __pyx_L7_except_return:; + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_XGIVEREF(__pyx_t_5); + __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_4, __pyx_t_5); + goto __pyx_L0; + __pyx_L9_try_end:; + } + + /* "View.MemoryView":436 + * + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): # <<<<<<<<<<<<<< + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + */ + } + + /* "View.MemoryView":443 + * return None + * + * return obj # <<<<<<<<<<<<<< + * + * cdef setitem_slice_assignment(self, dst, src): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_obj); + __pyx_r = __pyx_v_obj; + goto __pyx_L0; + + /* "View.MemoryView":435 + * self.setitem_indexed(index, value) + * + * cdef is_slice(self, obj): # <<<<<<<<<<<<<< + * if not isinstance(obj, memoryview): + * try: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("View.MemoryView.memoryview.is_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_obj); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":445 + * return obj + * + * cdef setitem_slice_assignment(self, dst, src): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice dst_slice + * cdef __Pyx_memviewslice src_slice + */ + +static PyObject *__pyx_memoryview_setitem_slice_assignment(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_dst, PyObject *__pyx_v_src) { + __Pyx_memviewslice __pyx_v_dst_slice; + __Pyx_memviewslice __pyx_v_src_slice; + __Pyx_memviewslice __pyx_v_msrc; + __Pyx_memviewslice __pyx_v_mdst; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_t_3; + int __pyx_t_4; + int __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("setitem_slice_assignment", 1); + + /* "View.MemoryView":448 + * cdef __Pyx_memviewslice dst_slice + * cdef __Pyx_memviewslice src_slice + * cdef __Pyx_memviewslice msrc = get_slice_from_memview(src, &src_slice)[0] # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice mdst = get_slice_from_memview(dst, &dst_slice)[0] + * + */ + if (!(likely(((__pyx_v_src) == Py_None) || likely(__Pyx_TypeTest(__pyx_v_src, __pyx_memoryview_type))))) __PYX_ERR(0, 448, __pyx_L1_error) + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(((struct __pyx_memoryview_obj *)__pyx_v_src), (&__pyx_v_src_slice)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(0, 448, __pyx_L1_error) + __pyx_v_msrc = (__pyx_t_1[0]); + + /* "View.MemoryView":449 + * cdef __Pyx_memviewslice src_slice + * cdef __Pyx_memviewslice msrc = get_slice_from_memview(src, &src_slice)[0] + * cdef __Pyx_memviewslice mdst = get_slice_from_memview(dst, &dst_slice)[0] # <<<<<<<<<<<<<< + * + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) + */ + if (!(likely(((__pyx_v_dst) == Py_None) || likely(__Pyx_TypeTest(__pyx_v_dst, __pyx_memoryview_type))))) __PYX_ERR(0, 449, __pyx_L1_error) + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(((struct __pyx_memoryview_obj *)__pyx_v_dst), (&__pyx_v_dst_slice)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(0, 449, __pyx_L1_error) + __pyx_v_mdst = (__pyx_t_1[0]); + + /* "View.MemoryView":451 + * cdef __Pyx_memviewslice mdst = get_slice_from_memview(dst, &dst_slice)[0] + * + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) # <<<<<<<<<<<<<< + * + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_src, __pyx_n_s_ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 451, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_PyInt_As_int(__pyx_t_2); if (unlikely((__pyx_t_3 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 451, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_dst, __pyx_n_s_ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 451, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __Pyx_PyInt_As_int(__pyx_t_2); if (unlikely((__pyx_t_4 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 451, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_5 = __pyx_memoryview_copy_contents(__pyx_v_msrc, __pyx_v_mdst, __pyx_t_3, __pyx_t_4, __pyx_v_self->dtype_is_object); if (unlikely(__pyx_t_5 == ((int)-1))) __PYX_ERR(0, 451, __pyx_L1_error) + + /* "View.MemoryView":445 + * return obj + * + * cdef setitem_slice_assignment(self, dst, src): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice dst_slice + * cdef __Pyx_memviewslice src_slice + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.setitem_slice_assignment", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":453 + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) + * + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): # <<<<<<<<<<<<<< + * cdef int array[128] + * cdef void *tmp = NULL + */ + +static PyObject *__pyx_memoryview_setitem_slice_assign_scalar(struct __pyx_memoryview_obj *__pyx_v_self, struct __pyx_memoryview_obj *__pyx_v_dst, PyObject *__pyx_v_value) { + int __pyx_v_array[0x80]; + void *__pyx_v_tmp; + void *__pyx_v_item; + __Pyx_memviewslice *__pyx_v_dst_slice; + __Pyx_memviewslice __pyx_v_tmp_slice; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_t_5; + char const *__pyx_t_6; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + PyObject *__pyx_t_9 = NULL; + PyObject *__pyx_t_10 = NULL; + PyObject *__pyx_t_11 = NULL; + PyObject *__pyx_t_12 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("setitem_slice_assign_scalar", 1); + + /* "View.MemoryView":455 + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): + * cdef int array[128] + * cdef void *tmp = NULL # <<<<<<<<<<<<<< + * cdef void *item + * + */ + __pyx_v_tmp = NULL; + + /* "View.MemoryView":460 + * cdef __Pyx_memviewslice *dst_slice + * cdef __Pyx_memviewslice tmp_slice + * dst_slice = get_slice_from_memview(dst, &tmp_slice) # <<<<<<<<<<<<<< + * + * if self.view.itemsize > sizeof(array): + */ + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(__pyx_v_dst, (&__pyx_v_tmp_slice)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(0, 460, __pyx_L1_error) + __pyx_v_dst_slice = __pyx_t_1; + + /* "View.MemoryView":462 + * dst_slice = get_slice_from_memview(dst, &tmp_slice) + * + * if self.view.itemsize > sizeof(array): # <<<<<<<<<<<<<< + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: + */ + __pyx_t_2 = (((size_t)__pyx_v_self->view.itemsize) > (sizeof(__pyx_v_array))); + if (__pyx_t_2) { + + /* "View.MemoryView":463 + * + * if self.view.itemsize > sizeof(array): + * tmp = PyMem_Malloc(self.view.itemsize) # <<<<<<<<<<<<<< + * if tmp == NULL: + * raise MemoryError + */ + __pyx_v_tmp = PyMem_Malloc(__pyx_v_self->view.itemsize); + + /* "View.MemoryView":464 + * if self.view.itemsize > sizeof(array): + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * item = tmp + */ + __pyx_t_2 = (__pyx_v_tmp == NULL); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":465 + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: + * raise MemoryError # <<<<<<<<<<<<<< + * item = tmp + * else: + */ + PyErr_NoMemory(); __PYX_ERR(0, 465, __pyx_L1_error) + + /* "View.MemoryView":464 + * if self.view.itemsize > sizeof(array): + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * item = tmp + */ + } + + /* "View.MemoryView":466 + * if tmp == NULL: + * raise MemoryError + * item = tmp # <<<<<<<<<<<<<< + * else: + * item = array + */ + __pyx_v_item = __pyx_v_tmp; + + /* "View.MemoryView":462 + * dst_slice = get_slice_from_memview(dst, &tmp_slice) + * + * if self.view.itemsize > sizeof(array): # <<<<<<<<<<<<<< + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":468 + * item = tmp + * else: + * item = array # <<<<<<<<<<<<<< + * + * try: + */ + /*else*/ { + __pyx_v_item = ((void *)__pyx_v_array); + } + __pyx_L3:; + + /* "View.MemoryView":470 + * item = array + * + * try: # <<<<<<<<<<<<<< + * if self.dtype_is_object: + * ( item)[0] = value + */ + /*try:*/ { + + /* "View.MemoryView":471 + * + * try: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * ( item)[0] = value + * else: + */ + if (__pyx_v_self->dtype_is_object) { + + /* "View.MemoryView":472 + * try: + * if self.dtype_is_object: + * ( item)[0] = value # <<<<<<<<<<<<<< + * else: + * self.assign_item_from_object( item, value) + */ + (((PyObject **)__pyx_v_item)[0]) = ((PyObject *)__pyx_v_value); + + /* "View.MemoryView":471 + * + * try: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * ( item)[0] = value + * else: + */ + goto __pyx_L8; + } + + /* "View.MemoryView":474 + * ( item)[0] = value + * else: + * self.assign_item_from_object( item, value) # <<<<<<<<<<<<<< + * + * + */ + /*else*/ { + __pyx_t_3 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->assign_item_from_object(__pyx_v_self, ((char *)__pyx_v_item), __pyx_v_value); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 474, __pyx_L6_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_L8:; + + /* "View.MemoryView":478 + * + * + * if self.view.suboffsets != NULL: # <<<<<<<<<<<<<< + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, + */ + __pyx_t_2 = (__pyx_v_self->view.suboffsets != NULL); + if (__pyx_t_2) { + + /* "View.MemoryView":479 + * + * if self.view.suboffsets != NULL: + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) # <<<<<<<<<<<<<< + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, + * item, self.dtype_is_object) + */ + __pyx_t_4 = assert_direct_dimensions(__pyx_v_self->view.suboffsets, __pyx_v_self->view.ndim); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(0, 479, __pyx_L6_error) + + /* "View.MemoryView":478 + * + * + * if self.view.suboffsets != NULL: # <<<<<<<<<<<<<< + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, + */ + } + + /* "View.MemoryView":480 + * if self.view.suboffsets != NULL: + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, # <<<<<<<<<<<<<< + * item, self.dtype_is_object) + * finally: + */ + __pyx_memoryview_slice_assign_scalar(__pyx_v_dst_slice, __pyx_v_dst->view.ndim, __pyx_v_self->view.itemsize, __pyx_v_item, __pyx_v_self->dtype_is_object); + } + + /* "View.MemoryView":483 + * item, self.dtype_is_object) + * finally: + * PyMem_Free(tmp) # <<<<<<<<<<<<<< + * + * cdef setitem_indexed(self, index, value): + */ + /*finally:*/ { + /*normal exit:*/{ + PyMem_Free(__pyx_v_tmp); + goto __pyx_L7; + } + __pyx_L6_error:; + /*exception exit:*/{ + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __pyx_t_7 = 0; __pyx_t_8 = 0; __pyx_t_9 = 0; __pyx_t_10 = 0; __pyx_t_11 = 0; __pyx_t_12 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (PY_MAJOR_VERSION >= 3) __Pyx_ExceptionSwap(&__pyx_t_10, &__pyx_t_11, &__pyx_t_12); + if ((PY_MAJOR_VERSION < 3) || unlikely(__Pyx_GetException(&__pyx_t_7, &__pyx_t_8, &__pyx_t_9) < 0)) __Pyx_ErrFetch(&__pyx_t_7, &__pyx_t_8, &__pyx_t_9); + __Pyx_XGOTREF(__pyx_t_7); + __Pyx_XGOTREF(__pyx_t_8); + __Pyx_XGOTREF(__pyx_t_9); + __Pyx_XGOTREF(__pyx_t_10); + __Pyx_XGOTREF(__pyx_t_11); + __Pyx_XGOTREF(__pyx_t_12); + __pyx_t_4 = __pyx_lineno; __pyx_t_5 = __pyx_clineno; __pyx_t_6 = __pyx_filename; + { + PyMem_Free(__pyx_v_tmp); + } + if (PY_MAJOR_VERSION >= 3) { + __Pyx_XGIVEREF(__pyx_t_10); + __Pyx_XGIVEREF(__pyx_t_11); + __Pyx_XGIVEREF(__pyx_t_12); + __Pyx_ExceptionReset(__pyx_t_10, __pyx_t_11, __pyx_t_12); + } + __Pyx_XGIVEREF(__pyx_t_7); + __Pyx_XGIVEREF(__pyx_t_8); + __Pyx_XGIVEREF(__pyx_t_9); + __Pyx_ErrRestore(__pyx_t_7, __pyx_t_8, __pyx_t_9); + __pyx_t_7 = 0; __pyx_t_8 = 0; __pyx_t_9 = 0; __pyx_t_10 = 0; __pyx_t_11 = 0; __pyx_t_12 = 0; + __pyx_lineno = __pyx_t_4; __pyx_clineno = __pyx_t_5; __pyx_filename = __pyx_t_6; + goto __pyx_L1_error; + } + __pyx_L7:; + } + + /* "View.MemoryView":453 + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) + * + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): # <<<<<<<<<<<<<< + * cdef int array[128] + * cdef void *tmp = NULL + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.setitem_slice_assign_scalar", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":485 + * PyMem_Free(tmp) + * + * cdef setitem_indexed(self, index, value): # <<<<<<<<<<<<<< + * cdef char *itemp = self.get_item_pointer(index) + * self.assign_item_from_object(itemp, value) + */ + +static PyObject *__pyx_memoryview_setitem_indexed(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value) { + char *__pyx_v_itemp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + char *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("setitem_indexed", 1); + + /* "View.MemoryView":486 + * + * cdef setitem_indexed(self, index, value): + * cdef char *itemp = self.get_item_pointer(index) # <<<<<<<<<<<<<< + * self.assign_item_from_object(itemp, value) + * + */ + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->get_item_pointer(__pyx_v_self, __pyx_v_index); if (unlikely(__pyx_t_1 == ((char *)NULL))) __PYX_ERR(0, 486, __pyx_L1_error) + __pyx_v_itemp = __pyx_t_1; + + /* "View.MemoryView":487 + * cdef setitem_indexed(self, index, value): + * cdef char *itemp = self.get_item_pointer(index) + * self.assign_item_from_object(itemp, value) # <<<<<<<<<<<<<< + * + * cdef convert_item_to_object(self, char *itemp): + */ + __pyx_t_2 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->assign_item_from_object(__pyx_v_self, __pyx_v_itemp, __pyx_v_value); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 487, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":485 + * PyMem_Free(tmp) + * + * cdef setitem_indexed(self, index, value): # <<<<<<<<<<<<<< + * cdef char *itemp = self.get_item_pointer(index) + * self.assign_item_from_object(itemp, value) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.setitem_indexed", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":489 + * self.assign_item_from_object(itemp, value) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + +static PyObject *__pyx_memoryview_convert_item_to_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp) { + PyObject *__pyx_v_struct = NULL; + PyObject *__pyx_v_bytesitem = 0; + PyObject *__pyx_v_result = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + int __pyx_t_8; + Py_ssize_t __pyx_t_9; + int __pyx_t_10; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("convert_item_to_object", 1); + + /* "View.MemoryView":492 + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + * import struct # <<<<<<<<<<<<<< + * cdef bytes bytesitem + * + */ + __pyx_t_1 = __Pyx_ImportDottedModule(__pyx_n_s_struct, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 492, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_struct = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":495 + * cdef bytes bytesitem + * + * bytesitem = itemp[:self.view.itemsize] # <<<<<<<<<<<<<< + * try: + * result = struct.unpack(self.view.format, bytesitem) + */ + __pyx_t_1 = __Pyx_PyBytes_FromStringAndSize(__pyx_v_itemp + 0, __pyx_v_self->view.itemsize - 0); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 495, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_bytesitem = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":496 + * + * bytesitem = itemp[:self.view.itemsize] + * try: # <<<<<<<<<<<<<< + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_2, &__pyx_t_3, &__pyx_t_4); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_4); + /*try:*/ { + + /* "View.MemoryView":497 + * bytesitem = itemp[:self.view.itemsize] + * try: + * result = struct.unpack(self.view.format, bytesitem) # <<<<<<<<<<<<<< + * except struct.error: + * raise ValueError, "Unable to convert item to object" + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_unpack); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 497, __pyx_L3_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = __Pyx_PyBytes_FromString(__pyx_v_self->view.format); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 497, __pyx_L3_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_7 = NULL; + __pyx_t_8 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_8 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_7, __pyx_t_6, __pyx_v_bytesitem}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_8, 2+__pyx_t_8); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 497, __pyx_L3_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + __pyx_v_result = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":496 + * + * bytesitem = itemp[:self.view.itemsize] + * try: # <<<<<<<<<<<<<< + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + */ + } + + /* "View.MemoryView":501 + * raise ValueError, "Unable to convert item to object" + * else: + * if len(self.view.format) == 1: # <<<<<<<<<<<<<< + * return result[0] + * return result + */ + /*else:*/ { + __pyx_t_9 = __Pyx_ssize_strlen(__pyx_v_self->view.format); if (unlikely(__pyx_t_9 == ((Py_ssize_t)-1))) __PYX_ERR(0, 501, __pyx_L5_except_error) + __pyx_t_10 = (__pyx_t_9 == 1); + if (__pyx_t_10) { + + /* "View.MemoryView":502 + * else: + * if len(self.view.format) == 1: + * return result[0] # <<<<<<<<<<<<<< + * return result + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_result, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 502, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L6_except_return; + + /* "View.MemoryView":501 + * raise ValueError, "Unable to convert item to object" + * else: + * if len(self.view.format) == 1: # <<<<<<<<<<<<<< + * return result[0] + * return result + */ + } + + /* "View.MemoryView":503 + * if len(self.view.format) == 1: + * return result[0] + * return result # <<<<<<<<<<<<<< + * + * cdef assign_item_from_object(self, char *itemp, object value): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_result); + __pyx_r = __pyx_v_result; + goto __pyx_L6_except_return; + } + __pyx_L3_error:; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":498 + * try: + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: # <<<<<<<<<<<<<< + * raise ValueError, "Unable to convert item to object" + * else: + */ + __Pyx_ErrFetch(&__pyx_t_1, &__pyx_t_5, &__pyx_t_6); + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_error); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 498, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_8 = __Pyx_PyErr_GivenExceptionMatches(__pyx_t_1, __pyx_t_7); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_ErrRestore(__pyx_t_1, __pyx_t_5, __pyx_t_6); + __pyx_t_1 = 0; __pyx_t_5 = 0; __pyx_t_6 = 0; + if (__pyx_t_8) { + __Pyx_AddTraceback("View.MemoryView.memoryview.convert_item_to_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_6, &__pyx_t_5, &__pyx_t_1) < 0) __PYX_ERR(0, 498, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_1); + + /* "View.MemoryView":499 + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + * raise ValueError, "Unable to convert item to object" # <<<<<<<<<<<<<< + * else: + * if len(self.view.format) == 1: + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Unable_to_convert_item_to_object, 0, 0); + __PYX_ERR(0, 499, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "View.MemoryView":496 + * + * bytesitem = itemp[:self.view.itemsize] + * try: # <<<<<<<<<<<<<< + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_ExceptionReset(__pyx_t_2, __pyx_t_3, __pyx_t_4); + goto __pyx_L1_error; + __pyx_L6_except_return:; + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_ExceptionReset(__pyx_t_2, __pyx_t_3, __pyx_t_4); + goto __pyx_L0; + } + + /* "View.MemoryView":489 + * self.assign_item_from_object(itemp, value) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("View.MemoryView.memoryview.convert_item_to_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_struct); + __Pyx_XDECREF(__pyx_v_bytesitem); + __Pyx_XDECREF(__pyx_v_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":505 + * return result + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + +static PyObject *__pyx_memoryview_assign_item_from_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value) { + PyObject *__pyx_v_struct = NULL; + char __pyx_v_c; + PyObject *__pyx_v_bytesvalue = 0; + Py_ssize_t __pyx_v_i; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + Py_ssize_t __pyx_t_7; + PyObject *__pyx_t_8 = NULL; + char *__pyx_t_9; + char *__pyx_t_10; + char *__pyx_t_11; + char *__pyx_t_12; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("assign_item_from_object", 1); + + /* "View.MemoryView":508 + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + * import struct # <<<<<<<<<<<<<< + * cdef char c + * cdef bytes bytesvalue + */ + __pyx_t_1 = __Pyx_ImportDottedModule(__pyx_n_s_struct, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 508, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_struct = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":513 + * cdef Py_ssize_t i + * + * if isinstance(value, tuple): # <<<<<<<<<<<<<< + * bytesvalue = struct.pack(self.view.format, *value) + * else: + */ + __pyx_t_2 = PyTuple_Check(__pyx_v_value); + if (__pyx_t_2) { + + /* "View.MemoryView":514 + * + * if isinstance(value, tuple): + * bytesvalue = struct.pack(self.view.format, *value) # <<<<<<<<<<<<<< + * else: + * bytesvalue = struct.pack(self.view.format, value) + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_pack); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyBytes_FromString(__pyx_v_self->view.format); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PyTuple_New(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_3)) __PYX_ERR(0, 514, __pyx_L1_error); + __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PySequence_Tuple(__pyx_v_value); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = PyNumber_Add(__pyx_t_4, __pyx_t_3); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PyObject_Call(__pyx_t_1, __pyx_t_5, NULL); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (!(likely(PyBytes_CheckExact(__pyx_t_3))||((__pyx_t_3) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_t_3))) __PYX_ERR(0, 514, __pyx_L1_error) + __pyx_v_bytesvalue = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":513 + * cdef Py_ssize_t i + * + * if isinstance(value, tuple): # <<<<<<<<<<<<<< + * bytesvalue = struct.pack(self.view.format, *value) + * else: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":516 + * bytesvalue = struct.pack(self.view.format, *value) + * else: + * bytesvalue = struct.pack(self.view.format, value) # <<<<<<<<<<<<<< + * + * for i, c in enumerate(bytesvalue): + */ + /*else*/ { + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_pack); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 516, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 = __Pyx_PyBytes_FromString(__pyx_v_self->view.format); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 516, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_4 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_4, __pyx_t_1, __pyx_v_value}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 516, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + if (!(likely(PyBytes_CheckExact(__pyx_t_3))||((__pyx_t_3) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_t_3))) __PYX_ERR(0, 516, __pyx_L1_error) + __pyx_v_bytesvalue = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; + } + __pyx_L3:; + + /* "View.MemoryView":518 + * bytesvalue = struct.pack(self.view.format, value) + * + * for i, c in enumerate(bytesvalue): # <<<<<<<<<<<<<< + * itemp[i] = c + * + */ + __pyx_t_7 = 0; + if (unlikely(__pyx_v_bytesvalue == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' is not iterable"); + __PYX_ERR(0, 518, __pyx_L1_error) + } + __Pyx_INCREF(__pyx_v_bytesvalue); + __pyx_t_8 = __pyx_v_bytesvalue; + __pyx_t_10 = PyBytes_AS_STRING(__pyx_t_8); + __pyx_t_11 = (__pyx_t_10 + PyBytes_GET_SIZE(__pyx_t_8)); + for (__pyx_t_12 = __pyx_t_10; __pyx_t_12 < __pyx_t_11; __pyx_t_12++) { + __pyx_t_9 = __pyx_t_12; + __pyx_v_c = (__pyx_t_9[0]); + + /* "View.MemoryView":519 + * + * for i, c in enumerate(bytesvalue): + * itemp[i] = c # <<<<<<<<<<<<<< + * + * @cname('getbuffer') + */ + __pyx_v_i = __pyx_t_7; + + /* "View.MemoryView":518 + * bytesvalue = struct.pack(self.view.format, value) + * + * for i, c in enumerate(bytesvalue): # <<<<<<<<<<<<<< + * itemp[i] = c + * + */ + __pyx_t_7 = (__pyx_t_7 + 1); + + /* "View.MemoryView":519 + * + * for i, c in enumerate(bytesvalue): + * itemp[i] = c # <<<<<<<<<<<<<< + * + * @cname('getbuffer') + */ + (__pyx_v_itemp[__pyx_v_i]) = __pyx_v_c; + } + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + + /* "View.MemoryView":505 + * return result + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("View.MemoryView.memoryview.assign_item_from_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_struct); + __Pyx_XDECREF(__pyx_v_bytesvalue); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":521 + * itemp[i] = c + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: + */ + +/* Python wrapper */ +CYTHON_UNUSED static int __pyx_memoryview_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +CYTHON_UNUSED static int __pyx_memoryview_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getbuffer__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_8__getbuffer__(((struct __pyx_memoryview_obj *)__pyx_v_self), ((Py_buffer *)__pyx_v_info), ((int)__pyx_v_flags)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_8__getbuffer__(struct __pyx_memoryview_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + Py_ssize_t *__pyx_t_3; + char *__pyx_t_4; + void *__pyx_t_5; + int __pyx_t_6; + Py_ssize_t __pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + if (unlikely(__pyx_v_info == NULL)) { + PyErr_SetString(PyExc_BufferError, "PyObject_GetBuffer: view==NULL argument is obsolete"); + return -1; + } + __Pyx_RefNannySetupContext("__getbuffer__", 0); + __pyx_v_info->obj = Py_None; __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(__pyx_v_info->obj); + + /* "View.MemoryView":523 + * @cname('getbuffer') + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: # <<<<<<<<<<<<<< + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + */ + __pyx_t_2 = ((__pyx_v_flags & PyBUF_WRITABLE) != 0); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_1 = __pyx_v_self->view.readonly; + __pyx_L4_bool_binop_done:; + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":524 + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: + * raise ValueError, "Cannot create writable memory view from read-only memoryview" # <<<<<<<<<<<<<< + * + * if flags & PyBUF_ND: + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Cannot_create_writable_memory_vi, 0, 0); + __PYX_ERR(0, 524, __pyx_L1_error) + + /* "View.MemoryView":523 + * @cname('getbuffer') + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: # <<<<<<<<<<<<<< + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + */ + } + + /* "View.MemoryView":526 + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + * if flags & PyBUF_ND: # <<<<<<<<<<<<<< + * info.shape = self.view.shape + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_ND) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":527 + * + * if flags & PyBUF_ND: + * info.shape = self.view.shape # <<<<<<<<<<<<<< + * else: + * info.shape = NULL + */ + __pyx_t_3 = __pyx_v_self->view.shape; + __pyx_v_info->shape = __pyx_t_3; + + /* "View.MemoryView":526 + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + * if flags & PyBUF_ND: # <<<<<<<<<<<<<< + * info.shape = self.view.shape + * else: + */ + goto __pyx_L6; + } + + /* "View.MemoryView":529 + * info.shape = self.view.shape + * else: + * info.shape = NULL # <<<<<<<<<<<<<< + * + * if flags & PyBUF_STRIDES: + */ + /*else*/ { + __pyx_v_info->shape = NULL; + } + __pyx_L6:; + + /* "View.MemoryView":531 + * info.shape = NULL + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.strides = self.view.strides + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_STRIDES) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":532 + * + * if flags & PyBUF_STRIDES: + * info.strides = self.view.strides # <<<<<<<<<<<<<< + * else: + * info.strides = NULL + */ + __pyx_t_3 = __pyx_v_self->view.strides; + __pyx_v_info->strides = __pyx_t_3; + + /* "View.MemoryView":531 + * info.shape = NULL + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.strides = self.view.strides + * else: + */ + goto __pyx_L7; + } + + /* "View.MemoryView":534 + * info.strides = self.view.strides + * else: + * info.strides = NULL # <<<<<<<<<<<<<< + * + * if flags & PyBUF_INDIRECT: + */ + /*else*/ { + __pyx_v_info->strides = NULL; + } + __pyx_L7:; + + /* "View.MemoryView":536 + * info.strides = NULL + * + * if flags & PyBUF_INDIRECT: # <<<<<<<<<<<<<< + * info.suboffsets = self.view.suboffsets + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_INDIRECT) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":537 + * + * if flags & PyBUF_INDIRECT: + * info.suboffsets = self.view.suboffsets # <<<<<<<<<<<<<< + * else: + * info.suboffsets = NULL + */ + __pyx_t_3 = __pyx_v_self->view.suboffsets; + __pyx_v_info->suboffsets = __pyx_t_3; + + /* "View.MemoryView":536 + * info.strides = NULL + * + * if flags & PyBUF_INDIRECT: # <<<<<<<<<<<<<< + * info.suboffsets = self.view.suboffsets + * else: + */ + goto __pyx_L8; + } + + /* "View.MemoryView":539 + * info.suboffsets = self.view.suboffsets + * else: + * info.suboffsets = NULL # <<<<<<<<<<<<<< + * + * if flags & PyBUF_FORMAT: + */ + /*else*/ { + __pyx_v_info->suboffsets = NULL; + } + __pyx_L8:; + + /* "View.MemoryView":541 + * info.suboffsets = NULL + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * info.format = self.view.format + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_FORMAT) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":542 + * + * if flags & PyBUF_FORMAT: + * info.format = self.view.format # <<<<<<<<<<<<<< + * else: + * info.format = NULL + */ + __pyx_t_4 = __pyx_v_self->view.format; + __pyx_v_info->format = __pyx_t_4; + + /* "View.MemoryView":541 + * info.suboffsets = NULL + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * info.format = self.view.format + * else: + */ + goto __pyx_L9; + } + + /* "View.MemoryView":544 + * info.format = self.view.format + * else: + * info.format = NULL # <<<<<<<<<<<<<< + * + * info.buf = self.view.buf + */ + /*else*/ { + __pyx_v_info->format = NULL; + } + __pyx_L9:; + + /* "View.MemoryView":546 + * info.format = NULL + * + * info.buf = self.view.buf # <<<<<<<<<<<<<< + * info.ndim = self.view.ndim + * info.itemsize = self.view.itemsize + */ + __pyx_t_5 = __pyx_v_self->view.buf; + __pyx_v_info->buf = __pyx_t_5; + + /* "View.MemoryView":547 + * + * info.buf = self.view.buf + * info.ndim = self.view.ndim # <<<<<<<<<<<<<< + * info.itemsize = self.view.itemsize + * info.len = self.view.len + */ + __pyx_t_6 = __pyx_v_self->view.ndim; + __pyx_v_info->ndim = __pyx_t_6; + + /* "View.MemoryView":548 + * info.buf = self.view.buf + * info.ndim = self.view.ndim + * info.itemsize = self.view.itemsize # <<<<<<<<<<<<<< + * info.len = self.view.len + * info.readonly = self.view.readonly + */ + __pyx_t_7 = __pyx_v_self->view.itemsize; + __pyx_v_info->itemsize = __pyx_t_7; + + /* "View.MemoryView":549 + * info.ndim = self.view.ndim + * info.itemsize = self.view.itemsize + * info.len = self.view.len # <<<<<<<<<<<<<< + * info.readonly = self.view.readonly + * info.obj = self + */ + __pyx_t_7 = __pyx_v_self->view.len; + __pyx_v_info->len = __pyx_t_7; + + /* "View.MemoryView":550 + * info.itemsize = self.view.itemsize + * info.len = self.view.len + * info.readonly = self.view.readonly # <<<<<<<<<<<<<< + * info.obj = self + * + */ + __pyx_t_1 = __pyx_v_self->view.readonly; + __pyx_v_info->readonly = __pyx_t_1; + + /* "View.MemoryView":551 + * info.len = self.view.len + * info.readonly = self.view.readonly + * info.obj = self # <<<<<<<<<<<<<< + * + * + */ + __Pyx_INCREF((PyObject *)__pyx_v_self); + __Pyx_GIVEREF((PyObject *)__pyx_v_self); + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); + __pyx_v_info->obj = ((PyObject *)__pyx_v_self); + + /* "View.MemoryView":521 + * itemp[i] = c + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__getbuffer__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + if (__pyx_v_info->obj != NULL) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + goto __pyx_L2; + __pyx_L0:; + if (__pyx_v_info->obj == Py_None) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + __pyx_L2:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":554 + * + * + * @property # <<<<<<<<<<<<<< + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_1T_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_1T_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_1T___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_1T___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + struct __pyx_memoryviewslice_obj *__pyx_v_result = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":556 + * @property + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) # <<<<<<<<<<<<<< + * transpose_memslice(&result.from_slice) + * return result + */ + __pyx_t_1 = __pyx_memoryview_copy_object(__pyx_v_self); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 556, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (!(likely(((__pyx_t_1) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_1, __pyx_memoryviewslice_type))))) __PYX_ERR(0, 556, __pyx_L1_error) + __pyx_v_result = ((struct __pyx_memoryviewslice_obj *)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":557 + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) + * transpose_memslice(&result.from_slice) # <<<<<<<<<<<<<< + * return result + * + */ + __pyx_t_2 = __pyx_memslice_transpose((&__pyx_v_result->from_slice)); if (unlikely(__pyx_t_2 == ((int)-1))) __PYX_ERR(0, 557, __pyx_L1_error) + + /* "View.MemoryView":558 + * cdef _memoryviewslice result = memoryview_copy(self) + * transpose_memslice(&result.from_slice) + * return result # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = ((PyObject *)__pyx_v_result); + goto __pyx_L0; + + /* "View.MemoryView":554 + * + * + * @property # <<<<<<<<<<<<<< + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.T.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":560 + * return result + * + * @property # <<<<<<<<<<<<<< + * def base(self): + * return self._get_base() + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4base_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4base_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_4base___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4base___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":562 + * @property + * def base(self): + * return self._get_base() # <<<<<<<<<<<<<< + * + * cdef _get_base(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->_get_base(__pyx_v_self); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 562, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":560 + * return result + * + * @property # <<<<<<<<<<<<<< + * def base(self): + * return self._get_base() + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.base.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":564 + * return self._get_base() + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.obj + * + */ + +static PyObject *__pyx_memoryview__get_base(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("_get_base", 1); + + /* "View.MemoryView":565 + * + * cdef _get_base(self): + * return self.obj # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->obj); + __pyx_r = __pyx_v_self->obj; + goto __pyx_L0; + + /* "View.MemoryView":564 + * return self._get_base() + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.obj + * + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":567 + * return self.obj + * + * @property # <<<<<<<<<<<<<< + * def shape(self): + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_5shape_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_5shape_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_5shape___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_5shape___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_7genexpr__pyx_v_length; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + PyObject *__pyx_t_5 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":569 + * @property + * def shape(self): + * return tuple([length for length in self.view.shape[:self.view.ndim]]) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + { /* enter inner scope */ + __pyx_t_1 = PyList_New(0); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 569, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = (__pyx_v_self->view.shape + __pyx_v_self->view.ndim); + for (__pyx_t_4 = __pyx_v_self->view.shape; __pyx_t_4 < __pyx_t_3; __pyx_t_4++) { + __pyx_t_2 = __pyx_t_4; + __pyx_7genexpr__pyx_v_length = (__pyx_t_2[0]); + __pyx_t_5 = PyInt_FromSsize_t(__pyx_7genexpr__pyx_v_length); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 569, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_1, (PyObject*)__pyx_t_5))) __PYX_ERR(0, 569, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + } /* exit inner scope */ + __pyx_t_5 = PyList_AsTuple(((PyObject*)__pyx_t_1)); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 569, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_5; + __pyx_t_5 = 0; + goto __pyx_L0; + + /* "View.MemoryView":567 + * return self.obj + * + * @property # <<<<<<<<<<<<<< + * def shape(self): + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.memoryview.shape.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":571 + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def strides(self): + * if self.view.strides == NULL: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_7strides_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_7strides_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_7strides___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_7strides___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_8genexpr1__pyx_v_stride; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + Py_ssize_t *__pyx_t_5; + PyObject *__pyx_t_6 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":573 + * @property + * def strides(self): + * if self.view.strides == NULL: # <<<<<<<<<<<<<< + * + * raise ValueError, "Buffer view does not expose strides" + */ + __pyx_t_1 = (__pyx_v_self->view.strides == NULL); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":575 + * if self.view.strides == NULL: + * + * raise ValueError, "Buffer view does not expose strides" # <<<<<<<<<<<<<< + * + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Buffer_view_does_not_expose_stri, 0, 0); + __PYX_ERR(0, 575, __pyx_L1_error) + + /* "View.MemoryView":573 + * @property + * def strides(self): + * if self.view.strides == NULL: # <<<<<<<<<<<<<< + * + * raise ValueError, "Buffer view does not expose strides" + */ + } + + /* "View.MemoryView":577 + * raise ValueError, "Buffer view does not expose strides" + * + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + { /* enter inner scope */ + __pyx_t_2 = PyList_New(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 577, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = (__pyx_v_self->view.strides + __pyx_v_self->view.ndim); + for (__pyx_t_5 = __pyx_v_self->view.strides; __pyx_t_5 < __pyx_t_4; __pyx_t_5++) { + __pyx_t_3 = __pyx_t_5; + __pyx_8genexpr1__pyx_v_stride = (__pyx_t_3[0]); + __pyx_t_6 = PyInt_FromSsize_t(__pyx_8genexpr1__pyx_v_stride); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 577, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_2, (PyObject*)__pyx_t_6))) __PYX_ERR(0, 577, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + } /* exit inner scope */ + __pyx_t_6 = PyList_AsTuple(((PyObject*)__pyx_t_2)); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 577, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_6; + __pyx_t_6 = 0; + goto __pyx_L0; + + /* "View.MemoryView":571 + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def strides(self): + * if self.view.strides == NULL: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("View.MemoryView.memoryview.strides.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":579 + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def suboffsets(self): + * if self.view.suboffsets == NULL: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_10suboffsets_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_10suboffsets_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_10suboffsets___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_10suboffsets___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_8genexpr2__pyx_v_suboffset; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + Py_ssize_t *__pyx_t_5; + PyObject *__pyx_t_6 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":581 + * @property + * def suboffsets(self): + * if self.view.suboffsets == NULL: # <<<<<<<<<<<<<< + * return (-1,) * self.view.ndim + * + */ + __pyx_t_1 = (__pyx_v_self->view.suboffsets == NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":582 + * def suboffsets(self): + * if self.view.suboffsets == NULL: + * return (-1,) * self.view.ndim # <<<<<<<<<<<<<< + * + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PySequence_Multiply(__pyx_tuple__4, __pyx_v_self->view.ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 582, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":581 + * @property + * def suboffsets(self): + * if self.view.suboffsets == NULL: # <<<<<<<<<<<<<< + * return (-1,) * self.view.ndim + * + */ + } + + /* "View.MemoryView":584 + * return (-1,) * self.view.ndim + * + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + { /* enter inner scope */ + __pyx_t_2 = PyList_New(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 584, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = (__pyx_v_self->view.suboffsets + __pyx_v_self->view.ndim); + for (__pyx_t_5 = __pyx_v_self->view.suboffsets; __pyx_t_5 < __pyx_t_4; __pyx_t_5++) { + __pyx_t_3 = __pyx_t_5; + __pyx_8genexpr2__pyx_v_suboffset = (__pyx_t_3[0]); + __pyx_t_6 = PyInt_FromSsize_t(__pyx_8genexpr2__pyx_v_suboffset); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 584, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_2, (PyObject*)__pyx_t_6))) __PYX_ERR(0, 584, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + } /* exit inner scope */ + __pyx_t_6 = PyList_AsTuple(((PyObject*)__pyx_t_2)); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 584, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_6; + __pyx_t_6 = 0; + goto __pyx_L0; + + /* "View.MemoryView":579 + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def suboffsets(self): + * if self.view.suboffsets == NULL: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("View.MemoryView.memoryview.suboffsets.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":586 + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def ndim(self): + * return self.view.ndim + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4ndim_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4ndim_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_4ndim___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4ndim___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":588 + * @property + * def ndim(self): + * return self.view.ndim # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_self->view.ndim); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 588, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":586 + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def ndim(self): + * return self.view.ndim + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.ndim.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":590 + * return self.view.ndim + * + * @property # <<<<<<<<<<<<<< + * def itemsize(self): + * return self.view.itemsize + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_8itemsize_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_8itemsize_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_8itemsize___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_8itemsize___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":592 + * @property + * def itemsize(self): + * return self.view.itemsize # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyInt_FromSsize_t(__pyx_v_self->view.itemsize); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 592, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":590 + * return self.view.ndim + * + * @property # <<<<<<<<<<<<<< + * def itemsize(self): + * return self.view.itemsize + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.itemsize.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":594 + * return self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def nbytes(self): + * return self.size * self.view.itemsize + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_6nbytes_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_6nbytes_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_6nbytes___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_6nbytes___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":596 + * @property + * def nbytes(self): + * return self.size * self.view.itemsize # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_size); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 596, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = PyInt_FromSsize_t(__pyx_v_self->view.itemsize); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 596, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyNumber_Multiply(__pyx_t_1, __pyx_t_2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 596, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_3; + __pyx_t_3 = 0; + goto __pyx_L0; + + /* "View.MemoryView":594 + * return self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def nbytes(self): + * return self.size * self.view.itemsize + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.nbytes.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":598 + * return self.size * self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def size(self): + * if self._size is None: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4size_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4size_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_4size___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4size___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_v_result = NULL; + PyObject *__pyx_v_length = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + PyObject *__pyx_t_5 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":600 + * @property + * def size(self): + * if self._size is None: # <<<<<<<<<<<<<< + * result = 1 + * + */ + __pyx_t_1 = (__pyx_v_self->_size == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":601 + * def size(self): + * if self._size is None: + * result = 1 # <<<<<<<<<<<<<< + * + * for length in self.view.shape[:self.view.ndim]: + */ + __Pyx_INCREF(__pyx_int_1); + __pyx_v_result = __pyx_int_1; + + /* "View.MemoryView":603 + * result = 1 + * + * for length in self.view.shape[:self.view.ndim]: # <<<<<<<<<<<<<< + * result *= length + * + */ + __pyx_t_3 = (__pyx_v_self->view.shape + __pyx_v_self->view.ndim); + for (__pyx_t_4 = __pyx_v_self->view.shape; __pyx_t_4 < __pyx_t_3; __pyx_t_4++) { + __pyx_t_2 = __pyx_t_4; + __pyx_t_5 = PyInt_FromSsize_t((__pyx_t_2[0])); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 603, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_XDECREF_SET(__pyx_v_length, __pyx_t_5); + __pyx_t_5 = 0; + + /* "View.MemoryView":604 + * + * for length in self.view.shape[:self.view.ndim]: + * result *= length # <<<<<<<<<<<<<< + * + * self._size = result + */ + __pyx_t_5 = PyNumber_InPlaceMultiply(__pyx_v_result, __pyx_v_length); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 604, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF_SET(__pyx_v_result, __pyx_t_5); + __pyx_t_5 = 0; + } + + /* "View.MemoryView":606 + * result *= length + * + * self._size = result # <<<<<<<<<<<<<< + * + * return self._size + */ + __Pyx_INCREF(__pyx_v_result); + __Pyx_GIVEREF(__pyx_v_result); + __Pyx_GOTREF(__pyx_v_self->_size); + __Pyx_DECREF(__pyx_v_self->_size); + __pyx_v_self->_size = __pyx_v_result; + + /* "View.MemoryView":600 + * @property + * def size(self): + * if self._size is None: # <<<<<<<<<<<<<< + * result = 1 + * + */ + } + + /* "View.MemoryView":608 + * self._size = result + * + * return self._size # <<<<<<<<<<<<<< + * + * def __len__(self): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->_size); + __pyx_r = __pyx_v_self->_size; + goto __pyx_L0; + + /* "View.MemoryView":598 + * return self.size * self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def size(self): + * if self._size is None: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.memoryview.size.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_result); + __Pyx_XDECREF(__pyx_v_length); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":610 + * return self._size + * + * def __len__(self): # <<<<<<<<<<<<<< + * if self.view.ndim >= 1: + * return self.view.shape[0] + */ + +/* Python wrapper */ +static Py_ssize_t __pyx_memoryview___len__(PyObject *__pyx_v_self); /*proto*/ +static Py_ssize_t __pyx_memoryview___len__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + Py_ssize_t __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__len__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_10__len__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static Py_ssize_t __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_10__len__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_r; + int __pyx_t_1; + + /* "View.MemoryView":611 + * + * def __len__(self): + * if self.view.ndim >= 1: # <<<<<<<<<<<<<< + * return self.view.shape[0] + * + */ + __pyx_t_1 = (__pyx_v_self->view.ndim >= 1); + if (__pyx_t_1) { + + /* "View.MemoryView":612 + * def __len__(self): + * if self.view.ndim >= 1: + * return self.view.shape[0] # <<<<<<<<<<<<<< + * + * return 0 + */ + __pyx_r = (__pyx_v_self->view.shape[0]); + goto __pyx_L0; + + /* "View.MemoryView":611 + * + * def __len__(self): + * if self.view.ndim >= 1: # <<<<<<<<<<<<<< + * return self.view.shape[0] + * + */ + } + + /* "View.MemoryView":614 + * return self.view.shape[0] + * + * return 0 # <<<<<<<<<<<<<< + * + * def __repr__(self): + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":610 + * return self._size + * + * def __len__(self): # <<<<<<<<<<<<<< + * if self.view.ndim >= 1: + * return self.view.shape[0] + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":616 + * return 0 + * + * def __repr__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__, + * id(self)) + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview___repr__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_memoryview___repr__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__repr__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_12__repr__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_12__repr__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__repr__", 1); + + /* "View.MemoryView":617 + * + * def __repr__(self): + * return "" % (self.base.__class__.__name__, # <<<<<<<<<<<<<< + * id(self)) + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_base); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_class); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_name_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":618 + * def __repr__(self): + * return "" % (self.base.__class__.__name__, + * id(self)) # <<<<<<<<<<<<<< + * + * def __str__(self): + */ + __pyx_t_2 = __Pyx_PyObject_CallOneArg(__pyx_builtin_id, ((PyObject *)__pyx_v_self)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 618, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + + /* "View.MemoryView":617 + * + * def __repr__(self): + * return "" % (self.base.__class__.__name__, # <<<<<<<<<<<<<< + * id(self)) + * + */ + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_1)) __PYX_ERR(0, 617, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_2)) __PYX_ERR(0, 617, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyString_Format(__pyx_kp_s_MemoryView_of_r_at_0x_x, __pyx_t_3); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":616 + * return 0 + * + * def __repr__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__, + * id(self)) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.__repr__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":620 + * id(self)) + * + * def __str__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__,) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview___str__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_memoryview___str__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__str__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_14__str__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_14__str__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__str__", 1); + + /* "View.MemoryView":621 + * + * def __str__(self): + * return "" % (self.base.__class__.__name__,) # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_base); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_class); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_name_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = PyTuple_New(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_t_1)) __PYX_ERR(0, 621, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_MemoryView_of_r_object, __pyx_t_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":620 + * id(self)) + * + * def __str__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__,) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.__str__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":624 + * + * + * def is_c_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_is_c_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_is_c_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("is_c_contig (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("is_c_contig", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "is_c_contig", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_16is_c_contig(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_16is_c_contig(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice *__pyx_v_mslice; + __Pyx_memviewslice __pyx_v_tmp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("is_c_contig", 1); + + /* "View.MemoryView":627 + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) # <<<<<<<<<<<<<< + * return slice_is_contig(mslice[0], 'C', self.view.ndim) + * + */ + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(__pyx_v_self, (&__pyx_v_tmp)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(0, 627, __pyx_L1_error) + __pyx_v_mslice = __pyx_t_1; + + /* "View.MemoryView":628 + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) + * return slice_is_contig(mslice[0], 'C', self.view.ndim) # <<<<<<<<<<<<<< + * + * def is_f_contig(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_memviewslice_is_contig((__pyx_v_mslice[0]), 'C', __pyx_v_self->view.ndim)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 628, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":624 + * + * + * def is_c_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.is_c_contig", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":630 + * return slice_is_contig(mslice[0], 'C', self.view.ndim) + * + * def is_f_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_is_f_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_is_f_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("is_f_contig (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("is_f_contig", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "is_f_contig", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_18is_f_contig(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_18is_f_contig(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice *__pyx_v_mslice; + __Pyx_memviewslice __pyx_v_tmp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("is_f_contig", 1); + + /* "View.MemoryView":633 + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) # <<<<<<<<<<<<<< + * return slice_is_contig(mslice[0], 'F', self.view.ndim) + * + */ + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(__pyx_v_self, (&__pyx_v_tmp)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(0, 633, __pyx_L1_error) + __pyx_v_mslice = __pyx_t_1; + + /* "View.MemoryView":634 + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) + * return slice_is_contig(mslice[0], 'F', self.view.ndim) # <<<<<<<<<<<<<< + * + * def copy(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_memviewslice_is_contig((__pyx_v_mslice[0]), 'F', __pyx_v_self->view.ndim)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 634, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":630 + * return slice_is_contig(mslice[0], 'C', self.view.ndim) + * + * def is_f_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.is_f_contig", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":636 + * return slice_is_contig(mslice[0], 'F', self.view.ndim) + * + * def copy(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice mslice + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_copy(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_copy(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("copy (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("copy", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "copy", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_20copy(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_20copy(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice __pyx_v_mslice; + int __pyx_v_flags; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("copy", 1); + + /* "View.MemoryView":638 + * def copy(self): + * cdef __Pyx_memviewslice mslice + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS # <<<<<<<<<<<<<< + * + * slice_copy(self, &mslice) + */ + __pyx_v_flags = (__pyx_v_self->flags & (~PyBUF_F_CONTIGUOUS)); + + /* "View.MemoryView":640 + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS + * + * slice_copy(self, &mslice) # <<<<<<<<<<<<<< + * mslice = slice_copy_contig(&mslice, "c", self.view.ndim, + * self.view.itemsize, + */ + __pyx_memoryview_slice_copy(__pyx_v_self, (&__pyx_v_mslice)); + + /* "View.MemoryView":641 + * + * slice_copy(self, &mslice) + * mslice = slice_copy_contig(&mslice, "c", self.view.ndim, # <<<<<<<<<<<<<< + * self.view.itemsize, + * flags|PyBUF_C_CONTIGUOUS, + */ + __pyx_t_1 = __pyx_memoryview_copy_new_contig((&__pyx_v_mslice), ((char *)"c"), __pyx_v_self->view.ndim, __pyx_v_self->view.itemsize, (__pyx_v_flags | PyBUF_C_CONTIGUOUS), __pyx_v_self->dtype_is_object); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 641, __pyx_L1_error) + __pyx_v_mslice = __pyx_t_1; + + /* "View.MemoryView":646 + * self.dtype_is_object) + * + * return memoryview_copy_from_slice(self, &mslice) # <<<<<<<<<<<<<< + * + * def copy_fortran(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_memoryview_copy_object_from_slice(__pyx_v_self, (&__pyx_v_mslice)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 646, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":636 + * return slice_is_contig(mslice[0], 'F', self.view.ndim) + * + * def copy(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice mslice + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.copy", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":648 + * return memoryview_copy_from_slice(self, &mslice) + * + * def copy_fortran(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice src, dst + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_copy_fortran(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_copy_fortran(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("copy_fortran (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("copy_fortran", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "copy_fortran", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_22copy_fortran(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_22copy_fortran(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice __pyx_v_src; + __Pyx_memviewslice __pyx_v_dst; + int __pyx_v_flags; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("copy_fortran", 1); + + /* "View.MemoryView":650 + * def copy_fortran(self): + * cdef __Pyx_memviewslice src, dst + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS # <<<<<<<<<<<<<< + * + * slice_copy(self, &src) + */ + __pyx_v_flags = (__pyx_v_self->flags & (~PyBUF_C_CONTIGUOUS)); + + /* "View.MemoryView":652 + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS + * + * slice_copy(self, &src) # <<<<<<<<<<<<<< + * dst = slice_copy_contig(&src, "fortran", self.view.ndim, + * self.view.itemsize, + */ + __pyx_memoryview_slice_copy(__pyx_v_self, (&__pyx_v_src)); + + /* "View.MemoryView":653 + * + * slice_copy(self, &src) + * dst = slice_copy_contig(&src, "fortran", self.view.ndim, # <<<<<<<<<<<<<< + * self.view.itemsize, + * flags|PyBUF_F_CONTIGUOUS, + */ + __pyx_t_1 = __pyx_memoryview_copy_new_contig((&__pyx_v_src), ((char *)"fortran"), __pyx_v_self->view.ndim, __pyx_v_self->view.itemsize, (__pyx_v_flags | PyBUF_F_CONTIGUOUS), __pyx_v_self->dtype_is_object); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 653, __pyx_L1_error) + __pyx_v_dst = __pyx_t_1; + + /* "View.MemoryView":658 + * self.dtype_is_object) + * + * return memoryview_copy_from_slice(self, &dst) # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_memoryview_copy_object_from_slice(__pyx_v_self, (&__pyx_v_dst)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 658, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":648 + * return memoryview_copy_from_slice(self, &mslice) + * + * def copy_fortran(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice src, dst + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.copy_fortran", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryview_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryview_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_memoryview___reduce_cython__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryview___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(0, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryview_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryview_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(0, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.memoryview.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_memoryview_2__setstate_cython__(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryview_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(0, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":662 + * + * @cname('__pyx_memoryview_new') + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): # <<<<<<<<<<<<<< + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo + */ + +static PyObject *__pyx_memoryview_new(PyObject *__pyx_v_o, int __pyx_v_flags, int __pyx_v_dtype_is_object, __Pyx_TypeInfo *__pyx_v_typeinfo) { + struct __pyx_memoryview_obj *__pyx_v_result = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_cwrapper", 1); + + /* "View.MemoryView":663 + * @cname('__pyx_memoryview_new') + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): + * cdef memoryview result = memoryview(o, flags, dtype_is_object) # <<<<<<<<<<<<<< + * result.typeinfo = typeinfo + * return result + */ + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_flags); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_v_dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_v_o); + __Pyx_GIVEREF(__pyx_v_o); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_v_o)) __PYX_ERR(0, 663, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1)) __PYX_ERR(0, 663, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_t_2)) __PYX_ERR(0, 663, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_Call(((PyObject *)__pyx_memoryview_type), __pyx_t_3, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_v_result = ((struct __pyx_memoryview_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":664 + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo # <<<<<<<<<<<<<< + * return result + * + */ + __pyx_v_result->typeinfo = __pyx_v_typeinfo; + + /* "View.MemoryView":665 + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo + * return result # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_check') + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = ((PyObject *)__pyx_v_result); + goto __pyx_L0; + + /* "View.MemoryView":662 + * + * @cname('__pyx_memoryview_new') + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): # <<<<<<<<<<<<<< + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview_cwrapper", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":668 + * + * @cname('__pyx_memoryview_check') + * cdef inline bint memoryview_check(object o) noexcept: # <<<<<<<<<<<<<< + * return isinstance(o, memoryview) + * + */ + +static CYTHON_INLINE int __pyx_memoryview_check(PyObject *__pyx_v_o) { + int __pyx_r; + int __pyx_t_1; + + /* "View.MemoryView":669 + * @cname('__pyx_memoryview_check') + * cdef inline bint memoryview_check(object o) noexcept: + * return isinstance(o, memoryview) # <<<<<<<<<<<<<< + * + * cdef tuple _unellipsify(object index, int ndim): + */ + __pyx_t_1 = __Pyx_TypeCheck(__pyx_v_o, __pyx_memoryview_type); + __pyx_r = __pyx_t_1; + goto __pyx_L0; + + /* "View.MemoryView":668 + * + * @cname('__pyx_memoryview_check') + * cdef inline bint memoryview_check(object o) noexcept: # <<<<<<<<<<<<<< + * return isinstance(o, memoryview) + * + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":671 + * return isinstance(o, memoryview) + * + * cdef tuple _unellipsify(object index, int ndim): # <<<<<<<<<<<<<< + * """ + * Replace all ellipses with full slices and fill incomplete indices with + */ + +static PyObject *_unellipsify(PyObject *__pyx_v_index, int __pyx_v_ndim) { + Py_ssize_t __pyx_v_idx; + PyObject *__pyx_v_tup = NULL; + PyObject *__pyx_v_result = NULL; + int __pyx_v_have_slices; + int __pyx_v_seen_ellipsis; + PyObject *__pyx_v_item = NULL; + Py_ssize_t __pyx_v_nslices; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + Py_ssize_t __pyx_t_4; + Py_ssize_t __pyx_t_5; + Py_UCS4 __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("_unellipsify", 1); + + /* "View.MemoryView":677 + * """ + * cdef Py_ssize_t idx + * tup = index if isinstance(index, tuple) else (index,) # <<<<<<<<<<<<<< + * + * result = [slice(None)] * ndim + */ + __pyx_t_2 = PyTuple_Check(__pyx_v_index); + if (__pyx_t_2) { + __Pyx_INCREF(((PyObject*)__pyx_v_index)); + __pyx_t_1 = __pyx_v_index; + } else { + __pyx_t_3 = PyTuple_New(1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 677, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_v_index); + __Pyx_GIVEREF(__pyx_v_index); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_v_index)) __PYX_ERR(0, 677, __pyx_L1_error); + __pyx_t_1 = __pyx_t_3; + __pyx_t_3 = 0; + } + __pyx_v_tup = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":679 + * tup = index if isinstance(index, tuple) else (index,) + * + * result = [slice(None)] * ndim # <<<<<<<<<<<<<< + * have_slices = False + * seen_ellipsis = False + */ + __pyx_t_1 = PyList_New(1 * ((__pyx_v_ndim<0) ? 0:__pyx_v_ndim)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 679, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + { Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < __pyx_v_ndim; __pyx_temp++) { + __Pyx_INCREF(__pyx_slice__5); + __Pyx_GIVEREF(__pyx_slice__5); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, __pyx_temp, __pyx_slice__5)) __PYX_ERR(0, 679, __pyx_L1_error); + } + } + __pyx_v_result = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":680 + * + * result = [slice(None)] * ndim + * have_slices = False # <<<<<<<<<<<<<< + * seen_ellipsis = False + * idx = 0 + */ + __pyx_v_have_slices = 0; + + /* "View.MemoryView":681 + * result = [slice(None)] * ndim + * have_slices = False + * seen_ellipsis = False # <<<<<<<<<<<<<< + * idx = 0 + * for item in tup: + */ + __pyx_v_seen_ellipsis = 0; + + /* "View.MemoryView":682 + * have_slices = False + * seen_ellipsis = False + * idx = 0 # <<<<<<<<<<<<<< + * for item in tup: + * if item is Ellipsis: + */ + __pyx_v_idx = 0; + + /* "View.MemoryView":683 + * seen_ellipsis = False + * idx = 0 + * for item in tup: # <<<<<<<<<<<<<< + * if item is Ellipsis: + * if not seen_ellipsis: + */ + if (unlikely(__pyx_v_tup == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not iterable"); + __PYX_ERR(0, 683, __pyx_L1_error) + } + __pyx_t_1 = __pyx_v_tup; __Pyx_INCREF(__pyx_t_1); + __pyx_t_4 = 0; + for (;;) { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_1); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 683, __pyx_L1_error) + #endif + if (__pyx_t_4 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_3 = PyTuple_GET_ITEM(__pyx_t_1, __pyx_t_4); __Pyx_INCREF(__pyx_t_3); __pyx_t_4++; if (unlikely((0 < 0))) __PYX_ERR(0, 683, __pyx_L1_error) + #else + __pyx_t_3 = __Pyx_PySequence_ITEM(__pyx_t_1, __pyx_t_4); __pyx_t_4++; if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 683, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + #endif + __Pyx_XDECREF_SET(__pyx_v_item, __pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":684 + * idx = 0 + * for item in tup: + * if item is Ellipsis: # <<<<<<<<<<<<<< + * if not seen_ellipsis: + * idx += ndim - len(tup) + */ + __pyx_t_2 = (__pyx_v_item == __pyx_builtin_Ellipsis); + if (__pyx_t_2) { + + /* "View.MemoryView":685 + * for item in tup: + * if item is Ellipsis: + * if not seen_ellipsis: # <<<<<<<<<<<<<< + * idx += ndim - len(tup) + * seen_ellipsis = True + */ + __pyx_t_2 = (!__pyx_v_seen_ellipsis); + if (__pyx_t_2) { + + /* "View.MemoryView":686 + * if item is Ellipsis: + * if not seen_ellipsis: + * idx += ndim - len(tup) # <<<<<<<<<<<<<< + * seen_ellipsis = True + * have_slices = True + */ + if (unlikely(__pyx_v_tup == Py_None)) { + PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); + __PYX_ERR(0, 686, __pyx_L1_error) + } + __pyx_t_5 = __Pyx_PyTuple_GET_SIZE(__pyx_v_tup); if (unlikely(__pyx_t_5 == ((Py_ssize_t)-1))) __PYX_ERR(0, 686, __pyx_L1_error) + __pyx_v_idx = (__pyx_v_idx + (__pyx_v_ndim - __pyx_t_5)); + + /* "View.MemoryView":687 + * if not seen_ellipsis: + * idx += ndim - len(tup) + * seen_ellipsis = True # <<<<<<<<<<<<<< + * have_slices = True + * else: + */ + __pyx_v_seen_ellipsis = 1; + + /* "View.MemoryView":685 + * for item in tup: + * if item is Ellipsis: + * if not seen_ellipsis: # <<<<<<<<<<<<<< + * idx += ndim - len(tup) + * seen_ellipsis = True + */ + } + + /* "View.MemoryView":688 + * idx += ndim - len(tup) + * seen_ellipsis = True + * have_slices = True # <<<<<<<<<<<<<< + * else: + * if isinstance(item, slice): + */ + __pyx_v_have_slices = 1; + + /* "View.MemoryView":684 + * idx = 0 + * for item in tup: + * if item is Ellipsis: # <<<<<<<<<<<<<< + * if not seen_ellipsis: + * idx += ndim - len(tup) + */ + goto __pyx_L5; + } + + /* "View.MemoryView":690 + * have_slices = True + * else: + * if isinstance(item, slice): # <<<<<<<<<<<<<< + * have_slices = True + * elif not PyIndex_Check(item): + */ + /*else*/ { + __pyx_t_2 = PySlice_Check(__pyx_v_item); + if (__pyx_t_2) { + + /* "View.MemoryView":691 + * else: + * if isinstance(item, slice): + * have_slices = True # <<<<<<<<<<<<<< + * elif not PyIndex_Check(item): + * raise TypeError, f"Cannot index with type '{type(item)}'" + */ + __pyx_v_have_slices = 1; + + /* "View.MemoryView":690 + * have_slices = True + * else: + * if isinstance(item, slice): # <<<<<<<<<<<<<< + * have_slices = True + * elif not PyIndex_Check(item): + */ + goto __pyx_L7; + } + + /* "View.MemoryView":692 + * if isinstance(item, slice): + * have_slices = True + * elif not PyIndex_Check(item): # <<<<<<<<<<<<<< + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item + */ + __pyx_t_2 = (!(PyIndex_Check(__pyx_v_item) != 0)); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":693 + * have_slices = True + * elif not PyIndex_Check(item): + * raise TypeError, f"Cannot index with type '{type(item)}'" # <<<<<<<<<<<<<< + * result[idx] = item + * idx += 1 + */ + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 693, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = 0; + __pyx_t_6 = 127; + __Pyx_INCREF(__pyx_kp_u_Cannot_index_with_type); + __pyx_t_5 += 24; + __Pyx_GIVEREF(__pyx_kp_u_Cannot_index_with_type); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_kp_u_Cannot_index_with_type); + __pyx_t_7 = __Pyx_PyObject_FormatSimple(((PyObject *)Py_TYPE(__pyx_v_item)), __pyx_empty_unicode); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 693, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_7) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_7) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_7); + __pyx_t_7 = 0; + __Pyx_INCREF(__pyx_kp_u__6); + __pyx_t_5 += 1; + __Pyx_GIVEREF(__pyx_kp_u__6); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_kp_u__6); + __pyx_t_7 = __Pyx_PyUnicode_Join(__pyx_t_3, 3, __pyx_t_5, __pyx_t_6); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 693, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_t_7, 0, 0); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __PYX_ERR(0, 693, __pyx_L1_error) + + /* "View.MemoryView":692 + * if isinstance(item, slice): + * have_slices = True + * elif not PyIndex_Check(item): # <<<<<<<<<<<<<< + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item + */ + } + __pyx_L7:; + + /* "View.MemoryView":694 + * elif not PyIndex_Check(item): + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item # <<<<<<<<<<<<<< + * idx += 1 + * + */ + if (unlikely((__Pyx_SetItemInt(__pyx_v_result, __pyx_v_idx, __pyx_v_item, Py_ssize_t, 1, PyInt_FromSsize_t, 1, 1, 1) < 0))) __PYX_ERR(0, 694, __pyx_L1_error) + } + __pyx_L5:; + + /* "View.MemoryView":695 + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item + * idx += 1 # <<<<<<<<<<<<<< + * + * nslices = ndim - idx + */ + __pyx_v_idx = (__pyx_v_idx + 1); + + /* "View.MemoryView":683 + * seen_ellipsis = False + * idx = 0 + * for item in tup: # <<<<<<<<<<<<<< + * if item is Ellipsis: + * if not seen_ellipsis: + */ + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "View.MemoryView":697 + * idx += 1 + * + * nslices = ndim - idx # <<<<<<<<<<<<<< + * return have_slices or nslices, tuple(result) + * + */ + __pyx_v_nslices = (__pyx_v_ndim - __pyx_v_idx); + + /* "View.MemoryView":698 + * + * nslices = ndim - idx + * return have_slices or nslices, tuple(result) # <<<<<<<<<<<<<< + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + */ + __Pyx_XDECREF(__pyx_r); + if (!__pyx_v_have_slices) { + } else { + __pyx_t_7 = __Pyx_PyBool_FromLong(__pyx_v_have_slices); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_1 = __pyx_t_7; + __pyx_t_7 = 0; + goto __pyx_L9_bool_binop_done; + } + __pyx_t_7 = PyInt_FromSsize_t(__pyx_v_nslices); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_1 = __pyx_t_7; + __pyx_t_7 = 0; + __pyx_L9_bool_binop_done:; + __pyx_t_7 = PyList_AsTuple(__pyx_v_result); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_1)) __PYX_ERR(0, 698, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_7); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_7)) __PYX_ERR(0, 698, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_7 = 0; + __pyx_r = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; + goto __pyx_L0; + + /* "View.MemoryView":671 + * return isinstance(o, memoryview) + * + * cdef tuple _unellipsify(object index, int ndim): # <<<<<<<<<<<<<< + * """ + * Replace all ellipses with full slices and fill incomplete indices with + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("View.MemoryView._unellipsify", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_tup); + __Pyx_XDECREF(__pyx_v_result); + __Pyx_XDECREF(__pyx_v_item); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":700 + * return have_slices or nslices, tuple(result) + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: # <<<<<<<<<<<<<< + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: + */ + +static int assert_direct_dimensions(Py_ssize_t *__pyx_v_suboffsets, int __pyx_v_ndim) { + Py_ssize_t __pyx_v_suboffset; + int __pyx_r; + Py_ssize_t *__pyx_t_1; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + int __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + + /* "View.MemoryView":701 + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + * for suboffset in suboffsets[:ndim]: # <<<<<<<<<<<<<< + * if suboffset >= 0: + * raise ValueError, "Indirect dimensions not supported" + */ + __pyx_t_2 = (__pyx_v_suboffsets + __pyx_v_ndim); + for (__pyx_t_3 = __pyx_v_suboffsets; __pyx_t_3 < __pyx_t_2; __pyx_t_3++) { + __pyx_t_1 = __pyx_t_3; + __pyx_v_suboffset = (__pyx_t_1[0]); + + /* "View.MemoryView":702 + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * raise ValueError, "Indirect dimensions not supported" + * return 0 # return type just used as an error flag + */ + __pyx_t_4 = (__pyx_v_suboffset >= 0); + if (unlikely(__pyx_t_4)) { + + /* "View.MemoryView":703 + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: + * raise ValueError, "Indirect dimensions not supported" # <<<<<<<<<<<<<< + * return 0 # return type just used as an error flag + * + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Indirect_dimensions_not_supporte, 0, 0); + __PYX_ERR(0, 703, __pyx_L1_error) + + /* "View.MemoryView":702 + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * raise ValueError, "Indirect dimensions not supported" + * return 0 # return type just used as an error flag + */ + } + } + + /* "View.MemoryView":704 + * if suboffset >= 0: + * raise ValueError, "Indirect dimensions not supported" + * return 0 # return type just used as an error flag # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":700 + * return have_slices or nslices, tuple(result) + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: # <<<<<<<<<<<<<< + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.assert_direct_dimensions", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":711 + * + * @cname('__pyx_memview_slice') + * cdef memoryview memview_slice(memoryview memview, object indices): # <<<<<<<<<<<<<< + * cdef int new_ndim = 0, suboffset_dim = -1, dim + * cdef bint negative_step + */ + +static struct __pyx_memoryview_obj *__pyx_memview_slice(struct __pyx_memoryview_obj *__pyx_v_memview, PyObject *__pyx_v_indices) { + int __pyx_v_new_ndim; + int __pyx_v_suboffset_dim; + int __pyx_v_dim; + __Pyx_memviewslice __pyx_v_src; + __Pyx_memviewslice __pyx_v_dst; + __Pyx_memviewslice *__pyx_v_p_src; + struct __pyx_memoryviewslice_obj *__pyx_v_memviewsliceobj = 0; + __Pyx_memviewslice *__pyx_v_p_dst; + int *__pyx_v_p_suboffset_dim; + Py_ssize_t __pyx_v_start; + Py_ssize_t __pyx_v_stop; + Py_ssize_t __pyx_v_step; + Py_ssize_t __pyx_v_cindex; + int __pyx_v_have_start; + int __pyx_v_have_stop; + int __pyx_v_have_step; + PyObject *__pyx_v_index = NULL; + struct __pyx_memoryview_obj *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + struct __pyx_memoryview_obj *__pyx_t_3; + char *__pyx_t_4; + int __pyx_t_5; + Py_ssize_t __pyx_t_6; + PyObject *(*__pyx_t_7)(PyObject *); + PyObject *__pyx_t_8 = NULL; + Py_ssize_t __pyx_t_9; + int __pyx_t_10; + Py_ssize_t __pyx_t_11; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memview_slice", 1); + + /* "View.MemoryView":712 + * @cname('__pyx_memview_slice') + * cdef memoryview memview_slice(memoryview memview, object indices): + * cdef int new_ndim = 0, suboffset_dim = -1, dim # <<<<<<<<<<<<<< + * cdef bint negative_step + * cdef __Pyx_memviewslice src, dst + */ + __pyx_v_new_ndim = 0; + __pyx_v_suboffset_dim = -1; + + /* "View.MemoryView":719 + * + * + * memset(&dst, 0, sizeof(dst)) # <<<<<<<<<<<<<< + * + * cdef _memoryviewslice memviewsliceobj + */ + (void)(memset((&__pyx_v_dst), 0, (sizeof(__pyx_v_dst)))); + + /* "View.MemoryView":723 + * cdef _memoryviewslice memviewsliceobj + * + * assert memview.view.ndim > 0 # <<<<<<<<<<<<<< + * + * if isinstance(memview, _memoryviewslice): + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_1 = (__pyx_v_memview->view.ndim > 0); + if (unlikely(!__pyx_t_1)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(0, 723, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(0, 723, __pyx_L1_error) + #endif + + /* "View.MemoryView":725 + * assert memview.view.ndim > 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * memviewsliceobj = memview + * p_src = &memviewsliceobj.from_slice + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":726 + * + * if isinstance(memview, _memoryviewslice): + * memviewsliceobj = memview # <<<<<<<<<<<<<< + * p_src = &memviewsliceobj.from_slice + * else: + */ + if (!(likely(((((PyObject *)__pyx_v_memview)) == Py_None) || likely(__Pyx_TypeTest(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type))))) __PYX_ERR(0, 726, __pyx_L1_error) + __pyx_t_2 = ((PyObject *)__pyx_v_memview); + __Pyx_INCREF(__pyx_t_2); + __pyx_v_memviewsliceobj = ((struct __pyx_memoryviewslice_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":727 + * if isinstance(memview, _memoryviewslice): + * memviewsliceobj = memview + * p_src = &memviewsliceobj.from_slice # <<<<<<<<<<<<<< + * else: + * slice_copy(memview, &src) + */ + __pyx_v_p_src = (&__pyx_v_memviewsliceobj->from_slice); + + /* "View.MemoryView":725 + * assert memview.view.ndim > 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * memviewsliceobj = memview + * p_src = &memviewsliceobj.from_slice + */ + goto __pyx_L3; + } + + /* "View.MemoryView":729 + * p_src = &memviewsliceobj.from_slice + * else: + * slice_copy(memview, &src) # <<<<<<<<<<<<<< + * p_src = &src + * + */ + /*else*/ { + __pyx_memoryview_slice_copy(__pyx_v_memview, (&__pyx_v_src)); + + /* "View.MemoryView":730 + * else: + * slice_copy(memview, &src) + * p_src = &src # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_p_src = (&__pyx_v_src); + } + __pyx_L3:; + + /* "View.MemoryView":736 + * + * + * dst.memview = p_src.memview # <<<<<<<<<<<<<< + * dst.data = p_src.data + * + */ + __pyx_t_3 = __pyx_v_p_src->memview; + __pyx_v_dst.memview = __pyx_t_3; + + /* "View.MemoryView":737 + * + * dst.memview = p_src.memview + * dst.data = p_src.data # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_4 = __pyx_v_p_src->data; + __pyx_v_dst.data = __pyx_t_4; + + /* "View.MemoryView":742 + * + * + * cdef __Pyx_memviewslice *p_dst = &dst # <<<<<<<<<<<<<< + * cdef int *p_suboffset_dim = &suboffset_dim + * cdef Py_ssize_t start, stop, step, cindex + */ + __pyx_v_p_dst = (&__pyx_v_dst); + + /* "View.MemoryView":743 + * + * cdef __Pyx_memviewslice *p_dst = &dst + * cdef int *p_suboffset_dim = &suboffset_dim # <<<<<<<<<<<<<< + * cdef Py_ssize_t start, stop, step, cindex + * cdef bint have_start, have_stop, have_step + */ + __pyx_v_p_suboffset_dim = (&__pyx_v_suboffset_dim); + + /* "View.MemoryView":747 + * cdef bint have_start, have_stop, have_step + * + * for dim, index in enumerate(indices): # <<<<<<<<<<<<<< + * if PyIndex_Check(index): + * cindex = index + */ + __pyx_t_5 = 0; + if (likely(PyList_CheckExact(__pyx_v_indices)) || PyTuple_CheckExact(__pyx_v_indices)) { + __pyx_t_2 = __pyx_v_indices; __Pyx_INCREF(__pyx_t_2); + __pyx_t_6 = 0; + __pyx_t_7 = NULL; + } else { + __pyx_t_6 = -1; __pyx_t_2 = PyObject_GetIter(__pyx_v_indices); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 747, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_7 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_2); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 747, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_7)) { + if (likely(PyList_CheckExact(__pyx_t_2))) { + { + Py_ssize_t __pyx_temp = __Pyx_PyList_GET_SIZE(__pyx_t_2); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 747, __pyx_L1_error) + #endif + if (__pyx_t_6 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_8 = PyList_GET_ITEM(__pyx_t_2, __pyx_t_6); __Pyx_INCREF(__pyx_t_8); __pyx_t_6++; if (unlikely((0 < 0))) __PYX_ERR(0, 747, __pyx_L1_error) + #else + __pyx_t_8 = __Pyx_PySequence_ITEM(__pyx_t_2, __pyx_t_6); __pyx_t_6++; if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 747, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + #endif + } else { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_2); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 747, __pyx_L1_error) + #endif + if (__pyx_t_6 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_8 = PyTuple_GET_ITEM(__pyx_t_2, __pyx_t_6); __Pyx_INCREF(__pyx_t_8); __pyx_t_6++; if (unlikely((0 < 0))) __PYX_ERR(0, 747, __pyx_L1_error) + #else + __pyx_t_8 = __Pyx_PySequence_ITEM(__pyx_t_2, __pyx_t_6); __pyx_t_6++; if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 747, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + #endif + } + } else { + __pyx_t_8 = __pyx_t_7(__pyx_t_2); + if (unlikely(!__pyx_t_8)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(0, 747, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_8); + } + __Pyx_XDECREF_SET(__pyx_v_index, __pyx_t_8); + __pyx_t_8 = 0; + __pyx_v_dim = __pyx_t_5; + __pyx_t_5 = (__pyx_t_5 + 1); + + /* "View.MemoryView":748 + * + * for dim, index in enumerate(indices): + * if PyIndex_Check(index): # <<<<<<<<<<<<<< + * cindex = index + * slice_memviewslice( + */ + __pyx_t_1 = (PyIndex_Check(__pyx_v_index) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":749 + * for dim, index in enumerate(indices): + * if PyIndex_Check(index): + * cindex = index # <<<<<<<<<<<<<< + * slice_memviewslice( + * p_dst, p_src.shape[dim], p_src.strides[dim], p_src.suboffsets[dim], + */ + __pyx_t_9 = __Pyx_PyIndex_AsSsize_t(__pyx_v_index); if (unlikely((__pyx_t_9 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 749, __pyx_L1_error) + __pyx_v_cindex = __pyx_t_9; + + /* "View.MemoryView":750 + * if PyIndex_Check(index): + * cindex = index + * slice_memviewslice( # <<<<<<<<<<<<<< + * p_dst, p_src.shape[dim], p_src.strides[dim], p_src.suboffsets[dim], + * dim, new_ndim, p_suboffset_dim, + */ + __pyx_t_10 = __pyx_memoryview_slice_memviewslice(__pyx_v_p_dst, (__pyx_v_p_src->shape[__pyx_v_dim]), (__pyx_v_p_src->strides[__pyx_v_dim]), (__pyx_v_p_src->suboffsets[__pyx_v_dim]), __pyx_v_dim, __pyx_v_new_ndim, __pyx_v_p_suboffset_dim, __pyx_v_cindex, 0, 0, 0, 0, 0, 0); if (unlikely(__pyx_t_10 == ((int)-1))) __PYX_ERR(0, 750, __pyx_L1_error) + + /* "View.MemoryView":748 + * + * for dim, index in enumerate(indices): + * if PyIndex_Check(index): # <<<<<<<<<<<<<< + * cindex = index + * slice_memviewslice( + */ + goto __pyx_L6; + } + + /* "View.MemoryView":756 + * 0, 0, 0, # have_{start,stop,step} + * False) + * elif index is None: # <<<<<<<<<<<<<< + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 + */ + __pyx_t_1 = (__pyx_v_index == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":757 + * False) + * elif index is None: + * p_dst.shape[new_ndim] = 1 # <<<<<<<<<<<<<< + * p_dst.strides[new_ndim] = 0 + * p_dst.suboffsets[new_ndim] = -1 + */ + (__pyx_v_p_dst->shape[__pyx_v_new_ndim]) = 1; + + /* "View.MemoryView":758 + * elif index is None: + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 # <<<<<<<<<<<<<< + * p_dst.suboffsets[new_ndim] = -1 + * new_ndim += 1 + */ + (__pyx_v_p_dst->strides[__pyx_v_new_ndim]) = 0; + + /* "View.MemoryView":759 + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 + * p_dst.suboffsets[new_ndim] = -1 # <<<<<<<<<<<<<< + * new_ndim += 1 + * else: + */ + (__pyx_v_p_dst->suboffsets[__pyx_v_new_ndim]) = -1L; + + /* "View.MemoryView":760 + * p_dst.strides[new_ndim] = 0 + * p_dst.suboffsets[new_ndim] = -1 + * new_ndim += 1 # <<<<<<<<<<<<<< + * else: + * start = index.start or 0 + */ + __pyx_v_new_ndim = (__pyx_v_new_ndim + 1); + + /* "View.MemoryView":756 + * 0, 0, 0, # have_{start,stop,step} + * False) + * elif index is None: # <<<<<<<<<<<<<< + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 + */ + goto __pyx_L6; + } + + /* "View.MemoryView":762 + * new_ndim += 1 + * else: + * start = index.start or 0 # <<<<<<<<<<<<<< + * stop = index.stop or 0 + * step = index.step or 0 + */ + /*else*/ { + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_start); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 762, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_t_8); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(0, 762, __pyx_L1_error) + if (!__pyx_t_1) { + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } else { + __pyx_t_11 = __Pyx_PyIndex_AsSsize_t(__pyx_t_8); if (unlikely((__pyx_t_11 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 762, __pyx_L1_error) + __pyx_t_9 = __pyx_t_11; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L7_bool_binop_done; + } + __pyx_t_9 = 0; + __pyx_L7_bool_binop_done:; + __pyx_v_start = __pyx_t_9; + + /* "View.MemoryView":763 + * else: + * start = index.start or 0 + * stop = index.stop or 0 # <<<<<<<<<<<<<< + * step = index.step or 0 + * + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_stop); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 763, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_t_8); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(0, 763, __pyx_L1_error) + if (!__pyx_t_1) { + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } else { + __pyx_t_11 = __Pyx_PyIndex_AsSsize_t(__pyx_t_8); if (unlikely((__pyx_t_11 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 763, __pyx_L1_error) + __pyx_t_9 = __pyx_t_11; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L9_bool_binop_done; + } + __pyx_t_9 = 0; + __pyx_L9_bool_binop_done:; + __pyx_v_stop = __pyx_t_9; + + /* "View.MemoryView":764 + * start = index.start or 0 + * stop = index.stop or 0 + * step = index.step or 0 # <<<<<<<<<<<<<< + * + * have_start = index.start is not None + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_step); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 764, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_t_8); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(0, 764, __pyx_L1_error) + if (!__pyx_t_1) { + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } else { + __pyx_t_11 = __Pyx_PyIndex_AsSsize_t(__pyx_t_8); if (unlikely((__pyx_t_11 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 764, __pyx_L1_error) + __pyx_t_9 = __pyx_t_11; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L11_bool_binop_done; + } + __pyx_t_9 = 0; + __pyx_L11_bool_binop_done:; + __pyx_v_step = __pyx_t_9; + + /* "View.MemoryView":766 + * step = index.step or 0 + * + * have_start = index.start is not None # <<<<<<<<<<<<<< + * have_stop = index.stop is not None + * have_step = index.step is not None + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_start); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 766, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = (__pyx_t_8 != Py_None); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_v_have_start = __pyx_t_1; + + /* "View.MemoryView":767 + * + * have_start = index.start is not None + * have_stop = index.stop is not None # <<<<<<<<<<<<<< + * have_step = index.step is not None + * + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_stop); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 767, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = (__pyx_t_8 != Py_None); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_v_have_stop = __pyx_t_1; + + /* "View.MemoryView":768 + * have_start = index.start is not None + * have_stop = index.stop is not None + * have_step = index.step is not None # <<<<<<<<<<<<<< + * + * slice_memviewslice( + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_step); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 768, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = (__pyx_t_8 != Py_None); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_v_have_step = __pyx_t_1; + + /* "View.MemoryView":770 + * have_step = index.step is not None + * + * slice_memviewslice( # <<<<<<<<<<<<<< + * p_dst, p_src.shape[dim], p_src.strides[dim], p_src.suboffsets[dim], + * dim, new_ndim, p_suboffset_dim, + */ + __pyx_t_10 = __pyx_memoryview_slice_memviewslice(__pyx_v_p_dst, (__pyx_v_p_src->shape[__pyx_v_dim]), (__pyx_v_p_src->strides[__pyx_v_dim]), (__pyx_v_p_src->suboffsets[__pyx_v_dim]), __pyx_v_dim, __pyx_v_new_ndim, __pyx_v_p_suboffset_dim, __pyx_v_start, __pyx_v_stop, __pyx_v_step, __pyx_v_have_start, __pyx_v_have_stop, __pyx_v_have_step, 1); if (unlikely(__pyx_t_10 == ((int)-1))) __PYX_ERR(0, 770, __pyx_L1_error) + + /* "View.MemoryView":776 + * have_start, have_stop, have_step, + * True) + * new_ndim += 1 # <<<<<<<<<<<<<< + * + * if isinstance(memview, _memoryviewslice): + */ + __pyx_v_new_ndim = (__pyx_v_new_ndim + 1); + } + __pyx_L6:; + + /* "View.MemoryView":747 + * cdef bint have_start, have_stop, have_step + * + * for dim, index in enumerate(indices): # <<<<<<<<<<<<<< + * if PyIndex_Check(index): + * cindex = index + */ + } + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":778 + * new_ndim += 1 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":779 + * + * if isinstance(memview, _memoryviewslice): + * return memoryview_fromslice(dst, new_ndim, # <<<<<<<<<<<<<< + * memviewsliceobj.to_object_func, + * memviewsliceobj.to_dtype_func, + */ + __Pyx_XDECREF((PyObject *)__pyx_r); + + /* "View.MemoryView":780 + * if isinstance(memview, _memoryviewslice): + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, # <<<<<<<<<<<<<< + * memviewsliceobj.to_dtype_func, + * memview.dtype_is_object) + */ + if (unlikely(!__pyx_v_memviewsliceobj)) { __Pyx_RaiseUnboundLocalError("memviewsliceobj"); __PYX_ERR(0, 780, __pyx_L1_error) } + + /* "View.MemoryView":781 + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, + * memviewsliceobj.to_dtype_func, # <<<<<<<<<<<<<< + * memview.dtype_is_object) + * else: + */ + if (unlikely(!__pyx_v_memviewsliceobj)) { __Pyx_RaiseUnboundLocalError("memviewsliceobj"); __PYX_ERR(0, 781, __pyx_L1_error) } + + /* "View.MemoryView":779 + * + * if isinstance(memview, _memoryviewslice): + * return memoryview_fromslice(dst, new_ndim, # <<<<<<<<<<<<<< + * memviewsliceobj.to_object_func, + * memviewsliceobj.to_dtype_func, + */ + __pyx_t_2 = __pyx_memoryview_fromslice(__pyx_v_dst, __pyx_v_new_ndim, __pyx_v_memviewsliceobj->to_object_func, __pyx_v_memviewsliceobj->to_dtype_func, __pyx_v_memview->dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 779, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (!(likely(((__pyx_t_2) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_2, __pyx_memoryview_type))))) __PYX_ERR(0, 779, __pyx_L1_error) + __pyx_r = ((struct __pyx_memoryview_obj *)__pyx_t_2); + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":778 + * new_ndim += 1 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, + */ + } + + /* "View.MemoryView":784 + * memview.dtype_is_object) + * else: + * return memoryview_fromslice(dst, new_ndim, NULL, NULL, # <<<<<<<<<<<<<< + * memview.dtype_is_object) + * + */ + /*else*/ { + __Pyx_XDECREF((PyObject *)__pyx_r); + + /* "View.MemoryView":785 + * else: + * return memoryview_fromslice(dst, new_ndim, NULL, NULL, + * memview.dtype_is_object) # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = __pyx_memoryview_fromslice(__pyx_v_dst, __pyx_v_new_ndim, NULL, NULL, __pyx_v_memview->dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 784, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + + /* "View.MemoryView":784 + * memview.dtype_is_object) + * else: + * return memoryview_fromslice(dst, new_ndim, NULL, NULL, # <<<<<<<<<<<<<< + * memview.dtype_is_object) + * + */ + if (!(likely(((__pyx_t_2) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_2, __pyx_memoryview_type))))) __PYX_ERR(0, 784, __pyx_L1_error) + __pyx_r = ((struct __pyx_memoryview_obj *)__pyx_t_2); + __pyx_t_2 = 0; + goto __pyx_L0; + } + + /* "View.MemoryView":711 + * + * @cname('__pyx_memview_slice') + * cdef memoryview memview_slice(memoryview memview, object indices): # <<<<<<<<<<<<<< + * cdef int new_ndim = 0, suboffset_dim = -1, dim + * cdef bint negative_step + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("View.MemoryView.memview_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_memviewsliceobj); + __Pyx_XDECREF(__pyx_v_index); + __Pyx_XGIVEREF((PyObject *)__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":793 + * + * @cname('__pyx_memoryview_slice_memviewslice') + * cdef int slice_memviewslice( # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * Py_ssize_t shape, Py_ssize_t stride, Py_ssize_t suboffset, + */ + +static int __pyx_memoryview_slice_memviewslice(__Pyx_memviewslice *__pyx_v_dst, Py_ssize_t __pyx_v_shape, Py_ssize_t __pyx_v_stride, Py_ssize_t __pyx_v_suboffset, int __pyx_v_dim, int __pyx_v_new_ndim, int *__pyx_v_suboffset_dim, Py_ssize_t __pyx_v_start, Py_ssize_t __pyx_v_stop, Py_ssize_t __pyx_v_step, int __pyx_v_have_start, int __pyx_v_have_stop, int __pyx_v_have_step, int __pyx_v_is_slice) { + Py_ssize_t __pyx_v_new_shape; + int __pyx_v_negative_step; + int __pyx_r; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":813 + * cdef bint negative_step + * + * if not is_slice: # <<<<<<<<<<<<<< + * + * if start < 0: + */ + __pyx_t_1 = (!__pyx_v_is_slice); + if (__pyx_t_1) { + + /* "View.MemoryView":815 + * if not is_slice: + * + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if not 0 <= start < shape: + */ + __pyx_t_1 = (__pyx_v_start < 0); + if (__pyx_t_1) { + + /* "View.MemoryView":816 + * + * if start < 0: + * start += shape # <<<<<<<<<<<<<< + * if not 0 <= start < shape: + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) + */ + __pyx_v_start = (__pyx_v_start + __pyx_v_shape); + + /* "View.MemoryView":815 + * if not is_slice: + * + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if not 0 <= start < shape: + */ + } + + /* "View.MemoryView":817 + * if start < 0: + * start += shape + * if not 0 <= start < shape: # <<<<<<<<<<<<<< + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) + * else: + */ + __pyx_t_1 = (0 <= __pyx_v_start); + if (__pyx_t_1) { + __pyx_t_1 = (__pyx_v_start < __pyx_v_shape); + } + __pyx_t_2 = (!__pyx_t_1); + if (__pyx_t_2) { + + /* "View.MemoryView":818 + * start += shape + * if not 0 <= start < shape: + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) # <<<<<<<<<<<<<< + * else: + * + */ + __pyx_t_3 = __pyx_memoryview_err_dim(PyExc_IndexError, __pyx_kp_s_Index_out_of_bounds_axis_d, __pyx_v_dim); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(0, 818, __pyx_L1_error) + + /* "View.MemoryView":817 + * if start < 0: + * start += shape + * if not 0 <= start < shape: # <<<<<<<<<<<<<< + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) + * else: + */ + } + + /* "View.MemoryView":813 + * cdef bint negative_step + * + * if not is_slice: # <<<<<<<<<<<<<< + * + * if start < 0: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":821 + * else: + * + * if have_step: # <<<<<<<<<<<<<< + * negative_step = step < 0 + * if step == 0: + */ + /*else*/ { + __pyx_t_2 = (__pyx_v_have_step != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":822 + * + * if have_step: + * negative_step = step < 0 # <<<<<<<<<<<<<< + * if step == 0: + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + */ + __pyx_v_negative_step = (__pyx_v_step < 0); + + /* "View.MemoryView":823 + * if have_step: + * negative_step = step < 0 + * if step == 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + * else: + */ + __pyx_t_2 = (__pyx_v_step == 0); + if (__pyx_t_2) { + + /* "View.MemoryView":824 + * negative_step = step < 0 + * if step == 0: + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) # <<<<<<<<<<<<<< + * else: + * negative_step = False + */ + __pyx_t_3 = __pyx_memoryview_err_dim(PyExc_ValueError, __pyx_kp_s_Step_may_not_be_zero_axis_d, __pyx_v_dim); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(0, 824, __pyx_L1_error) + + /* "View.MemoryView":823 + * if have_step: + * negative_step = step < 0 + * if step == 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + * else: + */ + } + + /* "View.MemoryView":821 + * else: + * + * if have_step: # <<<<<<<<<<<<<< + * negative_step = step < 0 + * if step == 0: + */ + goto __pyx_L6; + } + + /* "View.MemoryView":826 + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + * else: + * negative_step = False # <<<<<<<<<<<<<< + * step = 1 + * + */ + /*else*/ { + __pyx_v_negative_step = 0; + + /* "View.MemoryView":827 + * else: + * negative_step = False + * step = 1 # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_step = 1; + } + __pyx_L6:; + + /* "View.MemoryView":830 + * + * + * if have_start: # <<<<<<<<<<<<<< + * if start < 0: + * start += shape + */ + __pyx_t_2 = (__pyx_v_have_start != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":831 + * + * if have_start: + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if start < 0: + */ + __pyx_t_2 = (__pyx_v_start < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":832 + * if have_start: + * if start < 0: + * start += shape # <<<<<<<<<<<<<< + * if start < 0: + * start = 0 + */ + __pyx_v_start = (__pyx_v_start + __pyx_v_shape); + + /* "View.MemoryView":833 + * if start < 0: + * start += shape + * if start < 0: # <<<<<<<<<<<<<< + * start = 0 + * elif start >= shape: + */ + __pyx_t_2 = (__pyx_v_start < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":834 + * start += shape + * if start < 0: + * start = 0 # <<<<<<<<<<<<<< + * elif start >= shape: + * if negative_step: + */ + __pyx_v_start = 0; + + /* "View.MemoryView":833 + * if start < 0: + * start += shape + * if start < 0: # <<<<<<<<<<<<<< + * start = 0 + * elif start >= shape: + */ + } + + /* "View.MemoryView":831 + * + * if have_start: + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if start < 0: + */ + goto __pyx_L9; + } + + /* "View.MemoryView":835 + * if start < 0: + * start = 0 + * elif start >= shape: # <<<<<<<<<<<<<< + * if negative_step: + * start = shape - 1 + */ + __pyx_t_2 = (__pyx_v_start >= __pyx_v_shape); + if (__pyx_t_2) { + + /* "View.MemoryView":836 + * start = 0 + * elif start >= shape: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + if (__pyx_v_negative_step) { + + /* "View.MemoryView":837 + * elif start >= shape: + * if negative_step: + * start = shape - 1 # <<<<<<<<<<<<<< + * else: + * start = shape + */ + __pyx_v_start = (__pyx_v_shape - 1); + + /* "View.MemoryView":836 + * start = 0 + * elif start >= shape: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + goto __pyx_L11; + } + + /* "View.MemoryView":839 + * start = shape - 1 + * else: + * start = shape # <<<<<<<<<<<<<< + * else: + * if negative_step: + */ + /*else*/ { + __pyx_v_start = __pyx_v_shape; + } + __pyx_L11:; + + /* "View.MemoryView":835 + * if start < 0: + * start = 0 + * elif start >= shape: # <<<<<<<<<<<<<< + * if negative_step: + * start = shape - 1 + */ + } + __pyx_L9:; + + /* "View.MemoryView":830 + * + * + * if have_start: # <<<<<<<<<<<<<< + * if start < 0: + * start += shape + */ + goto __pyx_L8; + } + + /* "View.MemoryView":841 + * start = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + /*else*/ { + if (__pyx_v_negative_step) { + + /* "View.MemoryView":842 + * else: + * if negative_step: + * start = shape - 1 # <<<<<<<<<<<<<< + * else: + * start = 0 + */ + __pyx_v_start = (__pyx_v_shape - 1); + + /* "View.MemoryView":841 + * start = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + goto __pyx_L12; + } + + /* "View.MemoryView":844 + * start = shape - 1 + * else: + * start = 0 # <<<<<<<<<<<<<< + * + * if have_stop: + */ + /*else*/ { + __pyx_v_start = 0; + } + __pyx_L12:; + } + __pyx_L8:; + + /* "View.MemoryView":846 + * start = 0 + * + * if have_stop: # <<<<<<<<<<<<<< + * if stop < 0: + * stop += shape + */ + __pyx_t_2 = (__pyx_v_have_stop != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":847 + * + * if have_stop: + * if stop < 0: # <<<<<<<<<<<<<< + * stop += shape + * if stop < 0: + */ + __pyx_t_2 = (__pyx_v_stop < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":848 + * if have_stop: + * if stop < 0: + * stop += shape # <<<<<<<<<<<<<< + * if stop < 0: + * stop = 0 + */ + __pyx_v_stop = (__pyx_v_stop + __pyx_v_shape); + + /* "View.MemoryView":849 + * if stop < 0: + * stop += shape + * if stop < 0: # <<<<<<<<<<<<<< + * stop = 0 + * elif stop > shape: + */ + __pyx_t_2 = (__pyx_v_stop < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":850 + * stop += shape + * if stop < 0: + * stop = 0 # <<<<<<<<<<<<<< + * elif stop > shape: + * stop = shape + */ + __pyx_v_stop = 0; + + /* "View.MemoryView":849 + * if stop < 0: + * stop += shape + * if stop < 0: # <<<<<<<<<<<<<< + * stop = 0 + * elif stop > shape: + */ + } + + /* "View.MemoryView":847 + * + * if have_stop: + * if stop < 0: # <<<<<<<<<<<<<< + * stop += shape + * if stop < 0: + */ + goto __pyx_L14; + } + + /* "View.MemoryView":851 + * if stop < 0: + * stop = 0 + * elif stop > shape: # <<<<<<<<<<<<<< + * stop = shape + * else: + */ + __pyx_t_2 = (__pyx_v_stop > __pyx_v_shape); + if (__pyx_t_2) { + + /* "View.MemoryView":852 + * stop = 0 + * elif stop > shape: + * stop = shape # <<<<<<<<<<<<<< + * else: + * if negative_step: + */ + __pyx_v_stop = __pyx_v_shape; + + /* "View.MemoryView":851 + * if stop < 0: + * stop = 0 + * elif stop > shape: # <<<<<<<<<<<<<< + * stop = shape + * else: + */ + } + __pyx_L14:; + + /* "View.MemoryView":846 + * start = 0 + * + * if have_stop: # <<<<<<<<<<<<<< + * if stop < 0: + * stop += shape + */ + goto __pyx_L13; + } + + /* "View.MemoryView":854 + * stop = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * stop = -1 + * else: + */ + /*else*/ { + if (__pyx_v_negative_step) { + + /* "View.MemoryView":855 + * else: + * if negative_step: + * stop = -1 # <<<<<<<<<<<<<< + * else: + * stop = shape + */ + __pyx_v_stop = -1L; + + /* "View.MemoryView":854 + * stop = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * stop = -1 + * else: + */ + goto __pyx_L16; + } + + /* "View.MemoryView":857 + * stop = -1 + * else: + * stop = shape # <<<<<<<<<<<<<< + * + * + */ + /*else*/ { + __pyx_v_stop = __pyx_v_shape; + } + __pyx_L16:; + } + __pyx_L13:; + + /* "View.MemoryView":861 + * + * with cython.cdivision(True): + * new_shape = (stop - start) // step # <<<<<<<<<<<<<< + * + * if (stop - start) - step * new_shape: + */ + __pyx_v_new_shape = ((__pyx_v_stop - __pyx_v_start) / __pyx_v_step); + + /* "View.MemoryView":863 + * new_shape = (stop - start) // step + * + * if (stop - start) - step * new_shape: # <<<<<<<<<<<<<< + * new_shape += 1 + * + */ + __pyx_t_2 = (((__pyx_v_stop - __pyx_v_start) - (__pyx_v_step * __pyx_v_new_shape)) != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":864 + * + * if (stop - start) - step * new_shape: + * new_shape += 1 # <<<<<<<<<<<<<< + * + * if new_shape < 0: + */ + __pyx_v_new_shape = (__pyx_v_new_shape + 1); + + /* "View.MemoryView":863 + * new_shape = (stop - start) // step + * + * if (stop - start) - step * new_shape: # <<<<<<<<<<<<<< + * new_shape += 1 + * + */ + } + + /* "View.MemoryView":866 + * new_shape += 1 + * + * if new_shape < 0: # <<<<<<<<<<<<<< + * new_shape = 0 + * + */ + __pyx_t_2 = (__pyx_v_new_shape < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":867 + * + * if new_shape < 0: + * new_shape = 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_new_shape = 0; + + /* "View.MemoryView":866 + * new_shape += 1 + * + * if new_shape < 0: # <<<<<<<<<<<<<< + * new_shape = 0 + * + */ + } + + /* "View.MemoryView":870 + * + * + * dst.strides[new_ndim] = stride * step # <<<<<<<<<<<<<< + * dst.shape[new_ndim] = new_shape + * dst.suboffsets[new_ndim] = suboffset + */ + (__pyx_v_dst->strides[__pyx_v_new_ndim]) = (__pyx_v_stride * __pyx_v_step); + + /* "View.MemoryView":871 + * + * dst.strides[new_ndim] = stride * step + * dst.shape[new_ndim] = new_shape # <<<<<<<<<<<<<< + * dst.suboffsets[new_ndim] = suboffset + * + */ + (__pyx_v_dst->shape[__pyx_v_new_ndim]) = __pyx_v_new_shape; + + /* "View.MemoryView":872 + * dst.strides[new_ndim] = stride * step + * dst.shape[new_ndim] = new_shape + * dst.suboffsets[new_ndim] = suboffset # <<<<<<<<<<<<<< + * + * + */ + (__pyx_v_dst->suboffsets[__pyx_v_new_ndim]) = __pyx_v_suboffset; + } + __pyx_L3:; + + /* "View.MemoryView":875 + * + * + * if suboffset_dim[0] < 0: # <<<<<<<<<<<<<< + * dst.data += start * stride + * else: + */ + __pyx_t_2 = ((__pyx_v_suboffset_dim[0]) < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":876 + * + * if suboffset_dim[0] < 0: + * dst.data += start * stride # <<<<<<<<<<<<<< + * else: + * dst.suboffsets[suboffset_dim[0]] += start * stride + */ + __pyx_v_dst->data = (__pyx_v_dst->data + (__pyx_v_start * __pyx_v_stride)); + + /* "View.MemoryView":875 + * + * + * if suboffset_dim[0] < 0: # <<<<<<<<<<<<<< + * dst.data += start * stride + * else: + */ + goto __pyx_L19; + } + + /* "View.MemoryView":878 + * dst.data += start * stride + * else: + * dst.suboffsets[suboffset_dim[0]] += start * stride # <<<<<<<<<<<<<< + * + * if suboffset >= 0: + */ + /*else*/ { + __pyx_t_3 = (__pyx_v_suboffset_dim[0]); + (__pyx_v_dst->suboffsets[__pyx_t_3]) = ((__pyx_v_dst->suboffsets[__pyx_t_3]) + (__pyx_v_start * __pyx_v_stride)); + } + __pyx_L19:; + + /* "View.MemoryView":880 + * dst.suboffsets[suboffset_dim[0]] += start * stride + * + * if suboffset >= 0: # <<<<<<<<<<<<<< + * if not is_slice: + * if new_ndim == 0: + */ + __pyx_t_2 = (__pyx_v_suboffset >= 0); + if (__pyx_t_2) { + + /* "View.MemoryView":881 + * + * if suboffset >= 0: + * if not is_slice: # <<<<<<<<<<<<<< + * if new_ndim == 0: + * dst.data = ( dst.data)[0] + suboffset + */ + __pyx_t_2 = (!__pyx_v_is_slice); + if (__pyx_t_2) { + + /* "View.MemoryView":882 + * if suboffset >= 0: + * if not is_slice: + * if new_ndim == 0: # <<<<<<<<<<<<<< + * dst.data = ( dst.data)[0] + suboffset + * else: + */ + __pyx_t_2 = (__pyx_v_new_ndim == 0); + if (__pyx_t_2) { + + /* "View.MemoryView":883 + * if not is_slice: + * if new_ndim == 0: + * dst.data = ( dst.data)[0] + suboffset # <<<<<<<<<<<<<< + * else: + * _err_dim(PyExc_IndexError, "All dimensions preceding dimension %d " + */ + __pyx_v_dst->data = ((((char **)__pyx_v_dst->data)[0]) + __pyx_v_suboffset); + + /* "View.MemoryView":882 + * if suboffset >= 0: + * if not is_slice: + * if new_ndim == 0: # <<<<<<<<<<<<<< + * dst.data = ( dst.data)[0] + suboffset + * else: + */ + goto __pyx_L22; + } + + /* "View.MemoryView":885 + * dst.data = ( dst.data)[0] + suboffset + * else: + * _err_dim(PyExc_IndexError, "All dimensions preceding dimension %d " # <<<<<<<<<<<<<< + * "must be indexed and not sliced", dim) + * else: + */ + /*else*/ { + + /* "View.MemoryView":886 + * else: + * _err_dim(PyExc_IndexError, "All dimensions preceding dimension %d " + * "must be indexed and not sliced", dim) # <<<<<<<<<<<<<< + * else: + * suboffset_dim[0] = new_ndim + */ + __pyx_t_3 = __pyx_memoryview_err_dim(PyExc_IndexError, __pyx_kp_s_All_dimensions_preceding_dimensi, __pyx_v_dim); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(0, 885, __pyx_L1_error) + } + __pyx_L22:; + + /* "View.MemoryView":881 + * + * if suboffset >= 0: + * if not is_slice: # <<<<<<<<<<<<<< + * if new_ndim == 0: + * dst.data = ( dst.data)[0] + suboffset + */ + goto __pyx_L21; + } + + /* "View.MemoryView":888 + * "must be indexed and not sliced", dim) + * else: + * suboffset_dim[0] = new_ndim # <<<<<<<<<<<<<< + * + * return 0 + */ + /*else*/ { + (__pyx_v_suboffset_dim[0]) = __pyx_v_new_ndim; + } + __pyx_L21:; + + /* "View.MemoryView":880 + * dst.suboffsets[suboffset_dim[0]] += start * stride + * + * if suboffset >= 0: # <<<<<<<<<<<<<< + * if not is_slice: + * if new_ndim == 0: + */ + } + + /* "View.MemoryView":890 + * suboffset_dim[0] = new_ndim + * + * return 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":793 + * + * @cname('__pyx_memoryview_slice_memviewslice') + * cdef int slice_memviewslice( # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * Py_ssize_t shape, Py_ssize_t stride, Py_ssize_t suboffset, + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.slice_memviewslice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":896 + * + * @cname('__pyx_pybuffer_index') + * cdef char *pybuffer_index(Py_buffer *view, char *bufp, Py_ssize_t index, # <<<<<<<<<<<<<< + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 + */ + +static char *__pyx_pybuffer_index(Py_buffer *__pyx_v_view, char *__pyx_v_bufp, Py_ssize_t __pyx_v_index, Py_ssize_t __pyx_v_dim) { + Py_ssize_t __pyx_v_shape; + Py_ssize_t __pyx_v_stride; + Py_ssize_t __pyx_v_suboffset; + Py_ssize_t __pyx_v_itemsize; + char *__pyx_v_resultp; + char *__pyx_r; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + Py_UCS4 __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("pybuffer_index", 1); + + /* "View.MemoryView":898 + * cdef char *pybuffer_index(Py_buffer *view, char *bufp, Py_ssize_t index, + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 # <<<<<<<<<<<<<< + * cdef Py_ssize_t itemsize = view.itemsize + * cdef char *resultp + */ + __pyx_v_suboffset = -1L; + + /* "View.MemoryView":899 + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 + * cdef Py_ssize_t itemsize = view.itemsize # <<<<<<<<<<<<<< + * cdef char *resultp + * + */ + __pyx_t_1 = __pyx_v_view->itemsize; + __pyx_v_itemsize = __pyx_t_1; + + /* "View.MemoryView":902 + * cdef char *resultp + * + * if view.ndim == 0: # <<<<<<<<<<<<<< + * shape = view.len // itemsize + * stride = itemsize + */ + __pyx_t_2 = (__pyx_v_view->ndim == 0); + if (__pyx_t_2) { + + /* "View.MemoryView":903 + * + * if view.ndim == 0: + * shape = view.len // itemsize # <<<<<<<<<<<<<< + * stride = itemsize + * else: + */ + if (unlikely(__pyx_v_itemsize == 0)) { + PyErr_SetString(PyExc_ZeroDivisionError, "integer division or modulo by zero"); + __PYX_ERR(0, 903, __pyx_L1_error) + } + else if (sizeof(Py_ssize_t) == sizeof(long) && (!(((Py_ssize_t)-1) > 0)) && unlikely(__pyx_v_itemsize == (Py_ssize_t)-1) && unlikely(__Pyx_UNARY_NEG_WOULD_OVERFLOW(__pyx_v_view->len))) { + PyErr_SetString(PyExc_OverflowError, "value too large to perform division"); + __PYX_ERR(0, 903, __pyx_L1_error) + } + __pyx_v_shape = __Pyx_div_Py_ssize_t(__pyx_v_view->len, __pyx_v_itemsize); + + /* "View.MemoryView":904 + * if view.ndim == 0: + * shape = view.len // itemsize + * stride = itemsize # <<<<<<<<<<<<<< + * else: + * shape = view.shape[dim] + */ + __pyx_v_stride = __pyx_v_itemsize; + + /* "View.MemoryView":902 + * cdef char *resultp + * + * if view.ndim == 0: # <<<<<<<<<<<<<< + * shape = view.len // itemsize + * stride = itemsize + */ + goto __pyx_L3; + } + + /* "View.MemoryView":906 + * stride = itemsize + * else: + * shape = view.shape[dim] # <<<<<<<<<<<<<< + * stride = view.strides[dim] + * if view.suboffsets != NULL: + */ + /*else*/ { + __pyx_v_shape = (__pyx_v_view->shape[__pyx_v_dim]); + + /* "View.MemoryView":907 + * else: + * shape = view.shape[dim] + * stride = view.strides[dim] # <<<<<<<<<<<<<< + * if view.suboffsets != NULL: + * suboffset = view.suboffsets[dim] + */ + __pyx_v_stride = (__pyx_v_view->strides[__pyx_v_dim]); + + /* "View.MemoryView":908 + * shape = view.shape[dim] + * stride = view.strides[dim] + * if view.suboffsets != NULL: # <<<<<<<<<<<<<< + * suboffset = view.suboffsets[dim] + * + */ + __pyx_t_2 = (__pyx_v_view->suboffsets != NULL); + if (__pyx_t_2) { + + /* "View.MemoryView":909 + * stride = view.strides[dim] + * if view.suboffsets != NULL: + * suboffset = view.suboffsets[dim] # <<<<<<<<<<<<<< + * + * if index < 0: + */ + __pyx_v_suboffset = (__pyx_v_view->suboffsets[__pyx_v_dim]); + + /* "View.MemoryView":908 + * shape = view.shape[dim] + * stride = view.strides[dim] + * if view.suboffsets != NULL: # <<<<<<<<<<<<<< + * suboffset = view.suboffsets[dim] + * + */ + } + } + __pyx_L3:; + + /* "View.MemoryView":911 + * suboffset = view.suboffsets[dim] + * + * if index < 0: # <<<<<<<<<<<<<< + * index += view.shape[dim] + * if index < 0: + */ + __pyx_t_2 = (__pyx_v_index < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":912 + * + * if index < 0: + * index += view.shape[dim] # <<<<<<<<<<<<<< + * if index < 0: + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + */ + __pyx_v_index = (__pyx_v_index + (__pyx_v_view->shape[__pyx_v_dim])); + + /* "View.MemoryView":913 + * if index < 0: + * index += view.shape[dim] + * if index < 0: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + __pyx_t_2 = (__pyx_v_index < 0); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":914 + * index += view.shape[dim] + * if index < 0: + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" # <<<<<<<<<<<<<< + * + * if index >= shape: + */ + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 914, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = 0; + __pyx_t_4 = 127; + __Pyx_INCREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_1 += 37; + __Pyx_GIVEREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_5 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_dim, 0, ' ', 'd'); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 914, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_5); + __Pyx_GIVEREF(__pyx_t_5); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_5); + __pyx_t_5 = 0; + __Pyx_INCREF(__pyx_kp_u__7); + __pyx_t_1 += 1; + __Pyx_GIVEREF(__pyx_kp_u__7); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_kp_u__7); + __pyx_t_5 = __Pyx_PyUnicode_Join(__pyx_t_3, 3, __pyx_t_1, __pyx_t_4); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 914, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_builtin_IndexError, __pyx_t_5, 0, 0); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __PYX_ERR(0, 914, __pyx_L1_error) + + /* "View.MemoryView":913 + * if index < 0: + * index += view.shape[dim] + * if index < 0: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + } + + /* "View.MemoryView":911 + * suboffset = view.suboffsets[dim] + * + * if index < 0: # <<<<<<<<<<<<<< + * index += view.shape[dim] + * if index < 0: + */ + } + + /* "View.MemoryView":916 + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + * if index >= shape: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + __pyx_t_2 = (__pyx_v_index >= __pyx_v_shape); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":917 + * + * if index >= shape: + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" # <<<<<<<<<<<<<< + * + * resultp = bufp + index * stride + */ + __pyx_t_5 = PyTuple_New(3); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 917, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 = 0; + __pyx_t_4 = 127; + __Pyx_INCREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_1 += 37; + __Pyx_GIVEREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_3 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_dim, 0, ' ', 'd'); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 917, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_3); + PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_3); + __pyx_t_3 = 0; + __Pyx_INCREF(__pyx_kp_u__7); + __pyx_t_1 += 1; + __Pyx_GIVEREF(__pyx_kp_u__7); + PyTuple_SET_ITEM(__pyx_t_5, 2, __pyx_kp_u__7); + __pyx_t_3 = __Pyx_PyUnicode_Join(__pyx_t_5, 3, __pyx_t_1, __pyx_t_4); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 917, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_Raise(__pyx_builtin_IndexError, __pyx_t_3, 0, 0); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __PYX_ERR(0, 917, __pyx_L1_error) + + /* "View.MemoryView":916 + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + * if index >= shape: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + } + + /* "View.MemoryView":919 + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + * resultp = bufp + index * stride # <<<<<<<<<<<<<< + * if suboffset >= 0: + * resultp = ( resultp)[0] + suboffset + */ + __pyx_v_resultp = (__pyx_v_bufp + (__pyx_v_index * __pyx_v_stride)); + + /* "View.MemoryView":920 + * + * resultp = bufp + index * stride + * if suboffset >= 0: # <<<<<<<<<<<<<< + * resultp = ( resultp)[0] + suboffset + * + */ + __pyx_t_2 = (__pyx_v_suboffset >= 0); + if (__pyx_t_2) { + + /* "View.MemoryView":921 + * resultp = bufp + index * stride + * if suboffset >= 0: + * resultp = ( resultp)[0] + suboffset # <<<<<<<<<<<<<< + * + * return resultp + */ + __pyx_v_resultp = ((((char **)__pyx_v_resultp)[0]) + __pyx_v_suboffset); + + /* "View.MemoryView":920 + * + * resultp = bufp + index * stride + * if suboffset >= 0: # <<<<<<<<<<<<<< + * resultp = ( resultp)[0] + suboffset + * + */ + } + + /* "View.MemoryView":923 + * resultp = ( resultp)[0] + suboffset + * + * return resultp # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = __pyx_v_resultp; + goto __pyx_L0; + + /* "View.MemoryView":896 + * + * @cname('__pyx_pybuffer_index') + * cdef char *pybuffer_index(Py_buffer *view, char *bufp, Py_ssize_t index, # <<<<<<<<<<<<<< + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.pybuffer_index", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":929 + * + * @cname('__pyx_memslice_transpose') + * cdef int transpose_memslice(__Pyx_memviewslice *memslice) except -1 nogil: # <<<<<<<<<<<<<< + * cdef int ndim = memslice.memview.view.ndim + * + */ + +static int __pyx_memslice_transpose(__Pyx_memviewslice *__pyx_v_memslice) { + int __pyx_v_ndim; + Py_ssize_t *__pyx_v_shape; + Py_ssize_t *__pyx_v_strides; + int __pyx_v_i; + int __pyx_v_j; + int __pyx_r; + int __pyx_t_1; + Py_ssize_t *__pyx_t_2; + long __pyx_t_3; + long __pyx_t_4; + Py_ssize_t __pyx_t_5; + Py_ssize_t __pyx_t_6; + int __pyx_t_7; + int __pyx_t_8; + int __pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":930 + * @cname('__pyx_memslice_transpose') + * cdef int transpose_memslice(__Pyx_memviewslice *memslice) except -1 nogil: + * cdef int ndim = memslice.memview.view.ndim # <<<<<<<<<<<<<< + * + * cdef Py_ssize_t *shape = memslice.shape + */ + __pyx_t_1 = __pyx_v_memslice->memview->view.ndim; + __pyx_v_ndim = __pyx_t_1; + + /* "View.MemoryView":932 + * cdef int ndim = memslice.memview.view.ndim + * + * cdef Py_ssize_t *shape = memslice.shape # <<<<<<<<<<<<<< + * cdef Py_ssize_t *strides = memslice.strides + * + */ + __pyx_t_2 = __pyx_v_memslice->shape; + __pyx_v_shape = __pyx_t_2; + + /* "View.MemoryView":933 + * + * cdef Py_ssize_t *shape = memslice.shape + * cdef Py_ssize_t *strides = memslice.strides # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = __pyx_v_memslice->strides; + __pyx_v_strides = __pyx_t_2; + + /* "View.MemoryView":937 + * + * cdef int i, j + * for i in range(ndim // 2): # <<<<<<<<<<<<<< + * j = ndim - 1 - i + * strides[i], strides[j] = strides[j], strides[i] + */ + __pyx_t_3 = __Pyx_div_long(__pyx_v_ndim, 2); + __pyx_t_4 = __pyx_t_3; + for (__pyx_t_1 = 0; __pyx_t_1 < __pyx_t_4; __pyx_t_1+=1) { + __pyx_v_i = __pyx_t_1; + + /* "View.MemoryView":938 + * cdef int i, j + * for i in range(ndim // 2): + * j = ndim - 1 - i # <<<<<<<<<<<<<< + * strides[i], strides[j] = strides[j], strides[i] + * shape[i], shape[j] = shape[j], shape[i] + */ + __pyx_v_j = ((__pyx_v_ndim - 1) - __pyx_v_i); + + /* "View.MemoryView":939 + * for i in range(ndim // 2): + * j = ndim - 1 - i + * strides[i], strides[j] = strides[j], strides[i] # <<<<<<<<<<<<<< + * shape[i], shape[j] = shape[j], shape[i] + * + */ + __pyx_t_5 = (__pyx_v_strides[__pyx_v_j]); + __pyx_t_6 = (__pyx_v_strides[__pyx_v_i]); + (__pyx_v_strides[__pyx_v_i]) = __pyx_t_5; + (__pyx_v_strides[__pyx_v_j]) = __pyx_t_6; + + /* "View.MemoryView":940 + * j = ndim - 1 - i + * strides[i], strides[j] = strides[j], strides[i] + * shape[i], shape[j] = shape[j], shape[i] # <<<<<<<<<<<<<< + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: + */ + __pyx_t_6 = (__pyx_v_shape[__pyx_v_j]); + __pyx_t_5 = (__pyx_v_shape[__pyx_v_i]); + (__pyx_v_shape[__pyx_v_i]) = __pyx_t_6; + (__pyx_v_shape[__pyx_v_j]) = __pyx_t_5; + + /* "View.MemoryView":942 + * shape[i], shape[j] = shape[j], shape[i] + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: # <<<<<<<<<<<<<< + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") + * + */ + __pyx_t_8 = ((__pyx_v_memslice->suboffsets[__pyx_v_i]) >= 0); + if (!__pyx_t_8) { + } else { + __pyx_t_7 = __pyx_t_8; + goto __pyx_L6_bool_binop_done; + } + __pyx_t_8 = ((__pyx_v_memslice->suboffsets[__pyx_v_j]) >= 0); + __pyx_t_7 = __pyx_t_8; + __pyx_L6_bool_binop_done:; + if (__pyx_t_7) { + + /* "View.MemoryView":943 + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") # <<<<<<<<<<<<<< + * + * return 0 + */ + __pyx_t_9 = __pyx_memoryview_err(PyExc_ValueError, __pyx_kp_s_Cannot_transpose_memoryview_with); if (unlikely(__pyx_t_9 == ((int)-1))) __PYX_ERR(0, 943, __pyx_L1_error) + + /* "View.MemoryView":942 + * shape[i], shape[j] = shape[j], shape[i] + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: # <<<<<<<<<<<<<< + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") + * + */ + } + } + + /* "View.MemoryView":945 + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") + * + * return 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":929 + * + * @cname('__pyx_memslice_transpose') + * cdef int transpose_memslice(__Pyx_memviewslice *memslice) except -1 nogil: # <<<<<<<<<<<<<< + * cdef int ndim = memslice.memview.view.ndim + * + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.transpose_memslice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":963 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + */ + +/* Python wrapper */ +static void __pyx_memoryviewslice___dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_memoryviewslice___dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_memoryviewslice___pyx_pf_15View_dot_MemoryView_16_memoryviewslice___dealloc__(((struct __pyx_memoryviewslice_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_memoryviewslice___pyx_pf_15View_dot_MemoryView_16_memoryviewslice___dealloc__(struct __pyx_memoryviewslice_obj *__pyx_v_self) { + + /* "View.MemoryView":964 + * + * def __dealloc__(self): + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) # <<<<<<<<<<<<<< + * + * cdef convert_item_to_object(self, char *itemp): + */ + __PYX_XCLEAR_MEMVIEW((&__pyx_v_self->from_slice), 1); + + /* "View.MemoryView":963 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + */ + + /* function exit code */ +} + +/* "View.MemoryView":966 + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * if self.to_object_func != NULL: + * return self.to_object_func(itemp) + */ + +static PyObject *__pyx_memoryviewslice_convert_item_to_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("convert_item_to_object", 1); + + /* "View.MemoryView":967 + * + * cdef convert_item_to_object(self, char *itemp): + * if self.to_object_func != NULL: # <<<<<<<<<<<<<< + * return self.to_object_func(itemp) + * else: + */ + __pyx_t_1 = (__pyx_v_self->to_object_func != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":968 + * cdef convert_item_to_object(self, char *itemp): + * if self.to_object_func != NULL: + * return self.to_object_func(itemp) # <<<<<<<<<<<<<< + * else: + * return memoryview.convert_item_to_object(self, itemp) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_v_self->to_object_func(__pyx_v_itemp); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 968, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":967 + * + * cdef convert_item_to_object(self, char *itemp): + * if self.to_object_func != NULL: # <<<<<<<<<<<<<< + * return self.to_object_func(itemp) + * else: + */ + } + + /* "View.MemoryView":970 + * return self.to_object_func(itemp) + * else: + * return memoryview.convert_item_to_object(self, itemp) # <<<<<<<<<<<<<< + * + * cdef assign_item_from_object(self, char *itemp, object value): + */ + /*else*/ { + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_memoryview_convert_item_to_object(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v_itemp); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 970, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + } + + /* "View.MemoryView":966 + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * if self.to_object_func != NULL: + * return self.to_object_func(itemp) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.convert_item_to_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":972 + * return memoryview.convert_item_to_object(self, itemp) + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * if self.to_dtype_func != NULL: + * self.to_dtype_func(itemp, value) + */ + +static PyObject *__pyx_memoryviewslice_assign_item_from_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("assign_item_from_object", 1); + + /* "View.MemoryView":973 + * + * cdef assign_item_from_object(self, char *itemp, object value): + * if self.to_dtype_func != NULL: # <<<<<<<<<<<<<< + * self.to_dtype_func(itemp, value) + * else: + */ + __pyx_t_1 = (__pyx_v_self->to_dtype_func != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":974 + * cdef assign_item_from_object(self, char *itemp, object value): + * if self.to_dtype_func != NULL: + * self.to_dtype_func(itemp, value) # <<<<<<<<<<<<<< + * else: + * memoryview.assign_item_from_object(self, itemp, value) + */ + __pyx_t_2 = __pyx_v_self->to_dtype_func(__pyx_v_itemp, __pyx_v_value); if (unlikely(__pyx_t_2 == ((int)0))) __PYX_ERR(0, 974, __pyx_L1_error) + + /* "View.MemoryView":973 + * + * cdef assign_item_from_object(self, char *itemp, object value): + * if self.to_dtype_func != NULL: # <<<<<<<<<<<<<< + * self.to_dtype_func(itemp, value) + * else: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":976 + * self.to_dtype_func(itemp, value) + * else: + * memoryview.assign_item_from_object(self, itemp, value) # <<<<<<<<<<<<<< + * + * cdef _get_base(self): + */ + /*else*/ { + __pyx_t_3 = __pyx_memoryview_assign_item_from_object(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v_itemp, __pyx_v_value); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 976, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_L3:; + + /* "View.MemoryView":972 + * return memoryview.convert_item_to_object(self, itemp) + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * if self.to_dtype_func != NULL: + * self.to_dtype_func(itemp, value) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.assign_item_from_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":978 + * memoryview.assign_item_from_object(self, itemp, value) + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.from_object + * + */ + +static PyObject *__pyx_memoryviewslice__get_base(struct __pyx_memoryviewslice_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("_get_base", 1); + + /* "View.MemoryView":979 + * + * cdef _get_base(self): + * return self.from_object # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->from_object); + __pyx_r = __pyx_v_self->from_object; + goto __pyx_L0; + + /* "View.MemoryView":978 + * memoryview.assign_item_from_object(self, itemp, value) + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.from_object + * + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryviewslice_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryviewslice_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_memoryviewslice___reduce_cython__(((struct __pyx_memoryviewslice_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryviewslice___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(0, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryviewslice_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryviewslice_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(0, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_memoryviewslice_2__setstate_cython__(((struct __pyx_memoryviewslice_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryviewslice_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(0, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":999 + * + * @cname('__pyx_memoryview_fromslice') + * cdef memoryview_fromslice(__Pyx_memviewslice memviewslice, # <<<<<<<<<<<<<< + * int ndim, + * object (*to_object_func)(char *), + */ + +static PyObject *__pyx_memoryview_fromslice(__Pyx_memviewslice __pyx_v_memviewslice, int __pyx_v_ndim, PyObject *(*__pyx_v_to_object_func)(char *), int (*__pyx_v_to_dtype_func)(char *, PyObject *), int __pyx_v_dtype_is_object) { + struct __pyx_memoryviewslice_obj *__pyx_v_result = 0; + Py_ssize_t __pyx_v_suboffset; + PyObject *__pyx_v_length = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + __Pyx_TypeInfo *__pyx_t_4; + Py_buffer __pyx_t_5; + Py_ssize_t *__pyx_t_6; + Py_ssize_t *__pyx_t_7; + Py_ssize_t *__pyx_t_8; + Py_ssize_t __pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_fromslice", 1); + + /* "View.MemoryView":1007 + * cdef _memoryviewslice result + * + * if memviewslice.memview == Py_None: # <<<<<<<<<<<<<< + * return None + * + */ + __pyx_t_1 = (((PyObject *)__pyx_v_memviewslice.memview) == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":1008 + * + * if memviewslice.memview == Py_None: + * return None # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "View.MemoryView":1007 + * cdef _memoryviewslice result + * + * if memviewslice.memview == Py_None: # <<<<<<<<<<<<<< + * return None + * + */ + } + + /* "View.MemoryView":1013 + * + * + * result = _memoryviewslice.__new__(_memoryviewslice, None, 0, dtype_is_object) # <<<<<<<<<<<<<< + * + * result.from_slice = memviewslice + */ + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_v_dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 1013, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 1013, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(Py_None); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, Py_None)) __PYX_ERR(0, 1013, __pyx_L1_error); + __Pyx_INCREF(__pyx_int_0); + __Pyx_GIVEREF(__pyx_int_0); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_int_0)) __PYX_ERR(0, 1013, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_t_2)) __PYX_ERR(0, 1013, __pyx_L1_error); + __pyx_t_2 = 0; + __pyx_t_2 = ((PyObject *)__pyx_tp_new__memoryviewslice(((PyTypeObject *)__pyx_memoryviewslice_type), __pyx_t_3, NULL)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 1013, __pyx_L1_error) + __Pyx_GOTREF((PyObject *)__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_v_result = ((struct __pyx_memoryviewslice_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":1015 + * result = _memoryviewslice.__new__(_memoryviewslice, None, 0, dtype_is_object) + * + * result.from_slice = memviewslice # <<<<<<<<<<<<<< + * __PYX_INC_MEMVIEW(&memviewslice, 1) + * + */ + __pyx_v_result->from_slice = __pyx_v_memviewslice; + + /* "View.MemoryView":1016 + * + * result.from_slice = memviewslice + * __PYX_INC_MEMVIEW(&memviewslice, 1) # <<<<<<<<<<<<<< + * + * result.from_object = ( memviewslice.memview)._get_base() + */ + __PYX_INC_MEMVIEW((&__pyx_v_memviewslice), 1); + + /* "View.MemoryView":1018 + * __PYX_INC_MEMVIEW(&memviewslice, 1) + * + * result.from_object = ( memviewslice.memview)._get_base() # <<<<<<<<<<<<<< + * result.typeinfo = memviewslice.memview.typeinfo + * + */ + __pyx_t_2 = ((struct __pyx_vtabstruct_memoryview *)((struct __pyx_memoryview_obj *)__pyx_v_memviewslice.memview)->__pyx_vtab)->_get_base(((struct __pyx_memoryview_obj *)__pyx_v_memviewslice.memview)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 1018, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + __Pyx_GOTREF(__pyx_v_result->from_object); + __Pyx_DECREF(__pyx_v_result->from_object); + __pyx_v_result->from_object = __pyx_t_2; + __pyx_t_2 = 0; + + /* "View.MemoryView":1019 + * + * result.from_object = ( memviewslice.memview)._get_base() + * result.typeinfo = memviewslice.memview.typeinfo # <<<<<<<<<<<<<< + * + * result.view = memviewslice.memview.view + */ + __pyx_t_4 = __pyx_v_memviewslice.memview->typeinfo; + __pyx_v_result->__pyx_base.typeinfo = __pyx_t_4; + + /* "View.MemoryView":1021 + * result.typeinfo = memviewslice.memview.typeinfo + * + * result.view = memviewslice.memview.view # <<<<<<<<<<<<<< + * result.view.buf = memviewslice.data + * result.view.ndim = ndim + */ + __pyx_t_5 = __pyx_v_memviewslice.memview->view; + __pyx_v_result->__pyx_base.view = __pyx_t_5; + + /* "View.MemoryView":1022 + * + * result.view = memviewslice.memview.view + * result.view.buf = memviewslice.data # <<<<<<<<<<<<<< + * result.view.ndim = ndim + * (<__pyx_buffer *> &result.view).obj = Py_None + */ + __pyx_v_result->__pyx_base.view.buf = ((void *)__pyx_v_memviewslice.data); + + /* "View.MemoryView":1023 + * result.view = memviewslice.memview.view + * result.view.buf = memviewslice.data + * result.view.ndim = ndim # <<<<<<<<<<<<<< + * (<__pyx_buffer *> &result.view).obj = Py_None + * Py_INCREF(Py_None) + */ + __pyx_v_result->__pyx_base.view.ndim = __pyx_v_ndim; + + /* "View.MemoryView":1024 + * result.view.buf = memviewslice.data + * result.view.ndim = ndim + * (<__pyx_buffer *> &result.view).obj = Py_None # <<<<<<<<<<<<<< + * Py_INCREF(Py_None) + * + */ + ((Py_buffer *)(&__pyx_v_result->__pyx_base.view))->obj = Py_None; + + /* "View.MemoryView":1025 + * result.view.ndim = ndim + * (<__pyx_buffer *> &result.view).obj = Py_None + * Py_INCREF(Py_None) # <<<<<<<<<<<<<< + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: + */ + Py_INCREF(Py_None); + + /* "View.MemoryView":1027 + * Py_INCREF(Py_None) + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: # <<<<<<<<<<<<<< + * result.flags = PyBUF_RECORDS + * else: + */ + __pyx_t_1 = ((((struct __pyx_memoryview_obj *)__pyx_v_memviewslice.memview)->flags & PyBUF_WRITABLE) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":1028 + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: + * result.flags = PyBUF_RECORDS # <<<<<<<<<<<<<< + * else: + * result.flags = PyBUF_RECORDS_RO + */ + __pyx_v_result->__pyx_base.flags = PyBUF_RECORDS; + + /* "View.MemoryView":1027 + * Py_INCREF(Py_None) + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: # <<<<<<<<<<<<<< + * result.flags = PyBUF_RECORDS + * else: + */ + goto __pyx_L4; + } + + /* "View.MemoryView":1030 + * result.flags = PyBUF_RECORDS + * else: + * result.flags = PyBUF_RECORDS_RO # <<<<<<<<<<<<<< + * + * result.view.shape = result.from_slice.shape + */ + /*else*/ { + __pyx_v_result->__pyx_base.flags = PyBUF_RECORDS_RO; + } + __pyx_L4:; + + /* "View.MemoryView":1032 + * result.flags = PyBUF_RECORDS_RO + * + * result.view.shape = result.from_slice.shape # <<<<<<<<<<<<<< + * result.view.strides = result.from_slice.strides + * + */ + __pyx_v_result->__pyx_base.view.shape = ((Py_ssize_t *)__pyx_v_result->from_slice.shape); + + /* "View.MemoryView":1033 + * + * result.view.shape = result.from_slice.shape + * result.view.strides = result.from_slice.strides # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_result->__pyx_base.view.strides = ((Py_ssize_t *)__pyx_v_result->from_slice.strides); + + /* "View.MemoryView":1036 + * + * + * result.view.suboffsets = NULL # <<<<<<<<<<<<<< + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: + */ + __pyx_v_result->__pyx_base.view.suboffsets = NULL; + + /* "View.MemoryView":1037 + * + * result.view.suboffsets = NULL + * for suboffset in result.from_slice.suboffsets[:ndim]: # <<<<<<<<<<<<<< + * if suboffset >= 0: + * result.view.suboffsets = result.from_slice.suboffsets + */ + __pyx_t_7 = (__pyx_v_result->from_slice.suboffsets + __pyx_v_ndim); + for (__pyx_t_8 = __pyx_v_result->from_slice.suboffsets; __pyx_t_8 < __pyx_t_7; __pyx_t_8++) { + __pyx_t_6 = __pyx_t_8; + __pyx_v_suboffset = (__pyx_t_6[0]); + + /* "View.MemoryView":1038 + * result.view.suboffsets = NULL + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * result.view.suboffsets = result.from_slice.suboffsets + * break + */ + __pyx_t_1 = (__pyx_v_suboffset >= 0); + if (__pyx_t_1) { + + /* "View.MemoryView":1039 + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: + * result.view.suboffsets = result.from_slice.suboffsets # <<<<<<<<<<<<<< + * break + * + */ + __pyx_v_result->__pyx_base.view.suboffsets = ((Py_ssize_t *)__pyx_v_result->from_slice.suboffsets); + + /* "View.MemoryView":1040 + * if suboffset >= 0: + * result.view.suboffsets = result.from_slice.suboffsets + * break # <<<<<<<<<<<<<< + * + * result.view.len = result.view.itemsize + */ + goto __pyx_L6_break; + + /* "View.MemoryView":1038 + * result.view.suboffsets = NULL + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * result.view.suboffsets = result.from_slice.suboffsets + * break + */ + } + } + __pyx_L6_break:; + + /* "View.MemoryView":1042 + * break + * + * result.view.len = result.view.itemsize # <<<<<<<<<<<<<< + * for length in result.view.shape[:ndim]: + * result.view.len *= length + */ + __pyx_t_9 = __pyx_v_result->__pyx_base.view.itemsize; + __pyx_v_result->__pyx_base.view.len = __pyx_t_9; + + /* "View.MemoryView":1043 + * + * result.view.len = result.view.itemsize + * for length in result.view.shape[:ndim]: # <<<<<<<<<<<<<< + * result.view.len *= length + * + */ + __pyx_t_7 = (__pyx_v_result->__pyx_base.view.shape + __pyx_v_ndim); + for (__pyx_t_8 = __pyx_v_result->__pyx_base.view.shape; __pyx_t_8 < __pyx_t_7; __pyx_t_8++) { + __pyx_t_6 = __pyx_t_8; + __pyx_t_2 = PyInt_FromSsize_t((__pyx_t_6[0])); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 1043, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_XDECREF_SET(__pyx_v_length, __pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":1044 + * result.view.len = result.view.itemsize + * for length in result.view.shape[:ndim]: + * result.view.len *= length # <<<<<<<<<<<<<< + * + * result.to_object_func = to_object_func + */ + __pyx_t_2 = PyInt_FromSsize_t(__pyx_v_result->__pyx_base.view.len); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 1044, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyNumber_InPlaceMultiply(__pyx_t_2, __pyx_v_length); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 1044, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_9 = __Pyx_PyIndex_AsSsize_t(__pyx_t_3); if (unlikely((__pyx_t_9 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 1044, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_v_result->__pyx_base.view.len = __pyx_t_9; + } + + /* "View.MemoryView":1046 + * result.view.len *= length + * + * result.to_object_func = to_object_func # <<<<<<<<<<<<<< + * result.to_dtype_func = to_dtype_func + * + */ + __pyx_v_result->to_object_func = __pyx_v_to_object_func; + + /* "View.MemoryView":1047 + * + * result.to_object_func = to_object_func + * result.to_dtype_func = to_dtype_func # <<<<<<<<<<<<<< + * + * return result + */ + __pyx_v_result->to_dtype_func = __pyx_v_to_dtype_func; + + /* "View.MemoryView":1049 + * result.to_dtype_func = to_dtype_func + * + * return result # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_get_slice_from_memoryview') + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = ((PyObject *)__pyx_v_result); + goto __pyx_L0; + + /* "View.MemoryView":999 + * + * @cname('__pyx_memoryview_fromslice') + * cdef memoryview_fromslice(__Pyx_memviewslice memviewslice, # <<<<<<<<<<<<<< + * int ndim, + * object (*to_object_func)(char *), + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview_fromslice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XDECREF(__pyx_v_length); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1052 + * + * @cname('__pyx_memoryview_get_slice_from_memoryview') + * cdef __Pyx_memviewslice *get_slice_from_memview(memoryview memview, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + */ + +static __Pyx_memviewslice *__pyx_memoryview_get_slice_from_memoryview(struct __pyx_memoryview_obj *__pyx_v_memview, __Pyx_memviewslice *__pyx_v_mslice) { + struct __pyx_memoryviewslice_obj *__pyx_v_obj = 0; + __Pyx_memviewslice *__pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_slice_from_memview", 1); + + /* "View.MemoryView":1055 + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * obj = memview + * return &obj.from_slice + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":1056 + * cdef _memoryviewslice obj + * if isinstance(memview, _memoryviewslice): + * obj = memview # <<<<<<<<<<<<<< + * return &obj.from_slice + * else: + */ + if (!(likely(((((PyObject *)__pyx_v_memview)) == Py_None) || likely(__Pyx_TypeTest(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type))))) __PYX_ERR(0, 1056, __pyx_L1_error) + __pyx_t_2 = ((PyObject *)__pyx_v_memview); + __Pyx_INCREF(__pyx_t_2); + __pyx_v_obj = ((struct __pyx_memoryviewslice_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":1057 + * if isinstance(memview, _memoryviewslice): + * obj = memview + * return &obj.from_slice # <<<<<<<<<<<<<< + * else: + * slice_copy(memview, mslice) + */ + __pyx_r = (&__pyx_v_obj->from_slice); + goto __pyx_L0; + + /* "View.MemoryView":1055 + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * obj = memview + * return &obj.from_slice + */ + } + + /* "View.MemoryView":1059 + * return &obj.from_slice + * else: + * slice_copy(memview, mslice) # <<<<<<<<<<<<<< + * return mslice + * + */ + /*else*/ { + __pyx_memoryview_slice_copy(__pyx_v_memview, __pyx_v_mslice); + + /* "View.MemoryView":1060 + * else: + * slice_copy(memview, mslice) + * return mslice # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_slice_copy') + */ + __pyx_r = __pyx_v_mslice; + goto __pyx_L0; + } + + /* "View.MemoryView":1052 + * + * @cname('__pyx_memoryview_get_slice_from_memoryview') + * cdef __Pyx_memviewslice *get_slice_from_memview(memoryview memview, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.get_slice_from_memview", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_obj); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1063 + * + * @cname('__pyx_memoryview_slice_copy') + * cdef void slice_copy(memoryview memview, __Pyx_memviewslice *dst) noexcept: # <<<<<<<<<<<<<< + * cdef int dim + * cdef (Py_ssize_t*) shape, strides, suboffsets + */ + +static void __pyx_memoryview_slice_copy(struct __pyx_memoryview_obj *__pyx_v_memview, __Pyx_memviewslice *__pyx_v_dst) { + int __pyx_v_dim; + Py_ssize_t *__pyx_v_shape; + Py_ssize_t *__pyx_v_strides; + Py_ssize_t *__pyx_v_suboffsets; + Py_ssize_t *__pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + Py_ssize_t __pyx_t_5; + int __pyx_t_6; + + /* "View.MemoryView":1067 + * cdef (Py_ssize_t*) shape, strides, suboffsets + * + * shape = memview.view.shape # <<<<<<<<<<<<<< + * strides = memview.view.strides + * suboffsets = memview.view.suboffsets + */ + __pyx_t_1 = __pyx_v_memview->view.shape; + __pyx_v_shape = __pyx_t_1; + + /* "View.MemoryView":1068 + * + * shape = memview.view.shape + * strides = memview.view.strides # <<<<<<<<<<<<<< + * suboffsets = memview.view.suboffsets + * + */ + __pyx_t_1 = __pyx_v_memview->view.strides; + __pyx_v_strides = __pyx_t_1; + + /* "View.MemoryView":1069 + * shape = memview.view.shape + * strides = memview.view.strides + * suboffsets = memview.view.suboffsets # <<<<<<<<<<<<<< + * + * dst.memview = <__pyx_memoryview *> memview + */ + __pyx_t_1 = __pyx_v_memview->view.suboffsets; + __pyx_v_suboffsets = __pyx_t_1; + + /* "View.MemoryView":1071 + * suboffsets = memview.view.suboffsets + * + * dst.memview = <__pyx_memoryview *> memview # <<<<<<<<<<<<<< + * dst.data = memview.view.buf + * + */ + __pyx_v_dst->memview = ((struct __pyx_memoryview_obj *)__pyx_v_memview); + + /* "View.MemoryView":1072 + * + * dst.memview = <__pyx_memoryview *> memview + * dst.data = memview.view.buf # <<<<<<<<<<<<<< + * + * for dim in range(memview.view.ndim): + */ + __pyx_v_dst->data = ((char *)__pyx_v_memview->view.buf); + + /* "View.MemoryView":1074 + * dst.data = memview.view.buf + * + * for dim in range(memview.view.ndim): # <<<<<<<<<<<<<< + * dst.shape[dim] = shape[dim] + * dst.strides[dim] = strides[dim] + */ + __pyx_t_2 = __pyx_v_memview->view.ndim; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_dim = __pyx_t_4; + + /* "View.MemoryView":1075 + * + * for dim in range(memview.view.ndim): + * dst.shape[dim] = shape[dim] # <<<<<<<<<<<<<< + * dst.strides[dim] = strides[dim] + * dst.suboffsets[dim] = suboffsets[dim] if suboffsets else -1 + */ + (__pyx_v_dst->shape[__pyx_v_dim]) = (__pyx_v_shape[__pyx_v_dim]); + + /* "View.MemoryView":1076 + * for dim in range(memview.view.ndim): + * dst.shape[dim] = shape[dim] + * dst.strides[dim] = strides[dim] # <<<<<<<<<<<<<< + * dst.suboffsets[dim] = suboffsets[dim] if suboffsets else -1 + * + */ + (__pyx_v_dst->strides[__pyx_v_dim]) = (__pyx_v_strides[__pyx_v_dim]); + + /* "View.MemoryView":1077 + * dst.shape[dim] = shape[dim] + * dst.strides[dim] = strides[dim] + * dst.suboffsets[dim] = suboffsets[dim] if suboffsets else -1 # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_copy_object') + */ + __pyx_t_6 = (__pyx_v_suboffsets != 0); + if (__pyx_t_6) { + __pyx_t_5 = (__pyx_v_suboffsets[__pyx_v_dim]); + } else { + __pyx_t_5 = -1L; + } + (__pyx_v_dst->suboffsets[__pyx_v_dim]) = __pyx_t_5; + } + + /* "View.MemoryView":1063 + * + * @cname('__pyx_memoryview_slice_copy') + * cdef void slice_copy(memoryview memview, __Pyx_memviewslice *dst) noexcept: # <<<<<<<<<<<<<< + * cdef int dim + * cdef (Py_ssize_t*) shape, strides, suboffsets + */ + + /* function exit code */ +} + +/* "View.MemoryView":1080 + * + * @cname('__pyx_memoryview_copy_object') + * cdef memoryview_copy(memoryview memview): # <<<<<<<<<<<<<< + * "Create a new memoryview object" + * cdef __Pyx_memviewslice memviewslice + */ + +static PyObject *__pyx_memoryview_copy_object(struct __pyx_memoryview_obj *__pyx_v_memview) { + __Pyx_memviewslice __pyx_v_memviewslice; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_copy", 1); + + /* "View.MemoryView":1083 + * "Create a new memoryview object" + * cdef __Pyx_memviewslice memviewslice + * slice_copy(memview, &memviewslice) # <<<<<<<<<<<<<< + * return memoryview_copy_from_slice(memview, &memviewslice) + * + */ + __pyx_memoryview_slice_copy(__pyx_v_memview, (&__pyx_v_memviewslice)); + + /* "View.MemoryView":1084 + * cdef __Pyx_memviewslice memviewslice + * slice_copy(memview, &memviewslice) + * return memoryview_copy_from_slice(memview, &memviewslice) # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_copy_object_from_slice') + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __pyx_memoryview_copy_object_from_slice(__pyx_v_memview, (&__pyx_v_memviewslice)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 1084, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":1080 + * + * @cname('__pyx_memoryview_copy_object') + * cdef memoryview_copy(memoryview memview): # <<<<<<<<<<<<<< + * "Create a new memoryview object" + * cdef __Pyx_memviewslice memviewslice + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview_copy", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1087 + * + * @cname('__pyx_memoryview_copy_object_from_slice') + * cdef memoryview_copy_from_slice(memoryview memview, __Pyx_memviewslice *memviewslice): # <<<<<<<<<<<<<< + * """ + * Create a new memoryview object from a given memoryview object and slice. + */ + +static PyObject *__pyx_memoryview_copy_object_from_slice(struct __pyx_memoryview_obj *__pyx_v_memview, __Pyx_memviewslice *__pyx_v_memviewslice) { + PyObject *(*__pyx_v_to_object_func)(char *); + int (*__pyx_v_to_dtype_func)(char *, PyObject *); + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *(*__pyx_t_2)(char *); + int (*__pyx_t_3)(char *, PyObject *); + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_copy_from_slice", 1); + + /* "View.MemoryView":1094 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * to_object_func = (<_memoryviewslice> memview).to_object_func + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":1095 + * + * if isinstance(memview, _memoryviewslice): + * to_object_func = (<_memoryviewslice> memview).to_object_func # <<<<<<<<<<<<<< + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + * else: + */ + __pyx_t_2 = ((struct __pyx_memoryviewslice_obj *)__pyx_v_memview)->to_object_func; + __pyx_v_to_object_func = __pyx_t_2; + + /* "View.MemoryView":1096 + * if isinstance(memview, _memoryviewslice): + * to_object_func = (<_memoryviewslice> memview).to_object_func + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func # <<<<<<<<<<<<<< + * else: + * to_object_func = NULL + */ + __pyx_t_3 = ((struct __pyx_memoryviewslice_obj *)__pyx_v_memview)->to_dtype_func; + __pyx_v_to_dtype_func = __pyx_t_3; + + /* "View.MemoryView":1094 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * to_object_func = (<_memoryviewslice> memview).to_object_func + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1098 + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + * else: + * to_object_func = NULL # <<<<<<<<<<<<<< + * to_dtype_func = NULL + * + */ + /*else*/ { + __pyx_v_to_object_func = NULL; + + /* "View.MemoryView":1099 + * else: + * to_object_func = NULL + * to_dtype_func = NULL # <<<<<<<<<<<<<< + * + * return memoryview_fromslice(memviewslice[0], memview.view.ndim, + */ + __pyx_v_to_dtype_func = NULL; + } + __pyx_L3:; + + /* "View.MemoryView":1101 + * to_dtype_func = NULL + * + * return memoryview_fromslice(memviewslice[0], memview.view.ndim, # <<<<<<<<<<<<<< + * to_object_func, to_dtype_func, + * memview.dtype_is_object) + */ + __Pyx_XDECREF(__pyx_r); + + /* "View.MemoryView":1103 + * return memoryview_fromslice(memviewslice[0], memview.view.ndim, + * to_object_func, to_dtype_func, + * memview.dtype_is_object) # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_4 = __pyx_memoryview_fromslice((__pyx_v_memviewslice[0]), __pyx_v_memview->view.ndim, __pyx_v_to_object_func, __pyx_v_to_dtype_func, __pyx_v_memview->dtype_is_object); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 1101, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_r = __pyx_t_4; + __pyx_t_4 = 0; + goto __pyx_L0; + + /* "View.MemoryView":1087 + * + * @cname('__pyx_memoryview_copy_object_from_slice') + * cdef memoryview_copy_from_slice(memoryview memview, __Pyx_memviewslice *memviewslice): # <<<<<<<<<<<<<< + * """ + * Create a new memoryview object from a given memoryview object and slice. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.memoryview_copy_from_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1109 + * + * + * cdef Py_ssize_t abs_py_ssize_t(Py_ssize_t arg) noexcept nogil: # <<<<<<<<<<<<<< + * return -arg if arg < 0 else arg + * + */ + +static Py_ssize_t abs_py_ssize_t(Py_ssize_t __pyx_v_arg) { + Py_ssize_t __pyx_r; + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + + /* "View.MemoryView":1110 + * + * cdef Py_ssize_t abs_py_ssize_t(Py_ssize_t arg) noexcept nogil: + * return -arg if arg < 0 else arg # <<<<<<<<<<<<<< + * + * @cname('__pyx_get_best_slice_order') + */ + __pyx_t_2 = (__pyx_v_arg < 0); + if (__pyx_t_2) { + __pyx_t_1 = (-__pyx_v_arg); + } else { + __pyx_t_1 = __pyx_v_arg; + } + __pyx_r = __pyx_t_1; + goto __pyx_L0; + + /* "View.MemoryView":1109 + * + * + * cdef Py_ssize_t abs_py_ssize_t(Py_ssize_t arg) noexcept nogil: # <<<<<<<<<<<<<< + * return -arg if arg < 0 else arg + * + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1113 + * + * @cname('__pyx_get_best_slice_order') + * cdef char get_best_order(__Pyx_memviewslice *mslice, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * """ + * Figure out the best memory access order for a given slice. + */ + +static char __pyx_get_best_slice_order(__Pyx_memviewslice *__pyx_v_mslice, int __pyx_v_ndim) { + int __pyx_v_i; + Py_ssize_t __pyx_v_c_stride; + Py_ssize_t __pyx_v_f_stride; + char __pyx_r; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + + /* "View.MemoryView":1118 + * """ + * cdef int i + * cdef Py_ssize_t c_stride = 0 # <<<<<<<<<<<<<< + * cdef Py_ssize_t f_stride = 0 + * + */ + __pyx_v_c_stride = 0; + + /* "View.MemoryView":1119 + * cdef int i + * cdef Py_ssize_t c_stride = 0 + * cdef Py_ssize_t f_stride = 0 # <<<<<<<<<<<<<< + * + * for i in range(ndim - 1, -1, -1): + */ + __pyx_v_f_stride = 0; + + /* "View.MemoryView":1121 + * cdef Py_ssize_t f_stride = 0 + * + * for i in range(ndim - 1, -1, -1): # <<<<<<<<<<<<<< + * if mslice.shape[i] > 1: + * c_stride = mslice.strides[i] + */ + for (__pyx_t_1 = (__pyx_v_ndim - 1); __pyx_t_1 > -1; __pyx_t_1-=1) { + __pyx_v_i = __pyx_t_1; + + /* "View.MemoryView":1122 + * + * for i in range(ndim - 1, -1, -1): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * c_stride = mslice.strides[i] + * break + */ + __pyx_t_2 = ((__pyx_v_mslice->shape[__pyx_v_i]) > 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1123 + * for i in range(ndim - 1, -1, -1): + * if mslice.shape[i] > 1: + * c_stride = mslice.strides[i] # <<<<<<<<<<<<<< + * break + * + */ + __pyx_v_c_stride = (__pyx_v_mslice->strides[__pyx_v_i]); + + /* "View.MemoryView":1124 + * if mslice.shape[i] > 1: + * c_stride = mslice.strides[i] + * break # <<<<<<<<<<<<<< + * + * for i in range(ndim): + */ + goto __pyx_L4_break; + + /* "View.MemoryView":1122 + * + * for i in range(ndim - 1, -1, -1): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * c_stride = mslice.strides[i] + * break + */ + } + } + __pyx_L4_break:; + + /* "View.MemoryView":1126 + * break + * + * for i in range(ndim): # <<<<<<<<<<<<<< + * if mslice.shape[i] > 1: + * f_stride = mslice.strides[i] + */ + __pyx_t_1 = __pyx_v_ndim; + __pyx_t_3 = __pyx_t_1; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1127 + * + * for i in range(ndim): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * f_stride = mslice.strides[i] + * break + */ + __pyx_t_2 = ((__pyx_v_mslice->shape[__pyx_v_i]) > 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1128 + * for i in range(ndim): + * if mslice.shape[i] > 1: + * f_stride = mslice.strides[i] # <<<<<<<<<<<<<< + * break + * + */ + __pyx_v_f_stride = (__pyx_v_mslice->strides[__pyx_v_i]); + + /* "View.MemoryView":1129 + * if mslice.shape[i] > 1: + * f_stride = mslice.strides[i] + * break # <<<<<<<<<<<<<< + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): + */ + goto __pyx_L7_break; + + /* "View.MemoryView":1127 + * + * for i in range(ndim): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * f_stride = mslice.strides[i] + * break + */ + } + } + __pyx_L7_break:; + + /* "View.MemoryView":1131 + * break + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): # <<<<<<<<<<<<<< + * return 'C' + * else: + */ + __pyx_t_2 = (abs_py_ssize_t(__pyx_v_c_stride) <= abs_py_ssize_t(__pyx_v_f_stride)); + if (__pyx_t_2) { + + /* "View.MemoryView":1132 + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): + * return 'C' # <<<<<<<<<<<<<< + * else: + * return 'F' + */ + __pyx_r = 'C'; + goto __pyx_L0; + + /* "View.MemoryView":1131 + * break + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): # <<<<<<<<<<<<<< + * return 'C' + * else: + */ + } + + /* "View.MemoryView":1134 + * return 'C' + * else: + * return 'F' # <<<<<<<<<<<<<< + * + * @cython.cdivision(True) + */ + /*else*/ { + __pyx_r = 'F'; + goto __pyx_L0; + } + + /* "View.MemoryView":1113 + * + * @cname('__pyx_get_best_slice_order') + * cdef char get_best_order(__Pyx_memviewslice *mslice, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * """ + * Figure out the best memory access order for a given slice. + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1137 + * + * @cython.cdivision(True) + * cdef void _copy_strided_to_strided(char *src_data, Py_ssize_t *src_strides, # <<<<<<<<<<<<<< + * char *dst_data, Py_ssize_t *dst_strides, + * Py_ssize_t *src_shape, Py_ssize_t *dst_shape, + */ + +static void _copy_strided_to_strided(char *__pyx_v_src_data, Py_ssize_t *__pyx_v_src_strides, char *__pyx_v_dst_data, Py_ssize_t *__pyx_v_dst_strides, Py_ssize_t *__pyx_v_src_shape, Py_ssize_t *__pyx_v_dst_shape, int __pyx_v_ndim, size_t __pyx_v_itemsize) { + CYTHON_UNUSED Py_ssize_t __pyx_v_i; + CYTHON_UNUSED Py_ssize_t __pyx_v_src_extent; + Py_ssize_t __pyx_v_dst_extent; + Py_ssize_t __pyx_v_src_stride; + Py_ssize_t __pyx_v_dst_stride; + int __pyx_t_1; + int __pyx_t_2; + Py_ssize_t __pyx_t_3; + Py_ssize_t __pyx_t_4; + Py_ssize_t __pyx_t_5; + + /* "View.MemoryView":1144 + * + * cdef Py_ssize_t i + * cdef Py_ssize_t src_extent = src_shape[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t dst_extent = dst_shape[0] + * cdef Py_ssize_t src_stride = src_strides[0] + */ + __pyx_v_src_extent = (__pyx_v_src_shape[0]); + + /* "View.MemoryView":1145 + * cdef Py_ssize_t i + * cdef Py_ssize_t src_extent = src_shape[0] + * cdef Py_ssize_t dst_extent = dst_shape[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t src_stride = src_strides[0] + * cdef Py_ssize_t dst_stride = dst_strides[0] + */ + __pyx_v_dst_extent = (__pyx_v_dst_shape[0]); + + /* "View.MemoryView":1146 + * cdef Py_ssize_t src_extent = src_shape[0] + * cdef Py_ssize_t dst_extent = dst_shape[0] + * cdef Py_ssize_t src_stride = src_strides[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t dst_stride = dst_strides[0] + * + */ + __pyx_v_src_stride = (__pyx_v_src_strides[0]); + + /* "View.MemoryView":1147 + * cdef Py_ssize_t dst_extent = dst_shape[0] + * cdef Py_ssize_t src_stride = src_strides[0] + * cdef Py_ssize_t dst_stride = dst_strides[0] # <<<<<<<<<<<<<< + * + * if ndim == 1: + */ + __pyx_v_dst_stride = (__pyx_v_dst_strides[0]); + + /* "View.MemoryView":1149 + * cdef Py_ssize_t dst_stride = dst_strides[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): + */ + __pyx_t_1 = (__pyx_v_ndim == 1); + if (__pyx_t_1) { + + /* "View.MemoryView":1150 + * + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and # <<<<<<<<<<<<<< + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) + */ + __pyx_t_2 = (__pyx_v_src_stride > 0); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L5_bool_binop_done; + } + __pyx_t_2 = (__pyx_v_dst_stride > 0); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L5_bool_binop_done; + } + + /* "View.MemoryView":1151 + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): # <<<<<<<<<<<<<< + * memcpy(dst_data, src_data, itemsize * dst_extent) + * else: + */ + __pyx_t_2 = (((size_t)__pyx_v_src_stride) == __pyx_v_itemsize); + if (__pyx_t_2) { + __pyx_t_2 = (__pyx_v_itemsize == ((size_t)__pyx_v_dst_stride)); + } + __pyx_t_1 = __pyx_t_2; + __pyx_L5_bool_binop_done:; + + /* "View.MemoryView":1150 + * + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and # <<<<<<<<<<<<<< + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) + */ + if (__pyx_t_1) { + + /* "View.MemoryView":1152 + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) # <<<<<<<<<<<<<< + * else: + * for i in range(dst_extent): + */ + (void)(memcpy(__pyx_v_dst_data, __pyx_v_src_data, (__pyx_v_itemsize * __pyx_v_dst_extent))); + + /* "View.MemoryView":1150 + * + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and # <<<<<<<<<<<<<< + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) + */ + goto __pyx_L4; + } + + /* "View.MemoryView":1154 + * memcpy(dst_data, src_data, itemsize * dst_extent) + * else: + * for i in range(dst_extent): # <<<<<<<<<<<<<< + * memcpy(dst_data, src_data, itemsize) + * src_data += src_stride + */ + /*else*/ { + __pyx_t_3 = __pyx_v_dst_extent; + __pyx_t_4 = __pyx_t_3; + for (__pyx_t_5 = 0; __pyx_t_5 < __pyx_t_4; __pyx_t_5+=1) { + __pyx_v_i = __pyx_t_5; + + /* "View.MemoryView":1155 + * else: + * for i in range(dst_extent): + * memcpy(dst_data, src_data, itemsize) # <<<<<<<<<<<<<< + * src_data += src_stride + * dst_data += dst_stride + */ + (void)(memcpy(__pyx_v_dst_data, __pyx_v_src_data, __pyx_v_itemsize)); + + /* "View.MemoryView":1156 + * for i in range(dst_extent): + * memcpy(dst_data, src_data, itemsize) + * src_data += src_stride # <<<<<<<<<<<<<< + * dst_data += dst_stride + * else: + */ + __pyx_v_src_data = (__pyx_v_src_data + __pyx_v_src_stride); + + /* "View.MemoryView":1157 + * memcpy(dst_data, src_data, itemsize) + * src_data += src_stride + * dst_data += dst_stride # <<<<<<<<<<<<<< + * else: + * for i in range(dst_extent): + */ + __pyx_v_dst_data = (__pyx_v_dst_data + __pyx_v_dst_stride); + } + } + __pyx_L4:; + + /* "View.MemoryView":1149 + * cdef Py_ssize_t dst_stride = dst_strides[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1159 + * dst_data += dst_stride + * else: + * for i in range(dst_extent): # <<<<<<<<<<<<<< + * _copy_strided_to_strided(src_data, src_strides + 1, + * dst_data, dst_strides + 1, + */ + /*else*/ { + __pyx_t_3 = __pyx_v_dst_extent; + __pyx_t_4 = __pyx_t_3; + for (__pyx_t_5 = 0; __pyx_t_5 < __pyx_t_4; __pyx_t_5+=1) { + __pyx_v_i = __pyx_t_5; + + /* "View.MemoryView":1160 + * else: + * for i in range(dst_extent): + * _copy_strided_to_strided(src_data, src_strides + 1, # <<<<<<<<<<<<<< + * dst_data, dst_strides + 1, + * src_shape + 1, dst_shape + 1, + */ + _copy_strided_to_strided(__pyx_v_src_data, (__pyx_v_src_strides + 1), __pyx_v_dst_data, (__pyx_v_dst_strides + 1), (__pyx_v_src_shape + 1), (__pyx_v_dst_shape + 1), (__pyx_v_ndim - 1), __pyx_v_itemsize); + + /* "View.MemoryView":1164 + * src_shape + 1, dst_shape + 1, + * ndim - 1, itemsize) + * src_data += src_stride # <<<<<<<<<<<<<< + * dst_data += dst_stride + * + */ + __pyx_v_src_data = (__pyx_v_src_data + __pyx_v_src_stride); + + /* "View.MemoryView":1165 + * ndim - 1, itemsize) + * src_data += src_stride + * dst_data += dst_stride # <<<<<<<<<<<<<< + * + * cdef void copy_strided_to_strided(__Pyx_memviewslice *src, + */ + __pyx_v_dst_data = (__pyx_v_dst_data + __pyx_v_dst_stride); + } + } + __pyx_L3:; + + /* "View.MemoryView":1137 + * + * @cython.cdivision(True) + * cdef void _copy_strided_to_strided(char *src_data, Py_ssize_t *src_strides, # <<<<<<<<<<<<<< + * char *dst_data, Py_ssize_t *dst_strides, + * Py_ssize_t *src_shape, Py_ssize_t *dst_shape, + */ + + /* function exit code */ +} + +/* "View.MemoryView":1167 + * dst_data += dst_stride + * + * cdef void copy_strided_to_strided(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * int ndim, size_t itemsize) noexcept nogil: + */ + +static void copy_strided_to_strided(__Pyx_memviewslice *__pyx_v_src, __Pyx_memviewslice *__pyx_v_dst, int __pyx_v_ndim, size_t __pyx_v_itemsize) { + + /* "View.MemoryView":1170 + * __Pyx_memviewslice *dst, + * int ndim, size_t itemsize) noexcept nogil: + * _copy_strided_to_strided(src.data, src.strides, dst.data, dst.strides, # <<<<<<<<<<<<<< + * src.shape, dst.shape, ndim, itemsize) + * + */ + _copy_strided_to_strided(__pyx_v_src->data, __pyx_v_src->strides, __pyx_v_dst->data, __pyx_v_dst->strides, __pyx_v_src->shape, __pyx_v_dst->shape, __pyx_v_ndim, __pyx_v_itemsize); + + /* "View.MemoryView":1167 + * dst_data += dst_stride + * + * cdef void copy_strided_to_strided(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * int ndim, size_t itemsize) noexcept nogil: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1174 + * + * @cname('__pyx_memoryview_slice_get_size') + * cdef Py_ssize_t slice_get_size(__Pyx_memviewslice *src, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * "Return the size of the memory occupied by the slice in number of bytes" + * cdef Py_ssize_t shape, size = src.memview.view.itemsize + */ + +static Py_ssize_t __pyx_memoryview_slice_get_size(__Pyx_memviewslice *__pyx_v_src, int __pyx_v_ndim) { + Py_ssize_t __pyx_v_shape; + Py_ssize_t __pyx_v_size; + Py_ssize_t __pyx_r; + Py_ssize_t __pyx_t_1; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + + /* "View.MemoryView":1176 + * cdef Py_ssize_t slice_get_size(__Pyx_memviewslice *src, int ndim) noexcept nogil: + * "Return the size of the memory occupied by the slice in number of bytes" + * cdef Py_ssize_t shape, size = src.memview.view.itemsize # <<<<<<<<<<<<<< + * + * for shape in src.shape[:ndim]: + */ + __pyx_t_1 = __pyx_v_src->memview->view.itemsize; + __pyx_v_size = __pyx_t_1; + + /* "View.MemoryView":1178 + * cdef Py_ssize_t shape, size = src.memview.view.itemsize + * + * for shape in src.shape[:ndim]: # <<<<<<<<<<<<<< + * size *= shape + * + */ + __pyx_t_3 = (__pyx_v_src->shape + __pyx_v_ndim); + for (__pyx_t_4 = __pyx_v_src->shape; __pyx_t_4 < __pyx_t_3; __pyx_t_4++) { + __pyx_t_2 = __pyx_t_4; + __pyx_v_shape = (__pyx_t_2[0]); + + /* "View.MemoryView":1179 + * + * for shape in src.shape[:ndim]: + * size *= shape # <<<<<<<<<<<<<< + * + * return size + */ + __pyx_v_size = (__pyx_v_size * __pyx_v_shape); + } + + /* "View.MemoryView":1181 + * size *= shape + * + * return size # <<<<<<<<<<<<<< + * + * @cname('__pyx_fill_contig_strides_array') + */ + __pyx_r = __pyx_v_size; + goto __pyx_L0; + + /* "View.MemoryView":1174 + * + * @cname('__pyx_memoryview_slice_get_size') + * cdef Py_ssize_t slice_get_size(__Pyx_memviewslice *src, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * "Return the size of the memory occupied by the slice in number of bytes" + * cdef Py_ssize_t shape, size = src.memview.view.itemsize + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1184 + * + * @cname('__pyx_fill_contig_strides_array') + * cdef Py_ssize_t fill_contig_strides_array( # <<<<<<<<<<<<<< + * Py_ssize_t *shape, Py_ssize_t *strides, Py_ssize_t stride, + * int ndim, char order) noexcept nogil: + */ + +static Py_ssize_t __pyx_fill_contig_strides_array(Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, Py_ssize_t __pyx_v_stride, int __pyx_v_ndim, char __pyx_v_order) { + int __pyx_v_idx; + Py_ssize_t __pyx_r; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + + /* "View.MemoryView":1193 + * cdef int idx + * + * if order == 'F': # <<<<<<<<<<<<<< + * for idx in range(ndim): + * strides[idx] = stride + */ + __pyx_t_1 = (__pyx_v_order == 'F'); + if (__pyx_t_1) { + + /* "View.MemoryView":1194 + * + * if order == 'F': + * for idx in range(ndim): # <<<<<<<<<<<<<< + * strides[idx] = stride + * stride *= shape[idx] + */ + __pyx_t_2 = __pyx_v_ndim; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_idx = __pyx_t_4; + + /* "View.MemoryView":1195 + * if order == 'F': + * for idx in range(ndim): + * strides[idx] = stride # <<<<<<<<<<<<<< + * stride *= shape[idx] + * else: + */ + (__pyx_v_strides[__pyx_v_idx]) = __pyx_v_stride; + + /* "View.MemoryView":1196 + * for idx in range(ndim): + * strides[idx] = stride + * stride *= shape[idx] # <<<<<<<<<<<<<< + * else: + * for idx in range(ndim - 1, -1, -1): + */ + __pyx_v_stride = (__pyx_v_stride * (__pyx_v_shape[__pyx_v_idx])); + } + + /* "View.MemoryView":1193 + * cdef int idx + * + * if order == 'F': # <<<<<<<<<<<<<< + * for idx in range(ndim): + * strides[idx] = stride + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1198 + * stride *= shape[idx] + * else: + * for idx in range(ndim - 1, -1, -1): # <<<<<<<<<<<<<< + * strides[idx] = stride + * stride *= shape[idx] + */ + /*else*/ { + for (__pyx_t_2 = (__pyx_v_ndim - 1); __pyx_t_2 > -1; __pyx_t_2-=1) { + __pyx_v_idx = __pyx_t_2; + + /* "View.MemoryView":1199 + * else: + * for idx in range(ndim - 1, -1, -1): + * strides[idx] = stride # <<<<<<<<<<<<<< + * stride *= shape[idx] + * + */ + (__pyx_v_strides[__pyx_v_idx]) = __pyx_v_stride; + + /* "View.MemoryView":1200 + * for idx in range(ndim - 1, -1, -1): + * strides[idx] = stride + * stride *= shape[idx] # <<<<<<<<<<<<<< + * + * return stride + */ + __pyx_v_stride = (__pyx_v_stride * (__pyx_v_shape[__pyx_v_idx])); + } + } + __pyx_L3:; + + /* "View.MemoryView":1202 + * stride *= shape[idx] + * + * return stride # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_copy_data_to_temp') + */ + __pyx_r = __pyx_v_stride; + goto __pyx_L0; + + /* "View.MemoryView":1184 + * + * @cname('__pyx_fill_contig_strides_array') + * cdef Py_ssize_t fill_contig_strides_array( # <<<<<<<<<<<<<< + * Py_ssize_t *shape, Py_ssize_t *strides, Py_ssize_t stride, + * int ndim, char order) noexcept nogil: + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1205 + * + * @cname('__pyx_memoryview_copy_data_to_temp') + * cdef void *copy_data_to_temp(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *tmpslice, + * char order, + */ + +static void *__pyx_memoryview_copy_data_to_temp(__Pyx_memviewslice *__pyx_v_src, __Pyx_memviewslice *__pyx_v_tmpslice, char __pyx_v_order, int __pyx_v_ndim) { + int __pyx_v_i; + void *__pyx_v_result; + size_t __pyx_v_itemsize; + size_t __pyx_v_size; + void *__pyx_r; + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + struct __pyx_memoryview_obj *__pyx_t_4; + int __pyx_t_5; + int __pyx_t_6; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":1216 + * cdef void *result + * + * cdef size_t itemsize = src.memview.view.itemsize # <<<<<<<<<<<<<< + * cdef size_t size = slice_get_size(src, ndim) + * + */ + __pyx_t_1 = __pyx_v_src->memview->view.itemsize; + __pyx_v_itemsize = __pyx_t_1; + + /* "View.MemoryView":1217 + * + * cdef size_t itemsize = src.memview.view.itemsize + * cdef size_t size = slice_get_size(src, ndim) # <<<<<<<<<<<<<< + * + * result = malloc(size) + */ + __pyx_v_size = __pyx_memoryview_slice_get_size(__pyx_v_src, __pyx_v_ndim); + + /* "View.MemoryView":1219 + * cdef size_t size = slice_get_size(src, ndim) + * + * result = malloc(size) # <<<<<<<<<<<<<< + * if not result: + * _err_no_memory() + */ + __pyx_v_result = malloc(__pyx_v_size); + + /* "View.MemoryView":1220 + * + * result = malloc(size) + * if not result: # <<<<<<<<<<<<<< + * _err_no_memory() + * + */ + __pyx_t_2 = (!(__pyx_v_result != 0)); + if (__pyx_t_2) { + + /* "View.MemoryView":1221 + * result = malloc(size) + * if not result: + * _err_no_memory() # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_3 = __pyx_memoryview_err_no_memory(); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(0, 1221, __pyx_L1_error) + + /* "View.MemoryView":1220 + * + * result = malloc(size) + * if not result: # <<<<<<<<<<<<<< + * _err_no_memory() + * + */ + } + + /* "View.MemoryView":1224 + * + * + * tmpslice.data = result # <<<<<<<<<<<<<< + * tmpslice.memview = src.memview + * for i in range(ndim): + */ + __pyx_v_tmpslice->data = ((char *)__pyx_v_result); + + /* "View.MemoryView":1225 + * + * tmpslice.data = result + * tmpslice.memview = src.memview # <<<<<<<<<<<<<< + * for i in range(ndim): + * tmpslice.shape[i] = src.shape[i] + */ + __pyx_t_4 = __pyx_v_src->memview; + __pyx_v_tmpslice->memview = __pyx_t_4; + + /* "View.MemoryView":1226 + * tmpslice.data = result + * tmpslice.memview = src.memview + * for i in range(ndim): # <<<<<<<<<<<<<< + * tmpslice.shape[i] = src.shape[i] + * tmpslice.suboffsets[i] = -1 + */ + __pyx_t_3 = __pyx_v_ndim; + __pyx_t_5 = __pyx_t_3; + for (__pyx_t_6 = 0; __pyx_t_6 < __pyx_t_5; __pyx_t_6+=1) { + __pyx_v_i = __pyx_t_6; + + /* "View.MemoryView":1227 + * tmpslice.memview = src.memview + * for i in range(ndim): + * tmpslice.shape[i] = src.shape[i] # <<<<<<<<<<<<<< + * tmpslice.suboffsets[i] = -1 + * + */ + (__pyx_v_tmpslice->shape[__pyx_v_i]) = (__pyx_v_src->shape[__pyx_v_i]); + + /* "View.MemoryView":1228 + * for i in range(ndim): + * tmpslice.shape[i] = src.shape[i] + * tmpslice.suboffsets[i] = -1 # <<<<<<<<<<<<<< + * + * fill_contig_strides_array(&tmpslice.shape[0], &tmpslice.strides[0], itemsize, ndim, order) + */ + (__pyx_v_tmpslice->suboffsets[__pyx_v_i]) = -1L; + } + + /* "View.MemoryView":1230 + * tmpslice.suboffsets[i] = -1 + * + * fill_contig_strides_array(&tmpslice.shape[0], &tmpslice.strides[0], itemsize, ndim, order) # <<<<<<<<<<<<<< + * + * + */ + (void)(__pyx_fill_contig_strides_array((&(__pyx_v_tmpslice->shape[0])), (&(__pyx_v_tmpslice->strides[0])), __pyx_v_itemsize, __pyx_v_ndim, __pyx_v_order)); + + /* "View.MemoryView":1233 + * + * + * for i in range(ndim): # <<<<<<<<<<<<<< + * if tmpslice.shape[i] == 1: + * tmpslice.strides[i] = 0 + */ + __pyx_t_3 = __pyx_v_ndim; + __pyx_t_5 = __pyx_t_3; + for (__pyx_t_6 = 0; __pyx_t_6 < __pyx_t_5; __pyx_t_6+=1) { + __pyx_v_i = __pyx_t_6; + + /* "View.MemoryView":1234 + * + * for i in range(ndim): + * if tmpslice.shape[i] == 1: # <<<<<<<<<<<<<< + * tmpslice.strides[i] = 0 + * + */ + __pyx_t_2 = ((__pyx_v_tmpslice->shape[__pyx_v_i]) == 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1235 + * for i in range(ndim): + * if tmpslice.shape[i] == 1: + * tmpslice.strides[i] = 0 # <<<<<<<<<<<<<< + * + * if slice_is_contig(src[0], order, ndim): + */ + (__pyx_v_tmpslice->strides[__pyx_v_i]) = 0; + + /* "View.MemoryView":1234 + * + * for i in range(ndim): + * if tmpslice.shape[i] == 1: # <<<<<<<<<<<<<< + * tmpslice.strides[i] = 0 + * + */ + } + } + + /* "View.MemoryView":1237 + * tmpslice.strides[i] = 0 + * + * if slice_is_contig(src[0], order, ndim): # <<<<<<<<<<<<<< + * memcpy(result, src.data, size) + * else: + */ + __pyx_t_2 = __pyx_memviewslice_is_contig((__pyx_v_src[0]), __pyx_v_order, __pyx_v_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1238 + * + * if slice_is_contig(src[0], order, ndim): + * memcpy(result, src.data, size) # <<<<<<<<<<<<<< + * else: + * copy_strided_to_strided(src, tmpslice, ndim, itemsize) + */ + (void)(memcpy(__pyx_v_result, __pyx_v_src->data, __pyx_v_size)); + + /* "View.MemoryView":1237 + * tmpslice.strides[i] = 0 + * + * if slice_is_contig(src[0], order, ndim): # <<<<<<<<<<<<<< + * memcpy(result, src.data, size) + * else: + */ + goto __pyx_L9; + } + + /* "View.MemoryView":1240 + * memcpy(result, src.data, size) + * else: + * copy_strided_to_strided(src, tmpslice, ndim, itemsize) # <<<<<<<<<<<<<< + * + * return result + */ + /*else*/ { + copy_strided_to_strided(__pyx_v_src, __pyx_v_tmpslice, __pyx_v_ndim, __pyx_v_itemsize); + } + __pyx_L9:; + + /* "View.MemoryView":1242 + * copy_strided_to_strided(src, tmpslice, ndim, itemsize) + * + * return result # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = __pyx_v_result; + goto __pyx_L0; + + /* "View.MemoryView":1205 + * + * @cname('__pyx_memoryview_copy_data_to_temp') + * cdef void *copy_data_to_temp(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *tmpslice, + * char order, + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.copy_data_to_temp", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1247 + * + * @cname('__pyx_memoryview_err_extents') + * cdef int _err_extents(int i, Py_ssize_t extent1, # <<<<<<<<<<<<<< + * Py_ssize_t extent2) except -1 with gil: + * raise ValueError, f"got differing extents in dimension {i} (got {extent1} and {extent2})" + */ + +static int __pyx_memoryview_err_extents(int __pyx_v_i, Py_ssize_t __pyx_v_extent1, Py_ssize_t __pyx_v_extent2) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + Py_ssize_t __pyx_t_2; + Py_UCS4 __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_RefNannySetupContext("_err_extents", 0); + + /* "View.MemoryView":1249 + * cdef int _err_extents(int i, Py_ssize_t extent1, + * Py_ssize_t extent2) except -1 with gil: + * raise ValueError, f"got differing extents in dimension {i} (got {extent1} and {extent2})" # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_err_dim') + */ + __pyx_t_1 = PyTuple_New(7); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = 0; + __pyx_t_3 = 127; + __Pyx_INCREF(__pyx_kp_u_got_differing_extents_in_dimensi); + __pyx_t_2 += 35; + __Pyx_GIVEREF(__pyx_kp_u_got_differing_extents_in_dimensi); + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_kp_u_got_differing_extents_in_dimensi); + __pyx_t_4 = __Pyx_PyUnicode_From_int(__pyx_v_i, 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_2 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_t_4); + __pyx_t_4 = 0; + __Pyx_INCREF(__pyx_kp_u_got); + __pyx_t_2 += 6; + __Pyx_GIVEREF(__pyx_kp_u_got); + PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_kp_u_got); + __pyx_t_4 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_extent1, 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_2 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_1, 3, __pyx_t_4); + __pyx_t_4 = 0; + __Pyx_INCREF(__pyx_kp_u_and); + __pyx_t_2 += 5; + __Pyx_GIVEREF(__pyx_kp_u_and); + PyTuple_SET_ITEM(__pyx_t_1, 4, __pyx_kp_u_and); + __pyx_t_4 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_extent2, 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_2 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_1, 5, __pyx_t_4); + __pyx_t_4 = 0; + __Pyx_INCREF(__pyx_kp_u__7); + __pyx_t_2 += 1; + __Pyx_GIVEREF(__pyx_kp_u__7); + PyTuple_SET_ITEM(__pyx_t_1, 6, __pyx_kp_u__7); + __pyx_t_4 = __Pyx_PyUnicode_Join(__pyx_t_1, 7, __pyx_t_2, __pyx_t_3); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_t_4, 0, 0); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __PYX_ERR(0, 1249, __pyx_L1_error) + + /* "View.MemoryView":1247 + * + * @cname('__pyx_memoryview_err_extents') + * cdef int _err_extents(int i, Py_ssize_t extent1, # <<<<<<<<<<<<<< + * Py_ssize_t extent2) except -1 with gil: + * raise ValueError, f"got differing extents in dimension {i} (got {extent1} and {extent2})" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView._err_extents", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __Pyx_RefNannyFinishContext(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1252 + * + * @cname('__pyx_memoryview_err_dim') + * cdef int _err_dim(PyObject *error, str msg, int dim) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg % dim + * + */ + +static int __pyx_memoryview_err_dim(PyObject *__pyx_v_error, PyObject *__pyx_v_msg, int __pyx_v_dim) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_RefNannySetupContext("_err_dim", 0); + __Pyx_INCREF(__pyx_v_msg); + + /* "View.MemoryView":1253 + * @cname('__pyx_memoryview_err_dim') + * cdef int _err_dim(PyObject *error, str msg, int dim) except -1 with gil: + * raise error, msg % dim # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_err') + */ + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_dim); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 1253, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyString_FormatSafe(__pyx_v_msg, __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 1253, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(((PyObject *)__pyx_v_error), __pyx_t_2, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 1253, __pyx_L1_error) + + /* "View.MemoryView":1252 + * + * @cname('__pyx_memoryview_err_dim') + * cdef int _err_dim(PyObject *error, str msg, int dim) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg % dim + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView._err_dim", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __Pyx_XDECREF(__pyx_v_msg); + __Pyx_RefNannyFinishContext(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1256 + * + * @cname('__pyx_memoryview_err') + * cdef int _err(PyObject *error, str msg) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg + * + */ + +static int __pyx_memoryview_err(PyObject *__pyx_v_error, PyObject *__pyx_v_msg) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_RefNannySetupContext("_err", 0); + __Pyx_INCREF(__pyx_v_msg); + + /* "View.MemoryView":1257 + * @cname('__pyx_memoryview_err') + * cdef int _err(PyObject *error, str msg) except -1 with gil: + * raise error, msg # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_err_no_memory') + */ + __Pyx_Raise(((PyObject *)__pyx_v_error), __pyx_v_msg, 0, 0); + __PYX_ERR(0, 1257, __pyx_L1_error) + + /* "View.MemoryView":1256 + * + * @cname('__pyx_memoryview_err') + * cdef int _err(PyObject *error, str msg) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._err", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __Pyx_XDECREF(__pyx_v_msg); + __Pyx_RefNannyFinishContext(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1260 + * + * @cname('__pyx_memoryview_err_no_memory') + * cdef int _err_no_memory() except -1 with gil: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + +static int __pyx_memoryview_err_no_memory(void) { + int __pyx_r; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + + /* "View.MemoryView":1261 + * @cname('__pyx_memoryview_err_no_memory') + * cdef int _err_no_memory() except -1 with gil: + * raise MemoryError # <<<<<<<<<<<<<< + * + * + */ + PyErr_NoMemory(); __PYX_ERR(0, 1261, __pyx_L1_error) + + /* "View.MemoryView":1260 + * + * @cname('__pyx_memoryview_err_no_memory') + * cdef int _err_no_memory() except -1 with gil: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._err_no_memory", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1265 + * + * @cname('__pyx_memoryview_copy_contents') + * cdef int memoryview_copy_contents(__Pyx_memviewslice src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice dst, + * int src_ndim, int dst_ndim, + */ + +static int __pyx_memoryview_copy_contents(__Pyx_memviewslice __pyx_v_src, __Pyx_memviewslice __pyx_v_dst, int __pyx_v_src_ndim, int __pyx_v_dst_ndim, int __pyx_v_dtype_is_object) { + void *__pyx_v_tmpdata; + size_t __pyx_v_itemsize; + int __pyx_v_i; + char __pyx_v_order; + int __pyx_v_broadcasting; + int __pyx_v_direct_copy; + __Pyx_memviewslice __pyx_v_tmp; + int __pyx_v_ndim; + int __pyx_r; + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + int __pyx_t_5; + int __pyx_t_6; + void *__pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":1273 + * Check for overlapping memory and verify the shapes. + * """ + * cdef void *tmpdata = NULL # <<<<<<<<<<<<<< + * cdef size_t itemsize = src.memview.view.itemsize + * cdef int i + */ + __pyx_v_tmpdata = NULL; + + /* "View.MemoryView":1274 + * """ + * cdef void *tmpdata = NULL + * cdef size_t itemsize = src.memview.view.itemsize # <<<<<<<<<<<<<< + * cdef int i + * cdef char order = get_best_order(&src, src_ndim) + */ + __pyx_t_1 = __pyx_v_src.memview->view.itemsize; + __pyx_v_itemsize = __pyx_t_1; + + /* "View.MemoryView":1276 + * cdef size_t itemsize = src.memview.view.itemsize + * cdef int i + * cdef char order = get_best_order(&src, src_ndim) # <<<<<<<<<<<<<< + * cdef bint broadcasting = False + * cdef bint direct_copy = False + */ + __pyx_v_order = __pyx_get_best_slice_order((&__pyx_v_src), __pyx_v_src_ndim); + + /* "View.MemoryView":1277 + * cdef int i + * cdef char order = get_best_order(&src, src_ndim) + * cdef bint broadcasting = False # <<<<<<<<<<<<<< + * cdef bint direct_copy = False + * cdef __Pyx_memviewslice tmp + */ + __pyx_v_broadcasting = 0; + + /* "View.MemoryView":1278 + * cdef char order = get_best_order(&src, src_ndim) + * cdef bint broadcasting = False + * cdef bint direct_copy = False # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice tmp + * + */ + __pyx_v_direct_copy = 0; + + /* "View.MemoryView":1281 + * cdef __Pyx_memviewslice tmp + * + * if src_ndim < dst_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: + */ + __pyx_t_2 = (__pyx_v_src_ndim < __pyx_v_dst_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1282 + * + * if src_ndim < dst_ndim: + * broadcast_leading(&src, src_ndim, dst_ndim) # <<<<<<<<<<<<<< + * elif dst_ndim < src_ndim: + * broadcast_leading(&dst, dst_ndim, src_ndim) + */ + __pyx_memoryview_broadcast_leading((&__pyx_v_src), __pyx_v_src_ndim, __pyx_v_dst_ndim); + + /* "View.MemoryView":1281 + * cdef __Pyx_memviewslice tmp + * + * if src_ndim < dst_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1283 + * if src_ndim < dst_ndim: + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&dst, dst_ndim, src_ndim) + * + */ + __pyx_t_2 = (__pyx_v_dst_ndim < __pyx_v_src_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1284 + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: + * broadcast_leading(&dst, dst_ndim, src_ndim) # <<<<<<<<<<<<<< + * + * cdef int ndim = max(src_ndim, dst_ndim) + */ + __pyx_memoryview_broadcast_leading((&__pyx_v_dst), __pyx_v_dst_ndim, __pyx_v_src_ndim); + + /* "View.MemoryView":1283 + * if src_ndim < dst_ndim: + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&dst, dst_ndim, src_ndim) + * + */ + } + __pyx_L3:; + + /* "View.MemoryView":1286 + * broadcast_leading(&dst, dst_ndim, src_ndim) + * + * cdef int ndim = max(src_ndim, dst_ndim) # <<<<<<<<<<<<<< + * + * for i in range(ndim): + */ + __pyx_t_3 = __pyx_v_dst_ndim; + __pyx_t_4 = __pyx_v_src_ndim; + __pyx_t_2 = (__pyx_t_3 > __pyx_t_4); + if (__pyx_t_2) { + __pyx_t_5 = __pyx_t_3; + } else { + __pyx_t_5 = __pyx_t_4; + } + __pyx_v_ndim = __pyx_t_5; + + /* "View.MemoryView":1288 + * cdef int ndim = max(src_ndim, dst_ndim) + * + * for i in range(ndim): # <<<<<<<<<<<<<< + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: + */ + __pyx_t_5 = __pyx_v_ndim; + __pyx_t_3 = __pyx_t_5; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1289 + * + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: # <<<<<<<<<<<<<< + * if src.shape[i] == 1: + * broadcasting = True + */ + __pyx_t_2 = ((__pyx_v_src.shape[__pyx_v_i]) != (__pyx_v_dst.shape[__pyx_v_i])); + if (__pyx_t_2) { + + /* "View.MemoryView":1290 + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: # <<<<<<<<<<<<<< + * broadcasting = True + * src.strides[i] = 0 + */ + __pyx_t_2 = ((__pyx_v_src.shape[__pyx_v_i]) == 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1291 + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: + * broadcasting = True # <<<<<<<<<<<<<< + * src.strides[i] = 0 + * else: + */ + __pyx_v_broadcasting = 1; + + /* "View.MemoryView":1292 + * if src.shape[i] == 1: + * broadcasting = True + * src.strides[i] = 0 # <<<<<<<<<<<<<< + * else: + * _err_extents(i, dst.shape[i], src.shape[i]) + */ + (__pyx_v_src.strides[__pyx_v_i]) = 0; + + /* "View.MemoryView":1290 + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: # <<<<<<<<<<<<<< + * broadcasting = True + * src.strides[i] = 0 + */ + goto __pyx_L7; + } + + /* "View.MemoryView":1294 + * src.strides[i] = 0 + * else: + * _err_extents(i, dst.shape[i], src.shape[i]) # <<<<<<<<<<<<<< + * + * if src.suboffsets[i] >= 0: + */ + /*else*/ { + __pyx_t_6 = __pyx_memoryview_err_extents(__pyx_v_i, (__pyx_v_dst.shape[__pyx_v_i]), (__pyx_v_src.shape[__pyx_v_i])); if (unlikely(__pyx_t_6 == ((int)-1))) __PYX_ERR(0, 1294, __pyx_L1_error) + } + __pyx_L7:; + + /* "View.MemoryView":1289 + * + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: # <<<<<<<<<<<<<< + * if src.shape[i] == 1: + * broadcasting = True + */ + } + + /* "View.MemoryView":1296 + * _err_extents(i, dst.shape[i], src.shape[i]) + * + * if src.suboffsets[i] >= 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + */ + __pyx_t_2 = ((__pyx_v_src.suboffsets[__pyx_v_i]) >= 0); + if (__pyx_t_2) { + + /* "View.MemoryView":1297 + * + * if src.suboffsets[i] >= 0: + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) # <<<<<<<<<<<<<< + * + * if slices_overlap(&src, &dst, ndim, itemsize): + */ + __pyx_t_6 = __pyx_memoryview_err_dim(PyExc_ValueError, __pyx_kp_s_Dimension_d_is_not_direct, __pyx_v_i); if (unlikely(__pyx_t_6 == ((int)-1))) __PYX_ERR(0, 1297, __pyx_L1_error) + + /* "View.MemoryView":1296 + * _err_extents(i, dst.shape[i], src.shape[i]) + * + * if src.suboffsets[i] >= 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + */ + } + } + + /* "View.MemoryView":1299 + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + * if slices_overlap(&src, &dst, ndim, itemsize): # <<<<<<<<<<<<<< + * + * if not slice_is_contig(src, order, ndim): + */ + __pyx_t_2 = __pyx_slices_overlap((&__pyx_v_src), (&__pyx_v_dst), __pyx_v_ndim, __pyx_v_itemsize); + if (__pyx_t_2) { + + /* "View.MemoryView":1301 + * if slices_overlap(&src, &dst, ndim, itemsize): + * + * if not slice_is_contig(src, order, ndim): # <<<<<<<<<<<<<< + * order = get_best_order(&dst, ndim) + * + */ + __pyx_t_2 = (!__pyx_memviewslice_is_contig(__pyx_v_src, __pyx_v_order, __pyx_v_ndim)); + if (__pyx_t_2) { + + /* "View.MemoryView":1302 + * + * if not slice_is_contig(src, order, ndim): + * order = get_best_order(&dst, ndim) # <<<<<<<<<<<<<< + * + * tmpdata = copy_data_to_temp(&src, &tmp, order, ndim) + */ + __pyx_v_order = __pyx_get_best_slice_order((&__pyx_v_dst), __pyx_v_ndim); + + /* "View.MemoryView":1301 + * if slices_overlap(&src, &dst, ndim, itemsize): + * + * if not slice_is_contig(src, order, ndim): # <<<<<<<<<<<<<< + * order = get_best_order(&dst, ndim) + * + */ + } + + /* "View.MemoryView":1304 + * order = get_best_order(&dst, ndim) + * + * tmpdata = copy_data_to_temp(&src, &tmp, order, ndim) # <<<<<<<<<<<<<< + * src = tmp + * + */ + __pyx_t_7 = __pyx_memoryview_copy_data_to_temp((&__pyx_v_src), (&__pyx_v_tmp), __pyx_v_order, __pyx_v_ndim); if (unlikely(__pyx_t_7 == ((void *)NULL))) __PYX_ERR(0, 1304, __pyx_L1_error) + __pyx_v_tmpdata = __pyx_t_7; + + /* "View.MemoryView":1305 + * + * tmpdata = copy_data_to_temp(&src, &tmp, order, ndim) + * src = tmp # <<<<<<<<<<<<<< + * + * if not broadcasting: + */ + __pyx_v_src = __pyx_v_tmp; + + /* "View.MemoryView":1299 + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + * if slices_overlap(&src, &dst, ndim, itemsize): # <<<<<<<<<<<<<< + * + * if not slice_is_contig(src, order, ndim): + */ + } + + /* "View.MemoryView":1307 + * src = tmp + * + * if not broadcasting: # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = (!__pyx_v_broadcasting); + if (__pyx_t_2) { + + /* "View.MemoryView":1310 + * + * + * if slice_is_contig(src, 'C', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): + */ + __pyx_t_2 = __pyx_memviewslice_is_contig(__pyx_v_src, 'C', __pyx_v_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1311 + * + * if slice_is_contig(src, 'C', ndim): + * direct_copy = slice_is_contig(dst, 'C', ndim) # <<<<<<<<<<<<<< + * elif slice_is_contig(src, 'F', ndim): + * direct_copy = slice_is_contig(dst, 'F', ndim) + */ + __pyx_v_direct_copy = __pyx_memviewslice_is_contig(__pyx_v_dst, 'C', __pyx_v_ndim); + + /* "View.MemoryView":1310 + * + * + * if slice_is_contig(src, 'C', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): + */ + goto __pyx_L12; + } + + /* "View.MemoryView":1312 + * if slice_is_contig(src, 'C', ndim): + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + */ + __pyx_t_2 = __pyx_memviewslice_is_contig(__pyx_v_src, 'F', __pyx_v_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1313 + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): + * direct_copy = slice_is_contig(dst, 'F', ndim) # <<<<<<<<<<<<<< + * + * if direct_copy: + */ + __pyx_v_direct_copy = __pyx_memviewslice_is_contig(__pyx_v_dst, 'F', __pyx_v_ndim); + + /* "View.MemoryView":1312 + * if slice_is_contig(src, 'C', ndim): + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + */ + } + __pyx_L12:; + + /* "View.MemoryView":1315 + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + * if direct_copy: # <<<<<<<<<<<<<< + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + */ + if (__pyx_v_direct_copy) { + + /* "View.MemoryView":1317 + * if direct_copy: + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) # <<<<<<<<<<<<<< + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 0); + + /* "View.MemoryView":1318 + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) # <<<<<<<<<<<<<< + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * free(tmpdata) + */ + (void)(memcpy(__pyx_v_dst.data, __pyx_v_src.data, __pyx_memoryview_slice_get_size((&__pyx_v_src), __pyx_v_ndim))); + + /* "View.MemoryView":1319 + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) # <<<<<<<<<<<<<< + * free(tmpdata) + * return 0 + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 1); + + /* "View.MemoryView":1320 + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * free(tmpdata) # <<<<<<<<<<<<<< + * return 0 + * + */ + free(__pyx_v_tmpdata); + + /* "View.MemoryView":1321 + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * free(tmpdata) + * return 0 # <<<<<<<<<<<<<< + * + * if order == 'F' == get_best_order(&dst, ndim): + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":1315 + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + * if direct_copy: # <<<<<<<<<<<<<< + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + */ + } + + /* "View.MemoryView":1307 + * src = tmp + * + * if not broadcasting: # <<<<<<<<<<<<<< + * + * + */ + } + + /* "View.MemoryView":1323 + * return 0 + * + * if order == 'F' == get_best_order(&dst, ndim): # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = (__pyx_v_order == 'F'); + if (__pyx_t_2) { + __pyx_t_2 = ('F' == __pyx_get_best_slice_order((&__pyx_v_dst), __pyx_v_ndim)); + } + if (__pyx_t_2) { + + /* "View.MemoryView":1326 + * + * + * transpose_memslice(&src) # <<<<<<<<<<<<<< + * transpose_memslice(&dst) + * + */ + __pyx_t_5 = __pyx_memslice_transpose((&__pyx_v_src)); if (unlikely(__pyx_t_5 == ((int)-1))) __PYX_ERR(0, 1326, __pyx_L1_error) + + /* "View.MemoryView":1327 + * + * transpose_memslice(&src) + * transpose_memslice(&dst) # <<<<<<<<<<<<<< + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + */ + __pyx_t_5 = __pyx_memslice_transpose((&__pyx_v_dst)); if (unlikely(__pyx_t_5 == ((int)-1))) __PYX_ERR(0, 1327, __pyx_L1_error) + + /* "View.MemoryView":1323 + * return 0 + * + * if order == 'F' == get_best_order(&dst, ndim): # <<<<<<<<<<<<<< + * + * + */ + } + + /* "View.MemoryView":1329 + * transpose_memslice(&dst) + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) # <<<<<<<<<<<<<< + * copy_strided_to_strided(&src, &dst, ndim, itemsize) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 0); + + /* "View.MemoryView":1330 + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * copy_strided_to_strided(&src, &dst, ndim, itemsize) # <<<<<<<<<<<<<< + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * + */ + copy_strided_to_strided((&__pyx_v_src), (&__pyx_v_dst), __pyx_v_ndim, __pyx_v_itemsize); + + /* "View.MemoryView":1331 + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * copy_strided_to_strided(&src, &dst, ndim, itemsize) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) # <<<<<<<<<<<<<< + * + * free(tmpdata) + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 1); + + /* "View.MemoryView":1333 + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * + * free(tmpdata) # <<<<<<<<<<<<<< + * return 0 + * + */ + free(__pyx_v_tmpdata); + + /* "View.MemoryView":1334 + * + * free(tmpdata) + * return 0 # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_broadcast_leading') + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":1265 + * + * @cname('__pyx_memoryview_copy_contents') + * cdef int memoryview_copy_contents(__Pyx_memviewslice src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice dst, + * int src_ndim, int dst_ndim, + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.memoryview_copy_contents", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1337 + * + * @cname('__pyx_memoryview_broadcast_leading') + * cdef void broadcast_leading(__Pyx_memviewslice *mslice, # <<<<<<<<<<<<<< + * int ndim, + * int ndim_other) noexcept nogil: + */ + +static void __pyx_memoryview_broadcast_leading(__Pyx_memviewslice *__pyx_v_mslice, int __pyx_v_ndim, int __pyx_v_ndim_other) { + int __pyx_v_i; + int __pyx_v_offset; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + + /* "View.MemoryView":1341 + * int ndim_other) noexcept nogil: + * cdef int i + * cdef int offset = ndim_other - ndim # <<<<<<<<<<<<<< + * + * for i in range(ndim - 1, -1, -1): + */ + __pyx_v_offset = (__pyx_v_ndim_other - __pyx_v_ndim); + + /* "View.MemoryView":1343 + * cdef int offset = ndim_other - ndim + * + * for i in range(ndim - 1, -1, -1): # <<<<<<<<<<<<<< + * mslice.shape[i + offset] = mslice.shape[i] + * mslice.strides[i + offset] = mslice.strides[i] + */ + for (__pyx_t_1 = (__pyx_v_ndim - 1); __pyx_t_1 > -1; __pyx_t_1-=1) { + __pyx_v_i = __pyx_t_1; + + /* "View.MemoryView":1344 + * + * for i in range(ndim - 1, -1, -1): + * mslice.shape[i + offset] = mslice.shape[i] # <<<<<<<<<<<<<< + * mslice.strides[i + offset] = mslice.strides[i] + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] + */ + (__pyx_v_mslice->shape[(__pyx_v_i + __pyx_v_offset)]) = (__pyx_v_mslice->shape[__pyx_v_i]); + + /* "View.MemoryView":1345 + * for i in range(ndim - 1, -1, -1): + * mslice.shape[i + offset] = mslice.shape[i] + * mslice.strides[i + offset] = mslice.strides[i] # <<<<<<<<<<<<<< + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] + * + */ + (__pyx_v_mslice->strides[(__pyx_v_i + __pyx_v_offset)]) = (__pyx_v_mslice->strides[__pyx_v_i]); + + /* "View.MemoryView":1346 + * mslice.shape[i + offset] = mslice.shape[i] + * mslice.strides[i + offset] = mslice.strides[i] + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] # <<<<<<<<<<<<<< + * + * for i in range(offset): + */ + (__pyx_v_mslice->suboffsets[(__pyx_v_i + __pyx_v_offset)]) = (__pyx_v_mslice->suboffsets[__pyx_v_i]); + } + + /* "View.MemoryView":1348 + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] + * + * for i in range(offset): # <<<<<<<<<<<<<< + * mslice.shape[i] = 1 + * mslice.strides[i] = mslice.strides[0] + */ + __pyx_t_1 = __pyx_v_offset; + __pyx_t_2 = __pyx_t_1; + for (__pyx_t_3 = 0; __pyx_t_3 < __pyx_t_2; __pyx_t_3+=1) { + __pyx_v_i = __pyx_t_3; + + /* "View.MemoryView":1349 + * + * for i in range(offset): + * mslice.shape[i] = 1 # <<<<<<<<<<<<<< + * mslice.strides[i] = mslice.strides[0] + * mslice.suboffsets[i] = -1 + */ + (__pyx_v_mslice->shape[__pyx_v_i]) = 1; + + /* "View.MemoryView":1350 + * for i in range(offset): + * mslice.shape[i] = 1 + * mslice.strides[i] = mslice.strides[0] # <<<<<<<<<<<<<< + * mslice.suboffsets[i] = -1 + * + */ + (__pyx_v_mslice->strides[__pyx_v_i]) = (__pyx_v_mslice->strides[0]); + + /* "View.MemoryView":1351 + * mslice.shape[i] = 1 + * mslice.strides[i] = mslice.strides[0] + * mslice.suboffsets[i] = -1 # <<<<<<<<<<<<<< + * + * + */ + (__pyx_v_mslice->suboffsets[__pyx_v_i]) = -1L; + } + + /* "View.MemoryView":1337 + * + * @cname('__pyx_memoryview_broadcast_leading') + * cdef void broadcast_leading(__Pyx_memviewslice *mslice, # <<<<<<<<<<<<<< + * int ndim, + * int ndim_other) noexcept nogil: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1359 + * + * @cname('__pyx_memoryview_refcount_copying') + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: # <<<<<<<<<<<<<< + * + * if dtype_is_object: + */ + +static void __pyx_memoryview_refcount_copying(__Pyx_memviewslice *__pyx_v_dst, int __pyx_v_dtype_is_object, int __pyx_v_ndim, int __pyx_v_inc) { + + /* "View.MemoryView":1361 + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: + * + * if dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice_with_gil(dst.data, dst.shape, dst.strides, ndim, inc) + * + */ + if (__pyx_v_dtype_is_object) { + + /* "View.MemoryView":1362 + * + * if dtype_is_object: + * refcount_objects_in_slice_with_gil(dst.data, dst.shape, dst.strides, ndim, inc) # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_refcount_objects_in_slice_with_gil') + */ + __pyx_memoryview_refcount_objects_in_slice_with_gil(__pyx_v_dst->data, __pyx_v_dst->shape, __pyx_v_dst->strides, __pyx_v_ndim, __pyx_v_inc); + + /* "View.MemoryView":1361 + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: + * + * if dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice_with_gil(dst.data, dst.shape, dst.strides, ndim, inc) + * + */ + } + + /* "View.MemoryView":1359 + * + * @cname('__pyx_memoryview_refcount_copying') + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: # <<<<<<<<<<<<<< + * + * if dtype_is_object: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1365 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice_with_gil') + * cdef void refcount_objects_in_slice_with_gil(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * bint inc) noexcept with gil: + */ + +static void __pyx_memoryview_refcount_objects_in_slice_with_gil(char *__pyx_v_data, Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, int __pyx_v_ndim, int __pyx_v_inc) { + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + + /* "View.MemoryView":1368 + * Py_ssize_t *strides, int ndim, + * bint inc) noexcept with gil: + * refcount_objects_in_slice(data, shape, strides, ndim, inc) # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_refcount_objects_in_slice') + */ + __pyx_memoryview_refcount_objects_in_slice(__pyx_v_data, __pyx_v_shape, __pyx_v_strides, __pyx_v_ndim, __pyx_v_inc); + + /* "View.MemoryView":1365 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice_with_gil') + * cdef void refcount_objects_in_slice_with_gil(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * bint inc) noexcept with gil: + */ + + /* function exit code */ + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif +} + +/* "View.MemoryView":1371 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice') + * cdef void refcount_objects_in_slice(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, bint inc) noexcept: + * cdef Py_ssize_t i + */ + +static void __pyx_memoryview_refcount_objects_in_slice(char *__pyx_v_data, Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, int __pyx_v_ndim, int __pyx_v_inc) { + CYTHON_UNUSED Py_ssize_t __pyx_v_i; + Py_ssize_t __pyx_v_stride; + Py_ssize_t __pyx_t_1; + Py_ssize_t __pyx_t_2; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + + /* "View.MemoryView":1374 + * Py_ssize_t *strides, int ndim, bint inc) noexcept: + * cdef Py_ssize_t i + * cdef Py_ssize_t stride = strides[0] # <<<<<<<<<<<<<< + * + * for i in range(shape[0]): + */ + __pyx_v_stride = (__pyx_v_strides[0]); + + /* "View.MemoryView":1376 + * cdef Py_ssize_t stride = strides[0] + * + * for i in range(shape[0]): # <<<<<<<<<<<<<< + * if ndim == 1: + * if inc: + */ + __pyx_t_1 = (__pyx_v_shape[0]); + __pyx_t_2 = __pyx_t_1; + for (__pyx_t_3 = 0; __pyx_t_3 < __pyx_t_2; __pyx_t_3+=1) { + __pyx_v_i = __pyx_t_3; + + /* "View.MemoryView":1377 + * + * for i in range(shape[0]): + * if ndim == 1: # <<<<<<<<<<<<<< + * if inc: + * Py_INCREF(( data)[0]) + */ + __pyx_t_4 = (__pyx_v_ndim == 1); + if (__pyx_t_4) { + + /* "View.MemoryView":1378 + * for i in range(shape[0]): + * if ndim == 1: + * if inc: # <<<<<<<<<<<<<< + * Py_INCREF(( data)[0]) + * else: + */ + if (__pyx_v_inc) { + + /* "View.MemoryView":1379 + * if ndim == 1: + * if inc: + * Py_INCREF(( data)[0]) # <<<<<<<<<<<<<< + * else: + * Py_DECREF(( data)[0]) + */ + Py_INCREF((((PyObject **)__pyx_v_data)[0])); + + /* "View.MemoryView":1378 + * for i in range(shape[0]): + * if ndim == 1: + * if inc: # <<<<<<<<<<<<<< + * Py_INCREF(( data)[0]) + * else: + */ + goto __pyx_L6; + } + + /* "View.MemoryView":1381 + * Py_INCREF(( data)[0]) + * else: + * Py_DECREF(( data)[0]) # <<<<<<<<<<<<<< + * else: + * refcount_objects_in_slice(data, shape + 1, strides + 1, ndim - 1, inc) + */ + /*else*/ { + Py_DECREF((((PyObject **)__pyx_v_data)[0])); + } + __pyx_L6:; + + /* "View.MemoryView":1377 + * + * for i in range(shape[0]): + * if ndim == 1: # <<<<<<<<<<<<<< + * if inc: + * Py_INCREF(( data)[0]) + */ + goto __pyx_L5; + } + + /* "View.MemoryView":1383 + * Py_DECREF(( data)[0]) + * else: + * refcount_objects_in_slice(data, shape + 1, strides + 1, ndim - 1, inc) # <<<<<<<<<<<<<< + * + * data += stride + */ + /*else*/ { + __pyx_memoryview_refcount_objects_in_slice(__pyx_v_data, (__pyx_v_shape + 1), (__pyx_v_strides + 1), (__pyx_v_ndim - 1), __pyx_v_inc); + } + __pyx_L5:; + + /* "View.MemoryView":1385 + * refcount_objects_in_slice(data, shape + 1, strides + 1, ndim - 1, inc) + * + * data += stride # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_data = (__pyx_v_data + __pyx_v_stride); + } + + /* "View.MemoryView":1371 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice') + * cdef void refcount_objects_in_slice(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, bint inc) noexcept: + * cdef Py_ssize_t i + */ + + /* function exit code */ +} + +/* "View.MemoryView":1391 + * + * @cname('__pyx_memoryview_slice_assign_scalar') + * cdef void slice_assign_scalar(__Pyx_memviewslice *dst, int ndim, # <<<<<<<<<<<<<< + * size_t itemsize, void *item, + * bint dtype_is_object) noexcept nogil: + */ + +static void __pyx_memoryview_slice_assign_scalar(__Pyx_memviewslice *__pyx_v_dst, int __pyx_v_ndim, size_t __pyx_v_itemsize, void *__pyx_v_item, int __pyx_v_dtype_is_object) { + + /* "View.MemoryView":1394 + * size_t itemsize, void *item, + * bint dtype_is_object) noexcept nogil: + * refcount_copying(dst, dtype_is_object, ndim, inc=False) # <<<<<<<<<<<<<< + * _slice_assign_scalar(dst.data, dst.shape, dst.strides, ndim, itemsize, item) + * refcount_copying(dst, dtype_is_object, ndim, inc=True) + */ + __pyx_memoryview_refcount_copying(__pyx_v_dst, __pyx_v_dtype_is_object, __pyx_v_ndim, 0); + + /* "View.MemoryView":1395 + * bint dtype_is_object) noexcept nogil: + * refcount_copying(dst, dtype_is_object, ndim, inc=False) + * _slice_assign_scalar(dst.data, dst.shape, dst.strides, ndim, itemsize, item) # <<<<<<<<<<<<<< + * refcount_copying(dst, dtype_is_object, ndim, inc=True) + * + */ + __pyx_memoryview__slice_assign_scalar(__pyx_v_dst->data, __pyx_v_dst->shape, __pyx_v_dst->strides, __pyx_v_ndim, __pyx_v_itemsize, __pyx_v_item); + + /* "View.MemoryView":1396 + * refcount_copying(dst, dtype_is_object, ndim, inc=False) + * _slice_assign_scalar(dst.data, dst.shape, dst.strides, ndim, itemsize, item) + * refcount_copying(dst, dtype_is_object, ndim, inc=True) # <<<<<<<<<<<<<< + * + * + */ + __pyx_memoryview_refcount_copying(__pyx_v_dst, __pyx_v_dtype_is_object, __pyx_v_ndim, 1); + + /* "View.MemoryView":1391 + * + * @cname('__pyx_memoryview_slice_assign_scalar') + * cdef void slice_assign_scalar(__Pyx_memviewslice *dst, int ndim, # <<<<<<<<<<<<<< + * size_t itemsize, void *item, + * bint dtype_is_object) noexcept nogil: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1400 + * + * @cname('__pyx_memoryview__slice_assign_scalar') + * cdef void _slice_assign_scalar(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * size_t itemsize, void *item) noexcept nogil: + */ + +static void __pyx_memoryview__slice_assign_scalar(char *__pyx_v_data, Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, int __pyx_v_ndim, size_t __pyx_v_itemsize, void *__pyx_v_item) { + CYTHON_UNUSED Py_ssize_t __pyx_v_i; + Py_ssize_t __pyx_v_stride; + Py_ssize_t __pyx_v_extent; + int __pyx_t_1; + Py_ssize_t __pyx_t_2; + Py_ssize_t __pyx_t_3; + Py_ssize_t __pyx_t_4; + + /* "View.MemoryView":1404 + * size_t itemsize, void *item) noexcept nogil: + * cdef Py_ssize_t i + * cdef Py_ssize_t stride = strides[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t extent = shape[0] + * + */ + __pyx_v_stride = (__pyx_v_strides[0]); + + /* "View.MemoryView":1405 + * cdef Py_ssize_t i + * cdef Py_ssize_t stride = strides[0] + * cdef Py_ssize_t extent = shape[0] # <<<<<<<<<<<<<< + * + * if ndim == 1: + */ + __pyx_v_extent = (__pyx_v_shape[0]); + + /* "View.MemoryView":1407 + * cdef Py_ssize_t extent = shape[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * for i in range(extent): + * memcpy(data, item, itemsize) + */ + __pyx_t_1 = (__pyx_v_ndim == 1); + if (__pyx_t_1) { + + /* "View.MemoryView":1408 + * + * if ndim == 1: + * for i in range(extent): # <<<<<<<<<<<<<< + * memcpy(data, item, itemsize) + * data += stride + */ + __pyx_t_2 = __pyx_v_extent; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1409 + * if ndim == 1: + * for i in range(extent): + * memcpy(data, item, itemsize) # <<<<<<<<<<<<<< + * data += stride + * else: + */ + (void)(memcpy(__pyx_v_data, __pyx_v_item, __pyx_v_itemsize)); + + /* "View.MemoryView":1410 + * for i in range(extent): + * memcpy(data, item, itemsize) + * data += stride # <<<<<<<<<<<<<< + * else: + * for i in range(extent): + */ + __pyx_v_data = (__pyx_v_data + __pyx_v_stride); + } + + /* "View.MemoryView":1407 + * cdef Py_ssize_t extent = shape[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * for i in range(extent): + * memcpy(data, item, itemsize) + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1412 + * data += stride + * else: + * for i in range(extent): # <<<<<<<<<<<<<< + * _slice_assign_scalar(data, shape + 1, strides + 1, ndim - 1, itemsize, item) + * data += stride + */ + /*else*/ { + __pyx_t_2 = __pyx_v_extent; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1413 + * else: + * for i in range(extent): + * _slice_assign_scalar(data, shape + 1, strides + 1, ndim - 1, itemsize, item) # <<<<<<<<<<<<<< + * data += stride + * + */ + __pyx_memoryview__slice_assign_scalar(__pyx_v_data, (__pyx_v_shape + 1), (__pyx_v_strides + 1), (__pyx_v_ndim - 1), __pyx_v_itemsize, __pyx_v_item); + + /* "View.MemoryView":1414 + * for i in range(extent): + * _slice_assign_scalar(data, shape + 1, strides + 1, ndim - 1, itemsize, item) + * data += stride # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_data = (__pyx_v_data + __pyx_v_stride); + } + } + __pyx_L3:; + + /* "View.MemoryView":1400 + * + * @cname('__pyx_memoryview__slice_assign_scalar') + * cdef void _slice_assign_scalar(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * size_t itemsize, void *item) noexcept nogil: + */ + + /* function exit code */ +} + +/* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_1__pyx_unpickle_Enum(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_15View_dot_MemoryView_1__pyx_unpickle_Enum = {"__pyx_unpickle_Enum", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15View_dot_MemoryView_1__pyx_unpickle_Enum, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15View_dot_MemoryView_1__pyx_unpickle_Enum(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v___pyx_type = 0; + long __pyx_v___pyx_checksum; + PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__pyx_unpickle_Enum (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_type,&__pyx_n_s_pyx_checksum,&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_type)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 1, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_checksum)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 1, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle_Enum", 1, 3, 3, 1); __PYX_ERR(0, 1, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 1, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle_Enum", 1, 3, 3, 2); __PYX_ERR(0, 1, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__pyx_unpickle_Enum") < 0)) __PYX_ERR(0, 1, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + } + __pyx_v___pyx_type = values[0]; + __pyx_v___pyx_checksum = __Pyx_PyInt_As_long(values[1]); if (unlikely((__pyx_v___pyx_checksum == (long)-1) && PyErr_Occurred())) __PYX_ERR(0, 1, __pyx_L3_error) + __pyx_v___pyx_state = values[2]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle_Enum", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 1, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.__pyx_unpickle_Enum", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15View_dot_MemoryView___pyx_unpickle_Enum(__pyx_self, __pyx_v___pyx_type, __pyx_v___pyx_checksum, __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView___pyx_unpickle_Enum(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v___pyx_type, long __pyx_v___pyx_checksum, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_v___pyx_PickleError = 0; + PyObject *__pyx_v___pyx_result = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_unpickle_Enum", 1); + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + */ + __pyx_t_1 = __Pyx_PyInt_From_long(__pyx_v___pyx_checksum); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 4, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = (__Pyx_PySequence_ContainsTF(__pyx_t_1, __pyx_tuple__8, Py_NE)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 4, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (__pyx_t_2) { + + /* "(tree fragment)":5 + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): + * from pickle import PickleError as __pyx_PickleError # <<<<<<<<<<<<<< + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) + */ + __pyx_t_1 = PyList_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_s_PickleError); + __Pyx_GIVEREF(__pyx_n_s_PickleError); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_s_PickleError)) __PYX_ERR(0, 5, __pyx_L1_error); + __pyx_t_3 = __Pyx_Import(__pyx_n_s_pickle, __pyx_t_1, 0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_ImportFrom(__pyx_t_3, __pyx_n_s_PickleError); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_t_1); + __pyx_v___pyx_PickleError = __pyx_t_1; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "(tree fragment)":6 + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum # <<<<<<<<<<<<<< + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: + */ + __pyx_t_3 = __Pyx_PyInt_From_long(__pyx_v___pyx_checksum); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_Incompatible_checksums_0x_x_vs_0, __pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_v___pyx_PickleError, __pyx_t_1, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 6, __pyx_L1_error) + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + */ + } + + /* "(tree fragment)":7 + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) # <<<<<<<<<<<<<< + * if __pyx_state is not None: + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_MemviewEnum_type), __pyx_n_s_new); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 7, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = NULL; + __pyx_t_5 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_5 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_4, __pyx_v___pyx_type}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_5, 1+__pyx_t_5); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 7, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_v___pyx_result = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":8 + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + */ + __pyx_t_2 = (__pyx_v___pyx_state != Py_None); + if (__pyx_t_2) { + + /* "(tree fragment)":9 + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) # <<<<<<<<<<<<<< + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + */ + if (!(likely(PyTuple_CheckExact(__pyx_v___pyx_state))||((__pyx_v___pyx_state) == Py_None) || __Pyx_RaiseUnexpectedTypeError("tuple", __pyx_v___pyx_state))) __PYX_ERR(0, 9, __pyx_L1_error) + __pyx_t_1 = __pyx_unpickle_Enum__set_state(((struct __pyx_MemviewEnum_obj *)__pyx_v___pyx_result), ((PyObject*)__pyx_v___pyx_state)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 9, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":8 + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + */ + } + + /* "(tree fragment)":10 + * if __pyx_state is not None: + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result # <<<<<<<<<<<<<< + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v___pyx_result); + __pyx_r = __pyx_v___pyx_result; + goto __pyx_L0; + + /* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.__pyx_unpickle_Enum", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v___pyx_PickleError); + __Pyx_XDECREF(__pyx_v___pyx_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":11 + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): # <<<<<<<<<<<<<< + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + */ + +static PyObject *__pyx_unpickle_Enum__set_state(struct __pyx_MemviewEnum_obj *__pyx_v___pyx_result, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + int __pyx_t_8; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_unpickle_Enum__set_state", 1); + + /* "(tree fragment)":12 + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] # <<<<<<<<<<<<<< + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + * __pyx_result.__dict__.update(__pyx_state[1]) + */ + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(0, 12, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 12, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + __Pyx_GOTREF(__pyx_v___pyx_result->name); + __Pyx_DECREF(__pyx_v___pyx_result->name); + __pyx_v___pyx_result->name = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":13 + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): # <<<<<<<<<<<<<< + * __pyx_result.__dict__.update(__pyx_state[1]) + */ + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); + __PYX_ERR(0, 13, __pyx_L1_error) + } + __pyx_t_3 = __Pyx_PyTuple_GET_SIZE(__pyx_v___pyx_state); if (unlikely(__pyx_t_3 == ((Py_ssize_t)-1))) __PYX_ERR(0, 13, __pyx_L1_error) + __pyx_t_4 = (__pyx_t_3 > 1); + if (__pyx_t_4) { + } else { + __pyx_t_2 = __pyx_t_4; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_4 = __Pyx_HasAttr(((PyObject *)__pyx_v___pyx_result), __pyx_n_s_dict); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(0, 13, __pyx_L1_error) + __pyx_t_2 = __pyx_t_4; + __pyx_L4_bool_binop_done:; + if (__pyx_t_2) { + + /* "(tree fragment)":14 + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + * __pyx_result.__dict__.update(__pyx_state[1]) # <<<<<<<<<<<<<< + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v___pyx_result), __pyx_n_s_dict); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_update); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(0, 14, __pyx_L1_error) + } + __pyx_t_5 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_7 = NULL; + __pyx_t_8 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_6))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_6); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_6); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_6, function); + __pyx_t_8 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_7, __pyx_t_5}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_6, __pyx_callargs+1-__pyx_t_8, 1+__pyx_t_8); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":13 + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): # <<<<<<<<<<<<<< + * __pyx_result.__dict__.update(__pyx_state[1]) + */ + } + + /* "(tree fragment)":11 + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): # <<<<<<<<<<<<<< + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("View.MemoryView.__pyx_unpickle_Enum__set_state", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "selfdrive/modeld/runners/snpemodel_pyx.pyx":16 + * + * cdef class SNPEModel(RunModel): + * def __cinit__(self, string path, float[:] output, int runtime, bool use_tf8, CLContext context): # <<<<<<<<<<<<<< + * self.model = new cppSNPEModel(path, &output[0], len(output), runtime, use_tf8, context.context) + */ + +/* Python wrapper */ +static int __pyx_pw_9selfdrive_6modeld_7runners_13snpemodel_pyx_9SNPEModel_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_pw_9selfdrive_6modeld_7runners_13snpemodel_pyx_9SNPEModel_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + std::string __pyx_v_path; + __Pyx_memviewslice __pyx_v_output = { 0, 0, { 0 }, { 0 }, { 0 } }; + int __pyx_v_runtime; + bool __pyx_v_use_tf8; + struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext *__pyx_v_context = 0; + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[5] = {0,0,0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_path,&__pyx_n_s_output,&__pyx_n_s_runtime,&__pyx_n_s_use_tf8,&__pyx_n_s_context,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 5: values[4] = __Pyx_Arg_VARARGS(__pyx_args, 4); + CYTHON_FALLTHROUGH; + case 4: values[3] = __Pyx_Arg_VARARGS(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_path)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 16, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_output)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 16, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 5, 5, 1); __PYX_ERR(1, 16, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_runtime)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 16, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 5, 5, 2); __PYX_ERR(1, 16, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 3: + if (likely((values[3] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_use_tf8)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[3]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 16, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 5, 5, 3); __PYX_ERR(1, 16, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 4: + if (likely((values[4] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_context)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[4]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 16, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 5, 5, 4); __PYX_ERR(1, 16, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(1, 16, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 5)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + values[3] = __Pyx_Arg_VARARGS(__pyx_args, 3); + values[4] = __Pyx_Arg_VARARGS(__pyx_args, 4); + } + __pyx_v_path = __pyx_convert_string_from_py_std__in_string(values[0]); if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 16, __pyx_L3_error) + __pyx_v_output = __Pyx_PyObject_to_MemoryviewSlice_ds_float(values[1], PyBUF_WRITABLE); if (unlikely(!__pyx_v_output.memview)) __PYX_ERR(1, 16, __pyx_L3_error) + __pyx_v_runtime = __Pyx_PyInt_As_int(values[2]); if (unlikely((__pyx_v_runtime == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 16, __pyx_L3_error) + __pyx_v_use_tf8 = __Pyx_PyObject_IsTrue(values[3]); if (unlikely((__pyx_v_use_tf8 == ((bool)-1)) && PyErr_Occurred())) __PYX_ERR(1, 16, __pyx_L3_error) + __pyx_v_context = ((struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext *)values[4]); + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 5, 5, __pyx_nargs); __PYX_ERR(1, 16, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __PYX_XCLEAR_MEMVIEW(&__pyx_v_output, 1); + __Pyx_AddTraceback("selfdrive.modeld.runners.snpemodel_pyx.SNPEModel.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_context), __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext, 1, "context", 0))) __PYX_ERR(1, 16, __pyx_L1_error) + __pyx_r = __pyx_pf_9selfdrive_6modeld_7runners_13snpemodel_pyx_9SNPEModel___cinit__(((struct __pyx_obj_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel *)__pyx_v_self), __PYX_STD_MOVE_IF_SUPPORTED(__pyx_v_path), __pyx_v_output, __pyx_v_runtime, __pyx_v_use_tf8, __pyx_v_context); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = -1; + __pyx_L0:; + __PYX_XCLEAR_MEMVIEW(&__pyx_v_output, 1); + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_9selfdrive_6modeld_7runners_13snpemodel_pyx_9SNPEModel___cinit__(struct __pyx_obj_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel *__pyx_v_self, std::string __pyx_v_path, __Pyx_memviewslice __pyx_v_output, int __pyx_v_runtime, bool __pyx_v_use_tf8, struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext *__pyx_v_context) { + int __pyx_r; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + Py_ssize_t __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__cinit__", 1); + + /* "selfdrive/modeld/runners/snpemodel_pyx.pyx":17 + * cdef class SNPEModel(RunModel): + * def __cinit__(self, string path, float[:] output, int runtime, bool use_tf8, CLContext context): + * self.model = new cppSNPEModel(path, &output[0], len(output), runtime, use_tf8, context.context) # <<<<<<<<<<<<<< + */ + __pyx_t_1 = 0; + __pyx_t_2 = -1; + if (__pyx_t_1 < 0) { + __pyx_t_1 += __pyx_v_output.shape[0]; + if (unlikely(__pyx_t_1 < 0)) __pyx_t_2 = 0; + } else if (unlikely(__pyx_t_1 >= __pyx_v_output.shape[0])) __pyx_t_2 = 0; + if (unlikely(__pyx_t_2 != -1)) { + __Pyx_RaiseBufferIndexError(__pyx_t_2); + __PYX_ERR(1, 17, __pyx_L1_error) + } + __pyx_t_3 = __Pyx_MemoryView_Len(__pyx_v_output); + __pyx_t_4 = __Pyx_PyBool_FromLong(__pyx_v_use_tf8); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 17, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_v_self->__pyx_base.model = ((RunModel *)new SNPEModel(__pyx_v_path, (&(*((float *) ( /* dim=0 */ (__pyx_v_output.data + __pyx_t_1 * __pyx_v_output.strides[0]) )))), __pyx_t_3, __pyx_v_runtime, __pyx_t_4, __pyx_v_context->__pyx_base.context)); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "selfdrive/modeld/runners/snpemodel_pyx.pyx":16 + * + * cdef class SNPEModel(RunModel): + * def __cinit__(self, string path, float[:] output, int runtime, bool use_tf8, CLContext context): # <<<<<<<<<<<<<< + * self.model = new cppSNPEModel(path, &output[0], len(output), runtime, use_tf8, context.context) + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("selfdrive.modeld.runners.snpemodel_pyx.SNPEModel.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_9selfdrive_6modeld_7runners_13snpemodel_pyx_9SNPEModel_3__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_9selfdrive_6modeld_7runners_13snpemodel_pyx_9SNPEModel_3__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_9selfdrive_6modeld_7runners_13snpemodel_pyx_9SNPEModel_3__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_9selfdrive_6modeld_7runners_13snpemodel_pyx_9SNPEModel_3__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_9selfdrive_6modeld_7runners_13snpemodel_pyx_9SNPEModel_2__reduce_cython__(((struct __pyx_obj_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_9selfdrive_6modeld_7runners_13snpemodel_pyx_9SNPEModel_2__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(0, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("selfdrive.modeld.runners.snpemodel_pyx.SNPEModel.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_9selfdrive_6modeld_7runners_13snpemodel_pyx_9SNPEModel_5__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_9selfdrive_6modeld_7runners_13snpemodel_pyx_9SNPEModel_5__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_9selfdrive_6modeld_7runners_13snpemodel_pyx_9SNPEModel_5__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_9selfdrive_6modeld_7runners_13snpemodel_pyx_9SNPEModel_5__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(0, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("selfdrive.modeld.runners.snpemodel_pyx.SNPEModel.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_9selfdrive_6modeld_7runners_13snpemodel_pyx_9SNPEModel_4__setstate_cython__(((struct __pyx_obj_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_9selfdrive_6modeld_7runners_13snpemodel_pyx_9SNPEModel_4__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(0, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("selfdrive.modeld.runners.snpemodel_pyx.SNPEModel.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_tp_new_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel(PyTypeObject *t, PyObject *a, PyObject *k) { + PyObject *o = __Pyx_PyType_GetSlot(__pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel, tp_new, newfunc)(t, a, k); + if (unlikely(!o)) return 0; + if (unlikely(__pyx_pw_9selfdrive_6modeld_7runners_13snpemodel_pyx_9SNPEModel_1__cinit__(o, a, k) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static PyMethodDef __pyx_methods_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel[] = { + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_9selfdrive_6modeld_7runners_13snpemodel_pyx_9SNPEModel_3__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_9selfdrive_6modeld_7runners_13snpemodel_pyx_9SNPEModel_5__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel_slots[] = { + {Py_tp_methods, (void *)__pyx_methods_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel}, + {Py_tp_new, (void *)__pyx_tp_new_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel}, + {0, 0}, +}; +static PyType_Spec __pyx_type_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel_spec = { + "selfdrive.modeld.runners.snpemodel_pyx.SNPEModel", + sizeof(struct __pyx_obj_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_FINALIZE, + __pyx_type_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel_slots, +}; +#else + +static PyTypeObject __pyx_type_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel = { + PyVarObject_HEAD_INIT(0, 0) + "selfdrive.modeld.runners.snpemodel_pyx.""SNPEModel", /*tp_name*/ + sizeof(struct __pyx_obj_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + 0, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_FINALIZE, /*tp_flags*/ + 0, /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif +static struct __pyx_vtabstruct_array __pyx_vtable_array; + +static PyObject *__pyx_tp_new_array(PyTypeObject *t, PyObject *a, PyObject *k) { + struct __pyx_array_obj *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_array_obj *)o); + p->__pyx_vtab = __pyx_vtabptr_array; + p->mode = ((PyObject*)Py_None); Py_INCREF(Py_None); + p->_format = ((PyObject*)Py_None); Py_INCREF(Py_None); + if (unlikely(__pyx_array___cinit__(o, a, k) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static void __pyx_tp_dealloc_array(PyObject *o) { + struct __pyx_array_obj *p = (struct __pyx_array_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_array) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_array___dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + Py_CLEAR(p->mode); + Py_CLEAR(p->_format); + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} +static PyObject *__pyx_sq_item_array(PyObject *o, Py_ssize_t i) { + PyObject *r; + PyObject *x = PyInt_FromSsize_t(i); if(!x) return 0; + r = Py_TYPE(o)->tp_as_mapping->mp_subscript(o, x); + Py_DECREF(x); + return r; +} + +static int __pyx_mp_ass_subscript_array(PyObject *o, PyObject *i, PyObject *v) { + if (v) { + return __pyx_array___setitem__(o, i, v); + } + else { + __Pyx_TypeName o_type_name; + o_type_name = __Pyx_PyType_GetName(Py_TYPE(o)); + PyErr_Format(PyExc_NotImplementedError, + "Subscript deletion not supported by " __Pyx_FMT_TYPENAME, o_type_name); + __Pyx_DECREF_TypeName(o_type_name); + return -1; + } +} + +static PyObject *__pyx_tp_getattro_array(PyObject *o, PyObject *n) { + PyObject *v = __Pyx_PyObject_GenericGetAttr(o, n); + if (!v && PyErr_ExceptionMatches(PyExc_AttributeError)) { + PyErr_Clear(); + v = __pyx_array___getattr__(o, n); + } + return v; +} + +static PyObject *__pyx_getprop___pyx_array_memview(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_5array_7memview_1__get__(o); +} + +static PyMethodDef __pyx_methods_array[] = { + {"__getattr__", (PyCFunction)__pyx_array___getattr__, METH_O|METH_COEXIST, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_array_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_array_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; + +static struct PyGetSetDef __pyx_getsets_array[] = { + {(char *)"memview", __pyx_getprop___pyx_array_memview, 0, (char *)0, 0}, + {0, 0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +#if !CYTHON_COMPILING_IN_LIMITED_API + +static PyBufferProcs __pyx_tp_as_buffer_array = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_array_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; +#endif +static PyType_Slot __pyx_type___pyx_array_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_array}, + {Py_sq_length, (void *)__pyx_array___len__}, + {Py_sq_item, (void *)__pyx_sq_item_array}, + {Py_mp_length, (void *)__pyx_array___len__}, + {Py_mp_subscript, (void *)__pyx_array___getitem__}, + {Py_mp_ass_subscript, (void *)__pyx_mp_ass_subscript_array}, + {Py_tp_getattro, (void *)__pyx_tp_getattro_array}, + #if defined(Py_bf_getbuffer) + {Py_bf_getbuffer, (void *)__pyx_array_getbuffer}, + #endif + {Py_tp_methods, (void *)__pyx_methods_array}, + {Py_tp_getset, (void *)__pyx_getsets_array}, + {Py_tp_new, (void *)__pyx_tp_new_array}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_array_spec = { + "selfdrive.modeld.runners.snpemodel_pyx.array", + sizeof(struct __pyx_array_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_SEQUENCE, + __pyx_type___pyx_array_slots, +}; +#else + +static PySequenceMethods __pyx_tp_as_sequence_array = { + __pyx_array___len__, /*sq_length*/ + 0, /*sq_concat*/ + 0, /*sq_repeat*/ + __pyx_sq_item_array, /*sq_item*/ + 0, /*sq_slice*/ + 0, /*sq_ass_item*/ + 0, /*sq_ass_slice*/ + 0, /*sq_contains*/ + 0, /*sq_inplace_concat*/ + 0, /*sq_inplace_repeat*/ +}; + +static PyMappingMethods __pyx_tp_as_mapping_array = { + __pyx_array___len__, /*mp_length*/ + __pyx_array___getitem__, /*mp_subscript*/ + __pyx_mp_ass_subscript_array, /*mp_ass_subscript*/ +}; + +static PyBufferProcs __pyx_tp_as_buffer_array = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_array_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; + +static PyTypeObject __pyx_type___pyx_array = { + PyVarObject_HEAD_INIT(0, 0) + "selfdrive.modeld.runners.snpemodel_pyx.""array", /*tp_name*/ + sizeof(struct __pyx_array_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_array, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + &__pyx_tp_as_sequence_array, /*tp_as_sequence*/ + &__pyx_tp_as_mapping_array, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + __pyx_tp_getattro_array, /*tp_getattro*/ + 0, /*tp_setattro*/ + &__pyx_tp_as_buffer_array, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_SEQUENCE, /*tp_flags*/ + 0, /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_array, /*tp_methods*/ + 0, /*tp_members*/ + __pyx_getsets_array, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_array, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyObject *__pyx_tp_new_Enum(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { + struct __pyx_MemviewEnum_obj *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_MemviewEnum_obj *)o); + p->name = Py_None; Py_INCREF(Py_None); + return o; +} + +static void __pyx_tp_dealloc_Enum(PyObject *o) { + struct __pyx_MemviewEnum_obj *p = (struct __pyx_MemviewEnum_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_Enum) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + Py_CLEAR(p->name); + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} + +static int __pyx_tp_traverse_Enum(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_MemviewEnum_obj *p = (struct __pyx_MemviewEnum_obj *)o; + if (p->name) { + e = (*v)(p->name, a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear_Enum(PyObject *o) { + PyObject* tmp; + struct __pyx_MemviewEnum_obj *p = (struct __pyx_MemviewEnum_obj *)o; + tmp = ((PyObject*)p->name); + p->name = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + return 0; +} + +static PyObject *__pyx_specialmethod___pyx_MemviewEnum___repr__(PyObject *self, CYTHON_UNUSED PyObject *arg) { + return __pyx_MemviewEnum___repr__(self); +} + +static PyMethodDef __pyx_methods_Enum[] = { + {"__repr__", (PyCFunction)__pyx_specialmethod___pyx_MemviewEnum___repr__, METH_NOARGS|METH_COEXIST, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_MemviewEnum_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_MemviewEnum_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type___pyx_MemviewEnum_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_Enum}, + {Py_tp_repr, (void *)__pyx_MemviewEnum___repr__}, + {Py_tp_traverse, (void *)__pyx_tp_traverse_Enum}, + {Py_tp_clear, (void *)__pyx_tp_clear_Enum}, + {Py_tp_methods, (void *)__pyx_methods_Enum}, + {Py_tp_init, (void *)__pyx_MemviewEnum___init__}, + {Py_tp_new, (void *)__pyx_tp_new_Enum}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_MemviewEnum_spec = { + "selfdrive.modeld.runners.snpemodel_pyx.Enum", + sizeof(struct __pyx_MemviewEnum_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, + __pyx_type___pyx_MemviewEnum_slots, +}; +#else + +static PyTypeObject __pyx_type___pyx_MemviewEnum = { + PyVarObject_HEAD_INIT(0, 0) + "selfdrive.modeld.runners.snpemodel_pyx.""Enum", /*tp_name*/ + sizeof(struct __pyx_MemviewEnum_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_Enum, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + __pyx_MemviewEnum___repr__, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, /*tp_flags*/ + 0, /*tp_doc*/ + __pyx_tp_traverse_Enum, /*tp_traverse*/ + __pyx_tp_clear_Enum, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_Enum, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + __pyx_MemviewEnum___init__, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_Enum, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif +static struct __pyx_vtabstruct_memoryview __pyx_vtable_memoryview; + +static PyObject *__pyx_tp_new_memoryview(PyTypeObject *t, PyObject *a, PyObject *k) { + struct __pyx_memoryview_obj *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_memoryview_obj *)o); + p->__pyx_vtab = __pyx_vtabptr_memoryview; + p->obj = Py_None; Py_INCREF(Py_None); + p->_size = Py_None; Py_INCREF(Py_None); + p->_array_interface = Py_None; Py_INCREF(Py_None); + p->view.obj = NULL; + if (unlikely(__pyx_memoryview___cinit__(o, a, k) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static void __pyx_tp_dealloc_memoryview(PyObject *o) { + struct __pyx_memoryview_obj *p = (struct __pyx_memoryview_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_memoryview) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_memoryview___dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + Py_CLEAR(p->obj); + Py_CLEAR(p->_size); + Py_CLEAR(p->_array_interface); + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} + +static int __pyx_tp_traverse_memoryview(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_memoryview_obj *p = (struct __pyx_memoryview_obj *)o; + if (p->obj) { + e = (*v)(p->obj, a); if (e) return e; + } + if (p->_size) { + e = (*v)(p->_size, a); if (e) return e; + } + if (p->_array_interface) { + e = (*v)(p->_array_interface, a); if (e) return e; + } + if (p->view.obj) { + e = (*v)(p->view.obj, a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear_memoryview(PyObject *o) { + PyObject* tmp; + struct __pyx_memoryview_obj *p = (struct __pyx_memoryview_obj *)o; + tmp = ((PyObject*)p->obj); + p->obj = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + tmp = ((PyObject*)p->_size); + p->_size = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + tmp = ((PyObject*)p->_array_interface); + p->_array_interface = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + Py_CLEAR(p->view.obj); + return 0; +} +static PyObject *__pyx_sq_item_memoryview(PyObject *o, Py_ssize_t i) { + PyObject *r; + PyObject *x = PyInt_FromSsize_t(i); if(!x) return 0; + r = Py_TYPE(o)->tp_as_mapping->mp_subscript(o, x); + Py_DECREF(x); + return r; +} + +static int __pyx_mp_ass_subscript_memoryview(PyObject *o, PyObject *i, PyObject *v) { + if (v) { + return __pyx_memoryview___setitem__(o, i, v); + } + else { + __Pyx_TypeName o_type_name; + o_type_name = __Pyx_PyType_GetName(Py_TYPE(o)); + PyErr_Format(PyExc_NotImplementedError, + "Subscript deletion not supported by " __Pyx_FMT_TYPENAME, o_type_name); + __Pyx_DECREF_TypeName(o_type_name); + return -1; + } +} + +static PyObject *__pyx_getprop___pyx_memoryview_T(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_1T_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_base(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_4base_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_shape(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_5shape_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_strides(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_7strides_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_suboffsets(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_10suboffsets_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_ndim(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_4ndim_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_itemsize(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_8itemsize_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_nbytes(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_6nbytes_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_size(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_4size_1__get__(o); +} + +static PyObject *__pyx_specialmethod___pyx_memoryview___repr__(PyObject *self, CYTHON_UNUSED PyObject *arg) { + return __pyx_memoryview___repr__(self); +} + +static PyMethodDef __pyx_methods_memoryview[] = { + {"__repr__", (PyCFunction)__pyx_specialmethod___pyx_memoryview___repr__, METH_NOARGS|METH_COEXIST, 0}, + {"is_c_contig", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_is_c_contig, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"is_f_contig", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_is_f_contig, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"copy", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_copy, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"copy_fortran", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_copy_fortran, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryview_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryview_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; + +static struct PyGetSetDef __pyx_getsets_memoryview[] = { + {(char *)"T", __pyx_getprop___pyx_memoryview_T, 0, (char *)0, 0}, + {(char *)"base", __pyx_getprop___pyx_memoryview_base, 0, (char *)0, 0}, + {(char *)"shape", __pyx_getprop___pyx_memoryview_shape, 0, (char *)0, 0}, + {(char *)"strides", __pyx_getprop___pyx_memoryview_strides, 0, (char *)0, 0}, + {(char *)"suboffsets", __pyx_getprop___pyx_memoryview_suboffsets, 0, (char *)0, 0}, + {(char *)"ndim", __pyx_getprop___pyx_memoryview_ndim, 0, (char *)0, 0}, + {(char *)"itemsize", __pyx_getprop___pyx_memoryview_itemsize, 0, (char *)0, 0}, + {(char *)"nbytes", __pyx_getprop___pyx_memoryview_nbytes, 0, (char *)0, 0}, + {(char *)"size", __pyx_getprop___pyx_memoryview_size, 0, (char *)0, 0}, + {0, 0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +#if !CYTHON_COMPILING_IN_LIMITED_API + +static PyBufferProcs __pyx_tp_as_buffer_memoryview = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_memoryview_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; +#endif +static PyType_Slot __pyx_type___pyx_memoryview_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_memoryview}, + {Py_tp_repr, (void *)__pyx_memoryview___repr__}, + {Py_sq_length, (void *)__pyx_memoryview___len__}, + {Py_sq_item, (void *)__pyx_sq_item_memoryview}, + {Py_mp_length, (void *)__pyx_memoryview___len__}, + {Py_mp_subscript, (void *)__pyx_memoryview___getitem__}, + {Py_mp_ass_subscript, (void *)__pyx_mp_ass_subscript_memoryview}, + {Py_tp_str, (void *)__pyx_memoryview___str__}, + #if defined(Py_bf_getbuffer) + {Py_bf_getbuffer, (void *)__pyx_memoryview_getbuffer}, + #endif + {Py_tp_traverse, (void *)__pyx_tp_traverse_memoryview}, + {Py_tp_clear, (void *)__pyx_tp_clear_memoryview}, + {Py_tp_methods, (void *)__pyx_methods_memoryview}, + {Py_tp_getset, (void *)__pyx_getsets_memoryview}, + {Py_tp_new, (void *)__pyx_tp_new_memoryview}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_memoryview_spec = { + "selfdrive.modeld.runners.snpemodel_pyx.memoryview", + sizeof(struct __pyx_memoryview_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, + __pyx_type___pyx_memoryview_slots, +}; +#else + +static PySequenceMethods __pyx_tp_as_sequence_memoryview = { + __pyx_memoryview___len__, /*sq_length*/ + 0, /*sq_concat*/ + 0, /*sq_repeat*/ + __pyx_sq_item_memoryview, /*sq_item*/ + 0, /*sq_slice*/ + 0, /*sq_ass_item*/ + 0, /*sq_ass_slice*/ + 0, /*sq_contains*/ + 0, /*sq_inplace_concat*/ + 0, /*sq_inplace_repeat*/ +}; + +static PyMappingMethods __pyx_tp_as_mapping_memoryview = { + __pyx_memoryview___len__, /*mp_length*/ + __pyx_memoryview___getitem__, /*mp_subscript*/ + __pyx_mp_ass_subscript_memoryview, /*mp_ass_subscript*/ +}; + +static PyBufferProcs __pyx_tp_as_buffer_memoryview = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_memoryview_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; + +static PyTypeObject __pyx_type___pyx_memoryview = { + PyVarObject_HEAD_INIT(0, 0) + "selfdrive.modeld.runners.snpemodel_pyx.""memoryview", /*tp_name*/ + sizeof(struct __pyx_memoryview_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_memoryview, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + __pyx_memoryview___repr__, /*tp_repr*/ + 0, /*tp_as_number*/ + &__pyx_tp_as_sequence_memoryview, /*tp_as_sequence*/ + &__pyx_tp_as_mapping_memoryview, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + __pyx_memoryview___str__, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + &__pyx_tp_as_buffer_memoryview, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, /*tp_flags*/ + 0, /*tp_doc*/ + __pyx_tp_traverse_memoryview, /*tp_traverse*/ + __pyx_tp_clear_memoryview, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_memoryview, /*tp_methods*/ + 0, /*tp_members*/ + __pyx_getsets_memoryview, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_memoryview, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif +static struct __pyx_vtabstruct__memoryviewslice __pyx_vtable__memoryviewslice; + +static PyObject *__pyx_tp_new__memoryviewslice(PyTypeObject *t, PyObject *a, PyObject *k) { + struct __pyx_memoryviewslice_obj *p; + PyObject *o = __pyx_tp_new_memoryview(t, a, k); + if (unlikely(!o)) return 0; + p = ((struct __pyx_memoryviewslice_obj *)o); + p->__pyx_base.__pyx_vtab = (struct __pyx_vtabstruct_memoryview*)__pyx_vtabptr__memoryviewslice; + new((void*)&(p->from_slice)) __Pyx_memviewslice(); + p->from_object = Py_None; Py_INCREF(Py_None); + p->from_slice.memview = NULL; + return o; +} + +static void __pyx_tp_dealloc__memoryviewslice(PyObject *o) { + struct __pyx_memoryviewslice_obj *p = (struct __pyx_memoryviewslice_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc__memoryviewslice) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_memoryviewslice___dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + __Pyx_call_destructor(p->from_slice); + Py_CLEAR(p->from_object); + PyObject_GC_Track(o); + __pyx_tp_dealloc_memoryview(o); +} + +static int __pyx_tp_traverse__memoryviewslice(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_memoryviewslice_obj *p = (struct __pyx_memoryviewslice_obj *)o; + e = __pyx_tp_traverse_memoryview(o, v, a); if (e) return e; + if (p->from_object) { + e = (*v)(p->from_object, a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear__memoryviewslice(PyObject *o) { + PyObject* tmp; + struct __pyx_memoryviewslice_obj *p = (struct __pyx_memoryviewslice_obj *)o; + __pyx_tp_clear_memoryview(o); + tmp = ((PyObject*)p->from_object); + p->from_object = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + __PYX_XCLEAR_MEMVIEW(&p->from_slice, 1); + return 0; +} + +static PyMethodDef __pyx_methods__memoryviewslice[] = { + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryviewslice_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryviewslice_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type___pyx_memoryviewslice_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc__memoryviewslice}, + {Py_tp_doc, (void *)PyDoc_STR("Internal class for passing memoryview slices to Python")}, + {Py_tp_traverse, (void *)__pyx_tp_traverse__memoryviewslice}, + {Py_tp_clear, (void *)__pyx_tp_clear__memoryviewslice}, + {Py_tp_methods, (void *)__pyx_methods__memoryviewslice}, + {Py_tp_new, (void *)__pyx_tp_new__memoryviewslice}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_memoryviewslice_spec = { + "selfdrive.modeld.runners.snpemodel_pyx._memoryviewslice", + sizeof(struct __pyx_memoryviewslice_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_SEQUENCE, + __pyx_type___pyx_memoryviewslice_slots, +}; +#else + +static PyTypeObject __pyx_type___pyx_memoryviewslice = { + PyVarObject_HEAD_INIT(0, 0) + "selfdrive.modeld.runners.snpemodel_pyx.""_memoryviewslice", /*tp_name*/ + sizeof(struct __pyx_memoryviewslice_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc__memoryviewslice, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + #if CYTHON_COMPILING_IN_PYPY || 0 + __pyx_memoryview___repr__, /*tp_repr*/ + #else + 0, /*tp_repr*/ + #endif + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + #if CYTHON_COMPILING_IN_PYPY || 0 + __pyx_memoryview___str__, /*tp_str*/ + #else + 0, /*tp_str*/ + #endif + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_SEQUENCE, /*tp_flags*/ + PyDoc_STR("Internal class for passing memoryview slices to Python"), /*tp_doc*/ + __pyx_tp_traverse__memoryviewslice, /*tp_traverse*/ + __pyx_tp_clear__memoryviewslice, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods__memoryviewslice, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new__memoryviewslice, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyMethodDef __pyx_methods[] = { + {0, 0, 0, 0} +}; +#ifndef CYTHON_SMALL_CODE +#if defined(__clang__) + #define CYTHON_SMALL_CODE +#elif defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 3)) + #define CYTHON_SMALL_CODE __attribute__((cold)) +#else + #define CYTHON_SMALL_CODE +#endif +#endif +/* #### Code section: pystring_table ### */ + +static int __Pyx_CreateStringTabAndInitStrings(void) { + __Pyx_StringTabEntry __pyx_string_tab[] = { + {&__pyx_kp_u_, __pyx_k_, sizeof(__pyx_k_), 0, 1, 0, 0}, + {&__pyx_n_s_ADSP_LIBRARY_PATH, __pyx_k_ADSP_LIBRARY_PATH, sizeof(__pyx_k_ADSP_LIBRARY_PATH), 0, 0, 1, 1}, + {&__pyx_n_s_ASCII, __pyx_k_ASCII, sizeof(__pyx_k_ASCII), 0, 0, 1, 1}, + {&__pyx_kp_s_All_dimensions_preceding_dimensi, __pyx_k_All_dimensions_preceding_dimensi, sizeof(__pyx_k_All_dimensions_preceding_dimensi), 0, 0, 1, 0}, + {&__pyx_n_s_AssertionError, __pyx_k_AssertionError, sizeof(__pyx_k_AssertionError), 0, 0, 1, 1}, + {&__pyx_kp_s_Buffer_view_does_not_expose_stri, __pyx_k_Buffer_view_does_not_expose_stri, sizeof(__pyx_k_Buffer_view_does_not_expose_stri), 0, 0, 1, 0}, + {&__pyx_kp_s_Can_only_create_a_buffer_that_is, __pyx_k_Can_only_create_a_buffer_that_is, sizeof(__pyx_k_Can_only_create_a_buffer_that_is), 0, 0, 1, 0}, + {&__pyx_kp_s_Cannot_assign_to_read_only_memor, __pyx_k_Cannot_assign_to_read_only_memor, sizeof(__pyx_k_Cannot_assign_to_read_only_memor), 0, 0, 1, 0}, + {&__pyx_kp_s_Cannot_create_writable_memory_vi, __pyx_k_Cannot_create_writable_memory_vi, sizeof(__pyx_k_Cannot_create_writable_memory_vi), 0, 0, 1, 0}, + {&__pyx_kp_u_Cannot_index_with_type, __pyx_k_Cannot_index_with_type, sizeof(__pyx_k_Cannot_index_with_type), 0, 1, 0, 0}, + {&__pyx_kp_s_Cannot_transpose_memoryview_with, __pyx_k_Cannot_transpose_memoryview_with, sizeof(__pyx_k_Cannot_transpose_memoryview_with), 0, 0, 1, 0}, + {&__pyx_kp_s_Dimension_d_is_not_direct, __pyx_k_Dimension_d_is_not_direct, sizeof(__pyx_k_Dimension_d_is_not_direct), 0, 0, 1, 0}, + {&__pyx_n_s_Ellipsis, __pyx_k_Ellipsis, sizeof(__pyx_k_Ellipsis), 0, 0, 1, 1}, + {&__pyx_kp_s_Empty_shape_tuple_for_cython_arr, __pyx_k_Empty_shape_tuple_for_cython_arr, sizeof(__pyx_k_Empty_shape_tuple_for_cython_arr), 0, 0, 1, 0}, + {&__pyx_kp_s_Incompatible_checksums_0x_x_vs_0, __pyx_k_Incompatible_checksums_0x_x_vs_0, sizeof(__pyx_k_Incompatible_checksums_0x_x_vs_0), 0, 0, 1, 0}, + {&__pyx_n_s_IndexError, __pyx_k_IndexError, sizeof(__pyx_k_IndexError), 0, 0, 1, 1}, + {&__pyx_kp_s_Index_out_of_bounds_axis_d, __pyx_k_Index_out_of_bounds_axis_d, sizeof(__pyx_k_Index_out_of_bounds_axis_d), 0, 0, 1, 0}, + {&__pyx_kp_s_Indirect_dimensions_not_supporte, __pyx_k_Indirect_dimensions_not_supporte, sizeof(__pyx_k_Indirect_dimensions_not_supporte), 0, 0, 1, 0}, + {&__pyx_kp_u_Invalid_mode_expected_c_or_fortr, __pyx_k_Invalid_mode_expected_c_or_fortr, sizeof(__pyx_k_Invalid_mode_expected_c_or_fortr), 0, 1, 0, 0}, + {&__pyx_kp_u_Invalid_shape_in_axis, __pyx_k_Invalid_shape_in_axis, sizeof(__pyx_k_Invalid_shape_in_axis), 0, 1, 0, 0}, + {&__pyx_n_s_MemoryError, __pyx_k_MemoryError, sizeof(__pyx_k_MemoryError), 0, 0, 1, 1}, + {&__pyx_kp_s_MemoryView_of_r_at_0x_x, __pyx_k_MemoryView_of_r_at_0x_x, sizeof(__pyx_k_MemoryView_of_r_at_0x_x), 0, 0, 1, 0}, + {&__pyx_kp_s_MemoryView_of_r_object, __pyx_k_MemoryView_of_r_object, sizeof(__pyx_k_MemoryView_of_r_object), 0, 0, 1, 0}, + {&__pyx_n_b_O, __pyx_k_O, sizeof(__pyx_k_O), 0, 0, 0, 1}, + {&__pyx_kp_u_Out_of_bounds_on_buffer_access_a, __pyx_k_Out_of_bounds_on_buffer_access_a, sizeof(__pyx_k_Out_of_bounds_on_buffer_access_a), 0, 1, 0, 0}, + {&__pyx_n_s_PickleError, __pyx_k_PickleError, sizeof(__pyx_k_PickleError), 0, 0, 1, 1}, + {&__pyx_n_s_SNPEModel, __pyx_k_SNPEModel, sizeof(__pyx_k_SNPEModel), 0, 0, 1, 1}, + {&__pyx_n_s_SNPEModel___reduce_cython, __pyx_k_SNPEModel___reduce_cython, sizeof(__pyx_k_SNPEModel___reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_SNPEModel___setstate_cython, __pyx_k_SNPEModel___setstate_cython, sizeof(__pyx_k_SNPEModel___setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_Sequence, __pyx_k_Sequence, sizeof(__pyx_k_Sequence), 0, 0, 1, 1}, + {&__pyx_kp_s_Step_may_not_be_zero_axis_d, __pyx_k_Step_may_not_be_zero_axis_d, sizeof(__pyx_k_Step_may_not_be_zero_axis_d), 0, 0, 1, 0}, + {&__pyx_n_s_TypeError, __pyx_k_TypeError, sizeof(__pyx_k_TypeError), 0, 0, 1, 1}, + {&__pyx_kp_s_Unable_to_convert_item_to_object, __pyx_k_Unable_to_convert_item_to_object, sizeof(__pyx_k_Unable_to_convert_item_to_object), 0, 0, 1, 0}, + {&__pyx_n_s_ValueError, __pyx_k_ValueError, sizeof(__pyx_k_ValueError), 0, 0, 1, 1}, + {&__pyx_n_s_View_MemoryView, __pyx_k_View_MemoryView, sizeof(__pyx_k_View_MemoryView), 0, 0, 1, 1}, + {&__pyx_kp_u__2, __pyx_k__2, sizeof(__pyx_k__2), 0, 1, 0, 0}, + {&__pyx_n_s__24, __pyx_k__24, sizeof(__pyx_k__24), 0, 0, 1, 1}, + {&__pyx_n_s__3, __pyx_k__3, sizeof(__pyx_k__3), 0, 0, 1, 1}, + {&__pyx_kp_u__6, __pyx_k__6, sizeof(__pyx_k__6), 0, 1, 0, 0}, + {&__pyx_kp_u__7, __pyx_k__7, sizeof(__pyx_k__7), 0, 1, 0, 0}, + {&__pyx_n_s_abc, __pyx_k_abc, sizeof(__pyx_k_abc), 0, 0, 1, 1}, + {&__pyx_n_s_allocate_buffer, __pyx_k_allocate_buffer, sizeof(__pyx_k_allocate_buffer), 0, 0, 1, 1}, + {&__pyx_kp_u_and, __pyx_k_and, sizeof(__pyx_k_and), 0, 1, 0, 0}, + {&__pyx_n_s_asyncio_coroutines, __pyx_k_asyncio_coroutines, sizeof(__pyx_k_asyncio_coroutines), 0, 0, 1, 1}, + {&__pyx_n_s_base, __pyx_k_base, sizeof(__pyx_k_base), 0, 0, 1, 1}, + {&__pyx_n_s_c, __pyx_k_c, sizeof(__pyx_k_c), 0, 0, 1, 1}, + {&__pyx_n_u_c, __pyx_k_c, sizeof(__pyx_k_c), 0, 1, 0, 1}, + {&__pyx_n_s_class, __pyx_k_class, sizeof(__pyx_k_class), 0, 0, 1, 1}, + {&__pyx_n_s_class_getitem, __pyx_k_class_getitem, sizeof(__pyx_k_class_getitem), 0, 0, 1, 1}, + {&__pyx_n_s_cline_in_traceback, __pyx_k_cline_in_traceback, sizeof(__pyx_k_cline_in_traceback), 0, 0, 1, 1}, + {&__pyx_n_s_collections, __pyx_k_collections, sizeof(__pyx_k_collections), 0, 0, 1, 1}, + {&__pyx_kp_s_collections_abc, __pyx_k_collections_abc, sizeof(__pyx_k_collections_abc), 0, 0, 1, 0}, + {&__pyx_n_s_context, __pyx_k_context, sizeof(__pyx_k_context), 0, 0, 1, 1}, + {&__pyx_kp_s_contiguous_and_direct, __pyx_k_contiguous_and_direct, sizeof(__pyx_k_contiguous_and_direct), 0, 0, 1, 0}, + {&__pyx_kp_s_contiguous_and_indirect, __pyx_k_contiguous_and_indirect, sizeof(__pyx_k_contiguous_and_indirect), 0, 0, 1, 0}, + {&__pyx_n_s_count, __pyx_k_count, sizeof(__pyx_k_count), 0, 0, 1, 1}, + {&__pyx_kp_s_data_pythonpath_third_party_snp, __pyx_k_data_pythonpath_third_party_snp, sizeof(__pyx_k_data_pythonpath_third_party_snp), 0, 0, 1, 0}, + {&__pyx_n_s_dict, __pyx_k_dict, sizeof(__pyx_k_dict), 0, 0, 1, 1}, + {&__pyx_kp_u_disable, __pyx_k_disable, sizeof(__pyx_k_disable), 0, 1, 0, 0}, + {&__pyx_n_s_dtype_is_object, __pyx_k_dtype_is_object, sizeof(__pyx_k_dtype_is_object), 0, 0, 1, 1}, + {&__pyx_kp_u_enable, __pyx_k_enable, sizeof(__pyx_k_enable), 0, 1, 0, 0}, + {&__pyx_n_s_encode, __pyx_k_encode, sizeof(__pyx_k_encode), 0, 0, 1, 1}, + {&__pyx_n_s_enumerate, __pyx_k_enumerate, sizeof(__pyx_k_enumerate), 0, 0, 1, 1}, + {&__pyx_n_s_environ, __pyx_k_environ, sizeof(__pyx_k_environ), 0, 0, 1, 1}, + {&__pyx_n_s_error, __pyx_k_error, sizeof(__pyx_k_error), 0, 0, 1, 1}, + {&__pyx_n_s_flags, __pyx_k_flags, sizeof(__pyx_k_flags), 0, 0, 1, 1}, + {&__pyx_n_s_format, __pyx_k_format, sizeof(__pyx_k_format), 0, 0, 1, 1}, + {&__pyx_n_s_fortran, __pyx_k_fortran, sizeof(__pyx_k_fortran), 0, 0, 1, 1}, + {&__pyx_n_u_fortran, __pyx_k_fortran, sizeof(__pyx_k_fortran), 0, 1, 0, 1}, + {&__pyx_kp_u_gc, __pyx_k_gc, sizeof(__pyx_k_gc), 0, 1, 0, 0}, + {&__pyx_n_s_getstate, __pyx_k_getstate, sizeof(__pyx_k_getstate), 0, 0, 1, 1}, + {&__pyx_kp_u_got, __pyx_k_got, sizeof(__pyx_k_got), 0, 1, 0, 0}, + {&__pyx_kp_u_got_differing_extents_in_dimensi, __pyx_k_got_differing_extents_in_dimensi, sizeof(__pyx_k_got_differing_extents_in_dimensi), 0, 1, 0, 0}, + {&__pyx_n_s_id, __pyx_k_id, sizeof(__pyx_k_id), 0, 0, 1, 1}, + {&__pyx_n_s_import, __pyx_k_import, sizeof(__pyx_k_import), 0, 0, 1, 1}, + {&__pyx_n_s_index, __pyx_k_index, sizeof(__pyx_k_index), 0, 0, 1, 1}, + {&__pyx_n_s_initializing, __pyx_k_initializing, sizeof(__pyx_k_initializing), 0, 0, 1, 1}, + {&__pyx_n_s_is_coroutine, __pyx_k_is_coroutine, sizeof(__pyx_k_is_coroutine), 0, 0, 1, 1}, + {&__pyx_kp_u_isenabled, __pyx_k_isenabled, sizeof(__pyx_k_isenabled), 0, 1, 0, 0}, + {&__pyx_n_s_itemsize, __pyx_k_itemsize, sizeof(__pyx_k_itemsize), 0, 0, 1, 1}, + {&__pyx_kp_s_itemsize_0_for_cython_array, __pyx_k_itemsize_0_for_cython_array, sizeof(__pyx_k_itemsize_0_for_cython_array), 0, 0, 1, 0}, + {&__pyx_n_s_main, __pyx_k_main, sizeof(__pyx_k_main), 0, 0, 1, 1}, + {&__pyx_n_s_memview, __pyx_k_memview, sizeof(__pyx_k_memview), 0, 0, 1, 1}, + {&__pyx_n_s_mode, __pyx_k_mode, sizeof(__pyx_k_mode), 0, 0, 1, 1}, + {&__pyx_n_s_name, __pyx_k_name, sizeof(__pyx_k_name), 0, 0, 1, 1}, + {&__pyx_n_s_name_2, __pyx_k_name_2, sizeof(__pyx_k_name_2), 0, 0, 1, 1}, + {&__pyx_n_s_ndim, __pyx_k_ndim, sizeof(__pyx_k_ndim), 0, 0, 1, 1}, + {&__pyx_n_s_new, __pyx_k_new, sizeof(__pyx_k_new), 0, 0, 1, 1}, + {&__pyx_kp_s_no_default___reduce___due_to_non, __pyx_k_no_default___reduce___due_to_non, sizeof(__pyx_k_no_default___reduce___due_to_non), 0, 0, 1, 0}, + {&__pyx_n_s_obj, __pyx_k_obj, sizeof(__pyx_k_obj), 0, 0, 1, 1}, + {&__pyx_n_s_os, __pyx_k_os, sizeof(__pyx_k_os), 0, 0, 1, 1}, + {&__pyx_n_s_output, __pyx_k_output, sizeof(__pyx_k_output), 0, 0, 1, 1}, + {&__pyx_n_s_pack, __pyx_k_pack, sizeof(__pyx_k_pack), 0, 0, 1, 1}, + {&__pyx_n_s_path, __pyx_k_path, sizeof(__pyx_k_path), 0, 0, 1, 1}, + {&__pyx_n_s_pickle, __pyx_k_pickle, sizeof(__pyx_k_pickle), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_PickleError, __pyx_k_pyx_PickleError, sizeof(__pyx_k_pyx_PickleError), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_checksum, __pyx_k_pyx_checksum, sizeof(__pyx_k_pyx_checksum), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_result, __pyx_k_pyx_result, sizeof(__pyx_k_pyx_result), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_state, __pyx_k_pyx_state, sizeof(__pyx_k_pyx_state), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_type, __pyx_k_pyx_type, sizeof(__pyx_k_pyx_type), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_unpickle_Enum, __pyx_k_pyx_unpickle_Enum, sizeof(__pyx_k_pyx_unpickle_Enum), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_vtable, __pyx_k_pyx_vtable, sizeof(__pyx_k_pyx_vtable), 0, 0, 1, 1}, + {&__pyx_n_s_range, __pyx_k_range, sizeof(__pyx_k_range), 0, 0, 1, 1}, + {&__pyx_n_s_reduce, __pyx_k_reduce, sizeof(__pyx_k_reduce), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_cython, __pyx_k_reduce_cython, sizeof(__pyx_k_reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_ex, __pyx_k_reduce_ex, sizeof(__pyx_k_reduce_ex), 0, 0, 1, 1}, + {&__pyx_n_s_register, __pyx_k_register, sizeof(__pyx_k_register), 0, 0, 1, 1}, + {&__pyx_n_s_runtime, __pyx_k_runtime, sizeof(__pyx_k_runtime), 0, 0, 1, 1}, + {&__pyx_n_s_self, __pyx_k_self, sizeof(__pyx_k_self), 0, 0, 1, 1}, + {&__pyx_n_s_selfdrive_modeld_runners_snpemod, __pyx_k_selfdrive_modeld_runners_snpemod, sizeof(__pyx_k_selfdrive_modeld_runners_snpemod), 0, 0, 1, 1}, + {&__pyx_n_s_setstate, __pyx_k_setstate, sizeof(__pyx_k_setstate), 0, 0, 1, 1}, + {&__pyx_n_s_setstate_cython, __pyx_k_setstate_cython, sizeof(__pyx_k_setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_shape, __pyx_k_shape, sizeof(__pyx_k_shape), 0, 0, 1, 1}, + {&__pyx_n_s_size, __pyx_k_size, sizeof(__pyx_k_size), 0, 0, 1, 1}, + {&__pyx_n_s_spec, __pyx_k_spec, sizeof(__pyx_k_spec), 0, 0, 1, 1}, + {&__pyx_n_s_start, __pyx_k_start, sizeof(__pyx_k_start), 0, 0, 1, 1}, + {&__pyx_n_s_step, __pyx_k_step, sizeof(__pyx_k_step), 0, 0, 1, 1}, + {&__pyx_n_s_stop, __pyx_k_stop, sizeof(__pyx_k_stop), 0, 0, 1, 1}, + {&__pyx_kp_s_strided_and_direct, __pyx_k_strided_and_direct, sizeof(__pyx_k_strided_and_direct), 0, 0, 1, 0}, + {&__pyx_kp_s_strided_and_direct_or_indirect, __pyx_k_strided_and_direct_or_indirect, sizeof(__pyx_k_strided_and_direct_or_indirect), 0, 0, 1, 0}, + {&__pyx_kp_s_strided_and_indirect, __pyx_k_strided_and_indirect, sizeof(__pyx_k_strided_and_indirect), 0, 0, 1, 0}, + {&__pyx_kp_s_stringsource, __pyx_k_stringsource, sizeof(__pyx_k_stringsource), 0, 0, 1, 0}, + {&__pyx_n_s_struct, __pyx_k_struct, sizeof(__pyx_k_struct), 0, 0, 1, 1}, + {&__pyx_n_s_sys, __pyx_k_sys, sizeof(__pyx_k_sys), 0, 0, 1, 1}, + {&__pyx_n_s_test, __pyx_k_test, sizeof(__pyx_k_test), 0, 0, 1, 1}, + {&__pyx_kp_s_unable_to_allocate_array_data, __pyx_k_unable_to_allocate_array_data, sizeof(__pyx_k_unable_to_allocate_array_data), 0, 0, 1, 0}, + {&__pyx_kp_s_unable_to_allocate_shape_and_str, __pyx_k_unable_to_allocate_shape_and_str, sizeof(__pyx_k_unable_to_allocate_shape_and_str), 0, 0, 1, 0}, + {&__pyx_n_s_unpack, __pyx_k_unpack, sizeof(__pyx_k_unpack), 0, 0, 1, 1}, + {&__pyx_n_s_update, __pyx_k_update, sizeof(__pyx_k_update), 0, 0, 1, 1}, + {&__pyx_n_s_use_tf8, __pyx_k_use_tf8, sizeof(__pyx_k_use_tf8), 0, 0, 1, 1}, + {&__pyx_n_s_version_info, __pyx_k_version_info, sizeof(__pyx_k_version_info), 0, 0, 1, 1}, + {0, 0, 0, 0, 0, 0, 0} + }; + return __Pyx_InitStrings(__pyx_string_tab); +} +/* #### Code section: cached_builtins ### */ +static CYTHON_SMALL_CODE int __Pyx_InitCachedBuiltins(void) { + __pyx_builtin_TypeError = __Pyx_GetBuiltinName(__pyx_n_s_TypeError); if (!__pyx_builtin_TypeError) __PYX_ERR(0, 2, __pyx_L1_error) + __pyx_builtin___import__ = __Pyx_GetBuiltinName(__pyx_n_s_import); if (!__pyx_builtin___import__) __PYX_ERR(0, 100, __pyx_L1_error) + __pyx_builtin_ValueError = __Pyx_GetBuiltinName(__pyx_n_s_ValueError); if (!__pyx_builtin_ValueError) __PYX_ERR(0, 141, __pyx_L1_error) + __pyx_builtin_MemoryError = __Pyx_GetBuiltinName(__pyx_n_s_MemoryError); if (!__pyx_builtin_MemoryError) __PYX_ERR(0, 156, __pyx_L1_error) + __pyx_builtin_enumerate = __Pyx_GetBuiltinName(__pyx_n_s_enumerate); if (!__pyx_builtin_enumerate) __PYX_ERR(0, 159, __pyx_L1_error) + __pyx_builtin_range = __Pyx_GetBuiltinName(__pyx_n_s_range); if (!__pyx_builtin_range) __PYX_ERR(0, 261, __pyx_L1_error) + __pyx_builtin_AssertionError = __Pyx_GetBuiltinName(__pyx_n_s_AssertionError); if (!__pyx_builtin_AssertionError) __PYX_ERR(0, 373, __pyx_L1_error) + __pyx_builtin_Ellipsis = __Pyx_GetBuiltinName(__pyx_n_s_Ellipsis); if (!__pyx_builtin_Ellipsis) __PYX_ERR(0, 408, __pyx_L1_error) + __pyx_builtin_id = __Pyx_GetBuiltinName(__pyx_n_s_id); if (!__pyx_builtin_id) __PYX_ERR(0, 618, __pyx_L1_error) + __pyx_builtin_IndexError = __Pyx_GetBuiltinName(__pyx_n_s_IndexError); if (!__pyx_builtin_IndexError) __PYX_ERR(0, 914, __pyx_L1_error) + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: cached_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_InitCachedConstants", 0); + + /* "View.MemoryView":582 + * def suboffsets(self): + * if self.view.suboffsets == NULL: + * return (-1,) * self.view.ndim # <<<<<<<<<<<<<< + * + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + */ + __pyx_tuple__4 = PyTuple_New(1); if (unlikely(!__pyx_tuple__4)) __PYX_ERR(0, 582, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__4); + __Pyx_INCREF(__pyx_int_neg_1); + __Pyx_GIVEREF(__pyx_int_neg_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_tuple__4, 0, __pyx_int_neg_1)) __PYX_ERR(0, 582, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_tuple__4); + + /* "View.MemoryView":679 + * tup = index if isinstance(index, tuple) else (index,) + * + * result = [slice(None)] * ndim # <<<<<<<<<<<<<< + * have_slices = False + * seen_ellipsis = False + */ + __pyx_slice__5 = PySlice_New(Py_None, Py_None, Py_None); if (unlikely(!__pyx_slice__5)) __PYX_ERR(0, 679, __pyx_L1_error) + __Pyx_GOTREF(__pyx_slice__5); + __Pyx_GIVEREF(__pyx_slice__5); + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + */ + __pyx_tuple__8 = PyTuple_Pack(3, __pyx_int_136983863, __pyx_int_112105877, __pyx_int_184977713); if (unlikely(!__pyx_tuple__8)) __PYX_ERR(0, 4, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__8); + __Pyx_GIVEREF(__pyx_tuple__8); + + /* "View.MemoryView":100 + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: + * if __import__("sys").version_info >= (3, 3): # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + */ + __pyx_tuple__9 = PyTuple_Pack(1, __pyx_n_s_sys); if (unlikely(!__pyx_tuple__9)) __PYX_ERR(0, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__9); + __Pyx_GIVEREF(__pyx_tuple__9); + __pyx_tuple__10 = PyTuple_Pack(2, __pyx_int_3, __pyx_int_3); if (unlikely(!__pyx_tuple__10)) __PYX_ERR(0, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__10); + __Pyx_GIVEREF(__pyx_tuple__10); + + /* "View.MemoryView":101 + * try: + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence # <<<<<<<<<<<<<< + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence + */ + __pyx_tuple__11 = PyTuple_Pack(1, __pyx_kp_s_collections_abc); if (unlikely(!__pyx_tuple__11)) __PYX_ERR(0, 101, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__11); + __Pyx_GIVEREF(__pyx_tuple__11); + + /* "View.MemoryView":103 + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence # <<<<<<<<<<<<<< + * except: + * + */ + __pyx_tuple__12 = PyTuple_Pack(1, __pyx_n_s_collections); if (unlikely(!__pyx_tuple__12)) __PYX_ERR(0, 103, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__12); + __Pyx_GIVEREF(__pyx_tuple__12); + + /* "View.MemoryView":309 + * return self.name + * + * cdef generic = Enum("") # <<<<<<<<<<<<<< + * cdef strided = Enum("") # default + * cdef indirect = Enum("") + */ + __pyx_tuple__13 = PyTuple_Pack(1, __pyx_kp_s_strided_and_direct_or_indirect); if (unlikely(!__pyx_tuple__13)) __PYX_ERR(0, 309, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__13); + __Pyx_GIVEREF(__pyx_tuple__13); + + /* "View.MemoryView":310 + * + * cdef generic = Enum("") + * cdef strided = Enum("") # default # <<<<<<<<<<<<<< + * cdef indirect = Enum("") + * + */ + __pyx_tuple__14 = PyTuple_Pack(1, __pyx_kp_s_strided_and_direct); if (unlikely(!__pyx_tuple__14)) __PYX_ERR(0, 310, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__14); + __Pyx_GIVEREF(__pyx_tuple__14); + + /* "View.MemoryView":311 + * cdef generic = Enum("") + * cdef strided = Enum("") # default + * cdef indirect = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_tuple__15 = PyTuple_Pack(1, __pyx_kp_s_strided_and_indirect); if (unlikely(!__pyx_tuple__15)) __PYX_ERR(0, 311, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__15); + __Pyx_GIVEREF(__pyx_tuple__15); + + /* "View.MemoryView":314 + * + * + * cdef contiguous = Enum("") # <<<<<<<<<<<<<< + * cdef indirect_contiguous = Enum("") + * + */ + __pyx_tuple__16 = PyTuple_Pack(1, __pyx_kp_s_contiguous_and_direct); if (unlikely(!__pyx_tuple__16)) __PYX_ERR(0, 314, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__16); + __Pyx_GIVEREF(__pyx_tuple__16); + + /* "View.MemoryView":315 + * + * cdef contiguous = Enum("") + * cdef indirect_contiguous = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_tuple__17 = PyTuple_Pack(1, __pyx_kp_s_contiguous_and_indirect); if (unlikely(!__pyx_tuple__17)) __PYX_ERR(0, 315, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__17); + __Pyx_GIVEREF(__pyx_tuple__17); + + /* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + __pyx_tuple__18 = PyTuple_Pack(5, __pyx_n_s_pyx_type, __pyx_n_s_pyx_checksum, __pyx_n_s_pyx_state, __pyx_n_s_pyx_PickleError, __pyx_n_s_pyx_result); if (unlikely(!__pyx_tuple__18)) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__18); + __Pyx_GIVEREF(__pyx_tuple__18); + __pyx_codeobj__19 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__18, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_pyx_unpickle_Enum, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__19)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_tuple__20 = PyTuple_Pack(1, __pyx_n_s_self); if (unlikely(!__pyx_tuple__20)) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__20); + __Pyx_GIVEREF(__pyx_tuple__20); + __pyx_codeobj__21 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__20, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__21)) __PYX_ERR(0, 1, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_tuple__22 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_pyx_state); if (unlikely(!__pyx_tuple__22)) __PYX_ERR(0, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__22); + __Pyx_GIVEREF(__pyx_tuple__22); + __pyx_codeobj__23 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__22, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__23)) __PYX_ERR(0, 3, __pyx_L1_error) + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_RefNannyFinishContext(); + return -1; +} +/* #### Code section: init_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitConstants(void) { + if (__Pyx_CreateStringTabAndInitStrings() < 0) __PYX_ERR(1, 1, __pyx_L1_error); + __pyx_int_0 = PyInt_FromLong(0); if (unlikely(!__pyx_int_0)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_int_1 = PyInt_FromLong(1); if (unlikely(!__pyx_int_1)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_int_3 = PyInt_FromLong(3); if (unlikely(!__pyx_int_3)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_int_112105877 = PyInt_FromLong(112105877L); if (unlikely(!__pyx_int_112105877)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_int_136983863 = PyInt_FromLong(136983863L); if (unlikely(!__pyx_int_136983863)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_int_184977713 = PyInt_FromLong(184977713L); if (unlikely(!__pyx_int_184977713)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_int_neg_1 = PyInt_FromLong(-1); if (unlikely(!__pyx_int_neg_1)) __PYX_ERR(1, 1, __pyx_L1_error) + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: init_globals ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitGlobals(void) { + /* AssertionsEnabled.init */ + if (likely(__Pyx_init_assertions_enabled() == 0)); else + +if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L1_error) + + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: init_module ### */ + +static CYTHON_SMALL_CODE int __Pyx_modinit_global_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_import_code(void); /*proto*/ + +static int __Pyx_modinit_global_init_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_global_init_code", 0); + /*--- Global init code ---*/ + __pyx_collections_abc_Sequence = Py_None; Py_INCREF(Py_None); + generic = Py_None; Py_INCREF(Py_None); + strided = Py_None; Py_INCREF(Py_None); + indirect = Py_None; Py_INCREF(Py_None); + contiguous = Py_None; Py_INCREF(Py_None); + indirect_contiguous = Py_None; Py_INCREF(Py_None); + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_variable_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_export_code", 0); + /*--- Variable export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_export_code", 0); + /*--- Function export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_type_init_code(void) { + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_modinit_type_init_code", 0); + /*--- Type init code ---*/ + __pyx_t_1 = PyImport_ImportModule("selfdrive.modeld.runners.runmodel_pyx"); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel = __Pyx_ImportType_3_0_8(__pyx_t_1, "selfdrive.modeld.runners.runmodel_pyx", "RunModel", sizeof(struct __pyx_obj_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(struct __pyx_obj_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel) __PYX_ERR(1, 1, __pyx_L1_error) + #if CYTHON_USE_TYPE_SPECS + __pyx_t_2 = PyTuple_Pack(1, (PyObject *)__pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_ptype_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel_spec, __pyx_t_2); + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + if (unlikely(!__pyx_ptype_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel)) __PYX_ERR(1, 15, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel_spec, __pyx_ptype_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel) < 0) __PYX_ERR(1, 15, __pyx_L1_error) + #else + __pyx_ptype_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel = &__pyx_type_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + __pyx_ptype_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel->tp_dealloc = __pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel->tp_dealloc; + __pyx_ptype_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel->tp_base = __pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel; + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel) < 0) __PYX_ERR(1, 15, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel->tp_dictoffset && __pyx_ptype_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_SNPEModel, (PyObject *) __pyx_ptype_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel) < 0) __PYX_ERR(1, 15, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_9selfdrive_6modeld_7runners_13snpemodel_pyx_SNPEModel) < 0) __PYX_ERR(1, 15, __pyx_L1_error) + #endif + __pyx_vtabptr_array = &__pyx_vtable_array; + __pyx_vtable_array.get_memview = (PyObject *(*)(struct __pyx_array_obj *))__pyx_array_get_memview; + #if CYTHON_USE_TYPE_SPECS + __pyx_array_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_array_spec, NULL); if (unlikely(!__pyx_array_type)) __PYX_ERR(0, 114, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + __pyx_array_type->tp_as_buffer = &__pyx_tp_as_buffer_array; + if (!__pyx_array_type->tp_as_buffer->bf_releasebuffer && __pyx_array_type->tp_base->tp_as_buffer && __pyx_array_type->tp_base->tp_as_buffer->bf_releasebuffer) { + __pyx_array_type->tp_as_buffer->bf_releasebuffer = __pyx_array_type->tp_base->tp_as_buffer->bf_releasebuffer; + } + #elif defined(Py_bf_getbuffer) && defined(Py_bf_releasebuffer) + /* PY_VERSION_HEX >= 0x03090000 || Py_LIMITED_API >= 0x030B0000 */ + #elif defined(_MSC_VER) + #pragma message ("The buffer protocol is not supported in the Limited C-API < 3.11.") + #else + #warning "The buffer protocol is not supported in the Limited C-API < 3.11." + #endif + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_array_spec, __pyx_array_type) < 0) __PYX_ERR(0, 114, __pyx_L1_error) + #else + __pyx_array_type = &__pyx_type___pyx_array; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_array_type) < 0) __PYX_ERR(0, 114, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_array_type->tp_print = 0; + #endif + if (__Pyx_SetVtable(__pyx_array_type, __pyx_vtabptr_array) < 0) __PYX_ERR(0, 114, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_array_type) < 0) __PYX_ERR(0, 114, __pyx_L1_error) + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_array_type) < 0) __PYX_ERR(0, 114, __pyx_L1_error) + #endif + #if CYTHON_USE_TYPE_SPECS + __pyx_MemviewEnum_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_MemviewEnum_spec, NULL); if (unlikely(!__pyx_MemviewEnum_type)) __PYX_ERR(0, 302, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_MemviewEnum_spec, __pyx_MemviewEnum_type) < 0) __PYX_ERR(0, 302, __pyx_L1_error) + #else + __pyx_MemviewEnum_type = &__pyx_type___pyx_MemviewEnum; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_MemviewEnum_type) < 0) __PYX_ERR(0, 302, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_MemviewEnum_type->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_MemviewEnum_type->tp_dictoffset && __pyx_MemviewEnum_type->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_MemviewEnum_type->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_MemviewEnum_type) < 0) __PYX_ERR(0, 302, __pyx_L1_error) + #endif + __pyx_vtabptr_memoryview = &__pyx_vtable_memoryview; + __pyx_vtable_memoryview.get_item_pointer = (char *(*)(struct __pyx_memoryview_obj *, PyObject *))__pyx_memoryview_get_item_pointer; + __pyx_vtable_memoryview.is_slice = (PyObject *(*)(struct __pyx_memoryview_obj *, PyObject *))__pyx_memoryview_is_slice; + __pyx_vtable_memoryview.setitem_slice_assignment = (PyObject *(*)(struct __pyx_memoryview_obj *, PyObject *, PyObject *))__pyx_memoryview_setitem_slice_assignment; + __pyx_vtable_memoryview.setitem_slice_assign_scalar = (PyObject *(*)(struct __pyx_memoryview_obj *, struct __pyx_memoryview_obj *, PyObject *))__pyx_memoryview_setitem_slice_assign_scalar; + __pyx_vtable_memoryview.setitem_indexed = (PyObject *(*)(struct __pyx_memoryview_obj *, PyObject *, PyObject *))__pyx_memoryview_setitem_indexed; + __pyx_vtable_memoryview.convert_item_to_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *))__pyx_memoryview_convert_item_to_object; + __pyx_vtable_memoryview.assign_item_from_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *, PyObject *))__pyx_memoryview_assign_item_from_object; + __pyx_vtable_memoryview._get_base = (PyObject *(*)(struct __pyx_memoryview_obj *))__pyx_memoryview__get_base; + #if CYTHON_USE_TYPE_SPECS + __pyx_memoryview_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_memoryview_spec, NULL); if (unlikely(!__pyx_memoryview_type)) __PYX_ERR(0, 337, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + __pyx_memoryview_type->tp_as_buffer = &__pyx_tp_as_buffer_memoryview; + if (!__pyx_memoryview_type->tp_as_buffer->bf_releasebuffer && __pyx_memoryview_type->tp_base->tp_as_buffer && __pyx_memoryview_type->tp_base->tp_as_buffer->bf_releasebuffer) { + __pyx_memoryview_type->tp_as_buffer->bf_releasebuffer = __pyx_memoryview_type->tp_base->tp_as_buffer->bf_releasebuffer; + } + #elif defined(Py_bf_getbuffer) && defined(Py_bf_releasebuffer) + /* PY_VERSION_HEX >= 0x03090000 || Py_LIMITED_API >= 0x030B0000 */ + #elif defined(_MSC_VER) + #pragma message ("The buffer protocol is not supported in the Limited C-API < 3.11.") + #else + #warning "The buffer protocol is not supported in the Limited C-API < 3.11." + #endif + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_memoryview_spec, __pyx_memoryview_type) < 0) __PYX_ERR(0, 337, __pyx_L1_error) + #else + __pyx_memoryview_type = &__pyx_type___pyx_memoryview; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_memoryview_type) < 0) __PYX_ERR(0, 337, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_memoryview_type->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_memoryview_type->tp_dictoffset && __pyx_memoryview_type->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_memoryview_type->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (__Pyx_SetVtable(__pyx_memoryview_type, __pyx_vtabptr_memoryview) < 0) __PYX_ERR(0, 337, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_memoryview_type) < 0) __PYX_ERR(0, 337, __pyx_L1_error) + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_memoryview_type) < 0) __PYX_ERR(0, 337, __pyx_L1_error) + #endif + __pyx_vtabptr__memoryviewslice = &__pyx_vtable__memoryviewslice; + __pyx_vtable__memoryviewslice.__pyx_base = *__pyx_vtabptr_memoryview; + __pyx_vtable__memoryviewslice.__pyx_base.convert_item_to_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *))__pyx_memoryviewslice_convert_item_to_object; + __pyx_vtable__memoryviewslice.__pyx_base.assign_item_from_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *, PyObject *))__pyx_memoryviewslice_assign_item_from_object; + __pyx_vtable__memoryviewslice.__pyx_base._get_base = (PyObject *(*)(struct __pyx_memoryview_obj *))__pyx_memoryviewslice__get_base; + #if CYTHON_USE_TYPE_SPECS + __pyx_t_2 = PyTuple_Pack(1, (PyObject *)__pyx_memoryview_type); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 952, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_memoryviewslice_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_memoryviewslice_spec, __pyx_t_2); + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + if (unlikely(!__pyx_memoryviewslice_type)) __PYX_ERR(0, 952, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_memoryviewslice_spec, __pyx_memoryviewslice_type) < 0) __PYX_ERR(0, 952, __pyx_L1_error) + #else + __pyx_memoryviewslice_type = &__pyx_type___pyx_memoryviewslice; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + __pyx_memoryviewslice_type->tp_base = __pyx_memoryview_type; + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_memoryviewslice_type) < 0) __PYX_ERR(0, 952, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_memoryviewslice_type->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_memoryviewslice_type->tp_dictoffset && __pyx_memoryviewslice_type->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_memoryviewslice_type->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (__Pyx_SetVtable(__pyx_memoryviewslice_type, __pyx_vtabptr__memoryviewslice) < 0) __PYX_ERR(0, 952, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_memoryviewslice_type) < 0) __PYX_ERR(0, 952, __pyx_L1_error) + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_memoryviewslice_type) < 0) __PYX_ERR(0, 952, __pyx_L1_error) + #endif + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_RefNannyFinishContext(); + return -1; +} + +static int __Pyx_modinit_type_import_code(void) { + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_modinit_type_import_code", 0); + /*--- Type import code ---*/ + __pyx_t_1 = PyImport_ImportModule("cereal.visionipc.visionipc_pyx"); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 7, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext = __Pyx_ImportType_3_0_8(__pyx_t_1, "cereal.visionipc.visionipc_pyx", "CLContext", sizeof(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_CLContext), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_CLContext),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext) __PYX_ERR(2, 7, __pyx_L1_error) + __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf = __Pyx_ImportType_3_0_8(__pyx_t_1, "cereal.visionipc.visionipc_pyx", "VisionBuf", sizeof(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf) __PYX_ERR(2, 11, __pyx_L1_error) + __pyx_vtabptr_6cereal_9visionipc_13visionipc_pyx_VisionBuf = (struct __pyx_vtabstruct_6cereal_9visionipc_13visionipc_pyx_VisionBuf*)__Pyx_GetVtable(__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf); if (unlikely(!__pyx_vtabptr_6cereal_9visionipc_13visionipc_pyx_VisionBuf)) __PYX_ERR(2, 11, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = PyImport_ImportModule("selfdrive.modeld.models.commonmodel_pyx"); if (unlikely(!__pyx_t_1)) __PYX_ERR(3, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext = __Pyx_ImportType_3_0_8(__pyx_t_1, "selfdrive.modeld.models.commonmodel_pyx", "CLContext", sizeof(struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext) __PYX_ERR(3, 6, __pyx_L1_error) + __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem = __Pyx_ImportType_3_0_8(__pyx_t_1, "selfdrive.modeld.models.commonmodel_pyx", "CLMem", sizeof(struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem) __PYX_ERR(3, 9, __pyx_L1_error) + __pyx_vtabptr_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem = (struct __pyx_vtabstruct_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem*)__Pyx_GetVtable(__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem); if (unlikely(!__pyx_vtabptr_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem)) __PYX_ERR(3, 9, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_RefNannyFinishContext(); + return -1; +} + +static int __Pyx_modinit_variable_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_import_code", 0); + /*--- Variable import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_import_code", 0); + /*--- Function import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + + +#if PY_MAJOR_VERSION >= 3 +#if CYTHON_PEP489_MULTI_PHASE_INIT +static PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def); /*proto*/ +static int __pyx_pymod_exec_snpemodel_pyx(PyObject* module); /*proto*/ +static PyModuleDef_Slot __pyx_moduledef_slots[] = { + {Py_mod_create, (void*)__pyx_pymod_create}, + {Py_mod_exec, (void*)__pyx_pymod_exec_snpemodel_pyx}, + {0, NULL} +}; +#endif + +#ifdef __cplusplus +namespace { + struct PyModuleDef __pyx_moduledef = + #else + static struct PyModuleDef __pyx_moduledef = + #endif + { + PyModuleDef_HEAD_INIT, + "snpemodel_pyx", + 0, /* m_doc */ + #if CYTHON_PEP489_MULTI_PHASE_INIT + 0, /* m_size */ + #elif CYTHON_USE_MODULE_STATE + sizeof(__pyx_mstate), /* m_size */ + #else + -1, /* m_size */ + #endif + __pyx_methods /* m_methods */, + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_moduledef_slots, /* m_slots */ + #else + NULL, /* m_reload */ + #endif + #if CYTHON_USE_MODULE_STATE + __pyx_m_traverse, /* m_traverse */ + __pyx_m_clear, /* m_clear */ + NULL /* m_free */ + #else + NULL, /* m_traverse */ + NULL, /* m_clear */ + NULL /* m_free */ + #endif + }; + #ifdef __cplusplus +} /* anonymous namespace */ +#endif +#endif + +#ifndef CYTHON_NO_PYINIT_EXPORT +#define __Pyx_PyMODINIT_FUNC PyMODINIT_FUNC +#elif PY_MAJOR_VERSION < 3 +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" void +#else +#define __Pyx_PyMODINIT_FUNC void +#endif +#else +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" PyObject * +#else +#define __Pyx_PyMODINIT_FUNC PyObject * +#endif +#endif + + +#if PY_MAJOR_VERSION < 3 +__Pyx_PyMODINIT_FUNC initsnpemodel_pyx(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC initsnpemodel_pyx(void) +#else +__Pyx_PyMODINIT_FUNC PyInit_snpemodel_pyx(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC PyInit_snpemodel_pyx(void) +#if CYTHON_PEP489_MULTI_PHASE_INIT +{ + return PyModuleDef_Init(&__pyx_moduledef); +} +static CYTHON_SMALL_CODE int __Pyx_check_single_interpreter(void) { + #if PY_VERSION_HEX >= 0x030700A1 + static PY_INT64_T main_interpreter_id = -1; + PY_INT64_T current_id = PyInterpreterState_GetID(PyThreadState_Get()->interp); + if (main_interpreter_id == -1) { + main_interpreter_id = current_id; + return (unlikely(current_id == -1)) ? -1 : 0; + } else if (unlikely(main_interpreter_id != current_id)) + #else + static PyInterpreterState *main_interpreter = NULL; + PyInterpreterState *current_interpreter = PyThreadState_Get()->interp; + if (!main_interpreter) { + main_interpreter = current_interpreter; + } else if (unlikely(main_interpreter != current_interpreter)) + #endif + { + PyErr_SetString( + PyExc_ImportError, + "Interpreter change detected - this module can only be loaded into one interpreter per process."); + return -1; + } + return 0; +} +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *module, const char* from_name, const char* to_name, int allow_none) +#else +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *moddict, const char* from_name, const char* to_name, int allow_none) +#endif +{ + PyObject *value = PyObject_GetAttrString(spec, from_name); + int result = 0; + if (likely(value)) { + if (allow_none || value != Py_None) { +#if CYTHON_COMPILING_IN_LIMITED_API + result = PyModule_AddObject(module, to_name, value); +#else + result = PyDict_SetItemString(moddict, to_name, value); +#endif + } + Py_DECREF(value); + } else if (PyErr_ExceptionMatches(PyExc_AttributeError)) { + PyErr_Clear(); + } else { + result = -1; + } + return result; +} +static CYTHON_SMALL_CODE PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def) { + PyObject *module = NULL, *moddict, *modname; + CYTHON_UNUSED_VAR(def); + if (__Pyx_check_single_interpreter()) + return NULL; + if (__pyx_m) + return __Pyx_NewRef(__pyx_m); + modname = PyObject_GetAttrString(spec, "name"); + if (unlikely(!modname)) goto bad; + module = PyModule_NewObject(modname); + Py_DECREF(modname); + if (unlikely(!module)) goto bad; +#if CYTHON_COMPILING_IN_LIMITED_API + moddict = module; +#else + moddict = PyModule_GetDict(module); + if (unlikely(!moddict)) goto bad; +#endif + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "loader", "__loader__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "origin", "__file__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "parent", "__package__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "submodule_search_locations", "__path__", 0) < 0)) goto bad; + return module; +bad: + Py_XDECREF(module); + return NULL; +} + + +static CYTHON_SMALL_CODE int __pyx_pymod_exec_snpemodel_pyx(PyObject *__pyx_pyinit_module) +#endif +#endif +{ + int stringtab_initialized = 0; + #if CYTHON_USE_MODULE_STATE + int pystate_addmodule_run = 0; + #endif + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + static PyThread_type_lock __pyx_t_8[8]; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannyDeclarations + #if CYTHON_PEP489_MULTI_PHASE_INIT + if (__pyx_m) { + if (__pyx_m == __pyx_pyinit_module) return 0; + PyErr_SetString(PyExc_RuntimeError, "Module 'snpemodel_pyx' has already been imported. Re-initialisation is not supported."); + return -1; + } + #elif PY_MAJOR_VERSION >= 3 + if (__pyx_m) return __Pyx_NewRef(__pyx_m); + #endif + /*--- Module creation code ---*/ + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_m = __pyx_pyinit_module; + Py_INCREF(__pyx_m); + #else + #if PY_MAJOR_VERSION < 3 + __pyx_m = Py_InitModule4("snpemodel_pyx", __pyx_methods, 0, 0, PYTHON_API_VERSION); Py_XINCREF(__pyx_m); + if (unlikely(!__pyx_m)) __PYX_ERR(1, 1, __pyx_L1_error) + #elif CYTHON_USE_MODULE_STATE + __pyx_t_1 = PyModule_Create(&__pyx_moduledef); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 1, __pyx_L1_error) + { + int add_module_result = PyState_AddModule(__pyx_t_1, &__pyx_moduledef); + __pyx_t_1 = 0; /* transfer ownership from __pyx_t_1 to "snpemodel_pyx" pseudovariable */ + if (unlikely((add_module_result < 0))) __PYX_ERR(1, 1, __pyx_L1_error) + pystate_addmodule_run = 1; + } + #else + __pyx_m = PyModule_Create(&__pyx_moduledef); + if (unlikely(!__pyx_m)) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + #endif + CYTHON_UNUSED_VAR(__pyx_t_1); + __pyx_d = PyModule_GetDict(__pyx_m); if (unlikely(!__pyx_d)) __PYX_ERR(1, 1, __pyx_L1_error) + Py_INCREF(__pyx_d); + __pyx_b = __Pyx_PyImport_AddModuleRef(__Pyx_BUILTIN_MODULE_NAME); if (unlikely(!__pyx_b)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_cython_runtime = __Pyx_PyImport_AddModuleRef((const char *) "cython_runtime"); if (unlikely(!__pyx_cython_runtime)) __PYX_ERR(1, 1, __pyx_L1_error) + if (PyObject_SetAttrString(__pyx_m, "__builtins__", __pyx_b) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #if CYTHON_REFNANNY +__Pyx_RefNanny = __Pyx_RefNannyImportAPI("refnanny"); +if (!__Pyx_RefNanny) { + PyErr_Clear(); + __Pyx_RefNanny = __Pyx_RefNannyImportAPI("Cython.Runtime.refnanny"); + if (!__Pyx_RefNanny) + Py_FatalError("failed to import 'refnanny' module"); +} +#endif + __Pyx_RefNannySetupContext("__Pyx_PyMODINIT_FUNC PyInit_snpemodel_pyx(void)", 0); + if (__Pyx_check_binary_version(__PYX_LIMITED_VERSION_HEX, __Pyx_get_runtime_version(), CYTHON_COMPILING_IN_LIMITED_API) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #ifdef __Pxy_PyFrame_Initialize_Offsets + __Pxy_PyFrame_Initialize_Offsets(); + #endif + __pyx_empty_tuple = PyTuple_New(0); if (unlikely(!__pyx_empty_tuple)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_empty_bytes = PyBytes_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_bytes)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_empty_unicode = PyUnicode_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_unicode)) __PYX_ERR(1, 1, __pyx_L1_error) + #ifdef __Pyx_CyFunction_USED + if (__pyx_CyFunction_init(__pyx_m) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_FusedFunction_USED + if (__pyx_FusedFunction_init(__pyx_m) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Coroutine_USED + if (__pyx_Coroutine_init(__pyx_m) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Generator_USED + if (__pyx_Generator_init(__pyx_m) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_AsyncGen_USED + if (__pyx_AsyncGen_init(__pyx_m) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_StopAsyncIteration_USED + if (__pyx_StopAsyncIteration_init(__pyx_m) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + /*--- Library function declarations ---*/ + /*--- Threads initialization code ---*/ + #if defined(WITH_THREAD) && PY_VERSION_HEX < 0x030700F0 && defined(__PYX_FORCE_INIT_THREADS) && __PYX_FORCE_INIT_THREADS + PyEval_InitThreads(); + #endif + /*--- Initialize various global constants etc. ---*/ + if (__Pyx_InitConstants() < 0) __PYX_ERR(1, 1, __pyx_L1_error) + stringtab_initialized = 1; + if (__Pyx_InitGlobals() < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #if PY_MAJOR_VERSION < 3 && (__PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT) + if (__Pyx_init_sys_getdefaultencoding_params() < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + if (__pyx_module_is_main_selfdrive__modeld__runners__snpemodel_pyx) { + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_name_2, __pyx_n_s_main) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + } + #if PY_MAJOR_VERSION >= 3 + { + PyObject *modules = PyImport_GetModuleDict(); if (unlikely(!modules)) __PYX_ERR(1, 1, __pyx_L1_error) + if (!PyDict_GetItemString(modules, "selfdrive.modeld.runners.snpemodel_pyx")) { + if (unlikely((PyDict_SetItemString(modules, "selfdrive.modeld.runners.snpemodel_pyx", __pyx_m) < 0))) __PYX_ERR(1, 1, __pyx_L1_error) + } + } + #endif + /*--- Builtin init code ---*/ + if (__Pyx_InitCachedBuiltins() < 0) __PYX_ERR(1, 1, __pyx_L1_error) + /*--- Constants init code ---*/ + if (__Pyx_InitCachedConstants() < 0) __PYX_ERR(1, 1, __pyx_L1_error) + /*--- Global type/function init code ---*/ + (void)__Pyx_modinit_global_init_code(); + (void)__Pyx_modinit_variable_export_code(); + (void)__Pyx_modinit_function_export_code(); + if (unlikely((__Pyx_modinit_type_init_code() < 0))) __PYX_ERR(1, 1, __pyx_L1_error) + if (unlikely((__Pyx_modinit_type_import_code() < 0))) __PYX_ERR(1, 1, __pyx_L1_error) + (void)__Pyx_modinit_variable_import_code(); + (void)__Pyx_modinit_function_import_code(); + /*--- Execution code ---*/ + #if defined(__Pyx_Generator_USED) || defined(__Pyx_Coroutine_USED) + if (__Pyx_patch_abc() < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + + /* "View.MemoryView":99 + * + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: # <<<<<<<<<<<<<< + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "View.MemoryView":100 + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: + * if __import__("sys").version_info >= (3, 3): # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + */ + __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__9, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 100, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_version_info); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 100, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = PyObject_RichCompare(__pyx_t_5, __pyx_tuple__10, Py_GE); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 100, __pyx_L2_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_6 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 100, __pyx_L2_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (__pyx_t_6) { + + /* "View.MemoryView":101 + * try: + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence # <<<<<<<<<<<<<< + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence + */ + __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__11, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 101, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_abc); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 101, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_Sequence); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 101, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XGOTREF(__pyx_collections_abc_Sequence); + __Pyx_DECREF_SET(__pyx_collections_abc_Sequence, __pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + __pyx_t_4 = 0; + + /* "View.MemoryView":100 + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: + * if __import__("sys").version_info >= (3, 3): # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + */ + goto __pyx_L8; + } + + /* "View.MemoryView":103 + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence # <<<<<<<<<<<<<< + * except: + * + */ + /*else*/ { + __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__12, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 103, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_Sequence); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 103, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XGOTREF(__pyx_collections_abc_Sequence); + __Pyx_DECREF_SET(__pyx_collections_abc_Sequence, __pyx_t_5); + __Pyx_GIVEREF(__pyx_t_5); + __pyx_t_5 = 0; + } + __pyx_L8:; + + /* "View.MemoryView":99 + * + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: # <<<<<<<<<<<<<< + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L7_try_end; + __pyx_L2_error:; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "View.MemoryView":104 + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence + * except: # <<<<<<<<<<<<<< + * + * __pyx_collections_abc_Sequence = None + */ + /*except:*/ { + __Pyx_AddTraceback("View.MemoryView", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_4, &__pyx_t_7) < 0) __PYX_ERR(0, 104, __pyx_L4_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_4); + __Pyx_XGOTREF(__pyx_t_7); + + /* "View.MemoryView":106 + * except: + * + * __pyx_collections_abc_Sequence = None # <<<<<<<<<<<<<< + * + * + */ + __Pyx_INCREF(Py_None); + __Pyx_XGOTREF(__pyx_collections_abc_Sequence); + __Pyx_DECREF_SET(__pyx_collections_abc_Sequence, Py_None); + __Pyx_GIVEREF(Py_None); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + goto __pyx_L3_exception_handled; + } + + /* "View.MemoryView":99 + * + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: # <<<<<<<<<<<<<< + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + */ + __pyx_L4_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + goto __pyx_L1_error; + __pyx_L3_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + __pyx_L7_try_end:; + } + + /* "View.MemoryView":241 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_3, &__pyx_t_2, &__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_1); + /*try:*/ { + + /* "View.MemoryView":242 + * + * try: + * count = __pyx_collections_abc_Sequence.count # <<<<<<<<<<<<<< + * index = __pyx_collections_abc_Sequence.index + * except: + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_count); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 242, __pyx_L11_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict(__pyx_array_type, __pyx_n_s_count, __pyx_t_7) < 0) __PYX_ERR(0, 242, __pyx_L11_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_array_type); + + /* "View.MemoryView":243 + * try: + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index # <<<<<<<<<<<<<< + * except: + * pass + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_index); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 243, __pyx_L11_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict(__pyx_array_type, __pyx_n_s_index, __pyx_t_7) < 0) __PYX_ERR(0, 243, __pyx_L11_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_array_type); + + /* "View.MemoryView":241 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + } + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + goto __pyx_L16_try_end; + __pyx_L11_error:; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":244 + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + * except: # <<<<<<<<<<<<<< + * pass + * + */ + /*except:*/ { + __Pyx_ErrRestore(0,0,0); + goto __pyx_L12_exception_handled; + } + __pyx_L12_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_2, __pyx_t_1); + __pyx_L16_try_end:; + } + + /* "View.MemoryView":309 + * return self.name + * + * cdef generic = Enum("") # <<<<<<<<<<<<<< + * cdef strided = Enum("") # default + * cdef indirect = Enum("") + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__13, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 309, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(generic); + __Pyx_DECREF_SET(generic, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":310 + * + * cdef generic = Enum("") + * cdef strided = Enum("") # default # <<<<<<<<<<<<<< + * cdef indirect = Enum("") + * + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__14, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 310, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(strided); + __Pyx_DECREF_SET(strided, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":311 + * cdef generic = Enum("") + * cdef strided = Enum("") # default + * cdef indirect = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__15, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 311, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(indirect); + __Pyx_DECREF_SET(indirect, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":314 + * + * + * cdef contiguous = Enum("") # <<<<<<<<<<<<<< + * cdef indirect_contiguous = Enum("") + * + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__16, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 314, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(contiguous); + __Pyx_DECREF_SET(contiguous, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":315 + * + * cdef contiguous = Enum("") + * cdef indirect_contiguous = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__17, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 315, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(indirect_contiguous); + __Pyx_DECREF_SET(indirect_contiguous, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":323 + * + * + * cdef int __pyx_memoryview_thread_locks_used = 0 # <<<<<<<<<<<<<< + * cdef PyThread_type_lock[8] __pyx_memoryview_thread_locks = [ + * PyThread_allocate_lock(), + */ + __pyx_memoryview_thread_locks_used = 0; + + /* "View.MemoryView":324 + * + * cdef int __pyx_memoryview_thread_locks_used = 0 + * cdef PyThread_type_lock[8] __pyx_memoryview_thread_locks = [ # <<<<<<<<<<<<<< + * PyThread_allocate_lock(), + * PyThread_allocate_lock(), + */ + __pyx_t_8[0] = PyThread_allocate_lock(); + __pyx_t_8[1] = PyThread_allocate_lock(); + __pyx_t_8[2] = PyThread_allocate_lock(); + __pyx_t_8[3] = PyThread_allocate_lock(); + __pyx_t_8[4] = PyThread_allocate_lock(); + __pyx_t_8[5] = PyThread_allocate_lock(); + __pyx_t_8[6] = PyThread_allocate_lock(); + __pyx_t_8[7] = PyThread_allocate_lock(); + memcpy(&(__pyx_memoryview_thread_locks[0]), __pyx_t_8, sizeof(__pyx_memoryview_thread_locks[0]) * (8)); + + /* "View.MemoryView":982 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "View.MemoryView":983 + * + * try: + * count = __pyx_collections_abc_Sequence.count # <<<<<<<<<<<<<< + * index = __pyx_collections_abc_Sequence.index + * except: + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_count); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 983, __pyx_L17_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict(__pyx_memoryviewslice_type, __pyx_n_s_count, __pyx_t_7) < 0) __PYX_ERR(0, 983, __pyx_L17_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_memoryviewslice_type); + + /* "View.MemoryView":984 + * try: + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index # <<<<<<<<<<<<<< + * except: + * pass + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_index); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 984, __pyx_L17_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict(__pyx_memoryviewslice_type, __pyx_n_s_index, __pyx_t_7) < 0) __PYX_ERR(0, 984, __pyx_L17_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_memoryviewslice_type); + + /* "View.MemoryView":982 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L22_try_end; + __pyx_L17_error:; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":985 + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + * except: # <<<<<<<<<<<<<< + * pass + * + */ + /*except:*/ { + __Pyx_ErrRestore(0,0,0); + goto __pyx_L18_exception_handled; + } + __pyx_L18_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + __pyx_L22_try_end:; + } + + /* "View.MemoryView":988 + * pass + * + * try: # <<<<<<<<<<<<<< + * if __pyx_collections_abc_Sequence: + * + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_3, &__pyx_t_2, &__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_1); + /*try:*/ { + + /* "View.MemoryView":989 + * + * try: + * if __pyx_collections_abc_Sequence: # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_6 = __Pyx_PyObject_IsTrue(__pyx_collections_abc_Sequence); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 989, __pyx_L23_error) + if (__pyx_t_6) { + + /* "View.MemoryView":993 + * + * + * __pyx_collections_abc_Sequence.register(_memoryviewslice) # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence.register(array) + * except: + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_register); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 993, __pyx_L23_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_4 = __Pyx_PyObject_CallOneArg(__pyx_t_7, ((PyObject *)__pyx_memoryviewslice_type)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 993, __pyx_L23_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "View.MemoryView":994 + * + * __pyx_collections_abc_Sequence.register(_memoryviewslice) + * __pyx_collections_abc_Sequence.register(array) # <<<<<<<<<<<<<< + * except: + * pass # ignore failure, it's a minor issue + */ + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_register); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 994, __pyx_L23_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_7 = __Pyx_PyObject_CallOneArg(__pyx_t_4, ((PyObject *)__pyx_array_type)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 994, __pyx_L23_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":989 + * + * try: + * if __pyx_collections_abc_Sequence: # <<<<<<<<<<<<<< + * + * + */ + } + + /* "View.MemoryView":988 + * pass + * + * try: # <<<<<<<<<<<<<< + * if __pyx_collections_abc_Sequence: + * + */ + } + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + goto __pyx_L28_try_end; + __pyx_L23_error:; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":995 + * __pyx_collections_abc_Sequence.register(_memoryviewslice) + * __pyx_collections_abc_Sequence.register(array) + * except: # <<<<<<<<<<<<<< + * pass # ignore failure, it's a minor issue + * + */ + /*except:*/ { + __Pyx_ErrRestore(0,0,0); + goto __pyx_L24_exception_handled; + } + __pyx_L24_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_2, __pyx_t_1); + __pyx_L28_try_end:; + } + + /* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + __pyx_t_7 = PyCFunction_NewEx(&__pyx_mdef_15View_dot_MemoryView_1__pyx_unpickle_Enum, NULL, __pyx_n_s_View_MemoryView); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_pyx_unpickle_Enum, __pyx_t_7) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "selfdrive/modeld/runners/snpemodel_pyx.pyx":4 + * # cython: c_string_encoding=ascii + * + * import os # <<<<<<<<<<<<<< + * from libcpp cimport bool + * from libcpp.string cimport string + */ + __pyx_t_7 = __Pyx_ImportDottedModule(__pyx_n_s_os, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 4, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_os, __pyx_t_7) < 0) __PYX_ERR(1, 4, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "selfdrive/modeld/runners/snpemodel_pyx.pyx":13 + * from selfdrive.modeld.runners.runmodel cimport RunModel as cppRunModel + * + * os.environ['ADSP_LIBRARY_PATH'] = "/data/pythonpath/third_party/snpe/dsp/" # <<<<<<<<<<<<<< + * + * cdef class SNPEModel(RunModel): + */ + __Pyx_GetModuleGlobalName(__pyx_t_7, __pyx_n_s_os); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_7, __pyx_n_s_environ); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + if (unlikely((PyObject_SetItem(__pyx_t_4, __pyx_n_s_ADSP_LIBRARY_PATH, __pyx_kp_s_data_pythonpath_third_party_snp) < 0))) __PYX_ERR(1, 13, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_9selfdrive_6modeld_7runners_13snpemodel_pyx_9SNPEModel_3__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_SNPEModel___reduce_cython, NULL, __pyx_n_s_selfdrive_modeld_runners_snpemod, __pyx_d, ((PyObject *)__pyx_codeobj__21)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_4) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_t_4 = __Pyx_CyFunction_New(&__pyx_mdef_9selfdrive_6modeld_7runners_13snpemodel_pyx_9SNPEModel_5__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_SNPEModel___setstate_cython, NULL, __pyx_n_s_selfdrive_modeld_runners_snpemod, __pyx_d, ((PyObject *)__pyx_codeobj__23)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_4) < 0) __PYX_ERR(0, 3, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "selfdrive/modeld/runners/snpemodel_pyx.pyx":1 + * # distutils: language = c++ # <<<<<<<<<<<<<< + * # cython: c_string_encoding=ascii + * + */ + __pyx_t_4 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_test, __pyx_t_4) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /*--- Wrapped vars code ---*/ + + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_7); + if (__pyx_m) { + if (__pyx_d && stringtab_initialized) { + __Pyx_AddTraceback("init selfdrive.modeld.runners.snpemodel_pyx", __pyx_clineno, __pyx_lineno, __pyx_filename); + } + #if !CYTHON_USE_MODULE_STATE + Py_CLEAR(__pyx_m); + #else + Py_DECREF(__pyx_m); + if (pystate_addmodule_run) { + PyObject *tp, *value, *tb; + PyErr_Fetch(&tp, &value, &tb); + PyState_RemoveModule(&__pyx_moduledef); + PyErr_Restore(tp, value, tb); + } + #endif + } else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_ImportError, "init selfdrive.modeld.runners.snpemodel_pyx"); + } + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + #if CYTHON_PEP489_MULTI_PHASE_INIT + return (__pyx_m != NULL) ? 0 : -1; + #elif PY_MAJOR_VERSION >= 3 + return __pyx_m; + #else + return; + #endif +} +/* #### Code section: cleanup_globals ### */ +/* #### Code section: cleanup_module ### */ +/* #### Code section: main_method ### */ +/* #### Code section: utility_code_pragmas ### */ +#ifdef _MSC_VER +#pragma warning( push ) +/* Warning 4127: conditional expression is constant + * Cython uses constant conditional expressions to allow in inline functions to be optimized at + * compile-time, so this warning is not useful + */ +#pragma warning( disable : 4127 ) +#endif + + + +/* #### Code section: utility_code_def ### */ + +/* --- Runtime support code --- */ +/* Refnanny */ +#if CYTHON_REFNANNY +static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname) { + PyObject *m = NULL, *p = NULL; + void *r = NULL; + m = PyImport_ImportModule(modname); + if (!m) goto end; + p = PyObject_GetAttrString(m, "RefNannyAPI"); + if (!p) goto end; + r = PyLong_AsVoidPtr(p); +end: + Py_XDECREF(p); + Py_XDECREF(m); + return (__Pyx_RefNannyAPIStruct *)r; +} +#endif + +/* PyErrExceptionMatches */ +#if CYTHON_FAST_THREAD_STATE +static int __Pyx_PyErr_ExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; i= 0x030C00A6 + PyObject *current_exception = tstate->current_exception; + if (unlikely(!current_exception)) return 0; + exc_type = (PyObject*) Py_TYPE(current_exception); + if (exc_type == err) return 1; +#else + exc_type = tstate->curexc_type; + if (exc_type == err) return 1; + if (unlikely(!exc_type)) return 0; +#endif + #if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(exc_type); + #endif + if (unlikely(PyTuple_Check(err))) { + result = __Pyx_PyErr_ExceptionMatchesTuple(exc_type, err); + } else { + result = __Pyx_PyErr_GivenExceptionMatches(exc_type, err); + } + #if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(exc_type); + #endif + return result; +} +#endif + +/* PyErrFetchRestore */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject *tmp_value; + assert(type == NULL || (value != NULL && type == (PyObject*) Py_TYPE(value))); + if (value) { + #if CYTHON_COMPILING_IN_CPYTHON + if (unlikely(((PyBaseExceptionObject*) value)->traceback != tb)) + #endif + PyException_SetTraceback(value, tb); + } + tmp_value = tstate->current_exception; + tstate->current_exception = value; + Py_XDECREF(tmp_value); + Py_XDECREF(type); + Py_XDECREF(tb); +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + tmp_type = tstate->curexc_type; + tmp_value = tstate->curexc_value; + tmp_tb = tstate->curexc_traceback; + tstate->curexc_type = type; + tstate->curexc_value = value; + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); +#endif +} +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject* exc_value; + exc_value = tstate->current_exception; + tstate->current_exception = 0; + *value = exc_value; + *type = NULL; + *tb = NULL; + if (exc_value) { + *type = (PyObject*) Py_TYPE(exc_value); + Py_INCREF(*type); + #if CYTHON_COMPILING_IN_CPYTHON + *tb = ((PyBaseExceptionObject*) exc_value)->traceback; + Py_XINCREF(*tb); + #else + *tb = PyException_GetTraceback(exc_value); + #endif + } +#else + *type = tstate->curexc_type; + *value = tstate->curexc_value; + *tb = tstate->curexc_traceback; + tstate->curexc_type = 0; + tstate->curexc_value = 0; + tstate->curexc_traceback = 0; +#endif +} +#endif + +/* PyObjectGetAttrStr */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name) { + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro)) + return tp->tp_getattro(obj, attr_name); +#if PY_MAJOR_VERSION < 3 + if (likely(tp->tp_getattr)) + return tp->tp_getattr(obj, PyString_AS_STRING(attr_name)); +#endif + return PyObject_GetAttr(obj, attr_name); +} +#endif + +/* PyObjectGetAttrStrNoError */ +#if __PYX_LIMITED_VERSION_HEX < 0x030d00A1 +static void __Pyx_PyObject_GetAttrStr_ClearAttributeError(void) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + if (likely(__Pyx_PyErr_ExceptionMatches(PyExc_AttributeError))) + __Pyx_PyErr_Clear(); +} +#endif +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name) { + PyObject *result; +#if __PYX_LIMITED_VERSION_HEX >= 0x030d00A1 + (void) PyObject_GetOptionalAttr(obj, attr_name, &result); + return result; +#else +#if CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_TYPE_SLOTS && PY_VERSION_HEX >= 0x030700B1 + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro == PyObject_GenericGetAttr)) { + return _PyObject_GenericGetAttrWithDict(obj, attr_name, NULL, 1); + } +#endif + result = __Pyx_PyObject_GetAttrStr(obj, attr_name); + if (unlikely(!result)) { + __Pyx_PyObject_GetAttrStr_ClearAttributeError(); + } + return result; +#endif +} + +/* GetBuiltinName */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name) { + PyObject* result = __Pyx_PyObject_GetAttrStrNoError(__pyx_b, name); + if (unlikely(!result) && !PyErr_Occurred()) { + PyErr_Format(PyExc_NameError, +#if PY_MAJOR_VERSION >= 3 + "name '%U' is not defined", name); +#else + "name '%.200s' is not defined", PyString_AS_STRING(name)); +#endif + } + return result; +} + +/* TupleAndListFromArray */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE void __Pyx_copy_object_array(PyObject *const *CYTHON_RESTRICT src, PyObject** CYTHON_RESTRICT dest, Py_ssize_t length) { + PyObject *v; + Py_ssize_t i; + for (i = 0; i < length; i++) { + v = dest[i] = src[i]; + Py_INCREF(v); + } +} +static CYTHON_INLINE PyObject * +__Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + Py_INCREF(__pyx_empty_tuple); + return __pyx_empty_tuple; + } + res = PyTuple_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyTupleObject*)res)->ob_item, n); + return res; +} +static CYTHON_INLINE PyObject * +__Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + return PyList_New(0); + } + res = PyList_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyListObject*)res)->ob_item, n); + return res; +} +#endif + +/* BytesEquals */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else + if (s1 == s2) { + return (equals == Py_EQ); + } else if (PyBytes_CheckExact(s1) & PyBytes_CheckExact(s2)) { + const char *ps1, *ps2; + Py_ssize_t length = PyBytes_GET_SIZE(s1); + if (length != PyBytes_GET_SIZE(s2)) + return (equals == Py_NE); + ps1 = PyBytes_AS_STRING(s1); + ps2 = PyBytes_AS_STRING(s2); + if (ps1[0] != ps2[0]) { + return (equals == Py_NE); + } else if (length == 1) { + return (equals == Py_EQ); + } else { + int result; +#if CYTHON_USE_UNICODE_INTERNALS && (PY_VERSION_HEX < 0x030B0000) + Py_hash_t hash1, hash2; + hash1 = ((PyBytesObject*)s1)->ob_shash; + hash2 = ((PyBytesObject*)s2)->ob_shash; + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + return (equals == Py_NE); + } +#endif + result = memcmp(ps1, ps2, (size_t)length); + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & PyBytes_CheckExact(s2)) { + return (equals == Py_NE); + } else if ((s2 == Py_None) & PyBytes_CheckExact(s1)) { + return (equals == Py_NE); + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +#endif +} + +/* UnicodeEquals */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else +#if PY_MAJOR_VERSION < 3 + PyObject* owned_ref = NULL; +#endif + int s1_is_unicode, s2_is_unicode; + if (s1 == s2) { + goto return_eq; + } + s1_is_unicode = PyUnicode_CheckExact(s1); + s2_is_unicode = PyUnicode_CheckExact(s2); +#if PY_MAJOR_VERSION < 3 + if ((s1_is_unicode & (!s2_is_unicode)) && PyString_CheckExact(s2)) { + owned_ref = PyUnicode_FromObject(s2); + if (unlikely(!owned_ref)) + return -1; + s2 = owned_ref; + s2_is_unicode = 1; + } else if ((s2_is_unicode & (!s1_is_unicode)) && PyString_CheckExact(s1)) { + owned_ref = PyUnicode_FromObject(s1); + if (unlikely(!owned_ref)) + return -1; + s1 = owned_ref; + s1_is_unicode = 1; + } else if (((!s2_is_unicode) & (!s1_is_unicode))) { + return __Pyx_PyBytes_Equals(s1, s2, equals); + } +#endif + if (s1_is_unicode & s2_is_unicode) { + Py_ssize_t length; + int kind; + void *data1, *data2; + if (unlikely(__Pyx_PyUnicode_READY(s1) < 0) || unlikely(__Pyx_PyUnicode_READY(s2) < 0)) + return -1; + length = __Pyx_PyUnicode_GET_LENGTH(s1); + if (length != __Pyx_PyUnicode_GET_LENGTH(s2)) { + goto return_ne; + } +#if CYTHON_USE_UNICODE_INTERNALS + { + Py_hash_t hash1, hash2; + #if CYTHON_PEP393_ENABLED + hash1 = ((PyASCIIObject*)s1)->hash; + hash2 = ((PyASCIIObject*)s2)->hash; + #else + hash1 = ((PyUnicodeObject*)s1)->hash; + hash2 = ((PyUnicodeObject*)s2)->hash; + #endif + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + goto return_ne; + } + } +#endif + kind = __Pyx_PyUnicode_KIND(s1); + if (kind != __Pyx_PyUnicode_KIND(s2)) { + goto return_ne; + } + data1 = __Pyx_PyUnicode_DATA(s1); + data2 = __Pyx_PyUnicode_DATA(s2); + if (__Pyx_PyUnicode_READ(kind, data1, 0) != __Pyx_PyUnicode_READ(kind, data2, 0)) { + goto return_ne; + } else if (length == 1) { + goto return_eq; + } else { + int result = memcmp(data1, data2, (size_t)(length * kind)); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & s2_is_unicode) { + goto return_ne; + } else if ((s2 == Py_None) & s1_is_unicode) { + goto return_ne; + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +return_eq: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ); +return_ne: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_NE); +#endif +} + +/* fastcall */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s) +{ + Py_ssize_t i, n = PyTuple_GET_SIZE(kwnames); + for (i = 0; i < n; i++) + { + if (s == PyTuple_GET_ITEM(kwnames, i)) return kwvalues[i]; + } + for (i = 0; i < n; i++) + { + int eq = __Pyx_PyUnicode_Equals(s, PyTuple_GET_ITEM(kwnames, i), Py_EQ); + if (unlikely(eq != 0)) { + if (unlikely(eq < 0)) return NULL; + return kwvalues[i]; + } + } + return NULL; +} +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 +CYTHON_UNUSED static PyObject *__Pyx_KwargsAsDict_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues) { + Py_ssize_t i, nkwargs = PyTuple_GET_SIZE(kwnames); + PyObject *dict; + dict = PyDict_New(); + if (unlikely(!dict)) + return NULL; + for (i=0; i= 3 + "%s() got multiple values for keyword argument '%U'", func_name, kw_name); + #else + "%s() got multiple values for keyword argument '%s'", func_name, + PyString_AsString(kw_name)); + #endif +} + +/* ParseKeywords */ +static int __Pyx_ParseOptionalKeywords( + PyObject *kwds, + PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, + PyObject *values[], + Py_ssize_t num_pos_args, + const char* function_name) +{ + PyObject *key = 0, *value = 0; + Py_ssize_t pos = 0; + PyObject*** name; + PyObject*** first_kw_arg = argnames + num_pos_args; + int kwds_is_tuple = CYTHON_METH_FASTCALL && likely(PyTuple_Check(kwds)); + while (1) { + Py_XDECREF(key); key = NULL; + Py_XDECREF(value); value = NULL; + if (kwds_is_tuple) { + Py_ssize_t size; +#if CYTHON_ASSUME_SAFE_MACROS + size = PyTuple_GET_SIZE(kwds); +#else + size = PyTuple_Size(kwds); + if (size < 0) goto bad; +#endif + if (pos >= size) break; +#if CYTHON_AVOID_BORROWED_REFS + key = __Pyx_PySequence_ITEM(kwds, pos); + if (!key) goto bad; +#elif CYTHON_ASSUME_SAFE_MACROS + key = PyTuple_GET_ITEM(kwds, pos); +#else + key = PyTuple_GetItem(kwds, pos); + if (!key) goto bad; +#endif + value = kwvalues[pos]; + pos++; + } + else + { + if (!PyDict_Next(kwds, &pos, &key, &value)) break; +#if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(key); +#endif + } + name = first_kw_arg; + while (*name && (**name != key)) name++; + if (*name) { + values[name-argnames] = value; +#if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(value); + Py_DECREF(key); +#endif + key = NULL; + value = NULL; + continue; + } +#if !CYTHON_AVOID_BORROWED_REFS + Py_INCREF(key); +#endif + Py_INCREF(value); + name = first_kw_arg; + #if PY_MAJOR_VERSION < 3 + if (likely(PyString_Check(key))) { + while (*name) { + if ((CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**name) == PyString_GET_SIZE(key)) + && _PyString_Eq(**name, key)) { + values[name-argnames] = value; +#if CYTHON_AVOID_BORROWED_REFS + value = NULL; +#endif + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + if ((**argname == key) || ( + (CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**argname) == PyString_GET_SIZE(key)) + && _PyString_Eq(**argname, key))) { + goto arg_passed_twice; + } + argname++; + } + } + } else + #endif + if (likely(PyUnicode_Check(key))) { + while (*name) { + int cmp = ( + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**name) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**name, key) + ); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) { + values[name-argnames] = value; +#if CYTHON_AVOID_BORROWED_REFS + value = NULL; +#endif + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + int cmp = (**argname == key) ? 0 : + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**argname) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**argname, key); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) goto arg_passed_twice; + argname++; + } + } + } else + goto invalid_keyword_type; + if (kwds2) { + if (unlikely(PyDict_SetItem(kwds2, key, value))) goto bad; + } else { + goto invalid_keyword; + } + } + Py_XDECREF(key); + Py_XDECREF(value); + return 0; +arg_passed_twice: + __Pyx_RaiseDoubleKeywordsError(function_name, key); + goto bad; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + goto bad; +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif +bad: + Py_XDECREF(key); + Py_XDECREF(value); + return -1; +} + +/* ArgTypeTest */ +static int __Pyx__ArgTypeTest(PyObject *obj, PyTypeObject *type, const char *name, int exact) +{ + __Pyx_TypeName type_name; + __Pyx_TypeName obj_type_name; + if (unlikely(!type)) { + PyErr_SetString(PyExc_SystemError, "Missing type object"); + return 0; + } + else if (exact) { + #if PY_MAJOR_VERSION == 2 + if ((type == &PyBaseString_Type) && likely(__Pyx_PyBaseString_CheckExact(obj))) return 1; + #endif + } + else { + if (likely(__Pyx_TypeCheck(obj, type))) return 1; + } + type_name = __Pyx_PyType_GetName(type); + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "Argument '%.200s' has incorrect type (expected " __Pyx_FMT_TYPENAME + ", got " __Pyx_FMT_TYPENAME ")", name, type_name, obj_type_name); + __Pyx_DECREF_TypeName(type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return 0; +} + +/* RaiseException */ +#if PY_MAJOR_VERSION < 3 +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + __Pyx_PyThreadState_declare + CYTHON_UNUSED_VAR(cause); + Py_XINCREF(type); + if (!value || value == Py_None) + value = NULL; + else + Py_INCREF(value); + if (!tb || tb == Py_None) + tb = NULL; + else { + Py_INCREF(tb); + if (!PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto raise_error; + } + } + if (PyType_Check(type)) { +#if CYTHON_COMPILING_IN_PYPY + if (!value) { + Py_INCREF(Py_None); + value = Py_None; + } +#endif + PyErr_NormalizeException(&type, &value, &tb); + } else { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto raise_error; + } + value = type; + type = (PyObject*) Py_TYPE(type); + Py_INCREF(type); + if (!PyType_IsSubtype((PyTypeObject *)type, (PyTypeObject *)PyExc_BaseException)) { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto raise_error; + } + } + __Pyx_PyThreadState_assign + __Pyx_ErrRestore(type, value, tb); + return; +raise_error: + Py_XDECREF(value); + Py_XDECREF(type); + Py_XDECREF(tb); + return; +} +#else +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + PyObject* owned_instance = NULL; + if (tb == Py_None) { + tb = 0; + } else if (tb && !PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto bad; + } + if (value == Py_None) + value = 0; + if (PyExceptionInstance_Check(type)) { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto bad; + } + value = type; + type = (PyObject*) Py_TYPE(value); + } else if (PyExceptionClass_Check(type)) { + PyObject *instance_class = NULL; + if (value && PyExceptionInstance_Check(value)) { + instance_class = (PyObject*) Py_TYPE(value); + if (instance_class != type) { + int is_subclass = PyObject_IsSubclass(instance_class, type); + if (!is_subclass) { + instance_class = NULL; + } else if (unlikely(is_subclass == -1)) { + goto bad; + } else { + type = instance_class; + } + } + } + if (!instance_class) { + PyObject *args; + if (!value) + args = PyTuple_New(0); + else if (PyTuple_Check(value)) { + Py_INCREF(value); + args = value; + } else + args = PyTuple_Pack(1, value); + if (!args) + goto bad; + owned_instance = PyObject_Call(type, args, NULL); + Py_DECREF(args); + if (!owned_instance) + goto bad; + value = owned_instance; + if (!PyExceptionInstance_Check(value)) { + PyErr_Format(PyExc_TypeError, + "calling %R should have returned an instance of " + "BaseException, not %R", + type, Py_TYPE(value)); + goto bad; + } + } + } else { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto bad; + } + if (cause) { + PyObject *fixed_cause; + if (cause == Py_None) { + fixed_cause = NULL; + } else if (PyExceptionClass_Check(cause)) { + fixed_cause = PyObject_CallObject(cause, NULL); + if (fixed_cause == NULL) + goto bad; + } else if (PyExceptionInstance_Check(cause)) { + fixed_cause = cause; + Py_INCREF(fixed_cause); + } else { + PyErr_SetString(PyExc_TypeError, + "exception causes must derive from " + "BaseException"); + goto bad; + } + PyException_SetCause(value, fixed_cause); + } + PyErr_SetObject(type, value); + if (tb) { + #if PY_VERSION_HEX >= 0x030C00A6 + PyException_SetTraceback(value, tb); + #elif CYTHON_FAST_THREAD_STATE + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject* tmp_tb = tstate->curexc_traceback; + if (tb != tmp_tb) { + Py_INCREF(tb); + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_tb); + } +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + PyErr_Fetch(&tmp_type, &tmp_value, &tmp_tb); + Py_INCREF(tb); + PyErr_Restore(tmp_type, tmp_value, tb); + Py_XDECREF(tmp_tb); +#endif + } +bad: + Py_XDECREF(owned_instance); + return; +} +#endif + +/* PyFunctionFastCall */ +#if CYTHON_FAST_PYCALL && !CYTHON_VECTORCALL +static PyObject* __Pyx_PyFunction_FastCallNoKw(PyCodeObject *co, PyObject **args, Py_ssize_t na, + PyObject *globals) { + PyFrameObject *f; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject **fastlocals; + Py_ssize_t i; + PyObject *result; + assert(globals != NULL); + /* XXX Perhaps we should create a specialized + PyFrame_New() that doesn't take locals, but does + take builtins without sanity checking them. + */ + assert(tstate != NULL); + f = PyFrame_New(tstate, co, globals, NULL); + if (f == NULL) { + return NULL; + } + fastlocals = __Pyx_PyFrame_GetLocalsplus(f); + for (i = 0; i < na; i++) { + Py_INCREF(*args); + fastlocals[i] = *args++; + } + result = PyEval_EvalFrameEx(f,0); + ++tstate->recursion_depth; + Py_DECREF(f); + --tstate->recursion_depth; + return result; +} +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs) { + PyCodeObject *co = (PyCodeObject *)PyFunction_GET_CODE(func); + PyObject *globals = PyFunction_GET_GLOBALS(func); + PyObject *argdefs = PyFunction_GET_DEFAULTS(func); + PyObject *closure; +#if PY_MAJOR_VERSION >= 3 + PyObject *kwdefs; +#endif + PyObject *kwtuple, **k; + PyObject **d; + Py_ssize_t nd; + Py_ssize_t nk; + PyObject *result; + assert(kwargs == NULL || PyDict_Check(kwargs)); + nk = kwargs ? PyDict_Size(kwargs) : 0; + #if PY_MAJOR_VERSION < 3 + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) { + return NULL; + } + #else + if (unlikely(Py_EnterRecursiveCall(" while calling a Python object"))) { + return NULL; + } + #endif + if ( +#if PY_MAJOR_VERSION >= 3 + co->co_kwonlyargcount == 0 && +#endif + likely(kwargs == NULL || nk == 0) && + co->co_flags == (CO_OPTIMIZED | CO_NEWLOCALS | CO_NOFREE)) { + if (argdefs == NULL && co->co_argcount == nargs) { + result = __Pyx_PyFunction_FastCallNoKw(co, args, nargs, globals); + goto done; + } + else if (nargs == 0 && argdefs != NULL + && co->co_argcount == Py_SIZE(argdefs)) { + /* function called with no arguments, but all parameters have + a default value: use default values as arguments .*/ + args = &PyTuple_GET_ITEM(argdefs, 0); + result =__Pyx_PyFunction_FastCallNoKw(co, args, Py_SIZE(argdefs), globals); + goto done; + } + } + if (kwargs != NULL) { + Py_ssize_t pos, i; + kwtuple = PyTuple_New(2 * nk); + if (kwtuple == NULL) { + result = NULL; + goto done; + } + k = &PyTuple_GET_ITEM(kwtuple, 0); + pos = i = 0; + while (PyDict_Next(kwargs, &pos, &k[i], &k[i+1])) { + Py_INCREF(k[i]); + Py_INCREF(k[i+1]); + i += 2; + } + nk = i / 2; + } + else { + kwtuple = NULL; + k = NULL; + } + closure = PyFunction_GET_CLOSURE(func); +#if PY_MAJOR_VERSION >= 3 + kwdefs = PyFunction_GET_KW_DEFAULTS(func); +#endif + if (argdefs != NULL) { + d = &PyTuple_GET_ITEM(argdefs, 0); + nd = Py_SIZE(argdefs); + } + else { + d = NULL; + nd = 0; + } +#if PY_MAJOR_VERSION >= 3 + result = PyEval_EvalCodeEx((PyObject*)co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, kwdefs, closure); +#else + result = PyEval_EvalCodeEx(co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, closure); +#endif + Py_XDECREF(kwtuple); +done: + Py_LeaveRecursiveCall(); + return result; +} +#endif + +/* PyObjectCall */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw) { + PyObject *result; + ternaryfunc call = Py_TYPE(func)->tp_call; + if (unlikely(!call)) + return PyObject_Call(func, arg, kw); + #if PY_MAJOR_VERSION < 3 + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + #else + if (unlikely(Py_EnterRecursiveCall(" while calling a Python object"))) + return NULL; + #endif + result = (*call)(func, arg, kw); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* PyObjectCallMethO */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg) { + PyObject *self, *result; + PyCFunction cfunc; + cfunc = __Pyx_CyOrPyCFunction_GET_FUNCTION(func); + self = __Pyx_CyOrPyCFunction_GET_SELF(func); + #if PY_MAJOR_VERSION < 3 + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + #else + if (unlikely(Py_EnterRecursiveCall(" while calling a Python object"))) + return NULL; + #endif + result = cfunc(self, arg); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* PyObjectFastCall */ +#if PY_VERSION_HEX < 0x03090000 || CYTHON_COMPILING_IN_LIMITED_API +static PyObject* __Pyx_PyObject_FastCall_fallback(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs) { + PyObject *argstuple; + PyObject *result = 0; + size_t i; + argstuple = PyTuple_New((Py_ssize_t)nargs); + if (unlikely(!argstuple)) return NULL; + for (i = 0; i < nargs; i++) { + Py_INCREF(args[i]); + if (__Pyx_PyTuple_SET_ITEM(argstuple, (Py_ssize_t)i, args[i]) < 0) goto bad; + } + result = __Pyx_PyObject_Call(func, argstuple, kwargs); + bad: + Py_DECREF(argstuple); + return result; +} +#endif +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t _nargs, PyObject *kwargs) { + Py_ssize_t nargs = __Pyx_PyVectorcall_NARGS(_nargs); +#if CYTHON_COMPILING_IN_CPYTHON + if (nargs == 0 && kwargs == NULL) { + if (__Pyx_CyOrPyCFunction_Check(func) && likely( __Pyx_CyOrPyCFunction_GET_FLAGS(func) & METH_NOARGS)) + return __Pyx_PyObject_CallMethO(func, NULL); + } + else if (nargs == 1 && kwargs == NULL) { + if (__Pyx_CyOrPyCFunction_Check(func) && likely( __Pyx_CyOrPyCFunction_GET_FLAGS(func) & METH_O)) + return __Pyx_PyObject_CallMethO(func, args[0]); + } +#endif + #if PY_VERSION_HEX < 0x030800B1 + #if CYTHON_FAST_PYCCALL + if (PyCFunction_Check(func)) { + if (kwargs) { + return _PyCFunction_FastCallDict(func, args, nargs, kwargs); + } else { + return _PyCFunction_FastCallKeywords(func, args, nargs, NULL); + } + } + #if PY_VERSION_HEX >= 0x030700A1 + if (!kwargs && __Pyx_IS_TYPE(func, &PyMethodDescr_Type)) { + return _PyMethodDescr_FastCallKeywords(func, args, nargs, NULL); + } + #endif + #endif + #if CYTHON_FAST_PYCALL + if (PyFunction_Check(func)) { + return __Pyx_PyFunction_FastCallDict(func, args, nargs, kwargs); + } + #endif + #endif + if (kwargs == NULL) { + #if CYTHON_VECTORCALL + #if PY_VERSION_HEX < 0x03090000 + vectorcallfunc f = _PyVectorcall_Function(func); + #else + vectorcallfunc f = PyVectorcall_Function(func); + #endif + if (f) { + return f(func, args, (size_t)nargs, NULL); + } + #elif defined(__Pyx_CyFunction_USED) && CYTHON_BACKPORT_VECTORCALL + if (__Pyx_CyFunction_CheckExact(func)) { + __pyx_vectorcallfunc f = __Pyx_CyFunction_func_vectorcall(func); + if (f) return f(func, args, (size_t)nargs, NULL); + } + #endif + } + if (nargs == 0) { + return __Pyx_PyObject_Call(func, __pyx_empty_tuple, kwargs); + } + #if PY_VERSION_HEX >= 0x03090000 && !CYTHON_COMPILING_IN_LIMITED_API + return PyObject_VectorcallDict(func, args, (size_t)nargs, kwargs); + #else + return __Pyx_PyObject_FastCall_fallback(func, args, (size_t)nargs, kwargs); + #endif +} + +/* RaiseUnexpectedTypeError */ +static int +__Pyx_RaiseUnexpectedTypeError(const char *expected, PyObject *obj) +{ + __Pyx_TypeName obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, "Expected %s, got " __Pyx_FMT_TYPENAME, + expected, obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return 0; +} + +/* CIntToDigits */ +static const char DIGIT_PAIRS_10[2*10*10+1] = { + "00010203040506070809" + "10111213141516171819" + "20212223242526272829" + "30313233343536373839" + "40414243444546474849" + "50515253545556575859" + "60616263646566676869" + "70717273747576777879" + "80818283848586878889" + "90919293949596979899" +}; +static const char DIGIT_PAIRS_8[2*8*8+1] = { + "0001020304050607" + "1011121314151617" + "2021222324252627" + "3031323334353637" + "4041424344454647" + "5051525354555657" + "6061626364656667" + "7071727374757677" +}; +static const char DIGITS_HEX[2*16+1] = { + "0123456789abcdef" + "0123456789ABCDEF" +}; + +/* BuildPyUnicode */ +static PyObject* __Pyx_PyUnicode_BuildFromAscii(Py_ssize_t ulength, char* chars, int clength, + int prepend_sign, char padding_char) { + PyObject *uval; + Py_ssize_t uoffset = ulength - clength; +#if CYTHON_USE_UNICODE_INTERNALS + Py_ssize_t i; +#if CYTHON_PEP393_ENABLED + void *udata; + uval = PyUnicode_New(ulength, 127); + if (unlikely(!uval)) return NULL; + udata = PyUnicode_DATA(uval); +#else + Py_UNICODE *udata; + uval = PyUnicode_FromUnicode(NULL, ulength); + if (unlikely(!uval)) return NULL; + udata = PyUnicode_AS_UNICODE(uval); +#endif + if (uoffset > 0) { + i = 0; + if (prepend_sign) { + __Pyx_PyUnicode_WRITE(PyUnicode_1BYTE_KIND, udata, 0, '-'); + i++; + } + for (; i < uoffset; i++) { + __Pyx_PyUnicode_WRITE(PyUnicode_1BYTE_KIND, udata, i, padding_char); + } + } + for (i=0; i < clength; i++) { + __Pyx_PyUnicode_WRITE(PyUnicode_1BYTE_KIND, udata, uoffset+i, chars[i]); + } +#else + { + PyObject *sign = NULL, *padding = NULL; + uval = NULL; + if (uoffset > 0) { + prepend_sign = !!prepend_sign; + if (uoffset > prepend_sign) { + padding = PyUnicode_FromOrdinal(padding_char); + if (likely(padding) && uoffset > prepend_sign + 1) { + PyObject *tmp; + PyObject *repeat = PyInt_FromSsize_t(uoffset - prepend_sign); + if (unlikely(!repeat)) goto done_or_error; + tmp = PyNumber_Multiply(padding, repeat); + Py_DECREF(repeat); + Py_DECREF(padding); + padding = tmp; + } + if (unlikely(!padding)) goto done_or_error; + } + if (prepend_sign) { + sign = PyUnicode_FromOrdinal('-'); + if (unlikely(!sign)) goto done_or_error; + } + } + uval = PyUnicode_DecodeASCII(chars, clength, NULL); + if (likely(uval) && padding) { + PyObject *tmp = PyNumber_Add(padding, uval); + Py_DECREF(uval); + uval = tmp; + } + if (likely(uval) && sign) { + PyObject *tmp = PyNumber_Add(sign, uval); + Py_DECREF(uval); + uval = tmp; + } +done_or_error: + Py_XDECREF(padding); + Py_XDECREF(sign); + } +#endif + return uval; +} + +/* CIntToPyUnicode */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_int(int value, Py_ssize_t width, char padding_char, char format_char) { + char digits[sizeof(int)*3+2]; + char *dpos, *end = digits + sizeof(int)*3+2; + const char *hex_digits = DIGITS_HEX; + Py_ssize_t length, ulength; + int prepend_sign, last_one_off; + int remaining; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (format_char == 'X') { + hex_digits += 16; + format_char = 'x'; + } + remaining = value; + last_one_off = 0; + dpos = end; + do { + int digit_pos; + switch (format_char) { + case 'o': + digit_pos = abs((int)(remaining % (8*8))); + remaining = (int) (remaining / (8*8)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_8 + digit_pos * 2, 2); + last_one_off = (digit_pos < 8); + break; + case 'd': + digit_pos = abs((int)(remaining % (10*10))); + remaining = (int) (remaining / (10*10)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_10 + digit_pos * 2, 2); + last_one_off = (digit_pos < 10); + break; + case 'x': + *(--dpos) = hex_digits[abs((int)(remaining % 16))]; + remaining = (int) (remaining / 16); + break; + default: + assert(0); + break; + } + } while (unlikely(remaining != 0)); + assert(!last_one_off || *dpos == '0'); + dpos += last_one_off; + length = end - dpos; + ulength = length; + prepend_sign = 0; + if (!is_unsigned && value <= neg_one) { + if (padding_char == ' ' || width <= length + 1) { + *(--dpos) = '-'; + ++length; + } else { + prepend_sign = 1; + } + ++ulength; + } + if (width > ulength) { + ulength = width; + } + if (ulength == 1) { + return PyUnicode_FromOrdinal(*dpos); + } + return __Pyx_PyUnicode_BuildFromAscii(ulength, dpos, (int) length, prepend_sign, padding_char); +} + +/* CIntToPyUnicode */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_Py_ssize_t(Py_ssize_t value, Py_ssize_t width, char padding_char, char format_char) { + char digits[sizeof(Py_ssize_t)*3+2]; + char *dpos, *end = digits + sizeof(Py_ssize_t)*3+2; + const char *hex_digits = DIGITS_HEX; + Py_ssize_t length, ulength; + int prepend_sign, last_one_off; + Py_ssize_t remaining; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const Py_ssize_t neg_one = (Py_ssize_t) -1, const_zero = (Py_ssize_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (format_char == 'X') { + hex_digits += 16; + format_char = 'x'; + } + remaining = value; + last_one_off = 0; + dpos = end; + do { + int digit_pos; + switch (format_char) { + case 'o': + digit_pos = abs((int)(remaining % (8*8))); + remaining = (Py_ssize_t) (remaining / (8*8)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_8 + digit_pos * 2, 2); + last_one_off = (digit_pos < 8); + break; + case 'd': + digit_pos = abs((int)(remaining % (10*10))); + remaining = (Py_ssize_t) (remaining / (10*10)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_10 + digit_pos * 2, 2); + last_one_off = (digit_pos < 10); + break; + case 'x': + *(--dpos) = hex_digits[abs((int)(remaining % 16))]; + remaining = (Py_ssize_t) (remaining / 16); + break; + default: + assert(0); + break; + } + } while (unlikely(remaining != 0)); + assert(!last_one_off || *dpos == '0'); + dpos += last_one_off; + length = end - dpos; + ulength = length; + prepend_sign = 0; + if (!is_unsigned && value <= neg_one) { + if (padding_char == ' ' || width <= length + 1) { + *(--dpos) = '-'; + ++length; + } else { + prepend_sign = 1; + } + ++ulength; + } + if (width > ulength) { + ulength = width; + } + if (ulength == 1) { + return PyUnicode_FromOrdinal(*dpos); + } + return __Pyx_PyUnicode_BuildFromAscii(ulength, dpos, (int) length, prepend_sign, padding_char); +} + +/* JoinPyUnicode */ +static PyObject* __Pyx_PyUnicode_Join(PyObject* value_tuple, Py_ssize_t value_count, Py_ssize_t result_ulength, + Py_UCS4 max_char) { +#if CYTHON_USE_UNICODE_INTERNALS && CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + PyObject *result_uval; + int result_ukind, kind_shift; + Py_ssize_t i, char_pos; + void *result_udata; + CYTHON_MAYBE_UNUSED_VAR(max_char); +#if CYTHON_PEP393_ENABLED + result_uval = PyUnicode_New(result_ulength, max_char); + if (unlikely(!result_uval)) return NULL; + result_ukind = (max_char <= 255) ? PyUnicode_1BYTE_KIND : (max_char <= 65535) ? PyUnicode_2BYTE_KIND : PyUnicode_4BYTE_KIND; + kind_shift = (result_ukind == PyUnicode_4BYTE_KIND) ? 2 : result_ukind - 1; + result_udata = PyUnicode_DATA(result_uval); +#else + result_uval = PyUnicode_FromUnicode(NULL, result_ulength); + if (unlikely(!result_uval)) return NULL; + result_ukind = sizeof(Py_UNICODE); + kind_shift = (result_ukind == 4) ? 2 : result_ukind - 1; + result_udata = PyUnicode_AS_UNICODE(result_uval); +#endif + assert(kind_shift == 2 || kind_shift == 1 || kind_shift == 0); + char_pos = 0; + for (i=0; i < value_count; i++) { + int ukind; + Py_ssize_t ulength; + void *udata; + PyObject *uval = PyTuple_GET_ITEM(value_tuple, i); + if (unlikely(__Pyx_PyUnicode_READY(uval))) + goto bad; + ulength = __Pyx_PyUnicode_GET_LENGTH(uval); + if (unlikely(!ulength)) + continue; + if (unlikely((PY_SSIZE_T_MAX >> kind_shift) - ulength < char_pos)) + goto overflow; + ukind = __Pyx_PyUnicode_KIND(uval); + udata = __Pyx_PyUnicode_DATA(uval); + if (!CYTHON_PEP393_ENABLED || ukind == result_ukind) { + memcpy((char *)result_udata + (char_pos << kind_shift), udata, (size_t) (ulength << kind_shift)); + } else { + #if PY_VERSION_HEX >= 0x030d0000 + if (unlikely(PyUnicode_CopyCharacters(result_uval, char_pos, uval, 0, ulength) < 0)) goto bad; + #elif CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030300F0 || defined(_PyUnicode_FastCopyCharacters) + _PyUnicode_FastCopyCharacters(result_uval, char_pos, uval, 0, ulength); + #else + Py_ssize_t j; + for (j=0; j < ulength; j++) { + Py_UCS4 uchar = __Pyx_PyUnicode_READ(ukind, udata, j); + __Pyx_PyUnicode_WRITE(result_ukind, result_udata, char_pos+j, uchar); + } + #endif + } + char_pos += ulength; + } + return result_uval; +overflow: + PyErr_SetString(PyExc_OverflowError, "join() result is too long for a Python string"); +bad: + Py_DECREF(result_uval); + return NULL; +#else + CYTHON_UNUSED_VAR(max_char); + CYTHON_UNUSED_VAR(result_ulength); + CYTHON_UNUSED_VAR(value_count); + return PyUnicode_Join(__pyx_empty_unicode, value_tuple); +#endif +} + +/* GetAttr */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr(PyObject *o, PyObject *n) { +#if CYTHON_USE_TYPE_SLOTS +#if PY_MAJOR_VERSION >= 3 + if (likely(PyUnicode_Check(n))) +#else + if (likely(PyString_Check(n))) +#endif + return __Pyx_PyObject_GetAttrStr(o, n); +#endif + return PyObject_GetAttr(o, n); +} + +/* GetItemInt */ +static PyObject *__Pyx_GetItemInt_Generic(PyObject *o, PyObject* j) { + PyObject *r; + if (unlikely(!j)) return NULL; + r = PyObject_GetItem(o, j); + Py_DECREF(j); + return r; +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_List_Fast(PyObject *o, Py_ssize_t i, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + Py_ssize_t wrapped_i = i; + if (wraparound & unlikely(i < 0)) { + wrapped_i += PyList_GET_SIZE(o); + } + if ((!boundscheck) || likely(__Pyx_is_valid_index(wrapped_i, PyList_GET_SIZE(o)))) { + PyObject *r = PyList_GET_ITEM(o, wrapped_i); + Py_INCREF(r); + return r; + } + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +#else + return PySequence_GetItem(o, i); +#endif +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Tuple_Fast(PyObject *o, Py_ssize_t i, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + Py_ssize_t wrapped_i = i; + if (wraparound & unlikely(i < 0)) { + wrapped_i += PyTuple_GET_SIZE(o); + } + if ((!boundscheck) || likely(__Pyx_is_valid_index(wrapped_i, PyTuple_GET_SIZE(o)))) { + PyObject *r = PyTuple_GET_ITEM(o, wrapped_i); + Py_INCREF(r); + return r; + } + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +#else + return PySequence_GetItem(o, i); +#endif +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Fast(PyObject *o, Py_ssize_t i, int is_list, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS && CYTHON_USE_TYPE_SLOTS + if (is_list || PyList_CheckExact(o)) { + Py_ssize_t n = ((!wraparound) | likely(i >= 0)) ? i : i + PyList_GET_SIZE(o); + if ((!boundscheck) || (likely(__Pyx_is_valid_index(n, PyList_GET_SIZE(o))))) { + PyObject *r = PyList_GET_ITEM(o, n); + Py_INCREF(r); + return r; + } + } + else if (PyTuple_CheckExact(o)) { + Py_ssize_t n = ((!wraparound) | likely(i >= 0)) ? i : i + PyTuple_GET_SIZE(o); + if ((!boundscheck) || likely(__Pyx_is_valid_index(n, PyTuple_GET_SIZE(o)))) { + PyObject *r = PyTuple_GET_ITEM(o, n); + Py_INCREF(r); + return r; + } + } else { + PyMappingMethods *mm = Py_TYPE(o)->tp_as_mapping; + PySequenceMethods *sm = Py_TYPE(o)->tp_as_sequence; + if (mm && mm->mp_subscript) { + PyObject *r, *key = PyInt_FromSsize_t(i); + if (unlikely(!key)) return NULL; + r = mm->mp_subscript(o, key); + Py_DECREF(key); + return r; + } + if (likely(sm && sm->sq_item)) { + if (wraparound && unlikely(i < 0) && likely(sm->sq_length)) { + Py_ssize_t l = sm->sq_length(o); + if (likely(l >= 0)) { + i += l; + } else { + if (!PyErr_ExceptionMatches(PyExc_OverflowError)) + return NULL; + PyErr_Clear(); + } + } + return sm->sq_item(o, i); + } + } +#else + if (is_list || !PyMapping_Check(o)) { + return PySequence_GetItem(o, i); + } +#endif + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +} + +/* PyObjectCallOneArg */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg) { + PyObject *args[2] = {NULL, arg}; + return __Pyx_PyObject_FastCall(func, args+1, 1 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* ObjectGetItem */ +#if CYTHON_USE_TYPE_SLOTS +static PyObject *__Pyx_PyObject_GetIndex(PyObject *obj, PyObject *index) { + PyObject *runerr = NULL; + Py_ssize_t key_value; + key_value = __Pyx_PyIndex_AsSsize_t(index); + if (likely(key_value != -1 || !(runerr = PyErr_Occurred()))) { + return __Pyx_GetItemInt_Fast(obj, key_value, 0, 1, 1); + } + if (PyErr_GivenExceptionMatches(runerr, PyExc_OverflowError)) { + __Pyx_TypeName index_type_name = __Pyx_PyType_GetName(Py_TYPE(index)); + PyErr_Clear(); + PyErr_Format(PyExc_IndexError, + "cannot fit '" __Pyx_FMT_TYPENAME "' into an index-sized integer", index_type_name); + __Pyx_DECREF_TypeName(index_type_name); + } + return NULL; +} +static PyObject *__Pyx_PyObject_GetItem_Slow(PyObject *obj, PyObject *key) { + __Pyx_TypeName obj_type_name; + if (likely(PyType_Check(obj))) { + PyObject *meth = __Pyx_PyObject_GetAttrStrNoError(obj, __pyx_n_s_class_getitem); + if (!meth) { + PyErr_Clear(); + } else { + PyObject *result = __Pyx_PyObject_CallOneArg(meth, key); + Py_DECREF(meth); + return result; + } + } + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "'" __Pyx_FMT_TYPENAME "' object is not subscriptable", obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return NULL; +} +static PyObject *__Pyx_PyObject_GetItem(PyObject *obj, PyObject *key) { + PyTypeObject *tp = Py_TYPE(obj); + PyMappingMethods *mm = tp->tp_as_mapping; + PySequenceMethods *sm = tp->tp_as_sequence; + if (likely(mm && mm->mp_subscript)) { + return mm->mp_subscript(obj, key); + } + if (likely(sm && sm->sq_item)) { + return __Pyx_PyObject_GetIndex(obj, key); + } + return __Pyx_PyObject_GetItem_Slow(obj, key); +} +#endif + +/* KeywordStringCheck */ +static int __Pyx_CheckKeywordStrings( + PyObject *kw, + const char* function_name, + int kw_allowed) +{ + PyObject* key = 0; + Py_ssize_t pos = 0; +#if CYTHON_COMPILING_IN_PYPY + if (!kw_allowed && PyDict_Next(kw, &pos, &key, 0)) + goto invalid_keyword; + return 1; +#else + if (CYTHON_METH_FASTCALL && likely(PyTuple_Check(kw))) { + Py_ssize_t kwsize; +#if CYTHON_ASSUME_SAFE_MACROS + kwsize = PyTuple_GET_SIZE(kw); +#else + kwsize = PyTuple_Size(kw); + if (kwsize < 0) return 0; +#endif + if (unlikely(kwsize == 0)) + return 1; + if (!kw_allowed) { +#if CYTHON_ASSUME_SAFE_MACROS + key = PyTuple_GET_ITEM(kw, 0); +#else + key = PyTuple_GetItem(kw, pos); + if (!key) return 0; +#endif + goto invalid_keyword; + } +#if PY_VERSION_HEX < 0x03090000 + for (pos = 0; pos < kwsize; pos++) { +#if CYTHON_ASSUME_SAFE_MACROS + key = PyTuple_GET_ITEM(kw, pos); +#else + key = PyTuple_GetItem(kw, pos); + if (!key) return 0; +#endif + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } +#endif + return 1; + } + while (PyDict_Next(kw, &pos, &key, 0)) { + #if PY_MAJOR_VERSION < 3 + if (unlikely(!PyString_Check(key))) + #endif + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } + if (!kw_allowed && unlikely(key)) + goto invalid_keyword; + return 1; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + return 0; +#endif +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif + return 0; +} + +/* DivInt[Py_ssize_t] */ +static CYTHON_INLINE Py_ssize_t __Pyx_div_Py_ssize_t(Py_ssize_t a, Py_ssize_t b) { + Py_ssize_t q = a / b; + Py_ssize_t r = a - q*b; + q -= ((r != 0) & ((r ^ b) < 0)); + return q; +} + +/* GetAttr3 */ +#if __PYX_LIMITED_VERSION_HEX < 0x030d00A1 +static PyObject *__Pyx_GetAttr3Default(PyObject *d) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + if (unlikely(!__Pyx_PyErr_ExceptionMatches(PyExc_AttributeError))) + return NULL; + __Pyx_PyErr_Clear(); + Py_INCREF(d); + return d; +} +#endif +static CYTHON_INLINE PyObject *__Pyx_GetAttr3(PyObject *o, PyObject *n, PyObject *d) { + PyObject *r; +#if __PYX_LIMITED_VERSION_HEX >= 0x030d00A1 + int res = PyObject_GetOptionalAttr(o, n, &r); + return (res != 0) ? r : __Pyx_NewRef(d); +#else + #if CYTHON_USE_TYPE_SLOTS + if (likely(PyString_Check(n))) { + r = __Pyx_PyObject_GetAttrStrNoError(o, n); + if (unlikely(!r) && likely(!PyErr_Occurred())) { + r = __Pyx_NewRef(d); + } + return r; + } + #endif + r = PyObject_GetAttr(o, n); + return (likely(r)) ? r : __Pyx_GetAttr3Default(d); +#endif +} + +/* PyDictVersioning */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + return likely(dict) ? __PYX_GET_DICT_VERSION(dict) : 0; +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj) { + PyObject **dictptr = NULL; + Py_ssize_t offset = Py_TYPE(obj)->tp_dictoffset; + if (offset) { +#if CYTHON_COMPILING_IN_CPYTHON + dictptr = (likely(offset > 0)) ? (PyObject **) ((char *)obj + offset) : _PyObject_GetDictPtr(obj); +#else + dictptr = _PyObject_GetDictPtr(obj); +#endif + } + return (dictptr && *dictptr) ? __PYX_GET_DICT_VERSION(*dictptr) : 0; +} +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + if (unlikely(!dict) || unlikely(tp_dict_version != __PYX_GET_DICT_VERSION(dict))) + return 0; + return obj_dict_version == __Pyx_get_object_dict_version(obj); +} +#endif + +/* GetModuleGlobalName */ +#if CYTHON_USE_DICT_VERSIONS +static PyObject *__Pyx__GetModuleGlobalName(PyObject *name, PY_UINT64_T *dict_version, PyObject **dict_cached_value) +#else +static CYTHON_INLINE PyObject *__Pyx__GetModuleGlobalName(PyObject *name) +#endif +{ + PyObject *result; +#if !CYTHON_AVOID_BORROWED_REFS +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030500A1 && PY_VERSION_HEX < 0x030d0000 + result = _PyDict_GetItem_KnownHash(__pyx_d, name, ((PyASCIIObject *) name)->hash); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } else if (unlikely(PyErr_Occurred())) { + return NULL; + } +#elif CYTHON_COMPILING_IN_LIMITED_API + if (unlikely(!__pyx_m)) { + return NULL; + } + result = PyObject_GetAttr(__pyx_m, name); + if (likely(result)) { + return result; + } +#else + result = PyDict_GetItem(__pyx_d, name); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } +#endif +#else + result = PyObject_GetItem(__pyx_d, name); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } + PyErr_Clear(); +#endif + return __Pyx_GetBuiltinName(name); +} + +/* RaiseTooManyValuesToUnpack */ +static CYTHON_INLINE void __Pyx_RaiseTooManyValuesError(Py_ssize_t expected) { + PyErr_Format(PyExc_ValueError, + "too many values to unpack (expected %" CYTHON_FORMAT_SSIZE_T "d)", expected); +} + +/* RaiseNeedMoreValuesToUnpack */ +static CYTHON_INLINE void __Pyx_RaiseNeedMoreValuesError(Py_ssize_t index) { + PyErr_Format(PyExc_ValueError, + "need more than %" CYTHON_FORMAT_SSIZE_T "d value%.1s to unpack", + index, (index == 1) ? "" : "s"); +} + +/* RaiseNoneIterError */ +static CYTHON_INLINE void __Pyx_RaiseNoneNotIterableError(void) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not iterable"); +} + +/* ExtTypeTest */ +static CYTHON_INLINE int __Pyx_TypeTest(PyObject *obj, PyTypeObject *type) { + __Pyx_TypeName obj_type_name; + __Pyx_TypeName type_name; + if (unlikely(!type)) { + PyErr_SetString(PyExc_SystemError, "Missing type object"); + return 0; + } + if (likely(__Pyx_TypeCheck(obj, type))) + return 1; + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + type_name = __Pyx_PyType_GetName(type); + PyErr_Format(PyExc_TypeError, + "Cannot convert " __Pyx_FMT_TYPENAME " to " __Pyx_FMT_TYPENAME, + obj_type_name, type_name); + __Pyx_DECREF_TypeName(obj_type_name); + __Pyx_DECREF_TypeName(type_name); + return 0; +} + +/* GetTopmostException */ +#if CYTHON_USE_EXC_INFO_STACK && CYTHON_FAST_THREAD_STATE +static _PyErr_StackItem * +__Pyx_PyErr_GetTopmostException(PyThreadState *tstate) +{ + _PyErr_StackItem *exc_info = tstate->exc_info; + while ((exc_info->exc_value == NULL || exc_info->exc_value == Py_None) && + exc_info->previous_item != NULL) + { + exc_info = exc_info->previous_item; + } + return exc_info; +} +#endif + +/* SaveResetException */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx__ExceptionSave(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { + #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 + _PyErr_StackItem *exc_info = __Pyx_PyErr_GetTopmostException(tstate); + PyObject *exc_value = exc_info->exc_value; + if (exc_value == NULL || exc_value == Py_None) { + *value = NULL; + *type = NULL; + *tb = NULL; + } else { + *value = exc_value; + Py_INCREF(*value); + *type = (PyObject*) Py_TYPE(exc_value); + Py_INCREF(*type); + *tb = PyException_GetTraceback(exc_value); + } + #elif CYTHON_USE_EXC_INFO_STACK + _PyErr_StackItem *exc_info = __Pyx_PyErr_GetTopmostException(tstate); + *type = exc_info->exc_type; + *value = exc_info->exc_value; + *tb = exc_info->exc_traceback; + Py_XINCREF(*type); + Py_XINCREF(*value); + Py_XINCREF(*tb); + #else + *type = tstate->exc_type; + *value = tstate->exc_value; + *tb = tstate->exc_traceback; + Py_XINCREF(*type); + Py_XINCREF(*value); + Py_XINCREF(*tb); + #endif +} +static CYTHON_INLINE void __Pyx__ExceptionReset(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb) { + #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 + _PyErr_StackItem *exc_info = tstate->exc_info; + PyObject *tmp_value = exc_info->exc_value; + exc_info->exc_value = value; + Py_XDECREF(tmp_value); + Py_XDECREF(type); + Py_XDECREF(tb); + #else + PyObject *tmp_type, *tmp_value, *tmp_tb; + #if CYTHON_USE_EXC_INFO_STACK + _PyErr_StackItem *exc_info = tstate->exc_info; + tmp_type = exc_info->exc_type; + tmp_value = exc_info->exc_value; + tmp_tb = exc_info->exc_traceback; + exc_info->exc_type = type; + exc_info->exc_value = value; + exc_info->exc_traceback = tb; + #else + tmp_type = tstate->exc_type; + tmp_value = tstate->exc_value; + tmp_tb = tstate->exc_traceback; + tstate->exc_type = type; + tstate->exc_value = value; + tstate->exc_traceback = tb; + #endif + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); + #endif +} +#endif + +/* GetException */ +#if CYTHON_FAST_THREAD_STATE +static int __Pyx__GetException(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) +#else +static int __Pyx_GetException(PyObject **type, PyObject **value, PyObject **tb) +#endif +{ + PyObject *local_type = NULL, *local_value, *local_tb = NULL; +#if CYTHON_FAST_THREAD_STATE + PyObject *tmp_type, *tmp_value, *tmp_tb; + #if PY_VERSION_HEX >= 0x030C00A6 + local_value = tstate->current_exception; + tstate->current_exception = 0; + if (likely(local_value)) { + local_type = (PyObject*) Py_TYPE(local_value); + Py_INCREF(local_type); + local_tb = PyException_GetTraceback(local_value); + } + #else + local_type = tstate->curexc_type; + local_value = tstate->curexc_value; + local_tb = tstate->curexc_traceback; + tstate->curexc_type = 0; + tstate->curexc_value = 0; + tstate->curexc_traceback = 0; + #endif +#else + PyErr_Fetch(&local_type, &local_value, &local_tb); +#endif + PyErr_NormalizeException(&local_type, &local_value, &local_tb); +#if CYTHON_FAST_THREAD_STATE && PY_VERSION_HEX >= 0x030C00A6 + if (unlikely(tstate->current_exception)) +#elif CYTHON_FAST_THREAD_STATE + if (unlikely(tstate->curexc_type)) +#else + if (unlikely(PyErr_Occurred())) +#endif + goto bad; + #if PY_MAJOR_VERSION >= 3 + if (local_tb) { + if (unlikely(PyException_SetTraceback(local_value, local_tb) < 0)) + goto bad; + } + #endif + Py_XINCREF(local_tb); + Py_XINCREF(local_type); + Py_XINCREF(local_value); + *type = local_type; + *value = local_value; + *tb = local_tb; +#if CYTHON_FAST_THREAD_STATE + #if CYTHON_USE_EXC_INFO_STACK + { + _PyErr_StackItem *exc_info = tstate->exc_info; + #if PY_VERSION_HEX >= 0x030B00a4 + tmp_value = exc_info->exc_value; + exc_info->exc_value = local_value; + tmp_type = NULL; + tmp_tb = NULL; + Py_XDECREF(local_type); + Py_XDECREF(local_tb); + #else + tmp_type = exc_info->exc_type; + tmp_value = exc_info->exc_value; + tmp_tb = exc_info->exc_traceback; + exc_info->exc_type = local_type; + exc_info->exc_value = local_value; + exc_info->exc_traceback = local_tb; + #endif + } + #else + tmp_type = tstate->exc_type; + tmp_value = tstate->exc_value; + tmp_tb = tstate->exc_traceback; + tstate->exc_type = local_type; + tstate->exc_value = local_value; + tstate->exc_traceback = local_tb; + #endif + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); +#else + PyErr_SetExcInfo(local_type, local_value, local_tb); +#endif + return 0; +bad: + *type = 0; + *value = 0; + *tb = 0; + Py_XDECREF(local_type); + Py_XDECREF(local_value); + Py_XDECREF(local_tb); + return -1; +} + +/* SwapException */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx__ExceptionSwap(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { + PyObject *tmp_type, *tmp_value, *tmp_tb; + #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 + _PyErr_StackItem *exc_info = tstate->exc_info; + tmp_value = exc_info->exc_value; + exc_info->exc_value = *value; + if (tmp_value == NULL || tmp_value == Py_None) { + Py_XDECREF(tmp_value); + tmp_value = NULL; + tmp_type = NULL; + tmp_tb = NULL; + } else { + tmp_type = (PyObject*) Py_TYPE(tmp_value); + Py_INCREF(tmp_type); + #if CYTHON_COMPILING_IN_CPYTHON + tmp_tb = ((PyBaseExceptionObject*) tmp_value)->traceback; + Py_XINCREF(tmp_tb); + #else + tmp_tb = PyException_GetTraceback(tmp_value); + #endif + } + #elif CYTHON_USE_EXC_INFO_STACK + _PyErr_StackItem *exc_info = tstate->exc_info; + tmp_type = exc_info->exc_type; + tmp_value = exc_info->exc_value; + tmp_tb = exc_info->exc_traceback; + exc_info->exc_type = *type; + exc_info->exc_value = *value; + exc_info->exc_traceback = *tb; + #else + tmp_type = tstate->exc_type; + tmp_value = tstate->exc_value; + tmp_tb = tstate->exc_traceback; + tstate->exc_type = *type; + tstate->exc_value = *value; + tstate->exc_traceback = *tb; + #endif + *type = tmp_type; + *value = tmp_value; + *tb = tmp_tb; +} +#else +static CYTHON_INLINE void __Pyx_ExceptionSwap(PyObject **type, PyObject **value, PyObject **tb) { + PyObject *tmp_type, *tmp_value, *tmp_tb; + PyErr_GetExcInfo(&tmp_type, &tmp_value, &tmp_tb); + PyErr_SetExcInfo(*type, *value, *tb); + *type = tmp_type; + *value = tmp_value; + *tb = tmp_tb; +} +#endif + +/* Import */ +static PyObject *__Pyx_Import(PyObject *name, PyObject *from_list, int level) { + PyObject *module = 0; + PyObject *empty_dict = 0; + PyObject *empty_list = 0; + #if PY_MAJOR_VERSION < 3 + PyObject *py_import; + py_import = __Pyx_PyObject_GetAttrStr(__pyx_b, __pyx_n_s_import); + if (unlikely(!py_import)) + goto bad; + if (!from_list) { + empty_list = PyList_New(0); + if (unlikely(!empty_list)) + goto bad; + from_list = empty_list; + } + #endif + empty_dict = PyDict_New(); + if (unlikely(!empty_dict)) + goto bad; + { + #if PY_MAJOR_VERSION >= 3 + if (level == -1) { + if (strchr(__Pyx_MODULE_NAME, '.') != NULL) { + module = PyImport_ImportModuleLevelObject( + name, __pyx_d, empty_dict, from_list, 1); + if (unlikely(!module)) { + if (unlikely(!PyErr_ExceptionMatches(PyExc_ImportError))) + goto bad; + PyErr_Clear(); + } + } + level = 0; + } + #endif + if (!module) { + #if PY_MAJOR_VERSION < 3 + PyObject *py_level = PyInt_FromLong(level); + if (unlikely(!py_level)) + goto bad; + module = PyObject_CallFunctionObjArgs(py_import, + name, __pyx_d, empty_dict, from_list, py_level, (PyObject *)NULL); + Py_DECREF(py_level); + #else + module = PyImport_ImportModuleLevelObject( + name, __pyx_d, empty_dict, from_list, level); + #endif + } + } +bad: + Py_XDECREF(empty_dict); + Py_XDECREF(empty_list); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_import); + #endif + return module; +} + +/* ImportDottedModule */ +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx__ImportDottedModule_Error(PyObject *name, PyObject *parts_tuple, Py_ssize_t count) { + PyObject *partial_name = NULL, *slice = NULL, *sep = NULL; + if (unlikely(PyErr_Occurred())) { + PyErr_Clear(); + } + if (likely(PyTuple_GET_SIZE(parts_tuple) == count)) { + partial_name = name; + } else { + slice = PySequence_GetSlice(parts_tuple, 0, count); + if (unlikely(!slice)) + goto bad; + sep = PyUnicode_FromStringAndSize(".", 1); + if (unlikely(!sep)) + goto bad; + partial_name = PyUnicode_Join(sep, slice); + } + PyErr_Format( +#if PY_MAJOR_VERSION < 3 + PyExc_ImportError, + "No module named '%s'", PyString_AS_STRING(partial_name)); +#else +#if PY_VERSION_HEX >= 0x030600B1 + PyExc_ModuleNotFoundError, +#else + PyExc_ImportError, +#endif + "No module named '%U'", partial_name); +#endif +bad: + Py_XDECREF(sep); + Py_XDECREF(slice); + Py_XDECREF(partial_name); + return NULL; +} +#endif +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx__ImportDottedModule_Lookup(PyObject *name) { + PyObject *imported_module; +#if PY_VERSION_HEX < 0x030700A1 || (CYTHON_COMPILING_IN_PYPY && PYPY_VERSION_NUM < 0x07030400) + PyObject *modules = PyImport_GetModuleDict(); + if (unlikely(!modules)) + return NULL; + imported_module = __Pyx_PyDict_GetItemStr(modules, name); + Py_XINCREF(imported_module); +#else + imported_module = PyImport_GetModule(name); +#endif + return imported_module; +} +#endif +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_ImportDottedModule_WalkParts(PyObject *module, PyObject *name, PyObject *parts_tuple) { + Py_ssize_t i, nparts; + nparts = PyTuple_GET_SIZE(parts_tuple); + for (i=1; i < nparts && module; i++) { + PyObject *part, *submodule; +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + part = PyTuple_GET_ITEM(parts_tuple, i); +#else + part = PySequence_ITEM(parts_tuple, i); +#endif + submodule = __Pyx_PyObject_GetAttrStrNoError(module, part); +#if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(part); +#endif + Py_DECREF(module); + module = submodule; + } + if (unlikely(!module)) { + return __Pyx__ImportDottedModule_Error(name, parts_tuple, i); + } + return module; +} +#endif +static PyObject *__Pyx__ImportDottedModule(PyObject *name, PyObject *parts_tuple) { +#if PY_MAJOR_VERSION < 3 + PyObject *module, *from_list, *star = __pyx_n_s__3; + CYTHON_UNUSED_VAR(parts_tuple); + from_list = PyList_New(1); + if (unlikely(!from_list)) + return NULL; + Py_INCREF(star); + PyList_SET_ITEM(from_list, 0, star); + module = __Pyx_Import(name, from_list, 0); + Py_DECREF(from_list); + return module; +#else + PyObject *imported_module; + PyObject *module = __Pyx_Import(name, NULL, 0); + if (!parts_tuple || unlikely(!module)) + return module; + imported_module = __Pyx__ImportDottedModule_Lookup(name); + if (likely(imported_module)) { + Py_DECREF(module); + return imported_module; + } + PyErr_Clear(); + return __Pyx_ImportDottedModule_WalkParts(module, name, parts_tuple); +#endif +} +static PyObject *__Pyx_ImportDottedModule(PyObject *name, PyObject *parts_tuple) { +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030400B1 + PyObject *module = __Pyx__ImportDottedModule_Lookup(name); + if (likely(module)) { + PyObject *spec = __Pyx_PyObject_GetAttrStrNoError(module, __pyx_n_s_spec); + if (likely(spec)) { + PyObject *unsafe = __Pyx_PyObject_GetAttrStrNoError(spec, __pyx_n_s_initializing); + if (likely(!unsafe || !__Pyx_PyObject_IsTrue(unsafe))) { + Py_DECREF(spec); + spec = NULL; + } + Py_XDECREF(unsafe); + } + if (likely(!spec)) { + PyErr_Clear(); + return module; + } + Py_DECREF(spec); + Py_DECREF(module); + } else if (PyErr_Occurred()) { + PyErr_Clear(); + } +#endif + return __Pyx__ImportDottedModule(name, parts_tuple); +} + +/* FastTypeChecks */ +#if CYTHON_COMPILING_IN_CPYTHON +static int __Pyx_InBases(PyTypeObject *a, PyTypeObject *b) { + while (a) { + a = __Pyx_PyType_GetSlot(a, tp_base, PyTypeObject*); + if (a == b) + return 1; + } + return b == &PyBaseObject_Type; +} +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (a == b) return 1; + mro = a->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + if (PyTuple_GET_ITEM(mro, i) == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(a, b); +} +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (cls == a || cls == b) return 1; + mro = cls->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + PyObject *base = PyTuple_GET_ITEM(mro, i); + if (base == (PyObject *)a || base == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(cls, a) || __Pyx_InBases(cls, b); +} +#if PY_MAJOR_VERSION == 2 +static int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject* exc_type2) { + PyObject *exception, *value, *tb; + int res; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&exception, &value, &tb); + res = exc_type1 ? PyObject_IsSubclass(err, exc_type1) : 0; + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + if (!res) { + res = PyObject_IsSubclass(err, exc_type2); + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + } + __Pyx_ErrRestore(exception, value, tb); + return res; +} +#else +static CYTHON_INLINE int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject *exc_type2) { + if (exc_type1) { + return __Pyx_IsAnySubtype2((PyTypeObject*)err, (PyTypeObject*)exc_type1, (PyTypeObject*)exc_type2); + } else { + return __Pyx_IsSubtype((PyTypeObject*)err, (PyTypeObject*)exc_type2); + } +} +#endif +static int __Pyx_PyErr_GivenExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + assert(PyExceptionClass_Check(exc_type)); + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; itp_as_sequence && type->tp_as_sequence->sq_repeat)) { + return type->tp_as_sequence->sq_repeat(seq, mul); + } else +#endif + { + return __Pyx_PySequence_Multiply_Generic(seq, mul); + } +} + +/* SetItemInt */ +static int __Pyx_SetItemInt_Generic(PyObject *o, PyObject *j, PyObject *v) { + int r; + if (unlikely(!j)) return -1; + r = PyObject_SetItem(o, j, v); + Py_DECREF(j); + return r; +} +static CYTHON_INLINE int __Pyx_SetItemInt_Fast(PyObject *o, Py_ssize_t i, PyObject *v, int is_list, + CYTHON_NCP_UNUSED int wraparound, CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS && CYTHON_USE_TYPE_SLOTS + if (is_list || PyList_CheckExact(o)) { + Py_ssize_t n = (!wraparound) ? i : ((likely(i >= 0)) ? i : i + PyList_GET_SIZE(o)); + if ((!boundscheck) || likely(__Pyx_is_valid_index(n, PyList_GET_SIZE(o)))) { + PyObject* old = PyList_GET_ITEM(o, n); + Py_INCREF(v); + PyList_SET_ITEM(o, n, v); + Py_DECREF(old); + return 1; + } + } else { + PyMappingMethods *mm = Py_TYPE(o)->tp_as_mapping; + PySequenceMethods *sm = Py_TYPE(o)->tp_as_sequence; + if (mm && mm->mp_ass_subscript) { + int r; + PyObject *key = PyInt_FromSsize_t(i); + if (unlikely(!key)) return -1; + r = mm->mp_ass_subscript(o, key, v); + Py_DECREF(key); + return r; + } + if (likely(sm && sm->sq_ass_item)) { + if (wraparound && unlikely(i < 0) && likely(sm->sq_length)) { + Py_ssize_t l = sm->sq_length(o); + if (likely(l >= 0)) { + i += l; + } else { + if (!PyErr_ExceptionMatches(PyExc_OverflowError)) + return -1; + PyErr_Clear(); + } + } + return sm->sq_ass_item(o, i, v); + } + } +#else + if (is_list || !PyMapping_Check(o)) + { + return PySequence_SetItem(o, i, v); + } +#endif + return __Pyx_SetItemInt_Generic(o, PyInt_FromSsize_t(i), v); +} + +/* RaiseUnboundLocalError */ +static CYTHON_INLINE void __Pyx_RaiseUnboundLocalError(const char *varname) { + PyErr_Format(PyExc_UnboundLocalError, "local variable '%s' referenced before assignment", varname); +} + +/* DivInt[long] */ +static CYTHON_INLINE long __Pyx_div_long(long a, long b) { + long q = a / b; + long r = a - q*b; + q -= ((r != 0) & ((r ^ b) < 0)); + return q; +} + +/* ImportFrom */ +static PyObject* __Pyx_ImportFrom(PyObject* module, PyObject* name) { + PyObject* value = __Pyx_PyObject_GetAttrStr(module, name); + if (unlikely(!value) && PyErr_ExceptionMatches(PyExc_AttributeError)) { + const char* module_name_str = 0; + PyObject* module_name = 0; + PyObject* module_dot = 0; + PyObject* full_name = 0; + PyErr_Clear(); + module_name_str = PyModule_GetName(module); + if (unlikely(!module_name_str)) { goto modbad; } + module_name = PyUnicode_FromString(module_name_str); + if (unlikely(!module_name)) { goto modbad; } + module_dot = PyUnicode_Concat(module_name, __pyx_kp_u__2); + if (unlikely(!module_dot)) { goto modbad; } + full_name = PyUnicode_Concat(module_dot, name); + if (unlikely(!full_name)) { goto modbad; } + #if PY_VERSION_HEX < 0x030700A1 || (CYTHON_COMPILING_IN_PYPY && PYPY_VERSION_NUM < 0x07030400) + { + PyObject *modules = PyImport_GetModuleDict(); + if (unlikely(!modules)) + goto modbad; + value = PyObject_GetItem(modules, full_name); + } + #else + value = PyImport_GetModule(full_name); + #endif + modbad: + Py_XDECREF(full_name); + Py_XDECREF(module_dot); + Py_XDECREF(module_name); + } + if (unlikely(!value)) { + PyErr_Format(PyExc_ImportError, + #if PY_MAJOR_VERSION < 3 + "cannot import name %.230s", PyString_AS_STRING(name)); + #else + "cannot import name %S", name); + #endif + } + return value; +} + +/* HasAttr */ +#if __PYX_LIMITED_VERSION_HEX < 0x030d00A1 +static CYTHON_INLINE int __Pyx_HasAttr(PyObject *o, PyObject *n) { + PyObject *r; + if (unlikely(!__Pyx_PyBaseString_Check(n))) { + PyErr_SetString(PyExc_TypeError, + "hasattr(): attribute name must be string"); + return -1; + } + r = __Pyx_GetAttr(o, n); + if (!r) { + PyErr_Clear(); + return 0; + } else { + Py_DECREF(r); + return 1; + } +} +#endif + +/* BufferIndexError */ +static void __Pyx_RaiseBufferIndexError(int axis) { + PyErr_Format(PyExc_IndexError, + "Out of bounds on buffer access (axis %d)", axis); +} + +/* PyObject_GenericGetAttrNoDict */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject *__Pyx_RaiseGenericGetAttributeError(PyTypeObject *tp, PyObject *attr_name) { + __Pyx_TypeName type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, attr_name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(attr_name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name) { + PyObject *descr; + PyTypeObject *tp = Py_TYPE(obj); + if (unlikely(!PyString_Check(attr_name))) { + return PyObject_GenericGetAttr(obj, attr_name); + } + assert(!tp->tp_dictoffset); + descr = _PyType_Lookup(tp, attr_name); + if (unlikely(!descr)) { + return __Pyx_RaiseGenericGetAttributeError(tp, attr_name); + } + Py_INCREF(descr); + #if PY_MAJOR_VERSION < 3 + if (likely(PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_HAVE_CLASS))) + #endif + { + descrgetfunc f = Py_TYPE(descr)->tp_descr_get; + if (unlikely(f)) { + PyObject *res = f(descr, obj, (PyObject *)tp); + Py_DECREF(descr); + return res; + } + } + return descr; +} +#endif + +/* PyObject_GenericGetAttr */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name) { + if (unlikely(Py_TYPE(obj)->tp_dictoffset)) { + return PyObject_GenericGetAttr(obj, attr_name); + } + return __Pyx_PyObject_GenericGetAttrNoDict(obj, attr_name); +} +#endif + +/* TypeImport */ +#ifndef __PYX_HAVE_RT_ImportType_3_0_8 +#define __PYX_HAVE_RT_ImportType_3_0_8 +static PyTypeObject *__Pyx_ImportType_3_0_8(PyObject *module, const char *module_name, const char *class_name, + size_t size, size_t alignment, enum __Pyx_ImportType_CheckSize_3_0_8 check_size) +{ + PyObject *result = 0; + char warning[200]; + Py_ssize_t basicsize; + Py_ssize_t itemsize; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *py_basicsize; + PyObject *py_itemsize; +#endif + result = PyObject_GetAttrString(module, class_name); + if (!result) + goto bad; + if (!PyType_Check(result)) { + PyErr_Format(PyExc_TypeError, + "%.200s.%.200s is not a type object", + module_name, class_name); + goto bad; + } +#if !CYTHON_COMPILING_IN_LIMITED_API + basicsize = ((PyTypeObject *)result)->tp_basicsize; + itemsize = ((PyTypeObject *)result)->tp_itemsize; +#else + py_basicsize = PyObject_GetAttrString(result, "__basicsize__"); + if (!py_basicsize) + goto bad; + basicsize = PyLong_AsSsize_t(py_basicsize); + Py_DECREF(py_basicsize); + py_basicsize = 0; + if (basicsize == (Py_ssize_t)-1 && PyErr_Occurred()) + goto bad; + py_itemsize = PyObject_GetAttrString(result, "__itemsize__"); + if (!py_itemsize) + goto bad; + itemsize = PyLong_AsSsize_t(py_itemsize); + Py_DECREF(py_itemsize); + py_itemsize = 0; + if (itemsize == (Py_ssize_t)-1 && PyErr_Occurred()) + goto bad; +#endif + if (itemsize) { + if (size % alignment) { + alignment = size % alignment; + } + if (itemsize < (Py_ssize_t)alignment) + itemsize = (Py_ssize_t)alignment; + } + if ((size_t)(basicsize + itemsize) < size) { + PyErr_Format(PyExc_ValueError, + "%.200s.%.200s size changed, may indicate binary incompatibility. " + "Expected %zd from C header, got %zd from PyObject", + module_name, class_name, size, basicsize+itemsize); + goto bad; + } + if (check_size == __Pyx_ImportType_CheckSize_Error_3_0_8 && + ((size_t)basicsize > size || (size_t)(basicsize + itemsize) < size)) { + PyErr_Format(PyExc_ValueError, + "%.200s.%.200s size changed, may indicate binary incompatibility. " + "Expected %zd from C header, got %zd-%zd from PyObject", + module_name, class_name, size, basicsize, basicsize+itemsize); + goto bad; + } + else if (check_size == __Pyx_ImportType_CheckSize_Warn_3_0_8 && (size_t)basicsize > size) { + PyOS_snprintf(warning, sizeof(warning), + "%s.%s size changed, may indicate binary incompatibility. " + "Expected %zd from C header, got %zd from PyObject", + module_name, class_name, size, basicsize); + if (PyErr_WarnEx(NULL, warning, 0) < 0) goto bad; + } + return (PyTypeObject *)result; +bad: + Py_XDECREF(result); + return NULL; +} +#endif + +/* FixUpExtensionType */ +#if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type) { +#if PY_VERSION_HEX > 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + CYTHON_UNUSED_VAR(spec); + CYTHON_UNUSED_VAR(type); +#else + const PyType_Slot *slot = spec->slots; + while (slot && slot->slot && slot->slot != Py_tp_members) + slot++; + if (slot && slot->slot == Py_tp_members) { + int changed = 0; +#if !(PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON) + const +#endif + PyMemberDef *memb = (PyMemberDef*) slot->pfunc; + while (memb && memb->name) { + if (memb->name[0] == '_' && memb->name[1] == '_') { +#if PY_VERSION_HEX < 0x030900b1 + if (strcmp(memb->name, "__weaklistoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_weaklistoffset = memb->offset; + changed = 1; + } + else if (strcmp(memb->name, "__dictoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_dictoffset = memb->offset; + changed = 1; + } +#if CYTHON_METH_FASTCALL + else if (strcmp(memb->name, "__vectorcalloffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); +#if PY_VERSION_HEX >= 0x030800b4 + type->tp_vectorcall_offset = memb->offset; +#else + type->tp_print = (printfunc) memb->offset; +#endif + changed = 1; + } +#endif +#else + if ((0)); +#endif +#if PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON + else if (strcmp(memb->name, "__module__") == 0) { + PyObject *descr; + assert(memb->type == T_OBJECT); + assert(memb->flags == 0 || memb->flags == READONLY); + descr = PyDescr_NewMember(type, memb); + if (unlikely(!descr)) + return -1; + if (unlikely(PyDict_SetItem(type->tp_dict, PyDescr_NAME(descr), descr) < 0)) { + Py_DECREF(descr); + return -1; + } + Py_DECREF(descr); + changed = 1; + } +#endif + } + memb++; + } + if (changed) + PyType_Modified(type); + } +#endif + return 0; +} +#endif + +/* PyObjectCallNoArg */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func) { + PyObject *arg[2] = {NULL, NULL}; + return __Pyx_PyObject_FastCall(func, arg + 1, 0 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* PyObjectGetMethod */ +static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method) { + PyObject *attr; +#if CYTHON_UNPACK_METHODS && CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_PYTYPE_LOOKUP + __Pyx_TypeName type_name; + PyTypeObject *tp = Py_TYPE(obj); + PyObject *descr; + descrgetfunc f = NULL; + PyObject **dictptr, *dict; + int meth_found = 0; + assert (*method == NULL); + if (unlikely(tp->tp_getattro != PyObject_GenericGetAttr)) { + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; + } + if (unlikely(tp->tp_dict == NULL) && unlikely(PyType_Ready(tp) < 0)) { + return 0; + } + descr = _PyType_Lookup(tp, name); + if (likely(descr != NULL)) { + Py_INCREF(descr); +#if defined(Py_TPFLAGS_METHOD_DESCRIPTOR) && Py_TPFLAGS_METHOD_DESCRIPTOR + if (__Pyx_PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_METHOD_DESCRIPTOR)) +#elif PY_MAJOR_VERSION >= 3 + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type))) + #endif +#else + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr))) + #endif +#endif + { + meth_found = 1; + } else { + f = Py_TYPE(descr)->tp_descr_get; + if (f != NULL && PyDescr_IsData(descr)) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + } + } + dictptr = _PyObject_GetDictPtr(obj); + if (dictptr != NULL && (dict = *dictptr) != NULL) { + Py_INCREF(dict); + attr = __Pyx_PyDict_GetItemStr(dict, name); + if (attr != NULL) { + Py_INCREF(attr); + Py_DECREF(dict); + Py_XDECREF(descr); + goto try_unpack; + } + Py_DECREF(dict); + } + if (meth_found) { + *method = descr; + return 1; + } + if (f != NULL) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + if (likely(descr != NULL)) { + *method = descr; + return 0; + } + type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return 0; +#else + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; +#endif +try_unpack: +#if CYTHON_UNPACK_METHODS + if (likely(attr) && PyMethod_Check(attr) && likely(PyMethod_GET_SELF(attr) == obj)) { + PyObject *function = PyMethod_GET_FUNCTION(attr); + Py_INCREF(function); + Py_DECREF(attr); + *method = function; + return 1; + } +#endif + *method = attr; + return 0; +} + +/* PyObjectCallMethod0 */ +static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name) { + PyObject *method = NULL, *result = NULL; + int is_method = __Pyx_PyObject_GetMethod(obj, method_name, &method); + if (likely(is_method)) { + result = __Pyx_PyObject_CallOneArg(method, obj); + Py_DECREF(method); + return result; + } + if (unlikely(!method)) goto bad; + result = __Pyx_PyObject_CallNoArg(method); + Py_DECREF(method); +bad: + return result; +} + +/* ValidateBasesTuple */ +#if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases) { + Py_ssize_t i, n; +#if CYTHON_ASSUME_SAFE_MACROS + n = PyTuple_GET_SIZE(bases); +#else + n = PyTuple_Size(bases); + if (n < 0) return -1; +#endif + for (i = 1; i < n; i++) + { +#if CYTHON_AVOID_BORROWED_REFS + PyObject *b0 = PySequence_GetItem(bases, i); + if (!b0) return -1; +#elif CYTHON_ASSUME_SAFE_MACROS + PyObject *b0 = PyTuple_GET_ITEM(bases, i); +#else + PyObject *b0 = PyTuple_GetItem(bases, i); + if (!b0) return -1; +#endif + PyTypeObject *b; +#if PY_MAJOR_VERSION < 3 + if (PyClass_Check(b0)) + { + PyErr_Format(PyExc_TypeError, "base class '%.200s' is an old-style class", + PyString_AS_STRING(((PyClassObject*)b0)->cl_name)); +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + return -1; + } +#endif + b = (PyTypeObject*) b0; + if (!__Pyx_PyType_HasFeature(b, Py_TPFLAGS_HEAPTYPE)) + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "base class '" __Pyx_FMT_TYPENAME "' is not a heap type", b_name); + __Pyx_DECREF_TypeName(b_name); +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + return -1; + } + if (dictoffset == 0) + { + Py_ssize_t b_dictoffset = 0; +#if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + b_dictoffset = b->tp_dictoffset; +#else + PyObject *py_b_dictoffset = PyObject_GetAttrString((PyObject*)b, "__dictoffset__"); + if (!py_b_dictoffset) goto dictoffset_return; + b_dictoffset = PyLong_AsSsize_t(py_b_dictoffset); + Py_DECREF(py_b_dictoffset); + if (b_dictoffset == -1 && PyErr_Occurred()) goto dictoffset_return; +#endif + if (b_dictoffset) { + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "extension type '%.200s' has no __dict__ slot, " + "but base type '" __Pyx_FMT_TYPENAME "' has: " + "either add 'cdef dict __dict__' to the extension type " + "or add '__slots__ = [...]' to the base type", + type_name, b_name); + __Pyx_DECREF_TypeName(b_name); + } +#if !(CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY) + dictoffset_return: +#endif +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + return -1; + } + } +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + } + return 0; +} +#endif + +/* PyType_Ready */ +static int __Pyx_PyType_Ready(PyTypeObject *t) { +#if CYTHON_USE_TYPE_SPECS || !(CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API) || defined(PYSTON_MAJOR_VERSION) + (void)__Pyx_PyObject_CallMethod0; +#if CYTHON_USE_TYPE_SPECS + (void)__Pyx_validate_bases_tuple; +#endif + return PyType_Ready(t); +#else + int r; + PyObject *bases = __Pyx_PyType_GetSlot(t, tp_bases, PyObject*); + if (bases && unlikely(__Pyx_validate_bases_tuple(t->tp_name, t->tp_dictoffset, bases) == -1)) + return -1; +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + { + int gc_was_enabled; + #if PY_VERSION_HEX >= 0x030A00b1 + gc_was_enabled = PyGC_Disable(); + (void)__Pyx_PyObject_CallMethod0; + #else + PyObject *ret, *py_status; + PyObject *gc = NULL; + #if PY_VERSION_HEX >= 0x030700a1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM+0 >= 0x07030400) + gc = PyImport_GetModule(__pyx_kp_u_gc); + #endif + if (unlikely(!gc)) gc = PyImport_Import(__pyx_kp_u_gc); + if (unlikely(!gc)) return -1; + py_status = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_isenabled); + if (unlikely(!py_status)) { + Py_DECREF(gc); + return -1; + } + gc_was_enabled = __Pyx_PyObject_IsTrue(py_status); + Py_DECREF(py_status); + if (gc_was_enabled > 0) { + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_disable); + if (unlikely(!ret)) { + Py_DECREF(gc); + return -1; + } + Py_DECREF(ret); + } else if (unlikely(gc_was_enabled == -1)) { + Py_DECREF(gc); + return -1; + } + #endif + t->tp_flags |= Py_TPFLAGS_HEAPTYPE; +#if PY_VERSION_HEX >= 0x030A0000 + t->tp_flags |= Py_TPFLAGS_IMMUTABLETYPE; +#endif +#else + (void)__Pyx_PyObject_CallMethod0; +#endif + r = PyType_Ready(t); +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + t->tp_flags &= ~Py_TPFLAGS_HEAPTYPE; + #if PY_VERSION_HEX >= 0x030A00b1 + if (gc_was_enabled) + PyGC_Enable(); + #else + if (gc_was_enabled) { + PyObject *tp, *v, *tb; + PyErr_Fetch(&tp, &v, &tb); + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_enable); + if (likely(ret || r == -1)) { + Py_XDECREF(ret); + PyErr_Restore(tp, v, tb); + } else { + Py_XDECREF(tp); + Py_XDECREF(v); + Py_XDECREF(tb); + r = -1; + } + } + Py_DECREF(gc); + #endif + } +#endif + return r; +#endif +} + +/* SetupReduce */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce_is_named(PyObject* meth, PyObject* name) { + int ret; + PyObject *name_attr; + name_attr = __Pyx_PyObject_GetAttrStrNoError(meth, __pyx_n_s_name_2); + if (likely(name_attr)) { + ret = PyObject_RichCompareBool(name_attr, name, Py_EQ); + } else { + ret = -1; + } + if (unlikely(ret < 0)) { + PyErr_Clear(); + ret = 0; + } + Py_XDECREF(name_attr); + return ret; +} +static int __Pyx_setup_reduce(PyObject* type_obj) { + int ret = 0; + PyObject *object_reduce = NULL; + PyObject *object_getstate = NULL; + PyObject *object_reduce_ex = NULL; + PyObject *reduce = NULL; + PyObject *reduce_ex = NULL; + PyObject *reduce_cython = NULL; + PyObject *setstate = NULL; + PyObject *setstate_cython = NULL; + PyObject *getstate = NULL; +#if CYTHON_USE_PYTYPE_LOOKUP + getstate = _PyType_Lookup((PyTypeObject*)type_obj, __pyx_n_s_getstate); +#else + getstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_getstate); + if (!getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (getstate) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_getstate = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_getstate); +#else + object_getstate = __Pyx_PyObject_GetAttrStrNoError((PyObject*)&PyBaseObject_Type, __pyx_n_s_getstate); + if (!object_getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (object_getstate != getstate) { + goto __PYX_GOOD; + } + } +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce_ex = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#else + object_reduce_ex = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#endif + reduce_ex = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce_ex); if (unlikely(!reduce_ex)) goto __PYX_BAD; + if (reduce_ex == object_reduce_ex) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#else + object_reduce = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#endif + reduce = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce); if (unlikely(!reduce)) goto __PYX_BAD; + if (reduce == object_reduce || __Pyx_setup_reduce_is_named(reduce, __pyx_n_s_reduce_cython)) { + reduce_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_reduce_cython); + if (likely(reduce_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce, reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (reduce == object_reduce || PyErr_Occurred()) { + goto __PYX_BAD; + } + setstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate); + if (!setstate) PyErr_Clear(); + if (!setstate || __Pyx_setup_reduce_is_named(setstate, __pyx_n_s_setstate_cython)) { + setstate_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate_cython); + if (likely(setstate_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate, setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (!setstate || PyErr_Occurred()) { + goto __PYX_BAD; + } + } + PyType_Modified((PyTypeObject*)type_obj); + } + } + goto __PYX_GOOD; +__PYX_BAD: + if (!PyErr_Occurred()) { + __Pyx_TypeName type_obj_name = + __Pyx_PyType_GetName((PyTypeObject*)type_obj); + PyErr_Format(PyExc_RuntimeError, + "Unable to initialize pickling for " __Pyx_FMT_TYPENAME, type_obj_name); + __Pyx_DECREF_TypeName(type_obj_name); + } + ret = -1; +__PYX_GOOD: +#if !CYTHON_USE_PYTYPE_LOOKUP + Py_XDECREF(object_reduce); + Py_XDECREF(object_reduce_ex); + Py_XDECREF(object_getstate); + Py_XDECREF(getstate); +#endif + Py_XDECREF(reduce); + Py_XDECREF(reduce_ex); + Py_XDECREF(reduce_cython); + Py_XDECREF(setstate); + Py_XDECREF(setstate_cython); + return ret; +} +#endif + +/* SetVTable */ +static int __Pyx_SetVtable(PyTypeObject *type, void *vtable) { + PyObject *ob = PyCapsule_New(vtable, 0, 0); + if (unlikely(!ob)) + goto bad; +#if CYTHON_COMPILING_IN_LIMITED_API + if (unlikely(PyObject_SetAttr((PyObject *) type, __pyx_n_s_pyx_vtable, ob) < 0)) +#else + if (unlikely(PyDict_SetItem(type->tp_dict, __pyx_n_s_pyx_vtable, ob) < 0)) +#endif + goto bad; + Py_DECREF(ob); + return 0; +bad: + Py_XDECREF(ob); + return -1; +} + +/* GetVTable */ +static void* __Pyx_GetVtable(PyTypeObject *type) { + void* ptr; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *ob = PyObject_GetAttr((PyObject *)type, __pyx_n_s_pyx_vtable); +#else + PyObject *ob = PyObject_GetItem(type->tp_dict, __pyx_n_s_pyx_vtable); +#endif + if (!ob) + goto bad; + ptr = PyCapsule_GetPointer(ob, 0); + if (!ptr && !PyErr_Occurred()) + PyErr_SetString(PyExc_RuntimeError, "invalid vtable found for imported type"); + Py_DECREF(ob); + return ptr; +bad: + Py_XDECREF(ob); + return NULL; +} + +/* MergeVTables */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_MergeVtables(PyTypeObject *type) { + int i; + void** base_vtables; + __Pyx_TypeName tp_base_name; + __Pyx_TypeName base_name; + void* unknown = (void*)-1; + PyObject* bases = type->tp_bases; + int base_depth = 0; + { + PyTypeObject* base = type->tp_base; + while (base) { + base_depth += 1; + base = base->tp_base; + } + } + base_vtables = (void**) malloc(sizeof(void*) * (size_t)(base_depth + 1)); + base_vtables[0] = unknown; + for (i = 1; i < PyTuple_GET_SIZE(bases); i++) { + void* base_vtable = __Pyx_GetVtable(((PyTypeObject*)PyTuple_GET_ITEM(bases, i))); + if (base_vtable != NULL) { + int j; + PyTypeObject* base = type->tp_base; + for (j = 0; j < base_depth; j++) { + if (base_vtables[j] == unknown) { + base_vtables[j] = __Pyx_GetVtable(base); + base_vtables[j + 1] = unknown; + } + if (base_vtables[j] == base_vtable) { + break; + } else if (base_vtables[j] == NULL) { + goto bad; + } + base = base->tp_base; + } + } + } + PyErr_Clear(); + free(base_vtables); + return 0; +bad: + tp_base_name = __Pyx_PyType_GetName(type->tp_base); + base_name = __Pyx_PyType_GetName((PyTypeObject*)PyTuple_GET_ITEM(bases, i)); + PyErr_Format(PyExc_TypeError, + "multiple bases have vtable conflict: '" __Pyx_FMT_TYPENAME "' and '" __Pyx_FMT_TYPENAME "'", tp_base_name, base_name); + __Pyx_DECREF_TypeName(tp_base_name); + __Pyx_DECREF_TypeName(base_name); + free(base_vtables); + return -1; +} +#endif + +/* FetchSharedCythonModule */ +static PyObject *__Pyx_FetchSharedCythonABIModule(void) { + return __Pyx_PyImport_AddModuleRef((char*) __PYX_ABI_MODULE_NAME); +} + +/* FetchCommonType */ +static int __Pyx_VerifyCachedType(PyObject *cached_type, + const char *name, + Py_ssize_t basicsize, + Py_ssize_t expected_basicsize) { + if (!PyType_Check(cached_type)) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s is not a type object", name); + return -1; + } + if (basicsize != expected_basicsize) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s has the wrong size, try recompiling", + name); + return -1; + } + return 0; +} +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type) { + PyObject* abi_module; + const char* object_name; + PyTypeObject *cached_type = NULL; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + object_name = strrchr(type->tp_name, '.'); + object_name = object_name ? object_name+1 : type->tp_name; + cached_type = (PyTypeObject*) PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + if (__Pyx_VerifyCachedType( + (PyObject *)cached_type, + object_name, + cached_type->tp_basicsize, + type->tp_basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + if (PyType_Ready(type) < 0) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, (PyObject *)type) < 0) + goto bad; + Py_INCREF(type); + cached_type = type; +done: + Py_DECREF(abi_module); + return cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#else +static PyTypeObject *__Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases) { + PyObject *abi_module, *cached_type = NULL; + const char* object_name = strrchr(spec->name, '.'); + object_name = object_name ? object_name+1 : spec->name; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + cached_type = PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + Py_ssize_t basicsize; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *py_basicsize; + py_basicsize = PyObject_GetAttrString(cached_type, "__basicsize__"); + if (unlikely(!py_basicsize)) goto bad; + basicsize = PyLong_AsSsize_t(py_basicsize); + Py_DECREF(py_basicsize); + py_basicsize = 0; + if (unlikely(basicsize == (Py_ssize_t)-1) && PyErr_Occurred()) goto bad; +#else + basicsize = likely(PyType_Check(cached_type)) ? ((PyTypeObject*) cached_type)->tp_basicsize : -1; +#endif + if (__Pyx_VerifyCachedType( + cached_type, + object_name, + basicsize, + spec->basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + CYTHON_UNUSED_VAR(module); + cached_type = __Pyx_PyType_FromModuleAndSpec(abi_module, spec, bases); + if (unlikely(!cached_type)) goto bad; + if (unlikely(__Pyx_fix_up_extension_type_from_spec(spec, (PyTypeObject *) cached_type) < 0)) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, cached_type) < 0) goto bad; +done: + Py_DECREF(abi_module); + assert(cached_type == NULL || PyType_Check(cached_type)); + return (PyTypeObject *) cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#endif + +/* PyVectorcallFastCallDict */ +#if CYTHON_METH_FASTCALL +static PyObject *__Pyx_PyVectorcall_FastCallDict_kw(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + PyObject *res = NULL; + PyObject *kwnames; + PyObject **newargs; + PyObject **kwvalues; + Py_ssize_t i, pos; + size_t j; + PyObject *key, *value; + unsigned long keys_are_strings; + Py_ssize_t nkw = PyDict_GET_SIZE(kw); + newargs = (PyObject **)PyMem_Malloc((nargs + (size_t)nkw) * sizeof(args[0])); + if (unlikely(newargs == NULL)) { + PyErr_NoMemory(); + return NULL; + } + for (j = 0; j < nargs; j++) newargs[j] = args[j]; + kwnames = PyTuple_New(nkw); + if (unlikely(kwnames == NULL)) { + PyMem_Free(newargs); + return NULL; + } + kwvalues = newargs + nargs; + pos = i = 0; + keys_are_strings = Py_TPFLAGS_UNICODE_SUBCLASS; + while (PyDict_Next(kw, &pos, &key, &value)) { + keys_are_strings &= Py_TYPE(key)->tp_flags; + Py_INCREF(key); + Py_INCREF(value); + PyTuple_SET_ITEM(kwnames, i, key); + kwvalues[i] = value; + i++; + } + if (unlikely(!keys_are_strings)) { + PyErr_SetString(PyExc_TypeError, "keywords must be strings"); + goto cleanup; + } + res = vc(func, newargs, nargs, kwnames); +cleanup: + Py_DECREF(kwnames); + for (i = 0; i < nkw; i++) + Py_DECREF(kwvalues[i]); + PyMem_Free(newargs); + return res; +} +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + if (likely(kw == NULL) || PyDict_GET_SIZE(kw) == 0) { + return vc(func, args, nargs, NULL); + } + return __Pyx_PyVectorcall_FastCallDict_kw(func, vc, args, nargs, kw); +} +#endif + +/* CythonFunctionShared */ +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc) { + if (__Pyx_CyFunction_Check(func)) { + return PyCFunction_GetFunction(((__pyx_CyFunctionObject*)func)->func) == (PyCFunction) cfunc; + } else if (PyCFunction_Check(func)) { + return PyCFunction_GetFunction(func) == (PyCFunction) cfunc; + } + return 0; +} +#else +static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc) { + return __Pyx_CyOrPyCFunction_Check(func) && __Pyx_CyOrPyCFunction_GET_FUNCTION(func) == (PyCFunction) cfunc; +} +#endif +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj) { +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + __Pyx_Py_XDECREF_SET( + __Pyx_CyFunction_GetClassObj(f), + ((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#else + __Pyx_Py_XDECREF_SET( + ((PyCMethodObject *) (f))->mm_class, + (PyTypeObject*)((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#endif +} +static PyObject * +__Pyx_CyFunction_get_doc(__pyx_CyFunctionObject *op, void *closure) +{ + CYTHON_UNUSED_VAR(closure); + if (unlikely(op->func_doc == NULL)) { +#if CYTHON_COMPILING_IN_LIMITED_API + op->func_doc = PyObject_GetAttrString(op->func, "__doc__"); + if (unlikely(!op->func_doc)) return NULL; +#else + if (((PyCFunctionObject*)op)->m_ml->ml_doc) { +#if PY_MAJOR_VERSION >= 3 + op->func_doc = PyUnicode_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#else + op->func_doc = PyString_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#endif + if (unlikely(op->func_doc == NULL)) + return NULL; + } else { + Py_INCREF(Py_None); + return Py_None; + } +#endif + } + Py_INCREF(op->func_doc); + return op->func_doc; +} +static int +__Pyx_CyFunction_set_doc(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (value == NULL) { + value = Py_None; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_doc, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_name(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_name == NULL)) { +#if CYTHON_COMPILING_IN_LIMITED_API + op->func_name = PyObject_GetAttrString(op->func, "__name__"); +#elif PY_MAJOR_VERSION >= 3 + op->func_name = PyUnicode_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#else + op->func_name = PyString_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#endif + if (unlikely(op->func_name == NULL)) + return NULL; + } + Py_INCREF(op->func_name); + return op->func_name; +} +static int +__Pyx_CyFunction_set_name(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__name__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_name, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_qualname(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_qualname); + return op->func_qualname; +} +static int +__Pyx_CyFunction_set_qualname(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__qualname__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_qualname, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_dict(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_dict == NULL)) { + op->func_dict = PyDict_New(); + if (unlikely(op->func_dict == NULL)) + return NULL; + } + Py_INCREF(op->func_dict); + return op->func_dict; +} +static int +__Pyx_CyFunction_set_dict(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(value == NULL)) { + PyErr_SetString(PyExc_TypeError, + "function's dictionary may not be deleted"); + return -1; + } + if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "setting function's dictionary to a non-dict"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_dict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_globals(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_globals); + return op->func_globals; +} +static PyObject * +__Pyx_CyFunction_get_closure(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(op); + CYTHON_UNUSED_VAR(context); + Py_INCREF(Py_None); + return Py_None; +} +static PyObject * +__Pyx_CyFunction_get_code(__pyx_CyFunctionObject *op, void *context) +{ + PyObject* result = (op->func_code) ? op->func_code : Py_None; + CYTHON_UNUSED_VAR(context); + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_init_defaults(__pyx_CyFunctionObject *op) { + int result = 0; + PyObject *res = op->defaults_getter((PyObject *) op); + if (unlikely(!res)) + return -1; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + op->defaults_tuple = PyTuple_GET_ITEM(res, 0); + Py_INCREF(op->defaults_tuple); + op->defaults_kwdict = PyTuple_GET_ITEM(res, 1); + Py_INCREF(op->defaults_kwdict); + #else + op->defaults_tuple = __Pyx_PySequence_ITEM(res, 0); + if (unlikely(!op->defaults_tuple)) result = -1; + else { + op->defaults_kwdict = __Pyx_PySequence_ITEM(res, 1); + if (unlikely(!op->defaults_kwdict)) result = -1; + } + #endif + Py_DECREF(res); + return result; +} +static int +__Pyx_CyFunction_set_defaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyTuple_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__defaults__ must be set to a tuple object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__defaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_tuple, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_defaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_tuple; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_tuple; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_kwdefaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__kwdefaults__ must be set to a dict object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__kwdefaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_kwdict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_kwdefaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_kwdict; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_kwdict; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_annotations(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value || value == Py_None) { + value = NULL; + } else if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__annotations__ must be set to a dict object"); + return -1; + } + Py_XINCREF(value); + __Pyx_Py_XDECREF_SET(op->func_annotations, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_annotations(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->func_annotations; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + result = PyDict_New(); + if (unlikely(!result)) return NULL; + op->func_annotations = result; + } + Py_INCREF(result); + return result; +} +static PyObject * +__Pyx_CyFunction_get_is_coroutine(__pyx_CyFunctionObject *op, void *context) { + int is_coroutine; + CYTHON_UNUSED_VAR(context); + if (op->func_is_coroutine) { + return __Pyx_NewRef(op->func_is_coroutine); + } + is_coroutine = op->flags & __Pyx_CYFUNCTION_COROUTINE; +#if PY_VERSION_HEX >= 0x03050000 + if (is_coroutine) { + PyObject *module, *fromlist, *marker = __pyx_n_s_is_coroutine; + fromlist = PyList_New(1); + if (unlikely(!fromlist)) return NULL; + Py_INCREF(marker); +#if CYTHON_ASSUME_SAFE_MACROS + PyList_SET_ITEM(fromlist, 0, marker); +#else + if (unlikely(PyList_SetItem(fromlist, 0, marker) < 0)) { + Py_DECREF(marker); + Py_DECREF(fromlist); + return NULL; + } +#endif + module = PyImport_ImportModuleLevelObject(__pyx_n_s_asyncio_coroutines, NULL, NULL, fromlist, 0); + Py_DECREF(fromlist); + if (unlikely(!module)) goto ignore; + op->func_is_coroutine = __Pyx_PyObject_GetAttrStr(module, marker); + Py_DECREF(module); + if (likely(op->func_is_coroutine)) { + return __Pyx_NewRef(op->func_is_coroutine); + } +ignore: + PyErr_Clear(); + } +#endif + op->func_is_coroutine = __Pyx_PyBool_FromLong(is_coroutine); + return __Pyx_NewRef(op->func_is_coroutine); +} +#if CYTHON_COMPILING_IN_LIMITED_API +static PyObject * +__Pyx_CyFunction_get_module(__pyx_CyFunctionObject *op, void *context) { + CYTHON_UNUSED_VAR(context); + return PyObject_GetAttrString(op->func, "__module__"); +} +static int +__Pyx_CyFunction_set_module(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + return PyObject_SetAttrString(op->func, "__module__", value); +} +#endif +static PyGetSetDef __pyx_CyFunction_getsets[] = { + {(char *) "func_doc", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "__doc__", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "func_name", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__name__", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__qualname__", (getter)__Pyx_CyFunction_get_qualname, (setter)__Pyx_CyFunction_set_qualname, 0, 0}, + {(char *) "func_dict", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "__dict__", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "func_globals", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "__globals__", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "func_closure", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "__closure__", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "func_code", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "__code__", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "func_defaults", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__defaults__", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__kwdefaults__", (getter)__Pyx_CyFunction_get_kwdefaults, (setter)__Pyx_CyFunction_set_kwdefaults, 0, 0}, + {(char *) "__annotations__", (getter)__Pyx_CyFunction_get_annotations, (setter)__Pyx_CyFunction_set_annotations, 0, 0}, + {(char *) "_is_coroutine", (getter)__Pyx_CyFunction_get_is_coroutine, 0, 0, 0}, +#if CYTHON_COMPILING_IN_LIMITED_API + {"__module__", (getter)__Pyx_CyFunction_get_module, (setter)__Pyx_CyFunction_set_module, 0, 0}, +#endif + {0, 0, 0, 0, 0} +}; +static PyMemberDef __pyx_CyFunction_members[] = { +#if !CYTHON_COMPILING_IN_LIMITED_API + {(char *) "__module__", T_OBJECT, offsetof(PyCFunctionObject, m_module), 0, 0}, +#endif +#if CYTHON_USE_TYPE_SPECS + {(char *) "__dictoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_dict), READONLY, 0}, +#if CYTHON_METH_FASTCALL +#if CYTHON_BACKPORT_VECTORCALL + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_vectorcall), READONLY, 0}, +#else +#if !CYTHON_COMPILING_IN_LIMITED_API + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(PyCFunctionObject, vectorcall), READONLY, 0}, +#endif +#endif +#endif +#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_weakreflist), READONLY, 0}, +#else + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(PyCFunctionObject, m_weakreflist), READONLY, 0}, +#endif +#endif + {0, 0, 0, 0, 0} +}; +static PyObject * +__Pyx_CyFunction_reduce(__pyx_CyFunctionObject *m, PyObject *args) +{ + CYTHON_UNUSED_VAR(args); +#if PY_MAJOR_VERSION >= 3 + Py_INCREF(m->func_qualname); + return m->func_qualname; +#else + return PyString_FromString(((PyCFunctionObject*)m)->m_ml->ml_name); +#endif +} +static PyMethodDef __pyx_CyFunction_methods[] = { + {"__reduce__", (PyCFunction)__Pyx_CyFunction_reduce, METH_VARARGS, 0}, + {0, 0, 0, 0} +}; +#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API +#define __Pyx_CyFunction_weakreflist(cyfunc) ((cyfunc)->func_weakreflist) +#else +#define __Pyx_CyFunction_weakreflist(cyfunc) (((PyCFunctionObject*)cyfunc)->m_weakreflist) +#endif +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject *op, PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { +#if !CYTHON_COMPILING_IN_LIMITED_API + PyCFunctionObject *cf = (PyCFunctionObject*) op; +#endif + if (unlikely(op == NULL)) + return NULL; +#if CYTHON_COMPILING_IN_LIMITED_API + op->func = PyCFunction_NewEx(ml, (PyObject*)op, module); + if (unlikely(!op->func)) return NULL; +#endif + op->flags = flags; + __Pyx_CyFunction_weakreflist(op) = NULL; +#if !CYTHON_COMPILING_IN_LIMITED_API + cf->m_ml = ml; + cf->m_self = (PyObject *) op; +#endif + Py_XINCREF(closure); + op->func_closure = closure; +#if !CYTHON_COMPILING_IN_LIMITED_API + Py_XINCREF(module); + cf->m_module = module; +#endif + op->func_dict = NULL; + op->func_name = NULL; + Py_INCREF(qualname); + op->func_qualname = qualname; + op->func_doc = NULL; +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + op->func_classobj = NULL; +#else + ((PyCMethodObject*)op)->mm_class = NULL; +#endif + op->func_globals = globals; + Py_INCREF(op->func_globals); + Py_XINCREF(code); + op->func_code = code; + op->defaults_pyobjects = 0; + op->defaults_size = 0; + op->defaults = NULL; + op->defaults_tuple = NULL; + op->defaults_kwdict = NULL; + op->defaults_getter = NULL; + op->func_annotations = NULL; + op->func_is_coroutine = NULL; +#if CYTHON_METH_FASTCALL + switch (ml->ml_flags & (METH_VARARGS | METH_FASTCALL | METH_NOARGS | METH_O | METH_KEYWORDS | METH_METHOD)) { + case METH_NOARGS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_NOARGS; + break; + case METH_O: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_O; + break; + case METH_METHOD | METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD; + break; + case METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS; + break; + case METH_VARARGS | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = NULL; + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + Py_DECREF(op); + return NULL; + } +#endif + return (PyObject *) op; +} +static int +__Pyx_CyFunction_clear(__pyx_CyFunctionObject *m) +{ + Py_CLEAR(m->func_closure); +#if CYTHON_COMPILING_IN_LIMITED_API + Py_CLEAR(m->func); +#else + Py_CLEAR(((PyCFunctionObject*)m)->m_module); +#endif + Py_CLEAR(m->func_dict); + Py_CLEAR(m->func_name); + Py_CLEAR(m->func_qualname); + Py_CLEAR(m->func_doc); + Py_CLEAR(m->func_globals); + Py_CLEAR(m->func_code); +#if !CYTHON_COMPILING_IN_LIMITED_API +#if PY_VERSION_HEX < 0x030900B1 + Py_CLEAR(__Pyx_CyFunction_GetClassObj(m)); +#else + { + PyObject *cls = (PyObject*) ((PyCMethodObject *) (m))->mm_class; + ((PyCMethodObject *) (m))->mm_class = NULL; + Py_XDECREF(cls); + } +#endif +#endif + Py_CLEAR(m->defaults_tuple); + Py_CLEAR(m->defaults_kwdict); + Py_CLEAR(m->func_annotations); + Py_CLEAR(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_XDECREF(pydefaults[i]); + PyObject_Free(m->defaults); + m->defaults = NULL; + } + return 0; +} +static void __Pyx__CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + if (__Pyx_CyFunction_weakreflist(m) != NULL) + PyObject_ClearWeakRefs((PyObject *) m); + __Pyx_CyFunction_clear(m); + __Pyx_PyHeapTypeObject_GC_Del(m); +} +static void __Pyx_CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + PyObject_GC_UnTrack(m); + __Pyx__CyFunction_dealloc(m); +} +static int __Pyx_CyFunction_traverse(__pyx_CyFunctionObject *m, visitproc visit, void *arg) +{ + Py_VISIT(m->func_closure); +#if CYTHON_COMPILING_IN_LIMITED_API + Py_VISIT(m->func); +#else + Py_VISIT(((PyCFunctionObject*)m)->m_module); +#endif + Py_VISIT(m->func_dict); + Py_VISIT(m->func_name); + Py_VISIT(m->func_qualname); + Py_VISIT(m->func_doc); + Py_VISIT(m->func_globals); + Py_VISIT(m->func_code); +#if !CYTHON_COMPILING_IN_LIMITED_API + Py_VISIT(__Pyx_CyFunction_GetClassObj(m)); +#endif + Py_VISIT(m->defaults_tuple); + Py_VISIT(m->defaults_kwdict); + Py_VISIT(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_VISIT(pydefaults[i]); + } + return 0; +} +static PyObject* +__Pyx_CyFunction_repr(__pyx_CyFunctionObject *op) +{ +#if PY_MAJOR_VERSION >= 3 + return PyUnicode_FromFormat("", + op->func_qualname, (void *)op); +#else + return PyString_FromFormat("", + PyString_AsString(op->func_qualname), (void *)op); +#endif +} +static PyObject * __Pyx_CyFunction_CallMethod(PyObject *func, PyObject *self, PyObject *arg, PyObject *kw) { +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *f = ((__pyx_CyFunctionObject*)func)->func; + PyObject *py_name = NULL; + PyCFunction meth; + int flags; + meth = PyCFunction_GetFunction(f); + if (unlikely(!meth)) return NULL; + flags = PyCFunction_GetFlags(f); + if (unlikely(flags < 0)) return NULL; +#else + PyCFunctionObject* f = (PyCFunctionObject*)func; + PyCFunction meth = f->m_ml->ml_meth; + int flags = f->m_ml->ml_flags; +#endif + Py_ssize_t size; + switch (flags & (METH_VARARGS | METH_KEYWORDS | METH_NOARGS | METH_O)) { + case METH_VARARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) + return (*meth)(self, arg); + break; + case METH_VARARGS | METH_KEYWORDS: + return (*(PyCFunctionWithKeywords)(void*)meth)(self, arg, kw); + case METH_NOARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { +#if CYTHON_ASSUME_SAFE_MACROS + size = PyTuple_GET_SIZE(arg); +#else + size = PyTuple_Size(arg); + if (unlikely(size < 0)) return NULL; +#endif + if (likely(size == 0)) + return (*meth)(self, NULL); +#if CYTHON_COMPILING_IN_LIMITED_API + py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); + if (!py_name) return NULL; + PyErr_Format(PyExc_TypeError, + "%.200S() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + py_name, size); + Py_DECREF(py_name); +#else + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); +#endif + return NULL; + } + break; + case METH_O: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { +#if CYTHON_ASSUME_SAFE_MACROS + size = PyTuple_GET_SIZE(arg); +#else + size = PyTuple_Size(arg); + if (unlikely(size < 0)) return NULL; +#endif + if (likely(size == 1)) { + PyObject *result, *arg0; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + arg0 = PyTuple_GET_ITEM(arg, 0); + #else + arg0 = __Pyx_PySequence_ITEM(arg, 0); if (unlikely(!arg0)) return NULL; + #endif + result = (*meth)(self, arg0); + #if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(arg0); + #endif + return result; + } +#if CYTHON_COMPILING_IN_LIMITED_API + py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); + if (!py_name) return NULL; + PyErr_Format(PyExc_TypeError, + "%.200S() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + py_name, size); + Py_DECREF(py_name); +#else + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); +#endif + return NULL; + } + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + return NULL; + } +#if CYTHON_COMPILING_IN_LIMITED_API + py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); + if (!py_name) return NULL; + PyErr_Format(PyExc_TypeError, "%.200S() takes no keyword arguments", + py_name); + Py_DECREF(py_name); +#else + PyErr_Format(PyExc_TypeError, "%.200s() takes no keyword arguments", + f->m_ml->ml_name); +#endif + return NULL; +} +static CYTHON_INLINE PyObject *__Pyx_CyFunction_Call(PyObject *func, PyObject *arg, PyObject *kw) { + PyObject *self, *result; +#if CYTHON_COMPILING_IN_LIMITED_API + self = PyCFunction_GetSelf(((__pyx_CyFunctionObject*)func)->func); + if (unlikely(!self) && PyErr_Occurred()) return NULL; +#else + self = ((PyCFunctionObject*)func)->m_self; +#endif + result = __Pyx_CyFunction_CallMethod(func, self, arg, kw); + return result; +} +static PyObject *__Pyx_CyFunction_CallAsMethod(PyObject *func, PyObject *args, PyObject *kw) { + PyObject *result; + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *) func; +#if CYTHON_METH_FASTCALL + __pyx_vectorcallfunc vc = __Pyx_CyFunction_func_vectorcall(cyfunc); + if (vc) { +#if CYTHON_ASSUME_SAFE_MACROS + return __Pyx_PyVectorcall_FastCallDict(func, vc, &PyTuple_GET_ITEM(args, 0), (size_t)PyTuple_GET_SIZE(args), kw); +#else + (void) &__Pyx_PyVectorcall_FastCallDict; + return PyVectorcall_Call(func, args, kw); +#endif + } +#endif + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + Py_ssize_t argc; + PyObject *new_args; + PyObject *self; +#if CYTHON_ASSUME_SAFE_MACROS + argc = PyTuple_GET_SIZE(args); +#else + argc = PyTuple_Size(args); + if (unlikely(!argc) < 0) return NULL; +#endif + new_args = PyTuple_GetSlice(args, 1, argc); + if (unlikely(!new_args)) + return NULL; + self = PyTuple_GetItem(args, 0); + if (unlikely(!self)) { + Py_DECREF(new_args); +#if PY_MAJOR_VERSION > 2 + PyErr_Format(PyExc_TypeError, + "unbound method %.200S() needs an argument", + cyfunc->func_qualname); +#else + PyErr_SetString(PyExc_TypeError, + "unbound method needs an argument"); +#endif + return NULL; + } + result = __Pyx_CyFunction_CallMethod(func, self, new_args, kw); + Py_DECREF(new_args); + } else { + result = __Pyx_CyFunction_Call(func, args, kw); + } + return result; +} +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE int __Pyx_CyFunction_Vectorcall_CheckArgs(__pyx_CyFunctionObject *cyfunc, Py_ssize_t nargs, PyObject *kwnames) +{ + int ret = 0; + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + if (unlikely(nargs < 1)) { + PyErr_Format(PyExc_TypeError, "%.200s() needs an argument", + ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + ret = 1; + } + if (unlikely(kwnames) && unlikely(PyTuple_GET_SIZE(kwnames))) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no keyword arguments", ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + return ret; +} +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 0)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, NULL); +} +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 1)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, args[0]); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((_PyCFunctionFastWithKeywords)(void(*)(void))def->ml_meth)(self, args, nargs, kwnames); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; + PyTypeObject *cls = (PyTypeObject *) __Pyx_CyFunction_GetClassObj(cyfunc); +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((__Pyx_PyCMethod)(void(*)(void))def->ml_meth)(self, cls, args, (size_t)nargs, kwnames); +} +#endif +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_CyFunctionType_slots[] = { + {Py_tp_dealloc, (void *)__Pyx_CyFunction_dealloc}, + {Py_tp_repr, (void *)__Pyx_CyFunction_repr}, + {Py_tp_call, (void *)__Pyx_CyFunction_CallAsMethod}, + {Py_tp_traverse, (void *)__Pyx_CyFunction_traverse}, + {Py_tp_clear, (void *)__Pyx_CyFunction_clear}, + {Py_tp_methods, (void *)__pyx_CyFunction_methods}, + {Py_tp_members, (void *)__pyx_CyFunction_members}, + {Py_tp_getset, (void *)__pyx_CyFunction_getsets}, + {Py_tp_descr_get, (void *)__Pyx_PyMethod_New}, + {0, 0}, +}; +static PyType_Spec __pyx_CyFunctionType_spec = { + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#if (defined(_Py_TPFLAGS_HAVE_VECTORCALL) && CYTHON_METH_FASTCALL) + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + __pyx_CyFunctionType_slots +}; +#else +static PyTypeObject __pyx_CyFunctionType_type = { + PyVarObject_HEAD_INIT(0, 0) + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, + (destructor) __Pyx_CyFunction_dealloc, +#if !CYTHON_METH_FASTCALL + 0, +#elif CYTHON_BACKPORT_VECTORCALL + (printfunc)offsetof(__pyx_CyFunctionObject, func_vectorcall), +#else + offsetof(PyCFunctionObject, vectorcall), +#endif + 0, + 0, +#if PY_MAJOR_VERSION < 3 + 0, +#else + 0, +#endif + (reprfunc) __Pyx_CyFunction_repr, + 0, + 0, + 0, + 0, + __Pyx_CyFunction_CallAsMethod, + 0, + 0, + 0, + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#if defined(_Py_TPFLAGS_HAVE_VECTORCALL) && CYTHON_METH_FASTCALL + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + 0, + (traverseproc) __Pyx_CyFunction_traverse, + (inquiry) __Pyx_CyFunction_clear, + 0, +#if PY_VERSION_HEX < 0x030500A0 + offsetof(__pyx_CyFunctionObject, func_weakreflist), +#else + offsetof(PyCFunctionObject, m_weakreflist), +#endif + 0, + 0, + __pyx_CyFunction_methods, + __pyx_CyFunction_members, + __pyx_CyFunction_getsets, + 0, + 0, + __Pyx_PyMethod_New, + 0, + offsetof(__pyx_CyFunctionObject, func_dict), + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, +#if PY_VERSION_HEX >= 0x030400a1 + 0, +#endif +#if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, +#endif +#if __PYX_NEED_TP_PRINT_SLOT + 0, +#endif +#if PY_VERSION_HEX >= 0x030C0000 + 0, +#endif +#if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, +#endif +}; +#endif +static int __pyx_CyFunction_init(PyObject *module) { +#if CYTHON_USE_TYPE_SPECS + __pyx_CyFunctionType = __Pyx_FetchCommonTypeFromSpec(module, &__pyx_CyFunctionType_spec, NULL); +#else + CYTHON_UNUSED_VAR(module); + __pyx_CyFunctionType = __Pyx_FetchCommonType(&__pyx_CyFunctionType_type); +#endif + if (unlikely(__pyx_CyFunctionType == NULL)) { + return -1; + } + return 0; +} +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *func, size_t size, int pyobjects) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults = PyObject_Malloc(size); + if (unlikely(!m->defaults)) + return PyErr_NoMemory(); + memset(m->defaults, 0, size); + m->defaults_pyobjects = pyobjects; + m->defaults_size = size; + return m->defaults; +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *func, PyObject *tuple) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_tuple = tuple; + Py_INCREF(tuple); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_kwdict = dict; + Py_INCREF(dict); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->func_annotations = dict; + Py_INCREF(dict); +} + +/* CythonFunction */ +static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { + PyObject *op = __Pyx_CyFunction_Init( + PyObject_GC_New(__pyx_CyFunctionObject, __pyx_CyFunctionType), + ml, flags, qualname, closure, module, globals, code + ); + if (likely(op)) { + PyObject_GC_Track(op); + } + return op; +} + +/* CLineInTraceback */ +#ifndef CYTHON_CLINE_IN_TRACEBACK +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line) { + PyObject *use_cline; + PyObject *ptype, *pvalue, *ptraceback; +#if CYTHON_COMPILING_IN_CPYTHON + PyObject **cython_runtime_dict; +#endif + CYTHON_MAYBE_UNUSED_VAR(tstate); + if (unlikely(!__pyx_cython_runtime)) { + return c_line; + } + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); +#if CYTHON_COMPILING_IN_CPYTHON + cython_runtime_dict = _PyObject_GetDictPtr(__pyx_cython_runtime); + if (likely(cython_runtime_dict)) { + __PYX_PY_DICT_LOOKUP_IF_MODIFIED( + use_cline, *cython_runtime_dict, + __Pyx_PyDict_GetItemStr(*cython_runtime_dict, __pyx_n_s_cline_in_traceback)) + } else +#endif + { + PyObject *use_cline_obj = __Pyx_PyObject_GetAttrStrNoError(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback); + if (use_cline_obj) { + use_cline = PyObject_Not(use_cline_obj) ? Py_False : Py_True; + Py_DECREF(use_cline_obj); + } else { + PyErr_Clear(); + use_cline = NULL; + } + } + if (!use_cline) { + c_line = 0; + (void) PyObject_SetAttr(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback, Py_False); + } + else if (use_cline == Py_False || (use_cline != Py_True && PyObject_Not(use_cline) != 0)) { + c_line = 0; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + return c_line; +} +#endif + +/* CodeObjectCache */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line) { + int start = 0, mid = 0, end = count - 1; + if (end >= 0 && code_line > entries[end].code_line) { + return count; + } + while (start < end) { + mid = start + (end - start) / 2; + if (code_line < entries[mid].code_line) { + end = mid; + } else if (code_line > entries[mid].code_line) { + start = mid + 1; + } else { + return mid; + } + } + if (code_line <= entries[mid].code_line) { + return mid; + } else { + return mid + 1; + } +} +static PyCodeObject *__pyx_find_code_object(int code_line) { + PyCodeObject* code_object; + int pos; + if (unlikely(!code_line) || unlikely(!__pyx_code_cache.entries)) { + return NULL; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if (unlikely(pos >= __pyx_code_cache.count) || unlikely(__pyx_code_cache.entries[pos].code_line != code_line)) { + return NULL; + } + code_object = __pyx_code_cache.entries[pos].code_object; + Py_INCREF(code_object); + return code_object; +} +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object) { + int pos, i; + __Pyx_CodeObjectCacheEntry* entries = __pyx_code_cache.entries; + if (unlikely(!code_line)) { + return; + } + if (unlikely(!entries)) { + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Malloc(64*sizeof(__Pyx_CodeObjectCacheEntry)); + if (likely(entries)) { + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = 64; + __pyx_code_cache.count = 1; + entries[0].code_line = code_line; + entries[0].code_object = code_object; + Py_INCREF(code_object); + } + return; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if ((pos < __pyx_code_cache.count) && unlikely(__pyx_code_cache.entries[pos].code_line == code_line)) { + PyCodeObject* tmp = entries[pos].code_object; + entries[pos].code_object = code_object; + Py_DECREF(tmp); + return; + } + if (__pyx_code_cache.count == __pyx_code_cache.max_count) { + int new_max = __pyx_code_cache.max_count + 64; + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Realloc( + __pyx_code_cache.entries, ((size_t)new_max) * sizeof(__Pyx_CodeObjectCacheEntry)); + if (unlikely(!entries)) { + return; + } + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = new_max; + } + for (i=__pyx_code_cache.count; i>pos; i--) { + entries[i] = entries[i-1]; + } + entries[pos].code_line = code_line; + entries[pos].code_object = code_object; + __pyx_code_cache.count++; + Py_INCREF(code_object); +} +#endif + +/* AddTraceback */ +#include "compile.h" +#include "frameobject.h" +#include "traceback.h" +#if PY_VERSION_HEX >= 0x030b00a6 && !CYTHON_COMPILING_IN_LIMITED_API + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static PyObject *__Pyx_PyCode_Replace_For_AddTraceback(PyObject *code, PyObject *scratch_dict, + PyObject *firstlineno, PyObject *name) { + PyObject *replace = NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "co_firstlineno", firstlineno))) return NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "co_name", name))) return NULL; + replace = PyObject_GetAttrString(code, "replace"); + if (likely(replace)) { + PyObject *result; + result = PyObject_Call(replace, __pyx_empty_tuple, scratch_dict); + Py_DECREF(replace); + return result; + } + PyErr_Clear(); + #if __PYX_LIMITED_VERSION_HEX < 0x030780000 + { + PyObject *compiled = NULL, *result = NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "code", code))) return NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "type", (PyObject*)(&PyType_Type)))) return NULL; + compiled = Py_CompileString( + "out = type(code)(\n" + " code.co_argcount, code.co_kwonlyargcount, code.co_nlocals, code.co_stacksize,\n" + " code.co_flags, code.co_code, code.co_consts, code.co_names,\n" + " code.co_varnames, code.co_filename, co_name, co_firstlineno,\n" + " code.co_lnotab)\n", "", Py_file_input); + if (!compiled) return NULL; + result = PyEval_EvalCode(compiled, scratch_dict, scratch_dict); + Py_DECREF(compiled); + if (!result) PyErr_Print(); + Py_DECREF(result); + result = PyDict_GetItemString(scratch_dict, "out"); + if (result) Py_INCREF(result); + return result; + } + #else + return NULL; + #endif +} +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + PyObject *code_object = NULL, *py_py_line = NULL, *py_funcname = NULL, *dict = NULL; + PyObject *replace = NULL, *getframe = NULL, *frame = NULL; + PyObject *exc_type, *exc_value, *exc_traceback; + int success = 0; + if (c_line) { + (void) __pyx_cfilenm; + (void) __Pyx_CLineForTraceback(__Pyx_PyThreadState_Current, c_line); + } + PyErr_Fetch(&exc_type, &exc_value, &exc_traceback); + code_object = Py_CompileString("_getframe()", filename, Py_eval_input); + if (unlikely(!code_object)) goto bad; + py_py_line = PyLong_FromLong(py_line); + if (unlikely(!py_py_line)) goto bad; + py_funcname = PyUnicode_FromString(funcname); + if (unlikely(!py_funcname)) goto bad; + dict = PyDict_New(); + if (unlikely(!dict)) goto bad; + { + PyObject *old_code_object = code_object; + code_object = __Pyx_PyCode_Replace_For_AddTraceback(code_object, dict, py_py_line, py_funcname); + Py_DECREF(old_code_object); + } + if (unlikely(!code_object)) goto bad; + getframe = PySys_GetObject("_getframe"); + if (unlikely(!getframe)) goto bad; + if (unlikely(PyDict_SetItemString(dict, "_getframe", getframe))) goto bad; + frame = PyEval_EvalCode(code_object, dict, dict); + if (unlikely(!frame) || frame == Py_None) goto bad; + success = 1; + bad: + PyErr_Restore(exc_type, exc_value, exc_traceback); + Py_XDECREF(code_object); + Py_XDECREF(py_py_line); + Py_XDECREF(py_funcname); + Py_XDECREF(dict); + Py_XDECREF(replace); + if (success) { + PyTraceBack_Here( + (struct _frame*)frame); + } + Py_XDECREF(frame); +} +#else +static PyCodeObject* __Pyx_CreateCodeObjectForTraceback( + const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = NULL; + PyObject *py_funcname = NULL; + #if PY_MAJOR_VERSION < 3 + PyObject *py_srcfile = NULL; + py_srcfile = PyString_FromString(filename); + if (!py_srcfile) goto bad; + #endif + if (c_line) { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + #else + py_funcname = PyUnicode_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + funcname = PyUnicode_AsUTF8(py_funcname); + if (!funcname) goto bad; + #endif + } + else { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromString(funcname); + if (!py_funcname) goto bad; + #endif + } + #if PY_MAJOR_VERSION < 3 + py_code = __Pyx_PyCode_New( + 0, + 0, + 0, + 0, + 0, + 0, + __pyx_empty_bytes, /*PyObject *code,*/ + __pyx_empty_tuple, /*PyObject *consts,*/ + __pyx_empty_tuple, /*PyObject *names,*/ + __pyx_empty_tuple, /*PyObject *varnames,*/ + __pyx_empty_tuple, /*PyObject *freevars,*/ + __pyx_empty_tuple, /*PyObject *cellvars,*/ + py_srcfile, /*PyObject *filename,*/ + py_funcname, /*PyObject *name,*/ + py_line, + __pyx_empty_bytes /*PyObject *lnotab*/ + ); + Py_DECREF(py_srcfile); + #else + py_code = PyCode_NewEmpty(filename, funcname, py_line); + #endif + Py_XDECREF(py_funcname); + return py_code; +bad: + Py_XDECREF(py_funcname); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_srcfile); + #endif + return NULL; +} +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = 0; + PyFrameObject *py_frame = 0; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject *ptype, *pvalue, *ptraceback; + if (c_line) { + c_line = __Pyx_CLineForTraceback(tstate, c_line); + } + py_code = __pyx_find_code_object(c_line ? -c_line : py_line); + if (!py_code) { + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); + py_code = __Pyx_CreateCodeObjectForTraceback( + funcname, c_line, py_line, filename); + if (!py_code) { + /* If the code object creation fails, then we should clear the + fetched exception references and propagate the new exception */ + Py_XDECREF(ptype); + Py_XDECREF(pvalue); + Py_XDECREF(ptraceback); + goto bad; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + __pyx_insert_code_object(c_line ? -c_line : py_line, py_code); + } + py_frame = PyFrame_New( + tstate, /*PyThreadState *tstate,*/ + py_code, /*PyCodeObject *code,*/ + __pyx_d, /*PyObject *globals,*/ + 0 /*PyObject *locals*/ + ); + if (!py_frame) goto bad; + __Pyx_PyFrame_SetLineNumber(py_frame, py_line); + PyTraceBack_Here(py_frame); +bad: + Py_XDECREF(py_code); + Py_XDECREF(py_frame); +} +#endif + +#if PY_MAJOR_VERSION < 3 +static int __Pyx_GetBuffer(PyObject *obj, Py_buffer *view, int flags) { + __Pyx_TypeName obj_type_name; + if (PyObject_CheckBuffer(obj)) return PyObject_GetBuffer(obj, view, flags); + if (__Pyx_TypeCheck(obj, __pyx_array_type)) return __pyx_array_getbuffer(obj, view, flags); + if (__Pyx_TypeCheck(obj, __pyx_memoryview_type)) return __pyx_memoryview_getbuffer(obj, view, flags); + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "'" __Pyx_FMT_TYPENAME "' does not have the buffer interface", + obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return -1; +} +static void __Pyx_ReleaseBuffer(Py_buffer *view) { + PyObject *obj = view->obj; + if (!obj) return; + if (PyObject_CheckBuffer(obj)) { + PyBuffer_Release(view); + return; + } + if ((0)) {} + view->obj = NULL; + Py_DECREF(obj); +} +#endif + + +/* MemviewSliceIsContig */ +static int +__pyx_memviewslice_is_contig(const __Pyx_memviewslice mvs, char order, int ndim) +{ + int i, index, step, start; + Py_ssize_t itemsize = mvs.memview->view.itemsize; + if (order == 'F') { + step = 1; + start = 0; + } else { + step = -1; + start = ndim - 1; + } + for (i = 0; i < ndim; i++) { + index = start + step * i; + if (mvs.suboffsets[index] >= 0 || mvs.strides[index] != itemsize) + return 0; + itemsize *= mvs.shape[index]; + } + return 1; +} + +/* OverlappingSlices */ +static void +__pyx_get_array_memory_extents(__Pyx_memviewslice *slice, + void **out_start, void **out_end, + int ndim, size_t itemsize) +{ + char *start, *end; + int i; + start = end = slice->data; + for (i = 0; i < ndim; i++) { + Py_ssize_t stride = slice->strides[i]; + Py_ssize_t extent = slice->shape[i]; + if (extent == 0) { + *out_start = *out_end = start; + return; + } else { + if (stride > 0) + end += stride * (extent - 1); + else + start += stride * (extent - 1); + } + } + *out_start = start; + *out_end = end + itemsize; +} +static int +__pyx_slices_overlap(__Pyx_memviewslice *slice1, + __Pyx_memviewslice *slice2, + int ndim, size_t itemsize) +{ + void *start1, *end1, *start2, *end2; + __pyx_get_array_memory_extents(slice1, &start1, &end1, ndim, itemsize); + __pyx_get_array_memory_extents(slice2, &start2, &end2, ndim, itemsize); + return (start1 < end2) && (start2 < end1); +} + +/* IsLittleEndian */ +static CYTHON_INLINE int __Pyx_Is_Little_Endian(void) +{ + union { + uint32_t u32; + uint8_t u8[4]; + } S; + S.u32 = 0x01020304; + return S.u8[0] == 4; +} + +/* BufferFormatCheck */ +static void __Pyx_BufFmt_Init(__Pyx_BufFmt_Context* ctx, + __Pyx_BufFmt_StackElem* stack, + __Pyx_TypeInfo* type) { + stack[0].field = &ctx->root; + stack[0].parent_offset = 0; + ctx->root.type = type; + ctx->root.name = "buffer dtype"; + ctx->root.offset = 0; + ctx->head = stack; + ctx->head->field = &ctx->root; + ctx->fmt_offset = 0; + ctx->head->parent_offset = 0; + ctx->new_packmode = '@'; + ctx->enc_packmode = '@'; + ctx->new_count = 1; + ctx->enc_count = 0; + ctx->enc_type = 0; + ctx->is_complex = 0; + ctx->is_valid_array = 0; + ctx->struct_alignment = 0; + while (type->typegroup == 'S') { + ++ctx->head; + ctx->head->field = type->fields; + ctx->head->parent_offset = 0; + type = type->fields->type; + } +} +static int __Pyx_BufFmt_ParseNumber(const char** ts) { + int count; + const char* t = *ts; + if (*t < '0' || *t > '9') { + return -1; + } else { + count = *t++ - '0'; + while (*t >= '0' && *t <= '9') { + count *= 10; + count += *t++ - '0'; + } + } + *ts = t; + return count; +} +static int __Pyx_BufFmt_ExpectNumber(const char **ts) { + int number = __Pyx_BufFmt_ParseNumber(ts); + if (number == -1) + PyErr_Format(PyExc_ValueError,\ + "Does not understand character buffer dtype format string ('%c')", **ts); + return number; +} +static void __Pyx_BufFmt_RaiseUnexpectedChar(char ch) { + PyErr_Format(PyExc_ValueError, + "Unexpected format string character: '%c'", ch); +} +static const char* __Pyx_BufFmt_DescribeTypeChar(char ch, int is_complex) { + switch (ch) { + case '?': return "'bool'"; + case 'c': return "'char'"; + case 'b': return "'signed char'"; + case 'B': return "'unsigned char'"; + case 'h': return "'short'"; + case 'H': return "'unsigned short'"; + case 'i': return "'int'"; + case 'I': return "'unsigned int'"; + case 'l': return "'long'"; + case 'L': return "'unsigned long'"; + case 'q': return "'long long'"; + case 'Q': return "'unsigned long long'"; + case 'f': return (is_complex ? "'complex float'" : "'float'"); + case 'd': return (is_complex ? "'complex double'" : "'double'"); + case 'g': return (is_complex ? "'complex long double'" : "'long double'"); + case 'T': return "a struct"; + case 'O': return "Python object"; + case 'P': return "a pointer"; + case 's': case 'p': return "a string"; + case 0: return "end"; + default: return "unparsable format string"; + } +} +static size_t __Pyx_BufFmt_TypeCharToStandardSize(char ch, int is_complex) { + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return 2; + case 'i': case 'I': case 'l': case 'L': return 4; + case 'q': case 'Q': return 8; + case 'f': return (is_complex ? 8 : 4); + case 'd': return (is_complex ? 16 : 8); + case 'g': { + PyErr_SetString(PyExc_ValueError, "Python does not define a standard format string size for long double ('g').."); + return 0; + } + case 'O': case 'P': return sizeof(void*); + default: + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } +} +static size_t __Pyx_BufFmt_TypeCharToNativeSize(char ch, int is_complex) { + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return sizeof(short); + case 'i': case 'I': return sizeof(int); + case 'l': case 'L': return sizeof(long); + #ifdef HAVE_LONG_LONG + case 'q': case 'Q': return sizeof(PY_LONG_LONG); + #endif + case 'f': return sizeof(float) * (is_complex ? 2 : 1); + case 'd': return sizeof(double) * (is_complex ? 2 : 1); + case 'g': return sizeof(long double) * (is_complex ? 2 : 1); + case 'O': case 'P': return sizeof(void*); + default: { + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } + } +} +typedef struct { char c; short x; } __Pyx_st_short; +typedef struct { char c; int x; } __Pyx_st_int; +typedef struct { char c; long x; } __Pyx_st_long; +typedef struct { char c; float x; } __Pyx_st_float; +typedef struct { char c; double x; } __Pyx_st_double; +typedef struct { char c; long double x; } __Pyx_st_longdouble; +typedef struct { char c; void *x; } __Pyx_st_void_p; +#ifdef HAVE_LONG_LONG +typedef struct { char c; PY_LONG_LONG x; } __Pyx_st_longlong; +#endif +static size_t __Pyx_BufFmt_TypeCharToAlignment(char ch, int is_complex) { + CYTHON_UNUSED_VAR(is_complex); + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return sizeof(__Pyx_st_short) - sizeof(short); + case 'i': case 'I': return sizeof(__Pyx_st_int) - sizeof(int); + case 'l': case 'L': return sizeof(__Pyx_st_long) - sizeof(long); +#ifdef HAVE_LONG_LONG + case 'q': case 'Q': return sizeof(__Pyx_st_longlong) - sizeof(PY_LONG_LONG); +#endif + case 'f': return sizeof(__Pyx_st_float) - sizeof(float); + case 'd': return sizeof(__Pyx_st_double) - sizeof(double); + case 'g': return sizeof(__Pyx_st_longdouble) - sizeof(long double); + case 'P': case 'O': return sizeof(__Pyx_st_void_p) - sizeof(void*); + default: + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } +} +/* These are for computing the padding at the end of the struct to align + on the first member of the struct. This will probably the same as above, + but we don't have any guarantees. + */ +typedef struct { short x; char c; } __Pyx_pad_short; +typedef struct { int x; char c; } __Pyx_pad_int; +typedef struct { long x; char c; } __Pyx_pad_long; +typedef struct { float x; char c; } __Pyx_pad_float; +typedef struct { double x; char c; } __Pyx_pad_double; +typedef struct { long double x; char c; } __Pyx_pad_longdouble; +typedef struct { void *x; char c; } __Pyx_pad_void_p; +#ifdef HAVE_LONG_LONG +typedef struct { PY_LONG_LONG x; char c; } __Pyx_pad_longlong; +#endif +static size_t __Pyx_BufFmt_TypeCharToPadding(char ch, int is_complex) { + CYTHON_UNUSED_VAR(is_complex); + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return sizeof(__Pyx_pad_short) - sizeof(short); + case 'i': case 'I': return sizeof(__Pyx_pad_int) - sizeof(int); + case 'l': case 'L': return sizeof(__Pyx_pad_long) - sizeof(long); +#ifdef HAVE_LONG_LONG + case 'q': case 'Q': return sizeof(__Pyx_pad_longlong) - sizeof(PY_LONG_LONG); +#endif + case 'f': return sizeof(__Pyx_pad_float) - sizeof(float); + case 'd': return sizeof(__Pyx_pad_double) - sizeof(double); + case 'g': return sizeof(__Pyx_pad_longdouble) - sizeof(long double); + case 'P': case 'O': return sizeof(__Pyx_pad_void_p) - sizeof(void*); + default: + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } +} +static char __Pyx_BufFmt_TypeCharToGroup(char ch, int is_complex) { + switch (ch) { + case 'c': + return 'H'; + case 'b': case 'h': case 'i': + case 'l': case 'q': case 's': case 'p': + return 'I'; + case '?': case 'B': case 'H': case 'I': case 'L': case 'Q': + return 'U'; + case 'f': case 'd': case 'g': + return (is_complex ? 'C' : 'R'); + case 'O': + return 'O'; + case 'P': + return 'P'; + default: { + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } + } +} +static void __Pyx_BufFmt_RaiseExpected(__Pyx_BufFmt_Context* ctx) { + if (ctx->head == NULL || ctx->head->field == &ctx->root) { + const char* expected; + const char* quote; + if (ctx->head == NULL) { + expected = "end"; + quote = ""; + } else { + expected = ctx->head->field->type->name; + quote = "'"; + } + PyErr_Format(PyExc_ValueError, + "Buffer dtype mismatch, expected %s%s%s but got %s", + quote, expected, quote, + __Pyx_BufFmt_DescribeTypeChar(ctx->enc_type, ctx->is_complex)); + } else { + __Pyx_StructField* field = ctx->head->field; + __Pyx_StructField* parent = (ctx->head - 1)->field; + PyErr_Format(PyExc_ValueError, + "Buffer dtype mismatch, expected '%s' but got %s in '%s.%s'", + field->type->name, __Pyx_BufFmt_DescribeTypeChar(ctx->enc_type, ctx->is_complex), + parent->type->name, field->name); + } +} +static int __Pyx_BufFmt_ProcessTypeChunk(__Pyx_BufFmt_Context* ctx) { + char group; + size_t size, offset, arraysize = 1; + if (ctx->enc_type == 0) return 0; + if (ctx->head->field->type->arraysize[0]) { + int i, ndim = 0; + if (ctx->enc_type == 's' || ctx->enc_type == 'p') { + ctx->is_valid_array = ctx->head->field->type->ndim == 1; + ndim = 1; + if (ctx->enc_count != ctx->head->field->type->arraysize[0]) { + PyErr_Format(PyExc_ValueError, + "Expected a dimension of size %zu, got %zu", + ctx->head->field->type->arraysize[0], ctx->enc_count); + return -1; + } + } + if (!ctx->is_valid_array) { + PyErr_Format(PyExc_ValueError, "Expected %d dimensions, got %d", + ctx->head->field->type->ndim, ndim); + return -1; + } + for (i = 0; i < ctx->head->field->type->ndim; i++) { + arraysize *= ctx->head->field->type->arraysize[i]; + } + ctx->is_valid_array = 0; + ctx->enc_count = 1; + } + group = __Pyx_BufFmt_TypeCharToGroup(ctx->enc_type, ctx->is_complex); + do { + __Pyx_StructField* field = ctx->head->field; + __Pyx_TypeInfo* type = field->type; + if (ctx->enc_packmode == '@' || ctx->enc_packmode == '^') { + size = __Pyx_BufFmt_TypeCharToNativeSize(ctx->enc_type, ctx->is_complex); + } else { + size = __Pyx_BufFmt_TypeCharToStandardSize(ctx->enc_type, ctx->is_complex); + } + if (ctx->enc_packmode == '@') { + size_t align_at = __Pyx_BufFmt_TypeCharToAlignment(ctx->enc_type, ctx->is_complex); + size_t align_mod_offset; + if (align_at == 0) return -1; + align_mod_offset = ctx->fmt_offset % align_at; + if (align_mod_offset > 0) ctx->fmt_offset += align_at - align_mod_offset; + if (ctx->struct_alignment == 0) + ctx->struct_alignment = __Pyx_BufFmt_TypeCharToPadding(ctx->enc_type, + ctx->is_complex); + } + if (type->size != size || type->typegroup != group) { + if (type->typegroup == 'C' && type->fields != NULL) { + size_t parent_offset = ctx->head->parent_offset + field->offset; + ++ctx->head; + ctx->head->field = type->fields; + ctx->head->parent_offset = parent_offset; + continue; + } + if ((type->typegroup == 'H' || group == 'H') && type->size == size) { + } else { + __Pyx_BufFmt_RaiseExpected(ctx); + return -1; + } + } + offset = ctx->head->parent_offset + field->offset; + if (ctx->fmt_offset != offset) { + PyErr_Format(PyExc_ValueError, + "Buffer dtype mismatch; next field is at offset %" CYTHON_FORMAT_SSIZE_T "d but %" CYTHON_FORMAT_SSIZE_T "d expected", + (Py_ssize_t)ctx->fmt_offset, (Py_ssize_t)offset); + return -1; + } + ctx->fmt_offset += size; + if (arraysize) + ctx->fmt_offset += (arraysize - 1) * size; + --ctx->enc_count; + while (1) { + if (field == &ctx->root) { + ctx->head = NULL; + if (ctx->enc_count != 0) { + __Pyx_BufFmt_RaiseExpected(ctx); + return -1; + } + break; + } + ctx->head->field = ++field; + if (field->type == NULL) { + --ctx->head; + field = ctx->head->field; + continue; + } else if (field->type->typegroup == 'S') { + size_t parent_offset = ctx->head->parent_offset + field->offset; + if (field->type->fields->type == NULL) continue; + field = field->type->fields; + ++ctx->head; + ctx->head->field = field; + ctx->head->parent_offset = parent_offset; + break; + } else { + break; + } + } + } while (ctx->enc_count); + ctx->enc_type = 0; + ctx->is_complex = 0; + return 0; +} +static int +__pyx_buffmt_parse_array(__Pyx_BufFmt_Context* ctx, const char** tsp) +{ + const char *ts = *tsp; + int i = 0, number, ndim; + ++ts; + if (ctx->new_count != 1) { + PyErr_SetString(PyExc_ValueError, + "Cannot handle repeated arrays in format string"); + return -1; + } + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return -1; + ndim = ctx->head->field->type->ndim; + while (*ts && *ts != ')') { + switch (*ts) { + case ' ': case '\f': case '\r': case '\n': case '\t': case '\v': continue; + default: break; + } + number = __Pyx_BufFmt_ExpectNumber(&ts); + if (number == -1) return -1; + if (i < ndim && (size_t) number != ctx->head->field->type->arraysize[i]) { + PyErr_Format(PyExc_ValueError, + "Expected a dimension of size %zu, got %d", + ctx->head->field->type->arraysize[i], number); + return -1; + } + if (*ts != ',' && *ts != ')') { + PyErr_Format(PyExc_ValueError, + "Expected a comma in format string, got '%c'", *ts); + return -1; + } + if (*ts == ',') ts++; + i++; + } + if (i != ndim) { + PyErr_Format(PyExc_ValueError, "Expected %d dimension(s), got %d", + ctx->head->field->type->ndim, i); + return -1; + } + if (!*ts) { + PyErr_SetString(PyExc_ValueError, + "Unexpected end of format string, expected ')'"); + return -1; + } + ctx->is_valid_array = 1; + ctx->new_count = 1; + *tsp = ++ts; + return 0; +} +static const char* __Pyx_BufFmt_CheckString(__Pyx_BufFmt_Context* ctx, const char* ts) { + int got_Z = 0; + while (1) { + switch(*ts) { + case 0: + if (ctx->enc_type != 0 && ctx->head == NULL) { + __Pyx_BufFmt_RaiseExpected(ctx); + return NULL; + } + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + if (ctx->head != NULL) { + __Pyx_BufFmt_RaiseExpected(ctx); + return NULL; + } + return ts; + case ' ': + case '\r': + case '\n': + ++ts; + break; + case '<': + if (!__Pyx_Is_Little_Endian()) { + PyErr_SetString(PyExc_ValueError, "Little-endian buffer not supported on big-endian compiler"); + return NULL; + } + ctx->new_packmode = '='; + ++ts; + break; + case '>': + case '!': + if (__Pyx_Is_Little_Endian()) { + PyErr_SetString(PyExc_ValueError, "Big-endian buffer not supported on little-endian compiler"); + return NULL; + } + ctx->new_packmode = '='; + ++ts; + break; + case '=': + case '@': + case '^': + ctx->new_packmode = *ts++; + break; + case 'T': + { + const char* ts_after_sub; + size_t i, struct_count = ctx->new_count; + size_t struct_alignment = ctx->struct_alignment; + ctx->new_count = 1; + ++ts; + if (*ts != '{') { + PyErr_SetString(PyExc_ValueError, "Buffer acquisition: Expected '{' after 'T'"); + return NULL; + } + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->enc_type = 0; + ctx->enc_count = 0; + ctx->struct_alignment = 0; + ++ts; + ts_after_sub = ts; + for (i = 0; i != struct_count; ++i) { + ts_after_sub = __Pyx_BufFmt_CheckString(ctx, ts); + if (!ts_after_sub) return NULL; + } + ts = ts_after_sub; + if (struct_alignment) ctx->struct_alignment = struct_alignment; + } + break; + case '}': + { + size_t alignment = ctx->struct_alignment; + ++ts; + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->enc_type = 0; + if (alignment && ctx->fmt_offset % alignment) { + ctx->fmt_offset += alignment - (ctx->fmt_offset % alignment); + } + } + return ts; + case 'x': + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->fmt_offset += ctx->new_count; + ctx->new_count = 1; + ctx->enc_count = 0; + ctx->enc_type = 0; + ctx->enc_packmode = ctx->new_packmode; + ++ts; + break; + case 'Z': + got_Z = 1; + ++ts; + if (*ts != 'f' && *ts != 'd' && *ts != 'g') { + __Pyx_BufFmt_RaiseUnexpectedChar('Z'); + return NULL; + } + CYTHON_FALLTHROUGH; + case '?': case 'c': case 'b': case 'B': case 'h': case 'H': case 'i': case 'I': + case 'l': case 'L': case 'q': case 'Q': + case 'f': case 'd': case 'g': + case 'O': case 'p': + if ((ctx->enc_type == *ts) && (got_Z == ctx->is_complex) && + (ctx->enc_packmode == ctx->new_packmode) && (!ctx->is_valid_array)) { + ctx->enc_count += ctx->new_count; + ctx->new_count = 1; + got_Z = 0; + ++ts; + break; + } + CYTHON_FALLTHROUGH; + case 's': + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->enc_count = ctx->new_count; + ctx->enc_packmode = ctx->new_packmode; + ctx->enc_type = *ts; + ctx->is_complex = got_Z; + ++ts; + ctx->new_count = 1; + got_Z = 0; + break; + case ':': + ++ts; + while(*ts != ':') ++ts; + ++ts; + break; + case '(': + if (__pyx_buffmt_parse_array(ctx, &ts) < 0) return NULL; + break; + default: + { + int number = __Pyx_BufFmt_ExpectNumber(&ts); + if (number == -1) return NULL; + ctx->new_count = (size_t)number; + } + } + } +} + +/* TypeInfoCompare */ + static int +__pyx_typeinfo_cmp(__Pyx_TypeInfo *a, __Pyx_TypeInfo *b) +{ + int i; + if (!a || !b) + return 0; + if (a == b) + return 1; + if (a->size != b->size || a->typegroup != b->typegroup || + a->is_unsigned != b->is_unsigned || a->ndim != b->ndim) { + if (a->typegroup == 'H' || b->typegroup == 'H') { + return a->size == b->size; + } else { + return 0; + } + } + if (a->ndim) { + for (i = 0; i < a->ndim; i++) + if (a->arraysize[i] != b->arraysize[i]) + return 0; + } + if (a->typegroup == 'S') { + if (a->flags != b->flags) + return 0; + if (a->fields || b->fields) { + if (!(a->fields && b->fields)) + return 0; + for (i = 0; a->fields[i].type && b->fields[i].type; i++) { + __Pyx_StructField *field_a = a->fields + i; + __Pyx_StructField *field_b = b->fields + i; + if (field_a->offset != field_b->offset || + !__pyx_typeinfo_cmp(field_a->type, field_b->type)) + return 0; + } + return !a->fields[i].type && !b->fields[i].type; + } + } + return 1; +} + +/* MemviewSliceValidateAndInit */ + static int +__pyx_check_strides(Py_buffer *buf, int dim, int ndim, int spec) +{ + if (buf->shape[dim] <= 1) + return 1; + if (buf->strides) { + if (spec & __Pyx_MEMVIEW_CONTIG) { + if (spec & (__Pyx_MEMVIEW_PTR|__Pyx_MEMVIEW_FULL)) { + if (unlikely(buf->strides[dim] != sizeof(void *))) { + PyErr_Format(PyExc_ValueError, + "Buffer is not indirectly contiguous " + "in dimension %d.", dim); + goto fail; + } + } else if (unlikely(buf->strides[dim] != buf->itemsize)) { + PyErr_SetString(PyExc_ValueError, + "Buffer and memoryview are not contiguous " + "in the same dimension."); + goto fail; + } + } + if (spec & __Pyx_MEMVIEW_FOLLOW) { + Py_ssize_t stride = buf->strides[dim]; + if (stride < 0) + stride = -stride; + if (unlikely(stride < buf->itemsize)) { + PyErr_SetString(PyExc_ValueError, + "Buffer and memoryview are not contiguous " + "in the same dimension."); + goto fail; + } + } + } else { + if (unlikely(spec & __Pyx_MEMVIEW_CONTIG && dim != ndim - 1)) { + PyErr_Format(PyExc_ValueError, + "C-contiguous buffer is not contiguous in " + "dimension %d", dim); + goto fail; + } else if (unlikely(spec & (__Pyx_MEMVIEW_PTR))) { + PyErr_Format(PyExc_ValueError, + "C-contiguous buffer is not indirect in " + "dimension %d", dim); + goto fail; + } else if (unlikely(buf->suboffsets)) { + PyErr_SetString(PyExc_ValueError, + "Buffer exposes suboffsets but no strides"); + goto fail; + } + } + return 1; +fail: + return 0; +} +static int +__pyx_check_suboffsets(Py_buffer *buf, int dim, int ndim, int spec) +{ + CYTHON_UNUSED_VAR(ndim); + if (spec & __Pyx_MEMVIEW_DIRECT) { + if (unlikely(buf->suboffsets && buf->suboffsets[dim] >= 0)) { + PyErr_Format(PyExc_ValueError, + "Buffer not compatible with direct access " + "in dimension %d.", dim); + goto fail; + } + } + if (spec & __Pyx_MEMVIEW_PTR) { + if (unlikely(!buf->suboffsets || (buf->suboffsets[dim] < 0))) { + PyErr_Format(PyExc_ValueError, + "Buffer is not indirectly accessible " + "in dimension %d.", dim); + goto fail; + } + } + return 1; +fail: + return 0; +} +static int +__pyx_verify_contig(Py_buffer *buf, int ndim, int c_or_f_flag) +{ + int i; + if (c_or_f_flag & __Pyx_IS_F_CONTIG) { + Py_ssize_t stride = 1; + for (i = 0; i < ndim; i++) { + if (unlikely(stride * buf->itemsize != buf->strides[i] && buf->shape[i] > 1)) { + PyErr_SetString(PyExc_ValueError, + "Buffer not fortran contiguous."); + goto fail; + } + stride = stride * buf->shape[i]; + } + } else if (c_or_f_flag & __Pyx_IS_C_CONTIG) { + Py_ssize_t stride = 1; + for (i = ndim - 1; i >- 1; i--) { + if (unlikely(stride * buf->itemsize != buf->strides[i] && buf->shape[i] > 1)) { + PyErr_SetString(PyExc_ValueError, + "Buffer not C contiguous."); + goto fail; + } + stride = stride * buf->shape[i]; + } + } + return 1; +fail: + return 0; +} +static int __Pyx_ValidateAndInit_memviewslice( + int *axes_specs, + int c_or_f_flag, + int buf_flags, + int ndim, + __Pyx_TypeInfo *dtype, + __Pyx_BufFmt_StackElem stack[], + __Pyx_memviewslice *memviewslice, + PyObject *original_obj) +{ + struct __pyx_memoryview_obj *memview, *new_memview; + __Pyx_RefNannyDeclarations + Py_buffer *buf; + int i, spec = 0, retval = -1; + __Pyx_BufFmt_Context ctx; + int from_memoryview = __pyx_memoryview_check(original_obj); + __Pyx_RefNannySetupContext("ValidateAndInit_memviewslice", 0); + if (from_memoryview && __pyx_typeinfo_cmp(dtype, ((struct __pyx_memoryview_obj *) + original_obj)->typeinfo)) { + memview = (struct __pyx_memoryview_obj *) original_obj; + new_memview = NULL; + } else { + memview = (struct __pyx_memoryview_obj *) __pyx_memoryview_new( + original_obj, buf_flags, 0, dtype); + new_memview = memview; + if (unlikely(!memview)) + goto fail; + } + buf = &memview->view; + if (unlikely(buf->ndim != ndim)) { + PyErr_Format(PyExc_ValueError, + "Buffer has wrong number of dimensions (expected %d, got %d)", + ndim, buf->ndim); + goto fail; + } + if (new_memview) { + __Pyx_BufFmt_Init(&ctx, stack, dtype); + if (unlikely(!__Pyx_BufFmt_CheckString(&ctx, buf->format))) goto fail; + } + if (unlikely((unsigned) buf->itemsize != dtype->size)) { + PyErr_Format(PyExc_ValueError, + "Item size of buffer (%" CYTHON_FORMAT_SSIZE_T "u byte%s) " + "does not match size of '%s' (%" CYTHON_FORMAT_SSIZE_T "u byte%s)", + buf->itemsize, + (buf->itemsize > 1) ? "s" : "", + dtype->name, + dtype->size, + (dtype->size > 1) ? "s" : ""); + goto fail; + } + if (buf->len > 0) { + for (i = 0; i < ndim; i++) { + spec = axes_specs[i]; + if (unlikely(!__pyx_check_strides(buf, i, ndim, spec))) + goto fail; + if (unlikely(!__pyx_check_suboffsets(buf, i, ndim, spec))) + goto fail; + } + if (unlikely(buf->strides && !__pyx_verify_contig(buf, ndim, c_or_f_flag))) + goto fail; + } + if (unlikely(__Pyx_init_memviewslice(memview, ndim, memviewslice, + new_memview != NULL) == -1)) { + goto fail; + } + retval = 0; + goto no_fail; +fail: + Py_XDECREF(new_memview); + retval = -1; +no_fail: + __Pyx_RefNannyFinishContext(); + return retval; +} + +/* ObjectToMemviewSlice */ + static CYTHON_INLINE __Pyx_memviewslice __Pyx_PyObject_to_MemoryviewSlice_ds_float(PyObject *obj, int writable_flag) { + __Pyx_memviewslice result = { 0, 0, { 0 }, { 0 }, { 0 } }; + __Pyx_BufFmt_StackElem stack[1]; + int axes_specs[] = { (__Pyx_MEMVIEW_DIRECT | __Pyx_MEMVIEW_STRIDED) }; + int retcode; + if (obj == Py_None) { + result.memview = (struct __pyx_memoryview_obj *) Py_None; + return result; + } + retcode = __Pyx_ValidateAndInit_memviewslice(axes_specs, 0, + PyBUF_RECORDS_RO | writable_flag, 1, + &__Pyx_TypeInfo_float, stack, + &result, obj); + if (unlikely(retcode == -1)) + goto __pyx_fail; + return result; +__pyx_fail: + result.memview = NULL; + result.data = NULL; + return result; +} + +/* CIntFromPyVerify */ + #define __PYX_VERIFY_RETURN_INT(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 0) +#define __PYX_VERIFY_RETURN_INT_EXC(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 1) +#define __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, exc)\ + {\ + func_type value = func_value;\ + if (sizeof(target_type) < sizeof(func_type)) {\ + if (unlikely(value != (func_type) (target_type) value)) {\ + func_type zero = 0;\ + if (exc && unlikely(value == (func_type)-1 && PyErr_Occurred()))\ + return (target_type) -1;\ + if (is_unsigned && unlikely(value < zero))\ + goto raise_neg_overflow;\ + else\ + goto raise_overflow;\ + }\ + }\ + return (target_type) value;\ + } + +/* MemviewDtypeToObject */ + static CYTHON_INLINE PyObject *__pyx_memview_get_float(const char *itemp) { + return (PyObject *) PyFloat_FromDouble(*(float *) itemp); +} +static CYTHON_INLINE int __pyx_memview_set_float(const char *itemp, PyObject *obj) { + float value = __pyx_PyFloat_AsFloat(obj); + if (unlikely((value == (float)-1) && PyErr_Occurred())) + return 0; + *(float *) itemp = value; + return 1; +} + +/* MemviewSliceCopyTemplate */ + static __Pyx_memviewslice +__pyx_memoryview_copy_new_contig(const __Pyx_memviewslice *from_mvs, + const char *mode, int ndim, + size_t sizeof_dtype, int contig_flag, + int dtype_is_object) +{ + __Pyx_RefNannyDeclarations + int i; + __Pyx_memviewslice new_mvs = { 0, 0, { 0 }, { 0 }, { 0 } }; + struct __pyx_memoryview_obj *from_memview = from_mvs->memview; + Py_buffer *buf = &from_memview->view; + PyObject *shape_tuple = NULL; + PyObject *temp_int = NULL; + struct __pyx_array_obj *array_obj = NULL; + struct __pyx_memoryview_obj *memview_obj = NULL; + __Pyx_RefNannySetupContext("__pyx_memoryview_copy_new_contig", 0); + for (i = 0; i < ndim; i++) { + if (unlikely(from_mvs->suboffsets[i] >= 0)) { + PyErr_Format(PyExc_ValueError, "Cannot copy memoryview slice with " + "indirect dimensions (axis %d)", i); + goto fail; + } + } + shape_tuple = PyTuple_New(ndim); + if (unlikely(!shape_tuple)) { + goto fail; + } + __Pyx_GOTREF(shape_tuple); + for(i = 0; i < ndim; i++) { + temp_int = PyInt_FromSsize_t(from_mvs->shape[i]); + if(unlikely(!temp_int)) { + goto fail; + } else { + PyTuple_SET_ITEM(shape_tuple, i, temp_int); + temp_int = NULL; + } + } + array_obj = __pyx_array_new(shape_tuple, sizeof_dtype, buf->format, (char *) mode, NULL); + if (unlikely(!array_obj)) { + goto fail; + } + __Pyx_GOTREF(array_obj); + memview_obj = (struct __pyx_memoryview_obj *) __pyx_memoryview_new( + (PyObject *) array_obj, contig_flag, + dtype_is_object, + from_mvs->memview->typeinfo); + if (unlikely(!memview_obj)) + goto fail; + if (unlikely(__Pyx_init_memviewslice(memview_obj, ndim, &new_mvs, 1) < 0)) + goto fail; + if (unlikely(__pyx_memoryview_copy_contents(*from_mvs, new_mvs, ndim, ndim, + dtype_is_object) < 0)) + goto fail; + goto no_fail; +fail: + __Pyx_XDECREF(new_mvs.memview); + new_mvs.memview = NULL; + new_mvs.data = NULL; +no_fail: + __Pyx_XDECREF(shape_tuple); + __Pyx_XDECREF(temp_int); + __Pyx_XDECREF(array_obj); + __Pyx_RefNannyFinishContext(); + return new_mvs; +} + +/* MemviewSliceInit */ + static int +__Pyx_init_memviewslice(struct __pyx_memoryview_obj *memview, + int ndim, + __Pyx_memviewslice *memviewslice, + int memview_is_new_reference) +{ + __Pyx_RefNannyDeclarations + int i, retval=-1; + Py_buffer *buf = &memview->view; + __Pyx_RefNannySetupContext("init_memviewslice", 0); + if (unlikely(memviewslice->memview || memviewslice->data)) { + PyErr_SetString(PyExc_ValueError, + "memviewslice is already initialized!"); + goto fail; + } + if (buf->strides) { + for (i = 0; i < ndim; i++) { + memviewslice->strides[i] = buf->strides[i]; + } + } else { + Py_ssize_t stride = buf->itemsize; + for (i = ndim - 1; i >= 0; i--) { + memviewslice->strides[i] = stride; + stride *= buf->shape[i]; + } + } + for (i = 0; i < ndim; i++) { + memviewslice->shape[i] = buf->shape[i]; + if (buf->suboffsets) { + memviewslice->suboffsets[i] = buf->suboffsets[i]; + } else { + memviewslice->suboffsets[i] = -1; + } + } + memviewslice->memview = memview; + memviewslice->data = (char *)buf->buf; + if (__pyx_add_acquisition_count(memview) == 0 && !memview_is_new_reference) { + Py_INCREF(memview); + } + retval = 0; + goto no_fail; +fail: + memviewslice->memview = 0; + memviewslice->data = 0; + retval = -1; +no_fail: + __Pyx_RefNannyFinishContext(); + return retval; +} +#ifndef Py_NO_RETURN +#define Py_NO_RETURN +#endif +static void __pyx_fatalerror(const char *fmt, ...) Py_NO_RETURN { + va_list vargs; + char msg[200]; +#if PY_VERSION_HEX >= 0x030A0000 || defined(HAVE_STDARG_PROTOTYPES) + va_start(vargs, fmt); +#else + va_start(vargs); +#endif + vsnprintf(msg, 200, fmt, vargs); + va_end(vargs); + Py_FatalError(msg); +} +static CYTHON_INLINE int +__pyx_add_acquisition_count_locked(__pyx_atomic_int_type *acquisition_count, + PyThread_type_lock lock) +{ + int result; + PyThread_acquire_lock(lock, 1); + result = (*acquisition_count)++; + PyThread_release_lock(lock); + return result; +} +static CYTHON_INLINE int +__pyx_sub_acquisition_count_locked(__pyx_atomic_int_type *acquisition_count, + PyThread_type_lock lock) +{ + int result; + PyThread_acquire_lock(lock, 1); + result = (*acquisition_count)--; + PyThread_release_lock(lock); + return result; +} +static CYTHON_INLINE void +__Pyx_INC_MEMVIEW(__Pyx_memviewslice *memslice, int have_gil, int lineno) +{ + __pyx_nonatomic_int_type old_acquisition_count; + struct __pyx_memoryview_obj *memview = memslice->memview; + if (unlikely(!memview || (PyObject *) memview == Py_None)) { + return; + } + old_acquisition_count = __pyx_add_acquisition_count(memview); + if (unlikely(old_acquisition_count <= 0)) { + if (likely(old_acquisition_count == 0)) { + if (have_gil) { + Py_INCREF((PyObject *) memview); + } else { + PyGILState_STATE _gilstate = PyGILState_Ensure(); + Py_INCREF((PyObject *) memview); + PyGILState_Release(_gilstate); + } + } else { + __pyx_fatalerror("Acquisition count is %d (line %d)", + old_acquisition_count+1, lineno); + } + } +} +static CYTHON_INLINE void __Pyx_XCLEAR_MEMVIEW(__Pyx_memviewslice *memslice, + int have_gil, int lineno) { + __pyx_nonatomic_int_type old_acquisition_count; + struct __pyx_memoryview_obj *memview = memslice->memview; + if (unlikely(!memview || (PyObject *) memview == Py_None)) { + memslice->memview = NULL; + return; + } + old_acquisition_count = __pyx_sub_acquisition_count(memview); + memslice->data = NULL; + if (likely(old_acquisition_count > 1)) { + memslice->memview = NULL; + } else if (likely(old_acquisition_count == 1)) { + if (have_gil) { + Py_CLEAR(memslice->memview); + } else { + PyGILState_STATE _gilstate = PyGILState_Ensure(); + Py_CLEAR(memslice->memview); + PyGILState_Release(_gilstate); + } + } else { + __pyx_fatalerror("Acquisition count is %d (line %d)", + old_acquisition_count-1, lineno); + } +} + +/* CIntFromPy */ + static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(int) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(int, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (int) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 2 * PyLong_SHIFT)) { + return (int) (((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 3 * PyLong_SHIFT)) { + return (int) (((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 4 * PyLong_SHIFT)) { + return (int) (((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(int) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(int) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) ((((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) ((((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) ((((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(int) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + int val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (int) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (int) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (int) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (int) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(int) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(int) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((int) 1) << (sizeof(int) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (int) -1; + } + } else { + int val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (int) -1; + val = __Pyx_PyInt_As_int(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to int"); + return (int) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to int"); + return (int) -1; +} + +/* CIntFromPy */ + static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(long) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(long, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (long) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 2 * PyLong_SHIFT)) { + return (long) (((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 3 * PyLong_SHIFT)) { + return (long) (((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 4 * PyLong_SHIFT)) { + return (long) (((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(long) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(long) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) ((((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) ((((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) ((((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(long) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + long val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (long) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (long) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (long) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (long) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(long) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(long) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((long) 1) << (sizeof(long) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (long) -1; + } + } else { + long val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (long) -1; + val = __Pyx_PyInt_As_long(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to long"); + return (long) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to long"); + return (long) -1; +} + +/* CIntToPy */ + static CYTHON_INLINE PyObject* __Pyx_PyInt_From_int(int value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(int) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(int) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(int) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(int) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(int) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; +#if !CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030d0000 + return _PyLong_FromByteArray(bytes, sizeof(int), + little, !is_unsigned); +#else + PyObject *from_bytes, *result = NULL; + PyObject *py_bytes = NULL, *arg_tuple = NULL, *kwds = NULL, *order_str = NULL; + from_bytes = PyObject_GetAttrString((PyObject*)&PyLong_Type, "from_bytes"); + if (!from_bytes) return NULL; + py_bytes = PyBytes_FromStringAndSize((char*)bytes, sizeof(int)); + if (!py_bytes) goto limited_bad; + order_str = PyUnicode_FromString(little ? "little" : "big"); + if (!order_str) goto limited_bad; + arg_tuple = PyTuple_Pack(2, py_bytes, order_str); + if (!arg_tuple) goto limited_bad; + if (!is_unsigned) { + kwds = PyDict_New(); + if (!kwds) goto limited_bad; + if (PyDict_SetItemString(kwds, "signed", __Pyx_NewRef(Py_True))) goto limited_bad; + } + result = PyObject_Call(from_bytes, arg_tuple, kwds); + limited_bad: + Py_XDECREF(kwds); + Py_XDECREF(arg_tuple); + Py_XDECREF(order_str); + Py_XDECREF(py_bytes); + Py_XDECREF(from_bytes); + return result; +#endif + } +} + +/* CIntToPy */ + static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(long) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(long) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(long) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; +#if !CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030d0000 + return _PyLong_FromByteArray(bytes, sizeof(long), + little, !is_unsigned); +#else + PyObject *from_bytes, *result = NULL; + PyObject *py_bytes = NULL, *arg_tuple = NULL, *kwds = NULL, *order_str = NULL; + from_bytes = PyObject_GetAttrString((PyObject*)&PyLong_Type, "from_bytes"); + if (!from_bytes) return NULL; + py_bytes = PyBytes_FromStringAndSize((char*)bytes, sizeof(long)); + if (!py_bytes) goto limited_bad; + order_str = PyUnicode_FromString(little ? "little" : "big"); + if (!order_str) goto limited_bad; + arg_tuple = PyTuple_Pack(2, py_bytes, order_str); + if (!arg_tuple) goto limited_bad; + if (!is_unsigned) { + kwds = PyDict_New(); + if (!kwds) goto limited_bad; + if (PyDict_SetItemString(kwds, "signed", __Pyx_NewRef(Py_True))) goto limited_bad; + } + result = PyObject_Call(from_bytes, arg_tuple, kwds); + limited_bad: + Py_XDECREF(kwds); + Py_XDECREF(arg_tuple); + Py_XDECREF(order_str); + Py_XDECREF(py_bytes); + Py_XDECREF(from_bytes); + return result; +#endif + } +} + +/* CIntFromPy */ + static CYTHON_INLINE char __Pyx_PyInt_As_char(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const char neg_one = (char) -1, const_zero = (char) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(char) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(char, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (char) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(char, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(char) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) >= 2 * PyLong_SHIFT)) { + return (char) (((((char)digits[1]) << PyLong_SHIFT) | (char)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(char) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) >= 3 * PyLong_SHIFT)) { + return (char) (((((((char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(char) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) >= 4 * PyLong_SHIFT)) { + return (char) (((((((((char)digits[3]) << PyLong_SHIFT) | (char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (char) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(char) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(char, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(char) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(char, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(char, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(char) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 2 * PyLong_SHIFT)) { + return (char) (((char)-1)*(((((char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(char) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 2 * PyLong_SHIFT)) { + return (char) ((((((char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(char) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 3 * PyLong_SHIFT)) { + return (char) (((char)-1)*(((((((char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(char) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 3 * PyLong_SHIFT)) { + return (char) ((((((((char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(char) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 4 * PyLong_SHIFT)) { + return (char) (((char)-1)*(((((((((char)digits[3]) << PyLong_SHIFT) | (char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(char) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 4 * PyLong_SHIFT)) { + return (char) ((((((((((char)digits[3]) << PyLong_SHIFT) | (char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(char) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(char, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(char) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(char, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + char val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (char) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (char) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (char) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (char) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (char) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(char) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((char) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(char) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((char) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((char) 1) << (sizeof(char) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (char) -1; + } + } else { + char val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (char) -1; + val = __Pyx_PyInt_As_char(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to char"); + return (char) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to char"); + return (char) -1; +} + +/* FormatTypeName */ + #if CYTHON_COMPILING_IN_LIMITED_API +static __Pyx_TypeName +__Pyx_PyType_GetName(PyTypeObject* tp) +{ + PyObject *name = __Pyx_PyObject_GetAttrStr((PyObject *)tp, + __pyx_n_s_name_2); + if (unlikely(name == NULL) || unlikely(!PyUnicode_Check(name))) { + PyErr_Clear(); + Py_XDECREF(name); + name = __Pyx_NewRef(__pyx_n_s__24); + } + return name; +} +#endif + +/* CheckBinaryVersion */ + static unsigned long __Pyx_get_runtime_version(void) { +#if __PYX_LIMITED_VERSION_HEX >= 0x030B00A4 + return Py_Version & ~0xFFUL; +#else + const char* rt_version = Py_GetVersion(); + unsigned long version = 0; + unsigned long factor = 0x01000000UL; + unsigned int digit = 0; + int i = 0; + while (factor) { + while ('0' <= rt_version[i] && rt_version[i] <= '9') { + digit = digit * 10 + (unsigned int) (rt_version[i] - '0'); + ++i; + } + version += factor * digit; + if (rt_version[i] != '.') + break; + digit = 0; + factor >>= 8; + ++i; + } + return version; +#endif +} +static int __Pyx_check_binary_version(unsigned long ct_version, unsigned long rt_version, int allow_newer) { + const unsigned long MAJOR_MINOR = 0xFFFF0000UL; + if ((rt_version & MAJOR_MINOR) == (ct_version & MAJOR_MINOR)) + return 0; + if (likely(allow_newer && (rt_version & MAJOR_MINOR) > (ct_version & MAJOR_MINOR))) + return 1; + { + char message[200]; + PyOS_snprintf(message, sizeof(message), + "compile time Python version %d.%d " + "of module '%.100s' " + "%s " + "runtime version %d.%d", + (int) (ct_version >> 24), (int) ((ct_version >> 16) & 0xFF), + __Pyx_MODULE_NAME, + (allow_newer) ? "was newer than" : "does not match", + (int) (rt_version >> 24), (int) ((rt_version >> 16) & 0xFF) + ); + return PyErr_WarnEx(NULL, message, 1); + } +} + +/* InitStrings */ + #if PY_MAJOR_VERSION >= 3 +static int __Pyx_InitString(__Pyx_StringTabEntry t, PyObject **str) { + if (t.is_unicode | t.is_str) { + if (t.intern) { + *str = PyUnicode_InternFromString(t.s); + } else if (t.encoding) { + *str = PyUnicode_Decode(t.s, t.n - 1, t.encoding, NULL); + } else { + *str = PyUnicode_FromStringAndSize(t.s, t.n - 1); + } + } else { + *str = PyBytes_FromStringAndSize(t.s, t.n - 1); + } + if (!*str) + return -1; + if (PyObject_Hash(*str) == -1) + return -1; + return 0; +} +#endif +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t) { + while (t->p) { + #if PY_MAJOR_VERSION >= 3 + __Pyx_InitString(*t, t->p); + #else + if (t->is_unicode) { + *t->p = PyUnicode_DecodeUTF8(t->s, t->n - 1, NULL); + } else if (t->intern) { + *t->p = PyString_InternFromString(t->s); + } else { + *t->p = PyString_FromStringAndSize(t->s, t->n - 1); + } + if (!*t->p) + return -1; + if (PyObject_Hash(*t->p) == -1) + return -1; + #endif + ++t; + } + return 0; +} + +#include +static CYTHON_INLINE Py_ssize_t __Pyx_ssize_strlen(const char *s) { + size_t len = strlen(s); + if (unlikely(len > (size_t) PY_SSIZE_T_MAX)) { + PyErr_SetString(PyExc_OverflowError, "byte string is too long"); + return -1; + } + return (Py_ssize_t) len; +} +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char* c_str) { + Py_ssize_t len = __Pyx_ssize_strlen(c_str); + if (unlikely(len < 0)) return NULL; + return __Pyx_PyUnicode_FromStringAndSize(c_str, len); +} +static CYTHON_INLINE PyObject* __Pyx_PyByteArray_FromString(const char* c_str) { + Py_ssize_t len = __Pyx_ssize_strlen(c_str); + if (unlikely(len < 0)) return NULL; + return PyByteArray_FromStringAndSize(c_str, len); +} +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject* o) { + Py_ssize_t ignore; + return __Pyx_PyObject_AsStringAndSize(o, &ignore); +} +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +#if !CYTHON_PEP393_ENABLED +static const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + char* defenc_c; + PyObject* defenc = _PyUnicode_AsDefaultEncodedString(o, NULL); + if (!defenc) return NULL; + defenc_c = PyBytes_AS_STRING(defenc); +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + { + char* end = defenc_c + PyBytes_GET_SIZE(defenc); + char* c; + for (c = defenc_c; c < end; c++) { + if ((unsigned char) (*c) >= 128) { + PyUnicode_AsASCIIString(o); + return NULL; + } + } + } +#endif + *length = PyBytes_GET_SIZE(defenc); + return defenc_c; +} +#else +static CYTHON_INLINE const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + if (unlikely(__Pyx_PyUnicode_READY(o) == -1)) return NULL; +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + if (likely(PyUnicode_IS_ASCII(o))) { + *length = PyUnicode_GET_LENGTH(o); + return PyUnicode_AsUTF8(o); + } else { + PyUnicode_AsASCIIString(o); + return NULL; + } +#else + return PyUnicode_AsUTF8AndSize(o, length); +#endif +} +#endif +#endif +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject* o, Py_ssize_t *length) { +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT + if ( +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + __Pyx_sys_getdefaultencoding_not_ascii && +#endif + PyUnicode_Check(o)) { + return __Pyx_PyUnicode_AsStringAndSize(o, length); + } else +#endif +#if (!CYTHON_COMPILING_IN_PYPY && !CYTHON_COMPILING_IN_LIMITED_API) || (defined(PyByteArray_AS_STRING) && defined(PyByteArray_GET_SIZE)) + if (PyByteArray_Check(o)) { + *length = PyByteArray_GET_SIZE(o); + return PyByteArray_AS_STRING(o); + } else +#endif + { + char* result; + int r = PyBytes_AsStringAndSize(o, &result, length); + if (unlikely(r < 0)) { + return NULL; + } else { + return result; + } + } +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject* x) { + int is_true = x == Py_True; + if (is_true | (x == Py_False) | (x == Py_None)) return is_true; + else return PyObject_IsTrue(x); +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject* x) { + int retval; + if (unlikely(!x)) return -1; + retval = __Pyx_PyObject_IsTrue(x); + Py_DECREF(x); + return retval; +} +static PyObject* __Pyx_PyNumber_IntOrLongWrongResultType(PyObject* result, const char* type_name) { + __Pyx_TypeName result_type_name = __Pyx_PyType_GetName(Py_TYPE(result)); +#if PY_MAJOR_VERSION >= 3 + if (PyLong_Check(result)) { + if (PyErr_WarnFormat(PyExc_DeprecationWarning, 1, + "__int__ returned non-int (type " __Pyx_FMT_TYPENAME "). " + "The ability to return an instance of a strict subclass of int is deprecated, " + "and may be removed in a future version of Python.", + result_type_name)) { + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; + } + __Pyx_DECREF_TypeName(result_type_name); + return result; + } +#endif + PyErr_Format(PyExc_TypeError, + "__%.4s__ returned non-%.4s (type " __Pyx_FMT_TYPENAME ")", + type_name, type_name, result_type_name); + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x) { +#if CYTHON_USE_TYPE_SLOTS + PyNumberMethods *m; +#endif + const char *name = NULL; + PyObject *res = NULL; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x) || PyLong_Check(x))) +#else + if (likely(PyLong_Check(x))) +#endif + return __Pyx_NewRef(x); +#if CYTHON_USE_TYPE_SLOTS + m = Py_TYPE(x)->tp_as_number; + #if PY_MAJOR_VERSION < 3 + if (m && m->nb_int) { + name = "int"; + res = m->nb_int(x); + } + else if (m && m->nb_long) { + name = "long"; + res = m->nb_long(x); + } + #else + if (likely(m && m->nb_int)) { + name = "int"; + res = m->nb_int(x); + } + #endif +#else + if (!PyBytes_CheckExact(x) && !PyUnicode_CheckExact(x)) { + res = PyNumber_Int(x); + } +#endif + if (likely(res)) { +#if PY_MAJOR_VERSION < 3 + if (unlikely(!PyInt_Check(res) && !PyLong_Check(res))) { +#else + if (unlikely(!PyLong_CheckExact(res))) { +#endif + return __Pyx_PyNumber_IntOrLongWrongResultType(res, name); + } + } + else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_TypeError, + "an integer is required"); + } + return res; +} +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject* b) { + Py_ssize_t ival; + PyObject *x; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_CheckExact(b))) { + if (sizeof(Py_ssize_t) >= sizeof(long)) + return PyInt_AS_LONG(b); + else + return PyInt_AsSsize_t(b); + } +#endif + if (likely(PyLong_CheckExact(b))) { + #if CYTHON_USE_PYLONG_INTERNALS + if (likely(__Pyx_PyLong_IsCompact(b))) { + return __Pyx_PyLong_CompactValue(b); + } else { + const digit* digits = __Pyx_PyLong_Digits(b); + const Py_ssize_t size = __Pyx_PyLong_SignedDigitCount(b); + switch (size) { + case 2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return (Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + } + } + #endif + return PyLong_AsSsize_t(b); + } + x = PyNumber_Index(b); + if (!x) return -1; + ival = PyInt_AsSsize_t(x); + Py_DECREF(x); + return ival; +} +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject* o) { + if (sizeof(Py_hash_t) == sizeof(Py_ssize_t)) { + return (Py_hash_t) __Pyx_PyIndex_AsSsize_t(o); +#if PY_MAJOR_VERSION < 3 + } else if (likely(PyInt_CheckExact(o))) { + return PyInt_AS_LONG(o); +#endif + } else { + Py_ssize_t ival; + PyObject *x; + x = PyNumber_Index(o); + if (!x) return -1; + ival = PyInt_AsLong(x); + Py_DECREF(x); + return ival; + } +} +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b) { + return b ? __Pyx_NewRef(Py_True) : __Pyx_NewRef(Py_False); +} +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t ival) { + return PyInt_FromSize_t(ival); +} + + +/* #### Code section: utility_code_pragmas_end ### */ +#ifdef _MSC_VER +#pragma warning( pop ) +#endif + + + +/* #### Code section: end ### */ +#endif /* Py_PYTHON_H */ diff --git a/selfdrive/modeld/runners/snpemodel_pyx.so b/selfdrive/modeld/runners/snpemodel_pyx.so new file mode 100755 index 0000000..f6313d2 Binary files /dev/null and b/selfdrive/modeld/runners/snpemodel_pyx.so differ diff --git a/selfdrive/modeld/runners/thneedmodel.cc b/selfdrive/modeld/runners/thneedmodel.cc deleted file mode 100644 index a16d8b4..0000000 --- a/selfdrive/modeld/runners/thneedmodel.cc +++ /dev/null @@ -1,58 +0,0 @@ -#include "selfdrive/modeld/runners/thneedmodel.h" - -#include - -#include "common/swaglog.h" - -ThneedModel::ThneedModel(const std::string path, float *_output, size_t _output_size, int runtime, bool luse_tf8, cl_context context) { - thneed = new Thneed(true, context); - thneed->load(path.c_str()); - thneed->clexec(); - - recorded = false; - output = _output; -} - -void* ThneedModel::getCLBuffer(const std::string name) { - int index = -1; - for (int i = 0; i < inputs.size(); i++) { - if (name == inputs[i]->name) { - index = i; - break; - } - } - - if (index == -1) { - LOGE("Tried to get CL buffer for input `%s` but no input with this name exists", name.c_str()); - assert(false); - } - - if (thneed->input_clmem.size() >= inputs.size()) { - return &thneed->input_clmem[inputs.size() - index - 1]; - } else { - return nullptr; - } -} - -void ThneedModel::execute() { - if (!recorded) { - thneed->record = true; - float *input_buffers[inputs.size()]; - for (int i = 0; i < inputs.size(); i++) { - input_buffers[inputs.size() - i - 1] = inputs[i]->buffer; - } - - thneed->copy_inputs(input_buffers); - thneed->clexec(); - thneed->copy_output(output); - thneed->stop(); - - recorded = true; - } else { - float *input_buffers[inputs.size()]; - for (int i = 0; i < inputs.size(); i++) { - input_buffers[inputs.size() - i - 1] = inputs[i]->buffer; - } - thneed->execute(input_buffers, output); - } -} diff --git a/selfdrive/modeld/runners/thneedmodel.h b/selfdrive/modeld/runners/thneedmodel.h deleted file mode 100644 index 6ed479c..0000000 --- a/selfdrive/modeld/runners/thneedmodel.h +++ /dev/null @@ -1,17 +0,0 @@ -#pragma once - -#include - -#include "selfdrive/modeld/runners/runmodel.h" -#include "selfdrive/modeld/thneed/thneed.h" - -class ThneedModel : public RunModel { -public: - ThneedModel(const std::string path, float *_output, size_t _output_size, int runtime, bool use_tf8 = false, cl_context context = NULL); - void *getCLBuffer(const std::string name); - void execute(); -private: - Thneed *thneed = NULL; - bool recorded; - float *output; -}; diff --git a/selfdrive/modeld/runners/thneedmodel_pyx.cpp b/selfdrive/modeld/runners/thneedmodel_pyx.cpp new file mode 100644 index 0000000..1cab645 --- /dev/null +++ b/selfdrive/modeld/runners/thneedmodel_pyx.cpp @@ -0,0 +1,27767 @@ +/* Generated by Cython 3.0.8 */ + +/* BEGIN: Cython Metadata +{ + "distutils": { + "depends": [ + "cereal/visionipc/visionbuf.h", + "cereal/visionipc/visionipc.h", + "cereal/visionipc/visionipc_client.h", + "cereal/visionipc/visionipc_server.h", + "selfdrive/modeld/runners/runmodel.h", + "selfdrive/modeld/runners/thneedmodel.h" + ], + "language": "c++", + "name": "selfdrive.modeld.runners.thneedmodel_pyx", + "sources": [ + "/data/openpilot/selfdrive/modeld/runners/thneedmodel_pyx.pyx" + ] + }, + "module_name": "selfdrive.modeld.runners.thneedmodel_pyx" +} +END: Cython Metadata */ + +#ifndef PY_SSIZE_T_CLEAN +#define PY_SSIZE_T_CLEAN +#endif /* PY_SSIZE_T_CLEAN */ +#if defined(CYTHON_LIMITED_API) && 0 + #ifndef Py_LIMITED_API + #if CYTHON_LIMITED_API+0 > 0x03030000 + #define Py_LIMITED_API CYTHON_LIMITED_API + #else + #define Py_LIMITED_API 0x03030000 + #endif + #endif +#endif + +#include "Python.h" +#ifndef Py_PYTHON_H + #error Python headers needed to compile C extensions, please install development version of Python. +#elif PY_VERSION_HEX < 0x02070000 || (0x03000000 <= PY_VERSION_HEX && PY_VERSION_HEX < 0x03030000) + #error Cython requires Python 2.7+ or Python 3.3+. +#else +#if defined(CYTHON_LIMITED_API) && CYTHON_LIMITED_API +#define __PYX_EXTRA_ABI_MODULE_NAME "limited" +#else +#define __PYX_EXTRA_ABI_MODULE_NAME "" +#endif +#define CYTHON_ABI "3_0_8" __PYX_EXTRA_ABI_MODULE_NAME +#define __PYX_ABI_MODULE_NAME "_cython_" CYTHON_ABI +#define __PYX_TYPE_MODULE_PREFIX __PYX_ABI_MODULE_NAME "." +#define CYTHON_HEX_VERSION 0x030008F0 +#define CYTHON_FUTURE_DIVISION 1 +#include +#ifndef offsetof + #define offsetof(type, member) ( (size_t) & ((type*)0) -> member ) +#endif +#if !defined(_WIN32) && !defined(WIN32) && !defined(MS_WINDOWS) + #ifndef __stdcall + #define __stdcall + #endif + #ifndef __cdecl + #define __cdecl + #endif + #ifndef __fastcall + #define __fastcall + #endif +#endif +#ifndef DL_IMPORT + #define DL_IMPORT(t) t +#endif +#ifndef DL_EXPORT + #define DL_EXPORT(t) t +#endif +#define __PYX_COMMA , +#ifndef HAVE_LONG_LONG + #define HAVE_LONG_LONG +#endif +#ifndef PY_LONG_LONG + #define PY_LONG_LONG LONG_LONG +#endif +#ifndef Py_HUGE_VAL + #define Py_HUGE_VAL HUGE_VAL +#endif +#define __PYX_LIMITED_VERSION_HEX PY_VERSION_HEX +#if defined(GRAALVM_PYTHON) + /* For very preliminary testing purposes. Most variables are set the same as PyPy. + The existence of this section does not imply that anything works or is even tested */ + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 1 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(PYPY_VERSION) + #define CYTHON_COMPILING_IN_PYPY 1 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #ifndef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #endif + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #undef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 1 + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS (PY_MAJOR_VERSION >= 3) + #endif + #if PY_VERSION_HEX < 0x03090000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE (PY_VERSION_HEX >= 0x030400a1 && PYPY_VERSION_NUM >= 0x07030C00) + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(CYTHON_LIMITED_API) + #ifdef Py_LIMITED_API + #undef __PYX_LIMITED_VERSION_HEX + #define __PYX_LIMITED_VERSION_HEX Py_LIMITED_API + #endif + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 1 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #undef CYTHON_CLINE_IN_TRACEBACK + #define CYTHON_CLINE_IN_TRACEBACK 0 + #undef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 0 + #undef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 1 + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #undef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #endif + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #undef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 0 + #undef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 0 + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL 0 + #undef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #undef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 1 + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 0 + #endif +#elif defined(Py_GIL_DISABLED) || defined(Py_NOGIL) + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 0 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 1 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #undef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 0 + #ifndef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #undef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 0 + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #undef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 0 + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #undef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 0 + #undef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 0 + #ifndef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 +#else + #define CYTHON_COMPILING_IN_PYPY 0 + #define CYTHON_COMPILING_IN_CPYTHON 1 + #define CYTHON_COMPILING_IN_LIMITED_API 0 + #define CYTHON_COMPILING_IN_GRAAL 0 + #define CYTHON_COMPILING_IN_NOGIL 0 + #ifndef CYTHON_USE_TYPE_SLOTS + #define CYTHON_USE_TYPE_SLOTS 1 + #endif + #ifndef CYTHON_USE_TYPE_SPECS + #define CYTHON_USE_TYPE_SPECS 0 + #endif + #ifndef CYTHON_USE_PYTYPE_LOOKUP + #define CYTHON_USE_PYTYPE_LOOKUP 1 + #endif + #if PY_MAJOR_VERSION < 3 + #undef CYTHON_USE_ASYNC_SLOTS + #define CYTHON_USE_ASYNC_SLOTS 0 + #elif !defined(CYTHON_USE_ASYNC_SLOTS) + #define CYTHON_USE_ASYNC_SLOTS 1 + #endif + #ifndef CYTHON_USE_PYLONG_INTERNALS + #define CYTHON_USE_PYLONG_INTERNALS 1 + #endif + #ifndef CYTHON_USE_PYLIST_INTERNALS + #define CYTHON_USE_PYLIST_INTERNALS 1 + #endif + #ifndef CYTHON_USE_UNICODE_INTERNALS + #define CYTHON_USE_UNICODE_INTERNALS 1 + #endif + #if PY_VERSION_HEX < 0x030300F0 || PY_VERSION_HEX >= 0x030B00A2 + #undef CYTHON_USE_UNICODE_WRITER + #define CYTHON_USE_UNICODE_WRITER 0 + #elif !defined(CYTHON_USE_UNICODE_WRITER) + #define CYTHON_USE_UNICODE_WRITER 1 + #endif + #ifndef CYTHON_AVOID_BORROWED_REFS + #define CYTHON_AVOID_BORROWED_REFS 0 + #endif + #ifndef CYTHON_ASSUME_SAFE_MACROS + #define CYTHON_ASSUME_SAFE_MACROS 1 + #endif + #ifndef CYTHON_UNPACK_METHODS + #define CYTHON_UNPACK_METHODS 1 + #endif + #ifndef CYTHON_FAST_THREAD_STATE + #define CYTHON_FAST_THREAD_STATE 1 + #endif + #ifndef CYTHON_FAST_GIL + #define CYTHON_FAST_GIL (PY_MAJOR_VERSION < 3 || PY_VERSION_HEX >= 0x03060000 && PY_VERSION_HEX < 0x030C00A6) + #endif + #ifndef CYTHON_METH_FASTCALL + #define CYTHON_METH_FASTCALL (PY_VERSION_HEX >= 0x030700A1) + #endif + #ifndef CYTHON_FAST_PYCALL + #define CYTHON_FAST_PYCALL 1 + #endif + #ifndef CYTHON_PEP487_INIT_SUBCLASS + #define CYTHON_PEP487_INIT_SUBCLASS 1 + #endif + #if PY_VERSION_HEX < 0x03050000 + #undef CYTHON_PEP489_MULTI_PHASE_INIT + #define CYTHON_PEP489_MULTI_PHASE_INIT 0 + #elif !defined(CYTHON_PEP489_MULTI_PHASE_INIT) + #define CYTHON_PEP489_MULTI_PHASE_INIT 1 + #endif + #ifndef CYTHON_USE_MODULE_STATE + #define CYTHON_USE_MODULE_STATE 0 + #endif + #if PY_VERSION_HEX < 0x030400a1 + #undef CYTHON_USE_TP_FINALIZE + #define CYTHON_USE_TP_FINALIZE 0 + #elif !defined(CYTHON_USE_TP_FINALIZE) + #define CYTHON_USE_TP_FINALIZE 1 + #endif + #if PY_VERSION_HEX < 0x030600B1 + #undef CYTHON_USE_DICT_VERSIONS + #define CYTHON_USE_DICT_VERSIONS 0 + #elif !defined(CYTHON_USE_DICT_VERSIONS) + #define CYTHON_USE_DICT_VERSIONS (PY_VERSION_HEX < 0x030C00A5) + #endif + #if PY_VERSION_HEX < 0x030700A3 + #undef CYTHON_USE_EXC_INFO_STACK + #define CYTHON_USE_EXC_INFO_STACK 0 + #elif !defined(CYTHON_USE_EXC_INFO_STACK) + #define CYTHON_USE_EXC_INFO_STACK 1 + #endif + #ifndef CYTHON_UPDATE_DESCRIPTOR_DOC + #define CYTHON_UPDATE_DESCRIPTOR_DOC 1 + #endif +#endif +#if !defined(CYTHON_FAST_PYCCALL) +#define CYTHON_FAST_PYCCALL (CYTHON_FAST_PYCALL && PY_VERSION_HEX >= 0x030600B1) +#endif +#if !defined(CYTHON_VECTORCALL) +#define CYTHON_VECTORCALL (CYTHON_FAST_PYCCALL && PY_VERSION_HEX >= 0x030800B1) +#endif +#define CYTHON_BACKPORT_VECTORCALL (CYTHON_METH_FASTCALL && PY_VERSION_HEX < 0x030800B1) +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_MAJOR_VERSION < 3 + #include "longintrepr.h" + #endif + #undef SHIFT + #undef BASE + #undef MASK + #ifdef SIZEOF_VOID_P + enum { __pyx_check_sizeof_voidp = 1 / (int)(SIZEOF_VOID_P == sizeof(void*)) }; + #endif +#endif +#ifndef __has_attribute + #define __has_attribute(x) 0 +#endif +#ifndef __has_cpp_attribute + #define __has_cpp_attribute(x) 0 +#endif +#ifndef CYTHON_RESTRICT + #if defined(__GNUC__) + #define CYTHON_RESTRICT __restrict__ + #elif defined(_MSC_VER) && _MSC_VER >= 1400 + #define CYTHON_RESTRICT __restrict + #elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define CYTHON_RESTRICT restrict + #else + #define CYTHON_RESTRICT + #endif +#endif +#ifndef CYTHON_UNUSED + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(maybe_unused) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(maybe_unused) + #define CYTHON_UNUSED [[maybe_unused]] + #endif + #endif + #endif +#endif +#ifndef CYTHON_UNUSED +# if defined(__GNUC__) +# if !(defined(__cplusplus)) || (__GNUC__ > 3 || (__GNUC__ == 3 && __GNUC_MINOR__ >= 4)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +# elif defined(__ICC) || (defined(__INTEL_COMPILER) && !defined(_MSC_VER)) +# define CYTHON_UNUSED __attribute__ ((__unused__)) +# else +# define CYTHON_UNUSED +# endif +#endif +#ifndef CYTHON_UNUSED_VAR +# if defined(__cplusplus) + template void CYTHON_UNUSED_VAR( const T& ) { } +# else +# define CYTHON_UNUSED_VAR(x) (void)(x) +# endif +#endif +#ifndef CYTHON_MAYBE_UNUSED_VAR + #define CYTHON_MAYBE_UNUSED_VAR(x) CYTHON_UNUSED_VAR(x) +#endif +#ifndef CYTHON_NCP_UNUSED +# if CYTHON_COMPILING_IN_CPYTHON +# define CYTHON_NCP_UNUSED +# else +# define CYTHON_NCP_UNUSED CYTHON_UNUSED +# endif +#endif +#ifndef CYTHON_USE_CPP_STD_MOVE + #if defined(__cplusplus) && (\ + __cplusplus >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1600)) + #define CYTHON_USE_CPP_STD_MOVE 1 + #else + #define CYTHON_USE_CPP_STD_MOVE 0 + #endif +#endif +#define __Pyx_void_to_None(void_result) ((void)(void_result), Py_INCREF(Py_None), Py_None) +#ifdef _MSC_VER + #ifndef _MSC_STDINT_H_ + #if _MSC_VER < 1300 + typedef unsigned char uint8_t; + typedef unsigned short uint16_t; + typedef unsigned int uint32_t; + #else + typedef unsigned __int8 uint8_t; + typedef unsigned __int16 uint16_t; + typedef unsigned __int32 uint32_t; + #endif + #endif + #if _MSC_VER < 1300 + #ifdef _WIN64 + typedef unsigned long long __pyx_uintptr_t; + #else + typedef unsigned int __pyx_uintptr_t; + #endif + #else + #ifdef _WIN64 + typedef unsigned __int64 __pyx_uintptr_t; + #else + typedef unsigned __int32 __pyx_uintptr_t; + #endif + #endif +#else + #include + typedef uintptr_t __pyx_uintptr_t; +#endif +#ifndef CYTHON_FALLTHROUGH + #if defined(__cplusplus) + /* for clang __has_cpp_attribute(fallthrough) is true even before C++17 + * but leads to warnings with -pedantic, since it is a C++17 feature */ + #if ((defined(_MSVC_LANG) && _MSVC_LANG >= 201703L) || __cplusplus >= 201703L) + #if __has_cpp_attribute(fallthrough) + #define CYTHON_FALLTHROUGH [[fallthrough]] + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_cpp_attribute(clang::fallthrough) + #define CYTHON_FALLTHROUGH [[clang::fallthrough]] + #elif __has_cpp_attribute(gnu::fallthrough) + #define CYTHON_FALLTHROUGH [[gnu::fallthrough]] + #endif + #endif + #endif + #ifndef CYTHON_FALLTHROUGH + #if __has_attribute(fallthrough) + #define CYTHON_FALLTHROUGH __attribute__((fallthrough)) + #else + #define CYTHON_FALLTHROUGH + #endif + #endif + #if defined(__clang__) && defined(__apple_build_version__) + #if __apple_build_version__ < 7000000 + #undef CYTHON_FALLTHROUGH + #define CYTHON_FALLTHROUGH + #endif + #endif +#endif +#ifdef __cplusplus + template + struct __PYX_IS_UNSIGNED_IMPL {static const bool value = T(0) < T(-1);}; + #define __PYX_IS_UNSIGNED(type) (__PYX_IS_UNSIGNED_IMPL::value) +#else + #define __PYX_IS_UNSIGNED(type) (((type)-1) > 0) +#endif +#if CYTHON_COMPILING_IN_PYPY == 1 + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x030A0000) +#else + #define __PYX_NEED_TP_PRINT_SLOT (PY_VERSION_HEX >= 0x030800b4 && PY_VERSION_HEX < 0x03090000) +#endif +#define __PYX_REINTERPRET_FUNCION(func_pointer, other_pointer) ((func_pointer)(void(*)(void))(other_pointer)) + +#ifndef __cplusplus + #error "Cython files generated with the C++ option must be compiled with a C++ compiler." +#endif +#ifndef CYTHON_INLINE + #if defined(__clang__) + #define CYTHON_INLINE __inline__ __attribute__ ((__unused__)) + #else + #define CYTHON_INLINE inline + #endif +#endif +template +void __Pyx_call_destructor(T& x) { + x.~T(); +} +template +class __Pyx_FakeReference { + public: + __Pyx_FakeReference() : ptr(NULL) { } + __Pyx_FakeReference(const T& ref) : ptr(const_cast(&ref)) { } + T *operator->() { return ptr; } + T *operator&() { return ptr; } + operator T&() { return *ptr; } + template bool operator ==(const U& other) const { return *ptr == other; } + template bool operator !=(const U& other) const { return *ptr != other; } + template bool operator==(const __Pyx_FakeReference& other) const { return *ptr == *other.ptr; } + template bool operator!=(const __Pyx_FakeReference& other) const { return *ptr != *other.ptr; } + private: + T *ptr; +}; + +#define __PYX_BUILD_PY_SSIZE_T "n" +#define CYTHON_FORMAT_SSIZE_T "z" +#if PY_MAJOR_VERSION < 3 + #define __Pyx_BUILTIN_MODULE_NAME "__builtin__" + #define __Pyx_DefaultClassType PyClass_Type + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a+k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_BUILTIN_MODULE_NAME "builtins" + #define __Pyx_DefaultClassType PyType_Type +#if CYTHON_COMPILING_IN_LIMITED_API + static CYTHON_INLINE PyObject* __Pyx_PyCode_New(int a, int p, int k, int l, int s, int f, + PyObject *code, PyObject *c, PyObject* n, PyObject *v, + PyObject *fv, PyObject *cell, PyObject* fn, + PyObject *name, int fline, PyObject *lnos) { + PyObject *exception_table = NULL; + PyObject *types_module=NULL, *code_type=NULL, *result=NULL; + #if __PYX_LIMITED_VERSION_HEX < 0x030B0000 + PyObject *version_info; + PyObject *py_minor_version = NULL; + #endif + long minor_version = 0; + PyObject *type, *value, *traceback; + PyErr_Fetch(&type, &value, &traceback); + #if __PYX_LIMITED_VERSION_HEX >= 0x030B0000 + minor_version = 11; + #else + if (!(version_info = PySys_GetObject("version_info"))) goto end; + if (!(py_minor_version = PySequence_GetItem(version_info, 1))) goto end; + minor_version = PyLong_AsLong(py_minor_version); + Py_DECREF(py_minor_version); + if (minor_version == -1 && PyErr_Occurred()) goto end; + #endif + if (!(types_module = PyImport_ImportModule("types"))) goto end; + if (!(code_type = PyObject_GetAttrString(types_module, "CodeType"))) goto end; + if (minor_version <= 7) { + (void)p; + result = PyObject_CallFunction(code_type, "iiiiiOOOOOOiOO", a, k, l, s, f, code, + c, n, v, fn, name, fline, lnos, fv, cell); + } else if (minor_version <= 10) { + result = PyObject_CallFunction(code_type, "iiiiiiOOOOOOiOO", a,p, k, l, s, f, code, + c, n, v, fn, name, fline, lnos, fv, cell); + } else { + if (!(exception_table = PyBytes_FromStringAndSize(NULL, 0))) goto end; + result = PyObject_CallFunction(code_type, "iiiiiiOOOOOOOiOO", a,p, k, l, s, f, code, + c, n, v, fn, name, name, fline, lnos, exception_table, fv, cell); + } + end: + Py_XDECREF(code_type); + Py_XDECREF(exception_table); + Py_XDECREF(types_module); + if (type) { + PyErr_Restore(type, value, traceback); + } + return result; + } + #ifndef CO_OPTIMIZED + #define CO_OPTIMIZED 0x0001 + #endif + #ifndef CO_NEWLOCALS + #define CO_NEWLOCALS 0x0002 + #endif + #ifndef CO_VARARGS + #define CO_VARARGS 0x0004 + #endif + #ifndef CO_VARKEYWORDS + #define CO_VARKEYWORDS 0x0008 + #endif + #ifndef CO_ASYNC_GENERATOR + #define CO_ASYNC_GENERATOR 0x0200 + #endif + #ifndef CO_GENERATOR + #define CO_GENERATOR 0x0020 + #endif + #ifndef CO_COROUTINE + #define CO_COROUTINE 0x0080 + #endif +#elif PY_VERSION_HEX >= 0x030B0000 + static CYTHON_INLINE PyCodeObject* __Pyx_PyCode_New(int a, int p, int k, int l, int s, int f, + PyObject *code, PyObject *c, PyObject* n, PyObject *v, + PyObject *fv, PyObject *cell, PyObject* fn, + PyObject *name, int fline, PyObject *lnos) { + PyCodeObject *result; + PyObject *empty_bytes = PyBytes_FromStringAndSize("", 0); + if (!empty_bytes) return NULL; + result = + #if PY_VERSION_HEX >= 0x030C0000 + PyUnstable_Code_NewWithPosOnlyArgs + #else + PyCode_NewWithPosOnlyArgs + #endif + (a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, name, fline, lnos, empty_bytes); + Py_DECREF(empty_bytes); + return result; + } +#elif PY_VERSION_HEX >= 0x030800B2 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_NewWithPosOnlyArgs(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#else + #define __Pyx_PyCode_New(a, p, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos)\ + PyCode_New(a, k, l, s, f, code, c, n, v, fv, cell, fn, name, fline, lnos) +#endif +#endif +#if PY_VERSION_HEX >= 0x030900A4 || defined(Py_IS_TYPE) + #define __Pyx_IS_TYPE(ob, type) Py_IS_TYPE(ob, type) +#else + #define __Pyx_IS_TYPE(ob, type) (((const PyObject*)ob)->ob_type == (type)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_Is) + #define __Pyx_Py_Is(x, y) Py_Is(x, y) +#else + #define __Pyx_Py_Is(x, y) ((x) == (y)) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsNone) + #define __Pyx_Py_IsNone(ob) Py_IsNone(ob) +#else + #define __Pyx_Py_IsNone(ob) __Pyx_Py_Is((ob), Py_None) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsTrue) + #define __Pyx_Py_IsTrue(ob) Py_IsTrue(ob) +#else + #define __Pyx_Py_IsTrue(ob) __Pyx_Py_Is((ob), Py_True) +#endif +#if PY_VERSION_HEX >= 0x030A00B1 || defined(Py_IsFalse) + #define __Pyx_Py_IsFalse(ob) Py_IsFalse(ob) +#else + #define __Pyx_Py_IsFalse(ob) __Pyx_Py_Is((ob), Py_False) +#endif +#define __Pyx_NoneAsNull(obj) (__Pyx_Py_IsNone(obj) ? NULL : (obj)) +#if PY_VERSION_HEX >= 0x030900F0 && !CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_GC_IsFinalized(o) PyObject_GC_IsFinalized(o) +#else + #define __Pyx_PyObject_GC_IsFinalized(o) _PyGC_FINALIZED(o) +#endif +#ifndef CO_COROUTINE + #define CO_COROUTINE 0x80 +#endif +#ifndef CO_ASYNC_GENERATOR + #define CO_ASYNC_GENERATOR 0x200 +#endif +#ifndef Py_TPFLAGS_CHECKTYPES + #define Py_TPFLAGS_CHECKTYPES 0 +#endif +#ifndef Py_TPFLAGS_HAVE_INDEX + #define Py_TPFLAGS_HAVE_INDEX 0 +#endif +#ifndef Py_TPFLAGS_HAVE_NEWBUFFER + #define Py_TPFLAGS_HAVE_NEWBUFFER 0 +#endif +#ifndef Py_TPFLAGS_HAVE_FINALIZE + #define Py_TPFLAGS_HAVE_FINALIZE 0 +#endif +#ifndef Py_TPFLAGS_SEQUENCE + #define Py_TPFLAGS_SEQUENCE 0 +#endif +#ifndef Py_TPFLAGS_MAPPING + #define Py_TPFLAGS_MAPPING 0 +#endif +#ifndef METH_STACKLESS + #define METH_STACKLESS 0 +#endif +#if PY_VERSION_HEX <= 0x030700A3 || !defined(METH_FASTCALL) + #ifndef METH_FASTCALL + #define METH_FASTCALL 0x80 + #endif + typedef PyObject *(*__Pyx_PyCFunctionFast) (PyObject *self, PyObject *const *args, Py_ssize_t nargs); + typedef PyObject *(*__Pyx_PyCFunctionFastWithKeywords) (PyObject *self, PyObject *const *args, + Py_ssize_t nargs, PyObject *kwnames); +#else + #define __Pyx_PyCFunctionFast _PyCFunctionFast + #define __Pyx_PyCFunctionFastWithKeywords _PyCFunctionFastWithKeywords +#endif +#if CYTHON_METH_FASTCALL + #define __Pyx_METH_FASTCALL METH_FASTCALL + #define __Pyx_PyCFunction_FastCall __Pyx_PyCFunctionFast + #define __Pyx_PyCFunction_FastCallWithKeywords __Pyx_PyCFunctionFastWithKeywords +#else + #define __Pyx_METH_FASTCALL METH_VARARGS + #define __Pyx_PyCFunction_FastCall PyCFunction + #define __Pyx_PyCFunction_FastCallWithKeywords PyCFunctionWithKeywords +#endif +#if CYTHON_VECTORCALL + #define __pyx_vectorcallfunc vectorcallfunc + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET PY_VECTORCALL_ARGUMENTS_OFFSET + #define __Pyx_PyVectorcall_NARGS(n) PyVectorcall_NARGS((size_t)(n)) +#elif CYTHON_BACKPORT_VECTORCALL + typedef PyObject *(*__pyx_vectorcallfunc)(PyObject *callable, PyObject *const *args, + size_t nargsf, PyObject *kwnames); + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET ((size_t)1 << (8 * sizeof(size_t) - 1)) + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(((size_t)(n)) & ~__Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET)) +#else + #define __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET 0 + #define __Pyx_PyVectorcall_NARGS(n) ((Py_ssize_t)(n)) +#endif +#if PY_MAJOR_VERSION >= 0x030900B1 +#define __Pyx_PyCFunction_CheckExact(func) PyCFunction_CheckExact(func) +#else +#define __Pyx_PyCFunction_CheckExact(func) PyCFunction_Check(func) +#endif +#define __Pyx_CyOrPyCFunction_Check(func) PyCFunction_Check(func) +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_CyOrPyCFunction_GET_FUNCTION(func) (((PyCFunctionObject*)(func))->m_ml->ml_meth) +#elif !CYTHON_COMPILING_IN_LIMITED_API +#define __Pyx_CyOrPyCFunction_GET_FUNCTION(func) PyCFunction_GET_FUNCTION(func) +#endif +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_CyOrPyCFunction_GET_FLAGS(func) (((PyCFunctionObject*)(func))->m_ml->ml_flags) +static CYTHON_INLINE PyObject* __Pyx_CyOrPyCFunction_GET_SELF(PyObject *func) { + return (__Pyx_CyOrPyCFunction_GET_FLAGS(func) & METH_STATIC) ? NULL : ((PyCFunctionObject*)func)->m_self; +} +#endif +static CYTHON_INLINE int __Pyx__IsSameCFunction(PyObject *func, void *cfunc) { +#if CYTHON_COMPILING_IN_LIMITED_API + return PyCFunction_Check(func) && PyCFunction_GetFunction(func) == (PyCFunction) cfunc; +#else + return PyCFunction_Check(func) && PyCFunction_GET_FUNCTION(func) == (PyCFunction) cfunc; +#endif +} +#define __Pyx_IsSameCFunction(func, cfunc) __Pyx__IsSameCFunction(func, cfunc) +#if __PYX_LIMITED_VERSION_HEX < 0x030900B1 + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) ((void)m, PyType_FromSpecWithBases(s, b)) + typedef PyObject *(*__Pyx_PyCMethod)(PyObject *, PyTypeObject *, PyObject *const *, size_t, PyObject *); +#else + #define __Pyx_PyType_FromModuleAndSpec(m, s, b) PyType_FromModuleAndSpec(m, s, b) + #define __Pyx_PyCMethod PyCMethod +#endif +#ifndef METH_METHOD + #define METH_METHOD 0x200 +#endif +#if CYTHON_COMPILING_IN_PYPY && !defined(PyObject_Malloc) + #define PyObject_Malloc(s) PyMem_Malloc(s) + #define PyObject_Free(p) PyMem_Free(p) + #define PyObject_Realloc(p) PyMem_Realloc(p) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) +#else + #define __Pyx_PyCode_HasFreeVars(co) (PyCode_GetNumFree(co) > 0) + #define __Pyx_PyFrame_SetLineNumber(frame, lineno) (frame)->f_lineno = (lineno) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyThreadState_Current PyThreadState_Get() +#elif !CYTHON_FAST_THREAD_STATE + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#elif PY_VERSION_HEX >= 0x030d00A1 + #define __Pyx_PyThreadState_Current PyThreadState_GetUnchecked() +#elif PY_VERSION_HEX >= 0x03060000 + #define __Pyx_PyThreadState_Current _PyThreadState_UncheckedGet() +#elif PY_VERSION_HEX >= 0x03000000 + #define __Pyx_PyThreadState_Current PyThreadState_GET() +#else + #define __Pyx_PyThreadState_Current _PyThreadState_Current +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE void *__Pyx_PyModule_GetState(PyObject *op) +{ + void *result; + result = PyModule_GetState(op); + if (!result) + Py_FatalError("Couldn't find the module state"); + return result; +} +#endif +#define __Pyx_PyObject_GetSlot(obj, name, func_ctype) __Pyx_PyType_GetSlot(Py_TYPE(obj), name, func_ctype) +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((func_ctype) PyType_GetSlot((type), Py_##name)) +#else + #define __Pyx_PyType_GetSlot(type, name, func_ctype) ((type)->name) +#endif +#if PY_VERSION_HEX < 0x030700A2 && !defined(PyThread_tss_create) && !defined(Py_tss_NEEDS_INIT) +#include "pythread.h" +#define Py_tss_NEEDS_INIT 0 +typedef int Py_tss_t; +static CYTHON_INLINE int PyThread_tss_create(Py_tss_t *key) { + *key = PyThread_create_key(); + return 0; +} +static CYTHON_INLINE Py_tss_t * PyThread_tss_alloc(void) { + Py_tss_t *key = (Py_tss_t *)PyObject_Malloc(sizeof(Py_tss_t)); + *key = Py_tss_NEEDS_INIT; + return key; +} +static CYTHON_INLINE void PyThread_tss_free(Py_tss_t *key) { + PyObject_Free(key); +} +static CYTHON_INLINE int PyThread_tss_is_created(Py_tss_t *key) { + return *key != Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE void PyThread_tss_delete(Py_tss_t *key) { + PyThread_delete_key(*key); + *key = Py_tss_NEEDS_INIT; +} +static CYTHON_INLINE int PyThread_tss_set(Py_tss_t *key, void *value) { + return PyThread_set_key_value(*key, value); +} +static CYTHON_INLINE void * PyThread_tss_get(Py_tss_t *key) { + return PyThread_get_key_value(*key); +} +#endif +#if PY_MAJOR_VERSION < 3 + #if CYTHON_COMPILING_IN_PYPY + #if PYPY_VERSION_NUM < 0x07030600 + #if defined(__cplusplus) && __cplusplus >= 201402L + [[deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")]] + #elif defined(__GNUC__) || defined(__clang__) + __attribute__ ((__deprecated__("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6"))) + #elif defined(_MSC_VER) + __declspec(deprecated("`with nogil:` inside a nogil function will not release the GIL in PyPy2 < 7.3.6")) + #endif + static CYTHON_INLINE int PyGILState_Check(void) { + return 0; + } + #else // PYPY_VERSION_NUM < 0x07030600 + #endif // PYPY_VERSION_NUM < 0x07030600 + #else + static CYTHON_INLINE int PyGILState_Check(void) { + PyThreadState * tstate = _PyThreadState_Current; + return tstate && (tstate == PyGILState_GetThisThreadState()); + } + #endif +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030d0000 || defined(_PyDict_NewPresized) +#define __Pyx_PyDict_NewPresized(n) ((n <= 8) ? PyDict_New() : _PyDict_NewPresized(n)) +#else +#define __Pyx_PyDict_NewPresized(n) PyDict_New() +#endif +#if PY_MAJOR_VERSION >= 3 || CYTHON_FUTURE_DIVISION + #define __Pyx_PyNumber_Divide(x,y) PyNumber_TrueDivide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceTrueDivide(x,y) +#else + #define __Pyx_PyNumber_Divide(x,y) PyNumber_Divide(x,y) + #define __Pyx_PyNumber_InPlaceDivide(x,y) PyNumber_InPlaceDivide(x,y) +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX > 0x030600B4 && PY_VERSION_HEX < 0x030d0000 && CYTHON_USE_UNICODE_INTERNALS +#define __Pyx_PyDict_GetItemStrWithError(dict, name) _PyDict_GetItem_KnownHash(dict, name, ((PyASCIIObject *) name)->hash) +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStr(PyObject *dict, PyObject *name) { + PyObject *res = __Pyx_PyDict_GetItemStrWithError(dict, name); + if (res == NULL) PyErr_Clear(); + return res; +} +#elif PY_MAJOR_VERSION >= 3 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07020000) +#define __Pyx_PyDict_GetItemStrWithError PyDict_GetItemWithError +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#else +static CYTHON_INLINE PyObject * __Pyx_PyDict_GetItemStrWithError(PyObject *dict, PyObject *name) { +#if CYTHON_COMPILING_IN_PYPY + return PyDict_GetItem(dict, name); +#else + PyDictEntry *ep; + PyDictObject *mp = (PyDictObject*) dict; + long hash = ((PyStringObject *) name)->ob_shash; + assert(hash != -1); + ep = (mp->ma_lookup)(mp, name, hash); + if (ep == NULL) { + return NULL; + } + return ep->me_value; +#endif +} +#define __Pyx_PyDict_GetItemStr PyDict_GetItem +#endif +#if CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyType_GetFlags(tp) (((PyTypeObject *)tp)->tp_flags) + #define __Pyx_PyType_HasFeature(type, feature) ((__Pyx_PyType_GetFlags(type) & (feature)) != 0) + #define __Pyx_PyObject_GetIterNextFunc(obj) (Py_TYPE(obj)->tp_iternext) +#else + #define __Pyx_PyType_GetFlags(tp) (PyType_GetFlags((PyTypeObject *)tp)) + #define __Pyx_PyType_HasFeature(type, feature) PyType_HasFeature(type, feature) + #define __Pyx_PyObject_GetIterNextFunc(obj) PyIter_Next +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_SetItemOnTypeDict(tp, k, v) PyObject_GenericSetAttr((PyObject*)tp, k, v) +#else + #define __Pyx_SetItemOnTypeDict(tp, k, v) PyDict_SetItem(tp->tp_dict, k, v) +#endif +#if CYTHON_USE_TYPE_SPECS && PY_VERSION_HEX >= 0x03080000 +#define __Pyx_PyHeapTypeObject_GC_Del(obj) {\ + PyTypeObject *type = Py_TYPE((PyObject*)obj);\ + assert(__Pyx_PyType_HasFeature(type, Py_TPFLAGS_HEAPTYPE));\ + PyObject_GC_Del(obj);\ + Py_DECREF(type);\ +} +#else +#define __Pyx_PyHeapTypeObject_GC_Del(obj) PyObject_GC_Del(obj) +#endif +#if CYTHON_COMPILING_IN_LIMITED_API + #define CYTHON_PEP393_ENABLED 1 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GetLength(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_ReadChar(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((void)u, 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((void)u, (0)) + #define __Pyx_PyUnicode_DATA(u) ((void*)u) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)k, PyUnicode_ReadChar((PyObject*)(d), i)) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GetLength(u)) +#elif PY_VERSION_HEX > 0x03030000 && defined(PyUnicode_KIND) + #define CYTHON_PEP393_ENABLED 1 + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_READY(op) (0) + #else + #define __Pyx_PyUnicode_READY(op) (likely(PyUnicode_IS_READY(op)) ?\ + 0 : _PyUnicode_Ready((PyObject *)(op))) + #endif + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_LENGTH(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) PyUnicode_READ_CHAR(u, i) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) PyUnicode_MAX_CHAR_VALUE(u) + #define __Pyx_PyUnicode_KIND(u) ((int)PyUnicode_KIND(u)) + #define __Pyx_PyUnicode_DATA(u) PyUnicode_DATA(u) + #define __Pyx_PyUnicode_READ(k, d, i) PyUnicode_READ(k, d, i) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) PyUnicode_WRITE(k, d, i, (Py_UCS4) ch) + #if PY_VERSION_HEX >= 0x030C0000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_LENGTH(u)) + #else + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x03090000 + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : ((PyCompactUnicodeObject *)(u))->wstr_length)) + #else + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != (likely(PyUnicode_IS_READY(u)) ? PyUnicode_GET_LENGTH(u) : PyUnicode_GET_SIZE(u))) + #endif + #endif +#else + #define CYTHON_PEP393_ENABLED 0 + #define PyUnicode_1BYTE_KIND 1 + #define PyUnicode_2BYTE_KIND 2 + #define PyUnicode_4BYTE_KIND 4 + #define __Pyx_PyUnicode_READY(op) (0) + #define __Pyx_PyUnicode_GET_LENGTH(u) PyUnicode_GET_SIZE(u) + #define __Pyx_PyUnicode_READ_CHAR(u, i) ((Py_UCS4)(PyUnicode_AS_UNICODE(u)[i])) + #define __Pyx_PyUnicode_MAX_CHAR_VALUE(u) ((sizeof(Py_UNICODE) == 2) ? 65535U : 1114111U) + #define __Pyx_PyUnicode_KIND(u) ((int)sizeof(Py_UNICODE)) + #define __Pyx_PyUnicode_DATA(u) ((void*)PyUnicode_AS_UNICODE(u)) + #define __Pyx_PyUnicode_READ(k, d, i) ((void)(k), (Py_UCS4)(((Py_UNICODE*)d)[i])) + #define __Pyx_PyUnicode_WRITE(k, d, i, ch) (((void)(k)), ((Py_UNICODE*)d)[i] = (Py_UNICODE) ch) + #define __Pyx_PyUnicode_IS_TRUE(u) (0 != PyUnicode_GET_SIZE(u)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyUnicode_Concat(a, b) PyNumber_Add(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) PyNumber_Add(a, b) +#else + #define __Pyx_PyUnicode_Concat(a, b) PyUnicode_Concat(a, b) + #define __Pyx_PyUnicode_ConcatSafe(a, b) ((unlikely((a) == Py_None) || unlikely((b) == Py_None)) ?\ + PyNumber_Add(a, b) : __Pyx_PyUnicode_Concat(a, b)) +#endif +#if CYTHON_COMPILING_IN_PYPY + #if !defined(PyUnicode_DecodeUnicodeEscape) + #define PyUnicode_DecodeUnicodeEscape(s, size, errors) PyUnicode_Decode(s, size, "unicode_escape", errors) + #endif + #if !defined(PyUnicode_Contains) || (PY_MAJOR_VERSION == 2 && PYPY_VERSION_NUM < 0x07030500) + #undef PyUnicode_Contains + #define PyUnicode_Contains(u, s) PySequence_Contains(u, s) + #endif + #if !defined(PyByteArray_Check) + #define PyByteArray_Check(obj) PyObject_TypeCheck(obj, &PyByteArray_Type) + #endif + #if !defined(PyObject_Format) + #define PyObject_Format(obj, fmt) PyObject_CallMethod(obj, "__format__", "O", fmt) + #endif +#endif +#define __Pyx_PyString_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyString_Check(b) && !PyString_CheckExact(b)))) ? PyNumber_Remainder(a, b) : __Pyx_PyString_Format(a, b)) +#define __Pyx_PyUnicode_FormatSafe(a, b) ((unlikely((a) == Py_None || (PyUnicode_Check(b) && !PyUnicode_CheckExact(b)))) ? PyNumber_Remainder(a, b) : PyUnicode_Format(a, b)) +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyString_Format(a, b) PyUnicode_Format(a, b) +#else + #define __Pyx_PyString_Format(a, b) PyString_Format(a, b) +#endif +#if PY_MAJOR_VERSION < 3 && !defined(PyObject_ASCII) + #define PyObject_ASCII(o) PyObject_Repr(o) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBaseString_Type PyUnicode_Type + #define PyStringObject PyUnicodeObject + #define PyString_Type PyUnicode_Type + #define PyString_Check PyUnicode_Check + #define PyString_CheckExact PyUnicode_CheckExact +#ifndef PyObject_Unicode + #define PyObject_Unicode PyObject_Str +#endif +#endif +#if PY_MAJOR_VERSION >= 3 + #define __Pyx_PyBaseString_Check(obj) PyUnicode_Check(obj) + #define __Pyx_PyBaseString_CheckExact(obj) PyUnicode_CheckExact(obj) +#else + #define __Pyx_PyBaseString_Check(obj) (PyString_Check(obj) || PyUnicode_Check(obj)) + #define __Pyx_PyBaseString_CheckExact(obj) (PyString_CheckExact(obj) || PyUnicode_CheckExact(obj)) +#endif +#if CYTHON_COMPILING_IN_CPYTHON + #define __Pyx_PySequence_ListKeepNew(obj)\ + (likely(PyList_CheckExact(obj) && Py_REFCNT(obj) == 1) ? __Pyx_NewRef(obj) : PySequence_List(obj)) +#else + #define __Pyx_PySequence_ListKeepNew(obj) PySequence_List(obj) +#endif +#ifndef PySet_CheckExact + #define PySet_CheckExact(obj) __Pyx_IS_TYPE(obj, &PySet_Type) +#endif +#if PY_VERSION_HEX >= 0x030900A4 + #define __Pyx_SET_REFCNT(obj, refcnt) Py_SET_REFCNT(obj, refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SET_SIZE(obj, size) +#else + #define __Pyx_SET_REFCNT(obj, refcnt) Py_REFCNT(obj) = (refcnt) + #define __Pyx_SET_SIZE(obj, size) Py_SIZE(obj) = (size) +#endif +#if CYTHON_ASSUME_SAFE_MACROS + #define __Pyx_PySequence_ITEM(o, i) PySequence_ITEM(o, i) + #define __Pyx_PySequence_SIZE(seq) Py_SIZE(seq) + #define __Pyx_PyTuple_SET_ITEM(o, i, v) (PyTuple_SET_ITEM(o, i, v), (0)) + #define __Pyx_PyList_SET_ITEM(o, i, v) (PyList_SET_ITEM(o, i, v), (0)) + #define __Pyx_PyTuple_GET_SIZE(o) PyTuple_GET_SIZE(o) + #define __Pyx_PyList_GET_SIZE(o) PyList_GET_SIZE(o) + #define __Pyx_PySet_GET_SIZE(o) PySet_GET_SIZE(o) + #define __Pyx_PyBytes_GET_SIZE(o) PyBytes_GET_SIZE(o) + #define __Pyx_PyByteArray_GET_SIZE(o) PyByteArray_GET_SIZE(o) +#else + #define __Pyx_PySequence_ITEM(o, i) PySequence_GetItem(o, i) + #define __Pyx_PySequence_SIZE(seq) PySequence_Size(seq) + #define __Pyx_PyTuple_SET_ITEM(o, i, v) PyTuple_SetItem(o, i, v) + #define __Pyx_PyList_SET_ITEM(o, i, v) PyList_SetItem(o, i, v) + #define __Pyx_PyTuple_GET_SIZE(o) PyTuple_Size(o) + #define __Pyx_PyList_GET_SIZE(o) PyList_Size(o) + #define __Pyx_PySet_GET_SIZE(o) PySet_Size(o) + #define __Pyx_PyBytes_GET_SIZE(o) PyBytes_Size(o) + #define __Pyx_PyByteArray_GET_SIZE(o) PyByteArray_Size(o) +#endif +#if PY_VERSION_HEX >= 0x030d00A1 + #define __Pyx_PyImport_AddModuleRef(name) PyImport_AddModuleRef(name) +#else + static CYTHON_INLINE PyObject *__Pyx_PyImport_AddModuleRef(const char *name) { + PyObject *module = PyImport_AddModule(name); + Py_XINCREF(module); + return module; + } +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyIntObject PyLongObject + #define PyInt_Type PyLong_Type + #define PyInt_Check(op) PyLong_Check(op) + #define PyInt_CheckExact(op) PyLong_CheckExact(op) + #define __Pyx_Py3Int_Check(op) PyLong_Check(op) + #define __Pyx_Py3Int_CheckExact(op) PyLong_CheckExact(op) + #define PyInt_FromString PyLong_FromString + #define PyInt_FromUnicode PyLong_FromUnicode + #define PyInt_FromLong PyLong_FromLong + #define PyInt_FromSize_t PyLong_FromSize_t + #define PyInt_FromSsize_t PyLong_FromSsize_t + #define PyInt_AsLong PyLong_AsLong + #define PyInt_AS_LONG PyLong_AS_LONG + #define PyInt_AsSsize_t PyLong_AsSsize_t + #define PyInt_AsUnsignedLongMask PyLong_AsUnsignedLongMask + #define PyInt_AsUnsignedLongLongMask PyLong_AsUnsignedLongLongMask + #define PyNumber_Int PyNumber_Long +#else + #define __Pyx_Py3Int_Check(op) (PyLong_Check(op) || PyInt_Check(op)) + #define __Pyx_Py3Int_CheckExact(op) (PyLong_CheckExact(op) || PyInt_CheckExact(op)) +#endif +#if PY_MAJOR_VERSION >= 3 + #define PyBoolObject PyLongObject +#endif +#if PY_MAJOR_VERSION >= 3 && CYTHON_COMPILING_IN_PYPY + #ifndef PyUnicode_InternFromString + #define PyUnicode_InternFromString(s) PyUnicode_FromString(s) + #endif +#endif +#if PY_VERSION_HEX < 0x030200A4 + typedef long Py_hash_t; + #define __Pyx_PyInt_FromHash_t PyInt_FromLong + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsHash_t +#else + #define __Pyx_PyInt_FromHash_t PyInt_FromSsize_t + #define __Pyx_PyInt_AsHash_t __Pyx_PyIndex_AsSsize_t +#endif +#if CYTHON_USE_ASYNC_SLOTS + #if PY_VERSION_HEX >= 0x030500B1 + #define __Pyx_PyAsyncMethodsStruct PyAsyncMethods + #define __Pyx_PyType_AsAsync(obj) (Py_TYPE(obj)->tp_as_async) + #else + #define __Pyx_PyType_AsAsync(obj) ((__Pyx_PyAsyncMethodsStruct*) (Py_TYPE(obj)->tp_reserved)) + #endif +#else + #define __Pyx_PyType_AsAsync(obj) NULL +#endif +#ifndef __Pyx_PyAsyncMethodsStruct + typedef struct { + unaryfunc am_await; + unaryfunc am_aiter; + unaryfunc am_anext; + } __Pyx_PyAsyncMethodsStruct; +#endif + +#if defined(_WIN32) || defined(WIN32) || defined(MS_WINDOWS) + #if !defined(_USE_MATH_DEFINES) + #define _USE_MATH_DEFINES + #endif +#endif +#include +#ifdef NAN +#define __PYX_NAN() ((float) NAN) +#else +static CYTHON_INLINE float __PYX_NAN() { + float value; + memset(&value, 0xFF, sizeof(value)); + return value; +} +#endif +#if defined(__CYGWIN__) && defined(_LDBL_EQ_DBL) +#define __Pyx_truncl trunc +#else +#define __Pyx_truncl truncl +#endif + +#define __PYX_MARK_ERR_POS(f_index, lineno) \ + { __pyx_filename = __pyx_f[f_index]; (void)__pyx_filename; __pyx_lineno = lineno; (void)__pyx_lineno; __pyx_clineno = __LINE__; (void)__pyx_clineno; } +#define __PYX_ERR(f_index, lineno, Ln_error) \ + { __PYX_MARK_ERR_POS(f_index, lineno) goto Ln_error; } + +#ifdef CYTHON_EXTERN_C + #undef __PYX_EXTERN_C + #define __PYX_EXTERN_C CYTHON_EXTERN_C +#elif defined(__PYX_EXTERN_C) + #ifdef _MSC_VER + #pragma message ("Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead.") + #else + #warning Please do not define the '__PYX_EXTERN_C' macro externally. Use 'CYTHON_EXTERN_C' instead. + #endif +#else + #define __PYX_EXTERN_C extern "C++" +#endif + +#define __PYX_HAVE__selfdrive__modeld__runners__thneedmodel_pyx +#define __PYX_HAVE_API__selfdrive__modeld__runners__thneedmodel_pyx +/* Early includes */ +#include +#include +#include "ios" +#include "new" +#include "stdexcept" +#include "typeinfo" +#include +#include + + #if __cplusplus >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1600) + // move should be defined for these versions of MSVC, but __cplusplus isn't set usefully + #include + + namespace cython_std { + template typename std::remove_reference::type&& move(T& t) noexcept { return std::move(t); } + template typename std::remove_reference::type&& move(T&& t) noexcept { return std::move(t); } + } + + #endif + +#include +#include +#include "cereal/visionipc/visionbuf.h" +#include "cereal/visionipc/visionipc.h" +#include "cereal/visionipc/visionipc_server.h" +#include "cereal/visionipc/visionipc_client.h" +#include "selfdrive/modeld/runners/thneedmodel.h" +#include "selfdrive/modeld/runners/runmodel.h" +#include "pythread.h" +#include +#ifdef _OPENMP +#include +#endif /* _OPENMP */ + +#if defined(PYREX_WITHOUT_ASSERTIONS) && !defined(CYTHON_WITHOUT_ASSERTIONS) +#define CYTHON_WITHOUT_ASSERTIONS +#endif + +typedef struct {PyObject **p; const char *s; const Py_ssize_t n; const char* encoding; + const char is_unicode; const char is_str; const char intern; } __Pyx_StringTabEntry; + +#define __PYX_DEFAULT_STRING_ENCODING_IS_ASCII 1 +#define __PYX_DEFAULT_STRING_ENCODING_IS_UTF8 0 +#define __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT (PY_MAJOR_VERSION >= 3 && __PYX_DEFAULT_STRING_ENCODING_IS_UTF8) +#define __PYX_DEFAULT_STRING_ENCODING "ascii" +#define __Pyx_PyObject_FromString __Pyx_PyBytes_FromString +#define __Pyx_PyObject_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#define __Pyx_uchar_cast(c) ((unsigned char)c) +#define __Pyx_long_cast(x) ((long)x) +#define __Pyx_fits_Py_ssize_t(v, type, is_signed) (\ + (sizeof(type) < sizeof(Py_ssize_t)) ||\ + (sizeof(type) > sizeof(Py_ssize_t) &&\ + likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX) &&\ + (!is_signed || likely(v > (type)PY_SSIZE_T_MIN ||\ + v == (type)PY_SSIZE_T_MIN))) ||\ + (sizeof(type) == sizeof(Py_ssize_t) &&\ + (is_signed || likely(v < (type)PY_SSIZE_T_MAX ||\ + v == (type)PY_SSIZE_T_MAX))) ) +static CYTHON_INLINE int __Pyx_is_valid_index(Py_ssize_t i, Py_ssize_t limit) { + return (size_t) i < (size_t) limit; +} +#if defined (__cplusplus) && __cplusplus >= 201103L + #include + #define __Pyx_sst_abs(value) std::abs(value) +#elif SIZEOF_INT >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) abs(value) +#elif SIZEOF_LONG >= SIZEOF_SIZE_T + #define __Pyx_sst_abs(value) labs(value) +#elif defined (_MSC_VER) + #define __Pyx_sst_abs(value) ((Py_ssize_t)_abs64(value)) +#elif defined (__STDC_VERSION__) && __STDC_VERSION__ >= 199901L + #define __Pyx_sst_abs(value) llabs(value) +#elif defined (__GNUC__) + #define __Pyx_sst_abs(value) __builtin_llabs(value) +#else + #define __Pyx_sst_abs(value) ((value<0) ? -value : value) +#endif +static CYTHON_INLINE Py_ssize_t __Pyx_ssize_strlen(const char *s); +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject*); +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject*, Py_ssize_t* length); +static CYTHON_INLINE PyObject* __Pyx_PyByteArray_FromString(const char*); +#define __Pyx_PyByteArray_FromStringAndSize(s, l) PyByteArray_FromStringAndSize((const char*)s, l) +#define __Pyx_PyBytes_FromString PyBytes_FromString +#define __Pyx_PyBytes_FromStringAndSize PyBytes_FromStringAndSize +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char*); +#if PY_MAJOR_VERSION < 3 + #define __Pyx_PyStr_FromString __Pyx_PyBytes_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyBytes_FromStringAndSize +#else + #define __Pyx_PyStr_FromString __Pyx_PyUnicode_FromString + #define __Pyx_PyStr_FromStringAndSize __Pyx_PyUnicode_FromStringAndSize +#endif +#define __Pyx_PyBytes_AsWritableString(s) ((char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableSString(s) ((signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsWritableUString(s) ((unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsString(s) ((const char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsSString(s) ((const signed char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyBytes_AsUString(s) ((const unsigned char*) PyBytes_AS_STRING(s)) +#define __Pyx_PyObject_AsWritableString(s) ((char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableSString(s) ((signed char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsWritableUString(s) ((unsigned char*)(__pyx_uintptr_t) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsSString(s) ((const signed char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_AsUString(s) ((const unsigned char*) __Pyx_PyObject_AsString(s)) +#define __Pyx_PyObject_FromCString(s) __Pyx_PyObject_FromString((const char*)s) +#define __Pyx_PyBytes_FromCString(s) __Pyx_PyBytes_FromString((const char*)s) +#define __Pyx_PyByteArray_FromCString(s) __Pyx_PyByteArray_FromString((const char*)s) +#define __Pyx_PyStr_FromCString(s) __Pyx_PyStr_FromString((const char*)s) +#define __Pyx_PyUnicode_FromCString(s) __Pyx_PyUnicode_FromString((const char*)s) +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const wchar_t *u) +{ + const wchar_t *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#else +static CYTHON_INLINE size_t __Pyx_Py_UNICODE_strlen(const Py_UNICODE *u) +{ + const Py_UNICODE *u_end = u; + while (*u_end++) ; + return (size_t)(u_end - u - 1); +} +#endif +#define __Pyx_PyUnicode_FromOrdinal(o) PyUnicode_FromOrdinal((int)o) +#define __Pyx_PyUnicode_FromUnicode(u) PyUnicode_FromUnicode(u, __Pyx_Py_UNICODE_strlen(u)) +#define __Pyx_PyUnicode_FromUnicodeAndLength PyUnicode_FromUnicode +#define __Pyx_PyUnicode_AsUnicode PyUnicode_AsUnicode +#define __Pyx_NewRef(obj) (Py_INCREF(obj), obj) +#define __Pyx_Owned_Py_None(b) __Pyx_NewRef(Py_None) +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b); +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject*); +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject*); +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x); +#define __Pyx_PySequence_Tuple(obj)\ + (likely(PyTuple_CheckExact(obj)) ? __Pyx_NewRef(obj) : PySequence_Tuple(obj)) +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject*); +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t); +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject*); +#if CYTHON_ASSUME_SAFE_MACROS +#define __pyx_PyFloat_AsDouble(x) (PyFloat_CheckExact(x) ? PyFloat_AS_DOUBLE(x) : PyFloat_AsDouble(x)) +#else +#define __pyx_PyFloat_AsDouble(x) PyFloat_AsDouble(x) +#endif +#define __pyx_PyFloat_AsFloat(x) ((float) __pyx_PyFloat_AsDouble(x)) +#if PY_MAJOR_VERSION >= 3 +#define __Pyx_PyNumber_Int(x) (PyLong_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Long(x)) +#else +#define __Pyx_PyNumber_Int(x) (PyInt_CheckExact(x) ? __Pyx_NewRef(x) : PyNumber_Int(x)) +#endif +#if CYTHON_USE_PYLONG_INTERNALS + #if PY_VERSION_HEX >= 0x030C00A7 + #ifndef _PyLong_SIGN_MASK + #define _PyLong_SIGN_MASK 3 + #endif + #ifndef _PyLong_NON_SIZE_BITS + #define _PyLong_NON_SIZE_BITS 3 + #endif + #define __Pyx_PyLong_Sign(x) (((PyLongObject*)x)->long_value.lv_tag & _PyLong_SIGN_MASK) + #define __Pyx_PyLong_IsNeg(x) ((__Pyx_PyLong_Sign(x) & 2) != 0) + #define __Pyx_PyLong_IsNonNeg(x) (!__Pyx_PyLong_IsNeg(x)) + #define __Pyx_PyLong_IsZero(x) (__Pyx_PyLong_Sign(x) & 1) + #define __Pyx_PyLong_IsPos(x) (__Pyx_PyLong_Sign(x) == 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) (__Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) ((Py_ssize_t) (((PyLongObject*)x)->long_value.lv_tag >> _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_SignedDigitCount(x)\ + ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * __Pyx_PyLong_DigitCount(x)) + #if defined(PyUnstable_Long_IsCompact) && defined(PyUnstable_Long_CompactValue) + #define __Pyx_PyLong_IsCompact(x) PyUnstable_Long_IsCompact((PyLongObject*) x) + #define __Pyx_PyLong_CompactValue(x) PyUnstable_Long_CompactValue((PyLongObject*) x) + #else + #define __Pyx_PyLong_IsCompact(x) (((PyLongObject*)x)->long_value.lv_tag < (2 << _PyLong_NON_SIZE_BITS)) + #define __Pyx_PyLong_CompactValue(x) ((1 - (Py_ssize_t) __Pyx_PyLong_Sign(x)) * (Py_ssize_t) __Pyx_PyLong_Digits(x)[0]) + #endif + typedef Py_ssize_t __Pyx_compact_pylong; + typedef size_t __Pyx_compact_upylong; + #else + #define __Pyx_PyLong_IsNeg(x) (Py_SIZE(x) < 0) + #define __Pyx_PyLong_IsNonNeg(x) (Py_SIZE(x) >= 0) + #define __Pyx_PyLong_IsZero(x) (Py_SIZE(x) == 0) + #define __Pyx_PyLong_IsPos(x) (Py_SIZE(x) > 0) + #define __Pyx_PyLong_CompactValueUnsigned(x) ((Py_SIZE(x) == 0) ? 0 : __Pyx_PyLong_Digits(x)[0]) + #define __Pyx_PyLong_DigitCount(x) __Pyx_sst_abs(Py_SIZE(x)) + #define __Pyx_PyLong_SignedDigitCount(x) Py_SIZE(x) + #define __Pyx_PyLong_IsCompact(x) (Py_SIZE(x) == 0 || Py_SIZE(x) == 1 || Py_SIZE(x) == -1) + #define __Pyx_PyLong_CompactValue(x)\ + ((Py_SIZE(x) == 0) ? (sdigit) 0 : ((Py_SIZE(x) < 0) ? -(sdigit)__Pyx_PyLong_Digits(x)[0] : (sdigit)__Pyx_PyLong_Digits(x)[0])) + typedef sdigit __Pyx_compact_pylong; + typedef digit __Pyx_compact_upylong; + #endif + #if PY_VERSION_HEX >= 0x030C00A5 + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->long_value.ob_digit) + #else + #define __Pyx_PyLong_Digits(x) (((PyLongObject*)x)->ob_digit) + #endif +#endif +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII +#include +static int __Pyx_sys_getdefaultencoding_not_ascii; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + PyObject* ascii_chars_u = NULL; + PyObject* ascii_chars_b = NULL; + const char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + if (strcmp(default_encoding_c, "ascii") == 0) { + __Pyx_sys_getdefaultencoding_not_ascii = 0; + } else { + char ascii_chars[128]; + int c; + for (c = 0; c < 128; c++) { + ascii_chars[c] = (char) c; + } + __Pyx_sys_getdefaultencoding_not_ascii = 1; + ascii_chars_u = PyUnicode_DecodeASCII(ascii_chars, 128, NULL); + if (!ascii_chars_u) goto bad; + ascii_chars_b = PyUnicode_AsEncodedString(ascii_chars_u, default_encoding_c, NULL); + if (!ascii_chars_b || !PyBytes_Check(ascii_chars_b) || memcmp(ascii_chars, PyBytes_AS_STRING(ascii_chars_b), 128) != 0) { + PyErr_Format( + PyExc_ValueError, + "This module compiled with c_string_encoding=ascii, but default encoding '%.200s' is not a superset of ascii.", + default_encoding_c); + goto bad; + } + Py_DECREF(ascii_chars_u); + Py_DECREF(ascii_chars_b); + } + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + Py_XDECREF(ascii_chars_u); + Py_XDECREF(ascii_chars_b); + return -1; +} +#endif +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT && PY_MAJOR_VERSION >= 3 +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_DecodeUTF8(c_str, size, NULL) +#else +#define __Pyx_PyUnicode_FromStringAndSize(c_str, size) PyUnicode_Decode(c_str, size, __PYX_DEFAULT_STRING_ENCODING, NULL) +#if __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +#include +static char* __PYX_DEFAULT_STRING_ENCODING; +static int __Pyx_init_sys_getdefaultencoding_params(void) { + PyObject* sys; + PyObject* default_encoding = NULL; + char* default_encoding_c; + sys = PyImport_ImportModule("sys"); + if (!sys) goto bad; + default_encoding = PyObject_CallMethod(sys, (char*) (const char*) "getdefaultencoding", NULL); + Py_DECREF(sys); + if (!default_encoding) goto bad; + default_encoding_c = PyBytes_AsString(default_encoding); + if (!default_encoding_c) goto bad; + __PYX_DEFAULT_STRING_ENCODING = (char*) malloc(strlen(default_encoding_c) + 1); + if (!__PYX_DEFAULT_STRING_ENCODING) goto bad; + strcpy(__PYX_DEFAULT_STRING_ENCODING, default_encoding_c); + Py_DECREF(default_encoding); + return 0; +bad: + Py_XDECREF(default_encoding); + return -1; +} +#endif +#endif + + +/* Test for GCC > 2.95 */ +#if defined(__GNUC__) && (__GNUC__ > 2 || (__GNUC__ == 2 && (__GNUC_MINOR__ > 95))) + #define likely(x) __builtin_expect(!!(x), 1) + #define unlikely(x) __builtin_expect(!!(x), 0) +#else /* !__GNUC__ or GCC < 2.95 */ + #define likely(x) (x) + #define unlikely(x) (x) +#endif /* __GNUC__ */ +static CYTHON_INLINE void __Pyx_pretend_to_initialize(void* ptr) { (void)ptr; } + +#if !CYTHON_USE_MODULE_STATE +static PyObject *__pyx_m = NULL; +#endif +static int __pyx_lineno; +static int __pyx_clineno = 0; +static const char * __pyx_cfilenm = __FILE__; +static const char *__pyx_filename; + +/* #### Code section: filename_table ### */ + +static const char *__pyx_f[] = { + "", + "selfdrive/modeld/runners/thneedmodel_pyx.pyx", + "cereal/visionipc/visionipc_pyx.pxd", + "selfdrive/modeld/models/commonmodel_pyx.pxd", +}; +/* #### Code section: utility_code_proto_before_types ### */ +/* ForceInitThreads.proto */ +#ifndef __PYX_FORCE_INIT_THREADS + #define __PYX_FORCE_INIT_THREADS 0 +#endif + +/* NoFastGil.proto */ +#define __Pyx_PyGILState_Ensure PyGILState_Ensure +#define __Pyx_PyGILState_Release PyGILState_Release +#define __Pyx_FastGIL_Remember() +#define __Pyx_FastGIL_Forget() +#define __Pyx_FastGilFuncInit() + +/* BufferFormatStructs.proto */ +struct __Pyx_StructField_; +#define __PYX_BUF_FLAGS_PACKED_STRUCT (1 << 0) +typedef struct { + const char* name; + struct __Pyx_StructField_* fields; + size_t size; + size_t arraysize[8]; + int ndim; + char typegroup; + char is_unsigned; + int flags; +} __Pyx_TypeInfo; +typedef struct __Pyx_StructField_ { + __Pyx_TypeInfo* type; + const char* name; + size_t offset; +} __Pyx_StructField; +typedef struct { + __Pyx_StructField* field; + size_t parent_offset; +} __Pyx_BufFmt_StackElem; +typedef struct { + __Pyx_StructField root; + __Pyx_BufFmt_StackElem* head; + size_t fmt_offset; + size_t new_count, enc_count; + size_t struct_alignment; + int is_complex; + char enc_type; + char new_packmode; + char enc_packmode; + char is_valid_array; +} __Pyx_BufFmt_Context; + +/* Atomics.proto */ +#include +#ifndef CYTHON_ATOMICS + #define CYTHON_ATOMICS 1 +#endif +#define __PYX_CYTHON_ATOMICS_ENABLED() CYTHON_ATOMICS +#define __pyx_atomic_int_type int +#define __pyx_nonatomic_int_type int +#if CYTHON_ATOMICS && (defined(__STDC_VERSION__) &&\ + (__STDC_VERSION__ >= 201112L) &&\ + !defined(__STDC_NO_ATOMICS__)) + #include +#elif CYTHON_ATOMICS && (defined(__cplusplus) && (\ + (__cplusplus >= 201103L) ||\ + (defined(_MSC_VER) && _MSC_VER >= 1700))) + #include +#endif +#if CYTHON_ATOMICS && (defined(__STDC_VERSION__) &&\ + (__STDC_VERSION__ >= 201112L) &&\ + !defined(__STDC_NO_ATOMICS__) &&\ + ATOMIC_INT_LOCK_FREE == 2) + #undef __pyx_atomic_int_type + #define __pyx_atomic_int_type atomic_int + #define __pyx_atomic_incr_aligned(value) atomic_fetch_add_explicit(value, 1, memory_order_relaxed) + #define __pyx_atomic_decr_aligned(value) atomic_fetch_sub_explicit(value, 1, memory_order_acq_rel) + #if defined(__PYX_DEBUG_ATOMICS) && defined(_MSC_VER) + #pragma message ("Using standard C atomics") + #elif defined(__PYX_DEBUG_ATOMICS) + #warning "Using standard C atomics" + #endif +#elif CYTHON_ATOMICS && (defined(__cplusplus) && (\ + (__cplusplus >= 201103L) ||\ +\ + (defined(_MSC_VER) && _MSC_VER >= 1700)) &&\ + ATOMIC_INT_LOCK_FREE == 2) + #undef __pyx_atomic_int_type + #define __pyx_atomic_int_type std::atomic_int + #define __pyx_atomic_incr_aligned(value) std::atomic_fetch_add_explicit(value, 1, std::memory_order_relaxed) + #define __pyx_atomic_decr_aligned(value) std::atomic_fetch_sub_explicit(value, 1, std::memory_order_acq_rel) + #if defined(__PYX_DEBUG_ATOMICS) && defined(_MSC_VER) + #pragma message ("Using standard C++ atomics") + #elif defined(__PYX_DEBUG_ATOMICS) + #warning "Using standard C++ atomics" + #endif +#elif CYTHON_ATOMICS && (__GNUC__ >= 5 || (__GNUC__ == 4 &&\ + (__GNUC_MINOR__ > 1 ||\ + (__GNUC_MINOR__ == 1 && __GNUC_PATCHLEVEL__ >= 2)))) + #define __pyx_atomic_incr_aligned(value) __sync_fetch_and_add(value, 1) + #define __pyx_atomic_decr_aligned(value) __sync_fetch_and_sub(value, 1) + #ifdef __PYX_DEBUG_ATOMICS + #warning "Using GNU atomics" + #endif +#elif CYTHON_ATOMICS && defined(_MSC_VER) + #include + #undef __pyx_atomic_int_type + #define __pyx_atomic_int_type long + #undef __pyx_nonatomic_int_type + #define __pyx_nonatomic_int_type long + #pragma intrinsic (_InterlockedExchangeAdd) + #define __pyx_atomic_incr_aligned(value) _InterlockedExchangeAdd(value, 1) + #define __pyx_atomic_decr_aligned(value) _InterlockedExchangeAdd(value, -1) + #ifdef __PYX_DEBUG_ATOMICS + #pragma message ("Using MSVC atomics") + #endif +#else + #undef CYTHON_ATOMICS + #define CYTHON_ATOMICS 0 + #ifdef __PYX_DEBUG_ATOMICS + #warning "Not using atomics" + #endif +#endif +#if CYTHON_ATOMICS + #define __pyx_add_acquisition_count(memview)\ + __pyx_atomic_incr_aligned(__pyx_get_slice_count_pointer(memview)) + #define __pyx_sub_acquisition_count(memview)\ + __pyx_atomic_decr_aligned(__pyx_get_slice_count_pointer(memview)) +#else + #define __pyx_add_acquisition_count(memview)\ + __pyx_add_acquisition_count_locked(__pyx_get_slice_count_pointer(memview), memview->lock) + #define __pyx_sub_acquisition_count(memview)\ + __pyx_sub_acquisition_count_locked(__pyx_get_slice_count_pointer(memview), memview->lock) +#endif + +/* MemviewSliceStruct.proto */ +struct __pyx_memoryview_obj; +typedef struct { + struct __pyx_memoryview_obj *memview; + char *data; + Py_ssize_t shape[8]; + Py_ssize_t strides[8]; + Py_ssize_t suboffsets[8]; +} __Pyx_memviewslice; +#define __Pyx_MemoryView_Len(m) (m.shape[0]) + +/* #### Code section: numeric_typedefs ### */ +/* #### Code section: complex_type_declarations ### */ +/* #### Code section: type_declarations ### */ + +/*--- Type declarations ---*/ +struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_CLContext; +struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf; +struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext; +struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem; +struct __pyx_obj_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel; +struct __pyx_obj_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel; +struct __pyx_array_obj; +struct __pyx_MemviewEnum_obj; +struct __pyx_memoryview_obj; +struct __pyx_memoryviewslice_obj; + +/* "cereal/visionipc/visionipc_pyx.pxd":7 + * from .visionipc cimport cl_device_id, cl_context + * + * cdef class CLContext: # <<<<<<<<<<<<<< + * cdef cl_device_id device_id + * cdef cl_context context + */ +struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_CLContext { + PyObject_HEAD + cl_device_id device_id; + cl_context context; +}; + + +/* "cereal/visionipc/visionipc_pyx.pxd":11 + * cdef cl_context context + * + * cdef class VisionBuf: # <<<<<<<<<<<<<< + * cdef cppVisionBuf * buf + * + */ +struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf { + PyObject_HEAD + struct __pyx_vtabstruct_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_vtab; + VisionBuf *buf; +}; + + +/* "selfdrive/modeld/models/commonmodel_pyx.pxd":6 + * from cereal.visionipc.visionipc_pyx cimport CLContext as BaseCLContext + * + * cdef class CLContext(BaseCLContext): # <<<<<<<<<<<<<< + * pass + * + */ +struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext { + struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_CLContext __pyx_base; +}; + + +/* "selfdrive/modeld/models/commonmodel_pyx.pxd":9 + * pass + * + * cdef class CLMem: # <<<<<<<<<<<<<< + * cdef cl_mem * mem + * + */ +struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem { + PyObject_HEAD + struct __pyx_vtabstruct_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem *__pyx_vtab; + cl_mem *mem; +}; + + +/* "selfdrive/modeld/runners/runmodel_pyx.pxd":5 + * from .runmodel cimport RunModel as cppRunModel + * + * cdef class RunModel: # <<<<<<<<<<<<<< + * cdef cppRunModel * model + */ +struct __pyx_obj_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel { + PyObject_HEAD + RunModel *model; +}; + + +/* "selfdrive/modeld/runners/thneedmodel_pyx.pyx":12 + * from selfdrive.modeld.runners.runmodel cimport RunModel as cppRunModel + * + * cdef class ThneedModel(RunModel): # <<<<<<<<<<<<<< + * def __cinit__(self, string path, float[:] output, int runtime, bool use_tf8, CLContext context): + * self.model = new cppThneedModel(path, &output[0], len(output), runtime, use_tf8, context.context) + */ +struct __pyx_obj_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel { + struct __pyx_obj_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel __pyx_base; +}; + + +/* "View.MemoryView":114 + * @cython.collection_type("sequence") + * @cname("__pyx_array") + * cdef class array: # <<<<<<<<<<<<<< + * + * cdef: + */ +struct __pyx_array_obj { + PyObject_HEAD + struct __pyx_vtabstruct_array *__pyx_vtab; + char *data; + Py_ssize_t len; + char *format; + int ndim; + Py_ssize_t *_shape; + Py_ssize_t *_strides; + Py_ssize_t itemsize; + PyObject *mode; + PyObject *_format; + void (*callback_free_data)(void *); + int free_data; + int dtype_is_object; +}; + + +/* "View.MemoryView":302 + * + * @cname('__pyx_MemviewEnum') + * cdef class Enum(object): # <<<<<<<<<<<<<< + * cdef object name + * def __init__(self, name): + */ +struct __pyx_MemviewEnum_obj { + PyObject_HEAD + PyObject *name; +}; + + +/* "View.MemoryView":337 + * + * @cname('__pyx_memoryview') + * cdef class memoryview: # <<<<<<<<<<<<<< + * + * cdef object obj + */ +struct __pyx_memoryview_obj { + PyObject_HEAD + struct __pyx_vtabstruct_memoryview *__pyx_vtab; + PyObject *obj; + PyObject *_size; + PyObject *_array_interface; + PyThread_type_lock lock; + __pyx_atomic_int_type acquisition_count; + Py_buffer view; + int flags; + int dtype_is_object; + __Pyx_TypeInfo *typeinfo; +}; + + +/* "View.MemoryView":952 + * @cython.collection_type("sequence") + * @cname('__pyx_memoryviewslice') + * cdef class _memoryviewslice(memoryview): # <<<<<<<<<<<<<< + * "Internal class for passing memoryview slices to Python" + * + */ +struct __pyx_memoryviewslice_obj { + struct __pyx_memoryview_obj __pyx_base; + __Pyx_memviewslice from_slice; + PyObject *from_object; + PyObject *(*to_object_func)(char *); + int (*to_dtype_func)(char *, PyObject *); +}; + + + +/* "cereal/visionipc/visionipc_pyx.pxd":11 + * cdef cl_context context + * + * cdef class VisionBuf: # <<<<<<<<<<<<<< + * cdef cppVisionBuf * buf + * + */ + +struct __pyx_vtabstruct_6cereal_9visionipc_13visionipc_pyx_VisionBuf { + PyObject *(*create)(VisionBuf *); +}; +static struct __pyx_vtabstruct_6cereal_9visionipc_13visionipc_pyx_VisionBuf *__pyx_vtabptr_6cereal_9visionipc_13visionipc_pyx_VisionBuf; + + +/* "selfdrive/modeld/models/commonmodel_pyx.pxd":9 + * pass + * + * cdef class CLMem: # <<<<<<<<<<<<<< + * cdef cl_mem * mem + * + */ + +struct __pyx_vtabstruct_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem { + PyObject *(*create)(void *); +}; +static struct __pyx_vtabstruct_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem *__pyx_vtabptr_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem; + + +/* "View.MemoryView":114 + * @cython.collection_type("sequence") + * @cname("__pyx_array") + * cdef class array: # <<<<<<<<<<<<<< + * + * cdef: + */ + +struct __pyx_vtabstruct_array { + PyObject *(*get_memview)(struct __pyx_array_obj *); +}; +static struct __pyx_vtabstruct_array *__pyx_vtabptr_array; + + +/* "View.MemoryView":337 + * + * @cname('__pyx_memoryview') + * cdef class memoryview: # <<<<<<<<<<<<<< + * + * cdef object obj + */ + +struct __pyx_vtabstruct_memoryview { + char *(*get_item_pointer)(struct __pyx_memoryview_obj *, PyObject *); + PyObject *(*is_slice)(struct __pyx_memoryview_obj *, PyObject *); + PyObject *(*setitem_slice_assignment)(struct __pyx_memoryview_obj *, PyObject *, PyObject *); + PyObject *(*setitem_slice_assign_scalar)(struct __pyx_memoryview_obj *, struct __pyx_memoryview_obj *, PyObject *); + PyObject *(*setitem_indexed)(struct __pyx_memoryview_obj *, PyObject *, PyObject *); + PyObject *(*convert_item_to_object)(struct __pyx_memoryview_obj *, char *); + PyObject *(*assign_item_from_object)(struct __pyx_memoryview_obj *, char *, PyObject *); + PyObject *(*_get_base)(struct __pyx_memoryview_obj *); +}; +static struct __pyx_vtabstruct_memoryview *__pyx_vtabptr_memoryview; + + +/* "View.MemoryView":952 + * @cython.collection_type("sequence") + * @cname('__pyx_memoryviewslice') + * cdef class _memoryviewslice(memoryview): # <<<<<<<<<<<<<< + * "Internal class for passing memoryview slices to Python" + * + */ + +struct __pyx_vtabstruct__memoryviewslice { + struct __pyx_vtabstruct_memoryview __pyx_base; +}; +static struct __pyx_vtabstruct__memoryviewslice *__pyx_vtabptr__memoryviewslice; +/* #### Code section: utility_code_proto ### */ + +/* --- Runtime support code (head) --- */ +/* Refnanny.proto */ +#ifndef CYTHON_REFNANNY + #define CYTHON_REFNANNY 0 +#endif +#if CYTHON_REFNANNY + typedef struct { + void (*INCREF)(void*, PyObject*, Py_ssize_t); + void (*DECREF)(void*, PyObject*, Py_ssize_t); + void (*GOTREF)(void*, PyObject*, Py_ssize_t); + void (*GIVEREF)(void*, PyObject*, Py_ssize_t); + void* (*SetupContext)(const char*, Py_ssize_t, const char*); + void (*FinishContext)(void**); + } __Pyx_RefNannyAPIStruct; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNanny = NULL; + static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname); + #define __Pyx_RefNannyDeclarations void *__pyx_refnanny = NULL; +#ifdef WITH_THREAD + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + if (acquire_gil) {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + PyGILState_Release(__pyx_gilstate_save);\ + } else {\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__));\ + } + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } +#else + #define __Pyx_RefNannySetupContext(name, acquire_gil)\ + __pyx_refnanny = __Pyx_RefNanny->SetupContext((name), (__LINE__), (__FILE__)) + #define __Pyx_RefNannyFinishContextNogil() __Pyx_RefNannyFinishContext() +#endif + #define __Pyx_RefNannyFinishContextNogil() {\ + PyGILState_STATE __pyx_gilstate_save = PyGILState_Ensure();\ + __Pyx_RefNannyFinishContext();\ + PyGILState_Release(__pyx_gilstate_save);\ + } + #define __Pyx_RefNannyFinishContext()\ + __Pyx_RefNanny->FinishContext(&__pyx_refnanny) + #define __Pyx_INCREF(r) __Pyx_RefNanny->INCREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_DECREF(r) __Pyx_RefNanny->DECREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GOTREF(r) __Pyx_RefNanny->GOTREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_GIVEREF(r) __Pyx_RefNanny->GIVEREF(__pyx_refnanny, (PyObject *)(r), (__LINE__)) + #define __Pyx_XINCREF(r) do { if((r) == NULL); else {__Pyx_INCREF(r); }} while(0) + #define __Pyx_XDECREF(r) do { if((r) == NULL); else {__Pyx_DECREF(r); }} while(0) + #define __Pyx_XGOTREF(r) do { if((r) == NULL); else {__Pyx_GOTREF(r); }} while(0) + #define __Pyx_XGIVEREF(r) do { if((r) == NULL); else {__Pyx_GIVEREF(r);}} while(0) +#else + #define __Pyx_RefNannyDeclarations + #define __Pyx_RefNannySetupContext(name, acquire_gil) + #define __Pyx_RefNannyFinishContextNogil() + #define __Pyx_RefNannyFinishContext() + #define __Pyx_INCREF(r) Py_INCREF(r) + #define __Pyx_DECREF(r) Py_DECREF(r) + #define __Pyx_GOTREF(r) + #define __Pyx_GIVEREF(r) + #define __Pyx_XINCREF(r) Py_XINCREF(r) + #define __Pyx_XDECREF(r) Py_XDECREF(r) + #define __Pyx_XGOTREF(r) + #define __Pyx_XGIVEREF(r) +#endif +#define __Pyx_Py_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; Py_XDECREF(tmp);\ + } while (0) +#define __Pyx_XDECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_XDECREF(tmp);\ + } while (0) +#define __Pyx_DECREF_SET(r, v) do {\ + PyObject *tmp = (PyObject *) r;\ + r = v; __Pyx_DECREF(tmp);\ + } while (0) +#define __Pyx_CLEAR(r) do { PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);} while(0) +#define __Pyx_XCLEAR(r) do { if((r) != NULL) {PyObject* tmp = ((PyObject*)(r)); r = NULL; __Pyx_DECREF(tmp);}} while(0) + +/* PyErrExceptionMatches.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_ExceptionMatches(err) __Pyx_PyErr_ExceptionMatchesInState(__pyx_tstate, err) +static CYTHON_INLINE int __Pyx_PyErr_ExceptionMatchesInState(PyThreadState* tstate, PyObject* err); +#else +#define __Pyx_PyErr_ExceptionMatches(err) PyErr_ExceptionMatches(err) +#endif + +/* PyThreadStateGet.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyThreadState_declare PyThreadState *__pyx_tstate; +#define __Pyx_PyThreadState_assign __pyx_tstate = __Pyx_PyThreadState_Current; +#if PY_VERSION_HEX >= 0x030C00A6 +#define __Pyx_PyErr_Occurred() (__pyx_tstate->current_exception != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->current_exception ? (PyObject*) Py_TYPE(__pyx_tstate->current_exception) : (PyObject*) NULL) +#else +#define __Pyx_PyErr_Occurred() (__pyx_tstate->curexc_type != NULL) +#define __Pyx_PyErr_CurrentExceptionType() (__pyx_tstate->curexc_type) +#endif +#else +#define __Pyx_PyThreadState_declare +#define __Pyx_PyThreadState_assign +#define __Pyx_PyErr_Occurred() (PyErr_Occurred() != NULL) +#define __Pyx_PyErr_CurrentExceptionType() PyErr_Occurred() +#endif + +/* PyErrFetchRestore.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_PyErr_Clear() __Pyx_ErrRestore(NULL, NULL, NULL) +#define __Pyx_ErrRestoreWithState(type, value, tb) __Pyx_ErrRestoreInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) __Pyx_ErrFetchInState(PyThreadState_GET(), type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) __Pyx_ErrRestoreInState(__pyx_tstate, type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) __Pyx_ErrFetchInState(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb); +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A6 +#define __Pyx_PyErr_SetNone(exc) (Py_INCREF(exc), __Pyx_ErrRestore((exc), NULL, NULL)) +#else +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#endif +#else +#define __Pyx_PyErr_Clear() PyErr_Clear() +#define __Pyx_PyErr_SetNone(exc) PyErr_SetNone(exc) +#define __Pyx_ErrRestoreWithState(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchWithState(type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestoreInState(tstate, type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetchInState(tstate, type, value, tb) PyErr_Fetch(type, value, tb) +#define __Pyx_ErrRestore(type, value, tb) PyErr_Restore(type, value, tb) +#define __Pyx_ErrFetch(type, value, tb) PyErr_Fetch(type, value, tb) +#endif + +/* PyObjectGetAttrStr.proto */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GetAttrStr(o,n) PyObject_GetAttr(o,n) +#endif + +/* PyObjectGetAttrStrNoError.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name); + +/* GetBuiltinName.proto */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name); + +/* TupleAndListFromArray.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n); +static CYTHON_INLINE PyObject* __Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n); +#endif + +/* IncludeStringH.proto */ +#include + +/* BytesEquals.proto */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals); + +/* UnicodeEquals.proto */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals); + +/* fastcall.proto */ +#if CYTHON_AVOID_BORROWED_REFS + #define __Pyx_Arg_VARARGS(args, i) PySequence_GetItem(args, i) +#elif CYTHON_ASSUME_SAFE_MACROS + #define __Pyx_Arg_VARARGS(args, i) PyTuple_GET_ITEM(args, i) +#else + #define __Pyx_Arg_VARARGS(args, i) PyTuple_GetItem(args, i) +#endif +#if CYTHON_AVOID_BORROWED_REFS + #define __Pyx_Arg_NewRef_VARARGS(arg) __Pyx_NewRef(arg) + #define __Pyx_Arg_XDECREF_VARARGS(arg) Py_XDECREF(arg) +#else + #define __Pyx_Arg_NewRef_VARARGS(arg) arg + #define __Pyx_Arg_XDECREF_VARARGS(arg) +#endif +#define __Pyx_NumKwargs_VARARGS(kwds) PyDict_Size(kwds) +#define __Pyx_KwValues_VARARGS(args, nargs) NULL +#define __Pyx_GetKwValue_VARARGS(kw, kwvalues, s) __Pyx_PyDict_GetItemStrWithError(kw, s) +#define __Pyx_KwargsAsDict_VARARGS(kw, kwvalues) PyDict_Copy(kw) +#if CYTHON_METH_FASTCALL + #define __Pyx_Arg_FASTCALL(args, i) args[i] + #define __Pyx_NumKwargs_FASTCALL(kwds) PyTuple_GET_SIZE(kwds) + #define __Pyx_KwValues_FASTCALL(args, nargs) ((args) + (nargs)) + static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s); +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 + CYTHON_UNUSED static PyObject *__Pyx_KwargsAsDict_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues); + #else + #define __Pyx_KwargsAsDict_FASTCALL(kw, kwvalues) _PyStack_AsDict(kwvalues, kw) + #endif + #define __Pyx_Arg_NewRef_FASTCALL(arg) arg /* no-op, __Pyx_Arg_FASTCALL is direct and this needs + to have the same reference counting */ + #define __Pyx_Arg_XDECREF_FASTCALL(arg) +#else + #define __Pyx_Arg_FASTCALL __Pyx_Arg_VARARGS + #define __Pyx_NumKwargs_FASTCALL __Pyx_NumKwargs_VARARGS + #define __Pyx_KwValues_FASTCALL __Pyx_KwValues_VARARGS + #define __Pyx_GetKwValue_FASTCALL __Pyx_GetKwValue_VARARGS + #define __Pyx_KwargsAsDict_FASTCALL __Pyx_KwargsAsDict_VARARGS + #define __Pyx_Arg_NewRef_FASTCALL(arg) __Pyx_Arg_NewRef_VARARGS(arg) + #define __Pyx_Arg_XDECREF_FASTCALL(arg) __Pyx_Arg_XDECREF_VARARGS(arg) +#endif +#if CYTHON_COMPILING_IN_CPYTHON && CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_VARARGS(args, start), stop - start) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) __Pyx_PyTuple_FromArray(&__Pyx_Arg_FASTCALL(args, start), stop - start) +#else +#define __Pyx_ArgsSlice_VARARGS(args, start, stop) PyTuple_GetSlice(args, start, stop) +#define __Pyx_ArgsSlice_FASTCALL(args, start, stop) PyTuple_GetSlice(args, start, stop) +#endif + +/* RaiseArgTupleInvalid.proto */ +static void __Pyx_RaiseArgtupleInvalid(const char* func_name, int exact, + Py_ssize_t num_min, Py_ssize_t num_max, Py_ssize_t num_found); + +/* RaiseDoubleKeywords.proto */ +static void __Pyx_RaiseDoubleKeywordsError(const char* func_name, PyObject* kw_name); + +/* ParseKeywords.proto */ +static int __Pyx_ParseOptionalKeywords(PyObject *kwds, PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, PyObject *values[], Py_ssize_t num_pos_args, + const char* function_name); + +/* ArgTypeTest.proto */ +#define __Pyx_ArgTypeTest(obj, type, none_allowed, name, exact)\ + ((likely(__Pyx_IS_TYPE(obj, type) | (none_allowed && (obj == Py_None)))) ? 1 :\ + __Pyx__ArgTypeTest(obj, type, name, exact)) +static int __Pyx__ArgTypeTest(PyObject *obj, PyTypeObject *type, const char *name, int exact); + +/* RaiseException.proto */ +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause); + +/* PyFunctionFastCall.proto */ +#if CYTHON_FAST_PYCALL +#if !CYTHON_VECTORCALL +#define __Pyx_PyFunction_FastCall(func, args, nargs)\ + __Pyx_PyFunction_FastCallDict((func), (args), (nargs), NULL) +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs); +#endif +#define __Pyx_BUILD_ASSERT_EXPR(cond)\ + (sizeof(char [1 - 2*!(cond)]) - 1) +#ifndef Py_MEMBER_SIZE +#define Py_MEMBER_SIZE(type, member) sizeof(((type *)0)->member) +#endif +#if !CYTHON_VECTORCALL +#if PY_VERSION_HEX >= 0x03080000 + #include "frameobject.h" +#if PY_VERSION_HEX >= 0x030b00a6 && !CYTHON_COMPILING_IN_LIMITED_API + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif + #define __Pxy_PyFrame_Initialize_Offsets() + #define __Pyx_PyFrame_GetLocalsplus(frame) ((frame)->f_localsplus) +#else + static size_t __pyx_pyframe_localsplus_offset = 0; + #include "frameobject.h" + #define __Pxy_PyFrame_Initialize_Offsets()\ + ((void)__Pyx_BUILD_ASSERT_EXPR(sizeof(PyFrameObject) == offsetof(PyFrameObject, f_localsplus) + Py_MEMBER_SIZE(PyFrameObject, f_localsplus)),\ + (void)(__pyx_pyframe_localsplus_offset = ((size_t)PyFrame_Type.tp_basicsize) - Py_MEMBER_SIZE(PyFrameObject, f_localsplus))) + #define __Pyx_PyFrame_GetLocalsplus(frame)\ + (assert(__pyx_pyframe_localsplus_offset), (PyObject **)(((char *)(frame)) + __pyx_pyframe_localsplus_offset)) +#endif +#endif +#endif + +/* PyObjectCall.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw); +#else +#define __Pyx_PyObject_Call(func, arg, kw) PyObject_Call(func, arg, kw) +#endif + +/* PyObjectCallMethO.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg); +#endif + +/* PyObjectFastCall.proto */ +#define __Pyx_PyObject_FastCall(func, args, nargs) __Pyx_PyObject_FastCallDict(func, args, (size_t)(nargs), NULL) +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs); + +/* RaiseUnexpectedTypeError.proto */ +static int __Pyx_RaiseUnexpectedTypeError(const char *expected, PyObject *obj); + +/* GCCDiagnostics.proto */ +#if !defined(__INTEL_COMPILER) && defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 6)) +#define __Pyx_HAS_GCC_DIAGNOSTIC +#endif + +/* BuildPyUnicode.proto */ +static PyObject* __Pyx_PyUnicode_BuildFromAscii(Py_ssize_t ulength, char* chars, int clength, + int prepend_sign, char padding_char); + +/* CIntToPyUnicode.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_int(int value, Py_ssize_t width, char padding_char, char format_char); + +/* CIntToPyUnicode.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_Py_ssize_t(Py_ssize_t value, Py_ssize_t width, char padding_char, char format_char); + +/* JoinPyUnicode.proto */ +static PyObject* __Pyx_PyUnicode_Join(PyObject* value_tuple, Py_ssize_t value_count, Py_ssize_t result_ulength, + Py_UCS4 max_char); + +/* StrEquals.proto */ +#if PY_MAJOR_VERSION >= 3 +#define __Pyx_PyString_Equals __Pyx_PyUnicode_Equals +#else +#define __Pyx_PyString_Equals __Pyx_PyBytes_Equals +#endif + +/* PyObjectFormatSimple.proto */ +#if CYTHON_COMPILING_IN_PYPY + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + PyObject_Format(s, f)) +#elif PY_MAJOR_VERSION < 3 + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + likely(PyString_CheckExact(s)) ? PyUnicode_FromEncodedObject(s, NULL, "strict") :\ + PyObject_Format(s, f)) +#elif CYTHON_USE_TYPE_SLOTS + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + likely(PyLong_CheckExact(s)) ? PyLong_Type.tp_repr(s) :\ + likely(PyFloat_CheckExact(s)) ? PyFloat_Type.tp_repr(s) :\ + PyObject_Format(s, f)) +#else + #define __Pyx_PyObject_FormatSimple(s, f) (\ + likely(PyUnicode_CheckExact(s)) ? (Py_INCREF(s), s) :\ + PyObject_Format(s, f)) +#endif + +CYTHON_UNUSED static int __pyx_array_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +static PyObject *__pyx_array_get_memview(struct __pyx_array_obj *); /*proto*/ +/* GetAttr.proto */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr(PyObject *, PyObject *); + +/* GetItemInt.proto */ +#define __Pyx_GetItemInt(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_Fast(o, (Py_ssize_t)i, is_list, wraparound, boundscheck) :\ + (is_list ? (PyErr_SetString(PyExc_IndexError, "list index out of range"), (PyObject*)NULL) :\ + __Pyx_GetItemInt_Generic(o, to_py_func(i)))) +#define __Pyx_GetItemInt_List(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_List_Fast(o, (Py_ssize_t)i, wraparound, boundscheck) :\ + (PyErr_SetString(PyExc_IndexError, "list index out of range"), (PyObject*)NULL)) +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_List_Fast(PyObject *o, Py_ssize_t i, + int wraparound, int boundscheck); +#define __Pyx_GetItemInt_Tuple(o, i, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_GetItemInt_Tuple_Fast(o, (Py_ssize_t)i, wraparound, boundscheck) :\ + (PyErr_SetString(PyExc_IndexError, "tuple index out of range"), (PyObject*)NULL)) +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Tuple_Fast(PyObject *o, Py_ssize_t i, + int wraparound, int boundscheck); +static PyObject *__Pyx_GetItemInt_Generic(PyObject *o, PyObject* j); +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Fast(PyObject *o, Py_ssize_t i, + int is_list, int wraparound, int boundscheck); + +/* PyObjectCallOneArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg); + +/* ObjectGetItem.proto */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject *__Pyx_PyObject_GetItem(PyObject *obj, PyObject *key); +#else +#define __Pyx_PyObject_GetItem(obj, key) PyObject_GetItem(obj, key) +#endif + +/* KeywordStringCheck.proto */ +static int __Pyx_CheckKeywordStrings(PyObject *kw, const char* function_name, int kw_allowed); + +/* DivInt[Py_ssize_t].proto */ +static CYTHON_INLINE Py_ssize_t __Pyx_div_Py_ssize_t(Py_ssize_t, Py_ssize_t); + +/* UnaryNegOverflows.proto */ +#define __Pyx_UNARY_NEG_WOULD_OVERFLOW(x)\ + (((x) < 0) & ((unsigned long)(x) == 0-(unsigned long)(x))) + +/* GetAttr3.proto */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr3(PyObject *, PyObject *, PyObject *); + +/* PyDictVersioning.proto */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +#define __PYX_DICT_VERSION_INIT ((PY_UINT64_T) -1) +#define __PYX_GET_DICT_VERSION(dict) (((PyDictObject*)(dict))->ma_version_tag) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var)\ + (version_var) = __PYX_GET_DICT_VERSION(dict);\ + (cache_var) = (value); +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + if (likely(__PYX_GET_DICT_VERSION(DICT) == __pyx_dict_version)) {\ + (VAR) = __pyx_dict_cached_value;\ + } else {\ + (VAR) = __pyx_dict_cached_value = (LOOKUP);\ + __pyx_dict_version = __PYX_GET_DICT_VERSION(DICT);\ + }\ +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj); +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj); +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version); +#else +#define __PYX_GET_DICT_VERSION(dict) (0) +#define __PYX_UPDATE_DICT_CACHE(dict, value, cache_var, version_var) +#define __PYX_PY_DICT_LOOKUP_IF_MODIFIED(VAR, DICT, LOOKUP) (VAR) = (LOOKUP); +#endif + +/* GetModuleGlobalName.proto */ +#if CYTHON_USE_DICT_VERSIONS +#define __Pyx_GetModuleGlobalName(var, name) do {\ + static PY_UINT64_T __pyx_dict_version = 0;\ + static PyObject *__pyx_dict_cached_value = NULL;\ + (var) = (likely(__pyx_dict_version == __PYX_GET_DICT_VERSION(__pyx_d))) ?\ + (likely(__pyx_dict_cached_value) ? __Pyx_NewRef(__pyx_dict_cached_value) : __Pyx_GetBuiltinName(name)) :\ + __Pyx__GetModuleGlobalName(name, &__pyx_dict_version, &__pyx_dict_cached_value);\ +} while(0) +#define __Pyx_GetModuleGlobalNameUncached(var, name) do {\ + PY_UINT64_T __pyx_dict_version;\ + PyObject *__pyx_dict_cached_value;\ + (var) = __Pyx__GetModuleGlobalName(name, &__pyx_dict_version, &__pyx_dict_cached_value);\ +} while(0) +static PyObject *__Pyx__GetModuleGlobalName(PyObject *name, PY_UINT64_T *dict_version, PyObject **dict_cached_value); +#else +#define __Pyx_GetModuleGlobalName(var, name) (var) = __Pyx__GetModuleGlobalName(name) +#define __Pyx_GetModuleGlobalNameUncached(var, name) (var) = __Pyx__GetModuleGlobalName(name) +static CYTHON_INLINE PyObject *__Pyx__GetModuleGlobalName(PyObject *name); +#endif + +/* AssertionsEnabled.proto */ +#if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX < 0x02070600 && !defined(Py_OptimizeFlag) + #define __Pyx_init_assertions_enabled() (0) + #define __pyx_assertions_enabled() (1) +#elif CYTHON_COMPILING_IN_LIMITED_API || (CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030C0000) + static int __pyx_assertions_enabled_flag; + #define __pyx_assertions_enabled() (__pyx_assertions_enabled_flag) + static int __Pyx_init_assertions_enabled(void) { + PyObject *builtins, *debug, *debug_str; + int flag; + builtins = PyEval_GetBuiltins(); + if (!builtins) goto bad; + debug_str = PyUnicode_FromStringAndSize("__debug__", 9); + if (!debug_str) goto bad; + debug = PyObject_GetItem(builtins, debug_str); + Py_DECREF(debug_str); + if (!debug) goto bad; + flag = PyObject_IsTrue(debug); + Py_DECREF(debug); + if (flag == -1) goto bad; + __pyx_assertions_enabled_flag = flag; + return 0; + bad: + __pyx_assertions_enabled_flag = 1; + return -1; + } +#else + #define __Pyx_init_assertions_enabled() (0) + #define __pyx_assertions_enabled() (!Py_OptimizeFlag) +#endif + +/* RaiseTooManyValuesToUnpack.proto */ +static CYTHON_INLINE void __Pyx_RaiseTooManyValuesError(Py_ssize_t expected); + +/* RaiseNeedMoreValuesToUnpack.proto */ +static CYTHON_INLINE void __Pyx_RaiseNeedMoreValuesError(Py_ssize_t index); + +/* RaiseNoneIterError.proto */ +static CYTHON_INLINE void __Pyx_RaiseNoneNotIterableError(void); + +/* ExtTypeTest.proto */ +static CYTHON_INLINE int __Pyx_TypeTest(PyObject *obj, PyTypeObject *type); + +/* GetTopmostException.proto */ +#if CYTHON_USE_EXC_INFO_STACK && CYTHON_FAST_THREAD_STATE +static _PyErr_StackItem * __Pyx_PyErr_GetTopmostException(PyThreadState *tstate); +#endif + +/* SaveResetException.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_ExceptionSave(type, value, tb) __Pyx__ExceptionSave(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx__ExceptionSave(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#define __Pyx_ExceptionReset(type, value, tb) __Pyx__ExceptionReset(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx__ExceptionReset(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb); +#else +#define __Pyx_ExceptionSave(type, value, tb) PyErr_GetExcInfo(type, value, tb) +#define __Pyx_ExceptionReset(type, value, tb) PyErr_SetExcInfo(type, value, tb) +#endif + +/* GetException.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_GetException(type, value, tb) __Pyx__GetException(__pyx_tstate, type, value, tb) +static int __Pyx__GetException(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#else +static int __Pyx_GetException(PyObject **type, PyObject **value, PyObject **tb); +#endif + +/* SwapException.proto */ +#if CYTHON_FAST_THREAD_STATE +#define __Pyx_ExceptionSwap(type, value, tb) __Pyx__ExceptionSwap(__pyx_tstate, type, value, tb) +static CYTHON_INLINE void __Pyx__ExceptionSwap(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb); +#else +static CYTHON_INLINE void __Pyx_ExceptionSwap(PyObject **type, PyObject **value, PyObject **tb); +#endif + +/* Import.proto */ +static PyObject *__Pyx_Import(PyObject *name, PyObject *from_list, int level); + +/* ImportDottedModule.proto */ +static PyObject *__Pyx_ImportDottedModule(PyObject *name, PyObject *parts_tuple); +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_ImportDottedModule_WalkParts(PyObject *module, PyObject *name, PyObject *parts_tuple); +#endif + +/* FastTypeChecks.proto */ +#if CYTHON_COMPILING_IN_CPYTHON +#define __Pyx_TypeCheck(obj, type) __Pyx_IsSubtype(Py_TYPE(obj), (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) __Pyx_IsAnySubtype2(Py_TYPE(obj), (PyTypeObject *)type1, (PyTypeObject *)type2) +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches(PyObject *err, PyObject *type); +static CYTHON_INLINE int __Pyx_PyErr_GivenExceptionMatches2(PyObject *err, PyObject *type1, PyObject *type2); +#else +#define __Pyx_TypeCheck(obj, type) PyObject_TypeCheck(obj, (PyTypeObject *)type) +#define __Pyx_TypeCheck2(obj, type1, type2) (PyObject_TypeCheck(obj, (PyTypeObject *)type1) || PyObject_TypeCheck(obj, (PyTypeObject *)type2)) +#define __Pyx_PyErr_GivenExceptionMatches(err, type) PyErr_GivenExceptionMatches(err, type) +#define __Pyx_PyErr_GivenExceptionMatches2(err, type1, type2) (PyErr_GivenExceptionMatches(err, type1) || PyErr_GivenExceptionMatches(err, type2)) +#endif +#define __Pyx_PyErr_ExceptionMatches2(err1, err2) __Pyx_PyErr_GivenExceptionMatches2(__Pyx_PyErr_CurrentExceptionType(), err1, err2) +#define __Pyx_PyException_Check(obj) __Pyx_TypeCheck(obj, PyExc_Exception) + +CYTHON_UNUSED static int __pyx_memoryview_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +/* ListCompAppend.proto */ +#if CYTHON_USE_PYLIST_INTERNALS && CYTHON_ASSUME_SAFE_MACROS +static CYTHON_INLINE int __Pyx_ListComp_Append(PyObject* list, PyObject* x) { + PyListObject* L = (PyListObject*) list; + Py_ssize_t len = Py_SIZE(list); + if (likely(L->allocated > len)) { + Py_INCREF(x); + #if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 + L->ob_item[len] = x; + #else + PyList_SET_ITEM(list, len, x); + #endif + __Pyx_SET_SIZE(list, len + 1); + return 0; + } + return PyList_Append(list, x); +} +#else +#define __Pyx_ListComp_Append(L,x) PyList_Append(L,x) +#endif + +/* PySequenceMultiply.proto */ +#define __Pyx_PySequence_Multiply_Left(mul, seq) __Pyx_PySequence_Multiply(seq, mul) +static CYTHON_INLINE PyObject* __Pyx_PySequence_Multiply(PyObject *seq, Py_ssize_t mul); + +/* SetItemInt.proto */ +#define __Pyx_SetItemInt(o, i, v, type, is_signed, to_py_func, is_list, wraparound, boundscheck)\ + (__Pyx_fits_Py_ssize_t(i, type, is_signed) ?\ + __Pyx_SetItemInt_Fast(o, (Py_ssize_t)i, v, is_list, wraparound, boundscheck) :\ + (is_list ? (PyErr_SetString(PyExc_IndexError, "list assignment index out of range"), -1) :\ + __Pyx_SetItemInt_Generic(o, to_py_func(i), v))) +static int __Pyx_SetItemInt_Generic(PyObject *o, PyObject *j, PyObject *v); +static CYTHON_INLINE int __Pyx_SetItemInt_Fast(PyObject *o, Py_ssize_t i, PyObject *v, + int is_list, int wraparound, int boundscheck); + +/* RaiseUnboundLocalError.proto */ +static CYTHON_INLINE void __Pyx_RaiseUnboundLocalError(const char *varname); + +/* DivInt[long].proto */ +static CYTHON_INLINE long __Pyx_div_long(long, long); + +/* PySequenceContains.proto */ +static CYTHON_INLINE int __Pyx_PySequence_ContainsTF(PyObject* item, PyObject* seq, int eq) { + int result = PySequence_Contains(seq, item); + return unlikely(result < 0) ? result : (result == (eq == Py_EQ)); +} + +/* ImportFrom.proto */ +static PyObject* __Pyx_ImportFrom(PyObject* module, PyObject* name); + +/* HasAttr.proto */ +#if __PYX_LIMITED_VERSION_HEX >= 0x030d00A1 +#define __Pyx_HasAttr(o, n) PyObject_HasAttrWithError(o, n) +#else +static CYTHON_INLINE int __Pyx_HasAttr(PyObject *, PyObject *); +#endif + +/* MoveIfSupported.proto */ +#if CYTHON_USE_CPP_STD_MOVE + #include + #define __PYX_STD_MOVE_IF_SUPPORTED(x) std::move(x) +#else + #define __PYX_STD_MOVE_IF_SUPPORTED(x) x +#endif + +/* BufferIndexError.proto */ +static void __Pyx_RaiseBufferIndexError(int axis); + +/* PyObject_GenericGetAttrNoDict.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttrNoDict PyObject_GenericGetAttr +#endif + +/* PyObject_GenericGetAttr.proto */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name); +#else +#define __Pyx_PyObject_GenericGetAttr PyObject_GenericGetAttr +#endif + +/* TypeImport.proto */ +#ifndef __PYX_HAVE_RT_ImportType_proto_3_0_8 +#define __PYX_HAVE_RT_ImportType_proto_3_0_8 +#if defined (__STDC_VERSION__) && __STDC_VERSION__ >= 201112L +#include +#endif +#if (defined (__STDC_VERSION__) && __STDC_VERSION__ >= 201112L) || __cplusplus >= 201103L +#define __PYX_GET_STRUCT_ALIGNMENT_3_0_8(s) alignof(s) +#else +#define __PYX_GET_STRUCT_ALIGNMENT_3_0_8(s) sizeof(void*) +#endif +enum __Pyx_ImportType_CheckSize_3_0_8 { + __Pyx_ImportType_CheckSize_Error_3_0_8 = 0, + __Pyx_ImportType_CheckSize_Warn_3_0_8 = 1, + __Pyx_ImportType_CheckSize_Ignore_3_0_8 = 2 +}; +static PyTypeObject *__Pyx_ImportType_3_0_8(PyObject* module, const char *module_name, const char *class_name, size_t size, size_t alignment, enum __Pyx_ImportType_CheckSize_3_0_8 check_size); +#endif + +/* IncludeStructmemberH.proto */ +#include + +/* FixUpExtensionType.proto */ +#if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type); +#endif + +/* PyObjectCallNoArg.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func); + +/* PyObjectGetMethod.proto */ +static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method); + +/* PyObjectCallMethod0.proto */ +static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name); + +/* ValidateBasesTuple.proto */ +#if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases); +#endif + +/* PyType_Ready.proto */ +CYTHON_UNUSED static int __Pyx_PyType_Ready(PyTypeObject *t); + +/* SetupReduce.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce(PyObject* type_obj); +#endif + +/* SetVTable.proto */ +static int __Pyx_SetVtable(PyTypeObject* typeptr , void* vtable); + +/* GetVTable.proto */ +static void* __Pyx_GetVtable(PyTypeObject *type); + +/* MergeVTables.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_MergeVtables(PyTypeObject *type); +#endif + +/* FetchSharedCythonModule.proto */ +static PyObject *__Pyx_FetchSharedCythonABIModule(void); + +/* FetchCommonType.proto */ +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type); +#else +static PyTypeObject* __Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases); +#endif + +/* PyMethodNew.proto */ +#if CYTHON_COMPILING_IN_LIMITED_API +static PyObject *__Pyx_PyMethod_New(PyObject *func, PyObject *self, PyObject *typ) { + PyObject *typesModule=NULL, *methodType=NULL, *result=NULL; + CYTHON_UNUSED_VAR(typ); + if (!self) + return __Pyx_NewRef(func); + typesModule = PyImport_ImportModule("types"); + if (!typesModule) return NULL; + methodType = PyObject_GetAttrString(typesModule, "MethodType"); + Py_DECREF(typesModule); + if (!methodType) return NULL; + result = PyObject_CallFunctionObjArgs(methodType, func, self, NULL); + Py_DECREF(methodType); + return result; +} +#elif PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_PyMethod_New(PyObject *func, PyObject *self, PyObject *typ) { + CYTHON_UNUSED_VAR(typ); + if (!self) + return __Pyx_NewRef(func); + return PyMethod_New(func, self); +} +#else + #define __Pyx_PyMethod_New PyMethod_New +#endif + +/* PyVectorcallFastCallDict.proto */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw); +#endif + +/* CythonFunctionShared.proto */ +#define __Pyx_CyFunction_USED +#define __Pyx_CYFUNCTION_STATICMETHOD 0x01 +#define __Pyx_CYFUNCTION_CLASSMETHOD 0x02 +#define __Pyx_CYFUNCTION_CCLASS 0x04 +#define __Pyx_CYFUNCTION_COROUTINE 0x08 +#define __Pyx_CyFunction_GetClosure(f)\ + (((__pyx_CyFunctionObject *) (f))->func_closure) +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + #define __Pyx_CyFunction_GetClassObj(f)\ + (((__pyx_CyFunctionObject *) (f))->func_classobj) +#else + #define __Pyx_CyFunction_GetClassObj(f)\ + ((PyObject*) ((PyCMethodObject *) (f))->mm_class) +#endif +#define __Pyx_CyFunction_SetClassObj(f, classobj)\ + __Pyx__CyFunction_SetClassObj((__pyx_CyFunctionObject *) (f), (classobj)) +#define __Pyx_CyFunction_Defaults(type, f)\ + ((type *)(((__pyx_CyFunctionObject *) (f))->defaults)) +#define __Pyx_CyFunction_SetDefaultsGetter(f, g)\ + ((__pyx_CyFunctionObject *) (f))->defaults_getter = (g) +typedef struct { +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject_HEAD + PyObject *func; +#elif PY_VERSION_HEX < 0x030900B1 + PyCFunctionObject func; +#else + PyCMethodObject func; +#endif +#if CYTHON_BACKPORT_VECTORCALL + __pyx_vectorcallfunc func_vectorcall; +#endif +#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API + PyObject *func_weakreflist; +#endif + PyObject *func_dict; + PyObject *func_name; + PyObject *func_qualname; + PyObject *func_doc; + PyObject *func_globals; + PyObject *func_code; + PyObject *func_closure; +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + PyObject *func_classobj; +#endif + void *defaults; + int defaults_pyobjects; + size_t defaults_size; + int flags; + PyObject *defaults_tuple; + PyObject *defaults_kwdict; + PyObject *(*defaults_getter)(PyObject *); + PyObject *func_annotations; + PyObject *func_is_coroutine; +} __pyx_CyFunctionObject; +#undef __Pyx_CyOrPyCFunction_Check +#define __Pyx_CyFunction_Check(obj) __Pyx_TypeCheck(obj, __pyx_CyFunctionType) +#define __Pyx_CyOrPyCFunction_Check(obj) __Pyx_TypeCheck2(obj, __pyx_CyFunctionType, &PyCFunction_Type) +#define __Pyx_CyFunction_CheckExact(obj) __Pyx_IS_TYPE(obj, __pyx_CyFunctionType) +static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc); +#undef __Pyx_IsSameCFunction +#define __Pyx_IsSameCFunction(func, cfunc) __Pyx__IsSameCyOrCFunction(func, cfunc) +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject* op, PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj); +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *m, + size_t size, + int pyobjects); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *m, + PyObject *tuple); +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *m, + PyObject *dict); +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *m, + PyObject *dict); +static int __pyx_CyFunction_init(PyObject *module); +#if CYTHON_METH_FASTCALL +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames); +#if CYTHON_BACKPORT_VECTORCALL +#define __Pyx_CyFunction_func_vectorcall(f) (((__pyx_CyFunctionObject*)f)->func_vectorcall) +#else +#define __Pyx_CyFunction_func_vectorcall(f) (((PyCFunctionObject*)f)->vectorcall) +#endif +#endif + +/* CythonFunction.proto */ +static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, + int flags, PyObject* qualname, + PyObject *closure, + PyObject *module, PyObject *globals, + PyObject* code); + +/* CLineInTraceback.proto */ +#ifdef CYTHON_CLINE_IN_TRACEBACK +#define __Pyx_CLineForTraceback(tstate, c_line) (((CYTHON_CLINE_IN_TRACEBACK)) ? c_line : 0) +#else +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line); +#endif + +/* CodeObjectCache.proto */ +#if !CYTHON_COMPILING_IN_LIMITED_API +typedef struct { + PyCodeObject* code_object; + int code_line; +} __Pyx_CodeObjectCacheEntry; +struct __Pyx_CodeObjectCache { + int count; + int max_count; + __Pyx_CodeObjectCacheEntry* entries; +}; +static struct __Pyx_CodeObjectCache __pyx_code_cache = {0,0,NULL}; +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line); +static PyCodeObject *__pyx_find_code_object(int code_line); +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object); +#endif + +/* AddTraceback.proto */ +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename); + +#if PY_MAJOR_VERSION < 3 + static int __Pyx_GetBuffer(PyObject *obj, Py_buffer *view, int flags); + static void __Pyx_ReleaseBuffer(Py_buffer *view); +#else + #define __Pyx_GetBuffer PyObject_GetBuffer + #define __Pyx_ReleaseBuffer PyBuffer_Release +#endif + + +/* BufferStructDeclare.proto */ +typedef struct { + Py_ssize_t shape, strides, suboffsets; +} __Pyx_Buf_DimInfo; +typedef struct { + size_t refcount; + Py_buffer pybuffer; +} __Pyx_Buffer; +typedef struct { + __Pyx_Buffer *rcbuffer; + char *data; + __Pyx_Buf_DimInfo diminfo[8]; +} __Pyx_LocalBuf_ND; + +/* MemviewSliceIsContig.proto */ +static int __pyx_memviewslice_is_contig(const __Pyx_memviewslice mvs, char order, int ndim); + +/* OverlappingSlices.proto */ +static int __pyx_slices_overlap(__Pyx_memviewslice *slice1, + __Pyx_memviewslice *slice2, + int ndim, size_t itemsize); + +/* IsLittleEndian.proto */ +static CYTHON_INLINE int __Pyx_Is_Little_Endian(void); + +/* BufferFormatCheck.proto */ +static const char* __Pyx_BufFmt_CheckString(__Pyx_BufFmt_Context* ctx, const char* ts); +static void __Pyx_BufFmt_Init(__Pyx_BufFmt_Context* ctx, + __Pyx_BufFmt_StackElem* stack, + __Pyx_TypeInfo* type); + +/* TypeInfoCompare.proto */ +static int __pyx_typeinfo_cmp(__Pyx_TypeInfo *a, __Pyx_TypeInfo *b); + +/* MemviewSliceValidateAndInit.proto */ +static int __Pyx_ValidateAndInit_memviewslice( + int *axes_specs, + int c_or_f_flag, + int buf_flags, + int ndim, + __Pyx_TypeInfo *dtype, + __Pyx_BufFmt_StackElem stack[], + __Pyx_memviewslice *memviewslice, + PyObject *original_obj); + +/* ObjectToMemviewSlice.proto */ +static CYTHON_INLINE __Pyx_memviewslice __Pyx_PyObject_to_MemoryviewSlice_ds_float(PyObject *, int writable_flag); + +/* MemviewDtypeToObject.proto */ +static CYTHON_INLINE PyObject *__pyx_memview_get_float(const char *itemp); +static CYTHON_INLINE int __pyx_memview_set_float(const char *itemp, PyObject *obj); + +/* MemviewSliceCopyTemplate.proto */ +static __Pyx_memviewslice +__pyx_memoryview_copy_new_contig(const __Pyx_memviewslice *from_mvs, + const char *mode, int ndim, + size_t sizeof_dtype, int contig_flag, + int dtype_is_object); + +/* MemviewSliceInit.proto */ +#define __Pyx_BUF_MAX_NDIMS %(BUF_MAX_NDIMS)d +#define __Pyx_MEMVIEW_DIRECT 1 +#define __Pyx_MEMVIEW_PTR 2 +#define __Pyx_MEMVIEW_FULL 4 +#define __Pyx_MEMVIEW_CONTIG 8 +#define __Pyx_MEMVIEW_STRIDED 16 +#define __Pyx_MEMVIEW_FOLLOW 32 +#define __Pyx_IS_C_CONTIG 1 +#define __Pyx_IS_F_CONTIG 2 +static int __Pyx_init_memviewslice( + struct __pyx_memoryview_obj *memview, + int ndim, + __Pyx_memviewslice *memviewslice, + int memview_is_new_reference); +static CYTHON_INLINE int __pyx_add_acquisition_count_locked( + __pyx_atomic_int_type *acquisition_count, PyThread_type_lock lock); +static CYTHON_INLINE int __pyx_sub_acquisition_count_locked( + __pyx_atomic_int_type *acquisition_count, PyThread_type_lock lock); +#define __pyx_get_slice_count_pointer(memview) (&memview->acquisition_count) +#define __PYX_INC_MEMVIEW(slice, have_gil) __Pyx_INC_MEMVIEW(slice, have_gil, __LINE__) +#define __PYX_XCLEAR_MEMVIEW(slice, have_gil) __Pyx_XCLEAR_MEMVIEW(slice, have_gil, __LINE__) +static CYTHON_INLINE void __Pyx_INC_MEMVIEW(__Pyx_memviewslice *, int, int); +static CYTHON_INLINE void __Pyx_XCLEAR_MEMVIEW(__Pyx_memviewslice *, int, int); + +/* CIntFromPy.proto */ +static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *); + +/* CppExceptionConversion.proto */ +#ifndef __Pyx_CppExn2PyErr +#include +#include +#include +#include +static void __Pyx_CppExn2PyErr() { + try { + if (PyErr_Occurred()) + ; // let the latest Python exn pass through and ignore the current one + else + throw; + } catch (const std::bad_alloc& exn) { + PyErr_SetString(PyExc_MemoryError, exn.what()); + } catch (const std::bad_cast& exn) { + PyErr_SetString(PyExc_TypeError, exn.what()); + } catch (const std::bad_typeid& exn) { + PyErr_SetString(PyExc_TypeError, exn.what()); + } catch (const std::domain_error& exn) { + PyErr_SetString(PyExc_ValueError, exn.what()); + } catch (const std::invalid_argument& exn) { + PyErr_SetString(PyExc_ValueError, exn.what()); + } catch (const std::ios_base::failure& exn) { + PyErr_SetString(PyExc_IOError, exn.what()); + } catch (const std::out_of_range& exn) { + PyErr_SetString(PyExc_IndexError, exn.what()); + } catch (const std::overflow_error& exn) { + PyErr_SetString(PyExc_OverflowError, exn.what()); + } catch (const std::range_error& exn) { + PyErr_SetString(PyExc_ArithmeticError, exn.what()); + } catch (const std::underflow_error& exn) { + PyErr_SetString(PyExc_ArithmeticError, exn.what()); + } catch (const std::exception& exn) { + PyErr_SetString(PyExc_RuntimeError, exn.what()); + } + catch (...) + { + PyErr_SetString(PyExc_RuntimeError, "Unknown exception"); + } +} +#endif + +/* None.proto */ +#include + +/* CIntFromPy.proto */ +static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_int(int value); + +/* CIntToPy.proto */ +static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value); + +/* CIntFromPy.proto */ +static CYTHON_INLINE char __Pyx_PyInt_As_char(PyObject *); + +/* FormatTypeName.proto */ +#if CYTHON_COMPILING_IN_LIMITED_API +typedef PyObject *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%U" +static __Pyx_TypeName __Pyx_PyType_GetName(PyTypeObject* tp); +#define __Pyx_DECREF_TypeName(obj) Py_XDECREF(obj) +#else +typedef const char *__Pyx_TypeName; +#define __Pyx_FMT_TYPENAME "%.200s" +#define __Pyx_PyType_GetName(tp) ((tp)->tp_name) +#define __Pyx_DECREF_TypeName(obj) +#endif + +/* CheckBinaryVersion.proto */ +static unsigned long __Pyx_get_runtime_version(void); +static int __Pyx_check_binary_version(unsigned long ct_version, unsigned long rt_version, int allow_newer); + +/* InitStrings.proto */ +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t); + +/* #### Code section: module_declarations ### */ +static PyObject *__pyx_array_get_memview(struct __pyx_array_obj *__pyx_v_self); /* proto*/ +static char *__pyx_memoryview_get_item_pointer(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index); /* proto*/ +static PyObject *__pyx_memoryview_is_slice(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj); /* proto*/ +static PyObject *__pyx_memoryview_setitem_slice_assignment(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_dst, PyObject *__pyx_v_src); /* proto*/ +static PyObject *__pyx_memoryview_setitem_slice_assign_scalar(struct __pyx_memoryview_obj *__pyx_v_self, struct __pyx_memoryview_obj *__pyx_v_dst, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryview_setitem_indexed(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryview_convert_item_to_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp); /* proto*/ +static PyObject *__pyx_memoryview_assign_item_from_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryview__get_base(struct __pyx_memoryview_obj *__pyx_v_self); /* proto*/ +static PyObject *__pyx_memoryviewslice_convert_item_to_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp); /* proto*/ +static PyObject *__pyx_memoryviewslice_assign_item_from_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value); /* proto*/ +static PyObject *__pyx_memoryviewslice__get_base(struct __pyx_memoryviewslice_obj *__pyx_v_self); /* proto*/ + +/* Module declarations from "libcpp" */ + +/* Module declarations from "libc.string" */ + +/* Module declarations from "libcpp.string" */ + +/* Module declarations from "libcpp.vector" */ + +/* Module declarations from "libcpp.utility" */ + +/* Module declarations from "libcpp.set" */ + +/* Module declarations from "libc.stdint" */ + +/* Module declarations from "cereal.visionipc.visionipc" */ + +/* Module declarations from "selfdrive.modeld.runners.thneedmodel" */ + +/* Module declarations from "cereal.visionipc.visionipc_pyx" */ + +/* Module declarations from "selfdrive.modeld.models.commonmodel_pyx" */ + +/* Module declarations from "selfdrive.modeld.runners.runmodel" */ + +/* Module declarations from "selfdrive.modeld.runners.runmodel_pyx" */ + +/* Module declarations from "selfdrive.modeld.runners.thneedmodel_pyx" */ +static PyObject *__pyx_collections_abc_Sequence = 0; +static PyObject *generic = 0; +static PyObject *strided = 0; +static PyObject *indirect = 0; +static PyObject *contiguous = 0; +static PyObject *indirect_contiguous = 0; +static int __pyx_memoryview_thread_locks_used; +static PyThread_type_lock __pyx_memoryview_thread_locks[8]; +static std::string __pyx_convert_string_from_py_std__in_string(PyObject *); /*proto*/ +static int __pyx_array_allocate_buffer(struct __pyx_array_obj *); /*proto*/ +static struct __pyx_array_obj *__pyx_array_new(PyObject *, Py_ssize_t, char *, char *, char *); /*proto*/ +static PyObject *__pyx_memoryview_new(PyObject *, int, int, __Pyx_TypeInfo *); /*proto*/ +static CYTHON_INLINE int __pyx_memoryview_check(PyObject *); /*proto*/ +static PyObject *_unellipsify(PyObject *, int); /*proto*/ +static int assert_direct_dimensions(Py_ssize_t *, int); /*proto*/ +static struct __pyx_memoryview_obj *__pyx_memview_slice(struct __pyx_memoryview_obj *, PyObject *); /*proto*/ +static int __pyx_memoryview_slice_memviewslice(__Pyx_memviewslice *, Py_ssize_t, Py_ssize_t, Py_ssize_t, int, int, int *, Py_ssize_t, Py_ssize_t, Py_ssize_t, int, int, int, int); /*proto*/ +static char *__pyx_pybuffer_index(Py_buffer *, char *, Py_ssize_t, Py_ssize_t); /*proto*/ +static int __pyx_memslice_transpose(__Pyx_memviewslice *); /*proto*/ +static PyObject *__pyx_memoryview_fromslice(__Pyx_memviewslice, int, PyObject *(*)(char *), int (*)(char *, PyObject *), int); /*proto*/ +static __Pyx_memviewslice *__pyx_memoryview_get_slice_from_memoryview(struct __pyx_memoryview_obj *, __Pyx_memviewslice *); /*proto*/ +static void __pyx_memoryview_slice_copy(struct __pyx_memoryview_obj *, __Pyx_memviewslice *); /*proto*/ +static PyObject *__pyx_memoryview_copy_object(struct __pyx_memoryview_obj *); /*proto*/ +static PyObject *__pyx_memoryview_copy_object_from_slice(struct __pyx_memoryview_obj *, __Pyx_memviewslice *); /*proto*/ +static Py_ssize_t abs_py_ssize_t(Py_ssize_t); /*proto*/ +static char __pyx_get_best_slice_order(__Pyx_memviewslice *, int); /*proto*/ +static void _copy_strided_to_strided(char *, Py_ssize_t *, char *, Py_ssize_t *, Py_ssize_t *, Py_ssize_t *, int, size_t); /*proto*/ +static void copy_strided_to_strided(__Pyx_memviewslice *, __Pyx_memviewslice *, int, size_t); /*proto*/ +static Py_ssize_t __pyx_memoryview_slice_get_size(__Pyx_memviewslice *, int); /*proto*/ +static Py_ssize_t __pyx_fill_contig_strides_array(Py_ssize_t *, Py_ssize_t *, Py_ssize_t, int, char); /*proto*/ +static void *__pyx_memoryview_copy_data_to_temp(__Pyx_memviewslice *, __Pyx_memviewslice *, char, int); /*proto*/ +static int __pyx_memoryview_err_extents(int, Py_ssize_t, Py_ssize_t); /*proto*/ +static int __pyx_memoryview_err_dim(PyObject *, PyObject *, int); /*proto*/ +static int __pyx_memoryview_err(PyObject *, PyObject *); /*proto*/ +static int __pyx_memoryview_err_no_memory(void); /*proto*/ +static int __pyx_memoryview_copy_contents(__Pyx_memviewslice, __Pyx_memviewslice, int, int, int); /*proto*/ +static void __pyx_memoryview_broadcast_leading(__Pyx_memviewslice *, int, int); /*proto*/ +static void __pyx_memoryview_refcount_copying(__Pyx_memviewslice *, int, int, int); /*proto*/ +static void __pyx_memoryview_refcount_objects_in_slice_with_gil(char *, Py_ssize_t *, Py_ssize_t *, int, int); /*proto*/ +static void __pyx_memoryview_refcount_objects_in_slice(char *, Py_ssize_t *, Py_ssize_t *, int, int); /*proto*/ +static void __pyx_memoryview_slice_assign_scalar(__Pyx_memviewslice *, int, size_t, void *, int); /*proto*/ +static void __pyx_memoryview__slice_assign_scalar(char *, Py_ssize_t *, Py_ssize_t *, int, size_t, void *); /*proto*/ +static PyObject *__pyx_unpickle_Enum__set_state(struct __pyx_MemviewEnum_obj *, PyObject *); /*proto*/ +/* #### Code section: typeinfo ### */ +static __Pyx_TypeInfo __Pyx_TypeInfo_float = { "float", NULL, sizeof(float), { 0 }, 0, 'R', 0, 0 }; +/* #### Code section: before_global_var ### */ +#define __Pyx_MODULE_NAME "selfdrive.modeld.runners.thneedmodel_pyx" +extern int __pyx_module_is_main_selfdrive__modeld__runners__thneedmodel_pyx; +int __pyx_module_is_main_selfdrive__modeld__runners__thneedmodel_pyx = 0; + +/* Implementation of "selfdrive.modeld.runners.thneedmodel_pyx" */ +/* #### Code section: global_var ### */ +static PyObject *__pyx_builtin_TypeError; +static PyObject *__pyx_builtin___import__; +static PyObject *__pyx_builtin_ValueError; +static PyObject *__pyx_builtin_MemoryError; +static PyObject *__pyx_builtin_enumerate; +static PyObject *__pyx_builtin_range; +static PyObject *__pyx_builtin_AssertionError; +static PyObject *__pyx_builtin_Ellipsis; +static PyObject *__pyx_builtin_id; +static PyObject *__pyx_builtin_IndexError; +/* #### Code section: string_decls ### */ +static const char __pyx_k_[] = ": "; +static const char __pyx_k_O[] = "O"; +static const char __pyx_k_c[] = "c"; +static const char __pyx_k__2[] = "."; +static const char __pyx_k__3[] = "*"; +static const char __pyx_k__6[] = "'"; +static const char __pyx_k__7[] = ")"; +static const char __pyx_k_gc[] = "gc"; +static const char __pyx_k_id[] = "id"; +static const char __pyx_k__24[] = "?"; +static const char __pyx_k_abc[] = "abc"; +static const char __pyx_k_and[] = " and "; +static const char __pyx_k_got[] = " (got "; +static const char __pyx_k_new[] = "__new__"; +static const char __pyx_k_obj[] = "obj"; +static const char __pyx_k_sys[] = "sys"; +static const char __pyx_k_base[] = "base"; +static const char __pyx_k_dict[] = "__dict__"; +static const char __pyx_k_main[] = "__main__"; +static const char __pyx_k_mode[] = "mode"; +static const char __pyx_k_name[] = "name"; +static const char __pyx_k_ndim[] = "ndim"; +static const char __pyx_k_pack[] = "pack"; +static const char __pyx_k_path[] = "path"; +static const char __pyx_k_self[] = "self"; +static const char __pyx_k_size[] = "size"; +static const char __pyx_k_spec[] = "__spec__"; +static const char __pyx_k_step[] = "step"; +static const char __pyx_k_stop[] = "stop"; +static const char __pyx_k_test[] = "__test__"; +static const char __pyx_k_ASCII[] = "ASCII"; +static const char __pyx_k_class[] = "__class__"; +static const char __pyx_k_count[] = "count"; +static const char __pyx_k_error[] = "error"; +static const char __pyx_k_flags[] = "flags"; +static const char __pyx_k_index[] = "index"; +static const char __pyx_k_range[] = "range"; +static const char __pyx_k_shape[] = "shape"; +static const char __pyx_k_start[] = "start"; +static const char __pyx_k_enable[] = "enable"; +static const char __pyx_k_encode[] = "encode"; +static const char __pyx_k_format[] = "format"; +static const char __pyx_k_import[] = "__import__"; +static const char __pyx_k_name_2[] = "__name__"; +static const char __pyx_k_output[] = "output"; +static const char __pyx_k_pickle[] = "pickle"; +static const char __pyx_k_reduce[] = "__reduce__"; +static const char __pyx_k_struct[] = "struct"; +static const char __pyx_k_unpack[] = "unpack"; +static const char __pyx_k_update[] = "update"; +static const char __pyx_k_context[] = "context"; +static const char __pyx_k_disable[] = "disable"; +static const char __pyx_k_fortran[] = "fortran"; +static const char __pyx_k_memview[] = "memview"; +static const char __pyx_k_runtime[] = "runtime"; +static const char __pyx_k_use_tf8[] = "use_tf8"; +static const char __pyx_k_Ellipsis[] = "Ellipsis"; +static const char __pyx_k_Sequence[] = "Sequence"; +static const char __pyx_k_getstate[] = "__getstate__"; +static const char __pyx_k_itemsize[] = "itemsize"; +static const char __pyx_k_pyx_type[] = "__pyx_type"; +static const char __pyx_k_register[] = "register"; +static const char __pyx_k_setstate[] = "__setstate__"; +static const char __pyx_k_TypeError[] = "TypeError"; +static const char __pyx_k_enumerate[] = "enumerate"; +static const char __pyx_k_isenabled[] = "isenabled"; +static const char __pyx_k_pyx_state[] = "__pyx_state"; +static const char __pyx_k_reduce_ex[] = "__reduce_ex__"; +static const char __pyx_k_IndexError[] = "IndexError"; +static const char __pyx_k_ValueError[] = "ValueError"; +static const char __pyx_k_pyx_result[] = "__pyx_result"; +static const char __pyx_k_pyx_vtable[] = "__pyx_vtable__"; +static const char __pyx_k_MemoryError[] = "MemoryError"; +static const char __pyx_k_PickleError[] = "PickleError"; +static const char __pyx_k_ThneedModel[] = "ThneedModel"; +static const char __pyx_k_collections[] = "collections"; +static const char __pyx_k_initializing[] = "_initializing"; +static const char __pyx_k_is_coroutine[] = "_is_coroutine"; +static const char __pyx_k_pyx_checksum[] = "__pyx_checksum"; +static const char __pyx_k_stringsource[] = ""; +static const char __pyx_k_version_info[] = "version_info"; +static const char __pyx_k_class_getitem[] = "__class_getitem__"; +static const char __pyx_k_reduce_cython[] = "__reduce_cython__"; +static const char __pyx_k_AssertionError[] = "AssertionError"; +static const char __pyx_k_View_MemoryView[] = "View.MemoryView"; +static const char __pyx_k_allocate_buffer[] = "allocate_buffer"; +static const char __pyx_k_collections_abc[] = "collections.abc"; +static const char __pyx_k_dtype_is_object[] = "dtype_is_object"; +static const char __pyx_k_pyx_PickleError[] = "__pyx_PickleError"; +static const char __pyx_k_setstate_cython[] = "__setstate_cython__"; +static const char __pyx_k_pyx_unpickle_Enum[] = "__pyx_unpickle_Enum"; +static const char __pyx_k_asyncio_coroutines[] = "asyncio.coroutines"; +static const char __pyx_k_cline_in_traceback[] = "cline_in_traceback"; +static const char __pyx_k_strided_and_direct[] = ""; +static const char __pyx_k_strided_and_indirect[] = ""; +static const char __pyx_k_Invalid_shape_in_axis[] = "Invalid shape in axis "; +static const char __pyx_k_contiguous_and_direct[] = ""; +static const char __pyx_k_Cannot_index_with_type[] = "Cannot index with type '"; +static const char __pyx_k_MemoryView_of_r_object[] = ""; +static const char __pyx_k_MemoryView_of_r_at_0x_x[] = ""; +static const char __pyx_k_contiguous_and_indirect[] = ""; +static const char __pyx_k_Dimension_d_is_not_direct[] = "Dimension %d is not direct"; +static const char __pyx_k_Index_out_of_bounds_axis_d[] = "Index out of bounds (axis %d)"; +static const char __pyx_k_Step_may_not_be_zero_axis_d[] = "Step may not be zero (axis %d)"; +static const char __pyx_k_ThneedModel___reduce_cython[] = "ThneedModel.__reduce_cython__"; +static const char __pyx_k_itemsize_0_for_cython_array[] = "itemsize <= 0 for cython.array"; +static const char __pyx_k_ThneedModel___setstate_cython[] = "ThneedModel.__setstate_cython__"; +static const char __pyx_k_unable_to_allocate_array_data[] = "unable to allocate array data."; +static const char __pyx_k_strided_and_direct_or_indirect[] = ""; +static const char __pyx_k_All_dimensions_preceding_dimensi[] = "All dimensions preceding dimension %d must be indexed and not sliced"; +static const char __pyx_k_Buffer_view_does_not_expose_stri[] = "Buffer view does not expose strides"; +static const char __pyx_k_Can_only_create_a_buffer_that_is[] = "Can only create a buffer that is contiguous in memory."; +static const char __pyx_k_Cannot_assign_to_read_only_memor[] = "Cannot assign to read-only memoryview"; +static const char __pyx_k_Cannot_create_writable_memory_vi[] = "Cannot create writable memory view from read-only memoryview"; +static const char __pyx_k_Cannot_transpose_memoryview_with[] = "Cannot transpose memoryview with indirect dimensions"; +static const char __pyx_k_Empty_shape_tuple_for_cython_arr[] = "Empty shape tuple for cython.array"; +static const char __pyx_k_Incompatible_checksums_0x_x_vs_0[] = "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))"; +static const char __pyx_k_Indirect_dimensions_not_supporte[] = "Indirect dimensions not supported"; +static const char __pyx_k_Invalid_mode_expected_c_or_fortr[] = "Invalid mode, expected 'c' or 'fortran', got "; +static const char __pyx_k_Out_of_bounds_on_buffer_access_a[] = "Out of bounds on buffer access (axis "; +static const char __pyx_k_Unable_to_convert_item_to_object[] = "Unable to convert item to object"; +static const char __pyx_k_got_differing_extents_in_dimensi[] = "got differing extents in dimension "; +static const char __pyx_k_no_default___reduce___due_to_non[] = "no default __reduce__ due to non-trivial __cinit__"; +static const char __pyx_k_selfdrive_modeld_runners_thneedm[] = "selfdrive.modeld.runners.thneedmodel_pyx"; +static const char __pyx_k_unable_to_allocate_shape_and_str[] = "unable to allocate shape and strides."; +/* #### Code section: decls ### */ +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array___cinit__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_shape, Py_ssize_t __pyx_v_itemsize, PyObject *__pyx_v_format, PyObject *__pyx_v_mode, int __pyx_v_allocate_buffer); /* proto */ +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_2__getbuffer__(struct __pyx_array_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /* proto */ +static void __pyx_array___pyx_pf_15View_dot_MemoryView_5array_4__dealloc__(struct __pyx_array_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_5array_7memview___get__(struct __pyx_array_obj *__pyx_v_self); /* proto */ +static Py_ssize_t __pyx_array___pyx_pf_15View_dot_MemoryView_5array_6__len__(struct __pyx_array_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_8__getattr__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_attr); /* proto */ +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_10__getitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item); /* proto */ +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_12__setitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value); /* proto */ +static PyObject *__pyx_pf___pyx_array___reduce_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_array_2__setstate_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum___init__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v_name); /* proto */ +static PyObject *__pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum_2__repr__(struct __pyx_MemviewEnum_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_MemviewEnum___reduce_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_MemviewEnum_2__setstate_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview___cinit__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj, int __pyx_v_flags, int __pyx_v_dtype_is_object); /* proto */ +static void __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_2__dealloc__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_4__getitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index); /* proto */ +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_6__setitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value); /* proto */ +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_8__getbuffer__(struct __pyx_memoryview_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_1T___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4base___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_5shape___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_7strides___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_10suboffsets___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4ndim___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_8itemsize___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_6nbytes___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4size___get__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static Py_ssize_t __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_10__len__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_12__repr__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_14__str__(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_16is_c_contig(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_18is_f_contig(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_20copy(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_22copy_fortran(struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryview___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryview_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static void __pyx_memoryviewslice___pyx_pf_15View_dot_MemoryView_16_memoryviewslice___dealloc__(struct __pyx_memoryviewslice_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryviewslice___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf___pyx_memoryviewslice_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_pf_15View_dot_MemoryView___pyx_unpickle_Enum(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v___pyx_type, long __pyx_v___pyx_checksum, PyObject *__pyx_v___pyx_state); /* proto */ +static int __pyx_pf_9selfdrive_6modeld_7runners_15thneedmodel_pyx_11ThneedModel___cinit__(struct __pyx_obj_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel *__pyx_v_self, std::string __pyx_v_path, __Pyx_memviewslice __pyx_v_output, int __pyx_v_runtime, bool __pyx_v_use_tf8, struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext *__pyx_v_context); /* proto */ +static PyObject *__pyx_pf_9selfdrive_6modeld_7runners_15thneedmodel_pyx_11ThneedModel_2__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel *__pyx_v_self); /* proto */ +static PyObject *__pyx_pf_9selfdrive_6modeld_7runners_15thneedmodel_pyx_11ThneedModel_4__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state); /* proto */ +static PyObject *__pyx_tp_new_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_array(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_Enum(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new_memoryview(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +static PyObject *__pyx_tp_new__memoryviewslice(PyTypeObject *t, PyObject *a, PyObject *k); /*proto*/ +/* #### Code section: late_includes ### */ +/* #### Code section: module_state ### */ +typedef struct { + PyObject *__pyx_d; + PyObject *__pyx_b; + PyObject *__pyx_cython_runtime; + PyObject *__pyx_empty_tuple; + PyObject *__pyx_empty_bytes; + PyObject *__pyx_empty_unicode; + #ifdef __Pyx_CyFunction_USED + PyTypeObject *__pyx_CyFunctionType; + #endif + #ifdef __Pyx_FusedFunction_USED + PyTypeObject *__pyx_FusedFunctionType; + #endif + #ifdef __Pyx_Generator_USED + PyTypeObject *__pyx_GeneratorType; + #endif + #ifdef __Pyx_IterableCoroutine_USED + PyTypeObject *__pyx_IterableCoroutineType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineAwaitType; + #endif + #ifdef __Pyx_Coroutine_USED + PyTypeObject *__pyx_CoroutineType; + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + PyTypeObject *__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext; + PyTypeObject *__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf; + #if CYTHON_USE_MODULE_STATE + #endif + PyTypeObject *__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext; + PyTypeObject *__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem; + #if CYTHON_USE_MODULE_STATE + #endif + #if CYTHON_USE_MODULE_STATE + #endif + PyTypeObject *__pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel; + #if CYTHON_USE_MODULE_STATE + PyObject *__pyx_type_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel; + PyObject *__pyx_type___pyx_array; + PyObject *__pyx_type___pyx_MemviewEnum; + PyObject *__pyx_type___pyx_memoryview; + PyObject *__pyx_type___pyx_memoryviewslice; + #endif + PyTypeObject *__pyx_ptype_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel; + PyTypeObject *__pyx_array_type; + PyTypeObject *__pyx_MemviewEnum_type; + PyTypeObject *__pyx_memoryview_type; + PyTypeObject *__pyx_memoryviewslice_type; + PyObject *__pyx_kp_u_; + PyObject *__pyx_n_s_ASCII; + PyObject *__pyx_kp_s_All_dimensions_preceding_dimensi; + PyObject *__pyx_n_s_AssertionError; + PyObject *__pyx_kp_s_Buffer_view_does_not_expose_stri; + PyObject *__pyx_kp_s_Can_only_create_a_buffer_that_is; + PyObject *__pyx_kp_s_Cannot_assign_to_read_only_memor; + PyObject *__pyx_kp_s_Cannot_create_writable_memory_vi; + PyObject *__pyx_kp_u_Cannot_index_with_type; + PyObject *__pyx_kp_s_Cannot_transpose_memoryview_with; + PyObject *__pyx_kp_s_Dimension_d_is_not_direct; + PyObject *__pyx_n_s_Ellipsis; + PyObject *__pyx_kp_s_Empty_shape_tuple_for_cython_arr; + PyObject *__pyx_kp_s_Incompatible_checksums_0x_x_vs_0; + PyObject *__pyx_n_s_IndexError; + PyObject *__pyx_kp_s_Index_out_of_bounds_axis_d; + PyObject *__pyx_kp_s_Indirect_dimensions_not_supporte; + PyObject *__pyx_kp_u_Invalid_mode_expected_c_or_fortr; + PyObject *__pyx_kp_u_Invalid_shape_in_axis; + PyObject *__pyx_n_s_MemoryError; + PyObject *__pyx_kp_s_MemoryView_of_r_at_0x_x; + PyObject *__pyx_kp_s_MemoryView_of_r_object; + PyObject *__pyx_n_b_O; + PyObject *__pyx_kp_u_Out_of_bounds_on_buffer_access_a; + PyObject *__pyx_n_s_PickleError; + PyObject *__pyx_n_s_Sequence; + PyObject *__pyx_kp_s_Step_may_not_be_zero_axis_d; + PyObject *__pyx_n_s_ThneedModel; + PyObject *__pyx_n_s_ThneedModel___reduce_cython; + PyObject *__pyx_n_s_ThneedModel___setstate_cython; + PyObject *__pyx_n_s_TypeError; + PyObject *__pyx_kp_s_Unable_to_convert_item_to_object; + PyObject *__pyx_n_s_ValueError; + PyObject *__pyx_n_s_View_MemoryView; + PyObject *__pyx_kp_u__2; + PyObject *__pyx_n_s__24; + PyObject *__pyx_n_s__3; + PyObject *__pyx_kp_u__6; + PyObject *__pyx_kp_u__7; + PyObject *__pyx_n_s_abc; + PyObject *__pyx_n_s_allocate_buffer; + PyObject *__pyx_kp_u_and; + PyObject *__pyx_n_s_asyncio_coroutines; + PyObject *__pyx_n_s_base; + PyObject *__pyx_n_s_c; + PyObject *__pyx_n_u_c; + PyObject *__pyx_n_s_class; + PyObject *__pyx_n_s_class_getitem; + PyObject *__pyx_n_s_cline_in_traceback; + PyObject *__pyx_n_s_collections; + PyObject *__pyx_kp_s_collections_abc; + PyObject *__pyx_n_s_context; + PyObject *__pyx_kp_s_contiguous_and_direct; + PyObject *__pyx_kp_s_contiguous_and_indirect; + PyObject *__pyx_n_s_count; + PyObject *__pyx_n_s_dict; + PyObject *__pyx_kp_u_disable; + PyObject *__pyx_n_s_dtype_is_object; + PyObject *__pyx_kp_u_enable; + PyObject *__pyx_n_s_encode; + PyObject *__pyx_n_s_enumerate; + PyObject *__pyx_n_s_error; + PyObject *__pyx_n_s_flags; + PyObject *__pyx_n_s_format; + PyObject *__pyx_n_s_fortran; + PyObject *__pyx_n_u_fortran; + PyObject *__pyx_kp_u_gc; + PyObject *__pyx_n_s_getstate; + PyObject *__pyx_kp_u_got; + PyObject *__pyx_kp_u_got_differing_extents_in_dimensi; + PyObject *__pyx_n_s_id; + PyObject *__pyx_n_s_import; + PyObject *__pyx_n_s_index; + PyObject *__pyx_n_s_initializing; + PyObject *__pyx_n_s_is_coroutine; + PyObject *__pyx_kp_u_isenabled; + PyObject *__pyx_n_s_itemsize; + PyObject *__pyx_kp_s_itemsize_0_for_cython_array; + PyObject *__pyx_n_s_main; + PyObject *__pyx_n_s_memview; + PyObject *__pyx_n_s_mode; + PyObject *__pyx_n_s_name; + PyObject *__pyx_n_s_name_2; + PyObject *__pyx_n_s_ndim; + PyObject *__pyx_n_s_new; + PyObject *__pyx_kp_s_no_default___reduce___due_to_non; + PyObject *__pyx_n_s_obj; + PyObject *__pyx_n_s_output; + PyObject *__pyx_n_s_pack; + PyObject *__pyx_n_s_path; + PyObject *__pyx_n_s_pickle; + PyObject *__pyx_n_s_pyx_PickleError; + PyObject *__pyx_n_s_pyx_checksum; + PyObject *__pyx_n_s_pyx_result; + PyObject *__pyx_n_s_pyx_state; + PyObject *__pyx_n_s_pyx_type; + PyObject *__pyx_n_s_pyx_unpickle_Enum; + PyObject *__pyx_n_s_pyx_vtable; + PyObject *__pyx_n_s_range; + PyObject *__pyx_n_s_reduce; + PyObject *__pyx_n_s_reduce_cython; + PyObject *__pyx_n_s_reduce_ex; + PyObject *__pyx_n_s_register; + PyObject *__pyx_n_s_runtime; + PyObject *__pyx_n_s_self; + PyObject *__pyx_n_s_selfdrive_modeld_runners_thneedm; + PyObject *__pyx_n_s_setstate; + PyObject *__pyx_n_s_setstate_cython; + PyObject *__pyx_n_s_shape; + PyObject *__pyx_n_s_size; + PyObject *__pyx_n_s_spec; + PyObject *__pyx_n_s_start; + PyObject *__pyx_n_s_step; + PyObject *__pyx_n_s_stop; + PyObject *__pyx_kp_s_strided_and_direct; + PyObject *__pyx_kp_s_strided_and_direct_or_indirect; + PyObject *__pyx_kp_s_strided_and_indirect; + PyObject *__pyx_kp_s_stringsource; + PyObject *__pyx_n_s_struct; + PyObject *__pyx_n_s_sys; + PyObject *__pyx_n_s_test; + PyObject *__pyx_kp_s_unable_to_allocate_array_data; + PyObject *__pyx_kp_s_unable_to_allocate_shape_and_str; + PyObject *__pyx_n_s_unpack; + PyObject *__pyx_n_s_update; + PyObject *__pyx_n_s_use_tf8; + PyObject *__pyx_n_s_version_info; + PyObject *__pyx_int_0; + PyObject *__pyx_int_1; + PyObject *__pyx_int_3; + PyObject *__pyx_int_112105877; + PyObject *__pyx_int_136983863; + PyObject *__pyx_int_184977713; + PyObject *__pyx_int_neg_1; + PyObject *__pyx_slice__5; + PyObject *__pyx_tuple__4; + PyObject *__pyx_tuple__8; + PyObject *__pyx_tuple__9; + PyObject *__pyx_tuple__10; + PyObject *__pyx_tuple__11; + PyObject *__pyx_tuple__12; + PyObject *__pyx_tuple__13; + PyObject *__pyx_tuple__14; + PyObject *__pyx_tuple__15; + PyObject *__pyx_tuple__16; + PyObject *__pyx_tuple__17; + PyObject *__pyx_tuple__18; + PyObject *__pyx_tuple__20; + PyObject *__pyx_tuple__22; + PyObject *__pyx_codeobj__19; + PyObject *__pyx_codeobj__21; + PyObject *__pyx_codeobj__23; +} __pyx_mstate; + +#if CYTHON_USE_MODULE_STATE +#ifdef __cplusplus +namespace { + extern struct PyModuleDef __pyx_moduledef; +} /* anonymous namespace */ +#else +static struct PyModuleDef __pyx_moduledef; +#endif + +#define __pyx_mstate(o) ((__pyx_mstate *)__Pyx_PyModule_GetState(o)) + +#define __pyx_mstate_global (__pyx_mstate(PyState_FindModule(&__pyx_moduledef))) + +#define __pyx_m (PyState_FindModule(&__pyx_moduledef)) +#else +static __pyx_mstate __pyx_mstate_global_static = +#ifdef __cplusplus + {}; +#else + {0}; +#endif +static __pyx_mstate *__pyx_mstate_global = &__pyx_mstate_global_static; +#endif +/* #### Code section: module_state_clear ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_clear(PyObject *m) { + __pyx_mstate *clear_module_state = __pyx_mstate(m); + if (!clear_module_state) return 0; + Py_CLEAR(clear_module_state->__pyx_d); + Py_CLEAR(clear_module_state->__pyx_b); + Py_CLEAR(clear_module_state->__pyx_cython_runtime); + Py_CLEAR(clear_module_state->__pyx_empty_tuple); + Py_CLEAR(clear_module_state->__pyx_empty_bytes); + Py_CLEAR(clear_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_CLEAR(clear_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_CLEAR(clear_module_state->__pyx_FusedFunctionType); + #endif + Py_CLEAR(clear_module_state->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext); + Py_CLEAR(clear_module_state->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf); + Py_CLEAR(clear_module_state->__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext); + Py_CLEAR(clear_module_state->__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem); + Py_CLEAR(clear_module_state->__pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel); + Py_CLEAR(clear_module_state->__pyx_ptype_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel); + Py_CLEAR(clear_module_state->__pyx_type_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel); + Py_CLEAR(clear_module_state->__pyx_array_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_array); + Py_CLEAR(clear_module_state->__pyx_MemviewEnum_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_MemviewEnum); + Py_CLEAR(clear_module_state->__pyx_memoryview_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_memoryview); + Py_CLEAR(clear_module_state->__pyx_memoryviewslice_type); + Py_CLEAR(clear_module_state->__pyx_type___pyx_memoryviewslice); + Py_CLEAR(clear_module_state->__pyx_kp_u_); + Py_CLEAR(clear_module_state->__pyx_n_s_ASCII); + Py_CLEAR(clear_module_state->__pyx_kp_s_All_dimensions_preceding_dimensi); + Py_CLEAR(clear_module_state->__pyx_n_s_AssertionError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Buffer_view_does_not_expose_stri); + Py_CLEAR(clear_module_state->__pyx_kp_s_Can_only_create_a_buffer_that_is); + Py_CLEAR(clear_module_state->__pyx_kp_s_Cannot_assign_to_read_only_memor); + Py_CLEAR(clear_module_state->__pyx_kp_s_Cannot_create_writable_memory_vi); + Py_CLEAR(clear_module_state->__pyx_kp_u_Cannot_index_with_type); + Py_CLEAR(clear_module_state->__pyx_kp_s_Cannot_transpose_memoryview_with); + Py_CLEAR(clear_module_state->__pyx_kp_s_Dimension_d_is_not_direct); + Py_CLEAR(clear_module_state->__pyx_n_s_Ellipsis); + Py_CLEAR(clear_module_state->__pyx_kp_s_Empty_shape_tuple_for_cython_arr); + Py_CLEAR(clear_module_state->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0); + Py_CLEAR(clear_module_state->__pyx_n_s_IndexError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Index_out_of_bounds_axis_d); + Py_CLEAR(clear_module_state->__pyx_kp_s_Indirect_dimensions_not_supporte); + Py_CLEAR(clear_module_state->__pyx_kp_u_Invalid_mode_expected_c_or_fortr); + Py_CLEAR(clear_module_state->__pyx_kp_u_Invalid_shape_in_axis); + Py_CLEAR(clear_module_state->__pyx_n_s_MemoryError); + Py_CLEAR(clear_module_state->__pyx_kp_s_MemoryView_of_r_at_0x_x); + Py_CLEAR(clear_module_state->__pyx_kp_s_MemoryView_of_r_object); + Py_CLEAR(clear_module_state->__pyx_n_b_O); + Py_CLEAR(clear_module_state->__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + Py_CLEAR(clear_module_state->__pyx_n_s_PickleError); + Py_CLEAR(clear_module_state->__pyx_n_s_Sequence); + Py_CLEAR(clear_module_state->__pyx_kp_s_Step_may_not_be_zero_axis_d); + Py_CLEAR(clear_module_state->__pyx_n_s_ThneedModel); + Py_CLEAR(clear_module_state->__pyx_n_s_ThneedModel___reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_ThneedModel___setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_TypeError); + Py_CLEAR(clear_module_state->__pyx_kp_s_Unable_to_convert_item_to_object); + Py_CLEAR(clear_module_state->__pyx_n_s_ValueError); + Py_CLEAR(clear_module_state->__pyx_n_s_View_MemoryView); + Py_CLEAR(clear_module_state->__pyx_kp_u__2); + Py_CLEAR(clear_module_state->__pyx_n_s__24); + Py_CLEAR(clear_module_state->__pyx_n_s__3); + Py_CLEAR(clear_module_state->__pyx_kp_u__6); + Py_CLEAR(clear_module_state->__pyx_kp_u__7); + Py_CLEAR(clear_module_state->__pyx_n_s_abc); + Py_CLEAR(clear_module_state->__pyx_n_s_allocate_buffer); + Py_CLEAR(clear_module_state->__pyx_kp_u_and); + Py_CLEAR(clear_module_state->__pyx_n_s_asyncio_coroutines); + Py_CLEAR(clear_module_state->__pyx_n_s_base); + Py_CLEAR(clear_module_state->__pyx_n_s_c); + Py_CLEAR(clear_module_state->__pyx_n_u_c); + Py_CLEAR(clear_module_state->__pyx_n_s_class); + Py_CLEAR(clear_module_state->__pyx_n_s_class_getitem); + Py_CLEAR(clear_module_state->__pyx_n_s_cline_in_traceback); + Py_CLEAR(clear_module_state->__pyx_n_s_collections); + Py_CLEAR(clear_module_state->__pyx_kp_s_collections_abc); + Py_CLEAR(clear_module_state->__pyx_n_s_context); + Py_CLEAR(clear_module_state->__pyx_kp_s_contiguous_and_direct); + Py_CLEAR(clear_module_state->__pyx_kp_s_contiguous_and_indirect); + Py_CLEAR(clear_module_state->__pyx_n_s_count); + Py_CLEAR(clear_module_state->__pyx_n_s_dict); + Py_CLEAR(clear_module_state->__pyx_kp_u_disable); + Py_CLEAR(clear_module_state->__pyx_n_s_dtype_is_object); + Py_CLEAR(clear_module_state->__pyx_kp_u_enable); + Py_CLEAR(clear_module_state->__pyx_n_s_encode); + Py_CLEAR(clear_module_state->__pyx_n_s_enumerate); + Py_CLEAR(clear_module_state->__pyx_n_s_error); + Py_CLEAR(clear_module_state->__pyx_n_s_flags); + Py_CLEAR(clear_module_state->__pyx_n_s_format); + Py_CLEAR(clear_module_state->__pyx_n_s_fortran); + Py_CLEAR(clear_module_state->__pyx_n_u_fortran); + Py_CLEAR(clear_module_state->__pyx_kp_u_gc); + Py_CLEAR(clear_module_state->__pyx_n_s_getstate); + Py_CLEAR(clear_module_state->__pyx_kp_u_got); + Py_CLEAR(clear_module_state->__pyx_kp_u_got_differing_extents_in_dimensi); + Py_CLEAR(clear_module_state->__pyx_n_s_id); + Py_CLEAR(clear_module_state->__pyx_n_s_import); + Py_CLEAR(clear_module_state->__pyx_n_s_index); + Py_CLEAR(clear_module_state->__pyx_n_s_initializing); + Py_CLEAR(clear_module_state->__pyx_n_s_is_coroutine); + Py_CLEAR(clear_module_state->__pyx_kp_u_isenabled); + Py_CLEAR(clear_module_state->__pyx_n_s_itemsize); + Py_CLEAR(clear_module_state->__pyx_kp_s_itemsize_0_for_cython_array); + Py_CLEAR(clear_module_state->__pyx_n_s_main); + Py_CLEAR(clear_module_state->__pyx_n_s_memview); + Py_CLEAR(clear_module_state->__pyx_n_s_mode); + Py_CLEAR(clear_module_state->__pyx_n_s_name); + Py_CLEAR(clear_module_state->__pyx_n_s_name_2); + Py_CLEAR(clear_module_state->__pyx_n_s_ndim); + Py_CLEAR(clear_module_state->__pyx_n_s_new); + Py_CLEAR(clear_module_state->__pyx_kp_s_no_default___reduce___due_to_non); + Py_CLEAR(clear_module_state->__pyx_n_s_obj); + Py_CLEAR(clear_module_state->__pyx_n_s_output); + Py_CLEAR(clear_module_state->__pyx_n_s_pack); + Py_CLEAR(clear_module_state->__pyx_n_s_path); + Py_CLEAR(clear_module_state->__pyx_n_s_pickle); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_PickleError); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_checksum); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_result); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_state); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_type); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_unpickle_Enum); + Py_CLEAR(clear_module_state->__pyx_n_s_pyx_vtable); + Py_CLEAR(clear_module_state->__pyx_n_s_range); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_reduce_ex); + Py_CLEAR(clear_module_state->__pyx_n_s_register); + Py_CLEAR(clear_module_state->__pyx_n_s_runtime); + Py_CLEAR(clear_module_state->__pyx_n_s_self); + Py_CLEAR(clear_module_state->__pyx_n_s_selfdrive_modeld_runners_thneedm); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate); + Py_CLEAR(clear_module_state->__pyx_n_s_setstate_cython); + Py_CLEAR(clear_module_state->__pyx_n_s_shape); + Py_CLEAR(clear_module_state->__pyx_n_s_size); + Py_CLEAR(clear_module_state->__pyx_n_s_spec); + Py_CLEAR(clear_module_state->__pyx_n_s_start); + Py_CLEAR(clear_module_state->__pyx_n_s_step); + Py_CLEAR(clear_module_state->__pyx_n_s_stop); + Py_CLEAR(clear_module_state->__pyx_kp_s_strided_and_direct); + Py_CLEAR(clear_module_state->__pyx_kp_s_strided_and_direct_or_indirect); + Py_CLEAR(clear_module_state->__pyx_kp_s_strided_and_indirect); + Py_CLEAR(clear_module_state->__pyx_kp_s_stringsource); + Py_CLEAR(clear_module_state->__pyx_n_s_struct); + Py_CLEAR(clear_module_state->__pyx_n_s_sys); + Py_CLEAR(clear_module_state->__pyx_n_s_test); + Py_CLEAR(clear_module_state->__pyx_kp_s_unable_to_allocate_array_data); + Py_CLEAR(clear_module_state->__pyx_kp_s_unable_to_allocate_shape_and_str); + Py_CLEAR(clear_module_state->__pyx_n_s_unpack); + Py_CLEAR(clear_module_state->__pyx_n_s_update); + Py_CLEAR(clear_module_state->__pyx_n_s_use_tf8); + Py_CLEAR(clear_module_state->__pyx_n_s_version_info); + Py_CLEAR(clear_module_state->__pyx_int_0); + Py_CLEAR(clear_module_state->__pyx_int_1); + Py_CLEAR(clear_module_state->__pyx_int_3); + Py_CLEAR(clear_module_state->__pyx_int_112105877); + Py_CLEAR(clear_module_state->__pyx_int_136983863); + Py_CLEAR(clear_module_state->__pyx_int_184977713); + Py_CLEAR(clear_module_state->__pyx_int_neg_1); + Py_CLEAR(clear_module_state->__pyx_slice__5); + Py_CLEAR(clear_module_state->__pyx_tuple__4); + Py_CLEAR(clear_module_state->__pyx_tuple__8); + Py_CLEAR(clear_module_state->__pyx_tuple__9); + Py_CLEAR(clear_module_state->__pyx_tuple__10); + Py_CLEAR(clear_module_state->__pyx_tuple__11); + Py_CLEAR(clear_module_state->__pyx_tuple__12); + Py_CLEAR(clear_module_state->__pyx_tuple__13); + Py_CLEAR(clear_module_state->__pyx_tuple__14); + Py_CLEAR(clear_module_state->__pyx_tuple__15); + Py_CLEAR(clear_module_state->__pyx_tuple__16); + Py_CLEAR(clear_module_state->__pyx_tuple__17); + Py_CLEAR(clear_module_state->__pyx_tuple__18); + Py_CLEAR(clear_module_state->__pyx_tuple__20); + Py_CLEAR(clear_module_state->__pyx_tuple__22); + Py_CLEAR(clear_module_state->__pyx_codeobj__19); + Py_CLEAR(clear_module_state->__pyx_codeobj__21); + Py_CLEAR(clear_module_state->__pyx_codeobj__23); + return 0; +} +#endif +/* #### Code section: module_state_traverse ### */ +#if CYTHON_USE_MODULE_STATE +static int __pyx_m_traverse(PyObject *m, visitproc visit, void *arg) { + __pyx_mstate *traverse_module_state = __pyx_mstate(m); + if (!traverse_module_state) return 0; + Py_VISIT(traverse_module_state->__pyx_d); + Py_VISIT(traverse_module_state->__pyx_b); + Py_VISIT(traverse_module_state->__pyx_cython_runtime); + Py_VISIT(traverse_module_state->__pyx_empty_tuple); + Py_VISIT(traverse_module_state->__pyx_empty_bytes); + Py_VISIT(traverse_module_state->__pyx_empty_unicode); + #ifdef __Pyx_CyFunction_USED + Py_VISIT(traverse_module_state->__pyx_CyFunctionType); + #endif + #ifdef __Pyx_FusedFunction_USED + Py_VISIT(traverse_module_state->__pyx_FusedFunctionType); + #endif + Py_VISIT(traverse_module_state->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext); + Py_VISIT(traverse_module_state->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf); + Py_VISIT(traverse_module_state->__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext); + Py_VISIT(traverse_module_state->__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem); + Py_VISIT(traverse_module_state->__pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel); + Py_VISIT(traverse_module_state->__pyx_ptype_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel); + Py_VISIT(traverse_module_state->__pyx_type_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel); + Py_VISIT(traverse_module_state->__pyx_array_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_array); + Py_VISIT(traverse_module_state->__pyx_MemviewEnum_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_MemviewEnum); + Py_VISIT(traverse_module_state->__pyx_memoryview_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_memoryview); + Py_VISIT(traverse_module_state->__pyx_memoryviewslice_type); + Py_VISIT(traverse_module_state->__pyx_type___pyx_memoryviewslice); + Py_VISIT(traverse_module_state->__pyx_kp_u_); + Py_VISIT(traverse_module_state->__pyx_n_s_ASCII); + Py_VISIT(traverse_module_state->__pyx_kp_s_All_dimensions_preceding_dimensi); + Py_VISIT(traverse_module_state->__pyx_n_s_AssertionError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Buffer_view_does_not_expose_stri); + Py_VISIT(traverse_module_state->__pyx_kp_s_Can_only_create_a_buffer_that_is); + Py_VISIT(traverse_module_state->__pyx_kp_s_Cannot_assign_to_read_only_memor); + Py_VISIT(traverse_module_state->__pyx_kp_s_Cannot_create_writable_memory_vi); + Py_VISIT(traverse_module_state->__pyx_kp_u_Cannot_index_with_type); + Py_VISIT(traverse_module_state->__pyx_kp_s_Cannot_transpose_memoryview_with); + Py_VISIT(traverse_module_state->__pyx_kp_s_Dimension_d_is_not_direct); + Py_VISIT(traverse_module_state->__pyx_n_s_Ellipsis); + Py_VISIT(traverse_module_state->__pyx_kp_s_Empty_shape_tuple_for_cython_arr); + Py_VISIT(traverse_module_state->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0); + Py_VISIT(traverse_module_state->__pyx_n_s_IndexError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Index_out_of_bounds_axis_d); + Py_VISIT(traverse_module_state->__pyx_kp_s_Indirect_dimensions_not_supporte); + Py_VISIT(traverse_module_state->__pyx_kp_u_Invalid_mode_expected_c_or_fortr); + Py_VISIT(traverse_module_state->__pyx_kp_u_Invalid_shape_in_axis); + Py_VISIT(traverse_module_state->__pyx_n_s_MemoryError); + Py_VISIT(traverse_module_state->__pyx_kp_s_MemoryView_of_r_at_0x_x); + Py_VISIT(traverse_module_state->__pyx_kp_s_MemoryView_of_r_object); + Py_VISIT(traverse_module_state->__pyx_n_b_O); + Py_VISIT(traverse_module_state->__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + Py_VISIT(traverse_module_state->__pyx_n_s_PickleError); + Py_VISIT(traverse_module_state->__pyx_n_s_Sequence); + Py_VISIT(traverse_module_state->__pyx_kp_s_Step_may_not_be_zero_axis_d); + Py_VISIT(traverse_module_state->__pyx_n_s_ThneedModel); + Py_VISIT(traverse_module_state->__pyx_n_s_ThneedModel___reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_ThneedModel___setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_TypeError); + Py_VISIT(traverse_module_state->__pyx_kp_s_Unable_to_convert_item_to_object); + Py_VISIT(traverse_module_state->__pyx_n_s_ValueError); + Py_VISIT(traverse_module_state->__pyx_n_s_View_MemoryView); + Py_VISIT(traverse_module_state->__pyx_kp_u__2); + Py_VISIT(traverse_module_state->__pyx_n_s__24); + Py_VISIT(traverse_module_state->__pyx_n_s__3); + Py_VISIT(traverse_module_state->__pyx_kp_u__6); + Py_VISIT(traverse_module_state->__pyx_kp_u__7); + Py_VISIT(traverse_module_state->__pyx_n_s_abc); + Py_VISIT(traverse_module_state->__pyx_n_s_allocate_buffer); + Py_VISIT(traverse_module_state->__pyx_kp_u_and); + Py_VISIT(traverse_module_state->__pyx_n_s_asyncio_coroutines); + Py_VISIT(traverse_module_state->__pyx_n_s_base); + Py_VISIT(traverse_module_state->__pyx_n_s_c); + Py_VISIT(traverse_module_state->__pyx_n_u_c); + Py_VISIT(traverse_module_state->__pyx_n_s_class); + Py_VISIT(traverse_module_state->__pyx_n_s_class_getitem); + Py_VISIT(traverse_module_state->__pyx_n_s_cline_in_traceback); + Py_VISIT(traverse_module_state->__pyx_n_s_collections); + Py_VISIT(traverse_module_state->__pyx_kp_s_collections_abc); + Py_VISIT(traverse_module_state->__pyx_n_s_context); + Py_VISIT(traverse_module_state->__pyx_kp_s_contiguous_and_direct); + Py_VISIT(traverse_module_state->__pyx_kp_s_contiguous_and_indirect); + Py_VISIT(traverse_module_state->__pyx_n_s_count); + Py_VISIT(traverse_module_state->__pyx_n_s_dict); + Py_VISIT(traverse_module_state->__pyx_kp_u_disable); + Py_VISIT(traverse_module_state->__pyx_n_s_dtype_is_object); + Py_VISIT(traverse_module_state->__pyx_kp_u_enable); + Py_VISIT(traverse_module_state->__pyx_n_s_encode); + Py_VISIT(traverse_module_state->__pyx_n_s_enumerate); + Py_VISIT(traverse_module_state->__pyx_n_s_error); + Py_VISIT(traverse_module_state->__pyx_n_s_flags); + Py_VISIT(traverse_module_state->__pyx_n_s_format); + Py_VISIT(traverse_module_state->__pyx_n_s_fortran); + Py_VISIT(traverse_module_state->__pyx_n_u_fortran); + Py_VISIT(traverse_module_state->__pyx_kp_u_gc); + Py_VISIT(traverse_module_state->__pyx_n_s_getstate); + Py_VISIT(traverse_module_state->__pyx_kp_u_got); + Py_VISIT(traverse_module_state->__pyx_kp_u_got_differing_extents_in_dimensi); + Py_VISIT(traverse_module_state->__pyx_n_s_id); + Py_VISIT(traverse_module_state->__pyx_n_s_import); + Py_VISIT(traverse_module_state->__pyx_n_s_index); + Py_VISIT(traverse_module_state->__pyx_n_s_initializing); + Py_VISIT(traverse_module_state->__pyx_n_s_is_coroutine); + Py_VISIT(traverse_module_state->__pyx_kp_u_isenabled); + Py_VISIT(traverse_module_state->__pyx_n_s_itemsize); + Py_VISIT(traverse_module_state->__pyx_kp_s_itemsize_0_for_cython_array); + Py_VISIT(traverse_module_state->__pyx_n_s_main); + Py_VISIT(traverse_module_state->__pyx_n_s_memview); + Py_VISIT(traverse_module_state->__pyx_n_s_mode); + Py_VISIT(traverse_module_state->__pyx_n_s_name); + Py_VISIT(traverse_module_state->__pyx_n_s_name_2); + Py_VISIT(traverse_module_state->__pyx_n_s_ndim); + Py_VISIT(traverse_module_state->__pyx_n_s_new); + Py_VISIT(traverse_module_state->__pyx_kp_s_no_default___reduce___due_to_non); + Py_VISIT(traverse_module_state->__pyx_n_s_obj); + Py_VISIT(traverse_module_state->__pyx_n_s_output); + Py_VISIT(traverse_module_state->__pyx_n_s_pack); + Py_VISIT(traverse_module_state->__pyx_n_s_path); + Py_VISIT(traverse_module_state->__pyx_n_s_pickle); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_PickleError); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_checksum); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_result); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_state); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_type); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_unpickle_Enum); + Py_VISIT(traverse_module_state->__pyx_n_s_pyx_vtable); + Py_VISIT(traverse_module_state->__pyx_n_s_range); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_reduce_ex); + Py_VISIT(traverse_module_state->__pyx_n_s_register); + Py_VISIT(traverse_module_state->__pyx_n_s_runtime); + Py_VISIT(traverse_module_state->__pyx_n_s_self); + Py_VISIT(traverse_module_state->__pyx_n_s_selfdrive_modeld_runners_thneedm); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate); + Py_VISIT(traverse_module_state->__pyx_n_s_setstate_cython); + Py_VISIT(traverse_module_state->__pyx_n_s_shape); + Py_VISIT(traverse_module_state->__pyx_n_s_size); + Py_VISIT(traverse_module_state->__pyx_n_s_spec); + Py_VISIT(traverse_module_state->__pyx_n_s_start); + Py_VISIT(traverse_module_state->__pyx_n_s_step); + Py_VISIT(traverse_module_state->__pyx_n_s_stop); + Py_VISIT(traverse_module_state->__pyx_kp_s_strided_and_direct); + Py_VISIT(traverse_module_state->__pyx_kp_s_strided_and_direct_or_indirect); + Py_VISIT(traverse_module_state->__pyx_kp_s_strided_and_indirect); + Py_VISIT(traverse_module_state->__pyx_kp_s_stringsource); + Py_VISIT(traverse_module_state->__pyx_n_s_struct); + Py_VISIT(traverse_module_state->__pyx_n_s_sys); + Py_VISIT(traverse_module_state->__pyx_n_s_test); + Py_VISIT(traverse_module_state->__pyx_kp_s_unable_to_allocate_array_data); + Py_VISIT(traverse_module_state->__pyx_kp_s_unable_to_allocate_shape_and_str); + Py_VISIT(traverse_module_state->__pyx_n_s_unpack); + Py_VISIT(traverse_module_state->__pyx_n_s_update); + Py_VISIT(traverse_module_state->__pyx_n_s_use_tf8); + Py_VISIT(traverse_module_state->__pyx_n_s_version_info); + Py_VISIT(traverse_module_state->__pyx_int_0); + Py_VISIT(traverse_module_state->__pyx_int_1); + Py_VISIT(traverse_module_state->__pyx_int_3); + Py_VISIT(traverse_module_state->__pyx_int_112105877); + Py_VISIT(traverse_module_state->__pyx_int_136983863); + Py_VISIT(traverse_module_state->__pyx_int_184977713); + Py_VISIT(traverse_module_state->__pyx_int_neg_1); + Py_VISIT(traverse_module_state->__pyx_slice__5); + Py_VISIT(traverse_module_state->__pyx_tuple__4); + Py_VISIT(traverse_module_state->__pyx_tuple__8); + Py_VISIT(traverse_module_state->__pyx_tuple__9); + Py_VISIT(traverse_module_state->__pyx_tuple__10); + Py_VISIT(traverse_module_state->__pyx_tuple__11); + Py_VISIT(traverse_module_state->__pyx_tuple__12); + Py_VISIT(traverse_module_state->__pyx_tuple__13); + Py_VISIT(traverse_module_state->__pyx_tuple__14); + Py_VISIT(traverse_module_state->__pyx_tuple__15); + Py_VISIT(traverse_module_state->__pyx_tuple__16); + Py_VISIT(traverse_module_state->__pyx_tuple__17); + Py_VISIT(traverse_module_state->__pyx_tuple__18); + Py_VISIT(traverse_module_state->__pyx_tuple__20); + Py_VISIT(traverse_module_state->__pyx_tuple__22); + Py_VISIT(traverse_module_state->__pyx_codeobj__19); + Py_VISIT(traverse_module_state->__pyx_codeobj__21); + Py_VISIT(traverse_module_state->__pyx_codeobj__23); + return 0; +} +#endif +/* #### Code section: module_state_defines ### */ +#define __pyx_d __pyx_mstate_global->__pyx_d +#define __pyx_b __pyx_mstate_global->__pyx_b +#define __pyx_cython_runtime __pyx_mstate_global->__pyx_cython_runtime +#define __pyx_empty_tuple __pyx_mstate_global->__pyx_empty_tuple +#define __pyx_empty_bytes __pyx_mstate_global->__pyx_empty_bytes +#define __pyx_empty_unicode __pyx_mstate_global->__pyx_empty_unicode +#ifdef __Pyx_CyFunction_USED +#define __pyx_CyFunctionType __pyx_mstate_global->__pyx_CyFunctionType +#endif +#ifdef __Pyx_FusedFunction_USED +#define __pyx_FusedFunctionType __pyx_mstate_global->__pyx_FusedFunctionType +#endif +#ifdef __Pyx_Generator_USED +#define __pyx_GeneratorType __pyx_mstate_global->__pyx_GeneratorType +#endif +#ifdef __Pyx_IterableCoroutine_USED +#define __pyx_IterableCoroutineType __pyx_mstate_global->__pyx_IterableCoroutineType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineAwaitType __pyx_mstate_global->__pyx_CoroutineAwaitType +#endif +#ifdef __Pyx_Coroutine_USED +#define __pyx_CoroutineType __pyx_mstate_global->__pyx_CoroutineType +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#define __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext __pyx_mstate_global->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext +#define __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf __pyx_mstate_global->__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf +#if CYTHON_USE_MODULE_STATE +#endif +#define __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext __pyx_mstate_global->__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext +#define __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem __pyx_mstate_global->__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem +#if CYTHON_USE_MODULE_STATE +#endif +#if CYTHON_USE_MODULE_STATE +#endif +#define __pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel __pyx_mstate_global->__pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel +#if CYTHON_USE_MODULE_STATE +#define __pyx_type_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel __pyx_mstate_global->__pyx_type_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel +#define __pyx_type___pyx_array __pyx_mstate_global->__pyx_type___pyx_array +#define __pyx_type___pyx_MemviewEnum __pyx_mstate_global->__pyx_type___pyx_MemviewEnum +#define __pyx_type___pyx_memoryview __pyx_mstate_global->__pyx_type___pyx_memoryview +#define __pyx_type___pyx_memoryviewslice __pyx_mstate_global->__pyx_type___pyx_memoryviewslice +#endif +#define __pyx_ptype_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel __pyx_mstate_global->__pyx_ptype_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel +#define __pyx_array_type __pyx_mstate_global->__pyx_array_type +#define __pyx_MemviewEnum_type __pyx_mstate_global->__pyx_MemviewEnum_type +#define __pyx_memoryview_type __pyx_mstate_global->__pyx_memoryview_type +#define __pyx_memoryviewslice_type __pyx_mstate_global->__pyx_memoryviewslice_type +#define __pyx_kp_u_ __pyx_mstate_global->__pyx_kp_u_ +#define __pyx_n_s_ASCII __pyx_mstate_global->__pyx_n_s_ASCII +#define __pyx_kp_s_All_dimensions_preceding_dimensi __pyx_mstate_global->__pyx_kp_s_All_dimensions_preceding_dimensi +#define __pyx_n_s_AssertionError __pyx_mstate_global->__pyx_n_s_AssertionError +#define __pyx_kp_s_Buffer_view_does_not_expose_stri __pyx_mstate_global->__pyx_kp_s_Buffer_view_does_not_expose_stri +#define __pyx_kp_s_Can_only_create_a_buffer_that_is __pyx_mstate_global->__pyx_kp_s_Can_only_create_a_buffer_that_is +#define __pyx_kp_s_Cannot_assign_to_read_only_memor __pyx_mstate_global->__pyx_kp_s_Cannot_assign_to_read_only_memor +#define __pyx_kp_s_Cannot_create_writable_memory_vi __pyx_mstate_global->__pyx_kp_s_Cannot_create_writable_memory_vi +#define __pyx_kp_u_Cannot_index_with_type __pyx_mstate_global->__pyx_kp_u_Cannot_index_with_type +#define __pyx_kp_s_Cannot_transpose_memoryview_with __pyx_mstate_global->__pyx_kp_s_Cannot_transpose_memoryview_with +#define __pyx_kp_s_Dimension_d_is_not_direct __pyx_mstate_global->__pyx_kp_s_Dimension_d_is_not_direct +#define __pyx_n_s_Ellipsis __pyx_mstate_global->__pyx_n_s_Ellipsis +#define __pyx_kp_s_Empty_shape_tuple_for_cython_arr __pyx_mstate_global->__pyx_kp_s_Empty_shape_tuple_for_cython_arr +#define __pyx_kp_s_Incompatible_checksums_0x_x_vs_0 __pyx_mstate_global->__pyx_kp_s_Incompatible_checksums_0x_x_vs_0 +#define __pyx_n_s_IndexError __pyx_mstate_global->__pyx_n_s_IndexError +#define __pyx_kp_s_Index_out_of_bounds_axis_d __pyx_mstate_global->__pyx_kp_s_Index_out_of_bounds_axis_d +#define __pyx_kp_s_Indirect_dimensions_not_supporte __pyx_mstate_global->__pyx_kp_s_Indirect_dimensions_not_supporte +#define __pyx_kp_u_Invalid_mode_expected_c_or_fortr __pyx_mstate_global->__pyx_kp_u_Invalid_mode_expected_c_or_fortr +#define __pyx_kp_u_Invalid_shape_in_axis __pyx_mstate_global->__pyx_kp_u_Invalid_shape_in_axis +#define __pyx_n_s_MemoryError __pyx_mstate_global->__pyx_n_s_MemoryError +#define __pyx_kp_s_MemoryView_of_r_at_0x_x __pyx_mstate_global->__pyx_kp_s_MemoryView_of_r_at_0x_x +#define __pyx_kp_s_MemoryView_of_r_object __pyx_mstate_global->__pyx_kp_s_MemoryView_of_r_object +#define __pyx_n_b_O __pyx_mstate_global->__pyx_n_b_O +#define __pyx_kp_u_Out_of_bounds_on_buffer_access_a __pyx_mstate_global->__pyx_kp_u_Out_of_bounds_on_buffer_access_a +#define __pyx_n_s_PickleError __pyx_mstate_global->__pyx_n_s_PickleError +#define __pyx_n_s_Sequence __pyx_mstate_global->__pyx_n_s_Sequence +#define __pyx_kp_s_Step_may_not_be_zero_axis_d __pyx_mstate_global->__pyx_kp_s_Step_may_not_be_zero_axis_d +#define __pyx_n_s_ThneedModel __pyx_mstate_global->__pyx_n_s_ThneedModel +#define __pyx_n_s_ThneedModel___reduce_cython __pyx_mstate_global->__pyx_n_s_ThneedModel___reduce_cython +#define __pyx_n_s_ThneedModel___setstate_cython __pyx_mstate_global->__pyx_n_s_ThneedModel___setstate_cython +#define __pyx_n_s_TypeError __pyx_mstate_global->__pyx_n_s_TypeError +#define __pyx_kp_s_Unable_to_convert_item_to_object __pyx_mstate_global->__pyx_kp_s_Unable_to_convert_item_to_object +#define __pyx_n_s_ValueError __pyx_mstate_global->__pyx_n_s_ValueError +#define __pyx_n_s_View_MemoryView __pyx_mstate_global->__pyx_n_s_View_MemoryView +#define __pyx_kp_u__2 __pyx_mstate_global->__pyx_kp_u__2 +#define __pyx_n_s__24 __pyx_mstate_global->__pyx_n_s__24 +#define __pyx_n_s__3 __pyx_mstate_global->__pyx_n_s__3 +#define __pyx_kp_u__6 __pyx_mstate_global->__pyx_kp_u__6 +#define __pyx_kp_u__7 __pyx_mstate_global->__pyx_kp_u__7 +#define __pyx_n_s_abc __pyx_mstate_global->__pyx_n_s_abc +#define __pyx_n_s_allocate_buffer __pyx_mstate_global->__pyx_n_s_allocate_buffer +#define __pyx_kp_u_and __pyx_mstate_global->__pyx_kp_u_and +#define __pyx_n_s_asyncio_coroutines __pyx_mstate_global->__pyx_n_s_asyncio_coroutines +#define __pyx_n_s_base __pyx_mstate_global->__pyx_n_s_base +#define __pyx_n_s_c __pyx_mstate_global->__pyx_n_s_c +#define __pyx_n_u_c __pyx_mstate_global->__pyx_n_u_c +#define __pyx_n_s_class __pyx_mstate_global->__pyx_n_s_class +#define __pyx_n_s_class_getitem __pyx_mstate_global->__pyx_n_s_class_getitem +#define __pyx_n_s_cline_in_traceback __pyx_mstate_global->__pyx_n_s_cline_in_traceback +#define __pyx_n_s_collections __pyx_mstate_global->__pyx_n_s_collections +#define __pyx_kp_s_collections_abc __pyx_mstate_global->__pyx_kp_s_collections_abc +#define __pyx_n_s_context __pyx_mstate_global->__pyx_n_s_context +#define __pyx_kp_s_contiguous_and_direct __pyx_mstate_global->__pyx_kp_s_contiguous_and_direct +#define __pyx_kp_s_contiguous_and_indirect __pyx_mstate_global->__pyx_kp_s_contiguous_and_indirect +#define __pyx_n_s_count __pyx_mstate_global->__pyx_n_s_count +#define __pyx_n_s_dict __pyx_mstate_global->__pyx_n_s_dict +#define __pyx_kp_u_disable __pyx_mstate_global->__pyx_kp_u_disable +#define __pyx_n_s_dtype_is_object __pyx_mstate_global->__pyx_n_s_dtype_is_object +#define __pyx_kp_u_enable __pyx_mstate_global->__pyx_kp_u_enable +#define __pyx_n_s_encode __pyx_mstate_global->__pyx_n_s_encode +#define __pyx_n_s_enumerate __pyx_mstate_global->__pyx_n_s_enumerate +#define __pyx_n_s_error __pyx_mstate_global->__pyx_n_s_error +#define __pyx_n_s_flags __pyx_mstate_global->__pyx_n_s_flags +#define __pyx_n_s_format __pyx_mstate_global->__pyx_n_s_format +#define __pyx_n_s_fortran __pyx_mstate_global->__pyx_n_s_fortran +#define __pyx_n_u_fortran __pyx_mstate_global->__pyx_n_u_fortran +#define __pyx_kp_u_gc __pyx_mstate_global->__pyx_kp_u_gc +#define __pyx_n_s_getstate __pyx_mstate_global->__pyx_n_s_getstate +#define __pyx_kp_u_got __pyx_mstate_global->__pyx_kp_u_got +#define __pyx_kp_u_got_differing_extents_in_dimensi __pyx_mstate_global->__pyx_kp_u_got_differing_extents_in_dimensi +#define __pyx_n_s_id __pyx_mstate_global->__pyx_n_s_id +#define __pyx_n_s_import __pyx_mstate_global->__pyx_n_s_import +#define __pyx_n_s_index __pyx_mstate_global->__pyx_n_s_index +#define __pyx_n_s_initializing __pyx_mstate_global->__pyx_n_s_initializing +#define __pyx_n_s_is_coroutine __pyx_mstate_global->__pyx_n_s_is_coroutine +#define __pyx_kp_u_isenabled __pyx_mstate_global->__pyx_kp_u_isenabled +#define __pyx_n_s_itemsize __pyx_mstate_global->__pyx_n_s_itemsize +#define __pyx_kp_s_itemsize_0_for_cython_array __pyx_mstate_global->__pyx_kp_s_itemsize_0_for_cython_array +#define __pyx_n_s_main __pyx_mstate_global->__pyx_n_s_main +#define __pyx_n_s_memview __pyx_mstate_global->__pyx_n_s_memview +#define __pyx_n_s_mode __pyx_mstate_global->__pyx_n_s_mode +#define __pyx_n_s_name __pyx_mstate_global->__pyx_n_s_name +#define __pyx_n_s_name_2 __pyx_mstate_global->__pyx_n_s_name_2 +#define __pyx_n_s_ndim __pyx_mstate_global->__pyx_n_s_ndim +#define __pyx_n_s_new __pyx_mstate_global->__pyx_n_s_new +#define __pyx_kp_s_no_default___reduce___due_to_non __pyx_mstate_global->__pyx_kp_s_no_default___reduce___due_to_non +#define __pyx_n_s_obj __pyx_mstate_global->__pyx_n_s_obj +#define __pyx_n_s_output __pyx_mstate_global->__pyx_n_s_output +#define __pyx_n_s_pack __pyx_mstate_global->__pyx_n_s_pack +#define __pyx_n_s_path __pyx_mstate_global->__pyx_n_s_path +#define __pyx_n_s_pickle __pyx_mstate_global->__pyx_n_s_pickle +#define __pyx_n_s_pyx_PickleError __pyx_mstate_global->__pyx_n_s_pyx_PickleError +#define __pyx_n_s_pyx_checksum __pyx_mstate_global->__pyx_n_s_pyx_checksum +#define __pyx_n_s_pyx_result __pyx_mstate_global->__pyx_n_s_pyx_result +#define __pyx_n_s_pyx_state __pyx_mstate_global->__pyx_n_s_pyx_state +#define __pyx_n_s_pyx_type __pyx_mstate_global->__pyx_n_s_pyx_type +#define __pyx_n_s_pyx_unpickle_Enum __pyx_mstate_global->__pyx_n_s_pyx_unpickle_Enum +#define __pyx_n_s_pyx_vtable __pyx_mstate_global->__pyx_n_s_pyx_vtable +#define __pyx_n_s_range __pyx_mstate_global->__pyx_n_s_range +#define __pyx_n_s_reduce __pyx_mstate_global->__pyx_n_s_reduce +#define __pyx_n_s_reduce_cython __pyx_mstate_global->__pyx_n_s_reduce_cython +#define __pyx_n_s_reduce_ex __pyx_mstate_global->__pyx_n_s_reduce_ex +#define __pyx_n_s_register __pyx_mstate_global->__pyx_n_s_register +#define __pyx_n_s_runtime __pyx_mstate_global->__pyx_n_s_runtime +#define __pyx_n_s_self __pyx_mstate_global->__pyx_n_s_self +#define __pyx_n_s_selfdrive_modeld_runners_thneedm __pyx_mstate_global->__pyx_n_s_selfdrive_modeld_runners_thneedm +#define __pyx_n_s_setstate __pyx_mstate_global->__pyx_n_s_setstate +#define __pyx_n_s_setstate_cython __pyx_mstate_global->__pyx_n_s_setstate_cython +#define __pyx_n_s_shape __pyx_mstate_global->__pyx_n_s_shape +#define __pyx_n_s_size __pyx_mstate_global->__pyx_n_s_size +#define __pyx_n_s_spec __pyx_mstate_global->__pyx_n_s_spec +#define __pyx_n_s_start __pyx_mstate_global->__pyx_n_s_start +#define __pyx_n_s_step __pyx_mstate_global->__pyx_n_s_step +#define __pyx_n_s_stop __pyx_mstate_global->__pyx_n_s_stop +#define __pyx_kp_s_strided_and_direct __pyx_mstate_global->__pyx_kp_s_strided_and_direct +#define __pyx_kp_s_strided_and_direct_or_indirect __pyx_mstate_global->__pyx_kp_s_strided_and_direct_or_indirect +#define __pyx_kp_s_strided_and_indirect __pyx_mstate_global->__pyx_kp_s_strided_and_indirect +#define __pyx_kp_s_stringsource __pyx_mstate_global->__pyx_kp_s_stringsource +#define __pyx_n_s_struct __pyx_mstate_global->__pyx_n_s_struct +#define __pyx_n_s_sys __pyx_mstate_global->__pyx_n_s_sys +#define __pyx_n_s_test __pyx_mstate_global->__pyx_n_s_test +#define __pyx_kp_s_unable_to_allocate_array_data __pyx_mstate_global->__pyx_kp_s_unable_to_allocate_array_data +#define __pyx_kp_s_unable_to_allocate_shape_and_str __pyx_mstate_global->__pyx_kp_s_unable_to_allocate_shape_and_str +#define __pyx_n_s_unpack __pyx_mstate_global->__pyx_n_s_unpack +#define __pyx_n_s_update __pyx_mstate_global->__pyx_n_s_update +#define __pyx_n_s_use_tf8 __pyx_mstate_global->__pyx_n_s_use_tf8 +#define __pyx_n_s_version_info __pyx_mstate_global->__pyx_n_s_version_info +#define __pyx_int_0 __pyx_mstate_global->__pyx_int_0 +#define __pyx_int_1 __pyx_mstate_global->__pyx_int_1 +#define __pyx_int_3 __pyx_mstate_global->__pyx_int_3 +#define __pyx_int_112105877 __pyx_mstate_global->__pyx_int_112105877 +#define __pyx_int_136983863 __pyx_mstate_global->__pyx_int_136983863 +#define __pyx_int_184977713 __pyx_mstate_global->__pyx_int_184977713 +#define __pyx_int_neg_1 __pyx_mstate_global->__pyx_int_neg_1 +#define __pyx_slice__5 __pyx_mstate_global->__pyx_slice__5 +#define __pyx_tuple__4 __pyx_mstate_global->__pyx_tuple__4 +#define __pyx_tuple__8 __pyx_mstate_global->__pyx_tuple__8 +#define __pyx_tuple__9 __pyx_mstate_global->__pyx_tuple__9 +#define __pyx_tuple__10 __pyx_mstate_global->__pyx_tuple__10 +#define __pyx_tuple__11 __pyx_mstate_global->__pyx_tuple__11 +#define __pyx_tuple__12 __pyx_mstate_global->__pyx_tuple__12 +#define __pyx_tuple__13 __pyx_mstate_global->__pyx_tuple__13 +#define __pyx_tuple__14 __pyx_mstate_global->__pyx_tuple__14 +#define __pyx_tuple__15 __pyx_mstate_global->__pyx_tuple__15 +#define __pyx_tuple__16 __pyx_mstate_global->__pyx_tuple__16 +#define __pyx_tuple__17 __pyx_mstate_global->__pyx_tuple__17 +#define __pyx_tuple__18 __pyx_mstate_global->__pyx_tuple__18 +#define __pyx_tuple__20 __pyx_mstate_global->__pyx_tuple__20 +#define __pyx_tuple__22 __pyx_mstate_global->__pyx_tuple__22 +#define __pyx_codeobj__19 __pyx_mstate_global->__pyx_codeobj__19 +#define __pyx_codeobj__21 __pyx_mstate_global->__pyx_codeobj__21 +#define __pyx_codeobj__23 __pyx_mstate_global->__pyx_codeobj__23 +/* #### Code section: module_code ### */ + +/* "string.from_py":13 + * + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: # <<<<<<<<<<<<<< + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + */ + +static std::string __pyx_convert_string_from_py_std__in_string(PyObject *__pyx_v_o) { + Py_ssize_t __pyx_v_length; + char const *__pyx_v_data; + std::string __pyx_r; + char const *__pyx_t_1; + std::string __pyx_t_2; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + + /* "string.from_py":14 + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: + * cdef Py_ssize_t length = 0 # <<<<<<<<<<<<<< + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + * return string(data, length) + */ + __pyx_v_length = 0; + + /* "string.from_py":15 + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) # <<<<<<<<<<<<<< + * return string(data, length) + * + */ + __pyx_t_1 = __Pyx_PyObject_AsStringAndSize(__pyx_v_o, (&__pyx_v_length)); if (unlikely(__pyx_t_1 == ((char const *)NULL))) __PYX_ERR(0, 15, __pyx_L1_error) + __pyx_v_data = __pyx_t_1; + + /* "string.from_py":16 + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + * return string(data, length) # <<<<<<<<<<<<<< + * + * + */ + try { + __pyx_t_2 = std::string(__pyx_v_data, __pyx_v_length); + } catch(...) { + __Pyx_CppExn2PyErr(); + __PYX_ERR(0, 16, __pyx_L1_error) + } + __pyx_r = __pyx_t_2; + goto __pyx_L0; + + /* "string.from_py":13 + * + * @cname("__pyx_convert_string_from_py_std__in_string") + * cdef string __pyx_convert_string_from_py_std__in_string(object o) except *: # <<<<<<<<<<<<<< + * cdef Py_ssize_t length = 0 + * cdef const char* data = __Pyx_PyObject_AsStringAndSize(o, &length) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("string.from_py.__pyx_convert_string_from_py_std__in_string", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_pretend_to_initialize(&__pyx_r); + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":131 + * cdef bint dtype_is_object + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, # <<<<<<<<<<<<<< + * mode="c", bint allocate_buffer=True): + * + */ + +/* Python wrapper */ +static int __pyx_array___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_array___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_shape = 0; + Py_ssize_t __pyx_v_itemsize; + PyObject *__pyx_v_format = 0; + PyObject *__pyx_v_mode = 0; + int __pyx_v_allocate_buffer; + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[5] = {0,0,0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_shape,&__pyx_n_s_itemsize,&__pyx_n_s_format,&__pyx_n_s_mode,&__pyx_n_s_allocate_buffer,0}; + values[3] = __Pyx_Arg_NewRef_VARARGS(((PyObject *)__pyx_n_s_c)); + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 5: values[4] = __Pyx_Arg_VARARGS(__pyx_args, 4); + CYTHON_FALLTHROUGH; + case 4: values[3] = __Pyx_Arg_VARARGS(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_shape)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 131, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_itemsize)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 131, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 3, 5, 1); __PYX_ERR(0, 131, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_format)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 131, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 3, 5, 2); __PYX_ERR(0, 131, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 3: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_mode); + if (value) { values[3] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 131, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 4: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_allocate_buffer); + if (value) { values[4] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 131, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(0, 131, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 5: values[4] = __Pyx_Arg_VARARGS(__pyx_args, 4); + CYTHON_FALLTHROUGH; + case 4: values[3] = __Pyx_Arg_VARARGS(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_shape = ((PyObject*)values[0]); + __pyx_v_itemsize = __Pyx_PyIndex_AsSsize_t(values[1]); if (unlikely((__pyx_v_itemsize == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 131, __pyx_L3_error) + __pyx_v_format = values[2]; + __pyx_v_mode = values[3]; + if (values[4]) { + __pyx_v_allocate_buffer = __Pyx_PyObject_IsTrue(values[4]); if (unlikely((__pyx_v_allocate_buffer == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 132, __pyx_L3_error) + } else { + + /* "View.MemoryView":132 + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, + * mode="c", bint allocate_buffer=True): # <<<<<<<<<<<<<< + * + * cdef int idx + */ + __pyx_v_allocate_buffer = ((int)1); + } + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 3, 5, __pyx_nargs); __PYX_ERR(0, 131, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.array.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_shape), (&PyTuple_Type), 1, "shape", 1))) __PYX_ERR(0, 131, __pyx_L1_error) + if (unlikely(((PyObject *)__pyx_v_format) == Py_None)) { + PyErr_Format(PyExc_TypeError, "Argument '%.200s' must not be None", "format"); __PYX_ERR(0, 131, __pyx_L1_error) + } + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array___cinit__(((struct __pyx_array_obj *)__pyx_v_self), __pyx_v_shape, __pyx_v_itemsize, __pyx_v_format, __pyx_v_mode, __pyx_v_allocate_buffer); + + /* "View.MemoryView":131 + * cdef bint dtype_is_object + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, # <<<<<<<<<<<<<< + * mode="c", bint allocate_buffer=True): + * + */ + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = -1; + __pyx_L0:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array___cinit__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_shape, Py_ssize_t __pyx_v_itemsize, PyObject *__pyx_v_format, PyObject *__pyx_v_mode, int __pyx_v_allocate_buffer) { + int __pyx_v_idx; + Py_ssize_t __pyx_v_dim; + char __pyx_v_order; + int __pyx_r; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + int __pyx_t_7; + char *__pyx_t_8; + Py_ssize_t __pyx_t_9; + Py_UCS4 __pyx_t_10; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__cinit__", 0); + __Pyx_INCREF(__pyx_v_format); + + /* "View.MemoryView":137 + * cdef Py_ssize_t dim + * + * self.ndim = len(shape) # <<<<<<<<<<<<<< + * self.itemsize = itemsize + * + */ + if (unlikely(__pyx_v_shape == Py_None)) { + PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); + __PYX_ERR(0, 137, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_PyTuple_GET_SIZE(__pyx_v_shape); if (unlikely(__pyx_t_1 == ((Py_ssize_t)-1))) __PYX_ERR(0, 137, __pyx_L1_error) + __pyx_v_self->ndim = ((int)__pyx_t_1); + + /* "View.MemoryView":138 + * + * self.ndim = len(shape) + * self.itemsize = itemsize # <<<<<<<<<<<<<< + * + * if not self.ndim: + */ + __pyx_v_self->itemsize = __pyx_v_itemsize; + + /* "View.MemoryView":140 + * self.itemsize = itemsize + * + * if not self.ndim: # <<<<<<<<<<<<<< + * raise ValueError, "Empty shape tuple for cython.array" + * + */ + __pyx_t_2 = (!(__pyx_v_self->ndim != 0)); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":141 + * + * if not self.ndim: + * raise ValueError, "Empty shape tuple for cython.array" # <<<<<<<<<<<<<< + * + * if itemsize <= 0: + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Empty_shape_tuple_for_cython_arr, 0, 0); + __PYX_ERR(0, 141, __pyx_L1_error) + + /* "View.MemoryView":140 + * self.itemsize = itemsize + * + * if not self.ndim: # <<<<<<<<<<<<<< + * raise ValueError, "Empty shape tuple for cython.array" + * + */ + } + + /* "View.MemoryView":143 + * raise ValueError, "Empty shape tuple for cython.array" + * + * if itemsize <= 0: # <<<<<<<<<<<<<< + * raise ValueError, "itemsize <= 0 for cython.array" + * + */ + __pyx_t_2 = (__pyx_v_itemsize <= 0); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":144 + * + * if itemsize <= 0: + * raise ValueError, "itemsize <= 0 for cython.array" # <<<<<<<<<<<<<< + * + * if not isinstance(format, bytes): + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_itemsize_0_for_cython_array, 0, 0); + __PYX_ERR(0, 144, __pyx_L1_error) + + /* "View.MemoryView":143 + * raise ValueError, "Empty shape tuple for cython.array" + * + * if itemsize <= 0: # <<<<<<<<<<<<<< + * raise ValueError, "itemsize <= 0 for cython.array" + * + */ + } + + /* "View.MemoryView":146 + * raise ValueError, "itemsize <= 0 for cython.array" + * + * if not isinstance(format, bytes): # <<<<<<<<<<<<<< + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string + */ + __pyx_t_2 = PyBytes_Check(__pyx_v_format); + __pyx_t_3 = (!__pyx_t_2); + if (__pyx_t_3) { + + /* "View.MemoryView":147 + * + * if not isinstance(format, bytes): + * format = format.encode('ASCII') # <<<<<<<<<<<<<< + * self._format = format # keep a reference to the byte string + * self.format = self._format + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_format, __pyx_n_s_encode); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 147, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = NULL; + __pyx_t_7 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_6 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_6)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_6); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_7 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_6, __pyx_n_s_ASCII}; + __pyx_t_4 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_7, 1+__pyx_t_7); + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 147, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + __Pyx_DECREF_SET(__pyx_v_format, __pyx_t_4); + __pyx_t_4 = 0; + + /* "View.MemoryView":146 + * raise ValueError, "itemsize <= 0 for cython.array" + * + * if not isinstance(format, bytes): # <<<<<<<<<<<<<< + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string + */ + } + + /* "View.MemoryView":148 + * if not isinstance(format, bytes): + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string # <<<<<<<<<<<<<< + * self.format = self._format + * + */ + if (!(likely(PyBytes_CheckExact(__pyx_v_format))||((__pyx_v_format) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_v_format))) __PYX_ERR(0, 148, __pyx_L1_error) + __pyx_t_4 = __pyx_v_format; + __Pyx_INCREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + __Pyx_GOTREF(__pyx_v_self->_format); + __Pyx_DECREF(__pyx_v_self->_format); + __pyx_v_self->_format = ((PyObject*)__pyx_t_4); + __pyx_t_4 = 0; + + /* "View.MemoryView":149 + * format = format.encode('ASCII') + * self._format = format # keep a reference to the byte string + * self.format = self._format # <<<<<<<<<<<<<< + * + * + */ + if (unlikely(__pyx_v_self->_format == Py_None)) { + PyErr_SetString(PyExc_TypeError, "expected bytes, NoneType found"); + __PYX_ERR(0, 149, __pyx_L1_error) + } + __pyx_t_8 = __Pyx_PyBytes_AsWritableString(__pyx_v_self->_format); if (unlikely((!__pyx_t_8) && PyErr_Occurred())) __PYX_ERR(0, 149, __pyx_L1_error) + __pyx_v_self->format = __pyx_t_8; + + /* "View.MemoryView":152 + * + * + * self._shape = PyObject_Malloc(sizeof(Py_ssize_t)*self.ndim*2) # <<<<<<<<<<<<<< + * self._strides = self._shape + self.ndim + * + */ + __pyx_v_self->_shape = ((Py_ssize_t *)PyObject_Malloc((((sizeof(Py_ssize_t)) * __pyx_v_self->ndim) * 2))); + + /* "View.MemoryView":153 + * + * self._shape = PyObject_Malloc(sizeof(Py_ssize_t)*self.ndim*2) + * self._strides = self._shape + self.ndim # <<<<<<<<<<<<<< + * + * if not self._shape: + */ + __pyx_v_self->_strides = (__pyx_v_self->_shape + __pyx_v_self->ndim); + + /* "View.MemoryView":155 + * self._strides = self._shape + self.ndim + * + * if not self._shape: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate shape and strides." + * + */ + __pyx_t_3 = (!(__pyx_v_self->_shape != 0)); + if (unlikely(__pyx_t_3)) { + + /* "View.MemoryView":156 + * + * if not self._shape: + * raise MemoryError, "unable to allocate shape and strides." # <<<<<<<<<<<<<< + * + * + */ + __Pyx_Raise(__pyx_builtin_MemoryError, __pyx_kp_s_unable_to_allocate_shape_and_str, 0, 0); + __PYX_ERR(0, 156, __pyx_L1_error) + + /* "View.MemoryView":155 + * self._strides = self._shape + self.ndim + * + * if not self._shape: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate shape and strides." + * + */ + } + + /* "View.MemoryView":159 + * + * + * for idx, dim in enumerate(shape): # <<<<<<<<<<<<<< + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + */ + __pyx_t_7 = 0; + __pyx_t_4 = __pyx_v_shape; __Pyx_INCREF(__pyx_t_4); + __pyx_t_1 = 0; + for (;;) { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_4); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 159, __pyx_L1_error) + #endif + if (__pyx_t_1 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_5 = PyTuple_GET_ITEM(__pyx_t_4, __pyx_t_1); __Pyx_INCREF(__pyx_t_5); __pyx_t_1++; if (unlikely((0 < 0))) __PYX_ERR(0, 159, __pyx_L1_error) + #else + __pyx_t_5 = __Pyx_PySequence_ITEM(__pyx_t_4, __pyx_t_1); __pyx_t_1++; if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 159, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + #endif + __pyx_t_9 = __Pyx_PyIndex_AsSsize_t(__pyx_t_5); if (unlikely((__pyx_t_9 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 159, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_v_dim = __pyx_t_9; + __pyx_v_idx = __pyx_t_7; + __pyx_t_7 = (__pyx_t_7 + 1); + + /* "View.MemoryView":160 + * + * for idx, dim in enumerate(shape): + * if dim <= 0: # <<<<<<<<<<<<<< + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + * self._shape[idx] = dim + */ + __pyx_t_3 = (__pyx_v_dim <= 0); + if (unlikely(__pyx_t_3)) { + + /* "View.MemoryView":161 + * for idx, dim in enumerate(shape): + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." # <<<<<<<<<<<<<< + * self._shape[idx] = dim + * + */ + __pyx_t_5 = PyTuple_New(5); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_9 = 0; + __pyx_t_10 = 127; + __Pyx_INCREF(__pyx_kp_u_Invalid_shape_in_axis); + __pyx_t_9 += 22; + __Pyx_GIVEREF(__pyx_kp_u_Invalid_shape_in_axis); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_kp_u_Invalid_shape_in_axis); + __pyx_t_6 = __Pyx_PyUnicode_From_int(__pyx_v_idx, 0, ' ', 'd'); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_9 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_6); + __Pyx_GIVEREF(__pyx_t_6); + PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_6); + __pyx_t_6 = 0; + __Pyx_INCREF(__pyx_kp_u_); + __pyx_t_9 += 2; + __Pyx_GIVEREF(__pyx_kp_u_); + PyTuple_SET_ITEM(__pyx_t_5, 2, __pyx_kp_u_); + __pyx_t_6 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_dim, 0, ' ', 'd'); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_9 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_6); + __Pyx_GIVEREF(__pyx_t_6); + PyTuple_SET_ITEM(__pyx_t_5, 3, __pyx_t_6); + __pyx_t_6 = 0; + __Pyx_INCREF(__pyx_kp_u__2); + __pyx_t_9 += 1; + __Pyx_GIVEREF(__pyx_kp_u__2); + PyTuple_SET_ITEM(__pyx_t_5, 4, __pyx_kp_u__2); + __pyx_t_6 = __Pyx_PyUnicode_Join(__pyx_t_5, 5, __pyx_t_9, __pyx_t_10); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 161, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_t_6, 0, 0); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __PYX_ERR(0, 161, __pyx_L1_error) + + /* "View.MemoryView":160 + * + * for idx, dim in enumerate(shape): + * if dim <= 0: # <<<<<<<<<<<<<< + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + * self._shape[idx] = dim + */ + } + + /* "View.MemoryView":162 + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + * self._shape[idx] = dim # <<<<<<<<<<<<<< + * + * cdef char order + */ + (__pyx_v_self->_shape[__pyx_v_idx]) = __pyx_v_dim; + + /* "View.MemoryView":159 + * + * + * for idx, dim in enumerate(shape): # <<<<<<<<<<<<<< + * if dim <= 0: + * raise ValueError, f"Invalid shape in axis {idx}: {dim}." + */ + } + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "View.MemoryView":165 + * + * cdef char order + * if mode == 'c': # <<<<<<<<<<<<<< + * order = b'C' + * self.mode = u'c' + */ + __pyx_t_3 = (__Pyx_PyString_Equals(__pyx_v_mode, __pyx_n_s_c, Py_EQ)); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(0, 165, __pyx_L1_error) + if (__pyx_t_3) { + + /* "View.MemoryView":166 + * cdef char order + * if mode == 'c': + * order = b'C' # <<<<<<<<<<<<<< + * self.mode = u'c' + * elif mode == 'fortran': + */ + __pyx_v_order = 'C'; + + /* "View.MemoryView":167 + * if mode == 'c': + * order = b'C' + * self.mode = u'c' # <<<<<<<<<<<<<< + * elif mode == 'fortran': + * order = b'F' + */ + __Pyx_INCREF(__pyx_n_u_c); + __Pyx_GIVEREF(__pyx_n_u_c); + __Pyx_GOTREF(__pyx_v_self->mode); + __Pyx_DECREF(__pyx_v_self->mode); + __pyx_v_self->mode = __pyx_n_u_c; + + /* "View.MemoryView":165 + * + * cdef char order + * if mode == 'c': # <<<<<<<<<<<<<< + * order = b'C' + * self.mode = u'c' + */ + goto __pyx_L11; + } + + /* "View.MemoryView":168 + * order = b'C' + * self.mode = u'c' + * elif mode == 'fortran': # <<<<<<<<<<<<<< + * order = b'F' + * self.mode = u'fortran' + */ + __pyx_t_3 = (__Pyx_PyString_Equals(__pyx_v_mode, __pyx_n_s_fortran, Py_EQ)); if (unlikely((__pyx_t_3 < 0))) __PYX_ERR(0, 168, __pyx_L1_error) + if (likely(__pyx_t_3)) { + + /* "View.MemoryView":169 + * self.mode = u'c' + * elif mode == 'fortran': + * order = b'F' # <<<<<<<<<<<<<< + * self.mode = u'fortran' + * else: + */ + __pyx_v_order = 'F'; + + /* "View.MemoryView":170 + * elif mode == 'fortran': + * order = b'F' + * self.mode = u'fortran' # <<<<<<<<<<<<<< + * else: + * raise ValueError, f"Invalid mode, expected 'c' or 'fortran', got {mode}" + */ + __Pyx_INCREF(__pyx_n_u_fortran); + __Pyx_GIVEREF(__pyx_n_u_fortran); + __Pyx_GOTREF(__pyx_v_self->mode); + __Pyx_DECREF(__pyx_v_self->mode); + __pyx_v_self->mode = __pyx_n_u_fortran; + + /* "View.MemoryView":168 + * order = b'C' + * self.mode = u'c' + * elif mode == 'fortran': # <<<<<<<<<<<<<< + * order = b'F' + * self.mode = u'fortran' + */ + goto __pyx_L11; + } + + /* "View.MemoryView":172 + * self.mode = u'fortran' + * else: + * raise ValueError, f"Invalid mode, expected 'c' or 'fortran', got {mode}" # <<<<<<<<<<<<<< + * + * self.len = fill_contig_strides_array(self._shape, self._strides, itemsize, self.ndim, order) + */ + /*else*/ { + __pyx_t_4 = __Pyx_PyObject_FormatSimple(__pyx_v_mode, __pyx_empty_unicode); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 172, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_6 = __Pyx_PyUnicode_Concat(__pyx_kp_u_Invalid_mode_expected_c_or_fortr, __pyx_t_4); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 172, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_t_6, 0, 0); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __PYX_ERR(0, 172, __pyx_L1_error) + } + __pyx_L11:; + + /* "View.MemoryView":174 + * raise ValueError, f"Invalid mode, expected 'c' or 'fortran', got {mode}" + * + * self.len = fill_contig_strides_array(self._shape, self._strides, itemsize, self.ndim, order) # <<<<<<<<<<<<<< + * + * self.free_data = allocate_buffer + */ + __pyx_v_self->len = __pyx_fill_contig_strides_array(__pyx_v_self->_shape, __pyx_v_self->_strides, __pyx_v_itemsize, __pyx_v_self->ndim, __pyx_v_order); + + /* "View.MemoryView":176 + * self.len = fill_contig_strides_array(self._shape, self._strides, itemsize, self.ndim, order) + * + * self.free_data = allocate_buffer # <<<<<<<<<<<<<< + * self.dtype_is_object = format == b'O' + * + */ + __pyx_v_self->free_data = __pyx_v_allocate_buffer; + + /* "View.MemoryView":177 + * + * self.free_data = allocate_buffer + * self.dtype_is_object = format == b'O' # <<<<<<<<<<<<<< + * + * if allocate_buffer: + */ + __pyx_t_6 = PyObject_RichCompare(__pyx_v_format, __pyx_n_b_O, Py_EQ); __Pyx_XGOTREF(__pyx_t_6); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 177, __pyx_L1_error) + __pyx_t_3 = __Pyx_PyObject_IsTrue(__pyx_t_6); if (unlikely((__pyx_t_3 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 177, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __pyx_v_self->dtype_is_object = __pyx_t_3; + + /* "View.MemoryView":179 + * self.dtype_is_object = format == b'O' + * + * if allocate_buffer: # <<<<<<<<<<<<<< + * _allocate_buffer(self) + * + */ + if (__pyx_v_allocate_buffer) { + + /* "View.MemoryView":180 + * + * if allocate_buffer: + * _allocate_buffer(self) # <<<<<<<<<<<<<< + * + * @cname('getbuffer') + */ + __pyx_t_7 = __pyx_array_allocate_buffer(__pyx_v_self); if (unlikely(__pyx_t_7 == ((int)-1))) __PYX_ERR(0, 180, __pyx_L1_error) + + /* "View.MemoryView":179 + * self.dtype_is_object = format == b'O' + * + * if allocate_buffer: # <<<<<<<<<<<<<< + * _allocate_buffer(self) + * + */ + } + + /* "View.MemoryView":131 + * cdef bint dtype_is_object + * + * def __cinit__(array self, tuple shape, Py_ssize_t itemsize, format not None, # <<<<<<<<<<<<<< + * mode="c", bint allocate_buffer=True): + * + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("View.MemoryView.array.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_format); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":182 + * _allocate_buffer(self) + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + */ + +/* Python wrapper */ +CYTHON_UNUSED static int __pyx_array_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +CYTHON_UNUSED static int __pyx_array_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getbuffer__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_2__getbuffer__(((struct __pyx_array_obj *)__pyx_v_self), ((Py_buffer *)__pyx_v_info), ((int)__pyx_v_flags)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_2__getbuffer__(struct __pyx_array_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + int __pyx_v_bufmode; + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + char *__pyx_t_2; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + Py_ssize_t *__pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + if (unlikely(__pyx_v_info == NULL)) { + PyErr_SetString(PyExc_BufferError, "PyObject_GetBuffer: view==NULL argument is obsolete"); + return -1; + } + __Pyx_RefNannySetupContext("__getbuffer__", 0); + __pyx_v_info->obj = Py_None; __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(__pyx_v_info->obj); + + /* "View.MemoryView":184 + * @cname('getbuffer') + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 # <<<<<<<<<<<<<< + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": + */ + __pyx_v_bufmode = -1; + + /* "View.MemoryView":185 + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): # <<<<<<<<<<<<<< + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + */ + __pyx_t_1 = ((__pyx_v_flags & ((PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS) | PyBUF_ANY_CONTIGUOUS)) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":186 + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": # <<<<<<<<<<<<<< + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": + */ + __pyx_t_1 = (__Pyx_PyUnicode_Equals(__pyx_v_self->mode, __pyx_n_u_c, Py_EQ)); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(0, 186, __pyx_L1_error) + if (__pyx_t_1) { + + /* "View.MemoryView":187 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS # <<<<<<<<<<<<<< + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + */ + __pyx_v_bufmode = (PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS); + + /* "View.MemoryView":186 + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): + * if self.mode == u"c": # <<<<<<<<<<<<<< + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": + */ + goto __pyx_L4; + } + + /* "View.MemoryView":188 + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": # <<<<<<<<<<<<<< + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): + */ + __pyx_t_1 = (__Pyx_PyUnicode_Equals(__pyx_v_self->mode, __pyx_n_u_fortran, Py_EQ)); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(0, 188, __pyx_L1_error) + if (__pyx_t_1) { + + /* "View.MemoryView":189 + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS # <<<<<<<<<<<<<< + * if not (flags & bufmode): + * raise ValueError, "Can only create a buffer that is contiguous in memory." + */ + __pyx_v_bufmode = (PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS); + + /* "View.MemoryView":188 + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * elif self.mode == u"fortran": # <<<<<<<<<<<<<< + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): + */ + } + __pyx_L4:; + + /* "View.MemoryView":190 + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): # <<<<<<<<<<<<<< + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data + */ + __pyx_t_1 = (!((__pyx_v_flags & __pyx_v_bufmode) != 0)); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":191 + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): + * raise ValueError, "Can only create a buffer that is contiguous in memory." # <<<<<<<<<<<<<< + * info.buf = self.data + * info.len = self.len + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Can_only_create_a_buffer_that_is, 0, 0); + __PYX_ERR(0, 191, __pyx_L1_error) + + /* "View.MemoryView":190 + * elif self.mode == u"fortran": + * bufmode = PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + * if not (flags & bufmode): # <<<<<<<<<<<<<< + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data + */ + } + + /* "View.MemoryView":185 + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + * if flags & (PyBUF_C_CONTIGUOUS | PyBUF_F_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS): # <<<<<<<<<<<<<< + * if self.mode == u"c": + * bufmode = PyBUF_C_CONTIGUOUS | PyBUF_ANY_CONTIGUOUS + */ + } + + /* "View.MemoryView":192 + * if not (flags & bufmode): + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data # <<<<<<<<<<<<<< + * info.len = self.len + * + */ + __pyx_t_2 = __pyx_v_self->data; + __pyx_v_info->buf = __pyx_t_2; + + /* "View.MemoryView":193 + * raise ValueError, "Can only create a buffer that is contiguous in memory." + * info.buf = self.data + * info.len = self.len # <<<<<<<<<<<<<< + * + * if flags & PyBUF_STRIDES: + */ + __pyx_t_3 = __pyx_v_self->len; + __pyx_v_info->len = __pyx_t_3; + + /* "View.MemoryView":195 + * info.len = self.len + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.ndim = self.ndim + * info.shape = self._shape + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_STRIDES) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":196 + * + * if flags & PyBUF_STRIDES: + * info.ndim = self.ndim # <<<<<<<<<<<<<< + * info.shape = self._shape + * info.strides = self._strides + */ + __pyx_t_4 = __pyx_v_self->ndim; + __pyx_v_info->ndim = __pyx_t_4; + + /* "View.MemoryView":197 + * if flags & PyBUF_STRIDES: + * info.ndim = self.ndim + * info.shape = self._shape # <<<<<<<<<<<<<< + * info.strides = self._strides + * else: + */ + __pyx_t_5 = __pyx_v_self->_shape; + __pyx_v_info->shape = __pyx_t_5; + + /* "View.MemoryView":198 + * info.ndim = self.ndim + * info.shape = self._shape + * info.strides = self._strides # <<<<<<<<<<<<<< + * else: + * info.ndim = 1 + */ + __pyx_t_5 = __pyx_v_self->_strides; + __pyx_v_info->strides = __pyx_t_5; + + /* "View.MemoryView":195 + * info.len = self.len + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.ndim = self.ndim + * info.shape = self._shape + */ + goto __pyx_L6; + } + + /* "View.MemoryView":200 + * info.strides = self._strides + * else: + * info.ndim = 1 # <<<<<<<<<<<<<< + * info.shape = &self.len if flags & PyBUF_ND else NULL + * info.strides = NULL + */ + /*else*/ { + __pyx_v_info->ndim = 1; + + /* "View.MemoryView":201 + * else: + * info.ndim = 1 + * info.shape = &self.len if flags & PyBUF_ND else NULL # <<<<<<<<<<<<<< + * info.strides = NULL + * + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_ND) != 0); + if (__pyx_t_1) { + __pyx_t_5 = (&__pyx_v_self->len); + } else { + __pyx_t_5 = NULL; + } + __pyx_v_info->shape = __pyx_t_5; + + /* "View.MemoryView":202 + * info.ndim = 1 + * info.shape = &self.len if flags & PyBUF_ND else NULL + * info.strides = NULL # <<<<<<<<<<<<<< + * + * info.suboffsets = NULL + */ + __pyx_v_info->strides = NULL; + } + __pyx_L6:; + + /* "View.MemoryView":204 + * info.strides = NULL + * + * info.suboffsets = NULL # <<<<<<<<<<<<<< + * info.itemsize = self.itemsize + * info.readonly = 0 + */ + __pyx_v_info->suboffsets = NULL; + + /* "View.MemoryView":205 + * + * info.suboffsets = NULL + * info.itemsize = self.itemsize # <<<<<<<<<<<<<< + * info.readonly = 0 + * info.format = self.format if flags & PyBUF_FORMAT else NULL + */ + __pyx_t_3 = __pyx_v_self->itemsize; + __pyx_v_info->itemsize = __pyx_t_3; + + /* "View.MemoryView":206 + * info.suboffsets = NULL + * info.itemsize = self.itemsize + * info.readonly = 0 # <<<<<<<<<<<<<< + * info.format = self.format if flags & PyBUF_FORMAT else NULL + * info.obj = self + */ + __pyx_v_info->readonly = 0; + + /* "View.MemoryView":207 + * info.itemsize = self.itemsize + * info.readonly = 0 + * info.format = self.format if flags & PyBUF_FORMAT else NULL # <<<<<<<<<<<<<< + * info.obj = self + * + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_FORMAT) != 0); + if (__pyx_t_1) { + __pyx_t_2 = __pyx_v_self->format; + } else { + __pyx_t_2 = NULL; + } + __pyx_v_info->format = __pyx_t_2; + + /* "View.MemoryView":208 + * info.readonly = 0 + * info.format = self.format if flags & PyBUF_FORMAT else NULL + * info.obj = self # <<<<<<<<<<<<<< + * + * def __dealloc__(array self): + */ + __Pyx_INCREF((PyObject *)__pyx_v_self); + __Pyx_GIVEREF((PyObject *)__pyx_v_self); + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); + __pyx_v_info->obj = ((PyObject *)__pyx_v_self); + + /* "View.MemoryView":182 + * _allocate_buffer(self) + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * cdef int bufmode = -1 + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.array.__getbuffer__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + if (__pyx_v_info->obj != NULL) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + goto __pyx_L2; + __pyx_L0:; + if (__pyx_v_info->obj == Py_None) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + __pyx_L2:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":210 + * info.obj = self + * + * def __dealloc__(array self): # <<<<<<<<<<<<<< + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + */ + +/* Python wrapper */ +static void __pyx_array___dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_array___dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_array___pyx_pf_15View_dot_MemoryView_5array_4__dealloc__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_array___pyx_pf_15View_dot_MemoryView_5array_4__dealloc__(struct __pyx_array_obj *__pyx_v_self) { + int __pyx_t_1; + int __pyx_t_2; + + /* "View.MemoryView":211 + * + * def __dealloc__(array self): + * if self.callback_free_data != NULL: # <<<<<<<<<<<<<< + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + */ + __pyx_t_1 = (__pyx_v_self->callback_free_data != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":212 + * def __dealloc__(array self): + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) # <<<<<<<<<<<<<< + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: + */ + __pyx_v_self->callback_free_data(__pyx_v_self->data); + + /* "View.MemoryView":211 + * + * def __dealloc__(array self): + * if self.callback_free_data != NULL: # <<<<<<<<<<<<<< + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":213 + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: # <<<<<<<<<<<<<< + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + */ + if (__pyx_v_self->free_data) { + } else { + __pyx_t_1 = __pyx_v_self->free_data; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_2 = (__pyx_v_self->data != NULL); + __pyx_t_1 = __pyx_t_2; + __pyx_L4_bool_binop_done:; + if (__pyx_t_1) { + + /* "View.MemoryView":214 + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) + */ + if (__pyx_v_self->dtype_is_object) { + + /* "View.MemoryView":215 + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) # <<<<<<<<<<<<<< + * free(self.data) + * PyObject_Free(self._shape) + */ + __pyx_memoryview_refcount_objects_in_slice(__pyx_v_self->data, __pyx_v_self->_shape, __pyx_v_self->_strides, __pyx_v_self->ndim, 0); + + /* "View.MemoryView":214 + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) + */ + } + + /* "View.MemoryView":216 + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) # <<<<<<<<<<<<<< + * PyObject_Free(self._shape) + * + */ + free(__pyx_v_self->data); + + /* "View.MemoryView":213 + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + * elif self.free_data and self.data is not NULL: # <<<<<<<<<<<<<< + * if self.dtype_is_object: + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + */ + } + __pyx_L3:; + + /* "View.MemoryView":217 + * refcount_objects_in_slice(self.data, self._shape, self._strides, self.ndim, inc=False) + * free(self.data) + * PyObject_Free(self._shape) # <<<<<<<<<<<<<< + * + * @property + */ + PyObject_Free(__pyx_v_self->_shape); + + /* "View.MemoryView":210 + * info.obj = self + * + * def __dealloc__(array self): # <<<<<<<<<<<<<< + * if self.callback_free_data != NULL: + * self.callback_free_data(self.data) + */ + + /* function exit code */ +} + +/* "View.MemoryView":219 + * PyObject_Free(self._shape) + * + * @property # <<<<<<<<<<<<<< + * def memview(self): + * return self.get_memview() + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_5array_7memview_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_5array_7memview_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_5array_7memview___get__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_5array_7memview___get__(struct __pyx_array_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":221 + * @property + * def memview(self): + * return self.get_memview() # <<<<<<<<<<<<<< + * + * @cname('get_memview') + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = ((struct __pyx_vtabstruct_array *)__pyx_v_self->__pyx_vtab)->get_memview(__pyx_v_self); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 221, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":219 + * PyObject_Free(self._shape) + * + * @property # <<<<<<<<<<<<<< + * def memview(self): + * return self.get_memview() + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.array.memview.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":224 + * + * @cname('get_memview') + * cdef get_memview(self): # <<<<<<<<<<<<<< + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE + * return memoryview(self, flags, self.dtype_is_object) + */ + +static PyObject *__pyx_array_get_memview(struct __pyx_array_obj *__pyx_v_self) { + int __pyx_v_flags; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_memview", 1); + + /* "View.MemoryView":225 + * @cname('get_memview') + * cdef get_memview(self): + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE # <<<<<<<<<<<<<< + * return memoryview(self, flags, self.dtype_is_object) + * + */ + __pyx_v_flags = ((PyBUF_ANY_CONTIGUOUS | PyBUF_FORMAT) | PyBUF_WRITABLE); + + /* "View.MemoryView":226 + * cdef get_memview(self): + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE + * return memoryview(self, flags, self.dtype_is_object) # <<<<<<<<<<<<<< + * + * def __len__(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_flags); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_v_self->dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF((PyObject *)__pyx_v_self); + __Pyx_GIVEREF((PyObject *)__pyx_v_self); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, ((PyObject *)__pyx_v_self))) __PYX_ERR(0, 226, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1)) __PYX_ERR(0, 226, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_t_2)) __PYX_ERR(0, 226, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_Call(((PyObject *)__pyx_memoryview_type), __pyx_t_3, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 226, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":224 + * + * @cname('get_memview') + * cdef get_memview(self): # <<<<<<<<<<<<<< + * flags = PyBUF_ANY_CONTIGUOUS|PyBUF_FORMAT|PyBUF_WRITABLE + * return memoryview(self, flags, self.dtype_is_object) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.array.get_memview", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":228 + * return memoryview(self, flags, self.dtype_is_object) + * + * def __len__(self): # <<<<<<<<<<<<<< + * return self._shape[0] + * + */ + +/* Python wrapper */ +static Py_ssize_t __pyx_array___len__(PyObject *__pyx_v_self); /*proto*/ +static Py_ssize_t __pyx_array___len__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + Py_ssize_t __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__len__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_6__len__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static Py_ssize_t __pyx_array___pyx_pf_15View_dot_MemoryView_5array_6__len__(struct __pyx_array_obj *__pyx_v_self) { + Py_ssize_t __pyx_r; + + /* "View.MemoryView":229 + * + * def __len__(self): + * return self._shape[0] # <<<<<<<<<<<<<< + * + * def __getattr__(self, attr): + */ + __pyx_r = (__pyx_v_self->_shape[0]); + goto __pyx_L0; + + /* "View.MemoryView":228 + * return memoryview(self, flags, self.dtype_is_object) + * + * def __len__(self): # <<<<<<<<<<<<<< + * return self._shape[0] + * + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":231 + * return self._shape[0] + * + * def __getattr__(self, attr): # <<<<<<<<<<<<<< + * return getattr(self.memview, attr) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_array___getattr__(PyObject *__pyx_v_self, PyObject *__pyx_v_attr); /*proto*/ +static PyObject *__pyx_array___getattr__(PyObject *__pyx_v_self, PyObject *__pyx_v_attr) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getattr__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_8__getattr__(((struct __pyx_array_obj *)__pyx_v_self), ((PyObject *)__pyx_v_attr)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_8__getattr__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_attr) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__getattr__", 1); + + /* "View.MemoryView":232 + * + * def __getattr__(self, attr): + * return getattr(self.memview, attr) # <<<<<<<<<<<<<< + * + * def __getitem__(self, item): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_memview); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 232, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_GetAttr(__pyx_t_1, __pyx_v_attr); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 232, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":231 + * return self._shape[0] + * + * def __getattr__(self, attr): # <<<<<<<<<<<<<< + * return getattr(self.memview, attr) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.array.__getattr__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":234 + * return getattr(self.memview, attr) + * + * def __getitem__(self, item): # <<<<<<<<<<<<<< + * return self.memview[item] + * + */ + +/* Python wrapper */ +static PyObject *__pyx_array___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item); /*proto*/ +static PyObject *__pyx_array___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getitem__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_10__getitem__(((struct __pyx_array_obj *)__pyx_v_self), ((PyObject *)__pyx_v_item)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_array___pyx_pf_15View_dot_MemoryView_5array_10__getitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__getitem__", 1); + + /* "View.MemoryView":235 + * + * def __getitem__(self, item): + * return self.memview[item] # <<<<<<<<<<<<<< + * + * def __setitem__(self, item, value): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_memview); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 235, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetItem(__pyx_t_1, __pyx_v_item); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 235, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":234 + * return getattr(self.memview, attr) + * + * def __getitem__(self, item): # <<<<<<<<<<<<<< + * return self.memview[item] + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.array.__getitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":237 + * return self.memview[item] + * + * def __setitem__(self, item, value): # <<<<<<<<<<<<<< + * self.memview[item] = value + * + */ + +/* Python wrapper */ +static int __pyx_array___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value); /*proto*/ +static int __pyx_array___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setitem__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_array___pyx_pf_15View_dot_MemoryView_5array_12__setitem__(((struct __pyx_array_obj *)__pyx_v_self), ((PyObject *)__pyx_v_item), ((PyObject *)__pyx_v_value)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_array___pyx_pf_15View_dot_MemoryView_5array_12__setitem__(struct __pyx_array_obj *__pyx_v_self, PyObject *__pyx_v_item, PyObject *__pyx_v_value) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setitem__", 1); + + /* "View.MemoryView":238 + * + * def __setitem__(self, item, value): + * self.memview[item] = value # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_memview); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 238, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (unlikely((PyObject_SetItem(__pyx_t_1, __pyx_v_item, __pyx_v_value) < 0))) __PYX_ERR(0, 238, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "View.MemoryView":237 + * return self.memview[item] + * + * def __setitem__(self, item, value): # <<<<<<<<<<<<<< + * self.memview[item] = value + * + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.array.__setitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_array_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_array_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_array___reduce_cython__(((struct __pyx_array_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_array___reduce_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(0, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.array.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_array_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_array_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(0, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.array.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_array_2__setstate_cython__(((struct __pyx_array_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_array_2__setstate_cython__(CYTHON_UNUSED struct __pyx_array_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(0, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.array.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":248 + * + * @cname("__pyx_array_allocate_buffer") + * cdef int _allocate_buffer(array self) except -1: # <<<<<<<<<<<<<< + * + * + */ + +static int __pyx_array_allocate_buffer(struct __pyx_array_obj *__pyx_v_self) { + Py_ssize_t __pyx_v_i; + PyObject **__pyx_v_p; + int __pyx_r; + int __pyx_t_1; + Py_ssize_t __pyx_t_2; + Py_ssize_t __pyx_t_3; + Py_ssize_t __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + + /* "View.MemoryView":254 + * cdef PyObject **p + * + * self.free_data = True # <<<<<<<<<<<<<< + * self.data = malloc(self.len) + * if not self.data: + */ + __pyx_v_self->free_data = 1; + + /* "View.MemoryView":255 + * + * self.free_data = True + * self.data = malloc(self.len) # <<<<<<<<<<<<<< + * if not self.data: + * raise MemoryError, "unable to allocate array data." + */ + __pyx_v_self->data = ((char *)malloc(__pyx_v_self->len)); + + /* "View.MemoryView":256 + * self.free_data = True + * self.data = malloc(self.len) + * if not self.data: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate array data." + * + */ + __pyx_t_1 = (!(__pyx_v_self->data != 0)); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":257 + * self.data = malloc(self.len) + * if not self.data: + * raise MemoryError, "unable to allocate array data." # <<<<<<<<<<<<<< + * + * if self.dtype_is_object: + */ + __Pyx_Raise(__pyx_builtin_MemoryError, __pyx_kp_s_unable_to_allocate_array_data, 0, 0); + __PYX_ERR(0, 257, __pyx_L1_error) + + /* "View.MemoryView":256 + * self.free_data = True + * self.data = malloc(self.len) + * if not self.data: # <<<<<<<<<<<<<< + * raise MemoryError, "unable to allocate array data." + * + */ + } + + /* "View.MemoryView":259 + * raise MemoryError, "unable to allocate array data." + * + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * p = self.data + * for i in range(self.len // self.itemsize): + */ + if (__pyx_v_self->dtype_is_object) { + + /* "View.MemoryView":260 + * + * if self.dtype_is_object: + * p = self.data # <<<<<<<<<<<<<< + * for i in range(self.len // self.itemsize): + * p[i] = Py_None + */ + __pyx_v_p = ((PyObject **)__pyx_v_self->data); + + /* "View.MemoryView":261 + * if self.dtype_is_object: + * p = self.data + * for i in range(self.len // self.itemsize): # <<<<<<<<<<<<<< + * p[i] = Py_None + * Py_INCREF(Py_None) + */ + if (unlikely(__pyx_v_self->itemsize == 0)) { + PyErr_SetString(PyExc_ZeroDivisionError, "integer division or modulo by zero"); + __PYX_ERR(0, 261, __pyx_L1_error) + } + else if (sizeof(Py_ssize_t) == sizeof(long) && (!(((Py_ssize_t)-1) > 0)) && unlikely(__pyx_v_self->itemsize == (Py_ssize_t)-1) && unlikely(__Pyx_UNARY_NEG_WOULD_OVERFLOW(__pyx_v_self->len))) { + PyErr_SetString(PyExc_OverflowError, "value too large to perform division"); + __PYX_ERR(0, 261, __pyx_L1_error) + } + __pyx_t_2 = __Pyx_div_Py_ssize_t(__pyx_v_self->len, __pyx_v_self->itemsize); + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":262 + * p = self.data + * for i in range(self.len // self.itemsize): + * p[i] = Py_None # <<<<<<<<<<<<<< + * Py_INCREF(Py_None) + * return 0 + */ + (__pyx_v_p[__pyx_v_i]) = Py_None; + + /* "View.MemoryView":263 + * for i in range(self.len // self.itemsize): + * p[i] = Py_None + * Py_INCREF(Py_None) # <<<<<<<<<<<<<< + * return 0 + * + */ + Py_INCREF(Py_None); + } + + /* "View.MemoryView":259 + * raise MemoryError, "unable to allocate array data." + * + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * p = self.data + * for i in range(self.len // self.itemsize): + */ + } + + /* "View.MemoryView":264 + * p[i] = Py_None + * Py_INCREF(Py_None) + * return 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":248 + * + * @cname("__pyx_array_allocate_buffer") + * cdef int _allocate_buffer(array self) except -1: # <<<<<<<<<<<<<< + * + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._allocate_buffer", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":268 + * + * @cname("__pyx_array_new") + * cdef array array_cwrapper(tuple shape, Py_ssize_t itemsize, char *format, char *c_mode, char *buf): # <<<<<<<<<<<<<< + * cdef array result + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + */ + +static struct __pyx_array_obj *__pyx_array_new(PyObject *__pyx_v_shape, Py_ssize_t __pyx_v_itemsize, char *__pyx_v_format, char *__pyx_v_c_mode, char *__pyx_v_buf) { + struct __pyx_array_obj *__pyx_v_result = 0; + PyObject *__pyx_v_mode = 0; + struct __pyx_array_obj *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("array_cwrapper", 1); + + /* "View.MemoryView":270 + * cdef array array_cwrapper(tuple shape, Py_ssize_t itemsize, char *format, char *c_mode, char *buf): + * cdef array result + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. # <<<<<<<<<<<<<< + * + * if buf is NULL: + */ + __pyx_t_2 = ((__pyx_v_c_mode[0]) == 'f'); + if (__pyx_t_2) { + __Pyx_INCREF(__pyx_n_s_fortran); + __pyx_t_1 = __pyx_n_s_fortran; + } else { + __Pyx_INCREF(__pyx_n_s_c); + __pyx_t_1 = __pyx_n_s_c; + } + __pyx_v_mode = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":272 + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + * + * if buf is NULL: # <<<<<<<<<<<<<< + * result = array.__new__(array, shape, itemsize, format, mode) + * else: + */ + __pyx_t_2 = (__pyx_v_buf == NULL); + if (__pyx_t_2) { + + /* "View.MemoryView":273 + * + * if buf is NULL: + * result = array.__new__(array, shape, itemsize, format, mode) # <<<<<<<<<<<<<< + * else: + * result = array.__new__(array, shape, itemsize, format, mode, allocate_buffer=False) + */ + __pyx_t_1 = PyInt_FromSsize_t(__pyx_v_itemsize); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 273, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyBytes_FromString(__pyx_v_format); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 273, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PyTuple_New(4); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 273, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_INCREF(__pyx_v_shape); + __Pyx_GIVEREF(__pyx_v_shape); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_v_shape)) __PYX_ERR(0, 273, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_t_1)) __PYX_ERR(0, 273, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 2, __pyx_t_3)) __PYX_ERR(0, 273, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_mode); + __Pyx_GIVEREF(__pyx_v_mode); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 3, __pyx_v_mode)) __PYX_ERR(0, 273, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_3 = 0; + __pyx_t_3 = ((PyObject *)__pyx_tp_new_array(((PyTypeObject *)__pyx_array_type), __pyx_t_4, NULL)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 273, __pyx_L1_error) + __Pyx_GOTREF((PyObject *)__pyx_t_3); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_v_result = ((struct __pyx_array_obj *)__pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":272 + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + * + * if buf is NULL: # <<<<<<<<<<<<<< + * result = array.__new__(array, shape, itemsize, format, mode) + * else: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":275 + * result = array.__new__(array, shape, itemsize, format, mode) + * else: + * result = array.__new__(array, shape, itemsize, format, mode, allocate_buffer=False) # <<<<<<<<<<<<<< + * result.data = buf + * + */ + /*else*/ { + __pyx_t_3 = PyInt_FromSsize_t(__pyx_v_itemsize); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = __Pyx_PyBytes_FromString(__pyx_v_format); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_1 = PyTuple_New(4); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v_shape); + __Pyx_GIVEREF(__pyx_v_shape); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v_shape)) __PYX_ERR(0, 275, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_t_3)) __PYX_ERR(0, 275, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_4); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_t_4)) __PYX_ERR(0, 275, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_mode); + __Pyx_GIVEREF(__pyx_v_mode); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 3, __pyx_v_mode)) __PYX_ERR(0, 275, __pyx_L1_error); + __pyx_t_3 = 0; + __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyDict_NewPresized(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 275, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + if (PyDict_SetItem(__pyx_t_4, __pyx_n_s_allocate_buffer, Py_False) < 0) __PYX_ERR(0, 275, __pyx_L1_error) + __pyx_t_3 = ((PyObject *)__pyx_tp_new_array(((PyTypeObject *)__pyx_array_type), __pyx_t_1, __pyx_t_4)); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 275, __pyx_L1_error) + __Pyx_GOTREF((PyObject *)__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_v_result = ((struct __pyx_array_obj *)__pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":276 + * else: + * result = array.__new__(array, shape, itemsize, format, mode, allocate_buffer=False) + * result.data = buf # <<<<<<<<<<<<<< + * + * return result + */ + __pyx_v_result->data = __pyx_v_buf; + } + __pyx_L3:; + + /* "View.MemoryView":278 + * result.data = buf + * + * return result # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF((PyObject *)__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = __pyx_v_result; + goto __pyx_L0; + + /* "View.MemoryView":268 + * + * @cname("__pyx_array_new") + * cdef array array_cwrapper(tuple shape, Py_ssize_t itemsize, char *format, char *c_mode, char *buf): # <<<<<<<<<<<<<< + * cdef array result + * cdef str mode = "fortran" if c_mode[0] == b'f' else "c" # this often comes from a constant C string. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.array_cwrapper", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XDECREF(__pyx_v_mode); + __Pyx_XGIVEREF((PyObject *)__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":304 + * cdef class Enum(object): + * cdef object name + * def __init__(self, name): # <<<<<<<<<<<<<< + * self.name = name + * def __repr__(self): + */ + +/* Python wrapper */ +static int __pyx_MemviewEnum___init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_MemviewEnum___init__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_name = 0; + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__init__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_name,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_name)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 304, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__init__") < 0)) __PYX_ERR(0, 304, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + } + __pyx_v_name = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__init__", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 304, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.Enum.__init__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum___init__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self), __pyx_v_name); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum___init__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v_name) { + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__init__", 1); + + /* "View.MemoryView":305 + * cdef object name + * def __init__(self, name): + * self.name = name # <<<<<<<<<<<<<< + * def __repr__(self): + * return self.name + */ + __Pyx_INCREF(__pyx_v_name); + __Pyx_GIVEREF(__pyx_v_name); + __Pyx_GOTREF(__pyx_v_self->name); + __Pyx_DECREF(__pyx_v_self->name); + __pyx_v_self->name = __pyx_v_name; + + /* "View.MemoryView":304 + * cdef class Enum(object): + * cdef object name + * def __init__(self, name): # <<<<<<<<<<<<<< + * self.name = name + * def __repr__(self): + */ + + /* function exit code */ + __pyx_r = 0; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":306 + * def __init__(self, name): + * self.name = name + * def __repr__(self): # <<<<<<<<<<<<<< + * return self.name + * + */ + +/* Python wrapper */ +static PyObject *__pyx_MemviewEnum___repr__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_MemviewEnum___repr__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__repr__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum_2__repr__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_MemviewEnum___pyx_pf_15View_dot_MemoryView_4Enum_2__repr__(struct __pyx_MemviewEnum_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__repr__", 1); + + /* "View.MemoryView":307 + * self.name = name + * def __repr__(self): + * return self.name # <<<<<<<<<<<<<< + * + * cdef generic = Enum("") + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->name); + __pyx_r = __pyx_v_self->name; + goto __pyx_L0; + + /* "View.MemoryView":306 + * def __init__(self, name): + * self.name = name + * def __repr__(self): # <<<<<<<<<<<<<< + * return self.name + * + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * cdef tuple state + * cdef object _dict + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_MemviewEnum_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_MemviewEnum_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_MemviewEnum___reduce_cython__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_MemviewEnum___reduce_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self) { + PyObject *__pyx_v_state = 0; + PyObject *__pyx_v__dict = 0; + int __pyx_v_use_setstate; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":5 + * cdef object _dict + * cdef bint use_setstate + * state = (self.name,) # <<<<<<<<<<<<<< + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: + */ + __pyx_t_1 = PyTuple_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v_self->name); + __Pyx_GIVEREF(__pyx_v_self->name); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v_self->name)) __PYX_ERR(0, 5, __pyx_L1_error); + __pyx_v_state = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "(tree fragment)":6 + * cdef bint use_setstate + * state = (self.name,) + * _dict = getattr(self, '__dict__', None) # <<<<<<<<<<<<<< + * if _dict is not None: + * state += (_dict,) + */ + __pyx_t_1 = __Pyx_GetAttr3(((PyObject *)__pyx_v_self), __pyx_n_s_dict, Py_None); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v__dict = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":7 + * state = (self.name,) + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: # <<<<<<<<<<<<<< + * state += (_dict,) + * use_setstate = True + */ + __pyx_t_2 = (__pyx_v__dict != Py_None); + if (__pyx_t_2) { + + /* "(tree fragment)":8 + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: + * state += (_dict,) # <<<<<<<<<<<<<< + * use_setstate = True + * else: + */ + __pyx_t_1 = PyTuple_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 8, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_v__dict); + __Pyx_GIVEREF(__pyx_v__dict); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_v__dict)) __PYX_ERR(0, 8, __pyx_L1_error); + __pyx_t_3 = PyNumber_InPlaceAdd(__pyx_v_state, __pyx_t_1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 8, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF_SET(__pyx_v_state, ((PyObject*)__pyx_t_3)); + __pyx_t_3 = 0; + + /* "(tree fragment)":9 + * if _dict is not None: + * state += (_dict,) + * use_setstate = True # <<<<<<<<<<<<<< + * else: + * use_setstate = self.name is not None + */ + __pyx_v_use_setstate = 1; + + /* "(tree fragment)":7 + * state = (self.name,) + * _dict = getattr(self, '__dict__', None) + * if _dict is not None: # <<<<<<<<<<<<<< + * state += (_dict,) + * use_setstate = True + */ + goto __pyx_L3; + } + + /* "(tree fragment)":11 + * use_setstate = True + * else: + * use_setstate = self.name is not None # <<<<<<<<<<<<<< + * if use_setstate: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + */ + /*else*/ { + __pyx_t_2 = (__pyx_v_self->name != Py_None); + __pyx_v_use_setstate = __pyx_t_2; + } + __pyx_L3:; + + /* "(tree fragment)":12 + * else: + * use_setstate = self.name is not None + * if use_setstate: # <<<<<<<<<<<<<< + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + * else: + */ + if (__pyx_v_use_setstate) { + + /* "(tree fragment)":13 + * use_setstate = self.name is not None + * if use_setstate: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state # <<<<<<<<<<<<<< + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_GetModuleGlobalName(__pyx_t_3, __pyx_n_s_pyx_unpickle_Enum); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = PyTuple_New(3); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_GIVEREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, ((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self))))) __PYX_ERR(0, 13, __pyx_L1_error); + __Pyx_INCREF(__pyx_int_136983863); + __Pyx_GIVEREF(__pyx_int_136983863); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_int_136983863)) __PYX_ERR(0, 13, __pyx_L1_error); + __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(Py_None); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 2, Py_None)) __PYX_ERR(0, 13, __pyx_L1_error); + __pyx_t_4 = PyTuple_New(3); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 13, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_3)) __PYX_ERR(0, 13, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 1, __pyx_t_1)) __PYX_ERR(0, 13, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_state); + __Pyx_GIVEREF(__pyx_v_state); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 2, __pyx_v_state)) __PYX_ERR(0, 13, __pyx_L1_error); + __pyx_t_3 = 0; + __pyx_t_1 = 0; + __pyx_r = __pyx_t_4; + __pyx_t_4 = 0; + goto __pyx_L0; + + /* "(tree fragment)":12 + * else: + * use_setstate = self.name is not None + * if use_setstate: # <<<<<<<<<<<<<< + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + * else: + */ + } + + /* "(tree fragment)":15 + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, None), state + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * __pyx_unpickle_Enum__set_state(self, __pyx_state) + */ + /*else*/ { + __Pyx_XDECREF(__pyx_r); + __Pyx_GetModuleGlobalName(__pyx_t_4, __pyx_n_s_pyx_unpickle_Enum); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_1 = PyTuple_New(3); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + __Pyx_GIVEREF(((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self)))); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 0, ((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self))))) __PYX_ERR(0, 15, __pyx_L1_error); + __Pyx_INCREF(__pyx_int_136983863); + __Pyx_GIVEREF(__pyx_int_136983863); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_int_136983863)) __PYX_ERR(0, 15, __pyx_L1_error); + __Pyx_INCREF(__pyx_v_state); + __Pyx_GIVEREF(__pyx_v_state); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_v_state)) __PYX_ERR(0, 15, __pyx_L1_error); + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 15, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_4); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_4)) __PYX_ERR(0, 15, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1)) __PYX_ERR(0, 15, __pyx_L1_error); + __pyx_t_4 = 0; + __pyx_t_1 = 0; + __pyx_r = __pyx_t_3; + __pyx_t_3 = 0; + goto __pyx_L0; + } + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * cdef tuple state + * cdef object _dict + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.Enum.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_state); + __Pyx_XDECREF(__pyx_v__dict); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":16 + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state(self, __pyx_state) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_MemviewEnum_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_MemviewEnum_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 16, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(0, 16, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 16, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.Enum.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_MemviewEnum_2__setstate_cython__(((struct __pyx_MemviewEnum_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_MemviewEnum_2__setstate_cython__(struct __pyx_MemviewEnum_obj *__pyx_v_self, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":17 + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + * def __setstate_cython__(self, __pyx_state): + * __pyx_unpickle_Enum__set_state(self, __pyx_state) # <<<<<<<<<<<<<< + */ + if (!(likely(PyTuple_CheckExact(__pyx_v___pyx_state))||((__pyx_v___pyx_state) == Py_None) || __Pyx_RaiseUnexpectedTypeError("tuple", __pyx_v___pyx_state))) __PYX_ERR(0, 17, __pyx_L1_error) + __pyx_t_1 = __pyx_unpickle_Enum__set_state(__pyx_v_self, ((PyObject*)__pyx_v___pyx_state)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 17, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":16 + * else: + * return __pyx_unpickle_Enum, (type(self), 0x82a3537, state) + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state(self, __pyx_state) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.Enum.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":349 + * cdef __Pyx_TypeInfo *typeinfo + * + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): # <<<<<<<<<<<<<< + * self.obj = obj + * self.flags = flags + */ + +/* Python wrapper */ +static int __pyx_memoryview___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_memoryview___cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + PyObject *__pyx_v_obj = 0; + int __pyx_v_flags; + int __pyx_v_dtype_is_object; + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_obj,&__pyx_n_s_flags,&__pyx_n_s_dtype_is_object,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_obj)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 349, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_flags)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 349, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 2, 3, 1); __PYX_ERR(0, 349, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (kw_args > 0) { + PyObject* value = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_dtype_is_object); + if (value) { values[2] = __Pyx_Arg_NewRef_VARARGS(value); kw_args--; } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 349, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(0, 349, __pyx_L3_error) + } + } else { + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + break; + default: goto __pyx_L5_argtuple_error; + } + } + __pyx_v_obj = values[0]; + __pyx_v_flags = __Pyx_PyInt_As_int(values[1]); if (unlikely((__pyx_v_flags == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 349, __pyx_L3_error) + if (values[2]) { + __pyx_v_dtype_is_object = __Pyx_PyObject_IsTrue(values[2]); if (unlikely((__pyx_v_dtype_is_object == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 349, __pyx_L3_error) + } else { + __pyx_v_dtype_is_object = ((int)0); + } + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__cinit__", 0, 2, 3, __pyx_nargs); __PYX_ERR(0, 349, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.memoryview.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview___cinit__(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v_obj, __pyx_v_flags, __pyx_v_dtype_is_object); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview___cinit__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj, int __pyx_v_flags, int __pyx_v_dtype_is_object) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + Py_intptr_t __pyx_t_4; + size_t __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__cinit__", 1); + + /* "View.MemoryView":350 + * + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): + * self.obj = obj # <<<<<<<<<<<<<< + * self.flags = flags + * if type(self) is memoryview or obj is not None: + */ + __Pyx_INCREF(__pyx_v_obj); + __Pyx_GIVEREF(__pyx_v_obj); + __Pyx_GOTREF(__pyx_v_self->obj); + __Pyx_DECREF(__pyx_v_self->obj); + __pyx_v_self->obj = __pyx_v_obj; + + /* "View.MemoryView":351 + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): + * self.obj = obj + * self.flags = flags # <<<<<<<<<<<<<< + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) + */ + __pyx_v_self->flags = __pyx_v_flags; + + /* "View.MemoryView":352 + * self.obj = obj + * self.flags = flags + * if type(self) is memoryview or obj is not None: # <<<<<<<<<<<<<< + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: + */ + __pyx_t_2 = (((PyObject *)Py_TYPE(((PyObject *)__pyx_v_self))) == ((PyObject *)__pyx_memoryview_type)); + if (!__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_2 = (__pyx_v_obj != Py_None); + __pyx_t_1 = __pyx_t_2; + __pyx_L4_bool_binop_done:; + if (__pyx_t_1) { + + /* "View.MemoryView":353 + * self.flags = flags + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) # <<<<<<<<<<<<<< + * if self.view.obj == NULL: + * (<__pyx_buffer *> &self.view).obj = Py_None + */ + __pyx_t_3 = __Pyx_GetBuffer(__pyx_v_obj, (&__pyx_v_self->view), __pyx_v_flags); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(0, 353, __pyx_L1_error) + + /* "View.MemoryView":354 + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: # <<<<<<<<<<<<<< + * (<__pyx_buffer *> &self.view).obj = Py_None + * Py_INCREF(Py_None) + */ + __pyx_t_1 = (((PyObject *)__pyx_v_self->view.obj) == NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":355 + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: + * (<__pyx_buffer *> &self.view).obj = Py_None # <<<<<<<<<<<<<< + * Py_INCREF(Py_None) + * + */ + ((Py_buffer *)(&__pyx_v_self->view))->obj = Py_None; + + /* "View.MemoryView":356 + * if self.view.obj == NULL: + * (<__pyx_buffer *> &self.view).obj = Py_None + * Py_INCREF(Py_None) # <<<<<<<<<<<<<< + * + * if not __PYX_CYTHON_ATOMICS_ENABLED(): + */ + Py_INCREF(Py_None); + + /* "View.MemoryView":354 + * if type(self) is memoryview or obj is not None: + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: # <<<<<<<<<<<<<< + * (<__pyx_buffer *> &self.view).obj = Py_None + * Py_INCREF(Py_None) + */ + } + + /* "View.MemoryView":352 + * self.obj = obj + * self.flags = flags + * if type(self) is memoryview or obj is not None: # <<<<<<<<<<<<<< + * __Pyx_GetBuffer(obj, &self.view, flags) + * if self.view.obj == NULL: + */ + } + + /* "View.MemoryView":358 + * Py_INCREF(Py_None) + * + * if not __PYX_CYTHON_ATOMICS_ENABLED(): # <<<<<<<<<<<<<< + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: + */ + __pyx_t_1 = (!__PYX_CYTHON_ATOMICS_ENABLED()); + if (__pyx_t_1) { + + /* "View.MemoryView":360 + * if not __PYX_CYTHON_ATOMICS_ENABLED(): + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: # <<<<<<<<<<<<<< + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + */ + __pyx_t_1 = (__pyx_memoryview_thread_locks_used < 8); + if (__pyx_t_1) { + + /* "View.MemoryView":361 + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: + */ + __pyx_v_self->lock = (__pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used]); + + /* "View.MemoryView":362 + * if __pyx_memoryview_thread_locks_used < 8: + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 # <<<<<<<<<<<<<< + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() + */ + __pyx_memoryview_thread_locks_used = (__pyx_memoryview_thread_locks_used + 1); + + /* "View.MemoryView":360 + * if not __PYX_CYTHON_ATOMICS_ENABLED(): + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: # <<<<<<<<<<<<<< + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + */ + } + + /* "View.MemoryView":363 + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: # <<<<<<<<<<<<<< + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: + */ + __pyx_t_1 = (__pyx_v_self->lock == NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":364 + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() # <<<<<<<<<<<<<< + * if self.lock is NULL: + * raise MemoryError + */ + __pyx_v_self->lock = PyThread_allocate_lock(); + + /* "View.MemoryView":365 + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + __pyx_t_1 = (__pyx_v_self->lock == NULL); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":366 + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: + * raise MemoryError # <<<<<<<<<<<<<< + * + * if flags & PyBUF_FORMAT: + */ + PyErr_NoMemory(); __PYX_ERR(0, 366, __pyx_L1_error) + + /* "View.MemoryView":365 + * if self.lock is NULL: + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + } + + /* "View.MemoryView":363 + * self.lock = __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] + * __pyx_memoryview_thread_locks_used += 1 + * if self.lock is NULL: # <<<<<<<<<<<<<< + * self.lock = PyThread_allocate_lock() + * if self.lock is NULL: + */ + } + + /* "View.MemoryView":358 + * Py_INCREF(Py_None) + * + * if not __PYX_CYTHON_ATOMICS_ENABLED(): # <<<<<<<<<<<<<< + * global __pyx_memoryview_thread_locks_used + * if __pyx_memoryview_thread_locks_used < 8: + */ + } + + /* "View.MemoryView":368 + * raise MemoryError + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_FORMAT) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":369 + * + * if flags & PyBUF_FORMAT: + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') # <<<<<<<<<<<<<< + * else: + * self.dtype_is_object = dtype_is_object + */ + __pyx_t_2 = ((__pyx_v_self->view.format[0]) == 'O'); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L12_bool_binop_done; + } + __pyx_t_2 = ((__pyx_v_self->view.format[1]) == '\x00'); + __pyx_t_1 = __pyx_t_2; + __pyx_L12_bool_binop_done:; + __pyx_v_self->dtype_is_object = __pyx_t_1; + + /* "View.MemoryView":368 + * raise MemoryError + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') + * else: + */ + goto __pyx_L11; + } + + /* "View.MemoryView":371 + * self.dtype_is_object = (self.view.format[0] == b'O' and self.view.format[1] == b'\0') + * else: + * self.dtype_is_object = dtype_is_object # <<<<<<<<<<<<<< + * + * assert (&self.acquisition_count) % sizeof(__pyx_atomic_int_type) == 0 + */ + /*else*/ { + __pyx_v_self->dtype_is_object = __pyx_v_dtype_is_object; + } + __pyx_L11:; + + /* "View.MemoryView":373 + * self.dtype_is_object = dtype_is_object + * + * assert (&self.acquisition_count) % sizeof(__pyx_atomic_int_type) == 0 # <<<<<<<<<<<<<< + * self.typeinfo = NULL + * + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_4 = ((Py_intptr_t)((void *)(&__pyx_v_self->acquisition_count))); + __pyx_t_5 = (sizeof(__pyx_atomic_int_type)); + if (unlikely(__pyx_t_5 == 0)) { + PyErr_SetString(PyExc_ZeroDivisionError, "integer division or modulo by zero"); + __PYX_ERR(0, 373, __pyx_L1_error) + } + __pyx_t_1 = ((__pyx_t_4 % __pyx_t_5) == 0); + if (unlikely(!__pyx_t_1)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(0, 373, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(0, 373, __pyx_L1_error) + #endif + + /* "View.MemoryView":374 + * + * assert (&self.acquisition_count) % sizeof(__pyx_atomic_int_type) == 0 + * self.typeinfo = NULL # <<<<<<<<<<<<<< + * + * def __dealloc__(memoryview self): + */ + __pyx_v_self->typeinfo = NULL; + + /* "View.MemoryView":349 + * cdef __Pyx_TypeInfo *typeinfo + * + * def __cinit__(memoryview self, object obj, int flags, bint dtype_is_object=False): # <<<<<<<<<<<<<< + * self.obj = obj + * self.flags = flags + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":376 + * self.typeinfo = NULL + * + * def __dealloc__(memoryview self): # <<<<<<<<<<<<<< + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + */ + +/* Python wrapper */ +static void __pyx_memoryview___dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_memoryview___dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_2__dealloc__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_2__dealloc__(struct __pyx_memoryview_obj *__pyx_v_self) { + int __pyx_v_i; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + PyThread_type_lock __pyx_t_5; + PyThread_type_lock __pyx_t_6; + + /* "View.MemoryView":377 + * + * def __dealloc__(memoryview self): + * if self.obj is not None: # <<<<<<<<<<<<<< + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + */ + __pyx_t_1 = (__pyx_v_self->obj != Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":378 + * def __dealloc__(memoryview self): + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) # <<<<<<<<<<<<<< + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + * + */ + __Pyx_ReleaseBuffer((&__pyx_v_self->view)); + + /* "View.MemoryView":377 + * + * def __dealloc__(memoryview self): + * if self.obj is not None: # <<<<<<<<<<<<<< + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":379 + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: # <<<<<<<<<<<<<< + * + * (<__pyx_buffer *> &self.view).obj = NULL + */ + __pyx_t_1 = (((Py_buffer *)(&__pyx_v_self->view))->obj == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":381 + * elif (<__pyx_buffer *> &self.view).obj == Py_None: + * + * (<__pyx_buffer *> &self.view).obj = NULL # <<<<<<<<<<<<<< + * Py_DECREF(Py_None) + * + */ + ((Py_buffer *)(&__pyx_v_self->view))->obj = NULL; + + /* "View.MemoryView":382 + * + * (<__pyx_buffer *> &self.view).obj = NULL + * Py_DECREF(Py_None) # <<<<<<<<<<<<<< + * + * cdef int i + */ + Py_DECREF(Py_None); + + /* "View.MemoryView":379 + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + * elif (<__pyx_buffer *> &self.view).obj == Py_None: # <<<<<<<<<<<<<< + * + * (<__pyx_buffer *> &self.view).obj = NULL + */ + } + __pyx_L3:; + + /* "View.MemoryView":386 + * cdef int i + * global __pyx_memoryview_thread_locks_used + * if self.lock != NULL: # <<<<<<<<<<<<<< + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: + */ + __pyx_t_1 = (__pyx_v_self->lock != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":387 + * global __pyx_memoryview_thread_locks_used + * if self.lock != NULL: + * for i in range(__pyx_memoryview_thread_locks_used): # <<<<<<<<<<<<<< + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 + */ + __pyx_t_2 = __pyx_memoryview_thread_locks_used; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":388 + * if self.lock != NULL: + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: + */ + __pyx_t_1 = ((__pyx_memoryview_thread_locks[__pyx_v_i]) == __pyx_v_self->lock); + if (__pyx_t_1) { + + /* "View.MemoryView":389 + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 # <<<<<<<<<<<<<< + * if i != __pyx_memoryview_thread_locks_used: + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + */ + __pyx_memoryview_thread_locks_used = (__pyx_memoryview_thread_locks_used - 1); + + /* "View.MemoryView":390 + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + */ + __pyx_t_1 = (__pyx_v_i != __pyx_memoryview_thread_locks_used); + if (__pyx_t_1) { + + /* "View.MemoryView":392 + * if i != __pyx_memoryview_thread_locks_used: + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) # <<<<<<<<<<<<<< + * break + * else: + */ + __pyx_t_5 = (__pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used]); + __pyx_t_6 = (__pyx_memoryview_thread_locks[__pyx_v_i]); + + /* "View.MemoryView":391 + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + * break + */ + (__pyx_memoryview_thread_locks[__pyx_v_i]) = __pyx_t_5; + (__pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used]) = __pyx_t_6; + + /* "View.MemoryView":390 + * if __pyx_memoryview_thread_locks[i] is self.lock: + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + */ + } + + /* "View.MemoryView":393 + * __pyx_memoryview_thread_locks[i], __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used] = ( + * __pyx_memoryview_thread_locks[__pyx_memoryview_thread_locks_used], __pyx_memoryview_thread_locks[i]) + * break # <<<<<<<<<<<<<< + * else: + * PyThread_free_lock(self.lock) + */ + goto __pyx_L6_break; + + /* "View.MemoryView":388 + * if self.lock != NULL: + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: # <<<<<<<<<<<<<< + * __pyx_memoryview_thread_locks_used -= 1 + * if i != __pyx_memoryview_thread_locks_used: + */ + } + } + /*else*/ { + + /* "View.MemoryView":395 + * break + * else: + * PyThread_free_lock(self.lock) # <<<<<<<<<<<<<< + * + * cdef char *get_item_pointer(memoryview self, object index) except NULL: + */ + PyThread_free_lock(__pyx_v_self->lock); + } + __pyx_L6_break:; + + /* "View.MemoryView":386 + * cdef int i + * global __pyx_memoryview_thread_locks_used + * if self.lock != NULL: # <<<<<<<<<<<<<< + * for i in range(__pyx_memoryview_thread_locks_used): + * if __pyx_memoryview_thread_locks[i] is self.lock: + */ + } + + /* "View.MemoryView":376 + * self.typeinfo = NULL + * + * def __dealloc__(memoryview self): # <<<<<<<<<<<<<< + * if self.obj is not None: + * __Pyx_ReleaseBuffer(&self.view) + */ + + /* function exit code */ +} + +/* "View.MemoryView":397 + * PyThread_free_lock(self.lock) + * + * cdef char *get_item_pointer(memoryview self, object index) except NULL: # <<<<<<<<<<<<<< + * cdef Py_ssize_t dim + * cdef char *itemp = self.view.buf + */ + +static char *__pyx_memoryview_get_item_pointer(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index) { + Py_ssize_t __pyx_v_dim; + char *__pyx_v_itemp; + PyObject *__pyx_v_idx = NULL; + char *__pyx_r; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + Py_ssize_t __pyx_t_3; + PyObject *(*__pyx_t_4)(PyObject *); + PyObject *__pyx_t_5 = NULL; + Py_ssize_t __pyx_t_6; + char *__pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_item_pointer", 1); + + /* "View.MemoryView":399 + * cdef char *get_item_pointer(memoryview self, object index) except NULL: + * cdef Py_ssize_t dim + * cdef char *itemp = self.view.buf # <<<<<<<<<<<<<< + * + * for dim, idx in enumerate(index): + */ + __pyx_v_itemp = ((char *)__pyx_v_self->view.buf); + + /* "View.MemoryView":401 + * cdef char *itemp = self.view.buf + * + * for dim, idx in enumerate(index): # <<<<<<<<<<<<<< + * itemp = pybuffer_index(&self.view, itemp, idx, dim) + * + */ + __pyx_t_1 = 0; + if (likely(PyList_CheckExact(__pyx_v_index)) || PyTuple_CheckExact(__pyx_v_index)) { + __pyx_t_2 = __pyx_v_index; __Pyx_INCREF(__pyx_t_2); + __pyx_t_3 = 0; + __pyx_t_4 = NULL; + } else { + __pyx_t_3 = -1; __pyx_t_2 = PyObject_GetIter(__pyx_v_index); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 401, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_2); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 401, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_4)) { + if (likely(PyList_CheckExact(__pyx_t_2))) { + { + Py_ssize_t __pyx_temp = __Pyx_PyList_GET_SIZE(__pyx_t_2); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 401, __pyx_L1_error) + #endif + if (__pyx_t_3 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_5 = PyList_GET_ITEM(__pyx_t_2, __pyx_t_3); __Pyx_INCREF(__pyx_t_5); __pyx_t_3++; if (unlikely((0 < 0))) __PYX_ERR(0, 401, __pyx_L1_error) + #else + __pyx_t_5 = __Pyx_PySequence_ITEM(__pyx_t_2, __pyx_t_3); __pyx_t_3++; if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 401, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + #endif + } else { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_2); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 401, __pyx_L1_error) + #endif + if (__pyx_t_3 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_5 = PyTuple_GET_ITEM(__pyx_t_2, __pyx_t_3); __Pyx_INCREF(__pyx_t_5); __pyx_t_3++; if (unlikely((0 < 0))) __PYX_ERR(0, 401, __pyx_L1_error) + #else + __pyx_t_5 = __Pyx_PySequence_ITEM(__pyx_t_2, __pyx_t_3); __pyx_t_3++; if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 401, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + #endif + } + } else { + __pyx_t_5 = __pyx_t_4(__pyx_t_2); + if (unlikely(!__pyx_t_5)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(0, 401, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_5); + } + __Pyx_XDECREF_SET(__pyx_v_idx, __pyx_t_5); + __pyx_t_5 = 0; + __pyx_v_dim = __pyx_t_1; + __pyx_t_1 = (__pyx_t_1 + 1); + + /* "View.MemoryView":402 + * + * for dim, idx in enumerate(index): + * itemp = pybuffer_index(&self.view, itemp, idx, dim) # <<<<<<<<<<<<<< + * + * return itemp + */ + __pyx_t_6 = __Pyx_PyIndex_AsSsize_t(__pyx_v_idx); if (unlikely((__pyx_t_6 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 402, __pyx_L1_error) + __pyx_t_7 = __pyx_pybuffer_index((&__pyx_v_self->view), __pyx_v_itemp, __pyx_t_6, __pyx_v_dim); if (unlikely(__pyx_t_7 == ((char *)NULL))) __PYX_ERR(0, 402, __pyx_L1_error) + __pyx_v_itemp = __pyx_t_7; + + /* "View.MemoryView":401 + * cdef char *itemp = self.view.buf + * + * for dim, idx in enumerate(index): # <<<<<<<<<<<<<< + * itemp = pybuffer_index(&self.view, itemp, idx, dim) + * + */ + } + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":404 + * itemp = pybuffer_index(&self.view, itemp, idx, dim) + * + * return itemp # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = __pyx_v_itemp; + goto __pyx_L0; + + /* "View.MemoryView":397 + * PyThread_free_lock(self.lock) + * + * cdef char *get_item_pointer(memoryview self, object index) except NULL: # <<<<<<<<<<<<<< + * cdef Py_ssize_t dim + * cdef char *itemp = self.view.buf + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.memoryview.get_item_pointer", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_idx); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":407 + * + * + * def __getitem__(memoryview self, object index): # <<<<<<<<<<<<<< + * if index is Ellipsis: + * return self + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index); /*proto*/ +static PyObject *__pyx_memoryview___getitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getitem__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_4__getitem__(((struct __pyx_memoryview_obj *)__pyx_v_self), ((PyObject *)__pyx_v_index)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_4__getitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index) { + PyObject *__pyx_v_have_slices = NULL; + PyObject *__pyx_v_indices = NULL; + char *__pyx_v_itemp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + char *__pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__getitem__", 1); + + /* "View.MemoryView":408 + * + * def __getitem__(memoryview self, object index): + * if index is Ellipsis: # <<<<<<<<<<<<<< + * return self + * + */ + __pyx_t_1 = (__pyx_v_index == __pyx_builtin_Ellipsis); + if (__pyx_t_1) { + + /* "View.MemoryView":409 + * def __getitem__(memoryview self, object index): + * if index is Ellipsis: + * return self # <<<<<<<<<<<<<< + * + * have_slices, indices = _unellipsify(index, self.view.ndim) + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_self); + __pyx_r = ((PyObject *)__pyx_v_self); + goto __pyx_L0; + + /* "View.MemoryView":408 + * + * def __getitem__(memoryview self, object index): + * if index is Ellipsis: # <<<<<<<<<<<<<< + * return self + * + */ + } + + /* "View.MemoryView":411 + * return self + * + * have_slices, indices = _unellipsify(index, self.view.ndim) # <<<<<<<<<<<<<< + * + * cdef char *itemp + */ + __pyx_t_2 = _unellipsify(__pyx_v_index, __pyx_v_self->view.ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 411, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (likely(__pyx_t_2 != Py_None)) { + PyObject* sequence = __pyx_t_2; + Py_ssize_t size = __Pyx_PySequence_SIZE(sequence); + if (unlikely(size != 2)) { + if (size > 2) __Pyx_RaiseTooManyValuesError(2); + else if (size >= 0) __Pyx_RaiseNeedMoreValuesError(size); + __PYX_ERR(0, 411, __pyx_L1_error) + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_3 = PyTuple_GET_ITEM(sequence, 0); + __pyx_t_4 = PyTuple_GET_ITEM(sequence, 1); + __Pyx_INCREF(__pyx_t_3); + __Pyx_INCREF(__pyx_t_4); + #else + __pyx_t_3 = PySequence_ITEM(sequence, 0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 411, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PySequence_ITEM(sequence, 1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 411, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + #endif + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + } else { + __Pyx_RaiseNoneNotIterableError(); __PYX_ERR(0, 411, __pyx_L1_error) + } + __pyx_v_have_slices = __pyx_t_3; + __pyx_t_3 = 0; + __pyx_v_indices = __pyx_t_4; + __pyx_t_4 = 0; + + /* "View.MemoryView":414 + * + * cdef char *itemp + * if have_slices: # <<<<<<<<<<<<<< + * return memview_slice(self, indices) + * else: + */ + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_v_have_slices); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(0, 414, __pyx_L1_error) + if (__pyx_t_1) { + + /* "View.MemoryView":415 + * cdef char *itemp + * if have_slices: + * return memview_slice(self, indices) # <<<<<<<<<<<<<< + * else: + * itemp = self.get_item_pointer(indices) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = ((PyObject *)__pyx_memview_slice(__pyx_v_self, __pyx_v_indices)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 415, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":414 + * + * cdef char *itemp + * if have_slices: # <<<<<<<<<<<<<< + * return memview_slice(self, indices) + * else: + */ + } + + /* "View.MemoryView":417 + * return memview_slice(self, indices) + * else: + * itemp = self.get_item_pointer(indices) # <<<<<<<<<<<<<< + * return self.convert_item_to_object(itemp) + * + */ + /*else*/ { + __pyx_t_5 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->get_item_pointer(__pyx_v_self, __pyx_v_indices); if (unlikely(__pyx_t_5 == ((char *)NULL))) __PYX_ERR(0, 417, __pyx_L1_error) + __pyx_v_itemp = __pyx_t_5; + + /* "View.MemoryView":418 + * else: + * itemp = self.get_item_pointer(indices) + * return self.convert_item_to_object(itemp) # <<<<<<<<<<<<<< + * + * def __setitem__(memoryview self, object index, object value): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->convert_item_to_object(__pyx_v_self, __pyx_v_itemp); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 418, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + } + + /* "View.MemoryView":407 + * + * + * def __getitem__(memoryview self, object index): # <<<<<<<<<<<<<< + * if index is Ellipsis: + * return self + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.memoryview.__getitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_have_slices); + __Pyx_XDECREF(__pyx_v_indices); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":420 + * return self.convert_item_to_object(itemp) + * + * def __setitem__(memoryview self, object index, object value): # <<<<<<<<<<<<<< + * if self.view.readonly: + * raise TypeError, "Cannot assign to read-only memoryview" + */ + +/* Python wrapper */ +static int __pyx_memoryview___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value); /*proto*/ +static int __pyx_memoryview___setitem__(PyObject *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setitem__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_6__setitem__(((struct __pyx_memoryview_obj *)__pyx_v_self), ((PyObject *)__pyx_v_index), ((PyObject *)__pyx_v_value)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_6__setitem__(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value) { + PyObject *__pyx_v_have_slices = NULL; + PyObject *__pyx_v_obj = NULL; + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setitem__", 0); + __Pyx_INCREF(__pyx_v_index); + + /* "View.MemoryView":421 + * + * def __setitem__(memoryview self, object index, object value): + * if self.view.readonly: # <<<<<<<<<<<<<< + * raise TypeError, "Cannot assign to read-only memoryview" + * + */ + if (unlikely(__pyx_v_self->view.readonly)) { + + /* "View.MemoryView":422 + * def __setitem__(memoryview self, object index, object value): + * if self.view.readonly: + * raise TypeError, "Cannot assign to read-only memoryview" # <<<<<<<<<<<<<< + * + * have_slices, index = _unellipsify(index, self.view.ndim) + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_Cannot_assign_to_read_only_memor, 0, 0); + __PYX_ERR(0, 422, __pyx_L1_error) + + /* "View.MemoryView":421 + * + * def __setitem__(memoryview self, object index, object value): + * if self.view.readonly: # <<<<<<<<<<<<<< + * raise TypeError, "Cannot assign to read-only memoryview" + * + */ + } + + /* "View.MemoryView":424 + * raise TypeError, "Cannot assign to read-only memoryview" + * + * have_slices, index = _unellipsify(index, self.view.ndim) # <<<<<<<<<<<<<< + * + * if have_slices: + */ + __pyx_t_1 = _unellipsify(__pyx_v_index, __pyx_v_self->view.ndim); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 424, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (likely(__pyx_t_1 != Py_None)) { + PyObject* sequence = __pyx_t_1; + Py_ssize_t size = __Pyx_PySequence_SIZE(sequence); + if (unlikely(size != 2)) { + if (size > 2) __Pyx_RaiseTooManyValuesError(2); + else if (size >= 0) __Pyx_RaiseNeedMoreValuesError(size); + __PYX_ERR(0, 424, __pyx_L1_error) + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_2 = PyTuple_GET_ITEM(sequence, 0); + __pyx_t_3 = PyTuple_GET_ITEM(sequence, 1); + __Pyx_INCREF(__pyx_t_2); + __Pyx_INCREF(__pyx_t_3); + #else + __pyx_t_2 = PySequence_ITEM(sequence, 0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 424, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PySequence_ITEM(sequence, 1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 424, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + #endif + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } else { + __Pyx_RaiseNoneNotIterableError(); __PYX_ERR(0, 424, __pyx_L1_error) + } + __pyx_v_have_slices = __pyx_t_2; + __pyx_t_2 = 0; + __Pyx_DECREF_SET(__pyx_v_index, __pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":426 + * have_slices, index = _unellipsify(index, self.view.ndim) + * + * if have_slices: # <<<<<<<<<<<<<< + * obj = self.is_slice(value) + * if obj: + */ + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_v_have_slices); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 426, __pyx_L1_error) + if (__pyx_t_4) { + + /* "View.MemoryView":427 + * + * if have_slices: + * obj = self.is_slice(value) # <<<<<<<<<<<<<< + * if obj: + * self.setitem_slice_assignment(self[index], obj) + */ + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->is_slice(__pyx_v_self, __pyx_v_value); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 427, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_obj = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":428 + * if have_slices: + * obj = self.is_slice(value) + * if obj: # <<<<<<<<<<<<<< + * self.setitem_slice_assignment(self[index], obj) + * else: + */ + __pyx_t_4 = __Pyx_PyObject_IsTrue(__pyx_v_obj); if (unlikely((__pyx_t_4 < 0))) __PYX_ERR(0, 428, __pyx_L1_error) + if (__pyx_t_4) { + + /* "View.MemoryView":429 + * obj = self.is_slice(value) + * if obj: + * self.setitem_slice_assignment(self[index], obj) # <<<<<<<<<<<<<< + * else: + * self.setitem_slice_assign_scalar(self[index], value) + */ + __pyx_t_1 = __Pyx_PyObject_GetItem(((PyObject *)__pyx_v_self), __pyx_v_index); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 429, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->setitem_slice_assignment(__pyx_v_self, __pyx_t_1, __pyx_v_obj); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 429, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "View.MemoryView":428 + * if have_slices: + * obj = self.is_slice(value) + * if obj: # <<<<<<<<<<<<<< + * self.setitem_slice_assignment(self[index], obj) + * else: + */ + goto __pyx_L5; + } + + /* "View.MemoryView":431 + * self.setitem_slice_assignment(self[index], obj) + * else: + * self.setitem_slice_assign_scalar(self[index], value) # <<<<<<<<<<<<<< + * else: + * self.setitem_indexed(index, value) + */ + /*else*/ { + __pyx_t_3 = __Pyx_PyObject_GetItem(((PyObject *)__pyx_v_self), __pyx_v_index); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 431, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + if (!(likely(((__pyx_t_3) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_3, __pyx_memoryview_type))))) __PYX_ERR(0, 431, __pyx_L1_error) + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->setitem_slice_assign_scalar(__pyx_v_self, ((struct __pyx_memoryview_obj *)__pyx_t_3), __pyx_v_value); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 431, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_L5:; + + /* "View.MemoryView":426 + * have_slices, index = _unellipsify(index, self.view.ndim) + * + * if have_slices: # <<<<<<<<<<<<<< + * obj = self.is_slice(value) + * if obj: + */ + goto __pyx_L4; + } + + /* "View.MemoryView":433 + * self.setitem_slice_assign_scalar(self[index], value) + * else: + * self.setitem_indexed(index, value) # <<<<<<<<<<<<<< + * + * cdef is_slice(self, obj): + */ + /*else*/ { + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->setitem_indexed(__pyx_v_self, __pyx_v_index, __pyx_v_value); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 433, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + } + __pyx_L4:; + + /* "View.MemoryView":420 + * return self.convert_item_to_object(itemp) + * + * def __setitem__(memoryview self, object index, object value): # <<<<<<<<<<<<<< + * if self.view.readonly: + * raise TypeError, "Cannot assign to read-only memoryview" + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.__setitem__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_have_slices); + __Pyx_XDECREF(__pyx_v_obj); + __Pyx_XDECREF(__pyx_v_index); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":435 + * self.setitem_indexed(index, value) + * + * cdef is_slice(self, obj): # <<<<<<<<<<<<<< + * if not isinstance(obj, memoryview): + * try: + */ + +static PyObject *__pyx_memoryview_is_slice(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_obj) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + int __pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("is_slice", 0); + __Pyx_INCREF(__pyx_v_obj); + + /* "View.MemoryView":436 + * + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): # <<<<<<<<<<<<<< + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + */ + __pyx_t_1 = __Pyx_TypeCheck(__pyx_v_obj, __pyx_memoryview_type); + __pyx_t_2 = (!__pyx_t_1); + if (__pyx_t_2) { + + /* "View.MemoryView":437 + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): + * try: # <<<<<<<<<<<<<< + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_3, &__pyx_t_4, &__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_4); + __Pyx_XGOTREF(__pyx_t_5); + /*try:*/ { + + /* "View.MemoryView":438 + * if not isinstance(obj, memoryview): + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, # <<<<<<<<<<<<<< + * self.dtype_is_object) + * except TypeError: + */ + __pyx_t_6 = __Pyx_PyInt_From_int(((__pyx_v_self->flags & (~PyBUF_WRITABLE)) | PyBUF_ANY_CONTIGUOUS)); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 438, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_6); + + /* "View.MemoryView":439 + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) # <<<<<<<<<<<<<< + * except TypeError: + * return None + */ + __pyx_t_7 = __Pyx_PyBool_FromLong(__pyx_v_self->dtype_is_object); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 439, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_7); + + /* "View.MemoryView":438 + * if not isinstance(obj, memoryview): + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, # <<<<<<<<<<<<<< + * self.dtype_is_object) + * except TypeError: + */ + __pyx_t_8 = PyTuple_New(3); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 438, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_8); + __Pyx_INCREF(__pyx_v_obj); + __Pyx_GIVEREF(__pyx_v_obj); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_8, 0, __pyx_v_obj)) __PYX_ERR(0, 438, __pyx_L4_error); + __Pyx_GIVEREF(__pyx_t_6); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_8, 1, __pyx_t_6)) __PYX_ERR(0, 438, __pyx_L4_error); + __Pyx_GIVEREF(__pyx_t_7); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_8, 2, __pyx_t_7)) __PYX_ERR(0, 438, __pyx_L4_error); + __pyx_t_6 = 0; + __pyx_t_7 = 0; + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_memoryview_type), __pyx_t_8, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 438, __pyx_L4_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __Pyx_DECREF_SET(__pyx_v_obj, __pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":437 + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): + * try: # <<<<<<<<<<<<<< + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + */ + } + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + goto __pyx_L9_try_end; + __pyx_L4_error:; + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_XDECREF(__pyx_t_8); __pyx_t_8 = 0; + + /* "View.MemoryView":440 + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + * except TypeError: # <<<<<<<<<<<<<< + * return None + * + */ + __pyx_t_9 = __Pyx_PyErr_ExceptionMatches(__pyx_builtin_TypeError); + if (__pyx_t_9) { + __Pyx_AddTraceback("View.MemoryView.memoryview.is_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_7, &__pyx_t_8, &__pyx_t_6) < 0) __PYX_ERR(0, 440, __pyx_L6_except_error) + __Pyx_XGOTREF(__pyx_t_7); + __Pyx_XGOTREF(__pyx_t_8); + __Pyx_XGOTREF(__pyx_t_6); + + /* "View.MemoryView":441 + * self.dtype_is_object) + * except TypeError: + * return None # <<<<<<<<<<<<<< + * + * return obj + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L7_except_return; + } + goto __pyx_L6_except_error; + + /* "View.MemoryView":437 + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): + * try: # <<<<<<<<<<<<<< + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + * self.dtype_is_object) + */ + __pyx_L6_except_error:; + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_XGIVEREF(__pyx_t_5); + __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_4, __pyx_t_5); + goto __pyx_L1_error; + __pyx_L7_except_return:; + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_XGIVEREF(__pyx_t_5); + __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_4, __pyx_t_5); + goto __pyx_L0; + __pyx_L9_try_end:; + } + + /* "View.MemoryView":436 + * + * cdef is_slice(self, obj): + * if not isinstance(obj, memoryview): # <<<<<<<<<<<<<< + * try: + * obj = memoryview(obj, self.flags & ~PyBUF_WRITABLE | PyBUF_ANY_CONTIGUOUS, + */ + } + + /* "View.MemoryView":443 + * return None + * + * return obj # <<<<<<<<<<<<<< + * + * cdef setitem_slice_assignment(self, dst, src): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_obj); + __pyx_r = __pyx_v_obj; + goto __pyx_L0; + + /* "View.MemoryView":435 + * self.setitem_indexed(index, value) + * + * cdef is_slice(self, obj): # <<<<<<<<<<<<<< + * if not isinstance(obj, memoryview): + * try: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("View.MemoryView.memoryview.is_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_obj); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":445 + * return obj + * + * cdef setitem_slice_assignment(self, dst, src): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice dst_slice + * cdef __Pyx_memviewslice src_slice + */ + +static PyObject *__pyx_memoryview_setitem_slice_assignment(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_dst, PyObject *__pyx_v_src) { + __Pyx_memviewslice __pyx_v_dst_slice; + __Pyx_memviewslice __pyx_v_src_slice; + __Pyx_memviewslice __pyx_v_msrc; + __Pyx_memviewslice __pyx_v_mdst; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_t_3; + int __pyx_t_4; + int __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("setitem_slice_assignment", 1); + + /* "View.MemoryView":448 + * cdef __Pyx_memviewslice dst_slice + * cdef __Pyx_memviewslice src_slice + * cdef __Pyx_memviewslice msrc = get_slice_from_memview(src, &src_slice)[0] # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice mdst = get_slice_from_memview(dst, &dst_slice)[0] + * + */ + if (!(likely(((__pyx_v_src) == Py_None) || likely(__Pyx_TypeTest(__pyx_v_src, __pyx_memoryview_type))))) __PYX_ERR(0, 448, __pyx_L1_error) + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(((struct __pyx_memoryview_obj *)__pyx_v_src), (&__pyx_v_src_slice)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(0, 448, __pyx_L1_error) + __pyx_v_msrc = (__pyx_t_1[0]); + + /* "View.MemoryView":449 + * cdef __Pyx_memviewslice src_slice + * cdef __Pyx_memviewslice msrc = get_slice_from_memview(src, &src_slice)[0] + * cdef __Pyx_memviewslice mdst = get_slice_from_memview(dst, &dst_slice)[0] # <<<<<<<<<<<<<< + * + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) + */ + if (!(likely(((__pyx_v_dst) == Py_None) || likely(__Pyx_TypeTest(__pyx_v_dst, __pyx_memoryview_type))))) __PYX_ERR(0, 449, __pyx_L1_error) + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(((struct __pyx_memoryview_obj *)__pyx_v_dst), (&__pyx_v_dst_slice)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(0, 449, __pyx_L1_error) + __pyx_v_mdst = (__pyx_t_1[0]); + + /* "View.MemoryView":451 + * cdef __Pyx_memviewslice mdst = get_slice_from_memview(dst, &dst_slice)[0] + * + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) # <<<<<<<<<<<<<< + * + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): + */ + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_src, __pyx_n_s_ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 451, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = __Pyx_PyInt_As_int(__pyx_t_2); if (unlikely((__pyx_t_3 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 451, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_v_dst, __pyx_n_s_ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 451, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = __Pyx_PyInt_As_int(__pyx_t_2); if (unlikely((__pyx_t_4 == (int)-1) && PyErr_Occurred())) __PYX_ERR(0, 451, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_5 = __pyx_memoryview_copy_contents(__pyx_v_msrc, __pyx_v_mdst, __pyx_t_3, __pyx_t_4, __pyx_v_self->dtype_is_object); if (unlikely(__pyx_t_5 == ((int)-1))) __PYX_ERR(0, 451, __pyx_L1_error) + + /* "View.MemoryView":445 + * return obj + * + * cdef setitem_slice_assignment(self, dst, src): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice dst_slice + * cdef __Pyx_memviewslice src_slice + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.setitem_slice_assignment", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":453 + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) + * + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): # <<<<<<<<<<<<<< + * cdef int array[128] + * cdef void *tmp = NULL + */ + +static PyObject *__pyx_memoryview_setitem_slice_assign_scalar(struct __pyx_memoryview_obj *__pyx_v_self, struct __pyx_memoryview_obj *__pyx_v_dst, PyObject *__pyx_v_value) { + int __pyx_v_array[0x80]; + void *__pyx_v_tmp; + void *__pyx_v_item; + __Pyx_memviewslice *__pyx_v_dst_slice; + __Pyx_memviewslice __pyx_v_tmp_slice; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + int __pyx_t_4; + int __pyx_t_5; + char const *__pyx_t_6; + PyObject *__pyx_t_7 = NULL; + PyObject *__pyx_t_8 = NULL; + PyObject *__pyx_t_9 = NULL; + PyObject *__pyx_t_10 = NULL; + PyObject *__pyx_t_11 = NULL; + PyObject *__pyx_t_12 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("setitem_slice_assign_scalar", 1); + + /* "View.MemoryView":455 + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): + * cdef int array[128] + * cdef void *tmp = NULL # <<<<<<<<<<<<<< + * cdef void *item + * + */ + __pyx_v_tmp = NULL; + + /* "View.MemoryView":460 + * cdef __Pyx_memviewslice *dst_slice + * cdef __Pyx_memviewslice tmp_slice + * dst_slice = get_slice_from_memview(dst, &tmp_slice) # <<<<<<<<<<<<<< + * + * if self.view.itemsize > sizeof(array): + */ + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(__pyx_v_dst, (&__pyx_v_tmp_slice)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(0, 460, __pyx_L1_error) + __pyx_v_dst_slice = __pyx_t_1; + + /* "View.MemoryView":462 + * dst_slice = get_slice_from_memview(dst, &tmp_slice) + * + * if self.view.itemsize > sizeof(array): # <<<<<<<<<<<<<< + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: + */ + __pyx_t_2 = (((size_t)__pyx_v_self->view.itemsize) > (sizeof(__pyx_v_array))); + if (__pyx_t_2) { + + /* "View.MemoryView":463 + * + * if self.view.itemsize > sizeof(array): + * tmp = PyMem_Malloc(self.view.itemsize) # <<<<<<<<<<<<<< + * if tmp == NULL: + * raise MemoryError + */ + __pyx_v_tmp = PyMem_Malloc(__pyx_v_self->view.itemsize); + + /* "View.MemoryView":464 + * if self.view.itemsize > sizeof(array): + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * item = tmp + */ + __pyx_t_2 = (__pyx_v_tmp == NULL); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":465 + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: + * raise MemoryError # <<<<<<<<<<<<<< + * item = tmp + * else: + */ + PyErr_NoMemory(); __PYX_ERR(0, 465, __pyx_L1_error) + + /* "View.MemoryView":464 + * if self.view.itemsize > sizeof(array): + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: # <<<<<<<<<<<<<< + * raise MemoryError + * item = tmp + */ + } + + /* "View.MemoryView":466 + * if tmp == NULL: + * raise MemoryError + * item = tmp # <<<<<<<<<<<<<< + * else: + * item = array + */ + __pyx_v_item = __pyx_v_tmp; + + /* "View.MemoryView":462 + * dst_slice = get_slice_from_memview(dst, &tmp_slice) + * + * if self.view.itemsize > sizeof(array): # <<<<<<<<<<<<<< + * tmp = PyMem_Malloc(self.view.itemsize) + * if tmp == NULL: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":468 + * item = tmp + * else: + * item = array # <<<<<<<<<<<<<< + * + * try: + */ + /*else*/ { + __pyx_v_item = ((void *)__pyx_v_array); + } + __pyx_L3:; + + /* "View.MemoryView":470 + * item = array + * + * try: # <<<<<<<<<<<<<< + * if self.dtype_is_object: + * ( item)[0] = value + */ + /*try:*/ { + + /* "View.MemoryView":471 + * + * try: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * ( item)[0] = value + * else: + */ + if (__pyx_v_self->dtype_is_object) { + + /* "View.MemoryView":472 + * try: + * if self.dtype_is_object: + * ( item)[0] = value # <<<<<<<<<<<<<< + * else: + * self.assign_item_from_object( item, value) + */ + (((PyObject **)__pyx_v_item)[0]) = ((PyObject *)__pyx_v_value); + + /* "View.MemoryView":471 + * + * try: + * if self.dtype_is_object: # <<<<<<<<<<<<<< + * ( item)[0] = value + * else: + */ + goto __pyx_L8; + } + + /* "View.MemoryView":474 + * ( item)[0] = value + * else: + * self.assign_item_from_object( item, value) # <<<<<<<<<<<<<< + * + * + */ + /*else*/ { + __pyx_t_3 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->assign_item_from_object(__pyx_v_self, ((char *)__pyx_v_item), __pyx_v_value); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 474, __pyx_L6_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_L8:; + + /* "View.MemoryView":478 + * + * + * if self.view.suboffsets != NULL: # <<<<<<<<<<<<<< + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, + */ + __pyx_t_2 = (__pyx_v_self->view.suboffsets != NULL); + if (__pyx_t_2) { + + /* "View.MemoryView":479 + * + * if self.view.suboffsets != NULL: + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) # <<<<<<<<<<<<<< + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, + * item, self.dtype_is_object) + */ + __pyx_t_4 = assert_direct_dimensions(__pyx_v_self->view.suboffsets, __pyx_v_self->view.ndim); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(0, 479, __pyx_L6_error) + + /* "View.MemoryView":478 + * + * + * if self.view.suboffsets != NULL: # <<<<<<<<<<<<<< + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, + */ + } + + /* "View.MemoryView":480 + * if self.view.suboffsets != NULL: + * assert_direct_dimensions(self.view.suboffsets, self.view.ndim) + * slice_assign_scalar(dst_slice, dst.view.ndim, self.view.itemsize, # <<<<<<<<<<<<<< + * item, self.dtype_is_object) + * finally: + */ + __pyx_memoryview_slice_assign_scalar(__pyx_v_dst_slice, __pyx_v_dst->view.ndim, __pyx_v_self->view.itemsize, __pyx_v_item, __pyx_v_self->dtype_is_object); + } + + /* "View.MemoryView":483 + * item, self.dtype_is_object) + * finally: + * PyMem_Free(tmp) # <<<<<<<<<<<<<< + * + * cdef setitem_indexed(self, index, value): + */ + /*finally:*/ { + /*normal exit:*/{ + PyMem_Free(__pyx_v_tmp); + goto __pyx_L7; + } + __pyx_L6_error:; + /*exception exit:*/{ + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __pyx_t_7 = 0; __pyx_t_8 = 0; __pyx_t_9 = 0; __pyx_t_10 = 0; __pyx_t_11 = 0; __pyx_t_12 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + if (PY_MAJOR_VERSION >= 3) __Pyx_ExceptionSwap(&__pyx_t_10, &__pyx_t_11, &__pyx_t_12); + if ((PY_MAJOR_VERSION < 3) || unlikely(__Pyx_GetException(&__pyx_t_7, &__pyx_t_8, &__pyx_t_9) < 0)) __Pyx_ErrFetch(&__pyx_t_7, &__pyx_t_8, &__pyx_t_9); + __Pyx_XGOTREF(__pyx_t_7); + __Pyx_XGOTREF(__pyx_t_8); + __Pyx_XGOTREF(__pyx_t_9); + __Pyx_XGOTREF(__pyx_t_10); + __Pyx_XGOTREF(__pyx_t_11); + __Pyx_XGOTREF(__pyx_t_12); + __pyx_t_4 = __pyx_lineno; __pyx_t_5 = __pyx_clineno; __pyx_t_6 = __pyx_filename; + { + PyMem_Free(__pyx_v_tmp); + } + if (PY_MAJOR_VERSION >= 3) { + __Pyx_XGIVEREF(__pyx_t_10); + __Pyx_XGIVEREF(__pyx_t_11); + __Pyx_XGIVEREF(__pyx_t_12); + __Pyx_ExceptionReset(__pyx_t_10, __pyx_t_11, __pyx_t_12); + } + __Pyx_XGIVEREF(__pyx_t_7); + __Pyx_XGIVEREF(__pyx_t_8); + __Pyx_XGIVEREF(__pyx_t_9); + __Pyx_ErrRestore(__pyx_t_7, __pyx_t_8, __pyx_t_9); + __pyx_t_7 = 0; __pyx_t_8 = 0; __pyx_t_9 = 0; __pyx_t_10 = 0; __pyx_t_11 = 0; __pyx_t_12 = 0; + __pyx_lineno = __pyx_t_4; __pyx_clineno = __pyx_t_5; __pyx_filename = __pyx_t_6; + goto __pyx_L1_error; + } + __pyx_L7:; + } + + /* "View.MemoryView":453 + * memoryview_copy_contents(msrc, mdst, src.ndim, dst.ndim, self.dtype_is_object) + * + * cdef setitem_slice_assign_scalar(self, memoryview dst, value): # <<<<<<<<<<<<<< + * cdef int array[128] + * cdef void *tmp = NULL + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.setitem_slice_assign_scalar", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":485 + * PyMem_Free(tmp) + * + * cdef setitem_indexed(self, index, value): # <<<<<<<<<<<<<< + * cdef char *itemp = self.get_item_pointer(index) + * self.assign_item_from_object(itemp, value) + */ + +static PyObject *__pyx_memoryview_setitem_indexed(struct __pyx_memoryview_obj *__pyx_v_self, PyObject *__pyx_v_index, PyObject *__pyx_v_value) { + char *__pyx_v_itemp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + char *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("setitem_indexed", 1); + + /* "View.MemoryView":486 + * + * cdef setitem_indexed(self, index, value): + * cdef char *itemp = self.get_item_pointer(index) # <<<<<<<<<<<<<< + * self.assign_item_from_object(itemp, value) + * + */ + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->get_item_pointer(__pyx_v_self, __pyx_v_index); if (unlikely(__pyx_t_1 == ((char *)NULL))) __PYX_ERR(0, 486, __pyx_L1_error) + __pyx_v_itemp = __pyx_t_1; + + /* "View.MemoryView":487 + * cdef setitem_indexed(self, index, value): + * cdef char *itemp = self.get_item_pointer(index) + * self.assign_item_from_object(itemp, value) # <<<<<<<<<<<<<< + * + * cdef convert_item_to_object(self, char *itemp): + */ + __pyx_t_2 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->assign_item_from_object(__pyx_v_self, __pyx_v_itemp, __pyx_v_value); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 487, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":485 + * PyMem_Free(tmp) + * + * cdef setitem_indexed(self, index, value): # <<<<<<<<<<<<<< + * cdef char *itemp = self.get_item_pointer(index) + * self.assign_item_from_object(itemp, value) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.setitem_indexed", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":489 + * self.assign_item_from_object(itemp, value) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + +static PyObject *__pyx_memoryview_convert_item_to_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp) { + PyObject *__pyx_v_struct = NULL; + PyObject *__pyx_v_bytesitem = 0; + PyObject *__pyx_v_result = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + int __pyx_t_8; + Py_ssize_t __pyx_t_9; + int __pyx_t_10; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("convert_item_to_object", 1); + + /* "View.MemoryView":492 + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + * import struct # <<<<<<<<<<<<<< + * cdef bytes bytesitem + * + */ + __pyx_t_1 = __Pyx_ImportDottedModule(__pyx_n_s_struct, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 492, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_struct = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":495 + * cdef bytes bytesitem + * + * bytesitem = itemp[:self.view.itemsize] # <<<<<<<<<<<<<< + * try: + * result = struct.unpack(self.view.format, bytesitem) + */ + __pyx_t_1 = __Pyx_PyBytes_FromStringAndSize(__pyx_v_itemp + 0, __pyx_v_self->view.itemsize - 0); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 495, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_bytesitem = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":496 + * + * bytesitem = itemp[:self.view.itemsize] + * try: # <<<<<<<<<<<<<< + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_2, &__pyx_t_3, &__pyx_t_4); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_4); + /*try:*/ { + + /* "View.MemoryView":497 + * bytesitem = itemp[:self.view.itemsize] + * try: + * result = struct.unpack(self.view.format, bytesitem) # <<<<<<<<<<<<<< + * except struct.error: + * raise ValueError, "Unable to convert item to object" + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_unpack); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 497, __pyx_L3_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = __Pyx_PyBytes_FromString(__pyx_v_self->view.format); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 497, __pyx_L3_error) + __Pyx_GOTREF(__pyx_t_6); + __pyx_t_7 = NULL; + __pyx_t_8 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_8 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_7, __pyx_t_6, __pyx_v_bytesitem}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_8, 2+__pyx_t_8); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 497, __pyx_L3_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + __pyx_v_result = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":496 + * + * bytesitem = itemp[:self.view.itemsize] + * try: # <<<<<<<<<<<<<< + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + */ + } + + /* "View.MemoryView":501 + * raise ValueError, "Unable to convert item to object" + * else: + * if len(self.view.format) == 1: # <<<<<<<<<<<<<< + * return result[0] + * return result + */ + /*else:*/ { + __pyx_t_9 = __Pyx_ssize_strlen(__pyx_v_self->view.format); if (unlikely(__pyx_t_9 == ((Py_ssize_t)-1))) __PYX_ERR(0, 501, __pyx_L5_except_error) + __pyx_t_10 = (__pyx_t_9 == 1); + if (__pyx_t_10) { + + /* "View.MemoryView":502 + * else: + * if len(self.view.format) == 1: + * return result[0] # <<<<<<<<<<<<<< + * return result + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_GetItemInt(__pyx_v_result, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 502, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L6_except_return; + + /* "View.MemoryView":501 + * raise ValueError, "Unable to convert item to object" + * else: + * if len(self.view.format) == 1: # <<<<<<<<<<<<<< + * return result[0] + * return result + */ + } + + /* "View.MemoryView":503 + * if len(self.view.format) == 1: + * return result[0] + * return result # <<<<<<<<<<<<<< + * + * cdef assign_item_from_object(self, char *itemp, object value): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_result); + __pyx_r = __pyx_v_result; + goto __pyx_L6_except_return; + } + __pyx_L3_error:; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_6); __pyx_t_6 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":498 + * try: + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: # <<<<<<<<<<<<<< + * raise ValueError, "Unable to convert item to object" + * else: + */ + __Pyx_ErrFetch(&__pyx_t_1, &__pyx_t_5, &__pyx_t_6); + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_error); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 498, __pyx_L5_except_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_8 = __Pyx_PyErr_GivenExceptionMatches(__pyx_t_1, __pyx_t_7); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_ErrRestore(__pyx_t_1, __pyx_t_5, __pyx_t_6); + __pyx_t_1 = 0; __pyx_t_5 = 0; __pyx_t_6 = 0; + if (__pyx_t_8) { + __Pyx_AddTraceback("View.MemoryView.memoryview.convert_item_to_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_6, &__pyx_t_5, &__pyx_t_1) < 0) __PYX_ERR(0, 498, __pyx_L5_except_error) + __Pyx_XGOTREF(__pyx_t_6); + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_1); + + /* "View.MemoryView":499 + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + * raise ValueError, "Unable to convert item to object" # <<<<<<<<<<<<<< + * else: + * if len(self.view.format) == 1: + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Unable_to_convert_item_to_object, 0, 0); + __PYX_ERR(0, 499, __pyx_L5_except_error) + } + goto __pyx_L5_except_error; + + /* "View.MemoryView":496 + * + * bytesitem = itemp[:self.view.itemsize] + * try: # <<<<<<<<<<<<<< + * result = struct.unpack(self.view.format, bytesitem) + * except struct.error: + */ + __pyx_L5_except_error:; + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_ExceptionReset(__pyx_t_2, __pyx_t_3, __pyx_t_4); + goto __pyx_L1_error; + __pyx_L6_except_return:; + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_4); + __Pyx_ExceptionReset(__pyx_t_2, __pyx_t_3, __pyx_t_4); + goto __pyx_L0; + } + + /* "View.MemoryView":489 + * self.assign_item_from_object(itemp, value) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("View.MemoryView.memoryview.convert_item_to_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_struct); + __Pyx_XDECREF(__pyx_v_bytesitem); + __Pyx_XDECREF(__pyx_v_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":505 + * return result + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + +static PyObject *__pyx_memoryview_assign_item_from_object(struct __pyx_memoryview_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value) { + PyObject *__pyx_v_struct = NULL; + char __pyx_v_c; + PyObject *__pyx_v_bytesvalue = 0; + Py_ssize_t __pyx_v_i; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + Py_ssize_t __pyx_t_7; + PyObject *__pyx_t_8 = NULL; + char *__pyx_t_9; + char *__pyx_t_10; + char *__pyx_t_11; + char *__pyx_t_12; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("assign_item_from_object", 1); + + /* "View.MemoryView":508 + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + * import struct # <<<<<<<<<<<<<< + * cdef char c + * cdef bytes bytesvalue + */ + __pyx_t_1 = __Pyx_ImportDottedModule(__pyx_n_s_struct, NULL); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 508, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_v_struct = __pyx_t_1; + __pyx_t_1 = 0; + + /* "View.MemoryView":513 + * cdef Py_ssize_t i + * + * if isinstance(value, tuple): # <<<<<<<<<<<<<< + * bytesvalue = struct.pack(self.view.format, *value) + * else: + */ + __pyx_t_2 = PyTuple_Check(__pyx_v_value); + if (__pyx_t_2) { + + /* "View.MemoryView":514 + * + * if isinstance(value, tuple): + * bytesvalue = struct.pack(self.view.format, *value) # <<<<<<<<<<<<<< + * else: + * bytesvalue = struct.pack(self.view.format, value) + */ + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_pack); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = __Pyx_PyBytes_FromString(__pyx_v_self->view.format); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = PyTuple_New(1); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_3); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_4, 0, __pyx_t_3)) __PYX_ERR(0, 514, __pyx_L1_error); + __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PySequence_Tuple(__pyx_v_value); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = PyNumber_Add(__pyx_t_4, __pyx_t_3); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_t_3 = __Pyx_PyObject_Call(__pyx_t_1, __pyx_t_5, NULL); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 514, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (!(likely(PyBytes_CheckExact(__pyx_t_3))||((__pyx_t_3) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_t_3))) __PYX_ERR(0, 514, __pyx_L1_error) + __pyx_v_bytesvalue = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":513 + * cdef Py_ssize_t i + * + * if isinstance(value, tuple): # <<<<<<<<<<<<<< + * bytesvalue = struct.pack(self.view.format, *value) + * else: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":516 + * bytesvalue = struct.pack(self.view.format, *value) + * else: + * bytesvalue = struct.pack(self.view.format, value) # <<<<<<<<<<<<<< + * + * for i, c in enumerate(bytesvalue): + */ + /*else*/ { + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_v_struct, __pyx_n_s_pack); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 516, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 = __Pyx_PyBytes_FromString(__pyx_v_self->view.format); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 516, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_4 = NULL; + __pyx_t_6 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_5))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_5); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_5); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_5, function); + __pyx_t_6 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[3] = {__pyx_t_4, __pyx_t_1, __pyx_v_value}; + __pyx_t_3 = __Pyx_PyObject_FastCall(__pyx_t_5, __pyx_callargs+1-__pyx_t_6, 2+__pyx_t_6); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 516, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + if (!(likely(PyBytes_CheckExact(__pyx_t_3))||((__pyx_t_3) == Py_None) || __Pyx_RaiseUnexpectedTypeError("bytes", __pyx_t_3))) __PYX_ERR(0, 516, __pyx_L1_error) + __pyx_v_bytesvalue = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; + } + __pyx_L3:; + + /* "View.MemoryView":518 + * bytesvalue = struct.pack(self.view.format, value) + * + * for i, c in enumerate(bytesvalue): # <<<<<<<<<<<<<< + * itemp[i] = c + * + */ + __pyx_t_7 = 0; + if (unlikely(__pyx_v_bytesvalue == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' is not iterable"); + __PYX_ERR(0, 518, __pyx_L1_error) + } + __Pyx_INCREF(__pyx_v_bytesvalue); + __pyx_t_8 = __pyx_v_bytesvalue; + __pyx_t_10 = PyBytes_AS_STRING(__pyx_t_8); + __pyx_t_11 = (__pyx_t_10 + PyBytes_GET_SIZE(__pyx_t_8)); + for (__pyx_t_12 = __pyx_t_10; __pyx_t_12 < __pyx_t_11; __pyx_t_12++) { + __pyx_t_9 = __pyx_t_12; + __pyx_v_c = (__pyx_t_9[0]); + + /* "View.MemoryView":519 + * + * for i, c in enumerate(bytesvalue): + * itemp[i] = c # <<<<<<<<<<<<<< + * + * @cname('getbuffer') + */ + __pyx_v_i = __pyx_t_7; + + /* "View.MemoryView":518 + * bytesvalue = struct.pack(self.view.format, value) + * + * for i, c in enumerate(bytesvalue): # <<<<<<<<<<<<<< + * itemp[i] = c + * + */ + __pyx_t_7 = (__pyx_t_7 + 1); + + /* "View.MemoryView":519 + * + * for i, c in enumerate(bytesvalue): + * itemp[i] = c # <<<<<<<<<<<<<< + * + * @cname('getbuffer') + */ + (__pyx_v_itemp[__pyx_v_i]) = __pyx_v_c; + } + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + + /* "View.MemoryView":505 + * return result + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * """Only used if instantiated manually by the user, or if Cython doesn't + * know how to convert the type""" + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("View.MemoryView.memoryview.assign_item_from_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_struct); + __Pyx_XDECREF(__pyx_v_bytesvalue); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":521 + * itemp[i] = c + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: + */ + +/* Python wrapper */ +CYTHON_UNUSED static int __pyx_memoryview_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags); /*proto*/ +CYTHON_UNUSED static int __pyx_memoryview_getbuffer(PyObject *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__getbuffer__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_8__getbuffer__(((struct __pyx_memoryview_obj *)__pyx_v_self), ((Py_buffer *)__pyx_v_info), ((int)__pyx_v_flags)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_8__getbuffer__(struct __pyx_memoryview_obj *__pyx_v_self, Py_buffer *__pyx_v_info, int __pyx_v_flags) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + Py_ssize_t *__pyx_t_3; + char *__pyx_t_4; + void *__pyx_t_5; + int __pyx_t_6; + Py_ssize_t __pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + if (unlikely(__pyx_v_info == NULL)) { + PyErr_SetString(PyExc_BufferError, "PyObject_GetBuffer: view==NULL argument is obsolete"); + return -1; + } + __Pyx_RefNannySetupContext("__getbuffer__", 0); + __pyx_v_info->obj = Py_None; __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(__pyx_v_info->obj); + + /* "View.MemoryView":523 + * @cname('getbuffer') + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: # <<<<<<<<<<<<<< + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + */ + __pyx_t_2 = ((__pyx_v_flags & PyBUF_WRITABLE) != 0); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_1 = __pyx_v_self->view.readonly; + __pyx_L4_bool_binop_done:; + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":524 + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: + * raise ValueError, "Cannot create writable memory view from read-only memoryview" # <<<<<<<<<<<<<< + * + * if flags & PyBUF_ND: + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Cannot_create_writable_memory_vi, 0, 0); + __PYX_ERR(0, 524, __pyx_L1_error) + + /* "View.MemoryView":523 + * @cname('getbuffer') + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: # <<<<<<<<<<<<<< + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + */ + } + + /* "View.MemoryView":526 + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + * if flags & PyBUF_ND: # <<<<<<<<<<<<<< + * info.shape = self.view.shape + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_ND) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":527 + * + * if flags & PyBUF_ND: + * info.shape = self.view.shape # <<<<<<<<<<<<<< + * else: + * info.shape = NULL + */ + __pyx_t_3 = __pyx_v_self->view.shape; + __pyx_v_info->shape = __pyx_t_3; + + /* "View.MemoryView":526 + * raise ValueError, "Cannot create writable memory view from read-only memoryview" + * + * if flags & PyBUF_ND: # <<<<<<<<<<<<<< + * info.shape = self.view.shape + * else: + */ + goto __pyx_L6; + } + + /* "View.MemoryView":529 + * info.shape = self.view.shape + * else: + * info.shape = NULL # <<<<<<<<<<<<<< + * + * if flags & PyBUF_STRIDES: + */ + /*else*/ { + __pyx_v_info->shape = NULL; + } + __pyx_L6:; + + /* "View.MemoryView":531 + * info.shape = NULL + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.strides = self.view.strides + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_STRIDES) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":532 + * + * if flags & PyBUF_STRIDES: + * info.strides = self.view.strides # <<<<<<<<<<<<<< + * else: + * info.strides = NULL + */ + __pyx_t_3 = __pyx_v_self->view.strides; + __pyx_v_info->strides = __pyx_t_3; + + /* "View.MemoryView":531 + * info.shape = NULL + * + * if flags & PyBUF_STRIDES: # <<<<<<<<<<<<<< + * info.strides = self.view.strides + * else: + */ + goto __pyx_L7; + } + + /* "View.MemoryView":534 + * info.strides = self.view.strides + * else: + * info.strides = NULL # <<<<<<<<<<<<<< + * + * if flags & PyBUF_INDIRECT: + */ + /*else*/ { + __pyx_v_info->strides = NULL; + } + __pyx_L7:; + + /* "View.MemoryView":536 + * info.strides = NULL + * + * if flags & PyBUF_INDIRECT: # <<<<<<<<<<<<<< + * info.suboffsets = self.view.suboffsets + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_INDIRECT) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":537 + * + * if flags & PyBUF_INDIRECT: + * info.suboffsets = self.view.suboffsets # <<<<<<<<<<<<<< + * else: + * info.suboffsets = NULL + */ + __pyx_t_3 = __pyx_v_self->view.suboffsets; + __pyx_v_info->suboffsets = __pyx_t_3; + + /* "View.MemoryView":536 + * info.strides = NULL + * + * if flags & PyBUF_INDIRECT: # <<<<<<<<<<<<<< + * info.suboffsets = self.view.suboffsets + * else: + */ + goto __pyx_L8; + } + + /* "View.MemoryView":539 + * info.suboffsets = self.view.suboffsets + * else: + * info.suboffsets = NULL # <<<<<<<<<<<<<< + * + * if flags & PyBUF_FORMAT: + */ + /*else*/ { + __pyx_v_info->suboffsets = NULL; + } + __pyx_L8:; + + /* "View.MemoryView":541 + * info.suboffsets = NULL + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * info.format = self.view.format + * else: + */ + __pyx_t_1 = ((__pyx_v_flags & PyBUF_FORMAT) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":542 + * + * if flags & PyBUF_FORMAT: + * info.format = self.view.format # <<<<<<<<<<<<<< + * else: + * info.format = NULL + */ + __pyx_t_4 = __pyx_v_self->view.format; + __pyx_v_info->format = __pyx_t_4; + + /* "View.MemoryView":541 + * info.suboffsets = NULL + * + * if flags & PyBUF_FORMAT: # <<<<<<<<<<<<<< + * info.format = self.view.format + * else: + */ + goto __pyx_L9; + } + + /* "View.MemoryView":544 + * info.format = self.view.format + * else: + * info.format = NULL # <<<<<<<<<<<<<< + * + * info.buf = self.view.buf + */ + /*else*/ { + __pyx_v_info->format = NULL; + } + __pyx_L9:; + + /* "View.MemoryView":546 + * info.format = NULL + * + * info.buf = self.view.buf # <<<<<<<<<<<<<< + * info.ndim = self.view.ndim + * info.itemsize = self.view.itemsize + */ + __pyx_t_5 = __pyx_v_self->view.buf; + __pyx_v_info->buf = __pyx_t_5; + + /* "View.MemoryView":547 + * + * info.buf = self.view.buf + * info.ndim = self.view.ndim # <<<<<<<<<<<<<< + * info.itemsize = self.view.itemsize + * info.len = self.view.len + */ + __pyx_t_6 = __pyx_v_self->view.ndim; + __pyx_v_info->ndim = __pyx_t_6; + + /* "View.MemoryView":548 + * info.buf = self.view.buf + * info.ndim = self.view.ndim + * info.itemsize = self.view.itemsize # <<<<<<<<<<<<<< + * info.len = self.view.len + * info.readonly = self.view.readonly + */ + __pyx_t_7 = __pyx_v_self->view.itemsize; + __pyx_v_info->itemsize = __pyx_t_7; + + /* "View.MemoryView":549 + * info.ndim = self.view.ndim + * info.itemsize = self.view.itemsize + * info.len = self.view.len # <<<<<<<<<<<<<< + * info.readonly = self.view.readonly + * info.obj = self + */ + __pyx_t_7 = __pyx_v_self->view.len; + __pyx_v_info->len = __pyx_t_7; + + /* "View.MemoryView":550 + * info.itemsize = self.view.itemsize + * info.len = self.view.len + * info.readonly = self.view.readonly # <<<<<<<<<<<<<< + * info.obj = self + * + */ + __pyx_t_1 = __pyx_v_self->view.readonly; + __pyx_v_info->readonly = __pyx_t_1; + + /* "View.MemoryView":551 + * info.len = self.view.len + * info.readonly = self.view.readonly + * info.obj = self # <<<<<<<<<<<<<< + * + * + */ + __Pyx_INCREF((PyObject *)__pyx_v_self); + __Pyx_GIVEREF((PyObject *)__pyx_v_self); + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); + __pyx_v_info->obj = ((PyObject *)__pyx_v_self); + + /* "View.MemoryView":521 + * itemp[i] = c + * + * @cname('getbuffer') # <<<<<<<<<<<<<< + * def __getbuffer__(self, Py_buffer *info, int flags): + * if flags & PyBUF_WRITABLE and self.view.readonly: + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__getbuffer__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + if (__pyx_v_info->obj != NULL) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + goto __pyx_L2; + __pyx_L0:; + if (__pyx_v_info->obj == Py_None) { + __Pyx_GOTREF(__pyx_v_info->obj); + __Pyx_DECREF(__pyx_v_info->obj); __pyx_v_info->obj = 0; + } + __pyx_L2:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":554 + * + * + * @property # <<<<<<<<<<<<<< + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_1T_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_1T_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_1T___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_1T___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + struct __pyx_memoryviewslice_obj *__pyx_v_result = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":556 + * @property + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) # <<<<<<<<<<<<<< + * transpose_memslice(&result.from_slice) + * return result + */ + __pyx_t_1 = __pyx_memoryview_copy_object(__pyx_v_self); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 556, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + if (!(likely(((__pyx_t_1) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_1, __pyx_memoryviewslice_type))))) __PYX_ERR(0, 556, __pyx_L1_error) + __pyx_v_result = ((struct __pyx_memoryviewslice_obj *)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":557 + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) + * transpose_memslice(&result.from_slice) # <<<<<<<<<<<<<< + * return result + * + */ + __pyx_t_2 = __pyx_memslice_transpose((&__pyx_v_result->from_slice)); if (unlikely(__pyx_t_2 == ((int)-1))) __PYX_ERR(0, 557, __pyx_L1_error) + + /* "View.MemoryView":558 + * cdef _memoryviewslice result = memoryview_copy(self) + * transpose_memslice(&result.from_slice) + * return result # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = ((PyObject *)__pyx_v_result); + goto __pyx_L0; + + /* "View.MemoryView":554 + * + * + * @property # <<<<<<<<<<<<<< + * def T(self): + * cdef _memoryviewslice result = memoryview_copy(self) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.T.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":560 + * return result + * + * @property # <<<<<<<<<<<<<< + * def base(self): + * return self._get_base() + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4base_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4base_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_4base___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4base___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":562 + * @property + * def base(self): + * return self._get_base() # <<<<<<<<<<<<<< + * + * cdef _get_base(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = ((struct __pyx_vtabstruct_memoryview *)__pyx_v_self->__pyx_vtab)->_get_base(__pyx_v_self); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 562, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":560 + * return result + * + * @property # <<<<<<<<<<<<<< + * def base(self): + * return self._get_base() + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.base.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":564 + * return self._get_base() + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.obj + * + */ + +static PyObject *__pyx_memoryview__get_base(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("_get_base", 1); + + /* "View.MemoryView":565 + * + * cdef _get_base(self): + * return self.obj # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->obj); + __pyx_r = __pyx_v_self->obj; + goto __pyx_L0; + + /* "View.MemoryView":564 + * return self._get_base() + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.obj + * + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":567 + * return self.obj + * + * @property # <<<<<<<<<<<<<< + * def shape(self): + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_5shape_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_5shape_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_5shape___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_5shape___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_7genexpr__pyx_v_length; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + PyObject *__pyx_t_5 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":569 + * @property + * def shape(self): + * return tuple([length for length in self.view.shape[:self.view.ndim]]) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + { /* enter inner scope */ + __pyx_t_1 = PyList_New(0); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 569, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_3 = (__pyx_v_self->view.shape + __pyx_v_self->view.ndim); + for (__pyx_t_4 = __pyx_v_self->view.shape; __pyx_t_4 < __pyx_t_3; __pyx_t_4++) { + __pyx_t_2 = __pyx_t_4; + __pyx_7genexpr__pyx_v_length = (__pyx_t_2[0]); + __pyx_t_5 = PyInt_FromSsize_t(__pyx_7genexpr__pyx_v_length); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 569, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_1, (PyObject*)__pyx_t_5))) __PYX_ERR(0, 569, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + } + } /* exit inner scope */ + __pyx_t_5 = PyList_AsTuple(((PyObject*)__pyx_t_1)); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 569, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_r = __pyx_t_5; + __pyx_t_5 = 0; + goto __pyx_L0; + + /* "View.MemoryView":567 + * return self.obj + * + * @property # <<<<<<<<<<<<<< + * def shape(self): + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.memoryview.shape.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":571 + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def strides(self): + * if self.view.strides == NULL: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_7strides_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_7strides_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_7strides___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_7strides___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_8genexpr1__pyx_v_stride; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + Py_ssize_t *__pyx_t_5; + PyObject *__pyx_t_6 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":573 + * @property + * def strides(self): + * if self.view.strides == NULL: # <<<<<<<<<<<<<< + * + * raise ValueError, "Buffer view does not expose strides" + */ + __pyx_t_1 = (__pyx_v_self->view.strides == NULL); + if (unlikely(__pyx_t_1)) { + + /* "View.MemoryView":575 + * if self.view.strides == NULL: + * + * raise ValueError, "Buffer view does not expose strides" # <<<<<<<<<<<<<< + * + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Buffer_view_does_not_expose_stri, 0, 0); + __PYX_ERR(0, 575, __pyx_L1_error) + + /* "View.MemoryView":573 + * @property + * def strides(self): + * if self.view.strides == NULL: # <<<<<<<<<<<<<< + * + * raise ValueError, "Buffer view does not expose strides" + */ + } + + /* "View.MemoryView":577 + * raise ValueError, "Buffer view does not expose strides" + * + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + { /* enter inner scope */ + __pyx_t_2 = PyList_New(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 577, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = (__pyx_v_self->view.strides + __pyx_v_self->view.ndim); + for (__pyx_t_5 = __pyx_v_self->view.strides; __pyx_t_5 < __pyx_t_4; __pyx_t_5++) { + __pyx_t_3 = __pyx_t_5; + __pyx_8genexpr1__pyx_v_stride = (__pyx_t_3[0]); + __pyx_t_6 = PyInt_FromSsize_t(__pyx_8genexpr1__pyx_v_stride); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 577, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_2, (PyObject*)__pyx_t_6))) __PYX_ERR(0, 577, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + } /* exit inner scope */ + __pyx_t_6 = PyList_AsTuple(((PyObject*)__pyx_t_2)); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 577, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_6; + __pyx_t_6 = 0; + goto __pyx_L0; + + /* "View.MemoryView":571 + * return tuple([length for length in self.view.shape[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def strides(self): + * if self.view.strides == NULL: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("View.MemoryView.memoryview.strides.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":579 + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def suboffsets(self): + * if self.view.suboffsets == NULL: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_10suboffsets_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_10suboffsets_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_10suboffsets___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_10suboffsets___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_8genexpr2__pyx_v_suboffset; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + Py_ssize_t *__pyx_t_5; + PyObject *__pyx_t_6 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":581 + * @property + * def suboffsets(self): + * if self.view.suboffsets == NULL: # <<<<<<<<<<<<<< + * return (-1,) * self.view.ndim + * + */ + __pyx_t_1 = (__pyx_v_self->view.suboffsets == NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":582 + * def suboffsets(self): + * if self.view.suboffsets == NULL: + * return (-1,) * self.view.ndim # <<<<<<<<<<<<<< + * + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PySequence_Multiply(__pyx_tuple__4, __pyx_v_self->view.ndim); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 582, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":581 + * @property + * def suboffsets(self): + * if self.view.suboffsets == NULL: # <<<<<<<<<<<<<< + * return (-1,) * self.view.ndim + * + */ + } + + /* "View.MemoryView":584 + * return (-1,) * self.view.ndim + * + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + { /* enter inner scope */ + __pyx_t_2 = PyList_New(0); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 584, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_4 = (__pyx_v_self->view.suboffsets + __pyx_v_self->view.ndim); + for (__pyx_t_5 = __pyx_v_self->view.suboffsets; __pyx_t_5 < __pyx_t_4; __pyx_t_5++) { + __pyx_t_3 = __pyx_t_5; + __pyx_8genexpr2__pyx_v_suboffset = (__pyx_t_3[0]); + __pyx_t_6 = PyInt_FromSsize_t(__pyx_8genexpr2__pyx_v_suboffset); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 584, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + if (unlikely(__Pyx_ListComp_Append(__pyx_t_2, (PyObject*)__pyx_t_6))) __PYX_ERR(0, 584, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + } /* exit inner scope */ + __pyx_t_6 = PyList_AsTuple(((PyObject*)__pyx_t_2)); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 584, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_6; + __pyx_t_6 = 0; + goto __pyx_L0; + + /* "View.MemoryView":579 + * return tuple([stride for stride in self.view.strides[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def suboffsets(self): + * if self.view.suboffsets == NULL: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_AddTraceback("View.MemoryView.memoryview.suboffsets.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":586 + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def ndim(self): + * return self.view.ndim + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4ndim_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4ndim_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_4ndim___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4ndim___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":588 + * @property + * def ndim(self): + * return self.view.ndim # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_self->view.ndim); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 588, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":586 + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + * + * @property # <<<<<<<<<<<<<< + * def ndim(self): + * return self.view.ndim + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.ndim.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":590 + * return self.view.ndim + * + * @property # <<<<<<<<<<<<<< + * def itemsize(self): + * return self.view.itemsize + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_8itemsize_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_8itemsize_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_8itemsize___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_8itemsize___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":592 + * @property + * def itemsize(self): + * return self.view.itemsize # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = PyInt_FromSsize_t(__pyx_v_self->view.itemsize); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 592, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":590 + * return self.view.ndim + * + * @property # <<<<<<<<<<<<<< + * def itemsize(self): + * return self.view.itemsize + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview.itemsize.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":594 + * return self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def nbytes(self): + * return self.size * self.view.itemsize + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_6nbytes_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_6nbytes_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_6nbytes___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_6nbytes___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":596 + * @property + * def nbytes(self): + * return self.size * self.view.itemsize # <<<<<<<<<<<<<< + * + * @property + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_size); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 596, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = PyInt_FromSsize_t(__pyx_v_self->view.itemsize); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 596, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyNumber_Multiply(__pyx_t_1, __pyx_t_2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 596, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_3; + __pyx_t_3 = 0; + goto __pyx_L0; + + /* "View.MemoryView":594 + * return self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def nbytes(self): + * return self.size * self.view.itemsize + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.nbytes.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":598 + * return self.size * self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def size(self): + * if self._size is None: + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4size_1__get__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_pw_15View_dot_MemoryView_10memoryview_4size_1__get__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__get__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_pf_15View_dot_MemoryView_10memoryview_4size___get__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView_10memoryview_4size___get__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_v_result = NULL; + PyObject *__pyx_v_length = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + PyObject *__pyx_t_5 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__get__", 1); + + /* "View.MemoryView":600 + * @property + * def size(self): + * if self._size is None: # <<<<<<<<<<<<<< + * result = 1 + * + */ + __pyx_t_1 = (__pyx_v_self->_size == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":601 + * def size(self): + * if self._size is None: + * result = 1 # <<<<<<<<<<<<<< + * + * for length in self.view.shape[:self.view.ndim]: + */ + __Pyx_INCREF(__pyx_int_1); + __pyx_v_result = __pyx_int_1; + + /* "View.MemoryView":603 + * result = 1 + * + * for length in self.view.shape[:self.view.ndim]: # <<<<<<<<<<<<<< + * result *= length + * + */ + __pyx_t_3 = (__pyx_v_self->view.shape + __pyx_v_self->view.ndim); + for (__pyx_t_4 = __pyx_v_self->view.shape; __pyx_t_4 < __pyx_t_3; __pyx_t_4++) { + __pyx_t_2 = __pyx_t_4; + __pyx_t_5 = PyInt_FromSsize_t((__pyx_t_2[0])); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 603, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_XDECREF_SET(__pyx_v_length, __pyx_t_5); + __pyx_t_5 = 0; + + /* "View.MemoryView":604 + * + * for length in self.view.shape[:self.view.ndim]: + * result *= length # <<<<<<<<<<<<<< + * + * self._size = result + */ + __pyx_t_5 = PyNumber_InPlaceMultiply(__pyx_v_result, __pyx_v_length); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 604, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF_SET(__pyx_v_result, __pyx_t_5); + __pyx_t_5 = 0; + } + + /* "View.MemoryView":606 + * result *= length + * + * self._size = result # <<<<<<<<<<<<<< + * + * return self._size + */ + __Pyx_INCREF(__pyx_v_result); + __Pyx_GIVEREF(__pyx_v_result); + __Pyx_GOTREF(__pyx_v_self->_size); + __Pyx_DECREF(__pyx_v_self->_size); + __pyx_v_self->_size = __pyx_v_result; + + /* "View.MemoryView":600 + * @property + * def size(self): + * if self._size is None: # <<<<<<<<<<<<<< + * result = 1 + * + */ + } + + /* "View.MemoryView":608 + * self._size = result + * + * return self._size # <<<<<<<<<<<<<< + * + * def __len__(self): + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->_size); + __pyx_r = __pyx_v_self->_size; + goto __pyx_L0; + + /* "View.MemoryView":598 + * return self.size * self.view.itemsize + * + * @property # <<<<<<<<<<<<<< + * def size(self): + * if self._size is None: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.memoryview.size.__get__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_result); + __Pyx_XDECREF(__pyx_v_length); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":610 + * return self._size + * + * def __len__(self): # <<<<<<<<<<<<<< + * if self.view.ndim >= 1: + * return self.view.shape[0] + */ + +/* Python wrapper */ +static Py_ssize_t __pyx_memoryview___len__(PyObject *__pyx_v_self); /*proto*/ +static Py_ssize_t __pyx_memoryview___len__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + Py_ssize_t __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__len__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_10__len__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static Py_ssize_t __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_10__len__(struct __pyx_memoryview_obj *__pyx_v_self) { + Py_ssize_t __pyx_r; + int __pyx_t_1; + + /* "View.MemoryView":611 + * + * def __len__(self): + * if self.view.ndim >= 1: # <<<<<<<<<<<<<< + * return self.view.shape[0] + * + */ + __pyx_t_1 = (__pyx_v_self->view.ndim >= 1); + if (__pyx_t_1) { + + /* "View.MemoryView":612 + * def __len__(self): + * if self.view.ndim >= 1: + * return self.view.shape[0] # <<<<<<<<<<<<<< + * + * return 0 + */ + __pyx_r = (__pyx_v_self->view.shape[0]); + goto __pyx_L0; + + /* "View.MemoryView":611 + * + * def __len__(self): + * if self.view.ndim >= 1: # <<<<<<<<<<<<<< + * return self.view.shape[0] + * + */ + } + + /* "View.MemoryView":614 + * return self.view.shape[0] + * + * return 0 # <<<<<<<<<<<<<< + * + * def __repr__(self): + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":610 + * return self._size + * + * def __len__(self): # <<<<<<<<<<<<<< + * if self.view.ndim >= 1: + * return self.view.shape[0] + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":616 + * return 0 + * + * def __repr__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__, + * id(self)) + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview___repr__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_memoryview___repr__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__repr__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_12__repr__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_12__repr__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__repr__", 1); + + /* "View.MemoryView":617 + * + * def __repr__(self): + * return "" % (self.base.__class__.__name__, # <<<<<<<<<<<<<< + * id(self)) + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_base); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_class); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_name_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":618 + * def __repr__(self): + * return "" % (self.base.__class__.__name__, + * id(self)) # <<<<<<<<<<<<<< + * + * def __str__(self): + */ + __pyx_t_2 = __Pyx_PyObject_CallOneArg(__pyx_builtin_id, ((PyObject *)__pyx_v_self)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 618, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + + /* "View.MemoryView":617 + * + * def __repr__(self): + * return "" % (self.base.__class__.__name__, # <<<<<<<<<<<<<< + * id(self)) + * + */ + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_1)) __PYX_ERR(0, 617, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_2)) __PYX_ERR(0, 617, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyString_Format(__pyx_kp_s_MemoryView_of_r_at_0x_x, __pyx_t_3); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 617, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":616 + * return 0 + * + * def __repr__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__, + * id(self)) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview.__repr__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":620 + * id(self)) + * + * def __str__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__,) + * + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview___str__(PyObject *__pyx_v_self); /*proto*/ +static PyObject *__pyx_memoryview___str__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__str__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_14__str__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_14__str__(struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__str__", 1); + + /* "View.MemoryView":621 + * + * def __str__(self): + * return "" % (self.base.__class__.__name__,) # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v_self), __pyx_n_s_base); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyObject_GetAttrStr(__pyx_t_1, __pyx_n_s_class); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyObject_GetAttrStr(__pyx_t_2, __pyx_n_s_name_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_2 = PyTuple_New(1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_2, 0, __pyx_t_1)) __PYX_ERR(0, 621, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_MemoryView_of_r_object, __pyx_t_2); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 621, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":620 + * id(self)) + * + * def __str__(self): # <<<<<<<<<<<<<< + * return "" % (self.base.__class__.__name__,) + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.__str__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":624 + * + * + * def is_c_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_is_c_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_is_c_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("is_c_contig (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("is_c_contig", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "is_c_contig", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_16is_c_contig(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_16is_c_contig(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice *__pyx_v_mslice; + __Pyx_memviewslice __pyx_v_tmp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("is_c_contig", 1); + + /* "View.MemoryView":627 + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) # <<<<<<<<<<<<<< + * return slice_is_contig(mslice[0], 'C', self.view.ndim) + * + */ + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(__pyx_v_self, (&__pyx_v_tmp)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(0, 627, __pyx_L1_error) + __pyx_v_mslice = __pyx_t_1; + + /* "View.MemoryView":628 + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) + * return slice_is_contig(mslice[0], 'C', self.view.ndim) # <<<<<<<<<<<<<< + * + * def is_f_contig(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_memviewslice_is_contig((__pyx_v_mslice[0]), 'C', __pyx_v_self->view.ndim)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 628, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":624 + * + * + * def is_c_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.is_c_contig", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":630 + * return slice_is_contig(mslice[0], 'C', self.view.ndim) + * + * def is_f_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_is_f_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_is_f_contig(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("is_f_contig (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("is_f_contig", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "is_f_contig", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_18is_f_contig(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_18is_f_contig(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice *__pyx_v_mslice; + __Pyx_memviewslice __pyx_v_tmp; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice *__pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("is_f_contig", 1); + + /* "View.MemoryView":633 + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) # <<<<<<<<<<<<<< + * return slice_is_contig(mslice[0], 'F', self.view.ndim) + * + */ + __pyx_t_1 = __pyx_memoryview_get_slice_from_memoryview(__pyx_v_self, (&__pyx_v_tmp)); if (unlikely(__pyx_t_1 == ((__Pyx_memviewslice *)NULL))) __PYX_ERR(0, 633, __pyx_L1_error) + __pyx_v_mslice = __pyx_t_1; + + /* "View.MemoryView":634 + * cdef __Pyx_memviewslice tmp + * mslice = get_slice_from_memview(self, &tmp) + * return slice_is_contig(mslice[0], 'F', self.view.ndim) # <<<<<<<<<<<<<< + * + * def copy(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_memviewslice_is_contig((__pyx_v_mslice[0]), 'F', __pyx_v_self->view.ndim)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 634, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":630 + * return slice_is_contig(mslice[0], 'C', self.view.ndim) + * + * def is_f_contig(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice *mslice + * cdef __Pyx_memviewslice tmp + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.is_f_contig", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":636 + * return slice_is_contig(mslice[0], 'F', self.view.ndim) + * + * def copy(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice mslice + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_copy(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_copy(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("copy (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("copy", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "copy", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_20copy(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_20copy(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice __pyx_v_mslice; + int __pyx_v_flags; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("copy", 1); + + /* "View.MemoryView":638 + * def copy(self): + * cdef __Pyx_memviewslice mslice + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS # <<<<<<<<<<<<<< + * + * slice_copy(self, &mslice) + */ + __pyx_v_flags = (__pyx_v_self->flags & (~PyBUF_F_CONTIGUOUS)); + + /* "View.MemoryView":640 + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS + * + * slice_copy(self, &mslice) # <<<<<<<<<<<<<< + * mslice = slice_copy_contig(&mslice, "c", self.view.ndim, + * self.view.itemsize, + */ + __pyx_memoryview_slice_copy(__pyx_v_self, (&__pyx_v_mslice)); + + /* "View.MemoryView":641 + * + * slice_copy(self, &mslice) + * mslice = slice_copy_contig(&mslice, "c", self.view.ndim, # <<<<<<<<<<<<<< + * self.view.itemsize, + * flags|PyBUF_C_CONTIGUOUS, + */ + __pyx_t_1 = __pyx_memoryview_copy_new_contig((&__pyx_v_mslice), ((char *)"c"), __pyx_v_self->view.ndim, __pyx_v_self->view.itemsize, (__pyx_v_flags | PyBUF_C_CONTIGUOUS), __pyx_v_self->dtype_is_object); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 641, __pyx_L1_error) + __pyx_v_mslice = __pyx_t_1; + + /* "View.MemoryView":646 + * self.dtype_is_object) + * + * return memoryview_copy_from_slice(self, &mslice) # <<<<<<<<<<<<<< + * + * def copy_fortran(self): + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_memoryview_copy_object_from_slice(__pyx_v_self, (&__pyx_v_mslice)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 646, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":636 + * return slice_is_contig(mslice[0], 'F', self.view.ndim) + * + * def copy(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice mslice + * cdef int flags = self.flags & ~PyBUF_F_CONTIGUOUS + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.copy", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":648 + * return memoryview_copy_from_slice(self, &mslice) + * + * def copy_fortran(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice src, dst + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS + */ + +/* Python wrapper */ +static PyObject *__pyx_memoryview_copy_fortran(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_memoryview_copy_fortran(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("copy_fortran (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("copy_fortran", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "copy_fortran", 0))) return NULL; + __pyx_r = __pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_22copy_fortran(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_memoryview___pyx_pf_15View_dot_MemoryView_10memoryview_22copy_fortran(struct __pyx_memoryview_obj *__pyx_v_self) { + __Pyx_memviewslice __pyx_v_src; + __Pyx_memviewslice __pyx_v_dst; + int __pyx_v_flags; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_memviewslice __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("copy_fortran", 1); + + /* "View.MemoryView":650 + * def copy_fortran(self): + * cdef __Pyx_memviewslice src, dst + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS # <<<<<<<<<<<<<< + * + * slice_copy(self, &src) + */ + __pyx_v_flags = (__pyx_v_self->flags & (~PyBUF_C_CONTIGUOUS)); + + /* "View.MemoryView":652 + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS + * + * slice_copy(self, &src) # <<<<<<<<<<<<<< + * dst = slice_copy_contig(&src, "fortran", self.view.ndim, + * self.view.itemsize, + */ + __pyx_memoryview_slice_copy(__pyx_v_self, (&__pyx_v_src)); + + /* "View.MemoryView":653 + * + * slice_copy(self, &src) + * dst = slice_copy_contig(&src, "fortran", self.view.ndim, # <<<<<<<<<<<<<< + * self.view.itemsize, + * flags|PyBUF_F_CONTIGUOUS, + */ + __pyx_t_1 = __pyx_memoryview_copy_new_contig((&__pyx_v_src), ((char *)"fortran"), __pyx_v_self->view.ndim, __pyx_v_self->view.itemsize, (__pyx_v_flags | PyBUF_F_CONTIGUOUS), __pyx_v_self->dtype_is_object); if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 653, __pyx_L1_error) + __pyx_v_dst = __pyx_t_1; + + /* "View.MemoryView":658 + * self.dtype_is_object) + * + * return memoryview_copy_from_slice(self, &dst) # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_memoryview_copy_object_from_slice(__pyx_v_self, (&__pyx_v_dst)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 658, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":648 + * return memoryview_copy_from_slice(self, &mslice) + * + * def copy_fortran(self): # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice src, dst + * cdef int flags = self.flags & ~PyBUF_C_CONTIGUOUS + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.memoryview.copy_fortran", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryview_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryview_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_memoryview___reduce_cython__(((struct __pyx_memoryview_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryview___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(0, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryview_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryview_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(0, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.memoryview.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_memoryview_2__setstate_cython__(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryview_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryview_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(0, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.memoryview.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":662 + * + * @cname('__pyx_memoryview_new') + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): # <<<<<<<<<<<<<< + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo + */ + +static PyObject *__pyx_memoryview_new(PyObject *__pyx_v_o, int __pyx_v_flags, int __pyx_v_dtype_is_object, __Pyx_TypeInfo *__pyx_v_typeinfo) { + struct __pyx_memoryview_obj *__pyx_v_result = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_cwrapper", 1); + + /* "View.MemoryView":663 + * @cname('__pyx_memoryview_new') + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): + * cdef memoryview result = memoryview(o, flags, dtype_is_object) # <<<<<<<<<<<<<< + * result.typeinfo = typeinfo + * return result + */ + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_flags); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_v_dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_v_o); + __Pyx_GIVEREF(__pyx_v_o); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_v_o)) __PYX_ERR(0, 663, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_1)) __PYX_ERR(0, 663, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_t_2)) __PYX_ERR(0, 663, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_2 = 0; + __pyx_t_2 = __Pyx_PyObject_Call(((PyObject *)__pyx_memoryview_type), __pyx_t_3, NULL); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 663, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_v_result = ((struct __pyx_memoryview_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":664 + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo # <<<<<<<<<<<<<< + * return result + * + */ + __pyx_v_result->typeinfo = __pyx_v_typeinfo; + + /* "View.MemoryView":665 + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo + * return result # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_check') + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = ((PyObject *)__pyx_v_result); + goto __pyx_L0; + + /* "View.MemoryView":662 + * + * @cname('__pyx_memoryview_new') + * cdef memoryview_cwrapper(object o, int flags, bint dtype_is_object, __Pyx_TypeInfo *typeinfo): # <<<<<<<<<<<<<< + * cdef memoryview result = memoryview(o, flags, dtype_is_object) + * result.typeinfo = typeinfo + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview_cwrapper", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":668 + * + * @cname('__pyx_memoryview_check') + * cdef inline bint memoryview_check(object o) noexcept: # <<<<<<<<<<<<<< + * return isinstance(o, memoryview) + * + */ + +static CYTHON_INLINE int __pyx_memoryview_check(PyObject *__pyx_v_o) { + int __pyx_r; + int __pyx_t_1; + + /* "View.MemoryView":669 + * @cname('__pyx_memoryview_check') + * cdef inline bint memoryview_check(object o) noexcept: + * return isinstance(o, memoryview) # <<<<<<<<<<<<<< + * + * cdef tuple _unellipsify(object index, int ndim): + */ + __pyx_t_1 = __Pyx_TypeCheck(__pyx_v_o, __pyx_memoryview_type); + __pyx_r = __pyx_t_1; + goto __pyx_L0; + + /* "View.MemoryView":668 + * + * @cname('__pyx_memoryview_check') + * cdef inline bint memoryview_check(object o) noexcept: # <<<<<<<<<<<<<< + * return isinstance(o, memoryview) + * + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":671 + * return isinstance(o, memoryview) + * + * cdef tuple _unellipsify(object index, int ndim): # <<<<<<<<<<<<<< + * """ + * Replace all ellipses with full slices and fill incomplete indices with + */ + +static PyObject *_unellipsify(PyObject *__pyx_v_index, int __pyx_v_ndim) { + Py_ssize_t __pyx_v_idx; + PyObject *__pyx_v_tup = NULL; + PyObject *__pyx_v_result = NULL; + int __pyx_v_have_slices; + int __pyx_v_seen_ellipsis; + PyObject *__pyx_v_item = NULL; + Py_ssize_t __pyx_v_nslices; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + Py_ssize_t __pyx_t_4; + Py_ssize_t __pyx_t_5; + Py_UCS4 __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("_unellipsify", 1); + + /* "View.MemoryView":677 + * """ + * cdef Py_ssize_t idx + * tup = index if isinstance(index, tuple) else (index,) # <<<<<<<<<<<<<< + * + * result = [slice(None)] * ndim + */ + __pyx_t_2 = PyTuple_Check(__pyx_v_index); + if (__pyx_t_2) { + __Pyx_INCREF(((PyObject*)__pyx_v_index)); + __pyx_t_1 = __pyx_v_index; + } else { + __pyx_t_3 = PyTuple_New(1); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 677, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(__pyx_v_index); + __Pyx_GIVEREF(__pyx_v_index); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_v_index)) __PYX_ERR(0, 677, __pyx_L1_error); + __pyx_t_1 = __pyx_t_3; + __pyx_t_3 = 0; + } + __pyx_v_tup = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":679 + * tup = index if isinstance(index, tuple) else (index,) + * + * result = [slice(None)] * ndim # <<<<<<<<<<<<<< + * have_slices = False + * seen_ellipsis = False + */ + __pyx_t_1 = PyList_New(1 * ((__pyx_v_ndim<0) ? 0:__pyx_v_ndim)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 679, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + { Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < __pyx_v_ndim; __pyx_temp++) { + __Pyx_INCREF(__pyx_slice__5); + __Pyx_GIVEREF(__pyx_slice__5); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, __pyx_temp, __pyx_slice__5)) __PYX_ERR(0, 679, __pyx_L1_error); + } + } + __pyx_v_result = ((PyObject*)__pyx_t_1); + __pyx_t_1 = 0; + + /* "View.MemoryView":680 + * + * result = [slice(None)] * ndim + * have_slices = False # <<<<<<<<<<<<<< + * seen_ellipsis = False + * idx = 0 + */ + __pyx_v_have_slices = 0; + + /* "View.MemoryView":681 + * result = [slice(None)] * ndim + * have_slices = False + * seen_ellipsis = False # <<<<<<<<<<<<<< + * idx = 0 + * for item in tup: + */ + __pyx_v_seen_ellipsis = 0; + + /* "View.MemoryView":682 + * have_slices = False + * seen_ellipsis = False + * idx = 0 # <<<<<<<<<<<<<< + * for item in tup: + * if item is Ellipsis: + */ + __pyx_v_idx = 0; + + /* "View.MemoryView":683 + * seen_ellipsis = False + * idx = 0 + * for item in tup: # <<<<<<<<<<<<<< + * if item is Ellipsis: + * if not seen_ellipsis: + */ + if (unlikely(__pyx_v_tup == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not iterable"); + __PYX_ERR(0, 683, __pyx_L1_error) + } + __pyx_t_1 = __pyx_v_tup; __Pyx_INCREF(__pyx_t_1); + __pyx_t_4 = 0; + for (;;) { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_1); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 683, __pyx_L1_error) + #endif + if (__pyx_t_4 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_3 = PyTuple_GET_ITEM(__pyx_t_1, __pyx_t_4); __Pyx_INCREF(__pyx_t_3); __pyx_t_4++; if (unlikely((0 < 0))) __PYX_ERR(0, 683, __pyx_L1_error) + #else + __pyx_t_3 = __Pyx_PySequence_ITEM(__pyx_t_1, __pyx_t_4); __pyx_t_4++; if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 683, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + #endif + __Pyx_XDECREF_SET(__pyx_v_item, __pyx_t_3); + __pyx_t_3 = 0; + + /* "View.MemoryView":684 + * idx = 0 + * for item in tup: + * if item is Ellipsis: # <<<<<<<<<<<<<< + * if not seen_ellipsis: + * idx += ndim - len(tup) + */ + __pyx_t_2 = (__pyx_v_item == __pyx_builtin_Ellipsis); + if (__pyx_t_2) { + + /* "View.MemoryView":685 + * for item in tup: + * if item is Ellipsis: + * if not seen_ellipsis: # <<<<<<<<<<<<<< + * idx += ndim - len(tup) + * seen_ellipsis = True + */ + __pyx_t_2 = (!__pyx_v_seen_ellipsis); + if (__pyx_t_2) { + + /* "View.MemoryView":686 + * if item is Ellipsis: + * if not seen_ellipsis: + * idx += ndim - len(tup) # <<<<<<<<<<<<<< + * seen_ellipsis = True + * have_slices = True + */ + if (unlikely(__pyx_v_tup == Py_None)) { + PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); + __PYX_ERR(0, 686, __pyx_L1_error) + } + __pyx_t_5 = __Pyx_PyTuple_GET_SIZE(__pyx_v_tup); if (unlikely(__pyx_t_5 == ((Py_ssize_t)-1))) __PYX_ERR(0, 686, __pyx_L1_error) + __pyx_v_idx = (__pyx_v_idx + (__pyx_v_ndim - __pyx_t_5)); + + /* "View.MemoryView":687 + * if not seen_ellipsis: + * idx += ndim - len(tup) + * seen_ellipsis = True # <<<<<<<<<<<<<< + * have_slices = True + * else: + */ + __pyx_v_seen_ellipsis = 1; + + /* "View.MemoryView":685 + * for item in tup: + * if item is Ellipsis: + * if not seen_ellipsis: # <<<<<<<<<<<<<< + * idx += ndim - len(tup) + * seen_ellipsis = True + */ + } + + /* "View.MemoryView":688 + * idx += ndim - len(tup) + * seen_ellipsis = True + * have_slices = True # <<<<<<<<<<<<<< + * else: + * if isinstance(item, slice): + */ + __pyx_v_have_slices = 1; + + /* "View.MemoryView":684 + * idx = 0 + * for item in tup: + * if item is Ellipsis: # <<<<<<<<<<<<<< + * if not seen_ellipsis: + * idx += ndim - len(tup) + */ + goto __pyx_L5; + } + + /* "View.MemoryView":690 + * have_slices = True + * else: + * if isinstance(item, slice): # <<<<<<<<<<<<<< + * have_slices = True + * elif not PyIndex_Check(item): + */ + /*else*/ { + __pyx_t_2 = PySlice_Check(__pyx_v_item); + if (__pyx_t_2) { + + /* "View.MemoryView":691 + * else: + * if isinstance(item, slice): + * have_slices = True # <<<<<<<<<<<<<< + * elif not PyIndex_Check(item): + * raise TypeError, f"Cannot index with type '{type(item)}'" + */ + __pyx_v_have_slices = 1; + + /* "View.MemoryView":690 + * have_slices = True + * else: + * if isinstance(item, slice): # <<<<<<<<<<<<<< + * have_slices = True + * elif not PyIndex_Check(item): + */ + goto __pyx_L7; + } + + /* "View.MemoryView":692 + * if isinstance(item, slice): + * have_slices = True + * elif not PyIndex_Check(item): # <<<<<<<<<<<<<< + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item + */ + __pyx_t_2 = (!(PyIndex_Check(__pyx_v_item) != 0)); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":693 + * have_slices = True + * elif not PyIndex_Check(item): + * raise TypeError, f"Cannot index with type '{type(item)}'" # <<<<<<<<<<<<<< + * result[idx] = item + * idx += 1 + */ + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 693, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_5 = 0; + __pyx_t_6 = 127; + __Pyx_INCREF(__pyx_kp_u_Cannot_index_with_type); + __pyx_t_5 += 24; + __Pyx_GIVEREF(__pyx_kp_u_Cannot_index_with_type); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_kp_u_Cannot_index_with_type); + __pyx_t_7 = __Pyx_PyObject_FormatSimple(((PyObject *)Py_TYPE(__pyx_v_item)), __pyx_empty_unicode); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 693, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_6 = (__Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_7) > __pyx_t_6) ? __Pyx_PyUnicode_MAX_CHAR_VALUE(__pyx_t_7) : __pyx_t_6; + __pyx_t_5 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_7); + __pyx_t_7 = 0; + __Pyx_INCREF(__pyx_kp_u__6); + __pyx_t_5 += 1; + __Pyx_GIVEREF(__pyx_kp_u__6); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_kp_u__6); + __pyx_t_7 = __Pyx_PyUnicode_Join(__pyx_t_3, 3, __pyx_t_5, __pyx_t_6); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 693, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_t_7, 0, 0); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __PYX_ERR(0, 693, __pyx_L1_error) + + /* "View.MemoryView":692 + * if isinstance(item, slice): + * have_slices = True + * elif not PyIndex_Check(item): # <<<<<<<<<<<<<< + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item + */ + } + __pyx_L7:; + + /* "View.MemoryView":694 + * elif not PyIndex_Check(item): + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item # <<<<<<<<<<<<<< + * idx += 1 + * + */ + if (unlikely((__Pyx_SetItemInt(__pyx_v_result, __pyx_v_idx, __pyx_v_item, Py_ssize_t, 1, PyInt_FromSsize_t, 1, 1, 1) < 0))) __PYX_ERR(0, 694, __pyx_L1_error) + } + __pyx_L5:; + + /* "View.MemoryView":695 + * raise TypeError, f"Cannot index with type '{type(item)}'" + * result[idx] = item + * idx += 1 # <<<<<<<<<<<<<< + * + * nslices = ndim - idx + */ + __pyx_v_idx = (__pyx_v_idx + 1); + + /* "View.MemoryView":683 + * seen_ellipsis = False + * idx = 0 + * for item in tup: # <<<<<<<<<<<<<< + * if item is Ellipsis: + * if not seen_ellipsis: + */ + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "View.MemoryView":697 + * idx += 1 + * + * nslices = ndim - idx # <<<<<<<<<<<<<< + * return have_slices or nslices, tuple(result) + * + */ + __pyx_v_nslices = (__pyx_v_ndim - __pyx_v_idx); + + /* "View.MemoryView":698 + * + * nslices = ndim - idx + * return have_slices or nslices, tuple(result) # <<<<<<<<<<<<<< + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + */ + __Pyx_XDECREF(__pyx_r); + if (!__pyx_v_have_slices) { + } else { + __pyx_t_7 = __Pyx_PyBool_FromLong(__pyx_v_have_slices); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_1 = __pyx_t_7; + __pyx_t_7 = 0; + goto __pyx_L9_bool_binop_done; + } + __pyx_t_7 = PyInt_FromSsize_t(__pyx_v_nslices); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_1 = __pyx_t_7; + __pyx_t_7 = 0; + __pyx_L9_bool_binop_done:; + __pyx_t_7 = PyList_AsTuple(__pyx_v_result); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_3 = PyTuple_New(2); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 698, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_t_1)) __PYX_ERR(0, 698, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_7); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_7)) __PYX_ERR(0, 698, __pyx_L1_error); + __pyx_t_1 = 0; + __pyx_t_7 = 0; + __pyx_r = ((PyObject*)__pyx_t_3); + __pyx_t_3 = 0; + goto __pyx_L0; + + /* "View.MemoryView":671 + * return isinstance(o, memoryview) + * + * cdef tuple _unellipsify(object index, int ndim): # <<<<<<<<<<<<<< + * """ + * Replace all ellipses with full slices and fill incomplete indices with + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("View.MemoryView._unellipsify", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v_tup); + __Pyx_XDECREF(__pyx_v_result); + __Pyx_XDECREF(__pyx_v_item); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":700 + * return have_slices or nslices, tuple(result) + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: # <<<<<<<<<<<<<< + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: + */ + +static int assert_direct_dimensions(Py_ssize_t *__pyx_v_suboffsets, int __pyx_v_ndim) { + Py_ssize_t __pyx_v_suboffset; + int __pyx_r; + Py_ssize_t *__pyx_t_1; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + int __pyx_t_4; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + + /* "View.MemoryView":701 + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + * for suboffset in suboffsets[:ndim]: # <<<<<<<<<<<<<< + * if suboffset >= 0: + * raise ValueError, "Indirect dimensions not supported" + */ + __pyx_t_2 = (__pyx_v_suboffsets + __pyx_v_ndim); + for (__pyx_t_3 = __pyx_v_suboffsets; __pyx_t_3 < __pyx_t_2; __pyx_t_3++) { + __pyx_t_1 = __pyx_t_3; + __pyx_v_suboffset = (__pyx_t_1[0]); + + /* "View.MemoryView":702 + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * raise ValueError, "Indirect dimensions not supported" + * return 0 # return type just used as an error flag + */ + __pyx_t_4 = (__pyx_v_suboffset >= 0); + if (unlikely(__pyx_t_4)) { + + /* "View.MemoryView":703 + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: + * raise ValueError, "Indirect dimensions not supported" # <<<<<<<<<<<<<< + * return 0 # return type just used as an error flag + * + */ + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_kp_s_Indirect_dimensions_not_supporte, 0, 0); + __PYX_ERR(0, 703, __pyx_L1_error) + + /* "View.MemoryView":702 + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * raise ValueError, "Indirect dimensions not supported" + * return 0 # return type just used as an error flag + */ + } + } + + /* "View.MemoryView":704 + * if suboffset >= 0: + * raise ValueError, "Indirect dimensions not supported" + * return 0 # return type just used as an error flag # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":700 + * return have_slices or nslices, tuple(result) + * + * cdef int assert_direct_dimensions(Py_ssize_t *suboffsets, int ndim) except -1: # <<<<<<<<<<<<<< + * for suboffset in suboffsets[:ndim]: + * if suboffset >= 0: + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView.assert_direct_dimensions", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":711 + * + * @cname('__pyx_memview_slice') + * cdef memoryview memview_slice(memoryview memview, object indices): # <<<<<<<<<<<<<< + * cdef int new_ndim = 0, suboffset_dim = -1, dim + * cdef bint negative_step + */ + +static struct __pyx_memoryview_obj *__pyx_memview_slice(struct __pyx_memoryview_obj *__pyx_v_memview, PyObject *__pyx_v_indices) { + int __pyx_v_new_ndim; + int __pyx_v_suboffset_dim; + int __pyx_v_dim; + __Pyx_memviewslice __pyx_v_src; + __Pyx_memviewslice __pyx_v_dst; + __Pyx_memviewslice *__pyx_v_p_src; + struct __pyx_memoryviewslice_obj *__pyx_v_memviewsliceobj = 0; + __Pyx_memviewslice *__pyx_v_p_dst; + int *__pyx_v_p_suboffset_dim; + Py_ssize_t __pyx_v_start; + Py_ssize_t __pyx_v_stop; + Py_ssize_t __pyx_v_step; + Py_ssize_t __pyx_v_cindex; + int __pyx_v_have_start; + int __pyx_v_have_stop; + int __pyx_v_have_step; + PyObject *__pyx_v_index = NULL; + struct __pyx_memoryview_obj *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + struct __pyx_memoryview_obj *__pyx_t_3; + char *__pyx_t_4; + int __pyx_t_5; + Py_ssize_t __pyx_t_6; + PyObject *(*__pyx_t_7)(PyObject *); + PyObject *__pyx_t_8 = NULL; + Py_ssize_t __pyx_t_9; + int __pyx_t_10; + Py_ssize_t __pyx_t_11; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memview_slice", 1); + + /* "View.MemoryView":712 + * @cname('__pyx_memview_slice') + * cdef memoryview memview_slice(memoryview memview, object indices): + * cdef int new_ndim = 0, suboffset_dim = -1, dim # <<<<<<<<<<<<<< + * cdef bint negative_step + * cdef __Pyx_memviewslice src, dst + */ + __pyx_v_new_ndim = 0; + __pyx_v_suboffset_dim = -1; + + /* "View.MemoryView":719 + * + * + * memset(&dst, 0, sizeof(dst)) # <<<<<<<<<<<<<< + * + * cdef _memoryviewslice memviewsliceobj + */ + (void)(memset((&__pyx_v_dst), 0, (sizeof(__pyx_v_dst)))); + + /* "View.MemoryView":723 + * cdef _memoryviewslice memviewsliceobj + * + * assert memview.view.ndim > 0 # <<<<<<<<<<<<<< + * + * if isinstance(memview, _memoryviewslice): + */ + #ifndef CYTHON_WITHOUT_ASSERTIONS + if (unlikely(__pyx_assertions_enabled())) { + __pyx_t_1 = (__pyx_v_memview->view.ndim > 0); + if (unlikely(!__pyx_t_1)) { + __Pyx_Raise(__pyx_builtin_AssertionError, 0, 0, 0); + __PYX_ERR(0, 723, __pyx_L1_error) + } + } + #else + if ((1)); else __PYX_ERR(0, 723, __pyx_L1_error) + #endif + + /* "View.MemoryView":725 + * assert memview.view.ndim > 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * memviewsliceobj = memview + * p_src = &memviewsliceobj.from_slice + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":726 + * + * if isinstance(memview, _memoryviewslice): + * memviewsliceobj = memview # <<<<<<<<<<<<<< + * p_src = &memviewsliceobj.from_slice + * else: + */ + if (!(likely(((((PyObject *)__pyx_v_memview)) == Py_None) || likely(__Pyx_TypeTest(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type))))) __PYX_ERR(0, 726, __pyx_L1_error) + __pyx_t_2 = ((PyObject *)__pyx_v_memview); + __Pyx_INCREF(__pyx_t_2); + __pyx_v_memviewsliceobj = ((struct __pyx_memoryviewslice_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":727 + * if isinstance(memview, _memoryviewslice): + * memviewsliceobj = memview + * p_src = &memviewsliceobj.from_slice # <<<<<<<<<<<<<< + * else: + * slice_copy(memview, &src) + */ + __pyx_v_p_src = (&__pyx_v_memviewsliceobj->from_slice); + + /* "View.MemoryView":725 + * assert memview.view.ndim > 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * memviewsliceobj = memview + * p_src = &memviewsliceobj.from_slice + */ + goto __pyx_L3; + } + + /* "View.MemoryView":729 + * p_src = &memviewsliceobj.from_slice + * else: + * slice_copy(memview, &src) # <<<<<<<<<<<<<< + * p_src = &src + * + */ + /*else*/ { + __pyx_memoryview_slice_copy(__pyx_v_memview, (&__pyx_v_src)); + + /* "View.MemoryView":730 + * else: + * slice_copy(memview, &src) + * p_src = &src # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_p_src = (&__pyx_v_src); + } + __pyx_L3:; + + /* "View.MemoryView":736 + * + * + * dst.memview = p_src.memview # <<<<<<<<<<<<<< + * dst.data = p_src.data + * + */ + __pyx_t_3 = __pyx_v_p_src->memview; + __pyx_v_dst.memview = __pyx_t_3; + + /* "View.MemoryView":737 + * + * dst.memview = p_src.memview + * dst.data = p_src.data # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_4 = __pyx_v_p_src->data; + __pyx_v_dst.data = __pyx_t_4; + + /* "View.MemoryView":742 + * + * + * cdef __Pyx_memviewslice *p_dst = &dst # <<<<<<<<<<<<<< + * cdef int *p_suboffset_dim = &suboffset_dim + * cdef Py_ssize_t start, stop, step, cindex + */ + __pyx_v_p_dst = (&__pyx_v_dst); + + /* "View.MemoryView":743 + * + * cdef __Pyx_memviewslice *p_dst = &dst + * cdef int *p_suboffset_dim = &suboffset_dim # <<<<<<<<<<<<<< + * cdef Py_ssize_t start, stop, step, cindex + * cdef bint have_start, have_stop, have_step + */ + __pyx_v_p_suboffset_dim = (&__pyx_v_suboffset_dim); + + /* "View.MemoryView":747 + * cdef bint have_start, have_stop, have_step + * + * for dim, index in enumerate(indices): # <<<<<<<<<<<<<< + * if PyIndex_Check(index): + * cindex = index + */ + __pyx_t_5 = 0; + if (likely(PyList_CheckExact(__pyx_v_indices)) || PyTuple_CheckExact(__pyx_v_indices)) { + __pyx_t_2 = __pyx_v_indices; __Pyx_INCREF(__pyx_t_2); + __pyx_t_6 = 0; + __pyx_t_7 = NULL; + } else { + __pyx_t_6 = -1; __pyx_t_2 = PyObject_GetIter(__pyx_v_indices); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 747, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_7 = __Pyx_PyObject_GetIterNextFunc(__pyx_t_2); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 747, __pyx_L1_error) + } + for (;;) { + if (likely(!__pyx_t_7)) { + if (likely(PyList_CheckExact(__pyx_t_2))) { + { + Py_ssize_t __pyx_temp = __Pyx_PyList_GET_SIZE(__pyx_t_2); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 747, __pyx_L1_error) + #endif + if (__pyx_t_6 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_8 = PyList_GET_ITEM(__pyx_t_2, __pyx_t_6); __Pyx_INCREF(__pyx_t_8); __pyx_t_6++; if (unlikely((0 < 0))) __PYX_ERR(0, 747, __pyx_L1_error) + #else + __pyx_t_8 = __Pyx_PySequence_ITEM(__pyx_t_2, __pyx_t_6); __pyx_t_6++; if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 747, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + #endif + } else { + { + Py_ssize_t __pyx_temp = __Pyx_PyTuple_GET_SIZE(__pyx_t_2); + #if !CYTHON_ASSUME_SAFE_MACROS + if (unlikely((__pyx_temp < 0))) __PYX_ERR(0, 747, __pyx_L1_error) + #endif + if (__pyx_t_6 >= __pyx_temp) break; + } + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + __pyx_t_8 = PyTuple_GET_ITEM(__pyx_t_2, __pyx_t_6); __Pyx_INCREF(__pyx_t_8); __pyx_t_6++; if (unlikely((0 < 0))) __PYX_ERR(0, 747, __pyx_L1_error) + #else + __pyx_t_8 = __Pyx_PySequence_ITEM(__pyx_t_2, __pyx_t_6); __pyx_t_6++; if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 747, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + #endif + } + } else { + __pyx_t_8 = __pyx_t_7(__pyx_t_2); + if (unlikely(!__pyx_t_8)) { + PyObject* exc_type = PyErr_Occurred(); + if (exc_type) { + if (likely(__Pyx_PyErr_GivenExceptionMatches(exc_type, PyExc_StopIteration))) PyErr_Clear(); + else __PYX_ERR(0, 747, __pyx_L1_error) + } + break; + } + __Pyx_GOTREF(__pyx_t_8); + } + __Pyx_XDECREF_SET(__pyx_v_index, __pyx_t_8); + __pyx_t_8 = 0; + __pyx_v_dim = __pyx_t_5; + __pyx_t_5 = (__pyx_t_5 + 1); + + /* "View.MemoryView":748 + * + * for dim, index in enumerate(indices): + * if PyIndex_Check(index): # <<<<<<<<<<<<<< + * cindex = index + * slice_memviewslice( + */ + __pyx_t_1 = (PyIndex_Check(__pyx_v_index) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":749 + * for dim, index in enumerate(indices): + * if PyIndex_Check(index): + * cindex = index # <<<<<<<<<<<<<< + * slice_memviewslice( + * p_dst, p_src.shape[dim], p_src.strides[dim], p_src.suboffsets[dim], + */ + __pyx_t_9 = __Pyx_PyIndex_AsSsize_t(__pyx_v_index); if (unlikely((__pyx_t_9 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 749, __pyx_L1_error) + __pyx_v_cindex = __pyx_t_9; + + /* "View.MemoryView":750 + * if PyIndex_Check(index): + * cindex = index + * slice_memviewslice( # <<<<<<<<<<<<<< + * p_dst, p_src.shape[dim], p_src.strides[dim], p_src.suboffsets[dim], + * dim, new_ndim, p_suboffset_dim, + */ + __pyx_t_10 = __pyx_memoryview_slice_memviewslice(__pyx_v_p_dst, (__pyx_v_p_src->shape[__pyx_v_dim]), (__pyx_v_p_src->strides[__pyx_v_dim]), (__pyx_v_p_src->suboffsets[__pyx_v_dim]), __pyx_v_dim, __pyx_v_new_ndim, __pyx_v_p_suboffset_dim, __pyx_v_cindex, 0, 0, 0, 0, 0, 0); if (unlikely(__pyx_t_10 == ((int)-1))) __PYX_ERR(0, 750, __pyx_L1_error) + + /* "View.MemoryView":748 + * + * for dim, index in enumerate(indices): + * if PyIndex_Check(index): # <<<<<<<<<<<<<< + * cindex = index + * slice_memviewslice( + */ + goto __pyx_L6; + } + + /* "View.MemoryView":756 + * 0, 0, 0, # have_{start,stop,step} + * False) + * elif index is None: # <<<<<<<<<<<<<< + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 + */ + __pyx_t_1 = (__pyx_v_index == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":757 + * False) + * elif index is None: + * p_dst.shape[new_ndim] = 1 # <<<<<<<<<<<<<< + * p_dst.strides[new_ndim] = 0 + * p_dst.suboffsets[new_ndim] = -1 + */ + (__pyx_v_p_dst->shape[__pyx_v_new_ndim]) = 1; + + /* "View.MemoryView":758 + * elif index is None: + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 # <<<<<<<<<<<<<< + * p_dst.suboffsets[new_ndim] = -1 + * new_ndim += 1 + */ + (__pyx_v_p_dst->strides[__pyx_v_new_ndim]) = 0; + + /* "View.MemoryView":759 + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 + * p_dst.suboffsets[new_ndim] = -1 # <<<<<<<<<<<<<< + * new_ndim += 1 + * else: + */ + (__pyx_v_p_dst->suboffsets[__pyx_v_new_ndim]) = -1L; + + /* "View.MemoryView":760 + * p_dst.strides[new_ndim] = 0 + * p_dst.suboffsets[new_ndim] = -1 + * new_ndim += 1 # <<<<<<<<<<<<<< + * else: + * start = index.start or 0 + */ + __pyx_v_new_ndim = (__pyx_v_new_ndim + 1); + + /* "View.MemoryView":756 + * 0, 0, 0, # have_{start,stop,step} + * False) + * elif index is None: # <<<<<<<<<<<<<< + * p_dst.shape[new_ndim] = 1 + * p_dst.strides[new_ndim] = 0 + */ + goto __pyx_L6; + } + + /* "View.MemoryView":762 + * new_ndim += 1 + * else: + * start = index.start or 0 # <<<<<<<<<<<<<< + * stop = index.stop or 0 + * step = index.step or 0 + */ + /*else*/ { + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_start); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 762, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_t_8); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(0, 762, __pyx_L1_error) + if (!__pyx_t_1) { + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } else { + __pyx_t_11 = __Pyx_PyIndex_AsSsize_t(__pyx_t_8); if (unlikely((__pyx_t_11 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 762, __pyx_L1_error) + __pyx_t_9 = __pyx_t_11; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L7_bool_binop_done; + } + __pyx_t_9 = 0; + __pyx_L7_bool_binop_done:; + __pyx_v_start = __pyx_t_9; + + /* "View.MemoryView":763 + * else: + * start = index.start or 0 + * stop = index.stop or 0 # <<<<<<<<<<<<<< + * step = index.step or 0 + * + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_stop); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 763, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_t_8); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(0, 763, __pyx_L1_error) + if (!__pyx_t_1) { + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } else { + __pyx_t_11 = __Pyx_PyIndex_AsSsize_t(__pyx_t_8); if (unlikely((__pyx_t_11 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 763, __pyx_L1_error) + __pyx_t_9 = __pyx_t_11; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L9_bool_binop_done; + } + __pyx_t_9 = 0; + __pyx_L9_bool_binop_done:; + __pyx_v_stop = __pyx_t_9; + + /* "View.MemoryView":764 + * start = index.start or 0 + * stop = index.stop or 0 + * step = index.step or 0 # <<<<<<<<<<<<<< + * + * have_start = index.start is not None + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_step); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 764, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = __Pyx_PyObject_IsTrue(__pyx_t_8); if (unlikely((__pyx_t_1 < 0))) __PYX_ERR(0, 764, __pyx_L1_error) + if (!__pyx_t_1) { + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + } else { + __pyx_t_11 = __Pyx_PyIndex_AsSsize_t(__pyx_t_8); if (unlikely((__pyx_t_11 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 764, __pyx_L1_error) + __pyx_t_9 = __pyx_t_11; + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + goto __pyx_L11_bool_binop_done; + } + __pyx_t_9 = 0; + __pyx_L11_bool_binop_done:; + __pyx_v_step = __pyx_t_9; + + /* "View.MemoryView":766 + * step = index.step or 0 + * + * have_start = index.start is not None # <<<<<<<<<<<<<< + * have_stop = index.stop is not None + * have_step = index.step is not None + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_start); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 766, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = (__pyx_t_8 != Py_None); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_v_have_start = __pyx_t_1; + + /* "View.MemoryView":767 + * + * have_start = index.start is not None + * have_stop = index.stop is not None # <<<<<<<<<<<<<< + * have_step = index.step is not None + * + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_stop); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 767, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = (__pyx_t_8 != Py_None); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_v_have_stop = __pyx_t_1; + + /* "View.MemoryView":768 + * have_start = index.start is not None + * have_stop = index.stop is not None + * have_step = index.step is not None # <<<<<<<<<<<<<< + * + * slice_memviewslice( + */ + __pyx_t_8 = __Pyx_PyObject_GetAttrStr(__pyx_v_index, __pyx_n_s_step); if (unlikely(!__pyx_t_8)) __PYX_ERR(0, 768, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_8); + __pyx_t_1 = (__pyx_t_8 != Py_None); + __Pyx_DECREF(__pyx_t_8); __pyx_t_8 = 0; + __pyx_v_have_step = __pyx_t_1; + + /* "View.MemoryView":770 + * have_step = index.step is not None + * + * slice_memviewslice( # <<<<<<<<<<<<<< + * p_dst, p_src.shape[dim], p_src.strides[dim], p_src.suboffsets[dim], + * dim, new_ndim, p_suboffset_dim, + */ + __pyx_t_10 = __pyx_memoryview_slice_memviewslice(__pyx_v_p_dst, (__pyx_v_p_src->shape[__pyx_v_dim]), (__pyx_v_p_src->strides[__pyx_v_dim]), (__pyx_v_p_src->suboffsets[__pyx_v_dim]), __pyx_v_dim, __pyx_v_new_ndim, __pyx_v_p_suboffset_dim, __pyx_v_start, __pyx_v_stop, __pyx_v_step, __pyx_v_have_start, __pyx_v_have_stop, __pyx_v_have_step, 1); if (unlikely(__pyx_t_10 == ((int)-1))) __PYX_ERR(0, 770, __pyx_L1_error) + + /* "View.MemoryView":776 + * have_start, have_stop, have_step, + * True) + * new_ndim += 1 # <<<<<<<<<<<<<< + * + * if isinstance(memview, _memoryviewslice): + */ + __pyx_v_new_ndim = (__pyx_v_new_ndim + 1); + } + __pyx_L6:; + + /* "View.MemoryView":747 + * cdef bint have_start, have_stop, have_step + * + * for dim, index in enumerate(indices): # <<<<<<<<<<<<<< + * if PyIndex_Check(index): + * cindex = index + */ + } + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + + /* "View.MemoryView":778 + * new_ndim += 1 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":779 + * + * if isinstance(memview, _memoryviewslice): + * return memoryview_fromslice(dst, new_ndim, # <<<<<<<<<<<<<< + * memviewsliceobj.to_object_func, + * memviewsliceobj.to_dtype_func, + */ + __Pyx_XDECREF((PyObject *)__pyx_r); + + /* "View.MemoryView":780 + * if isinstance(memview, _memoryviewslice): + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, # <<<<<<<<<<<<<< + * memviewsliceobj.to_dtype_func, + * memview.dtype_is_object) + */ + if (unlikely(!__pyx_v_memviewsliceobj)) { __Pyx_RaiseUnboundLocalError("memviewsliceobj"); __PYX_ERR(0, 780, __pyx_L1_error) } + + /* "View.MemoryView":781 + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, + * memviewsliceobj.to_dtype_func, # <<<<<<<<<<<<<< + * memview.dtype_is_object) + * else: + */ + if (unlikely(!__pyx_v_memviewsliceobj)) { __Pyx_RaiseUnboundLocalError("memviewsliceobj"); __PYX_ERR(0, 781, __pyx_L1_error) } + + /* "View.MemoryView":779 + * + * if isinstance(memview, _memoryviewslice): + * return memoryview_fromslice(dst, new_ndim, # <<<<<<<<<<<<<< + * memviewsliceobj.to_object_func, + * memviewsliceobj.to_dtype_func, + */ + __pyx_t_2 = __pyx_memoryview_fromslice(__pyx_v_dst, __pyx_v_new_ndim, __pyx_v_memviewsliceobj->to_object_func, __pyx_v_memviewsliceobj->to_dtype_func, __pyx_v_memview->dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 779, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + if (!(likely(((__pyx_t_2) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_2, __pyx_memoryview_type))))) __PYX_ERR(0, 779, __pyx_L1_error) + __pyx_r = ((struct __pyx_memoryview_obj *)__pyx_t_2); + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":778 + * new_ndim += 1 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * return memoryview_fromslice(dst, new_ndim, + * memviewsliceobj.to_object_func, + */ + } + + /* "View.MemoryView":784 + * memview.dtype_is_object) + * else: + * return memoryview_fromslice(dst, new_ndim, NULL, NULL, # <<<<<<<<<<<<<< + * memview.dtype_is_object) + * + */ + /*else*/ { + __Pyx_XDECREF((PyObject *)__pyx_r); + + /* "View.MemoryView":785 + * else: + * return memoryview_fromslice(dst, new_ndim, NULL, NULL, + * memview.dtype_is_object) # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = __pyx_memoryview_fromslice(__pyx_v_dst, __pyx_v_new_ndim, NULL, NULL, __pyx_v_memview->dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 784, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + + /* "View.MemoryView":784 + * memview.dtype_is_object) + * else: + * return memoryview_fromslice(dst, new_ndim, NULL, NULL, # <<<<<<<<<<<<<< + * memview.dtype_is_object) + * + */ + if (!(likely(((__pyx_t_2) == Py_None) || likely(__Pyx_TypeTest(__pyx_t_2, __pyx_memoryview_type))))) __PYX_ERR(0, 784, __pyx_L1_error) + __pyx_r = ((struct __pyx_memoryview_obj *)__pyx_t_2); + __pyx_t_2 = 0; + goto __pyx_L0; + } + + /* "View.MemoryView":711 + * + * @cname('__pyx_memview_slice') + * cdef memoryview memview_slice(memoryview memview, object indices): # <<<<<<<<<<<<<< + * cdef int new_ndim = 0, suboffset_dim = -1, dim + * cdef bint negative_step + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_8); + __Pyx_AddTraceback("View.MemoryView.memview_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_memviewsliceobj); + __Pyx_XDECREF(__pyx_v_index); + __Pyx_XGIVEREF((PyObject *)__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":793 + * + * @cname('__pyx_memoryview_slice_memviewslice') + * cdef int slice_memviewslice( # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * Py_ssize_t shape, Py_ssize_t stride, Py_ssize_t suboffset, + */ + +static int __pyx_memoryview_slice_memviewslice(__Pyx_memviewslice *__pyx_v_dst, Py_ssize_t __pyx_v_shape, Py_ssize_t __pyx_v_stride, Py_ssize_t __pyx_v_suboffset, int __pyx_v_dim, int __pyx_v_new_ndim, int *__pyx_v_suboffset_dim, Py_ssize_t __pyx_v_start, Py_ssize_t __pyx_v_stop, Py_ssize_t __pyx_v_step, int __pyx_v_have_start, int __pyx_v_have_stop, int __pyx_v_have_step, int __pyx_v_is_slice) { + Py_ssize_t __pyx_v_new_shape; + int __pyx_v_negative_step; + int __pyx_r; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":813 + * cdef bint negative_step + * + * if not is_slice: # <<<<<<<<<<<<<< + * + * if start < 0: + */ + __pyx_t_1 = (!__pyx_v_is_slice); + if (__pyx_t_1) { + + /* "View.MemoryView":815 + * if not is_slice: + * + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if not 0 <= start < shape: + */ + __pyx_t_1 = (__pyx_v_start < 0); + if (__pyx_t_1) { + + /* "View.MemoryView":816 + * + * if start < 0: + * start += shape # <<<<<<<<<<<<<< + * if not 0 <= start < shape: + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) + */ + __pyx_v_start = (__pyx_v_start + __pyx_v_shape); + + /* "View.MemoryView":815 + * if not is_slice: + * + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if not 0 <= start < shape: + */ + } + + /* "View.MemoryView":817 + * if start < 0: + * start += shape + * if not 0 <= start < shape: # <<<<<<<<<<<<<< + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) + * else: + */ + __pyx_t_1 = (0 <= __pyx_v_start); + if (__pyx_t_1) { + __pyx_t_1 = (__pyx_v_start < __pyx_v_shape); + } + __pyx_t_2 = (!__pyx_t_1); + if (__pyx_t_2) { + + /* "View.MemoryView":818 + * start += shape + * if not 0 <= start < shape: + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) # <<<<<<<<<<<<<< + * else: + * + */ + __pyx_t_3 = __pyx_memoryview_err_dim(PyExc_IndexError, __pyx_kp_s_Index_out_of_bounds_axis_d, __pyx_v_dim); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(0, 818, __pyx_L1_error) + + /* "View.MemoryView":817 + * if start < 0: + * start += shape + * if not 0 <= start < shape: # <<<<<<<<<<<<<< + * _err_dim(PyExc_IndexError, "Index out of bounds (axis %d)", dim) + * else: + */ + } + + /* "View.MemoryView":813 + * cdef bint negative_step + * + * if not is_slice: # <<<<<<<<<<<<<< + * + * if start < 0: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":821 + * else: + * + * if have_step: # <<<<<<<<<<<<<< + * negative_step = step < 0 + * if step == 0: + */ + /*else*/ { + __pyx_t_2 = (__pyx_v_have_step != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":822 + * + * if have_step: + * negative_step = step < 0 # <<<<<<<<<<<<<< + * if step == 0: + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + */ + __pyx_v_negative_step = (__pyx_v_step < 0); + + /* "View.MemoryView":823 + * if have_step: + * negative_step = step < 0 + * if step == 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + * else: + */ + __pyx_t_2 = (__pyx_v_step == 0); + if (__pyx_t_2) { + + /* "View.MemoryView":824 + * negative_step = step < 0 + * if step == 0: + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) # <<<<<<<<<<<<<< + * else: + * negative_step = False + */ + __pyx_t_3 = __pyx_memoryview_err_dim(PyExc_ValueError, __pyx_kp_s_Step_may_not_be_zero_axis_d, __pyx_v_dim); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(0, 824, __pyx_L1_error) + + /* "View.MemoryView":823 + * if have_step: + * negative_step = step < 0 + * if step == 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + * else: + */ + } + + /* "View.MemoryView":821 + * else: + * + * if have_step: # <<<<<<<<<<<<<< + * negative_step = step < 0 + * if step == 0: + */ + goto __pyx_L6; + } + + /* "View.MemoryView":826 + * _err_dim(PyExc_ValueError, "Step may not be zero (axis %d)", dim) + * else: + * negative_step = False # <<<<<<<<<<<<<< + * step = 1 + * + */ + /*else*/ { + __pyx_v_negative_step = 0; + + /* "View.MemoryView":827 + * else: + * negative_step = False + * step = 1 # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_step = 1; + } + __pyx_L6:; + + /* "View.MemoryView":830 + * + * + * if have_start: # <<<<<<<<<<<<<< + * if start < 0: + * start += shape + */ + __pyx_t_2 = (__pyx_v_have_start != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":831 + * + * if have_start: + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if start < 0: + */ + __pyx_t_2 = (__pyx_v_start < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":832 + * if have_start: + * if start < 0: + * start += shape # <<<<<<<<<<<<<< + * if start < 0: + * start = 0 + */ + __pyx_v_start = (__pyx_v_start + __pyx_v_shape); + + /* "View.MemoryView":833 + * if start < 0: + * start += shape + * if start < 0: # <<<<<<<<<<<<<< + * start = 0 + * elif start >= shape: + */ + __pyx_t_2 = (__pyx_v_start < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":834 + * start += shape + * if start < 0: + * start = 0 # <<<<<<<<<<<<<< + * elif start >= shape: + * if negative_step: + */ + __pyx_v_start = 0; + + /* "View.MemoryView":833 + * if start < 0: + * start += shape + * if start < 0: # <<<<<<<<<<<<<< + * start = 0 + * elif start >= shape: + */ + } + + /* "View.MemoryView":831 + * + * if have_start: + * if start < 0: # <<<<<<<<<<<<<< + * start += shape + * if start < 0: + */ + goto __pyx_L9; + } + + /* "View.MemoryView":835 + * if start < 0: + * start = 0 + * elif start >= shape: # <<<<<<<<<<<<<< + * if negative_step: + * start = shape - 1 + */ + __pyx_t_2 = (__pyx_v_start >= __pyx_v_shape); + if (__pyx_t_2) { + + /* "View.MemoryView":836 + * start = 0 + * elif start >= shape: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + if (__pyx_v_negative_step) { + + /* "View.MemoryView":837 + * elif start >= shape: + * if negative_step: + * start = shape - 1 # <<<<<<<<<<<<<< + * else: + * start = shape + */ + __pyx_v_start = (__pyx_v_shape - 1); + + /* "View.MemoryView":836 + * start = 0 + * elif start >= shape: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + goto __pyx_L11; + } + + /* "View.MemoryView":839 + * start = shape - 1 + * else: + * start = shape # <<<<<<<<<<<<<< + * else: + * if negative_step: + */ + /*else*/ { + __pyx_v_start = __pyx_v_shape; + } + __pyx_L11:; + + /* "View.MemoryView":835 + * if start < 0: + * start = 0 + * elif start >= shape: # <<<<<<<<<<<<<< + * if negative_step: + * start = shape - 1 + */ + } + __pyx_L9:; + + /* "View.MemoryView":830 + * + * + * if have_start: # <<<<<<<<<<<<<< + * if start < 0: + * start += shape + */ + goto __pyx_L8; + } + + /* "View.MemoryView":841 + * start = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + /*else*/ { + if (__pyx_v_negative_step) { + + /* "View.MemoryView":842 + * else: + * if negative_step: + * start = shape - 1 # <<<<<<<<<<<<<< + * else: + * start = 0 + */ + __pyx_v_start = (__pyx_v_shape - 1); + + /* "View.MemoryView":841 + * start = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * start = shape - 1 + * else: + */ + goto __pyx_L12; + } + + /* "View.MemoryView":844 + * start = shape - 1 + * else: + * start = 0 # <<<<<<<<<<<<<< + * + * if have_stop: + */ + /*else*/ { + __pyx_v_start = 0; + } + __pyx_L12:; + } + __pyx_L8:; + + /* "View.MemoryView":846 + * start = 0 + * + * if have_stop: # <<<<<<<<<<<<<< + * if stop < 0: + * stop += shape + */ + __pyx_t_2 = (__pyx_v_have_stop != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":847 + * + * if have_stop: + * if stop < 0: # <<<<<<<<<<<<<< + * stop += shape + * if stop < 0: + */ + __pyx_t_2 = (__pyx_v_stop < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":848 + * if have_stop: + * if stop < 0: + * stop += shape # <<<<<<<<<<<<<< + * if stop < 0: + * stop = 0 + */ + __pyx_v_stop = (__pyx_v_stop + __pyx_v_shape); + + /* "View.MemoryView":849 + * if stop < 0: + * stop += shape + * if stop < 0: # <<<<<<<<<<<<<< + * stop = 0 + * elif stop > shape: + */ + __pyx_t_2 = (__pyx_v_stop < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":850 + * stop += shape + * if stop < 0: + * stop = 0 # <<<<<<<<<<<<<< + * elif stop > shape: + * stop = shape + */ + __pyx_v_stop = 0; + + /* "View.MemoryView":849 + * if stop < 0: + * stop += shape + * if stop < 0: # <<<<<<<<<<<<<< + * stop = 0 + * elif stop > shape: + */ + } + + /* "View.MemoryView":847 + * + * if have_stop: + * if stop < 0: # <<<<<<<<<<<<<< + * stop += shape + * if stop < 0: + */ + goto __pyx_L14; + } + + /* "View.MemoryView":851 + * if stop < 0: + * stop = 0 + * elif stop > shape: # <<<<<<<<<<<<<< + * stop = shape + * else: + */ + __pyx_t_2 = (__pyx_v_stop > __pyx_v_shape); + if (__pyx_t_2) { + + /* "View.MemoryView":852 + * stop = 0 + * elif stop > shape: + * stop = shape # <<<<<<<<<<<<<< + * else: + * if negative_step: + */ + __pyx_v_stop = __pyx_v_shape; + + /* "View.MemoryView":851 + * if stop < 0: + * stop = 0 + * elif stop > shape: # <<<<<<<<<<<<<< + * stop = shape + * else: + */ + } + __pyx_L14:; + + /* "View.MemoryView":846 + * start = 0 + * + * if have_stop: # <<<<<<<<<<<<<< + * if stop < 0: + * stop += shape + */ + goto __pyx_L13; + } + + /* "View.MemoryView":854 + * stop = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * stop = -1 + * else: + */ + /*else*/ { + if (__pyx_v_negative_step) { + + /* "View.MemoryView":855 + * else: + * if negative_step: + * stop = -1 # <<<<<<<<<<<<<< + * else: + * stop = shape + */ + __pyx_v_stop = -1L; + + /* "View.MemoryView":854 + * stop = shape + * else: + * if negative_step: # <<<<<<<<<<<<<< + * stop = -1 + * else: + */ + goto __pyx_L16; + } + + /* "View.MemoryView":857 + * stop = -1 + * else: + * stop = shape # <<<<<<<<<<<<<< + * + * + */ + /*else*/ { + __pyx_v_stop = __pyx_v_shape; + } + __pyx_L16:; + } + __pyx_L13:; + + /* "View.MemoryView":861 + * + * with cython.cdivision(True): + * new_shape = (stop - start) // step # <<<<<<<<<<<<<< + * + * if (stop - start) - step * new_shape: + */ + __pyx_v_new_shape = ((__pyx_v_stop - __pyx_v_start) / __pyx_v_step); + + /* "View.MemoryView":863 + * new_shape = (stop - start) // step + * + * if (stop - start) - step * new_shape: # <<<<<<<<<<<<<< + * new_shape += 1 + * + */ + __pyx_t_2 = (((__pyx_v_stop - __pyx_v_start) - (__pyx_v_step * __pyx_v_new_shape)) != 0); + if (__pyx_t_2) { + + /* "View.MemoryView":864 + * + * if (stop - start) - step * new_shape: + * new_shape += 1 # <<<<<<<<<<<<<< + * + * if new_shape < 0: + */ + __pyx_v_new_shape = (__pyx_v_new_shape + 1); + + /* "View.MemoryView":863 + * new_shape = (stop - start) // step + * + * if (stop - start) - step * new_shape: # <<<<<<<<<<<<<< + * new_shape += 1 + * + */ + } + + /* "View.MemoryView":866 + * new_shape += 1 + * + * if new_shape < 0: # <<<<<<<<<<<<<< + * new_shape = 0 + * + */ + __pyx_t_2 = (__pyx_v_new_shape < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":867 + * + * if new_shape < 0: + * new_shape = 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_new_shape = 0; + + /* "View.MemoryView":866 + * new_shape += 1 + * + * if new_shape < 0: # <<<<<<<<<<<<<< + * new_shape = 0 + * + */ + } + + /* "View.MemoryView":870 + * + * + * dst.strides[new_ndim] = stride * step # <<<<<<<<<<<<<< + * dst.shape[new_ndim] = new_shape + * dst.suboffsets[new_ndim] = suboffset + */ + (__pyx_v_dst->strides[__pyx_v_new_ndim]) = (__pyx_v_stride * __pyx_v_step); + + /* "View.MemoryView":871 + * + * dst.strides[new_ndim] = stride * step + * dst.shape[new_ndim] = new_shape # <<<<<<<<<<<<<< + * dst.suboffsets[new_ndim] = suboffset + * + */ + (__pyx_v_dst->shape[__pyx_v_new_ndim]) = __pyx_v_new_shape; + + /* "View.MemoryView":872 + * dst.strides[new_ndim] = stride * step + * dst.shape[new_ndim] = new_shape + * dst.suboffsets[new_ndim] = suboffset # <<<<<<<<<<<<<< + * + * + */ + (__pyx_v_dst->suboffsets[__pyx_v_new_ndim]) = __pyx_v_suboffset; + } + __pyx_L3:; + + /* "View.MemoryView":875 + * + * + * if suboffset_dim[0] < 0: # <<<<<<<<<<<<<< + * dst.data += start * stride + * else: + */ + __pyx_t_2 = ((__pyx_v_suboffset_dim[0]) < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":876 + * + * if suboffset_dim[0] < 0: + * dst.data += start * stride # <<<<<<<<<<<<<< + * else: + * dst.suboffsets[suboffset_dim[0]] += start * stride + */ + __pyx_v_dst->data = (__pyx_v_dst->data + (__pyx_v_start * __pyx_v_stride)); + + /* "View.MemoryView":875 + * + * + * if suboffset_dim[0] < 0: # <<<<<<<<<<<<<< + * dst.data += start * stride + * else: + */ + goto __pyx_L19; + } + + /* "View.MemoryView":878 + * dst.data += start * stride + * else: + * dst.suboffsets[suboffset_dim[0]] += start * stride # <<<<<<<<<<<<<< + * + * if suboffset >= 0: + */ + /*else*/ { + __pyx_t_3 = (__pyx_v_suboffset_dim[0]); + (__pyx_v_dst->suboffsets[__pyx_t_3]) = ((__pyx_v_dst->suboffsets[__pyx_t_3]) + (__pyx_v_start * __pyx_v_stride)); + } + __pyx_L19:; + + /* "View.MemoryView":880 + * dst.suboffsets[suboffset_dim[0]] += start * stride + * + * if suboffset >= 0: # <<<<<<<<<<<<<< + * if not is_slice: + * if new_ndim == 0: + */ + __pyx_t_2 = (__pyx_v_suboffset >= 0); + if (__pyx_t_2) { + + /* "View.MemoryView":881 + * + * if suboffset >= 0: + * if not is_slice: # <<<<<<<<<<<<<< + * if new_ndim == 0: + * dst.data = ( dst.data)[0] + suboffset + */ + __pyx_t_2 = (!__pyx_v_is_slice); + if (__pyx_t_2) { + + /* "View.MemoryView":882 + * if suboffset >= 0: + * if not is_slice: + * if new_ndim == 0: # <<<<<<<<<<<<<< + * dst.data = ( dst.data)[0] + suboffset + * else: + */ + __pyx_t_2 = (__pyx_v_new_ndim == 0); + if (__pyx_t_2) { + + /* "View.MemoryView":883 + * if not is_slice: + * if new_ndim == 0: + * dst.data = ( dst.data)[0] + suboffset # <<<<<<<<<<<<<< + * else: + * _err_dim(PyExc_IndexError, "All dimensions preceding dimension %d " + */ + __pyx_v_dst->data = ((((char **)__pyx_v_dst->data)[0]) + __pyx_v_suboffset); + + /* "View.MemoryView":882 + * if suboffset >= 0: + * if not is_slice: + * if new_ndim == 0: # <<<<<<<<<<<<<< + * dst.data = ( dst.data)[0] + suboffset + * else: + */ + goto __pyx_L22; + } + + /* "View.MemoryView":885 + * dst.data = ( dst.data)[0] + suboffset + * else: + * _err_dim(PyExc_IndexError, "All dimensions preceding dimension %d " # <<<<<<<<<<<<<< + * "must be indexed and not sliced", dim) + * else: + */ + /*else*/ { + + /* "View.MemoryView":886 + * else: + * _err_dim(PyExc_IndexError, "All dimensions preceding dimension %d " + * "must be indexed and not sliced", dim) # <<<<<<<<<<<<<< + * else: + * suboffset_dim[0] = new_ndim + */ + __pyx_t_3 = __pyx_memoryview_err_dim(PyExc_IndexError, __pyx_kp_s_All_dimensions_preceding_dimensi, __pyx_v_dim); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(0, 885, __pyx_L1_error) + } + __pyx_L22:; + + /* "View.MemoryView":881 + * + * if suboffset >= 0: + * if not is_slice: # <<<<<<<<<<<<<< + * if new_ndim == 0: + * dst.data = ( dst.data)[0] + suboffset + */ + goto __pyx_L21; + } + + /* "View.MemoryView":888 + * "must be indexed and not sliced", dim) + * else: + * suboffset_dim[0] = new_ndim # <<<<<<<<<<<<<< + * + * return 0 + */ + /*else*/ { + (__pyx_v_suboffset_dim[0]) = __pyx_v_new_ndim; + } + __pyx_L21:; + + /* "View.MemoryView":880 + * dst.suboffsets[suboffset_dim[0]] += start * stride + * + * if suboffset >= 0: # <<<<<<<<<<<<<< + * if not is_slice: + * if new_ndim == 0: + */ + } + + /* "View.MemoryView":890 + * suboffset_dim[0] = new_ndim + * + * return 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":793 + * + * @cname('__pyx_memoryview_slice_memviewslice') + * cdef int slice_memviewslice( # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * Py_ssize_t shape, Py_ssize_t stride, Py_ssize_t suboffset, + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.slice_memviewslice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":896 + * + * @cname('__pyx_pybuffer_index') + * cdef char *pybuffer_index(Py_buffer *view, char *bufp, Py_ssize_t index, # <<<<<<<<<<<<<< + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 + */ + +static char *__pyx_pybuffer_index(Py_buffer *__pyx_v_view, char *__pyx_v_bufp, Py_ssize_t __pyx_v_index, Py_ssize_t __pyx_v_dim) { + Py_ssize_t __pyx_v_shape; + Py_ssize_t __pyx_v_stride; + Py_ssize_t __pyx_v_suboffset; + Py_ssize_t __pyx_v_itemsize; + char *__pyx_v_resultp; + char *__pyx_r; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + Py_UCS4 __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("pybuffer_index", 1); + + /* "View.MemoryView":898 + * cdef char *pybuffer_index(Py_buffer *view, char *bufp, Py_ssize_t index, + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 # <<<<<<<<<<<<<< + * cdef Py_ssize_t itemsize = view.itemsize + * cdef char *resultp + */ + __pyx_v_suboffset = -1L; + + /* "View.MemoryView":899 + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 + * cdef Py_ssize_t itemsize = view.itemsize # <<<<<<<<<<<<<< + * cdef char *resultp + * + */ + __pyx_t_1 = __pyx_v_view->itemsize; + __pyx_v_itemsize = __pyx_t_1; + + /* "View.MemoryView":902 + * cdef char *resultp + * + * if view.ndim == 0: # <<<<<<<<<<<<<< + * shape = view.len // itemsize + * stride = itemsize + */ + __pyx_t_2 = (__pyx_v_view->ndim == 0); + if (__pyx_t_2) { + + /* "View.MemoryView":903 + * + * if view.ndim == 0: + * shape = view.len // itemsize # <<<<<<<<<<<<<< + * stride = itemsize + * else: + */ + if (unlikely(__pyx_v_itemsize == 0)) { + PyErr_SetString(PyExc_ZeroDivisionError, "integer division or modulo by zero"); + __PYX_ERR(0, 903, __pyx_L1_error) + } + else if (sizeof(Py_ssize_t) == sizeof(long) && (!(((Py_ssize_t)-1) > 0)) && unlikely(__pyx_v_itemsize == (Py_ssize_t)-1) && unlikely(__Pyx_UNARY_NEG_WOULD_OVERFLOW(__pyx_v_view->len))) { + PyErr_SetString(PyExc_OverflowError, "value too large to perform division"); + __PYX_ERR(0, 903, __pyx_L1_error) + } + __pyx_v_shape = __Pyx_div_Py_ssize_t(__pyx_v_view->len, __pyx_v_itemsize); + + /* "View.MemoryView":904 + * if view.ndim == 0: + * shape = view.len // itemsize + * stride = itemsize # <<<<<<<<<<<<<< + * else: + * shape = view.shape[dim] + */ + __pyx_v_stride = __pyx_v_itemsize; + + /* "View.MemoryView":902 + * cdef char *resultp + * + * if view.ndim == 0: # <<<<<<<<<<<<<< + * shape = view.len // itemsize + * stride = itemsize + */ + goto __pyx_L3; + } + + /* "View.MemoryView":906 + * stride = itemsize + * else: + * shape = view.shape[dim] # <<<<<<<<<<<<<< + * stride = view.strides[dim] + * if view.suboffsets != NULL: + */ + /*else*/ { + __pyx_v_shape = (__pyx_v_view->shape[__pyx_v_dim]); + + /* "View.MemoryView":907 + * else: + * shape = view.shape[dim] + * stride = view.strides[dim] # <<<<<<<<<<<<<< + * if view.suboffsets != NULL: + * suboffset = view.suboffsets[dim] + */ + __pyx_v_stride = (__pyx_v_view->strides[__pyx_v_dim]); + + /* "View.MemoryView":908 + * shape = view.shape[dim] + * stride = view.strides[dim] + * if view.suboffsets != NULL: # <<<<<<<<<<<<<< + * suboffset = view.suboffsets[dim] + * + */ + __pyx_t_2 = (__pyx_v_view->suboffsets != NULL); + if (__pyx_t_2) { + + /* "View.MemoryView":909 + * stride = view.strides[dim] + * if view.suboffsets != NULL: + * suboffset = view.suboffsets[dim] # <<<<<<<<<<<<<< + * + * if index < 0: + */ + __pyx_v_suboffset = (__pyx_v_view->suboffsets[__pyx_v_dim]); + + /* "View.MemoryView":908 + * shape = view.shape[dim] + * stride = view.strides[dim] + * if view.suboffsets != NULL: # <<<<<<<<<<<<<< + * suboffset = view.suboffsets[dim] + * + */ + } + } + __pyx_L3:; + + /* "View.MemoryView":911 + * suboffset = view.suboffsets[dim] + * + * if index < 0: # <<<<<<<<<<<<<< + * index += view.shape[dim] + * if index < 0: + */ + __pyx_t_2 = (__pyx_v_index < 0); + if (__pyx_t_2) { + + /* "View.MemoryView":912 + * + * if index < 0: + * index += view.shape[dim] # <<<<<<<<<<<<<< + * if index < 0: + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + */ + __pyx_v_index = (__pyx_v_index + (__pyx_v_view->shape[__pyx_v_dim])); + + /* "View.MemoryView":913 + * if index < 0: + * index += view.shape[dim] + * if index < 0: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + __pyx_t_2 = (__pyx_v_index < 0); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":914 + * index += view.shape[dim] + * if index < 0: + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" # <<<<<<<<<<<<<< + * + * if index >= shape: + */ + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 914, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = 0; + __pyx_t_4 = 127; + __Pyx_INCREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_1 += 37; + __Pyx_GIVEREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + PyTuple_SET_ITEM(__pyx_t_3, 0, __pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_5 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_dim, 0, ' ', 'd'); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 914, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_5); + __Pyx_GIVEREF(__pyx_t_5); + PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_t_5); + __pyx_t_5 = 0; + __Pyx_INCREF(__pyx_kp_u__7); + __pyx_t_1 += 1; + __Pyx_GIVEREF(__pyx_kp_u__7); + PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_kp_u__7); + __pyx_t_5 = __Pyx_PyUnicode_Join(__pyx_t_3, 3, __pyx_t_1, __pyx_t_4); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 914, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_builtin_IndexError, __pyx_t_5, 0, 0); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __PYX_ERR(0, 914, __pyx_L1_error) + + /* "View.MemoryView":913 + * if index < 0: + * index += view.shape[dim] + * if index < 0: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + } + + /* "View.MemoryView":911 + * suboffset = view.suboffsets[dim] + * + * if index < 0: # <<<<<<<<<<<<<< + * index += view.shape[dim] + * if index < 0: + */ + } + + /* "View.MemoryView":916 + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + * if index >= shape: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + __pyx_t_2 = (__pyx_v_index >= __pyx_v_shape); + if (unlikely(__pyx_t_2)) { + + /* "View.MemoryView":917 + * + * if index >= shape: + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" # <<<<<<<<<<<<<< + * + * resultp = bufp + index * stride + */ + __pyx_t_5 = PyTuple_New(3); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 917, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_1 = 0; + __pyx_t_4 = 127; + __Pyx_INCREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_1 += 37; + __Pyx_GIVEREF(__pyx_kp_u_Out_of_bounds_on_buffer_access_a); + PyTuple_SET_ITEM(__pyx_t_5, 0, __pyx_kp_u_Out_of_bounds_on_buffer_access_a); + __pyx_t_3 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_dim, 0, ' ', 'd'); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 917, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_3); + __Pyx_GIVEREF(__pyx_t_3); + PyTuple_SET_ITEM(__pyx_t_5, 1, __pyx_t_3); + __pyx_t_3 = 0; + __Pyx_INCREF(__pyx_kp_u__7); + __pyx_t_1 += 1; + __Pyx_GIVEREF(__pyx_kp_u__7); + PyTuple_SET_ITEM(__pyx_t_5, 2, __pyx_kp_u__7); + __pyx_t_3 = __Pyx_PyUnicode_Join(__pyx_t_5, 3, __pyx_t_1, __pyx_t_4); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 917, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_Raise(__pyx_builtin_IndexError, __pyx_t_3, 0, 0); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __PYX_ERR(0, 917, __pyx_L1_error) + + /* "View.MemoryView":916 + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + * if index >= shape: # <<<<<<<<<<<<<< + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + */ + } + + /* "View.MemoryView":919 + * raise IndexError, f"Out of bounds on buffer access (axis {dim})" + * + * resultp = bufp + index * stride # <<<<<<<<<<<<<< + * if suboffset >= 0: + * resultp = ( resultp)[0] + suboffset + */ + __pyx_v_resultp = (__pyx_v_bufp + (__pyx_v_index * __pyx_v_stride)); + + /* "View.MemoryView":920 + * + * resultp = bufp + index * stride + * if suboffset >= 0: # <<<<<<<<<<<<<< + * resultp = ( resultp)[0] + suboffset + * + */ + __pyx_t_2 = (__pyx_v_suboffset >= 0); + if (__pyx_t_2) { + + /* "View.MemoryView":921 + * resultp = bufp + index * stride + * if suboffset >= 0: + * resultp = ( resultp)[0] + suboffset # <<<<<<<<<<<<<< + * + * return resultp + */ + __pyx_v_resultp = ((((char **)__pyx_v_resultp)[0]) + __pyx_v_suboffset); + + /* "View.MemoryView":920 + * + * resultp = bufp + index * stride + * if suboffset >= 0: # <<<<<<<<<<<<<< + * resultp = ( resultp)[0] + suboffset + * + */ + } + + /* "View.MemoryView":923 + * resultp = ( resultp)[0] + suboffset + * + * return resultp # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = __pyx_v_resultp; + goto __pyx_L0; + + /* "View.MemoryView":896 + * + * @cname('__pyx_pybuffer_index') + * cdef char *pybuffer_index(Py_buffer *view, char *bufp, Py_ssize_t index, # <<<<<<<<<<<<<< + * Py_ssize_t dim) except NULL: + * cdef Py_ssize_t shape, stride, suboffset = -1 + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_AddTraceback("View.MemoryView.pybuffer_index", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":929 + * + * @cname('__pyx_memslice_transpose') + * cdef int transpose_memslice(__Pyx_memviewslice *memslice) except -1 nogil: # <<<<<<<<<<<<<< + * cdef int ndim = memslice.memview.view.ndim + * + */ + +static int __pyx_memslice_transpose(__Pyx_memviewslice *__pyx_v_memslice) { + int __pyx_v_ndim; + Py_ssize_t *__pyx_v_shape; + Py_ssize_t *__pyx_v_strides; + int __pyx_v_i; + int __pyx_v_j; + int __pyx_r; + int __pyx_t_1; + Py_ssize_t *__pyx_t_2; + long __pyx_t_3; + long __pyx_t_4; + Py_ssize_t __pyx_t_5; + Py_ssize_t __pyx_t_6; + int __pyx_t_7; + int __pyx_t_8; + int __pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":930 + * @cname('__pyx_memslice_transpose') + * cdef int transpose_memslice(__Pyx_memviewslice *memslice) except -1 nogil: + * cdef int ndim = memslice.memview.view.ndim # <<<<<<<<<<<<<< + * + * cdef Py_ssize_t *shape = memslice.shape + */ + __pyx_t_1 = __pyx_v_memslice->memview->view.ndim; + __pyx_v_ndim = __pyx_t_1; + + /* "View.MemoryView":932 + * cdef int ndim = memslice.memview.view.ndim + * + * cdef Py_ssize_t *shape = memslice.shape # <<<<<<<<<<<<<< + * cdef Py_ssize_t *strides = memslice.strides + * + */ + __pyx_t_2 = __pyx_v_memslice->shape; + __pyx_v_shape = __pyx_t_2; + + /* "View.MemoryView":933 + * + * cdef Py_ssize_t *shape = memslice.shape + * cdef Py_ssize_t *strides = memslice.strides # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = __pyx_v_memslice->strides; + __pyx_v_strides = __pyx_t_2; + + /* "View.MemoryView":937 + * + * cdef int i, j + * for i in range(ndim // 2): # <<<<<<<<<<<<<< + * j = ndim - 1 - i + * strides[i], strides[j] = strides[j], strides[i] + */ + __pyx_t_3 = __Pyx_div_long(__pyx_v_ndim, 2); + __pyx_t_4 = __pyx_t_3; + for (__pyx_t_1 = 0; __pyx_t_1 < __pyx_t_4; __pyx_t_1+=1) { + __pyx_v_i = __pyx_t_1; + + /* "View.MemoryView":938 + * cdef int i, j + * for i in range(ndim // 2): + * j = ndim - 1 - i # <<<<<<<<<<<<<< + * strides[i], strides[j] = strides[j], strides[i] + * shape[i], shape[j] = shape[j], shape[i] + */ + __pyx_v_j = ((__pyx_v_ndim - 1) - __pyx_v_i); + + /* "View.MemoryView":939 + * for i in range(ndim // 2): + * j = ndim - 1 - i + * strides[i], strides[j] = strides[j], strides[i] # <<<<<<<<<<<<<< + * shape[i], shape[j] = shape[j], shape[i] + * + */ + __pyx_t_5 = (__pyx_v_strides[__pyx_v_j]); + __pyx_t_6 = (__pyx_v_strides[__pyx_v_i]); + (__pyx_v_strides[__pyx_v_i]) = __pyx_t_5; + (__pyx_v_strides[__pyx_v_j]) = __pyx_t_6; + + /* "View.MemoryView":940 + * j = ndim - 1 - i + * strides[i], strides[j] = strides[j], strides[i] + * shape[i], shape[j] = shape[j], shape[i] # <<<<<<<<<<<<<< + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: + */ + __pyx_t_6 = (__pyx_v_shape[__pyx_v_j]); + __pyx_t_5 = (__pyx_v_shape[__pyx_v_i]); + (__pyx_v_shape[__pyx_v_i]) = __pyx_t_6; + (__pyx_v_shape[__pyx_v_j]) = __pyx_t_5; + + /* "View.MemoryView":942 + * shape[i], shape[j] = shape[j], shape[i] + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: # <<<<<<<<<<<<<< + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") + * + */ + __pyx_t_8 = ((__pyx_v_memslice->suboffsets[__pyx_v_i]) >= 0); + if (!__pyx_t_8) { + } else { + __pyx_t_7 = __pyx_t_8; + goto __pyx_L6_bool_binop_done; + } + __pyx_t_8 = ((__pyx_v_memslice->suboffsets[__pyx_v_j]) >= 0); + __pyx_t_7 = __pyx_t_8; + __pyx_L6_bool_binop_done:; + if (__pyx_t_7) { + + /* "View.MemoryView":943 + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") # <<<<<<<<<<<<<< + * + * return 0 + */ + __pyx_t_9 = __pyx_memoryview_err(PyExc_ValueError, __pyx_kp_s_Cannot_transpose_memoryview_with); if (unlikely(__pyx_t_9 == ((int)-1))) __PYX_ERR(0, 943, __pyx_L1_error) + + /* "View.MemoryView":942 + * shape[i], shape[j] = shape[j], shape[i] + * + * if memslice.suboffsets[i] >= 0 or memslice.suboffsets[j] >= 0: # <<<<<<<<<<<<<< + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") + * + */ + } + } + + /* "View.MemoryView":945 + * _err(PyExc_ValueError, "Cannot transpose memoryview with indirect dimensions") + * + * return 0 # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":929 + * + * @cname('__pyx_memslice_transpose') + * cdef int transpose_memslice(__Pyx_memviewslice *memslice) except -1 nogil: # <<<<<<<<<<<<<< + * cdef int ndim = memslice.memview.view.ndim + * + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.transpose_memslice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":963 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + */ + +/* Python wrapper */ +static void __pyx_memoryviewslice___dealloc__(PyObject *__pyx_v_self); /*proto*/ +static void __pyx_memoryviewslice___dealloc__(PyObject *__pyx_v_self) { + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__dealloc__ (wrapper)", 0); + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + __pyx_memoryviewslice___pyx_pf_15View_dot_MemoryView_16_memoryviewslice___dealloc__(((struct __pyx_memoryviewslice_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); +} + +static void __pyx_memoryviewslice___pyx_pf_15View_dot_MemoryView_16_memoryviewslice___dealloc__(struct __pyx_memoryviewslice_obj *__pyx_v_self) { + + /* "View.MemoryView":964 + * + * def __dealloc__(self): + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) # <<<<<<<<<<<<<< + * + * cdef convert_item_to_object(self, char *itemp): + */ + __PYX_XCLEAR_MEMVIEW((&__pyx_v_self->from_slice), 1); + + /* "View.MemoryView":963 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * def __dealloc__(self): # <<<<<<<<<<<<<< + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + */ + + /* function exit code */ +} + +/* "View.MemoryView":966 + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * if self.to_object_func != NULL: + * return self.to_object_func(itemp) + */ + +static PyObject *__pyx_memoryviewslice_convert_item_to_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("convert_item_to_object", 1); + + /* "View.MemoryView":967 + * + * cdef convert_item_to_object(self, char *itemp): + * if self.to_object_func != NULL: # <<<<<<<<<<<<<< + * return self.to_object_func(itemp) + * else: + */ + __pyx_t_1 = (__pyx_v_self->to_object_func != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":968 + * cdef convert_item_to_object(self, char *itemp): + * if self.to_object_func != NULL: + * return self.to_object_func(itemp) # <<<<<<<<<<<<<< + * else: + * return memoryview.convert_item_to_object(self, itemp) + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_v_self->to_object_func(__pyx_v_itemp); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 968, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + + /* "View.MemoryView":967 + * + * cdef convert_item_to_object(self, char *itemp): + * if self.to_object_func != NULL: # <<<<<<<<<<<<<< + * return self.to_object_func(itemp) + * else: + */ + } + + /* "View.MemoryView":970 + * return self.to_object_func(itemp) + * else: + * return memoryview.convert_item_to_object(self, itemp) # <<<<<<<<<<<<<< + * + * cdef assign_item_from_object(self, char *itemp, object value): + */ + /*else*/ { + __Pyx_XDECREF(__pyx_r); + __pyx_t_2 = __pyx_memoryview_convert_item_to_object(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v_itemp); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 970, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_r = __pyx_t_2; + __pyx_t_2 = 0; + goto __pyx_L0; + } + + /* "View.MemoryView":966 + * __PYX_XCLEAR_MEMVIEW(&self.from_slice, 1) + * + * cdef convert_item_to_object(self, char *itemp): # <<<<<<<<<<<<<< + * if self.to_object_func != NULL: + * return self.to_object_func(itemp) + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.convert_item_to_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":972 + * return memoryview.convert_item_to_object(self, itemp) + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * if self.to_dtype_func != NULL: + * self.to_dtype_func(itemp, value) + */ + +static PyObject *__pyx_memoryviewslice_assign_item_from_object(struct __pyx_memoryviewslice_obj *__pyx_v_self, char *__pyx_v_itemp, PyObject *__pyx_v_value) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("assign_item_from_object", 1); + + /* "View.MemoryView":973 + * + * cdef assign_item_from_object(self, char *itemp, object value): + * if self.to_dtype_func != NULL: # <<<<<<<<<<<<<< + * self.to_dtype_func(itemp, value) + * else: + */ + __pyx_t_1 = (__pyx_v_self->to_dtype_func != NULL); + if (__pyx_t_1) { + + /* "View.MemoryView":974 + * cdef assign_item_from_object(self, char *itemp, object value): + * if self.to_dtype_func != NULL: + * self.to_dtype_func(itemp, value) # <<<<<<<<<<<<<< + * else: + * memoryview.assign_item_from_object(self, itemp, value) + */ + __pyx_t_2 = __pyx_v_self->to_dtype_func(__pyx_v_itemp, __pyx_v_value); if (unlikely(__pyx_t_2 == ((int)0))) __PYX_ERR(0, 974, __pyx_L1_error) + + /* "View.MemoryView":973 + * + * cdef assign_item_from_object(self, char *itemp, object value): + * if self.to_dtype_func != NULL: # <<<<<<<<<<<<<< + * self.to_dtype_func(itemp, value) + * else: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":976 + * self.to_dtype_func(itemp, value) + * else: + * memoryview.assign_item_from_object(self, itemp, value) # <<<<<<<<<<<<<< + * + * cdef _get_base(self): + */ + /*else*/ { + __pyx_t_3 = __pyx_memoryview_assign_item_from_object(((struct __pyx_memoryview_obj *)__pyx_v_self), __pyx_v_itemp, __pyx_v_value); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 976, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_L3:; + + /* "View.MemoryView":972 + * return memoryview.convert_item_to_object(self, itemp) + * + * cdef assign_item_from_object(self, char *itemp, object value): # <<<<<<<<<<<<<< + * if self.to_dtype_func != NULL: + * self.to_dtype_func(itemp, value) + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.assign_item_from_object", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":978 + * memoryview.assign_item_from_object(self, itemp, value) + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.from_object + * + */ + +static PyObject *__pyx_memoryviewslice__get_base(struct __pyx_memoryviewslice_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("_get_base", 1); + + /* "View.MemoryView":979 + * + * cdef _get_base(self): + * return self.from_object # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v_self->from_object); + __pyx_r = __pyx_v_self->from_object; + goto __pyx_L0; + + /* "View.MemoryView":978 + * memoryview.assign_item_from_object(self, itemp, value) + * + * cdef _get_base(self): # <<<<<<<<<<<<<< + * return self.from_object + * + */ + + /* function exit code */ + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryviewslice_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryviewslice_1__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf___pyx_memoryviewslice___reduce_cython__(((struct __pyx_memoryviewslice_obj *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryviewslice___reduce_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(0, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw___pyx_memoryviewslice_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyObject *__pyx_pw___pyx_memoryviewslice_3__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(0, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf___pyx_memoryviewslice_2__setstate_cython__(((struct __pyx_memoryviewslice_obj *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf___pyx_memoryviewslice_2__setstate_cython__(CYTHON_UNUSED struct __pyx_memoryviewslice_obj *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(0, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._memoryviewslice.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":999 + * + * @cname('__pyx_memoryview_fromslice') + * cdef memoryview_fromslice(__Pyx_memviewslice memviewslice, # <<<<<<<<<<<<<< + * int ndim, + * object (*to_object_func)(char *), + */ + +static PyObject *__pyx_memoryview_fromslice(__Pyx_memviewslice __pyx_v_memviewslice, int __pyx_v_ndim, PyObject *(*__pyx_v_to_object_func)(char *), int (*__pyx_v_to_dtype_func)(char *, PyObject *), int __pyx_v_dtype_is_object) { + struct __pyx_memoryviewslice_obj *__pyx_v_result = 0; + Py_ssize_t __pyx_v_suboffset; + PyObject *__pyx_v_length = NULL; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + __Pyx_TypeInfo *__pyx_t_4; + Py_buffer __pyx_t_5; + Py_ssize_t *__pyx_t_6; + Py_ssize_t *__pyx_t_7; + Py_ssize_t *__pyx_t_8; + Py_ssize_t __pyx_t_9; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_fromslice", 1); + + /* "View.MemoryView":1007 + * cdef _memoryviewslice result + * + * if memviewslice.memview == Py_None: # <<<<<<<<<<<<<< + * return None + * + */ + __pyx_t_1 = (((PyObject *)__pyx_v_memviewslice.memview) == Py_None); + if (__pyx_t_1) { + + /* "View.MemoryView":1008 + * + * if memviewslice.memview == Py_None: + * return None # <<<<<<<<<<<<<< + * + * + */ + __Pyx_XDECREF(__pyx_r); + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + + /* "View.MemoryView":1007 + * cdef _memoryviewslice result + * + * if memviewslice.memview == Py_None: # <<<<<<<<<<<<<< + * return None + * + */ + } + + /* "View.MemoryView":1013 + * + * + * result = _memoryviewslice.__new__(_memoryviewslice, None, 0, dtype_is_object) # <<<<<<<<<<<<<< + * + * result.from_slice = memviewslice + */ + __pyx_t_2 = __Pyx_PyBool_FromLong(__pyx_v_dtype_is_object); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 1013, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyTuple_New(3); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 1013, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_INCREF(Py_None); + __Pyx_GIVEREF(Py_None); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 0, Py_None)) __PYX_ERR(0, 1013, __pyx_L1_error); + __Pyx_INCREF(__pyx_int_0); + __Pyx_GIVEREF(__pyx_int_0); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 1, __pyx_int_0)) __PYX_ERR(0, 1013, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_t_2); + if (__Pyx_PyTuple_SET_ITEM(__pyx_t_3, 2, __pyx_t_2)) __PYX_ERR(0, 1013, __pyx_L1_error); + __pyx_t_2 = 0; + __pyx_t_2 = ((PyObject *)__pyx_tp_new__memoryviewslice(((PyTypeObject *)__pyx_memoryviewslice_type), __pyx_t_3, NULL)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 1013, __pyx_L1_error) + __Pyx_GOTREF((PyObject *)__pyx_t_2); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_v_result = ((struct __pyx_memoryviewslice_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":1015 + * result = _memoryviewslice.__new__(_memoryviewslice, None, 0, dtype_is_object) + * + * result.from_slice = memviewslice # <<<<<<<<<<<<<< + * __PYX_INC_MEMVIEW(&memviewslice, 1) + * + */ + __pyx_v_result->from_slice = __pyx_v_memviewslice; + + /* "View.MemoryView":1016 + * + * result.from_slice = memviewslice + * __PYX_INC_MEMVIEW(&memviewslice, 1) # <<<<<<<<<<<<<< + * + * result.from_object = ( memviewslice.memview)._get_base() + */ + __PYX_INC_MEMVIEW((&__pyx_v_memviewslice), 1); + + /* "View.MemoryView":1018 + * __PYX_INC_MEMVIEW(&memviewslice, 1) + * + * result.from_object = ( memviewslice.memview)._get_base() # <<<<<<<<<<<<<< + * result.typeinfo = memviewslice.memview.typeinfo + * + */ + __pyx_t_2 = ((struct __pyx_vtabstruct_memoryview *)((struct __pyx_memoryview_obj *)__pyx_v_memviewslice.memview)->__pyx_vtab)->_get_base(((struct __pyx_memoryview_obj *)__pyx_v_memviewslice.memview)); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 1018, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_GIVEREF(__pyx_t_2); + __Pyx_GOTREF(__pyx_v_result->from_object); + __Pyx_DECREF(__pyx_v_result->from_object); + __pyx_v_result->from_object = __pyx_t_2; + __pyx_t_2 = 0; + + /* "View.MemoryView":1019 + * + * result.from_object = ( memviewslice.memview)._get_base() + * result.typeinfo = memviewslice.memview.typeinfo # <<<<<<<<<<<<<< + * + * result.view = memviewslice.memview.view + */ + __pyx_t_4 = __pyx_v_memviewslice.memview->typeinfo; + __pyx_v_result->__pyx_base.typeinfo = __pyx_t_4; + + /* "View.MemoryView":1021 + * result.typeinfo = memviewslice.memview.typeinfo + * + * result.view = memviewslice.memview.view # <<<<<<<<<<<<<< + * result.view.buf = memviewslice.data + * result.view.ndim = ndim + */ + __pyx_t_5 = __pyx_v_memviewslice.memview->view; + __pyx_v_result->__pyx_base.view = __pyx_t_5; + + /* "View.MemoryView":1022 + * + * result.view = memviewslice.memview.view + * result.view.buf = memviewslice.data # <<<<<<<<<<<<<< + * result.view.ndim = ndim + * (<__pyx_buffer *> &result.view).obj = Py_None + */ + __pyx_v_result->__pyx_base.view.buf = ((void *)__pyx_v_memviewslice.data); + + /* "View.MemoryView":1023 + * result.view = memviewslice.memview.view + * result.view.buf = memviewslice.data + * result.view.ndim = ndim # <<<<<<<<<<<<<< + * (<__pyx_buffer *> &result.view).obj = Py_None + * Py_INCREF(Py_None) + */ + __pyx_v_result->__pyx_base.view.ndim = __pyx_v_ndim; + + /* "View.MemoryView":1024 + * result.view.buf = memviewslice.data + * result.view.ndim = ndim + * (<__pyx_buffer *> &result.view).obj = Py_None # <<<<<<<<<<<<<< + * Py_INCREF(Py_None) + * + */ + ((Py_buffer *)(&__pyx_v_result->__pyx_base.view))->obj = Py_None; + + /* "View.MemoryView":1025 + * result.view.ndim = ndim + * (<__pyx_buffer *> &result.view).obj = Py_None + * Py_INCREF(Py_None) # <<<<<<<<<<<<<< + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: + */ + Py_INCREF(Py_None); + + /* "View.MemoryView":1027 + * Py_INCREF(Py_None) + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: # <<<<<<<<<<<<<< + * result.flags = PyBUF_RECORDS + * else: + */ + __pyx_t_1 = ((((struct __pyx_memoryview_obj *)__pyx_v_memviewslice.memview)->flags & PyBUF_WRITABLE) != 0); + if (__pyx_t_1) { + + /* "View.MemoryView":1028 + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: + * result.flags = PyBUF_RECORDS # <<<<<<<<<<<<<< + * else: + * result.flags = PyBUF_RECORDS_RO + */ + __pyx_v_result->__pyx_base.flags = PyBUF_RECORDS; + + /* "View.MemoryView":1027 + * Py_INCREF(Py_None) + * + * if (memviewslice.memview).flags & PyBUF_WRITABLE: # <<<<<<<<<<<<<< + * result.flags = PyBUF_RECORDS + * else: + */ + goto __pyx_L4; + } + + /* "View.MemoryView":1030 + * result.flags = PyBUF_RECORDS + * else: + * result.flags = PyBUF_RECORDS_RO # <<<<<<<<<<<<<< + * + * result.view.shape = result.from_slice.shape + */ + /*else*/ { + __pyx_v_result->__pyx_base.flags = PyBUF_RECORDS_RO; + } + __pyx_L4:; + + /* "View.MemoryView":1032 + * result.flags = PyBUF_RECORDS_RO + * + * result.view.shape = result.from_slice.shape # <<<<<<<<<<<<<< + * result.view.strides = result.from_slice.strides + * + */ + __pyx_v_result->__pyx_base.view.shape = ((Py_ssize_t *)__pyx_v_result->from_slice.shape); + + /* "View.MemoryView":1033 + * + * result.view.shape = result.from_slice.shape + * result.view.strides = result.from_slice.strides # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_result->__pyx_base.view.strides = ((Py_ssize_t *)__pyx_v_result->from_slice.strides); + + /* "View.MemoryView":1036 + * + * + * result.view.suboffsets = NULL # <<<<<<<<<<<<<< + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: + */ + __pyx_v_result->__pyx_base.view.suboffsets = NULL; + + /* "View.MemoryView":1037 + * + * result.view.suboffsets = NULL + * for suboffset in result.from_slice.suboffsets[:ndim]: # <<<<<<<<<<<<<< + * if suboffset >= 0: + * result.view.suboffsets = result.from_slice.suboffsets + */ + __pyx_t_7 = (__pyx_v_result->from_slice.suboffsets + __pyx_v_ndim); + for (__pyx_t_8 = __pyx_v_result->from_slice.suboffsets; __pyx_t_8 < __pyx_t_7; __pyx_t_8++) { + __pyx_t_6 = __pyx_t_8; + __pyx_v_suboffset = (__pyx_t_6[0]); + + /* "View.MemoryView":1038 + * result.view.suboffsets = NULL + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * result.view.suboffsets = result.from_slice.suboffsets + * break + */ + __pyx_t_1 = (__pyx_v_suboffset >= 0); + if (__pyx_t_1) { + + /* "View.MemoryView":1039 + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: + * result.view.suboffsets = result.from_slice.suboffsets # <<<<<<<<<<<<<< + * break + * + */ + __pyx_v_result->__pyx_base.view.suboffsets = ((Py_ssize_t *)__pyx_v_result->from_slice.suboffsets); + + /* "View.MemoryView":1040 + * if suboffset >= 0: + * result.view.suboffsets = result.from_slice.suboffsets + * break # <<<<<<<<<<<<<< + * + * result.view.len = result.view.itemsize + */ + goto __pyx_L6_break; + + /* "View.MemoryView":1038 + * result.view.suboffsets = NULL + * for suboffset in result.from_slice.suboffsets[:ndim]: + * if suboffset >= 0: # <<<<<<<<<<<<<< + * result.view.suboffsets = result.from_slice.suboffsets + * break + */ + } + } + __pyx_L6_break:; + + /* "View.MemoryView":1042 + * break + * + * result.view.len = result.view.itemsize # <<<<<<<<<<<<<< + * for length in result.view.shape[:ndim]: + * result.view.len *= length + */ + __pyx_t_9 = __pyx_v_result->__pyx_base.view.itemsize; + __pyx_v_result->__pyx_base.view.len = __pyx_t_9; + + /* "View.MemoryView":1043 + * + * result.view.len = result.view.itemsize + * for length in result.view.shape[:ndim]: # <<<<<<<<<<<<<< + * result.view.len *= length + * + */ + __pyx_t_7 = (__pyx_v_result->__pyx_base.view.shape + __pyx_v_ndim); + for (__pyx_t_8 = __pyx_v_result->__pyx_base.view.shape; __pyx_t_8 < __pyx_t_7; __pyx_t_8++) { + __pyx_t_6 = __pyx_t_8; + __pyx_t_2 = PyInt_FromSsize_t((__pyx_t_6[0])); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 1043, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_XDECREF_SET(__pyx_v_length, __pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":1044 + * result.view.len = result.view.itemsize + * for length in result.view.shape[:ndim]: + * result.view.len *= length # <<<<<<<<<<<<<< + * + * result.to_object_func = to_object_func + */ + __pyx_t_2 = PyInt_FromSsize_t(__pyx_v_result->__pyx_base.view.len); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 1044, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_t_3 = PyNumber_InPlaceMultiply(__pyx_t_2, __pyx_v_length); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 1044, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __pyx_t_9 = __Pyx_PyIndex_AsSsize_t(__pyx_t_3); if (unlikely((__pyx_t_9 == (Py_ssize_t)-1) && PyErr_Occurred())) __PYX_ERR(0, 1044, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __pyx_v_result->__pyx_base.view.len = __pyx_t_9; + } + + /* "View.MemoryView":1046 + * result.view.len *= length + * + * result.to_object_func = to_object_func # <<<<<<<<<<<<<< + * result.to_dtype_func = to_dtype_func + * + */ + __pyx_v_result->to_object_func = __pyx_v_to_object_func; + + /* "View.MemoryView":1047 + * + * result.to_object_func = to_object_func + * result.to_dtype_func = to_dtype_func # <<<<<<<<<<<<<< + * + * return result + */ + __pyx_v_result->to_dtype_func = __pyx_v_to_dtype_func; + + /* "View.MemoryView":1049 + * result.to_dtype_func = to_dtype_func + * + * return result # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_get_slice_from_memoryview') + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF((PyObject *)__pyx_v_result); + __pyx_r = ((PyObject *)__pyx_v_result); + goto __pyx_L0; + + /* "View.MemoryView":999 + * + * @cname('__pyx_memoryview_fromslice') + * cdef memoryview_fromslice(__Pyx_memviewslice memviewslice, # <<<<<<<<<<<<<< + * int ndim, + * object (*to_object_func)(char *), + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_AddTraceback("View.MemoryView.memoryview_fromslice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_result); + __Pyx_XDECREF(__pyx_v_length); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1052 + * + * @cname('__pyx_memoryview_get_slice_from_memoryview') + * cdef __Pyx_memviewslice *get_slice_from_memview(memoryview memview, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + */ + +static __Pyx_memviewslice *__pyx_memoryview_get_slice_from_memoryview(struct __pyx_memoryview_obj *__pyx_v_memview, __Pyx_memviewslice *__pyx_v_mslice) { + struct __pyx_memoryviewslice_obj *__pyx_v_obj = 0; + __Pyx_memviewslice *__pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("get_slice_from_memview", 1); + + /* "View.MemoryView":1055 + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * obj = memview + * return &obj.from_slice + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":1056 + * cdef _memoryviewslice obj + * if isinstance(memview, _memoryviewslice): + * obj = memview # <<<<<<<<<<<<<< + * return &obj.from_slice + * else: + */ + if (!(likely(((((PyObject *)__pyx_v_memview)) == Py_None) || likely(__Pyx_TypeTest(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type))))) __PYX_ERR(0, 1056, __pyx_L1_error) + __pyx_t_2 = ((PyObject *)__pyx_v_memview); + __Pyx_INCREF(__pyx_t_2); + __pyx_v_obj = ((struct __pyx_memoryviewslice_obj *)__pyx_t_2); + __pyx_t_2 = 0; + + /* "View.MemoryView":1057 + * if isinstance(memview, _memoryviewslice): + * obj = memview + * return &obj.from_slice # <<<<<<<<<<<<<< + * else: + * slice_copy(memview, mslice) + */ + __pyx_r = (&__pyx_v_obj->from_slice); + goto __pyx_L0; + + /* "View.MemoryView":1055 + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * obj = memview + * return &obj.from_slice + */ + } + + /* "View.MemoryView":1059 + * return &obj.from_slice + * else: + * slice_copy(memview, mslice) # <<<<<<<<<<<<<< + * return mslice + * + */ + /*else*/ { + __pyx_memoryview_slice_copy(__pyx_v_memview, __pyx_v_mslice); + + /* "View.MemoryView":1060 + * else: + * slice_copy(memview, mslice) + * return mslice # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_slice_copy') + */ + __pyx_r = __pyx_v_mslice; + goto __pyx_L0; + } + + /* "View.MemoryView":1052 + * + * @cname('__pyx_memoryview_get_slice_from_memoryview') + * cdef __Pyx_memviewslice *get_slice_from_memview(memoryview memview, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *mslice) except NULL: + * cdef _memoryviewslice obj + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView.get_slice_from_memview", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF((PyObject *)__pyx_v_obj); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1063 + * + * @cname('__pyx_memoryview_slice_copy') + * cdef void slice_copy(memoryview memview, __Pyx_memviewslice *dst) noexcept: # <<<<<<<<<<<<<< + * cdef int dim + * cdef (Py_ssize_t*) shape, strides, suboffsets + */ + +static void __pyx_memoryview_slice_copy(struct __pyx_memoryview_obj *__pyx_v_memview, __Pyx_memviewslice *__pyx_v_dst) { + int __pyx_v_dim; + Py_ssize_t *__pyx_v_shape; + Py_ssize_t *__pyx_v_strides; + Py_ssize_t *__pyx_v_suboffsets; + Py_ssize_t *__pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + Py_ssize_t __pyx_t_5; + int __pyx_t_6; + + /* "View.MemoryView":1067 + * cdef (Py_ssize_t*) shape, strides, suboffsets + * + * shape = memview.view.shape # <<<<<<<<<<<<<< + * strides = memview.view.strides + * suboffsets = memview.view.suboffsets + */ + __pyx_t_1 = __pyx_v_memview->view.shape; + __pyx_v_shape = __pyx_t_1; + + /* "View.MemoryView":1068 + * + * shape = memview.view.shape + * strides = memview.view.strides # <<<<<<<<<<<<<< + * suboffsets = memview.view.suboffsets + * + */ + __pyx_t_1 = __pyx_v_memview->view.strides; + __pyx_v_strides = __pyx_t_1; + + /* "View.MemoryView":1069 + * shape = memview.view.shape + * strides = memview.view.strides + * suboffsets = memview.view.suboffsets # <<<<<<<<<<<<<< + * + * dst.memview = <__pyx_memoryview *> memview + */ + __pyx_t_1 = __pyx_v_memview->view.suboffsets; + __pyx_v_suboffsets = __pyx_t_1; + + /* "View.MemoryView":1071 + * suboffsets = memview.view.suboffsets + * + * dst.memview = <__pyx_memoryview *> memview # <<<<<<<<<<<<<< + * dst.data = memview.view.buf + * + */ + __pyx_v_dst->memview = ((struct __pyx_memoryview_obj *)__pyx_v_memview); + + /* "View.MemoryView":1072 + * + * dst.memview = <__pyx_memoryview *> memview + * dst.data = memview.view.buf # <<<<<<<<<<<<<< + * + * for dim in range(memview.view.ndim): + */ + __pyx_v_dst->data = ((char *)__pyx_v_memview->view.buf); + + /* "View.MemoryView":1074 + * dst.data = memview.view.buf + * + * for dim in range(memview.view.ndim): # <<<<<<<<<<<<<< + * dst.shape[dim] = shape[dim] + * dst.strides[dim] = strides[dim] + */ + __pyx_t_2 = __pyx_v_memview->view.ndim; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_dim = __pyx_t_4; + + /* "View.MemoryView":1075 + * + * for dim in range(memview.view.ndim): + * dst.shape[dim] = shape[dim] # <<<<<<<<<<<<<< + * dst.strides[dim] = strides[dim] + * dst.suboffsets[dim] = suboffsets[dim] if suboffsets else -1 + */ + (__pyx_v_dst->shape[__pyx_v_dim]) = (__pyx_v_shape[__pyx_v_dim]); + + /* "View.MemoryView":1076 + * for dim in range(memview.view.ndim): + * dst.shape[dim] = shape[dim] + * dst.strides[dim] = strides[dim] # <<<<<<<<<<<<<< + * dst.suboffsets[dim] = suboffsets[dim] if suboffsets else -1 + * + */ + (__pyx_v_dst->strides[__pyx_v_dim]) = (__pyx_v_strides[__pyx_v_dim]); + + /* "View.MemoryView":1077 + * dst.shape[dim] = shape[dim] + * dst.strides[dim] = strides[dim] + * dst.suboffsets[dim] = suboffsets[dim] if suboffsets else -1 # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_copy_object') + */ + __pyx_t_6 = (__pyx_v_suboffsets != 0); + if (__pyx_t_6) { + __pyx_t_5 = (__pyx_v_suboffsets[__pyx_v_dim]); + } else { + __pyx_t_5 = -1L; + } + (__pyx_v_dst->suboffsets[__pyx_v_dim]) = __pyx_t_5; + } + + /* "View.MemoryView":1063 + * + * @cname('__pyx_memoryview_slice_copy') + * cdef void slice_copy(memoryview memview, __Pyx_memviewslice *dst) noexcept: # <<<<<<<<<<<<<< + * cdef int dim + * cdef (Py_ssize_t*) shape, strides, suboffsets + */ + + /* function exit code */ +} + +/* "View.MemoryView":1080 + * + * @cname('__pyx_memoryview_copy_object') + * cdef memoryview_copy(memoryview memview): # <<<<<<<<<<<<<< + * "Create a new memoryview object" + * cdef __Pyx_memviewslice memviewslice + */ + +static PyObject *__pyx_memoryview_copy_object(struct __pyx_memoryview_obj *__pyx_v_memview) { + __Pyx_memviewslice __pyx_v_memviewslice; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_copy", 1); + + /* "View.MemoryView":1083 + * "Create a new memoryview object" + * cdef __Pyx_memviewslice memviewslice + * slice_copy(memview, &memviewslice) # <<<<<<<<<<<<<< + * return memoryview_copy_from_slice(memview, &memviewslice) + * + */ + __pyx_memoryview_slice_copy(__pyx_v_memview, (&__pyx_v_memviewslice)); + + /* "View.MemoryView":1084 + * cdef __Pyx_memviewslice memviewslice + * slice_copy(memview, &memviewslice) + * return memoryview_copy_from_slice(memview, &memviewslice) # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_copy_object_from_slice') + */ + __Pyx_XDECREF(__pyx_r); + __pyx_t_1 = __pyx_memoryview_copy_object_from_slice(__pyx_v_memview, (&__pyx_v_memviewslice)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 1084, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_r = __pyx_t_1; + __pyx_t_1 = 0; + goto __pyx_L0; + + /* "View.MemoryView":1080 + * + * @cname('__pyx_memoryview_copy_object') + * cdef memoryview_copy(memoryview memview): # <<<<<<<<<<<<<< + * "Create a new memoryview object" + * cdef __Pyx_memviewslice memviewslice + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_AddTraceback("View.MemoryView.memoryview_copy", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1087 + * + * @cname('__pyx_memoryview_copy_object_from_slice') + * cdef memoryview_copy_from_slice(memoryview memview, __Pyx_memviewslice *memviewslice): # <<<<<<<<<<<<<< + * """ + * Create a new memoryview object from a given memoryview object and slice. + */ + +static PyObject *__pyx_memoryview_copy_object_from_slice(struct __pyx_memoryview_obj *__pyx_v_memview, __Pyx_memviewslice *__pyx_v_memviewslice) { + PyObject *(*__pyx_v_to_object_func)(char *); + int (*__pyx_v_to_dtype_func)(char *, PyObject *); + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_t_1; + PyObject *(*__pyx_t_2)(char *); + int (*__pyx_t_3)(char *, PyObject *); + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("memoryview_copy_from_slice", 1); + + /* "View.MemoryView":1094 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * to_object_func = (<_memoryviewslice> memview).to_object_func + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + */ + __pyx_t_1 = __Pyx_TypeCheck(((PyObject *)__pyx_v_memview), __pyx_memoryviewslice_type); + if (__pyx_t_1) { + + /* "View.MemoryView":1095 + * + * if isinstance(memview, _memoryviewslice): + * to_object_func = (<_memoryviewslice> memview).to_object_func # <<<<<<<<<<<<<< + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + * else: + */ + __pyx_t_2 = ((struct __pyx_memoryviewslice_obj *)__pyx_v_memview)->to_object_func; + __pyx_v_to_object_func = __pyx_t_2; + + /* "View.MemoryView":1096 + * if isinstance(memview, _memoryviewslice): + * to_object_func = (<_memoryviewslice> memview).to_object_func + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func # <<<<<<<<<<<<<< + * else: + * to_object_func = NULL + */ + __pyx_t_3 = ((struct __pyx_memoryviewslice_obj *)__pyx_v_memview)->to_dtype_func; + __pyx_v_to_dtype_func = __pyx_t_3; + + /* "View.MemoryView":1094 + * cdef int (*to_dtype_func)(char *, object) except 0 + * + * if isinstance(memview, _memoryviewslice): # <<<<<<<<<<<<<< + * to_object_func = (<_memoryviewslice> memview).to_object_func + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1098 + * to_dtype_func = (<_memoryviewslice> memview).to_dtype_func + * else: + * to_object_func = NULL # <<<<<<<<<<<<<< + * to_dtype_func = NULL + * + */ + /*else*/ { + __pyx_v_to_object_func = NULL; + + /* "View.MemoryView":1099 + * else: + * to_object_func = NULL + * to_dtype_func = NULL # <<<<<<<<<<<<<< + * + * return memoryview_fromslice(memviewslice[0], memview.view.ndim, + */ + __pyx_v_to_dtype_func = NULL; + } + __pyx_L3:; + + /* "View.MemoryView":1101 + * to_dtype_func = NULL + * + * return memoryview_fromslice(memviewslice[0], memview.view.ndim, # <<<<<<<<<<<<<< + * to_object_func, to_dtype_func, + * memview.dtype_is_object) + */ + __Pyx_XDECREF(__pyx_r); + + /* "View.MemoryView":1103 + * return memoryview_fromslice(memviewslice[0], memview.view.ndim, + * to_object_func, to_dtype_func, + * memview.dtype_is_object) # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_4 = __pyx_memoryview_fromslice((__pyx_v_memviewslice[0]), __pyx_v_memview->view.ndim, __pyx_v_to_object_func, __pyx_v_to_dtype_func, __pyx_v_memview->dtype_is_object); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 1101, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_r = __pyx_t_4; + __pyx_t_4 = 0; + goto __pyx_L0; + + /* "View.MemoryView":1087 + * + * @cname('__pyx_memoryview_copy_object_from_slice') + * cdef memoryview_copy_from_slice(memoryview memview, __Pyx_memviewslice *memviewslice): # <<<<<<<<<<<<<< + * """ + * Create a new memoryview object from a given memoryview object and slice. + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.memoryview_copy_from_slice", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "View.MemoryView":1109 + * + * + * cdef Py_ssize_t abs_py_ssize_t(Py_ssize_t arg) noexcept nogil: # <<<<<<<<<<<<<< + * return -arg if arg < 0 else arg + * + */ + +static Py_ssize_t abs_py_ssize_t(Py_ssize_t __pyx_v_arg) { + Py_ssize_t __pyx_r; + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + + /* "View.MemoryView":1110 + * + * cdef Py_ssize_t abs_py_ssize_t(Py_ssize_t arg) noexcept nogil: + * return -arg if arg < 0 else arg # <<<<<<<<<<<<<< + * + * @cname('__pyx_get_best_slice_order') + */ + __pyx_t_2 = (__pyx_v_arg < 0); + if (__pyx_t_2) { + __pyx_t_1 = (-__pyx_v_arg); + } else { + __pyx_t_1 = __pyx_v_arg; + } + __pyx_r = __pyx_t_1; + goto __pyx_L0; + + /* "View.MemoryView":1109 + * + * + * cdef Py_ssize_t abs_py_ssize_t(Py_ssize_t arg) noexcept nogil: # <<<<<<<<<<<<<< + * return -arg if arg < 0 else arg + * + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1113 + * + * @cname('__pyx_get_best_slice_order') + * cdef char get_best_order(__Pyx_memviewslice *mslice, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * """ + * Figure out the best memory access order for a given slice. + */ + +static char __pyx_get_best_slice_order(__Pyx_memviewslice *__pyx_v_mslice, int __pyx_v_ndim) { + int __pyx_v_i; + Py_ssize_t __pyx_v_c_stride; + Py_ssize_t __pyx_v_f_stride; + char __pyx_r; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + + /* "View.MemoryView":1118 + * """ + * cdef int i + * cdef Py_ssize_t c_stride = 0 # <<<<<<<<<<<<<< + * cdef Py_ssize_t f_stride = 0 + * + */ + __pyx_v_c_stride = 0; + + /* "View.MemoryView":1119 + * cdef int i + * cdef Py_ssize_t c_stride = 0 + * cdef Py_ssize_t f_stride = 0 # <<<<<<<<<<<<<< + * + * for i in range(ndim - 1, -1, -1): + */ + __pyx_v_f_stride = 0; + + /* "View.MemoryView":1121 + * cdef Py_ssize_t f_stride = 0 + * + * for i in range(ndim - 1, -1, -1): # <<<<<<<<<<<<<< + * if mslice.shape[i] > 1: + * c_stride = mslice.strides[i] + */ + for (__pyx_t_1 = (__pyx_v_ndim - 1); __pyx_t_1 > -1; __pyx_t_1-=1) { + __pyx_v_i = __pyx_t_1; + + /* "View.MemoryView":1122 + * + * for i in range(ndim - 1, -1, -1): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * c_stride = mslice.strides[i] + * break + */ + __pyx_t_2 = ((__pyx_v_mslice->shape[__pyx_v_i]) > 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1123 + * for i in range(ndim - 1, -1, -1): + * if mslice.shape[i] > 1: + * c_stride = mslice.strides[i] # <<<<<<<<<<<<<< + * break + * + */ + __pyx_v_c_stride = (__pyx_v_mslice->strides[__pyx_v_i]); + + /* "View.MemoryView":1124 + * if mslice.shape[i] > 1: + * c_stride = mslice.strides[i] + * break # <<<<<<<<<<<<<< + * + * for i in range(ndim): + */ + goto __pyx_L4_break; + + /* "View.MemoryView":1122 + * + * for i in range(ndim - 1, -1, -1): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * c_stride = mslice.strides[i] + * break + */ + } + } + __pyx_L4_break:; + + /* "View.MemoryView":1126 + * break + * + * for i in range(ndim): # <<<<<<<<<<<<<< + * if mslice.shape[i] > 1: + * f_stride = mslice.strides[i] + */ + __pyx_t_1 = __pyx_v_ndim; + __pyx_t_3 = __pyx_t_1; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1127 + * + * for i in range(ndim): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * f_stride = mslice.strides[i] + * break + */ + __pyx_t_2 = ((__pyx_v_mslice->shape[__pyx_v_i]) > 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1128 + * for i in range(ndim): + * if mslice.shape[i] > 1: + * f_stride = mslice.strides[i] # <<<<<<<<<<<<<< + * break + * + */ + __pyx_v_f_stride = (__pyx_v_mslice->strides[__pyx_v_i]); + + /* "View.MemoryView":1129 + * if mslice.shape[i] > 1: + * f_stride = mslice.strides[i] + * break # <<<<<<<<<<<<<< + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): + */ + goto __pyx_L7_break; + + /* "View.MemoryView":1127 + * + * for i in range(ndim): + * if mslice.shape[i] > 1: # <<<<<<<<<<<<<< + * f_stride = mslice.strides[i] + * break + */ + } + } + __pyx_L7_break:; + + /* "View.MemoryView":1131 + * break + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): # <<<<<<<<<<<<<< + * return 'C' + * else: + */ + __pyx_t_2 = (abs_py_ssize_t(__pyx_v_c_stride) <= abs_py_ssize_t(__pyx_v_f_stride)); + if (__pyx_t_2) { + + /* "View.MemoryView":1132 + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): + * return 'C' # <<<<<<<<<<<<<< + * else: + * return 'F' + */ + __pyx_r = 'C'; + goto __pyx_L0; + + /* "View.MemoryView":1131 + * break + * + * if abs_py_ssize_t(c_stride) <= abs_py_ssize_t(f_stride): # <<<<<<<<<<<<<< + * return 'C' + * else: + */ + } + + /* "View.MemoryView":1134 + * return 'C' + * else: + * return 'F' # <<<<<<<<<<<<<< + * + * @cython.cdivision(True) + */ + /*else*/ { + __pyx_r = 'F'; + goto __pyx_L0; + } + + /* "View.MemoryView":1113 + * + * @cname('__pyx_get_best_slice_order') + * cdef char get_best_order(__Pyx_memviewslice *mslice, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * """ + * Figure out the best memory access order for a given slice. + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1137 + * + * @cython.cdivision(True) + * cdef void _copy_strided_to_strided(char *src_data, Py_ssize_t *src_strides, # <<<<<<<<<<<<<< + * char *dst_data, Py_ssize_t *dst_strides, + * Py_ssize_t *src_shape, Py_ssize_t *dst_shape, + */ + +static void _copy_strided_to_strided(char *__pyx_v_src_data, Py_ssize_t *__pyx_v_src_strides, char *__pyx_v_dst_data, Py_ssize_t *__pyx_v_dst_strides, Py_ssize_t *__pyx_v_src_shape, Py_ssize_t *__pyx_v_dst_shape, int __pyx_v_ndim, size_t __pyx_v_itemsize) { + CYTHON_UNUSED Py_ssize_t __pyx_v_i; + CYTHON_UNUSED Py_ssize_t __pyx_v_src_extent; + Py_ssize_t __pyx_v_dst_extent; + Py_ssize_t __pyx_v_src_stride; + Py_ssize_t __pyx_v_dst_stride; + int __pyx_t_1; + int __pyx_t_2; + Py_ssize_t __pyx_t_3; + Py_ssize_t __pyx_t_4; + Py_ssize_t __pyx_t_5; + + /* "View.MemoryView":1144 + * + * cdef Py_ssize_t i + * cdef Py_ssize_t src_extent = src_shape[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t dst_extent = dst_shape[0] + * cdef Py_ssize_t src_stride = src_strides[0] + */ + __pyx_v_src_extent = (__pyx_v_src_shape[0]); + + /* "View.MemoryView":1145 + * cdef Py_ssize_t i + * cdef Py_ssize_t src_extent = src_shape[0] + * cdef Py_ssize_t dst_extent = dst_shape[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t src_stride = src_strides[0] + * cdef Py_ssize_t dst_stride = dst_strides[0] + */ + __pyx_v_dst_extent = (__pyx_v_dst_shape[0]); + + /* "View.MemoryView":1146 + * cdef Py_ssize_t src_extent = src_shape[0] + * cdef Py_ssize_t dst_extent = dst_shape[0] + * cdef Py_ssize_t src_stride = src_strides[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t dst_stride = dst_strides[0] + * + */ + __pyx_v_src_stride = (__pyx_v_src_strides[0]); + + /* "View.MemoryView":1147 + * cdef Py_ssize_t dst_extent = dst_shape[0] + * cdef Py_ssize_t src_stride = src_strides[0] + * cdef Py_ssize_t dst_stride = dst_strides[0] # <<<<<<<<<<<<<< + * + * if ndim == 1: + */ + __pyx_v_dst_stride = (__pyx_v_dst_strides[0]); + + /* "View.MemoryView":1149 + * cdef Py_ssize_t dst_stride = dst_strides[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): + */ + __pyx_t_1 = (__pyx_v_ndim == 1); + if (__pyx_t_1) { + + /* "View.MemoryView":1150 + * + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and # <<<<<<<<<<<<<< + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) + */ + __pyx_t_2 = (__pyx_v_src_stride > 0); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L5_bool_binop_done; + } + __pyx_t_2 = (__pyx_v_dst_stride > 0); + if (__pyx_t_2) { + } else { + __pyx_t_1 = __pyx_t_2; + goto __pyx_L5_bool_binop_done; + } + + /* "View.MemoryView":1151 + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): # <<<<<<<<<<<<<< + * memcpy(dst_data, src_data, itemsize * dst_extent) + * else: + */ + __pyx_t_2 = (((size_t)__pyx_v_src_stride) == __pyx_v_itemsize); + if (__pyx_t_2) { + __pyx_t_2 = (__pyx_v_itemsize == ((size_t)__pyx_v_dst_stride)); + } + __pyx_t_1 = __pyx_t_2; + __pyx_L5_bool_binop_done:; + + /* "View.MemoryView":1150 + * + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and # <<<<<<<<<<<<<< + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) + */ + if (__pyx_t_1) { + + /* "View.MemoryView":1152 + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) # <<<<<<<<<<<<<< + * else: + * for i in range(dst_extent): + */ + (void)(memcpy(__pyx_v_dst_data, __pyx_v_src_data, (__pyx_v_itemsize * __pyx_v_dst_extent))); + + /* "View.MemoryView":1150 + * + * if ndim == 1: + * if (src_stride > 0 and dst_stride > 0 and # <<<<<<<<<<<<<< + * src_stride == itemsize == dst_stride): + * memcpy(dst_data, src_data, itemsize * dst_extent) + */ + goto __pyx_L4; + } + + /* "View.MemoryView":1154 + * memcpy(dst_data, src_data, itemsize * dst_extent) + * else: + * for i in range(dst_extent): # <<<<<<<<<<<<<< + * memcpy(dst_data, src_data, itemsize) + * src_data += src_stride + */ + /*else*/ { + __pyx_t_3 = __pyx_v_dst_extent; + __pyx_t_4 = __pyx_t_3; + for (__pyx_t_5 = 0; __pyx_t_5 < __pyx_t_4; __pyx_t_5+=1) { + __pyx_v_i = __pyx_t_5; + + /* "View.MemoryView":1155 + * else: + * for i in range(dst_extent): + * memcpy(dst_data, src_data, itemsize) # <<<<<<<<<<<<<< + * src_data += src_stride + * dst_data += dst_stride + */ + (void)(memcpy(__pyx_v_dst_data, __pyx_v_src_data, __pyx_v_itemsize)); + + /* "View.MemoryView":1156 + * for i in range(dst_extent): + * memcpy(dst_data, src_data, itemsize) + * src_data += src_stride # <<<<<<<<<<<<<< + * dst_data += dst_stride + * else: + */ + __pyx_v_src_data = (__pyx_v_src_data + __pyx_v_src_stride); + + /* "View.MemoryView":1157 + * memcpy(dst_data, src_data, itemsize) + * src_data += src_stride + * dst_data += dst_stride # <<<<<<<<<<<<<< + * else: + * for i in range(dst_extent): + */ + __pyx_v_dst_data = (__pyx_v_dst_data + __pyx_v_dst_stride); + } + } + __pyx_L4:; + + /* "View.MemoryView":1149 + * cdef Py_ssize_t dst_stride = dst_strides[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * if (src_stride > 0 and dst_stride > 0 and + * src_stride == itemsize == dst_stride): + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1159 + * dst_data += dst_stride + * else: + * for i in range(dst_extent): # <<<<<<<<<<<<<< + * _copy_strided_to_strided(src_data, src_strides + 1, + * dst_data, dst_strides + 1, + */ + /*else*/ { + __pyx_t_3 = __pyx_v_dst_extent; + __pyx_t_4 = __pyx_t_3; + for (__pyx_t_5 = 0; __pyx_t_5 < __pyx_t_4; __pyx_t_5+=1) { + __pyx_v_i = __pyx_t_5; + + /* "View.MemoryView":1160 + * else: + * for i in range(dst_extent): + * _copy_strided_to_strided(src_data, src_strides + 1, # <<<<<<<<<<<<<< + * dst_data, dst_strides + 1, + * src_shape + 1, dst_shape + 1, + */ + _copy_strided_to_strided(__pyx_v_src_data, (__pyx_v_src_strides + 1), __pyx_v_dst_data, (__pyx_v_dst_strides + 1), (__pyx_v_src_shape + 1), (__pyx_v_dst_shape + 1), (__pyx_v_ndim - 1), __pyx_v_itemsize); + + /* "View.MemoryView":1164 + * src_shape + 1, dst_shape + 1, + * ndim - 1, itemsize) + * src_data += src_stride # <<<<<<<<<<<<<< + * dst_data += dst_stride + * + */ + __pyx_v_src_data = (__pyx_v_src_data + __pyx_v_src_stride); + + /* "View.MemoryView":1165 + * ndim - 1, itemsize) + * src_data += src_stride + * dst_data += dst_stride # <<<<<<<<<<<<<< + * + * cdef void copy_strided_to_strided(__Pyx_memviewslice *src, + */ + __pyx_v_dst_data = (__pyx_v_dst_data + __pyx_v_dst_stride); + } + } + __pyx_L3:; + + /* "View.MemoryView":1137 + * + * @cython.cdivision(True) + * cdef void _copy_strided_to_strided(char *src_data, Py_ssize_t *src_strides, # <<<<<<<<<<<<<< + * char *dst_data, Py_ssize_t *dst_strides, + * Py_ssize_t *src_shape, Py_ssize_t *dst_shape, + */ + + /* function exit code */ +} + +/* "View.MemoryView":1167 + * dst_data += dst_stride + * + * cdef void copy_strided_to_strided(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * int ndim, size_t itemsize) noexcept nogil: + */ + +static void copy_strided_to_strided(__Pyx_memviewslice *__pyx_v_src, __Pyx_memviewslice *__pyx_v_dst, int __pyx_v_ndim, size_t __pyx_v_itemsize) { + + /* "View.MemoryView":1170 + * __Pyx_memviewslice *dst, + * int ndim, size_t itemsize) noexcept nogil: + * _copy_strided_to_strided(src.data, src.strides, dst.data, dst.strides, # <<<<<<<<<<<<<< + * src.shape, dst.shape, ndim, itemsize) + * + */ + _copy_strided_to_strided(__pyx_v_src->data, __pyx_v_src->strides, __pyx_v_dst->data, __pyx_v_dst->strides, __pyx_v_src->shape, __pyx_v_dst->shape, __pyx_v_ndim, __pyx_v_itemsize); + + /* "View.MemoryView":1167 + * dst_data += dst_stride + * + * cdef void copy_strided_to_strided(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *dst, + * int ndim, size_t itemsize) noexcept nogil: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1174 + * + * @cname('__pyx_memoryview_slice_get_size') + * cdef Py_ssize_t slice_get_size(__Pyx_memviewslice *src, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * "Return the size of the memory occupied by the slice in number of bytes" + * cdef Py_ssize_t shape, size = src.memview.view.itemsize + */ + +static Py_ssize_t __pyx_memoryview_slice_get_size(__Pyx_memviewslice *__pyx_v_src, int __pyx_v_ndim) { + Py_ssize_t __pyx_v_shape; + Py_ssize_t __pyx_v_size; + Py_ssize_t __pyx_r; + Py_ssize_t __pyx_t_1; + Py_ssize_t *__pyx_t_2; + Py_ssize_t *__pyx_t_3; + Py_ssize_t *__pyx_t_4; + + /* "View.MemoryView":1176 + * cdef Py_ssize_t slice_get_size(__Pyx_memviewslice *src, int ndim) noexcept nogil: + * "Return the size of the memory occupied by the slice in number of bytes" + * cdef Py_ssize_t shape, size = src.memview.view.itemsize # <<<<<<<<<<<<<< + * + * for shape in src.shape[:ndim]: + */ + __pyx_t_1 = __pyx_v_src->memview->view.itemsize; + __pyx_v_size = __pyx_t_1; + + /* "View.MemoryView":1178 + * cdef Py_ssize_t shape, size = src.memview.view.itemsize + * + * for shape in src.shape[:ndim]: # <<<<<<<<<<<<<< + * size *= shape + * + */ + __pyx_t_3 = (__pyx_v_src->shape + __pyx_v_ndim); + for (__pyx_t_4 = __pyx_v_src->shape; __pyx_t_4 < __pyx_t_3; __pyx_t_4++) { + __pyx_t_2 = __pyx_t_4; + __pyx_v_shape = (__pyx_t_2[0]); + + /* "View.MemoryView":1179 + * + * for shape in src.shape[:ndim]: + * size *= shape # <<<<<<<<<<<<<< + * + * return size + */ + __pyx_v_size = (__pyx_v_size * __pyx_v_shape); + } + + /* "View.MemoryView":1181 + * size *= shape + * + * return size # <<<<<<<<<<<<<< + * + * @cname('__pyx_fill_contig_strides_array') + */ + __pyx_r = __pyx_v_size; + goto __pyx_L0; + + /* "View.MemoryView":1174 + * + * @cname('__pyx_memoryview_slice_get_size') + * cdef Py_ssize_t slice_get_size(__Pyx_memviewslice *src, int ndim) noexcept nogil: # <<<<<<<<<<<<<< + * "Return the size of the memory occupied by the slice in number of bytes" + * cdef Py_ssize_t shape, size = src.memview.view.itemsize + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1184 + * + * @cname('__pyx_fill_contig_strides_array') + * cdef Py_ssize_t fill_contig_strides_array( # <<<<<<<<<<<<<< + * Py_ssize_t *shape, Py_ssize_t *strides, Py_ssize_t stride, + * int ndim, char order) noexcept nogil: + */ + +static Py_ssize_t __pyx_fill_contig_strides_array(Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, Py_ssize_t __pyx_v_stride, int __pyx_v_ndim, char __pyx_v_order) { + int __pyx_v_idx; + Py_ssize_t __pyx_r; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + + /* "View.MemoryView":1193 + * cdef int idx + * + * if order == 'F': # <<<<<<<<<<<<<< + * for idx in range(ndim): + * strides[idx] = stride + */ + __pyx_t_1 = (__pyx_v_order == 'F'); + if (__pyx_t_1) { + + /* "View.MemoryView":1194 + * + * if order == 'F': + * for idx in range(ndim): # <<<<<<<<<<<<<< + * strides[idx] = stride + * stride *= shape[idx] + */ + __pyx_t_2 = __pyx_v_ndim; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_idx = __pyx_t_4; + + /* "View.MemoryView":1195 + * if order == 'F': + * for idx in range(ndim): + * strides[idx] = stride # <<<<<<<<<<<<<< + * stride *= shape[idx] + * else: + */ + (__pyx_v_strides[__pyx_v_idx]) = __pyx_v_stride; + + /* "View.MemoryView":1196 + * for idx in range(ndim): + * strides[idx] = stride + * stride *= shape[idx] # <<<<<<<<<<<<<< + * else: + * for idx in range(ndim - 1, -1, -1): + */ + __pyx_v_stride = (__pyx_v_stride * (__pyx_v_shape[__pyx_v_idx])); + } + + /* "View.MemoryView":1193 + * cdef int idx + * + * if order == 'F': # <<<<<<<<<<<<<< + * for idx in range(ndim): + * strides[idx] = stride + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1198 + * stride *= shape[idx] + * else: + * for idx in range(ndim - 1, -1, -1): # <<<<<<<<<<<<<< + * strides[idx] = stride + * stride *= shape[idx] + */ + /*else*/ { + for (__pyx_t_2 = (__pyx_v_ndim - 1); __pyx_t_2 > -1; __pyx_t_2-=1) { + __pyx_v_idx = __pyx_t_2; + + /* "View.MemoryView":1199 + * else: + * for idx in range(ndim - 1, -1, -1): + * strides[idx] = stride # <<<<<<<<<<<<<< + * stride *= shape[idx] + * + */ + (__pyx_v_strides[__pyx_v_idx]) = __pyx_v_stride; + + /* "View.MemoryView":1200 + * for idx in range(ndim - 1, -1, -1): + * strides[idx] = stride + * stride *= shape[idx] # <<<<<<<<<<<<<< + * + * return stride + */ + __pyx_v_stride = (__pyx_v_stride * (__pyx_v_shape[__pyx_v_idx])); + } + } + __pyx_L3:; + + /* "View.MemoryView":1202 + * stride *= shape[idx] + * + * return stride # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_copy_data_to_temp') + */ + __pyx_r = __pyx_v_stride; + goto __pyx_L0; + + /* "View.MemoryView":1184 + * + * @cname('__pyx_fill_contig_strides_array') + * cdef Py_ssize_t fill_contig_strides_array( # <<<<<<<<<<<<<< + * Py_ssize_t *shape, Py_ssize_t *strides, Py_ssize_t stride, + * int ndim, char order) noexcept nogil: + */ + + /* function exit code */ + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1205 + * + * @cname('__pyx_memoryview_copy_data_to_temp') + * cdef void *copy_data_to_temp(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *tmpslice, + * char order, + */ + +static void *__pyx_memoryview_copy_data_to_temp(__Pyx_memviewslice *__pyx_v_src, __Pyx_memviewslice *__pyx_v_tmpslice, char __pyx_v_order, int __pyx_v_ndim) { + int __pyx_v_i; + void *__pyx_v_result; + size_t __pyx_v_itemsize; + size_t __pyx_v_size; + void *__pyx_r; + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + struct __pyx_memoryview_obj *__pyx_t_4; + int __pyx_t_5; + int __pyx_t_6; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":1216 + * cdef void *result + * + * cdef size_t itemsize = src.memview.view.itemsize # <<<<<<<<<<<<<< + * cdef size_t size = slice_get_size(src, ndim) + * + */ + __pyx_t_1 = __pyx_v_src->memview->view.itemsize; + __pyx_v_itemsize = __pyx_t_1; + + /* "View.MemoryView":1217 + * + * cdef size_t itemsize = src.memview.view.itemsize + * cdef size_t size = slice_get_size(src, ndim) # <<<<<<<<<<<<<< + * + * result = malloc(size) + */ + __pyx_v_size = __pyx_memoryview_slice_get_size(__pyx_v_src, __pyx_v_ndim); + + /* "View.MemoryView":1219 + * cdef size_t size = slice_get_size(src, ndim) + * + * result = malloc(size) # <<<<<<<<<<<<<< + * if not result: + * _err_no_memory() + */ + __pyx_v_result = malloc(__pyx_v_size); + + /* "View.MemoryView":1220 + * + * result = malloc(size) + * if not result: # <<<<<<<<<<<<<< + * _err_no_memory() + * + */ + __pyx_t_2 = (!(__pyx_v_result != 0)); + if (__pyx_t_2) { + + /* "View.MemoryView":1221 + * result = malloc(size) + * if not result: + * _err_no_memory() # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_3 = __pyx_memoryview_err_no_memory(); if (unlikely(__pyx_t_3 == ((int)-1))) __PYX_ERR(0, 1221, __pyx_L1_error) + + /* "View.MemoryView":1220 + * + * result = malloc(size) + * if not result: # <<<<<<<<<<<<<< + * _err_no_memory() + * + */ + } + + /* "View.MemoryView":1224 + * + * + * tmpslice.data = result # <<<<<<<<<<<<<< + * tmpslice.memview = src.memview + * for i in range(ndim): + */ + __pyx_v_tmpslice->data = ((char *)__pyx_v_result); + + /* "View.MemoryView":1225 + * + * tmpslice.data = result + * tmpslice.memview = src.memview # <<<<<<<<<<<<<< + * for i in range(ndim): + * tmpslice.shape[i] = src.shape[i] + */ + __pyx_t_4 = __pyx_v_src->memview; + __pyx_v_tmpslice->memview = __pyx_t_4; + + /* "View.MemoryView":1226 + * tmpslice.data = result + * tmpslice.memview = src.memview + * for i in range(ndim): # <<<<<<<<<<<<<< + * tmpslice.shape[i] = src.shape[i] + * tmpslice.suboffsets[i] = -1 + */ + __pyx_t_3 = __pyx_v_ndim; + __pyx_t_5 = __pyx_t_3; + for (__pyx_t_6 = 0; __pyx_t_6 < __pyx_t_5; __pyx_t_6+=1) { + __pyx_v_i = __pyx_t_6; + + /* "View.MemoryView":1227 + * tmpslice.memview = src.memview + * for i in range(ndim): + * tmpslice.shape[i] = src.shape[i] # <<<<<<<<<<<<<< + * tmpslice.suboffsets[i] = -1 + * + */ + (__pyx_v_tmpslice->shape[__pyx_v_i]) = (__pyx_v_src->shape[__pyx_v_i]); + + /* "View.MemoryView":1228 + * for i in range(ndim): + * tmpslice.shape[i] = src.shape[i] + * tmpslice.suboffsets[i] = -1 # <<<<<<<<<<<<<< + * + * fill_contig_strides_array(&tmpslice.shape[0], &tmpslice.strides[0], itemsize, ndim, order) + */ + (__pyx_v_tmpslice->suboffsets[__pyx_v_i]) = -1L; + } + + /* "View.MemoryView":1230 + * tmpslice.suboffsets[i] = -1 + * + * fill_contig_strides_array(&tmpslice.shape[0], &tmpslice.strides[0], itemsize, ndim, order) # <<<<<<<<<<<<<< + * + * + */ + (void)(__pyx_fill_contig_strides_array((&(__pyx_v_tmpslice->shape[0])), (&(__pyx_v_tmpslice->strides[0])), __pyx_v_itemsize, __pyx_v_ndim, __pyx_v_order)); + + /* "View.MemoryView":1233 + * + * + * for i in range(ndim): # <<<<<<<<<<<<<< + * if tmpslice.shape[i] == 1: + * tmpslice.strides[i] = 0 + */ + __pyx_t_3 = __pyx_v_ndim; + __pyx_t_5 = __pyx_t_3; + for (__pyx_t_6 = 0; __pyx_t_6 < __pyx_t_5; __pyx_t_6+=1) { + __pyx_v_i = __pyx_t_6; + + /* "View.MemoryView":1234 + * + * for i in range(ndim): + * if tmpslice.shape[i] == 1: # <<<<<<<<<<<<<< + * tmpslice.strides[i] = 0 + * + */ + __pyx_t_2 = ((__pyx_v_tmpslice->shape[__pyx_v_i]) == 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1235 + * for i in range(ndim): + * if tmpslice.shape[i] == 1: + * tmpslice.strides[i] = 0 # <<<<<<<<<<<<<< + * + * if slice_is_contig(src[0], order, ndim): + */ + (__pyx_v_tmpslice->strides[__pyx_v_i]) = 0; + + /* "View.MemoryView":1234 + * + * for i in range(ndim): + * if tmpslice.shape[i] == 1: # <<<<<<<<<<<<<< + * tmpslice.strides[i] = 0 + * + */ + } + } + + /* "View.MemoryView":1237 + * tmpslice.strides[i] = 0 + * + * if slice_is_contig(src[0], order, ndim): # <<<<<<<<<<<<<< + * memcpy(result, src.data, size) + * else: + */ + __pyx_t_2 = __pyx_memviewslice_is_contig((__pyx_v_src[0]), __pyx_v_order, __pyx_v_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1238 + * + * if slice_is_contig(src[0], order, ndim): + * memcpy(result, src.data, size) # <<<<<<<<<<<<<< + * else: + * copy_strided_to_strided(src, tmpslice, ndim, itemsize) + */ + (void)(memcpy(__pyx_v_result, __pyx_v_src->data, __pyx_v_size)); + + /* "View.MemoryView":1237 + * tmpslice.strides[i] = 0 + * + * if slice_is_contig(src[0], order, ndim): # <<<<<<<<<<<<<< + * memcpy(result, src.data, size) + * else: + */ + goto __pyx_L9; + } + + /* "View.MemoryView":1240 + * memcpy(result, src.data, size) + * else: + * copy_strided_to_strided(src, tmpslice, ndim, itemsize) # <<<<<<<<<<<<<< + * + * return result + */ + /*else*/ { + copy_strided_to_strided(__pyx_v_src, __pyx_v_tmpslice, __pyx_v_ndim, __pyx_v_itemsize); + } + __pyx_L9:; + + /* "View.MemoryView":1242 + * copy_strided_to_strided(src, tmpslice, ndim, itemsize) + * + * return result # <<<<<<<<<<<<<< + * + * + */ + __pyx_r = __pyx_v_result; + goto __pyx_L0; + + /* "View.MemoryView":1205 + * + * @cname('__pyx_memoryview_copy_data_to_temp') + * cdef void *copy_data_to_temp(__Pyx_memviewslice *src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice *tmpslice, + * char order, + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.copy_data_to_temp", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1247 + * + * @cname('__pyx_memoryview_err_extents') + * cdef int _err_extents(int i, Py_ssize_t extent1, # <<<<<<<<<<<<<< + * Py_ssize_t extent2) except -1 with gil: + * raise ValueError, f"got differing extents in dimension {i} (got {extent1} and {extent2})" + */ + +static int __pyx_memoryview_err_extents(int __pyx_v_i, Py_ssize_t __pyx_v_extent1, Py_ssize_t __pyx_v_extent2) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + Py_ssize_t __pyx_t_2; + Py_UCS4 __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_RefNannySetupContext("_err_extents", 0); + + /* "View.MemoryView":1249 + * cdef int _err_extents(int i, Py_ssize_t extent1, + * Py_ssize_t extent2) except -1 with gil: + * raise ValueError, f"got differing extents in dimension {i} (got {extent1} and {extent2})" # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_err_dim') + */ + __pyx_t_1 = PyTuple_New(7); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = 0; + __pyx_t_3 = 127; + __Pyx_INCREF(__pyx_kp_u_got_differing_extents_in_dimensi); + __pyx_t_2 += 35; + __Pyx_GIVEREF(__pyx_kp_u_got_differing_extents_in_dimensi); + PyTuple_SET_ITEM(__pyx_t_1, 0, __pyx_kp_u_got_differing_extents_in_dimensi); + __pyx_t_4 = __Pyx_PyUnicode_From_int(__pyx_v_i, 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_2 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_1, 1, __pyx_t_4); + __pyx_t_4 = 0; + __Pyx_INCREF(__pyx_kp_u_got); + __pyx_t_2 += 6; + __Pyx_GIVEREF(__pyx_kp_u_got); + PyTuple_SET_ITEM(__pyx_t_1, 2, __pyx_kp_u_got); + __pyx_t_4 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_extent1, 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_2 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_1, 3, __pyx_t_4); + __pyx_t_4 = 0; + __Pyx_INCREF(__pyx_kp_u_and); + __pyx_t_2 += 5; + __Pyx_GIVEREF(__pyx_kp_u_and); + PyTuple_SET_ITEM(__pyx_t_1, 4, __pyx_kp_u_and); + __pyx_t_4 = __Pyx_PyUnicode_From_Py_ssize_t(__pyx_v_extent2, 0, ' ', 'd'); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_2 += __Pyx_PyUnicode_GET_LENGTH(__pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + PyTuple_SET_ITEM(__pyx_t_1, 5, __pyx_t_4); + __pyx_t_4 = 0; + __Pyx_INCREF(__pyx_kp_u__7); + __pyx_t_2 += 1; + __Pyx_GIVEREF(__pyx_kp_u__7); + PyTuple_SET_ITEM(__pyx_t_1, 6, __pyx_kp_u__7); + __pyx_t_4 = __Pyx_PyUnicode_Join(__pyx_t_1, 7, __pyx_t_2, __pyx_t_3); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 1249, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(__pyx_builtin_ValueError, __pyx_t_4, 0, 0); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __PYX_ERR(0, 1249, __pyx_L1_error) + + /* "View.MemoryView":1247 + * + * @cname('__pyx_memoryview_err_extents') + * cdef int _err_extents(int i, Py_ssize_t extent1, # <<<<<<<<<<<<<< + * Py_ssize_t extent2) except -1 with gil: + * raise ValueError, f"got differing extents in dimension {i} (got {extent1} and {extent2})" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView._err_extents", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __Pyx_RefNannyFinishContext(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1252 + * + * @cname('__pyx_memoryview_err_dim') + * cdef int _err_dim(PyObject *error, str msg, int dim) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg % dim + * + */ + +static int __pyx_memoryview_err_dim(PyObject *__pyx_v_error, PyObject *__pyx_v_msg, int __pyx_v_dim) { + int __pyx_r; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_RefNannySetupContext("_err_dim", 0); + __Pyx_INCREF(__pyx_v_msg); + + /* "View.MemoryView":1253 + * @cname('__pyx_memoryview_err_dim') + * cdef int _err_dim(PyObject *error, str msg, int dim) except -1 with gil: + * raise error, msg % dim # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_err') + */ + __pyx_t_1 = __Pyx_PyInt_From_int(__pyx_v_dim); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 1253, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = __Pyx_PyString_FormatSafe(__pyx_v_msg, __pyx_t_1); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 1253, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_Raise(((PyObject *)__pyx_v_error), __pyx_t_2, 0, 0); + __Pyx_DECREF(__pyx_t_2); __pyx_t_2 = 0; + __PYX_ERR(0, 1253, __pyx_L1_error) + + /* "View.MemoryView":1252 + * + * @cname('__pyx_memoryview_err_dim') + * cdef int _err_dim(PyObject *error, str msg, int dim) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg % dim + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_AddTraceback("View.MemoryView._err_dim", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __Pyx_XDECREF(__pyx_v_msg); + __Pyx_RefNannyFinishContext(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1256 + * + * @cname('__pyx_memoryview_err') + * cdef int _err(PyObject *error, str msg) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg + * + */ + +static int __pyx_memoryview_err(PyObject *__pyx_v_error, PyObject *__pyx_v_msg) { + int __pyx_r; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_RefNannySetupContext("_err", 0); + __Pyx_INCREF(__pyx_v_msg); + + /* "View.MemoryView":1257 + * @cname('__pyx_memoryview_err') + * cdef int _err(PyObject *error, str msg) except -1 with gil: + * raise error, msg # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_err_no_memory') + */ + __Pyx_Raise(((PyObject *)__pyx_v_error), __pyx_v_msg, 0, 0); + __PYX_ERR(0, 1257, __pyx_L1_error) + + /* "View.MemoryView":1256 + * + * @cname('__pyx_memoryview_err') + * cdef int _err(PyObject *error, str msg) except -1 with gil: # <<<<<<<<<<<<<< + * raise error, msg + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._err", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __Pyx_XDECREF(__pyx_v_msg); + __Pyx_RefNannyFinishContext(); + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1260 + * + * @cname('__pyx_memoryview_err_no_memory') + * cdef int _err_no_memory() except -1 with gil: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + +static int __pyx_memoryview_err_no_memory(void) { + int __pyx_r; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + + /* "View.MemoryView":1261 + * @cname('__pyx_memoryview_err_no_memory') + * cdef int _err_no_memory() except -1 with gil: + * raise MemoryError # <<<<<<<<<<<<<< + * + * + */ + PyErr_NoMemory(); __PYX_ERR(0, 1261, __pyx_L1_error) + + /* "View.MemoryView":1260 + * + * @cname('__pyx_memoryview_err_no_memory') + * cdef int _err_no_memory() except -1 with gil: # <<<<<<<<<<<<<< + * raise MemoryError + * + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("View.MemoryView._err_no_memory", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + return __pyx_r; +} + +/* "View.MemoryView":1265 + * + * @cname('__pyx_memoryview_copy_contents') + * cdef int memoryview_copy_contents(__Pyx_memviewslice src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice dst, + * int src_ndim, int dst_ndim, + */ + +static int __pyx_memoryview_copy_contents(__Pyx_memviewslice __pyx_v_src, __Pyx_memviewslice __pyx_v_dst, int __pyx_v_src_ndim, int __pyx_v_dst_ndim, int __pyx_v_dtype_is_object) { + void *__pyx_v_tmpdata; + size_t __pyx_v_itemsize; + int __pyx_v_i; + char __pyx_v_order; + int __pyx_v_broadcasting; + int __pyx_v_direct_copy; + __Pyx_memviewslice __pyx_v_tmp; + int __pyx_v_ndim; + int __pyx_r; + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + int __pyx_t_4; + int __pyx_t_5; + int __pyx_t_6; + void *__pyx_t_7; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save; + #endif + + /* "View.MemoryView":1273 + * Check for overlapping memory and verify the shapes. + * """ + * cdef void *tmpdata = NULL # <<<<<<<<<<<<<< + * cdef size_t itemsize = src.memview.view.itemsize + * cdef int i + */ + __pyx_v_tmpdata = NULL; + + /* "View.MemoryView":1274 + * """ + * cdef void *tmpdata = NULL + * cdef size_t itemsize = src.memview.view.itemsize # <<<<<<<<<<<<<< + * cdef int i + * cdef char order = get_best_order(&src, src_ndim) + */ + __pyx_t_1 = __pyx_v_src.memview->view.itemsize; + __pyx_v_itemsize = __pyx_t_1; + + /* "View.MemoryView":1276 + * cdef size_t itemsize = src.memview.view.itemsize + * cdef int i + * cdef char order = get_best_order(&src, src_ndim) # <<<<<<<<<<<<<< + * cdef bint broadcasting = False + * cdef bint direct_copy = False + */ + __pyx_v_order = __pyx_get_best_slice_order((&__pyx_v_src), __pyx_v_src_ndim); + + /* "View.MemoryView":1277 + * cdef int i + * cdef char order = get_best_order(&src, src_ndim) + * cdef bint broadcasting = False # <<<<<<<<<<<<<< + * cdef bint direct_copy = False + * cdef __Pyx_memviewslice tmp + */ + __pyx_v_broadcasting = 0; + + /* "View.MemoryView":1278 + * cdef char order = get_best_order(&src, src_ndim) + * cdef bint broadcasting = False + * cdef bint direct_copy = False # <<<<<<<<<<<<<< + * cdef __Pyx_memviewslice tmp + * + */ + __pyx_v_direct_copy = 0; + + /* "View.MemoryView":1281 + * cdef __Pyx_memviewslice tmp + * + * if src_ndim < dst_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: + */ + __pyx_t_2 = (__pyx_v_src_ndim < __pyx_v_dst_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1282 + * + * if src_ndim < dst_ndim: + * broadcast_leading(&src, src_ndim, dst_ndim) # <<<<<<<<<<<<<< + * elif dst_ndim < src_ndim: + * broadcast_leading(&dst, dst_ndim, src_ndim) + */ + __pyx_memoryview_broadcast_leading((&__pyx_v_src), __pyx_v_src_ndim, __pyx_v_dst_ndim); + + /* "View.MemoryView":1281 + * cdef __Pyx_memviewslice tmp + * + * if src_ndim < dst_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1283 + * if src_ndim < dst_ndim: + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&dst, dst_ndim, src_ndim) + * + */ + __pyx_t_2 = (__pyx_v_dst_ndim < __pyx_v_src_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1284 + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: + * broadcast_leading(&dst, dst_ndim, src_ndim) # <<<<<<<<<<<<<< + * + * cdef int ndim = max(src_ndim, dst_ndim) + */ + __pyx_memoryview_broadcast_leading((&__pyx_v_dst), __pyx_v_dst_ndim, __pyx_v_src_ndim); + + /* "View.MemoryView":1283 + * if src_ndim < dst_ndim: + * broadcast_leading(&src, src_ndim, dst_ndim) + * elif dst_ndim < src_ndim: # <<<<<<<<<<<<<< + * broadcast_leading(&dst, dst_ndim, src_ndim) + * + */ + } + __pyx_L3:; + + /* "View.MemoryView":1286 + * broadcast_leading(&dst, dst_ndim, src_ndim) + * + * cdef int ndim = max(src_ndim, dst_ndim) # <<<<<<<<<<<<<< + * + * for i in range(ndim): + */ + __pyx_t_3 = __pyx_v_dst_ndim; + __pyx_t_4 = __pyx_v_src_ndim; + __pyx_t_2 = (__pyx_t_3 > __pyx_t_4); + if (__pyx_t_2) { + __pyx_t_5 = __pyx_t_3; + } else { + __pyx_t_5 = __pyx_t_4; + } + __pyx_v_ndim = __pyx_t_5; + + /* "View.MemoryView":1288 + * cdef int ndim = max(src_ndim, dst_ndim) + * + * for i in range(ndim): # <<<<<<<<<<<<<< + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: + */ + __pyx_t_5 = __pyx_v_ndim; + __pyx_t_3 = __pyx_t_5; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1289 + * + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: # <<<<<<<<<<<<<< + * if src.shape[i] == 1: + * broadcasting = True + */ + __pyx_t_2 = ((__pyx_v_src.shape[__pyx_v_i]) != (__pyx_v_dst.shape[__pyx_v_i])); + if (__pyx_t_2) { + + /* "View.MemoryView":1290 + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: # <<<<<<<<<<<<<< + * broadcasting = True + * src.strides[i] = 0 + */ + __pyx_t_2 = ((__pyx_v_src.shape[__pyx_v_i]) == 1); + if (__pyx_t_2) { + + /* "View.MemoryView":1291 + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: + * broadcasting = True # <<<<<<<<<<<<<< + * src.strides[i] = 0 + * else: + */ + __pyx_v_broadcasting = 1; + + /* "View.MemoryView":1292 + * if src.shape[i] == 1: + * broadcasting = True + * src.strides[i] = 0 # <<<<<<<<<<<<<< + * else: + * _err_extents(i, dst.shape[i], src.shape[i]) + */ + (__pyx_v_src.strides[__pyx_v_i]) = 0; + + /* "View.MemoryView":1290 + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: + * if src.shape[i] == 1: # <<<<<<<<<<<<<< + * broadcasting = True + * src.strides[i] = 0 + */ + goto __pyx_L7; + } + + /* "View.MemoryView":1294 + * src.strides[i] = 0 + * else: + * _err_extents(i, dst.shape[i], src.shape[i]) # <<<<<<<<<<<<<< + * + * if src.suboffsets[i] >= 0: + */ + /*else*/ { + __pyx_t_6 = __pyx_memoryview_err_extents(__pyx_v_i, (__pyx_v_dst.shape[__pyx_v_i]), (__pyx_v_src.shape[__pyx_v_i])); if (unlikely(__pyx_t_6 == ((int)-1))) __PYX_ERR(0, 1294, __pyx_L1_error) + } + __pyx_L7:; + + /* "View.MemoryView":1289 + * + * for i in range(ndim): + * if src.shape[i] != dst.shape[i]: # <<<<<<<<<<<<<< + * if src.shape[i] == 1: + * broadcasting = True + */ + } + + /* "View.MemoryView":1296 + * _err_extents(i, dst.shape[i], src.shape[i]) + * + * if src.suboffsets[i] >= 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + */ + __pyx_t_2 = ((__pyx_v_src.suboffsets[__pyx_v_i]) >= 0); + if (__pyx_t_2) { + + /* "View.MemoryView":1297 + * + * if src.suboffsets[i] >= 0: + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) # <<<<<<<<<<<<<< + * + * if slices_overlap(&src, &dst, ndim, itemsize): + */ + __pyx_t_6 = __pyx_memoryview_err_dim(PyExc_ValueError, __pyx_kp_s_Dimension_d_is_not_direct, __pyx_v_i); if (unlikely(__pyx_t_6 == ((int)-1))) __PYX_ERR(0, 1297, __pyx_L1_error) + + /* "View.MemoryView":1296 + * _err_extents(i, dst.shape[i], src.shape[i]) + * + * if src.suboffsets[i] >= 0: # <<<<<<<<<<<<<< + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + */ + } + } + + /* "View.MemoryView":1299 + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + * if slices_overlap(&src, &dst, ndim, itemsize): # <<<<<<<<<<<<<< + * + * if not slice_is_contig(src, order, ndim): + */ + __pyx_t_2 = __pyx_slices_overlap((&__pyx_v_src), (&__pyx_v_dst), __pyx_v_ndim, __pyx_v_itemsize); + if (__pyx_t_2) { + + /* "View.MemoryView":1301 + * if slices_overlap(&src, &dst, ndim, itemsize): + * + * if not slice_is_contig(src, order, ndim): # <<<<<<<<<<<<<< + * order = get_best_order(&dst, ndim) + * + */ + __pyx_t_2 = (!__pyx_memviewslice_is_contig(__pyx_v_src, __pyx_v_order, __pyx_v_ndim)); + if (__pyx_t_2) { + + /* "View.MemoryView":1302 + * + * if not slice_is_contig(src, order, ndim): + * order = get_best_order(&dst, ndim) # <<<<<<<<<<<<<< + * + * tmpdata = copy_data_to_temp(&src, &tmp, order, ndim) + */ + __pyx_v_order = __pyx_get_best_slice_order((&__pyx_v_dst), __pyx_v_ndim); + + /* "View.MemoryView":1301 + * if slices_overlap(&src, &dst, ndim, itemsize): + * + * if not slice_is_contig(src, order, ndim): # <<<<<<<<<<<<<< + * order = get_best_order(&dst, ndim) + * + */ + } + + /* "View.MemoryView":1304 + * order = get_best_order(&dst, ndim) + * + * tmpdata = copy_data_to_temp(&src, &tmp, order, ndim) # <<<<<<<<<<<<<< + * src = tmp + * + */ + __pyx_t_7 = __pyx_memoryview_copy_data_to_temp((&__pyx_v_src), (&__pyx_v_tmp), __pyx_v_order, __pyx_v_ndim); if (unlikely(__pyx_t_7 == ((void *)NULL))) __PYX_ERR(0, 1304, __pyx_L1_error) + __pyx_v_tmpdata = __pyx_t_7; + + /* "View.MemoryView":1305 + * + * tmpdata = copy_data_to_temp(&src, &tmp, order, ndim) + * src = tmp # <<<<<<<<<<<<<< + * + * if not broadcasting: + */ + __pyx_v_src = __pyx_v_tmp; + + /* "View.MemoryView":1299 + * _err_dim(PyExc_ValueError, "Dimension %d is not direct", i) + * + * if slices_overlap(&src, &dst, ndim, itemsize): # <<<<<<<<<<<<<< + * + * if not slice_is_contig(src, order, ndim): + */ + } + + /* "View.MemoryView":1307 + * src = tmp + * + * if not broadcasting: # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = (!__pyx_v_broadcasting); + if (__pyx_t_2) { + + /* "View.MemoryView":1310 + * + * + * if slice_is_contig(src, 'C', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): + */ + __pyx_t_2 = __pyx_memviewslice_is_contig(__pyx_v_src, 'C', __pyx_v_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1311 + * + * if slice_is_contig(src, 'C', ndim): + * direct_copy = slice_is_contig(dst, 'C', ndim) # <<<<<<<<<<<<<< + * elif slice_is_contig(src, 'F', ndim): + * direct_copy = slice_is_contig(dst, 'F', ndim) + */ + __pyx_v_direct_copy = __pyx_memviewslice_is_contig(__pyx_v_dst, 'C', __pyx_v_ndim); + + /* "View.MemoryView":1310 + * + * + * if slice_is_contig(src, 'C', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): + */ + goto __pyx_L12; + } + + /* "View.MemoryView":1312 + * if slice_is_contig(src, 'C', ndim): + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + */ + __pyx_t_2 = __pyx_memviewslice_is_contig(__pyx_v_src, 'F', __pyx_v_ndim); + if (__pyx_t_2) { + + /* "View.MemoryView":1313 + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): + * direct_copy = slice_is_contig(dst, 'F', ndim) # <<<<<<<<<<<<<< + * + * if direct_copy: + */ + __pyx_v_direct_copy = __pyx_memviewslice_is_contig(__pyx_v_dst, 'F', __pyx_v_ndim); + + /* "View.MemoryView":1312 + * if slice_is_contig(src, 'C', ndim): + * direct_copy = slice_is_contig(dst, 'C', ndim) + * elif slice_is_contig(src, 'F', ndim): # <<<<<<<<<<<<<< + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + */ + } + __pyx_L12:; + + /* "View.MemoryView":1315 + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + * if direct_copy: # <<<<<<<<<<<<<< + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + */ + if (__pyx_v_direct_copy) { + + /* "View.MemoryView":1317 + * if direct_copy: + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) # <<<<<<<<<<<<<< + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 0); + + /* "View.MemoryView":1318 + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) # <<<<<<<<<<<<<< + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * free(tmpdata) + */ + (void)(memcpy(__pyx_v_dst.data, __pyx_v_src.data, __pyx_memoryview_slice_get_size((&__pyx_v_src), __pyx_v_ndim))); + + /* "View.MemoryView":1319 + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) # <<<<<<<<<<<<<< + * free(tmpdata) + * return 0 + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 1); + + /* "View.MemoryView":1320 + * memcpy(dst.data, src.data, slice_get_size(&src, ndim)) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * free(tmpdata) # <<<<<<<<<<<<<< + * return 0 + * + */ + free(__pyx_v_tmpdata); + + /* "View.MemoryView":1321 + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * free(tmpdata) + * return 0 # <<<<<<<<<<<<<< + * + * if order == 'F' == get_best_order(&dst, ndim): + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":1315 + * direct_copy = slice_is_contig(dst, 'F', ndim) + * + * if direct_copy: # <<<<<<<<<<<<<< + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + */ + } + + /* "View.MemoryView":1307 + * src = tmp + * + * if not broadcasting: # <<<<<<<<<<<<<< + * + * + */ + } + + /* "View.MemoryView":1323 + * return 0 + * + * if order == 'F' == get_best_order(&dst, ndim): # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_2 = (__pyx_v_order == 'F'); + if (__pyx_t_2) { + __pyx_t_2 = ('F' == __pyx_get_best_slice_order((&__pyx_v_dst), __pyx_v_ndim)); + } + if (__pyx_t_2) { + + /* "View.MemoryView":1326 + * + * + * transpose_memslice(&src) # <<<<<<<<<<<<<< + * transpose_memslice(&dst) + * + */ + __pyx_t_5 = __pyx_memslice_transpose((&__pyx_v_src)); if (unlikely(__pyx_t_5 == ((int)-1))) __PYX_ERR(0, 1326, __pyx_L1_error) + + /* "View.MemoryView":1327 + * + * transpose_memslice(&src) + * transpose_memslice(&dst) # <<<<<<<<<<<<<< + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + */ + __pyx_t_5 = __pyx_memslice_transpose((&__pyx_v_dst)); if (unlikely(__pyx_t_5 == ((int)-1))) __PYX_ERR(0, 1327, __pyx_L1_error) + + /* "View.MemoryView":1323 + * return 0 + * + * if order == 'F' == get_best_order(&dst, ndim): # <<<<<<<<<<<<<< + * + * + */ + } + + /* "View.MemoryView":1329 + * transpose_memslice(&dst) + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) # <<<<<<<<<<<<<< + * copy_strided_to_strided(&src, &dst, ndim, itemsize) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 0); + + /* "View.MemoryView":1330 + * + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * copy_strided_to_strided(&src, &dst, ndim, itemsize) # <<<<<<<<<<<<<< + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * + */ + copy_strided_to_strided((&__pyx_v_src), (&__pyx_v_dst), __pyx_v_ndim, __pyx_v_itemsize); + + /* "View.MemoryView":1331 + * refcount_copying(&dst, dtype_is_object, ndim, inc=False) + * copy_strided_to_strided(&src, &dst, ndim, itemsize) + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) # <<<<<<<<<<<<<< + * + * free(tmpdata) + */ + __pyx_memoryview_refcount_copying((&__pyx_v_dst), __pyx_v_dtype_is_object, __pyx_v_ndim, 1); + + /* "View.MemoryView":1333 + * refcount_copying(&dst, dtype_is_object, ndim, inc=True) + * + * free(tmpdata) # <<<<<<<<<<<<<< + * return 0 + * + */ + free(__pyx_v_tmpdata); + + /* "View.MemoryView":1334 + * + * free(tmpdata) + * return 0 # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_broadcast_leading') + */ + __pyx_r = 0; + goto __pyx_L0; + + /* "View.MemoryView":1265 + * + * @cname('__pyx_memoryview_copy_contents') + * cdef int memoryview_copy_contents(__Pyx_memviewslice src, # <<<<<<<<<<<<<< + * __Pyx_memviewslice dst, + * int src_ndim, int dst_ndim, + */ + + /* function exit code */ + __pyx_L1_error:; + #ifdef WITH_THREAD + __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + __Pyx_AddTraceback("View.MemoryView.memoryview_copy_contents", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif + __pyx_L0:; + return __pyx_r; +} + +/* "View.MemoryView":1337 + * + * @cname('__pyx_memoryview_broadcast_leading') + * cdef void broadcast_leading(__Pyx_memviewslice *mslice, # <<<<<<<<<<<<<< + * int ndim, + * int ndim_other) noexcept nogil: + */ + +static void __pyx_memoryview_broadcast_leading(__Pyx_memviewslice *__pyx_v_mslice, int __pyx_v_ndim, int __pyx_v_ndim_other) { + int __pyx_v_i; + int __pyx_v_offset; + int __pyx_t_1; + int __pyx_t_2; + int __pyx_t_3; + + /* "View.MemoryView":1341 + * int ndim_other) noexcept nogil: + * cdef int i + * cdef int offset = ndim_other - ndim # <<<<<<<<<<<<<< + * + * for i in range(ndim - 1, -1, -1): + */ + __pyx_v_offset = (__pyx_v_ndim_other - __pyx_v_ndim); + + /* "View.MemoryView":1343 + * cdef int offset = ndim_other - ndim + * + * for i in range(ndim - 1, -1, -1): # <<<<<<<<<<<<<< + * mslice.shape[i + offset] = mslice.shape[i] + * mslice.strides[i + offset] = mslice.strides[i] + */ + for (__pyx_t_1 = (__pyx_v_ndim - 1); __pyx_t_1 > -1; __pyx_t_1-=1) { + __pyx_v_i = __pyx_t_1; + + /* "View.MemoryView":1344 + * + * for i in range(ndim - 1, -1, -1): + * mslice.shape[i + offset] = mslice.shape[i] # <<<<<<<<<<<<<< + * mslice.strides[i + offset] = mslice.strides[i] + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] + */ + (__pyx_v_mslice->shape[(__pyx_v_i + __pyx_v_offset)]) = (__pyx_v_mslice->shape[__pyx_v_i]); + + /* "View.MemoryView":1345 + * for i in range(ndim - 1, -1, -1): + * mslice.shape[i + offset] = mslice.shape[i] + * mslice.strides[i + offset] = mslice.strides[i] # <<<<<<<<<<<<<< + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] + * + */ + (__pyx_v_mslice->strides[(__pyx_v_i + __pyx_v_offset)]) = (__pyx_v_mslice->strides[__pyx_v_i]); + + /* "View.MemoryView":1346 + * mslice.shape[i + offset] = mslice.shape[i] + * mslice.strides[i + offset] = mslice.strides[i] + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] # <<<<<<<<<<<<<< + * + * for i in range(offset): + */ + (__pyx_v_mslice->suboffsets[(__pyx_v_i + __pyx_v_offset)]) = (__pyx_v_mslice->suboffsets[__pyx_v_i]); + } + + /* "View.MemoryView":1348 + * mslice.suboffsets[i + offset] = mslice.suboffsets[i] + * + * for i in range(offset): # <<<<<<<<<<<<<< + * mslice.shape[i] = 1 + * mslice.strides[i] = mslice.strides[0] + */ + __pyx_t_1 = __pyx_v_offset; + __pyx_t_2 = __pyx_t_1; + for (__pyx_t_3 = 0; __pyx_t_3 < __pyx_t_2; __pyx_t_3+=1) { + __pyx_v_i = __pyx_t_3; + + /* "View.MemoryView":1349 + * + * for i in range(offset): + * mslice.shape[i] = 1 # <<<<<<<<<<<<<< + * mslice.strides[i] = mslice.strides[0] + * mslice.suboffsets[i] = -1 + */ + (__pyx_v_mslice->shape[__pyx_v_i]) = 1; + + /* "View.MemoryView":1350 + * for i in range(offset): + * mslice.shape[i] = 1 + * mslice.strides[i] = mslice.strides[0] # <<<<<<<<<<<<<< + * mslice.suboffsets[i] = -1 + * + */ + (__pyx_v_mslice->strides[__pyx_v_i]) = (__pyx_v_mslice->strides[0]); + + /* "View.MemoryView":1351 + * mslice.shape[i] = 1 + * mslice.strides[i] = mslice.strides[0] + * mslice.suboffsets[i] = -1 # <<<<<<<<<<<<<< + * + * + */ + (__pyx_v_mslice->suboffsets[__pyx_v_i]) = -1L; + } + + /* "View.MemoryView":1337 + * + * @cname('__pyx_memoryview_broadcast_leading') + * cdef void broadcast_leading(__Pyx_memviewslice *mslice, # <<<<<<<<<<<<<< + * int ndim, + * int ndim_other) noexcept nogil: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1359 + * + * @cname('__pyx_memoryview_refcount_copying') + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: # <<<<<<<<<<<<<< + * + * if dtype_is_object: + */ + +static void __pyx_memoryview_refcount_copying(__Pyx_memviewslice *__pyx_v_dst, int __pyx_v_dtype_is_object, int __pyx_v_ndim, int __pyx_v_inc) { + + /* "View.MemoryView":1361 + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: + * + * if dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice_with_gil(dst.data, dst.shape, dst.strides, ndim, inc) + * + */ + if (__pyx_v_dtype_is_object) { + + /* "View.MemoryView":1362 + * + * if dtype_is_object: + * refcount_objects_in_slice_with_gil(dst.data, dst.shape, dst.strides, ndim, inc) # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_refcount_objects_in_slice_with_gil') + */ + __pyx_memoryview_refcount_objects_in_slice_with_gil(__pyx_v_dst->data, __pyx_v_dst->shape, __pyx_v_dst->strides, __pyx_v_ndim, __pyx_v_inc); + + /* "View.MemoryView":1361 + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: + * + * if dtype_is_object: # <<<<<<<<<<<<<< + * refcount_objects_in_slice_with_gil(dst.data, dst.shape, dst.strides, ndim, inc) + * + */ + } + + /* "View.MemoryView":1359 + * + * @cname('__pyx_memoryview_refcount_copying') + * cdef void refcount_copying(__Pyx_memviewslice *dst, bint dtype_is_object, int ndim, bint inc) noexcept nogil: # <<<<<<<<<<<<<< + * + * if dtype_is_object: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1365 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice_with_gil') + * cdef void refcount_objects_in_slice_with_gil(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * bint inc) noexcept with gil: + */ + +static void __pyx_memoryview_refcount_objects_in_slice_with_gil(char *__pyx_v_data, Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, int __pyx_v_ndim, int __pyx_v_inc) { + #ifdef WITH_THREAD + PyGILState_STATE __pyx_gilstate_save = __Pyx_PyGILState_Ensure(); + #endif + + /* "View.MemoryView":1368 + * Py_ssize_t *strides, int ndim, + * bint inc) noexcept with gil: + * refcount_objects_in_slice(data, shape, strides, ndim, inc) # <<<<<<<<<<<<<< + * + * @cname('__pyx_memoryview_refcount_objects_in_slice') + */ + __pyx_memoryview_refcount_objects_in_slice(__pyx_v_data, __pyx_v_shape, __pyx_v_strides, __pyx_v_ndim, __pyx_v_inc); + + /* "View.MemoryView":1365 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice_with_gil') + * cdef void refcount_objects_in_slice_with_gil(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * bint inc) noexcept with gil: + */ + + /* function exit code */ + #ifdef WITH_THREAD + __Pyx_PyGILState_Release(__pyx_gilstate_save); + #endif +} + +/* "View.MemoryView":1371 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice') + * cdef void refcount_objects_in_slice(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, bint inc) noexcept: + * cdef Py_ssize_t i + */ + +static void __pyx_memoryview_refcount_objects_in_slice(char *__pyx_v_data, Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, int __pyx_v_ndim, int __pyx_v_inc) { + CYTHON_UNUSED Py_ssize_t __pyx_v_i; + Py_ssize_t __pyx_v_stride; + Py_ssize_t __pyx_t_1; + Py_ssize_t __pyx_t_2; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + + /* "View.MemoryView":1374 + * Py_ssize_t *strides, int ndim, bint inc) noexcept: + * cdef Py_ssize_t i + * cdef Py_ssize_t stride = strides[0] # <<<<<<<<<<<<<< + * + * for i in range(shape[0]): + */ + __pyx_v_stride = (__pyx_v_strides[0]); + + /* "View.MemoryView":1376 + * cdef Py_ssize_t stride = strides[0] + * + * for i in range(shape[0]): # <<<<<<<<<<<<<< + * if ndim == 1: + * if inc: + */ + __pyx_t_1 = (__pyx_v_shape[0]); + __pyx_t_2 = __pyx_t_1; + for (__pyx_t_3 = 0; __pyx_t_3 < __pyx_t_2; __pyx_t_3+=1) { + __pyx_v_i = __pyx_t_3; + + /* "View.MemoryView":1377 + * + * for i in range(shape[0]): + * if ndim == 1: # <<<<<<<<<<<<<< + * if inc: + * Py_INCREF(( data)[0]) + */ + __pyx_t_4 = (__pyx_v_ndim == 1); + if (__pyx_t_4) { + + /* "View.MemoryView":1378 + * for i in range(shape[0]): + * if ndim == 1: + * if inc: # <<<<<<<<<<<<<< + * Py_INCREF(( data)[0]) + * else: + */ + if (__pyx_v_inc) { + + /* "View.MemoryView":1379 + * if ndim == 1: + * if inc: + * Py_INCREF(( data)[0]) # <<<<<<<<<<<<<< + * else: + * Py_DECREF(( data)[0]) + */ + Py_INCREF((((PyObject **)__pyx_v_data)[0])); + + /* "View.MemoryView":1378 + * for i in range(shape[0]): + * if ndim == 1: + * if inc: # <<<<<<<<<<<<<< + * Py_INCREF(( data)[0]) + * else: + */ + goto __pyx_L6; + } + + /* "View.MemoryView":1381 + * Py_INCREF(( data)[0]) + * else: + * Py_DECREF(( data)[0]) # <<<<<<<<<<<<<< + * else: + * refcount_objects_in_slice(data, shape + 1, strides + 1, ndim - 1, inc) + */ + /*else*/ { + Py_DECREF((((PyObject **)__pyx_v_data)[0])); + } + __pyx_L6:; + + /* "View.MemoryView":1377 + * + * for i in range(shape[0]): + * if ndim == 1: # <<<<<<<<<<<<<< + * if inc: + * Py_INCREF(( data)[0]) + */ + goto __pyx_L5; + } + + /* "View.MemoryView":1383 + * Py_DECREF(( data)[0]) + * else: + * refcount_objects_in_slice(data, shape + 1, strides + 1, ndim - 1, inc) # <<<<<<<<<<<<<< + * + * data += stride + */ + /*else*/ { + __pyx_memoryview_refcount_objects_in_slice(__pyx_v_data, (__pyx_v_shape + 1), (__pyx_v_strides + 1), (__pyx_v_ndim - 1), __pyx_v_inc); + } + __pyx_L5:; + + /* "View.MemoryView":1385 + * refcount_objects_in_slice(data, shape + 1, strides + 1, ndim - 1, inc) + * + * data += stride # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_data = (__pyx_v_data + __pyx_v_stride); + } + + /* "View.MemoryView":1371 + * + * @cname('__pyx_memoryview_refcount_objects_in_slice') + * cdef void refcount_objects_in_slice(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, bint inc) noexcept: + * cdef Py_ssize_t i + */ + + /* function exit code */ +} + +/* "View.MemoryView":1391 + * + * @cname('__pyx_memoryview_slice_assign_scalar') + * cdef void slice_assign_scalar(__Pyx_memviewslice *dst, int ndim, # <<<<<<<<<<<<<< + * size_t itemsize, void *item, + * bint dtype_is_object) noexcept nogil: + */ + +static void __pyx_memoryview_slice_assign_scalar(__Pyx_memviewslice *__pyx_v_dst, int __pyx_v_ndim, size_t __pyx_v_itemsize, void *__pyx_v_item, int __pyx_v_dtype_is_object) { + + /* "View.MemoryView":1394 + * size_t itemsize, void *item, + * bint dtype_is_object) noexcept nogil: + * refcount_copying(dst, dtype_is_object, ndim, inc=False) # <<<<<<<<<<<<<< + * _slice_assign_scalar(dst.data, dst.shape, dst.strides, ndim, itemsize, item) + * refcount_copying(dst, dtype_is_object, ndim, inc=True) + */ + __pyx_memoryview_refcount_copying(__pyx_v_dst, __pyx_v_dtype_is_object, __pyx_v_ndim, 0); + + /* "View.MemoryView":1395 + * bint dtype_is_object) noexcept nogil: + * refcount_copying(dst, dtype_is_object, ndim, inc=False) + * _slice_assign_scalar(dst.data, dst.shape, dst.strides, ndim, itemsize, item) # <<<<<<<<<<<<<< + * refcount_copying(dst, dtype_is_object, ndim, inc=True) + * + */ + __pyx_memoryview__slice_assign_scalar(__pyx_v_dst->data, __pyx_v_dst->shape, __pyx_v_dst->strides, __pyx_v_ndim, __pyx_v_itemsize, __pyx_v_item); + + /* "View.MemoryView":1396 + * refcount_copying(dst, dtype_is_object, ndim, inc=False) + * _slice_assign_scalar(dst.data, dst.shape, dst.strides, ndim, itemsize, item) + * refcount_copying(dst, dtype_is_object, ndim, inc=True) # <<<<<<<<<<<<<< + * + * + */ + __pyx_memoryview_refcount_copying(__pyx_v_dst, __pyx_v_dtype_is_object, __pyx_v_ndim, 1); + + /* "View.MemoryView":1391 + * + * @cname('__pyx_memoryview_slice_assign_scalar') + * cdef void slice_assign_scalar(__Pyx_memviewslice *dst, int ndim, # <<<<<<<<<<<<<< + * size_t itemsize, void *item, + * bint dtype_is_object) noexcept nogil: + */ + + /* function exit code */ +} + +/* "View.MemoryView":1400 + * + * @cname('__pyx_memoryview__slice_assign_scalar') + * cdef void _slice_assign_scalar(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * size_t itemsize, void *item) noexcept nogil: + */ + +static void __pyx_memoryview__slice_assign_scalar(char *__pyx_v_data, Py_ssize_t *__pyx_v_shape, Py_ssize_t *__pyx_v_strides, int __pyx_v_ndim, size_t __pyx_v_itemsize, void *__pyx_v_item) { + CYTHON_UNUSED Py_ssize_t __pyx_v_i; + Py_ssize_t __pyx_v_stride; + Py_ssize_t __pyx_v_extent; + int __pyx_t_1; + Py_ssize_t __pyx_t_2; + Py_ssize_t __pyx_t_3; + Py_ssize_t __pyx_t_4; + + /* "View.MemoryView":1404 + * size_t itemsize, void *item) noexcept nogil: + * cdef Py_ssize_t i + * cdef Py_ssize_t stride = strides[0] # <<<<<<<<<<<<<< + * cdef Py_ssize_t extent = shape[0] + * + */ + __pyx_v_stride = (__pyx_v_strides[0]); + + /* "View.MemoryView":1405 + * cdef Py_ssize_t i + * cdef Py_ssize_t stride = strides[0] + * cdef Py_ssize_t extent = shape[0] # <<<<<<<<<<<<<< + * + * if ndim == 1: + */ + __pyx_v_extent = (__pyx_v_shape[0]); + + /* "View.MemoryView":1407 + * cdef Py_ssize_t extent = shape[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * for i in range(extent): + * memcpy(data, item, itemsize) + */ + __pyx_t_1 = (__pyx_v_ndim == 1); + if (__pyx_t_1) { + + /* "View.MemoryView":1408 + * + * if ndim == 1: + * for i in range(extent): # <<<<<<<<<<<<<< + * memcpy(data, item, itemsize) + * data += stride + */ + __pyx_t_2 = __pyx_v_extent; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1409 + * if ndim == 1: + * for i in range(extent): + * memcpy(data, item, itemsize) # <<<<<<<<<<<<<< + * data += stride + * else: + */ + (void)(memcpy(__pyx_v_data, __pyx_v_item, __pyx_v_itemsize)); + + /* "View.MemoryView":1410 + * for i in range(extent): + * memcpy(data, item, itemsize) + * data += stride # <<<<<<<<<<<<<< + * else: + * for i in range(extent): + */ + __pyx_v_data = (__pyx_v_data + __pyx_v_stride); + } + + /* "View.MemoryView":1407 + * cdef Py_ssize_t extent = shape[0] + * + * if ndim == 1: # <<<<<<<<<<<<<< + * for i in range(extent): + * memcpy(data, item, itemsize) + */ + goto __pyx_L3; + } + + /* "View.MemoryView":1412 + * data += stride + * else: + * for i in range(extent): # <<<<<<<<<<<<<< + * _slice_assign_scalar(data, shape + 1, strides + 1, ndim - 1, itemsize, item) + * data += stride + */ + /*else*/ { + __pyx_t_2 = __pyx_v_extent; + __pyx_t_3 = __pyx_t_2; + for (__pyx_t_4 = 0; __pyx_t_4 < __pyx_t_3; __pyx_t_4+=1) { + __pyx_v_i = __pyx_t_4; + + /* "View.MemoryView":1413 + * else: + * for i in range(extent): + * _slice_assign_scalar(data, shape + 1, strides + 1, ndim - 1, itemsize, item) # <<<<<<<<<<<<<< + * data += stride + * + */ + __pyx_memoryview__slice_assign_scalar(__pyx_v_data, (__pyx_v_shape + 1), (__pyx_v_strides + 1), (__pyx_v_ndim - 1), __pyx_v_itemsize, __pyx_v_item); + + /* "View.MemoryView":1414 + * for i in range(extent): + * _slice_assign_scalar(data, shape + 1, strides + 1, ndim - 1, itemsize, item) + * data += stride # <<<<<<<<<<<<<< + * + * + */ + __pyx_v_data = (__pyx_v_data + __pyx_v_stride); + } + } + __pyx_L3:; + + /* "View.MemoryView":1400 + * + * @cname('__pyx_memoryview__slice_assign_scalar') + * cdef void _slice_assign_scalar(char *data, Py_ssize_t *shape, # <<<<<<<<<<<<<< + * Py_ssize_t *strides, int ndim, + * size_t itemsize, void *item) noexcept nogil: + */ + + /* function exit code */ +} + +/* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_15View_dot_MemoryView_1__pyx_unpickle_Enum(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_15View_dot_MemoryView_1__pyx_unpickle_Enum = {"__pyx_unpickle_Enum", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_15View_dot_MemoryView_1__pyx_unpickle_Enum, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_15View_dot_MemoryView_1__pyx_unpickle_Enum(PyObject *__pyx_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + PyObject *__pyx_v___pyx_type = 0; + long __pyx_v___pyx_checksum; + PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[3] = {0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__pyx_unpickle_Enum (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_type,&__pyx_n_s_pyx_checksum,&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 3: values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_type)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 1, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_checksum)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 1, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle_Enum", 1, 3, 3, 1); __PYX_ERR(0, 1, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 1, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle_Enum", 1, 3, 3, 2); __PYX_ERR(0, 1, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__pyx_unpickle_Enum") < 0)) __PYX_ERR(0, 1, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 3)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + values[1] = __Pyx_Arg_FASTCALL(__pyx_args, 1); + values[2] = __Pyx_Arg_FASTCALL(__pyx_args, 2); + } + __pyx_v___pyx_type = values[0]; + __pyx_v___pyx_checksum = __Pyx_PyInt_As_long(values[1]); if (unlikely((__pyx_v___pyx_checksum == (long)-1) && PyErr_Occurred())) __PYX_ERR(0, 1, __pyx_L3_error) + __pyx_v___pyx_state = values[2]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__pyx_unpickle_Enum", 1, 3, 3, __pyx_nargs); __PYX_ERR(0, 1, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("View.MemoryView.__pyx_unpickle_Enum", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_15View_dot_MemoryView___pyx_unpickle_Enum(__pyx_self, __pyx_v___pyx_type, __pyx_v___pyx_checksum, __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_15View_dot_MemoryView___pyx_unpickle_Enum(CYTHON_UNUSED PyObject *__pyx_self, PyObject *__pyx_v___pyx_type, long __pyx_v___pyx_checksum, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_v___pyx_PickleError = 0; + PyObject *__pyx_v___pyx_result = 0; + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + int __pyx_t_5; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_unpickle_Enum", 1); + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + */ + __pyx_t_1 = __Pyx_PyInt_From_long(__pyx_v___pyx_checksum); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 4, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_t_2 = (__Pyx_PySequence_ContainsTF(__pyx_t_1, __pyx_tuple__8, Py_NE)); if (unlikely((__pyx_t_2 < 0))) __PYX_ERR(0, 4, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + if (__pyx_t_2) { + + /* "(tree fragment)":5 + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): + * from pickle import PickleError as __pyx_PickleError # <<<<<<<<<<<<<< + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) + */ + __pyx_t_1 = PyList_New(1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_n_s_PickleError); + __Pyx_GIVEREF(__pyx_n_s_PickleError); + if (__Pyx_PyList_SET_ITEM(__pyx_t_1, 0, __pyx_n_s_PickleError)) __PYX_ERR(0, 5, __pyx_L1_error); + __pyx_t_3 = __Pyx_Import(__pyx_n_s_pickle, __pyx_t_1, 0); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = __Pyx_ImportFrom(__pyx_t_3, __pyx_n_s_PickleError); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 5, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_INCREF(__pyx_t_1); + __pyx_v___pyx_PickleError = __pyx_t_1; + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + + /* "(tree fragment)":6 + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum # <<<<<<<<<<<<<< + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: + */ + __pyx_t_3 = __Pyx_PyInt_From_long(__pyx_v___pyx_checksum); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_1 = __Pyx_PyString_Format(__pyx_kp_s_Incompatible_checksums_0x_x_vs_0, __pyx_t_3); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_Raise(__pyx_v___pyx_PickleError, __pyx_t_1, 0, 0); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __PYX_ERR(0, 6, __pyx_L1_error) + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + */ + } + + /* "(tree fragment)":7 + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) # <<<<<<<<<<<<<< + * if __pyx_state is not None: + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + */ + __pyx_t_3 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_MemviewEnum_type), __pyx_n_s_new); if (unlikely(!__pyx_t_3)) __PYX_ERR(0, 7, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_3); + __pyx_t_4 = NULL; + __pyx_t_5 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_3))) { + __pyx_t_4 = PyMethod_GET_SELF(__pyx_t_3); + if (likely(__pyx_t_4)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_3); + __Pyx_INCREF(__pyx_t_4); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_3, function); + __pyx_t_5 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_4, __pyx_v___pyx_type}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_3, __pyx_callargs+1-__pyx_t_5, 1+__pyx_t_5); + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 7, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_3); __pyx_t_3 = 0; + } + __pyx_v___pyx_result = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":8 + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + */ + __pyx_t_2 = (__pyx_v___pyx_state != Py_None); + if (__pyx_t_2) { + + /* "(tree fragment)":9 + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) # <<<<<<<<<<<<<< + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + */ + if (!(likely(PyTuple_CheckExact(__pyx_v___pyx_state))||((__pyx_v___pyx_state) == Py_None) || __Pyx_RaiseUnexpectedTypeError("tuple", __pyx_v___pyx_state))) __PYX_ERR(0, 9, __pyx_L1_error) + __pyx_t_1 = __pyx_unpickle_Enum__set_state(((struct __pyx_MemviewEnum_obj *)__pyx_v___pyx_result), ((PyObject*)__pyx_v___pyx_state)); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 9, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":8 + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + * __pyx_result = Enum.__new__(__pyx_type) + * if __pyx_state is not None: # <<<<<<<<<<<<<< + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + */ + } + + /* "(tree fragment)":10 + * if __pyx_state is not None: + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result # <<<<<<<<<<<<<< + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] + */ + __Pyx_XDECREF(__pyx_r); + __Pyx_INCREF(__pyx_v___pyx_result); + __pyx_r = __pyx_v___pyx_result; + goto __pyx_L0; + + /* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_3); + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("View.MemoryView.__pyx_unpickle_Enum", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __pyx_L0:; + __Pyx_XDECREF(__pyx_v___pyx_PickleError); + __Pyx_XDECREF(__pyx_v___pyx_result); + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":11 + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): # <<<<<<<<<<<<<< + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + */ + +static PyObject *__pyx_unpickle_Enum__set_state(struct __pyx_MemviewEnum_obj *__pyx_v___pyx_result, PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_t_2; + Py_ssize_t __pyx_t_3; + int __pyx_t_4; + PyObject *__pyx_t_5 = NULL; + PyObject *__pyx_t_6 = NULL; + PyObject *__pyx_t_7 = NULL; + int __pyx_t_8; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__pyx_unpickle_Enum__set_state", 1); + + /* "(tree fragment)":12 + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] # <<<<<<<<<<<<<< + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + * __pyx_result.__dict__.update(__pyx_state[1]) + */ + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(0, 12, __pyx_L1_error) + } + __pyx_t_1 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 0, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 12, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_GIVEREF(__pyx_t_1); + __Pyx_GOTREF(__pyx_v___pyx_result->name); + __Pyx_DECREF(__pyx_v___pyx_result->name); + __pyx_v___pyx_result->name = __pyx_t_1; + __pyx_t_1 = 0; + + /* "(tree fragment)":13 + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): # <<<<<<<<<<<<<< + * __pyx_result.__dict__.update(__pyx_state[1]) + */ + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "object of type 'NoneType' has no len()"); + __PYX_ERR(0, 13, __pyx_L1_error) + } + __pyx_t_3 = __Pyx_PyTuple_GET_SIZE(__pyx_v___pyx_state); if (unlikely(__pyx_t_3 == ((Py_ssize_t)-1))) __PYX_ERR(0, 13, __pyx_L1_error) + __pyx_t_4 = (__pyx_t_3 > 1); + if (__pyx_t_4) { + } else { + __pyx_t_2 = __pyx_t_4; + goto __pyx_L4_bool_binop_done; + } + __pyx_t_4 = __Pyx_HasAttr(((PyObject *)__pyx_v___pyx_result), __pyx_n_s_dict); if (unlikely(__pyx_t_4 == ((int)-1))) __PYX_ERR(0, 13, __pyx_L1_error) + __pyx_t_2 = __pyx_t_4; + __pyx_L4_bool_binop_done:; + if (__pyx_t_2) { + + /* "(tree fragment)":14 + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + * __pyx_result.__dict__.update(__pyx_state[1]) # <<<<<<<<<<<<<< + */ + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(((PyObject *)__pyx_v___pyx_result), __pyx_n_s_dict); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_6 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_update); if (unlikely(!__pyx_t_6)) __PYX_ERR(0, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_6); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(__pyx_v___pyx_state == Py_None)) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not subscriptable"); + __PYX_ERR(0, 14, __pyx_L1_error) + } + __pyx_t_5 = __Pyx_GetItemInt_Tuple(__pyx_v___pyx_state, 1, long, 1, __Pyx_PyInt_From_long, 0, 0, 1); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_5); + __pyx_t_7 = NULL; + __pyx_t_8 = 0; + #if CYTHON_UNPACK_METHODS + if (likely(PyMethod_Check(__pyx_t_6))) { + __pyx_t_7 = PyMethod_GET_SELF(__pyx_t_6); + if (likely(__pyx_t_7)) { + PyObject* function = PyMethod_GET_FUNCTION(__pyx_t_6); + __Pyx_INCREF(__pyx_t_7); + __Pyx_INCREF(function); + __Pyx_DECREF_SET(__pyx_t_6, function); + __pyx_t_8 = 1; + } + } + #endif + { + PyObject *__pyx_callargs[2] = {__pyx_t_7, __pyx_t_5}; + __pyx_t_1 = __Pyx_PyObject_FastCall(__pyx_t_6, __pyx_callargs+1-__pyx_t_8, 1+__pyx_t_8); + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + if (unlikely(!__pyx_t_1)) __PYX_ERR(0, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __Pyx_DECREF(__pyx_t_6); __pyx_t_6 = 0; + } + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + + /* "(tree fragment)":13 + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): # <<<<<<<<<<<<<< + * __pyx_result.__dict__.update(__pyx_state[1]) + */ + } + + /* "(tree fragment)":11 + * __pyx_unpickle_Enum__set_state( __pyx_result, __pyx_state) + * return __pyx_result + * cdef __pyx_unpickle_Enum__set_state(Enum __pyx_result, tuple __pyx_state): # <<<<<<<<<<<<<< + * __pyx_result.name = __pyx_state[0] + * if len(__pyx_state) > 1 and hasattr(__pyx_result, '__dict__'): + */ + + /* function exit code */ + __pyx_r = Py_None; __Pyx_INCREF(Py_None); + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_6); + __Pyx_XDECREF(__pyx_t_7); + __Pyx_AddTraceback("View.MemoryView.__pyx_unpickle_Enum__set_state", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = 0; + __pyx_L0:; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "selfdrive/modeld/runners/thneedmodel_pyx.pyx":13 + * + * cdef class ThneedModel(RunModel): + * def __cinit__(self, string path, float[:] output, int runtime, bool use_tf8, CLContext context): # <<<<<<<<<<<<<< + * self.model = new cppThneedModel(path, &output[0], len(output), runtime, use_tf8, context.context) + */ + +/* Python wrapper */ +static int __pyx_pw_9selfdrive_6modeld_7runners_15thneedmodel_pyx_11ThneedModel_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds); /*proto*/ +static int __pyx_pw_9selfdrive_6modeld_7runners_15thneedmodel_pyx_11ThneedModel_1__cinit__(PyObject *__pyx_v_self, PyObject *__pyx_args, PyObject *__pyx_kwds) { + std::string __pyx_v_path; + __Pyx_memviewslice __pyx_v_output = { 0, 0, { 0 }, { 0 }, { 0 } }; + int __pyx_v_runtime; + bool __pyx_v_use_tf8; + struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext *__pyx_v_context = 0; + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[5] = {0,0,0,0,0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + int __pyx_r; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__cinit__ (wrapper)", 0); + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return -1; + #endif + __pyx_kwvalues = __Pyx_KwValues_VARARGS(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_path,&__pyx_n_s_output,&__pyx_n_s_runtime,&__pyx_n_s_use_tf8,&__pyx_n_s_context,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 5: values[4] = __Pyx_Arg_VARARGS(__pyx_args, 4); + CYTHON_FALLTHROUGH; + case 4: values[3] = __Pyx_Arg_VARARGS(__pyx_args, 3); + CYTHON_FALLTHROUGH; + case 3: values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + CYTHON_FALLTHROUGH; + case 2: values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + CYTHON_FALLTHROUGH; + case 1: values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_VARARGS(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_path)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 13, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + CYTHON_FALLTHROUGH; + case 1: + if (likely((values[1] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_output)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[1]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 13, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 5, 5, 1); __PYX_ERR(1, 13, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 2: + if (likely((values[2] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_runtime)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[2]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 13, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 5, 5, 2); __PYX_ERR(1, 13, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 3: + if (likely((values[3] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_use_tf8)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[3]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 13, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 5, 5, 3); __PYX_ERR(1, 13, __pyx_L3_error) + } + CYTHON_FALLTHROUGH; + case 4: + if (likely((values[4] = __Pyx_GetKwValue_VARARGS(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_context)) != 0)) { + (void)__Pyx_Arg_NewRef_VARARGS(values[4]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 13, __pyx_L3_error) + else { + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 5, 5, 4); __PYX_ERR(1, 13, __pyx_L3_error) + } + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__cinit__") < 0)) __PYX_ERR(1, 13, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 5)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_VARARGS(__pyx_args, 0); + values[1] = __Pyx_Arg_VARARGS(__pyx_args, 1); + values[2] = __Pyx_Arg_VARARGS(__pyx_args, 2); + values[3] = __Pyx_Arg_VARARGS(__pyx_args, 3); + values[4] = __Pyx_Arg_VARARGS(__pyx_args, 4); + } + __pyx_v_path = __pyx_convert_string_from_py_std__in_string(values[0]); if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 13, __pyx_L3_error) + __pyx_v_output = __Pyx_PyObject_to_MemoryviewSlice_ds_float(values[1], PyBUF_WRITABLE); if (unlikely(!__pyx_v_output.memview)) __PYX_ERR(1, 13, __pyx_L3_error) + __pyx_v_runtime = __Pyx_PyInt_As_int(values[2]); if (unlikely((__pyx_v_runtime == (int)-1) && PyErr_Occurred())) __PYX_ERR(1, 13, __pyx_L3_error) + __pyx_v_use_tf8 = __Pyx_PyObject_IsTrue(values[3]); if (unlikely((__pyx_v_use_tf8 == ((bool)-1)) && PyErr_Occurred())) __PYX_ERR(1, 13, __pyx_L3_error) + __pyx_v_context = ((struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext *)values[4]); + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__cinit__", 1, 5, 5, __pyx_nargs); __PYX_ERR(1, 13, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __PYX_XCLEAR_MEMVIEW(&__pyx_v_output, 1); + __Pyx_AddTraceback("selfdrive.modeld.runners.thneedmodel_pyx.ThneedModel.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return -1; + __pyx_L4_argument_unpacking_done:; + if (unlikely(!__Pyx_ArgTypeTest(((PyObject *)__pyx_v_context), __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext, 1, "context", 0))) __PYX_ERR(1, 13, __pyx_L1_error) + __pyx_r = __pyx_pf_9selfdrive_6modeld_7runners_15thneedmodel_pyx_11ThneedModel___cinit__(((struct __pyx_obj_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel *)__pyx_v_self), __PYX_STD_MOVE_IF_SUPPORTED(__pyx_v_path), __pyx_v_output, __pyx_v_runtime, __pyx_v_use_tf8, __pyx_v_context); + + /* function exit code */ + goto __pyx_L0; + __pyx_L1_error:; + __pyx_r = -1; + __pyx_L0:; + __PYX_XCLEAR_MEMVIEW(&__pyx_v_output, 1); + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_VARARGS(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static int __pyx_pf_9selfdrive_6modeld_7runners_15thneedmodel_pyx_11ThneedModel___cinit__(struct __pyx_obj_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel *__pyx_v_self, std::string __pyx_v_path, __Pyx_memviewslice __pyx_v_output, int __pyx_v_runtime, bool __pyx_v_use_tf8, struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext *__pyx_v_context) { + int __pyx_r; + __Pyx_RefNannyDeclarations + Py_ssize_t __pyx_t_1; + int __pyx_t_2; + Py_ssize_t __pyx_t_3; + PyObject *__pyx_t_4 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__cinit__", 1); + + /* "selfdrive/modeld/runners/thneedmodel_pyx.pyx":14 + * cdef class ThneedModel(RunModel): + * def __cinit__(self, string path, float[:] output, int runtime, bool use_tf8, CLContext context): + * self.model = new cppThneedModel(path, &output[0], len(output), runtime, use_tf8, context.context) # <<<<<<<<<<<<<< + */ + __pyx_t_1 = 0; + __pyx_t_2 = -1; + if (__pyx_t_1 < 0) { + __pyx_t_1 += __pyx_v_output.shape[0]; + if (unlikely(__pyx_t_1 < 0)) __pyx_t_2 = 0; + } else if (unlikely(__pyx_t_1 >= __pyx_v_output.shape[0])) __pyx_t_2 = 0; + if (unlikely(__pyx_t_2 != -1)) { + __Pyx_RaiseBufferIndexError(__pyx_t_2); + __PYX_ERR(1, 14, __pyx_L1_error) + } + __pyx_t_3 = __Pyx_MemoryView_Len(__pyx_v_output); + __pyx_t_4 = __Pyx_PyBool_FromLong(__pyx_v_use_tf8); if (unlikely(!__pyx_t_4)) __PYX_ERR(1, 14, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_v_self->__pyx_base.model = ((RunModel *)new ThneedModel(__pyx_v_path, (&(*((float *) ( /* dim=0 */ (__pyx_v_output.data + __pyx_t_1 * __pyx_v_output.strides[0]) )))), __pyx_t_3, __pyx_v_runtime, __pyx_t_4, __pyx_v_context->__pyx_base.context)); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "selfdrive/modeld/runners/thneedmodel_pyx.pyx":13 + * + * cdef class ThneedModel(RunModel): + * def __cinit__(self, string path, float[:] output, int runtime, bool use_tf8, CLContext context): # <<<<<<<<<<<<<< + * self.model = new cppThneedModel(path, &output[0], len(output), runtime, use_tf8, context.context) + */ + + /* function exit code */ + __pyx_r = 0; + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_AddTraceback("selfdrive.modeld.runners.thneedmodel_pyx.ThneedModel.__cinit__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = -1; + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_9selfdrive_6modeld_7runners_15thneedmodel_pyx_11ThneedModel_3__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_9selfdrive_6modeld_7runners_15thneedmodel_pyx_11ThneedModel_3__reduce_cython__ = {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_9selfdrive_6modeld_7runners_15thneedmodel_pyx_11ThneedModel_3__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_9selfdrive_6modeld_7runners_15thneedmodel_pyx_11ThneedModel_3__reduce_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__reduce_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + if (unlikely(__pyx_nargs > 0)) { + __Pyx_RaiseArgtupleInvalid("__reduce_cython__", 1, 0, 0, __pyx_nargs); return NULL;} + if (unlikely(__pyx_kwds) && __Pyx_NumKwargs_FASTCALL(__pyx_kwds) && unlikely(!__Pyx_CheckKeywordStrings(__pyx_kwds, "__reduce_cython__", 0))) return NULL; + __pyx_r = __pyx_pf_9selfdrive_6modeld_7runners_15thneedmodel_pyx_11ThneedModel_2__reduce_cython__(((struct __pyx_obj_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel *)__pyx_v_self)); + + /* function exit code */ + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_9selfdrive_6modeld_7runners_15thneedmodel_pyx_11ThneedModel_2__reduce_cython__(CYTHON_UNUSED struct __pyx_obj_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel *__pyx_v_self) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__reduce_cython__", 1); + + /* "(tree fragment)":2 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(0, 2, __pyx_L1_error) + + /* "(tree fragment)":1 + * def __reduce_cython__(self): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("selfdrive.modeld.runners.thneedmodel_pyx.ThneedModel.__reduce_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +/* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + +/* Python wrapper */ +static PyObject *__pyx_pw_9selfdrive_6modeld_7runners_15thneedmodel_pyx_11ThneedModel_5__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +); /*proto*/ +static PyMethodDef __pyx_mdef_9selfdrive_6modeld_7runners_15thneedmodel_pyx_11ThneedModel_5__setstate_cython__ = {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_9selfdrive_6modeld_7runners_15thneedmodel_pyx_11ThneedModel_5__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}; +static PyObject *__pyx_pw_9selfdrive_6modeld_7runners_15thneedmodel_pyx_11ThneedModel_5__setstate_cython__(PyObject *__pyx_v_self, +#if CYTHON_METH_FASTCALL +PyObject *const *__pyx_args, Py_ssize_t __pyx_nargs, PyObject *__pyx_kwds +#else +PyObject *__pyx_args, PyObject *__pyx_kwds +#endif +) { + CYTHON_UNUSED PyObject *__pyx_v___pyx_state = 0; + #if !CYTHON_METH_FASTCALL + CYTHON_UNUSED Py_ssize_t __pyx_nargs; + #endif + CYTHON_UNUSED PyObject *const *__pyx_kwvalues; + PyObject* values[1] = {0}; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + PyObject *__pyx_r = 0; + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__setstate_cython__ (wrapper)", 0); + #if !CYTHON_METH_FASTCALL + #if CYTHON_ASSUME_SAFE_MACROS + __pyx_nargs = PyTuple_GET_SIZE(__pyx_args); + #else + __pyx_nargs = PyTuple_Size(__pyx_args); if (unlikely(__pyx_nargs < 0)) return NULL; + #endif + #endif + __pyx_kwvalues = __Pyx_KwValues_FASTCALL(__pyx_args, __pyx_nargs); + { + PyObject **__pyx_pyargnames[] = {&__pyx_n_s_pyx_state,0}; + if (__pyx_kwds) { + Py_ssize_t kw_args; + switch (__pyx_nargs) { + case 1: values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + CYTHON_FALLTHROUGH; + case 0: break; + default: goto __pyx_L5_argtuple_error; + } + kw_args = __Pyx_NumKwargs_FASTCALL(__pyx_kwds); + switch (__pyx_nargs) { + case 0: + if (likely((values[0] = __Pyx_GetKwValue_FASTCALL(__pyx_kwds, __pyx_kwvalues, __pyx_n_s_pyx_state)) != 0)) { + (void)__Pyx_Arg_NewRef_FASTCALL(values[0]); + kw_args--; + } + else if (unlikely(PyErr_Occurred())) __PYX_ERR(0, 3, __pyx_L3_error) + else goto __pyx_L5_argtuple_error; + } + if (unlikely(kw_args > 0)) { + const Py_ssize_t kwd_pos_args = __pyx_nargs; + if (unlikely(__Pyx_ParseOptionalKeywords(__pyx_kwds, __pyx_kwvalues, __pyx_pyargnames, 0, values + 0, kwd_pos_args, "__setstate_cython__") < 0)) __PYX_ERR(0, 3, __pyx_L3_error) + } + } else if (unlikely(__pyx_nargs != 1)) { + goto __pyx_L5_argtuple_error; + } else { + values[0] = __Pyx_Arg_FASTCALL(__pyx_args, 0); + } + __pyx_v___pyx_state = values[0]; + } + goto __pyx_L6_skip; + __pyx_L5_argtuple_error:; + __Pyx_RaiseArgtupleInvalid("__setstate_cython__", 1, 1, 1, __pyx_nargs); __PYX_ERR(0, 3, __pyx_L3_error) + __pyx_L6_skip:; + goto __pyx_L4_argument_unpacking_done; + __pyx_L3_error:; + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_AddTraceback("selfdrive.modeld.runners.thneedmodel_pyx.ThneedModel.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __Pyx_RefNannyFinishContext(); + return NULL; + __pyx_L4_argument_unpacking_done:; + __pyx_r = __pyx_pf_9selfdrive_6modeld_7runners_15thneedmodel_pyx_11ThneedModel_4__setstate_cython__(((struct __pyx_obj_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel *)__pyx_v_self), __pyx_v___pyx_state); + + /* function exit code */ + { + Py_ssize_t __pyx_temp; + for (__pyx_temp=0; __pyx_temp < (Py_ssize_t)(sizeof(values)/sizeof(values[0])); ++__pyx_temp) { + __Pyx_Arg_XDECREF_FASTCALL(values[__pyx_temp]); + } + } + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_pf_9selfdrive_6modeld_7runners_15thneedmodel_pyx_11ThneedModel_4__setstate_cython__(CYTHON_UNUSED struct __pyx_obj_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel *__pyx_v_self, CYTHON_UNUSED PyObject *__pyx_v___pyx_state) { + PyObject *__pyx_r = NULL; + __Pyx_RefNannyDeclarations + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__setstate_cython__", 1); + + /* "(tree fragment)":4 + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" # <<<<<<<<<<<<<< + */ + __Pyx_Raise(__pyx_builtin_TypeError, __pyx_kp_s_no_default___reduce___due_to_non, 0, 0); + __PYX_ERR(0, 4, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + + /* function exit code */ + __pyx_L1_error:; + __Pyx_AddTraceback("selfdrive.modeld.runners.thneedmodel_pyx.ThneedModel.__setstate_cython__", __pyx_clineno, __pyx_lineno, __pyx_filename); + __pyx_r = NULL; + __Pyx_XGIVEREF(__pyx_r); + __Pyx_RefNannyFinishContext(); + return __pyx_r; +} + +static PyObject *__pyx_tp_new_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel(PyTypeObject *t, PyObject *a, PyObject *k) { + PyObject *o = __Pyx_PyType_GetSlot(__pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel, tp_new, newfunc)(t, a, k); + if (unlikely(!o)) return 0; + if (unlikely(__pyx_pw_9selfdrive_6modeld_7runners_15thneedmodel_pyx_11ThneedModel_1__cinit__(o, a, k) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static PyMethodDef __pyx_methods_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel[] = { + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_9selfdrive_6modeld_7runners_15thneedmodel_pyx_11ThneedModel_3__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw_9selfdrive_6modeld_7runners_15thneedmodel_pyx_11ThneedModel_5__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel_slots[] = { + {Py_tp_methods, (void *)__pyx_methods_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel}, + {Py_tp_new, (void *)__pyx_tp_new_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel}, + {0, 0}, +}; +static PyType_Spec __pyx_type_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel_spec = { + "selfdrive.modeld.runners.thneedmodel_pyx.ThneedModel", + sizeof(struct __pyx_obj_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_FINALIZE, + __pyx_type_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel_slots, +}; +#else + +static PyTypeObject __pyx_type_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel = { + PyVarObject_HEAD_INIT(0, 0) + "selfdrive.modeld.runners.thneedmodel_pyx.""ThneedModel", /*tp_name*/ + sizeof(struct __pyx_obj_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + 0, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_FINALIZE, /*tp_flags*/ + 0, /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif +static struct __pyx_vtabstruct_array __pyx_vtable_array; + +static PyObject *__pyx_tp_new_array(PyTypeObject *t, PyObject *a, PyObject *k) { + struct __pyx_array_obj *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_array_obj *)o); + p->__pyx_vtab = __pyx_vtabptr_array; + p->mode = ((PyObject*)Py_None); Py_INCREF(Py_None); + p->_format = ((PyObject*)Py_None); Py_INCREF(Py_None); + if (unlikely(__pyx_array___cinit__(o, a, k) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static void __pyx_tp_dealloc_array(PyObject *o) { + struct __pyx_array_obj *p = (struct __pyx_array_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && (!PyType_IS_GC(Py_TYPE(o)) || !__Pyx_PyObject_GC_IsFinalized(o))) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_array) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_array___dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + Py_CLEAR(p->mode); + Py_CLEAR(p->_format); + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} +static PyObject *__pyx_sq_item_array(PyObject *o, Py_ssize_t i) { + PyObject *r; + PyObject *x = PyInt_FromSsize_t(i); if(!x) return 0; + r = Py_TYPE(o)->tp_as_mapping->mp_subscript(o, x); + Py_DECREF(x); + return r; +} + +static int __pyx_mp_ass_subscript_array(PyObject *o, PyObject *i, PyObject *v) { + if (v) { + return __pyx_array___setitem__(o, i, v); + } + else { + __Pyx_TypeName o_type_name; + o_type_name = __Pyx_PyType_GetName(Py_TYPE(o)); + PyErr_Format(PyExc_NotImplementedError, + "Subscript deletion not supported by " __Pyx_FMT_TYPENAME, o_type_name); + __Pyx_DECREF_TypeName(o_type_name); + return -1; + } +} + +static PyObject *__pyx_tp_getattro_array(PyObject *o, PyObject *n) { + PyObject *v = __Pyx_PyObject_GenericGetAttr(o, n); + if (!v && PyErr_ExceptionMatches(PyExc_AttributeError)) { + PyErr_Clear(); + v = __pyx_array___getattr__(o, n); + } + return v; +} + +static PyObject *__pyx_getprop___pyx_array_memview(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_5array_7memview_1__get__(o); +} + +static PyMethodDef __pyx_methods_array[] = { + {"__getattr__", (PyCFunction)__pyx_array___getattr__, METH_O|METH_COEXIST, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_array_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_array_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; + +static struct PyGetSetDef __pyx_getsets_array[] = { + {(char *)"memview", __pyx_getprop___pyx_array_memview, 0, (char *)0, 0}, + {0, 0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +#if !CYTHON_COMPILING_IN_LIMITED_API + +static PyBufferProcs __pyx_tp_as_buffer_array = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_array_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; +#endif +static PyType_Slot __pyx_type___pyx_array_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_array}, + {Py_sq_length, (void *)__pyx_array___len__}, + {Py_sq_item, (void *)__pyx_sq_item_array}, + {Py_mp_length, (void *)__pyx_array___len__}, + {Py_mp_subscript, (void *)__pyx_array___getitem__}, + {Py_mp_ass_subscript, (void *)__pyx_mp_ass_subscript_array}, + {Py_tp_getattro, (void *)__pyx_tp_getattro_array}, + #if defined(Py_bf_getbuffer) + {Py_bf_getbuffer, (void *)__pyx_array_getbuffer}, + #endif + {Py_tp_methods, (void *)__pyx_methods_array}, + {Py_tp_getset, (void *)__pyx_getsets_array}, + {Py_tp_new, (void *)__pyx_tp_new_array}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_array_spec = { + "selfdrive.modeld.runners.thneedmodel_pyx.array", + sizeof(struct __pyx_array_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_SEQUENCE, + __pyx_type___pyx_array_slots, +}; +#else + +static PySequenceMethods __pyx_tp_as_sequence_array = { + __pyx_array___len__, /*sq_length*/ + 0, /*sq_concat*/ + 0, /*sq_repeat*/ + __pyx_sq_item_array, /*sq_item*/ + 0, /*sq_slice*/ + 0, /*sq_ass_item*/ + 0, /*sq_ass_slice*/ + 0, /*sq_contains*/ + 0, /*sq_inplace_concat*/ + 0, /*sq_inplace_repeat*/ +}; + +static PyMappingMethods __pyx_tp_as_mapping_array = { + __pyx_array___len__, /*mp_length*/ + __pyx_array___getitem__, /*mp_subscript*/ + __pyx_mp_ass_subscript_array, /*mp_ass_subscript*/ +}; + +static PyBufferProcs __pyx_tp_as_buffer_array = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_array_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; + +static PyTypeObject __pyx_type___pyx_array = { + PyVarObject_HEAD_INIT(0, 0) + "selfdrive.modeld.runners.thneedmodel_pyx.""array", /*tp_name*/ + sizeof(struct __pyx_array_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_array, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + 0, /*tp_repr*/ + 0, /*tp_as_number*/ + &__pyx_tp_as_sequence_array, /*tp_as_sequence*/ + &__pyx_tp_as_mapping_array, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + __pyx_tp_getattro_array, /*tp_getattro*/ + 0, /*tp_setattro*/ + &__pyx_tp_as_buffer_array, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_SEQUENCE, /*tp_flags*/ + 0, /*tp_doc*/ + 0, /*tp_traverse*/ + 0, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_array, /*tp_methods*/ + 0, /*tp_members*/ + __pyx_getsets_array, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_array, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyObject *__pyx_tp_new_Enum(PyTypeObject *t, CYTHON_UNUSED PyObject *a, CYTHON_UNUSED PyObject *k) { + struct __pyx_MemviewEnum_obj *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_MemviewEnum_obj *)o); + p->name = Py_None; Py_INCREF(Py_None); + return o; +} + +static void __pyx_tp_dealloc_Enum(PyObject *o) { + struct __pyx_MemviewEnum_obj *p = (struct __pyx_MemviewEnum_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_Enum) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + Py_CLEAR(p->name); + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} + +static int __pyx_tp_traverse_Enum(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_MemviewEnum_obj *p = (struct __pyx_MemviewEnum_obj *)o; + if (p->name) { + e = (*v)(p->name, a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear_Enum(PyObject *o) { + PyObject* tmp; + struct __pyx_MemviewEnum_obj *p = (struct __pyx_MemviewEnum_obj *)o; + tmp = ((PyObject*)p->name); + p->name = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + return 0; +} + +static PyObject *__pyx_specialmethod___pyx_MemviewEnum___repr__(PyObject *self, CYTHON_UNUSED PyObject *arg) { + return __pyx_MemviewEnum___repr__(self); +} + +static PyMethodDef __pyx_methods_Enum[] = { + {"__repr__", (PyCFunction)__pyx_specialmethod___pyx_MemviewEnum___repr__, METH_NOARGS|METH_COEXIST, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_MemviewEnum_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_MemviewEnum_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type___pyx_MemviewEnum_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_Enum}, + {Py_tp_repr, (void *)__pyx_MemviewEnum___repr__}, + {Py_tp_traverse, (void *)__pyx_tp_traverse_Enum}, + {Py_tp_clear, (void *)__pyx_tp_clear_Enum}, + {Py_tp_methods, (void *)__pyx_methods_Enum}, + {Py_tp_init, (void *)__pyx_MemviewEnum___init__}, + {Py_tp_new, (void *)__pyx_tp_new_Enum}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_MemviewEnum_spec = { + "selfdrive.modeld.runners.thneedmodel_pyx.Enum", + sizeof(struct __pyx_MemviewEnum_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, + __pyx_type___pyx_MemviewEnum_slots, +}; +#else + +static PyTypeObject __pyx_type___pyx_MemviewEnum = { + PyVarObject_HEAD_INIT(0, 0) + "selfdrive.modeld.runners.thneedmodel_pyx.""Enum", /*tp_name*/ + sizeof(struct __pyx_MemviewEnum_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_Enum, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + __pyx_MemviewEnum___repr__, /*tp_repr*/ + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + 0, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, /*tp_flags*/ + 0, /*tp_doc*/ + __pyx_tp_traverse_Enum, /*tp_traverse*/ + __pyx_tp_clear_Enum, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_Enum, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + __pyx_MemviewEnum___init__, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_Enum, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif +static struct __pyx_vtabstruct_memoryview __pyx_vtable_memoryview; + +static PyObject *__pyx_tp_new_memoryview(PyTypeObject *t, PyObject *a, PyObject *k) { + struct __pyx_memoryview_obj *p; + PyObject *o; + #if CYTHON_COMPILING_IN_LIMITED_API + allocfunc alloc_func = (allocfunc)PyType_GetSlot(t, Py_tp_alloc); + o = alloc_func(t, 0); + #else + if (likely(!__Pyx_PyType_HasFeature(t, Py_TPFLAGS_IS_ABSTRACT))) { + o = (*t->tp_alloc)(t, 0); + } else { + o = (PyObject *) PyBaseObject_Type.tp_new(t, __pyx_empty_tuple, 0); + } + if (unlikely(!o)) return 0; + #endif + p = ((struct __pyx_memoryview_obj *)o); + p->__pyx_vtab = __pyx_vtabptr_memoryview; + p->obj = Py_None; Py_INCREF(Py_None); + p->_size = Py_None; Py_INCREF(Py_None); + p->_array_interface = Py_None; Py_INCREF(Py_None); + p->view.obj = NULL; + if (unlikely(__pyx_memoryview___cinit__(o, a, k) < 0)) goto bad; + return o; + bad: + Py_DECREF(o); o = 0; + return NULL; +} + +static void __pyx_tp_dealloc_memoryview(PyObject *o) { + struct __pyx_memoryview_obj *p = (struct __pyx_memoryview_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc_memoryview) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_memoryview___dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + Py_CLEAR(p->obj); + Py_CLEAR(p->_size); + Py_CLEAR(p->_array_interface); + #if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + (*Py_TYPE(o)->tp_free)(o); + #else + { + freefunc tp_free = (freefunc)PyType_GetSlot(Py_TYPE(o), Py_tp_free); + if (tp_free) tp_free(o); + } + #endif +} + +static int __pyx_tp_traverse_memoryview(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_memoryview_obj *p = (struct __pyx_memoryview_obj *)o; + if (p->obj) { + e = (*v)(p->obj, a); if (e) return e; + } + if (p->_size) { + e = (*v)(p->_size, a); if (e) return e; + } + if (p->_array_interface) { + e = (*v)(p->_array_interface, a); if (e) return e; + } + if (p->view.obj) { + e = (*v)(p->view.obj, a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear_memoryview(PyObject *o) { + PyObject* tmp; + struct __pyx_memoryview_obj *p = (struct __pyx_memoryview_obj *)o; + tmp = ((PyObject*)p->obj); + p->obj = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + tmp = ((PyObject*)p->_size); + p->_size = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + tmp = ((PyObject*)p->_array_interface); + p->_array_interface = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + Py_CLEAR(p->view.obj); + return 0; +} +static PyObject *__pyx_sq_item_memoryview(PyObject *o, Py_ssize_t i) { + PyObject *r; + PyObject *x = PyInt_FromSsize_t(i); if(!x) return 0; + r = Py_TYPE(o)->tp_as_mapping->mp_subscript(o, x); + Py_DECREF(x); + return r; +} + +static int __pyx_mp_ass_subscript_memoryview(PyObject *o, PyObject *i, PyObject *v) { + if (v) { + return __pyx_memoryview___setitem__(o, i, v); + } + else { + __Pyx_TypeName o_type_name; + o_type_name = __Pyx_PyType_GetName(Py_TYPE(o)); + PyErr_Format(PyExc_NotImplementedError, + "Subscript deletion not supported by " __Pyx_FMT_TYPENAME, o_type_name); + __Pyx_DECREF_TypeName(o_type_name); + return -1; + } +} + +static PyObject *__pyx_getprop___pyx_memoryview_T(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_1T_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_base(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_4base_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_shape(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_5shape_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_strides(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_7strides_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_suboffsets(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_10suboffsets_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_ndim(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_4ndim_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_itemsize(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_8itemsize_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_nbytes(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_6nbytes_1__get__(o); +} + +static PyObject *__pyx_getprop___pyx_memoryview_size(PyObject *o, CYTHON_UNUSED void *x) { + return __pyx_pw_15View_dot_MemoryView_10memoryview_4size_1__get__(o); +} + +static PyObject *__pyx_specialmethod___pyx_memoryview___repr__(PyObject *self, CYTHON_UNUSED PyObject *arg) { + return __pyx_memoryview___repr__(self); +} + +static PyMethodDef __pyx_methods_memoryview[] = { + {"__repr__", (PyCFunction)__pyx_specialmethod___pyx_memoryview___repr__, METH_NOARGS|METH_COEXIST, 0}, + {"is_c_contig", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_is_c_contig, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"is_f_contig", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_is_f_contig, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"copy", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_copy, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"copy_fortran", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_memoryview_copy_fortran, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryview_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryview_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; + +static struct PyGetSetDef __pyx_getsets_memoryview[] = { + {(char *)"T", __pyx_getprop___pyx_memoryview_T, 0, (char *)0, 0}, + {(char *)"base", __pyx_getprop___pyx_memoryview_base, 0, (char *)0, 0}, + {(char *)"shape", __pyx_getprop___pyx_memoryview_shape, 0, (char *)0, 0}, + {(char *)"strides", __pyx_getprop___pyx_memoryview_strides, 0, (char *)0, 0}, + {(char *)"suboffsets", __pyx_getprop___pyx_memoryview_suboffsets, 0, (char *)0, 0}, + {(char *)"ndim", __pyx_getprop___pyx_memoryview_ndim, 0, (char *)0, 0}, + {(char *)"itemsize", __pyx_getprop___pyx_memoryview_itemsize, 0, (char *)0, 0}, + {(char *)"nbytes", __pyx_getprop___pyx_memoryview_nbytes, 0, (char *)0, 0}, + {(char *)"size", __pyx_getprop___pyx_memoryview_size, 0, (char *)0, 0}, + {0, 0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +#if !CYTHON_COMPILING_IN_LIMITED_API + +static PyBufferProcs __pyx_tp_as_buffer_memoryview = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_memoryview_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; +#endif +static PyType_Slot __pyx_type___pyx_memoryview_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc_memoryview}, + {Py_tp_repr, (void *)__pyx_memoryview___repr__}, + {Py_sq_length, (void *)__pyx_memoryview___len__}, + {Py_sq_item, (void *)__pyx_sq_item_memoryview}, + {Py_mp_length, (void *)__pyx_memoryview___len__}, + {Py_mp_subscript, (void *)__pyx_memoryview___getitem__}, + {Py_mp_ass_subscript, (void *)__pyx_mp_ass_subscript_memoryview}, + {Py_tp_str, (void *)__pyx_memoryview___str__}, + #if defined(Py_bf_getbuffer) + {Py_bf_getbuffer, (void *)__pyx_memoryview_getbuffer}, + #endif + {Py_tp_traverse, (void *)__pyx_tp_traverse_memoryview}, + {Py_tp_clear, (void *)__pyx_tp_clear_memoryview}, + {Py_tp_methods, (void *)__pyx_methods_memoryview}, + {Py_tp_getset, (void *)__pyx_getsets_memoryview}, + {Py_tp_new, (void *)__pyx_tp_new_memoryview}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_memoryview_spec = { + "selfdrive.modeld.runners.thneedmodel_pyx.memoryview", + sizeof(struct __pyx_memoryview_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, + __pyx_type___pyx_memoryview_slots, +}; +#else + +static PySequenceMethods __pyx_tp_as_sequence_memoryview = { + __pyx_memoryview___len__, /*sq_length*/ + 0, /*sq_concat*/ + 0, /*sq_repeat*/ + __pyx_sq_item_memoryview, /*sq_item*/ + 0, /*sq_slice*/ + 0, /*sq_ass_item*/ + 0, /*sq_ass_slice*/ + 0, /*sq_contains*/ + 0, /*sq_inplace_concat*/ + 0, /*sq_inplace_repeat*/ +}; + +static PyMappingMethods __pyx_tp_as_mapping_memoryview = { + __pyx_memoryview___len__, /*mp_length*/ + __pyx_memoryview___getitem__, /*mp_subscript*/ + __pyx_mp_ass_subscript_memoryview, /*mp_ass_subscript*/ +}; + +static PyBufferProcs __pyx_tp_as_buffer_memoryview = { + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getreadbuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getwritebuffer*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getsegcount*/ + #endif + #if PY_MAJOR_VERSION < 3 + 0, /*bf_getcharbuffer*/ + #endif + __pyx_memoryview_getbuffer, /*bf_getbuffer*/ + 0, /*bf_releasebuffer*/ +}; + +static PyTypeObject __pyx_type___pyx_memoryview = { + PyVarObject_HEAD_INIT(0, 0) + "selfdrive.modeld.runners.thneedmodel_pyx.""memoryview", /*tp_name*/ + sizeof(struct __pyx_memoryview_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc_memoryview, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + __pyx_memoryview___repr__, /*tp_repr*/ + 0, /*tp_as_number*/ + &__pyx_tp_as_sequence_memoryview, /*tp_as_sequence*/ + &__pyx_tp_as_mapping_memoryview, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + __pyx_memoryview___str__, /*tp_str*/ + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + &__pyx_tp_as_buffer_memoryview, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC, /*tp_flags*/ + 0, /*tp_doc*/ + __pyx_tp_traverse_memoryview, /*tp_traverse*/ + __pyx_tp_clear_memoryview, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods_memoryview, /*tp_methods*/ + 0, /*tp_members*/ + __pyx_getsets_memoryview, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new_memoryview, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif +static struct __pyx_vtabstruct__memoryviewslice __pyx_vtable__memoryviewslice; + +static PyObject *__pyx_tp_new__memoryviewslice(PyTypeObject *t, PyObject *a, PyObject *k) { + struct __pyx_memoryviewslice_obj *p; + PyObject *o = __pyx_tp_new_memoryview(t, a, k); + if (unlikely(!o)) return 0; + p = ((struct __pyx_memoryviewslice_obj *)o); + p->__pyx_base.__pyx_vtab = (struct __pyx_vtabstruct_memoryview*)__pyx_vtabptr__memoryviewslice; + new((void*)&(p->from_slice)) __Pyx_memviewslice(); + p->from_object = Py_None; Py_INCREF(Py_None); + p->from_slice.memview = NULL; + return o; +} + +static void __pyx_tp_dealloc__memoryviewslice(PyObject *o) { + struct __pyx_memoryviewslice_obj *p = (struct __pyx_memoryviewslice_obj *)o; + #if CYTHON_USE_TP_FINALIZE + if (unlikely((PY_VERSION_HEX >= 0x03080000 || __Pyx_PyType_HasFeature(Py_TYPE(o), Py_TPFLAGS_HAVE_FINALIZE)) && __Pyx_PyObject_GetSlot(o, tp_finalize, destructor)) && !__Pyx_PyObject_GC_IsFinalized(o)) { + if (__Pyx_PyObject_GetSlot(o, tp_dealloc, destructor) == __pyx_tp_dealloc__memoryviewslice) { + if (PyObject_CallFinalizerFromDealloc(o)) return; + } + } + #endif + PyObject_GC_UnTrack(o); + { + PyObject *etype, *eval, *etb; + PyErr_Fetch(&etype, &eval, &etb); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) + 1); + __pyx_memoryviewslice___dealloc__(o); + __Pyx_SET_REFCNT(o, Py_REFCNT(o) - 1); + PyErr_Restore(etype, eval, etb); + } + __Pyx_call_destructor(p->from_slice); + Py_CLEAR(p->from_object); + PyObject_GC_Track(o); + __pyx_tp_dealloc_memoryview(o); +} + +static int __pyx_tp_traverse__memoryviewslice(PyObject *o, visitproc v, void *a) { + int e; + struct __pyx_memoryviewslice_obj *p = (struct __pyx_memoryviewslice_obj *)o; + e = __pyx_tp_traverse_memoryview(o, v, a); if (e) return e; + if (p->from_object) { + e = (*v)(p->from_object, a); if (e) return e; + } + return 0; +} + +static int __pyx_tp_clear__memoryviewslice(PyObject *o) { + PyObject* tmp; + struct __pyx_memoryviewslice_obj *p = (struct __pyx_memoryviewslice_obj *)o; + __pyx_tp_clear_memoryview(o); + tmp = ((PyObject*)p->from_object); + p->from_object = Py_None; Py_INCREF(Py_None); + Py_XDECREF(tmp); + __PYX_XCLEAR_MEMVIEW(&p->from_slice, 1); + return 0; +} + +static PyMethodDef __pyx_methods__memoryviewslice[] = { + {"__reduce_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryviewslice_1__reduce_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {"__setstate_cython__", (PyCFunction)(void*)(__Pyx_PyCFunction_FastCallWithKeywords)__pyx_pw___pyx_memoryviewslice_3__setstate_cython__, __Pyx_METH_FASTCALL|METH_KEYWORDS, 0}, + {0, 0, 0, 0} +}; +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_type___pyx_memoryviewslice_slots[] = { + {Py_tp_dealloc, (void *)__pyx_tp_dealloc__memoryviewslice}, + {Py_tp_doc, (void *)PyDoc_STR("Internal class for passing memoryview slices to Python")}, + {Py_tp_traverse, (void *)__pyx_tp_traverse__memoryviewslice}, + {Py_tp_clear, (void *)__pyx_tp_clear__memoryviewslice}, + {Py_tp_methods, (void *)__pyx_methods__memoryviewslice}, + {Py_tp_new, (void *)__pyx_tp_new__memoryviewslice}, + {0, 0}, +}; +static PyType_Spec __pyx_type___pyx_memoryviewslice_spec = { + "selfdrive.modeld.runners.thneedmodel_pyx._memoryviewslice", + sizeof(struct __pyx_memoryviewslice_obj), + 0, + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_SEQUENCE, + __pyx_type___pyx_memoryviewslice_slots, +}; +#else + +static PyTypeObject __pyx_type___pyx_memoryviewslice = { + PyVarObject_HEAD_INIT(0, 0) + "selfdrive.modeld.runners.thneedmodel_pyx.""_memoryviewslice", /*tp_name*/ + sizeof(struct __pyx_memoryviewslice_obj), /*tp_basicsize*/ + 0, /*tp_itemsize*/ + __pyx_tp_dealloc__memoryviewslice, /*tp_dealloc*/ + #if PY_VERSION_HEX < 0x030800b4 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030800b4 + 0, /*tp_vectorcall_offset*/ + #endif + 0, /*tp_getattr*/ + 0, /*tp_setattr*/ + #if PY_MAJOR_VERSION < 3 + 0, /*tp_compare*/ + #endif + #if PY_MAJOR_VERSION >= 3 + 0, /*tp_as_async*/ + #endif + #if CYTHON_COMPILING_IN_PYPY || 0 + __pyx_memoryview___repr__, /*tp_repr*/ + #else + 0, /*tp_repr*/ + #endif + 0, /*tp_as_number*/ + 0, /*tp_as_sequence*/ + 0, /*tp_as_mapping*/ + 0, /*tp_hash*/ + 0, /*tp_call*/ + #if CYTHON_COMPILING_IN_PYPY || 0 + __pyx_memoryview___str__, /*tp_str*/ + #else + 0, /*tp_str*/ + #endif + 0, /*tp_getattro*/ + 0, /*tp_setattro*/ + 0, /*tp_as_buffer*/ + Py_TPFLAGS_DEFAULT|Py_TPFLAGS_HAVE_VERSION_TAG|Py_TPFLAGS_CHECKTYPES|Py_TPFLAGS_HAVE_NEWBUFFER|Py_TPFLAGS_BASETYPE|Py_TPFLAGS_HAVE_GC|Py_TPFLAGS_SEQUENCE, /*tp_flags*/ + PyDoc_STR("Internal class for passing memoryview slices to Python"), /*tp_doc*/ + __pyx_tp_traverse__memoryviewslice, /*tp_traverse*/ + __pyx_tp_clear__memoryviewslice, /*tp_clear*/ + 0, /*tp_richcompare*/ + 0, /*tp_weaklistoffset*/ + 0, /*tp_iter*/ + 0, /*tp_iternext*/ + __pyx_methods__memoryviewslice, /*tp_methods*/ + 0, /*tp_members*/ + 0, /*tp_getset*/ + 0, /*tp_base*/ + 0, /*tp_dict*/ + 0, /*tp_descr_get*/ + 0, /*tp_descr_set*/ + #if !CYTHON_USE_TYPE_SPECS + 0, /*tp_dictoffset*/ + #endif + 0, /*tp_init*/ + 0, /*tp_alloc*/ + __pyx_tp_new__memoryviewslice, /*tp_new*/ + 0, /*tp_free*/ + 0, /*tp_is_gc*/ + 0, /*tp_bases*/ + 0, /*tp_mro*/ + 0, /*tp_cache*/ + 0, /*tp_subclasses*/ + 0, /*tp_weaklist*/ + 0, /*tp_del*/ + 0, /*tp_version_tag*/ + #if PY_VERSION_HEX >= 0x030400a1 + #if CYTHON_USE_TP_FINALIZE + 0, /*tp_finalize*/ + #else + NULL, /*tp_finalize*/ + #endif + #endif + #if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, /*tp_vectorcall*/ + #endif + #if __PYX_NEED_TP_PRINT_SLOT == 1 + 0, /*tp_print*/ + #endif + #if PY_VERSION_HEX >= 0x030C0000 + 0, /*tp_watched*/ + #endif + #if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, /*tp_pypy_flags*/ + #endif +}; +#endif + +static PyMethodDef __pyx_methods[] = { + {0, 0, 0, 0} +}; +#ifndef CYTHON_SMALL_CODE +#if defined(__clang__) + #define CYTHON_SMALL_CODE +#elif defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 3)) + #define CYTHON_SMALL_CODE __attribute__((cold)) +#else + #define CYTHON_SMALL_CODE +#endif +#endif +/* #### Code section: pystring_table ### */ + +static int __Pyx_CreateStringTabAndInitStrings(void) { + __Pyx_StringTabEntry __pyx_string_tab[] = { + {&__pyx_kp_u_, __pyx_k_, sizeof(__pyx_k_), 0, 1, 0, 0}, + {&__pyx_n_s_ASCII, __pyx_k_ASCII, sizeof(__pyx_k_ASCII), 0, 0, 1, 1}, + {&__pyx_kp_s_All_dimensions_preceding_dimensi, __pyx_k_All_dimensions_preceding_dimensi, sizeof(__pyx_k_All_dimensions_preceding_dimensi), 0, 0, 1, 0}, + {&__pyx_n_s_AssertionError, __pyx_k_AssertionError, sizeof(__pyx_k_AssertionError), 0, 0, 1, 1}, + {&__pyx_kp_s_Buffer_view_does_not_expose_stri, __pyx_k_Buffer_view_does_not_expose_stri, sizeof(__pyx_k_Buffer_view_does_not_expose_stri), 0, 0, 1, 0}, + {&__pyx_kp_s_Can_only_create_a_buffer_that_is, __pyx_k_Can_only_create_a_buffer_that_is, sizeof(__pyx_k_Can_only_create_a_buffer_that_is), 0, 0, 1, 0}, + {&__pyx_kp_s_Cannot_assign_to_read_only_memor, __pyx_k_Cannot_assign_to_read_only_memor, sizeof(__pyx_k_Cannot_assign_to_read_only_memor), 0, 0, 1, 0}, + {&__pyx_kp_s_Cannot_create_writable_memory_vi, __pyx_k_Cannot_create_writable_memory_vi, sizeof(__pyx_k_Cannot_create_writable_memory_vi), 0, 0, 1, 0}, + {&__pyx_kp_u_Cannot_index_with_type, __pyx_k_Cannot_index_with_type, sizeof(__pyx_k_Cannot_index_with_type), 0, 1, 0, 0}, + {&__pyx_kp_s_Cannot_transpose_memoryview_with, __pyx_k_Cannot_transpose_memoryview_with, sizeof(__pyx_k_Cannot_transpose_memoryview_with), 0, 0, 1, 0}, + {&__pyx_kp_s_Dimension_d_is_not_direct, __pyx_k_Dimension_d_is_not_direct, sizeof(__pyx_k_Dimension_d_is_not_direct), 0, 0, 1, 0}, + {&__pyx_n_s_Ellipsis, __pyx_k_Ellipsis, sizeof(__pyx_k_Ellipsis), 0, 0, 1, 1}, + {&__pyx_kp_s_Empty_shape_tuple_for_cython_arr, __pyx_k_Empty_shape_tuple_for_cython_arr, sizeof(__pyx_k_Empty_shape_tuple_for_cython_arr), 0, 0, 1, 0}, + {&__pyx_kp_s_Incompatible_checksums_0x_x_vs_0, __pyx_k_Incompatible_checksums_0x_x_vs_0, sizeof(__pyx_k_Incompatible_checksums_0x_x_vs_0), 0, 0, 1, 0}, + {&__pyx_n_s_IndexError, __pyx_k_IndexError, sizeof(__pyx_k_IndexError), 0, 0, 1, 1}, + {&__pyx_kp_s_Index_out_of_bounds_axis_d, __pyx_k_Index_out_of_bounds_axis_d, sizeof(__pyx_k_Index_out_of_bounds_axis_d), 0, 0, 1, 0}, + {&__pyx_kp_s_Indirect_dimensions_not_supporte, __pyx_k_Indirect_dimensions_not_supporte, sizeof(__pyx_k_Indirect_dimensions_not_supporte), 0, 0, 1, 0}, + {&__pyx_kp_u_Invalid_mode_expected_c_or_fortr, __pyx_k_Invalid_mode_expected_c_or_fortr, sizeof(__pyx_k_Invalid_mode_expected_c_or_fortr), 0, 1, 0, 0}, + {&__pyx_kp_u_Invalid_shape_in_axis, __pyx_k_Invalid_shape_in_axis, sizeof(__pyx_k_Invalid_shape_in_axis), 0, 1, 0, 0}, + {&__pyx_n_s_MemoryError, __pyx_k_MemoryError, sizeof(__pyx_k_MemoryError), 0, 0, 1, 1}, + {&__pyx_kp_s_MemoryView_of_r_at_0x_x, __pyx_k_MemoryView_of_r_at_0x_x, sizeof(__pyx_k_MemoryView_of_r_at_0x_x), 0, 0, 1, 0}, + {&__pyx_kp_s_MemoryView_of_r_object, __pyx_k_MemoryView_of_r_object, sizeof(__pyx_k_MemoryView_of_r_object), 0, 0, 1, 0}, + {&__pyx_n_b_O, __pyx_k_O, sizeof(__pyx_k_O), 0, 0, 0, 1}, + {&__pyx_kp_u_Out_of_bounds_on_buffer_access_a, __pyx_k_Out_of_bounds_on_buffer_access_a, sizeof(__pyx_k_Out_of_bounds_on_buffer_access_a), 0, 1, 0, 0}, + {&__pyx_n_s_PickleError, __pyx_k_PickleError, sizeof(__pyx_k_PickleError), 0, 0, 1, 1}, + {&__pyx_n_s_Sequence, __pyx_k_Sequence, sizeof(__pyx_k_Sequence), 0, 0, 1, 1}, + {&__pyx_kp_s_Step_may_not_be_zero_axis_d, __pyx_k_Step_may_not_be_zero_axis_d, sizeof(__pyx_k_Step_may_not_be_zero_axis_d), 0, 0, 1, 0}, + {&__pyx_n_s_ThneedModel, __pyx_k_ThneedModel, sizeof(__pyx_k_ThneedModel), 0, 0, 1, 1}, + {&__pyx_n_s_ThneedModel___reduce_cython, __pyx_k_ThneedModel___reduce_cython, sizeof(__pyx_k_ThneedModel___reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_ThneedModel___setstate_cython, __pyx_k_ThneedModel___setstate_cython, sizeof(__pyx_k_ThneedModel___setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_TypeError, __pyx_k_TypeError, sizeof(__pyx_k_TypeError), 0, 0, 1, 1}, + {&__pyx_kp_s_Unable_to_convert_item_to_object, __pyx_k_Unable_to_convert_item_to_object, sizeof(__pyx_k_Unable_to_convert_item_to_object), 0, 0, 1, 0}, + {&__pyx_n_s_ValueError, __pyx_k_ValueError, sizeof(__pyx_k_ValueError), 0, 0, 1, 1}, + {&__pyx_n_s_View_MemoryView, __pyx_k_View_MemoryView, sizeof(__pyx_k_View_MemoryView), 0, 0, 1, 1}, + {&__pyx_kp_u__2, __pyx_k__2, sizeof(__pyx_k__2), 0, 1, 0, 0}, + {&__pyx_n_s__24, __pyx_k__24, sizeof(__pyx_k__24), 0, 0, 1, 1}, + {&__pyx_n_s__3, __pyx_k__3, sizeof(__pyx_k__3), 0, 0, 1, 1}, + {&__pyx_kp_u__6, __pyx_k__6, sizeof(__pyx_k__6), 0, 1, 0, 0}, + {&__pyx_kp_u__7, __pyx_k__7, sizeof(__pyx_k__7), 0, 1, 0, 0}, + {&__pyx_n_s_abc, __pyx_k_abc, sizeof(__pyx_k_abc), 0, 0, 1, 1}, + {&__pyx_n_s_allocate_buffer, __pyx_k_allocate_buffer, sizeof(__pyx_k_allocate_buffer), 0, 0, 1, 1}, + {&__pyx_kp_u_and, __pyx_k_and, sizeof(__pyx_k_and), 0, 1, 0, 0}, + {&__pyx_n_s_asyncio_coroutines, __pyx_k_asyncio_coroutines, sizeof(__pyx_k_asyncio_coroutines), 0, 0, 1, 1}, + {&__pyx_n_s_base, __pyx_k_base, sizeof(__pyx_k_base), 0, 0, 1, 1}, + {&__pyx_n_s_c, __pyx_k_c, sizeof(__pyx_k_c), 0, 0, 1, 1}, + {&__pyx_n_u_c, __pyx_k_c, sizeof(__pyx_k_c), 0, 1, 0, 1}, + {&__pyx_n_s_class, __pyx_k_class, sizeof(__pyx_k_class), 0, 0, 1, 1}, + {&__pyx_n_s_class_getitem, __pyx_k_class_getitem, sizeof(__pyx_k_class_getitem), 0, 0, 1, 1}, + {&__pyx_n_s_cline_in_traceback, __pyx_k_cline_in_traceback, sizeof(__pyx_k_cline_in_traceback), 0, 0, 1, 1}, + {&__pyx_n_s_collections, __pyx_k_collections, sizeof(__pyx_k_collections), 0, 0, 1, 1}, + {&__pyx_kp_s_collections_abc, __pyx_k_collections_abc, sizeof(__pyx_k_collections_abc), 0, 0, 1, 0}, + {&__pyx_n_s_context, __pyx_k_context, sizeof(__pyx_k_context), 0, 0, 1, 1}, + {&__pyx_kp_s_contiguous_and_direct, __pyx_k_contiguous_and_direct, sizeof(__pyx_k_contiguous_and_direct), 0, 0, 1, 0}, + {&__pyx_kp_s_contiguous_and_indirect, __pyx_k_contiguous_and_indirect, sizeof(__pyx_k_contiguous_and_indirect), 0, 0, 1, 0}, + {&__pyx_n_s_count, __pyx_k_count, sizeof(__pyx_k_count), 0, 0, 1, 1}, + {&__pyx_n_s_dict, __pyx_k_dict, sizeof(__pyx_k_dict), 0, 0, 1, 1}, + {&__pyx_kp_u_disable, __pyx_k_disable, sizeof(__pyx_k_disable), 0, 1, 0, 0}, + {&__pyx_n_s_dtype_is_object, __pyx_k_dtype_is_object, sizeof(__pyx_k_dtype_is_object), 0, 0, 1, 1}, + {&__pyx_kp_u_enable, __pyx_k_enable, sizeof(__pyx_k_enable), 0, 1, 0, 0}, + {&__pyx_n_s_encode, __pyx_k_encode, sizeof(__pyx_k_encode), 0, 0, 1, 1}, + {&__pyx_n_s_enumerate, __pyx_k_enumerate, sizeof(__pyx_k_enumerate), 0, 0, 1, 1}, + {&__pyx_n_s_error, __pyx_k_error, sizeof(__pyx_k_error), 0, 0, 1, 1}, + {&__pyx_n_s_flags, __pyx_k_flags, sizeof(__pyx_k_flags), 0, 0, 1, 1}, + {&__pyx_n_s_format, __pyx_k_format, sizeof(__pyx_k_format), 0, 0, 1, 1}, + {&__pyx_n_s_fortran, __pyx_k_fortran, sizeof(__pyx_k_fortran), 0, 0, 1, 1}, + {&__pyx_n_u_fortran, __pyx_k_fortran, sizeof(__pyx_k_fortran), 0, 1, 0, 1}, + {&__pyx_kp_u_gc, __pyx_k_gc, sizeof(__pyx_k_gc), 0, 1, 0, 0}, + {&__pyx_n_s_getstate, __pyx_k_getstate, sizeof(__pyx_k_getstate), 0, 0, 1, 1}, + {&__pyx_kp_u_got, __pyx_k_got, sizeof(__pyx_k_got), 0, 1, 0, 0}, + {&__pyx_kp_u_got_differing_extents_in_dimensi, __pyx_k_got_differing_extents_in_dimensi, sizeof(__pyx_k_got_differing_extents_in_dimensi), 0, 1, 0, 0}, + {&__pyx_n_s_id, __pyx_k_id, sizeof(__pyx_k_id), 0, 0, 1, 1}, + {&__pyx_n_s_import, __pyx_k_import, sizeof(__pyx_k_import), 0, 0, 1, 1}, + {&__pyx_n_s_index, __pyx_k_index, sizeof(__pyx_k_index), 0, 0, 1, 1}, + {&__pyx_n_s_initializing, __pyx_k_initializing, sizeof(__pyx_k_initializing), 0, 0, 1, 1}, + {&__pyx_n_s_is_coroutine, __pyx_k_is_coroutine, sizeof(__pyx_k_is_coroutine), 0, 0, 1, 1}, + {&__pyx_kp_u_isenabled, __pyx_k_isenabled, sizeof(__pyx_k_isenabled), 0, 1, 0, 0}, + {&__pyx_n_s_itemsize, __pyx_k_itemsize, sizeof(__pyx_k_itemsize), 0, 0, 1, 1}, + {&__pyx_kp_s_itemsize_0_for_cython_array, __pyx_k_itemsize_0_for_cython_array, sizeof(__pyx_k_itemsize_0_for_cython_array), 0, 0, 1, 0}, + {&__pyx_n_s_main, __pyx_k_main, sizeof(__pyx_k_main), 0, 0, 1, 1}, + {&__pyx_n_s_memview, __pyx_k_memview, sizeof(__pyx_k_memview), 0, 0, 1, 1}, + {&__pyx_n_s_mode, __pyx_k_mode, sizeof(__pyx_k_mode), 0, 0, 1, 1}, + {&__pyx_n_s_name, __pyx_k_name, sizeof(__pyx_k_name), 0, 0, 1, 1}, + {&__pyx_n_s_name_2, __pyx_k_name_2, sizeof(__pyx_k_name_2), 0, 0, 1, 1}, + {&__pyx_n_s_ndim, __pyx_k_ndim, sizeof(__pyx_k_ndim), 0, 0, 1, 1}, + {&__pyx_n_s_new, __pyx_k_new, sizeof(__pyx_k_new), 0, 0, 1, 1}, + {&__pyx_kp_s_no_default___reduce___due_to_non, __pyx_k_no_default___reduce___due_to_non, sizeof(__pyx_k_no_default___reduce___due_to_non), 0, 0, 1, 0}, + {&__pyx_n_s_obj, __pyx_k_obj, sizeof(__pyx_k_obj), 0, 0, 1, 1}, + {&__pyx_n_s_output, __pyx_k_output, sizeof(__pyx_k_output), 0, 0, 1, 1}, + {&__pyx_n_s_pack, __pyx_k_pack, sizeof(__pyx_k_pack), 0, 0, 1, 1}, + {&__pyx_n_s_path, __pyx_k_path, sizeof(__pyx_k_path), 0, 0, 1, 1}, + {&__pyx_n_s_pickle, __pyx_k_pickle, sizeof(__pyx_k_pickle), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_PickleError, __pyx_k_pyx_PickleError, sizeof(__pyx_k_pyx_PickleError), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_checksum, __pyx_k_pyx_checksum, sizeof(__pyx_k_pyx_checksum), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_result, __pyx_k_pyx_result, sizeof(__pyx_k_pyx_result), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_state, __pyx_k_pyx_state, sizeof(__pyx_k_pyx_state), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_type, __pyx_k_pyx_type, sizeof(__pyx_k_pyx_type), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_unpickle_Enum, __pyx_k_pyx_unpickle_Enum, sizeof(__pyx_k_pyx_unpickle_Enum), 0, 0, 1, 1}, + {&__pyx_n_s_pyx_vtable, __pyx_k_pyx_vtable, sizeof(__pyx_k_pyx_vtable), 0, 0, 1, 1}, + {&__pyx_n_s_range, __pyx_k_range, sizeof(__pyx_k_range), 0, 0, 1, 1}, + {&__pyx_n_s_reduce, __pyx_k_reduce, sizeof(__pyx_k_reduce), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_cython, __pyx_k_reduce_cython, sizeof(__pyx_k_reduce_cython), 0, 0, 1, 1}, + {&__pyx_n_s_reduce_ex, __pyx_k_reduce_ex, sizeof(__pyx_k_reduce_ex), 0, 0, 1, 1}, + {&__pyx_n_s_register, __pyx_k_register, sizeof(__pyx_k_register), 0, 0, 1, 1}, + {&__pyx_n_s_runtime, __pyx_k_runtime, sizeof(__pyx_k_runtime), 0, 0, 1, 1}, + {&__pyx_n_s_self, __pyx_k_self, sizeof(__pyx_k_self), 0, 0, 1, 1}, + {&__pyx_n_s_selfdrive_modeld_runners_thneedm, __pyx_k_selfdrive_modeld_runners_thneedm, sizeof(__pyx_k_selfdrive_modeld_runners_thneedm), 0, 0, 1, 1}, + {&__pyx_n_s_setstate, __pyx_k_setstate, sizeof(__pyx_k_setstate), 0, 0, 1, 1}, + {&__pyx_n_s_setstate_cython, __pyx_k_setstate_cython, sizeof(__pyx_k_setstate_cython), 0, 0, 1, 1}, + {&__pyx_n_s_shape, __pyx_k_shape, sizeof(__pyx_k_shape), 0, 0, 1, 1}, + {&__pyx_n_s_size, __pyx_k_size, sizeof(__pyx_k_size), 0, 0, 1, 1}, + {&__pyx_n_s_spec, __pyx_k_spec, sizeof(__pyx_k_spec), 0, 0, 1, 1}, + {&__pyx_n_s_start, __pyx_k_start, sizeof(__pyx_k_start), 0, 0, 1, 1}, + {&__pyx_n_s_step, __pyx_k_step, sizeof(__pyx_k_step), 0, 0, 1, 1}, + {&__pyx_n_s_stop, __pyx_k_stop, sizeof(__pyx_k_stop), 0, 0, 1, 1}, + {&__pyx_kp_s_strided_and_direct, __pyx_k_strided_and_direct, sizeof(__pyx_k_strided_and_direct), 0, 0, 1, 0}, + {&__pyx_kp_s_strided_and_direct_or_indirect, __pyx_k_strided_and_direct_or_indirect, sizeof(__pyx_k_strided_and_direct_or_indirect), 0, 0, 1, 0}, + {&__pyx_kp_s_strided_and_indirect, __pyx_k_strided_and_indirect, sizeof(__pyx_k_strided_and_indirect), 0, 0, 1, 0}, + {&__pyx_kp_s_stringsource, __pyx_k_stringsource, sizeof(__pyx_k_stringsource), 0, 0, 1, 0}, + {&__pyx_n_s_struct, __pyx_k_struct, sizeof(__pyx_k_struct), 0, 0, 1, 1}, + {&__pyx_n_s_sys, __pyx_k_sys, sizeof(__pyx_k_sys), 0, 0, 1, 1}, + {&__pyx_n_s_test, __pyx_k_test, sizeof(__pyx_k_test), 0, 0, 1, 1}, + {&__pyx_kp_s_unable_to_allocate_array_data, __pyx_k_unable_to_allocate_array_data, sizeof(__pyx_k_unable_to_allocate_array_data), 0, 0, 1, 0}, + {&__pyx_kp_s_unable_to_allocate_shape_and_str, __pyx_k_unable_to_allocate_shape_and_str, sizeof(__pyx_k_unable_to_allocate_shape_and_str), 0, 0, 1, 0}, + {&__pyx_n_s_unpack, __pyx_k_unpack, sizeof(__pyx_k_unpack), 0, 0, 1, 1}, + {&__pyx_n_s_update, __pyx_k_update, sizeof(__pyx_k_update), 0, 0, 1, 1}, + {&__pyx_n_s_use_tf8, __pyx_k_use_tf8, sizeof(__pyx_k_use_tf8), 0, 0, 1, 1}, + {&__pyx_n_s_version_info, __pyx_k_version_info, sizeof(__pyx_k_version_info), 0, 0, 1, 1}, + {0, 0, 0, 0, 0, 0, 0} + }; + return __Pyx_InitStrings(__pyx_string_tab); +} +/* #### Code section: cached_builtins ### */ +static CYTHON_SMALL_CODE int __Pyx_InitCachedBuiltins(void) { + __pyx_builtin_TypeError = __Pyx_GetBuiltinName(__pyx_n_s_TypeError); if (!__pyx_builtin_TypeError) __PYX_ERR(0, 2, __pyx_L1_error) + __pyx_builtin___import__ = __Pyx_GetBuiltinName(__pyx_n_s_import); if (!__pyx_builtin___import__) __PYX_ERR(0, 100, __pyx_L1_error) + __pyx_builtin_ValueError = __Pyx_GetBuiltinName(__pyx_n_s_ValueError); if (!__pyx_builtin_ValueError) __PYX_ERR(0, 141, __pyx_L1_error) + __pyx_builtin_MemoryError = __Pyx_GetBuiltinName(__pyx_n_s_MemoryError); if (!__pyx_builtin_MemoryError) __PYX_ERR(0, 156, __pyx_L1_error) + __pyx_builtin_enumerate = __Pyx_GetBuiltinName(__pyx_n_s_enumerate); if (!__pyx_builtin_enumerate) __PYX_ERR(0, 159, __pyx_L1_error) + __pyx_builtin_range = __Pyx_GetBuiltinName(__pyx_n_s_range); if (!__pyx_builtin_range) __PYX_ERR(0, 261, __pyx_L1_error) + __pyx_builtin_AssertionError = __Pyx_GetBuiltinName(__pyx_n_s_AssertionError); if (!__pyx_builtin_AssertionError) __PYX_ERR(0, 373, __pyx_L1_error) + __pyx_builtin_Ellipsis = __Pyx_GetBuiltinName(__pyx_n_s_Ellipsis); if (!__pyx_builtin_Ellipsis) __PYX_ERR(0, 408, __pyx_L1_error) + __pyx_builtin_id = __Pyx_GetBuiltinName(__pyx_n_s_id); if (!__pyx_builtin_id) __PYX_ERR(0, 618, __pyx_L1_error) + __pyx_builtin_IndexError = __Pyx_GetBuiltinName(__pyx_n_s_IndexError); if (!__pyx_builtin_IndexError) __PYX_ERR(0, 914, __pyx_L1_error) + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: cached_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitCachedConstants(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_InitCachedConstants", 0); + + /* "View.MemoryView":582 + * def suboffsets(self): + * if self.view.suboffsets == NULL: + * return (-1,) * self.view.ndim # <<<<<<<<<<<<<< + * + * return tuple([suboffset for suboffset in self.view.suboffsets[:self.view.ndim]]) + */ + __pyx_tuple__4 = PyTuple_New(1); if (unlikely(!__pyx_tuple__4)) __PYX_ERR(0, 582, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__4); + __Pyx_INCREF(__pyx_int_neg_1); + __Pyx_GIVEREF(__pyx_int_neg_1); + if (__Pyx_PyTuple_SET_ITEM(__pyx_tuple__4, 0, __pyx_int_neg_1)) __PYX_ERR(0, 582, __pyx_L1_error); + __Pyx_GIVEREF(__pyx_tuple__4); + + /* "View.MemoryView":679 + * tup = index if isinstance(index, tuple) else (index,) + * + * result = [slice(None)] * ndim # <<<<<<<<<<<<<< + * have_slices = False + * seen_ellipsis = False + */ + __pyx_slice__5 = PySlice_New(Py_None, Py_None, Py_None); if (unlikely(!__pyx_slice__5)) __PYX_ERR(0, 679, __pyx_L1_error) + __Pyx_GOTREF(__pyx_slice__5); + __Pyx_GIVEREF(__pyx_slice__5); + + /* "(tree fragment)":4 + * cdef object __pyx_PickleError + * cdef object __pyx_result + * if __pyx_checksum not in (0x82a3537, 0x6ae9995, 0xb068931): # <<<<<<<<<<<<<< + * from pickle import PickleError as __pyx_PickleError + * raise __pyx_PickleError, "Incompatible checksums (0x%x vs (0x82a3537, 0x6ae9995, 0xb068931) = (name))" % __pyx_checksum + */ + __pyx_tuple__8 = PyTuple_Pack(3, __pyx_int_136983863, __pyx_int_112105877, __pyx_int_184977713); if (unlikely(!__pyx_tuple__8)) __PYX_ERR(0, 4, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__8); + __Pyx_GIVEREF(__pyx_tuple__8); + + /* "View.MemoryView":100 + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: + * if __import__("sys").version_info >= (3, 3): # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + */ + __pyx_tuple__9 = PyTuple_Pack(1, __pyx_n_s_sys); if (unlikely(!__pyx_tuple__9)) __PYX_ERR(0, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__9); + __Pyx_GIVEREF(__pyx_tuple__9); + __pyx_tuple__10 = PyTuple_Pack(2, __pyx_int_3, __pyx_int_3); if (unlikely(!__pyx_tuple__10)) __PYX_ERR(0, 100, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__10); + __Pyx_GIVEREF(__pyx_tuple__10); + + /* "View.MemoryView":101 + * try: + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence # <<<<<<<<<<<<<< + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence + */ + __pyx_tuple__11 = PyTuple_Pack(1, __pyx_kp_s_collections_abc); if (unlikely(!__pyx_tuple__11)) __PYX_ERR(0, 101, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__11); + __Pyx_GIVEREF(__pyx_tuple__11); + + /* "View.MemoryView":103 + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence # <<<<<<<<<<<<<< + * except: + * + */ + __pyx_tuple__12 = PyTuple_Pack(1, __pyx_n_s_collections); if (unlikely(!__pyx_tuple__12)) __PYX_ERR(0, 103, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__12); + __Pyx_GIVEREF(__pyx_tuple__12); + + /* "View.MemoryView":309 + * return self.name + * + * cdef generic = Enum("") # <<<<<<<<<<<<<< + * cdef strided = Enum("") # default + * cdef indirect = Enum("") + */ + __pyx_tuple__13 = PyTuple_Pack(1, __pyx_kp_s_strided_and_direct_or_indirect); if (unlikely(!__pyx_tuple__13)) __PYX_ERR(0, 309, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__13); + __Pyx_GIVEREF(__pyx_tuple__13); + + /* "View.MemoryView":310 + * + * cdef generic = Enum("") + * cdef strided = Enum("") # default # <<<<<<<<<<<<<< + * cdef indirect = Enum("") + * + */ + __pyx_tuple__14 = PyTuple_Pack(1, __pyx_kp_s_strided_and_direct); if (unlikely(!__pyx_tuple__14)) __PYX_ERR(0, 310, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__14); + __Pyx_GIVEREF(__pyx_tuple__14); + + /* "View.MemoryView":311 + * cdef generic = Enum("") + * cdef strided = Enum("") # default + * cdef indirect = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_tuple__15 = PyTuple_Pack(1, __pyx_kp_s_strided_and_indirect); if (unlikely(!__pyx_tuple__15)) __PYX_ERR(0, 311, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__15); + __Pyx_GIVEREF(__pyx_tuple__15); + + /* "View.MemoryView":314 + * + * + * cdef contiguous = Enum("") # <<<<<<<<<<<<<< + * cdef indirect_contiguous = Enum("") + * + */ + __pyx_tuple__16 = PyTuple_Pack(1, __pyx_kp_s_contiguous_and_direct); if (unlikely(!__pyx_tuple__16)) __PYX_ERR(0, 314, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__16); + __Pyx_GIVEREF(__pyx_tuple__16); + + /* "View.MemoryView":315 + * + * cdef contiguous = Enum("") + * cdef indirect_contiguous = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_tuple__17 = PyTuple_Pack(1, __pyx_kp_s_contiguous_and_indirect); if (unlikely(!__pyx_tuple__17)) __PYX_ERR(0, 315, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__17); + __Pyx_GIVEREF(__pyx_tuple__17); + + /* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + __pyx_tuple__18 = PyTuple_Pack(5, __pyx_n_s_pyx_type, __pyx_n_s_pyx_checksum, __pyx_n_s_pyx_state, __pyx_n_s_pyx_PickleError, __pyx_n_s_pyx_result); if (unlikely(!__pyx_tuple__18)) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__18); + __Pyx_GIVEREF(__pyx_tuple__18); + __pyx_codeobj__19 = (PyObject*)__Pyx_PyCode_New(3, 0, 0, 5, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__18, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_pyx_unpickle_Enum, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__19)) __PYX_ERR(0, 1, __pyx_L1_error) + __pyx_tuple__20 = PyTuple_Pack(1, __pyx_n_s_self); if (unlikely(!__pyx_tuple__20)) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__20); + __Pyx_GIVEREF(__pyx_tuple__20); + __pyx_codeobj__21 = (PyObject*)__Pyx_PyCode_New(1, 0, 0, 1, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__20, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_reduce_cython, 1, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__21)) __PYX_ERR(0, 1, __pyx_L1_error) + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_tuple__22 = PyTuple_Pack(2, __pyx_n_s_self, __pyx_n_s_pyx_state); if (unlikely(!__pyx_tuple__22)) __PYX_ERR(0, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_tuple__22); + __Pyx_GIVEREF(__pyx_tuple__22); + __pyx_codeobj__23 = (PyObject*)__Pyx_PyCode_New(2, 0, 0, 2, 0, CO_OPTIMIZED|CO_NEWLOCALS, __pyx_empty_bytes, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_tuple__22, __pyx_empty_tuple, __pyx_empty_tuple, __pyx_kp_s_stringsource, __pyx_n_s_setstate_cython, 3, __pyx_empty_bytes); if (unlikely(!__pyx_codeobj__23)) __PYX_ERR(0, 3, __pyx_L1_error) + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_RefNannyFinishContext(); + return -1; +} +/* #### Code section: init_constants ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitConstants(void) { + if (__Pyx_CreateStringTabAndInitStrings() < 0) __PYX_ERR(1, 1, __pyx_L1_error); + __pyx_int_0 = PyInt_FromLong(0); if (unlikely(!__pyx_int_0)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_int_1 = PyInt_FromLong(1); if (unlikely(!__pyx_int_1)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_int_3 = PyInt_FromLong(3); if (unlikely(!__pyx_int_3)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_int_112105877 = PyInt_FromLong(112105877L); if (unlikely(!__pyx_int_112105877)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_int_136983863 = PyInt_FromLong(136983863L); if (unlikely(!__pyx_int_136983863)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_int_184977713 = PyInt_FromLong(184977713L); if (unlikely(!__pyx_int_184977713)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_int_neg_1 = PyInt_FromLong(-1); if (unlikely(!__pyx_int_neg_1)) __PYX_ERR(1, 1, __pyx_L1_error) + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: init_globals ### */ + +static CYTHON_SMALL_CODE int __Pyx_InitGlobals(void) { + /* AssertionsEnabled.init */ + if (likely(__Pyx_init_assertions_enabled() == 0)); else + +if (unlikely(PyErr_Occurred())) __PYX_ERR(1, 1, __pyx_L1_error) + + return 0; + __pyx_L1_error:; + return -1; +} +/* #### Code section: init_module ### */ + +static CYTHON_SMALL_CODE int __Pyx_modinit_global_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_export_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_init_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_type_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_variable_import_code(void); /*proto*/ +static CYTHON_SMALL_CODE int __Pyx_modinit_function_import_code(void); /*proto*/ + +static int __Pyx_modinit_global_init_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_global_init_code", 0); + /*--- Global init code ---*/ + __pyx_collections_abc_Sequence = Py_None; Py_INCREF(Py_None); + generic = Py_None; Py_INCREF(Py_None); + strided = Py_None; Py_INCREF(Py_None); + indirect = Py_None; Py_INCREF(Py_None); + contiguous = Py_None; Py_INCREF(Py_None); + indirect_contiguous = Py_None; Py_INCREF(Py_None); + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_variable_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_export_code", 0); + /*--- Variable export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_export_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_export_code", 0); + /*--- Function export code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_type_init_code(void) { + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_modinit_type_init_code", 0); + /*--- Type init code ---*/ + __pyx_t_1 = PyImport_ImportModule("selfdrive.modeld.runners.runmodel_pyx"); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel = __Pyx_ImportType_3_0_8(__pyx_t_1, "selfdrive.modeld.runners.runmodel_pyx", "RunModel", sizeof(struct __pyx_obj_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(struct __pyx_obj_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel) __PYX_ERR(1, 1, __pyx_L1_error) + #if CYTHON_USE_TYPE_SPECS + __pyx_t_2 = PyTuple_Pack(1, (PyObject *)__pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel); if (unlikely(!__pyx_t_2)) __PYX_ERR(1, 12, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_ptype_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel_spec, __pyx_t_2); + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + if (unlikely(!__pyx_ptype_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel)) __PYX_ERR(1, 12, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel_spec, __pyx_ptype_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel) < 0) __PYX_ERR(1, 12, __pyx_L1_error) + #else + __pyx_ptype_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel = &__pyx_type_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + __pyx_ptype_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel->tp_dealloc = __pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel->tp_dealloc; + __pyx_ptype_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel->tp_base = __pyx_ptype_9selfdrive_6modeld_7runners_12runmodel_pyx_RunModel; + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_ptype_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel) < 0) __PYX_ERR(1, 12, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_ptype_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_ptype_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel->tp_dictoffset && __pyx_ptype_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_ptype_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_ThneedModel, (PyObject *) __pyx_ptype_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel) < 0) __PYX_ERR(1, 12, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_ptype_9selfdrive_6modeld_7runners_15thneedmodel_pyx_ThneedModel) < 0) __PYX_ERR(1, 12, __pyx_L1_error) + #endif + __pyx_vtabptr_array = &__pyx_vtable_array; + __pyx_vtable_array.get_memview = (PyObject *(*)(struct __pyx_array_obj *))__pyx_array_get_memview; + #if CYTHON_USE_TYPE_SPECS + __pyx_array_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_array_spec, NULL); if (unlikely(!__pyx_array_type)) __PYX_ERR(0, 114, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + __pyx_array_type->tp_as_buffer = &__pyx_tp_as_buffer_array; + if (!__pyx_array_type->tp_as_buffer->bf_releasebuffer && __pyx_array_type->tp_base->tp_as_buffer && __pyx_array_type->tp_base->tp_as_buffer->bf_releasebuffer) { + __pyx_array_type->tp_as_buffer->bf_releasebuffer = __pyx_array_type->tp_base->tp_as_buffer->bf_releasebuffer; + } + #elif defined(Py_bf_getbuffer) && defined(Py_bf_releasebuffer) + /* PY_VERSION_HEX >= 0x03090000 || Py_LIMITED_API >= 0x030B0000 */ + #elif defined(_MSC_VER) + #pragma message ("The buffer protocol is not supported in the Limited C-API < 3.11.") + #else + #warning "The buffer protocol is not supported in the Limited C-API < 3.11." + #endif + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_array_spec, __pyx_array_type) < 0) __PYX_ERR(0, 114, __pyx_L1_error) + #else + __pyx_array_type = &__pyx_type___pyx_array; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_array_type) < 0) __PYX_ERR(0, 114, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_array_type->tp_print = 0; + #endif + if (__Pyx_SetVtable(__pyx_array_type, __pyx_vtabptr_array) < 0) __PYX_ERR(0, 114, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_array_type) < 0) __PYX_ERR(0, 114, __pyx_L1_error) + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_array_type) < 0) __PYX_ERR(0, 114, __pyx_L1_error) + #endif + #if CYTHON_USE_TYPE_SPECS + __pyx_MemviewEnum_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_MemviewEnum_spec, NULL); if (unlikely(!__pyx_MemviewEnum_type)) __PYX_ERR(0, 302, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_MemviewEnum_spec, __pyx_MemviewEnum_type) < 0) __PYX_ERR(0, 302, __pyx_L1_error) + #else + __pyx_MemviewEnum_type = &__pyx_type___pyx_MemviewEnum; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_MemviewEnum_type) < 0) __PYX_ERR(0, 302, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_MemviewEnum_type->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_MemviewEnum_type->tp_dictoffset && __pyx_MemviewEnum_type->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_MemviewEnum_type->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_MemviewEnum_type) < 0) __PYX_ERR(0, 302, __pyx_L1_error) + #endif + __pyx_vtabptr_memoryview = &__pyx_vtable_memoryview; + __pyx_vtable_memoryview.get_item_pointer = (char *(*)(struct __pyx_memoryview_obj *, PyObject *))__pyx_memoryview_get_item_pointer; + __pyx_vtable_memoryview.is_slice = (PyObject *(*)(struct __pyx_memoryview_obj *, PyObject *))__pyx_memoryview_is_slice; + __pyx_vtable_memoryview.setitem_slice_assignment = (PyObject *(*)(struct __pyx_memoryview_obj *, PyObject *, PyObject *))__pyx_memoryview_setitem_slice_assignment; + __pyx_vtable_memoryview.setitem_slice_assign_scalar = (PyObject *(*)(struct __pyx_memoryview_obj *, struct __pyx_memoryview_obj *, PyObject *))__pyx_memoryview_setitem_slice_assign_scalar; + __pyx_vtable_memoryview.setitem_indexed = (PyObject *(*)(struct __pyx_memoryview_obj *, PyObject *, PyObject *))__pyx_memoryview_setitem_indexed; + __pyx_vtable_memoryview.convert_item_to_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *))__pyx_memoryview_convert_item_to_object; + __pyx_vtable_memoryview.assign_item_from_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *, PyObject *))__pyx_memoryview_assign_item_from_object; + __pyx_vtable_memoryview._get_base = (PyObject *(*)(struct __pyx_memoryview_obj *))__pyx_memoryview__get_base; + #if CYTHON_USE_TYPE_SPECS + __pyx_memoryview_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_memoryview_spec, NULL); if (unlikely(!__pyx_memoryview_type)) __PYX_ERR(0, 337, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + __pyx_memoryview_type->tp_as_buffer = &__pyx_tp_as_buffer_memoryview; + if (!__pyx_memoryview_type->tp_as_buffer->bf_releasebuffer && __pyx_memoryview_type->tp_base->tp_as_buffer && __pyx_memoryview_type->tp_base->tp_as_buffer->bf_releasebuffer) { + __pyx_memoryview_type->tp_as_buffer->bf_releasebuffer = __pyx_memoryview_type->tp_base->tp_as_buffer->bf_releasebuffer; + } + #elif defined(Py_bf_getbuffer) && defined(Py_bf_releasebuffer) + /* PY_VERSION_HEX >= 0x03090000 || Py_LIMITED_API >= 0x030B0000 */ + #elif defined(_MSC_VER) + #pragma message ("The buffer protocol is not supported in the Limited C-API < 3.11.") + #else + #warning "The buffer protocol is not supported in the Limited C-API < 3.11." + #endif + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_memoryview_spec, __pyx_memoryview_type) < 0) __PYX_ERR(0, 337, __pyx_L1_error) + #else + __pyx_memoryview_type = &__pyx_type___pyx_memoryview; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_memoryview_type) < 0) __PYX_ERR(0, 337, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_memoryview_type->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_memoryview_type->tp_dictoffset && __pyx_memoryview_type->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_memoryview_type->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (__Pyx_SetVtable(__pyx_memoryview_type, __pyx_vtabptr_memoryview) < 0) __PYX_ERR(0, 337, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_memoryview_type) < 0) __PYX_ERR(0, 337, __pyx_L1_error) + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_memoryview_type) < 0) __PYX_ERR(0, 337, __pyx_L1_error) + #endif + __pyx_vtabptr__memoryviewslice = &__pyx_vtable__memoryviewslice; + __pyx_vtable__memoryviewslice.__pyx_base = *__pyx_vtabptr_memoryview; + __pyx_vtable__memoryviewslice.__pyx_base.convert_item_to_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *))__pyx_memoryviewslice_convert_item_to_object; + __pyx_vtable__memoryviewslice.__pyx_base.assign_item_from_object = (PyObject *(*)(struct __pyx_memoryview_obj *, char *, PyObject *))__pyx_memoryviewslice_assign_item_from_object; + __pyx_vtable__memoryviewslice.__pyx_base._get_base = (PyObject *(*)(struct __pyx_memoryview_obj *))__pyx_memoryviewslice__get_base; + #if CYTHON_USE_TYPE_SPECS + __pyx_t_2 = PyTuple_Pack(1, (PyObject *)__pyx_memoryview_type); if (unlikely(!__pyx_t_2)) __PYX_ERR(0, 952, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_2); + __pyx_memoryviewslice_type = (PyTypeObject *) __Pyx_PyType_FromModuleAndSpec(__pyx_m, &__pyx_type___pyx_memoryviewslice_spec, __pyx_t_2); + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + if (unlikely(!__pyx_memoryviewslice_type)) __PYX_ERR(0, 952, __pyx_L1_error) + if (__Pyx_fix_up_extension_type_from_spec(&__pyx_type___pyx_memoryviewslice_spec, __pyx_memoryviewslice_type) < 0) __PYX_ERR(0, 952, __pyx_L1_error) + #else + __pyx_memoryviewslice_type = &__pyx_type___pyx_memoryviewslice; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + __pyx_memoryviewslice_type->tp_base = __pyx_memoryview_type; + #endif + #if !CYTHON_USE_TYPE_SPECS + if (__Pyx_PyType_Ready(__pyx_memoryviewslice_type) < 0) __PYX_ERR(0, 952, __pyx_L1_error) + #endif + #if PY_MAJOR_VERSION < 3 + __pyx_memoryviewslice_type->tp_print = 0; + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if ((CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP) && likely(!__pyx_memoryviewslice_type->tp_dictoffset && __pyx_memoryviewslice_type->tp_getattro == PyObject_GenericGetAttr)) { + __pyx_memoryviewslice_type->tp_getattro = __Pyx_PyObject_GenericGetAttr; + } + #endif + if (__Pyx_SetVtable(__pyx_memoryviewslice_type, __pyx_vtabptr__memoryviewslice) < 0) __PYX_ERR(0, 952, __pyx_L1_error) + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_MergeVtables(__pyx_memoryviewslice_type) < 0) __PYX_ERR(0, 952, __pyx_L1_error) + #endif + #if !CYTHON_COMPILING_IN_LIMITED_API + if (__Pyx_setup_reduce((PyObject *) __pyx_memoryviewslice_type) < 0) __PYX_ERR(0, 952, __pyx_L1_error) + #endif + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_XDECREF(__pyx_t_2); + __Pyx_RefNannyFinishContext(); + return -1; +} + +static int __Pyx_modinit_type_import_code(void) { + __Pyx_RefNannyDeclarations + PyObject *__pyx_t_1 = NULL; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannySetupContext("__Pyx_modinit_type_import_code", 0); + /*--- Type import code ---*/ + __pyx_t_1 = PyImport_ImportModule("cereal.visionipc.visionipc_pyx"); if (unlikely(!__pyx_t_1)) __PYX_ERR(2, 7, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext = __Pyx_ImportType_3_0_8(__pyx_t_1, "cereal.visionipc.visionipc_pyx", "CLContext", sizeof(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_CLContext), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_CLContext),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_CLContext) __PYX_ERR(2, 7, __pyx_L1_error) + __pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf = __Pyx_ImportType_3_0_8(__pyx_t_1, "cereal.visionipc.visionipc_pyx", "VisionBuf", sizeof(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(struct __pyx_obj_6cereal_9visionipc_13visionipc_pyx_VisionBuf),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf) __PYX_ERR(2, 11, __pyx_L1_error) + __pyx_vtabptr_6cereal_9visionipc_13visionipc_pyx_VisionBuf = (struct __pyx_vtabstruct_6cereal_9visionipc_13visionipc_pyx_VisionBuf*)__Pyx_GetVtable(__pyx_ptype_6cereal_9visionipc_13visionipc_pyx_VisionBuf); if (unlikely(!__pyx_vtabptr_6cereal_9visionipc_13visionipc_pyx_VisionBuf)) __PYX_ERR(2, 11, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __pyx_t_1 = PyImport_ImportModule("selfdrive.modeld.models.commonmodel_pyx"); if (unlikely(!__pyx_t_1)) __PYX_ERR(3, 6, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_1); + __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext = __Pyx_ImportType_3_0_8(__pyx_t_1, "selfdrive.modeld.models.commonmodel_pyx", "CLContext", sizeof(struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLContext) __PYX_ERR(3, 6, __pyx_L1_error) + __pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem = __Pyx_ImportType_3_0_8(__pyx_t_1, "selfdrive.modeld.models.commonmodel_pyx", "CLMem", sizeof(struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem), __PYX_GET_STRUCT_ALIGNMENT_3_0_8(struct __pyx_obj_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem),__Pyx_ImportType_CheckSize_Warn_3_0_8); if (!__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem) __PYX_ERR(3, 9, __pyx_L1_error) + __pyx_vtabptr_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem = (struct __pyx_vtabstruct_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem*)__Pyx_GetVtable(__pyx_ptype_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem); if (unlikely(!__pyx_vtabptr_9selfdrive_6modeld_6models_15commonmodel_pyx_CLMem)) __PYX_ERR(3, 9, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_RefNannyFinishContext(); + return 0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_1); + __Pyx_RefNannyFinishContext(); + return -1; +} + +static int __Pyx_modinit_variable_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_variable_import_code", 0); + /*--- Variable import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + +static int __Pyx_modinit_function_import_code(void) { + __Pyx_RefNannyDeclarations + __Pyx_RefNannySetupContext("__Pyx_modinit_function_import_code", 0); + /*--- Function import code ---*/ + __Pyx_RefNannyFinishContext(); + return 0; +} + + +#if PY_MAJOR_VERSION >= 3 +#if CYTHON_PEP489_MULTI_PHASE_INIT +static PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def); /*proto*/ +static int __pyx_pymod_exec_thneedmodel_pyx(PyObject* module); /*proto*/ +static PyModuleDef_Slot __pyx_moduledef_slots[] = { + {Py_mod_create, (void*)__pyx_pymod_create}, + {Py_mod_exec, (void*)__pyx_pymod_exec_thneedmodel_pyx}, + {0, NULL} +}; +#endif + +#ifdef __cplusplus +namespace { + struct PyModuleDef __pyx_moduledef = + #else + static struct PyModuleDef __pyx_moduledef = + #endif + { + PyModuleDef_HEAD_INIT, + "thneedmodel_pyx", + 0, /* m_doc */ + #if CYTHON_PEP489_MULTI_PHASE_INIT + 0, /* m_size */ + #elif CYTHON_USE_MODULE_STATE + sizeof(__pyx_mstate), /* m_size */ + #else + -1, /* m_size */ + #endif + __pyx_methods /* m_methods */, + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_moduledef_slots, /* m_slots */ + #else + NULL, /* m_reload */ + #endif + #if CYTHON_USE_MODULE_STATE + __pyx_m_traverse, /* m_traverse */ + __pyx_m_clear, /* m_clear */ + NULL /* m_free */ + #else + NULL, /* m_traverse */ + NULL, /* m_clear */ + NULL /* m_free */ + #endif + }; + #ifdef __cplusplus +} /* anonymous namespace */ +#endif +#endif + +#ifndef CYTHON_NO_PYINIT_EXPORT +#define __Pyx_PyMODINIT_FUNC PyMODINIT_FUNC +#elif PY_MAJOR_VERSION < 3 +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" void +#else +#define __Pyx_PyMODINIT_FUNC void +#endif +#else +#ifdef __cplusplus +#define __Pyx_PyMODINIT_FUNC extern "C" PyObject * +#else +#define __Pyx_PyMODINIT_FUNC PyObject * +#endif +#endif + + +#if PY_MAJOR_VERSION < 3 +__Pyx_PyMODINIT_FUNC initthneedmodel_pyx(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC initthneedmodel_pyx(void) +#else +__Pyx_PyMODINIT_FUNC PyInit_thneedmodel_pyx(void) CYTHON_SMALL_CODE; /*proto*/ +__Pyx_PyMODINIT_FUNC PyInit_thneedmodel_pyx(void) +#if CYTHON_PEP489_MULTI_PHASE_INIT +{ + return PyModuleDef_Init(&__pyx_moduledef); +} +static CYTHON_SMALL_CODE int __Pyx_check_single_interpreter(void) { + #if PY_VERSION_HEX >= 0x030700A1 + static PY_INT64_T main_interpreter_id = -1; + PY_INT64_T current_id = PyInterpreterState_GetID(PyThreadState_Get()->interp); + if (main_interpreter_id == -1) { + main_interpreter_id = current_id; + return (unlikely(current_id == -1)) ? -1 : 0; + } else if (unlikely(main_interpreter_id != current_id)) + #else + static PyInterpreterState *main_interpreter = NULL; + PyInterpreterState *current_interpreter = PyThreadState_Get()->interp; + if (!main_interpreter) { + main_interpreter = current_interpreter; + } else if (unlikely(main_interpreter != current_interpreter)) + #endif + { + PyErr_SetString( + PyExc_ImportError, + "Interpreter change detected - this module can only be loaded into one interpreter per process."); + return -1; + } + return 0; +} +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *module, const char* from_name, const char* to_name, int allow_none) +#else +static CYTHON_SMALL_CODE int __Pyx_copy_spec_to_module(PyObject *spec, PyObject *moddict, const char* from_name, const char* to_name, int allow_none) +#endif +{ + PyObject *value = PyObject_GetAttrString(spec, from_name); + int result = 0; + if (likely(value)) { + if (allow_none || value != Py_None) { +#if CYTHON_COMPILING_IN_LIMITED_API + result = PyModule_AddObject(module, to_name, value); +#else + result = PyDict_SetItemString(moddict, to_name, value); +#endif + } + Py_DECREF(value); + } else if (PyErr_ExceptionMatches(PyExc_AttributeError)) { + PyErr_Clear(); + } else { + result = -1; + } + return result; +} +static CYTHON_SMALL_CODE PyObject* __pyx_pymod_create(PyObject *spec, PyModuleDef *def) { + PyObject *module = NULL, *moddict, *modname; + CYTHON_UNUSED_VAR(def); + if (__Pyx_check_single_interpreter()) + return NULL; + if (__pyx_m) + return __Pyx_NewRef(__pyx_m); + modname = PyObject_GetAttrString(spec, "name"); + if (unlikely(!modname)) goto bad; + module = PyModule_NewObject(modname); + Py_DECREF(modname); + if (unlikely(!module)) goto bad; +#if CYTHON_COMPILING_IN_LIMITED_API + moddict = module; +#else + moddict = PyModule_GetDict(module); + if (unlikely(!moddict)) goto bad; +#endif + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "loader", "__loader__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "origin", "__file__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "parent", "__package__", 1) < 0)) goto bad; + if (unlikely(__Pyx_copy_spec_to_module(spec, moddict, "submodule_search_locations", "__path__", 0) < 0)) goto bad; + return module; +bad: + Py_XDECREF(module); + return NULL; +} + + +static CYTHON_SMALL_CODE int __pyx_pymod_exec_thneedmodel_pyx(PyObject *__pyx_pyinit_module) +#endif +#endif +{ + int stringtab_initialized = 0; + #if CYTHON_USE_MODULE_STATE + int pystate_addmodule_run = 0; + #endif + PyObject *__pyx_t_1 = NULL; + PyObject *__pyx_t_2 = NULL; + PyObject *__pyx_t_3 = NULL; + PyObject *__pyx_t_4 = NULL; + PyObject *__pyx_t_5 = NULL; + int __pyx_t_6; + PyObject *__pyx_t_7 = NULL; + static PyThread_type_lock __pyx_t_8[8]; + int __pyx_lineno = 0; + const char *__pyx_filename = NULL; + int __pyx_clineno = 0; + __Pyx_RefNannyDeclarations + #if CYTHON_PEP489_MULTI_PHASE_INIT + if (__pyx_m) { + if (__pyx_m == __pyx_pyinit_module) return 0; + PyErr_SetString(PyExc_RuntimeError, "Module 'thneedmodel_pyx' has already been imported. Re-initialisation is not supported."); + return -1; + } + #elif PY_MAJOR_VERSION >= 3 + if (__pyx_m) return __Pyx_NewRef(__pyx_m); + #endif + /*--- Module creation code ---*/ + #if CYTHON_PEP489_MULTI_PHASE_INIT + __pyx_m = __pyx_pyinit_module; + Py_INCREF(__pyx_m); + #else + #if PY_MAJOR_VERSION < 3 + __pyx_m = Py_InitModule4("thneedmodel_pyx", __pyx_methods, 0, 0, PYTHON_API_VERSION); Py_XINCREF(__pyx_m); + if (unlikely(!__pyx_m)) __PYX_ERR(1, 1, __pyx_L1_error) + #elif CYTHON_USE_MODULE_STATE + __pyx_t_1 = PyModule_Create(&__pyx_moduledef); if (unlikely(!__pyx_t_1)) __PYX_ERR(1, 1, __pyx_L1_error) + { + int add_module_result = PyState_AddModule(__pyx_t_1, &__pyx_moduledef); + __pyx_t_1 = 0; /* transfer ownership from __pyx_t_1 to "thneedmodel_pyx" pseudovariable */ + if (unlikely((add_module_result < 0))) __PYX_ERR(1, 1, __pyx_L1_error) + pystate_addmodule_run = 1; + } + #else + __pyx_m = PyModule_Create(&__pyx_moduledef); + if (unlikely(!__pyx_m)) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + #endif + CYTHON_UNUSED_VAR(__pyx_t_1); + __pyx_d = PyModule_GetDict(__pyx_m); if (unlikely(!__pyx_d)) __PYX_ERR(1, 1, __pyx_L1_error) + Py_INCREF(__pyx_d); + __pyx_b = __Pyx_PyImport_AddModuleRef(__Pyx_BUILTIN_MODULE_NAME); if (unlikely(!__pyx_b)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_cython_runtime = __Pyx_PyImport_AddModuleRef((const char *) "cython_runtime"); if (unlikely(!__pyx_cython_runtime)) __PYX_ERR(1, 1, __pyx_L1_error) + if (PyObject_SetAttrString(__pyx_m, "__builtins__", __pyx_b) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #if CYTHON_REFNANNY +__Pyx_RefNanny = __Pyx_RefNannyImportAPI("refnanny"); +if (!__Pyx_RefNanny) { + PyErr_Clear(); + __Pyx_RefNanny = __Pyx_RefNannyImportAPI("Cython.Runtime.refnanny"); + if (!__Pyx_RefNanny) + Py_FatalError("failed to import 'refnanny' module"); +} +#endif + __Pyx_RefNannySetupContext("__Pyx_PyMODINIT_FUNC PyInit_thneedmodel_pyx(void)", 0); + if (__Pyx_check_binary_version(__PYX_LIMITED_VERSION_HEX, __Pyx_get_runtime_version(), CYTHON_COMPILING_IN_LIMITED_API) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #ifdef __Pxy_PyFrame_Initialize_Offsets + __Pxy_PyFrame_Initialize_Offsets(); + #endif + __pyx_empty_tuple = PyTuple_New(0); if (unlikely(!__pyx_empty_tuple)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_empty_bytes = PyBytes_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_bytes)) __PYX_ERR(1, 1, __pyx_L1_error) + __pyx_empty_unicode = PyUnicode_FromStringAndSize("", 0); if (unlikely(!__pyx_empty_unicode)) __PYX_ERR(1, 1, __pyx_L1_error) + #ifdef __Pyx_CyFunction_USED + if (__pyx_CyFunction_init(__pyx_m) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_FusedFunction_USED + if (__pyx_FusedFunction_init(__pyx_m) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Coroutine_USED + if (__pyx_Coroutine_init(__pyx_m) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_Generator_USED + if (__pyx_Generator_init(__pyx_m) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_AsyncGen_USED + if (__pyx_AsyncGen_init(__pyx_m) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + #ifdef __Pyx_StopAsyncIteration_USED + if (__pyx_StopAsyncIteration_init(__pyx_m) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + /*--- Library function declarations ---*/ + /*--- Threads initialization code ---*/ + #if defined(WITH_THREAD) && PY_VERSION_HEX < 0x030700F0 && defined(__PYX_FORCE_INIT_THREADS) && __PYX_FORCE_INIT_THREADS + PyEval_InitThreads(); + #endif + /*--- Initialize various global constants etc. ---*/ + if (__Pyx_InitConstants() < 0) __PYX_ERR(1, 1, __pyx_L1_error) + stringtab_initialized = 1; + if (__Pyx_InitGlobals() < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #if PY_MAJOR_VERSION < 3 && (__PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT) + if (__Pyx_init_sys_getdefaultencoding_params() < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + if (__pyx_module_is_main_selfdrive__modeld__runners__thneedmodel_pyx) { + if (PyObject_SetAttr(__pyx_m, __pyx_n_s_name_2, __pyx_n_s_main) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + } + #if PY_MAJOR_VERSION >= 3 + { + PyObject *modules = PyImport_GetModuleDict(); if (unlikely(!modules)) __PYX_ERR(1, 1, __pyx_L1_error) + if (!PyDict_GetItemString(modules, "selfdrive.modeld.runners.thneedmodel_pyx")) { + if (unlikely((PyDict_SetItemString(modules, "selfdrive.modeld.runners.thneedmodel_pyx", __pyx_m) < 0))) __PYX_ERR(1, 1, __pyx_L1_error) + } + } + #endif + /*--- Builtin init code ---*/ + if (__Pyx_InitCachedBuiltins() < 0) __PYX_ERR(1, 1, __pyx_L1_error) + /*--- Constants init code ---*/ + if (__Pyx_InitCachedConstants() < 0) __PYX_ERR(1, 1, __pyx_L1_error) + /*--- Global type/function init code ---*/ + (void)__Pyx_modinit_global_init_code(); + (void)__Pyx_modinit_variable_export_code(); + (void)__Pyx_modinit_function_export_code(); + if (unlikely((__Pyx_modinit_type_init_code() < 0))) __PYX_ERR(1, 1, __pyx_L1_error) + if (unlikely((__Pyx_modinit_type_import_code() < 0))) __PYX_ERR(1, 1, __pyx_L1_error) + (void)__Pyx_modinit_variable_import_code(); + (void)__Pyx_modinit_function_import_code(); + /*--- Execution code ---*/ + #if defined(__Pyx_Generator_USED) || defined(__Pyx_Coroutine_USED) + if (__Pyx_patch_abc() < 0) __PYX_ERR(1, 1, __pyx_L1_error) + #endif + + /* "View.MemoryView":99 + * + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: # <<<<<<<<<<<<<< + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "View.MemoryView":100 + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: + * if __import__("sys").version_info >= (3, 3): # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + */ + __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__9, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 100, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_version_info); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 100, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = PyObject_RichCompare(__pyx_t_5, __pyx_tuple__10, Py_GE); __Pyx_XGOTREF(__pyx_t_4); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 100, __pyx_L2_error) + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __pyx_t_6 = __Pyx_PyObject_IsTrue(__pyx_t_4); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 100, __pyx_L2_error) + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + if (__pyx_t_6) { + + /* "View.MemoryView":101 + * try: + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence # <<<<<<<<<<<<<< + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence + */ + __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__11, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 101, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_abc); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 101, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_t_5, __pyx_n_s_Sequence); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 101, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XGOTREF(__pyx_collections_abc_Sequence); + __Pyx_DECREF_SET(__pyx_collections_abc_Sequence, __pyx_t_4); + __Pyx_GIVEREF(__pyx_t_4); + __pyx_t_4 = 0; + + /* "View.MemoryView":100 + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: + * if __import__("sys").version_info >= (3, 3): # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + */ + goto __pyx_L8; + } + + /* "View.MemoryView":103 + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence # <<<<<<<<<<<<<< + * except: + * + */ + /*else*/ { + __pyx_t_4 = __Pyx_PyObject_Call(__pyx_builtin___import__, __pyx_tuple__12, NULL); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 103, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_5 = __Pyx_PyObject_GetAttrStr(__pyx_t_4, __pyx_n_s_Sequence); if (unlikely(!__pyx_t_5)) __PYX_ERR(0, 103, __pyx_L2_error) + __Pyx_GOTREF(__pyx_t_5); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XGOTREF(__pyx_collections_abc_Sequence); + __Pyx_DECREF_SET(__pyx_collections_abc_Sequence, __pyx_t_5); + __Pyx_GIVEREF(__pyx_t_5); + __pyx_t_5 = 0; + } + __pyx_L8:; + + /* "View.MemoryView":99 + * + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: # <<<<<<<<<<<<<< + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L7_try_end; + __pyx_L2_error:; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + + /* "View.MemoryView":104 + * else: + * __pyx_collections_abc_Sequence = __import__("collections").Sequence + * except: # <<<<<<<<<<<<<< + * + * __pyx_collections_abc_Sequence = None + */ + /*except:*/ { + __Pyx_AddTraceback("View.MemoryView", __pyx_clineno, __pyx_lineno, __pyx_filename); + if (__Pyx_GetException(&__pyx_t_5, &__pyx_t_4, &__pyx_t_7) < 0) __PYX_ERR(0, 104, __pyx_L4_except_error) + __Pyx_XGOTREF(__pyx_t_5); + __Pyx_XGOTREF(__pyx_t_4); + __Pyx_XGOTREF(__pyx_t_7); + + /* "View.MemoryView":106 + * except: + * + * __pyx_collections_abc_Sequence = None # <<<<<<<<<<<<<< + * + * + */ + __Pyx_INCREF(Py_None); + __Pyx_XGOTREF(__pyx_collections_abc_Sequence); + __Pyx_DECREF_SET(__pyx_collections_abc_Sequence, Py_None); + __Pyx_GIVEREF(Py_None); + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + goto __pyx_L3_exception_handled; + } + + /* "View.MemoryView":99 + * + * cdef object __pyx_collections_abc_Sequence "__pyx_collections_abc_Sequence" + * try: # <<<<<<<<<<<<<< + * if __import__("sys").version_info >= (3, 3): + * __pyx_collections_abc_Sequence = __import__("collections.abc").abc.Sequence + */ + __pyx_L4_except_error:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + goto __pyx_L1_error; + __pyx_L3_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + __pyx_L7_try_end:; + } + + /* "View.MemoryView":241 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_3, &__pyx_t_2, &__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_1); + /*try:*/ { + + /* "View.MemoryView":242 + * + * try: + * count = __pyx_collections_abc_Sequence.count # <<<<<<<<<<<<<< + * index = __pyx_collections_abc_Sequence.index + * except: + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_count); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 242, __pyx_L11_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict(__pyx_array_type, __pyx_n_s_count, __pyx_t_7) < 0) __PYX_ERR(0, 242, __pyx_L11_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_array_type); + + /* "View.MemoryView":243 + * try: + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index # <<<<<<<<<<<<<< + * except: + * pass + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_index); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 243, __pyx_L11_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict(__pyx_array_type, __pyx_n_s_index, __pyx_t_7) < 0) __PYX_ERR(0, 243, __pyx_L11_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_array_type); + + /* "View.MemoryView":241 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + } + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + goto __pyx_L16_try_end; + __pyx_L11_error:; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":244 + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + * except: # <<<<<<<<<<<<<< + * pass + * + */ + /*except:*/ { + __Pyx_ErrRestore(0,0,0); + goto __pyx_L12_exception_handled; + } + __pyx_L12_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_2, __pyx_t_1); + __pyx_L16_try_end:; + } + + /* "View.MemoryView":309 + * return self.name + * + * cdef generic = Enum("") # <<<<<<<<<<<<<< + * cdef strided = Enum("") # default + * cdef indirect = Enum("") + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__13, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 309, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(generic); + __Pyx_DECREF_SET(generic, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":310 + * + * cdef generic = Enum("") + * cdef strided = Enum("") # default # <<<<<<<<<<<<<< + * cdef indirect = Enum("") + * + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__14, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 310, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(strided); + __Pyx_DECREF_SET(strided, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":311 + * cdef generic = Enum("") + * cdef strided = Enum("") # default + * cdef indirect = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__15, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 311, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(indirect); + __Pyx_DECREF_SET(indirect, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":314 + * + * + * cdef contiguous = Enum("") # <<<<<<<<<<<<<< + * cdef indirect_contiguous = Enum("") + * + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__16, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 314, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(contiguous); + __Pyx_DECREF_SET(contiguous, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":315 + * + * cdef contiguous = Enum("") + * cdef indirect_contiguous = Enum("") # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_7 = __Pyx_PyObject_Call(((PyObject *)__pyx_MemviewEnum_type), __pyx_tuple__17, NULL); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 315, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_XGOTREF(indirect_contiguous); + __Pyx_DECREF_SET(indirect_contiguous, __pyx_t_7); + __Pyx_GIVEREF(__pyx_t_7); + __pyx_t_7 = 0; + + /* "View.MemoryView":323 + * + * + * cdef int __pyx_memoryview_thread_locks_used = 0 # <<<<<<<<<<<<<< + * cdef PyThread_type_lock[8] __pyx_memoryview_thread_locks = [ + * PyThread_allocate_lock(), + */ + __pyx_memoryview_thread_locks_used = 0; + + /* "View.MemoryView":324 + * + * cdef int __pyx_memoryview_thread_locks_used = 0 + * cdef PyThread_type_lock[8] __pyx_memoryview_thread_locks = [ # <<<<<<<<<<<<<< + * PyThread_allocate_lock(), + * PyThread_allocate_lock(), + */ + __pyx_t_8[0] = PyThread_allocate_lock(); + __pyx_t_8[1] = PyThread_allocate_lock(); + __pyx_t_8[2] = PyThread_allocate_lock(); + __pyx_t_8[3] = PyThread_allocate_lock(); + __pyx_t_8[4] = PyThread_allocate_lock(); + __pyx_t_8[5] = PyThread_allocate_lock(); + __pyx_t_8[6] = PyThread_allocate_lock(); + __pyx_t_8[7] = PyThread_allocate_lock(); + memcpy(&(__pyx_memoryview_thread_locks[0]), __pyx_t_8, sizeof(__pyx_memoryview_thread_locks[0]) * (8)); + + /* "View.MemoryView":982 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_1, &__pyx_t_2, &__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_3); + /*try:*/ { + + /* "View.MemoryView":983 + * + * try: + * count = __pyx_collections_abc_Sequence.count # <<<<<<<<<<<<<< + * index = __pyx_collections_abc_Sequence.index + * except: + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_count); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 983, __pyx_L17_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict(__pyx_memoryviewslice_type, __pyx_n_s_count, __pyx_t_7) < 0) __PYX_ERR(0, 983, __pyx_L17_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_memoryviewslice_type); + + /* "View.MemoryView":984 + * try: + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index # <<<<<<<<<<<<<< + * except: + * pass + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_index); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 984, __pyx_L17_error) + __Pyx_GOTREF(__pyx_t_7); + if (__Pyx_SetItemOnTypeDict(__pyx_memoryviewslice_type, __pyx_n_s_index, __pyx_t_7) < 0) __PYX_ERR(0, 984, __pyx_L17_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + PyType_Modified(__pyx_memoryviewslice_type); + + /* "View.MemoryView":982 + * + * + * try: # <<<<<<<<<<<<<< + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + */ + } + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + goto __pyx_L22_try_end; + __pyx_L17_error:; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":985 + * count = __pyx_collections_abc_Sequence.count + * index = __pyx_collections_abc_Sequence.index + * except: # <<<<<<<<<<<<<< + * pass + * + */ + /*except:*/ { + __Pyx_ErrRestore(0,0,0); + goto __pyx_L18_exception_handled; + } + __pyx_L18_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_ExceptionReset(__pyx_t_1, __pyx_t_2, __pyx_t_3); + __pyx_L22_try_end:; + } + + /* "View.MemoryView":988 + * pass + * + * try: # <<<<<<<<<<<<<< + * if __pyx_collections_abc_Sequence: + * + */ + { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ExceptionSave(&__pyx_t_3, &__pyx_t_2, &__pyx_t_1); + __Pyx_XGOTREF(__pyx_t_3); + __Pyx_XGOTREF(__pyx_t_2); + __Pyx_XGOTREF(__pyx_t_1); + /*try:*/ { + + /* "View.MemoryView":989 + * + * try: + * if __pyx_collections_abc_Sequence: # <<<<<<<<<<<<<< + * + * + */ + __pyx_t_6 = __Pyx_PyObject_IsTrue(__pyx_collections_abc_Sequence); if (unlikely((__pyx_t_6 < 0))) __PYX_ERR(0, 989, __pyx_L23_error) + if (__pyx_t_6) { + + /* "View.MemoryView":993 + * + * + * __pyx_collections_abc_Sequence.register(_memoryviewslice) # <<<<<<<<<<<<<< + * __pyx_collections_abc_Sequence.register(array) + * except: + */ + __pyx_t_7 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_register); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 993, __pyx_L23_error) + __Pyx_GOTREF(__pyx_t_7); + __pyx_t_4 = __Pyx_PyObject_CallOneArg(__pyx_t_7, ((PyObject *)__pyx_memoryviewslice_type)); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 993, __pyx_L23_error) + __Pyx_GOTREF(__pyx_t_4); + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + + /* "View.MemoryView":994 + * + * __pyx_collections_abc_Sequence.register(_memoryviewslice) + * __pyx_collections_abc_Sequence.register(array) # <<<<<<<<<<<<<< + * except: + * pass # ignore failure, it's a minor issue + */ + __pyx_t_4 = __Pyx_PyObject_GetAttrStr(__pyx_collections_abc_Sequence, __pyx_n_s_register); if (unlikely(!__pyx_t_4)) __PYX_ERR(0, 994, __pyx_L23_error) + __Pyx_GOTREF(__pyx_t_4); + __pyx_t_7 = __Pyx_PyObject_CallOneArg(__pyx_t_4, ((PyObject *)__pyx_array_type)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 994, __pyx_L23_error) + __Pyx_GOTREF(__pyx_t_7); + __Pyx_DECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":989 + * + * try: + * if __pyx_collections_abc_Sequence: # <<<<<<<<<<<<<< + * + * + */ + } + + /* "View.MemoryView":988 + * pass + * + * try: # <<<<<<<<<<<<<< + * if __pyx_collections_abc_Sequence: + * + */ + } + __Pyx_XDECREF(__pyx_t_3); __pyx_t_3 = 0; + __Pyx_XDECREF(__pyx_t_2); __pyx_t_2 = 0; + __Pyx_XDECREF(__pyx_t_1); __pyx_t_1 = 0; + goto __pyx_L28_try_end; + __pyx_L23_error:; + __Pyx_XDECREF(__pyx_t_4); __pyx_t_4 = 0; + __Pyx_XDECREF(__pyx_t_5); __pyx_t_5 = 0; + __Pyx_XDECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "View.MemoryView":995 + * __pyx_collections_abc_Sequence.register(_memoryviewslice) + * __pyx_collections_abc_Sequence.register(array) + * except: # <<<<<<<<<<<<<< + * pass # ignore failure, it's a minor issue + * + */ + /*except:*/ { + __Pyx_ErrRestore(0,0,0); + goto __pyx_L24_exception_handled; + } + __pyx_L24_exception_handled:; + __Pyx_XGIVEREF(__pyx_t_3); + __Pyx_XGIVEREF(__pyx_t_2); + __Pyx_XGIVEREF(__pyx_t_1); + __Pyx_ExceptionReset(__pyx_t_3, __pyx_t_2, __pyx_t_1); + __pyx_L28_try_end:; + } + + /* "(tree fragment)":1 + * def __pyx_unpickle_Enum(__pyx_type, long __pyx_checksum, __pyx_state): # <<<<<<<<<<<<<< + * cdef object __pyx_PickleError + * cdef object __pyx_result + */ + __pyx_t_7 = PyCFunction_NewEx(&__pyx_mdef_15View_dot_MemoryView_1__pyx_unpickle_Enum, NULL, __pyx_n_s_View_MemoryView); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_pyx_unpickle_Enum, __pyx_t_7) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "selfdrive/modeld/runners/thneedmodel_pyx.pyx":13 + * + * cdef class ThneedModel(RunModel): + * def __cinit__(self, string path, float[:] output, int runtime, bool use_tf8, CLContext context): # <<<<<<<<<<<<<< + * self.model = new cppThneedModel(path, &output[0], len(output), runtime, use_tf8, context.context) + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_9selfdrive_6modeld_7runners_15thneedmodel_pyx_11ThneedModel_3__reduce_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_ThneedModel___reduce_cython, NULL, __pyx_n_s_selfdrive_modeld_runners_thneedm, __pyx_d, ((PyObject *)__pyx_codeobj__21)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_reduce_cython, __pyx_t_7) < 0) __PYX_ERR(0, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "(tree fragment)":3 + * def __reduce_cython__(self): + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + * def __setstate_cython__(self, __pyx_state): # <<<<<<<<<<<<<< + * raise TypeError, "no default __reduce__ due to non-trivial __cinit__" + */ + __pyx_t_7 = __Pyx_CyFunction_New(&__pyx_mdef_9selfdrive_6modeld_7runners_15thneedmodel_pyx_11ThneedModel_5__setstate_cython__, __Pyx_CYFUNCTION_CCLASS, __pyx_n_s_ThneedModel___setstate_cython, NULL, __pyx_n_s_selfdrive_modeld_runners_thneedm, __pyx_d, ((PyObject *)__pyx_codeobj__23)); if (unlikely(!__pyx_t_7)) __PYX_ERR(0, 3, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_setstate_cython, __pyx_t_7) < 0) __PYX_ERR(0, 3, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /* "selfdrive/modeld/runners/thneedmodel_pyx.pyx":1 + * # distutils: language = c++ # <<<<<<<<<<<<<< + * # cython: c_string_encoding=ascii + * + */ + __pyx_t_7 = __Pyx_PyDict_NewPresized(0); if (unlikely(!__pyx_t_7)) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_GOTREF(__pyx_t_7); + if (PyDict_SetItem(__pyx_d, __pyx_n_s_test, __pyx_t_7) < 0) __PYX_ERR(1, 1, __pyx_L1_error) + __Pyx_DECREF(__pyx_t_7); __pyx_t_7 = 0; + + /*--- Wrapped vars code ---*/ + + goto __pyx_L0; + __pyx_L1_error:; + __Pyx_XDECREF(__pyx_t_4); + __Pyx_XDECREF(__pyx_t_5); + __Pyx_XDECREF(__pyx_t_7); + if (__pyx_m) { + if (__pyx_d && stringtab_initialized) { + __Pyx_AddTraceback("init selfdrive.modeld.runners.thneedmodel_pyx", __pyx_clineno, __pyx_lineno, __pyx_filename); + } + #if !CYTHON_USE_MODULE_STATE + Py_CLEAR(__pyx_m); + #else + Py_DECREF(__pyx_m); + if (pystate_addmodule_run) { + PyObject *tp, *value, *tb; + PyErr_Fetch(&tp, &value, &tb); + PyState_RemoveModule(&__pyx_moduledef); + PyErr_Restore(tp, value, tb); + } + #endif + } else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_ImportError, "init selfdrive.modeld.runners.thneedmodel_pyx"); + } + __pyx_L0:; + __Pyx_RefNannyFinishContext(); + #if CYTHON_PEP489_MULTI_PHASE_INIT + return (__pyx_m != NULL) ? 0 : -1; + #elif PY_MAJOR_VERSION >= 3 + return __pyx_m; + #else + return; + #endif +} +/* #### Code section: cleanup_globals ### */ +/* #### Code section: cleanup_module ### */ +/* #### Code section: main_method ### */ +/* #### Code section: utility_code_pragmas ### */ +#ifdef _MSC_VER +#pragma warning( push ) +/* Warning 4127: conditional expression is constant + * Cython uses constant conditional expressions to allow in inline functions to be optimized at + * compile-time, so this warning is not useful + */ +#pragma warning( disable : 4127 ) +#endif + + + +/* #### Code section: utility_code_def ### */ + +/* --- Runtime support code --- */ +/* Refnanny */ +#if CYTHON_REFNANNY +static __Pyx_RefNannyAPIStruct *__Pyx_RefNannyImportAPI(const char *modname) { + PyObject *m = NULL, *p = NULL; + void *r = NULL; + m = PyImport_ImportModule(modname); + if (!m) goto end; + p = PyObject_GetAttrString(m, "RefNannyAPI"); + if (!p) goto end; + r = PyLong_AsVoidPtr(p); +end: + Py_XDECREF(p); + Py_XDECREF(m); + return (__Pyx_RefNannyAPIStruct *)r; +} +#endif + +/* PyErrExceptionMatches */ +#if CYTHON_FAST_THREAD_STATE +static int __Pyx_PyErr_ExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; i= 0x030C00A6 + PyObject *current_exception = tstate->current_exception; + if (unlikely(!current_exception)) return 0; + exc_type = (PyObject*) Py_TYPE(current_exception); + if (exc_type == err) return 1; +#else + exc_type = tstate->curexc_type; + if (exc_type == err) return 1; + if (unlikely(!exc_type)) return 0; +#endif + #if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(exc_type); + #endif + if (unlikely(PyTuple_Check(err))) { + result = __Pyx_PyErr_ExceptionMatchesTuple(exc_type, err); + } else { + result = __Pyx_PyErr_GivenExceptionMatches(exc_type, err); + } + #if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(exc_type); + #endif + return result; +} +#endif + +/* PyErrFetchRestore */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx_ErrRestoreInState(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject *tmp_value; + assert(type == NULL || (value != NULL && type == (PyObject*) Py_TYPE(value))); + if (value) { + #if CYTHON_COMPILING_IN_CPYTHON + if (unlikely(((PyBaseExceptionObject*) value)->traceback != tb)) + #endif + PyException_SetTraceback(value, tb); + } + tmp_value = tstate->current_exception; + tstate->current_exception = value; + Py_XDECREF(tmp_value); + Py_XDECREF(type); + Py_XDECREF(tb); +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + tmp_type = tstate->curexc_type; + tmp_value = tstate->curexc_value; + tmp_tb = tstate->curexc_traceback; + tstate->curexc_type = type; + tstate->curexc_value = value; + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); +#endif +} +static CYTHON_INLINE void __Pyx_ErrFetchInState(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { +#if PY_VERSION_HEX >= 0x030C00A6 + PyObject* exc_value; + exc_value = tstate->current_exception; + tstate->current_exception = 0; + *value = exc_value; + *type = NULL; + *tb = NULL; + if (exc_value) { + *type = (PyObject*) Py_TYPE(exc_value); + Py_INCREF(*type); + #if CYTHON_COMPILING_IN_CPYTHON + *tb = ((PyBaseExceptionObject*) exc_value)->traceback; + Py_XINCREF(*tb); + #else + *tb = PyException_GetTraceback(exc_value); + #endif + } +#else + *type = tstate->curexc_type; + *value = tstate->curexc_value; + *tb = tstate->curexc_traceback; + tstate->curexc_type = 0; + tstate->curexc_value = 0; + tstate->curexc_traceback = 0; +#endif +} +#endif + +/* PyObjectGetAttrStr */ +#if CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStr(PyObject* obj, PyObject* attr_name) { + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro)) + return tp->tp_getattro(obj, attr_name); +#if PY_MAJOR_VERSION < 3 + if (likely(tp->tp_getattr)) + return tp->tp_getattr(obj, PyString_AS_STRING(attr_name)); +#endif + return PyObject_GetAttr(obj, attr_name); +} +#endif + +/* PyObjectGetAttrStrNoError */ +#if __PYX_LIMITED_VERSION_HEX < 0x030d00A1 +static void __Pyx_PyObject_GetAttrStr_ClearAttributeError(void) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + if (likely(__Pyx_PyErr_ExceptionMatches(PyExc_AttributeError))) + __Pyx_PyErr_Clear(); +} +#endif +static CYTHON_INLINE PyObject* __Pyx_PyObject_GetAttrStrNoError(PyObject* obj, PyObject* attr_name) { + PyObject *result; +#if __PYX_LIMITED_VERSION_HEX >= 0x030d00A1 + (void) PyObject_GetOptionalAttr(obj, attr_name, &result); + return result; +#else +#if CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_TYPE_SLOTS && PY_VERSION_HEX >= 0x030700B1 + PyTypeObject* tp = Py_TYPE(obj); + if (likely(tp->tp_getattro == PyObject_GenericGetAttr)) { + return _PyObject_GenericGetAttrWithDict(obj, attr_name, NULL, 1); + } +#endif + result = __Pyx_PyObject_GetAttrStr(obj, attr_name); + if (unlikely(!result)) { + __Pyx_PyObject_GetAttrStr_ClearAttributeError(); + } + return result; +#endif +} + +/* GetBuiltinName */ +static PyObject *__Pyx_GetBuiltinName(PyObject *name) { + PyObject* result = __Pyx_PyObject_GetAttrStrNoError(__pyx_b, name); + if (unlikely(!result) && !PyErr_Occurred()) { + PyErr_Format(PyExc_NameError, +#if PY_MAJOR_VERSION >= 3 + "name '%U' is not defined", name); +#else + "name '%.200s' is not defined", PyString_AS_STRING(name)); +#endif + } + return result; +} + +/* TupleAndListFromArray */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE void __Pyx_copy_object_array(PyObject *const *CYTHON_RESTRICT src, PyObject** CYTHON_RESTRICT dest, Py_ssize_t length) { + PyObject *v; + Py_ssize_t i; + for (i = 0; i < length; i++) { + v = dest[i] = src[i]; + Py_INCREF(v); + } +} +static CYTHON_INLINE PyObject * +__Pyx_PyTuple_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + Py_INCREF(__pyx_empty_tuple); + return __pyx_empty_tuple; + } + res = PyTuple_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyTupleObject*)res)->ob_item, n); + return res; +} +static CYTHON_INLINE PyObject * +__Pyx_PyList_FromArray(PyObject *const *src, Py_ssize_t n) +{ + PyObject *res; + if (n <= 0) { + return PyList_New(0); + } + res = PyList_New(n); + if (unlikely(res == NULL)) return NULL; + __Pyx_copy_object_array(src, ((PyListObject*)res)->ob_item, n); + return res; +} +#endif + +/* BytesEquals */ +static CYTHON_INLINE int __Pyx_PyBytes_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else + if (s1 == s2) { + return (equals == Py_EQ); + } else if (PyBytes_CheckExact(s1) & PyBytes_CheckExact(s2)) { + const char *ps1, *ps2; + Py_ssize_t length = PyBytes_GET_SIZE(s1); + if (length != PyBytes_GET_SIZE(s2)) + return (equals == Py_NE); + ps1 = PyBytes_AS_STRING(s1); + ps2 = PyBytes_AS_STRING(s2); + if (ps1[0] != ps2[0]) { + return (equals == Py_NE); + } else if (length == 1) { + return (equals == Py_EQ); + } else { + int result; +#if CYTHON_USE_UNICODE_INTERNALS && (PY_VERSION_HEX < 0x030B0000) + Py_hash_t hash1, hash2; + hash1 = ((PyBytesObject*)s1)->ob_shash; + hash2 = ((PyBytesObject*)s2)->ob_shash; + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + return (equals == Py_NE); + } +#endif + result = memcmp(ps1, ps2, (size_t)length); + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & PyBytes_CheckExact(s2)) { + return (equals == Py_NE); + } else if ((s2 == Py_None) & PyBytes_CheckExact(s1)) { + return (equals == Py_NE); + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +#endif +} + +/* UnicodeEquals */ +static CYTHON_INLINE int __Pyx_PyUnicode_Equals(PyObject* s1, PyObject* s2, int equals) { +#if CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API + return PyObject_RichCompareBool(s1, s2, equals); +#else +#if PY_MAJOR_VERSION < 3 + PyObject* owned_ref = NULL; +#endif + int s1_is_unicode, s2_is_unicode; + if (s1 == s2) { + goto return_eq; + } + s1_is_unicode = PyUnicode_CheckExact(s1); + s2_is_unicode = PyUnicode_CheckExact(s2); +#if PY_MAJOR_VERSION < 3 + if ((s1_is_unicode & (!s2_is_unicode)) && PyString_CheckExact(s2)) { + owned_ref = PyUnicode_FromObject(s2); + if (unlikely(!owned_ref)) + return -1; + s2 = owned_ref; + s2_is_unicode = 1; + } else if ((s2_is_unicode & (!s1_is_unicode)) && PyString_CheckExact(s1)) { + owned_ref = PyUnicode_FromObject(s1); + if (unlikely(!owned_ref)) + return -1; + s1 = owned_ref; + s1_is_unicode = 1; + } else if (((!s2_is_unicode) & (!s1_is_unicode))) { + return __Pyx_PyBytes_Equals(s1, s2, equals); + } +#endif + if (s1_is_unicode & s2_is_unicode) { + Py_ssize_t length; + int kind; + void *data1, *data2; + if (unlikely(__Pyx_PyUnicode_READY(s1) < 0) || unlikely(__Pyx_PyUnicode_READY(s2) < 0)) + return -1; + length = __Pyx_PyUnicode_GET_LENGTH(s1); + if (length != __Pyx_PyUnicode_GET_LENGTH(s2)) { + goto return_ne; + } +#if CYTHON_USE_UNICODE_INTERNALS + { + Py_hash_t hash1, hash2; + #if CYTHON_PEP393_ENABLED + hash1 = ((PyASCIIObject*)s1)->hash; + hash2 = ((PyASCIIObject*)s2)->hash; + #else + hash1 = ((PyUnicodeObject*)s1)->hash; + hash2 = ((PyUnicodeObject*)s2)->hash; + #endif + if (hash1 != hash2 && hash1 != -1 && hash2 != -1) { + goto return_ne; + } + } +#endif + kind = __Pyx_PyUnicode_KIND(s1); + if (kind != __Pyx_PyUnicode_KIND(s2)) { + goto return_ne; + } + data1 = __Pyx_PyUnicode_DATA(s1); + data2 = __Pyx_PyUnicode_DATA(s2); + if (__Pyx_PyUnicode_READ(kind, data1, 0) != __Pyx_PyUnicode_READ(kind, data2, 0)) { + goto return_ne; + } else if (length == 1) { + goto return_eq; + } else { + int result = memcmp(data1, data2, (size_t)(length * kind)); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ) ? (result == 0) : (result != 0); + } + } else if ((s1 == Py_None) & s2_is_unicode) { + goto return_ne; + } else if ((s2 == Py_None) & s1_is_unicode) { + goto return_ne; + } else { + int result; + PyObject* py_result = PyObject_RichCompare(s1, s2, equals); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + if (!py_result) + return -1; + result = __Pyx_PyObject_IsTrue(py_result); + Py_DECREF(py_result); + return result; + } +return_eq: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_EQ); +return_ne: + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(owned_ref); + #endif + return (equals == Py_NE); +#endif +} + +/* fastcall */ +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE PyObject * __Pyx_GetKwValue_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues, PyObject *s) +{ + Py_ssize_t i, n = PyTuple_GET_SIZE(kwnames); + for (i = 0; i < n; i++) + { + if (s == PyTuple_GET_ITEM(kwnames, i)) return kwvalues[i]; + } + for (i = 0; i < n; i++) + { + int eq = __Pyx_PyUnicode_Equals(s, PyTuple_GET_ITEM(kwnames, i), Py_EQ); + if (unlikely(eq != 0)) { + if (unlikely(eq < 0)) return NULL; + return kwvalues[i]; + } + } + return NULL; +} +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030d0000 +CYTHON_UNUSED static PyObject *__Pyx_KwargsAsDict_FASTCALL(PyObject *kwnames, PyObject *const *kwvalues) { + Py_ssize_t i, nkwargs = PyTuple_GET_SIZE(kwnames); + PyObject *dict; + dict = PyDict_New(); + if (unlikely(!dict)) + return NULL; + for (i=0; i= 3 + "%s() got multiple values for keyword argument '%U'", func_name, kw_name); + #else + "%s() got multiple values for keyword argument '%s'", func_name, + PyString_AsString(kw_name)); + #endif +} + +/* ParseKeywords */ +static int __Pyx_ParseOptionalKeywords( + PyObject *kwds, + PyObject *const *kwvalues, + PyObject **argnames[], + PyObject *kwds2, + PyObject *values[], + Py_ssize_t num_pos_args, + const char* function_name) +{ + PyObject *key = 0, *value = 0; + Py_ssize_t pos = 0; + PyObject*** name; + PyObject*** first_kw_arg = argnames + num_pos_args; + int kwds_is_tuple = CYTHON_METH_FASTCALL && likely(PyTuple_Check(kwds)); + while (1) { + Py_XDECREF(key); key = NULL; + Py_XDECREF(value); value = NULL; + if (kwds_is_tuple) { + Py_ssize_t size; +#if CYTHON_ASSUME_SAFE_MACROS + size = PyTuple_GET_SIZE(kwds); +#else + size = PyTuple_Size(kwds); + if (size < 0) goto bad; +#endif + if (pos >= size) break; +#if CYTHON_AVOID_BORROWED_REFS + key = __Pyx_PySequence_ITEM(kwds, pos); + if (!key) goto bad; +#elif CYTHON_ASSUME_SAFE_MACROS + key = PyTuple_GET_ITEM(kwds, pos); +#else + key = PyTuple_GetItem(kwds, pos); + if (!key) goto bad; +#endif + value = kwvalues[pos]; + pos++; + } + else + { + if (!PyDict_Next(kwds, &pos, &key, &value)) break; +#if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(key); +#endif + } + name = first_kw_arg; + while (*name && (**name != key)) name++; + if (*name) { + values[name-argnames] = value; +#if CYTHON_AVOID_BORROWED_REFS + Py_INCREF(value); + Py_DECREF(key); +#endif + key = NULL; + value = NULL; + continue; + } +#if !CYTHON_AVOID_BORROWED_REFS + Py_INCREF(key); +#endif + Py_INCREF(value); + name = first_kw_arg; + #if PY_MAJOR_VERSION < 3 + if (likely(PyString_Check(key))) { + while (*name) { + if ((CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**name) == PyString_GET_SIZE(key)) + && _PyString_Eq(**name, key)) { + values[name-argnames] = value; +#if CYTHON_AVOID_BORROWED_REFS + value = NULL; +#endif + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + if ((**argname == key) || ( + (CYTHON_COMPILING_IN_PYPY || PyString_GET_SIZE(**argname) == PyString_GET_SIZE(key)) + && _PyString_Eq(**argname, key))) { + goto arg_passed_twice; + } + argname++; + } + } + } else + #endif + if (likely(PyUnicode_Check(key))) { + while (*name) { + int cmp = ( + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**name) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**name, key) + ); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) { + values[name-argnames] = value; +#if CYTHON_AVOID_BORROWED_REFS + value = NULL; +#endif + break; + } + name++; + } + if (*name) continue; + else { + PyObject*** argname = argnames; + while (argname != first_kw_arg) { + int cmp = (**argname == key) ? 0 : + #if !CYTHON_COMPILING_IN_PYPY && PY_MAJOR_VERSION >= 3 + (__Pyx_PyUnicode_GET_LENGTH(**argname) != __Pyx_PyUnicode_GET_LENGTH(key)) ? 1 : + #endif + PyUnicode_Compare(**argname, key); + if (cmp < 0 && unlikely(PyErr_Occurred())) goto bad; + if (cmp == 0) goto arg_passed_twice; + argname++; + } + } + } else + goto invalid_keyword_type; + if (kwds2) { + if (unlikely(PyDict_SetItem(kwds2, key, value))) goto bad; + } else { + goto invalid_keyword; + } + } + Py_XDECREF(key); + Py_XDECREF(value); + return 0; +arg_passed_twice: + __Pyx_RaiseDoubleKeywordsError(function_name, key); + goto bad; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + goto bad; +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif +bad: + Py_XDECREF(key); + Py_XDECREF(value); + return -1; +} + +/* ArgTypeTest */ +static int __Pyx__ArgTypeTest(PyObject *obj, PyTypeObject *type, const char *name, int exact) +{ + __Pyx_TypeName type_name; + __Pyx_TypeName obj_type_name; + if (unlikely(!type)) { + PyErr_SetString(PyExc_SystemError, "Missing type object"); + return 0; + } + else if (exact) { + #if PY_MAJOR_VERSION == 2 + if ((type == &PyBaseString_Type) && likely(__Pyx_PyBaseString_CheckExact(obj))) return 1; + #endif + } + else { + if (likely(__Pyx_TypeCheck(obj, type))) return 1; + } + type_name = __Pyx_PyType_GetName(type); + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "Argument '%.200s' has incorrect type (expected " __Pyx_FMT_TYPENAME + ", got " __Pyx_FMT_TYPENAME ")", name, type_name, obj_type_name); + __Pyx_DECREF_TypeName(type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return 0; +} + +/* RaiseException */ +#if PY_MAJOR_VERSION < 3 +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + __Pyx_PyThreadState_declare + CYTHON_UNUSED_VAR(cause); + Py_XINCREF(type); + if (!value || value == Py_None) + value = NULL; + else + Py_INCREF(value); + if (!tb || tb == Py_None) + tb = NULL; + else { + Py_INCREF(tb); + if (!PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto raise_error; + } + } + if (PyType_Check(type)) { +#if CYTHON_COMPILING_IN_PYPY + if (!value) { + Py_INCREF(Py_None); + value = Py_None; + } +#endif + PyErr_NormalizeException(&type, &value, &tb); + } else { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto raise_error; + } + value = type; + type = (PyObject*) Py_TYPE(type); + Py_INCREF(type); + if (!PyType_IsSubtype((PyTypeObject *)type, (PyTypeObject *)PyExc_BaseException)) { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto raise_error; + } + } + __Pyx_PyThreadState_assign + __Pyx_ErrRestore(type, value, tb); + return; +raise_error: + Py_XDECREF(value); + Py_XDECREF(type); + Py_XDECREF(tb); + return; +} +#else +static void __Pyx_Raise(PyObject *type, PyObject *value, PyObject *tb, PyObject *cause) { + PyObject* owned_instance = NULL; + if (tb == Py_None) { + tb = 0; + } else if (tb && !PyTraceBack_Check(tb)) { + PyErr_SetString(PyExc_TypeError, + "raise: arg 3 must be a traceback or None"); + goto bad; + } + if (value == Py_None) + value = 0; + if (PyExceptionInstance_Check(type)) { + if (value) { + PyErr_SetString(PyExc_TypeError, + "instance exception may not have a separate value"); + goto bad; + } + value = type; + type = (PyObject*) Py_TYPE(value); + } else if (PyExceptionClass_Check(type)) { + PyObject *instance_class = NULL; + if (value && PyExceptionInstance_Check(value)) { + instance_class = (PyObject*) Py_TYPE(value); + if (instance_class != type) { + int is_subclass = PyObject_IsSubclass(instance_class, type); + if (!is_subclass) { + instance_class = NULL; + } else if (unlikely(is_subclass == -1)) { + goto bad; + } else { + type = instance_class; + } + } + } + if (!instance_class) { + PyObject *args; + if (!value) + args = PyTuple_New(0); + else if (PyTuple_Check(value)) { + Py_INCREF(value); + args = value; + } else + args = PyTuple_Pack(1, value); + if (!args) + goto bad; + owned_instance = PyObject_Call(type, args, NULL); + Py_DECREF(args); + if (!owned_instance) + goto bad; + value = owned_instance; + if (!PyExceptionInstance_Check(value)) { + PyErr_Format(PyExc_TypeError, + "calling %R should have returned an instance of " + "BaseException, not %R", + type, Py_TYPE(value)); + goto bad; + } + } + } else { + PyErr_SetString(PyExc_TypeError, + "raise: exception class must be a subclass of BaseException"); + goto bad; + } + if (cause) { + PyObject *fixed_cause; + if (cause == Py_None) { + fixed_cause = NULL; + } else if (PyExceptionClass_Check(cause)) { + fixed_cause = PyObject_CallObject(cause, NULL); + if (fixed_cause == NULL) + goto bad; + } else if (PyExceptionInstance_Check(cause)) { + fixed_cause = cause; + Py_INCREF(fixed_cause); + } else { + PyErr_SetString(PyExc_TypeError, + "exception causes must derive from " + "BaseException"); + goto bad; + } + PyException_SetCause(value, fixed_cause); + } + PyErr_SetObject(type, value); + if (tb) { + #if PY_VERSION_HEX >= 0x030C00A6 + PyException_SetTraceback(value, tb); + #elif CYTHON_FAST_THREAD_STATE + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject* tmp_tb = tstate->curexc_traceback; + if (tb != tmp_tb) { + Py_INCREF(tb); + tstate->curexc_traceback = tb; + Py_XDECREF(tmp_tb); + } +#else + PyObject *tmp_type, *tmp_value, *tmp_tb; + PyErr_Fetch(&tmp_type, &tmp_value, &tmp_tb); + Py_INCREF(tb); + PyErr_Restore(tmp_type, tmp_value, tb); + Py_XDECREF(tmp_tb); +#endif + } +bad: + Py_XDECREF(owned_instance); + return; +} +#endif + +/* PyFunctionFastCall */ +#if CYTHON_FAST_PYCALL && !CYTHON_VECTORCALL +static PyObject* __Pyx_PyFunction_FastCallNoKw(PyCodeObject *co, PyObject **args, Py_ssize_t na, + PyObject *globals) { + PyFrameObject *f; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject **fastlocals; + Py_ssize_t i; + PyObject *result; + assert(globals != NULL); + /* XXX Perhaps we should create a specialized + PyFrame_New() that doesn't take locals, but does + take builtins without sanity checking them. + */ + assert(tstate != NULL); + f = PyFrame_New(tstate, co, globals, NULL); + if (f == NULL) { + return NULL; + } + fastlocals = __Pyx_PyFrame_GetLocalsplus(f); + for (i = 0; i < na; i++) { + Py_INCREF(*args); + fastlocals[i] = *args++; + } + result = PyEval_EvalFrameEx(f,0); + ++tstate->recursion_depth; + Py_DECREF(f); + --tstate->recursion_depth; + return result; +} +static PyObject *__Pyx_PyFunction_FastCallDict(PyObject *func, PyObject **args, Py_ssize_t nargs, PyObject *kwargs) { + PyCodeObject *co = (PyCodeObject *)PyFunction_GET_CODE(func); + PyObject *globals = PyFunction_GET_GLOBALS(func); + PyObject *argdefs = PyFunction_GET_DEFAULTS(func); + PyObject *closure; +#if PY_MAJOR_VERSION >= 3 + PyObject *kwdefs; +#endif + PyObject *kwtuple, **k; + PyObject **d; + Py_ssize_t nd; + Py_ssize_t nk; + PyObject *result; + assert(kwargs == NULL || PyDict_Check(kwargs)); + nk = kwargs ? PyDict_Size(kwargs) : 0; + #if PY_MAJOR_VERSION < 3 + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) { + return NULL; + } + #else + if (unlikely(Py_EnterRecursiveCall(" while calling a Python object"))) { + return NULL; + } + #endif + if ( +#if PY_MAJOR_VERSION >= 3 + co->co_kwonlyargcount == 0 && +#endif + likely(kwargs == NULL || nk == 0) && + co->co_flags == (CO_OPTIMIZED | CO_NEWLOCALS | CO_NOFREE)) { + if (argdefs == NULL && co->co_argcount == nargs) { + result = __Pyx_PyFunction_FastCallNoKw(co, args, nargs, globals); + goto done; + } + else if (nargs == 0 && argdefs != NULL + && co->co_argcount == Py_SIZE(argdefs)) { + /* function called with no arguments, but all parameters have + a default value: use default values as arguments .*/ + args = &PyTuple_GET_ITEM(argdefs, 0); + result =__Pyx_PyFunction_FastCallNoKw(co, args, Py_SIZE(argdefs), globals); + goto done; + } + } + if (kwargs != NULL) { + Py_ssize_t pos, i; + kwtuple = PyTuple_New(2 * nk); + if (kwtuple == NULL) { + result = NULL; + goto done; + } + k = &PyTuple_GET_ITEM(kwtuple, 0); + pos = i = 0; + while (PyDict_Next(kwargs, &pos, &k[i], &k[i+1])) { + Py_INCREF(k[i]); + Py_INCREF(k[i+1]); + i += 2; + } + nk = i / 2; + } + else { + kwtuple = NULL; + k = NULL; + } + closure = PyFunction_GET_CLOSURE(func); +#if PY_MAJOR_VERSION >= 3 + kwdefs = PyFunction_GET_KW_DEFAULTS(func); +#endif + if (argdefs != NULL) { + d = &PyTuple_GET_ITEM(argdefs, 0); + nd = Py_SIZE(argdefs); + } + else { + d = NULL; + nd = 0; + } +#if PY_MAJOR_VERSION >= 3 + result = PyEval_EvalCodeEx((PyObject*)co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, kwdefs, closure); +#else + result = PyEval_EvalCodeEx(co, globals, (PyObject *)NULL, + args, (int)nargs, + k, (int)nk, + d, (int)nd, closure); +#endif + Py_XDECREF(kwtuple); +done: + Py_LeaveRecursiveCall(); + return result; +} +#endif + +/* PyObjectCall */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_Call(PyObject *func, PyObject *arg, PyObject *kw) { + PyObject *result; + ternaryfunc call = Py_TYPE(func)->tp_call; + if (unlikely(!call)) + return PyObject_Call(func, arg, kw); + #if PY_MAJOR_VERSION < 3 + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + #else + if (unlikely(Py_EnterRecursiveCall(" while calling a Python object"))) + return NULL; + #endif + result = (*call)(func, arg, kw); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* PyObjectCallMethO */ +#if CYTHON_COMPILING_IN_CPYTHON +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallMethO(PyObject *func, PyObject *arg) { + PyObject *self, *result; + PyCFunction cfunc; + cfunc = __Pyx_CyOrPyCFunction_GET_FUNCTION(func); + self = __Pyx_CyOrPyCFunction_GET_SELF(func); + #if PY_MAJOR_VERSION < 3 + if (unlikely(Py_EnterRecursiveCall((char*)" while calling a Python object"))) + return NULL; + #else + if (unlikely(Py_EnterRecursiveCall(" while calling a Python object"))) + return NULL; + #endif + result = cfunc(self, arg); + Py_LeaveRecursiveCall(); + if (unlikely(!result) && unlikely(!PyErr_Occurred())) { + PyErr_SetString( + PyExc_SystemError, + "NULL result without error in PyObject_Call"); + } + return result; +} +#endif + +/* PyObjectFastCall */ +#if PY_VERSION_HEX < 0x03090000 || CYTHON_COMPILING_IN_LIMITED_API +static PyObject* __Pyx_PyObject_FastCall_fallback(PyObject *func, PyObject **args, size_t nargs, PyObject *kwargs) { + PyObject *argstuple; + PyObject *result = 0; + size_t i; + argstuple = PyTuple_New((Py_ssize_t)nargs); + if (unlikely(!argstuple)) return NULL; + for (i = 0; i < nargs; i++) { + Py_INCREF(args[i]); + if (__Pyx_PyTuple_SET_ITEM(argstuple, (Py_ssize_t)i, args[i]) < 0) goto bad; + } + result = __Pyx_PyObject_Call(func, argstuple, kwargs); + bad: + Py_DECREF(argstuple); + return result; +} +#endif +static CYTHON_INLINE PyObject* __Pyx_PyObject_FastCallDict(PyObject *func, PyObject **args, size_t _nargs, PyObject *kwargs) { + Py_ssize_t nargs = __Pyx_PyVectorcall_NARGS(_nargs); +#if CYTHON_COMPILING_IN_CPYTHON + if (nargs == 0 && kwargs == NULL) { + if (__Pyx_CyOrPyCFunction_Check(func) && likely( __Pyx_CyOrPyCFunction_GET_FLAGS(func) & METH_NOARGS)) + return __Pyx_PyObject_CallMethO(func, NULL); + } + else if (nargs == 1 && kwargs == NULL) { + if (__Pyx_CyOrPyCFunction_Check(func) && likely( __Pyx_CyOrPyCFunction_GET_FLAGS(func) & METH_O)) + return __Pyx_PyObject_CallMethO(func, args[0]); + } +#endif + #if PY_VERSION_HEX < 0x030800B1 + #if CYTHON_FAST_PYCCALL + if (PyCFunction_Check(func)) { + if (kwargs) { + return _PyCFunction_FastCallDict(func, args, nargs, kwargs); + } else { + return _PyCFunction_FastCallKeywords(func, args, nargs, NULL); + } + } + #if PY_VERSION_HEX >= 0x030700A1 + if (!kwargs && __Pyx_IS_TYPE(func, &PyMethodDescr_Type)) { + return _PyMethodDescr_FastCallKeywords(func, args, nargs, NULL); + } + #endif + #endif + #if CYTHON_FAST_PYCALL + if (PyFunction_Check(func)) { + return __Pyx_PyFunction_FastCallDict(func, args, nargs, kwargs); + } + #endif + #endif + if (kwargs == NULL) { + #if CYTHON_VECTORCALL + #if PY_VERSION_HEX < 0x03090000 + vectorcallfunc f = _PyVectorcall_Function(func); + #else + vectorcallfunc f = PyVectorcall_Function(func); + #endif + if (f) { + return f(func, args, (size_t)nargs, NULL); + } + #elif defined(__Pyx_CyFunction_USED) && CYTHON_BACKPORT_VECTORCALL + if (__Pyx_CyFunction_CheckExact(func)) { + __pyx_vectorcallfunc f = __Pyx_CyFunction_func_vectorcall(func); + if (f) return f(func, args, (size_t)nargs, NULL); + } + #endif + } + if (nargs == 0) { + return __Pyx_PyObject_Call(func, __pyx_empty_tuple, kwargs); + } + #if PY_VERSION_HEX >= 0x03090000 && !CYTHON_COMPILING_IN_LIMITED_API + return PyObject_VectorcallDict(func, args, (size_t)nargs, kwargs); + #else + return __Pyx_PyObject_FastCall_fallback(func, args, (size_t)nargs, kwargs); + #endif +} + +/* RaiseUnexpectedTypeError */ +static int +__Pyx_RaiseUnexpectedTypeError(const char *expected, PyObject *obj) +{ + __Pyx_TypeName obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, "Expected %s, got " __Pyx_FMT_TYPENAME, + expected, obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return 0; +} + +/* CIntToDigits */ +static const char DIGIT_PAIRS_10[2*10*10+1] = { + "00010203040506070809" + "10111213141516171819" + "20212223242526272829" + "30313233343536373839" + "40414243444546474849" + "50515253545556575859" + "60616263646566676869" + "70717273747576777879" + "80818283848586878889" + "90919293949596979899" +}; +static const char DIGIT_PAIRS_8[2*8*8+1] = { + "0001020304050607" + "1011121314151617" + "2021222324252627" + "3031323334353637" + "4041424344454647" + "5051525354555657" + "6061626364656667" + "7071727374757677" +}; +static const char DIGITS_HEX[2*16+1] = { + "0123456789abcdef" + "0123456789ABCDEF" +}; + +/* BuildPyUnicode */ +static PyObject* __Pyx_PyUnicode_BuildFromAscii(Py_ssize_t ulength, char* chars, int clength, + int prepend_sign, char padding_char) { + PyObject *uval; + Py_ssize_t uoffset = ulength - clength; +#if CYTHON_USE_UNICODE_INTERNALS + Py_ssize_t i; +#if CYTHON_PEP393_ENABLED + void *udata; + uval = PyUnicode_New(ulength, 127); + if (unlikely(!uval)) return NULL; + udata = PyUnicode_DATA(uval); +#else + Py_UNICODE *udata; + uval = PyUnicode_FromUnicode(NULL, ulength); + if (unlikely(!uval)) return NULL; + udata = PyUnicode_AS_UNICODE(uval); +#endif + if (uoffset > 0) { + i = 0; + if (prepend_sign) { + __Pyx_PyUnicode_WRITE(PyUnicode_1BYTE_KIND, udata, 0, '-'); + i++; + } + for (; i < uoffset; i++) { + __Pyx_PyUnicode_WRITE(PyUnicode_1BYTE_KIND, udata, i, padding_char); + } + } + for (i=0; i < clength; i++) { + __Pyx_PyUnicode_WRITE(PyUnicode_1BYTE_KIND, udata, uoffset+i, chars[i]); + } +#else + { + PyObject *sign = NULL, *padding = NULL; + uval = NULL; + if (uoffset > 0) { + prepend_sign = !!prepend_sign; + if (uoffset > prepend_sign) { + padding = PyUnicode_FromOrdinal(padding_char); + if (likely(padding) && uoffset > prepend_sign + 1) { + PyObject *tmp; + PyObject *repeat = PyInt_FromSsize_t(uoffset - prepend_sign); + if (unlikely(!repeat)) goto done_or_error; + tmp = PyNumber_Multiply(padding, repeat); + Py_DECREF(repeat); + Py_DECREF(padding); + padding = tmp; + } + if (unlikely(!padding)) goto done_or_error; + } + if (prepend_sign) { + sign = PyUnicode_FromOrdinal('-'); + if (unlikely(!sign)) goto done_or_error; + } + } + uval = PyUnicode_DecodeASCII(chars, clength, NULL); + if (likely(uval) && padding) { + PyObject *tmp = PyNumber_Add(padding, uval); + Py_DECREF(uval); + uval = tmp; + } + if (likely(uval) && sign) { + PyObject *tmp = PyNumber_Add(sign, uval); + Py_DECREF(uval); + uval = tmp; + } +done_or_error: + Py_XDECREF(padding); + Py_XDECREF(sign); + } +#endif + return uval; +} + +/* CIntToPyUnicode */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_int(int value, Py_ssize_t width, char padding_char, char format_char) { + char digits[sizeof(int)*3+2]; + char *dpos, *end = digits + sizeof(int)*3+2; + const char *hex_digits = DIGITS_HEX; + Py_ssize_t length, ulength; + int prepend_sign, last_one_off; + int remaining; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (format_char == 'X') { + hex_digits += 16; + format_char = 'x'; + } + remaining = value; + last_one_off = 0; + dpos = end; + do { + int digit_pos; + switch (format_char) { + case 'o': + digit_pos = abs((int)(remaining % (8*8))); + remaining = (int) (remaining / (8*8)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_8 + digit_pos * 2, 2); + last_one_off = (digit_pos < 8); + break; + case 'd': + digit_pos = abs((int)(remaining % (10*10))); + remaining = (int) (remaining / (10*10)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_10 + digit_pos * 2, 2); + last_one_off = (digit_pos < 10); + break; + case 'x': + *(--dpos) = hex_digits[abs((int)(remaining % 16))]; + remaining = (int) (remaining / 16); + break; + default: + assert(0); + break; + } + } while (unlikely(remaining != 0)); + assert(!last_one_off || *dpos == '0'); + dpos += last_one_off; + length = end - dpos; + ulength = length; + prepend_sign = 0; + if (!is_unsigned && value <= neg_one) { + if (padding_char == ' ' || width <= length + 1) { + *(--dpos) = '-'; + ++length; + } else { + prepend_sign = 1; + } + ++ulength; + } + if (width > ulength) { + ulength = width; + } + if (ulength == 1) { + return PyUnicode_FromOrdinal(*dpos); + } + return __Pyx_PyUnicode_BuildFromAscii(ulength, dpos, (int) length, prepend_sign, padding_char); +} + +/* CIntToPyUnicode */ +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_From_Py_ssize_t(Py_ssize_t value, Py_ssize_t width, char padding_char, char format_char) { + char digits[sizeof(Py_ssize_t)*3+2]; + char *dpos, *end = digits + sizeof(Py_ssize_t)*3+2; + const char *hex_digits = DIGITS_HEX; + Py_ssize_t length, ulength; + int prepend_sign, last_one_off; + Py_ssize_t remaining; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const Py_ssize_t neg_one = (Py_ssize_t) -1, const_zero = (Py_ssize_t) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (format_char == 'X') { + hex_digits += 16; + format_char = 'x'; + } + remaining = value; + last_one_off = 0; + dpos = end; + do { + int digit_pos; + switch (format_char) { + case 'o': + digit_pos = abs((int)(remaining % (8*8))); + remaining = (Py_ssize_t) (remaining / (8*8)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_8 + digit_pos * 2, 2); + last_one_off = (digit_pos < 8); + break; + case 'd': + digit_pos = abs((int)(remaining % (10*10))); + remaining = (Py_ssize_t) (remaining / (10*10)); + dpos -= 2; + memcpy(dpos, DIGIT_PAIRS_10 + digit_pos * 2, 2); + last_one_off = (digit_pos < 10); + break; + case 'x': + *(--dpos) = hex_digits[abs((int)(remaining % 16))]; + remaining = (Py_ssize_t) (remaining / 16); + break; + default: + assert(0); + break; + } + } while (unlikely(remaining != 0)); + assert(!last_one_off || *dpos == '0'); + dpos += last_one_off; + length = end - dpos; + ulength = length; + prepend_sign = 0; + if (!is_unsigned && value <= neg_one) { + if (padding_char == ' ' || width <= length + 1) { + *(--dpos) = '-'; + ++length; + } else { + prepend_sign = 1; + } + ++ulength; + } + if (width > ulength) { + ulength = width; + } + if (ulength == 1) { + return PyUnicode_FromOrdinal(*dpos); + } + return __Pyx_PyUnicode_BuildFromAscii(ulength, dpos, (int) length, prepend_sign, padding_char); +} + +/* JoinPyUnicode */ +static PyObject* __Pyx_PyUnicode_Join(PyObject* value_tuple, Py_ssize_t value_count, Py_ssize_t result_ulength, + Py_UCS4 max_char) { +#if CYTHON_USE_UNICODE_INTERNALS && CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + PyObject *result_uval; + int result_ukind, kind_shift; + Py_ssize_t i, char_pos; + void *result_udata; + CYTHON_MAYBE_UNUSED_VAR(max_char); +#if CYTHON_PEP393_ENABLED + result_uval = PyUnicode_New(result_ulength, max_char); + if (unlikely(!result_uval)) return NULL; + result_ukind = (max_char <= 255) ? PyUnicode_1BYTE_KIND : (max_char <= 65535) ? PyUnicode_2BYTE_KIND : PyUnicode_4BYTE_KIND; + kind_shift = (result_ukind == PyUnicode_4BYTE_KIND) ? 2 : result_ukind - 1; + result_udata = PyUnicode_DATA(result_uval); +#else + result_uval = PyUnicode_FromUnicode(NULL, result_ulength); + if (unlikely(!result_uval)) return NULL; + result_ukind = sizeof(Py_UNICODE); + kind_shift = (result_ukind == 4) ? 2 : result_ukind - 1; + result_udata = PyUnicode_AS_UNICODE(result_uval); +#endif + assert(kind_shift == 2 || kind_shift == 1 || kind_shift == 0); + char_pos = 0; + for (i=0; i < value_count; i++) { + int ukind; + Py_ssize_t ulength; + void *udata; + PyObject *uval = PyTuple_GET_ITEM(value_tuple, i); + if (unlikely(__Pyx_PyUnicode_READY(uval))) + goto bad; + ulength = __Pyx_PyUnicode_GET_LENGTH(uval); + if (unlikely(!ulength)) + continue; + if (unlikely((PY_SSIZE_T_MAX >> kind_shift) - ulength < char_pos)) + goto overflow; + ukind = __Pyx_PyUnicode_KIND(uval); + udata = __Pyx_PyUnicode_DATA(uval); + if (!CYTHON_PEP393_ENABLED || ukind == result_ukind) { + memcpy((char *)result_udata + (char_pos << kind_shift), udata, (size_t) (ulength << kind_shift)); + } else { + #if PY_VERSION_HEX >= 0x030d0000 + if (unlikely(PyUnicode_CopyCharacters(result_uval, char_pos, uval, 0, ulength) < 0)) goto bad; + #elif CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030300F0 || defined(_PyUnicode_FastCopyCharacters) + _PyUnicode_FastCopyCharacters(result_uval, char_pos, uval, 0, ulength); + #else + Py_ssize_t j; + for (j=0; j < ulength; j++) { + Py_UCS4 uchar = __Pyx_PyUnicode_READ(ukind, udata, j); + __Pyx_PyUnicode_WRITE(result_ukind, result_udata, char_pos+j, uchar); + } + #endif + } + char_pos += ulength; + } + return result_uval; +overflow: + PyErr_SetString(PyExc_OverflowError, "join() result is too long for a Python string"); +bad: + Py_DECREF(result_uval); + return NULL; +#else + CYTHON_UNUSED_VAR(max_char); + CYTHON_UNUSED_VAR(result_ulength); + CYTHON_UNUSED_VAR(value_count); + return PyUnicode_Join(__pyx_empty_unicode, value_tuple); +#endif +} + +/* GetAttr */ +static CYTHON_INLINE PyObject *__Pyx_GetAttr(PyObject *o, PyObject *n) { +#if CYTHON_USE_TYPE_SLOTS +#if PY_MAJOR_VERSION >= 3 + if (likely(PyUnicode_Check(n))) +#else + if (likely(PyString_Check(n))) +#endif + return __Pyx_PyObject_GetAttrStr(o, n); +#endif + return PyObject_GetAttr(o, n); +} + +/* GetItemInt */ +static PyObject *__Pyx_GetItemInt_Generic(PyObject *o, PyObject* j) { + PyObject *r; + if (unlikely(!j)) return NULL; + r = PyObject_GetItem(o, j); + Py_DECREF(j); + return r; +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_List_Fast(PyObject *o, Py_ssize_t i, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + Py_ssize_t wrapped_i = i; + if (wraparound & unlikely(i < 0)) { + wrapped_i += PyList_GET_SIZE(o); + } + if ((!boundscheck) || likely(__Pyx_is_valid_index(wrapped_i, PyList_GET_SIZE(o)))) { + PyObject *r = PyList_GET_ITEM(o, wrapped_i); + Py_INCREF(r); + return r; + } + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +#else + return PySequence_GetItem(o, i); +#endif +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Tuple_Fast(PyObject *o, Py_ssize_t i, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + Py_ssize_t wrapped_i = i; + if (wraparound & unlikely(i < 0)) { + wrapped_i += PyTuple_GET_SIZE(o); + } + if ((!boundscheck) || likely(__Pyx_is_valid_index(wrapped_i, PyTuple_GET_SIZE(o)))) { + PyObject *r = PyTuple_GET_ITEM(o, wrapped_i); + Py_INCREF(r); + return r; + } + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +#else + return PySequence_GetItem(o, i); +#endif +} +static CYTHON_INLINE PyObject *__Pyx_GetItemInt_Fast(PyObject *o, Py_ssize_t i, int is_list, + CYTHON_NCP_UNUSED int wraparound, + CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS && CYTHON_USE_TYPE_SLOTS + if (is_list || PyList_CheckExact(o)) { + Py_ssize_t n = ((!wraparound) | likely(i >= 0)) ? i : i + PyList_GET_SIZE(o); + if ((!boundscheck) || (likely(__Pyx_is_valid_index(n, PyList_GET_SIZE(o))))) { + PyObject *r = PyList_GET_ITEM(o, n); + Py_INCREF(r); + return r; + } + } + else if (PyTuple_CheckExact(o)) { + Py_ssize_t n = ((!wraparound) | likely(i >= 0)) ? i : i + PyTuple_GET_SIZE(o); + if ((!boundscheck) || likely(__Pyx_is_valid_index(n, PyTuple_GET_SIZE(o)))) { + PyObject *r = PyTuple_GET_ITEM(o, n); + Py_INCREF(r); + return r; + } + } else { + PyMappingMethods *mm = Py_TYPE(o)->tp_as_mapping; + PySequenceMethods *sm = Py_TYPE(o)->tp_as_sequence; + if (mm && mm->mp_subscript) { + PyObject *r, *key = PyInt_FromSsize_t(i); + if (unlikely(!key)) return NULL; + r = mm->mp_subscript(o, key); + Py_DECREF(key); + return r; + } + if (likely(sm && sm->sq_item)) { + if (wraparound && unlikely(i < 0) && likely(sm->sq_length)) { + Py_ssize_t l = sm->sq_length(o); + if (likely(l >= 0)) { + i += l; + } else { + if (!PyErr_ExceptionMatches(PyExc_OverflowError)) + return NULL; + PyErr_Clear(); + } + } + return sm->sq_item(o, i); + } + } +#else + if (is_list || !PyMapping_Check(o)) { + return PySequence_GetItem(o, i); + } +#endif + return __Pyx_GetItemInt_Generic(o, PyInt_FromSsize_t(i)); +} + +/* PyObjectCallOneArg */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallOneArg(PyObject *func, PyObject *arg) { + PyObject *args[2] = {NULL, arg}; + return __Pyx_PyObject_FastCall(func, args+1, 1 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* ObjectGetItem */ +#if CYTHON_USE_TYPE_SLOTS +static PyObject *__Pyx_PyObject_GetIndex(PyObject *obj, PyObject *index) { + PyObject *runerr = NULL; + Py_ssize_t key_value; + key_value = __Pyx_PyIndex_AsSsize_t(index); + if (likely(key_value != -1 || !(runerr = PyErr_Occurred()))) { + return __Pyx_GetItemInt_Fast(obj, key_value, 0, 1, 1); + } + if (PyErr_GivenExceptionMatches(runerr, PyExc_OverflowError)) { + __Pyx_TypeName index_type_name = __Pyx_PyType_GetName(Py_TYPE(index)); + PyErr_Clear(); + PyErr_Format(PyExc_IndexError, + "cannot fit '" __Pyx_FMT_TYPENAME "' into an index-sized integer", index_type_name); + __Pyx_DECREF_TypeName(index_type_name); + } + return NULL; +} +static PyObject *__Pyx_PyObject_GetItem_Slow(PyObject *obj, PyObject *key) { + __Pyx_TypeName obj_type_name; + if (likely(PyType_Check(obj))) { + PyObject *meth = __Pyx_PyObject_GetAttrStrNoError(obj, __pyx_n_s_class_getitem); + if (!meth) { + PyErr_Clear(); + } else { + PyObject *result = __Pyx_PyObject_CallOneArg(meth, key); + Py_DECREF(meth); + return result; + } + } + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "'" __Pyx_FMT_TYPENAME "' object is not subscriptable", obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return NULL; +} +static PyObject *__Pyx_PyObject_GetItem(PyObject *obj, PyObject *key) { + PyTypeObject *tp = Py_TYPE(obj); + PyMappingMethods *mm = tp->tp_as_mapping; + PySequenceMethods *sm = tp->tp_as_sequence; + if (likely(mm && mm->mp_subscript)) { + return mm->mp_subscript(obj, key); + } + if (likely(sm && sm->sq_item)) { + return __Pyx_PyObject_GetIndex(obj, key); + } + return __Pyx_PyObject_GetItem_Slow(obj, key); +} +#endif + +/* KeywordStringCheck */ +static int __Pyx_CheckKeywordStrings( + PyObject *kw, + const char* function_name, + int kw_allowed) +{ + PyObject* key = 0; + Py_ssize_t pos = 0; +#if CYTHON_COMPILING_IN_PYPY + if (!kw_allowed && PyDict_Next(kw, &pos, &key, 0)) + goto invalid_keyword; + return 1; +#else + if (CYTHON_METH_FASTCALL && likely(PyTuple_Check(kw))) { + Py_ssize_t kwsize; +#if CYTHON_ASSUME_SAFE_MACROS + kwsize = PyTuple_GET_SIZE(kw); +#else + kwsize = PyTuple_Size(kw); + if (kwsize < 0) return 0; +#endif + if (unlikely(kwsize == 0)) + return 1; + if (!kw_allowed) { +#if CYTHON_ASSUME_SAFE_MACROS + key = PyTuple_GET_ITEM(kw, 0); +#else + key = PyTuple_GetItem(kw, pos); + if (!key) return 0; +#endif + goto invalid_keyword; + } +#if PY_VERSION_HEX < 0x03090000 + for (pos = 0; pos < kwsize; pos++) { +#if CYTHON_ASSUME_SAFE_MACROS + key = PyTuple_GET_ITEM(kw, pos); +#else + key = PyTuple_GetItem(kw, pos); + if (!key) return 0; +#endif + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } +#endif + return 1; + } + while (PyDict_Next(kw, &pos, &key, 0)) { + #if PY_MAJOR_VERSION < 3 + if (unlikely(!PyString_Check(key))) + #endif + if (unlikely(!PyUnicode_Check(key))) + goto invalid_keyword_type; + } + if (!kw_allowed && unlikely(key)) + goto invalid_keyword; + return 1; +invalid_keyword_type: + PyErr_Format(PyExc_TypeError, + "%.200s() keywords must be strings", function_name); + return 0; +#endif +invalid_keyword: + #if PY_MAJOR_VERSION < 3 + PyErr_Format(PyExc_TypeError, + "%.200s() got an unexpected keyword argument '%.200s'", + function_name, PyString_AsString(key)); + #else + PyErr_Format(PyExc_TypeError, + "%s() got an unexpected keyword argument '%U'", + function_name, key); + #endif + return 0; +} + +/* DivInt[Py_ssize_t] */ +static CYTHON_INLINE Py_ssize_t __Pyx_div_Py_ssize_t(Py_ssize_t a, Py_ssize_t b) { + Py_ssize_t q = a / b; + Py_ssize_t r = a - q*b; + q -= ((r != 0) & ((r ^ b) < 0)); + return q; +} + +/* GetAttr3 */ +#if __PYX_LIMITED_VERSION_HEX < 0x030d00A1 +static PyObject *__Pyx_GetAttr3Default(PyObject *d) { + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + if (unlikely(!__Pyx_PyErr_ExceptionMatches(PyExc_AttributeError))) + return NULL; + __Pyx_PyErr_Clear(); + Py_INCREF(d); + return d; +} +#endif +static CYTHON_INLINE PyObject *__Pyx_GetAttr3(PyObject *o, PyObject *n, PyObject *d) { + PyObject *r; +#if __PYX_LIMITED_VERSION_HEX >= 0x030d00A1 + int res = PyObject_GetOptionalAttr(o, n, &r); + return (res != 0) ? r : __Pyx_NewRef(d); +#else + #if CYTHON_USE_TYPE_SLOTS + if (likely(PyString_Check(n))) { + r = __Pyx_PyObject_GetAttrStrNoError(o, n); + if (unlikely(!r) && likely(!PyErr_Occurred())) { + r = __Pyx_NewRef(d); + } + return r; + } + #endif + r = PyObject_GetAttr(o, n); + return (likely(r)) ? r : __Pyx_GetAttr3Default(d); +#endif +} + +/* PyDictVersioning */ +#if CYTHON_USE_DICT_VERSIONS && CYTHON_USE_TYPE_SLOTS +static CYTHON_INLINE PY_UINT64_T __Pyx_get_tp_dict_version(PyObject *obj) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + return likely(dict) ? __PYX_GET_DICT_VERSION(dict) : 0; +} +static CYTHON_INLINE PY_UINT64_T __Pyx_get_object_dict_version(PyObject *obj) { + PyObject **dictptr = NULL; + Py_ssize_t offset = Py_TYPE(obj)->tp_dictoffset; + if (offset) { +#if CYTHON_COMPILING_IN_CPYTHON + dictptr = (likely(offset > 0)) ? (PyObject **) ((char *)obj + offset) : _PyObject_GetDictPtr(obj); +#else + dictptr = _PyObject_GetDictPtr(obj); +#endif + } + return (dictptr && *dictptr) ? __PYX_GET_DICT_VERSION(*dictptr) : 0; +} +static CYTHON_INLINE int __Pyx_object_dict_version_matches(PyObject* obj, PY_UINT64_T tp_dict_version, PY_UINT64_T obj_dict_version) { + PyObject *dict = Py_TYPE(obj)->tp_dict; + if (unlikely(!dict) || unlikely(tp_dict_version != __PYX_GET_DICT_VERSION(dict))) + return 0; + return obj_dict_version == __Pyx_get_object_dict_version(obj); +} +#endif + +/* GetModuleGlobalName */ +#if CYTHON_USE_DICT_VERSIONS +static PyObject *__Pyx__GetModuleGlobalName(PyObject *name, PY_UINT64_T *dict_version, PyObject **dict_cached_value) +#else +static CYTHON_INLINE PyObject *__Pyx__GetModuleGlobalName(PyObject *name) +#endif +{ + PyObject *result; +#if !CYTHON_AVOID_BORROWED_REFS +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030500A1 && PY_VERSION_HEX < 0x030d0000 + result = _PyDict_GetItem_KnownHash(__pyx_d, name, ((PyASCIIObject *) name)->hash); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } else if (unlikely(PyErr_Occurred())) { + return NULL; + } +#elif CYTHON_COMPILING_IN_LIMITED_API + if (unlikely(!__pyx_m)) { + return NULL; + } + result = PyObject_GetAttr(__pyx_m, name); + if (likely(result)) { + return result; + } +#else + result = PyDict_GetItem(__pyx_d, name); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } +#endif +#else + result = PyObject_GetItem(__pyx_d, name); + __PYX_UPDATE_DICT_CACHE(__pyx_d, result, *dict_cached_value, *dict_version) + if (likely(result)) { + return __Pyx_NewRef(result); + } + PyErr_Clear(); +#endif + return __Pyx_GetBuiltinName(name); +} + +/* RaiseTooManyValuesToUnpack */ +static CYTHON_INLINE void __Pyx_RaiseTooManyValuesError(Py_ssize_t expected) { + PyErr_Format(PyExc_ValueError, + "too many values to unpack (expected %" CYTHON_FORMAT_SSIZE_T "d)", expected); +} + +/* RaiseNeedMoreValuesToUnpack */ +static CYTHON_INLINE void __Pyx_RaiseNeedMoreValuesError(Py_ssize_t index) { + PyErr_Format(PyExc_ValueError, + "need more than %" CYTHON_FORMAT_SSIZE_T "d value%.1s to unpack", + index, (index == 1) ? "" : "s"); +} + +/* RaiseNoneIterError */ +static CYTHON_INLINE void __Pyx_RaiseNoneNotIterableError(void) { + PyErr_SetString(PyExc_TypeError, "'NoneType' object is not iterable"); +} + +/* ExtTypeTest */ +static CYTHON_INLINE int __Pyx_TypeTest(PyObject *obj, PyTypeObject *type) { + __Pyx_TypeName obj_type_name; + __Pyx_TypeName type_name; + if (unlikely(!type)) { + PyErr_SetString(PyExc_SystemError, "Missing type object"); + return 0; + } + if (likely(__Pyx_TypeCheck(obj, type))) + return 1; + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + type_name = __Pyx_PyType_GetName(type); + PyErr_Format(PyExc_TypeError, + "Cannot convert " __Pyx_FMT_TYPENAME " to " __Pyx_FMT_TYPENAME, + obj_type_name, type_name); + __Pyx_DECREF_TypeName(obj_type_name); + __Pyx_DECREF_TypeName(type_name); + return 0; +} + +/* GetTopmostException */ +#if CYTHON_USE_EXC_INFO_STACK && CYTHON_FAST_THREAD_STATE +static _PyErr_StackItem * +__Pyx_PyErr_GetTopmostException(PyThreadState *tstate) +{ + _PyErr_StackItem *exc_info = tstate->exc_info; + while ((exc_info->exc_value == NULL || exc_info->exc_value == Py_None) && + exc_info->previous_item != NULL) + { + exc_info = exc_info->previous_item; + } + return exc_info; +} +#endif + +/* SaveResetException */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx__ExceptionSave(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { + #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 + _PyErr_StackItem *exc_info = __Pyx_PyErr_GetTopmostException(tstate); + PyObject *exc_value = exc_info->exc_value; + if (exc_value == NULL || exc_value == Py_None) { + *value = NULL; + *type = NULL; + *tb = NULL; + } else { + *value = exc_value; + Py_INCREF(*value); + *type = (PyObject*) Py_TYPE(exc_value); + Py_INCREF(*type); + *tb = PyException_GetTraceback(exc_value); + } + #elif CYTHON_USE_EXC_INFO_STACK + _PyErr_StackItem *exc_info = __Pyx_PyErr_GetTopmostException(tstate); + *type = exc_info->exc_type; + *value = exc_info->exc_value; + *tb = exc_info->exc_traceback; + Py_XINCREF(*type); + Py_XINCREF(*value); + Py_XINCREF(*tb); + #else + *type = tstate->exc_type; + *value = tstate->exc_value; + *tb = tstate->exc_traceback; + Py_XINCREF(*type); + Py_XINCREF(*value); + Py_XINCREF(*tb); + #endif +} +static CYTHON_INLINE void __Pyx__ExceptionReset(PyThreadState *tstate, PyObject *type, PyObject *value, PyObject *tb) { + #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 + _PyErr_StackItem *exc_info = tstate->exc_info; + PyObject *tmp_value = exc_info->exc_value; + exc_info->exc_value = value; + Py_XDECREF(tmp_value); + Py_XDECREF(type); + Py_XDECREF(tb); + #else + PyObject *tmp_type, *tmp_value, *tmp_tb; + #if CYTHON_USE_EXC_INFO_STACK + _PyErr_StackItem *exc_info = tstate->exc_info; + tmp_type = exc_info->exc_type; + tmp_value = exc_info->exc_value; + tmp_tb = exc_info->exc_traceback; + exc_info->exc_type = type; + exc_info->exc_value = value; + exc_info->exc_traceback = tb; + #else + tmp_type = tstate->exc_type; + tmp_value = tstate->exc_value; + tmp_tb = tstate->exc_traceback; + tstate->exc_type = type; + tstate->exc_value = value; + tstate->exc_traceback = tb; + #endif + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); + #endif +} +#endif + +/* GetException */ +#if CYTHON_FAST_THREAD_STATE +static int __Pyx__GetException(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) +#else +static int __Pyx_GetException(PyObject **type, PyObject **value, PyObject **tb) +#endif +{ + PyObject *local_type = NULL, *local_value, *local_tb = NULL; +#if CYTHON_FAST_THREAD_STATE + PyObject *tmp_type, *tmp_value, *tmp_tb; + #if PY_VERSION_HEX >= 0x030C00A6 + local_value = tstate->current_exception; + tstate->current_exception = 0; + if (likely(local_value)) { + local_type = (PyObject*) Py_TYPE(local_value); + Py_INCREF(local_type); + local_tb = PyException_GetTraceback(local_value); + } + #else + local_type = tstate->curexc_type; + local_value = tstate->curexc_value; + local_tb = tstate->curexc_traceback; + tstate->curexc_type = 0; + tstate->curexc_value = 0; + tstate->curexc_traceback = 0; + #endif +#else + PyErr_Fetch(&local_type, &local_value, &local_tb); +#endif + PyErr_NormalizeException(&local_type, &local_value, &local_tb); +#if CYTHON_FAST_THREAD_STATE && PY_VERSION_HEX >= 0x030C00A6 + if (unlikely(tstate->current_exception)) +#elif CYTHON_FAST_THREAD_STATE + if (unlikely(tstate->curexc_type)) +#else + if (unlikely(PyErr_Occurred())) +#endif + goto bad; + #if PY_MAJOR_VERSION >= 3 + if (local_tb) { + if (unlikely(PyException_SetTraceback(local_value, local_tb) < 0)) + goto bad; + } + #endif + Py_XINCREF(local_tb); + Py_XINCREF(local_type); + Py_XINCREF(local_value); + *type = local_type; + *value = local_value; + *tb = local_tb; +#if CYTHON_FAST_THREAD_STATE + #if CYTHON_USE_EXC_INFO_STACK + { + _PyErr_StackItem *exc_info = tstate->exc_info; + #if PY_VERSION_HEX >= 0x030B00a4 + tmp_value = exc_info->exc_value; + exc_info->exc_value = local_value; + tmp_type = NULL; + tmp_tb = NULL; + Py_XDECREF(local_type); + Py_XDECREF(local_tb); + #else + tmp_type = exc_info->exc_type; + tmp_value = exc_info->exc_value; + tmp_tb = exc_info->exc_traceback; + exc_info->exc_type = local_type; + exc_info->exc_value = local_value; + exc_info->exc_traceback = local_tb; + #endif + } + #else + tmp_type = tstate->exc_type; + tmp_value = tstate->exc_value; + tmp_tb = tstate->exc_traceback; + tstate->exc_type = local_type; + tstate->exc_value = local_value; + tstate->exc_traceback = local_tb; + #endif + Py_XDECREF(tmp_type); + Py_XDECREF(tmp_value); + Py_XDECREF(tmp_tb); +#else + PyErr_SetExcInfo(local_type, local_value, local_tb); +#endif + return 0; +bad: + *type = 0; + *value = 0; + *tb = 0; + Py_XDECREF(local_type); + Py_XDECREF(local_value); + Py_XDECREF(local_tb); + return -1; +} + +/* SwapException */ +#if CYTHON_FAST_THREAD_STATE +static CYTHON_INLINE void __Pyx__ExceptionSwap(PyThreadState *tstate, PyObject **type, PyObject **value, PyObject **tb) { + PyObject *tmp_type, *tmp_value, *tmp_tb; + #if CYTHON_USE_EXC_INFO_STACK && PY_VERSION_HEX >= 0x030B00a4 + _PyErr_StackItem *exc_info = tstate->exc_info; + tmp_value = exc_info->exc_value; + exc_info->exc_value = *value; + if (tmp_value == NULL || tmp_value == Py_None) { + Py_XDECREF(tmp_value); + tmp_value = NULL; + tmp_type = NULL; + tmp_tb = NULL; + } else { + tmp_type = (PyObject*) Py_TYPE(tmp_value); + Py_INCREF(tmp_type); + #if CYTHON_COMPILING_IN_CPYTHON + tmp_tb = ((PyBaseExceptionObject*) tmp_value)->traceback; + Py_XINCREF(tmp_tb); + #else + tmp_tb = PyException_GetTraceback(tmp_value); + #endif + } + #elif CYTHON_USE_EXC_INFO_STACK + _PyErr_StackItem *exc_info = tstate->exc_info; + tmp_type = exc_info->exc_type; + tmp_value = exc_info->exc_value; + tmp_tb = exc_info->exc_traceback; + exc_info->exc_type = *type; + exc_info->exc_value = *value; + exc_info->exc_traceback = *tb; + #else + tmp_type = tstate->exc_type; + tmp_value = tstate->exc_value; + tmp_tb = tstate->exc_traceback; + tstate->exc_type = *type; + tstate->exc_value = *value; + tstate->exc_traceback = *tb; + #endif + *type = tmp_type; + *value = tmp_value; + *tb = tmp_tb; +} +#else +static CYTHON_INLINE void __Pyx_ExceptionSwap(PyObject **type, PyObject **value, PyObject **tb) { + PyObject *tmp_type, *tmp_value, *tmp_tb; + PyErr_GetExcInfo(&tmp_type, &tmp_value, &tmp_tb); + PyErr_SetExcInfo(*type, *value, *tb); + *type = tmp_type; + *value = tmp_value; + *tb = tmp_tb; +} +#endif + +/* Import */ +static PyObject *__Pyx_Import(PyObject *name, PyObject *from_list, int level) { + PyObject *module = 0; + PyObject *empty_dict = 0; + PyObject *empty_list = 0; + #if PY_MAJOR_VERSION < 3 + PyObject *py_import; + py_import = __Pyx_PyObject_GetAttrStr(__pyx_b, __pyx_n_s_import); + if (unlikely(!py_import)) + goto bad; + if (!from_list) { + empty_list = PyList_New(0); + if (unlikely(!empty_list)) + goto bad; + from_list = empty_list; + } + #endif + empty_dict = PyDict_New(); + if (unlikely(!empty_dict)) + goto bad; + { + #if PY_MAJOR_VERSION >= 3 + if (level == -1) { + if (strchr(__Pyx_MODULE_NAME, '.') != NULL) { + module = PyImport_ImportModuleLevelObject( + name, __pyx_d, empty_dict, from_list, 1); + if (unlikely(!module)) { + if (unlikely(!PyErr_ExceptionMatches(PyExc_ImportError))) + goto bad; + PyErr_Clear(); + } + } + level = 0; + } + #endif + if (!module) { + #if PY_MAJOR_VERSION < 3 + PyObject *py_level = PyInt_FromLong(level); + if (unlikely(!py_level)) + goto bad; + module = PyObject_CallFunctionObjArgs(py_import, + name, __pyx_d, empty_dict, from_list, py_level, (PyObject *)NULL); + Py_DECREF(py_level); + #else + module = PyImport_ImportModuleLevelObject( + name, __pyx_d, empty_dict, from_list, level); + #endif + } + } +bad: + Py_XDECREF(empty_dict); + Py_XDECREF(empty_list); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_import); + #endif + return module; +} + +/* ImportDottedModule */ +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx__ImportDottedModule_Error(PyObject *name, PyObject *parts_tuple, Py_ssize_t count) { + PyObject *partial_name = NULL, *slice = NULL, *sep = NULL; + if (unlikely(PyErr_Occurred())) { + PyErr_Clear(); + } + if (likely(PyTuple_GET_SIZE(parts_tuple) == count)) { + partial_name = name; + } else { + slice = PySequence_GetSlice(parts_tuple, 0, count); + if (unlikely(!slice)) + goto bad; + sep = PyUnicode_FromStringAndSize(".", 1); + if (unlikely(!sep)) + goto bad; + partial_name = PyUnicode_Join(sep, slice); + } + PyErr_Format( +#if PY_MAJOR_VERSION < 3 + PyExc_ImportError, + "No module named '%s'", PyString_AS_STRING(partial_name)); +#else +#if PY_VERSION_HEX >= 0x030600B1 + PyExc_ModuleNotFoundError, +#else + PyExc_ImportError, +#endif + "No module named '%U'", partial_name); +#endif +bad: + Py_XDECREF(sep); + Py_XDECREF(slice); + Py_XDECREF(partial_name); + return NULL; +} +#endif +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx__ImportDottedModule_Lookup(PyObject *name) { + PyObject *imported_module; +#if PY_VERSION_HEX < 0x030700A1 || (CYTHON_COMPILING_IN_PYPY && PYPY_VERSION_NUM < 0x07030400) + PyObject *modules = PyImport_GetModuleDict(); + if (unlikely(!modules)) + return NULL; + imported_module = __Pyx_PyDict_GetItemStr(modules, name); + Py_XINCREF(imported_module); +#else + imported_module = PyImport_GetModule(name); +#endif + return imported_module; +} +#endif +#if PY_MAJOR_VERSION >= 3 +static PyObject *__Pyx_ImportDottedModule_WalkParts(PyObject *module, PyObject *name, PyObject *parts_tuple) { + Py_ssize_t i, nparts; + nparts = PyTuple_GET_SIZE(parts_tuple); + for (i=1; i < nparts && module; i++) { + PyObject *part, *submodule; +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + part = PyTuple_GET_ITEM(parts_tuple, i); +#else + part = PySequence_ITEM(parts_tuple, i); +#endif + submodule = __Pyx_PyObject_GetAttrStrNoError(module, part); +#if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(part); +#endif + Py_DECREF(module); + module = submodule; + } + if (unlikely(!module)) { + return __Pyx__ImportDottedModule_Error(name, parts_tuple, i); + } + return module; +} +#endif +static PyObject *__Pyx__ImportDottedModule(PyObject *name, PyObject *parts_tuple) { +#if PY_MAJOR_VERSION < 3 + PyObject *module, *from_list, *star = __pyx_n_s__3; + CYTHON_UNUSED_VAR(parts_tuple); + from_list = PyList_New(1); + if (unlikely(!from_list)) + return NULL; + Py_INCREF(star); + PyList_SET_ITEM(from_list, 0, star); + module = __Pyx_Import(name, from_list, 0); + Py_DECREF(from_list); + return module; +#else + PyObject *imported_module; + PyObject *module = __Pyx_Import(name, NULL, 0); + if (!parts_tuple || unlikely(!module)) + return module; + imported_module = __Pyx__ImportDottedModule_Lookup(name); + if (likely(imported_module)) { + Py_DECREF(module); + return imported_module; + } + PyErr_Clear(); + return __Pyx_ImportDottedModule_WalkParts(module, name, parts_tuple); +#endif +} +static PyObject *__Pyx_ImportDottedModule(PyObject *name, PyObject *parts_tuple) { +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX >= 0x030400B1 + PyObject *module = __Pyx__ImportDottedModule_Lookup(name); + if (likely(module)) { + PyObject *spec = __Pyx_PyObject_GetAttrStrNoError(module, __pyx_n_s_spec); + if (likely(spec)) { + PyObject *unsafe = __Pyx_PyObject_GetAttrStrNoError(spec, __pyx_n_s_initializing); + if (likely(!unsafe || !__Pyx_PyObject_IsTrue(unsafe))) { + Py_DECREF(spec); + spec = NULL; + } + Py_XDECREF(unsafe); + } + if (likely(!spec)) { + PyErr_Clear(); + return module; + } + Py_DECREF(spec); + Py_DECREF(module); + } else if (PyErr_Occurred()) { + PyErr_Clear(); + } +#endif + return __Pyx__ImportDottedModule(name, parts_tuple); +} + +/* FastTypeChecks */ +#if CYTHON_COMPILING_IN_CPYTHON +static int __Pyx_InBases(PyTypeObject *a, PyTypeObject *b) { + while (a) { + a = __Pyx_PyType_GetSlot(a, tp_base, PyTypeObject*); + if (a == b) + return 1; + } + return b == &PyBaseObject_Type; +} +static CYTHON_INLINE int __Pyx_IsSubtype(PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (a == b) return 1; + mro = a->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + if (PyTuple_GET_ITEM(mro, i) == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(a, b); +} +static CYTHON_INLINE int __Pyx_IsAnySubtype2(PyTypeObject *cls, PyTypeObject *a, PyTypeObject *b) { + PyObject *mro; + if (cls == a || cls == b) return 1; + mro = cls->tp_mro; + if (likely(mro)) { + Py_ssize_t i, n; + n = PyTuple_GET_SIZE(mro); + for (i = 0; i < n; i++) { + PyObject *base = PyTuple_GET_ITEM(mro, i); + if (base == (PyObject *)a || base == (PyObject *)b) + return 1; + } + return 0; + } + return __Pyx_InBases(cls, a) || __Pyx_InBases(cls, b); +} +#if PY_MAJOR_VERSION == 2 +static int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject* exc_type2) { + PyObject *exception, *value, *tb; + int res; + __Pyx_PyThreadState_declare + __Pyx_PyThreadState_assign + __Pyx_ErrFetch(&exception, &value, &tb); + res = exc_type1 ? PyObject_IsSubclass(err, exc_type1) : 0; + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + if (!res) { + res = PyObject_IsSubclass(err, exc_type2); + if (unlikely(res == -1)) { + PyErr_WriteUnraisable(err); + res = 0; + } + } + __Pyx_ErrRestore(exception, value, tb); + return res; +} +#else +static CYTHON_INLINE int __Pyx_inner_PyErr_GivenExceptionMatches2(PyObject *err, PyObject* exc_type1, PyObject *exc_type2) { + if (exc_type1) { + return __Pyx_IsAnySubtype2((PyTypeObject*)err, (PyTypeObject*)exc_type1, (PyTypeObject*)exc_type2); + } else { + return __Pyx_IsSubtype((PyTypeObject*)err, (PyTypeObject*)exc_type2); + } +} +#endif +static int __Pyx_PyErr_GivenExceptionMatchesTuple(PyObject *exc_type, PyObject *tuple) { + Py_ssize_t i, n; + assert(PyExceptionClass_Check(exc_type)); + n = PyTuple_GET_SIZE(tuple); +#if PY_MAJOR_VERSION >= 3 + for (i=0; itp_as_sequence && type->tp_as_sequence->sq_repeat)) { + return type->tp_as_sequence->sq_repeat(seq, mul); + } else +#endif + { + return __Pyx_PySequence_Multiply_Generic(seq, mul); + } +} + +/* SetItemInt */ +static int __Pyx_SetItemInt_Generic(PyObject *o, PyObject *j, PyObject *v) { + int r; + if (unlikely(!j)) return -1; + r = PyObject_SetItem(o, j, v); + Py_DECREF(j); + return r; +} +static CYTHON_INLINE int __Pyx_SetItemInt_Fast(PyObject *o, Py_ssize_t i, PyObject *v, int is_list, + CYTHON_NCP_UNUSED int wraparound, CYTHON_NCP_UNUSED int boundscheck) { +#if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS && CYTHON_USE_TYPE_SLOTS + if (is_list || PyList_CheckExact(o)) { + Py_ssize_t n = (!wraparound) ? i : ((likely(i >= 0)) ? i : i + PyList_GET_SIZE(o)); + if ((!boundscheck) || likely(__Pyx_is_valid_index(n, PyList_GET_SIZE(o)))) { + PyObject* old = PyList_GET_ITEM(o, n); + Py_INCREF(v); + PyList_SET_ITEM(o, n, v); + Py_DECREF(old); + return 1; + } + } else { + PyMappingMethods *mm = Py_TYPE(o)->tp_as_mapping; + PySequenceMethods *sm = Py_TYPE(o)->tp_as_sequence; + if (mm && mm->mp_ass_subscript) { + int r; + PyObject *key = PyInt_FromSsize_t(i); + if (unlikely(!key)) return -1; + r = mm->mp_ass_subscript(o, key, v); + Py_DECREF(key); + return r; + } + if (likely(sm && sm->sq_ass_item)) { + if (wraparound && unlikely(i < 0) && likely(sm->sq_length)) { + Py_ssize_t l = sm->sq_length(o); + if (likely(l >= 0)) { + i += l; + } else { + if (!PyErr_ExceptionMatches(PyExc_OverflowError)) + return -1; + PyErr_Clear(); + } + } + return sm->sq_ass_item(o, i, v); + } + } +#else + if (is_list || !PyMapping_Check(o)) + { + return PySequence_SetItem(o, i, v); + } +#endif + return __Pyx_SetItemInt_Generic(o, PyInt_FromSsize_t(i), v); +} + +/* RaiseUnboundLocalError */ +static CYTHON_INLINE void __Pyx_RaiseUnboundLocalError(const char *varname) { + PyErr_Format(PyExc_UnboundLocalError, "local variable '%s' referenced before assignment", varname); +} + +/* DivInt[long] */ +static CYTHON_INLINE long __Pyx_div_long(long a, long b) { + long q = a / b; + long r = a - q*b; + q -= ((r != 0) & ((r ^ b) < 0)); + return q; +} + +/* ImportFrom */ +static PyObject* __Pyx_ImportFrom(PyObject* module, PyObject* name) { + PyObject* value = __Pyx_PyObject_GetAttrStr(module, name); + if (unlikely(!value) && PyErr_ExceptionMatches(PyExc_AttributeError)) { + const char* module_name_str = 0; + PyObject* module_name = 0; + PyObject* module_dot = 0; + PyObject* full_name = 0; + PyErr_Clear(); + module_name_str = PyModule_GetName(module); + if (unlikely(!module_name_str)) { goto modbad; } + module_name = PyUnicode_FromString(module_name_str); + if (unlikely(!module_name)) { goto modbad; } + module_dot = PyUnicode_Concat(module_name, __pyx_kp_u__2); + if (unlikely(!module_dot)) { goto modbad; } + full_name = PyUnicode_Concat(module_dot, name); + if (unlikely(!full_name)) { goto modbad; } + #if PY_VERSION_HEX < 0x030700A1 || (CYTHON_COMPILING_IN_PYPY && PYPY_VERSION_NUM < 0x07030400) + { + PyObject *modules = PyImport_GetModuleDict(); + if (unlikely(!modules)) + goto modbad; + value = PyObject_GetItem(modules, full_name); + } + #else + value = PyImport_GetModule(full_name); + #endif + modbad: + Py_XDECREF(full_name); + Py_XDECREF(module_dot); + Py_XDECREF(module_name); + } + if (unlikely(!value)) { + PyErr_Format(PyExc_ImportError, + #if PY_MAJOR_VERSION < 3 + "cannot import name %.230s", PyString_AS_STRING(name)); + #else + "cannot import name %S", name); + #endif + } + return value; +} + +/* HasAttr */ +#if __PYX_LIMITED_VERSION_HEX < 0x030d00A1 +static CYTHON_INLINE int __Pyx_HasAttr(PyObject *o, PyObject *n) { + PyObject *r; + if (unlikely(!__Pyx_PyBaseString_Check(n))) { + PyErr_SetString(PyExc_TypeError, + "hasattr(): attribute name must be string"); + return -1; + } + r = __Pyx_GetAttr(o, n); + if (!r) { + PyErr_Clear(); + return 0; + } else { + Py_DECREF(r); + return 1; + } +} +#endif + +/* BufferIndexError */ +static void __Pyx_RaiseBufferIndexError(int axis) { + PyErr_Format(PyExc_IndexError, + "Out of bounds on buffer access (axis %d)", axis); +} + +/* PyObject_GenericGetAttrNoDict */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject *__Pyx_RaiseGenericGetAttributeError(PyTypeObject *tp, PyObject *attr_name) { + __Pyx_TypeName type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, attr_name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(attr_name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyObject_GenericGetAttrNoDict(PyObject* obj, PyObject* attr_name) { + PyObject *descr; + PyTypeObject *tp = Py_TYPE(obj); + if (unlikely(!PyString_Check(attr_name))) { + return PyObject_GenericGetAttr(obj, attr_name); + } + assert(!tp->tp_dictoffset); + descr = _PyType_Lookup(tp, attr_name); + if (unlikely(!descr)) { + return __Pyx_RaiseGenericGetAttributeError(tp, attr_name); + } + Py_INCREF(descr); + #if PY_MAJOR_VERSION < 3 + if (likely(PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_HAVE_CLASS))) + #endif + { + descrgetfunc f = Py_TYPE(descr)->tp_descr_get; + if (unlikely(f)) { + PyObject *res = f(descr, obj, (PyObject *)tp); + Py_DECREF(descr); + return res; + } + } + return descr; +} +#endif + +/* PyObject_GenericGetAttr */ +#if CYTHON_USE_TYPE_SLOTS && CYTHON_USE_PYTYPE_LOOKUP && PY_VERSION_HEX < 0x03070000 +static PyObject* __Pyx_PyObject_GenericGetAttr(PyObject* obj, PyObject* attr_name) { + if (unlikely(Py_TYPE(obj)->tp_dictoffset)) { + return PyObject_GenericGetAttr(obj, attr_name); + } + return __Pyx_PyObject_GenericGetAttrNoDict(obj, attr_name); +} +#endif + +/* TypeImport */ +#ifndef __PYX_HAVE_RT_ImportType_3_0_8 +#define __PYX_HAVE_RT_ImportType_3_0_8 +static PyTypeObject *__Pyx_ImportType_3_0_8(PyObject *module, const char *module_name, const char *class_name, + size_t size, size_t alignment, enum __Pyx_ImportType_CheckSize_3_0_8 check_size) +{ + PyObject *result = 0; + char warning[200]; + Py_ssize_t basicsize; + Py_ssize_t itemsize; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *py_basicsize; + PyObject *py_itemsize; +#endif + result = PyObject_GetAttrString(module, class_name); + if (!result) + goto bad; + if (!PyType_Check(result)) { + PyErr_Format(PyExc_TypeError, + "%.200s.%.200s is not a type object", + module_name, class_name); + goto bad; + } +#if !CYTHON_COMPILING_IN_LIMITED_API + basicsize = ((PyTypeObject *)result)->tp_basicsize; + itemsize = ((PyTypeObject *)result)->tp_itemsize; +#else + py_basicsize = PyObject_GetAttrString(result, "__basicsize__"); + if (!py_basicsize) + goto bad; + basicsize = PyLong_AsSsize_t(py_basicsize); + Py_DECREF(py_basicsize); + py_basicsize = 0; + if (basicsize == (Py_ssize_t)-1 && PyErr_Occurred()) + goto bad; + py_itemsize = PyObject_GetAttrString(result, "__itemsize__"); + if (!py_itemsize) + goto bad; + itemsize = PyLong_AsSsize_t(py_itemsize); + Py_DECREF(py_itemsize); + py_itemsize = 0; + if (itemsize == (Py_ssize_t)-1 && PyErr_Occurred()) + goto bad; +#endif + if (itemsize) { + if (size % alignment) { + alignment = size % alignment; + } + if (itemsize < (Py_ssize_t)alignment) + itemsize = (Py_ssize_t)alignment; + } + if ((size_t)(basicsize + itemsize) < size) { + PyErr_Format(PyExc_ValueError, + "%.200s.%.200s size changed, may indicate binary incompatibility. " + "Expected %zd from C header, got %zd from PyObject", + module_name, class_name, size, basicsize+itemsize); + goto bad; + } + if (check_size == __Pyx_ImportType_CheckSize_Error_3_0_8 && + ((size_t)basicsize > size || (size_t)(basicsize + itemsize) < size)) { + PyErr_Format(PyExc_ValueError, + "%.200s.%.200s size changed, may indicate binary incompatibility. " + "Expected %zd from C header, got %zd-%zd from PyObject", + module_name, class_name, size, basicsize, basicsize+itemsize); + goto bad; + } + else if (check_size == __Pyx_ImportType_CheckSize_Warn_3_0_8 && (size_t)basicsize > size) { + PyOS_snprintf(warning, sizeof(warning), + "%s.%s size changed, may indicate binary incompatibility. " + "Expected %zd from C header, got %zd from PyObject", + module_name, class_name, size, basicsize); + if (PyErr_WarnEx(NULL, warning, 0) < 0) goto bad; + } + return (PyTypeObject *)result; +bad: + Py_XDECREF(result); + return NULL; +} +#endif + +/* FixUpExtensionType */ +#if CYTHON_USE_TYPE_SPECS +static int __Pyx_fix_up_extension_type_from_spec(PyType_Spec *spec, PyTypeObject *type) { +#if PY_VERSION_HEX > 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + CYTHON_UNUSED_VAR(spec); + CYTHON_UNUSED_VAR(type); +#else + const PyType_Slot *slot = spec->slots; + while (slot && slot->slot && slot->slot != Py_tp_members) + slot++; + if (slot && slot->slot == Py_tp_members) { + int changed = 0; +#if !(PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON) + const +#endif + PyMemberDef *memb = (PyMemberDef*) slot->pfunc; + while (memb && memb->name) { + if (memb->name[0] == '_' && memb->name[1] == '_') { +#if PY_VERSION_HEX < 0x030900b1 + if (strcmp(memb->name, "__weaklistoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_weaklistoffset = memb->offset; + changed = 1; + } + else if (strcmp(memb->name, "__dictoffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); + type->tp_dictoffset = memb->offset; + changed = 1; + } +#if CYTHON_METH_FASTCALL + else if (strcmp(memb->name, "__vectorcalloffset__") == 0) { + assert(memb->type == T_PYSSIZET); + assert(memb->flags == READONLY); +#if PY_VERSION_HEX >= 0x030800b4 + type->tp_vectorcall_offset = memb->offset; +#else + type->tp_print = (printfunc) memb->offset; +#endif + changed = 1; + } +#endif +#else + if ((0)); +#endif +#if PY_VERSION_HEX <= 0x030900b1 && CYTHON_COMPILING_IN_CPYTHON + else if (strcmp(memb->name, "__module__") == 0) { + PyObject *descr; + assert(memb->type == T_OBJECT); + assert(memb->flags == 0 || memb->flags == READONLY); + descr = PyDescr_NewMember(type, memb); + if (unlikely(!descr)) + return -1; + if (unlikely(PyDict_SetItem(type->tp_dict, PyDescr_NAME(descr), descr) < 0)) { + Py_DECREF(descr); + return -1; + } + Py_DECREF(descr); + changed = 1; + } +#endif + } + memb++; + } + if (changed) + PyType_Modified(type); + } +#endif + return 0; +} +#endif + +/* PyObjectCallNoArg */ +static CYTHON_INLINE PyObject* __Pyx_PyObject_CallNoArg(PyObject *func) { + PyObject *arg[2] = {NULL, NULL}; + return __Pyx_PyObject_FastCall(func, arg + 1, 0 | __Pyx_PY_VECTORCALL_ARGUMENTS_OFFSET); +} + +/* PyObjectGetMethod */ +static int __Pyx_PyObject_GetMethod(PyObject *obj, PyObject *name, PyObject **method) { + PyObject *attr; +#if CYTHON_UNPACK_METHODS && CYTHON_COMPILING_IN_CPYTHON && CYTHON_USE_PYTYPE_LOOKUP + __Pyx_TypeName type_name; + PyTypeObject *tp = Py_TYPE(obj); + PyObject *descr; + descrgetfunc f = NULL; + PyObject **dictptr, *dict; + int meth_found = 0; + assert (*method == NULL); + if (unlikely(tp->tp_getattro != PyObject_GenericGetAttr)) { + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; + } + if (unlikely(tp->tp_dict == NULL) && unlikely(PyType_Ready(tp) < 0)) { + return 0; + } + descr = _PyType_Lookup(tp, name); + if (likely(descr != NULL)) { + Py_INCREF(descr); +#if defined(Py_TPFLAGS_METHOD_DESCRIPTOR) && Py_TPFLAGS_METHOD_DESCRIPTOR + if (__Pyx_PyType_HasFeature(Py_TYPE(descr), Py_TPFLAGS_METHOD_DESCRIPTOR)) +#elif PY_MAJOR_VERSION >= 3 + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr) || __Pyx_IS_TYPE(descr, &PyMethodDescr_Type))) + #endif +#else + #ifdef __Pyx_CyFunction_USED + if (likely(PyFunction_Check(descr) || __Pyx_CyFunction_Check(descr))) + #else + if (likely(PyFunction_Check(descr))) + #endif +#endif + { + meth_found = 1; + } else { + f = Py_TYPE(descr)->tp_descr_get; + if (f != NULL && PyDescr_IsData(descr)) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + } + } + dictptr = _PyObject_GetDictPtr(obj); + if (dictptr != NULL && (dict = *dictptr) != NULL) { + Py_INCREF(dict); + attr = __Pyx_PyDict_GetItemStr(dict, name); + if (attr != NULL) { + Py_INCREF(attr); + Py_DECREF(dict); + Py_XDECREF(descr); + goto try_unpack; + } + Py_DECREF(dict); + } + if (meth_found) { + *method = descr; + return 1; + } + if (f != NULL) { + attr = f(descr, obj, (PyObject *)Py_TYPE(obj)); + Py_DECREF(descr); + goto try_unpack; + } + if (likely(descr != NULL)) { + *method = descr; + return 0; + } + type_name = __Pyx_PyType_GetName(tp); + PyErr_Format(PyExc_AttributeError, +#if PY_MAJOR_VERSION >= 3 + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%U'", + type_name, name); +#else + "'" __Pyx_FMT_TYPENAME "' object has no attribute '%.400s'", + type_name, PyString_AS_STRING(name)); +#endif + __Pyx_DECREF_TypeName(type_name); + return 0; +#else + attr = __Pyx_PyObject_GetAttrStr(obj, name); + goto try_unpack; +#endif +try_unpack: +#if CYTHON_UNPACK_METHODS + if (likely(attr) && PyMethod_Check(attr) && likely(PyMethod_GET_SELF(attr) == obj)) { + PyObject *function = PyMethod_GET_FUNCTION(attr); + Py_INCREF(function); + Py_DECREF(attr); + *method = function; + return 1; + } +#endif + *method = attr; + return 0; +} + +/* PyObjectCallMethod0 */ +static PyObject* __Pyx_PyObject_CallMethod0(PyObject* obj, PyObject* method_name) { + PyObject *method = NULL, *result = NULL; + int is_method = __Pyx_PyObject_GetMethod(obj, method_name, &method); + if (likely(is_method)) { + result = __Pyx_PyObject_CallOneArg(method, obj); + Py_DECREF(method); + return result; + } + if (unlikely(!method)) goto bad; + result = __Pyx_PyObject_CallNoArg(method); + Py_DECREF(method); +bad: + return result; +} + +/* ValidateBasesTuple */ +#if CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API || CYTHON_USE_TYPE_SPECS +static int __Pyx_validate_bases_tuple(const char *type_name, Py_ssize_t dictoffset, PyObject *bases) { + Py_ssize_t i, n; +#if CYTHON_ASSUME_SAFE_MACROS + n = PyTuple_GET_SIZE(bases); +#else + n = PyTuple_Size(bases); + if (n < 0) return -1; +#endif + for (i = 1; i < n; i++) + { +#if CYTHON_AVOID_BORROWED_REFS + PyObject *b0 = PySequence_GetItem(bases, i); + if (!b0) return -1; +#elif CYTHON_ASSUME_SAFE_MACROS + PyObject *b0 = PyTuple_GET_ITEM(bases, i); +#else + PyObject *b0 = PyTuple_GetItem(bases, i); + if (!b0) return -1; +#endif + PyTypeObject *b; +#if PY_MAJOR_VERSION < 3 + if (PyClass_Check(b0)) + { + PyErr_Format(PyExc_TypeError, "base class '%.200s' is an old-style class", + PyString_AS_STRING(((PyClassObject*)b0)->cl_name)); +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + return -1; + } +#endif + b = (PyTypeObject*) b0; + if (!__Pyx_PyType_HasFeature(b, Py_TPFLAGS_HEAPTYPE)) + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "base class '" __Pyx_FMT_TYPENAME "' is not a heap type", b_name); + __Pyx_DECREF_TypeName(b_name); +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + return -1; + } + if (dictoffset == 0) + { + Py_ssize_t b_dictoffset = 0; +#if CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY + b_dictoffset = b->tp_dictoffset; +#else + PyObject *py_b_dictoffset = PyObject_GetAttrString((PyObject*)b, "__dictoffset__"); + if (!py_b_dictoffset) goto dictoffset_return; + b_dictoffset = PyLong_AsSsize_t(py_b_dictoffset); + Py_DECREF(py_b_dictoffset); + if (b_dictoffset == -1 && PyErr_Occurred()) goto dictoffset_return; +#endif + if (b_dictoffset) { + { + __Pyx_TypeName b_name = __Pyx_PyType_GetName(b); + PyErr_Format(PyExc_TypeError, + "extension type '%.200s' has no __dict__ slot, " + "but base type '" __Pyx_FMT_TYPENAME "' has: " + "either add 'cdef dict __dict__' to the extension type " + "or add '__slots__ = [...]' to the base type", + type_name, b_name); + __Pyx_DECREF_TypeName(b_name); + } +#if !(CYTHON_USE_TYPE_SLOTS || CYTHON_COMPILING_IN_PYPY) + dictoffset_return: +#endif +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + return -1; + } + } +#if CYTHON_AVOID_BORROWED_REFS + Py_DECREF(b0); +#endif + } + return 0; +} +#endif + +/* PyType_Ready */ +static int __Pyx_PyType_Ready(PyTypeObject *t) { +#if CYTHON_USE_TYPE_SPECS || !(CYTHON_COMPILING_IN_CPYTHON || CYTHON_COMPILING_IN_LIMITED_API) || defined(PYSTON_MAJOR_VERSION) + (void)__Pyx_PyObject_CallMethod0; +#if CYTHON_USE_TYPE_SPECS + (void)__Pyx_validate_bases_tuple; +#endif + return PyType_Ready(t); +#else + int r; + PyObject *bases = __Pyx_PyType_GetSlot(t, tp_bases, PyObject*); + if (bases && unlikely(__Pyx_validate_bases_tuple(t->tp_name, t->tp_dictoffset, bases) == -1)) + return -1; +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + { + int gc_was_enabled; + #if PY_VERSION_HEX >= 0x030A00b1 + gc_was_enabled = PyGC_Disable(); + (void)__Pyx_PyObject_CallMethod0; + #else + PyObject *ret, *py_status; + PyObject *gc = NULL; + #if PY_VERSION_HEX >= 0x030700a1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM+0 >= 0x07030400) + gc = PyImport_GetModule(__pyx_kp_u_gc); + #endif + if (unlikely(!gc)) gc = PyImport_Import(__pyx_kp_u_gc); + if (unlikely(!gc)) return -1; + py_status = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_isenabled); + if (unlikely(!py_status)) { + Py_DECREF(gc); + return -1; + } + gc_was_enabled = __Pyx_PyObject_IsTrue(py_status); + Py_DECREF(py_status); + if (gc_was_enabled > 0) { + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_disable); + if (unlikely(!ret)) { + Py_DECREF(gc); + return -1; + } + Py_DECREF(ret); + } else if (unlikely(gc_was_enabled == -1)) { + Py_DECREF(gc); + return -1; + } + #endif + t->tp_flags |= Py_TPFLAGS_HEAPTYPE; +#if PY_VERSION_HEX >= 0x030A0000 + t->tp_flags |= Py_TPFLAGS_IMMUTABLETYPE; +#endif +#else + (void)__Pyx_PyObject_CallMethod0; +#endif + r = PyType_Ready(t); +#if PY_VERSION_HEX >= 0x03050000 && !defined(PYSTON_MAJOR_VERSION) + t->tp_flags &= ~Py_TPFLAGS_HEAPTYPE; + #if PY_VERSION_HEX >= 0x030A00b1 + if (gc_was_enabled) + PyGC_Enable(); + #else + if (gc_was_enabled) { + PyObject *tp, *v, *tb; + PyErr_Fetch(&tp, &v, &tb); + ret = __Pyx_PyObject_CallMethod0(gc, __pyx_kp_u_enable); + if (likely(ret || r == -1)) { + Py_XDECREF(ret); + PyErr_Restore(tp, v, tb); + } else { + Py_XDECREF(tp); + Py_XDECREF(v); + Py_XDECREF(tb); + r = -1; + } + } + Py_DECREF(gc); + #endif + } +#endif + return r; +#endif +} + +/* SetupReduce */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_setup_reduce_is_named(PyObject* meth, PyObject* name) { + int ret; + PyObject *name_attr; + name_attr = __Pyx_PyObject_GetAttrStrNoError(meth, __pyx_n_s_name_2); + if (likely(name_attr)) { + ret = PyObject_RichCompareBool(name_attr, name, Py_EQ); + } else { + ret = -1; + } + if (unlikely(ret < 0)) { + PyErr_Clear(); + ret = 0; + } + Py_XDECREF(name_attr); + return ret; +} +static int __Pyx_setup_reduce(PyObject* type_obj) { + int ret = 0; + PyObject *object_reduce = NULL; + PyObject *object_getstate = NULL; + PyObject *object_reduce_ex = NULL; + PyObject *reduce = NULL; + PyObject *reduce_ex = NULL; + PyObject *reduce_cython = NULL; + PyObject *setstate = NULL; + PyObject *setstate_cython = NULL; + PyObject *getstate = NULL; +#if CYTHON_USE_PYTYPE_LOOKUP + getstate = _PyType_Lookup((PyTypeObject*)type_obj, __pyx_n_s_getstate); +#else + getstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_getstate); + if (!getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (getstate) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_getstate = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_getstate); +#else + object_getstate = __Pyx_PyObject_GetAttrStrNoError((PyObject*)&PyBaseObject_Type, __pyx_n_s_getstate); + if (!object_getstate && PyErr_Occurred()) { + goto __PYX_BAD; + } +#endif + if (object_getstate != getstate) { + goto __PYX_GOOD; + } + } +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce_ex = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#else + object_reduce_ex = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce_ex); if (!object_reduce_ex) goto __PYX_BAD; +#endif + reduce_ex = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce_ex); if (unlikely(!reduce_ex)) goto __PYX_BAD; + if (reduce_ex == object_reduce_ex) { +#if CYTHON_USE_PYTYPE_LOOKUP + object_reduce = _PyType_Lookup(&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#else + object_reduce = __Pyx_PyObject_GetAttrStr((PyObject*)&PyBaseObject_Type, __pyx_n_s_reduce); if (!object_reduce) goto __PYX_BAD; +#endif + reduce = __Pyx_PyObject_GetAttrStr(type_obj, __pyx_n_s_reduce); if (unlikely(!reduce)) goto __PYX_BAD; + if (reduce == object_reduce || __Pyx_setup_reduce_is_named(reduce, __pyx_n_s_reduce_cython)) { + reduce_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_reduce_cython); + if (likely(reduce_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce, reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_reduce_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (reduce == object_reduce || PyErr_Occurred()) { + goto __PYX_BAD; + } + setstate = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate); + if (!setstate) PyErr_Clear(); + if (!setstate || __Pyx_setup_reduce_is_named(setstate, __pyx_n_s_setstate_cython)) { + setstate_cython = __Pyx_PyObject_GetAttrStrNoError(type_obj, __pyx_n_s_setstate_cython); + if (likely(setstate_cython)) { + ret = PyDict_SetItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate, setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + ret = PyDict_DelItem(((PyTypeObject*)type_obj)->tp_dict, __pyx_n_s_setstate_cython); if (unlikely(ret < 0)) goto __PYX_BAD; + } else if (!setstate || PyErr_Occurred()) { + goto __PYX_BAD; + } + } + PyType_Modified((PyTypeObject*)type_obj); + } + } + goto __PYX_GOOD; +__PYX_BAD: + if (!PyErr_Occurred()) { + __Pyx_TypeName type_obj_name = + __Pyx_PyType_GetName((PyTypeObject*)type_obj); + PyErr_Format(PyExc_RuntimeError, + "Unable to initialize pickling for " __Pyx_FMT_TYPENAME, type_obj_name); + __Pyx_DECREF_TypeName(type_obj_name); + } + ret = -1; +__PYX_GOOD: +#if !CYTHON_USE_PYTYPE_LOOKUP + Py_XDECREF(object_reduce); + Py_XDECREF(object_reduce_ex); + Py_XDECREF(object_getstate); + Py_XDECREF(getstate); +#endif + Py_XDECREF(reduce); + Py_XDECREF(reduce_ex); + Py_XDECREF(reduce_cython); + Py_XDECREF(setstate); + Py_XDECREF(setstate_cython); + return ret; +} +#endif + +/* SetVTable */ +static int __Pyx_SetVtable(PyTypeObject *type, void *vtable) { + PyObject *ob = PyCapsule_New(vtable, 0, 0); + if (unlikely(!ob)) + goto bad; +#if CYTHON_COMPILING_IN_LIMITED_API + if (unlikely(PyObject_SetAttr((PyObject *) type, __pyx_n_s_pyx_vtable, ob) < 0)) +#else + if (unlikely(PyDict_SetItem(type->tp_dict, __pyx_n_s_pyx_vtable, ob) < 0)) +#endif + goto bad; + Py_DECREF(ob); + return 0; +bad: + Py_XDECREF(ob); + return -1; +} + +/* GetVTable */ +static void* __Pyx_GetVtable(PyTypeObject *type) { + void* ptr; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *ob = PyObject_GetAttr((PyObject *)type, __pyx_n_s_pyx_vtable); +#else + PyObject *ob = PyObject_GetItem(type->tp_dict, __pyx_n_s_pyx_vtable); +#endif + if (!ob) + goto bad; + ptr = PyCapsule_GetPointer(ob, 0); + if (!ptr && !PyErr_Occurred()) + PyErr_SetString(PyExc_RuntimeError, "invalid vtable found for imported type"); + Py_DECREF(ob); + return ptr; +bad: + Py_XDECREF(ob); + return NULL; +} + +/* MergeVTables */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __Pyx_MergeVtables(PyTypeObject *type) { + int i; + void** base_vtables; + __Pyx_TypeName tp_base_name; + __Pyx_TypeName base_name; + void* unknown = (void*)-1; + PyObject* bases = type->tp_bases; + int base_depth = 0; + { + PyTypeObject* base = type->tp_base; + while (base) { + base_depth += 1; + base = base->tp_base; + } + } + base_vtables = (void**) malloc(sizeof(void*) * (size_t)(base_depth + 1)); + base_vtables[0] = unknown; + for (i = 1; i < PyTuple_GET_SIZE(bases); i++) { + void* base_vtable = __Pyx_GetVtable(((PyTypeObject*)PyTuple_GET_ITEM(bases, i))); + if (base_vtable != NULL) { + int j; + PyTypeObject* base = type->tp_base; + for (j = 0; j < base_depth; j++) { + if (base_vtables[j] == unknown) { + base_vtables[j] = __Pyx_GetVtable(base); + base_vtables[j + 1] = unknown; + } + if (base_vtables[j] == base_vtable) { + break; + } else if (base_vtables[j] == NULL) { + goto bad; + } + base = base->tp_base; + } + } + } + PyErr_Clear(); + free(base_vtables); + return 0; +bad: + tp_base_name = __Pyx_PyType_GetName(type->tp_base); + base_name = __Pyx_PyType_GetName((PyTypeObject*)PyTuple_GET_ITEM(bases, i)); + PyErr_Format(PyExc_TypeError, + "multiple bases have vtable conflict: '" __Pyx_FMT_TYPENAME "' and '" __Pyx_FMT_TYPENAME "'", tp_base_name, base_name); + __Pyx_DECREF_TypeName(tp_base_name); + __Pyx_DECREF_TypeName(base_name); + free(base_vtables); + return -1; +} +#endif + +/* FetchSharedCythonModule */ +static PyObject *__Pyx_FetchSharedCythonABIModule(void) { + return __Pyx_PyImport_AddModuleRef((char*) __PYX_ABI_MODULE_NAME); +} + +/* FetchCommonType */ +static int __Pyx_VerifyCachedType(PyObject *cached_type, + const char *name, + Py_ssize_t basicsize, + Py_ssize_t expected_basicsize) { + if (!PyType_Check(cached_type)) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s is not a type object", name); + return -1; + } + if (basicsize != expected_basicsize) { + PyErr_Format(PyExc_TypeError, + "Shared Cython type %.200s has the wrong size, try recompiling", + name); + return -1; + } + return 0; +} +#if !CYTHON_USE_TYPE_SPECS +static PyTypeObject* __Pyx_FetchCommonType(PyTypeObject* type) { + PyObject* abi_module; + const char* object_name; + PyTypeObject *cached_type = NULL; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + object_name = strrchr(type->tp_name, '.'); + object_name = object_name ? object_name+1 : type->tp_name; + cached_type = (PyTypeObject*) PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + if (__Pyx_VerifyCachedType( + (PyObject *)cached_type, + object_name, + cached_type->tp_basicsize, + type->tp_basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + if (PyType_Ready(type) < 0) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, (PyObject *)type) < 0) + goto bad; + Py_INCREF(type); + cached_type = type; +done: + Py_DECREF(abi_module); + return cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#else +static PyTypeObject *__Pyx_FetchCommonTypeFromSpec(PyObject *module, PyType_Spec *spec, PyObject *bases) { + PyObject *abi_module, *cached_type = NULL; + const char* object_name = strrchr(spec->name, '.'); + object_name = object_name ? object_name+1 : spec->name; + abi_module = __Pyx_FetchSharedCythonABIModule(); + if (!abi_module) return NULL; + cached_type = PyObject_GetAttrString(abi_module, object_name); + if (cached_type) { + Py_ssize_t basicsize; +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *py_basicsize; + py_basicsize = PyObject_GetAttrString(cached_type, "__basicsize__"); + if (unlikely(!py_basicsize)) goto bad; + basicsize = PyLong_AsSsize_t(py_basicsize); + Py_DECREF(py_basicsize); + py_basicsize = 0; + if (unlikely(basicsize == (Py_ssize_t)-1) && PyErr_Occurred()) goto bad; +#else + basicsize = likely(PyType_Check(cached_type)) ? ((PyTypeObject*) cached_type)->tp_basicsize : -1; +#endif + if (__Pyx_VerifyCachedType( + cached_type, + object_name, + basicsize, + spec->basicsize) < 0) { + goto bad; + } + goto done; + } + if (!PyErr_ExceptionMatches(PyExc_AttributeError)) goto bad; + PyErr_Clear(); + CYTHON_UNUSED_VAR(module); + cached_type = __Pyx_PyType_FromModuleAndSpec(abi_module, spec, bases); + if (unlikely(!cached_type)) goto bad; + if (unlikely(__Pyx_fix_up_extension_type_from_spec(spec, (PyTypeObject *) cached_type) < 0)) goto bad; + if (PyObject_SetAttrString(abi_module, object_name, cached_type) < 0) goto bad; +done: + Py_DECREF(abi_module); + assert(cached_type == NULL || PyType_Check(cached_type)); + return (PyTypeObject *) cached_type; +bad: + Py_XDECREF(cached_type); + cached_type = NULL; + goto done; +} +#endif + +/* PyVectorcallFastCallDict */ +#if CYTHON_METH_FASTCALL +static PyObject *__Pyx_PyVectorcall_FastCallDict_kw(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + PyObject *res = NULL; + PyObject *kwnames; + PyObject **newargs; + PyObject **kwvalues; + Py_ssize_t i, pos; + size_t j; + PyObject *key, *value; + unsigned long keys_are_strings; + Py_ssize_t nkw = PyDict_GET_SIZE(kw); + newargs = (PyObject **)PyMem_Malloc((nargs + (size_t)nkw) * sizeof(args[0])); + if (unlikely(newargs == NULL)) { + PyErr_NoMemory(); + return NULL; + } + for (j = 0; j < nargs; j++) newargs[j] = args[j]; + kwnames = PyTuple_New(nkw); + if (unlikely(kwnames == NULL)) { + PyMem_Free(newargs); + return NULL; + } + kwvalues = newargs + nargs; + pos = i = 0; + keys_are_strings = Py_TPFLAGS_UNICODE_SUBCLASS; + while (PyDict_Next(kw, &pos, &key, &value)) { + keys_are_strings &= Py_TYPE(key)->tp_flags; + Py_INCREF(key); + Py_INCREF(value); + PyTuple_SET_ITEM(kwnames, i, key); + kwvalues[i] = value; + i++; + } + if (unlikely(!keys_are_strings)) { + PyErr_SetString(PyExc_TypeError, "keywords must be strings"); + goto cleanup; + } + res = vc(func, newargs, nargs, kwnames); +cleanup: + Py_DECREF(kwnames); + for (i = 0; i < nkw; i++) + Py_DECREF(kwvalues[i]); + PyMem_Free(newargs); + return res; +} +static CYTHON_INLINE PyObject *__Pyx_PyVectorcall_FastCallDict(PyObject *func, __pyx_vectorcallfunc vc, PyObject *const *args, size_t nargs, PyObject *kw) +{ + if (likely(kw == NULL) || PyDict_GET_SIZE(kw) == 0) { + return vc(func, args, nargs, NULL); + } + return __Pyx_PyVectorcall_FastCallDict_kw(func, vc, args, nargs, kw); +} +#endif + +/* CythonFunctionShared */ +#if CYTHON_COMPILING_IN_LIMITED_API +static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc) { + if (__Pyx_CyFunction_Check(func)) { + return PyCFunction_GetFunction(((__pyx_CyFunctionObject*)func)->func) == (PyCFunction) cfunc; + } else if (PyCFunction_Check(func)) { + return PyCFunction_GetFunction(func) == (PyCFunction) cfunc; + } + return 0; +} +#else +static CYTHON_INLINE int __Pyx__IsSameCyOrCFunction(PyObject *func, void *cfunc) { + return __Pyx_CyOrPyCFunction_Check(func) && __Pyx_CyOrPyCFunction_GET_FUNCTION(func) == (PyCFunction) cfunc; +} +#endif +static CYTHON_INLINE void __Pyx__CyFunction_SetClassObj(__pyx_CyFunctionObject* f, PyObject* classobj) { +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + __Pyx_Py_XDECREF_SET( + __Pyx_CyFunction_GetClassObj(f), + ((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#else + __Pyx_Py_XDECREF_SET( + ((PyCMethodObject *) (f))->mm_class, + (PyTypeObject*)((classobj) ? __Pyx_NewRef(classobj) : NULL)); +#endif +} +static PyObject * +__Pyx_CyFunction_get_doc(__pyx_CyFunctionObject *op, void *closure) +{ + CYTHON_UNUSED_VAR(closure); + if (unlikely(op->func_doc == NULL)) { +#if CYTHON_COMPILING_IN_LIMITED_API + op->func_doc = PyObject_GetAttrString(op->func, "__doc__"); + if (unlikely(!op->func_doc)) return NULL; +#else + if (((PyCFunctionObject*)op)->m_ml->ml_doc) { +#if PY_MAJOR_VERSION >= 3 + op->func_doc = PyUnicode_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#else + op->func_doc = PyString_FromString(((PyCFunctionObject*)op)->m_ml->ml_doc); +#endif + if (unlikely(op->func_doc == NULL)) + return NULL; + } else { + Py_INCREF(Py_None); + return Py_None; + } +#endif + } + Py_INCREF(op->func_doc); + return op->func_doc; +} +static int +__Pyx_CyFunction_set_doc(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (value == NULL) { + value = Py_None; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_doc, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_name(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_name == NULL)) { +#if CYTHON_COMPILING_IN_LIMITED_API + op->func_name = PyObject_GetAttrString(op->func, "__name__"); +#elif PY_MAJOR_VERSION >= 3 + op->func_name = PyUnicode_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#else + op->func_name = PyString_InternFromString(((PyCFunctionObject*)op)->m_ml->ml_name); +#endif + if (unlikely(op->func_name == NULL)) + return NULL; + } + Py_INCREF(op->func_name); + return op->func_name; +} +static int +__Pyx_CyFunction_set_name(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__name__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_name, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_qualname(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_qualname); + return op->func_qualname; +} +static int +__Pyx_CyFunction_set_qualname(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); +#if PY_MAJOR_VERSION >= 3 + if (unlikely(value == NULL || !PyUnicode_Check(value))) +#else + if (unlikely(value == NULL || !PyString_Check(value))) +#endif + { + PyErr_SetString(PyExc_TypeError, + "__qualname__ must be set to a string object"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_qualname, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_dict(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(op->func_dict == NULL)) { + op->func_dict = PyDict_New(); + if (unlikely(op->func_dict == NULL)) + return NULL; + } + Py_INCREF(op->func_dict); + return op->func_dict; +} +static int +__Pyx_CyFunction_set_dict(__pyx_CyFunctionObject *op, PyObject *value, void *context) +{ + CYTHON_UNUSED_VAR(context); + if (unlikely(value == NULL)) { + PyErr_SetString(PyExc_TypeError, + "function's dictionary may not be deleted"); + return -1; + } + if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "setting function's dictionary to a non-dict"); + return -1; + } + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->func_dict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_globals(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(context); + Py_INCREF(op->func_globals); + return op->func_globals; +} +static PyObject * +__Pyx_CyFunction_get_closure(__pyx_CyFunctionObject *op, void *context) +{ + CYTHON_UNUSED_VAR(op); + CYTHON_UNUSED_VAR(context); + Py_INCREF(Py_None); + return Py_None; +} +static PyObject * +__Pyx_CyFunction_get_code(__pyx_CyFunctionObject *op, void *context) +{ + PyObject* result = (op->func_code) ? op->func_code : Py_None; + CYTHON_UNUSED_VAR(context); + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_init_defaults(__pyx_CyFunctionObject *op) { + int result = 0; + PyObject *res = op->defaults_getter((PyObject *) op); + if (unlikely(!res)) + return -1; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + op->defaults_tuple = PyTuple_GET_ITEM(res, 0); + Py_INCREF(op->defaults_tuple); + op->defaults_kwdict = PyTuple_GET_ITEM(res, 1); + Py_INCREF(op->defaults_kwdict); + #else + op->defaults_tuple = __Pyx_PySequence_ITEM(res, 0); + if (unlikely(!op->defaults_tuple)) result = -1; + else { + op->defaults_kwdict = __Pyx_PySequence_ITEM(res, 1); + if (unlikely(!op->defaults_kwdict)) result = -1; + } + #endif + Py_DECREF(res); + return result; +} +static int +__Pyx_CyFunction_set_defaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyTuple_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__defaults__ must be set to a tuple object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__defaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_tuple, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_defaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_tuple; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_tuple; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_kwdefaults(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value) { + value = Py_None; + } else if (unlikely(value != Py_None && !PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__kwdefaults__ must be set to a dict object"); + return -1; + } + PyErr_WarnEx(PyExc_RuntimeWarning, "changes to cyfunction.__kwdefaults__ will not " + "currently affect the values used in function calls", 1); + Py_INCREF(value); + __Pyx_Py_XDECREF_SET(op->defaults_kwdict, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_kwdefaults(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->defaults_kwdict; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + if (op->defaults_getter) { + if (unlikely(__Pyx_CyFunction_init_defaults(op) < 0)) return NULL; + result = op->defaults_kwdict; + } else { + result = Py_None; + } + } + Py_INCREF(result); + return result; +} +static int +__Pyx_CyFunction_set_annotations(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + if (!value || value == Py_None) { + value = NULL; + } else if (unlikely(!PyDict_Check(value))) { + PyErr_SetString(PyExc_TypeError, + "__annotations__ must be set to a dict object"); + return -1; + } + Py_XINCREF(value); + __Pyx_Py_XDECREF_SET(op->func_annotations, value); + return 0; +} +static PyObject * +__Pyx_CyFunction_get_annotations(__pyx_CyFunctionObject *op, void *context) { + PyObject* result = op->func_annotations; + CYTHON_UNUSED_VAR(context); + if (unlikely(!result)) { + result = PyDict_New(); + if (unlikely(!result)) return NULL; + op->func_annotations = result; + } + Py_INCREF(result); + return result; +} +static PyObject * +__Pyx_CyFunction_get_is_coroutine(__pyx_CyFunctionObject *op, void *context) { + int is_coroutine; + CYTHON_UNUSED_VAR(context); + if (op->func_is_coroutine) { + return __Pyx_NewRef(op->func_is_coroutine); + } + is_coroutine = op->flags & __Pyx_CYFUNCTION_COROUTINE; +#if PY_VERSION_HEX >= 0x03050000 + if (is_coroutine) { + PyObject *module, *fromlist, *marker = __pyx_n_s_is_coroutine; + fromlist = PyList_New(1); + if (unlikely(!fromlist)) return NULL; + Py_INCREF(marker); +#if CYTHON_ASSUME_SAFE_MACROS + PyList_SET_ITEM(fromlist, 0, marker); +#else + if (unlikely(PyList_SetItem(fromlist, 0, marker) < 0)) { + Py_DECREF(marker); + Py_DECREF(fromlist); + return NULL; + } +#endif + module = PyImport_ImportModuleLevelObject(__pyx_n_s_asyncio_coroutines, NULL, NULL, fromlist, 0); + Py_DECREF(fromlist); + if (unlikely(!module)) goto ignore; + op->func_is_coroutine = __Pyx_PyObject_GetAttrStr(module, marker); + Py_DECREF(module); + if (likely(op->func_is_coroutine)) { + return __Pyx_NewRef(op->func_is_coroutine); + } +ignore: + PyErr_Clear(); + } +#endif + op->func_is_coroutine = __Pyx_PyBool_FromLong(is_coroutine); + return __Pyx_NewRef(op->func_is_coroutine); +} +#if CYTHON_COMPILING_IN_LIMITED_API +static PyObject * +__Pyx_CyFunction_get_module(__pyx_CyFunctionObject *op, void *context) { + CYTHON_UNUSED_VAR(context); + return PyObject_GetAttrString(op->func, "__module__"); +} +static int +__Pyx_CyFunction_set_module(__pyx_CyFunctionObject *op, PyObject* value, void *context) { + CYTHON_UNUSED_VAR(context); + return PyObject_SetAttrString(op->func, "__module__", value); +} +#endif +static PyGetSetDef __pyx_CyFunction_getsets[] = { + {(char *) "func_doc", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "__doc__", (getter)__Pyx_CyFunction_get_doc, (setter)__Pyx_CyFunction_set_doc, 0, 0}, + {(char *) "func_name", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__name__", (getter)__Pyx_CyFunction_get_name, (setter)__Pyx_CyFunction_set_name, 0, 0}, + {(char *) "__qualname__", (getter)__Pyx_CyFunction_get_qualname, (setter)__Pyx_CyFunction_set_qualname, 0, 0}, + {(char *) "func_dict", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "__dict__", (getter)__Pyx_CyFunction_get_dict, (setter)__Pyx_CyFunction_set_dict, 0, 0}, + {(char *) "func_globals", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "__globals__", (getter)__Pyx_CyFunction_get_globals, 0, 0, 0}, + {(char *) "func_closure", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "__closure__", (getter)__Pyx_CyFunction_get_closure, 0, 0, 0}, + {(char *) "func_code", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "__code__", (getter)__Pyx_CyFunction_get_code, 0, 0, 0}, + {(char *) "func_defaults", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__defaults__", (getter)__Pyx_CyFunction_get_defaults, (setter)__Pyx_CyFunction_set_defaults, 0, 0}, + {(char *) "__kwdefaults__", (getter)__Pyx_CyFunction_get_kwdefaults, (setter)__Pyx_CyFunction_set_kwdefaults, 0, 0}, + {(char *) "__annotations__", (getter)__Pyx_CyFunction_get_annotations, (setter)__Pyx_CyFunction_set_annotations, 0, 0}, + {(char *) "_is_coroutine", (getter)__Pyx_CyFunction_get_is_coroutine, 0, 0, 0}, +#if CYTHON_COMPILING_IN_LIMITED_API + {"__module__", (getter)__Pyx_CyFunction_get_module, (setter)__Pyx_CyFunction_set_module, 0, 0}, +#endif + {0, 0, 0, 0, 0} +}; +static PyMemberDef __pyx_CyFunction_members[] = { +#if !CYTHON_COMPILING_IN_LIMITED_API + {(char *) "__module__", T_OBJECT, offsetof(PyCFunctionObject, m_module), 0, 0}, +#endif +#if CYTHON_USE_TYPE_SPECS + {(char *) "__dictoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_dict), READONLY, 0}, +#if CYTHON_METH_FASTCALL +#if CYTHON_BACKPORT_VECTORCALL + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_vectorcall), READONLY, 0}, +#else +#if !CYTHON_COMPILING_IN_LIMITED_API + {(char *) "__vectorcalloffset__", T_PYSSIZET, offsetof(PyCFunctionObject, vectorcall), READONLY, 0}, +#endif +#endif +#endif +#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(__pyx_CyFunctionObject, func_weakreflist), READONLY, 0}, +#else + {(char *) "__weaklistoffset__", T_PYSSIZET, offsetof(PyCFunctionObject, m_weakreflist), READONLY, 0}, +#endif +#endif + {0, 0, 0, 0, 0} +}; +static PyObject * +__Pyx_CyFunction_reduce(__pyx_CyFunctionObject *m, PyObject *args) +{ + CYTHON_UNUSED_VAR(args); +#if PY_MAJOR_VERSION >= 3 + Py_INCREF(m->func_qualname); + return m->func_qualname; +#else + return PyString_FromString(((PyCFunctionObject*)m)->m_ml->ml_name); +#endif +} +static PyMethodDef __pyx_CyFunction_methods[] = { + {"__reduce__", (PyCFunction)__Pyx_CyFunction_reduce, METH_VARARGS, 0}, + {0, 0, 0, 0} +}; +#if PY_VERSION_HEX < 0x030500A0 || CYTHON_COMPILING_IN_LIMITED_API +#define __Pyx_CyFunction_weakreflist(cyfunc) ((cyfunc)->func_weakreflist) +#else +#define __Pyx_CyFunction_weakreflist(cyfunc) (((PyCFunctionObject*)cyfunc)->m_weakreflist) +#endif +static PyObject *__Pyx_CyFunction_Init(__pyx_CyFunctionObject *op, PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { +#if !CYTHON_COMPILING_IN_LIMITED_API + PyCFunctionObject *cf = (PyCFunctionObject*) op; +#endif + if (unlikely(op == NULL)) + return NULL; +#if CYTHON_COMPILING_IN_LIMITED_API + op->func = PyCFunction_NewEx(ml, (PyObject*)op, module); + if (unlikely(!op->func)) return NULL; +#endif + op->flags = flags; + __Pyx_CyFunction_weakreflist(op) = NULL; +#if !CYTHON_COMPILING_IN_LIMITED_API + cf->m_ml = ml; + cf->m_self = (PyObject *) op; +#endif + Py_XINCREF(closure); + op->func_closure = closure; +#if !CYTHON_COMPILING_IN_LIMITED_API + Py_XINCREF(module); + cf->m_module = module; +#endif + op->func_dict = NULL; + op->func_name = NULL; + Py_INCREF(qualname); + op->func_qualname = qualname; + op->func_doc = NULL; +#if PY_VERSION_HEX < 0x030900B1 || CYTHON_COMPILING_IN_LIMITED_API + op->func_classobj = NULL; +#else + ((PyCMethodObject*)op)->mm_class = NULL; +#endif + op->func_globals = globals; + Py_INCREF(op->func_globals); + Py_XINCREF(code); + op->func_code = code; + op->defaults_pyobjects = 0; + op->defaults_size = 0; + op->defaults = NULL; + op->defaults_tuple = NULL; + op->defaults_kwdict = NULL; + op->defaults_getter = NULL; + op->func_annotations = NULL; + op->func_is_coroutine = NULL; +#if CYTHON_METH_FASTCALL + switch (ml->ml_flags & (METH_VARARGS | METH_FASTCALL | METH_NOARGS | METH_O | METH_KEYWORDS | METH_METHOD)) { + case METH_NOARGS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_NOARGS; + break; + case METH_O: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_O; + break; + case METH_METHOD | METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD; + break; + case METH_FASTCALL | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS; + break; + case METH_VARARGS | METH_KEYWORDS: + __Pyx_CyFunction_func_vectorcall(op) = NULL; + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + Py_DECREF(op); + return NULL; + } +#endif + return (PyObject *) op; +} +static int +__Pyx_CyFunction_clear(__pyx_CyFunctionObject *m) +{ + Py_CLEAR(m->func_closure); +#if CYTHON_COMPILING_IN_LIMITED_API + Py_CLEAR(m->func); +#else + Py_CLEAR(((PyCFunctionObject*)m)->m_module); +#endif + Py_CLEAR(m->func_dict); + Py_CLEAR(m->func_name); + Py_CLEAR(m->func_qualname); + Py_CLEAR(m->func_doc); + Py_CLEAR(m->func_globals); + Py_CLEAR(m->func_code); +#if !CYTHON_COMPILING_IN_LIMITED_API +#if PY_VERSION_HEX < 0x030900B1 + Py_CLEAR(__Pyx_CyFunction_GetClassObj(m)); +#else + { + PyObject *cls = (PyObject*) ((PyCMethodObject *) (m))->mm_class; + ((PyCMethodObject *) (m))->mm_class = NULL; + Py_XDECREF(cls); + } +#endif +#endif + Py_CLEAR(m->defaults_tuple); + Py_CLEAR(m->defaults_kwdict); + Py_CLEAR(m->func_annotations); + Py_CLEAR(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_XDECREF(pydefaults[i]); + PyObject_Free(m->defaults); + m->defaults = NULL; + } + return 0; +} +static void __Pyx__CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + if (__Pyx_CyFunction_weakreflist(m) != NULL) + PyObject_ClearWeakRefs((PyObject *) m); + __Pyx_CyFunction_clear(m); + __Pyx_PyHeapTypeObject_GC_Del(m); +} +static void __Pyx_CyFunction_dealloc(__pyx_CyFunctionObject *m) +{ + PyObject_GC_UnTrack(m); + __Pyx__CyFunction_dealloc(m); +} +static int __Pyx_CyFunction_traverse(__pyx_CyFunctionObject *m, visitproc visit, void *arg) +{ + Py_VISIT(m->func_closure); +#if CYTHON_COMPILING_IN_LIMITED_API + Py_VISIT(m->func); +#else + Py_VISIT(((PyCFunctionObject*)m)->m_module); +#endif + Py_VISIT(m->func_dict); + Py_VISIT(m->func_name); + Py_VISIT(m->func_qualname); + Py_VISIT(m->func_doc); + Py_VISIT(m->func_globals); + Py_VISIT(m->func_code); +#if !CYTHON_COMPILING_IN_LIMITED_API + Py_VISIT(__Pyx_CyFunction_GetClassObj(m)); +#endif + Py_VISIT(m->defaults_tuple); + Py_VISIT(m->defaults_kwdict); + Py_VISIT(m->func_is_coroutine); + if (m->defaults) { + PyObject **pydefaults = __Pyx_CyFunction_Defaults(PyObject *, m); + int i; + for (i = 0; i < m->defaults_pyobjects; i++) + Py_VISIT(pydefaults[i]); + } + return 0; +} +static PyObject* +__Pyx_CyFunction_repr(__pyx_CyFunctionObject *op) +{ +#if PY_MAJOR_VERSION >= 3 + return PyUnicode_FromFormat("", + op->func_qualname, (void *)op); +#else + return PyString_FromFormat("", + PyString_AsString(op->func_qualname), (void *)op); +#endif +} +static PyObject * __Pyx_CyFunction_CallMethod(PyObject *func, PyObject *self, PyObject *arg, PyObject *kw) { +#if CYTHON_COMPILING_IN_LIMITED_API + PyObject *f = ((__pyx_CyFunctionObject*)func)->func; + PyObject *py_name = NULL; + PyCFunction meth; + int flags; + meth = PyCFunction_GetFunction(f); + if (unlikely(!meth)) return NULL; + flags = PyCFunction_GetFlags(f); + if (unlikely(flags < 0)) return NULL; +#else + PyCFunctionObject* f = (PyCFunctionObject*)func; + PyCFunction meth = f->m_ml->ml_meth; + int flags = f->m_ml->ml_flags; +#endif + Py_ssize_t size; + switch (flags & (METH_VARARGS | METH_KEYWORDS | METH_NOARGS | METH_O)) { + case METH_VARARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) + return (*meth)(self, arg); + break; + case METH_VARARGS | METH_KEYWORDS: + return (*(PyCFunctionWithKeywords)(void*)meth)(self, arg, kw); + case METH_NOARGS: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { +#if CYTHON_ASSUME_SAFE_MACROS + size = PyTuple_GET_SIZE(arg); +#else + size = PyTuple_Size(arg); + if (unlikely(size < 0)) return NULL; +#endif + if (likely(size == 0)) + return (*meth)(self, NULL); +#if CYTHON_COMPILING_IN_LIMITED_API + py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); + if (!py_name) return NULL; + PyErr_Format(PyExc_TypeError, + "%.200S() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + py_name, size); + Py_DECREF(py_name); +#else + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); +#endif + return NULL; + } + break; + case METH_O: + if (likely(kw == NULL || PyDict_Size(kw) == 0)) { +#if CYTHON_ASSUME_SAFE_MACROS + size = PyTuple_GET_SIZE(arg); +#else + size = PyTuple_Size(arg); + if (unlikely(size < 0)) return NULL; +#endif + if (likely(size == 1)) { + PyObject *result, *arg0; + #if CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS + arg0 = PyTuple_GET_ITEM(arg, 0); + #else + arg0 = __Pyx_PySequence_ITEM(arg, 0); if (unlikely(!arg0)) return NULL; + #endif + result = (*meth)(self, arg0); + #if !(CYTHON_ASSUME_SAFE_MACROS && !CYTHON_AVOID_BORROWED_REFS) + Py_DECREF(arg0); + #endif + return result; + } +#if CYTHON_COMPILING_IN_LIMITED_API + py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); + if (!py_name) return NULL; + PyErr_Format(PyExc_TypeError, + "%.200S() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + py_name, size); + Py_DECREF(py_name); +#else + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + f->m_ml->ml_name, size); +#endif + return NULL; + } + break; + default: + PyErr_SetString(PyExc_SystemError, "Bad call flags for CyFunction"); + return NULL; + } +#if CYTHON_COMPILING_IN_LIMITED_API + py_name = __Pyx_CyFunction_get_name((__pyx_CyFunctionObject*)func, NULL); + if (!py_name) return NULL; + PyErr_Format(PyExc_TypeError, "%.200S() takes no keyword arguments", + py_name); + Py_DECREF(py_name); +#else + PyErr_Format(PyExc_TypeError, "%.200s() takes no keyword arguments", + f->m_ml->ml_name); +#endif + return NULL; +} +static CYTHON_INLINE PyObject *__Pyx_CyFunction_Call(PyObject *func, PyObject *arg, PyObject *kw) { + PyObject *self, *result; +#if CYTHON_COMPILING_IN_LIMITED_API + self = PyCFunction_GetSelf(((__pyx_CyFunctionObject*)func)->func); + if (unlikely(!self) && PyErr_Occurred()) return NULL; +#else + self = ((PyCFunctionObject*)func)->m_self; +#endif + result = __Pyx_CyFunction_CallMethod(func, self, arg, kw); + return result; +} +static PyObject *__Pyx_CyFunction_CallAsMethod(PyObject *func, PyObject *args, PyObject *kw) { + PyObject *result; + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *) func; +#if CYTHON_METH_FASTCALL + __pyx_vectorcallfunc vc = __Pyx_CyFunction_func_vectorcall(cyfunc); + if (vc) { +#if CYTHON_ASSUME_SAFE_MACROS + return __Pyx_PyVectorcall_FastCallDict(func, vc, &PyTuple_GET_ITEM(args, 0), (size_t)PyTuple_GET_SIZE(args), kw); +#else + (void) &__Pyx_PyVectorcall_FastCallDict; + return PyVectorcall_Call(func, args, kw); +#endif + } +#endif + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + Py_ssize_t argc; + PyObject *new_args; + PyObject *self; +#if CYTHON_ASSUME_SAFE_MACROS + argc = PyTuple_GET_SIZE(args); +#else + argc = PyTuple_Size(args); + if (unlikely(!argc) < 0) return NULL; +#endif + new_args = PyTuple_GetSlice(args, 1, argc); + if (unlikely(!new_args)) + return NULL; + self = PyTuple_GetItem(args, 0); + if (unlikely(!self)) { + Py_DECREF(new_args); +#if PY_MAJOR_VERSION > 2 + PyErr_Format(PyExc_TypeError, + "unbound method %.200S() needs an argument", + cyfunc->func_qualname); +#else + PyErr_SetString(PyExc_TypeError, + "unbound method needs an argument"); +#endif + return NULL; + } + result = __Pyx_CyFunction_CallMethod(func, self, new_args, kw); + Py_DECREF(new_args); + } else { + result = __Pyx_CyFunction_Call(func, args, kw); + } + return result; +} +#if CYTHON_METH_FASTCALL +static CYTHON_INLINE int __Pyx_CyFunction_Vectorcall_CheckArgs(__pyx_CyFunctionObject *cyfunc, Py_ssize_t nargs, PyObject *kwnames) +{ + int ret = 0; + if ((cyfunc->flags & __Pyx_CYFUNCTION_CCLASS) && !(cyfunc->flags & __Pyx_CYFUNCTION_STATICMETHOD)) { + if (unlikely(nargs < 1)) { + PyErr_Format(PyExc_TypeError, "%.200s() needs an argument", + ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + ret = 1; + } + if (unlikely(kwnames) && unlikely(PyTuple_GET_SIZE(kwnames))) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no keyword arguments", ((PyCFunctionObject*)cyfunc)->m_ml->ml_name); + return -1; + } + return ret; +} +static PyObject * __Pyx_CyFunction_Vectorcall_NOARGS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 0)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes no arguments (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, NULL); +} +static PyObject * __Pyx_CyFunction_Vectorcall_O(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, kwnames)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + if (unlikely(nargs != 1)) { + PyErr_Format(PyExc_TypeError, + "%.200s() takes exactly one argument (%" CYTHON_FORMAT_SSIZE_T "d given)", + def->ml_name, nargs); + return NULL; + } + return def->ml_meth(self, args[0]); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((_PyCFunctionFastWithKeywords)(void(*)(void))def->ml_meth)(self, args, nargs, kwnames); +} +static PyObject * __Pyx_CyFunction_Vectorcall_FASTCALL_KEYWORDS_METHOD(PyObject *func, PyObject *const *args, size_t nargsf, PyObject *kwnames) +{ + __pyx_CyFunctionObject *cyfunc = (__pyx_CyFunctionObject *)func; + PyMethodDef* def = ((PyCFunctionObject*)cyfunc)->m_ml; + PyTypeObject *cls = (PyTypeObject *) __Pyx_CyFunction_GetClassObj(cyfunc); +#if CYTHON_BACKPORT_VECTORCALL + Py_ssize_t nargs = (Py_ssize_t)nargsf; +#else + Py_ssize_t nargs = PyVectorcall_NARGS(nargsf); +#endif + PyObject *self; + switch (__Pyx_CyFunction_Vectorcall_CheckArgs(cyfunc, nargs, NULL)) { + case 1: + self = args[0]; + args += 1; + nargs -= 1; + break; + case 0: + self = ((PyCFunctionObject*)cyfunc)->m_self; + break; + default: + return NULL; + } + return ((__Pyx_PyCMethod)(void(*)(void))def->ml_meth)(self, cls, args, (size_t)nargs, kwnames); +} +#endif +#if CYTHON_USE_TYPE_SPECS +static PyType_Slot __pyx_CyFunctionType_slots[] = { + {Py_tp_dealloc, (void *)__Pyx_CyFunction_dealloc}, + {Py_tp_repr, (void *)__Pyx_CyFunction_repr}, + {Py_tp_call, (void *)__Pyx_CyFunction_CallAsMethod}, + {Py_tp_traverse, (void *)__Pyx_CyFunction_traverse}, + {Py_tp_clear, (void *)__Pyx_CyFunction_clear}, + {Py_tp_methods, (void *)__pyx_CyFunction_methods}, + {Py_tp_members, (void *)__pyx_CyFunction_members}, + {Py_tp_getset, (void *)__pyx_CyFunction_getsets}, + {Py_tp_descr_get, (void *)__Pyx_PyMethod_New}, + {0, 0}, +}; +static PyType_Spec __pyx_CyFunctionType_spec = { + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#if (defined(_Py_TPFLAGS_HAVE_VECTORCALL) && CYTHON_METH_FASTCALL) + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + __pyx_CyFunctionType_slots +}; +#else +static PyTypeObject __pyx_CyFunctionType_type = { + PyVarObject_HEAD_INIT(0, 0) + __PYX_TYPE_MODULE_PREFIX "cython_function_or_method", + sizeof(__pyx_CyFunctionObject), + 0, + (destructor) __Pyx_CyFunction_dealloc, +#if !CYTHON_METH_FASTCALL + 0, +#elif CYTHON_BACKPORT_VECTORCALL + (printfunc)offsetof(__pyx_CyFunctionObject, func_vectorcall), +#else + offsetof(PyCFunctionObject, vectorcall), +#endif + 0, + 0, +#if PY_MAJOR_VERSION < 3 + 0, +#else + 0, +#endif + (reprfunc) __Pyx_CyFunction_repr, + 0, + 0, + 0, + 0, + __Pyx_CyFunction_CallAsMethod, + 0, + 0, + 0, + 0, +#ifdef Py_TPFLAGS_METHOD_DESCRIPTOR + Py_TPFLAGS_METHOD_DESCRIPTOR | +#endif +#if defined(_Py_TPFLAGS_HAVE_VECTORCALL) && CYTHON_METH_FASTCALL + _Py_TPFLAGS_HAVE_VECTORCALL | +#endif + Py_TPFLAGS_DEFAULT | Py_TPFLAGS_HAVE_GC | Py_TPFLAGS_BASETYPE, + 0, + (traverseproc) __Pyx_CyFunction_traverse, + (inquiry) __Pyx_CyFunction_clear, + 0, +#if PY_VERSION_HEX < 0x030500A0 + offsetof(__pyx_CyFunctionObject, func_weakreflist), +#else + offsetof(PyCFunctionObject, m_weakreflist), +#endif + 0, + 0, + __pyx_CyFunction_methods, + __pyx_CyFunction_members, + __pyx_CyFunction_getsets, + 0, + 0, + __Pyx_PyMethod_New, + 0, + offsetof(__pyx_CyFunctionObject, func_dict), + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, +#if PY_VERSION_HEX >= 0x030400a1 + 0, +#endif +#if PY_VERSION_HEX >= 0x030800b1 && (!CYTHON_COMPILING_IN_PYPY || PYPY_VERSION_NUM >= 0x07030800) + 0, +#endif +#if __PYX_NEED_TP_PRINT_SLOT + 0, +#endif +#if PY_VERSION_HEX >= 0x030C0000 + 0, +#endif +#if CYTHON_COMPILING_IN_PYPY && PY_VERSION_HEX >= 0x03090000 && PY_VERSION_HEX < 0x030a0000 + 0, +#endif +}; +#endif +static int __pyx_CyFunction_init(PyObject *module) { +#if CYTHON_USE_TYPE_SPECS + __pyx_CyFunctionType = __Pyx_FetchCommonTypeFromSpec(module, &__pyx_CyFunctionType_spec, NULL); +#else + CYTHON_UNUSED_VAR(module); + __pyx_CyFunctionType = __Pyx_FetchCommonType(&__pyx_CyFunctionType_type); +#endif + if (unlikely(__pyx_CyFunctionType == NULL)) { + return -1; + } + return 0; +} +static CYTHON_INLINE void *__Pyx_CyFunction_InitDefaults(PyObject *func, size_t size, int pyobjects) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults = PyObject_Malloc(size); + if (unlikely(!m->defaults)) + return PyErr_NoMemory(); + memset(m->defaults, 0, size); + m->defaults_pyobjects = pyobjects; + m->defaults_size = size; + return m->defaults; +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsTuple(PyObject *func, PyObject *tuple) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_tuple = tuple; + Py_INCREF(tuple); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetDefaultsKwDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->defaults_kwdict = dict; + Py_INCREF(dict); +} +static CYTHON_INLINE void __Pyx_CyFunction_SetAnnotationsDict(PyObject *func, PyObject *dict) { + __pyx_CyFunctionObject *m = (__pyx_CyFunctionObject *) func; + m->func_annotations = dict; + Py_INCREF(dict); +} + +/* CythonFunction */ +static PyObject *__Pyx_CyFunction_New(PyMethodDef *ml, int flags, PyObject* qualname, + PyObject *closure, PyObject *module, PyObject* globals, PyObject* code) { + PyObject *op = __Pyx_CyFunction_Init( + PyObject_GC_New(__pyx_CyFunctionObject, __pyx_CyFunctionType), + ml, flags, qualname, closure, module, globals, code + ); + if (likely(op)) { + PyObject_GC_Track(op); + } + return op; +} + +/* CLineInTraceback */ +#ifndef CYTHON_CLINE_IN_TRACEBACK +static int __Pyx_CLineForTraceback(PyThreadState *tstate, int c_line) { + PyObject *use_cline; + PyObject *ptype, *pvalue, *ptraceback; +#if CYTHON_COMPILING_IN_CPYTHON + PyObject **cython_runtime_dict; +#endif + CYTHON_MAYBE_UNUSED_VAR(tstate); + if (unlikely(!__pyx_cython_runtime)) { + return c_line; + } + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); +#if CYTHON_COMPILING_IN_CPYTHON + cython_runtime_dict = _PyObject_GetDictPtr(__pyx_cython_runtime); + if (likely(cython_runtime_dict)) { + __PYX_PY_DICT_LOOKUP_IF_MODIFIED( + use_cline, *cython_runtime_dict, + __Pyx_PyDict_GetItemStr(*cython_runtime_dict, __pyx_n_s_cline_in_traceback)) + } else +#endif + { + PyObject *use_cline_obj = __Pyx_PyObject_GetAttrStrNoError(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback); + if (use_cline_obj) { + use_cline = PyObject_Not(use_cline_obj) ? Py_False : Py_True; + Py_DECREF(use_cline_obj); + } else { + PyErr_Clear(); + use_cline = NULL; + } + } + if (!use_cline) { + c_line = 0; + (void) PyObject_SetAttr(__pyx_cython_runtime, __pyx_n_s_cline_in_traceback, Py_False); + } + else if (use_cline == Py_False || (use_cline != Py_True && PyObject_Not(use_cline) != 0)) { + c_line = 0; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + return c_line; +} +#endif + +/* CodeObjectCache */ +#if !CYTHON_COMPILING_IN_LIMITED_API +static int __pyx_bisect_code_objects(__Pyx_CodeObjectCacheEntry* entries, int count, int code_line) { + int start = 0, mid = 0, end = count - 1; + if (end >= 0 && code_line > entries[end].code_line) { + return count; + } + while (start < end) { + mid = start + (end - start) / 2; + if (code_line < entries[mid].code_line) { + end = mid; + } else if (code_line > entries[mid].code_line) { + start = mid + 1; + } else { + return mid; + } + } + if (code_line <= entries[mid].code_line) { + return mid; + } else { + return mid + 1; + } +} +static PyCodeObject *__pyx_find_code_object(int code_line) { + PyCodeObject* code_object; + int pos; + if (unlikely(!code_line) || unlikely(!__pyx_code_cache.entries)) { + return NULL; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if (unlikely(pos >= __pyx_code_cache.count) || unlikely(__pyx_code_cache.entries[pos].code_line != code_line)) { + return NULL; + } + code_object = __pyx_code_cache.entries[pos].code_object; + Py_INCREF(code_object); + return code_object; +} +static void __pyx_insert_code_object(int code_line, PyCodeObject* code_object) { + int pos, i; + __Pyx_CodeObjectCacheEntry* entries = __pyx_code_cache.entries; + if (unlikely(!code_line)) { + return; + } + if (unlikely(!entries)) { + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Malloc(64*sizeof(__Pyx_CodeObjectCacheEntry)); + if (likely(entries)) { + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = 64; + __pyx_code_cache.count = 1; + entries[0].code_line = code_line; + entries[0].code_object = code_object; + Py_INCREF(code_object); + } + return; + } + pos = __pyx_bisect_code_objects(__pyx_code_cache.entries, __pyx_code_cache.count, code_line); + if ((pos < __pyx_code_cache.count) && unlikely(__pyx_code_cache.entries[pos].code_line == code_line)) { + PyCodeObject* tmp = entries[pos].code_object; + entries[pos].code_object = code_object; + Py_DECREF(tmp); + return; + } + if (__pyx_code_cache.count == __pyx_code_cache.max_count) { + int new_max = __pyx_code_cache.max_count + 64; + entries = (__Pyx_CodeObjectCacheEntry*)PyMem_Realloc( + __pyx_code_cache.entries, ((size_t)new_max) * sizeof(__Pyx_CodeObjectCacheEntry)); + if (unlikely(!entries)) { + return; + } + __pyx_code_cache.entries = entries; + __pyx_code_cache.max_count = new_max; + } + for (i=__pyx_code_cache.count; i>pos; i--) { + entries[i] = entries[i-1]; + } + entries[pos].code_line = code_line; + entries[pos].code_object = code_object; + __pyx_code_cache.count++; + Py_INCREF(code_object); +} +#endif + +/* AddTraceback */ +#include "compile.h" +#include "frameobject.h" +#include "traceback.h" +#if PY_VERSION_HEX >= 0x030b00a6 && !CYTHON_COMPILING_IN_LIMITED_API + #ifndef Py_BUILD_CORE + #define Py_BUILD_CORE 1 + #endif + #include "internal/pycore_frame.h" +#endif +#if CYTHON_COMPILING_IN_LIMITED_API +static PyObject *__Pyx_PyCode_Replace_For_AddTraceback(PyObject *code, PyObject *scratch_dict, + PyObject *firstlineno, PyObject *name) { + PyObject *replace = NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "co_firstlineno", firstlineno))) return NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "co_name", name))) return NULL; + replace = PyObject_GetAttrString(code, "replace"); + if (likely(replace)) { + PyObject *result; + result = PyObject_Call(replace, __pyx_empty_tuple, scratch_dict); + Py_DECREF(replace); + return result; + } + PyErr_Clear(); + #if __PYX_LIMITED_VERSION_HEX < 0x030780000 + { + PyObject *compiled = NULL, *result = NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "code", code))) return NULL; + if (unlikely(PyDict_SetItemString(scratch_dict, "type", (PyObject*)(&PyType_Type)))) return NULL; + compiled = Py_CompileString( + "out = type(code)(\n" + " code.co_argcount, code.co_kwonlyargcount, code.co_nlocals, code.co_stacksize,\n" + " code.co_flags, code.co_code, code.co_consts, code.co_names,\n" + " code.co_varnames, code.co_filename, co_name, co_firstlineno,\n" + " code.co_lnotab)\n", "", Py_file_input); + if (!compiled) return NULL; + result = PyEval_EvalCode(compiled, scratch_dict, scratch_dict); + Py_DECREF(compiled); + if (!result) PyErr_Print(); + Py_DECREF(result); + result = PyDict_GetItemString(scratch_dict, "out"); + if (result) Py_INCREF(result); + return result; + } + #else + return NULL; + #endif +} +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + PyObject *code_object = NULL, *py_py_line = NULL, *py_funcname = NULL, *dict = NULL; + PyObject *replace = NULL, *getframe = NULL, *frame = NULL; + PyObject *exc_type, *exc_value, *exc_traceback; + int success = 0; + if (c_line) { + (void) __pyx_cfilenm; + (void) __Pyx_CLineForTraceback(__Pyx_PyThreadState_Current, c_line); + } + PyErr_Fetch(&exc_type, &exc_value, &exc_traceback); + code_object = Py_CompileString("_getframe()", filename, Py_eval_input); + if (unlikely(!code_object)) goto bad; + py_py_line = PyLong_FromLong(py_line); + if (unlikely(!py_py_line)) goto bad; + py_funcname = PyUnicode_FromString(funcname); + if (unlikely(!py_funcname)) goto bad; + dict = PyDict_New(); + if (unlikely(!dict)) goto bad; + { + PyObject *old_code_object = code_object; + code_object = __Pyx_PyCode_Replace_For_AddTraceback(code_object, dict, py_py_line, py_funcname); + Py_DECREF(old_code_object); + } + if (unlikely(!code_object)) goto bad; + getframe = PySys_GetObject("_getframe"); + if (unlikely(!getframe)) goto bad; + if (unlikely(PyDict_SetItemString(dict, "_getframe", getframe))) goto bad; + frame = PyEval_EvalCode(code_object, dict, dict); + if (unlikely(!frame) || frame == Py_None) goto bad; + success = 1; + bad: + PyErr_Restore(exc_type, exc_value, exc_traceback); + Py_XDECREF(code_object); + Py_XDECREF(py_py_line); + Py_XDECREF(py_funcname); + Py_XDECREF(dict); + Py_XDECREF(replace); + if (success) { + PyTraceBack_Here( + (struct _frame*)frame); + } + Py_XDECREF(frame); +} +#else +static PyCodeObject* __Pyx_CreateCodeObjectForTraceback( + const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = NULL; + PyObject *py_funcname = NULL; + #if PY_MAJOR_VERSION < 3 + PyObject *py_srcfile = NULL; + py_srcfile = PyString_FromString(filename); + if (!py_srcfile) goto bad; + #endif + if (c_line) { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + #else + py_funcname = PyUnicode_FromFormat( "%s (%s:%d)", funcname, __pyx_cfilenm, c_line); + if (!py_funcname) goto bad; + funcname = PyUnicode_AsUTF8(py_funcname); + if (!funcname) goto bad; + #endif + } + else { + #if PY_MAJOR_VERSION < 3 + py_funcname = PyString_FromString(funcname); + if (!py_funcname) goto bad; + #endif + } + #if PY_MAJOR_VERSION < 3 + py_code = __Pyx_PyCode_New( + 0, + 0, + 0, + 0, + 0, + 0, + __pyx_empty_bytes, /*PyObject *code,*/ + __pyx_empty_tuple, /*PyObject *consts,*/ + __pyx_empty_tuple, /*PyObject *names,*/ + __pyx_empty_tuple, /*PyObject *varnames,*/ + __pyx_empty_tuple, /*PyObject *freevars,*/ + __pyx_empty_tuple, /*PyObject *cellvars,*/ + py_srcfile, /*PyObject *filename,*/ + py_funcname, /*PyObject *name,*/ + py_line, + __pyx_empty_bytes /*PyObject *lnotab*/ + ); + Py_DECREF(py_srcfile); + #else + py_code = PyCode_NewEmpty(filename, funcname, py_line); + #endif + Py_XDECREF(py_funcname); + return py_code; +bad: + Py_XDECREF(py_funcname); + #if PY_MAJOR_VERSION < 3 + Py_XDECREF(py_srcfile); + #endif + return NULL; +} +static void __Pyx_AddTraceback(const char *funcname, int c_line, + int py_line, const char *filename) { + PyCodeObject *py_code = 0; + PyFrameObject *py_frame = 0; + PyThreadState *tstate = __Pyx_PyThreadState_Current; + PyObject *ptype, *pvalue, *ptraceback; + if (c_line) { + c_line = __Pyx_CLineForTraceback(tstate, c_line); + } + py_code = __pyx_find_code_object(c_line ? -c_line : py_line); + if (!py_code) { + __Pyx_ErrFetchInState(tstate, &ptype, &pvalue, &ptraceback); + py_code = __Pyx_CreateCodeObjectForTraceback( + funcname, c_line, py_line, filename); + if (!py_code) { + /* If the code object creation fails, then we should clear the + fetched exception references and propagate the new exception */ + Py_XDECREF(ptype); + Py_XDECREF(pvalue); + Py_XDECREF(ptraceback); + goto bad; + } + __Pyx_ErrRestoreInState(tstate, ptype, pvalue, ptraceback); + __pyx_insert_code_object(c_line ? -c_line : py_line, py_code); + } + py_frame = PyFrame_New( + tstate, /*PyThreadState *tstate,*/ + py_code, /*PyCodeObject *code,*/ + __pyx_d, /*PyObject *globals,*/ + 0 /*PyObject *locals*/ + ); + if (!py_frame) goto bad; + __Pyx_PyFrame_SetLineNumber(py_frame, py_line); + PyTraceBack_Here(py_frame); +bad: + Py_XDECREF(py_code); + Py_XDECREF(py_frame); +} +#endif + +#if PY_MAJOR_VERSION < 3 +static int __Pyx_GetBuffer(PyObject *obj, Py_buffer *view, int flags) { + __Pyx_TypeName obj_type_name; + if (PyObject_CheckBuffer(obj)) return PyObject_GetBuffer(obj, view, flags); + if (__Pyx_TypeCheck(obj, __pyx_array_type)) return __pyx_array_getbuffer(obj, view, flags); + if (__Pyx_TypeCheck(obj, __pyx_memoryview_type)) return __pyx_memoryview_getbuffer(obj, view, flags); + obj_type_name = __Pyx_PyType_GetName(Py_TYPE(obj)); + PyErr_Format(PyExc_TypeError, + "'" __Pyx_FMT_TYPENAME "' does not have the buffer interface", + obj_type_name); + __Pyx_DECREF_TypeName(obj_type_name); + return -1; +} +static void __Pyx_ReleaseBuffer(Py_buffer *view) { + PyObject *obj = view->obj; + if (!obj) return; + if (PyObject_CheckBuffer(obj)) { + PyBuffer_Release(view); + return; + } + if ((0)) {} + view->obj = NULL; + Py_DECREF(obj); +} +#endif + + +/* MemviewSliceIsContig */ +static int +__pyx_memviewslice_is_contig(const __Pyx_memviewslice mvs, char order, int ndim) +{ + int i, index, step, start; + Py_ssize_t itemsize = mvs.memview->view.itemsize; + if (order == 'F') { + step = 1; + start = 0; + } else { + step = -1; + start = ndim - 1; + } + for (i = 0; i < ndim; i++) { + index = start + step * i; + if (mvs.suboffsets[index] >= 0 || mvs.strides[index] != itemsize) + return 0; + itemsize *= mvs.shape[index]; + } + return 1; +} + +/* OverlappingSlices */ +static void +__pyx_get_array_memory_extents(__Pyx_memviewslice *slice, + void **out_start, void **out_end, + int ndim, size_t itemsize) +{ + char *start, *end; + int i; + start = end = slice->data; + for (i = 0; i < ndim; i++) { + Py_ssize_t stride = slice->strides[i]; + Py_ssize_t extent = slice->shape[i]; + if (extent == 0) { + *out_start = *out_end = start; + return; + } else { + if (stride > 0) + end += stride * (extent - 1); + else + start += stride * (extent - 1); + } + } + *out_start = start; + *out_end = end + itemsize; +} +static int +__pyx_slices_overlap(__Pyx_memviewslice *slice1, + __Pyx_memviewslice *slice2, + int ndim, size_t itemsize) +{ + void *start1, *end1, *start2, *end2; + __pyx_get_array_memory_extents(slice1, &start1, &end1, ndim, itemsize); + __pyx_get_array_memory_extents(slice2, &start2, &end2, ndim, itemsize); + return (start1 < end2) && (start2 < end1); +} + +/* IsLittleEndian */ +static CYTHON_INLINE int __Pyx_Is_Little_Endian(void) +{ + union { + uint32_t u32; + uint8_t u8[4]; + } S; + S.u32 = 0x01020304; + return S.u8[0] == 4; +} + +/* BufferFormatCheck */ +static void __Pyx_BufFmt_Init(__Pyx_BufFmt_Context* ctx, + __Pyx_BufFmt_StackElem* stack, + __Pyx_TypeInfo* type) { + stack[0].field = &ctx->root; + stack[0].parent_offset = 0; + ctx->root.type = type; + ctx->root.name = "buffer dtype"; + ctx->root.offset = 0; + ctx->head = stack; + ctx->head->field = &ctx->root; + ctx->fmt_offset = 0; + ctx->head->parent_offset = 0; + ctx->new_packmode = '@'; + ctx->enc_packmode = '@'; + ctx->new_count = 1; + ctx->enc_count = 0; + ctx->enc_type = 0; + ctx->is_complex = 0; + ctx->is_valid_array = 0; + ctx->struct_alignment = 0; + while (type->typegroup == 'S') { + ++ctx->head; + ctx->head->field = type->fields; + ctx->head->parent_offset = 0; + type = type->fields->type; + } +} +static int __Pyx_BufFmt_ParseNumber(const char** ts) { + int count; + const char* t = *ts; + if (*t < '0' || *t > '9') { + return -1; + } else { + count = *t++ - '0'; + while (*t >= '0' && *t <= '9') { + count *= 10; + count += *t++ - '0'; + } + } + *ts = t; + return count; +} +static int __Pyx_BufFmt_ExpectNumber(const char **ts) { + int number = __Pyx_BufFmt_ParseNumber(ts); + if (number == -1) + PyErr_Format(PyExc_ValueError,\ + "Does not understand character buffer dtype format string ('%c')", **ts); + return number; +} +static void __Pyx_BufFmt_RaiseUnexpectedChar(char ch) { + PyErr_Format(PyExc_ValueError, + "Unexpected format string character: '%c'", ch); +} +static const char* __Pyx_BufFmt_DescribeTypeChar(char ch, int is_complex) { + switch (ch) { + case '?': return "'bool'"; + case 'c': return "'char'"; + case 'b': return "'signed char'"; + case 'B': return "'unsigned char'"; + case 'h': return "'short'"; + case 'H': return "'unsigned short'"; + case 'i': return "'int'"; + case 'I': return "'unsigned int'"; + case 'l': return "'long'"; + case 'L': return "'unsigned long'"; + case 'q': return "'long long'"; + case 'Q': return "'unsigned long long'"; + case 'f': return (is_complex ? "'complex float'" : "'float'"); + case 'd': return (is_complex ? "'complex double'" : "'double'"); + case 'g': return (is_complex ? "'complex long double'" : "'long double'"); + case 'T': return "a struct"; + case 'O': return "Python object"; + case 'P': return "a pointer"; + case 's': case 'p': return "a string"; + case 0: return "end"; + default: return "unparsable format string"; + } +} +static size_t __Pyx_BufFmt_TypeCharToStandardSize(char ch, int is_complex) { + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return 2; + case 'i': case 'I': case 'l': case 'L': return 4; + case 'q': case 'Q': return 8; + case 'f': return (is_complex ? 8 : 4); + case 'd': return (is_complex ? 16 : 8); + case 'g': { + PyErr_SetString(PyExc_ValueError, "Python does not define a standard format string size for long double ('g').."); + return 0; + } + case 'O': case 'P': return sizeof(void*); + default: + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } +} +static size_t __Pyx_BufFmt_TypeCharToNativeSize(char ch, int is_complex) { + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return sizeof(short); + case 'i': case 'I': return sizeof(int); + case 'l': case 'L': return sizeof(long); + #ifdef HAVE_LONG_LONG + case 'q': case 'Q': return sizeof(PY_LONG_LONG); + #endif + case 'f': return sizeof(float) * (is_complex ? 2 : 1); + case 'd': return sizeof(double) * (is_complex ? 2 : 1); + case 'g': return sizeof(long double) * (is_complex ? 2 : 1); + case 'O': case 'P': return sizeof(void*); + default: { + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } + } +} +typedef struct { char c; short x; } __Pyx_st_short; +typedef struct { char c; int x; } __Pyx_st_int; +typedef struct { char c; long x; } __Pyx_st_long; +typedef struct { char c; float x; } __Pyx_st_float; +typedef struct { char c; double x; } __Pyx_st_double; +typedef struct { char c; long double x; } __Pyx_st_longdouble; +typedef struct { char c; void *x; } __Pyx_st_void_p; +#ifdef HAVE_LONG_LONG +typedef struct { char c; PY_LONG_LONG x; } __Pyx_st_longlong; +#endif +static size_t __Pyx_BufFmt_TypeCharToAlignment(char ch, int is_complex) { + CYTHON_UNUSED_VAR(is_complex); + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return sizeof(__Pyx_st_short) - sizeof(short); + case 'i': case 'I': return sizeof(__Pyx_st_int) - sizeof(int); + case 'l': case 'L': return sizeof(__Pyx_st_long) - sizeof(long); +#ifdef HAVE_LONG_LONG + case 'q': case 'Q': return sizeof(__Pyx_st_longlong) - sizeof(PY_LONG_LONG); +#endif + case 'f': return sizeof(__Pyx_st_float) - sizeof(float); + case 'd': return sizeof(__Pyx_st_double) - sizeof(double); + case 'g': return sizeof(__Pyx_st_longdouble) - sizeof(long double); + case 'P': case 'O': return sizeof(__Pyx_st_void_p) - sizeof(void*); + default: + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } +} +/* These are for computing the padding at the end of the struct to align + on the first member of the struct. This will probably the same as above, + but we don't have any guarantees. + */ +typedef struct { short x; char c; } __Pyx_pad_short; +typedef struct { int x; char c; } __Pyx_pad_int; +typedef struct { long x; char c; } __Pyx_pad_long; +typedef struct { float x; char c; } __Pyx_pad_float; +typedef struct { double x; char c; } __Pyx_pad_double; +typedef struct { long double x; char c; } __Pyx_pad_longdouble; +typedef struct { void *x; char c; } __Pyx_pad_void_p; +#ifdef HAVE_LONG_LONG +typedef struct { PY_LONG_LONG x; char c; } __Pyx_pad_longlong; +#endif +static size_t __Pyx_BufFmt_TypeCharToPadding(char ch, int is_complex) { + CYTHON_UNUSED_VAR(is_complex); + switch (ch) { + case '?': case 'c': case 'b': case 'B': case 's': case 'p': return 1; + case 'h': case 'H': return sizeof(__Pyx_pad_short) - sizeof(short); + case 'i': case 'I': return sizeof(__Pyx_pad_int) - sizeof(int); + case 'l': case 'L': return sizeof(__Pyx_pad_long) - sizeof(long); +#ifdef HAVE_LONG_LONG + case 'q': case 'Q': return sizeof(__Pyx_pad_longlong) - sizeof(PY_LONG_LONG); +#endif + case 'f': return sizeof(__Pyx_pad_float) - sizeof(float); + case 'd': return sizeof(__Pyx_pad_double) - sizeof(double); + case 'g': return sizeof(__Pyx_pad_longdouble) - sizeof(long double); + case 'P': case 'O': return sizeof(__Pyx_pad_void_p) - sizeof(void*); + default: + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } +} +static char __Pyx_BufFmt_TypeCharToGroup(char ch, int is_complex) { + switch (ch) { + case 'c': + return 'H'; + case 'b': case 'h': case 'i': + case 'l': case 'q': case 's': case 'p': + return 'I'; + case '?': case 'B': case 'H': case 'I': case 'L': case 'Q': + return 'U'; + case 'f': case 'd': case 'g': + return (is_complex ? 'C' : 'R'); + case 'O': + return 'O'; + case 'P': + return 'P'; + default: { + __Pyx_BufFmt_RaiseUnexpectedChar(ch); + return 0; + } + } +} +static void __Pyx_BufFmt_RaiseExpected(__Pyx_BufFmt_Context* ctx) { + if (ctx->head == NULL || ctx->head->field == &ctx->root) { + const char* expected; + const char* quote; + if (ctx->head == NULL) { + expected = "end"; + quote = ""; + } else { + expected = ctx->head->field->type->name; + quote = "'"; + } + PyErr_Format(PyExc_ValueError, + "Buffer dtype mismatch, expected %s%s%s but got %s", + quote, expected, quote, + __Pyx_BufFmt_DescribeTypeChar(ctx->enc_type, ctx->is_complex)); + } else { + __Pyx_StructField* field = ctx->head->field; + __Pyx_StructField* parent = (ctx->head - 1)->field; + PyErr_Format(PyExc_ValueError, + "Buffer dtype mismatch, expected '%s' but got %s in '%s.%s'", + field->type->name, __Pyx_BufFmt_DescribeTypeChar(ctx->enc_type, ctx->is_complex), + parent->type->name, field->name); + } +} +static int __Pyx_BufFmt_ProcessTypeChunk(__Pyx_BufFmt_Context* ctx) { + char group; + size_t size, offset, arraysize = 1; + if (ctx->enc_type == 0) return 0; + if (ctx->head->field->type->arraysize[0]) { + int i, ndim = 0; + if (ctx->enc_type == 's' || ctx->enc_type == 'p') { + ctx->is_valid_array = ctx->head->field->type->ndim == 1; + ndim = 1; + if (ctx->enc_count != ctx->head->field->type->arraysize[0]) { + PyErr_Format(PyExc_ValueError, + "Expected a dimension of size %zu, got %zu", + ctx->head->field->type->arraysize[0], ctx->enc_count); + return -1; + } + } + if (!ctx->is_valid_array) { + PyErr_Format(PyExc_ValueError, "Expected %d dimensions, got %d", + ctx->head->field->type->ndim, ndim); + return -1; + } + for (i = 0; i < ctx->head->field->type->ndim; i++) { + arraysize *= ctx->head->field->type->arraysize[i]; + } + ctx->is_valid_array = 0; + ctx->enc_count = 1; + } + group = __Pyx_BufFmt_TypeCharToGroup(ctx->enc_type, ctx->is_complex); + do { + __Pyx_StructField* field = ctx->head->field; + __Pyx_TypeInfo* type = field->type; + if (ctx->enc_packmode == '@' || ctx->enc_packmode == '^') { + size = __Pyx_BufFmt_TypeCharToNativeSize(ctx->enc_type, ctx->is_complex); + } else { + size = __Pyx_BufFmt_TypeCharToStandardSize(ctx->enc_type, ctx->is_complex); + } + if (ctx->enc_packmode == '@') { + size_t align_at = __Pyx_BufFmt_TypeCharToAlignment(ctx->enc_type, ctx->is_complex); + size_t align_mod_offset; + if (align_at == 0) return -1; + align_mod_offset = ctx->fmt_offset % align_at; + if (align_mod_offset > 0) ctx->fmt_offset += align_at - align_mod_offset; + if (ctx->struct_alignment == 0) + ctx->struct_alignment = __Pyx_BufFmt_TypeCharToPadding(ctx->enc_type, + ctx->is_complex); + } + if (type->size != size || type->typegroup != group) { + if (type->typegroup == 'C' && type->fields != NULL) { + size_t parent_offset = ctx->head->parent_offset + field->offset; + ++ctx->head; + ctx->head->field = type->fields; + ctx->head->parent_offset = parent_offset; + continue; + } + if ((type->typegroup == 'H' || group == 'H') && type->size == size) { + } else { + __Pyx_BufFmt_RaiseExpected(ctx); + return -1; + } + } + offset = ctx->head->parent_offset + field->offset; + if (ctx->fmt_offset != offset) { + PyErr_Format(PyExc_ValueError, + "Buffer dtype mismatch; next field is at offset %" CYTHON_FORMAT_SSIZE_T "d but %" CYTHON_FORMAT_SSIZE_T "d expected", + (Py_ssize_t)ctx->fmt_offset, (Py_ssize_t)offset); + return -1; + } + ctx->fmt_offset += size; + if (arraysize) + ctx->fmt_offset += (arraysize - 1) * size; + --ctx->enc_count; + while (1) { + if (field == &ctx->root) { + ctx->head = NULL; + if (ctx->enc_count != 0) { + __Pyx_BufFmt_RaiseExpected(ctx); + return -1; + } + break; + } + ctx->head->field = ++field; + if (field->type == NULL) { + --ctx->head; + field = ctx->head->field; + continue; + } else if (field->type->typegroup == 'S') { + size_t parent_offset = ctx->head->parent_offset + field->offset; + if (field->type->fields->type == NULL) continue; + field = field->type->fields; + ++ctx->head; + ctx->head->field = field; + ctx->head->parent_offset = parent_offset; + break; + } else { + break; + } + } + } while (ctx->enc_count); + ctx->enc_type = 0; + ctx->is_complex = 0; + return 0; +} +static int +__pyx_buffmt_parse_array(__Pyx_BufFmt_Context* ctx, const char** tsp) +{ + const char *ts = *tsp; + int i = 0, number, ndim; + ++ts; + if (ctx->new_count != 1) { + PyErr_SetString(PyExc_ValueError, + "Cannot handle repeated arrays in format string"); + return -1; + } + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return -1; + ndim = ctx->head->field->type->ndim; + while (*ts && *ts != ')') { + switch (*ts) { + case ' ': case '\f': case '\r': case '\n': case '\t': case '\v': continue; + default: break; + } + number = __Pyx_BufFmt_ExpectNumber(&ts); + if (number == -1) return -1; + if (i < ndim && (size_t) number != ctx->head->field->type->arraysize[i]) { + PyErr_Format(PyExc_ValueError, + "Expected a dimension of size %zu, got %d", + ctx->head->field->type->arraysize[i], number); + return -1; + } + if (*ts != ',' && *ts != ')') { + PyErr_Format(PyExc_ValueError, + "Expected a comma in format string, got '%c'", *ts); + return -1; + } + if (*ts == ',') ts++; + i++; + } + if (i != ndim) { + PyErr_Format(PyExc_ValueError, "Expected %d dimension(s), got %d", + ctx->head->field->type->ndim, i); + return -1; + } + if (!*ts) { + PyErr_SetString(PyExc_ValueError, + "Unexpected end of format string, expected ')'"); + return -1; + } + ctx->is_valid_array = 1; + ctx->new_count = 1; + *tsp = ++ts; + return 0; +} +static const char* __Pyx_BufFmt_CheckString(__Pyx_BufFmt_Context* ctx, const char* ts) { + int got_Z = 0; + while (1) { + switch(*ts) { + case 0: + if (ctx->enc_type != 0 && ctx->head == NULL) { + __Pyx_BufFmt_RaiseExpected(ctx); + return NULL; + } + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + if (ctx->head != NULL) { + __Pyx_BufFmt_RaiseExpected(ctx); + return NULL; + } + return ts; + case ' ': + case '\r': + case '\n': + ++ts; + break; + case '<': + if (!__Pyx_Is_Little_Endian()) { + PyErr_SetString(PyExc_ValueError, "Little-endian buffer not supported on big-endian compiler"); + return NULL; + } + ctx->new_packmode = '='; + ++ts; + break; + case '>': + case '!': + if (__Pyx_Is_Little_Endian()) { + PyErr_SetString(PyExc_ValueError, "Big-endian buffer not supported on little-endian compiler"); + return NULL; + } + ctx->new_packmode = '='; + ++ts; + break; + case '=': + case '@': + case '^': + ctx->new_packmode = *ts++; + break; + case 'T': + { + const char* ts_after_sub; + size_t i, struct_count = ctx->new_count; + size_t struct_alignment = ctx->struct_alignment; + ctx->new_count = 1; + ++ts; + if (*ts != '{') { + PyErr_SetString(PyExc_ValueError, "Buffer acquisition: Expected '{' after 'T'"); + return NULL; + } + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->enc_type = 0; + ctx->enc_count = 0; + ctx->struct_alignment = 0; + ++ts; + ts_after_sub = ts; + for (i = 0; i != struct_count; ++i) { + ts_after_sub = __Pyx_BufFmt_CheckString(ctx, ts); + if (!ts_after_sub) return NULL; + } + ts = ts_after_sub; + if (struct_alignment) ctx->struct_alignment = struct_alignment; + } + break; + case '}': + { + size_t alignment = ctx->struct_alignment; + ++ts; + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->enc_type = 0; + if (alignment && ctx->fmt_offset % alignment) { + ctx->fmt_offset += alignment - (ctx->fmt_offset % alignment); + } + } + return ts; + case 'x': + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->fmt_offset += ctx->new_count; + ctx->new_count = 1; + ctx->enc_count = 0; + ctx->enc_type = 0; + ctx->enc_packmode = ctx->new_packmode; + ++ts; + break; + case 'Z': + got_Z = 1; + ++ts; + if (*ts != 'f' && *ts != 'd' && *ts != 'g') { + __Pyx_BufFmt_RaiseUnexpectedChar('Z'); + return NULL; + } + CYTHON_FALLTHROUGH; + case '?': case 'c': case 'b': case 'B': case 'h': case 'H': case 'i': case 'I': + case 'l': case 'L': case 'q': case 'Q': + case 'f': case 'd': case 'g': + case 'O': case 'p': + if ((ctx->enc_type == *ts) && (got_Z == ctx->is_complex) && + (ctx->enc_packmode == ctx->new_packmode) && (!ctx->is_valid_array)) { + ctx->enc_count += ctx->new_count; + ctx->new_count = 1; + got_Z = 0; + ++ts; + break; + } + CYTHON_FALLTHROUGH; + case 's': + if (__Pyx_BufFmt_ProcessTypeChunk(ctx) == -1) return NULL; + ctx->enc_count = ctx->new_count; + ctx->enc_packmode = ctx->new_packmode; + ctx->enc_type = *ts; + ctx->is_complex = got_Z; + ++ts; + ctx->new_count = 1; + got_Z = 0; + break; + case ':': + ++ts; + while(*ts != ':') ++ts; + ++ts; + break; + case '(': + if (__pyx_buffmt_parse_array(ctx, &ts) < 0) return NULL; + break; + default: + { + int number = __Pyx_BufFmt_ExpectNumber(&ts); + if (number == -1) return NULL; + ctx->new_count = (size_t)number; + } + } + } +} + +/* TypeInfoCompare */ + static int +__pyx_typeinfo_cmp(__Pyx_TypeInfo *a, __Pyx_TypeInfo *b) +{ + int i; + if (!a || !b) + return 0; + if (a == b) + return 1; + if (a->size != b->size || a->typegroup != b->typegroup || + a->is_unsigned != b->is_unsigned || a->ndim != b->ndim) { + if (a->typegroup == 'H' || b->typegroup == 'H') { + return a->size == b->size; + } else { + return 0; + } + } + if (a->ndim) { + for (i = 0; i < a->ndim; i++) + if (a->arraysize[i] != b->arraysize[i]) + return 0; + } + if (a->typegroup == 'S') { + if (a->flags != b->flags) + return 0; + if (a->fields || b->fields) { + if (!(a->fields && b->fields)) + return 0; + for (i = 0; a->fields[i].type && b->fields[i].type; i++) { + __Pyx_StructField *field_a = a->fields + i; + __Pyx_StructField *field_b = b->fields + i; + if (field_a->offset != field_b->offset || + !__pyx_typeinfo_cmp(field_a->type, field_b->type)) + return 0; + } + return !a->fields[i].type && !b->fields[i].type; + } + } + return 1; +} + +/* MemviewSliceValidateAndInit */ + static int +__pyx_check_strides(Py_buffer *buf, int dim, int ndim, int spec) +{ + if (buf->shape[dim] <= 1) + return 1; + if (buf->strides) { + if (spec & __Pyx_MEMVIEW_CONTIG) { + if (spec & (__Pyx_MEMVIEW_PTR|__Pyx_MEMVIEW_FULL)) { + if (unlikely(buf->strides[dim] != sizeof(void *))) { + PyErr_Format(PyExc_ValueError, + "Buffer is not indirectly contiguous " + "in dimension %d.", dim); + goto fail; + } + } else if (unlikely(buf->strides[dim] != buf->itemsize)) { + PyErr_SetString(PyExc_ValueError, + "Buffer and memoryview are not contiguous " + "in the same dimension."); + goto fail; + } + } + if (spec & __Pyx_MEMVIEW_FOLLOW) { + Py_ssize_t stride = buf->strides[dim]; + if (stride < 0) + stride = -stride; + if (unlikely(stride < buf->itemsize)) { + PyErr_SetString(PyExc_ValueError, + "Buffer and memoryview are not contiguous " + "in the same dimension."); + goto fail; + } + } + } else { + if (unlikely(spec & __Pyx_MEMVIEW_CONTIG && dim != ndim - 1)) { + PyErr_Format(PyExc_ValueError, + "C-contiguous buffer is not contiguous in " + "dimension %d", dim); + goto fail; + } else if (unlikely(spec & (__Pyx_MEMVIEW_PTR))) { + PyErr_Format(PyExc_ValueError, + "C-contiguous buffer is not indirect in " + "dimension %d", dim); + goto fail; + } else if (unlikely(buf->suboffsets)) { + PyErr_SetString(PyExc_ValueError, + "Buffer exposes suboffsets but no strides"); + goto fail; + } + } + return 1; +fail: + return 0; +} +static int +__pyx_check_suboffsets(Py_buffer *buf, int dim, int ndim, int spec) +{ + CYTHON_UNUSED_VAR(ndim); + if (spec & __Pyx_MEMVIEW_DIRECT) { + if (unlikely(buf->suboffsets && buf->suboffsets[dim] >= 0)) { + PyErr_Format(PyExc_ValueError, + "Buffer not compatible with direct access " + "in dimension %d.", dim); + goto fail; + } + } + if (spec & __Pyx_MEMVIEW_PTR) { + if (unlikely(!buf->suboffsets || (buf->suboffsets[dim] < 0))) { + PyErr_Format(PyExc_ValueError, + "Buffer is not indirectly accessible " + "in dimension %d.", dim); + goto fail; + } + } + return 1; +fail: + return 0; +} +static int +__pyx_verify_contig(Py_buffer *buf, int ndim, int c_or_f_flag) +{ + int i; + if (c_or_f_flag & __Pyx_IS_F_CONTIG) { + Py_ssize_t stride = 1; + for (i = 0; i < ndim; i++) { + if (unlikely(stride * buf->itemsize != buf->strides[i] && buf->shape[i] > 1)) { + PyErr_SetString(PyExc_ValueError, + "Buffer not fortran contiguous."); + goto fail; + } + stride = stride * buf->shape[i]; + } + } else if (c_or_f_flag & __Pyx_IS_C_CONTIG) { + Py_ssize_t stride = 1; + for (i = ndim - 1; i >- 1; i--) { + if (unlikely(stride * buf->itemsize != buf->strides[i] && buf->shape[i] > 1)) { + PyErr_SetString(PyExc_ValueError, + "Buffer not C contiguous."); + goto fail; + } + stride = stride * buf->shape[i]; + } + } + return 1; +fail: + return 0; +} +static int __Pyx_ValidateAndInit_memviewslice( + int *axes_specs, + int c_or_f_flag, + int buf_flags, + int ndim, + __Pyx_TypeInfo *dtype, + __Pyx_BufFmt_StackElem stack[], + __Pyx_memviewslice *memviewslice, + PyObject *original_obj) +{ + struct __pyx_memoryview_obj *memview, *new_memview; + __Pyx_RefNannyDeclarations + Py_buffer *buf; + int i, spec = 0, retval = -1; + __Pyx_BufFmt_Context ctx; + int from_memoryview = __pyx_memoryview_check(original_obj); + __Pyx_RefNannySetupContext("ValidateAndInit_memviewslice", 0); + if (from_memoryview && __pyx_typeinfo_cmp(dtype, ((struct __pyx_memoryview_obj *) + original_obj)->typeinfo)) { + memview = (struct __pyx_memoryview_obj *) original_obj; + new_memview = NULL; + } else { + memview = (struct __pyx_memoryview_obj *) __pyx_memoryview_new( + original_obj, buf_flags, 0, dtype); + new_memview = memview; + if (unlikely(!memview)) + goto fail; + } + buf = &memview->view; + if (unlikely(buf->ndim != ndim)) { + PyErr_Format(PyExc_ValueError, + "Buffer has wrong number of dimensions (expected %d, got %d)", + ndim, buf->ndim); + goto fail; + } + if (new_memview) { + __Pyx_BufFmt_Init(&ctx, stack, dtype); + if (unlikely(!__Pyx_BufFmt_CheckString(&ctx, buf->format))) goto fail; + } + if (unlikely((unsigned) buf->itemsize != dtype->size)) { + PyErr_Format(PyExc_ValueError, + "Item size of buffer (%" CYTHON_FORMAT_SSIZE_T "u byte%s) " + "does not match size of '%s' (%" CYTHON_FORMAT_SSIZE_T "u byte%s)", + buf->itemsize, + (buf->itemsize > 1) ? "s" : "", + dtype->name, + dtype->size, + (dtype->size > 1) ? "s" : ""); + goto fail; + } + if (buf->len > 0) { + for (i = 0; i < ndim; i++) { + spec = axes_specs[i]; + if (unlikely(!__pyx_check_strides(buf, i, ndim, spec))) + goto fail; + if (unlikely(!__pyx_check_suboffsets(buf, i, ndim, spec))) + goto fail; + } + if (unlikely(buf->strides && !__pyx_verify_contig(buf, ndim, c_or_f_flag))) + goto fail; + } + if (unlikely(__Pyx_init_memviewslice(memview, ndim, memviewslice, + new_memview != NULL) == -1)) { + goto fail; + } + retval = 0; + goto no_fail; +fail: + Py_XDECREF(new_memview); + retval = -1; +no_fail: + __Pyx_RefNannyFinishContext(); + return retval; +} + +/* ObjectToMemviewSlice */ + static CYTHON_INLINE __Pyx_memviewslice __Pyx_PyObject_to_MemoryviewSlice_ds_float(PyObject *obj, int writable_flag) { + __Pyx_memviewslice result = { 0, 0, { 0 }, { 0 }, { 0 } }; + __Pyx_BufFmt_StackElem stack[1]; + int axes_specs[] = { (__Pyx_MEMVIEW_DIRECT | __Pyx_MEMVIEW_STRIDED) }; + int retcode; + if (obj == Py_None) { + result.memview = (struct __pyx_memoryview_obj *) Py_None; + return result; + } + retcode = __Pyx_ValidateAndInit_memviewslice(axes_specs, 0, + PyBUF_RECORDS_RO | writable_flag, 1, + &__Pyx_TypeInfo_float, stack, + &result, obj); + if (unlikely(retcode == -1)) + goto __pyx_fail; + return result; +__pyx_fail: + result.memview = NULL; + result.data = NULL; + return result; +} + +/* CIntFromPyVerify */ + #define __PYX_VERIFY_RETURN_INT(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 0) +#define __PYX_VERIFY_RETURN_INT_EXC(target_type, func_type, func_value)\ + __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, 1) +#define __PYX__VERIFY_RETURN_INT(target_type, func_type, func_value, exc)\ + {\ + func_type value = func_value;\ + if (sizeof(target_type) < sizeof(func_type)) {\ + if (unlikely(value != (func_type) (target_type) value)) {\ + func_type zero = 0;\ + if (exc && unlikely(value == (func_type)-1 && PyErr_Occurred()))\ + return (target_type) -1;\ + if (is_unsigned && unlikely(value < zero))\ + goto raise_neg_overflow;\ + else\ + goto raise_overflow;\ + }\ + }\ + return (target_type) value;\ + } + +/* MemviewDtypeToObject */ + static CYTHON_INLINE PyObject *__pyx_memview_get_float(const char *itemp) { + return (PyObject *) PyFloat_FromDouble(*(float *) itemp); +} +static CYTHON_INLINE int __pyx_memview_set_float(const char *itemp, PyObject *obj) { + float value = __pyx_PyFloat_AsFloat(obj); + if (unlikely((value == (float)-1) && PyErr_Occurred())) + return 0; + *(float *) itemp = value; + return 1; +} + +/* MemviewSliceCopyTemplate */ + static __Pyx_memviewslice +__pyx_memoryview_copy_new_contig(const __Pyx_memviewslice *from_mvs, + const char *mode, int ndim, + size_t sizeof_dtype, int contig_flag, + int dtype_is_object) +{ + __Pyx_RefNannyDeclarations + int i; + __Pyx_memviewslice new_mvs = { 0, 0, { 0 }, { 0 }, { 0 } }; + struct __pyx_memoryview_obj *from_memview = from_mvs->memview; + Py_buffer *buf = &from_memview->view; + PyObject *shape_tuple = NULL; + PyObject *temp_int = NULL; + struct __pyx_array_obj *array_obj = NULL; + struct __pyx_memoryview_obj *memview_obj = NULL; + __Pyx_RefNannySetupContext("__pyx_memoryview_copy_new_contig", 0); + for (i = 0; i < ndim; i++) { + if (unlikely(from_mvs->suboffsets[i] >= 0)) { + PyErr_Format(PyExc_ValueError, "Cannot copy memoryview slice with " + "indirect dimensions (axis %d)", i); + goto fail; + } + } + shape_tuple = PyTuple_New(ndim); + if (unlikely(!shape_tuple)) { + goto fail; + } + __Pyx_GOTREF(shape_tuple); + for(i = 0; i < ndim; i++) { + temp_int = PyInt_FromSsize_t(from_mvs->shape[i]); + if(unlikely(!temp_int)) { + goto fail; + } else { + PyTuple_SET_ITEM(shape_tuple, i, temp_int); + temp_int = NULL; + } + } + array_obj = __pyx_array_new(shape_tuple, sizeof_dtype, buf->format, (char *) mode, NULL); + if (unlikely(!array_obj)) { + goto fail; + } + __Pyx_GOTREF(array_obj); + memview_obj = (struct __pyx_memoryview_obj *) __pyx_memoryview_new( + (PyObject *) array_obj, contig_flag, + dtype_is_object, + from_mvs->memview->typeinfo); + if (unlikely(!memview_obj)) + goto fail; + if (unlikely(__Pyx_init_memviewslice(memview_obj, ndim, &new_mvs, 1) < 0)) + goto fail; + if (unlikely(__pyx_memoryview_copy_contents(*from_mvs, new_mvs, ndim, ndim, + dtype_is_object) < 0)) + goto fail; + goto no_fail; +fail: + __Pyx_XDECREF(new_mvs.memview); + new_mvs.memview = NULL; + new_mvs.data = NULL; +no_fail: + __Pyx_XDECREF(shape_tuple); + __Pyx_XDECREF(temp_int); + __Pyx_XDECREF(array_obj); + __Pyx_RefNannyFinishContext(); + return new_mvs; +} + +/* MemviewSliceInit */ + static int +__Pyx_init_memviewslice(struct __pyx_memoryview_obj *memview, + int ndim, + __Pyx_memviewslice *memviewslice, + int memview_is_new_reference) +{ + __Pyx_RefNannyDeclarations + int i, retval=-1; + Py_buffer *buf = &memview->view; + __Pyx_RefNannySetupContext("init_memviewslice", 0); + if (unlikely(memviewslice->memview || memviewslice->data)) { + PyErr_SetString(PyExc_ValueError, + "memviewslice is already initialized!"); + goto fail; + } + if (buf->strides) { + for (i = 0; i < ndim; i++) { + memviewslice->strides[i] = buf->strides[i]; + } + } else { + Py_ssize_t stride = buf->itemsize; + for (i = ndim - 1; i >= 0; i--) { + memviewslice->strides[i] = stride; + stride *= buf->shape[i]; + } + } + for (i = 0; i < ndim; i++) { + memviewslice->shape[i] = buf->shape[i]; + if (buf->suboffsets) { + memviewslice->suboffsets[i] = buf->suboffsets[i]; + } else { + memviewslice->suboffsets[i] = -1; + } + } + memviewslice->memview = memview; + memviewslice->data = (char *)buf->buf; + if (__pyx_add_acquisition_count(memview) == 0 && !memview_is_new_reference) { + Py_INCREF(memview); + } + retval = 0; + goto no_fail; +fail: + memviewslice->memview = 0; + memviewslice->data = 0; + retval = -1; +no_fail: + __Pyx_RefNannyFinishContext(); + return retval; +} +#ifndef Py_NO_RETURN +#define Py_NO_RETURN +#endif +static void __pyx_fatalerror(const char *fmt, ...) Py_NO_RETURN { + va_list vargs; + char msg[200]; +#if PY_VERSION_HEX >= 0x030A0000 || defined(HAVE_STDARG_PROTOTYPES) + va_start(vargs, fmt); +#else + va_start(vargs); +#endif + vsnprintf(msg, 200, fmt, vargs); + va_end(vargs); + Py_FatalError(msg); +} +static CYTHON_INLINE int +__pyx_add_acquisition_count_locked(__pyx_atomic_int_type *acquisition_count, + PyThread_type_lock lock) +{ + int result; + PyThread_acquire_lock(lock, 1); + result = (*acquisition_count)++; + PyThread_release_lock(lock); + return result; +} +static CYTHON_INLINE int +__pyx_sub_acquisition_count_locked(__pyx_atomic_int_type *acquisition_count, + PyThread_type_lock lock) +{ + int result; + PyThread_acquire_lock(lock, 1); + result = (*acquisition_count)--; + PyThread_release_lock(lock); + return result; +} +static CYTHON_INLINE void +__Pyx_INC_MEMVIEW(__Pyx_memviewslice *memslice, int have_gil, int lineno) +{ + __pyx_nonatomic_int_type old_acquisition_count; + struct __pyx_memoryview_obj *memview = memslice->memview; + if (unlikely(!memview || (PyObject *) memview == Py_None)) { + return; + } + old_acquisition_count = __pyx_add_acquisition_count(memview); + if (unlikely(old_acquisition_count <= 0)) { + if (likely(old_acquisition_count == 0)) { + if (have_gil) { + Py_INCREF((PyObject *) memview); + } else { + PyGILState_STATE _gilstate = PyGILState_Ensure(); + Py_INCREF((PyObject *) memview); + PyGILState_Release(_gilstate); + } + } else { + __pyx_fatalerror("Acquisition count is %d (line %d)", + old_acquisition_count+1, lineno); + } + } +} +static CYTHON_INLINE void __Pyx_XCLEAR_MEMVIEW(__Pyx_memviewslice *memslice, + int have_gil, int lineno) { + __pyx_nonatomic_int_type old_acquisition_count; + struct __pyx_memoryview_obj *memview = memslice->memview; + if (unlikely(!memview || (PyObject *) memview == Py_None)) { + memslice->memview = NULL; + return; + } + old_acquisition_count = __pyx_sub_acquisition_count(memview); + memslice->data = NULL; + if (likely(old_acquisition_count > 1)) { + memslice->memview = NULL; + } else if (likely(old_acquisition_count == 1)) { + if (have_gil) { + Py_CLEAR(memslice->memview); + } else { + PyGILState_STATE _gilstate = PyGILState_Ensure(); + Py_CLEAR(memslice->memview); + PyGILState_Release(_gilstate); + } + } else { + __pyx_fatalerror("Acquisition count is %d (line %d)", + old_acquisition_count-1, lineno); + } +} + +/* CIntFromPy */ + static CYTHON_INLINE int __Pyx_PyInt_As_int(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(int) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(int, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (int) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 2 * PyLong_SHIFT)) { + return (int) (((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 3 * PyLong_SHIFT)) { + return (int) (((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) >= 4 * PyLong_SHIFT)) { + return (int) (((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(int) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(int, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(int) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(int) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + return (int) ((((((int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(int) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(int) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + return (int) ((((((((int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(int) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) (((int)-1)*(((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(int) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(int, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(int) - 1 > 4 * PyLong_SHIFT)) { + return (int) ((((((((((int)digits[3]) << PyLong_SHIFT) | (int)digits[2]) << PyLong_SHIFT) | (int)digits[1]) << PyLong_SHIFT) | (int)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(int) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(int, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(int) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(int, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + int val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (int) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (int) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (int) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (int) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (int) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(int) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(int) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((int) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((int) 1) << (sizeof(int) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (int) -1; + } + } else { + int val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (int) -1; + val = __Pyx_PyInt_As_int(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to int"); + return (int) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to int"); + return (int) -1; +} + +/* CIntFromPy */ + static CYTHON_INLINE long __Pyx_PyInt_As_long(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(long) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(long, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (long) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 2 * PyLong_SHIFT)) { + return (long) (((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 3 * PyLong_SHIFT)) { + return (long) (((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) >= 4 * PyLong_SHIFT)) { + return (long) (((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(long) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(long, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(long) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(long) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + return (long) ((((((long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(long) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(long) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + return (long) ((((((((long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(long) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) (((long)-1)*(((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(long) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(long, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(long) - 1 > 4 * PyLong_SHIFT)) { + return (long) ((((((((((long)digits[3]) << PyLong_SHIFT) | (long)digits[2]) << PyLong_SHIFT) | (long)digits[1]) << PyLong_SHIFT) | (long)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(long) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(long, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(long) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(long, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + long val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (long) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (long) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (long) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (long) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (long) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(long) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(long) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((long) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((long) 1) << (sizeof(long) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (long) -1; + } + } else { + long val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (long) -1; + val = __Pyx_PyInt_As_long(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to long"); + return (long) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to long"); + return (long) -1; +} + +/* CIntToPy */ + static CYTHON_INLINE PyObject* __Pyx_PyInt_From_int(int value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const int neg_one = (int) -1, const_zero = (int) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(int) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(int) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(int) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(int) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(int) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; +#if !CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030d0000 + return _PyLong_FromByteArray(bytes, sizeof(int), + little, !is_unsigned); +#else + PyObject *from_bytes, *result = NULL; + PyObject *py_bytes = NULL, *arg_tuple = NULL, *kwds = NULL, *order_str = NULL; + from_bytes = PyObject_GetAttrString((PyObject*)&PyLong_Type, "from_bytes"); + if (!from_bytes) return NULL; + py_bytes = PyBytes_FromStringAndSize((char*)bytes, sizeof(int)); + if (!py_bytes) goto limited_bad; + order_str = PyUnicode_FromString(little ? "little" : "big"); + if (!order_str) goto limited_bad; + arg_tuple = PyTuple_Pack(2, py_bytes, order_str); + if (!arg_tuple) goto limited_bad; + if (!is_unsigned) { + kwds = PyDict_New(); + if (!kwds) goto limited_bad; + if (PyDict_SetItemString(kwds, "signed", __Pyx_NewRef(Py_True))) goto limited_bad; + } + result = PyObject_Call(from_bytes, arg_tuple, kwds); + limited_bad: + Py_XDECREF(kwds); + Py_XDECREF(arg_tuple); + Py_XDECREF(order_str); + Py_XDECREF(py_bytes); + Py_XDECREF(from_bytes); + return result; +#endif + } +} + +/* CIntToPy */ + static CYTHON_INLINE PyObject* __Pyx_PyInt_From_long(long value) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const long neg_one = (long) -1, const_zero = (long) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; + if (is_unsigned) { + if (sizeof(long) < sizeof(long)) { + return PyInt_FromLong((long) value); + } else if (sizeof(long) <= sizeof(unsigned long)) { + return PyLong_FromUnsignedLong((unsigned long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(unsigned PY_LONG_LONG)) { + return PyLong_FromUnsignedLongLong((unsigned PY_LONG_LONG) value); +#endif + } + } else { + if (sizeof(long) <= sizeof(long)) { + return PyInt_FromLong((long) value); +#ifdef HAVE_LONG_LONG + } else if (sizeof(long) <= sizeof(PY_LONG_LONG)) { + return PyLong_FromLongLong((PY_LONG_LONG) value); +#endif + } + } + { + int one = 1; int little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&value; +#if !CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030d0000 + return _PyLong_FromByteArray(bytes, sizeof(long), + little, !is_unsigned); +#else + PyObject *from_bytes, *result = NULL; + PyObject *py_bytes = NULL, *arg_tuple = NULL, *kwds = NULL, *order_str = NULL; + from_bytes = PyObject_GetAttrString((PyObject*)&PyLong_Type, "from_bytes"); + if (!from_bytes) return NULL; + py_bytes = PyBytes_FromStringAndSize((char*)bytes, sizeof(long)); + if (!py_bytes) goto limited_bad; + order_str = PyUnicode_FromString(little ? "little" : "big"); + if (!order_str) goto limited_bad; + arg_tuple = PyTuple_Pack(2, py_bytes, order_str); + if (!arg_tuple) goto limited_bad; + if (!is_unsigned) { + kwds = PyDict_New(); + if (!kwds) goto limited_bad; + if (PyDict_SetItemString(kwds, "signed", __Pyx_NewRef(Py_True))) goto limited_bad; + } + result = PyObject_Call(from_bytes, arg_tuple, kwds); + limited_bad: + Py_XDECREF(kwds); + Py_XDECREF(arg_tuple); + Py_XDECREF(order_str); + Py_XDECREF(py_bytes); + Py_XDECREF(from_bytes); + return result; +#endif + } +} + +/* CIntFromPy */ + static CYTHON_INLINE char __Pyx_PyInt_As_char(PyObject *x) { +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wconversion" +#endif + const char neg_one = (char) -1, const_zero = (char) 0; +#ifdef __Pyx_HAS_GCC_DIAGNOSTIC +#pragma GCC diagnostic pop +#endif + const int is_unsigned = neg_one > const_zero; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x))) { + if ((sizeof(char) < sizeof(long))) { + __PYX_VERIFY_RETURN_INT(char, long, PyInt_AS_LONG(x)) + } else { + long val = PyInt_AS_LONG(x); + if (is_unsigned && unlikely(val < 0)) { + goto raise_neg_overflow; + } + return (char) val; + } + } else +#endif + if (likely(PyLong_Check(x))) { + if (is_unsigned) { +#if CYTHON_USE_PYLONG_INTERNALS + if (unlikely(__Pyx_PyLong_IsNeg(x))) { + goto raise_neg_overflow; + } else if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(char, __Pyx_compact_upylong, __Pyx_PyLong_CompactValueUnsigned(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_DigitCount(x)) { + case 2: + if ((8 * sizeof(char) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) >= 2 * PyLong_SHIFT)) { + return (char) (((((char)digits[1]) << PyLong_SHIFT) | (char)digits[0])); + } + } + break; + case 3: + if ((8 * sizeof(char) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) >= 3 * PyLong_SHIFT)) { + return (char) (((((((char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0])); + } + } + break; + case 4: + if ((8 * sizeof(char) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) >= 4 * PyLong_SHIFT)) { + return (char) (((((((((char)digits[3]) << PyLong_SHIFT) | (char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0])); + } + } + break; + } + } +#endif +#if CYTHON_COMPILING_IN_CPYTHON && PY_VERSION_HEX < 0x030C00A7 + if (unlikely(Py_SIZE(x) < 0)) { + goto raise_neg_overflow; + } +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (char) -1; + if (unlikely(result == 1)) + goto raise_neg_overflow; + } +#endif + if ((sizeof(char) <= sizeof(unsigned long))) { + __PYX_VERIFY_RETURN_INT_EXC(char, unsigned long, PyLong_AsUnsignedLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(char) <= sizeof(unsigned PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(char, unsigned PY_LONG_LONG, PyLong_AsUnsignedLongLong(x)) +#endif + } + } else { +#if CYTHON_USE_PYLONG_INTERNALS + if (__Pyx_PyLong_IsCompact(x)) { + __PYX_VERIFY_RETURN_INT(char, __Pyx_compact_pylong, __Pyx_PyLong_CompactValue(x)) + } else { + const digit* digits = __Pyx_PyLong_Digits(x); + assert(__Pyx_PyLong_DigitCount(x) > 1); + switch (__Pyx_PyLong_SignedDigitCount(x)) { + case -2: + if ((8 * sizeof(char) - 1 > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, long, -(long) (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 2 * PyLong_SHIFT)) { + return (char) (((char)-1)*(((((char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case 2: + if ((8 * sizeof(char) > 1 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 2 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 2 * PyLong_SHIFT)) { + return (char) ((((((char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case -3: + if ((8 * sizeof(char) - 1 > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, long, -(long) (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 3 * PyLong_SHIFT)) { + return (char) (((char)-1)*(((((((char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case 3: + if ((8 * sizeof(char) > 2 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 3 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 3 * PyLong_SHIFT)) { + return (char) ((((((((char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case -4: + if ((8 * sizeof(char) - 1 > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, long, -(long) (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 4 * PyLong_SHIFT)) { + return (char) (((char)-1)*(((((((((char)digits[3]) << PyLong_SHIFT) | (char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + case 4: + if ((8 * sizeof(char) > 3 * PyLong_SHIFT)) { + if ((8 * sizeof(unsigned long) > 4 * PyLong_SHIFT)) { + __PYX_VERIFY_RETURN_INT(char, unsigned long, (((((((((unsigned long)digits[3]) << PyLong_SHIFT) | (unsigned long)digits[2]) << PyLong_SHIFT) | (unsigned long)digits[1]) << PyLong_SHIFT) | (unsigned long)digits[0]))) + } else if ((8 * sizeof(char) - 1 > 4 * PyLong_SHIFT)) { + return (char) ((((((((((char)digits[3]) << PyLong_SHIFT) | (char)digits[2]) << PyLong_SHIFT) | (char)digits[1]) << PyLong_SHIFT) | (char)digits[0]))); + } + } + break; + } + } +#endif + if ((sizeof(char) <= sizeof(long))) { + __PYX_VERIFY_RETURN_INT_EXC(char, long, PyLong_AsLong(x)) +#ifdef HAVE_LONG_LONG + } else if ((sizeof(char) <= sizeof(PY_LONG_LONG))) { + __PYX_VERIFY_RETURN_INT_EXC(char, PY_LONG_LONG, PyLong_AsLongLong(x)) +#endif + } + } + { + char val; + PyObject *v = __Pyx_PyNumber_IntOrLong(x); +#if PY_MAJOR_VERSION < 3 + if (likely(v) && !PyLong_Check(v)) { + PyObject *tmp = v; + v = PyNumber_Long(tmp); + Py_DECREF(tmp); + } +#endif + if (likely(v)) { + int ret = -1; +#if PY_VERSION_HEX < 0x030d0000 && !(CYTHON_COMPILING_IN_PYPY || CYTHON_COMPILING_IN_LIMITED_API) || defined(_PyLong_AsByteArray) + int one = 1; int is_little = (int)*(unsigned char *)&one; + unsigned char *bytes = (unsigned char *)&val; + ret = _PyLong_AsByteArray((PyLongObject *)v, + bytes, sizeof(val), + is_little, !is_unsigned); +#else + PyObject *stepval = NULL, *mask = NULL, *shift = NULL; + int bits, remaining_bits, is_negative = 0; + long idigit; + int chunk_size = (sizeof(long) < 8) ? 30 : 62; + if (unlikely(!PyLong_CheckExact(v))) { + PyObject *tmp = v; + v = PyNumber_Long(v); + assert(PyLong_CheckExact(v)); + Py_DECREF(tmp); + if (unlikely(!v)) return (char) -1; + } +#if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(x) == 0) + return (char) 0; + is_negative = Py_SIZE(x) < 0; +#else + { + int result = PyObject_RichCompareBool(x, Py_False, Py_LT); + if (unlikely(result < 0)) + return (char) -1; + is_negative = result == 1; + } +#endif + if (is_unsigned && unlikely(is_negative)) { + goto raise_neg_overflow; + } else if (is_negative) { + stepval = PyNumber_Invert(v); + if (unlikely(!stepval)) + return (char) -1; + } else { + stepval = __Pyx_NewRef(v); + } + val = (char) 0; + mask = PyLong_FromLong((1L << chunk_size) - 1); if (unlikely(!mask)) goto done; + shift = PyLong_FromLong(chunk_size); if (unlikely(!shift)) goto done; + for (bits = 0; bits < (int) sizeof(char) * 8 - chunk_size; bits += chunk_size) { + PyObject *tmp, *digit; + digit = PyNumber_And(stepval, mask); + if (unlikely(!digit)) goto done; + idigit = PyLong_AsLong(digit); + Py_DECREF(digit); + if (unlikely(idigit < 0)) goto done; + tmp = PyNumber_Rshift(stepval, shift); + if (unlikely(!tmp)) goto done; + Py_DECREF(stepval); stepval = tmp; + val |= ((char) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + if (Py_SIZE(stepval) == 0) + goto unpacking_done; + #endif + } + idigit = PyLong_AsLong(stepval); + if (unlikely(idigit < 0)) goto done; + remaining_bits = ((int) sizeof(char) * 8) - bits - (is_unsigned ? 0 : 1); + if (unlikely(idigit >= (1L << remaining_bits))) + goto raise_overflow; + val |= ((char) idigit) << bits; + #if CYTHON_COMPILING_IN_LIMITED_API && PY_VERSION_HEX < 0x030B0000 + unpacking_done: + #endif + if (!is_unsigned) { + if (unlikely(val & (((char) 1) << (sizeof(char) * 8 - 1)))) + goto raise_overflow; + if (is_negative) + val = ~val; + } + ret = 0; + done: + Py_XDECREF(shift); + Py_XDECREF(mask); + Py_XDECREF(stepval); +#endif + Py_DECREF(v); + if (likely(!ret)) + return val; + } + return (char) -1; + } + } else { + char val; + PyObject *tmp = __Pyx_PyNumber_IntOrLong(x); + if (!tmp) return (char) -1; + val = __Pyx_PyInt_As_char(tmp); + Py_DECREF(tmp); + return val; + } +raise_overflow: + PyErr_SetString(PyExc_OverflowError, + "value too large to convert to char"); + return (char) -1; +raise_neg_overflow: + PyErr_SetString(PyExc_OverflowError, + "can't convert negative value to char"); + return (char) -1; +} + +/* FormatTypeName */ + #if CYTHON_COMPILING_IN_LIMITED_API +static __Pyx_TypeName +__Pyx_PyType_GetName(PyTypeObject* tp) +{ + PyObject *name = __Pyx_PyObject_GetAttrStr((PyObject *)tp, + __pyx_n_s_name_2); + if (unlikely(name == NULL) || unlikely(!PyUnicode_Check(name))) { + PyErr_Clear(); + Py_XDECREF(name); + name = __Pyx_NewRef(__pyx_n_s__24); + } + return name; +} +#endif + +/* CheckBinaryVersion */ + static unsigned long __Pyx_get_runtime_version(void) { +#if __PYX_LIMITED_VERSION_HEX >= 0x030B00A4 + return Py_Version & ~0xFFUL; +#else + const char* rt_version = Py_GetVersion(); + unsigned long version = 0; + unsigned long factor = 0x01000000UL; + unsigned int digit = 0; + int i = 0; + while (factor) { + while ('0' <= rt_version[i] && rt_version[i] <= '9') { + digit = digit * 10 + (unsigned int) (rt_version[i] - '0'); + ++i; + } + version += factor * digit; + if (rt_version[i] != '.') + break; + digit = 0; + factor >>= 8; + ++i; + } + return version; +#endif +} +static int __Pyx_check_binary_version(unsigned long ct_version, unsigned long rt_version, int allow_newer) { + const unsigned long MAJOR_MINOR = 0xFFFF0000UL; + if ((rt_version & MAJOR_MINOR) == (ct_version & MAJOR_MINOR)) + return 0; + if (likely(allow_newer && (rt_version & MAJOR_MINOR) > (ct_version & MAJOR_MINOR))) + return 1; + { + char message[200]; + PyOS_snprintf(message, sizeof(message), + "compile time Python version %d.%d " + "of module '%.100s' " + "%s " + "runtime version %d.%d", + (int) (ct_version >> 24), (int) ((ct_version >> 16) & 0xFF), + __Pyx_MODULE_NAME, + (allow_newer) ? "was newer than" : "does not match", + (int) (rt_version >> 24), (int) ((rt_version >> 16) & 0xFF) + ); + return PyErr_WarnEx(NULL, message, 1); + } +} + +/* InitStrings */ + #if PY_MAJOR_VERSION >= 3 +static int __Pyx_InitString(__Pyx_StringTabEntry t, PyObject **str) { + if (t.is_unicode | t.is_str) { + if (t.intern) { + *str = PyUnicode_InternFromString(t.s); + } else if (t.encoding) { + *str = PyUnicode_Decode(t.s, t.n - 1, t.encoding, NULL); + } else { + *str = PyUnicode_FromStringAndSize(t.s, t.n - 1); + } + } else { + *str = PyBytes_FromStringAndSize(t.s, t.n - 1); + } + if (!*str) + return -1; + if (PyObject_Hash(*str) == -1) + return -1; + return 0; +} +#endif +static int __Pyx_InitStrings(__Pyx_StringTabEntry *t) { + while (t->p) { + #if PY_MAJOR_VERSION >= 3 + __Pyx_InitString(*t, t->p); + #else + if (t->is_unicode) { + *t->p = PyUnicode_DecodeUTF8(t->s, t->n - 1, NULL); + } else if (t->intern) { + *t->p = PyString_InternFromString(t->s); + } else { + *t->p = PyString_FromStringAndSize(t->s, t->n - 1); + } + if (!*t->p) + return -1; + if (PyObject_Hash(*t->p) == -1) + return -1; + #endif + ++t; + } + return 0; +} + +#include +static CYTHON_INLINE Py_ssize_t __Pyx_ssize_strlen(const char *s) { + size_t len = strlen(s); + if (unlikely(len > (size_t) PY_SSIZE_T_MAX)) { + PyErr_SetString(PyExc_OverflowError, "byte string is too long"); + return -1; + } + return (Py_ssize_t) len; +} +static CYTHON_INLINE PyObject* __Pyx_PyUnicode_FromString(const char* c_str) { + Py_ssize_t len = __Pyx_ssize_strlen(c_str); + if (unlikely(len < 0)) return NULL; + return __Pyx_PyUnicode_FromStringAndSize(c_str, len); +} +static CYTHON_INLINE PyObject* __Pyx_PyByteArray_FromString(const char* c_str) { + Py_ssize_t len = __Pyx_ssize_strlen(c_str); + if (unlikely(len < 0)) return NULL; + return PyByteArray_FromStringAndSize(c_str, len); +} +static CYTHON_INLINE const char* __Pyx_PyObject_AsString(PyObject* o) { + Py_ssize_t ignore; + return __Pyx_PyObject_AsStringAndSize(o, &ignore); +} +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT +#if !CYTHON_PEP393_ENABLED +static const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + char* defenc_c; + PyObject* defenc = _PyUnicode_AsDefaultEncodedString(o, NULL); + if (!defenc) return NULL; + defenc_c = PyBytes_AS_STRING(defenc); +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + { + char* end = defenc_c + PyBytes_GET_SIZE(defenc); + char* c; + for (c = defenc_c; c < end; c++) { + if ((unsigned char) (*c) >= 128) { + PyUnicode_AsASCIIString(o); + return NULL; + } + } + } +#endif + *length = PyBytes_GET_SIZE(defenc); + return defenc_c; +} +#else +static CYTHON_INLINE const char* __Pyx_PyUnicode_AsStringAndSize(PyObject* o, Py_ssize_t *length) { + if (unlikely(__Pyx_PyUnicode_READY(o) == -1)) return NULL; +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + if (likely(PyUnicode_IS_ASCII(o))) { + *length = PyUnicode_GET_LENGTH(o); + return PyUnicode_AsUTF8(o); + } else { + PyUnicode_AsASCIIString(o); + return NULL; + } +#else + return PyUnicode_AsUTF8AndSize(o, length); +#endif +} +#endif +#endif +static CYTHON_INLINE const char* __Pyx_PyObject_AsStringAndSize(PyObject* o, Py_ssize_t *length) { +#if __PYX_DEFAULT_STRING_ENCODING_IS_ASCII || __PYX_DEFAULT_STRING_ENCODING_IS_DEFAULT + if ( +#if PY_MAJOR_VERSION < 3 && __PYX_DEFAULT_STRING_ENCODING_IS_ASCII + __Pyx_sys_getdefaultencoding_not_ascii && +#endif + PyUnicode_Check(o)) { + return __Pyx_PyUnicode_AsStringAndSize(o, length); + } else +#endif +#if (!CYTHON_COMPILING_IN_PYPY && !CYTHON_COMPILING_IN_LIMITED_API) || (defined(PyByteArray_AS_STRING) && defined(PyByteArray_GET_SIZE)) + if (PyByteArray_Check(o)) { + *length = PyByteArray_GET_SIZE(o); + return PyByteArray_AS_STRING(o); + } else +#endif + { + char* result; + int r = PyBytes_AsStringAndSize(o, &result, length); + if (unlikely(r < 0)) { + return NULL; + } else { + return result; + } + } +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrue(PyObject* x) { + int is_true = x == Py_True; + if (is_true | (x == Py_False) | (x == Py_None)) return is_true; + else return PyObject_IsTrue(x); +} +static CYTHON_INLINE int __Pyx_PyObject_IsTrueAndDecref(PyObject* x) { + int retval; + if (unlikely(!x)) return -1; + retval = __Pyx_PyObject_IsTrue(x); + Py_DECREF(x); + return retval; +} +static PyObject* __Pyx_PyNumber_IntOrLongWrongResultType(PyObject* result, const char* type_name) { + __Pyx_TypeName result_type_name = __Pyx_PyType_GetName(Py_TYPE(result)); +#if PY_MAJOR_VERSION >= 3 + if (PyLong_Check(result)) { + if (PyErr_WarnFormat(PyExc_DeprecationWarning, 1, + "__int__ returned non-int (type " __Pyx_FMT_TYPENAME "). " + "The ability to return an instance of a strict subclass of int is deprecated, " + "and may be removed in a future version of Python.", + result_type_name)) { + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; + } + __Pyx_DECREF_TypeName(result_type_name); + return result; + } +#endif + PyErr_Format(PyExc_TypeError, + "__%.4s__ returned non-%.4s (type " __Pyx_FMT_TYPENAME ")", + type_name, type_name, result_type_name); + __Pyx_DECREF_TypeName(result_type_name); + Py_DECREF(result); + return NULL; +} +static CYTHON_INLINE PyObject* __Pyx_PyNumber_IntOrLong(PyObject* x) { +#if CYTHON_USE_TYPE_SLOTS + PyNumberMethods *m; +#endif + const char *name = NULL; + PyObject *res = NULL; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_Check(x) || PyLong_Check(x))) +#else + if (likely(PyLong_Check(x))) +#endif + return __Pyx_NewRef(x); +#if CYTHON_USE_TYPE_SLOTS + m = Py_TYPE(x)->tp_as_number; + #if PY_MAJOR_VERSION < 3 + if (m && m->nb_int) { + name = "int"; + res = m->nb_int(x); + } + else if (m && m->nb_long) { + name = "long"; + res = m->nb_long(x); + } + #else + if (likely(m && m->nb_int)) { + name = "int"; + res = m->nb_int(x); + } + #endif +#else + if (!PyBytes_CheckExact(x) && !PyUnicode_CheckExact(x)) { + res = PyNumber_Int(x); + } +#endif + if (likely(res)) { +#if PY_MAJOR_VERSION < 3 + if (unlikely(!PyInt_Check(res) && !PyLong_Check(res))) { +#else + if (unlikely(!PyLong_CheckExact(res))) { +#endif + return __Pyx_PyNumber_IntOrLongWrongResultType(res, name); + } + } + else if (!PyErr_Occurred()) { + PyErr_SetString(PyExc_TypeError, + "an integer is required"); + } + return res; +} +static CYTHON_INLINE Py_ssize_t __Pyx_PyIndex_AsSsize_t(PyObject* b) { + Py_ssize_t ival; + PyObject *x; +#if PY_MAJOR_VERSION < 3 + if (likely(PyInt_CheckExact(b))) { + if (sizeof(Py_ssize_t) >= sizeof(long)) + return PyInt_AS_LONG(b); + else + return PyInt_AsSsize_t(b); + } +#endif + if (likely(PyLong_CheckExact(b))) { + #if CYTHON_USE_PYLONG_INTERNALS + if (likely(__Pyx_PyLong_IsCompact(b))) { + return __Pyx_PyLong_CompactValue(b); + } else { + const digit* digits = __Pyx_PyLong_Digits(b); + const Py_ssize_t size = __Pyx_PyLong_SignedDigitCount(b); + switch (size) { + case 2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return (Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -2: + if (8 * sizeof(Py_ssize_t) > 2 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -3: + if (8 * sizeof(Py_ssize_t) > 3 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case 4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return (Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + case -4: + if (8 * sizeof(Py_ssize_t) > 4 * PyLong_SHIFT) { + return -(Py_ssize_t) (((((((((size_t)digits[3]) << PyLong_SHIFT) | (size_t)digits[2]) << PyLong_SHIFT) | (size_t)digits[1]) << PyLong_SHIFT) | (size_t)digits[0])); + } + break; + } + } + #endif + return PyLong_AsSsize_t(b); + } + x = PyNumber_Index(b); + if (!x) return -1; + ival = PyInt_AsSsize_t(x); + Py_DECREF(x); + return ival; +} +static CYTHON_INLINE Py_hash_t __Pyx_PyIndex_AsHash_t(PyObject* o) { + if (sizeof(Py_hash_t) == sizeof(Py_ssize_t)) { + return (Py_hash_t) __Pyx_PyIndex_AsSsize_t(o); +#if PY_MAJOR_VERSION < 3 + } else if (likely(PyInt_CheckExact(o))) { + return PyInt_AS_LONG(o); +#endif + } else { + Py_ssize_t ival; + PyObject *x; + x = PyNumber_Index(o); + if (!x) return -1; + ival = PyInt_AsLong(x); + Py_DECREF(x); + return ival; + } +} +static CYTHON_INLINE PyObject * __Pyx_PyBool_FromLong(long b) { + return b ? __Pyx_NewRef(Py_True) : __Pyx_NewRef(Py_False); +} +static CYTHON_INLINE PyObject * __Pyx_PyInt_FromSize_t(size_t ival) { + return PyInt_FromSize_t(ival); +} + + +/* #### Code section: utility_code_pragmas_end ### */ +#ifdef _MSC_VER +#pragma warning( pop ) +#endif + + + +/* #### Code section: end ### */ +#endif /* Py_PYTHON_H */ diff --git a/selfdrive/modeld/runners/thneedmodel_pyx.so b/selfdrive/modeld/runners/thneedmodel_pyx.so new file mode 100755 index 0000000..f5638f8 Binary files /dev/null and b/selfdrive/modeld/runners/thneedmodel_pyx.so differ diff --git a/selfdrive/modeld/thneed/serialize.cc b/selfdrive/modeld/thneed/serialize.cc deleted file mode 100644 index 3dc2bef..0000000 --- a/selfdrive/modeld/thneed/serialize.cc +++ /dev/null @@ -1,154 +0,0 @@ -#include -#include - -#include "third_party/json11/json11.hpp" -#include "common/util.h" -#include "common/clutil.h" -#include "common/swaglog.h" -#include "selfdrive/modeld/thneed/thneed.h" -using namespace json11; - -extern map g_program_source; - -void Thneed::load(const char *filename) { - LOGD("Thneed::load: loading from %s\n", filename); - - string buf = util::read_file(filename); - int jsz = *(int *)buf.data(); - string jsonerr; - string jj(buf.data() + sizeof(int), jsz); - Json jdat = Json::parse(jj, jsonerr); - - map real_mem; - real_mem[NULL] = NULL; - - int ptr = sizeof(int)+jsz; - for (auto &obj : jdat["objects"].array_items()) { - auto mobj = obj.object_items(); - int sz = mobj["size"].int_value(); - cl_mem clbuf = NULL; - - if (mobj["buffer_id"].string_value().size() > 0) { - // image buffer must already be allocated - clbuf = real_mem[*(cl_mem*)(mobj["buffer_id"].string_value().data())]; - assert(mobj["needs_load"].bool_value() == false); - } else { - if (mobj["needs_load"].bool_value()) { - clbuf = clCreateBuffer(context, CL_MEM_COPY_HOST_PTR | CL_MEM_READ_WRITE, sz, &buf[ptr], NULL); - if (debug >= 1) printf("loading %p %d @ 0x%X\n", clbuf, sz, ptr); - ptr += sz; - } else { - // TODO: is there a faster way to init zeroed out buffers? - void *host_zeros = calloc(sz, 1); - clbuf = clCreateBuffer(context, CL_MEM_COPY_HOST_PTR | CL_MEM_READ_WRITE, sz, host_zeros, NULL); - free(host_zeros); - } - } - assert(clbuf != NULL); - - if (mobj["arg_type"] == "image2d_t" || mobj["arg_type"] == "image1d_t") { - cl_image_desc desc = {0}; - desc.image_type = (mobj["arg_type"] == "image2d_t") ? CL_MEM_OBJECT_IMAGE2D : CL_MEM_OBJECT_IMAGE1D_BUFFER; - desc.image_width = mobj["width"].int_value(); - desc.image_height = mobj["height"].int_value(); - desc.image_row_pitch = mobj["row_pitch"].int_value(); - assert(sz == desc.image_height*desc.image_row_pitch); -#ifdef QCOM2 - desc.buffer = clbuf; -#else - // TODO: we are creating unused buffers on PC - clReleaseMemObject(clbuf); -#endif - cl_image_format format = {0}; - format.image_channel_order = CL_RGBA; - format.image_channel_data_type = mobj["float32"].bool_value() ? CL_FLOAT : CL_HALF_FLOAT; - - cl_int errcode; - -#ifndef QCOM2 - if (mobj["needs_load"].bool_value()) { - clbuf = clCreateImage(context, CL_MEM_COPY_HOST_PTR | CL_MEM_READ_WRITE, &format, &desc, &buf[ptr-sz], &errcode); - } else { - clbuf = clCreateImage(context, CL_MEM_READ_WRITE, &format, &desc, NULL, &errcode); - } -#else - clbuf = clCreateImage(context, CL_MEM_READ_WRITE, &format, &desc, NULL, &errcode); -#endif - if (clbuf == NULL) { - LOGE("clError: %s create image %zux%zu rp %zu with buffer %p\n", cl_get_error_string(errcode), - desc.image_width, desc.image_height, desc.image_row_pitch, desc.buffer); - } - assert(clbuf != NULL); - } - - real_mem[*(cl_mem*)(mobj["id"].string_value().data())] = clbuf; - } - - map g_programs; - for (const auto &[name, source] : jdat["programs"].object_items()) { - if (debug >= 1) printf("building %s with size %zu\n", name.c_str(), source.string_value().size()); - g_programs[name] = cl_program_from_source(context, device_id, source.string_value()); - } - - for (auto &obj : jdat["inputs"].array_items()) { - auto mobj = obj.object_items(); - int sz = mobj["size"].int_value(); - cl_mem aa = real_mem[*(cl_mem*)(mobj["buffer_id"].string_value().data())]; - input_clmem.push_back(aa); - input_sizes.push_back(sz); - LOGD("Thneed::load: adding input %s with size %d\n", mobj["name"].string_value().data(), sz); - - cl_int cl_err; - void *ret = clEnqueueMapBuffer(command_queue, aa, CL_TRUE, CL_MAP_WRITE, 0, sz, 0, NULL, NULL, &cl_err); - if (cl_err != CL_SUCCESS) LOGE("clError: %s map %p %d\n", cl_get_error_string(cl_err), aa, sz); - assert(cl_err == CL_SUCCESS); - inputs.push_back(ret); - } - - for (auto &obj : jdat["outputs"].array_items()) { - auto mobj = obj.object_items(); - int sz = mobj["size"].int_value(); - LOGD("Thneed::save: adding output with size %d\n", sz); - // TODO: support multiple outputs - output = real_mem[*(cl_mem*)(mobj["buffer_id"].string_value().data())]; - assert(output != NULL); - } - - for (auto &obj : jdat["binaries"].array_items()) { - string name = obj["name"].string_value(); - size_t length = obj["length"].int_value(); - if (debug >= 1) printf("binary %s with size %zu\n", name.c_str(), length); - g_programs[name] = cl_program_from_binary(context, device_id, (const uint8_t*)&buf[ptr], length); - ptr += length; - } - - for (auto &obj : jdat["kernels"].array_items()) { - auto gws = obj["global_work_size"]; - auto lws = obj["local_work_size"]; - auto kk = shared_ptr(new CLQueuedKernel(this)); - - kk->name = obj["name"].string_value(); - kk->program = g_programs[kk->name]; - kk->work_dim = obj["work_dim"].int_value(); - for (int i = 0; i < kk->work_dim; i++) { - kk->global_work_size[i] = gws[i].int_value(); - kk->local_work_size[i] = lws[i].int_value(); - } - kk->num_args = obj["num_args"].int_value(); - for (int i = 0; i < kk->num_args; i++) { - string arg = obj["args"].array_items()[i].string_value(); - int arg_size = obj["args_size"].array_items()[i].int_value(); - kk->args_size.push_back(arg_size); - if (arg_size == 8) { - cl_mem val = *(cl_mem*)(arg.data()); - val = real_mem[val]; - kk->args.push_back(string((char*)&val, sizeof(val))); - } else { - kk->args.push_back(arg); - } - } - kq.push_back(kk); - } - - clFinish(command_queue); -} diff --git a/selfdrive/modeld/thneed/thneed.h b/selfdrive/modeld/thneed/thneed.h deleted file mode 100644 index 47e18e0..0000000 --- a/selfdrive/modeld/thneed/thneed.h +++ /dev/null @@ -1,133 +0,0 @@ -#pragma once - -#ifndef __user -#define __user __attribute__(()) -#endif - -#include -#include -#include -#include -#include - -#include - -#include "third_party/linux/include/msm_kgsl.h" - -using namespace std; - -cl_int thneed_clSetKernelArg(cl_kernel kernel, cl_uint arg_index, size_t arg_size, const void *arg_value); - -namespace json11 { - class Json; -} -class Thneed; - -class GPUMalloc { - public: - GPUMalloc(int size, int fd); - ~GPUMalloc(); - void *alloc(int size); - private: - uint64_t base; - int remaining; -}; - -class CLQueuedKernel { - public: - CLQueuedKernel(Thneed *lthneed) { thneed = lthneed; } - CLQueuedKernel(Thneed *lthneed, - cl_kernel _kernel, - cl_uint _work_dim, - const size_t *_global_work_size, - const size_t *_local_work_size); - cl_int exec(); - void debug_print(bool verbose); - int get_arg_num(const char *search_arg_name); - cl_program program; - string name; - cl_uint num_args; - vector arg_names; - vector arg_types; - vector args; - vector args_size; - cl_kernel kernel = NULL; - json11::Json to_json() const; - - cl_uint work_dim; - size_t global_work_size[3] = {0}; - size_t local_work_size[3] = {0}; - private: - Thneed *thneed; -}; - -class CachedIoctl { - public: - virtual void exec() {} -}; - -class CachedSync: public CachedIoctl { - public: - CachedSync(Thneed *lthneed, string ldata) { thneed = lthneed; data = ldata; } - void exec(); - private: - Thneed *thneed; - string data; -}; - -class CachedCommand: public CachedIoctl { - public: - CachedCommand(Thneed *lthneed, struct kgsl_gpu_command *cmd); - void exec(); - private: - void disassemble(int cmd_index); - struct kgsl_gpu_command cache; - unique_ptr cmds; - unique_ptr objs; - Thneed *thneed; - vector > kq; -}; - -class Thneed { - public: - Thneed(bool do_clinit=false, cl_context _context = NULL); - void stop(); - void execute(float **finputs, float *foutput, bool slow=false); - void wait(); - - vector input_clmem; - vector inputs; - vector input_sizes; - cl_mem output = NULL; - - cl_context context = NULL; - cl_command_queue command_queue; - cl_device_id device_id; - int context_id; - - // protected? - bool record = false; - int debug; - int timestamp; - -#ifdef QCOM2 - unique_ptr ram; - vector > cmds; - int fd; -#endif - - // all CL kernels - void copy_inputs(float **finputs, bool internal=false); - void copy_output(float *foutput); - cl_int clexec(); - vector > kq; - - // pending CL kernels - vector > ckq; - - // loading - void load(const char *filename); - private: - void clinit(); -}; - diff --git a/selfdrive/modeld/thneed/thneed_common.cc b/selfdrive/modeld/thneed/thneed_common.cc deleted file mode 100644 index ecdf123..0000000 --- a/selfdrive/modeld/thneed/thneed_common.cc +++ /dev/null @@ -1,216 +0,0 @@ -#include "selfdrive/modeld/thneed/thneed.h" - -#include -#include -#include - -#include "common/clutil.h" -#include "common/timing.h" - -map, string> g_args; -map, int> g_args_size; -map g_program_source; - -void Thneed::stop() { - //printf("Thneed::stop: recorded %lu commands\n", cmds.size()); - record = false; -} - -void Thneed::clinit() { - device_id = cl_get_device_id(CL_DEVICE_TYPE_DEFAULT); - if (context == NULL) context = CL_CHECK_ERR(clCreateContext(NULL, 1, &device_id, NULL, NULL, &err)); - //cl_command_queue_properties props[3] = {CL_QUEUE_PROPERTIES, CL_QUEUE_PROFILING_ENABLE, 0}; - cl_command_queue_properties props[3] = {CL_QUEUE_PROPERTIES, 0, 0}; - command_queue = CL_CHECK_ERR(clCreateCommandQueueWithProperties(context, device_id, props, &err)); - printf("Thneed::clinit done\n"); -} - -cl_int Thneed::clexec() { - if (debug >= 1) printf("Thneed::clexec: running %lu queued kernels\n", kq.size()); - for (auto &k : kq) { - if (record) ckq.push_back(k); - cl_int ret = k->exec(); - assert(ret == CL_SUCCESS); - } - return clFinish(command_queue); -} - -void Thneed::copy_inputs(float **finputs, bool internal) { - for (int idx = 0; idx < inputs.size(); ++idx) { - if (debug >= 1) printf("copying %lu -- %p -> %p (cl %p)\n", input_sizes[idx], finputs[idx], inputs[idx], input_clmem[idx]); - - if (internal) { - // if it's internal, using memcpy is fine since the buffer sync is cached in the ioctl layer - if (finputs[idx] != NULL) memcpy(inputs[idx], finputs[idx], input_sizes[idx]); - } else { - if (finputs[idx] != NULL) CL_CHECK(clEnqueueWriteBuffer(command_queue, input_clmem[idx], CL_TRUE, 0, input_sizes[idx], finputs[idx], 0, NULL, NULL)); - } - } -} - -void Thneed::copy_output(float *foutput) { - if (output != NULL) { - size_t sz; - clGetMemObjectInfo(output, CL_MEM_SIZE, sizeof(sz), &sz, NULL); - if (debug >= 1) printf("copying %lu for output %p -> %p\n", sz, output, foutput); - CL_CHECK(clEnqueueReadBuffer(command_queue, output, CL_TRUE, 0, sz, foutput, 0, NULL, NULL)); - } else { - printf("CAUTION: model output is NULL, does it have no outputs?\n"); - } -} - -// *********** CLQueuedKernel *********** - -CLQueuedKernel::CLQueuedKernel(Thneed *lthneed, - cl_kernel _kernel, - cl_uint _work_dim, - const size_t *_global_work_size, - const size_t *_local_work_size) { - thneed = lthneed; - kernel = _kernel; - work_dim = _work_dim; - assert(work_dim <= 3); - for (int i = 0; i < work_dim; i++) { - global_work_size[i] = _global_work_size[i]; - local_work_size[i] = _local_work_size[i]; - } - - char _name[0x100]; - clGetKernelInfo(kernel, CL_KERNEL_FUNCTION_NAME, sizeof(_name), _name, NULL); - name = string(_name); - clGetKernelInfo(kernel, CL_KERNEL_NUM_ARGS, sizeof(num_args), &num_args, NULL); - - // get args - for (int i = 0; i < num_args; i++) { - char arg_name[0x100] = {0}; - clGetKernelArgInfo(kernel, i, CL_KERNEL_ARG_NAME, sizeof(arg_name), arg_name, NULL); - arg_names.push_back(string(arg_name)); - clGetKernelArgInfo(kernel, i, CL_KERNEL_ARG_TYPE_NAME, sizeof(arg_name), arg_name, NULL); - arg_types.push_back(string(arg_name)); - - args.push_back(g_args[make_pair(kernel, i)]); - args_size.push_back(g_args_size[make_pair(kernel, i)]); - } - - // get program - clGetKernelInfo(kernel, CL_KERNEL_PROGRAM, sizeof(program), &program, NULL); -} - -int CLQueuedKernel::get_arg_num(const char *search_arg_name) { - for (int i = 0; i < num_args; i++) { - if (arg_names[i] == search_arg_name) return i; - } - printf("failed to find %s in %s\n", search_arg_name, name.c_str()); - assert(false); -} - -cl_int CLQueuedKernel::exec() { - if (kernel == NULL) { - kernel = clCreateKernel(program, name.c_str(), NULL); - arg_names.clear(); - arg_types.clear(); - - for (int j = 0; j < num_args; j++) { - char arg_name[0x100] = {0}; - clGetKernelArgInfo(kernel, j, CL_KERNEL_ARG_NAME, sizeof(arg_name), arg_name, NULL); - arg_names.push_back(string(arg_name)); - clGetKernelArgInfo(kernel, j, CL_KERNEL_ARG_TYPE_NAME, sizeof(arg_name), arg_name, NULL); - arg_types.push_back(string(arg_name)); - - cl_int ret; - if (args[j].size() != 0) { - assert(args[j].size() == args_size[j]); - ret = thneed_clSetKernelArg(kernel, j, args[j].size(), args[j].data()); - } else { - ret = thneed_clSetKernelArg(kernel, j, args_size[j], NULL); - } - assert(ret == CL_SUCCESS); - } - } - - if (thneed->debug >= 1) { - debug_print(thneed->debug >= 2); - } - - return clEnqueueNDRangeKernel(thneed->command_queue, - kernel, work_dim, NULL, global_work_size, local_work_size, 0, NULL, NULL); -} - -void CLQueuedKernel::debug_print(bool verbose) { - printf("%p %56s -- ", kernel, name.c_str()); - for (int i = 0; i < work_dim; i++) { - printf("%4zu ", global_work_size[i]); - } - printf(" -- "); - for (int i = 0; i < work_dim; i++) { - printf("%4zu ", local_work_size[i]); - } - printf("\n"); - - if (verbose) { - for (int i = 0; i < num_args; i++) { - string arg = args[i]; - printf(" %s %s", arg_types[i].c_str(), arg_names[i].c_str()); - void *arg_value = (void*)arg.data(); - int arg_size = arg.size(); - if (arg_size == 0) { - printf(" (size) %d", args_size[i]); - } else if (arg_size == 1) { - printf(" = %d", *((char*)arg_value)); - } else if (arg_size == 2) { - printf(" = %d", *((short*)arg_value)); - } else if (arg_size == 4) { - if (arg_types[i] == "float") { - printf(" = %f", *((float*)arg_value)); - } else { - printf(" = %d", *((int*)arg_value)); - } - } else if (arg_size == 8) { - cl_mem val = (cl_mem)(*((uintptr_t*)arg_value)); - printf(" = %p", val); - if (val != NULL) { - cl_mem_object_type obj_type; - clGetMemObjectInfo(val, CL_MEM_TYPE, sizeof(obj_type), &obj_type, NULL); - if (arg_types[i] == "image2d_t" || arg_types[i] == "image1d_t" || obj_type == CL_MEM_OBJECT_IMAGE2D) { - cl_image_format format; - size_t width, height, depth, array_size, row_pitch, slice_pitch; - cl_mem buf; - clGetImageInfo(val, CL_IMAGE_FORMAT, sizeof(format), &format, NULL); - assert(format.image_channel_order == CL_RGBA); - assert(format.image_channel_data_type == CL_HALF_FLOAT || format.image_channel_data_type == CL_FLOAT); - clGetImageInfo(val, CL_IMAGE_WIDTH, sizeof(width), &width, NULL); - clGetImageInfo(val, CL_IMAGE_HEIGHT, sizeof(height), &height, NULL); - clGetImageInfo(val, CL_IMAGE_ROW_PITCH, sizeof(row_pitch), &row_pitch, NULL); - clGetImageInfo(val, CL_IMAGE_DEPTH, sizeof(depth), &depth, NULL); - clGetImageInfo(val, CL_IMAGE_ARRAY_SIZE, sizeof(array_size), &array_size, NULL); - clGetImageInfo(val, CL_IMAGE_SLICE_PITCH, sizeof(slice_pitch), &slice_pitch, NULL); - assert(depth == 0); - assert(array_size == 0); - assert(slice_pitch == 0); - - clGetImageInfo(val, CL_IMAGE_BUFFER, sizeof(buf), &buf, NULL); - size_t sz = 0; - if (buf != NULL) clGetMemObjectInfo(buf, CL_MEM_SIZE, sizeof(sz), &sz, NULL); - printf(" image %zu x %zu rp %zu @ %p buffer %zu", width, height, row_pitch, buf, sz); - } else { - size_t sz; - clGetMemObjectInfo(val, CL_MEM_SIZE, sizeof(sz), &sz, NULL); - printf(" buffer %zu", sz); - } - } - } - printf("\n"); - } - } -} - -cl_int thneed_clSetKernelArg(cl_kernel kernel, cl_uint arg_index, size_t arg_size, const void *arg_value) { - g_args_size[make_pair(kernel, arg_index)] = arg_size; - if (arg_value != NULL) { - g_args[make_pair(kernel, arg_index)] = string((char*)arg_value, arg_size); - } else { - g_args[make_pair(kernel, arg_index)] = string(""); - } - cl_int ret = clSetKernelArg(kernel, arg_index, arg_size, arg_value); - return ret; -} diff --git a/selfdrive/modeld/thneed/thneed_qcom2.cc b/selfdrive/modeld/thneed/thneed_qcom2.cc deleted file mode 100644 index 21de15d..0000000 --- a/selfdrive/modeld/thneed/thneed_qcom2.cc +++ /dev/null @@ -1,258 +0,0 @@ -#include "selfdrive/modeld/thneed/thneed.h" - -#include -#include - -#include -#include -#include -#include -#include - -#include "common/clutil.h" -#include "common/timing.h" - -Thneed *g_thneed = NULL; -int g_fd = -1; - -void hexdump(uint8_t *d, int len) { - assert((len%4) == 0); - printf(" dumping %p len 0x%x\n", d, len); - for (int i = 0; i < len/4; i++) { - if (i != 0 && (i%0x10) == 0) printf("\n"); - printf("%8x ", d[i]); - } - printf("\n"); -} - -// *********** ioctl interceptor *********** - -extern "C" { - -int (*my_ioctl)(int filedes, unsigned long request, void *argp) = NULL; -#undef ioctl -int ioctl(int filedes, unsigned long request, void *argp) { - request &= 0xFFFFFFFF; // needed on QCOM2 - if (my_ioctl == NULL) my_ioctl = reinterpret_cast(dlsym(RTLD_NEXT, "ioctl")); - Thneed *thneed = g_thneed; - - // save the fd - if (request == IOCTL_KGSL_GPUOBJ_ALLOC) g_fd = filedes; - - // note that this runs always, even without a thneed object - if (request == IOCTL_KGSL_DRAWCTXT_CREATE) { - struct kgsl_drawctxt_create *create = (struct kgsl_drawctxt_create *)argp; - create->flags &= ~KGSL_CONTEXT_PRIORITY_MASK; - create->flags |= 6 << KGSL_CONTEXT_PRIORITY_SHIFT; // priority from 1-15, 1 is max priority - printf("IOCTL_KGSL_DRAWCTXT_CREATE: creating context with flags 0x%x\n", create->flags); - } - - if (thneed != NULL) { - if (request == IOCTL_KGSL_GPU_COMMAND) { - struct kgsl_gpu_command *cmd = (struct kgsl_gpu_command *)argp; - if (thneed->record) { - thneed->timestamp = cmd->timestamp; - thneed->context_id = cmd->context_id; - thneed->cmds.push_back(unique_ptr(new CachedCommand(thneed, cmd))); - } - if (thneed->debug >= 1) { - printf("IOCTL_KGSL_GPU_COMMAND(%2zu): flags: 0x%lx context_id: %u timestamp: %u numcmds: %d numobjs: %d\n", - thneed->cmds.size(), - cmd->flags, - cmd->context_id, cmd->timestamp, cmd->numcmds, cmd->numobjs); - } - } else if (request == IOCTL_KGSL_GPUOBJ_SYNC) { - struct kgsl_gpuobj_sync *cmd = (struct kgsl_gpuobj_sync *)argp; - struct kgsl_gpuobj_sync_obj *objs = (struct kgsl_gpuobj_sync_obj *)(cmd->objs); - - if (thneed->debug >= 2) { - printf("IOCTL_KGSL_GPUOBJ_SYNC count:%d ", cmd->count); - for (int i = 0; i < cmd->count; i++) { - printf(" -- offset:0x%lx len:0x%lx id:%d op:%d ", objs[i].offset, objs[i].length, objs[i].id, objs[i].op); - } - printf("\n"); - } - - if (thneed->record) { - thneed->cmds.push_back(unique_ptr(new - CachedSync(thneed, string((char *)objs, sizeof(struct kgsl_gpuobj_sync_obj)*cmd->count)))); - } - } else if (request == IOCTL_KGSL_DEVICE_WAITTIMESTAMP_CTXTID) { - struct kgsl_device_waittimestamp_ctxtid *cmd = (struct kgsl_device_waittimestamp_ctxtid *)argp; - if (thneed->debug >= 1) { - printf("IOCTL_KGSL_DEVICE_WAITTIMESTAMP_CTXTID: context_id: %d timestamp: %d timeout: %d\n", - cmd->context_id, cmd->timestamp, cmd->timeout); - } - } else if (request == IOCTL_KGSL_SETPROPERTY) { - if (thneed->debug >= 1) { - struct kgsl_device_getproperty *prop = (struct kgsl_device_getproperty *)argp; - printf("IOCTL_KGSL_SETPROPERTY: 0x%x sizebytes:%zu\n", prop->type, prop->sizebytes); - if (thneed->debug >= 2) { - hexdump((uint8_t *)prop->value, prop->sizebytes); - if (prop->type == KGSL_PROP_PWR_CONSTRAINT) { - struct kgsl_device_constraint *constraint = (struct kgsl_device_constraint *)prop->value; - hexdump((uint8_t *)constraint->data, constraint->size); - } - } - } - } else if (request == IOCTL_KGSL_DRAWCTXT_CREATE || request == IOCTL_KGSL_DRAWCTXT_DESTROY) { - // this happens - } else if (request == IOCTL_KGSL_GPUOBJ_ALLOC || request == IOCTL_KGSL_GPUOBJ_FREE) { - // this happens - } else { - if (thneed->debug >= 1) { - printf("other ioctl %lx\n", request); - } - } - } - - int ret = my_ioctl(filedes, request, argp); - // NOTE: This error message goes into stdout and messes up pyenv - // if (ret != 0) printf("ioctl returned %d with errno %d\n", ret, errno); - return ret; -} - -} - -// *********** GPUMalloc *********** - -GPUMalloc::GPUMalloc(int size, int fd) { - struct kgsl_gpuobj_alloc alloc; - memset(&alloc, 0, sizeof(alloc)); - alloc.size = size; - alloc.flags = 0x10000a00; - ioctl(fd, IOCTL_KGSL_GPUOBJ_ALLOC, &alloc); - void *addr = mmap64(NULL, alloc.mmapsize, 0x3, 0x1, fd, alloc.id*0x1000); - assert(addr != MAP_FAILED); - - base = (uint64_t)addr; - remaining = size; -} - -GPUMalloc::~GPUMalloc() { - // TODO: free the GPU malloced area -} - -void *GPUMalloc::alloc(int size) { - void *ret = (void*)base; - size = (size+0xff) & (~0xFF); - assert(size <= remaining); - remaining -= size; - base += size; - return ret; -} - -// *********** CachedSync, at the ioctl layer *********** - -void CachedSync::exec() { - struct kgsl_gpuobj_sync cmd; - - cmd.objs = (uint64_t)data.data(); - cmd.obj_len = data.length(); - cmd.count = data.length() / sizeof(struct kgsl_gpuobj_sync_obj); - - int ret = ioctl(thneed->fd, IOCTL_KGSL_GPUOBJ_SYNC, &cmd); - assert(ret == 0); -} - -// *********** CachedCommand, at the ioctl layer *********** - -CachedCommand::CachedCommand(Thneed *lthneed, struct kgsl_gpu_command *cmd) { - thneed = lthneed; - assert(cmd->numsyncs == 0); - - memcpy(&cache, cmd, sizeof(cache)); - - if (cmd->numcmds > 0) { - cmds = make_unique(cmd->numcmds); - memcpy(cmds.get(), (void *)cmd->cmdlist, sizeof(struct kgsl_command_object)*cmd->numcmds); - cache.cmdlist = (uint64_t)cmds.get(); - for (int i = 0; i < cmd->numcmds; i++) { - void *nn = thneed->ram->alloc(cmds[i].size); - memcpy(nn, (void*)cmds[i].gpuaddr, cmds[i].size); - cmds[i].gpuaddr = (uint64_t)nn; - } - } - - if (cmd->numobjs > 0) { - objs = make_unique(cmd->numobjs); - memcpy(objs.get(), (void *)cmd->objlist, sizeof(struct kgsl_command_object)*cmd->numobjs); - cache.objlist = (uint64_t)objs.get(); - for (int i = 0; i < cmd->numobjs; i++) { - void *nn = thneed->ram->alloc(objs[i].size); - memset(nn, 0, objs[i].size); - objs[i].gpuaddr = (uint64_t)nn; - } - } - - kq = thneed->ckq; - thneed->ckq.clear(); -} - -void CachedCommand::exec() { - cache.timestamp = ++thneed->timestamp; - int ret = ioctl(thneed->fd, IOCTL_KGSL_GPU_COMMAND, &cache); - - if (thneed->debug >= 1) printf("CachedCommand::exec got %d\n", ret); - - if (thneed->debug >= 2) { - for (auto &it : kq) { - it->debug_print(false); - } - } - - assert(ret == 0); -} - -// *********** Thneed *********** - -Thneed::Thneed(bool do_clinit, cl_context _context) { - // TODO: QCOM2 actually requires a different context - //context = _context; - if (do_clinit) clinit(); - assert(g_fd != -1); - fd = g_fd; - ram = make_unique(0x80000, fd); - timestamp = -1; - g_thneed = this; - char *thneed_debug_env = getenv("THNEED_DEBUG"); - debug = (thneed_debug_env != NULL) ? atoi(thneed_debug_env) : 0; -} - -void Thneed::wait() { - struct kgsl_device_waittimestamp_ctxtid wait; - wait.context_id = context_id; - wait.timestamp = timestamp; - wait.timeout = -1; - - uint64_t tb = nanos_since_boot(); - int wret = ioctl(fd, IOCTL_KGSL_DEVICE_WAITTIMESTAMP_CTXTID, &wait); - uint64_t te = nanos_since_boot(); - - if (debug >= 1) printf("wait %d after %lu us\n", wret, (te-tb)/1000); -} - -void Thneed::execute(float **finputs, float *foutput, bool slow) { - uint64_t tb, te; - if (debug >= 1) tb = nanos_since_boot(); - - // ****** copy inputs - copy_inputs(finputs, true); - - // ****** run commands - int i = 0; - for (auto &it : cmds) { - ++i; - if (debug >= 1) printf("run %2d @ %7lu us: ", i, (nanos_since_boot()-tb)/1000); - it->exec(); - if ((i == cmds.size()) || slow) wait(); - } - - // ****** copy outputs - copy_output(foutput); - - if (debug >= 1) { - te = nanos_since_boot(); - printf("model exec in %lu us\n", (te-tb)/1000); - } -} diff --git a/selfdrive/modeld/transforms/loadyuv.cc b/selfdrive/modeld/transforms/loadyuv.cc deleted file mode 100644 index c7ce7b0..0000000 --- a/selfdrive/modeld/transforms/loadyuv.cc +++ /dev/null @@ -1,74 +0,0 @@ -#include "selfdrive/modeld/transforms/loadyuv.h" - -#include -#include -#include - -void loadyuv_init(LoadYUVState* s, cl_context ctx, cl_device_id device_id, int width, int height) { - memset(s, 0, sizeof(*s)); - - s->width = width; - s->height = height; - - char args[1024]; - snprintf(args, sizeof(args), - "-cl-fast-relaxed-math -cl-denorms-are-zero " - "-DTRANSFORMED_WIDTH=%d -DTRANSFORMED_HEIGHT=%d", - width, height); - cl_program prg = cl_program_from_file(ctx, device_id, LOADYUV_PATH, args); - - s->loadys_krnl = CL_CHECK_ERR(clCreateKernel(prg, "loadys", &err)); - s->loaduv_krnl = CL_CHECK_ERR(clCreateKernel(prg, "loaduv", &err)); - s->copy_krnl = CL_CHECK_ERR(clCreateKernel(prg, "copy", &err)); - - // done with this - CL_CHECK(clReleaseProgram(prg)); -} - -void loadyuv_destroy(LoadYUVState* s) { - CL_CHECK(clReleaseKernel(s->loadys_krnl)); - CL_CHECK(clReleaseKernel(s->loaduv_krnl)); - CL_CHECK(clReleaseKernel(s->copy_krnl)); -} - -void loadyuv_queue(LoadYUVState* s, cl_command_queue q, - cl_mem y_cl, cl_mem u_cl, cl_mem v_cl, - cl_mem out_cl, bool do_shift) { - cl_int global_out_off = 0; - if (do_shift) { - // shift the image in slot 1 to slot 0, then place the new image in slot 1 - global_out_off += (s->width*s->height) + (s->width/2)*(s->height/2)*2; - CL_CHECK(clSetKernelArg(s->copy_krnl, 0, sizeof(cl_mem), &out_cl)); - CL_CHECK(clSetKernelArg(s->copy_krnl, 1, sizeof(cl_int), &global_out_off)); - const size_t copy_work_size = global_out_off/8; - CL_CHECK(clEnqueueNDRangeKernel(q, s->copy_krnl, 1, NULL, - ©_work_size, NULL, 0, 0, NULL)); - } - - CL_CHECK(clSetKernelArg(s->loadys_krnl, 0, sizeof(cl_mem), &y_cl)); - CL_CHECK(clSetKernelArg(s->loadys_krnl, 1, sizeof(cl_mem), &out_cl)); - CL_CHECK(clSetKernelArg(s->loadys_krnl, 2, sizeof(cl_int), &global_out_off)); - - const size_t loadys_work_size = (s->width*s->height)/8; - CL_CHECK(clEnqueueNDRangeKernel(q, s->loadys_krnl, 1, NULL, - &loadys_work_size, NULL, 0, 0, NULL)); - - const size_t loaduv_work_size = ((s->width/2)*(s->height/2))/8; - global_out_off += (s->width*s->height); - - CL_CHECK(clSetKernelArg(s->loaduv_krnl, 0, sizeof(cl_mem), &u_cl)); - CL_CHECK(clSetKernelArg(s->loaduv_krnl, 1, sizeof(cl_mem), &out_cl)); - CL_CHECK(clSetKernelArg(s->loaduv_krnl, 2, sizeof(cl_int), &global_out_off)); - - CL_CHECK(clEnqueueNDRangeKernel(q, s->loaduv_krnl, 1, NULL, - &loaduv_work_size, NULL, 0, 0, NULL)); - - global_out_off += (s->width/2)*(s->height/2); - - CL_CHECK(clSetKernelArg(s->loaduv_krnl, 0, sizeof(cl_mem), &v_cl)); - CL_CHECK(clSetKernelArg(s->loaduv_krnl, 1, sizeof(cl_mem), &out_cl)); - CL_CHECK(clSetKernelArg(s->loaduv_krnl, 2, sizeof(cl_int), &global_out_off)); - - CL_CHECK(clEnqueueNDRangeKernel(q, s->loaduv_krnl, 1, NULL, - &loaduv_work_size, NULL, 0, 0, NULL)); -} diff --git a/selfdrive/modeld/transforms/loadyuv.h b/selfdrive/modeld/transforms/loadyuv.h deleted file mode 100644 index 7d27ef5..0000000 --- a/selfdrive/modeld/transforms/loadyuv.h +++ /dev/null @@ -1,16 +0,0 @@ -#pragma once - -#include "common/clutil.h" - -typedef struct { - int width, height; - cl_kernel loadys_krnl, loaduv_krnl, copy_krnl; -} LoadYUVState; - -void loadyuv_init(LoadYUVState* s, cl_context ctx, cl_device_id device_id, int width, int height); - -void loadyuv_destroy(LoadYUVState* s); - -void loadyuv_queue(LoadYUVState* s, cl_command_queue q, - cl_mem y_cl, cl_mem u_cl, cl_mem v_cl, - cl_mem out_cl, bool do_shift = false); diff --git a/selfdrive/modeld/transforms/transform.cc b/selfdrive/modeld/transforms/transform.cc deleted file mode 100644 index 305643c..0000000 --- a/selfdrive/modeld/transforms/transform.cc +++ /dev/null @@ -1,97 +0,0 @@ -#include "selfdrive/modeld/transforms/transform.h" - -#include -#include - -#include "common/clutil.h" - -void transform_init(Transform* s, cl_context ctx, cl_device_id device_id) { - memset(s, 0, sizeof(*s)); - - cl_program prg = cl_program_from_file(ctx, device_id, TRANSFORM_PATH, ""); - s->krnl = CL_CHECK_ERR(clCreateKernel(prg, "warpPerspective", &err)); - // done with this - CL_CHECK(clReleaseProgram(prg)); - - s->m_y_cl = CL_CHECK_ERR(clCreateBuffer(ctx, CL_MEM_READ_WRITE, 3*3*sizeof(float), NULL, &err)); - s->m_uv_cl = CL_CHECK_ERR(clCreateBuffer(ctx, CL_MEM_READ_WRITE, 3*3*sizeof(float), NULL, &err)); -} - -void transform_destroy(Transform* s) { - CL_CHECK(clReleaseMemObject(s->m_y_cl)); - CL_CHECK(clReleaseMemObject(s->m_uv_cl)); - CL_CHECK(clReleaseKernel(s->krnl)); -} - -void transform_queue(Transform* s, - cl_command_queue q, - cl_mem in_yuv, int in_width, int in_height, int in_stride, int in_uv_offset, - cl_mem out_y, cl_mem out_u, cl_mem out_v, - int out_width, int out_height, - const mat3& projection) { - const int zero = 0; - - // sampled using pixel center origin - // (because that's how fastcv and opencv does it) - - mat3 projection_y = projection; - - // in and out uv is half the size of y. - mat3 projection_uv = transform_scale_buffer(projection, 0.5); - - CL_CHECK(clEnqueueWriteBuffer(q, s->m_y_cl, CL_TRUE, 0, 3*3*sizeof(float), (void*)projection_y.v, 0, NULL, NULL)); - CL_CHECK(clEnqueueWriteBuffer(q, s->m_uv_cl, CL_TRUE, 0, 3*3*sizeof(float), (void*)projection_uv.v, 0, NULL, NULL)); - - const int in_y_width = in_width; - const int in_y_height = in_height; - const int in_y_px_stride = 1; - const int in_uv_width = in_width/2; - const int in_uv_height = in_height/2; - const int in_uv_px_stride = 2; - const int in_u_offset = in_uv_offset; - const int in_v_offset = in_uv_offset + 1; - - const int out_y_width = out_width; - const int out_y_height = out_height; - const int out_uv_width = out_width/2; - const int out_uv_height = out_height/2; - - CL_CHECK(clSetKernelArg(s->krnl, 0, sizeof(cl_mem), &in_yuv)); // src - CL_CHECK(clSetKernelArg(s->krnl, 1, sizeof(cl_int), &in_stride)); // src_row_stride - CL_CHECK(clSetKernelArg(s->krnl, 2, sizeof(cl_int), &in_y_px_stride)); // src_px_stride - CL_CHECK(clSetKernelArg(s->krnl, 3, sizeof(cl_int), &zero)); // src_offset - CL_CHECK(clSetKernelArg(s->krnl, 4, sizeof(cl_int), &in_y_height)); // src_rows - CL_CHECK(clSetKernelArg(s->krnl, 5, sizeof(cl_int), &in_y_width)); // src_cols - CL_CHECK(clSetKernelArg(s->krnl, 6, sizeof(cl_mem), &out_y)); // dst - CL_CHECK(clSetKernelArg(s->krnl, 7, sizeof(cl_int), &out_y_width)); // dst_row_stride - CL_CHECK(clSetKernelArg(s->krnl, 8, sizeof(cl_int), &zero)); // dst_offset - CL_CHECK(clSetKernelArg(s->krnl, 9, sizeof(cl_int), &out_y_height)); // dst_rows - CL_CHECK(clSetKernelArg(s->krnl, 10, sizeof(cl_int), &out_y_width)); // dst_cols - CL_CHECK(clSetKernelArg(s->krnl, 11, sizeof(cl_mem), &s->m_y_cl)); // M - - const size_t work_size_y[2] = {(size_t)out_y_width, (size_t)out_y_height}; - - CL_CHECK(clEnqueueNDRangeKernel(q, s->krnl, 2, NULL, - (const size_t*)&work_size_y, NULL, 0, 0, NULL)); - - const size_t work_size_uv[2] = {(size_t)out_uv_width, (size_t)out_uv_height}; - - CL_CHECK(clSetKernelArg(s->krnl, 2, sizeof(cl_int), &in_uv_px_stride)); // src_px_stride - CL_CHECK(clSetKernelArg(s->krnl, 3, sizeof(cl_int), &in_u_offset)); // src_offset - CL_CHECK(clSetKernelArg(s->krnl, 4, sizeof(cl_int), &in_uv_height)); // src_rows - CL_CHECK(clSetKernelArg(s->krnl, 5, sizeof(cl_int), &in_uv_width)); // src_cols - CL_CHECK(clSetKernelArg(s->krnl, 6, sizeof(cl_mem), &out_u)); // dst - CL_CHECK(clSetKernelArg(s->krnl, 7, sizeof(cl_int), &out_uv_width)); // dst_row_stride - CL_CHECK(clSetKernelArg(s->krnl, 8, sizeof(cl_int), &zero)); // dst_offset - CL_CHECK(clSetKernelArg(s->krnl, 9, sizeof(cl_int), &out_uv_height)); // dst_rows - CL_CHECK(clSetKernelArg(s->krnl, 10, sizeof(cl_int), &out_uv_width)); // dst_cols - CL_CHECK(clSetKernelArg(s->krnl, 11, sizeof(cl_mem), &s->m_uv_cl)); // M - - CL_CHECK(clEnqueueNDRangeKernel(q, s->krnl, 2, NULL, - (const size_t*)&work_size_uv, NULL, 0, 0, NULL)); - CL_CHECK(clSetKernelArg(s->krnl, 3, sizeof(cl_int), &in_v_offset)); // src_ofset - CL_CHECK(clSetKernelArg(s->krnl, 6, sizeof(cl_mem), &out_v)); // dst - - CL_CHECK(clEnqueueNDRangeKernel(q, s->krnl, 2, NULL, - (const size_t*)&work_size_uv, NULL, 0, 0, NULL)); -} diff --git a/selfdrive/modeld/transforms/transform.h b/selfdrive/modeld/transforms/transform.h deleted file mode 100644 index 771a705..0000000 --- a/selfdrive/modeld/transforms/transform.h +++ /dev/null @@ -1,25 +0,0 @@ -#pragma once - -#define CL_USE_DEPRECATED_OPENCL_1_2_APIS -#ifdef __APPLE__ -#include -#else -#include -#endif - -#include "common/mat.h" - -typedef struct { - cl_kernel krnl; - cl_mem m_y_cl, m_uv_cl; -} Transform; - -void transform_init(Transform* s, cl_context ctx, cl_device_id device_id); - -void transform_destroy(Transform* transform); - -void transform_queue(Transform* s, cl_command_queue q, - cl_mem yuv, int in_width, int in_height, int in_stride, int in_uv_offset, - cl_mem out_y, cl_mem out_u, cl_mem out_v, - int out_width, int out_height, - const mat3& projection); diff --git a/selfdrive/navd/SConscript b/selfdrive/navd/SConscript deleted file mode 100644 index 5a173c0..0000000 --- a/selfdrive/navd/SConscript +++ /dev/null @@ -1,20 +0,0 @@ -Import('qt_env', 'arch', 'common', 'messaging', 'visionipc', 'cereal', 'transformations') - -map_env = qt_env.Clone() -libs = ['qt_widgets', 'qt_util', 'QMapLibre', common, messaging, cereal, visionipc, transformations, - 'zmq', 'capnp', 'kj', 'm', 'OpenCL', 'ssl', 'crypto', 'pthread', 'json11'] + map_env["LIBS"] -if arch == 'larch64': - libs.append(':libEGL_mesa.so.0') - -if arch in ['larch64', 'aarch64', 'x86_64']: - if arch == 'x86_64': - rpath = Dir(f"#third_party/maplibre-native-qt/{arch}/lib").srcnode().abspath - map_env["RPATH"] += [rpath, ] - - style_path = File("style.json").abspath - map_env['CXXFLAGS'].append(f'-DSTYLE_PATH=\\"{style_path}\\"') - - map_env["RPATH"].append(Dir('.').abspath) - map_env["LIBPATH"].append(Dir('.').abspath) - maplib = map_env.SharedLibrary("maprender", ["map_renderer.cc"], LIBS=libs) - map_env.Program("mapsd", ["main.cc", ], LIBS=[maplib[0].get_path(), ] + libs) diff --git a/third_party/snpe/x86_64-linux-clang/libHtpPrepare.so b/selfdrive/navd/libmaprender.so similarity index 53% rename from third_party/snpe/x86_64-linux-clang/libHtpPrepare.so rename to selfdrive/navd/libmaprender.so index 0b0657d..f155280 100644 Binary files a/third_party/snpe/x86_64-linux-clang/libHtpPrepare.so and b/selfdrive/navd/libmaprender.so differ diff --git a/selfdrive/navd/main.cc b/selfdrive/navd/main.cc deleted file mode 100644 index 2e7b4d3..0000000 --- a/selfdrive/navd/main.cc +++ /dev/null @@ -1,29 +0,0 @@ -#include -#include - -#include -#include - -#include "common/util.h" -#include "selfdrive/ui/qt/util.h" -#include "selfdrive/ui/qt/maps/map_helpers.h" -#include "selfdrive/navd/map_renderer.h" -#include "system/hardware/hw.h" - -int main(int argc, char *argv[]) { - Hardware::config_cpu_rendering(true); - - qInstallMessageHandler(swagLogMessageHandler); - setpriority(PRIO_PROCESS, 0, -20); - int ret = util::set_core_affinity({0, 1, 2, 3}); - assert(ret == 0); - - QApplication app(argc, argv); - std::signal(SIGINT, sigTermHandler); - std::signal(SIGTERM, sigTermHandler); - - MapRenderer * m = new MapRenderer(get_mapbox_settings()); - assert(m); - - return app.exec(); -} diff --git a/selfdrive/navd/map_renderer.cc b/selfdrive/navd/map_renderer.cc deleted file mode 100644 index d52ee16..0000000 --- a/selfdrive/navd/map_renderer.cc +++ /dev/null @@ -1,334 +0,0 @@ -#include "selfdrive/navd/map_renderer.h" - -#include -#include -#include -#include - -#include "common/util.h" -#include "common/timing.h" -#include "common/swaglog.h" -#include "selfdrive/ui/qt/maps/map_helpers.h" - -const float DEFAULT_ZOOM = 13.5; // Don't go below 13 or features will start to disappear -const int HEIGHT = 256, WIDTH = 256; -const int NUM_VIPC_BUFFERS = 4; - -const int EARTH_CIRCUMFERENCE_METERS = 40075000; -const int EARTH_RADIUS_METERS = 6378137; -const int PIXELS_PER_TILE = 256; -const int MAP_OFFSET = 128; - -const bool TEST_MODE = getenv("MAP_RENDER_TEST_MODE"); -const int LLK_DECIMATION = TEST_MODE ? 1 : 10; - -float get_zoom_level_for_scale(float lat, float meters_per_pixel) { - float meters_per_tile = meters_per_pixel * PIXELS_PER_TILE; - float num_tiles = cos(DEG2RAD(lat)) * EARTH_CIRCUMFERENCE_METERS / meters_per_tile; - return log2(num_tiles) - 1; -} - -QMapLibre::Coordinate get_point_along_line(float lat, float lon, float bearing, float dist) { - float ang_dist = dist / EARTH_RADIUS_METERS; - float lat1 = DEG2RAD(lat), lon1 = DEG2RAD(lon), bearing1 = DEG2RAD(bearing); - float lat2 = asin(sin(lat1)*cos(ang_dist) + cos(lat1)*sin(ang_dist)*cos(bearing1)); - float lon2 = lon1 + atan2(sin(bearing1)*sin(ang_dist)*cos(lat1), cos(ang_dist)-sin(lat1)*sin(lat2)); - return QMapLibre::Coordinate(RAD2DEG(lat2), RAD2DEG(lon2)); -} - - -MapRenderer::MapRenderer(const QMapLibre::Settings &settings, bool online) : m_settings(settings) { - QSurfaceFormat fmt; - fmt.setRenderableType(QSurfaceFormat::OpenGLES); - - ctx = std::make_unique(); - ctx->setFormat(fmt); - ctx->create(); - assert(ctx->isValid()); - - surface = std::make_unique(); - surface->setFormat(ctx->format()); - surface->create(); - - ctx->makeCurrent(surface.get()); - assert(QOpenGLContext::currentContext() == ctx.get()); - - gl_functions.reset(ctx->functions()); - gl_functions->initializeOpenGLFunctions(); - - QOpenGLFramebufferObjectFormat fbo_format; - fbo.reset(new QOpenGLFramebufferObject(WIDTH, HEIGHT, fbo_format)); - - std::string style = util::read_file(STYLE_PATH); - m_map.reset(new QMapLibre::Map(nullptr, m_settings, fbo->size(), 1)); - m_map->setCoordinateZoom(QMapLibre::Coordinate(0, 0), DEFAULT_ZOOM); - m_map->setStyleJson(style.c_str()); - m_map->createRenderer(); - ever_loaded = false; - - m_map->resize(fbo->size()); - m_map->setFramebufferObject(fbo->handle(), fbo->size()); - gl_functions->glViewport(0, 0, WIDTH, HEIGHT); - - QObject::connect(m_map.data(), &QMapLibre::Map::mapChanged, [=](QMapLibre::Map::MapChange change) { - // Ignore expected signals - // https://github.com/mapbox/mapbox-gl-native/blob/cf734a2fec960025350d8de0d01ad38aeae155a0/platform/qt/include/qmapboxgl.hpp#L116 - if (ever_loaded) { - if (change != QMapLibre::Map::MapChange::MapChangeRegionWillChange && - change != QMapLibre::Map::MapChange::MapChangeRegionDidChange && - change != QMapLibre::Map::MapChange::MapChangeWillStartRenderingFrame && - change != QMapLibre::Map::MapChange::MapChangeDidFinishRenderingFrameFullyRendered) { - LOGD("New map state: %d", change); - } - } - }); - - QObject::connect(m_map.data(), &QMapLibre::Map::mapLoadingFailed, [=](QMapLibre::Map::MapLoadingFailure err_code, const QString &reason) { - LOGE("Map loading failed with %d: '%s'\n", err_code, reason.toStdString().c_str()); - }); - - if (online) { - vipc_server.reset(new VisionIpcServer("navd")); - vipc_server->create_buffers(VisionStreamType::VISION_STREAM_MAP, NUM_VIPC_BUFFERS, false, WIDTH, HEIGHT); - vipc_server->start_listener(); - - pm.reset(new PubMaster({"navThumbnail", "mapRenderState"})); - sm.reset(new SubMaster({"liveLocationKalman", "navRoute"}, {"liveLocationKalman"})); - - timer = new QTimer(this); - timer->setSingleShot(true); - QObject::connect(timer, SIGNAL(timeout()), this, SLOT(msgUpdate())); - timer->start(0); - } -} - -void MapRenderer::msgUpdate() { - sm->update(1000); - - if (sm->updated("liveLocationKalman")) { - auto location = (*sm)["liveLocationKalman"].getLiveLocationKalman(); - auto pos = location.getPositionGeodetic(); - auto orientation = location.getCalibratedOrientationNED(); - - if ((sm->rcv_frame("liveLocationKalman") % LLK_DECIMATION) == 0) { - float bearing = RAD2DEG(orientation.getValue()[2]); - updatePosition(get_point_along_line(pos.getValue()[0], pos.getValue()[1], bearing, MAP_OFFSET), bearing); - - // TODO: use the static rendering mode instead - // retry render a few times - for (int i = 0; i < 5 && !rendered(); i++) { - QApplication::processEvents(QEventLoop::AllEvents, 100); - update(); - if (rendered()) { - LOGW("rendered after %d retries", i+1); - break; - } - } - - // fallback to sending a blank frame - if (!rendered()) { - publish(0, false); - } - } - } - - if (sm->updated("navRoute")) { - QList route; - auto coords = (*sm)["navRoute"].getNavRoute().getCoordinates(); - for (auto const &c : coords) { - route.push_back(QGeoCoordinate(c.getLatitude(), c.getLongitude())); - } - updateRoute(route); - } - - // schedule next update - timer->start(0); -} - -void MapRenderer::updatePosition(QMapLibre::Coordinate position, float bearing) { - if (m_map.isNull()) { - return; - } - - // Choose a scale that ensures above 13 zoom level up to and above 75deg of lat - float meters_per_pixel = 2; - float zoom = get_zoom_level_for_scale(position.first, meters_per_pixel); - - m_map->setCoordinate(position); - m_map->setBearing(bearing); - m_map->setZoom(zoom); - update(); -} - -bool MapRenderer::loaded() { - return m_map->isFullyLoaded(); -} - -void MapRenderer::update() { - double start_t = millis_since_boot(); - gl_functions->glClear(GL_COLOR_BUFFER_BIT); - m_map->render(); - gl_functions->glFlush(); - double end_t = millis_since_boot(); - - if ((vipc_server != nullptr) && loaded()) { - publish((end_t - start_t) / 1000.0, true); - last_llk_rendered = (*sm)["liveLocationKalman"].getLogMonoTime(); - } -} - -void MapRenderer::sendThumbnail(const uint64_t ts, const kj::Array &buf) { - MessageBuilder msg; - auto thumbnaild = msg.initEvent().initNavThumbnail(); - thumbnaild.setFrameId(frame_id); - thumbnaild.setTimestampEof(ts); - thumbnaild.setThumbnail(buf); - pm->send("navThumbnail", msg); -} - -void MapRenderer::publish(const double render_time, const bool loaded) { - QImage cap = fbo->toImage().convertToFormat(QImage::Format_RGB888, Qt::AutoColor); - - auto location = (*sm)["liveLocationKalman"].getLiveLocationKalman(); - bool valid = loaded && (location.getStatus() == cereal::LiveLocationKalman::Status::VALID) && location.getPositionGeodetic().getValid(); - ever_loaded = ever_loaded || loaded; - uint64_t ts = nanos_since_boot(); - VisionBuf* buf = vipc_server->get_buffer(VisionStreamType::VISION_STREAM_MAP); - VisionIpcBufExtra extra = { - .frame_id = frame_id, - .timestamp_sof = (*sm)["liveLocationKalman"].getLogMonoTime(), - .timestamp_eof = ts, - .valid = valid, - }; - - assert(cap.sizeInBytes() >= buf->len); - uint8_t* dst = (uint8_t*)buf->addr; - uint8_t* src = cap.bits(); - - // RGB to greyscale - memset(dst, 128, buf->len); - for (int i = 0; i < WIDTH * HEIGHT; i++) { - dst[i] = src[i * 3]; - } - - vipc_server->send(buf, &extra); - - // Send thumbnail - if (TEST_MODE) { - // Full image in thumbnails in test mode - kj::Array buffer_kj = kj::heapArray((const capnp::byte*)cap.bits(), cap.sizeInBytes()); - sendThumbnail(ts, buffer_kj); - } else if (frame_id % 100 == 0) { - // Write jpeg into buffer - QByteArray buffer_bytes; - QBuffer buffer(&buffer_bytes); - buffer.open(QIODevice::WriteOnly); - cap.save(&buffer, "JPG", 50); - - kj::Array buffer_kj = kj::heapArray((const capnp::byte*)buffer_bytes.constData(), buffer_bytes.size()); - sendThumbnail(ts, buffer_kj); - } - - // Send state msg - MessageBuilder msg; - auto evt = msg.initEvent(); - auto state = evt.initMapRenderState(); - evt.setValid(valid); - state.setLocationMonoTime((*sm)["liveLocationKalman"].getLogMonoTime()); - state.setRenderTime(render_time); - state.setFrameId(frame_id); - pm->send("mapRenderState", msg); - - frame_id++; -} - -uint8_t* MapRenderer::getImage() { - QImage cap = fbo->toImage().convertToFormat(QImage::Format_RGB888, Qt::AutoColor); - - uint8_t* src = cap.bits(); - uint8_t* dst = new uint8_t[WIDTH * HEIGHT]; - - // RGB to greyscale - for (int i = 0; i < WIDTH * HEIGHT; i++) { - dst[i] = src[i * 3]; - } - - return dst; -} - -void MapRenderer::updateRoute(QList coordinates) { - if (m_map.isNull()) return; - initLayers(); - - auto route_points = coordinate_list_to_collection(coordinates); - QMapLibre::Feature feature(QMapLibre::Feature::LineStringType, route_points, {}, {}); - QVariantMap navSource; - navSource["type"] = "geojson"; - navSource["data"] = QVariant::fromValue(feature); - m_map->updateSource("navSource", navSource); - m_map->setLayoutProperty("navLayer", "visibility", "visible"); -} - -void MapRenderer::initLayers() { - if (!m_map->layerExists("navLayer")) { - LOGD("Initializing navLayer"); - QVariantMap nav; - nav["type"] = "line"; - nav["source"] = "navSource"; - m_map->addLayer("navLayer", nav, "road-intersection"); - m_map->setPaintProperty("navLayer", "line-color", QColor("grey")); - m_map->setPaintProperty("navLayer", "line-width", 5); - m_map->setLayoutProperty("navLayer", "line-cap", "round"); - } -} - -MapRenderer::~MapRenderer() { -} - -extern "C" { - MapRenderer* map_renderer_init(char *maps_host = nullptr, char *token = nullptr) { - char *argv[] = { - (char*)"navd", - nullptr - }; - int argc = 0; - QApplication *app = new QApplication(argc, argv); - assert(app); - - QMapLibre::Settings settings; - settings.setProviderTemplate(QMapLibre::Settings::ProviderTemplate::MapboxProvider); - settings.setApiBaseUrl(maps_host == nullptr ? MAPS_HOST : maps_host); - settings.setApiKey(token == nullptr ? get_mapbox_token() : token); - - return new MapRenderer(settings, false); - } - - void map_renderer_update_position(MapRenderer *inst, float lat, float lon, float bearing) { - inst->updatePosition({lat, lon}, bearing); - QApplication::processEvents(); - } - - void map_renderer_update_route(MapRenderer *inst, char* polyline) { - inst->updateRoute(polyline_to_coordinate_list(QString::fromUtf8(polyline))); - } - - void map_renderer_update(MapRenderer *inst) { - inst->update(); - } - - void map_renderer_process(MapRenderer *inst) { - QApplication::processEvents(); - } - - bool map_renderer_loaded(MapRenderer *inst) { - return inst->loaded(); - } - - uint8_t * map_renderer_get_image(MapRenderer *inst) { - return inst->getImage(); - } - - void map_renderer_free_image(MapRenderer *inst, uint8_t * buf) { - delete[] buf; - } -} diff --git a/selfdrive/navd/map_renderer.h b/selfdrive/navd/map_renderer.h deleted file mode 100644 index fd5922b..0000000 --- a/selfdrive/navd/map_renderer.h +++ /dev/null @@ -1,59 +0,0 @@ -#pragma once - -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include "cereal/visionipc/visionipc_server.h" -#include "cereal/messaging/messaging.h" - - -class MapRenderer : public QObject { - Q_OBJECT - -public: - MapRenderer(const QMapLibre::Settings &, bool online=true); - uint8_t* getImage(); - void update(); - bool loaded(); - ~MapRenderer(); - -private: - std::unique_ptr ctx; - std::unique_ptr surface; - std::unique_ptr gl_functions; - std::unique_ptr fbo; - - std::unique_ptr vipc_server; - std::unique_ptr pm; - std::unique_ptr sm; - void publish(const double render_time, const bool loaded); - void sendThumbnail(const uint64_t ts, const kj::Array &buf); - - QMapLibre::Settings m_settings; - QScopedPointer m_map; - - void initLayers(); - - uint32_t frame_id = 0; - uint64_t last_llk_rendered = 0; - bool rendered() { - return last_llk_rendered == (*sm)["liveLocationKalman"].getLogMonoTime(); - } - - QTimer* timer; - bool ever_loaded = false; - -public slots: - void updatePosition(QMapLibre::Coordinate position, float bearing); - void updateRoute(QList coordinates); - void msgUpdate(); -}; diff --git a/selfdrive/navd/mapsd b/selfdrive/navd/mapsd new file mode 100755 index 0000000..854e92b Binary files /dev/null and b/selfdrive/navd/mapsd differ diff --git a/selfdrive/navd/tests/test_map_renderer.py b/selfdrive/navd/tests/test_map_renderer.py deleted file mode 100755 index b5f186d..0000000 --- a/selfdrive/navd/tests/test_map_renderer.py +++ /dev/null @@ -1,216 +0,0 @@ -#!/usr/bin/env python3 -import time -import numpy as np -import os -import pytest -import unittest -import requests -import threading -import http.server -import cereal.messaging as messaging - -from typing import Any -from cereal.visionipc import VisionIpcClient, VisionStreamType -from openpilot.common.mock.generators import LLK_DECIMATION, LOCATION1, LOCATION2, generate_liveLocationKalman -from openpilot.selfdrive.test.helpers import with_processes - -CACHE_PATH = "/data/mbgl-cache-navd.db" - -RENDER_FRAMES = 15 -DEFAULT_ITERATIONS = RENDER_FRAMES * LLK_DECIMATION -LOCATION1_REPEATED = [LOCATION1] * DEFAULT_ITERATIONS -LOCATION2_REPEATED = [LOCATION2] * DEFAULT_ITERATIONS - - -class MapBoxInternetDisabledRequestHandler(http.server.BaseHTTPRequestHandler): - INTERNET_ACTIVE = True - - def do_GET(self): - if not self.INTERNET_ACTIVE: - self.send_response(500) - self.end_headers() - return - - url = f'https://api.mapbox.com{self.path}' - - headers = dict(self.headers) - headers["Host"] = "api.mapbox.com" - - r = requests.get(url, headers=headers, timeout=5) - - self.send_response(r.status_code) - self.end_headers() - self.wfile.write(r.content) - - def log_message(self, *args: Any) -> None: - return - - def log_error(self, *args: Any) -> None: - return - - -class MapBoxInternetDisabledServer(threading.Thread): - def run(self): - self.server = http.server.HTTPServer(("127.0.0.1", 0), MapBoxInternetDisabledRequestHandler) - self.port = self.server.server_port - self.server.serve_forever() - - def stop(self): - self.server.shutdown() - - def disable_internet(self): - MapBoxInternetDisabledRequestHandler.INTERNET_ACTIVE = False - - def enable_internet(self): - MapBoxInternetDisabledRequestHandler.INTERNET_ACTIVE = True - - -class TestMapRenderer(unittest.TestCase): - server: MapBoxInternetDisabledServer - - @classmethod - def setUpClass(cls): - assert "MAPBOX_TOKEN" in os.environ - cls.original_token = os.environ["MAPBOX_TOKEN"] - cls.server = MapBoxInternetDisabledServer() - cls.server.start() - time.sleep(0.5) # wait for server to startup - - @classmethod - def tearDownClass(cls) -> None: - cls.server.stop() - - def setUp(self): - self.server.enable_internet() - os.environ['MAPS_HOST'] = f'http://localhost:{self.server.port}' - - self.sm = messaging.SubMaster(['mapRenderState']) - self.pm = messaging.PubMaster(['liveLocationKalman']) - self.vipc = VisionIpcClient("navd", VisionStreamType.VISION_STREAM_MAP, True) - - if os.path.exists(CACHE_PATH): - os.remove(CACHE_PATH) - - def _setup_test(self): - assert self.pm.wait_for_readers_to_update("liveLocationKalman", 10) - - time.sleep(0.5) - - assert VisionIpcClient.available_streams("navd", False) == {VisionStreamType.VISION_STREAM_MAP, } - assert self.vipc.connect(False) - self.vipc.recv() - - def _run_test(self, expect_valid, locations=LOCATION1_REPEATED): - starting_frame_id = None - - render_times = [] - - # run test - prev_frame_id = -1 - for i, location in enumerate(locations): - frame_expected = (i+1) % LLK_DECIMATION == 0 - - if self.sm.logMonoTime['mapRenderState'] == 0: - prev_valid = False - prev_frame_id = -1 - else: - prev_valid = self.sm.valid['mapRenderState'] - prev_frame_id = self.sm['mapRenderState'].frameId - - if starting_frame_id is None: - starting_frame_id = prev_frame_id - - llk = generate_liveLocationKalman(location) - self.pm.send("liveLocationKalman", llk) - self.pm.wait_for_readers_to_update("liveLocationKalman", 10) - self.sm.update(1000 if frame_expected else 0) - assert self.sm.updated['mapRenderState'] == frame_expected, "renderer running at wrong frequency" - - if not frame_expected: - continue - - frames_since_test_start = self.sm['mapRenderState'].frameId - starting_frame_id - - # give a few frames to switch from valid to invalid, or vice versa - invalid_and_not_previously_valid = (expect_valid and not self.sm.valid['mapRenderState'] and not prev_valid) - valid_and_not_previously_invalid = (not expect_valid and self.sm.valid['mapRenderState'] and prev_valid) - - if (invalid_and_not_previously_valid or valid_and_not_previously_invalid) and frames_since_test_start < 5: - continue - - # check output - assert self.sm.valid['mapRenderState'] == expect_valid - assert self.sm['mapRenderState'].frameId == (prev_frame_id + 1) - assert self.sm['mapRenderState'].locationMonoTime == llk.logMonoTime - if not expect_valid: - assert self.sm['mapRenderState'].renderTime == 0. - else: - assert 0. < self.sm['mapRenderState'].renderTime < 0.1 - render_times.append(self.sm['mapRenderState'].renderTime) - - # check vision ipc output - assert self.vipc.recv() is not None - assert self.vipc.valid == expect_valid - assert self.vipc.timestamp_sof == llk.logMonoTime - assert self.vipc.frame_id == self.sm['mapRenderState'].frameId - - assert frames_since_test_start >= RENDER_FRAMES - - return render_times - - @with_processes(["mapsd"]) - def test_with_internet(self): - self._setup_test() - self._run_test(True) - - @with_processes(["mapsd"]) - def test_with_no_internet(self): - self.server.disable_internet() - self._setup_test() - self._run_test(False) - - @with_processes(["mapsd"]) - @pytest.mark.skip(reason="slow, flaky, and unlikely to break") - def test_recover_from_no_internet(self): - self._setup_test() - self._run_test(True) - - self.server.disable_internet() - - # change locations to force mapsd to refetch - self._run_test(False, LOCATION2_REPEATED) - - self.server.enable_internet() - self._run_test(True, LOCATION2_REPEATED) - - @with_processes(["mapsd"]) - @pytest.mark.tici - def test_render_time_distribution(self): - self._setup_test() - # from location1 -> location2 and back - locations = np.array([*np.linspace(LOCATION1, LOCATION2, 2000), *np.linspace(LOCATION2, LOCATION1, 2000)]).tolist() - - render_times = self._run_test(True, locations) - - _min = np.min(render_times) - _max = np.max(render_times) - _mean = np.mean(render_times) - _median = np.median(render_times) - _stddev = np.std(render_times) - - print(f"Stats: min: {_min}, max: {_max}, mean: {_mean}, median: {_median}, stddev: {_stddev}, count: {len(render_times)}") - - def assert_stat(stat, nominal, tol=0.3): - tol = (nominal / (1+tol)), (nominal * (1+tol)) - self.assertTrue(tol[0] < stat < tol[1], f"{stat} not in tolerance {tol}") - - assert_stat(_mean, 0.030) - assert_stat(_median, 0.027) - assert_stat(_stddev, 0.0078) - - self.assertLess(_max, 0.065) - self.assertGreater(_min, 0.015) - - -if __name__ == "__main__": - unittest.main() diff --git a/selfdrive/navd/tests/test_navd.py b/selfdrive/navd/tests/test_navd.py deleted file mode 100755 index 61be6cc..0000000 --- a/selfdrive/navd/tests/test_navd.py +++ /dev/null @@ -1,63 +0,0 @@ -#!/usr/bin/env python3 -import json -import random -import unittest -import numpy as np - -from parameterized import parameterized - -import cereal.messaging as messaging -from openpilot.common.params import Params -from openpilot.selfdrive.manager.process_config import managed_processes - - -class TestNavd(unittest.TestCase): - def setUp(self): - self.params = Params() - self.sm = messaging.SubMaster(['navRoute', 'navInstruction']) - - def tearDown(self): - managed_processes['navd'].stop() - - def _check_route(self, start, end, check_coords=True): - self.params.put("NavDestination", json.dumps(end)) - self.params.put("LastGPSPosition", json.dumps(start)) - - managed_processes['navd'].start() - for _ in range(30): - self.sm.update(1000) - if all(f > 0 for f in self.sm.recv_frame.values()): - break - else: - raise Exception("didn't get a route") - - assert managed_processes['navd'].proc.is_alive() - managed_processes['navd'].stop() - - # ensure start and end match up - if check_coords: - coords = self.sm['navRoute'].coordinates - assert np.allclose([start['latitude'], start['longitude'], end['latitude'], end['longitude']], - [coords[0].latitude, coords[0].longitude, coords[-1].latitude, coords[-1].longitude], - rtol=1e-3) - - def test_simple(self): - start = { - "latitude": 32.7427228, - "longitude": -117.2321177, - } - end = { - "latitude": 32.7557004, - "longitude": -117.268002, - } - self._check_route(start, end) - - @parameterized.expand([(i,) for i in range(10)]) - def test_random(self, index): - start = {"latitude": random.uniform(-90, 90), "longitude": random.uniform(-180, 180)} - end = {"latitude": random.uniform(-90, 90), "longitude": random.uniform(-180, 180)} - self._check_route(start, end, check_coords=False) - - -if __name__ == "__main__": - unittest.main() diff --git a/selfdrive/test/.gitignore b/selfdrive/test/.gitignore deleted file mode 100644 index 5801faa..0000000 --- a/selfdrive/test/.gitignore +++ /dev/null @@ -1,9 +0,0 @@ -out/ -docker_out/ - -process_replay/diff.txt -process_replay/model_diff.txt -valgrind_logs.txt - -*.bz2 -*.hevc diff --git a/selfdrive/test/__init__.py b/selfdrive/test/__init__.py deleted file mode 100644 index e69de29..0000000 diff --git a/selfdrive/test/ci_shell.sh b/selfdrive/test/ci_shell.sh deleted file mode 100644 index a5ff714..0000000 --- a/selfdrive/test/ci_shell.sh +++ /dev/null @@ -1,19 +0,0 @@ -#!/bin/bash -e - -DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" -OP_ROOT="$DIR/../../" - -if [ -z "$BUILD" ]; then - docker pull ghcr.io/commaai/openpilot-base:latest -else - docker build --cache-from ghcr.io/commaai/openpilot-base:latest -t ghcr.io/commaai/openpilot-base:latest -f $OP_ROOT/Dockerfile.openpilot_base . -fi - -docker run \ - -it \ - --rm \ - --volume $OP_ROOT:$OP_ROOT \ - --workdir $PWD \ - --env PYTHONPATH=$OP_ROOT \ - ghcr.io/commaai/openpilot-base:latest \ - /bin/bash diff --git a/selfdrive/test/ciui.py b/selfdrive/test/ciui.py deleted file mode 100644 index f3b0c1a..0000000 --- a/selfdrive/test/ciui.py +++ /dev/null @@ -1,58 +0,0 @@ -#!/usr/bin/env python3 -import signal -import subprocess - -signal.signal(signal.SIGINT, signal.SIG_DFL) -signal.signal(signal.SIGTERM, signal.SIG_DFL) - -from PyQt5.QtCore import QTimer -from PyQt5.QtWidgets import QApplication, QWidget, QVBoxLayout, QLabel -from openpilot.selfdrive.ui.qt.python_helpers import set_main_window - -class Window(QWidget): - def __init__(self, parent=None): - super().__init__(parent) - - layout = QVBoxLayout() - self.setLayout(layout) - - self.l = QLabel("jenkins runner") - layout.addWidget(self.l) - layout.addStretch(1) - layout.setContentsMargins(20, 20, 20, 20) - - cmds = [ - "cat /etc/hostname", - "echo AGNOS v$(cat /VERSION)", - "uptime -p", - ] - self.labels = {} - for c in cmds: - self.labels[c] = QLabel(c) - layout.addWidget(self.labels[c]) - - self.setStyleSheet(""" - * { - color: white; - font-size: 55px; - background-color: black; - font-family: "JetBrains Mono"; - } - """) - - self.timer = QTimer() - self.timer.timeout.connect(self.update) - self.timer.start(10 * 1000) - self.update() - - def update(self): - for cmd, label in self.labels.items(): - out = subprocess.run(cmd, capture_output=True, - shell=True, check=False, encoding='utf8').stdout - label.setText(out.strip()) - -if __name__ == "__main__": - app = QApplication([]) - w = Window() - set_main_window(w) - app.exec_() diff --git a/selfdrive/test/cpp_harness.py b/selfdrive/test/cpp_harness.py deleted file mode 100644 index f9d3e68..0000000 --- a/selfdrive/test/cpp_harness.py +++ /dev/null @@ -1,11 +0,0 @@ -#!/usr/bin/env python3 -import subprocess -import sys - -from openpilot.common.prefix import OpenpilotPrefix - - -with OpenpilotPrefix(): - ret = subprocess.call(sys.argv[1:]) - -exit(ret) diff --git a/selfdrive/test/docker_build.sh b/selfdrive/test/docker_build.sh deleted file mode 100644 index 5f77ceb..0000000 --- a/selfdrive/test/docker_build.sh +++ /dev/null @@ -1,26 +0,0 @@ -#!/usr/bin/env bash -set -e - -# To build sim and docs, you can run the following to mount the scons cache to the same place as in CI: -# mkdir -p .ci_cache/scons_cache -# sudo mount --bind /tmp/scons_cache/ .ci_cache/scons_cache - -SCRIPT_DIR=$(dirname "$0") -OPENPILOT_DIR=$SCRIPT_DIR/../../ -if [ -n "$TARGET_ARCHITECTURE" ]; then - PLATFORM="linux/$TARGET_ARCHITECTURE" - TAG_SUFFIX="-$TARGET_ARCHITECTURE" -else - PLATFORM="linux/$(uname -m)" - TAG_SUFFIX="" -fi - -source $SCRIPT_DIR/docker_common.sh $1 "$TAG_SUFFIX" - -DOCKER_BUILDKIT=1 docker buildx build --provenance false --pull --platform $PLATFORM --load --cache-to type=inline --cache-from type=registry,ref=$REMOTE_TAG -t $REMOTE_TAG -t $LOCAL_TAG -f $OPENPILOT_DIR/$DOCKER_FILE $OPENPILOT_DIR - -if [ -n "$PUSH_IMAGE" ]; then - docker push $REMOTE_TAG - docker tag $REMOTE_TAG $REMOTE_SHA_TAG - docker push $REMOTE_SHA_TAG -fi diff --git a/selfdrive/test/docker_common.sh b/selfdrive/test/docker_common.sh deleted file mode 100644 index f8a4237..0000000 --- a/selfdrive/test/docker_common.sh +++ /dev/null @@ -1,21 +0,0 @@ -if [ "$1" = "base" ]; then - export DOCKER_IMAGE=openpilot-base - export DOCKER_FILE=Dockerfile.openpilot_base -elif [ "$1" = "sim" ]; then - export DOCKER_IMAGE=openpilot-sim - export DOCKER_FILE=tools/sim/Dockerfile.sim -elif [ "$1" = "prebuilt" ]; then - export DOCKER_IMAGE=openpilot-prebuilt - export DOCKER_FILE=Dockerfile.openpilot -else - echo "Invalid docker build image: '$1'" - exit 1 -fi - -export DOCKER_REGISTRY=ghcr.io/commaai -export COMMIT_SHA=$(git rev-parse HEAD) - -TAG_SUFFIX=$2 -LOCAL_TAG=$DOCKER_IMAGE$TAG_SUFFIX -REMOTE_TAG=$DOCKER_REGISTRY/$LOCAL_TAG -REMOTE_SHA_TAG=$DOCKER_REGISTRY/$LOCAL_TAG:$COMMIT_SHA diff --git a/selfdrive/test/docker_tag_multiarch.sh b/selfdrive/test/docker_tag_multiarch.sh deleted file mode 100644 index c176180..0000000 --- a/selfdrive/test/docker_tag_multiarch.sh +++ /dev/null @@ -1,25 +0,0 @@ -#!/usr/bin/env bash -set -e - -if [ $# -lt 2 ]; then - echo "Usage: $0 ..." - exit 1 -fi - -SCRIPT_DIR=$(dirname "$0") -ARCHS=("${@:2}") - -source $SCRIPT_DIR/docker_common.sh $1 - -MANIFEST_AMENDS="" -for ARCH in ${ARCHS[@]}; do - MANIFEST_AMENDS="$MANIFEST_AMENDS --amend $REMOTE_TAG-$ARCH:$COMMIT_SHA" -done - -docker manifest create $REMOTE_TAG $MANIFEST_AMENDS -docker manifest create $REMOTE_SHA_TAG $MANIFEST_AMENDS - -if [[ -n "$PUSH_IMAGE" ]]; then - docker manifest push $REMOTE_TAG - docker manifest push $REMOTE_SHA_TAG -fi diff --git a/selfdrive/test/fuzzy_generation.py b/selfdrive/test/fuzzy_generation.py deleted file mode 100644 index 26c35c0..0000000 --- a/selfdrive/test/fuzzy_generation.py +++ /dev/null @@ -1,85 +0,0 @@ -import capnp -import hypothesis.strategies as st -from typing import Any -from collections.abc import Callable - -from cereal import log - -DrawType = Callable[[st.SearchStrategy], Any] - - -class FuzzyGenerator: - def __init__(self, draw: DrawType, real_floats: bool): - self.draw = draw - self.real_floats = real_floats - - def generate_native_type(self, field: str) -> st.SearchStrategy[bool | int | float | str | bytes]: - def floats(**kwargs) -> st.SearchStrategy[float]: - allow_nan = not self.real_floats - allow_infinity = not self.real_floats - return st.floats(**kwargs, allow_nan=allow_nan, allow_infinity=allow_infinity) - - if field == 'bool': - return st.booleans() - elif field == 'int8': - return st.integers(min_value=-2**7, max_value=2**7-1) - elif field == 'int16': - return st.integers(min_value=-2**15, max_value=2**15-1) - elif field == 'int32': - return st.integers(min_value=-2**31, max_value=2**31-1) - elif field == 'int64': - return st.integers(min_value=-2**63, max_value=2**63-1) - elif field == 'uint8': - return st.integers(min_value=0, max_value=2**8-1) - elif field == 'uint16': - return st.integers(min_value=0, max_value=2**16-1) - elif field == 'uint32': - return st.integers(min_value=0, max_value=2**32-1) - elif field == 'uint64': - return st.integers(min_value=0, max_value=2**64-1) - elif field == 'float32': - return floats(width=32) - elif field == 'float64': - return floats(width=64) - elif field == 'text': - return st.text(max_size=1000) - elif field == 'data': - return st.binary(max_size=1000) - elif field == 'anyPointer': - return st.text() - else: - raise NotImplementedError(f'Invalid type : {field}') - - def generate_field(self, field: capnp.lib.capnp._StructSchemaField) -> st.SearchStrategy: - def rec(field_type: capnp.lib.capnp._DynamicStructReader) -> st.SearchStrategy: - if field_type.which() == 'struct': - return self.generate_struct(field.schema.elementType if base_type == 'list' else field.schema) - elif field_type.which() == 'list': - return st.lists(rec(field_type.list.elementType)) - elif field_type.which() == 'enum': - schema = field.schema.elementType if base_type == 'list' else field.schema - return st.sampled_from(list(schema.enumerants.keys())) - else: - return self.generate_native_type(field_type.which()) - - if 'slot' in field.proto.to_dict(): - base_type = field.proto.slot.type.which() - return rec(field.proto.slot.type) - else: - return self.generate_struct(field.schema) - - def generate_struct(self, schema: capnp.lib.capnp._StructSchema, event: str = None) -> st.SearchStrategy[dict[str, Any]]: - full_fill: list[str] = list(schema.non_union_fields) - single_fill: list[str] = [event] if event else [self.draw(st.sampled_from(schema.union_fields))] if schema.union_fields else [] - return st.fixed_dictionaries({field: self.generate_field(schema.fields[field]) for field in full_fill + single_fill}) - - @classmethod - def get_random_msg(cls, draw: DrawType, struct: capnp.lib.capnp._StructModule, real_floats: bool = False) -> dict[str, Any]: - fg = cls(draw, real_floats=real_floats) - data: dict[str, Any] = draw(fg.generate_struct(struct.schema)) - return data - - @classmethod - def get_random_event_msg(cls, draw: DrawType, events: list[str], real_floats: bool = False) -> list[dict[str, Any]]: - fg = cls(draw, real_floats=real_floats) - return [draw(fg.generate_struct(log.Event.schema, e)) for e in sorted(events)] diff --git a/selfdrive/test/helpers.py b/selfdrive/test/helpers.py deleted file mode 100644 index 210a283..0000000 --- a/selfdrive/test/helpers.py +++ /dev/null @@ -1,102 +0,0 @@ -import http.server -import os -import threading -import time - -from functools import wraps - -import cereal.messaging as messaging -from openpilot.common.params import Params -from openpilot.selfdrive.manager.process_config import managed_processes -from openpilot.system.hardware import PC -from openpilot.system.version import training_version, terms_version - - -def set_params_enabled(): - os.environ['FINGERPRINT'] = "TOYOTA COROLLA TSS2 2019" - os.environ['LOGPRINT'] = "debug" - - params = Params() - params.put("HasAcceptedTerms", terms_version) - params.put("CompletedTrainingVersion", training_version) - params.put_bool("OpenpilotEnabledToggle", True) - - # valid calib - msg = messaging.new_message('liveCalibration') - msg.liveCalibration.validBlocks = 20 - msg.liveCalibration.rpyCalib = [0.0, 0.0, 0.0] - params.put("CalibrationParams", msg.to_bytes()) - -def phone_only(f): - @wraps(f) - def wrap(self, *args, **kwargs): - if PC: - self.skipTest("This test is not meant to run on PC") - f(self, *args, **kwargs) - return wrap - -def release_only(f): - @wraps(f) - def wrap(self, *args, **kwargs): - if "RELEASE" not in os.environ: - self.skipTest("This test is only for release branches") - f(self, *args, **kwargs) - return wrap - -def with_processes(processes, init_time=0, ignore_stopped=None): - ignore_stopped = [] if ignore_stopped is None else ignore_stopped - - def wrapper(func): - @wraps(func) - def wrap(*args, **kwargs): - # start and assert started - for n, p in enumerate(processes): - managed_processes[p].start() - if n < len(processes) - 1: - time.sleep(init_time) - assert all(managed_processes[name].proc.exitcode is None for name in processes) - - # call the function - try: - func(*args, **kwargs) - # assert processes are still started - assert all(managed_processes[name].proc.exitcode is None for name in processes if name not in ignore_stopped) - finally: - for p in processes: - managed_processes[p].stop() - - return wrap - return wrapper - - -def noop(*args, **kwargs): - pass - - -def read_segment_list(segment_list_path): - with open(segment_list_path) as f: - seg_list = f.read().splitlines() - - return [(platform[2:], segment) for platform, segment in zip(seg_list[::2], seg_list[1::2], strict=True)] - - -def with_http_server(func, handler=http.server.BaseHTTPRequestHandler, setup=None): - @wraps(func) - def inner(*args, **kwargs): - host = '127.0.0.1' - server = http.server.HTTPServer((host, 0), handler) - port = server.server_port - t = threading.Thread(target=server.serve_forever) - t.start() - - if setup is not None: - setup(host, port) - - try: - return func(*args, f'http://{host}:{port}', **kwargs) - finally: - server.shutdown() - server.server_close() - t.join() - - return inner diff --git a/selfdrive/test/longitudinal_maneuvers/.gitignore b/selfdrive/test/longitudinal_maneuvers/.gitignore deleted file mode 100644 index d42ab35..0000000 --- a/selfdrive/test/longitudinal_maneuvers/.gitignore +++ /dev/null @@ -1 +0,0 @@ -out/* diff --git a/selfdrive/test/longitudinal_maneuvers/__init__.py b/selfdrive/test/longitudinal_maneuvers/__init__.py deleted file mode 100644 index e69de29..0000000 diff --git a/selfdrive/test/longitudinal_maneuvers/maneuver.py b/selfdrive/test/longitudinal_maneuvers/maneuver.py deleted file mode 100644 index 000225a..0000000 --- a/selfdrive/test/longitudinal_maneuvers/maneuver.py +++ /dev/null @@ -1,71 +0,0 @@ -import numpy as np -from openpilot.selfdrive.test.longitudinal_maneuvers.plant import Plant - - -class Maneuver: - def __init__(self, title, duration, **kwargs): - # Was tempted to make a builder class - self.distance_lead = kwargs.get("initial_distance_lead", 200.0) - self.speed = kwargs.get("initial_speed", 0.0) - self.lead_relevancy = kwargs.get("lead_relevancy", 0) - - self.breakpoints = kwargs.get("breakpoints", [0.0, duration]) - self.speed_lead_values = kwargs.get("speed_lead_values", [0.0 for i in range(len(self.breakpoints))]) - self.prob_lead_values = kwargs.get("prob_lead_values", [1.0 for i in range(len(self.breakpoints))]) - self.cruise_values = kwargs.get("cruise_values", [50.0 for i in range(len(self.breakpoints))]) - - self.only_lead2 = kwargs.get("only_lead2", False) - self.only_radar = kwargs.get("only_radar", False) - self.ensure_start = kwargs.get("ensure_start", False) - self.enabled = kwargs.get("enabled", True) - self.e2e = kwargs.get("e2e", False) - self.force_decel = kwargs.get("force_decel", False) - - self.duration = duration - self.title = title - - def evaluate(self): - plant = Plant( - lead_relevancy=self.lead_relevancy, - speed=self.speed, - distance_lead=self.distance_lead, - enabled=self.enabled, - only_lead2=self.only_lead2, - only_radar=self.only_radar, - e2e=self.e2e, - force_decel=self.force_decel, - ) - - valid = True - logs = [] - while plant.current_time < self.duration: - speed_lead = np.interp(plant.current_time, self.breakpoints, self.speed_lead_values) - prob = np.interp(plant.current_time, self.breakpoints, self.prob_lead_values) - cruise = np.interp(plant.current_time, self.breakpoints, self.cruise_values) - log = plant.step(speed_lead, prob, cruise) - - d_rel = log['distance_lead'] - log['distance'] if self.lead_relevancy else 200. - v_rel = speed_lead - log['speed'] if self.lead_relevancy else 0. - log['d_rel'] = d_rel - log['v_rel'] = v_rel - logs.append(np.array([plant.current_time, - log['distance'], - log['distance_lead'], - log['speed'], - speed_lead, - log['acceleration']])) - - if d_rel < .4 and (self.only_radar or prob > 0.5): - print("Crashed!!!!") - valid = False - - if self.ensure_start and log['v_rel'] > 0 and log['speeds'][-1] <= 0.1: - print('LongitudinalPlanner not starting!') - valid = False - if self.force_decel and log['speed'] > 1e-1 and log['acceleration'] > -0.04: - print('Not stopping with force decel') - valid = False - - - print("maneuver end", valid) - return valid, np.array(logs) diff --git a/selfdrive/test/longitudinal_maneuvers/plant.py b/selfdrive/test/longitudinal_maneuvers/plant.py deleted file mode 100644 index bb935fd..0000000 --- a/selfdrive/test/longitudinal_maneuvers/plant.py +++ /dev/null @@ -1,172 +0,0 @@ -#!/usr/bin/env python3 -import time -import numpy as np - -from cereal import log -import cereal.messaging as messaging -from openpilot.common.realtime import Ratekeeper, DT_MDL -from openpilot.selfdrive.controls.lib.longcontrol import LongCtrlState -from openpilot.selfdrive.modeld.constants import ModelConstants -from openpilot.selfdrive.controls.lib.longitudinal_planner import LongitudinalPlanner -from openpilot.selfdrive.controls.radard import _LEAD_ACCEL_TAU - - -class Plant: - messaging_initialized = False - - def __init__(self, lead_relevancy=False, speed=0.0, distance_lead=2.0, - enabled=True, only_lead2=False, only_radar=False, e2e=False, force_decel=False): - self.rate = 1. / DT_MDL - - if not Plant.messaging_initialized: - Plant.radar = messaging.pub_sock('radarState') - Plant.controls_state = messaging.pub_sock('controlsState') - Plant.car_state = messaging.pub_sock('carState') - Plant.plan = messaging.sub_sock('longitudinalPlan') - Plant.messaging_initialized = True - - self.v_lead_prev = 0.0 - - self.distance = 0. - self.speed = speed - self.acceleration = 0.0 - self.speeds = [] - - # lead car - self.lead_relevancy = lead_relevancy - self.distance_lead = distance_lead - self.enabled = enabled - self.only_lead2 = only_lead2 - self.only_radar = only_radar - self.e2e = e2e - self.force_decel = force_decel - - self.rk = Ratekeeper(self.rate, print_delay_threshold=100.0) - self.ts = 1. / self.rate - time.sleep(0.1) - self.sm = messaging.SubMaster(['longitudinalPlan']) - - from openpilot.selfdrive.car.honda.values import CAR - from openpilot.selfdrive.car.honda.interface import CarInterface - - self.planner = LongitudinalPlanner(CarInterface.get_non_essential_params(CAR.CIVIC), init_v=self.speed) - - @property - def current_time(self): - return float(self.rk.frame) / self.rate - - def step(self, v_lead=0.0, prob=1.0, v_cruise=50.): - # ******** publish a fake model going straight and fake calibration ******** - # note that this is worst case for MPC, since model will delay long mpc by one time step - radar = messaging.new_message('radarState') - control = messaging.new_message('controlsState') - car_state = messaging.new_message('carState') - model = messaging.new_message('modelV2') - a_lead = (v_lead - self.v_lead_prev)/self.ts - self.v_lead_prev = v_lead - - if self.lead_relevancy: - d_rel = np.maximum(0., self.distance_lead - self.distance) - v_rel = v_lead - self.speed - if self.only_radar: - status = True - elif prob > .5: - status = True - else: - status = False - else: - d_rel = 200. - v_rel = 0. - prob = 0.0 - status = False - - lead = log.RadarState.LeadData.new_message() - lead.dRel = float(d_rel) - lead.yRel = float(0.0) - lead.vRel = float(v_rel) - lead.aRel = float(a_lead - self.acceleration) - lead.vLead = float(v_lead) - lead.vLeadK = float(v_lead) - lead.aLeadK = float(a_lead) - # TODO use real radard logic for this - lead.aLeadTau = float(_LEAD_ACCEL_TAU) - lead.status = status - lead.modelProb = float(prob) - if not self.only_lead2: - radar.radarState.leadOne = lead - radar.radarState.leadTwo = lead - - # Simulate model predicting slightly faster speed - # this is to ensure lead policy is effective when model - # does not predict slowdown in e2e mode - position = log.XYZTData.new_message() - position.x = [float(x) for x in (self.speed + 0.5) * np.array(ModelConstants.T_IDXS)] - model.modelV2.position = position - velocity = log.XYZTData.new_message() - velocity.x = [float(x) for x in (self.speed + 0.5) * np.ones_like(ModelConstants.T_IDXS)] - model.modelV2.velocity = velocity - acceleration = log.XYZTData.new_message() - acceleration.x = [float(x) for x in np.zeros_like(ModelConstants.T_IDXS)] - model.modelV2.acceleration = acceleration - - control.controlsState.longControlState = LongCtrlState.pid if self.enabled else LongCtrlState.off - control.controlsState.vCruise = float(v_cruise * 3.6) - control.controlsState.experimentalMode = self.e2e - control.controlsState.forceDecel = self.force_decel - car_state.carState.vEgo = float(self.speed) - car_state.carState.standstill = self.speed < 0.01 - - # ******** get controlsState messages for plotting *** - sm = {'radarState': radar.radarState, - 'carState': car_state.carState, - 'controlsState': control.controlsState, - 'modelV2': model.modelV2} - self.planner.update(sm) - self.speed = self.planner.v_desired_filter.x - self.acceleration = self.planner.a_desired - self.speeds = self.planner.v_desired_trajectory.tolist() - fcw = self.planner.fcw - self.distance_lead = self.distance_lead + v_lead * self.ts - - # ******** run the car ******** - #print(self.distance, speed) - if self.speed <= 0: - self.speed = 0 - self.acceleration = 0 - self.distance = self.distance + self.speed * self.ts - - # *** radar model *** - if self.lead_relevancy: - d_rel = np.maximum(0., self.distance_lead - self.distance) - v_rel = v_lead - self.speed - else: - d_rel = 200. - v_rel = 0. - - # print at 5hz - # if (self.rk.frame % (self.rate // 5)) == 0: - # print("%2.2f sec %6.2f m %6.2f m/s %6.2f m/s2 lead_rel: %6.2f m %6.2f m/s" - # % (self.current_time, self.distance, self.speed, self.acceleration, d_rel, v_rel)) - - - # ******** update prevs ******** - self.rk.monitor_time() - - return { - "distance": self.distance, - "speed": self.speed, - "acceleration": self.acceleration, - "speeds": self.speeds, - "distance_lead": self.distance_lead, - "fcw": fcw, - } - -# simple engage in standalone mode -def plant_thread(): - plant = Plant() - while 1: - plant.step() - - -if __name__ == "__main__": - plant_thread() diff --git a/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py b/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py deleted file mode 100644 index 713b780..0000000 --- a/selfdrive/test/longitudinal_maneuvers/test_longitudinal.py +++ /dev/null @@ -1,160 +0,0 @@ -#!/usr/bin/env python3 -import itertools -import unittest -from parameterized import parameterized_class - -from openpilot.selfdrive.controls.lib.longitudinal_mpc_lib.long_mpc import STOP_DISTANCE -from openpilot.selfdrive.test.longitudinal_maneuvers.maneuver import Maneuver - - -# TODO: make new FCW tests -def create_maneuvers(kwargs): - maneuvers = [ - Maneuver( - 'approach stopped car at 25m/s, initial distance: 120m', - duration=20., - initial_speed=25., - lead_relevancy=True, - initial_distance_lead=120., - speed_lead_values=[30., 0.], - breakpoints=[0., 1.], - **kwargs, - ), - Maneuver( - 'approach stopped car at 20m/s, initial distance 90m', - duration=20., - initial_speed=20., - lead_relevancy=True, - initial_distance_lead=90., - speed_lead_values=[20., 0.], - breakpoints=[0., 1.], - **kwargs, - ), - Maneuver( - 'steady state following a car at 20m/s, then lead decel to 0mph at 1m/s^2', - duration=50., - initial_speed=20., - lead_relevancy=True, - initial_distance_lead=35., - speed_lead_values=[20., 20., 0.], - breakpoints=[0., 15., 35.0], - **kwargs, - ), - Maneuver( - 'steady state following a car at 20m/s, then lead decel to 0mph at 2m/s^2', - duration=50., - initial_speed=20., - lead_relevancy=True, - initial_distance_lead=35., - speed_lead_values=[20., 20., 0.], - breakpoints=[0., 15., 25.0], - **kwargs, - ), - Maneuver( - 'steady state following a car at 20m/s, then lead decel to 0mph at 3m/s^2', - duration=50., - initial_speed=20., - lead_relevancy=True, - initial_distance_lead=35., - speed_lead_values=[20., 20., 0.], - breakpoints=[0., 15., 21.66], - **kwargs, - ), - Maneuver( - 'steady state following a car at 20m/s, then lead decel to 0mph at 3+m/s^2', - duration=40., - initial_speed=20., - lead_relevancy=True, - initial_distance_lead=35., - speed_lead_values=[20., 20., 0.], - prob_lead_values=[0., 1., 1.], - cruise_values=[20., 20., 20.], - breakpoints=[2., 2.01, 8.8], - **kwargs, - ), - Maneuver( - "approach stopped car at 20m/s, with prob_lead_values", - duration=30., - initial_speed=20., - lead_relevancy=True, - initial_distance_lead=120., - speed_lead_values=[0.0, 0., 0.], - prob_lead_values=[0.0, 0., 1.], - cruise_values=[20., 20., 20.], - breakpoints=[0.0, 2., 2.01], - **kwargs, - ), - Maneuver( - "approach slower cut-in car at 20m/s", - duration=20., - initial_speed=20., - lead_relevancy=True, - initial_distance_lead=50., - speed_lead_values=[15., 15.], - breakpoints=[1., 11.], - only_lead2=True, - **kwargs, - ), - Maneuver( - "stay stopped behind radar override lead", - duration=20., - initial_speed=0., - lead_relevancy=True, - initial_distance_lead=10., - speed_lead_values=[0., 0.], - prob_lead_values=[0., 0.], - breakpoints=[1., 11.], - only_radar=True, - **kwargs, - ), - Maneuver( - "NaN recovery", - duration=30., - initial_speed=15., - lead_relevancy=True, - initial_distance_lead=60., - speed_lead_values=[0., 0., 0.0], - breakpoints=[1., 1.01, 11.], - cruise_values=[float("nan"), 15., 15.], - **kwargs, - ), - Maneuver( - 'cruising at 25 m/s while disabled', - duration=20., - initial_speed=25., - lead_relevancy=False, - enabled=False, - **kwargs, - ), - ] - if not kwargs['force_decel']: - # controls relies on planner commanding to move for stock-ACC resume spamming - maneuvers.append(Maneuver( - "resume from a stop", - duration=20., - initial_speed=0., - lead_relevancy=True, - initial_distance_lead=STOP_DISTANCE, - speed_lead_values=[0., 0., 2.], - breakpoints=[1., 10., 15.], - ensure_start=True, - **kwargs, - )) - return maneuvers - - -@parameterized_class(("e2e", "force_decel"), itertools.product([True, False], repeat=2)) -class LongitudinalControl(unittest.TestCase): - e2e: bool - force_decel: bool - - def test_maneuver(self): - for maneuver in create_maneuvers({"e2e": self.e2e, "force_decel": self.force_decel}): - with self.subTest(title=maneuver.title, e2e=maneuver.e2e, force_decel=maneuver.force_decel): - print(maneuver.title, f'in {"e2e" if maneuver.e2e else "acc"} mode') - valid, _ = maneuver.evaluate() - self.assertTrue(valid) - - -if __name__ == "__main__": - unittest.main(failfast=True) diff --git a/selfdrive/test/loop_until_fail.sh b/selfdrive/test/loop_until_fail.sh deleted file mode 100644 index b73009d..0000000 --- a/selfdrive/test/loop_until_fail.sh +++ /dev/null @@ -1,8 +0,0 @@ -#!/usr/bin/env bash -set -e - -# Loop something forever until it fails, for verifying new tests - -while true; do - $@ -done diff --git a/selfdrive/test/process_replay/.gitignore b/selfdrive/test/process_replay/.gitignore deleted file mode 100644 index 63c37e6..0000000 --- a/selfdrive/test/process_replay/.gitignore +++ /dev/null @@ -1,2 +0,0 @@ -fakedata/ -debayer_diff.txt diff --git a/selfdrive/test/process_replay/README.md b/selfdrive/test/process_replay/README.md deleted file mode 100644 index 008a901..0000000 --- a/selfdrive/test/process_replay/README.md +++ /dev/null @@ -1,126 +0,0 @@ -# Process replay - -Process replay is a regression test designed to identify any changes in the output of a process. This test replays a segment through individual processes and compares the output to a known good replay. Each make is represented in the test with a segment. - -If the test fails, make sure that you didn't unintentionally change anything. If there are intentional changes, the reference logs will be updated. - -Use `test_processes.py` to run the test locally. -Use `FILEREADER_CACHE='1' test_processes.py` to cache log files. - -Currently the following processes are tested: - -* controlsd -* radard -* plannerd -* calibrationd -* dmonitoringd -* locationd -* paramsd -* ubloxd -* torqued - -### Usage -``` -Usage: test_processes.py [-h] [--whitelist-procs PROCS] [--whitelist-cars CARS] [--blacklist-procs PROCS] - [--blacklist-cars CARS] [--ignore-fields FIELDS] [--ignore-msgs MSGS] [--update-refs] [--upload-only] -Regression test to identify changes in a process's output -optional arguments: - -h, --help show this help message and exit - --whitelist-procs PROCS Whitelist given processes from the test (e.g. controlsd) - --whitelist-cars WHITELIST_CARS Whitelist given cars from the test (e.g. HONDA) - --blacklist-procs BLACKLIST_PROCS Blacklist given processes from the test (e.g. controlsd) - --blacklist-cars BLACKLIST_CARS Blacklist given cars from the test (e.g. HONDA) - --ignore-fields IGNORE_FIELDS Extra fields or msgs to ignore (e.g. carState.events) - --ignore-msgs IGNORE_MSGS Msgs to ignore (e.g. onroadEvents) - --update-refs Updates reference logs using current commit - --upload-only Skips testing processes and uploads logs from previous test run -``` - -## Forks - -openpilot forks can use this test with their own reference logs, by default `test_proccess.py` saves logs locally. - -To generate new logs: - -`./test_processes.py` - -Then, check in the new logs using git-lfs. Make sure to also update the `ref_commit` file to the current commit. - -## API - -Process replay test suite exposes programmatic APIs for simultaneously running processes or groups of processes on provided logs. - -```py -def replay_process_with_name(name: Union[str, Iterable[str]], lr: LogIterable, *args, **kwargs) -> List[capnp._DynamicStructReader]: - -def replay_process( - cfg: Union[ProcessConfig, Iterable[ProcessConfig]], lr: LogIterable, frs: Optional[Dict[str, Any]] = None, - fingerprint: Optional[str] = None, return_all_logs: bool = False, custom_params: Optional[Dict[str, Any]] = None, disable_progress: bool = False -) -> List[capnp._DynamicStructReader]: -``` - -Example usage: -```py -from openpilot.selfdrive.test.process_replay import replay_process_with_name -from openpilot.tools.lib.logreader import LogReader - -lr = LogReader(...) - -# provide a name of the process to replay -output_logs = replay_process_with_name('locationd', lr) - -# or list of names -output_logs = replay_process_with_name(['ubloxd', 'locationd'], lr) -``` - -Supported processes: -* controlsd -* radard -* plannerd -* calibrationd -* dmonitoringd -* locationd -* paramsd -* ubloxd -* torqued -* modeld -* dmonitoringmodeld - -Certain processes may require an initial state, which is usually supplied within `Params` and persisting from segment to segment (e.g CalibrationParams, LiveParameters). The `custom_params` is dictionary used to prepopulate `Params` with arbitrary values. The `get_custom_params_from_lr` helper is provided to fetch meaningful values from log files. - -```py -from openpilot.selfdrive.test.process_replay import get_custom_params_from_lr - -previous_segment_lr = LogReader(...) -current_segment_lr = LogReader(...) - -custom_params = get_custom_params_from_lr(previous_segment_lr, 'last') - -output_logs = replay_process_with_name('calibrationd', lr, custom_params=custom_params) -``` - -Replaying processes that use VisionIPC (e.g. modeld, dmonitoringmodeld) require additional `frs` dictionary with camera states as keys and `FrameReader` objects as values. - -```py -from openpilot.tools.lib.framereader import FrameReader - -frs = { - 'roadCameraState': FrameReader(...), - 'wideRoadCameraState': FrameReader(...), - 'driverCameraState': FrameReader(...), -} - -output_logs = replay_process_with_name(['modeld', 'dmonitoringmodeld'], lr, frs=frs) -``` - -To capture stdout/stderr of the replayed process, `captured_output_store` can be provided. - -```py -output_store = dict() -# pass dictionary by reference, it will be filled with standard outputs - even if process replay fails -output_logs = replay_process_with_name(['radard', 'plannerd'], lr, captured_output_store=output_store) - -# entries with captured output in format { 'out': '...', 'err': '...' } will be added to provided dictionary for each replayed process -print(output_store['radard']['out']) # radard stdout -print(output_store['radard']['err']) # radard stderr -``` diff --git a/selfdrive/test/process_replay/__init__.py b/selfdrive/test/process_replay/__init__.py deleted file mode 100644 index b994277..0000000 --- a/selfdrive/test/process_replay/__init__.py +++ /dev/null @@ -1,2 +0,0 @@ -from openpilot.selfdrive.test.process_replay.process_replay import CONFIGS, get_process_config, get_custom_params_from_lr, \ - replay_process, replay_process_with_name # noqa: F401 diff --git a/selfdrive/test/process_replay/capture.py b/selfdrive/test/process_replay/capture.py deleted file mode 100644 index 90c279e..0000000 --- a/selfdrive/test/process_replay/capture.py +++ /dev/null @@ -1,59 +0,0 @@ -import os -import sys - -from typing import no_type_check - -class FdRedirect: - def __init__(self, file_prefix: str, fd: int): - fname = os.path.join("/tmp", f"{file_prefix}.{fd}") - if os.path.exists(fname): - os.unlink(fname) - self.dest_fd = os.open(fname, os.O_WRONLY | os.O_CREAT) - self.dest_fname = fname - self.source_fd = fd - os.set_inheritable(self.dest_fd, True) - - def __del__(self): - os.close(self.dest_fd) - - def purge(self) -> None: - os.unlink(self.dest_fname) - - def read(self) -> bytes: - with open(self.dest_fname, "rb") as f: - return f.read() or b"" - - def link(self) -> None: - os.dup2(self.dest_fd, self.source_fd) - - -class ProcessOutputCapture: - def __init__(self, proc_name: str, prefix: str): - prefix = f"{proc_name}_{prefix}" - self.stdout_redirect = FdRedirect(prefix, 1) - self.stderr_redirect = FdRedirect(prefix, 2) - - def __del__(self): - self.stdout_redirect.purge() - self.stderr_redirect.purge() - - @no_type_check # ipython classes have incompatible signatures - def link_with_current_proc(self) -> None: - try: - # prevent ipykernel from redirecting stdout/stderr of python subprocesses - from ipykernel.iostream import OutStream - if isinstance(sys.stdout, OutStream): - sys.stdout = sys.__stdout__ - if isinstance(sys.stderr, OutStream): - sys.stderr = sys.__stderr__ - except ImportError: - pass - - # link stdout/stderr to the fifo - self.stdout_redirect.link() - self.stderr_redirect.link() - - def read_outerr(self) -> tuple[str, str]: - out_str = self.stdout_redirect.read().decode() - err_str = self.stderr_redirect.read().decode() - return out_str, err_str diff --git a/selfdrive/test/process_replay/compare_logs.py b/selfdrive/test/process_replay/compare_logs.py deleted file mode 100644 index 673f3b4..0000000 --- a/selfdrive/test/process_replay/compare_logs.py +++ /dev/null @@ -1,150 +0,0 @@ -#!/usr/bin/env python3 -import sys -import math -import capnp -import numbers -import dictdiffer -from collections import Counter - -from openpilot.tools.lib.logreader import LogReader - -EPSILON = sys.float_info.epsilon - - -def remove_ignored_fields(msg, ignore): - msg = msg.as_builder() - for key in ignore: - attr = msg - keys = key.split(".") - if msg.which() != keys[0] and len(keys) > 1: - continue - - for k in keys[:-1]: - # indexing into list - if k.isdigit(): - attr = attr[int(k)] - else: - attr = getattr(attr, k) - - v = getattr(attr, keys[-1]) - if isinstance(v, bool): - val = False - elif isinstance(v, numbers.Number): - val = 0 - elif isinstance(v, (list, capnp.lib.capnp._DynamicListBuilder)): - val = [] - else: - raise NotImplementedError(f"Unknown type: {type(v)}") - setattr(attr, keys[-1], val) - return msg - - -def compare_logs(log1, log2, ignore_fields=None, ignore_msgs=None, tolerance=None,): - if ignore_fields is None: - ignore_fields = [] - if ignore_msgs is None: - ignore_msgs = [] - tolerance = EPSILON if tolerance is None else tolerance - - log1, log2 = ( - [m for m in log if m.which() not in ignore_msgs] - for log in (log1, log2) - ) - - if len(log1) != len(log2): - cnt1 = Counter(m.which() for m in log1) - cnt2 = Counter(m.which() for m in log2) - raise Exception(f"logs are not same length: {len(log1)} VS {len(log2)}\n\t\t{cnt1}\n\t\t{cnt2}") - - diff = [] - for msg1, msg2 in zip(log1, log2, strict=True): - if msg1.which() != msg2.which(): - raise Exception("msgs not aligned between logs") - - msg1 = remove_ignored_fields(msg1, ignore_fields) - msg2 = remove_ignored_fields(msg2, ignore_fields) - - if msg1.to_bytes() != msg2.to_bytes(): - msg1_dict = msg1.as_reader().to_dict(verbose=True) - msg2_dict = msg2.as_reader().to_dict(verbose=True) - - dd = dictdiffer.diff(msg1_dict, msg2_dict, ignore=ignore_fields) - - # Dictdiffer only supports relative tolerance, we also want to check for absolute - # TODO: add this to dictdiffer - def outside_tolerance(diff): - try: - if diff[0] == "change": - a, b = diff[2] - finite = math.isfinite(a) and math.isfinite(b) - if finite and isinstance(a, numbers.Number) and isinstance(b, numbers.Number): - return abs(a - b) > max(tolerance, tolerance * max(abs(a), abs(b))) - except TypeError: - pass - return True - - dd = list(filter(outside_tolerance, dd)) - - diff.extend(dd) - return diff - - -def format_process_diff(diff): - diff_short, diff_long = "", "" - - if isinstance(diff, str): - diff_short += f" {diff}\n" - diff_long += f"\t{diff}\n" - else: - cnt: dict[str, int] = {} - for d in diff: - diff_long += f"\t{str(d)}\n" - - k = str(d[1]) - cnt[k] = 1 if k not in cnt else cnt[k] + 1 - - for k, v in sorted(cnt.items()): - diff_short += f" {k}: {v}\n" - - return diff_short, diff_long - - -def format_diff(results, log_paths, ref_commit): - diff_short, diff_long = "", "" - diff_long += f"***** tested against commit {ref_commit} *****\n" - - failed = False - for segment, result in list(results.items()): - diff_short += f"***** results for segment {segment} *****\n" - diff_long += f"***** differences for segment {segment} *****\n" - - for proc, diff in list(result.items()): - diff_long += f"*** process: {proc} ***\n" - diff_long += f"\tref: {log_paths[segment][proc]['ref']}\n" - diff_long += f"\tnew: {log_paths[segment][proc]['new']}\n\n" - - diff_short += f" {proc}\n" - - if isinstance(diff, str) or len(diff): - diff_short += f" ref: {log_paths[segment][proc]['ref']}\n" - diff_short += f" new: {log_paths[segment][proc]['new']}\n\n" - failed = True - - proc_diff_short, proc_diff_long = format_process_diff(diff) - - diff_long += proc_diff_long - diff_short += proc_diff_short - - return diff_short, diff_long, failed - - -if __name__ == "__main__": - log1 = list(LogReader(sys.argv[1])) - log2 = list(LogReader(sys.argv[2])) - ignore_fields = sys.argv[3:] or ["logMonoTime", "controlsState.startMonoTime", "controlsState.cumLagMs"] - results = {"segment": {"proc": compare_logs(log1, log2, ignore_fields)}} - log_paths = {"segment": {"proc": {"ref": sys.argv[1], "new": sys.argv[2]}}} - diff_short, diff_long, failed = format_diff(results, log_paths, None) - - print(diff_long) - print(diff_short) diff --git a/selfdrive/test/process_replay/debayer_replay_ref_commit b/selfdrive/test/process_replay/debayer_replay_ref_commit deleted file mode 100644 index 551fc68..0000000 --- a/selfdrive/test/process_replay/debayer_replay_ref_commit +++ /dev/null @@ -1 +0,0 @@ -8f9ba7540b4549b4a57312129b8ff678d045f70f \ No newline at end of file diff --git a/selfdrive/test/process_replay/migration.py b/selfdrive/test/process_replay/migration.py deleted file mode 100644 index ef74314..0000000 --- a/selfdrive/test/process_replay/migration.py +++ /dev/null @@ -1,203 +0,0 @@ -from collections import defaultdict - -from cereal import messaging -from openpilot.selfdrive.test.process_replay.vision_meta import meta_from_encode_index -from openpilot.selfdrive.car.toyota.values import EPS_SCALE -from openpilot.selfdrive.manager.process_config import managed_processes -from panda import Panda - - -def migrate_all(lr, old_logtime=False, manager_states=False, panda_states=False, camera_states=False): - msgs = migrate_sensorEvents(lr, old_logtime) - msgs = migrate_carParams(msgs, old_logtime) - if manager_states: - msgs = migrate_managerState(msgs) - if panda_states: - msgs = migrate_pandaStates(msgs) - msgs = migrate_peripheralState(msgs) - if camera_states: - msgs = migrate_cameraStates(msgs) - - return msgs - - -def migrate_managerState(lr): - all_msgs = [] - for msg in lr: - if msg.which() != "managerState": - all_msgs.append(msg) - continue - - new_msg = msg.as_builder() - new_msg.managerState.processes = [{'name': name, 'running': True} for name in managed_processes] - all_msgs.append(new_msg.as_reader()) - - return all_msgs - - -def migrate_pandaStates(lr): - all_msgs = [] - # TODO: safety param migration should be handled automatically - safety_param_migration = { - "TOYOTA PRIUS 2017": EPS_SCALE["TOYOTA PRIUS 2017"] | Panda.FLAG_TOYOTA_STOCK_LONGITUDINAL, - "TOYOTA RAV4 2017": EPS_SCALE["TOYOTA RAV4 2017"] | Panda.FLAG_TOYOTA_ALT_BRAKE | Panda.FLAG_TOYOTA_GAS_INTERCEPTOR, - "KIA EV6 2022": Panda.FLAG_HYUNDAI_EV_GAS | Panda.FLAG_HYUNDAI_CANFD_HDA2, - } - - # Migrate safety param base on carState - CP = next((m.carParams for m in lr if m.which() == 'carParams'), None) - assert CP is not None, "carParams message not found" - if CP.carFingerprint in safety_param_migration: - safety_param = safety_param_migration[CP.carFingerprint] - elif len(CP.safetyConfigs): - safety_param = CP.safetyConfigs[0].safetyParam - if CP.safetyConfigs[0].safetyParamDEPRECATED != 0: - safety_param = CP.safetyConfigs[0].safetyParamDEPRECATED - else: - safety_param = CP.safetyParamDEPRECATED - - for msg in lr: - if msg.which() == 'pandaStateDEPRECATED': - new_msg = messaging.new_message('pandaStates', 1) - new_msg.valid = msg.valid - new_msg.logMonoTime = msg.logMonoTime - new_msg.pandaStates[0] = msg.pandaStateDEPRECATED - new_msg.pandaStates[0].safetyParam = safety_param - all_msgs.append(new_msg.as_reader()) - elif msg.which() == 'pandaStates': - new_msg = msg.as_builder() - new_msg.pandaStates[-1].safetyParam = safety_param - all_msgs.append(new_msg.as_reader()) - else: - all_msgs.append(msg) - - return all_msgs - - -def migrate_peripheralState(lr): - if any(msg.which() == "peripheralState" for msg in lr): - return lr - - all_msg = [] - for msg in lr: - all_msg.append(msg) - if msg.which() not in ["pandaStates", "pandaStateDEPRECATED"]: - continue - - new_msg = messaging.new_message("peripheralState") - new_msg.valid = msg.valid - new_msg.logMonoTime = msg.logMonoTime - all_msg.append(new_msg.as_reader()) - - return all_msg - - -def migrate_cameraStates(lr): - all_msgs = [] - frame_to_encode_id = defaultdict(dict) - # just for encodeId fallback mechanism - min_frame_id = defaultdict(lambda: float('inf')) - - for msg in lr: - if msg.which() not in ["roadEncodeIdx", "wideRoadEncodeIdx", "driverEncodeIdx"]: - continue - - encode_index = getattr(msg, msg.which()) - meta = meta_from_encode_index(msg.which()) - - assert encode_index.segmentId < 1200, f"Encoder index segmentId greater that 1200: {msg.which()} {encode_index.segmentId}" - frame_to_encode_id[meta.camera_state][encode_index.frameId] = encode_index.segmentId - - for msg in lr: - if msg.which() not in ["roadCameraState", "wideRoadCameraState", "driverCameraState"]: - all_msgs.append(msg) - continue - - camera_state = getattr(msg, msg.which()) - min_frame_id[msg.which()] = min(min_frame_id[msg.which()], camera_state.frameId) - - encode_id = frame_to_encode_id[msg.which()].get(camera_state.frameId) - if encode_id is None: - print(f"Missing encoded frame for camera feed {msg.which()} with frameId: {camera_state.frameId}") - if len(frame_to_encode_id[msg.which()]) != 0: - continue - - # fallback mechanism for logs without encodeIdx (e.g. logs from before 2022 with dcamera recording disabled) - # try to fake encode_id by subtracting lowest frameId - encode_id = camera_state.frameId - min_frame_id[msg.which()] - print(f"Faking encodeId to {encode_id} for camera feed {msg.which()} with frameId: {camera_state.frameId}") - - new_msg = messaging.new_message(msg.which()) - new_camera_state = getattr(new_msg, new_msg.which()) - new_camera_state.frameId = encode_id - new_camera_state.encodeId = encode_id - # timestampSof was added later so it might be missing on some old segments - if camera_state.timestampSof == 0 and camera_state.timestampEof > 25000000: - new_camera_state.timestampSof = camera_state.timestampEof - 18000000 - else: - new_camera_state.timestampSof = camera_state.timestampSof - new_camera_state.timestampEof = camera_state.timestampEof - new_msg.logMonoTime = msg.logMonoTime - new_msg.valid = msg.valid - - all_msgs.append(new_msg.as_reader()) - - return all_msgs - - -def migrate_carParams(lr, old_logtime=False): - all_msgs = [] - for msg in lr: - if msg.which() == 'carParams': - CP = messaging.new_message('carParams') - CP.valid = True - CP.carParams = msg.carParams.as_builder() - for car_fw in CP.carParams.carFw: - car_fw.brand = CP.carParams.carName - if old_logtime: - CP.logMonoTime = msg.logMonoTime - msg = CP.as_reader() - all_msgs.append(msg) - - return all_msgs - - -def migrate_sensorEvents(lr, old_logtime=False): - all_msgs = [] - for msg in lr: - if msg.which() != 'sensorEventsDEPRECATED': - all_msgs.append(msg) - continue - - # migrate to split sensor events - for evt in msg.sensorEventsDEPRECATED: - # build new message for each sensor type - sensor_service = '' - if evt.which() == 'acceleration': - sensor_service = 'accelerometer' - elif evt.which() == 'gyro' or evt.which() == 'gyroUncalibrated': - sensor_service = 'gyroscope' - elif evt.which() == 'light' or evt.which() == 'proximity': - sensor_service = 'lightSensor' - elif evt.which() == 'magnetic' or evt.which() == 'magneticUncalibrated': - sensor_service = 'magnetometer' - elif evt.which() == 'temperature': - sensor_service = 'temperatureSensor' - - m = messaging.new_message(sensor_service) - m.valid = True - if old_logtime: - m.logMonoTime = msg.logMonoTime - - m_dat = getattr(m, sensor_service) - m_dat.version = evt.version - m_dat.sensor = evt.sensor - m_dat.type = evt.type - m_dat.source = evt.source - if old_logtime: - m_dat.timestamp = evt.timestamp - setattr(m_dat, evt.which(), getattr(evt, evt.which())) - - all_msgs.append(m.as_reader()) - - return all_msgs diff --git a/selfdrive/test/process_replay/model_replay.py b/selfdrive/test/process_replay/model_replay.py deleted file mode 100644 index 97b7c7c..0000000 --- a/selfdrive/test/process_replay/model_replay.py +++ /dev/null @@ -1,249 +0,0 @@ -#!/usr/bin/env python3 -import os -import sys -import time -from collections import defaultdict -from typing import Any - -import cereal.messaging as messaging -from openpilot.common.params import Params -from openpilot.system.hardware import PC -from openpilot.selfdrive.manager.process_config import managed_processes -from openpilot.tools.lib.openpilotci import BASE_URL, get_url -from openpilot.selfdrive.test.process_replay.compare_logs import compare_logs, format_diff -from openpilot.selfdrive.test.process_replay.process_replay import get_process_config, replay_process -from openpilot.system.version import get_commit -from openpilot.tools.lib.framereader import FrameReader -from openpilot.tools.lib.logreader import LogReader -from openpilot.tools.lib.helpers import save_log - -TEST_ROUTE = "2f4452b03ccb98f0|2022-12-03--13-45-30" -SEGMENT = 6 -MAX_FRAMES = 100 if PC else 600 -NAV_FRAMES = 50 - -NO_NAV = "NO_NAV" in os.environ -NO_MODEL = "NO_MODEL" in os.environ -SEND_EXTRA_INPUTS = bool(int(os.getenv("SEND_EXTRA_INPUTS", "0"))) - - -def get_log_fn(ref_commit, test_route): - return f"{test_route}_model_tici_{ref_commit}.bz2" - - -def trim_logs_to_max_frames(logs, max_frames, frs_types, include_all_types): - all_msgs = [] - cam_state_counts = defaultdict(int) - # keep adding messages until cam states are equal to MAX_FRAMES - for msg in sorted(logs, key=lambda m: m.logMonoTime): - all_msgs.append(msg) - if msg.which() in frs_types: - cam_state_counts[msg.which()] += 1 - - if all(cam_state_counts[state] == max_frames for state in frs_types): - break - - if len(include_all_types) != 0: - other_msgs = [m for m in logs if m.which() in include_all_types] - all_msgs.extend(other_msgs) - - return all_msgs - - -def nav_model_replay(lr): - sm = messaging.SubMaster(['navModel', 'navThumbnail', 'mapRenderState']) - pm = messaging.PubMaster(['liveLocationKalman', 'navRoute']) - - nav = [m for m in lr if m.which() == 'navRoute'] - llk = [m for m in lr if m.which() == 'liveLocationKalman'] - assert len(nav) > 0 and len(llk) >= NAV_FRAMES and nav[0].logMonoTime < llk[-NAV_FRAMES].logMonoTime - - log_msgs = [] - try: - assert "MAPBOX_TOKEN" in os.environ - os.environ['MAP_RENDER_TEST_MODE'] = '1' - Params().put_bool('DmModelInitialized', True) - managed_processes['mapsd'].start() - managed_processes['navmodeld'].start() - - # setup position and route - for _ in range(10): - for s in (llk[-NAV_FRAMES], nav[0]): - pm.send(s.which(), s.as_builder().to_bytes()) - sm.update(1000) - if sm.updated['navModel']: - break - time.sleep(1) - - if not sm.updated['navModel']: - raise Exception("no navmodeld outputs, failed to initialize") - - # drain - time.sleep(2) - sm.update(0) - - # run replay - for n in range(len(llk) - NAV_FRAMES, len(llk)): - pm.send(llk[n].which(), llk[n].as_builder().to_bytes()) - m = messaging.recv_one(sm.sock['navThumbnail']) - assert m is not None, f"no navThumbnail, frame={n}" - log_msgs.append(m) - - m = messaging.recv_one(sm.sock['mapRenderState']) - assert m is not None, f"no mapRenderState, frame={n}" - log_msgs.append(m) - - m = messaging.recv_one(sm.sock['navModel']) - assert m is not None, f"no navModel response, frame={n}" - log_msgs.append(m) - finally: - managed_processes['mapsd'].stop() - managed_processes['navmodeld'].stop() - - return log_msgs - - -def model_replay(lr, frs): - # modeld is using frame pairs - modeld_logs = trim_logs_to_max_frames(lr, MAX_FRAMES, {"roadCameraState", "wideRoadCameraState"}, {"roadEncodeIdx", "wideRoadEncodeIdx", "carParams"}) - dmodeld_logs = trim_logs_to_max_frames(lr, MAX_FRAMES, {"driverCameraState"}, {"driverEncodeIdx", "carParams"}) - if not SEND_EXTRA_INPUTS: - modeld_logs = [msg for msg in modeld_logs if msg.which() not in ["liveCalibration",]] - dmodeld_logs = [msg for msg in dmodeld_logs if msg.which() not in ["liveCalibration",]] - # initial calibration - cal_msg = next(msg for msg in lr if msg.which() == "liveCalibration").as_builder() - cal_msg.logMonoTime = lr[0].logMonoTime - modeld_logs.insert(0, cal_msg.as_reader()) - dmodeld_logs.insert(0, cal_msg.as_reader()) - - modeld = get_process_config("modeld") - dmonitoringmodeld = get_process_config("dmonitoringmodeld") - - modeld_msgs = replay_process(modeld, modeld_logs, frs) - dmonitoringmodeld_msgs = replay_process(dmonitoringmodeld, dmodeld_logs, frs) - return modeld_msgs + dmonitoringmodeld_msgs - - -if __name__ == "__main__": - update = "--update" in sys.argv - replay_dir = os.path.dirname(os.path.abspath(__file__)) - ref_commit_fn = os.path.join(replay_dir, "model_replay_ref_commit") - - # load logs - lr = list(LogReader(get_url(TEST_ROUTE, SEGMENT))) - frs = { - 'roadCameraState': FrameReader(get_url(TEST_ROUTE, SEGMENT, log_type="fcamera"), readahead=True), - 'driverCameraState': FrameReader(get_url(TEST_ROUTE, SEGMENT, log_type="dcamera"), readahead=True), - 'wideRoadCameraState': FrameReader(get_url(TEST_ROUTE, SEGMENT, log_type="ecamera"), readahead=True) - } - - # Update tile refs - if update: - import urllib - import requests - import threading - import http.server - from openpilot.tools.lib.openpilotci import upload_bytes - os.environ['MAPS_HOST'] = 'http://localhost:5000' - - class HTTPRequestHandler(http.server.BaseHTTPRequestHandler): - def do_GET(self): - assert len(self.path) > 10 # Sanity check on path length - r = requests.get(f'https://api.mapbox.com{self.path}', timeout=30) - upload_bytes(r.content, urllib.parse.urlparse(self.path).path.lstrip('/')) - self.send_response(r.status_code) - self.send_header('Content-type','text/html') - self.end_headers() - self.wfile.write(r.content) - - server = http.server.HTTPServer(("127.0.0.1", 5000), HTTPRequestHandler) - thread = threading.Thread(None, server.serve_forever, daemon=True) - thread.start() - else: - os.environ['MAPS_HOST'] = BASE_URL.rstrip('/') - - log_msgs = [] - # run replays - if not NO_MODEL: - log_msgs += model_replay(lr, frs) - if not NO_NAV: - log_msgs += nav_model_replay(lr) - - # get diff - failed = False - if not update: - with open(ref_commit_fn) as f: - ref_commit = f.read().strip() - log_fn = get_log_fn(ref_commit, TEST_ROUTE) - try: - all_logs = list(LogReader(BASE_URL + log_fn)) - cmp_log = [] - - # logs are ordered based on type: modelV2, driverStateV2, nav messages (navThumbnail, mapRenderState, navModel) - if not NO_MODEL: - model_start_index = next(i for i, m in enumerate(all_logs) if m.which() in ("modelV2", "cameraOdometry")) - cmp_log += all_logs[model_start_index:model_start_index + MAX_FRAMES*2] - dmon_start_index = next(i for i, m in enumerate(all_logs) if m.which() == "driverStateV2") - cmp_log += all_logs[dmon_start_index:dmon_start_index + MAX_FRAMES] - if not NO_NAV: - nav_start_index = next(i for i, m in enumerate(all_logs) if m.which() in ["navThumbnail", "mapRenderState", "navModel"]) - nav_logs = all_logs[nav_start_index:nav_start_index + NAV_FRAMES*3] - cmp_log += nav_logs - - ignore = [ - 'logMonoTime', - 'modelV2.frameDropPerc', - 'modelV2.modelExecutionTime', - 'driverStateV2.modelExecutionTime', - 'driverStateV2.dspExecutionTime', - 'navModel.dspExecutionTime', - 'navModel.modelExecutionTime', - 'navThumbnail.timestampEof', - 'mapRenderState.locationMonoTime', - 'mapRenderState.renderTime', - ] - if PC: - ignore += [ - 'modelV2.laneLines.0.t', - 'modelV2.laneLines.1.t', - 'modelV2.laneLines.2.t', - 'modelV2.laneLines.3.t', - 'modelV2.roadEdges.0.t', - 'modelV2.roadEdges.1.t', - ] - # TODO this tolerance is absurdly large - tolerance = 2.0 if PC else None - results: Any = {TEST_ROUTE: {}} - log_paths: Any = {TEST_ROUTE: {"models": {'ref': BASE_URL + log_fn, 'new': log_fn}}} - results[TEST_ROUTE]["models"] = compare_logs(cmp_log, log_msgs, tolerance=tolerance, ignore_fields=ignore) - diff_short, diff_long, failed = format_diff(results, log_paths, ref_commit) - - print(diff_long) - print('-------------\n'*5) - print(diff_short) - with open("model_diff.txt", "w") as f: - f.write(diff_long) - except Exception as e: - print(str(e)) - failed = True - - # upload new refs - if (update or failed) and not PC: - from openpilot.tools.lib.openpilotci import upload_file - - print("Uploading new refs") - - new_commit = get_commit() - log_fn = get_log_fn(new_commit, TEST_ROUTE) - save_log(log_fn, log_msgs) - try: - upload_file(log_fn, os.path.basename(log_fn)) - except Exception as e: - print("failed to upload", e) - - with open(ref_commit_fn, 'w') as f: - f.write(str(new_commit)) - - print("\n\nNew ref commit: ", new_commit) - - sys.exit(int(failed)) diff --git a/selfdrive/test/process_replay/model_replay_ref_commit b/selfdrive/test/process_replay/model_replay_ref_commit deleted file mode 100644 index 786c2f2..0000000 --- a/selfdrive/test/process_replay/model_replay_ref_commit +++ /dev/null @@ -1 +0,0 @@ -e8b359a82316e6dfce3b6fb0fb9684431bfa0a1b diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py deleted file mode 100644 index 5119be0..0000000 --- a/selfdrive/test/process_replay/process_replay.py +++ /dev/null @@ -1,800 +0,0 @@ -#!/usr/bin/env python3 -import os -import time -import copy -import json -import heapq -import signal -import platform -from collections import OrderedDict -from dataclasses import dataclass, field -from typing import Any -from collections.abc import Callable, Iterable -from tqdm import tqdm -import capnp - -import cereal.messaging as messaging -from cereal import car -from cereal.services import SERVICE_LIST -from cereal.visionipc import VisionIpcServer, get_endpoint_name as vipc_get_endpoint_name -from openpilot.common.params import Params -from openpilot.common.prefix import OpenpilotPrefix -from openpilot.common.timeout import Timeout -from openpilot.common.realtime import DT_CTRL -from panda.python import ALTERNATIVE_EXPERIENCE -from openpilot.selfdrive.car.car_helpers import get_car, interfaces -from openpilot.selfdrive.manager.process_config import managed_processes -from openpilot.selfdrive.test.process_replay.vision_meta import meta_from_camera_state, available_streams -from openpilot.selfdrive.test.process_replay.migration import migrate_all -from openpilot.selfdrive.test.process_replay.capture import ProcessOutputCapture -from openpilot.tools.lib.logreader import LogIterable -from openpilot.tools.lib.framereader import BaseFrameReader - -# Numpy gives different results based on CPU features after version 19 -NUMPY_TOLERANCE = 1e-7 -PROC_REPLAY_DIR = os.path.dirname(os.path.abspath(__file__)) -FAKEDATA = os.path.join(PROC_REPLAY_DIR, "fakedata/") - -class DummySocket: - def __init__(self): - self.data: list[bytes] = [] - - def receive(self, non_blocking: bool = False) -> bytes | None: - if non_blocking: - return None - - return self.data.pop() - - def send(self, data: bytes): - self.data.append(data) - -class LauncherWithCapture: - def __init__(self, capture: ProcessOutputCapture, launcher: Callable): - self.capture = capture - self.launcher = launcher - - def __call__(self, *args, **kwargs): - self.capture.link_with_current_proc() - self.launcher(*args, **kwargs) - - -class ReplayContext: - def __init__(self, cfg): - self.proc_name = cfg.proc_name - self.pubs = cfg.pubs - self.main_pub = cfg.main_pub - self.main_pub_drained = cfg.main_pub_drained - self.unlocked_pubs = cfg.unlocked_pubs - assert(len(self.pubs) != 0 or self.main_pub is not None) - - def __enter__(self): - self.open_context() - - return self - - def __exit__(self, exc_type, exc_obj, exc_tb): - self.close_context() - - def open_context(self): - messaging.toggle_fake_events(True) - messaging.set_fake_prefix(self.proc_name) - - if self.main_pub is None: - self.events = OrderedDict() - pubs_with_events = [pub for pub in self.pubs if pub not in self.unlocked_pubs] - for pub in pubs_with_events: - self.events[pub] = messaging.fake_event_handle(pub, enable=True) - else: - self.events = {self.main_pub: messaging.fake_event_handle(self.main_pub, enable=True)} - - def close_context(self): - del self.events - - messaging.toggle_fake_events(False) - messaging.delete_fake_prefix() - - @property - def all_recv_called_events(self): - return [man.recv_called_event for man in self.events.values()] - - @property - def all_recv_ready_events(self): - return [man.recv_ready_event for man in self.events.values()] - - def send_sync(self, pm, endpoint, dat): - self.events[endpoint].recv_called_event.wait() - self.events[endpoint].recv_called_event.clear() - pm.send(endpoint, dat) - self.events[endpoint].recv_ready_event.set() - - def unlock_sockets(self): - expected_sets = len(self.events) - while expected_sets > 0: - index = messaging.wait_for_one_event(self.all_recv_called_events) - self.all_recv_called_events[index].clear() - self.all_recv_ready_events[index].set() - expected_sets -= 1 - - def wait_for_recv_called(self): - messaging.wait_for_one_event(self.all_recv_called_events) - - def wait_for_next_recv(self, trigger_empty_recv): - index = messaging.wait_for_one_event(self.all_recv_called_events) - if self.main_pub is not None and self.main_pub_drained and trigger_empty_recv: - self.all_recv_called_events[index].clear() - self.all_recv_ready_events[index].set() - self.all_recv_called_events[index].wait() - - -@dataclass -class ProcessConfig: - proc_name: str - pubs: list[str] - subs: list[str] - ignore: list[str] - config_callback: Callable | None = None - init_callback: Callable | None = None - should_recv_callback: Callable | None = None - tolerance: float | None = None - processing_time: float = 0.001 - timeout: int = 30 - simulation: bool = True - main_pub: str | None = None - main_pub_drained: bool = True - vision_pubs: list[str] = field(default_factory=list) - ignore_alive_pubs: list[str] = field(default_factory=list) - unlocked_pubs: list[str] = field(default_factory=list) - - -class ProcessContainer: - def __init__(self, cfg: ProcessConfig): - self.prefix = OpenpilotPrefix(clean_dirs_on_exit=False) - self.cfg = copy.deepcopy(cfg) - self.process = copy.deepcopy(managed_processes[cfg.proc_name]) - self.msg_queue: list[capnp._DynamicStructReader] = [] - self.cnt = 0 - self.pm: messaging.PubMaster | None = None - self.sockets: list[messaging.SubSocket] | None = None - self.rc: ReplayContext | None = None - self.vipc_server: VisionIpcServer | None = None - self.environ_config: dict[str, Any] | None = None - self.capture: ProcessOutputCapture | None = None - - @property - def has_empty_queue(self) -> bool: - return len(self.msg_queue) == 0 - - @property - def pubs(self) -> list[str]: - return self.cfg.pubs - - @property - def subs(self) -> list[str]: - return self.cfg.subs - - def _clean_env(self): - for k in self.environ_config.keys(): - if k in os.environ: - del os.environ[k] - - for k in ["PROC_NAME", "SIMULATION"]: - if k in os.environ: - del os.environ[k] - - def _setup_env(self, params_config: dict[str, Any], environ_config: dict[str, Any]): - for k, v in environ_config.items(): - if len(v) != 0: - os.environ[k] = v - elif k in os.environ: - del os.environ[k] - - os.environ["PROC_NAME"] = self.cfg.proc_name - if self.cfg.simulation: - os.environ["SIMULATION"] = "1" - elif "SIMULATION" in os.environ: - del os.environ["SIMULATION"] - - params = Params() - for k, v in params_config.items(): - if isinstance(v, bool): - params.put_bool(k, v) - else: - params.put(k, v) - - self.environ_config = environ_config - - def _setup_vision_ipc(self, all_msgs: LogIterable, frs: dict[str, Any]): - assert len(self.cfg.vision_pubs) != 0 - - vipc_server = VisionIpcServer("camerad") - streams_metas = available_streams(all_msgs) - for meta in streams_metas: - if meta.camera_state in self.cfg.vision_pubs: - frame_size = (frs[meta.camera_state].w, frs[meta.camera_state].h) - vipc_server.create_buffers(meta.stream, 2, False, *frame_size) - vipc_server.start_listener() - - self.vipc_server = vipc_server - self.cfg.vision_pubs = [meta.camera_state for meta in streams_metas if meta.camera_state in self.cfg.vision_pubs] - - def _start_process(self): - if self.capture is not None: - self.process.launcher = LauncherWithCapture(self.capture, self.process.launcher) - self.process.prepare() - self.process.start() - - def start( - self, params_config: dict[str, Any], environ_config: dict[str, Any], - all_msgs: LogIterable, frs: dict[str, BaseFrameReader] | None, - fingerprint: str | None, capture_output: bool - ): - with self.prefix as p: - self._setup_env(params_config, environ_config) - - if self.cfg.config_callback is not None: - params = Params() - self.cfg.config_callback(params, self.cfg, all_msgs) - - self.rc = ReplayContext(self.cfg) - self.rc.open_context() - - self.pm = messaging.PubMaster(self.cfg.pubs) - self.sockets = [messaging.sub_sock(s, timeout=100) for s in self.cfg.subs] - - if len(self.cfg.vision_pubs) != 0: - assert frs is not None - self._setup_vision_ipc(all_msgs, frs) - assert self.vipc_server is not None - - if capture_output: - self.capture = ProcessOutputCapture(self.cfg.proc_name, p.prefix) - - self._start_process() - - if self.cfg.init_callback is not None: - self.cfg.init_callback(self.rc, self.pm, all_msgs, fingerprint) - - # wait for process to startup - with Timeout(10, error_msg=f"timed out waiting for process to start: {repr(self.cfg.proc_name)}"): - while not all(self.pm.all_readers_updated(s) for s in self.cfg.pubs if s not in self.cfg.ignore_alive_pubs): - time.sleep(0) - - def stop(self): - with self.prefix: - self.process.signal(signal.SIGKILL) - self.process.stop() - self.rc.close_context() - self.prefix.clean_dirs() - self._clean_env() - - def run_step(self, msg: capnp._DynamicStructReader, frs: dict[str, BaseFrameReader] | None) -> list[capnp._DynamicStructReader]: - assert self.rc and self.pm and self.sockets and self.process.proc - - output_msgs = [] - with self.prefix, Timeout(self.cfg.timeout, error_msg=f"timed out testing process {repr(self.cfg.proc_name)}"): - end_of_cycle = True - if self.cfg.should_recv_callback is not None: - end_of_cycle = self.cfg.should_recv_callback(msg, self.cfg, self.cnt) - - self.msg_queue.append(msg) - if end_of_cycle: - self.rc.wait_for_recv_called() - - # call recv to let sub-sockets reconnect, after we know the process is ready - if self.cnt == 0: - for s in self.sockets: - messaging.recv_one_or_none(s) - - # empty recv on drained pub indicates the end of messages, only do that if there're any - trigger_empty_recv = False - if self.cfg.main_pub and self.cfg.main_pub_drained: - trigger_empty_recv = next((True for m in self.msg_queue if m.which() == self.cfg.main_pub), False) - - for m in self.msg_queue: - self.pm.send(m.which(), m.as_builder()) - # send frames if needed - if self.vipc_server is not None and m.which() in self.cfg.vision_pubs: - camera_state = getattr(m, m.which()) - camera_meta = meta_from_camera_state(m.which()) - assert frs is not None - img = frs[m.which()].get(camera_state.frameId, pix_fmt="nv12")[0] - self.vipc_server.send(camera_meta.stream, img.flatten().tobytes(), - camera_state.frameId, camera_state.timestampSof, camera_state.timestampEof) - self.msg_queue = [] - - self.rc.unlock_sockets() - self.rc.wait_for_next_recv(trigger_empty_recv) - - for socket in self.sockets: - ms = messaging.drain_sock(socket) - for m in ms: - m = m.as_builder() - m.logMonoTime = msg.logMonoTime + int(self.cfg.processing_time * 1e9) - output_msgs.append(m.as_reader()) - self.cnt += 1 - assert self.process.proc.is_alive() - - return output_msgs - - -def controlsd_fingerprint_callback(rc, pm, msgs, fingerprint): - print("start fingerprinting") - params = Params() - canmsgs = [msg for msg in msgs if msg.which() == "can"][:300] - - # controlsd expects one arbitrary can and pandaState - rc.send_sync(pm, "can", messaging.new_message("can", 1)) - pm.send("pandaStates", messaging.new_message("pandaStates", 1)) - rc.send_sync(pm, "can", messaging.new_message("can", 1)) - rc.wait_for_next_recv(True) - - # fingerprinting is done, when CarParams is set - while params.get("CarParams") is None: - if len(canmsgs) == 0: - raise ValueError("Fingerprinting failed. Run out of can msgs") - - m = canmsgs.pop(0) - rc.send_sync(pm, "can", m.as_builder().to_bytes()) - rc.wait_for_next_recv(False) - - -def get_car_params_callback(rc, pm, msgs, fingerprint): - params = Params() - if fingerprint: - CarInterface, _, _ = interfaces[fingerprint] - CP = CarInterface.get_non_essential_params(fingerprint) - else: - can = DummySocket() - sendcan = DummySocket() - - canmsgs = [msg for msg in msgs if msg.which() == "can"] - has_cached_cp = params.get("CarParamsCache") is not None - assert len(canmsgs) != 0, "CAN messages are required for fingerprinting" - assert os.environ.get("SKIP_FW_QUERY", False) or has_cached_cp, \ - "CarParamsCache is required for fingerprinting. Make sure to keep carParams msgs in the logs." - - for m in canmsgs[:300]: - can.send(m.as_builder().to_bytes()) - _, CP = get_car(can, sendcan, Params().get_bool("ExperimentalLongitudinalEnabled")) - params.put("CarParams", CP.to_bytes()) - return CP - - -def controlsd_rcv_callback(msg, cfg, frame): - # no sendcan until controlsd is initialized - if msg.which() != "can": - return False - - socks = [ - s for s in cfg.subs if - frame % int(SERVICE_LIST[msg.which()].frequency / SERVICE_LIST[s].frequency) == 0 - ] - if "sendcan" in socks and (frame - 1) < 2000: - socks.remove("sendcan") - return len(socks) > 0 - - -def calibration_rcv_callback(msg, cfg, frame): - # calibrationd publishes 1 calibrationData every 5 cameraOdometry packets. - # should_recv always true to increment frame - return (frame - 1) == 0 or msg.which() == 'cameraOdometry' - - -def torqued_rcv_callback(msg, cfg, frame): - # should_recv always true to increment frame - return (frame - 1) == 0 or msg.which() == 'liveLocationKalman' - - -def dmonitoringmodeld_rcv_callback(msg, cfg, frame): - return msg.which() == "driverCameraState" - - -class ModeldCameraSyncRcvCallback: - def __init__(self): - self.road_present = False - self.wide_road_present = False - self.is_dual_camera = True - - def __call__(self, msg, cfg, frame): - self.is_dual_camera = len(cfg.vision_pubs) == 2 - if msg.which() == "roadCameraState": - self.road_present = True - elif msg.which() == "wideRoadCameraState": - self.wide_road_present = True - - if self.road_present and self.wide_road_present: - self.road_present, self.wide_road_present = False, False - return True - elif self.road_present and not self.is_dual_camera: - self.road_present = False - return True - else: - return False - - -class MessageBasedRcvCallback: - def __init__(self, trigger_msg_type): - self.trigger_msg_type = trigger_msg_type - - def __call__(self, msg, cfg, frame): - return msg.which() == self.trigger_msg_type - - -class FrequencyBasedRcvCallback: - def __init__(self, trigger_msg_type): - self.trigger_msg_type = trigger_msg_type - - def __call__(self, msg, cfg, frame): - if msg.which() != self.trigger_msg_type: - return False - - resp_sockets = [ - s for s in cfg.subs - if frame % max(1, int(SERVICE_LIST[msg.which()].frequency / SERVICE_LIST[s].frequency)) == 0 - ] - return bool(len(resp_sockets)) - - -def controlsd_config_callback(params, cfg, lr): - controlsState = None - initialized = False - for msg in lr: - if msg.which() == "controlsState": - controlsState = msg.controlsState - if initialized: - break - elif msg.which() == "onroadEvents": - initialized = car.CarEvent.EventName.controlsInitializing not in [e.name for e in msg.onroadEvents] - - assert controlsState is not None and initialized, "controlsState never initialized" - params.put("ReplayControlsState", controlsState.as_builder().to_bytes()) - - -def locationd_config_pubsub_callback(params, cfg, lr): - ublox = params.get_bool("UbloxAvailable") - sub_keys = ({"gpsLocation", } if ublox else {"gpsLocationExternal", }) - - cfg.pubs = set(cfg.pubs) - sub_keys - - -CONFIGS = [ - ProcessConfig( - proc_name="controlsd", - pubs=[ - "can", "deviceState", "pandaStates", "peripheralState", "liveCalibration", "driverMonitoringState", - "longitudinalPlan", "liveLocationKalman", "liveParameters", "radarState", - "modelV2", "driverCameraState", "roadCameraState", "wideRoadCameraState", "managerState", - "testJoystick", "liveTorqueParameters", "accelerometer", "gyroscope" - ], - subs=["controlsState", "carState", "carControl", "sendcan", "onroadEvents", "carParams"], - ignore=["logMonoTime", "controlsState.startMonoTime", "controlsState.cumLagMs"], - config_callback=controlsd_config_callback, - init_callback=controlsd_fingerprint_callback, - should_recv_callback=controlsd_rcv_callback, - tolerance=NUMPY_TOLERANCE, - processing_time=0.004, - main_pub="can", - ), - ProcessConfig( - proc_name="radard", - pubs=["can", "carState", "modelV2"], - subs=["radarState", "liveTracks"], - ignore=["logMonoTime", "radarState.cumLagMs"], - init_callback=get_car_params_callback, - should_recv_callback=MessageBasedRcvCallback("can"), - main_pub="can", - ), - ProcessConfig( - proc_name="plannerd", - pubs=["modelV2", "carControl", "carState", "controlsState", "radarState"], - subs=["longitudinalPlan", "uiPlan"], - ignore=["logMonoTime", "longitudinalPlan.processingDelay", "longitudinalPlan.solverExecutionTime"], - init_callback=get_car_params_callback, - should_recv_callback=FrequencyBasedRcvCallback("modelV2"), - tolerance=NUMPY_TOLERANCE, - ), - ProcessConfig( - proc_name="calibrationd", - pubs=["carState", "cameraOdometry", "carParams"], - subs=["liveCalibration"], - ignore=["logMonoTime"], - should_recv_callback=calibration_rcv_callback, - ), - ProcessConfig( - proc_name="dmonitoringd", - pubs=["driverStateV2", "liveCalibration", "carState", "modelV2", "controlsState"], - subs=["driverMonitoringState"], - ignore=["logMonoTime"], - should_recv_callback=FrequencyBasedRcvCallback("driverStateV2"), - tolerance=NUMPY_TOLERANCE, - ), - ProcessConfig( - proc_name="locationd", - pubs=[ - "cameraOdometry", "accelerometer", "gyroscope", "gpsLocationExternal", - "liveCalibration", "carState", "gpsLocation" - ], - subs=["liveLocationKalman"], - ignore=["logMonoTime"], - config_callback=locationd_config_pubsub_callback, - tolerance=NUMPY_TOLERANCE, - ), - ProcessConfig( - proc_name="paramsd", - pubs=["liveLocationKalman", "carState"], - subs=["liveParameters"], - ignore=["logMonoTime"], - init_callback=get_car_params_callback, - should_recv_callback=FrequencyBasedRcvCallback("liveLocationKalman"), - tolerance=NUMPY_TOLERANCE, - processing_time=0.004, - ), - ProcessConfig( - proc_name="ubloxd", - pubs=["ubloxRaw"], - subs=["ubloxGnss", "gpsLocationExternal"], - ignore=["logMonoTime"], - ), - ProcessConfig( - proc_name="torqued", - pubs=["liveLocationKalman", "carState", "carControl"], - subs=["liveTorqueParameters"], - ignore=["logMonoTime"], - init_callback=get_car_params_callback, - should_recv_callback=torqued_rcv_callback, - tolerance=NUMPY_TOLERANCE, - ), - ProcessConfig( - proc_name="modeld", - pubs=["roadCameraState", "wideRoadCameraState", "liveCalibration", "driverMonitoringState"], - subs=["modelV2", "cameraOdometry"], - ignore=["logMonoTime", "modelV2.frameDropPerc", "modelV2.modelExecutionTime"], - should_recv_callback=ModeldCameraSyncRcvCallback(), - tolerance=NUMPY_TOLERANCE, - processing_time=0.020, - main_pub=vipc_get_endpoint_name("camerad", meta_from_camera_state("roadCameraState").stream), - main_pub_drained=False, - vision_pubs=["roadCameraState", "wideRoadCameraState"], - ignore_alive_pubs=["wideRoadCameraState"], - init_callback=get_car_params_callback, - ), - ProcessConfig( - proc_name="dmonitoringmodeld", - pubs=["liveCalibration", "driverCameraState"], - subs=["driverStateV2"], - ignore=["logMonoTime", "driverStateV2.modelExecutionTime", "driverStateV2.dspExecutionTime"], - should_recv_callback=dmonitoringmodeld_rcv_callback, - tolerance=NUMPY_TOLERANCE, - processing_time=0.020, - main_pub=vipc_get_endpoint_name("camerad", meta_from_camera_state("driverCameraState").stream), - main_pub_drained=False, - vision_pubs=["driverCameraState"], - ignore_alive_pubs=["driverCameraState"], - ), -] - - -def get_process_config(name: str) -> ProcessConfig: - try: - return copy.deepcopy(next(c for c in CONFIGS if c.proc_name == name)) - except StopIteration as ex: - raise Exception(f"Cannot find process config with name: {name}") from ex - - -def get_custom_params_from_lr(lr: LogIterable, initial_state: str = "first") -> dict[str, Any]: - """ - Use this to get custom params dict based on provided logs. - Useful when replaying following processes: calibrationd, paramsd, torqued - The params may be based on first or last message of given type (carParams, liveCalibration, liveParameters, liveTorqueParameters) in the logs. - """ - - car_params = [m for m in lr if m.which() == "carParams"] - live_calibration = [m for m in lr if m.which() == "liveCalibration"] - live_parameters = [m for m in lr if m.which() == "liveParameters"] - live_torque_parameters = [m for m in lr if m.which() == "liveTorqueParameters"] - - assert initial_state in ["first", "last"] - msg_index = 0 if initial_state == "first" else -1 - - assert len(car_params) > 0, "carParams required for initial state of liveParameters and CarParamsPrevRoute" - CP = car_params[msg_index].carParams - - custom_params = { - "CarParamsPrevRoute": CP.as_builder().to_bytes() - } - - if len(live_calibration) > 0: - custom_params["CalibrationParams"] = live_calibration[msg_index].as_builder().to_bytes() - if len(live_parameters) > 0: - lp_dict = live_parameters[msg_index].to_dict() - lp_dict["carFingerprint"] = CP.carFingerprint - custom_params["LiveParameters"] = json.dumps(lp_dict) - if len(live_torque_parameters) > 0: - custom_params["LiveTorqueParameters"] = live_torque_parameters[msg_index].as_builder().to_bytes() - - return custom_params - - -def replay_process_with_name(name: str | Iterable[str], lr: LogIterable, *args, **kwargs) -> list[capnp._DynamicStructReader]: - if isinstance(name, str): - cfgs = [get_process_config(name)] - elif isinstance(name, Iterable): - cfgs = [get_process_config(n) for n in name] - else: - raise ValueError("name must be str or collections of strings") - - return replay_process(cfgs, lr, *args, **kwargs) - - -def replay_process( - cfg: ProcessConfig | Iterable[ProcessConfig], lr: LogIterable, frs: dict[str, BaseFrameReader] = None, - fingerprint: str = None, return_all_logs: bool = False, custom_params: dict[str, Any] = None, - captured_output_store: dict[str, dict[str, str]] = None, disable_progress: bool = False -) -> list[capnp._DynamicStructReader]: - if isinstance(cfg, Iterable): - cfgs = list(cfg) - else: - cfgs = [cfg] - - all_msgs = migrate_all(lr, old_logtime=True, - manager_states=True, - panda_states=any("pandaStates" in cfg.pubs for cfg in cfgs), - camera_states=any(len(cfg.vision_pubs) != 0 for cfg in cfgs)) - process_logs = _replay_multi_process(cfgs, all_msgs, frs, fingerprint, custom_params, captured_output_store, disable_progress) - - if return_all_logs: - keys = {m.which() for m in process_logs} - modified_logs = [m for m in all_msgs if m.which() not in keys] - modified_logs.extend(process_logs) - modified_logs.sort(key=lambda m: int(m.logMonoTime)) - log_msgs = modified_logs - else: - log_msgs = process_logs - - return log_msgs - - -def _replay_multi_process( - cfgs: list[ProcessConfig], lr: LogIterable, frs: dict[str, BaseFrameReader] | None, fingerprint: str | None, - custom_params: dict[str, Any] | None, captured_output_store: dict[str, dict[str, str]] | None, disable_progress: bool -) -> list[capnp._DynamicStructReader]: - if fingerprint is not None: - params_config = generate_params_config(lr=lr, fingerprint=fingerprint, custom_params=custom_params) - env_config = generate_environ_config(fingerprint=fingerprint) - else: - CP = next((m.carParams for m in lr if m.which() == "carParams"), None) - params_config = generate_params_config(lr=lr, CP=CP, custom_params=custom_params) - env_config = generate_environ_config(CP=CP) - - # validate frs and vision pubs - all_vision_pubs = [pub for cfg in cfgs for pub in cfg.vision_pubs] - if len(all_vision_pubs) != 0: - assert frs is not None, "frs must be provided when replaying process using vision streams" - assert all(meta_from_camera_state(st) is not None for st in all_vision_pubs), \ - f"undefined vision stream spotted, probably misconfigured process: (vision pubs: {all_vision_pubs})" - required_vision_pubs = {m.camera_state for m in available_streams(lr)} & set(all_vision_pubs) - assert all(st in frs for st in required_vision_pubs), f"frs for this process must contain following vision streams: {required_vision_pubs}" - - all_msgs = sorted(lr, key=lambda msg: msg.logMonoTime) - log_msgs = [] - try: - containers = [] - for cfg in cfgs: - container = ProcessContainer(cfg) - containers.append(container) - container.start(params_config, env_config, all_msgs, frs, fingerprint, captured_output_store is not None) - - all_pubs = {pub for container in containers for pub in container.pubs} - all_subs = {sub for container in containers for sub in container.subs} - lr_pubs = all_pubs - all_subs - pubs_to_containers = {pub: [container for container in containers if pub in container.pubs] for pub in all_pubs} - - pub_msgs = [msg for msg in all_msgs if msg.which() in lr_pubs] - # external queue for messages taken from logs; internal queue for messages generated by processes, which will be republished - external_pub_queue: list[capnp._DynamicStructReader] = pub_msgs.copy() - internal_pub_queue: list[capnp._DynamicStructReader] = [] - # heap for maintaining the order of messages generated by processes, where each element: (logMonoTime, index in internal_pub_queue) - internal_pub_index_heap: list[tuple[int, int]] = [] - - pbar = tqdm(total=len(external_pub_queue), disable=disable_progress) - while len(external_pub_queue) != 0 or (len(internal_pub_index_heap) != 0 and not all(c.has_empty_queue for c in containers)): - if len(internal_pub_index_heap) == 0 or (len(external_pub_queue) != 0 and external_pub_queue[0].logMonoTime < internal_pub_index_heap[0][0]): - msg = external_pub_queue.pop(0) - pbar.update(1) - else: - _, index = heapq.heappop(internal_pub_index_heap) - msg = internal_pub_queue[index] - - target_containers = pubs_to_containers[msg.which()] - for container in target_containers: - output_msgs = container.run_step(msg, frs) - for m in output_msgs: - if m.which() in all_pubs: - internal_pub_queue.append(m) - heapq.heappush(internal_pub_index_heap, (m.logMonoTime, len(internal_pub_queue) - 1)) - log_msgs.extend(output_msgs) - finally: - for container in containers: - container.stop() - if captured_output_store is not None: - assert container.capture is not None - out, err = container.capture.read_outerr() - captured_output_store[container.cfg.proc_name] = {"out": out, "err": err} - - return log_msgs - - -def generate_params_config(lr=None, CP=None, fingerprint=None, custom_params=None) -> dict[str, Any]: - params_dict = { - "OpenpilotEnabledToggle": True, - "DisengageOnAccelerator": True, - "DisableLogging": False, - } - - if custom_params is not None: - params_dict.update(custom_params) - if lr is not None: - has_ublox = any(msg.which() == "ubloxGnss" for msg in lr) - params_dict["UbloxAvailable"] = has_ublox - is_rhd = next((msg.driverMonitoringState.isRHD for msg in lr if msg.which() == "driverMonitoringState"), False) - params_dict["IsRhdDetected"] = is_rhd - - if CP is not None: - if CP.alternativeExperience == ALTERNATIVE_EXPERIENCE.DISABLE_DISENGAGE_ON_GAS: - params_dict["DisengageOnAccelerator"] = False - - if fingerprint is None: - if CP.fingerprintSource == "fw": - params_dict["CarParamsCache"] = CP.as_builder().to_bytes() - - if CP.openpilotLongitudinalControl: - params_dict["ExperimentalLongitudinalEnabled"] = True - - if CP.notCar: - params_dict["JoystickDebugMode"] = True - - return params_dict - - -def generate_environ_config(CP=None, fingerprint=None, log_dir=None) -> dict[str, Any]: - environ_dict = {} - if platform.system() != "Darwin": - environ_dict["PARAMS_ROOT"] = "/dev/shm/params" - if log_dir is not None: - environ_dict["LOG_ROOT"] = log_dir - - environ_dict["REPLAY"] = "1" - - # Regen or python process - if CP is not None and fingerprint is None: - if CP.fingerprintSource == "fw": - environ_dict['SKIP_FW_QUERY'] = "" - environ_dict['FINGERPRINT'] = "" - else: - environ_dict['SKIP_FW_QUERY'] = "1" - environ_dict['FINGERPRINT'] = CP.carFingerprint - elif fingerprint is not None: - environ_dict['SKIP_FW_QUERY'] = "1" - environ_dict['FINGERPRINT'] = fingerprint - else: - environ_dict["SKIP_FW_QUERY"] = "" - environ_dict["FINGERPRINT"] = "" - - return environ_dict - - -def check_openpilot_enabled(msgs: LogIterable) -> bool: - cur_enabled_count = 0 - max_enabled_count = 0 - for msg in msgs: - if msg.which() == "carParams": - if msg.carParams.notCar: - return True - elif msg.which() == "controlsState": - if msg.controlsState.active: - cur_enabled_count += 1 - else: - cur_enabled_count = 0 - max_enabled_count = max(max_enabled_count, cur_enabled_count) - - return max_enabled_count > int(10. / DT_CTRL) diff --git a/selfdrive/test/process_replay/ref_commit b/selfdrive/test/process_replay/ref_commit deleted file mode 100644 index 46d6842..0000000 --- a/selfdrive/test/process_replay/ref_commit +++ /dev/null @@ -1 +0,0 @@ -43efe1cf08cba8c86bc1ae8234b3d3d084a40e5d diff --git a/selfdrive/test/process_replay/regen.py b/selfdrive/test/process_replay/regen.py deleted file mode 100644 index 8e88220..0000000 --- a/selfdrive/test/process_replay/regen.py +++ /dev/null @@ -1,158 +0,0 @@ -#!/usr/bin/env python3 -import os -import argparse -import time -import capnp -import numpy as np - -from typing import Any -from collections.abc import Iterable - -from openpilot.selfdrive.test.process_replay.process_replay import CONFIGS, FAKEDATA, ProcessConfig, replay_process, get_process_config, \ - check_openpilot_enabled, get_custom_params_from_lr -from openpilot.selfdrive.test.process_replay.vision_meta import DRIVER_FRAME_SIZES -from openpilot.selfdrive.test.update_ci_routes import upload_route -from openpilot.tools.lib.route import Route -from openpilot.tools.lib.framereader import FrameReader, BaseFrameReader, FrameType -from openpilot.tools.lib.logreader import LogReader, LogIterable -from openpilot.tools.lib.helpers import save_log - - -class DummyFrameReader(BaseFrameReader): - def __init__(self, w: int, h: int, frame_count: int, pix_val: int): - self.pix_val = pix_val - self.w, self.h = w, h - self.frame_count = frame_count - self.frame_type = FrameType.raw - - def get(self, idx, count=1, pix_fmt="yuv420p"): - if pix_fmt == "rgb24": - shape = (self.h, self.w, 3) - elif pix_fmt == "nv12" or pix_fmt == "yuv420p": - shape = (int((self.h * self.w) * 3 / 2),) - else: - raise NotImplementedError - - return [np.full(shape, self.pix_val, dtype=np.uint8) for _ in range(count)] - - @staticmethod - def zero_dcamera(): - return DummyFrameReader(*DRIVER_FRAME_SIZES["tici"], 1200, 0) - - -def regen_segment( - lr: LogIterable, frs: dict[str, Any] = None, - processes: Iterable[ProcessConfig] = CONFIGS, disable_tqdm: bool = False -) -> list[capnp._DynamicStructReader]: - all_msgs = sorted(lr, key=lambda m: m.logMonoTime) - custom_params = get_custom_params_from_lr(all_msgs) - - print("Replayed processes:", [p.proc_name for p in processes]) - print("\n\n", "*"*30, "\n\n", sep="") - - output_logs = replay_process(processes, all_msgs, frs, return_all_logs=True, custom_params=custom_params, disable_progress=disable_tqdm) - - return output_logs - - -def setup_data_readers( - route: str, sidx: int, use_route_meta: bool, - needs_driver_cam: bool = True, needs_road_cam: bool = True, dummy_driver_cam: bool = False -) -> tuple[LogReader, dict[str, Any]]: - if use_route_meta: - r = Route(route) - lr = LogReader(r.log_paths()[sidx]) - frs = {} - if needs_road_cam and len(r.camera_paths()) > sidx and r.camera_paths()[sidx] is not None: - frs['roadCameraState'] = FrameReader(r.camera_paths()[sidx]) - if needs_road_cam and len(r.ecamera_paths()) > sidx and r.ecamera_paths()[sidx] is not None: - frs['wideRoadCameraState'] = FrameReader(r.ecamera_paths()[sidx]) - if needs_driver_cam: - if dummy_driver_cam: - frs['driverCameraState'] = DummyFrameReader.zero_dcamera() - elif len(r.dcamera_paths()) > sidx and r.dcamera_paths()[sidx] is not None: - device_type = next(str(msg.initData.deviceType) for msg in lr if msg.which() == "initData") - assert device_type != "neo", "Driver camera not supported on neo segments. Use dummy dcamera." - frs['driverCameraState'] = FrameReader(r.dcamera_paths()[sidx]) - else: - lr = LogReader(f"cd:/{route.replace('|', '/')}/{sidx}/rlog.bz2") - frs = {} - if needs_road_cam: - frs['roadCameraState'] = FrameReader(f"cd:/{route.replace('|', '/')}/{sidx}/fcamera.hevc") - if next((True for m in lr if m.which() == "wideRoadCameraState"), False): - frs['wideRoadCameraState'] = FrameReader(f"cd:/{route.replace('|', '/')}/{sidx}/ecamera.hevc") - if needs_driver_cam: - if dummy_driver_cam: - frs['driverCameraState'] = DummyFrameReader.zero_dcamera() - else: - device_type = next(str(msg.initData.deviceType) for msg in lr if msg.which() == "initData") - assert device_type != "neo", "Driver camera not supported on neo segments. Use dummy dcamera." - frs['driverCameraState'] = FrameReader(f"cd:/{route.replace('|', '/')}/{sidx}/dcamera.hevc") - - return lr, frs - - -def regen_and_save( - route: str, sidx: int, processes: str | Iterable[str] = "all", outdir: str = FAKEDATA, - upload: bool = False, use_route_meta: bool = False, disable_tqdm: bool = False, dummy_driver_cam: bool = False -) -> str: - if not isinstance(processes, str) and not hasattr(processes, "__iter__"): - raise ValueError("whitelist_proc must be a string or iterable") - - if processes != "all": - if isinstance(processes, str): - raise ValueError(f"Invalid value for processes: {processes}") - - replayed_processes = [] - for d in processes: - cfg = get_process_config(d) - replayed_processes.append(cfg) - else: - replayed_processes = CONFIGS - - all_vision_pubs = {pub for cfg in replayed_processes for pub in cfg.vision_pubs} - lr, frs = setup_data_readers(route, sidx, use_route_meta, - needs_driver_cam="driverCameraState" in all_vision_pubs, - needs_road_cam="roadCameraState" in all_vision_pubs or "wideRoadCameraState" in all_vision_pubs, - dummy_driver_cam=dummy_driver_cam) - output_logs = regen_segment(lr, frs, replayed_processes, disable_tqdm=disable_tqdm) - - log_dir = os.path.join(outdir, time.strftime("%Y-%m-%d--%H-%M-%S--0", time.gmtime())) - rel_log_dir = os.path.relpath(log_dir) - rpath = os.path.join(log_dir, "rlog.bz2") - - os.makedirs(log_dir) - save_log(rpath, output_logs, compress=True) - - print("\n\n", "*"*30, "\n\n", sep="") - print("New route:", rel_log_dir, "\n") - - if not check_openpilot_enabled(output_logs): - raise Exception("Route did not engage for long enough") - - if upload: - upload_route(rel_log_dir) - - return rel_log_dir - - -if __name__ == "__main__": - def comma_separated_list(string): - return string.split(",") - - all_procs = [p.proc_name for p in CONFIGS] - parser = argparse.ArgumentParser(description="Generate new segments from old ones") - parser.add_argument("--upload", action="store_true", help="Upload the new segment to the CI bucket") - parser.add_argument("--outdir", help="log output dir", default=FAKEDATA) - parser.add_argument("--dummy-dcamera", action='store_true', help="Use dummy blank driver camera") - parser.add_argument("--whitelist-procs", type=comma_separated_list, default=all_procs, - help="Comma-separated whitelist of processes to regen (e.g. controlsd,radard)") - parser.add_argument("--blacklist-procs", type=comma_separated_list, default=[], - help="Comma-separated blacklist of processes to regen (e.g. controlsd,radard)") - parser.add_argument("route", type=str, help="The source route") - parser.add_argument("seg", type=int, help="Segment in source route") - args = parser.parse_args() - - blacklist_set = set(args.blacklist_procs) - processes = [p for p in args.whitelist_procs if p not in blacklist_set] - regen_and_save(args.route, args.seg, processes=processes, upload=args.upload, outdir=args.outdir, dummy_driver_cam=args.dummy_dcamera) diff --git a/selfdrive/test/process_replay/regen_all.py b/selfdrive/test/process_replay/regen_all.py deleted file mode 100644 index 656a5b8..0000000 --- a/selfdrive/test/process_replay/regen_all.py +++ /dev/null @@ -1,54 +0,0 @@ -#!/usr/bin/env python3 -import argparse -import concurrent.futures -import os -import random -import traceback -from tqdm import tqdm - -from openpilot.common.prefix import OpenpilotPrefix -from openpilot.selfdrive.test.process_replay.regen import regen_and_save -from openpilot.selfdrive.test.process_replay.test_processes import FAKEDATA, source_segments as segments -from openpilot.tools.lib.route import SegmentName - - -def regen_job(segment, upload, disable_tqdm): - with OpenpilotPrefix(): - sn = SegmentName(segment[1]) - fake_dongle_id = 'regen' + ''.join(random.choice('0123456789ABCDEF') for _ in range(11)) - try: - relr = regen_and_save(sn.route_name.canonical_name, sn.segment_num, upload=upload, use_route_meta=False, - outdir=os.path.join(FAKEDATA, fake_dongle_id), disable_tqdm=disable_tqdm, dummy_driver_cam=True) - relr = '|'.join(relr.split('/')[-2:]) - return f' ("{segment[0]}", "{relr}"), ' - except Exception as e: - err = f" {segment} failed: {str(e)}" - err += traceback.format_exc() - err += "\n\n" - return err - - -if __name__ == "__main__": - all_cars = {car for car, _ in segments} - - parser = argparse.ArgumentParser(description="Generate new segments from old ones") - parser.add_argument("-j", "--jobs", type=int, default=1) - parser.add_argument("--no-upload", action="store_true") - parser.add_argument("--whitelist-cars", type=str, nargs="*", default=all_cars, - help="Whitelist given cars from the test (e.g. HONDA)") - parser.add_argument("--blacklist-cars", type=str, nargs="*", default=[], - help="Blacklist given cars from the test (e.g. HONDA)") - args = parser.parse_args() - - tested_cars = set(args.whitelist_cars) - set(args.blacklist_cars) - tested_cars = {c.upper() for c in tested_cars} - tested_segments = [(car, segment) for car, segment in segments if car in tested_cars] - - with concurrent.futures.ProcessPoolExecutor(max_workers=args.jobs) as pool: - p = pool.map(regen_job, tested_segments, [not args.no_upload] * len(tested_segments), [args.jobs > 1] * len(tested_segments)) - msg = "Copy these new segments into test_processes.py:" - for seg in tqdm(p, desc="Generating segments", total=len(tested_segments)): - msg += "\n" + str(seg) - print() - print() - print(msg) diff --git a/selfdrive/test/process_replay/test_debayer.py b/selfdrive/test/process_replay/test_debayer.py deleted file mode 100644 index edf2cbd..0000000 --- a/selfdrive/test/process_replay/test_debayer.py +++ /dev/null @@ -1,196 +0,0 @@ -#!/usr/bin/env python3 -import os -import sys -import bz2 -import numpy as np - -import pyopencl as cl # install with `PYOPENCL_CL_PRETEND_VERSION=2.0 pip install pyopencl` - -from openpilot.system.hardware import PC, TICI -from openpilot.common.basedir import BASEDIR -from openpilot.tools.lib.openpilotci import BASE_URL -from openpilot.system.version import get_commit -from openpilot.system.camerad.snapshot.snapshot import yuv_to_rgb -from openpilot.tools.lib.logreader import LogReader -from openpilot.tools.lib.filereader import FileReader - -TEST_ROUTE = "8345e3b82948d454|2022-05-04--13-45-33/0" - -FRAME_WIDTH = 1928 -FRAME_HEIGHT = 1208 -FRAME_STRIDE = 2896 - -UV_WIDTH = FRAME_WIDTH // 2 -UV_HEIGHT = FRAME_HEIGHT // 2 -UV_SIZE = UV_WIDTH * UV_HEIGHT - - -def get_frame_fn(ref_commit, test_route, tici=True): - return f"{test_route}_debayer{'_tici' if tici else ''}_{ref_commit}.bz2" - - -def bzip_frames(frames): - data = b'' - for y, u, v in frames: - data += y.tobytes() - data += u.tobytes() - data += v.tobytes() - return bz2.compress(data) - - -def unbzip_frames(url): - with FileReader(url) as f: - dat = f.read() - - data = bz2.decompress(dat) - - res = [] - for y_start in range(0, len(data), FRAME_WIDTH * FRAME_HEIGHT + UV_SIZE * 2): - u_start = y_start + FRAME_WIDTH * FRAME_HEIGHT - v_start = u_start + UV_SIZE - - y = np.frombuffer(data[y_start: u_start], dtype=np.uint8).reshape((FRAME_HEIGHT, FRAME_WIDTH)) - u = np.frombuffer(data[u_start: v_start], dtype=np.uint8).reshape((UV_HEIGHT, UV_WIDTH)) - v = np.frombuffer(data[v_start: v_start + UV_SIZE], dtype=np.uint8).reshape((UV_HEIGHT, UV_WIDTH)) - - res.append((y, u, v)) - - return res - - -def init_kernels(frame_offset=0): - ctx = cl.create_some_context(interactive=False) - - with open(os.path.join(BASEDIR, 'system/camerad/cameras/real_debayer.cl')) as f: - build_args = ' -cl-fast-relaxed-math -cl-denorms-are-zero -cl-single-precision-constant' + \ - f' -DFRAME_STRIDE={FRAME_STRIDE} -DRGB_WIDTH={FRAME_WIDTH} -DRGB_HEIGHT={FRAME_HEIGHT} -DFRAME_OFFSET={frame_offset} -DCAM_NUM=0' - if PC: - build_args += ' -DHALF_AS_FLOAT=1 -cl-std=CL2.0' - debayer_prg = cl.Program(ctx, f.read()).build(options=build_args) - - return ctx, debayer_prg - -def debayer_frame(ctx, debayer_prg, data, rgb=False): - q = cl.CommandQueue(ctx) - - yuv_buff = np.empty(FRAME_WIDTH * FRAME_HEIGHT + UV_SIZE * 2, dtype=np.uint8) - - cam_g = cl.Buffer(ctx, cl.mem_flags.READ_ONLY | cl.mem_flags.COPY_HOST_PTR, hostbuf=data) - yuv_g = cl.Buffer(ctx, cl.mem_flags.WRITE_ONLY, FRAME_WIDTH * FRAME_HEIGHT + UV_SIZE * 2) - - local_worksize = (20, 20) if TICI else (4, 4) - ev1 = debayer_prg.debayer10(q, (UV_WIDTH, UV_HEIGHT), local_worksize, cam_g, yuv_g) - cl.enqueue_copy(q, yuv_buff, yuv_g, wait_for=[ev1]).wait() - cl.enqueue_barrier(q) - - y = yuv_buff[:FRAME_WIDTH*FRAME_HEIGHT].reshape((FRAME_HEIGHT, FRAME_WIDTH)) - u = yuv_buff[FRAME_WIDTH*FRAME_HEIGHT:FRAME_WIDTH*FRAME_HEIGHT+UV_SIZE].reshape((UV_HEIGHT, UV_WIDTH)) - v = yuv_buff[FRAME_WIDTH*FRAME_HEIGHT+UV_SIZE:].reshape((UV_HEIGHT, UV_WIDTH)) - - if rgb: - return yuv_to_rgb(y, u, v) - else: - return y, u, v - - -def debayer_replay(lr): - ctx, debayer_prg = init_kernels() - - frames = [] - for m in lr: - if m.which() == 'roadCameraState': - cs = m.roadCameraState - if cs.image: - data = np.frombuffer(cs.image, dtype=np.uint8) - img = debayer_frame(ctx, debayer_prg, data) - - frames.append(img) - - return frames - - -if __name__ == "__main__": - update = "--update" in sys.argv - replay_dir = os.path.dirname(os.path.abspath(__file__)) - ref_commit_fn = os.path.join(replay_dir, "debayer_replay_ref_commit") - - # load logs - lr = list(LogReader(TEST_ROUTE)) - - # run replay - frames = debayer_replay(lr) - - # get diff - failed = False - diff = '' - yuv_i = ['y', 'u', 'v'] - if not update: - with open(ref_commit_fn) as f: - ref_commit = f.read().strip() - frame_fn = get_frame_fn(ref_commit, TEST_ROUTE, tici=TICI) - - try: - cmp_frames = unbzip_frames(BASE_URL + frame_fn) - - if len(frames) != len(cmp_frames): - failed = True - diff += 'amount of frames not equal\n' - - for i, (frame, cmp_frame) in enumerate(zip(frames, cmp_frames, strict=True)): - for j in range(3): - fr = frame[j] - cmp_f = cmp_frame[j] - if fr.shape != cmp_f.shape: - failed = True - diff += f'frame shapes not equal for ({i}, {yuv_i[j]})\n' - diff += f'{ref_commit}: {cmp_f.shape}\n' - diff += f'HEAD: {fr.shape}\n' - elif not np.array_equal(fr, cmp_f): - failed = True - if np.allclose(fr, cmp_f, atol=1): - diff += f'frames not equal for ({i}, {yuv_i[j]}), but are all close\n' - else: - diff += f'frames not equal for ({i}, {yuv_i[j]})\n' - - frame_diff = np.abs(np.subtract(fr, cmp_f)) - diff_len = len(np.nonzero(frame_diff)[0]) - if diff_len > 10000: - diff += f'different at a large amount of pixels ({diff_len})\n' - else: - diff += 'different at (frame, yuv, pixel, ref, HEAD):\n' - for k in zip(*np.nonzero(frame_diff), strict=True): - diff += f'{i}, {yuv_i[j]}, {k}, {cmp_f[k]}, {fr[k]}\n' - - if failed: - print(diff) - with open("debayer_diff.txt", "w") as f: - f.write(diff) - except Exception as e: - print(str(e)) - failed = True - - # upload new refs - if update or (failed and TICI): - from openpilot.tools.lib.openpilotci import upload_file - - print("Uploading new refs") - - frames_bzip = bzip_frames(frames) - - new_commit = get_commit() - frame_fn = os.path.join(replay_dir, get_frame_fn(new_commit, TEST_ROUTE, tici=TICI)) - with open(frame_fn, "wb") as f2: - f2.write(frames_bzip) - - try: - upload_file(frame_fn, os.path.basename(frame_fn)) - except Exception as e: - print("failed to upload", e) - - if update: - with open(ref_commit_fn, 'w') as f: - f.write(str(new_commit)) - - print("\nNew ref commit: ", new_commit) - - sys.exit(int(failed)) diff --git a/selfdrive/test/process_replay/test_fuzzy.py b/selfdrive/test/process_replay/test_fuzzy.py deleted file mode 100644 index adff06f..0000000 --- a/selfdrive/test/process_replay/test_fuzzy.py +++ /dev/null @@ -1,33 +0,0 @@ -#!/usr/bin/env python3 -import copy -from hypothesis import given, HealthCheck, Phase, settings -import hypothesis.strategies as st -from parameterized import parameterized -import unittest - -from cereal import log -from openpilot.selfdrive.car.toyota.values import CAR as TOYOTA -from openpilot.selfdrive.test.fuzzy_generation import FuzzyGenerator -import openpilot.selfdrive.test.process_replay.process_replay as pr - -# These processes currently fail because of unrealistic data breaking assumptions -# that openpilot makes causing error with NaN, inf, int size, array indexing ... -# TODO: Make each one testable -NOT_TESTED = ['controlsd', 'plannerd', 'calibrationd', 'dmonitoringd', 'paramsd', 'dmonitoringmodeld', 'modeld'] - -TEST_CASES = [(cfg.proc_name, copy.deepcopy(cfg)) for cfg in pr.CONFIGS if cfg.proc_name not in NOT_TESTED] - -class TestFuzzProcesses(unittest.TestCase): - - # TODO: make this faster and increase examples - @parameterized.expand(TEST_CASES) - @given(st.data()) - @settings(phases=[Phase.generate, Phase.target], max_examples=10, deadline=1000, suppress_health_check=[HealthCheck.too_slow, HealthCheck.data_too_large]) - def test_fuzz_process(self, proc_name, cfg, data): - msgs = FuzzyGenerator.get_random_event_msg(data.draw, events=cfg.pubs, real_floats=True) - lr = [log.Event.new_message(**m).as_reader() for m in msgs] - cfg.timeout = 5 - pr.replay_process(cfg, lr, fingerprint=TOYOTA.COROLLA_TSS2, disable_progress=True) - -if __name__ == "__main__": - unittest.main() diff --git a/selfdrive/test/process_replay/test_processes.py b/selfdrive/test/process_replay/test_processes.py deleted file mode 100644 index 88e46ab..0000000 --- a/selfdrive/test/process_replay/test_processes.py +++ /dev/null @@ -1,231 +0,0 @@ -#!/usr/bin/env python3 -import argparse -import concurrent.futures -import os -import sys -from collections import defaultdict -from tqdm import tqdm -from typing import Any - -from openpilot.selfdrive.car.car_helpers import interface_names -from openpilot.tools.lib.openpilotci import get_url, upload_file -from openpilot.selfdrive.test.process_replay.compare_logs import compare_logs, format_diff -from openpilot.selfdrive.test.process_replay.process_replay import CONFIGS, PROC_REPLAY_DIR, FAKEDATA, check_openpilot_enabled, replay_process -from openpilot.system.version import get_commit -from openpilot.tools.lib.filereader import FileReader -from openpilot.tools.lib.logreader import LogReader -from openpilot.tools.lib.helpers import save_log - -source_segments = [ - ("BODY", "937ccb7243511b65|2022-05-24--16-03-09--1"), # COMMA.BODY - ("HYUNDAI", "02c45f73a2e5c6e9|2021-01-01--19-08-22--1"), # HYUNDAI.SONATA - ("HYUNDAI2", "d545129f3ca90f28|2022-11-07--20-43-08--3"), # HYUNDAI.KIA_EV6 (+ QCOM GPS) - ("TOYOTA", "0982d79ebb0de295|2021-01-04--17-13-21--13"), # TOYOTA.PRIUS - ("TOYOTA2", "0982d79ebb0de295|2021-01-03--20-03-36--6"), # TOYOTA.RAV4 - ("TOYOTA3", "f7d7e3538cda1a2a|2021-08-16--08-55-34--6"), # TOYOTA.COROLLA_TSS2 - ("HONDA", "eb140f119469d9ab|2021-06-12--10-46-24--27"), # HONDA.CIVIC (NIDEC) - ("HONDA2", "7d2244f34d1bbcda|2021-06-25--12-25-37--26"), # HONDA.ACCORD (BOSCH) - ("CHRYSLER", "4deb27de11bee626|2021-02-20--11-28-55--8"), # CHRYSLER.PACIFICA_2018_HYBRID - ("RAM", "17fc16d840fe9d21|2023-04-26--13-28-44--5"), # CHRYSLER.RAM_1500 - ("SUBARU", "341dccd5359e3c97|2022-09-12--10-35-33--3"), # SUBARU.OUTBACK - ("GM", "0c58b6a25109da2b|2021-02-23--16-35-50--11"), # GM.VOLT - ("GM2", "376bf99325883932|2022-10-27--13-41-22--1"), # GM.BOLT_EUV - ("NISSAN", "35336926920f3571|2021-02-12--18-38-48--46"), # NISSAN.XTRAIL - ("VOLKSWAGEN", "de9592456ad7d144|2021-06-29--11-00-15--6"), # VOLKSWAGEN.GOLF - ("MAZDA", "bd6a637565e91581|2021-10-30--15-14-53--4"), # MAZDA.CX9_2021 - ("FORD", "54827bf84c38b14f|2023-01-26--21-59-07--4"), # FORD.BRONCO_SPORT_MK1 - - # Enable when port is tested and dashcamOnly is no longer set - #("TESLA", "bb50caf5f0945ab1|2021-06-19--17-20-18--3"), # TESLA.AP2_MODELS - #("VOLKSWAGEN2", "3cfdec54aa035f3f|2022-07-19--23-45-10--2"), # VOLKSWAGEN.PASSAT_NMS -] - -segments = [ - ("BODY", "regen997DF2697CB|2023-10-30--23-14-29--0"), - ("HYUNDAI", "regen2A9D2A8E0B4|2023-10-30--23-13-34--0"), - ("HYUNDAI2", "regen6CA24BC3035|2023-10-30--23-14-28--0"), - ("TOYOTA", "regen5C019D76307|2023-10-30--23-13-31--0"), - ("TOYOTA2", "regen5DCADA88A96|2023-10-30--23-14-57--0"), - ("TOYOTA3", "regen7204CA3A498|2023-10-30--23-15-55--0"), - ("HONDA", "regen048F8FA0B24|2023-10-30--23-15-53--0"), - ("HONDA2", "regen7D2D3F82D5B|2023-10-30--23-15-55--0"), - ("CHRYSLER", "regen7125C42780C|2023-10-30--23-16-21--0"), - ("RAM", "regen2731F3213D2|2023-10-30--23-18-11--0"), - ("SUBARU", "regen86E4C1B4DDD|2023-10-30--23-18-14--0"), - ("GM", "regenF6393D64745|2023-10-30--23-17-18--0"), - ("GM2", "regen220F830C05B|2023-10-30--23-18-39--0"), - ("NISSAN", "regen4F671F7C435|2023-10-30--23-18-40--0"), - ("VOLKSWAGEN", "regen8BDFE7307A0|2023-10-30--23-19-36--0"), - ("MAZDA", "regen2E9F1A15FD5|2023-10-30--23-20-36--0"), - ("FORD", "regen6D39E54606E|2023-10-30--23-20-54--0"), -] - -# dashcamOnly makes don't need to be tested until a full port is done -excluded_interfaces = ["mock", "tesla"] - -BASE_URL = "https://commadataci.blob.core.windows.net/openpilotci/" -REF_COMMIT_FN = os.path.join(PROC_REPLAY_DIR, "ref_commit") -EXCLUDED_PROCS = {"modeld", "dmonitoringmodeld"} - - -def run_test_process(data): - segment, cfg, args, cur_log_fn, ref_log_path, lr_dat = data - res = None - if not args.upload_only: - lr = LogReader.from_bytes(lr_dat) - res, log_msgs = test_process(cfg, lr, segment, ref_log_path, cur_log_fn, args.ignore_fields, args.ignore_msgs) - # save logs so we can upload when updating refs - save_log(cur_log_fn, log_msgs) - - if args.update_refs or args.upload_only: - print(f'Uploading: {os.path.basename(cur_log_fn)}') - assert os.path.exists(cur_log_fn), f"Cannot find log to upload: {cur_log_fn}" - upload_file(cur_log_fn, os.path.basename(cur_log_fn)) - os.remove(cur_log_fn) - return (segment, cfg.proc_name, res) - - -def get_log_data(segment): - r, n = segment.rsplit("--", 1) - with FileReader(get_url(r, n)) as f: - return (segment, f.read()) - - -def test_process(cfg, lr, segment, ref_log_path, new_log_path, ignore_fields=None, ignore_msgs=None): - if ignore_fields is None: - ignore_fields = [] - if ignore_msgs is None: - ignore_msgs = [] - - ref_log_msgs = list(LogReader(ref_log_path)) - - try: - log_msgs = replay_process(cfg, lr, disable_progress=True) - except Exception as e: - raise Exception("failed on segment: " + segment) from e - - # check to make sure openpilot is engaged in the route - if cfg.proc_name == "controlsd": - if not check_openpilot_enabled(log_msgs): - # FIXME: these segments should work, but the replay enabling logic is too brittle - if segment not in ("regen6CA24BC3035|2023-10-30--23-14-28--0", "regen7D2D3F82D5B|2023-10-30--23-15-55--0"): - return f"Route did not enable at all or for long enough: {new_log_path}", log_msgs - - try: - return compare_logs(ref_log_msgs, log_msgs, ignore_fields + cfg.ignore, ignore_msgs, cfg.tolerance), log_msgs - except Exception as e: - return str(e), log_msgs - - -if __name__ == "__main__": - all_cars = {car for car, _ in segments} - all_procs = {cfg.proc_name for cfg in CONFIGS if cfg.proc_name not in EXCLUDED_PROCS} - - cpu_count = os.cpu_count() or 1 - - parser = argparse.ArgumentParser(description="Regression test to identify changes in a process's output") - parser.add_argument("--whitelist-procs", type=str, nargs="*", default=all_procs, - help="Whitelist given processes from the test (e.g. controlsd)") - parser.add_argument("--whitelist-cars", type=str, nargs="*", default=all_cars, - help="Whitelist given cars from the test (e.g. HONDA)") - parser.add_argument("--blacklist-procs", type=str, nargs="*", default=[], - help="Blacklist given processes from the test (e.g. controlsd)") - parser.add_argument("--blacklist-cars", type=str, nargs="*", default=[], - help="Blacklist given cars from the test (e.g. HONDA)") - parser.add_argument("--ignore-fields", type=str, nargs="*", default=[], - help="Extra fields or msgs to ignore (e.g. carState.events)") - parser.add_argument("--ignore-msgs", type=str, nargs="*", default=[], - help="Msgs to ignore (e.g. carEvents)") - parser.add_argument("--update-refs", action="store_true", - help="Updates reference logs using current commit") - parser.add_argument("--upload-only", action="store_true", - help="Skips testing processes and uploads logs from previous test run") - parser.add_argument("-j", "--jobs", type=int, default=max(cpu_count - 2, 1), - help="Max amount of parallel jobs") - args = parser.parse_args() - - tested_procs = set(args.whitelist_procs) - set(args.blacklist_procs) - tested_cars = set(args.whitelist_cars) - set(args.blacklist_cars) - tested_cars = {c.upper() for c in tested_cars} - - full_test = (tested_procs == all_procs) and (tested_cars == all_cars) and all(len(x) == 0 for x in (args.ignore_fields, args.ignore_msgs)) - upload = args.update_refs or args.upload_only - os.makedirs(os.path.dirname(FAKEDATA), exist_ok=True) - - if upload: - assert full_test, "Need to run full test when updating refs" - - try: - with open(REF_COMMIT_FN) as f: - ref_commit = f.read().strip() - except FileNotFoundError: - print("Couldn't find reference commit") - sys.exit(1) - - cur_commit = get_commit() - if not cur_commit: - raise Exception("Couldn't get current commit") - - print(f"***** testing against commit {ref_commit} *****") - - # check to make sure all car brands are tested - if full_test: - untested = (set(interface_names) - set(excluded_interfaces)) - {c.lower() for c in tested_cars} - assert len(untested) == 0, f"Cars missing routes: {str(untested)}" - - log_paths: defaultdict[str, dict[str, dict[str, str]]] = defaultdict(lambda: defaultdict(dict)) - with concurrent.futures.ProcessPoolExecutor(max_workers=args.jobs) as pool: - if not args.upload_only: - download_segments = [seg for car, seg in segments if car in tested_cars] - log_data: dict[str, LogReader] = {} - p1 = pool.map(get_log_data, download_segments) - for segment, lr in tqdm(p1, desc="Getting Logs", total=len(download_segments)): - log_data[segment] = lr - - pool_args: Any = [] - for car_brand, segment in segments: - if car_brand not in tested_cars: - continue - - for cfg in CONFIGS: - if cfg.proc_name not in tested_procs: - continue - - cur_log_fn = os.path.join(FAKEDATA, f"{segment}_{cfg.proc_name}_{cur_commit}.bz2") - if args.update_refs: # reference logs will not exist if routes were just regenerated - ref_log_path = get_url(*segment.rsplit("--", 1)) - else: - ref_log_fn = os.path.join(FAKEDATA, f"{segment}_{cfg.proc_name}_{ref_commit}.bz2") - ref_log_path = ref_log_fn if os.path.exists(ref_log_fn) else BASE_URL + os.path.basename(ref_log_fn) - - dat = None if args.upload_only else log_data[segment] - pool_args.append((segment, cfg, args, cur_log_fn, ref_log_path, dat)) - - log_paths[segment][cfg.proc_name]['ref'] = ref_log_path - log_paths[segment][cfg.proc_name]['new'] = cur_log_fn - - results: Any = defaultdict(dict) - p2 = pool.map(run_test_process, pool_args) - for (segment, proc, result) in tqdm(p2, desc="Running Tests", total=len(pool_args)): - if not args.upload_only: - results[segment][proc] = result - - diff_short, diff_long, failed = format_diff(results, log_paths, ref_commit) - if not upload: - with open(os.path.join(PROC_REPLAY_DIR, "diff.txt"), "w") as f: - f.write(diff_long) - print(diff_short) - - if failed: - print("TEST FAILED") - print("\n\nTo push the new reference logs for this commit run:") - print("./test_processes.py --upload-only") - else: - print("TEST SUCCEEDED") - - else: - with open(REF_COMMIT_FN, "w") as f: - f.write(cur_commit) - print(f"\n\nUpdated reference logs for commit: {cur_commit}") - - sys.exit(int(failed)) diff --git a/selfdrive/test/process_replay/test_regen.py b/selfdrive/test/process_replay/test_regen.py deleted file mode 100644 index 41d67ea..0000000 --- a/selfdrive/test/process_replay/test_regen.py +++ /dev/null @@ -1,45 +0,0 @@ -#!/usr/bin/env python3 - -import unittest - -from parameterized import parameterized - -from openpilot.selfdrive.test.process_replay.regen import regen_segment, DummyFrameReader -from openpilot.selfdrive.test.process_replay.process_replay import check_openpilot_enabled -from openpilot.tools.lib.openpilotci import get_url -from openpilot.tools.lib.logreader import LogReader -from openpilot.tools.lib.framereader import FrameReader - -TESTED_SEGMENTS = [ - ("PRIUS_C2", "0982d79ebb0de295|2021-01-04--17-13-21--13"), # TOYOTA PRIUS 2017: NEO, pandaStateDEPRECATED, no peripheralState, sensorEventsDEPRECATED - # Enable these once regen on CI becomes faster or use them for different tests running controlsd in isolation - # ("MAZDA_C3", "bd6a637565e91581|2021-10-30--15-14-53--4"), # MAZDA.CX9_2021: TICI, incomplete managerState - # ("FORD_C3", "54827bf84c38b14f|2023-01-26--21-59-07--4"), # FORD.BRONCO_SPORT_MK1: TICI -] - - -def ci_setup_data_readers(route, sidx): - lr = LogReader(get_url(route, sidx, "rlog")) - frs = { - 'roadCameraState': FrameReader(get_url(route, sidx, "fcamera")), - 'driverCameraState': DummyFrameReader.zero_dcamera() - } - if next((True for m in lr if m.which() == "wideRoadCameraState"), False): - frs["wideRoadCameraState"] = FrameReader(get_url(route, sidx, "ecamera")) - - return lr, frs - - -class TestRegen(unittest.TestCase): - @parameterized.expand(TESTED_SEGMENTS) - def test_engaged(self, case_name, segment): - route, sidx = segment.rsplit("--", 1) - lr, frs = ci_setup_data_readers(route, sidx) - output_logs = regen_segment(lr, frs, disable_tqdm=True) - - engaged = check_openpilot_enabled(output_logs) - self.assertTrue(engaged, f"openpilot not engaged in {case_name}") - - -if __name__=='__main__': - unittest.main() diff --git a/selfdrive/test/process_replay/vision_meta.py b/selfdrive/test/process_replay/vision_meta.py deleted file mode 100644 index b3c3dc0..0000000 --- a/selfdrive/test/process_replay/vision_meta.py +++ /dev/null @@ -1,43 +0,0 @@ -from collections import namedtuple -from cereal.visionipc import VisionStreamType -from openpilot.common.realtime import DT_MDL, DT_DMON -from openpilot.common.transformations.camera import tici_f_frame_size, tici_d_frame_size, tici_e_frame_size, eon_f_frame_size, eon_d_frame_size - -VideoStreamMeta = namedtuple("VideoStreamMeta", ["camera_state", "encode_index", "stream", "dt", "frame_sizes"]) -ROAD_CAMERA_FRAME_SIZES = {"tici": tici_f_frame_size, "tizi": tici_f_frame_size, "neo": eon_f_frame_size} -WIDE_ROAD_CAMERA_FRAME_SIZES = {"tici": tici_e_frame_size, "tizi": tici_e_frame_size} -DRIVER_FRAME_SIZES = {"tici": tici_d_frame_size, "tizi": tici_d_frame_size, "neo": eon_d_frame_size} -VIPC_STREAM_METADATA = [ - # metadata: (state_msg_type, encode_msg_type, stream_type, dt, frame_sizes) - ("roadCameraState", "roadEncodeIdx", VisionStreamType.VISION_STREAM_ROAD, DT_MDL, ROAD_CAMERA_FRAME_SIZES), - ("wideRoadCameraState", "wideRoadEncodeIdx", VisionStreamType.VISION_STREAM_WIDE_ROAD, DT_MDL, WIDE_ROAD_CAMERA_FRAME_SIZES), - ("driverCameraState", "driverEncodeIdx", VisionStreamType.VISION_STREAM_DRIVER, DT_DMON, DRIVER_FRAME_SIZES), -] - - -def meta_from_camera_state(state): - meta = next((VideoStreamMeta(*meta) for meta in VIPC_STREAM_METADATA if meta[0] == state), None) - return meta - - -def meta_from_encode_index(encode_index): - meta = next((VideoStreamMeta(*meta) for meta in VIPC_STREAM_METADATA if meta[1] == encode_index), None) - return meta - - -def meta_from_stream_type(stream_type): - meta = next((VideoStreamMeta(*meta) for meta in VIPC_STREAM_METADATA if meta[2] == stream_type), None) - return meta - - -def available_streams(lr=None): - if lr is None: - return [VideoStreamMeta(*meta) for meta in VIPC_STREAM_METADATA] - - result = [] - for meta in VIPC_STREAM_METADATA: - has_cam_state = next((True for m in lr if m.which() == meta[0]), False) - if has_cam_state: - result.append(VideoStreamMeta(*meta)) - - return result diff --git a/selfdrive/test/profiling/.gitignore b/selfdrive/test/profiling/.gitignore deleted file mode 100644 index 76acac7..0000000 --- a/selfdrive/test/profiling/.gitignore +++ /dev/null @@ -1,2 +0,0 @@ -cachegrind.out.* -*.prof diff --git a/selfdrive/test/profiling/__init__.py b/selfdrive/test/profiling/__init__.py deleted file mode 100644 index e69de29..0000000 diff --git a/selfdrive/test/profiling/lib.py b/selfdrive/test/profiling/lib.py deleted file mode 100644 index 7f3b012..0000000 --- a/selfdrive/test/profiling/lib.py +++ /dev/null @@ -1,91 +0,0 @@ -from collections import defaultdict, deque -from cereal.services import SERVICE_LIST -import cereal.messaging as messaging -import capnp - - -class ReplayDone(Exception): - pass - - -class SubSocket(): - def __init__(self, msgs, trigger): - self.i = 0 - self.trigger = trigger - self.msgs = [m.as_builder().to_bytes() for m in msgs if m.which() == trigger] - self.max_i = len(self.msgs) - 1 - - def receive(self, non_blocking=False): - if non_blocking: - return None - - if self.i == self.max_i: - raise ReplayDone - - while True: - msg = self.msgs[self.i] - self.i += 1 - return msg - - -class PubSocket(): - def send(self, data): - pass - - -class SubMaster(messaging.SubMaster): - def __init__(self, msgs, trigger, services, check_averag_freq=False): - self.frame = 0 - self.data = {} - self.ignore_alive = [] - - self.alive = {s: True for s in services} - self.updated = {s: False for s in services} - self.rcv_time = {s: 0. for s in services} - self.rcv_frame = {s: 0 for s in services} - self.valid = {s: True for s in services} - self.freq_ok = {s: True for s in services} - self.recv_dts = {s: deque([0.0] * messaging.AVG_FREQ_HISTORY, maxlen=messaging.AVG_FREQ_HISTORY) for s in services} - self.logMonoTime = {} - self.sock = {} - self.freq = {} - self.check_average_freq = check_averag_freq - self.non_polled_services = [] - self.ignore_average_freq = [] - - # TODO: specify multiple triggers for service like plannerd that poll on more than one service - cur_msgs = [] - self.msgs = [] - msgs = [m for m in msgs if m.which() in services] - - for msg in msgs: - cur_msgs.append(msg) - if msg.which() == trigger: - self.msgs.append(cur_msgs) - cur_msgs = [] - - self.msgs = list(reversed(self.msgs)) - - for s in services: - self.freq[s] = SERVICE_LIST[s].frequency - try: - data = messaging.new_message(s) - except capnp.lib.capnp.KjException: - # lists - data = messaging.new_message(s, 0) - - self.data[s] = getattr(data, s) - self.logMonoTime[s] = 0 - self.sock[s] = SubSocket(msgs, s) - - def update(self, timeout=None): - if not len(self.msgs): - raise ReplayDone - - cur_msgs = self.msgs.pop() - self.update_msgs(cur_msgs[0].logMonoTime, self.msgs.pop()) - - -class PubMaster(messaging.PubMaster): - def __init__(self): - self.sock = defaultdict(PubSocket) diff --git a/selfdrive/test/profiling/profiler.py b/selfdrive/test/profiling/profiler.py deleted file mode 100644 index 6571825..0000000 --- a/selfdrive/test/profiling/profiler.py +++ /dev/null @@ -1,97 +0,0 @@ -#!/usr/bin/env python3 -import os -import sys -import cProfile -import pprofile -import pyprof2calltree - -from openpilot.common.params import Params -from openpilot.tools.lib.logreader import LogReader -from openpilot.selfdrive.test.profiling.lib import SubMaster, PubMaster, SubSocket, ReplayDone -from openpilot.selfdrive.test.process_replay.process_replay import CONFIGS -from openpilot.selfdrive.car.toyota.values import CAR as TOYOTA -from openpilot.selfdrive.car.honda.values import CAR as HONDA -from openpilot.selfdrive.car.volkswagen.values import CAR as VW - -BASE_URL = "https://commadataci.blob.core.windows.net/openpilotci/" - -CARS = { - 'toyota': ("0982d79ebb0de295|2021-01-03--20-03-36/6", TOYOTA.RAV4), - 'honda': ("0982d79ebb0de295|2021-01-08--10-13-10/6", HONDA.CIVIC), - "vw": ("ef895f46af5fd73f|2021-05-22--14-06-35/6", VW.AUDI_A3_MK3), -} - - -def get_inputs(msgs, process, fingerprint): - for config in CONFIGS: - if config.proc_name == process: - sub_socks = list(config.pubs) - trigger = sub_socks[0] - break - - # some procs block on CarParams - for msg in msgs: - if msg.which() == 'carParams': - m = msg.as_builder() - m.carParams.carFingerprint = fingerprint - Params().put("CarParams", m.carParams.copy().to_bytes()) - break - - sm = SubMaster(msgs, trigger, sub_socks) - pm = PubMaster() - if 'can' in sub_socks: - can_sock = SubSocket(msgs, 'can') - else: - can_sock = None - return sm, pm, can_sock - - -def profile(proc, func, car='toyota'): - segment, fingerprint = CARS[car] - segment = segment.replace('|', '/') - rlog_url = f"{BASE_URL}{segment}/rlog.bz2" - msgs = list(LogReader(rlog_url)) * int(os.getenv("LOOP", "1")) - - os.environ['FINGERPRINT'] = fingerprint - os.environ['SKIP_FW_QUERY'] = "1" - os.environ['REPLAY'] = "1" - - def run(sm, pm, can_sock): - try: - if can_sock is not None: - func(sm, pm, can_sock) - else: - func(sm, pm) - except ReplayDone: - pass - - # Statistical - sm, pm, can_sock = get_inputs(msgs, proc, fingerprint) - with pprofile.StatisticalProfile()(period=0.00001) as pr: - run(sm, pm, can_sock) - pr.dump_stats(f'cachegrind.out.{proc}_statistical') - - # Deterministic - sm, pm, can_sock = get_inputs(msgs, proc, fingerprint) - with cProfile.Profile() as pr: - run(sm, pm, can_sock) - pyprof2calltree.convert(pr.getstats(), f'cachegrind.out.{proc}_deterministic') - - -if __name__ == '__main__': - from openpilot.selfdrive.controls.controlsd import main as controlsd_thread - from openpilot.selfdrive.locationd.paramsd import main as paramsd_thread - from openpilot.selfdrive.controls.plannerd import main as plannerd_thread - - procs = { - 'controlsd': controlsd_thread, - 'paramsd': paramsd_thread, - 'plannerd': plannerd_thread, - } - - proc = sys.argv[1] - if proc not in procs: - print(f"{proc} not available") - sys.exit(0) - else: - profile(proc, procs[proc]) diff --git a/selfdrive/test/scons_build_test.sh b/selfdrive/test/scons_build_test.sh deleted file mode 100644 index a3b33f7..0000000 --- a/selfdrive/test/scons_build_test.sh +++ /dev/null @@ -1,10 +0,0 @@ -#!/bin/bash - -SCRIPT_DIR=$(dirname "$0") -BASEDIR=$(realpath "$SCRIPT_DIR/../../") -cd $BASEDIR - -# tests that our build system's dependencies are configured properly, -# needs a machine with lots of cores -scons --clean -scons --no-cache --random -j$(nproc) \ No newline at end of file diff --git a/selfdrive/test/setup_device_ci.sh b/selfdrive/test/setup_device_ci.sh deleted file mode 100755 index 5c85312..0000000 --- a/selfdrive/test/setup_device_ci.sh +++ /dev/null @@ -1,120 +0,0 @@ -#!/usr/bin/bash - -set -e - -if [ -z "$SOURCE_DIR" ]; then - echo "SOURCE_DIR must be set" - exit 1 -fi - -if [ -z "$GIT_COMMIT" ]; then - echo "GIT_COMMIT must be set" - exit 1 -fi - -if [ -z "$TEST_DIR" ]; then - echo "TEST_DIR must be set" - exit 1 -fi - -umount /data/safe_staging/merged/ || true -sudo umount /data/safe_staging/merged/ || true -rm -rf /data/safe_staging/* || true - -CONTINUE_PATH="/data/continue.sh" -tee $CONTINUE_PATH << EOF -#!/usr/bin/bash - -sudo abctl --set_success - -# patch sshd config -sudo mount -o rw,remount / -sudo sed -i "s,/data/params/d/GithubSshKeys,/usr/comma/setup_keys," /etc/ssh/sshd_config -sudo systemctl daemon-reload -sudo systemctl restart ssh -sudo systemctl restart NetworkManager -sudo systemctl disable ssh-param-watcher.path -sudo systemctl disable ssh-param-watcher.service -sudo mount -o ro,remount / - -while true; do - if ! sudo systemctl is-active -q ssh; then - sudo systemctl start ssh - fi - - #if ! pgrep -f 'ciui.py' > /dev/null 2>&1; then - # echo 'starting UI' - # cp $SOURCE_DIR/selfdrive/test/ciui.py /data/ - # /data/ciui.py & - #fi - - sleep 5s -done - -sleep infinity -EOF -chmod +x $CONTINUE_PATH - -safe_checkout() { - # completely clean TEST_DIR - - cd $SOURCE_DIR - - # cleanup orphaned locks - find .git -type f -name "*.lock" -exec rm {} + - - git reset --hard - git fetch --no-tags --no-recurse-submodules -j4 --verbose --depth 1 origin $GIT_COMMIT - find . -maxdepth 1 -not -path './.git' -not -name '.' -not -name '..' -exec rm -rf '{}' \; - git reset --hard $GIT_COMMIT - git checkout $GIT_COMMIT - git clean -xdff - git submodule sync - git submodule update --init --recursive - git submodule foreach --recursive "git reset --hard && git clean -xdff" - - git lfs pull - (ulimit -n 65535 && git lfs prune) - - echo "git checkout done, t=$SECONDS" - du -hs $SOURCE_DIR $SOURCE_DIR/.git - - rsync -a --delete $SOURCE_DIR $TEST_DIR -} - -unsafe_checkout() { - # checkout directly in test dir, leave old build products - - cd $TEST_DIR - - # cleanup orphaned locks - find .git -type f -name "*.lock" -exec rm {} + - - git fetch --no-tags --no-recurse-submodules -j8 --verbose --depth 1 origin $GIT_COMMIT - git checkout --force --no-recurse-submodules $GIT_COMMIT - git reset --hard $GIT_COMMIT - git clean -df - git submodule sync - git submodule update --init --recursive - git submodule foreach --recursive "git reset --hard && git clean -df" - - git lfs pull - (ulimit -n 65535 && git lfs prune) -} - -export GIT_PACK_THREADS=8 - -# set up environment -if [ ! -d "$SOURCE_DIR" ]; then - git clone https://github.com/commaai/openpilot.git $SOURCE_DIR -fi - -if [ ! -z "$UNSAFE" ]; then - echo "doing unsafe checkout" - unsafe_checkout -else - echo "doing safe checkout" - safe_checkout -fi - -echo "$TEST_DIR synced with $GIT_COMMIT, t=$SECONDS" diff --git a/selfdrive/test/setup_vsound.sh b/selfdrive/test/setup_vsound.sh deleted file mode 100644 index a6601d0..0000000 --- a/selfdrive/test/setup_vsound.sh +++ /dev/null @@ -1,10 +0,0 @@ -#!/bin/bash - -{ - #start pulseaudio daemon - sudo pulseaudio -D - - # create a virtual null audio and set it to default device - sudo pactl load-module module-null-sink sink_name=virtual_audio - sudo pactl set-default-sink virtual_audio -} > /dev/null 2>&1 diff --git a/selfdrive/test/setup_xvfb.sh b/selfdrive/test/setup_xvfb.sh deleted file mode 100644 index 692b84d..0000000 --- a/selfdrive/test/setup_xvfb.sh +++ /dev/null @@ -1,19 +0,0 @@ -#!/usr/bin/env bash - -# Sets up a virtual display for running map renderer and simulator without an X11 display - -DISP_ID=99 -export DISPLAY=:$DISP_ID - -sudo Xvfb $DISPLAY -screen 0 2160x1080x24 2>/dev/null & - -# check for x11 socket for the specified display ID -while [ ! -S /tmp/.X11-unix/X$DISP_ID ] -do - echo "Waiting for Xvfb..." - sleep 1 -done - -touch ~/.Xauthority -export XDG_SESSION_TYPE="x11" -xset -q \ No newline at end of file diff --git a/selfdrive/test/test_onroad.py b/selfdrive/test/test_onroad.py deleted file mode 100755 index 4be9b8a..0000000 --- a/selfdrive/test/test_onroad.py +++ /dev/null @@ -1,427 +0,0 @@ -#!/usr/bin/env python3 -import bz2 -import math -import json -import os -import pathlib -import psutil -import pytest -import shutil -import subprocess -import time -import numpy as np -import unittest -from collections import Counter, defaultdict -from functools import cached_property -from pathlib import Path - -from cereal import car -import cereal.messaging as messaging -from cereal.services import SERVICE_LIST -from openpilot.common.basedir import BASEDIR -from openpilot.common.timeout import Timeout -from openpilot.common.params import Params -from openpilot.selfdrive.controls.lib.events import EVENTS, ET -from openpilot.system.hardware import HARDWARE -from openpilot.selfdrive.test.helpers import set_params_enabled, release_only -from openpilot.system.hardware.hw import Paths -from openpilot.tools.lib.logreader import LogReader - -# Baseline CPU usage by process -PROCS = { - "selfdrive.controls.controlsd": 46.0, - "./loggerd": 14.0, - "./encoderd": 17.0, - "./camerad": 14.5, - "./locationd": 11.0, - "./mapsd": (0.5, 10.0), - "selfdrive.controls.plannerd": 11.0, - "./ui": 18.0, - "selfdrive.locationd.paramsd": 9.0, - "./sensord": 7.0, - "selfdrive.controls.radard": 7.0, - "selfdrive.modeld.modeld": 13.0, - "selfdrive.modeld.dmonitoringmodeld": 8.0, - "selfdrive.modeld.navmodeld": 1.0, - "selfdrive.thermald.thermald": 3.87, - "selfdrive.locationd.calibrationd": 2.0, - "selfdrive.locationd.torqued": 5.0, - "selfdrive.ui.soundd": 3.5, - "selfdrive.monitoring.dmonitoringd": 4.0, - "./proclogd": 1.54, - "system.logmessaged": 0.2, - "selfdrive.tombstoned": 0, - "./logcatd": 0, - "system.micd": 6.0, - "system.timed": 0, - "selfdrive.boardd.pandad": 0, - "selfdrive.statsd": 0.4, - "selfdrive.navd.navd": 0.4, - "system.loggerd.uploader": (0.5, 15.0), - "system.loggerd.deleter": 0.1, -} - -PROCS.update({ - "tici": { - "./boardd": 4.0, - "./ubloxd": 0.02, - "system.sensord.pigeond": 6.0, - }, - "tizi": { - "./boardd": 19.0, - "system.qcomgpsd.qcomgpsd": 1.0, - } -}.get(HARDWARE.get_device_type(), {})) - -TIMINGS = { - # rtols: max/min, rsd - "can": [2.5, 0.35], - "pandaStates": [2.5, 0.35], - "peripheralState": [2.5, 0.35], - "sendcan": [2.5, 0.35], - "carState": [2.5, 0.35], - "carControl": [2.5, 0.35], - "controlsState": [2.5, 0.35], - "longitudinalPlan": [2.5, 0.5], - "roadCameraState": [2.5, 0.35], - "driverCameraState": [2.5, 0.35], - "modelV2": [2.5, 0.35], - "driverStateV2": [2.5, 0.40], - "navModel": [2.5, 0.35], - "mapRenderState": [2.5, 0.35], - "liveLocationKalman": [2.5, 0.35], - "wideRoadCameraState": [1.5, 0.35], -} - - -def cputime_total(ct): - return ct.cpuUser + ct.cpuSystem + ct.cpuChildrenUser + ct.cpuChildrenSystem - - -@pytest.mark.tici -class TestOnroad(unittest.TestCase): - - @classmethod - def setUpClass(cls): - if "DEBUG" in os.environ: - segs = filter(lambda x: os.path.exists(os.path.join(x, "rlog")), Path(Paths.log_root()).iterdir()) - segs = sorted(segs, key=lambda x: x.stat().st_mtime) - print(segs[-3]) - cls.lr = list(LogReader(os.path.join(segs[-3], "rlog"))) - return - - # setup env - params = Params() - params.remove("CurrentRoute") - set_params_enabled() - os.environ['REPLAY'] = '1' - os.environ['TESTING_CLOSET'] = '1' - if os.path.exists(Paths.log_root()): - shutil.rmtree(Paths.log_root()) - - # start manager and run openpilot for a minute - proc = None - try: - manager_path = os.path.join(BASEDIR, "selfdrive/manager/manager.py") - proc = subprocess.Popen(["python", manager_path]) - - sm = messaging.SubMaster(['carState']) - with Timeout(150, "controls didn't start"): - while sm.recv_frame['carState'] < 0: - sm.update(1000) - - # make sure we get at least two full segments - route = None - cls.segments = [] - with Timeout(300, "timed out waiting for logs"): - while route is None: - route = params.get("CurrentRoute", encoding="utf-8") - time.sleep(0.1) - - while len(cls.segments) < 3: - segs = set() - if Path(Paths.log_root()).exists(): - segs = set(Path(Paths.log_root()).glob(f"{route}--*")) - cls.segments = sorted(segs, key=lambda s: int(str(s).rsplit('--')[-1])) - time.sleep(2) - - # chop off last, incomplete segment - cls.segments = cls.segments[:-1] - - finally: - cls.gpu_procs = {psutil.Process(int(f.name)).name() for f in pathlib.Path('/sys/devices/virtual/kgsl/kgsl/proc/').iterdir() if f.is_dir()} - - if proc is not None: - proc.terminate() - if proc.wait(60) is None: - proc.kill() - - cls.lrs = [list(LogReader(os.path.join(str(s), "rlog"))) for s in cls.segments] - - # use the second segment by default as it's the first full segment - cls.lr = list(LogReader(os.path.join(str(cls.segments[1]), "rlog"))) - cls.log_path = cls.segments[1] - - cls.log_sizes = {} - for f in cls.log_path.iterdir(): - assert f.is_file() - cls.log_sizes[f] = f.stat().st_size / 1e6 - if f.name in ("qlog", "rlog"): - with open(f, 'rb') as ff: - cls.log_sizes[f] = len(bz2.compress(ff.read())) / 1e6 - - - @cached_property - def service_msgs(self): - msgs = defaultdict(list) - for m in self.lr: - msgs[m.which()].append(m) - return msgs - - def test_service_frequencies(self): - for s, msgs in self.service_msgs.items(): - if s in ('initData', 'sentinel'): - continue - - # skip gps services for now - if s in ('ubloxGnss', 'ubloxRaw', 'gnssMeasurements', 'gpsLocation', 'gpsLocationExternal', 'qcomGnss'): - continue - - with self.subTest(service=s): - assert len(msgs) >= math.floor(SERVICE_LIST[s].frequency*55) - - def test_cloudlog_size(self): - msgs = [m for m in self.lr if m.which() == 'logMessage'] - - total_size = sum(len(m.as_builder().to_bytes()) for m in msgs) - self.assertLess(total_size, 3.5e5) - - cnt = Counter(json.loads(m.logMessage)['filename'] for m in msgs) - big_logs = [f for f, n in cnt.most_common(3) if n / sum(cnt.values()) > 30.] - self.assertEqual(len(big_logs), 0, f"Log spam: {big_logs}") - - def test_log_sizes(self): - for f, sz in self.log_sizes.items(): - if f.name == "qcamera.ts": - assert 2.15 < sz < 2.35 - elif f.name == "qlog": - assert 0.7 < sz < 1.0 - elif f.name == "rlog": - assert 5 < sz < 50 - elif f.name.endswith('.hevc'): - assert 70 < sz < 77 - else: - raise NotImplementedError - - def test_ui_timings(self): - result = "\n" - result += "------------------------------------------------\n" - result += "-------------- UI Draw Timing ------------------\n" - result += "------------------------------------------------\n" - - ts = [m.uiDebug.drawTimeMillis for m in self.service_msgs['uiDebug']] - result += f"min {min(ts):.2f}ms\n" - result += f"max {max(ts):.2f}ms\n" - result += f"std {np.std(ts):.2f}ms\n" - result += f"mean {np.mean(ts):.2f}ms\n" - result += "------------------------------------------------\n" - print(result) - - self.assertLess(max(ts), 250.) - self.assertLess(np.mean(ts), 10.) - #self.assertLess(np.std(ts), 5.) - - # some slow frames are expected since camerad/modeld can preempt ui - veryslow = [x for x in ts if x > 40.] - assert len(veryslow) < 5, f"Too many slow frame draw times: {veryslow}" - - def test_cpu_usage(self): - result = "\n" - result += "------------------------------------------------\n" - result += "------------------ CPU Usage -------------------\n" - result += "------------------------------------------------\n" - - plogs_by_proc = defaultdict(list) - for pl in self.service_msgs['procLog']: - for x in pl.procLog.procs: - if len(x.cmdline) > 0: - n = list(x.cmdline)[0] - plogs_by_proc[n].append(x) - print(plogs_by_proc.keys()) - - cpu_ok = True - dt = (self.service_msgs['procLog'][-1].logMonoTime - self.service_msgs['procLog'][0].logMonoTime) / 1e9 - for proc_name, expected_cpu in PROCS.items(): - - err = "" - cpu_usage = 0. - x = plogs_by_proc[proc_name] - if len(x) > 2: - cpu_time = cputime_total(x[-1]) - cputime_total(x[0]) - cpu_usage = cpu_time / dt * 100. - - if isinstance(expected_cpu, tuple): - exp = str(expected_cpu) - minn, maxx = expected_cpu - else: - exp = f"{expected_cpu:5.2f}" - minn = min(expected_cpu * 0.65, max(expected_cpu - 1.0, 0.0)) - maxx = max(expected_cpu * 1.15, expected_cpu + 5.0) - - if cpu_usage > maxx: - err = "using more CPU than expected" - elif cpu_usage < minn: - err = "using less CPU than expected" - else: - err = "NO METRICS FOUND" - - result += f"{proc_name.ljust(35)} {cpu_usage:5.2f}% ({exp}%) {err}\n" - if len(err) > 0: - cpu_ok = False - - # Ensure there's no missing procs - all_procs = {p.name for p in self.service_msgs['managerState'][0].managerState.processes if p.shouldBeRunning} - for p in all_procs: - with self.subTest(proc=p): - assert any(p in pp for pp in PROCS.keys()), f"Expected CPU usage missing for {p}" - - result += "------------------------------------------------\n" - print(result) - - self.assertTrue(cpu_ok) - - def test_memory_usage(self): - mems = [m.deviceState.memoryUsagePercent for m in self.service_msgs['deviceState']] - print("Memory usage: ", mems) - - # check for big leaks. note that memory usage is - # expected to go up while the MSGQ buffers fill up - self.assertLessEqual(max(mems) - min(mems), 3.0) - - def test_gpu_usage(self): - self.assertEqual(self.gpu_procs, {"weston", "ui", "camerad", "selfdrive.modeld.modeld"}) - - def test_camera_processing_time(self): - result = "\n" - result += "------------------------------------------------\n" - result += "-------------- Debayer Timing ------------------\n" - result += "------------------------------------------------\n" - - ts = [getattr(m, m.which()).processingTime for m in self.lr if 'CameraState' in m.which()] - self.assertLess(min(ts), 0.025, f"high execution time: {min(ts)}") - result += f"execution time: min {min(ts):.5f}s\n" - result += f"execution time: max {max(ts):.5f}s\n" - result += f"execution time: mean {np.mean(ts):.5f}s\n" - result += "------------------------------------------------\n" - print(result) - - @unittest.skip("TODO: enable once timings are fixed") - def test_camera_frame_timings(self): - result = "\n" - result += "------------------------------------------------\n" - result += "----------------- SoF Timing ------------------\n" - result += "------------------------------------------------\n" - for name in ['roadCameraState', 'wideRoadCameraState', 'driverCameraState']: - ts = [getattr(m, m.which()).timestampSof for m in self.lr if name in m.which()] - d_ms = np.diff(ts) / 1e6 - d50 = np.abs(d_ms-50) - self.assertLess(max(d50), 1.0, f"high sof delta vs 50ms: {max(d50)}") - result += f"{name} sof delta vs 50ms: min {min(d50):.5f}s\n" - result += f"{name} sof delta vs 50ms: max {max(d50):.5f}s\n" - result += f"{name} sof delta vs 50ms: mean {d50.mean():.5f}s\n" - result += "------------------------------------------------\n" - print(result) - - def test_mpc_execution_timings(self): - result = "\n" - result += "------------------------------------------------\n" - result += "----------------- MPC Timing ------------------\n" - result += "------------------------------------------------\n" - - cfgs = [("longitudinalPlan", 0.05, 0.05),] - for (s, instant_max, avg_max) in cfgs: - ts = [getattr(m, s).solverExecutionTime for m in self.service_msgs[s]] - self.assertLess(max(ts), instant_max, f"high '{s}' execution time: {max(ts)}") - self.assertLess(np.mean(ts), avg_max, f"high avg '{s}' execution time: {np.mean(ts)}") - result += f"'{s}' execution time: min {min(ts):.5f}s\n" - result += f"'{s}' execution time: max {max(ts):.5f}s\n" - result += f"'{s}' execution time: mean {np.mean(ts):.5f}s\n" - result += "------------------------------------------------\n" - print(result) - - def test_model_execution_timings(self): - result = "\n" - result += "------------------------------------------------\n" - result += "----------------- Model Timing -----------------\n" - result += "------------------------------------------------\n" - # TODO: this went up when plannerd cpu usage increased, why? - cfgs = [ - ("modelV2", 0.050, 0.036), - ("driverStateV2", 0.050, 0.026), - ] - for (s, instant_max, avg_max) in cfgs: - ts = [getattr(m, s).modelExecutionTime for m in self.service_msgs[s]] - self.assertLess(max(ts), instant_max, f"high '{s}' execution time: {max(ts)}") - self.assertLess(np.mean(ts), avg_max, f"high avg '{s}' execution time: {np.mean(ts)}") - result += f"'{s}' execution time: min {min(ts):.5f}s\n" - result += f"'{s}' execution time: max {max(ts):.5f}s\n" - result += f"'{s}' execution time: mean {np.mean(ts):.5f}s\n" - result += "------------------------------------------------\n" - print(result) - - def test_timings(self): - passed = True - result = "\n" - result += "------------------------------------------------\n" - result += "----------------- Service Timings --------------\n" - result += "------------------------------------------------\n" - for s, (maxmin, rsd) in TIMINGS.items(): - msgs = [m.logMonoTime for m in self.service_msgs[s]] - if not len(msgs): - raise Exception(f"missing {s}") - - ts = np.diff(msgs) / 1e9 - dt = 1 / SERVICE_LIST[s].frequency - - try: - np.testing.assert_allclose(np.mean(ts), dt, rtol=0.03, err_msg=f"{s} - failed mean timing check") - np.testing.assert_allclose([np.max(ts), np.min(ts)], dt, rtol=maxmin, err_msg=f"{s} - failed max/min timing check") - except Exception as e: - result += str(e) + "\n" - passed = False - - if np.std(ts) / dt > rsd: - result += f"{s} - failed RSD timing check\n" - passed = False - - result += f"{s.ljust(40)}: {np.array([np.mean(ts), np.max(ts), np.min(ts)])*1e3}\n" - result += f"{''.ljust(40)} {np.max(np.absolute([np.max(ts)/dt, np.min(ts)/dt]))} {np.std(ts)/dt}\n" - result += "="*67 - print(result) - self.assertTrue(passed) - - @release_only - def test_startup(self): - startup_alert = None - for msg in self.lrs[0]: - # can't use onroadEvents because the first msg can be dropped while loggerd is starting up - if msg.which() == "controlsState": - startup_alert = msg.controlsState.alertText1 - break - expected = EVENTS[car.CarEvent.EventName.startup][ET.PERMANENT].alert_text_1 - self.assertEqual(startup_alert, expected, "wrong startup alert") - - def test_engagable(self): - no_entries = Counter() - for m in self.service_msgs['onroadEvents']: - for evt in m.onroadEvents: - if evt.noEntry: - no_entries[evt.name] += 1 - - eng = [m.controlsState.engageable for m in self.service_msgs['controlsState']] - assert all(eng), \ - f"Not engageable for whole segment:\n- controlsState.engageable: {Counter(eng)}\n- No entry events: {no_entries}" - - -if __name__ == "__main__": - unittest.main() diff --git a/selfdrive/test/test_time_to_onroad.py b/selfdrive/test/test_time_to_onroad.py deleted file mode 100755 index a3f803e..0000000 --- a/selfdrive/test/test_time_to_onroad.py +++ /dev/null @@ -1,57 +0,0 @@ -#!/usr/bin/env python3 -import os -import pytest -import time -import subprocess - -import cereal.messaging as messaging -from openpilot.common.basedir import BASEDIR -from openpilot.common.timeout import Timeout -from openpilot.selfdrive.test.helpers import set_params_enabled - - -@pytest.mark.tici -def test_time_to_onroad(): - # launch - set_params_enabled() - manager_path = os.path.join(BASEDIR, "selfdrive/manager/manager.py") - proc = subprocess.Popen(["python", manager_path]) - - start_time = time.monotonic() - sm = messaging.SubMaster(['controlsState', 'deviceState', 'onroadEvents', 'sendcan']) - try: - # wait for onroad. timeout assumes panda is up to date - with Timeout(10, "timed out waiting to go onroad"): - while not sm['deviceState'].started: - sm.update(100) - - # wait for engageability - try: - with Timeout(10, "timed out waiting for engageable"): - sendcan_frame = None - while True: - sm.update(100) - - # sendcan is only sent once we're initialized - if sm.seen['controlsState'] and sendcan_frame is None: - sendcan_frame = sm.frame - - if sendcan_frame is not None and sm.recv_frame['sendcan'] > sendcan_frame: - sm.update(100) - assert sm['controlsState'].engageable, f"events: {sm['onroadEvents']}" - break - finally: - print(f"onroad events: {sm['onroadEvents']}") - print(f"engageable after {time.monotonic() - start_time:.2f}s") - - # once we're enageable, must stay for the next few seconds - st = time.monotonic() - while (time.monotonic() - st) < 10.: - sm.update(100) - assert sm.all_alive(), sm.alive - assert sm['controlsState'].engageable, f"events: {sm['onroadEvents']}" - assert sm['controlsState'].cumLagMs < 10. - finally: - proc.terminate() - if proc.wait(20) is None: - proc.kill() diff --git a/selfdrive/test/test_updated.py b/selfdrive/test/test_updated.py deleted file mode 100644 index dd79e03..0000000 --- a/selfdrive/test/test_updated.py +++ /dev/null @@ -1,302 +0,0 @@ -#!/usr/bin/env python3 -import datetime -import os -import pytest -import time -import tempfile -import unittest -import shutil -import signal -import subprocess -import random - -from openpilot.common.basedir import BASEDIR -from openpilot.common.params import Params - - -@pytest.mark.tici -class TestUpdated(unittest.TestCase): - - def setUp(self): - self.updated_proc = None - - self.tmp_dir = tempfile.TemporaryDirectory() - org_dir = os.path.join(self.tmp_dir.name, "commaai") - - self.basedir = os.path.join(org_dir, "openpilot") - self.git_remote_dir = os.path.join(org_dir, "openpilot_remote") - self.staging_dir = os.path.join(org_dir, "safe_staging") - for d in [org_dir, self.basedir, self.git_remote_dir, self.staging_dir]: - os.mkdir(d) - - self.neos_version = os.path.join(org_dir, "neos_version") - self.neosupdate_dir = os.path.join(org_dir, "neosupdate") - with open(self.neos_version, "w") as f: - v = subprocess.check_output(r"bash -c 'source launch_env.sh && echo $REQUIRED_NEOS_VERSION'", - cwd=BASEDIR, shell=True, encoding='utf8').strip() - f.write(v) - - self.upper_dir = os.path.join(self.staging_dir, "upper") - self.merged_dir = os.path.join(self.staging_dir, "merged") - self.finalized_dir = os.path.join(self.staging_dir, "finalized") - - # setup local submodule remotes - submodules = subprocess.check_output("git submodule --quiet foreach 'echo $name'", - shell=True, cwd=BASEDIR, encoding='utf8').split() - for s in submodules: - sub_path = os.path.join(org_dir, s.split("_repo")[0]) - self._run(f"git clone {s} {sub_path}.git", cwd=BASEDIR) - - # setup two git repos, a remote and one we'll run updated in - self._run([ - f"git clone {BASEDIR} {self.git_remote_dir}", - f"git clone {self.git_remote_dir} {self.basedir}", - f"cd {self.basedir} && git submodule init && git submodule update", - f"cd {self.basedir} && scons -j{os.cpu_count()} cereal/ common/" - ]) - - self.params = Params(os.path.join(self.basedir, "persist/params")) - self.params.clear_all() - os.sync() - - def tearDown(self): - try: - if self.updated_proc is not None: - self.updated_proc.terminate() - self.updated_proc.wait(30) - except Exception as e: - print(e) - self.tmp_dir.cleanup() - - - # *** test helpers *** - - - def _run(self, cmd, cwd=None): - if not isinstance(cmd, list): - cmd = (cmd,) - - for c in cmd: - subprocess.check_output(c, cwd=cwd, shell=True) - - def _get_updated_proc(self): - os.environ["PYTHONPATH"] = self.basedir - os.environ["GIT_AUTHOR_NAME"] = "testy tester" - os.environ["GIT_COMMITTER_NAME"] = "testy tester" - os.environ["GIT_AUTHOR_EMAIL"] = "testy@tester.test" - os.environ["GIT_COMMITTER_EMAIL"] = "testy@tester.test" - os.environ["UPDATER_TEST_IP"] = "localhost" - os.environ["UPDATER_LOCK_FILE"] = os.path.join(self.tmp_dir.name, "updater.lock") - os.environ["UPDATER_STAGING_ROOT"] = self.staging_dir - os.environ["UPDATER_NEOS_VERSION"] = self.neos_version - os.environ["UPDATER_NEOSUPDATE_DIR"] = self.neosupdate_dir - updated_path = os.path.join(self.basedir, "selfdrive/updated.py") - return subprocess.Popen(updated_path, env=os.environ) - - def _start_updater(self, offroad=True, nosleep=False): - self.params.put_bool("IsOffroad", offroad) - self.updated_proc = self._get_updated_proc() - if not nosleep: - time.sleep(1) - - def _update_now(self): - self.updated_proc.send_signal(signal.SIGHUP) - - # TODO: this should be implemented in params - def _read_param(self, key, timeout=1): - ret = None - start_time = time.monotonic() - while ret is None: - ret = self.params.get(key, encoding='utf8') - if time.monotonic() - start_time > timeout: - break - time.sleep(0.01) - return ret - - def _wait_for_update(self, timeout=30, clear_param=False): - if clear_param: - self.params.remove("LastUpdateTime") - - self._update_now() - t = self._read_param("LastUpdateTime", timeout=timeout) - if t is None: - raise Exception("timed out waiting for update to complete") - - def _make_commit(self): - all_dirs, all_files = [], [] - for root, dirs, files in os.walk(self.git_remote_dir): - if ".git" in root: - continue - for d in dirs: - all_dirs.append(os.path.join(root, d)) - for f in files: - all_files.append(os.path.join(root, f)) - - # make a new dir and some new files - new_dir = os.path.join(self.git_remote_dir, "this_is_a_new_dir") - os.mkdir(new_dir) - for _ in range(random.randrange(5, 30)): - for d in (new_dir, random.choice(all_dirs)): - with tempfile.NamedTemporaryFile(dir=d, delete=False) as f: - f.write(os.urandom(random.randrange(1, 1000000))) - - # modify some files - for f in random.sample(all_files, random.randrange(5, 50)): - with open(f, "w+") as ff: - txt = ff.readlines() - ff.seek(0) - for line in txt: - ff.write(line[::-1]) - - # remove some files - for f in random.sample(all_files, random.randrange(5, 50)): - os.remove(f) - - # remove some dirs - for d in random.sample(all_dirs, random.randrange(1, 10)): - shutil.rmtree(d) - - # commit the changes - self._run([ - "git add -A", - "git commit -m 'an update'", - ], cwd=self.git_remote_dir) - - def _check_update_state(self, update_available): - # make sure LastUpdateTime is recent - t = self._read_param("LastUpdateTime") - last_update_time = datetime.datetime.fromisoformat(t) - td = datetime.datetime.utcnow() - last_update_time - self.assertLess(td.total_seconds(), 10) - self.params.remove("LastUpdateTime") - - # wait a bit for the rest of the params to be written - time.sleep(0.1) - - # check params - update = self._read_param("UpdateAvailable") - self.assertEqual(update == "1", update_available, f"UpdateAvailable: {repr(update)}") - self.assertEqual(self._read_param("UpdateFailedCount"), "0") - - # TODO: check that the finalized update actually matches remote - # check the .overlay_init and .overlay_consistent flags - self.assertTrue(os.path.isfile(os.path.join(self.basedir, ".overlay_init"))) - self.assertEqual(os.path.isfile(os.path.join(self.finalized_dir, ".overlay_consistent")), update_available) - - - # *** test cases *** - - - # Run updated for 100 cycles with no update - def test_no_update(self): - self._start_updater() - for _ in range(100): - self._wait_for_update(clear_param=True) - self._check_update_state(False) - - # Let the updater run with no update for a cycle, then write an update - def test_update(self): - self._start_updater() - - # run for a cycle with no update - self._wait_for_update(clear_param=True) - self._check_update_state(False) - - # write an update to our remote - self._make_commit() - - # run for a cycle to get the update - self._wait_for_update(timeout=60, clear_param=True) - self._check_update_state(True) - - # run another cycle with no update - self._wait_for_update(clear_param=True) - self._check_update_state(True) - - # Let the updater run for 10 cycles, and write an update every cycle - @unittest.skip("need to make this faster") - def test_update_loop(self): - self._start_updater() - - # run for a cycle with no update - self._wait_for_update(clear_param=True) - for _ in range(10): - time.sleep(0.5) - self._make_commit() - self._wait_for_update(timeout=90, clear_param=True) - self._check_update_state(True) - - # Test overlay re-creation after tracking a new file in basedir's git - def test_overlay_reinit(self): - self._start_updater() - - overlay_init_fn = os.path.join(self.basedir, ".overlay_init") - - # run for a cycle with no update - self._wait_for_update(clear_param=True) - self.params.remove("LastUpdateTime") - first_mtime = os.path.getmtime(overlay_init_fn) - - # touch a file in the basedir - self._run("touch new_file && git add new_file", cwd=self.basedir) - - # run another cycle, should have a new mtime - self._wait_for_update(clear_param=True) - second_mtime = os.path.getmtime(overlay_init_fn) - self.assertTrue(first_mtime != second_mtime) - - # run another cycle, mtime should be same as last cycle - self._wait_for_update(clear_param=True) - new_mtime = os.path.getmtime(overlay_init_fn) - self.assertTrue(second_mtime == new_mtime) - - # Make sure updated exits if another instance is running - def test_multiple_instances(self): - # start updated and let it run for a cycle - self._start_updater() - time.sleep(1) - self._wait_for_update(clear_param=True) - - # start another instance - second_updated = self._get_updated_proc() - ret_code = second_updated.wait(timeout=5) - self.assertTrue(ret_code is not None) - - - # *** test cases with NEOS updates *** - - - # Run updated with no update, make sure it clears the old NEOS update - def test_clear_neos_cache(self): - # make the dir and some junk files - os.mkdir(self.neosupdate_dir) - for _ in range(15): - with tempfile.NamedTemporaryFile(dir=self.neosupdate_dir, delete=False) as f: - f.write(os.urandom(random.randrange(1, 1000000))) - - self._start_updater() - self._wait_for_update(clear_param=True) - self._check_update_state(False) - self.assertFalse(os.path.isdir(self.neosupdate_dir)) - - # Let the updater run with no update for a cycle, then write an update - @unittest.skip("TODO: only runs on device") - def test_update_with_neos_update(self): - # bump the NEOS version and commit it - self._run([ - "echo 'export REQUIRED_NEOS_VERSION=3' >> launch_env.sh", - "git -c user.name='testy' -c user.email='testy@tester.test' \ - commit -am 'a neos update'", - ], cwd=self.git_remote_dir) - - # run for a cycle to get the update - self._start_updater() - self._wait_for_update(timeout=60, clear_param=True) - self._check_update_state(True) - - # TODO: more comprehensive check - self.assertTrue(os.path.isdir(self.neosupdate_dir)) - - -if __name__ == "__main__": - unittest.main() diff --git a/selfdrive/test/test_valgrind_replay.py b/selfdrive/test/test_valgrind_replay.py deleted file mode 100644 index 75520df..0000000 --- a/selfdrive/test/test_valgrind_replay.py +++ /dev/null @@ -1,117 +0,0 @@ -#!/usr/bin/env python3 -import os -import threading -import time -import unittest -import subprocess -import signal - -if "CI" in os.environ: - def tqdm(x): - return x -else: - from tqdm import tqdm # type: ignore - -import cereal.messaging as messaging -from collections import namedtuple -from openpilot.tools.lib.logreader import LogReader -from openpilot.tools.lib.openpilotci import get_url -from openpilot.common.basedir import BASEDIR - -ProcessConfig = namedtuple('ProcessConfig', ['proc_name', 'pub_sub', 'ignore', 'command', 'path', 'segment', 'wait_for_response']) - -CONFIGS = [ - ProcessConfig( - proc_name="ubloxd", - pub_sub={ - "ubloxRaw": ["ubloxGnss", "gpsLocationExternal"], - }, - ignore=[], - command="./ubloxd", - path="system/ubloxd", - segment="0375fdf7b1ce594d|2019-06-13--08-32-25--3", - wait_for_response=True - ), -] - - -class TestValgrind(unittest.TestCase): - def extract_leak_sizes(self, log): - if "All heap blocks were freed -- no leaks are possible" in log: - return (0,0,0) - - log = log.replace(",","") # fixes casting to int issue with large leaks - err_lost1 = log.split("definitely lost: ")[1] - err_lost2 = log.split("indirectly lost: ")[1] - err_lost3 = log.split("possibly lost: ")[1] - definitely_lost = int(err_lost1.split(" ")[0]) - indirectly_lost = int(err_lost2.split(" ")[0]) - possibly_lost = int(err_lost3.split(" ")[0]) - return (definitely_lost, indirectly_lost, possibly_lost) - - def valgrindlauncher(self, arg, cwd): - os.chdir(os.path.join(BASEDIR, cwd)) - # Run valgrind on a process - command = "valgrind --leak-check=full " + arg - p = subprocess.Popen(command, stderr=subprocess.PIPE, shell=True, preexec_fn=os.setsid) - - while not self.replay_done: - time.sleep(0.1) - - # Kill valgrind and extract leak output - os.killpg(os.getpgid(p.pid), signal.SIGINT) - _, err = p.communicate() - error_msg = str(err, encoding='utf-8') - with open(os.path.join(BASEDIR, "selfdrive/test/valgrind_logs.txt"), "a") as f: - f.write(error_msg) - f.write(5 * "\n") - definitely_lost, indirectly_lost, possibly_lost = self.extract_leak_sizes(error_msg) - if max(definitely_lost, indirectly_lost, possibly_lost) > 0: - self.leak = True - print("LEAKS from", arg, "\nDefinitely lost:", definitely_lost, "\nIndirectly lost", indirectly_lost, "\nPossibly lost", possibly_lost) - else: - self.leak = False - - def replay_process(self, config, logreader): - pub_sockets = list(config.pub_sub.keys()) # We dump data from logs here - sub_sockets = [s for _, sub in config.pub_sub.items() for s in sub] # We get responses here - pm = messaging.PubMaster(pub_sockets) - sm = messaging.SubMaster(sub_sockets) - - print("Sorting logs") - all_msgs = sorted(logreader, key=lambda msg: msg.logMonoTime) - pub_msgs = [msg for msg in all_msgs if msg.which() in list(config.pub_sub.keys())] - - thread = threading.Thread(target=self.valgrindlauncher, args=(config.command, config.path)) - thread.daemon = True - thread.start() - - while not all(pm.all_readers_updated(s) for s in config.pub_sub.keys()): - time.sleep(0) - - for msg in tqdm(pub_msgs): - pm.send(msg.which(), msg.as_builder()) - if config.wait_for_response: - sm.update(100) - - self.replay_done = True - - def test_config(self): - open(os.path.join(BASEDIR, "selfdrive/test/valgrind_logs.txt"), "w").close() - - for cfg in CONFIGS: - self.leak = None - self.replay_done = False - - r, n = cfg.segment.rsplit("--", 1) - lr = LogReader(get_url(r, n)) - self.replay_process(cfg, lr) - - while self.leak is None: - time.sleep(0.1) # Wait for the valgrind to finish - - self.assertFalse(self.leak) - - -if __name__ == "__main__": - unittest.main() diff --git a/selfdrive/test/update_ci_routes.py b/selfdrive/test/update_ci_routes.py deleted file mode 100644 index a9f4494..0000000 --- a/selfdrive/test/update_ci_routes.py +++ /dev/null @@ -1,84 +0,0 @@ -#!/usr/bin/env python3 -import os -import re -import subprocess -import sys -from collections.abc import Iterable - -from tqdm import tqdm - -from openpilot.selfdrive.car.tests.routes import routes as test_car_models_routes -from openpilot.selfdrive.test.process_replay.test_processes import source_segments as replay_segments -from openpilot.tools.lib.azure_container import AzureContainer -from openpilot.tools.lib.openpilotcontainers import DataCIContainer, DataProdContainer, OpenpilotCIContainer - -SOURCES: list[AzureContainer] = [ - DataProdContainer, - DataCIContainer -] - -DEST = OpenpilotCIContainer - -def upload_route(path: str, exclude_patterns: Iterable[str] = None) -> None: - if exclude_patterns is None: - exclude_patterns = [r'dcamera\.hevc'] - - r, n = path.rsplit("--", 1) - r = '/'.join(r.split('/')[-2:]) # strip out anything extra in the path - destpath = f"{r}/{n}" - for file in os.listdir(path): - if any(re.search(pattern, file) for pattern in exclude_patterns): - continue - DEST.upload_file(os.path.join(path, file), f"{destpath}/{file}") - - -def sync_to_ci_public(route: str) -> bool: - dest_container, dest_key = DEST.get_client_and_key() - key_prefix = route.replace('|', '/') - dongle_id = key_prefix.split('/')[0] - - if next(dest_container.list_blob_names(name_starts_with=key_prefix), None) is not None: - return True - - print(f"Uploading {route}") - for source_container in SOURCES: - # assumes az login has been run - print(f"Trying {source_container.ACCOUNT}/{source_container.CONTAINER}") - _, source_key = source_container.get_client_and_key() - cmd = [ - "azcopy", - "copy", - f"{source_container.BASE_URL}{key_prefix}?{source_key}", - f"{DEST.BASE_URL}{dongle_id}?{dest_key}", - "--recursive=true", - "--overwrite=false", - "--exclude-pattern=*/dcamera.hevc", - ] - - try: - result = subprocess.call(cmd, stdout=subprocess.DEVNULL) - if result == 0: - print("Success") - return True - except subprocess.CalledProcessError: - print("Failed") - - return False - - -if __name__ == "__main__": - failed_routes = [] - - to_sync = sys.argv[1:] - - if not len(to_sync): - # sync routes from the car tests routes and process replay - to_sync.extend([rt.route for rt in test_car_models_routes]) - to_sync.extend([s[1].rsplit('--', 1)[0] for s in replay_segments]) - - for r in tqdm(to_sync): - if not sync_to_ci_public(r): - failed_routes.append(r) - - if len(failed_routes): - print("failed routes:", failed_routes) diff --git a/selfdrive/ui/SConscript b/selfdrive/ui/SConscript deleted file mode 100644 index aeee164..0000000 --- a/selfdrive/ui/SConscript +++ /dev/null @@ -1,141 +0,0 @@ -import os -import json -Import('qt_env', 'arch', 'common', 'messaging', 'visionipc', - 'cereal', 'transformations') - -base_libs = [common, messaging, cereal, visionipc, transformations, 'zmq', - 'capnp', 'kj', 'm', 'OpenCL', 'ssl', 'crypto', 'pthread', 'OmxCore', 'avformat', 'avcodec', 'avutil', 'yuv'] + qt_env["LIBS"] - -if arch == 'larch64': - base_libs.append('EGL') - -maps = arch in ['larch64', 'aarch64', 'x86_64'] - -if arch == "Darwin": - del base_libs[base_libs.index('OpenCL')] - qt_env['FRAMEWORKS'] += ['OpenCL'] - -# FIXME: remove this once we're on 5.15 (24.04) -qt_env['CXXFLAGS'] += ["-Wno-deprecated-declarations"] - -qt_util = qt_env.Library("qt_util", ["#selfdrive/ui/qt/api.cc", "#selfdrive/ui/qt/util.cc"], LIBS=base_libs) -widgets_src = ["ui.cc", "qt/widgets/input.cc", "qt/widgets/drive_stats.cc", "qt/widgets/wifi.cc", - "qt/widgets/ssh_keys.cc", "qt/widgets/toggle.cc", "qt/widgets/controls.cc", - "qt/widgets/offroad_alerts.cc", "qt/widgets/prime.cc", "qt/widgets/keyboard.cc", - "qt/widgets/scrollview.cc", "qt/widgets/cameraview.cc", "#third_party/qrcode/QrCode.cc", - "qt/request_repeater.cc", "qt/qt_window.cc", "qt/network/networking.cc", "qt/network/wifi_manager.cc", - "../frogpilot/ui/frogpilot_ui_functions.cc", "../frogpilot/navigation/ui/navigation_settings.cc", - "../frogpilot/ui/control_settings.cc", "../frogpilot/ui/vehicle_settings.cc", - "../frogpilot/ui/visual_settings.cc"] - -qt_env['CPPDEFINES'] = [] -if maps: - base_libs += ['QMapLibre'] - widgets_src += ["qt/maps/map_helpers.cc", "qt/maps/map_settings.cc", "qt/maps/map.cc", "qt/maps/map_panel.cc", - "qt/maps/map_eta.cc", "qt/maps/map_instructions.cc"] - qt_env['CPPDEFINES'] += ["ENABLE_MAPS"] - -widgets = qt_env.Library("qt_widgets", widgets_src, LIBS=base_libs) -Export('widgets') -qt_libs = [widgets, qt_util] + base_libs - -qt_src = ["main.cc", "qt/sidebar.cc", "qt/onroad.cc", "qt/body.cc", - "qt/window.cc", "qt/home.cc", "qt/offroad/settings.cc", - "qt/offroad/software_settings.cc", "qt/offroad/onboarding.cc", - "qt/offroad/driverview.cc", "qt/offroad/experimental_mode.cc", - "../frogpilot/screenrecorder/omx_encoder.cc", "../frogpilot/screenrecorder/screenrecorder.cc"] - -if GetOption("nosr"): - qt_env.Append(CXXFLAGS=['-DNO_SR']) - base_libs.remove('OmxCore') - qt_libs.remove('OmxCore') - qt_src.remove("../frogpilot/screenrecorder/screenrecorder.cc") - qt_src.remove("../frogpilot/screenrecorder/omx_encoder.cc") - print("Removing Screen Recorder") - -# build translation files -with open(File("translations/languages.json").abspath) as f: - languages = json.loads(f.read()) -translation_sources = [f"#selfdrive/ui/translations/{l}.ts" for l in languages.values()] -translation_targets = [src.replace(".ts", ".qm") for src in translation_sources] -lrelease_bin = 'third_party/qt5/larch64/bin/lrelease' if arch == 'larch64' else 'lrelease' - -lupdate = qt_env.Command(translation_sources, qt_src + widgets_src, "selfdrive/ui/update_translations.py") -lrelease = qt_env.Command(translation_targets, translation_sources, f"{lrelease_bin} $SOURCES") -qt_env.Depends(lrelease, lupdate) -qt_env.NoClean(translation_sources) -qt_env.Precious(translation_sources) -qt_env.NoCache(lupdate) - -# create qrc file for compiled translations to include with assets -translations_assets_src = "#selfdrive/assets/translations_assets.qrc" -with open(File(translations_assets_src).abspath, 'w') as f: - f.write('\n\n') - f.write('\n'.join([f'../ui/translations/{l}.qm' for l in languages.values()])) - f.write('\n\n') - -# build assets -assets = "#selfdrive/assets/assets.cc" -assets_src = "#selfdrive/assets/assets.qrc" -qt_env.Command(assets, [assets_src, translations_assets_src], f"rcc $SOURCES -o $TARGET") -qt_env.Depends(assets, Glob('#selfdrive/assets/*', exclude=[assets, assets_src, translations_assets_src, "#selfdrive/assets/assets.o"]) + [lrelease]) -asset_obj = qt_env.Object("assets", assets) - -qt_env.SharedLibrary("qt/python_helpers", ["qt/qt_window.cc"], LIBS=qt_libs) - -# spinner and text window -qt_env.Program("_text", ["qt/text.cc"], LIBS=qt_libs) -qt_env.Program("_spinner", ["qt/spinner.cc"], LIBS=qt_libs) - -# build main UI -qt_env.Program("ui", qt_src + [asset_obj], LIBS=qt_libs) -if GetOption('extras'): - qt_src.remove("main.cc") # replaced by test_runner - qt_env.Program('tests/test_translations', [asset_obj, 'tests/test_runner.cc', 'tests/test_translations.cc'] + qt_src, LIBS=qt_libs) - qt_env.Program('tests/ui_snapshot', [asset_obj, "tests/ui_snapshot.cc"] + qt_src, LIBS=qt_libs) - -qt_env['CPPPATH'] += ["../frogpilot/screenrecorder/openmax/include/"] - -if GetOption('extras') and arch != "Darwin": - # setup and factory resetter - qt_env.Program("qt/setup/reset", ["qt/setup/reset.cc"], LIBS=qt_libs) - qt_env.Program("qt/setup/setup", ["qt/setup/setup.cc", asset_obj], - LIBS=qt_libs + ['curl', 'common', 'json11']) - - # build updater UI - qt_env.Program("qt/setup/updater", ["qt/setup/updater.cc", asset_obj], LIBS=qt_libs) - - # build mui - qt_env.Program("mui", ["mui.cc"], LIBS=qt_libs) - - # build installers - senv = qt_env.Clone() - senv['LINKFLAGS'].append('-Wl,-strip-debug') - - release = "release3" - installers = [ - ("openpilot", release), - ("openpilot_test", f"{release}-staging"), - ("openpilot_nightly", "nightly"), - ("openpilot_internal", "master"), - ] - - cont = senv.Command(f"installer/continue_openpilot.o", f"installer/continue_openpilot.sh", - "ld -r -b binary -o $TARGET $SOURCE") - for name, branch in installers: - d = {'BRANCH': f"'\"{branch}\"'"} - if "internal" in name: - d['INTERNAL'] = "1" - - import requests - r = requests.get("https://github.com/commaci2.keys") - r.raise_for_status() - d['SSH_KEYS'] = f'\\"{r.text.strip()}\\"' - obj = senv.Object(f"installer/installers/installer_{name}.o", ["installer/installer.cc"], CPPDEFINES=d) - f = senv.Program(f"installer/installers/installer_{name}", [obj, cont], LIBS=qt_libs) - # keep installers small - assert f[0].get_size() < 350*1e3 - -# build watch3 -if arch in ['x86_64', 'aarch64', 'Darwin'] or GetOption('extras'): - qt_env.Program("watch3", ["watch3.cc"], LIBS=qt_libs + ['common', 'json11', 'zmq', 'visionipc', 'messaging']) diff --git a/selfdrive/ui/_spinner b/selfdrive/ui/_spinner new file mode 100755 index 0000000..0e10c27 Binary files /dev/null and b/selfdrive/ui/_spinner differ diff --git a/selfdrive/ui/_text b/selfdrive/ui/_text new file mode 100755 index 0000000..cc7647e Binary files /dev/null and b/selfdrive/ui/_text differ diff --git a/selfdrive/ui/installer/installer.cc b/selfdrive/ui/installer/installer.cc deleted file mode 100644 index d43ed37..0000000 --- a/selfdrive/ui/installer/installer.cc +++ /dev/null @@ -1,221 +0,0 @@ -#include -#include - -#include -#include -#include -#include - -#include -#include -#include -#include - -#include "selfdrive/ui/installer/installer.h" -#include "selfdrive/ui/qt/util.h" -#include "selfdrive/ui/qt/qt_window.h" - -std::string get_str(std::string const s) { - std::string::size_type pos = s.find('?'); - assert(pos != std::string::npos); - return s.substr(0, pos); -} - -// Leave some extra space for the fork installer -const std::string GIT_URL = get_str("https://github.com/commaai/openpilot.git" "? "); -const std::string BRANCH_STR = get_str(BRANCH "? "); - -#define GIT_SSH_URL "git@github.com:commaai/openpilot.git" -#define CONTINUE_PATH "/data/continue.sh" - -const QString CACHE_PATH = "/data/openpilot.cache"; - -#define INSTALL_PATH "/data/openpilot" -#define TMP_INSTALL_PATH "/data/tmppilot" - -extern const uint8_t str_continue[] asm("_binary_selfdrive_ui_installer_continue_openpilot_sh_start"); -extern const uint8_t str_continue_end[] asm("_binary_selfdrive_ui_installer_continue_openpilot_sh_end"); - -bool time_valid() { - time_t rawtime; - time(&rawtime); - - struct tm * sys_time = gmtime(&rawtime); - return (1900 + sys_time->tm_year) >= 2020; -} - -void run(const char* cmd) { - int err = std::system(cmd); - assert(err == 0); -} - -Installer::Installer(QWidget *parent) : QWidget(parent) { - QVBoxLayout *layout = new QVBoxLayout(this); - layout->setContentsMargins(150, 290, 150, 150); - layout->setSpacing(0); - - QLabel *title = new QLabel(tr("Installing...")); - title->setStyleSheet("font-size: 90px; font-weight: 600;"); - layout->addWidget(title, 0, Qt::AlignTop); - - layout->addSpacing(170); - - bar = new QProgressBar(); - bar->setRange(0, 100); - bar->setTextVisible(false); - bar->setFixedHeight(72); - layout->addWidget(bar, 0, Qt::AlignTop); - - layout->addSpacing(30); - - val = new QLabel("0%"); - val->setStyleSheet("font-size: 70px; font-weight: 300;"); - layout->addWidget(val, 0, Qt::AlignTop); - - layout->addStretch(); - - QObject::connect(&proc, QOverload::of(&QProcess::finished), this, &Installer::cloneFinished); - QObject::connect(&proc, &QProcess::readyReadStandardError, this, &Installer::readProgress); - - QTimer::singleShot(100, this, &Installer::doInstall); - - setStyleSheet(R"( - * { - font-family: Inter; - color: white; - background-color: black; - } - QProgressBar { - border: none; - background-color: #292929; - } - QProgressBar::chunk { - background-color: #364DEF; - } - )"); -} - -void Installer::updateProgress(int percent) { - bar->setValue(percent); - val->setText(QString("%1%").arg(percent)); - update(); -} - -void Installer::doInstall() { - // wait for valid time - while (!time_valid()) { - usleep(500 * 1000); - qDebug() << "Waiting for valid time"; - } - - // cleanup previous install attempts - run("rm -rf " TMP_INSTALL_PATH " " INSTALL_PATH); - - // do the install - if (QDir(CACHE_PATH).exists()) { - cachedFetch(CACHE_PATH); - } else { - freshClone(); - } -} - -void Installer::freshClone() { - qDebug() << "Doing fresh clone"; - proc.start("git", {"clone", "--progress", GIT_URL.c_str(), "-b", BRANCH_STR.c_str(), - "--depth=1", "--recurse-submodules", TMP_INSTALL_PATH}); -} - -void Installer::cachedFetch(const QString &cache) { - qDebug() << "Fetching with cache: " << cache; - - run(QString("cp -rp %1 %2").arg(cache, TMP_INSTALL_PATH).toStdString().c_str()); - int err = chdir(TMP_INSTALL_PATH); - assert(err == 0); - run(("git remote set-branches --add origin " + BRANCH_STR).c_str()); - - updateProgress(10); - - proc.setWorkingDirectory(TMP_INSTALL_PATH); - proc.start("git", {"fetch", "--progress", "origin", BRANCH_STR.c_str()}); -} - -void Installer::readProgress() { - const QVector> stages = { - // prefix, weight in percentage - {"Receiving objects: ", 91}, - {"Resolving deltas: ", 2}, - {"Updating files: ", 7}, - }; - - auto line = QString(proc.readAllStandardError()); - - int base = 0; - for (const QPair kv : stages) { - if (line.startsWith(kv.first)) { - auto perc = line.split(kv.first)[1].split("%")[0]; - int p = base + int(perc.toFloat() / 100. * kv.second); - updateProgress(p); - break; - } - base += kv.second; - } -} - -void Installer::cloneFinished(int exitCode, QProcess::ExitStatus exitStatus) { - qDebug() << "git finished with " << exitCode; - assert(exitCode == 0); - - updateProgress(100); - - // ensure correct branch is checked out - int err = chdir(TMP_INSTALL_PATH); - assert(err == 0); - run(("git checkout " + BRANCH_STR).c_str()); - run(("git reset --hard origin/" + BRANCH_STR).c_str()); - run("git submodule update --init"); - - // move into place - run("mv " TMP_INSTALL_PATH " " INSTALL_PATH); - -#ifdef INTERNAL - run("mkdir -p /data/params/d/"); - - std::map params = { - {"SshEnabled", "1"}, - {"RecordFrontLock", "1"}, - {"GithubSshKeys", SSH_KEYS}, - }; - for (const auto& [key, value] : params) { - std::ofstream param; - param.open("/data/params/d/" + key); - param << value; - param.close(); - } - run("cd " INSTALL_PATH " && " - "git remote set-url origin --push " GIT_SSH_URL " && " - "git config --replace-all remote.origin.fetch \"+refs/heads/*:refs/remotes/origin/*\""); -#endif - - // write continue.sh - FILE *of = fopen("/data/continue.sh.new", "wb"); - assert(of != NULL); - - size_t num = str_continue_end - str_continue; - size_t num_written = fwrite(str_continue, 1, num, of); - assert(num == num_written); - fclose(of); - - run("chmod +x /data/continue.sh.new"); - run("mv /data/continue.sh.new " CONTINUE_PATH); - - // wait for the installed software's UI to take over - QTimer::singleShot(60 * 1000, &QCoreApplication::quit); -} - -int main(int argc, char *argv[]) { - initApp(argc, argv); - QApplication a(argc, argv); - Installer installer; - setMainWindow(&installer); - return a.exec(); -} diff --git a/selfdrive/ui/installer/installer.h b/selfdrive/ui/installer/installer.h deleted file mode 100644 index de3af0f..0000000 --- a/selfdrive/ui/installer/installer.h +++ /dev/null @@ -1,28 +0,0 @@ -#pragma once - -#include -#include -#include -#include - -class Installer : public QWidget { - Q_OBJECT - -public: - explicit Installer(QWidget *parent = 0); - -private slots: - void updateProgress(int percent); - - void readProgress(); - void cloneFinished(int exitCode, QProcess::ExitStatus exitStatus); - -private: - QLabel *val; - QProgressBar *bar; - QProcess proc; - - void doInstall(); - void freshClone(); - void cachedFetch(const QString &cache); -}; diff --git a/selfdrive/ui/main.cc b/selfdrive/ui/main.cc deleted file mode 100644 index 4903a3d..0000000 --- a/selfdrive/ui/main.cc +++ /dev/null @@ -1,30 +0,0 @@ -#include - -#include -#include - -#include "system/hardware/hw.h" -#include "selfdrive/ui/qt/qt_window.h" -#include "selfdrive/ui/qt/util.h" -#include "selfdrive/ui/qt/window.h" - -int main(int argc, char *argv[]) { - setpriority(PRIO_PROCESS, 0, -20); - - qInstallMessageHandler(swagLogMessageHandler); - initApp(argc, argv); - - QTranslator translator; - QString translation_file = QString::fromStdString(Params().get("LanguageSetting")); - if (!translator.load(QString(":/%1").arg(translation_file)) && translation_file.length()) { - qCritical() << "Failed to load translation file:" << translation_file; - } - - QApplication a(argc, argv); - a.installTranslator(&translator); - - MainWindow w; - setMainWindow(&w); - a.installEventFilter(&w); - return a.exec(); -} diff --git a/selfdrive/ui/mui.cc b/selfdrive/ui/mui.cc deleted file mode 100644 index 98029ee..0000000 --- a/selfdrive/ui/mui.cc +++ /dev/null @@ -1,50 +0,0 @@ -#include -#include -#include - -#include "cereal/messaging/messaging.h" -#include "selfdrive/ui/ui.h" -#include "selfdrive/ui/qt/qt_window.h" - -int main(int argc, char *argv[]) { - QApplication a(argc, argv); - QWidget w; - setMainWindow(&w); - - w.setStyleSheet("background-color: black;"); - - // our beautiful UI - QVBoxLayout *layout = new QVBoxLayout(&w); - QLabel *label = new QLabel("〇"); - layout->addWidget(label, 0, Qt::AlignCenter); - - QTimer timer; - QObject::connect(&timer, &QTimer::timeout, [=]() { - static SubMaster sm({"deviceState", "controlsState"}); - - bool onroad_prev = sm.allAliveAndValid({"deviceState"}) && - sm["deviceState"].getDeviceState().getStarted(); - sm.update(0); - - bool onroad = sm.allAliveAndValid({"deviceState"}) && - sm["deviceState"].getDeviceState().getStarted(); - - if (onroad) { - label->setText("〇"); - auto cs = sm["controlsState"].getControlsState(); - UIStatus status = cs.getEnabled() ? STATUS_ENGAGED : STATUS_DISENGAGED; - label->setStyleSheet(QString("color: %1; font-size: 250px;").arg(bg_colors[status].name())); - } else { - label->setText("offroad"); - label->setStyleSheet("color: grey; font-size: 40px;"); - } - - if ((onroad != onroad_prev) || sm.frame < 2) { - Hardware::set_brightness(50); - Hardware::set_display_power(onroad); - } - }); - timer.start(50); - - return a.exec(); -} diff --git a/selfdrive/ui/qt/api.cc b/selfdrive/ui/qt/api.cc deleted file mode 100644 index 0e321d4..0000000 --- a/selfdrive/ui/qt/api.cc +++ /dev/null @@ -1,142 +0,0 @@ -#include "selfdrive/ui/qt/api.h" - -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include - -#include - -#include "common/params.h" -#include "common/util.h" -#include "system/hardware/hw.h" -#include "selfdrive/ui/qt/util.h" - -namespace CommaApi { - -QByteArray rsa_sign(const QByteArray &data) { - static std::string key = util::read_file(Path::rsa_file()); - if (key.empty()) { - qDebug() << "No RSA private key found, please run manager.py or registration.py"; - return {}; - } - - BIO* mem = BIO_new_mem_buf(key.data(), key.size()); - assert(mem); - RSA* rsa_private = PEM_read_bio_RSAPrivateKey(mem, NULL, NULL, NULL); - assert(rsa_private); - auto sig = QByteArray(); - sig.resize(RSA_size(rsa_private)); - unsigned int sig_len; - int ret = RSA_sign(NID_sha256, (unsigned char*)data.data(), data.size(), (unsigned char*)sig.data(), &sig_len, rsa_private); - assert(ret == 1); - assert(sig_len == sig.size()); - BIO_free(mem); - RSA_free(rsa_private); - return sig; -} - -QString create_jwt(const QJsonObject &payloads, int expiry) { - QJsonObject header = {{"alg", "RS256"}}; - - auto t = QDateTime::currentSecsSinceEpoch(); - QJsonObject payload = {{"identity", getDongleId().value_or("")}, {"nbf", t}, {"iat", t}, {"exp", t + expiry}}; - for (auto it = payloads.begin(); it != payloads.end(); ++it) { - payload.insert(it.key(), it.value()); - } - - auto b64_opts = QByteArray::Base64UrlEncoding | QByteArray::OmitTrailingEquals; - QString jwt = QJsonDocument(header).toJson(QJsonDocument::Compact).toBase64(b64_opts) + '.' + - QJsonDocument(payload).toJson(QJsonDocument::Compact).toBase64(b64_opts); - - auto hash = QCryptographicHash::hash(jwt.toUtf8(), QCryptographicHash::Sha256); - auto sig = rsa_sign(hash); - jwt += '.' + sig.toBase64(b64_opts); - return jwt; -} - -} // namespace CommaApi - -HttpRequest::HttpRequest(QObject *parent, bool create_jwt, int timeout) : create_jwt(create_jwt), QObject(parent) { - networkTimer = new QTimer(this); - networkTimer->setSingleShot(true); - networkTimer->setInterval(timeout); - connect(networkTimer, &QTimer::timeout, this, &HttpRequest::requestTimeout); -} - -bool HttpRequest::active() const { - return reply != nullptr; -} - -bool HttpRequest::timeout() const { - return reply && reply->error() == QNetworkReply::OperationCanceledError; -} - -void HttpRequest::sendRequest(const QString &requestURL, const HttpRequest::Method method) { - if (active()) { - qDebug() << "HttpRequest is active"; - return; - } - QString token; - if (create_jwt) { - token = CommaApi::create_jwt(); - } else { - QString token_json = QString::fromStdString(util::read_file(util::getenv("HOME") + "/.comma/auth.json")); - QJsonDocument json_d = QJsonDocument::fromJson(token_json.toUtf8()); - token = json_d["access_token"].toString(); - } - - QNetworkRequest request; - request.setUrl(QUrl(requestURL)); - request.setRawHeader("User-Agent", getUserAgent().toUtf8()); - - if (!token.isEmpty()) { - request.setRawHeader(QByteArray("Authorization"), ("JWT " + token).toUtf8()); - } - - if (method == HttpRequest::Method::GET) { - reply = nam()->get(request); - } else if (method == HttpRequest::Method::DELETE) { - reply = nam()->deleteResource(request); - } - - networkTimer->start(); - connect(reply, &QNetworkReply::finished, this, &HttpRequest::requestFinished); -} - -void HttpRequest::requestTimeout() { - reply->abort(); -} - -void HttpRequest::requestFinished() { - networkTimer->stop(); - - if (reply->error() == QNetworkReply::NoError) { - emit requestDone(reply->readAll(), true, reply->error()); - } else { - QString error; - if (reply->error() == QNetworkReply::OperationCanceledError) { - nam()->clearAccessCache(); - nam()->clearConnectionCache(); - error = "Request timed out"; - } else { - error = reply->errorString(); - } - emit requestDone(error, false, reply->error()); - } - - reply->deleteLater(); - reply = nullptr; -} - -QNetworkAccessManager *HttpRequest::nam() { - static QNetworkAccessManager *networkAccessManager = new QNetworkAccessManager(qApp); - return networkAccessManager; -} diff --git a/selfdrive/ui/qt/api.h b/selfdrive/ui/qt/api.h deleted file mode 100644 index ad64d7e..0000000 --- a/selfdrive/ui/qt/api.h +++ /dev/null @@ -1,47 +0,0 @@ -#pragma once - -#include -#include -#include -#include - -#include "common/util.h" - -namespace CommaApi { - -const QString BASE_URL = util::getenv("API_HOST", "https://api.commadotai.com").c_str(); -QByteArray rsa_sign(const QByteArray &data); -QString create_jwt(const QJsonObject &payloads = {}, int expiry = 3600); - -} // namespace CommaApi - -/** - * Makes a request to the request endpoint. - */ - -class HttpRequest : public QObject { - Q_OBJECT - -public: - enum class Method {GET, DELETE}; - - explicit HttpRequest(QObject* parent, bool create_jwt = true, int timeout = 20000); - void sendRequest(const QString &requestURL, const Method method = Method::GET); - bool active() const; - bool timeout() const; - -signals: - void requestDone(const QString &response, bool success, QNetworkReply::NetworkError error); - -protected: - QNetworkReply *reply = nullptr; - -private: - static QNetworkAccessManager *nam(); - QTimer *networkTimer = nullptr; - bool create_jwt; - -private slots: - void requestTimeout(); - void requestFinished(); -}; diff --git a/selfdrive/ui/qt/body.cc b/selfdrive/ui/qt/body.cc deleted file mode 100644 index e01adbe..0000000 --- a/selfdrive/ui/qt/body.cc +++ /dev/null @@ -1,161 +0,0 @@ -#include "selfdrive/ui/qt/body.h" - -#include -#include - -#include -#include - -#include "common/params.h" -#include "common/timing.h" - -RecordButton::RecordButton(QWidget *parent) : QPushButton(parent) { - setCheckable(true); - setChecked(false); - setFixedSize(148, 148); - - QObject::connect(this, &QPushButton::toggled, [=]() { - setEnabled(false); - }); -} - -void RecordButton::paintEvent(QPaintEvent *event) { - QPainter p(this); - p.setRenderHint(QPainter::Antialiasing); - - QPoint center(width() / 2, height() / 2); - - QColor bg(isChecked() ? "#FFFFFF" : "#737373"); - QColor accent(isChecked() ? "#FF0000" : "#FFFFFF"); - if (!isEnabled()) { - bg = QColor("#404040"); - accent = QColor("#FFFFFF"); - } - - if (isDown()) { - accent.setAlphaF(0.7); - } - - p.setPen(Qt::NoPen); - p.setBrush(bg); - p.drawEllipse(center, 74, 74); - - p.setPen(QPen(accent, 6)); - p.setBrush(Qt::NoBrush); - p.drawEllipse(center, 42, 42); - - p.setPen(Qt::NoPen); - p.setBrush(accent); - p.drawEllipse(center, 22, 22); -} - - -BodyWindow::BodyWindow(QWidget *parent) : fuel_filter(1.0, 5., 1. / UI_FREQ), QWidget(parent) { - QStackedLayout *layout = new QStackedLayout(this); - layout->setStackingMode(QStackedLayout::StackAll); - - QWidget *w = new QWidget; - QVBoxLayout *vlayout = new QVBoxLayout(w); - vlayout->setMargin(45); - layout->addWidget(w); - - // face - face = new QLabel(); - face->setAlignment(Qt::AlignCenter); - layout->addWidget(face); - awake = new QMovie("../assets/body/awake.gif", {}, this); - awake->setCacheMode(QMovie::CacheAll); - sleep = new QMovie("../assets/body/sleep.gif", {}, this); - sleep->setCacheMode(QMovie::CacheAll); - - // record button - btn = new RecordButton(this); - vlayout->addWidget(btn, 0, Qt::AlignBottom | Qt::AlignRight); - QObject::connect(btn, &QPushButton::clicked, [=](bool checked) { - btn->setEnabled(false); - Params().putBool("DisableLogging", !checked); - last_button = nanos_since_boot(); - }); - w->raise(); - - QObject::connect(uiState(), &UIState::uiUpdate, this, &BodyWindow::updateState); -} - -void BodyWindow::paintEvent(QPaintEvent *event) { - QPainter p(this); - p.setRenderHint(QPainter::Antialiasing); - - p.fillRect(rect(), QColor(0, 0, 0)); - - // battery outline + detail - p.translate(width() - 136, 16); - const QColor gray = QColor("#737373"); - p.setBrush(Qt::NoBrush); - p.setPen(QPen(gray, 4, Qt::SolidLine, Qt::RoundCap, Qt::RoundJoin)); - p.drawRoundedRect(2, 2, 78, 36, 8, 8); - - p.setPen(Qt::NoPen); - p.setBrush(gray); - p.drawRoundedRect(84, 12, 6, 16, 4, 4); - p.drawRect(84, 12, 3, 16); - - // battery level - double fuel = std::clamp(fuel_filter.x(), 0.2f, 1.0f); - const int m = 5; // manual margin since we can't do an inner border - p.setPen(Qt::NoPen); - p.setBrush(fuel > 0.25 ? QColor("#32D74B") : QColor("#FF453A")); - p.drawRoundedRect(2 + m, 2 + m, (78 - 2*m)*fuel, 36 - 2*m, 4, 4); - - // charging status - if (charging) { - p.setPen(Qt::NoPen); - p.setBrush(Qt::white); - const QPolygonF charger({ - QPointF(12.31, 0), - QPointF(12.31, 16.92), - QPointF(18.46, 16.92), - QPointF(6.15, 40), - QPointF(6.15, 23.08), - QPointF(0, 23.08), - }); - p.drawPolygon(charger.translated(98, 0)); - } -} - -void BodyWindow::offroadTransition(bool offroad) { - btn->setChecked(true); - btn->setEnabled(true); - fuel_filter.reset(1.0); -} - -void BodyWindow::updateState(const UIState &s) { - if (!isVisible()) { - return; - } - - const SubMaster &sm = *(s.sm); - auto cs = sm["carState"].getCarState(); - - charging = cs.getCharging(); - fuel_filter.update(cs.getFuelGauge()); - - // TODO: use carState.standstill when that's fixed - const bool standstill = std::abs(cs.getVEgo()) < 0.01; - QMovie *m = standstill ? sleep : awake; - if (m != face->movie()) { - face->setMovie(m); - face->movie()->start(); - } - - // update record button state - if (sm.updated("managerState") && (sm.rcv_time("managerState") - last_button)*1e-9 > 0.5) { - for (auto proc : sm["managerState"].getManagerState().getProcesses()) { - if (proc.getName() == "loggerd") { - btn->setEnabled(true); - btn->setChecked(proc.getRunning()); - } - } - } - - update(); -} diff --git a/selfdrive/ui/qt/body.h b/selfdrive/ui/qt/body.h deleted file mode 100644 index 567a54d..0000000 --- a/selfdrive/ui/qt/body.h +++ /dev/null @@ -1,38 +0,0 @@ -#pragma once - -#include -#include -#include - -#include "common/util.h" -#include "selfdrive/ui/ui.h" - -class RecordButton : public QPushButton { - Q_OBJECT - -public: - RecordButton(QWidget* parent = 0); - -private: - void paintEvent(QPaintEvent*) override; -}; - -class BodyWindow : public QWidget { - Q_OBJECT - -public: - BodyWindow(QWidget* parent = 0); - -private: - bool charging = false; - uint64_t last_button = 0; - FirstOrderFilter fuel_filter; - QLabel *face; - QMovie *awake, *sleep; - RecordButton *btn; - void paintEvent(QPaintEvent*) override; - -private slots: - void updateState(const UIState &s); - void offroadTransition(bool onroad); -}; diff --git a/selfdrive/ui/qt/home.cc b/selfdrive/ui/qt/home.cc deleted file mode 100644 index 902d0af..0000000 --- a/selfdrive/ui/qt/home.cc +++ /dev/null @@ -1,265 +0,0 @@ -#include "selfdrive/ui/qt/home.h" - -#include -#include -#include -#include - -#include "selfdrive/ui/qt/offroad/experimental_mode.h" -#include "selfdrive/ui/qt/util.h" -#include "selfdrive/ui/qt/widgets/drive_stats.h" -#include "selfdrive/ui/qt/widgets/prime.h" - -#ifdef ENABLE_MAPS -#include "selfdrive/ui/qt/maps/map_settings.h" -#endif - -// HomeWindow: the container for the offroad and onroad UIs - -HomeWindow::HomeWindow(QWidget* parent) : QWidget(parent) { - QHBoxLayout *main_layout = new QHBoxLayout(this); - main_layout->setMargin(0); - main_layout->setSpacing(0); - - sidebar = new Sidebar(this); - main_layout->addWidget(sidebar); - QObject::connect(sidebar, &Sidebar::openSettings, this, &HomeWindow::openSettings); - - slayout = new QStackedLayout(); - main_layout->addLayout(slayout); - - home = new OffroadHome(this); - QObject::connect(home, &OffroadHome::openSettings, this, &HomeWindow::openSettings); - slayout->addWidget(home); - - onroad = new OnroadWindow(this); - QObject::connect(onroad, &OnroadWindow::mapPanelRequested, this, [=] { sidebar->hide(); }); - slayout->addWidget(onroad); - - body = new BodyWindow(this); - slayout->addWidget(body); - - driver_view = new DriverViewWindow(this); - connect(driver_view, &DriverViewWindow::done, [=] { - showDriverView(false); - }); - slayout->addWidget(driver_view); - setAttribute(Qt::WA_NoSystemBackground); - QObject::connect(uiState(), &UIState::uiUpdate, this, &HomeWindow::updateState); - QObject::connect(uiState(), &UIState::offroadTransition, this, &HomeWindow::offroadTransition); - QObject::connect(uiState(), &UIState::offroadTransition, sidebar, &Sidebar::offroadTransition); -} - -void HomeWindow::showSidebar(bool show) { - sidebar->setVisible(show); -} - -void HomeWindow::showMapPanel(bool show) { - onroad->showMapPanel(show); -} - -void HomeWindow::updateState(const UIState &s) { - const SubMaster &sm = *(s.sm); - - // switch to the generic robot UI - if (onroad->isVisible() && !body->isEnabled() && sm["carParams"].getCarParams().getNotCar()) { - body->setEnabled(true); - slayout->setCurrentWidget(body); - } -} - -void HomeWindow::offroadTransition(bool offroad) { - body->setEnabled(false); - sidebar->setVisible(offroad); - if (offroad) { - slayout->setCurrentWidget(home); - } else { - slayout->setCurrentWidget(onroad); - } -} - -void HomeWindow::showDriverView(bool show) { - if (show) { - emit closeSettings(); - slayout->setCurrentWidget(driver_view); - } else { - slayout->setCurrentWidget(home); - } - sidebar->setVisible(show == false); -} - -void HomeWindow::mousePressEvent(QMouseEvent* e) { - // Handle sidebar collapsing - if ((onroad->isVisible() || body->isVisible()) && (!sidebar->isVisible() || e->x() > sidebar->width())) { - sidebar->setVisible(!sidebar->isVisible() && !onroad->isMapVisible()); - params.putBool("Sidebar", sidebar->isVisible()); - } -} - -void HomeWindow::mouseDoubleClickEvent(QMouseEvent* e) { - HomeWindow::mousePressEvent(e); - const SubMaster &sm = *(uiState()->sm); - if (sm["carParams"].getCarParams().getNotCar()) { - if (onroad->isVisible()) { - slayout->setCurrentWidget(body); - } else if (body->isVisible()) { - slayout->setCurrentWidget(onroad); - } - showSidebar(false); - } -} - -// OffroadHome: the offroad home page - -OffroadHome::OffroadHome(QWidget* parent) : QFrame(parent) { - QVBoxLayout* main_layout = new QVBoxLayout(this); - main_layout->setContentsMargins(40, 40, 40, 40); - - // top header - QHBoxLayout* header_layout = new QHBoxLayout(); - header_layout->setContentsMargins(0, 0, 0, 0); - header_layout->setSpacing(16); - - update_notif = new QPushButton(tr("UPDATE")); - update_notif->setVisible(false); - update_notif->setStyleSheet("background-color: #364DEF;"); - QObject::connect(update_notif, &QPushButton::clicked, [=]() { center_layout->setCurrentIndex(1); }); - header_layout->addWidget(update_notif, 0, Qt::AlignHCenter | Qt::AlignLeft); - - alert_notif = new QPushButton(); - alert_notif->setVisible(false); - alert_notif->setStyleSheet("background-color: #E22C2C;"); - QObject::connect(alert_notif, &QPushButton::clicked, [=] { center_layout->setCurrentIndex(2); }); - header_layout->addWidget(alert_notif, 0, Qt::AlignHCenter | Qt::AlignLeft); - - date = new ElidedLabel(); - header_layout->addWidget(date, 0, Qt::AlignHCenter | Qt::AlignLeft); - - version = new ElidedLabel(); - header_layout->addWidget(version, 0, Qt::AlignHCenter | Qt::AlignRight); - - main_layout->addLayout(header_layout); - - // main content - main_layout->addSpacing(25); - center_layout = new QStackedLayout(); - - QWidget *home_widget = new QWidget(this); - { - QHBoxLayout *home_layout = new QHBoxLayout(home_widget); - home_layout->setContentsMargins(0, 0, 0, 0); - home_layout->setSpacing(30); - - // left: MapSettings/PrimeAdWidget - QStackedWidget *left_widget = new QStackedWidget(this); -#ifdef ENABLE_MAPS - left_widget->addWidget(new MapSettings); -#else - left_widget->addWidget(new QWidget); -#endif - left_widget->addWidget(new PrimeAdWidget); - left_widget->addWidget(new DriveStats); - left_widget->setStyleSheet("border-radius: 10px;"); - - left_widget->setCurrentIndex(params.getBool("DriveStats") ? 2 : uiState()->hasPrime() ? 0 : 1); - connect(uiState(), &UIState::primeChanged, [=](bool prime) { - left_widget->setCurrentIndex(params.getBool("DriveStats") ? 2 : uiState()->hasPrime() ? 0 : 1); - }); - - home_layout->addWidget(left_widget, 1); - - // right: ExperimentalModeButton, SetupWidget - QWidget* right_widget = new QWidget(this); - QVBoxLayout* right_column = new QVBoxLayout(right_widget); - right_column->setContentsMargins(0, 0, 0, 0); - right_widget->setFixedWidth(750); - right_column->setSpacing(30); - - ExperimentalModeButton *experimental_mode = new ExperimentalModeButton(this); - QObject::connect(experimental_mode, &ExperimentalModeButton::openSettings, this, &OffroadHome::openSettings); - right_column->addWidget(experimental_mode, 1); - - SetupWidget *setup_widget = new SetupWidget; - QObject::connect(setup_widget, &SetupWidget::openSettings, this, &OffroadHome::openSettings); - right_column->addWidget(setup_widget, 1); - - home_layout->addWidget(right_widget, 1); - } - center_layout->addWidget(home_widget); - - // add update & alerts widgets - update_widget = new UpdateAlert(); - QObject::connect(update_widget, &UpdateAlert::dismiss, [=]() { center_layout->setCurrentIndex(0); }); - center_layout->addWidget(update_widget); - alerts_widget = new OffroadAlert(); - QObject::connect(alerts_widget, &OffroadAlert::dismiss, [=]() { center_layout->setCurrentIndex(0); }); - center_layout->addWidget(alerts_widget); - - main_layout->addLayout(center_layout, 1); - - // set up refresh timer - timer = new QTimer(this); - timer->callOnTimeout(this, &OffroadHome::refresh); - - setStyleSheet(R"( - * { - color: white; - } - OffroadHome { - background-color: black; - } - OffroadHome > QPushButton { - padding: 15px 30px; - border-radius: 5px; - font-size: 40px; - font-weight: 500; - } - OffroadHome > QLabel { - font-size: 55px; - } - )"); - - // Set the model name - MODEL_NAME = { - {"los-angeles", "Los Angeles"}, - {"certified-herbalist", "Certified Herbalist"}, - {"duck-amigo", "Duck Amigo"}, - {"recertified-herbalist", "Recertified Herbalist"}, - }; -} - -void OffroadHome::showEvent(QShowEvent *event) { - refresh(); - timer->start(10 * 1000); -} - -void OffroadHome::hideEvent(QHideEvent *event) { - timer->stop(); -} - -void OffroadHome::refresh() { - QString model = QString::fromStdString(params.get("Model")); - - date->setText(QLocale(uiState()->language.mid(5)).toString(QDateTime::currentDateTime(), "dddd, MMMM d")); - version->setText(getBrand() + " v" + getVersion().left(14).trimmed() + " - " + MODEL_NAME[model]); - - bool updateAvailable = update_widget->refresh(); - int alerts = alerts_widget->refresh(); - - // pop-up new notification - int idx = center_layout->currentIndex(); - if (!updateAvailable && !alerts) { - idx = 0; - } else if (updateAvailable && (!update_notif->isVisible() || (!alerts && idx == 2))) { - idx = 1; - } else if (alerts && (!alert_notif->isVisible() || (!updateAvailable && idx == 1))) { - idx = 2; - } - center_layout->setCurrentIndex(idx); - - update_notif->setVisible(updateAvailable); - alert_notif->setVisible(alerts); - if (alerts) { - alert_notif->setText(QString::number(alerts) + (alerts > 1 ? tr(" ALERTS") : tr(" ALERT"))); - } -} diff --git a/selfdrive/ui/qt/home.h b/selfdrive/ui/qt/home.h deleted file mode 100644 index b3f02cf..0000000 --- a/selfdrive/ui/qt/home.h +++ /dev/null @@ -1,81 +0,0 @@ -#pragma once - -#include -#include -#include -#include -#include -#include - -#include "common/params.h" -#include "selfdrive/ui/qt/offroad/driverview.h" -#include "selfdrive/ui/qt/body.h" -#include "selfdrive/ui/qt/onroad.h" -#include "selfdrive/ui/qt/sidebar.h" -#include "selfdrive/ui/qt/widgets/controls.h" -#include "selfdrive/ui/qt/widgets/offroad_alerts.h" -#include "selfdrive/ui/ui.h" - -class OffroadHome : public QFrame { - Q_OBJECT - -public: - explicit OffroadHome(QWidget* parent = 0); - -signals: - void openSettings(int index = 0, const QString ¶m = ""); - -private: - void showEvent(QShowEvent *event) override; - void hideEvent(QHideEvent *event) override; - void refresh(); - - Params params; - - QTimer* timer; - ElidedLabel* date; - ElidedLabel* version; - QStackedLayout* center_layout; - UpdateAlert *update_widget; - OffroadAlert* alerts_widget; - QPushButton* alert_notif; - QPushButton* update_notif; - - // FrogPilot variables - std::map MODEL_NAME; -}; - -class HomeWindow : public QWidget { - Q_OBJECT - -public: - explicit HomeWindow(QWidget* parent = 0); - -signals: - void openSettings(int index = 0, const QString ¶m = ""); - void closeSettings(); - -public slots: - void offroadTransition(bool offroad); - void showDriverView(bool show); - void showSidebar(bool show); - void showMapPanel(bool show); - -protected: - void mousePressEvent(QMouseEvent* e) override; - void mouseDoubleClickEvent(QMouseEvent* e) override; - -private: - Sidebar *sidebar; - OffroadHome *home; - OnroadWindow *onroad; - BodyWindow *body; - DriverViewWindow *driver_view; - QStackedLayout *slayout; - - // FrogPilot variables - Params params; - -private slots: - void updateState(const UIState &s); -}; diff --git a/selfdrive/ui/qt/libpython_helpers.so b/selfdrive/ui/qt/libpython_helpers.so new file mode 100755 index 0000000..b8d2bef Binary files /dev/null and b/selfdrive/ui/qt/libpython_helpers.so differ diff --git a/selfdrive/ui/qt/maps/map.cc b/selfdrive/ui/qt/maps/map.cc deleted file mode 100644 index bd9a4a6..0000000 --- a/selfdrive/ui/qt/maps/map.cc +++ /dev/null @@ -1,469 +0,0 @@ -#include "selfdrive/ui/qt/maps/map.h" - -#include -#include - -#include - -#include "selfdrive/ui/qt/maps/map_helpers.h" -#include "selfdrive/ui/qt/util.h" -#include "selfdrive/ui/ui.h" - - -const int INTERACTION_TIMEOUT = 100; - -const float MAX_ZOOM = 17; -const float MIN_ZOOM = 14; -const float MAX_PITCH = 50; -const float MIN_PITCH = 0; -const float MAP_SCALE = 2; - -MapWindow::MapWindow(const QMapLibre::Settings &settings) : m_settings(settings), velocity_filter(0, 10, 0.05, false) { - QObject::connect(uiState(), &UIState::uiUpdate, this, &MapWindow::updateState); - - map_overlay = new QWidget (this); - map_overlay->setAttribute(Qt::WA_TranslucentBackground, true); - QVBoxLayout *overlay_layout = new QVBoxLayout(map_overlay); - overlay_layout->setContentsMargins(0, 0, 0, 0); - - // Instructions - map_instructions = new MapInstructions(this); - map_instructions->setVisible(false); - - map_eta = new MapETA(this); - map_eta->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Fixed); - map_eta->setFixedHeight(120); - - error = new QLabel(this); - error->setStyleSheet(R"(color:white;padding:50px 11px;font-size: 90px; background-color:rgba(0, 0, 0, 150);)"); - error->setAlignment(Qt::AlignCenter); - - overlay_layout->addWidget(error); - overlay_layout->addWidget(map_instructions); - overlay_layout->addStretch(1); - overlay_layout->addWidget(map_eta); - - last_position = coordinate_from_param("LastGPSPosition"); - grabGesture(Qt::GestureType::PinchGesture); - qDebug() << "MapWindow initialized"; -} - -MapWindow::~MapWindow() { - makeCurrent(); -} - -void MapWindow::initLayers() { - // This doesn't work from initializeGL - if (!m_map->layerExists("navLayer")) { - qDebug() << "Initializing navLayer"; - QVariantMap nav; - nav["type"] = "line"; - nav["source"] = "navSource"; - m_map->addLayer("navLayer", nav, "road-intersection"); - - QVariantMap transition; - transition["duration"] = 400; // ms - m_map->setPaintProperty("navLayer", "line-color", getNavPathColor(uiState()->scene.navigate_on_openpilot)); - m_map->setPaintProperty("navLayer", "line-color-transition", transition); - m_map->setPaintProperty("navLayer", "line-width", 7.5); - m_map->setLayoutProperty("navLayer", "line-cap", "round"); - } -if (!m_map->layerExists("modelPathLayer")) { - qDebug() << "Initializing modelPathLayer"; - QVariantMap modelPath; - //modelPath["id"] = "modelPathLayer"; - modelPath["type"] = "line"; - modelPath["source"] = "modelPathSource"; - m_map->addLayer("modelPathLayer", modelPath); - m_map->setPaintProperty("modelPathLayer", "line-color", QColor("red")); - m_map->setPaintProperty("modelPathLayer", "line-width", 5.0); - m_map->setLayoutProperty("modelPathLayer", "line-cap", "round"); - } - if (!m_map->layerExists("pinLayer")) { - qDebug() << "Initializing pinLayer"; - m_map->addImage("default_marker", QImage("../assets/navigation/default_marker.svg")); - QVariantMap pin; - pin["type"] = "symbol"; - pin["source"] = "pinSource"; - m_map->addLayer("pinLayer", pin); - m_map->setLayoutProperty("pinLayer", "icon-pitch-alignment", "viewport"); - m_map->setLayoutProperty("pinLayer", "icon-image", "default_marker"); - m_map->setLayoutProperty("pinLayer", "icon-ignore-placement", true); - m_map->setLayoutProperty("pinLayer", "icon-allow-overlap", true); - m_map->setLayoutProperty("pinLayer", "symbol-sort-key", 0); - m_map->setLayoutProperty("pinLayer", "icon-anchor", "bottom"); - } - if (!m_map->layerExists("carPosLayer")) { - qDebug() << "Initializing carPosLayer"; - m_map->addImage("label-arrow", QImage("../assets/images/triangle.svg")); - - QVariantMap carPos; - carPos["type"] = "symbol"; - carPos["source"] = "carPosSource"; - m_map->addLayer("carPosLayer", carPos); - m_map->setLayoutProperty("carPosLayer", "icon-pitch-alignment", "map"); - m_map->setLayoutProperty("carPosLayer", "icon-image", "label-arrow"); - m_map->setLayoutProperty("carPosLayer", "icon-size", 0.5); - m_map->setLayoutProperty("carPosLayer", "icon-ignore-placement", true); - m_map->setLayoutProperty("carPosLayer", "icon-allow-overlap", true); - // TODO: remove, symbol-sort-key does not seem to matter outside of each layer - m_map->setLayoutProperty("carPosLayer", "symbol-sort-key", 0); - } - - if (!m_map->layerExists("buildingsLayer")) { - qDebug() << "Initializing buildingsLayer"; - QVariantMap buildings; - buildings["id"] = "buildingsLayer"; - buildings["source"] = "composite"; - buildings["source-layer"] = "building"; - buildings["type"] = "fill-extrusion"; - buildings["minzoom"] = 15; - m_map->addLayer("buildingsLayer", buildings); - m_map->setFilter("buildingsLayer", QVariantList({"==", "extrude", "true"})); - - QVariantList fillExtrusionHight = { - "interpolate", - QVariantList{"linear"}, - QVariantList{"zoom"}, - 15, 0, - 15.05, QVariantList{"get", "height"} - }; - - QVariantList fillExtrusionBase = { - "interpolate", - QVariantList{"linear"}, - QVariantList{"zoom"}, - 15, 0, - 15.05, QVariantList{"get", "min_height"} - }; - - QVariantList fillExtrusionOpacity = { - "interpolate", - QVariantList{"linear"}, - QVariantList{"zoom"}, - 15, 0, - 15.5, .6, - 17, .6, - 20, 0 - }; - - m_map->setPaintProperty("buildingsLayer", "fill-extrusion-color", QColor("grey")); - m_map->setPaintProperty("buildingsLayer", "fill-extrusion-opacity", fillExtrusionOpacity); - m_map->setPaintProperty("buildingsLayer", "fill-extrusion-height", fillExtrusionHight); - m_map->setPaintProperty("buildingsLayer", "fill-extrusion-base", fillExtrusionBase); - m_map->setLayoutProperty("buildingsLayer", "visibility", "visible"); - } -} - -void MapWindow::updateState(const UIState &s) { - if (!uiState()->scene.started) { - return; - } - const SubMaster &sm = *(s.sm); - update(); - - if (sm.updated("modelV2")) { - // set path color on change, and show map on rising edge of navigate on openpilot - bool nav_enabled = sm["modelV2"].getModelV2().getNavEnabled() && - (sm["controlsState"].getControlsState().getEnabled() || sm["frogpilotCarControl"].getFrogpilotCarControl().getAlwaysOnLateral()); - if (nav_enabled != uiState()->scene.navigate_on_openpilot) { - if (loaded_once) { - m_map->setPaintProperty("navLayer", "line-color", getNavPathColor(nav_enabled)); - } - if (nav_enabled) { - emit requestVisible(true); - } - } - uiState()->scene.navigate_on_openpilot = nav_enabled; - } - - if (sm.updated("liveLocationKalman")) { - auto locationd_location = sm["liveLocationKalman"].getLiveLocationKalman(); - auto locationd_pos = locationd_location.getPositionGeodetic(); - auto locationd_orientation = locationd_location.getCalibratedOrientationNED(); - auto locationd_velocity = locationd_location.getVelocityCalibrated(); - - // Check std norm - auto pos_ecef_std = locationd_location.getPositionECEF().getStd(); - bool pos_accurate_enough = sqrt(pow(pos_ecef_std[0], 2) + pow(pos_ecef_std[1], 2) + pow(pos_ecef_std[2], 2)) < 100; - - locationd_valid = (locationd_pos.getValid() && locationd_orientation.getValid() && locationd_velocity.getValid() && pos_accurate_enough); - - if (locationd_valid) { - last_position = QMapLibre::Coordinate(locationd_pos.getValue()[0], locationd_pos.getValue()[1]); - last_bearing = RAD2DEG(locationd_orientation.getValue()[2]); - velocity_filter.update(std::max(10.0, locationd_velocity.getValue()[0])); - } -} - // Credit to jakethesnake420 - if (loaded_once && (sm.rcv_frame("uiPlan") != model_rcv_frame)) { - auto locationd_location = sm["liveLocationKalman"].getLiveLocationKalman(); - auto model_path = model_to_collection(locationd_location.getCalibratedOrientationECEF(), locationd_location.getPositionECEF(), sm["uiPlan"].getUiPlan().getPosition()); - QMapLibre::Feature model_path_feature(QMapLibre::Feature::LineStringType, model_path, {}, {}); - QVariantMap modelV2Path; - modelV2Path["type"] = "geojson"; - modelV2Path["data"] = QVariant::fromValue(model_path_feature); - m_map->updateSource("modelPathSource", modelV2Path); - model_rcv_frame = sm.rcv_frame("uiPlan"); - } - - if (sm.updated("navRoute") && sm["navRoute"].getNavRoute().getCoordinates().size()) { - auto nav_dest = coordinate_from_param("NavDestination"); - bool allow_open = std::exchange(last_valid_nav_dest, nav_dest) != nav_dest && - nav_dest && !isVisible(); - qWarning() << "Got new navRoute from navd. Opening map:" << allow_open; - - // Show map on destination set/change - if (allow_open) { - emit requestSettings(false); - emit requestVisible(true); - } - } - - loaded_once = loaded_once || (m_map && m_map->isFullyLoaded()); - if (!loaded_once) { - setError(tr("Map Loading")); - return; - } - initLayers(); - - if (!locationd_valid) { - setError(tr("Waiting for GPS")); - } else if (routing_problem) { - setError(tr("Waiting for route")); - } else { - setError(""); - } - - if (locationd_valid) { - // Update current location marker - auto point = coordinate_to_collection(*last_position); - QMapLibre::Feature feature1(QMapLibre::Feature::PointType, point, {}, {}); - QVariantMap carPosSource; - carPosSource["type"] = "geojson"; - carPosSource["data"] = QVariant::fromValue(feature1); - m_map->updateSource("carPosSource", carPosSource); - - // Map bearing isn't updated when interacting, keep location marker up to date - if (last_bearing) { - m_map->setLayoutProperty("carPosLayer", "icon-rotate", *last_bearing - m_map->bearing()); - } - } - - if (interaction_counter == 0) { - if (last_position) m_map->setCoordinate(*last_position); - if (last_bearing) m_map->setBearing(*last_bearing); - m_map->setZoom(util::map_val(velocity_filter.x(), 0, 30, MAX_ZOOM, MIN_ZOOM)); - } else { - interaction_counter--; - } - - if (sm.updated("navInstruction")) { - // an invalid navInstruction packet with a nav destination is only possible if: - // - API exception/no internet - // - route response is empty - // - any time navd is waiting for recompute_countdown - routing_problem = !sm.valid("navInstruction") && coordinate_from_param("NavDestination").has_value(); - - if (sm.valid("navInstruction")) { - auto i = sm["navInstruction"].getNavInstruction(); - map_eta->updateETA(i.getTimeRemaining(), i.getTimeRemainingTypical(), i.getDistanceRemaining()); - - if (locationd_valid) { - m_map->setPitch(MAX_PITCH); // TODO: smooth pitching based on maneuver distance - map_instructions->updateInstructions(i); - } - } else { - clearRoute(); - } - } - - if (sm.rcv_frame("navRoute") != route_rcv_frame) { - qWarning() << "Updating navLayer with new route"; - auto route = sm["navRoute"].getNavRoute(); - auto route_points = capnp_coordinate_list_to_collection(route.getCoordinates()); - QMapLibre::Feature feature(QMapLibre::Feature::LineStringType, route_points, {}, {}); - QVariantMap navSource; - navSource["type"] = "geojson"; - navSource["data"] = QVariant::fromValue(feature); - m_map->updateSource("navSource", navSource); - m_map->setLayoutProperty("navLayer", "visibility", "visible"); - - route_rcv_frame = sm.rcv_frame("navRoute"); - updateDestinationMarker(); - } - - // Map Styling - Credit goes to OPKR! - int map_style = uiState()->scene.map_style; - - if (map_style != previous_map_style) { - std::unordered_map styleUrls = { - {0, "mapbox://styles/commaai/clkqztk0f00ou01qyhsa5bzpj"}, // Stock openpilot - {1, "mapbox://styles/mapbox/streets-v11"}, // Mapbox Streets - {2, "mapbox://styles/mapbox/outdoors-v11"}, // Mapbox Outdoors - {3, "mapbox://styles/mapbox/light-v10"}, // Mapbox Light - {4, "mapbox://styles/mapbox/dark-v10"}, // Mapbox Dark - {5, "mapbox://styles/mapbox/satellite-v9"}, // Mapbox Satellite - {6, "mapbox://styles/mapbox/satellite-streets-v11"}, // Mapbox Satellite Streets - {7, "mapbox://styles/mapbox/navigation-day-v1"}, // Mapbox Navigation Day - {8, "mapbox://styles/mapbox/navigation-night-v1"}, // Mapbox Navigation Night - {9, "mapbox://styles/mapbox/traffic-night-v2"}, // Mapbox Traffic Night - {10, "mapbox://styles/mike854/clt0hm8mw01ok01p4blkr27jp"}, // mike854's (Satellite hybrid) - }; - - std::unordered_map::iterator it = styleUrls.find(map_style); - m_map->setStyleUrl(QString::fromStdString(it->second)); - } - - previous_map_style = map_style; -} - -void MapWindow::setError(const QString &err_str) { - if (err_str != error->text()) { - error->setText(err_str); - error->setVisible(!err_str.isEmpty()); - if (!err_str.isEmpty()) map_instructions->setVisible(false); - } -} - -void MapWindow::resizeGL(int w, int h) { - m_map->resize(size() / MAP_SCALE); - map_overlay->setFixedSize(width(), height()); -} - -void MapWindow::initializeGL() { - m_map.reset(new QMapLibre::Map(this, m_settings, size(), 1)); - - if (last_position) { - m_map->setCoordinateZoom(*last_position, MAX_ZOOM); - } else { - m_map->setCoordinateZoom(QMapLibre::Coordinate(64.31990695292795, -149.79038934046247), MIN_ZOOM); - } - - m_map->setMargins({0, 350, 0, 50}); - m_map->setPitch(MIN_PITCH); - m_map->setStyleUrl("mapbox://styles/commaai/clkqztk0f00ou01qyhsa5bzpj"); - - QObject::connect(m_map.data(), &QMapLibre::Map::mapChanged, [=](QMapLibre::Map::MapChange change) { - // set global animation duration to 0 ms so visibility changes are instant - if (change == QMapLibre::Map::MapChange::MapChangeDidFinishLoadingStyle) { - m_map->setTransitionOptions(0, 0); - } - if (change == QMapLibre::Map::MapChange::MapChangeDidFinishLoadingMap) { - loaded_once = true; - } - }); -} - -void MapWindow::paintGL() { - if (!isVisible() || m_map.isNull()) return; - m_map->render(); -} - -void MapWindow::clearRoute() { - if (!m_map.isNull()) { - m_map->setLayoutProperty("navLayer", "visibility", "none"); - m_map->setPitch(MIN_PITCH); - updateDestinationMarker(); - } - - map_instructions->setVisible(false); - map_eta->setVisible(false); - last_valid_nav_dest = std::nullopt; -} - -void MapWindow::mousePressEvent(QMouseEvent *ev) { - m_lastPos = ev->localPos(); - ev->accept(); -} - -void MapWindow::mouseDoubleClickEvent(QMouseEvent *ev) { - if (last_position) m_map->setCoordinate(*last_position); - if (last_bearing) m_map->setBearing(*last_bearing); - m_map->setZoom(util::map_val(velocity_filter.x(), 0, 30, MAX_ZOOM, MIN_ZOOM)); - update(); - - interaction_counter = 0; -} - -void MapWindow::mouseMoveEvent(QMouseEvent *ev) { - QPointF delta = ev->localPos() - m_lastPos; - - if (!delta.isNull()) { - interaction_counter = INTERACTION_TIMEOUT; - m_map->moveBy(delta / MAP_SCALE); - update(); - } - - m_lastPos = ev->localPos(); - ev->accept(); -} - -void MapWindow::wheelEvent(QWheelEvent *ev) { - if (ev->orientation() == Qt::Horizontal) { - return; - } - - float factor = ev->delta() / 1200.; - if (ev->delta() < 0) { - factor = factor > -1 ? factor : 1 / factor; - } - - m_map->scaleBy(1 + factor, ev->pos() / MAP_SCALE); - update(); - - interaction_counter = INTERACTION_TIMEOUT; - ev->accept(); -} - -bool MapWindow::event(QEvent *event) { - if (event->type() == QEvent::Gesture) { - return gestureEvent(static_cast(event)); - } - - return QWidget::event(event); -} - -bool MapWindow::gestureEvent(QGestureEvent *event) { - if (QGesture *pinch = event->gesture(Qt::PinchGesture)) { - pinchTriggered(static_cast(pinch)); - } - return true; -} - -void MapWindow::pinchTriggered(QPinchGesture *gesture) { - QPinchGesture::ChangeFlags changeFlags = gesture->changeFlags(); - if (changeFlags & QPinchGesture::ScaleFactorChanged) { - // TODO: figure out why gesture centerPoint doesn't work - m_map->scaleBy(gesture->scaleFactor(), {width() / 2.0 / MAP_SCALE, height() / 2.0 / MAP_SCALE}); - update(); - interaction_counter = INTERACTION_TIMEOUT; - } -} - -void MapWindow::offroadTransition(bool offroad) { - if (offroad) { - clearRoute(); - uiState()->scene.navigate_on_openpilot = false; - routing_problem = false; - } else { - auto dest = coordinate_from_param("NavDestination"); - emit requestVisible(dest.has_value()); - } - last_bearing = {}; -} - -void MapWindow::updateDestinationMarker() { - auto nav_dest = coordinate_from_param("NavDestination"); - if (nav_dest.has_value()) { - auto point = coordinate_to_collection(*nav_dest); - QMapLibre::Feature feature(QMapLibre::Feature::PointType, point, {}, {}); - QVariantMap pinSource; - pinSource["type"] = "geojson"; - pinSource["data"] = QVariant::fromValue(feature); - m_map->updateSource("pinSource", pinSource); - m_map->setPaintProperty("pinLayer", "visibility", "visible"); - } else { - m_map->setPaintProperty("pinLayer", "visibility", "none"); - } -} diff --git a/selfdrive/ui/qt/maps/map.h b/selfdrive/ui/qt/maps/map.h deleted file mode 100644 index 2447b8d..0000000 --- a/selfdrive/ui/qt/maps/map.h +++ /dev/null @@ -1,96 +0,0 @@ -#pragma once - -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include "cereal/messaging/messaging.h" -#include "common/params.h" -#include "common/util.h" -#include "selfdrive/ui/ui.h" -#include "selfdrive/ui/qt/maps/map_eta.h" -#include "selfdrive/ui/qt/maps/map_instructions.h" - -class MapWindow : public QOpenGLWidget { - Q_OBJECT - -public: - MapWindow(const QMapLibre::Settings &); - ~MapWindow(); - -private: - void initializeGL() final; - void paintGL() final; - void resizeGL(int w, int h) override; - - QMapLibre::Settings m_settings; - QScopedPointer m_map; - - void initLayers(); - - void mousePressEvent(QMouseEvent *ev) final; - void mouseDoubleClickEvent(QMouseEvent *ev) final; - void mouseMoveEvent(QMouseEvent *ev) final; - void wheelEvent(QWheelEvent *ev) final; - bool event(QEvent *event) final; - bool gestureEvent(QGestureEvent *event); - void pinchTriggered(QPinchGesture *gesture); - void setError(const QString &err_str); - - bool loaded_once = false; - - // Panning - QPointF m_lastPos; - int interaction_counter = 0; - - // Position - std::optional last_valid_nav_dest; - std::optional last_position; - std::optional last_bearing; - FirstOrderFilter velocity_filter; - bool locationd_valid = false; - bool routing_problem = false; - - QWidget *map_overlay; - QLabel *error; - MapInstructions* map_instructions; - MapETA* map_eta; - - // Blue with normal nav, green when nav is input into the model - QColor getNavPathColor(bool nav_enabled) { - return nav_enabled ? QColor("#31ee73") : QColor("#31a1ee"); - } - - void clearRoute(); - void updateDestinationMarker(); - uint64_t route_rcv_frame = 0; - uint64_t model_rcv_frame = 0; - - // FrogPilot variables - Params params; - - int previous_map_style; - -private slots: - void updateState(const UIState &s); - -public slots: - void offroadTransition(bool offroad); - -signals: - void requestVisible(bool visible); - void requestSettings(bool settings); -}; diff --git a/selfdrive/ui/qt/maps/map_eta.cc b/selfdrive/ui/qt/maps/map_eta.cc deleted file mode 100644 index 161844c..0000000 --- a/selfdrive/ui/qt/maps/map_eta.cc +++ /dev/null @@ -1,56 +0,0 @@ -#include "selfdrive/ui/qt/maps/map_eta.h" - -#include -#include - -#include "selfdrive/ui/qt/maps/map_helpers.h" -#include "selfdrive/ui/ui.h" - -const float MANEUVER_TRANSITION_THRESHOLD = 10; - -MapETA::MapETA(QWidget *parent) : QWidget(parent) { - setVisible(false); - setAttribute(Qt::WA_TranslucentBackground); - eta_doc.setUndoRedoEnabled(false); - eta_doc.setDefaultStyleSheet("body {font-family:Inter;font-size:70px;color:white;} b{font-weight:600;} td{padding:0 3px;}"); -} - -void MapETA::paintEvent(QPaintEvent *event) { - if (!eta_doc.isEmpty()) { - QPainter p(this); - p.setRenderHint(QPainter::Antialiasing); - p.setPen(Qt::NoPen); - p.setBrush(QColor(0, 0, 0, 255)); - QSizeF txt_size = eta_doc.size(); - p.drawRoundedRect((width() - txt_size.width()) / 2 - UI_BORDER_SIZE, 0, txt_size.width() + UI_BORDER_SIZE * 2, height() + 25, 25, 25); - p.translate((width() - txt_size.width()) / 2, (height() - txt_size.height()) / 2); - eta_doc.drawContents(&p); - } -} - -void MapETA::updateETA(float s, float s_typical, float d) { - // ETA - auto eta_t = QDateTime::currentDateTime().addSecs(s).time(); - auto eta = format_24h ? std::pair{eta_t.toString("HH:mm"), tr("eta")} - : std::pair{eta_t.toString("h:mm a").split(' ')[0], eta_t.toString("a")}; - - // Remaining time - auto remaining = s < 3600 ? std::pair{QString::number(int(s / 60)), tr("min")} - : std::pair{QString("%1:%2").arg((int)s / 3600).arg(((int)s % 3600) / 60, 2, 10, QLatin1Char('0')), tr("hr")}; - QString color = "#25DA6E"; - if (s / s_typical > 1.5) - color = "#DA3025"; - else if (s / s_typical > 1.2) - color = "#DAA725"; - - // Distance - auto distance = map_format_distance(d, uiState()->scene.is_metric); - - eta_doc.setHtml(QString(R"( - - )") - .arg(eta.first, eta.second, color, remaining.first, remaining.second, distance.first, distance.second)); - - setVisible(d >= MANEUVER_TRANSITION_THRESHOLD); - update(); -} diff --git a/selfdrive/ui/qt/maps/map_eta.h b/selfdrive/ui/qt/maps/map_eta.h deleted file mode 100644 index 6e59837..0000000 --- a/selfdrive/ui/qt/maps/map_eta.h +++ /dev/null @@ -1,23 +0,0 @@ -#pragma once - -#include -#include -#include - -#include "common/params.h" - -class MapETA : public QWidget { - Q_OBJECT - -public: - MapETA(QWidget * parent=nullptr); - void updateETA(float seconds, float seconds_typical, float distance); - -private: - void paintEvent(QPaintEvent *event) override; - void showEvent(QShowEvent *event) override { format_24h = param.getBool("NavSettingTime24h"); } - - bool format_24h = false; - QTextDocument eta_doc; - Params param; -}; diff --git a/selfdrive/ui/qt/maps/map_helpers.cc b/selfdrive/ui/qt/maps/map_helpers.cc deleted file mode 100644 index 3907ff7..0000000 --- a/selfdrive/ui/qt/maps/map_helpers.cc +++ /dev/null @@ -1,153 +0,0 @@ -#include "selfdrive/ui/qt/maps/map_helpers.h" - -#include -#include -#include - -#include -#include - -#include "common/params.h" -#include "system/hardware/hw.h" -#include "selfdrive/ui/qt/api.h" - -QString get_mapbox_token() { - // Valid for 4 weeks since we can't swap tokens on the fly - return MAPBOX_TOKEN.isEmpty() ? CommaApi::create_jwt({}, 4 * 7 * 24 * 3600) : MAPBOX_TOKEN; -} - -QMapLibre::Settings get_mapbox_settings() { - QMapLibre::Settings settings; - settings.setProviderTemplate(QMapLibre::Settings::ProviderTemplate::MapboxProvider); - - if (!Hardware::PC()) { - settings.setCacheDatabasePath(MAPS_CACHE_PATH); - settings.setCacheDatabaseMaximumSize(100 * 1024 * 1024); - } - settings.setApiBaseUrl(MAPS_HOST); - settings.setApiKey(get_mapbox_token()); - - return settings; -} - -QGeoCoordinate to_QGeoCoordinate(const QMapLibre::Coordinate &in) { - return QGeoCoordinate(in.first, in.second); -} - -QMapLibre::CoordinatesCollections model_to_collection( - const cereal::LiveLocationKalman::Measurement::Reader &calibratedOrientationECEF, - const cereal::LiveLocationKalman::Measurement::Reader &positionECEF, - const cereal::XYZTData::Reader &line){ - - Eigen::Vector3d ecef(positionECEF.getValue()[0], positionECEF.getValue()[1], positionECEF.getValue()[2]); - Eigen::Vector3d orient(calibratedOrientationECEF.getValue()[0], calibratedOrientationECEF.getValue()[1], calibratedOrientationECEF.getValue()[2]); - Eigen::Matrix3d ecef_from_local = euler2rot(orient); - - QMapLibre::Coordinates coordinates; - auto x = line.getX(); - auto y = line.getY(); - auto z = line.getZ(); - for (int i = 0; i < x.size(); i++) { - Eigen::Vector3d point_ecef = ecef_from_local * Eigen::Vector3d(x[i], y[i], z[i]) + ecef; - Geodetic point_geodetic = ecef2geodetic((ECEF){.x = point_ecef[0], .y = point_ecef[1], .z = point_ecef[2]}); - coordinates.push_back({point_geodetic.lat, point_geodetic.lon}); - } - - return {QMapLibre::CoordinatesCollection{coordinates}}; -} - -QMapLibre::CoordinatesCollections coordinate_to_collection(const QMapLibre::Coordinate &c) { - QMapLibre::Coordinates coordinates{c}; - return {QMapLibre::CoordinatesCollection{coordinates}}; -} - -QMapLibre::CoordinatesCollections capnp_coordinate_list_to_collection(const capnp::List::Reader& coordinate_list) { - QMapLibre::Coordinates coordinates; - for (auto const &c : coordinate_list) { - coordinates.push_back({c.getLatitude(), c.getLongitude()}); - } - return {QMapLibre::CoordinatesCollection{coordinates}}; -} - -QMapLibre::CoordinatesCollections coordinate_list_to_collection(const QList &coordinate_list) { - QMapLibre::Coordinates coordinates; - for (auto &c : coordinate_list) { - coordinates.push_back({c.latitude(), c.longitude()}); - } - return {QMapLibre::CoordinatesCollection{coordinates}}; -} - -QList polyline_to_coordinate_list(const QString &polylineString) { - QList path; - if (polylineString.isEmpty()) - return path; - - QByteArray data = polylineString.toLatin1(); - - bool parsingLatitude = true; - - int shift = 0; - int value = 0; - - QGeoCoordinate coord(0, 0); - - for (int i = 0; i < data.length(); ++i) { - unsigned char c = data.at(i) - 63; - - value |= (c & 0x1f) << shift; - shift += 5; - - // another chunk - if (c & 0x20) - continue; - - int diff = (value & 1) ? ~(value >> 1) : (value >> 1); - - if (parsingLatitude) { - coord.setLatitude(coord.latitude() + (double)diff/1e6); - } else { - coord.setLongitude(coord.longitude() + (double)diff/1e6); - path.append(coord); - } - - parsingLatitude = !parsingLatitude; - - value = 0; - shift = 0; - } - - return path; -} - -std::optional coordinate_from_param(const std::string ¶m) { - QString json_str = QString::fromStdString(Params().get(param)); - if (json_str.isEmpty()) return {}; - - QJsonDocument doc = QJsonDocument::fromJson(json_str.toUtf8()); - if (doc.isNull()) return {}; - - QJsonObject json = doc.object(); - if (json["latitude"].isDouble() && json["longitude"].isDouble()) { - QMapLibre::Coordinate coord(json["latitude"].toDouble(), json["longitude"].toDouble()); - return coord; - } else { - return {}; - } -} - -// return {distance, unit} -std::pair map_format_distance(float d, bool is_metric) { - auto round_distance = [](float d) -> float { - return (d > 10) ? std::nearbyint(d) : std::nearbyint(d * 10) / 10.0; - }; - - d = std::max(d, 0.0f); - if (is_metric) { - return (d > 500) ? std::pair{QString::number(round_distance(d / 1000)), QObject::tr("km")} - : std::pair{QString::number(50 * std::nearbyint(d / 50)), QObject::tr("m")}; - } else { - float feet = d * METER_TO_FOOT; - return (feet > 500) ? std::pair{QString::number(round_distance(d * METER_TO_MILE)), QObject::tr("mi")} - : std::pair{QString::number(50 * std::nearbyint(d / 50)), QObject::tr("ft")}; - } -} diff --git a/selfdrive/ui/qt/maps/map_helpers.h b/selfdrive/ui/qt/maps/map_helpers.h deleted file mode 100644 index d1ac768..0000000 --- a/selfdrive/ui/qt/maps/map_helpers.h +++ /dev/null @@ -1,33 +0,0 @@ -#pragma once - -#include -#include -#include -#include -#include -#include -#include - -#include "common/params.h" -#include "common/util.h" -#include "common/transformations/coordinates.hpp" -#include "common/transformations/orientation.hpp" -#include "cereal/messaging/messaging.h" - -const QString MAPBOX_TOKEN = QString::fromStdString(Params().get("MapboxPublicKey")); -const QString MAPS_HOST = util::getenv("MAPS_HOST", MAPBOX_TOKEN.isEmpty() ? "https://maps.comma.ai" : "https://api.mapbox.com").c_str(); -const QString MAPS_CACHE_PATH = "/data/mbgl-cache-navd.db"; - -QString get_mapbox_token(); -QMapLibre::Settings get_mapbox_settings(); -QGeoCoordinate to_QGeoCoordinate(const QMapLibre::Coordinate &in); -QMapLibre::CoordinatesCollections model_to_collection( - const cereal::LiveLocationKalman::Measurement::Reader &calibratedOrientationECEF, - const cereal::LiveLocationKalman::Measurement::Reader &positionECEF, - const cereal::XYZTData::Reader &line); -QMapLibre::CoordinatesCollections coordinate_to_collection(const QMapLibre::Coordinate &c); -QMapLibre::CoordinatesCollections capnp_coordinate_list_to_collection(const capnp::List::Reader &coordinate_list); -QMapLibre::CoordinatesCollections coordinate_list_to_collection(const QList &coordinate_list); -QList polyline_to_coordinate_list(const QString &polylineString); -std::optional coordinate_from_param(const std::string ¶m); -std::pair map_format_distance(float d, bool is_metric); diff --git a/selfdrive/ui/qt/maps/map_instructions.cc b/selfdrive/ui/qt/maps/map_instructions.cc deleted file mode 100644 index ba8cb35..0000000 --- a/selfdrive/ui/qt/maps/map_instructions.cc +++ /dev/null @@ -1,144 +0,0 @@ -#include "selfdrive/ui/qt/maps/map_instructions.h" - -#include -#include - -#include "selfdrive/ui/qt/maps/map_helpers.h" -#include "selfdrive/ui/ui.h" - -const QString ICON_SUFFIX = ".png"; - -MapInstructions::MapInstructions(QWidget *parent) : QWidget(parent) { - is_rhd = Params().getBool("IsRhdDetected"); - QVBoxLayout *main_layout = new QVBoxLayout(this); - main_layout->setContentsMargins(11, UI_BORDER_SIZE, 11, 20); - - QHBoxLayout *top_layout = new QHBoxLayout; - top_layout->addWidget(icon_01 = new QLabel, 0, Qt::AlignTop); - - QVBoxLayout *right_layout = new QVBoxLayout; - right_layout->setContentsMargins(9, 9, 9, 0); - right_layout->addWidget(distance = new QLabel); - distance->setStyleSheet(R"(font-size: 90px;)"); - - right_layout->addWidget(primary = new QLabel); - primary->setStyleSheet(R"(font-size: 60px;)"); - primary->setWordWrap(true); - - right_layout->addWidget(secondary = new QLabel); - secondary->setStyleSheet(R"(font-size: 50px;)"); - secondary->setWordWrap(true); - - top_layout->addLayout(right_layout); - - main_layout->addLayout(top_layout); - main_layout->addLayout(lane_layout = new QHBoxLayout); - lane_layout->setAlignment(Qt::AlignHCenter); - lane_layout->setSpacing(10); - - setStyleSheet("color:white"); - QPalette pal = palette(); - pal.setColor(QPalette::Background, QColor(0, 0, 0, 150)); - setAutoFillBackground(true); - setPalette(pal); - - buildPixmapCache(); -} - -void MapInstructions::buildPixmapCache() { - QDir dir("../assets/navigation"); - for (QString fn : dir.entryList({"*" + ICON_SUFFIX}, QDir::Files)) { - QPixmap pm(dir.filePath(fn)); - QString key = fn.left(fn.size() - ICON_SUFFIX.length()); - pm = pm.scaledToWidth(200, Qt::SmoothTransformation); - - // Maneuver icons - pixmap_cache[key] = pm; - // lane direction icons - if (key.contains("turn_")) { - pixmap_cache["lane_" + key] = pm.scaled({125, 125}, Qt::IgnoreAspectRatio, Qt::SmoothTransformation); - } - - // for rhd, reflect direction and then flip - if (key.contains("_left")) { - pixmap_cache["rhd_" + key.replace("_left", "_right")] = pm.transformed(QTransform().scale(-1, 1)); - } else if (key.contains("_right")) { - pixmap_cache["rhd_" + key.replace("_right", "_left")] = pm.transformed(QTransform().scale(-1, 1)); - } - } -} - -void MapInstructions::updateInstructions(cereal::NavInstruction::Reader instruction) { - setUpdatesEnabled(false); - - // Show instruction text - QString primary_str = QString::fromStdString(instruction.getManeuverPrimaryText()); - QString secondary_str = QString::fromStdString(instruction.getManeuverSecondaryText()); - - primary->setText(primary_str); - secondary->setVisible(secondary_str.length() > 0); - secondary->setText(secondary_str); - - auto distance_str_pair = map_format_distance(instruction.getManeuverDistance(), uiState()->scene.is_metric); - distance->setText(QString("%1 %2").arg(distance_str_pair.first, distance_str_pair.second)); - - // Show arrow with direction - QString type = QString::fromStdString(instruction.getManeuverType()); - QString modifier = QString::fromStdString(instruction.getManeuverModifier()); - if (!type.isEmpty()) { - QString fn = "direction_" + type; - if (!modifier.isEmpty()) { - fn += "_" + modifier; - } - fn = fn.replace(' ', '_'); - bool rhd = is_rhd && (fn.contains("_left") || fn.contains("_right")); - icon_01->setPixmap(pixmap_cache[!rhd ? fn : "rhd_" + fn]); - icon_01->setSizePolicy(QSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed)); - icon_01->setVisible(true); - } else { - icon_01->setVisible(false); - } - - // Hide distance after arrival - distance->setVisible(type != "arrive" || instruction.getManeuverDistance() > 0); - - // Show lanes - auto lanes = instruction.getLanes(); - for (int i = 0; i < lanes.size(); ++i) { - bool active = lanes[i].getActive(); - const auto active_direction = lanes[i].getActiveDirection(); - - // TODO: Make more images based on active direction and combined directions - QString fn = "lane_direction_"; - - // active direction has precedence - if (active && active_direction != cereal::NavInstruction::Direction::NONE) { - fn += "turn_" + DIRECTIONS[active_direction]; - } else { - for (auto const &direction : lanes[i].getDirections()) { - if (direction != cereal::NavInstruction::Direction::NONE) { - fn += "turn_" + DIRECTIONS[direction]; - break; - } - } - } - - if (!active) { - fn += "_inactive"; - } - - QLabel *label = (i < lane_labels.size()) ? lane_labels[i] : lane_labels.emplace_back(new QLabel); - if (!label->parentWidget()) { - lane_layout->addWidget(label); - } - label->setPixmap(pixmap_cache[fn]); - label->setVisible(true); - } - - for (int i = lanes.size(); i < lane_labels.size(); ++i) { - lane_labels[i]->setVisible(false); - } - - setUpdatesEnabled(true); - setVisible(true); -} diff --git a/selfdrive/ui/qt/maps/map_instructions.h b/selfdrive/ui/qt/maps/map_instructions.h deleted file mode 100644 index 06a943d..0000000 --- a/selfdrive/ui/qt/maps/map_instructions.h +++ /dev/null @@ -1,38 +0,0 @@ -#pragma once - -#include -#include - -#include -#include -#include - -#include "cereal/gen/cpp/log.capnp.h" - -static std::map DIRECTIONS = { - {cereal::NavInstruction::Direction::NONE, "none"}, - {cereal::NavInstruction::Direction::LEFT, "left"}, - {cereal::NavInstruction::Direction::RIGHT, "right"}, - {cereal::NavInstruction::Direction::STRAIGHT, "straight"}, - {cereal::NavInstruction::Direction::SLIGHT_LEFT, "slight_left"}, - {cereal::NavInstruction::Direction::SLIGHT_RIGHT, "slight_right"}, -}; - -class MapInstructions : public QWidget { - Q_OBJECT - -private: - QLabel *distance; - QLabel *primary; - QLabel *secondary; - QLabel *icon_01; - QHBoxLayout *lane_layout; - bool is_rhd = false; - std::vector lane_labels; - QHash pixmap_cache; - -public: - MapInstructions(QWidget * parent=nullptr); - void buildPixmapCache(); - void updateInstructions(cereal::NavInstruction::Reader instruction); -}; diff --git a/selfdrive/ui/qt/maps/map_panel.cc b/selfdrive/ui/qt/maps/map_panel.cc deleted file mode 100644 index 1044cc0..0000000 --- a/selfdrive/ui/qt/maps/map_panel.cc +++ /dev/null @@ -1,48 +0,0 @@ -#include "selfdrive/ui/qt/maps/map_panel.h" - -#include -#include - -#include "selfdrive/ui/qt/maps/map.h" -#include "selfdrive/ui/qt/maps/map_settings.h" -#include "selfdrive/ui/qt/util.h" -#include "selfdrive/ui/ui.h" - -MapPanel::MapPanel(const QMapLibre::Settings &mapboxSettings, QWidget *parent) : QFrame(parent) { - content_stack = new QStackedLayout(this); - content_stack->setContentsMargins(0, 0, 0, 0); - - auto map = new MapWindow(mapboxSettings); - QObject::connect(uiState(), &UIState::offroadTransition, map, &MapWindow::offroadTransition); - QObject::connect(device(), &Device::interactiveTimeout, this, [=]() { - content_stack->setCurrentIndex(0); - }); - QObject::connect(map, &MapWindow::requestVisible, this, [=](bool visible) { - // when we show the map for a new route, signal HomeWindow to hide the sidebar - if (visible) { emit mapPanelRequested(); } - setVisible(visible); - }); - QObject::connect(map, &MapWindow::requestSettings, this, [=](bool settings) { - content_stack->setCurrentIndex(settings ? 1 : 0); - }); - content_stack->addWidget(map); - - auto settings = new MapSettings(true, parent); - QObject::connect(settings, &MapSettings::closeSettings, this, [=]() { - content_stack->setCurrentIndex(0); - }); - content_stack->addWidget(settings); -} - -void MapPanel::toggleMapSettings() { - // show settings if not visible, then toggle between map and settings - int new_index = isVisible() ? (1 - content_stack->currentIndex()) : 1; - content_stack->setCurrentIndex(new_index); - emit mapPanelRequested(); - show(); -} - -void MapPanel::setVisible(bool visible) { - QFrame::setVisible(visible); - uiState()->scene.map_open = visible; -} diff --git a/selfdrive/ui/qt/maps/map_panel.h b/selfdrive/ui/qt/maps/map_panel.h deleted file mode 100644 index ed287b1..0000000 --- a/selfdrive/ui/qt/maps/map_panel.h +++ /dev/null @@ -1,22 +0,0 @@ -#pragma once - -#include -#include -#include - -class MapPanel : public QFrame { - Q_OBJECT - -public: - explicit MapPanel(const QMapLibre::Settings &settings, QWidget *parent = nullptr); - void setVisible(bool visible); - -signals: - void mapPanelRequested(); - -public slots: - void toggleMapSettings(); - -private: - QStackedLayout *content_stack; -}; diff --git a/selfdrive/ui/qt/maps/map_settings.cc b/selfdrive/ui/qt/maps/map_settings.cc deleted file mode 100644 index d6fc724..0000000 --- a/selfdrive/ui/qt/maps/map_settings.cc +++ /dev/null @@ -1,393 +0,0 @@ -#include "selfdrive/ui/qt/maps/map_settings.h" - -#include - -#include -#include - -#include "common/util.h" -#include "selfdrive/ui/qt/request_repeater.h" -#include "selfdrive/ui/qt/widgets/scrollview.h" - -static void swap(QJsonValueRef v1, QJsonValueRef v2) { std::swap(v1, v2); } - -static bool locationEqual(const QJsonValue &v1, const QJsonValue &v2) { - return v1["latitude"] == v2["latitude"] && v1["longitude"] == v2["longitude"]; -} - -static qint64 convertTimestampToEpoch(const QString ×tamp) { - QDateTime dt = QDateTime::fromString(timestamp, Qt::ISODate); - return dt.isValid() ? dt.toSecsSinceEpoch() : 0; -} - -MapSettings::MapSettings(bool closeable, QWidget *parent) : QFrame(parent) { - setContentsMargins(0, 0, 0, 0); - setAttribute(Qt::WA_NoMousePropagation); - - auto *frame = new QVBoxLayout(this); - frame->setContentsMargins(40, 40, 40, 0); - frame->setSpacing(0); - - auto *heading_frame = new QHBoxLayout; - heading_frame->setContentsMargins(0, 0, 0, 0); - heading_frame->setSpacing(32); - { - if (closeable) { - auto *close_btn = new QPushButton("←"); - close_btn->setStyleSheet(R"( - QPushButton { - color: #FFFFFF; - font-size: 100px; - padding-bottom: 8px; - border 1px grey solid; - border-radius: 70px; - background-color: #292929; - font-weight: 500; - } - QPushButton:pressed { - background-color: #3B3B3B; - } - )"); - close_btn->setFixedSize(140, 140); - QObject::connect(close_btn, &QPushButton::clicked, [=]() { emit closeSettings(); }); - // TODO: read map_on_left from ui state - heading_frame->addWidget(close_btn); - } - - auto *heading = new QVBoxLayout; - heading->setContentsMargins(0, 0, 0, 0); - heading->setSpacing(16); - { - auto *title = new QLabel(tr("NAVIGATION"), this); - title->setStyleSheet("color: #FFFFFF; font-size: 54px; font-weight: 600;"); - heading->addWidget(title); - - subtitle = new QLabel(tr("Manage at connect.comma.ai"), this); - subtitle->setStyleSheet("color: #A0A0A0; font-size: 40px; font-weight: 300;"); - heading->addWidget(subtitle); - } - heading_frame->addLayout(heading, 1); - } - frame->addLayout(heading_frame); - frame->addSpacing(32); - - current_widget = new DestinationWidget(this); - QObject::connect(current_widget, &DestinationWidget::actionClicked, - []() { NavManager::instance()->setCurrentDestination({}); }); - frame->addWidget(current_widget); - frame->addSpacing(32); - - QWidget *destinations_container = new QWidget(this); - destinations_layout = new QVBoxLayout(destinations_container); - destinations_layout->setContentsMargins(0, 32, 0, 32); - destinations_layout->setSpacing(20); - destinations_layout->addWidget(home_widget = new DestinationWidget(this)); - destinations_layout->addWidget(work_widget = new DestinationWidget(this)); - QObject::connect(home_widget, &DestinationWidget::navigateTo, this, &MapSettings::navigateTo); - QObject::connect(work_widget, &DestinationWidget::navigateTo, this, &MapSettings::navigateTo); - destinations_layout->addStretch(); - - ScrollView *destinations_scroller = new ScrollView(destinations_container, this); - destinations_scroller->setFrameShape(QFrame::NoFrame); - frame->addWidget(destinations_scroller); - - setStyleSheet("MapSettings { background-color: #333333; }"); - QObject::connect(NavManager::instance(), &NavManager::updated, this, &MapSettings::refresh); - - wifi = new WifiManager(this); -} - -void MapSettings::showEvent(QShowEvent *event) { - refresh(); -} - -void MapSettings::refresh() { - if (!isVisible()) return; - - setUpdatesEnabled(false); - - auto get_w = [this](int i) { - auto w = i < widgets.size() ? widgets[i] : widgets.emplace_back(new DestinationWidget); - if (!w->parentWidget()) { - destinations_layout->insertWidget(destinations_layout->count() - 1, w); - QObject::connect(w, &DestinationWidget::navigateTo, this, &MapSettings::navigateTo); - } - return w; - }; - - const auto current_dest = NavManager::instance()->currentDestination(); - if (!current_dest.isEmpty()) { - current_widget->set(current_dest, true); - } else { - current_widget->unset("", true); - } - home_widget->unset(NAV_FAVORITE_LABEL_HOME); - work_widget->unset(NAV_FAVORITE_LABEL_WORK); - - int n = 0; - for (auto location : NavManager::instance()->currentLocations()) { - DestinationWidget *w = nullptr; - auto dest = location.toObject(); - if (dest["save_type"].toString() == NAV_TYPE_FAVORITE) { - auto label = dest["label"].toString(); - if (label == NAV_FAVORITE_LABEL_HOME) w = home_widget; - if (label == NAV_FAVORITE_LABEL_WORK) w = work_widget; - } - w = w ? w : get_w(n++); - w->set(dest, false); - w->setVisible(!locationEqual(dest, current_dest)); - } - for (; n < widgets.size(); ++n) widgets[n]->setVisible(false); - - setUpdatesEnabled(true); - - // Use IP for NOO without Prime - if (!uiState()->hasPrime()) { - QString ipAddress = QString("%1:8082").arg(wifi->getIp4Address()); - subtitle->setText(tr("Manage at %1").arg(ipAddress)); - } -} - -void MapSettings::navigateTo(const QJsonObject &place) { - NavManager::instance()->setCurrentDestination(place); - emit closeSettings(); -} - -DestinationWidget::DestinationWidget(QWidget *parent) : QPushButton(parent) { - setContentsMargins(0, 0, 0, 0); - - auto *frame = new QHBoxLayout(this); - frame->setContentsMargins(32, 24, 32, 24); - frame->setSpacing(32); - - icon = new QLabel(this); - icon->setAlignment(Qt::AlignCenter); - icon->setFixedSize(96, 96); - icon->setObjectName("icon"); - frame->addWidget(icon); - - auto *inner_frame = new QVBoxLayout; - inner_frame->setContentsMargins(0, 0, 0, 0); - inner_frame->setSpacing(0); - { - title = new ElidedLabel(this); - title->setAttribute(Qt::WA_TransparentForMouseEvents); - inner_frame->addWidget(title); - - subtitle = new ElidedLabel(this); - subtitle->setAttribute(Qt::WA_TransparentForMouseEvents); - subtitle->setObjectName("subtitle"); - inner_frame->addWidget(subtitle); - } - frame->addLayout(inner_frame, 1); - - action = new QPushButton(this); - action->setFixedSize(96, 96); - action->setObjectName("action"); - action->setStyleSheet("font-size: 65px; font-weight: 600;"); - QObject::connect(action, &QPushButton::clicked, this, &QPushButton::clicked); - QObject::connect(action, &QPushButton::clicked, this, &DestinationWidget::actionClicked); - frame->addWidget(action); - - setFixedHeight(164); - setStyleSheet(R"( - DestinationWidget { background-color: #202123; border-radius: 10px; } - QLabel { color: #FFFFFF; font-size: 48px; font-weight: 400; } - #icon { background-color: #3B4356; border-radius: 48px; } - #subtitle { color: #9BA0A5; } - #action { border: none; border-radius: 48px; color: #FFFFFF; padding-bottom: 4px; } - - /* current destination */ - [current="true"] { background-color: #E8E8E8; } - [current="true"] QLabel { color: #000000; } - [current="true"] #icon { background-color: #42906B; } - [current="true"] #subtitle { color: #333333; } - [current="true"] #action { color: #202123; } - - /* no saved destination */ - [set="false"] QLabel { color: #9BA0A5; } - [current="true"][set="false"] QLabel { color: #A0000000; } - - /* pressed */ - [current="false"]:pressed { background-color: #18191B; } - [current="true"] #action:pressed { background-color: #D6D6D6; } - )"); - QObject::connect(this, &QPushButton::clicked, [this]() { if (!dest.isEmpty()) emit navigateTo(dest); }); -} - -void DestinationWidget::set(const QJsonObject &destination, bool current) { - if (dest == destination) return; - - dest = destination; - setProperty("current", current); - setProperty("set", true); - - auto icon_pixmap = current ? icons().directions : icons().recent; - auto title_text = destination["place_name"].toString(); - auto subtitle_text = destination["place_details"].toString(); - - if (destination["save_type"] == NAV_TYPE_FAVORITE) { - if (destination["label"] == NAV_FAVORITE_LABEL_HOME) { - icon_pixmap = icons().home; - subtitle_text = title_text + ", " + subtitle_text; - title_text = tr("Home"); - } else if (destination["label"] == NAV_FAVORITE_LABEL_WORK) { - icon_pixmap = icons().work; - subtitle_text = title_text + ", " + subtitle_text; - title_text = tr("Work"); - } else { - icon_pixmap = icons().favorite; - } - } - - icon->setPixmap(icon_pixmap); - - title->setText(title_text); - subtitle->setText(subtitle_text); - subtitle->setVisible(true); - - // TODO: use pixmap - action->setAttribute(Qt::WA_TransparentForMouseEvents, !current); - action->setText(current ? "×" : "→"); - action->setVisible(true); - - setStyleSheet(styleSheet()); -} - -void DestinationWidget::unset(const QString &label, bool current) { - dest = {}; - setProperty("current", current); - setProperty("set", false); - - if (label.isEmpty()) { - icon->setPixmap(icons().directions); - title->setText(tr("No destination set")); - } else { - QString title_text = label == NAV_FAVORITE_LABEL_HOME ? tr("home") : tr("work"); - icon->setPixmap(label == NAV_FAVORITE_LABEL_HOME ? icons().home : icons().work); - title->setText(tr("No %1 location set").arg(title_text)); - } - - subtitle->setVisible(false); - action->setVisible(false); - - setStyleSheet(styleSheet()); - setVisible(true); -} - -// singleton NavManager - -NavManager *NavManager::instance() { - static NavManager *request = new NavManager(qApp); - return request; -} - -NavManager::NavManager(QObject *parent) : QObject(parent) { - locations = QJsonDocument::fromJson(params.get("NavPastDestinations").c_str()).array(); - current_dest = QJsonDocument::fromJson(params.get("NavDestination").c_str()).object(); - if (auto dongle_id = getDongleId()) { - { - // Fetch favorite and recent locations - QString url = CommaApi::BASE_URL + "/v1/navigation/" + *dongle_id + "/locations"; - RequestRepeater *repeater = new RequestRepeater(this, url, "ApiCache_NavDestinations", 30, true); - QObject::connect(repeater, &RequestRepeater::requestDone, this, &NavManager::parseLocationsResponse); - } - { - auto param_watcher = new ParamWatcher(this); - QObject::connect(param_watcher, &ParamWatcher::paramChanged, this, &NavManager::updated); - - // Destination set while offline - QString url = CommaApi::BASE_URL + "/v1/navigation/" + *dongle_id + "/next"; - HttpRequest *deleter = new HttpRequest(this); - RequestRepeater *repeater = new RequestRepeater(this, url, "", 10, true); - QObject::connect(repeater, &RequestRepeater::requestDone, [=](const QString &resp, bool success) { - if (success && resp != "null") { - if (params.get("NavDestination").empty()) { - qWarning() << "Setting NavDestination from /next" << resp; - params.put("NavDestination", resp.toStdString()); - } else { - qWarning() << "Got location from /next, but NavDestination already set"; - } - // Send DELETE to clear destination server side - deleter->sendRequest(url, HttpRequest::Method::DELETE); - } - - // athena can set destination at any time - param_watcher->addParam("NavDestination"); - current_dest = QJsonDocument::fromJson(params.get("NavDestination").c_str()).object(); - emit updated(); - }); - } - } -} - -void NavManager::parseLocationsResponse(const QString &response, bool success) { - if (!success || response == prev_response) return; - - prev_response = response; - QJsonDocument doc = QJsonDocument::fromJson(response.trimmed().toUtf8()); - if (doc.isNull()) { - qWarning() << "JSON Parse failed on navigation locations" << response; - return; - } - - // set last activity time. - auto remote_locations = doc.array(); - for (QJsonValueRef loc : remote_locations) { - auto obj = loc.toObject(); - auto serverTime = convertTimestampToEpoch(obj["modified"].toString()); - obj.insert("time", qMax(serverTime, getLastActivity(obj))); - loc = obj; - } - - locations = remote_locations; - sortLocations(); - emit updated(); -} - -void NavManager::sortLocations() { - // Sort: alphabetical FAVORITES, and then most recent. - // We don't need to care about the ordering of HOME and WORK. DestinationWidget always displays them at the top. - std::stable_sort(locations.begin(), locations.end(), [](const QJsonValue &a, const QJsonValue &b) { - if (a["save_type"] == NAV_TYPE_FAVORITE || b["save_type"] == NAV_TYPE_FAVORITE) { - return (std::tuple(a["save_type"].toString(), a["place_name"].toString()) < - std::tuple(b["save_type"].toString(), b["place_name"].toString())); - } else { - return a["time"].toVariant().toLongLong() > b["time"].toVariant().toLongLong(); - } - }); - - write_param_future = std::async(std::launch::async, [destinations = QJsonArray(locations)]() { - Params().put("NavPastDestinations", QJsonDocument(destinations).toJson().toStdString()); - }); -} - -qint64 NavManager::getLastActivity(const QJsonObject &loc) const { - qint64 last_activity = 0; - auto it = std::find_if(locations.begin(), locations.end(), - [&loc](const QJsonValue &l) { return locationEqual(loc, l); }); - if (it != locations.end()) { - auto tm = it->toObject().value("time"); - if (!tm.isUndefined() && !tm.isNull()) { - last_activity = tm.toVariant().toLongLong(); - } - } - return last_activity; -} - -void NavManager::setCurrentDestination(const QJsonObject &loc) { - current_dest = loc; - if (!current_dest.isEmpty()) { - current_dest["time"] = QDateTime::currentSecsSinceEpoch(); - auto it = std::find_if(locations.begin(), locations.end(), - [&loc](const QJsonValue &l) { return locationEqual(loc, l); }); - if (it != locations.end()) { - *it = current_dest; - sortLocations(); - } - params.put("NavDestination", QJsonDocument(current_dest).toJson().toStdString()); - } else { - params.remove("NavDestination"); - } - emit updated(); -} diff --git a/selfdrive/ui/qt/maps/map_settings.h b/selfdrive/ui/qt/maps/map_settings.h deleted file mode 100644 index 1a96336..0000000 --- a/selfdrive/ui/qt/maps/map_settings.h +++ /dev/null @@ -1,108 +0,0 @@ -#pragma once - -#include -#include - -#include -#include -#include -#include -#include -#include -#include - -#include "common/params.h" -#include "selfdrive/ui/qt/network/wifi_manager.h" -#include "selfdrive/ui/qt/util.h" -#include "selfdrive/ui/qt/widgets/controls.h" - -const QString NAV_TYPE_FAVORITE = "favorite"; -const QString NAV_TYPE_RECENT = "recent"; - -const QString NAV_FAVORITE_LABEL_HOME = "home"; -const QString NAV_FAVORITE_LABEL_WORK = "work"; - -class DestinationWidget; - -class NavManager : public QObject { - Q_OBJECT - -public: - static NavManager *instance(); - QJsonArray currentLocations() const { return locations; } - QJsonObject currentDestination() const { return current_dest; } - void setCurrentDestination(const QJsonObject &loc); - qint64 getLastActivity(const QJsonObject &loc) const; - -signals: - void updated(); - -private: - NavManager(QObject *parent); - void parseLocationsResponse(const QString &response, bool success); - void sortLocations(); - - Params params; - QString prev_response; - QJsonArray locations; - QJsonObject current_dest; - std::future write_param_future; -}; - -class MapSettings : public QFrame { - Q_OBJECT -public: - explicit MapSettings(bool closeable = false, QWidget *parent = nullptr); - void navigateTo(const QJsonObject &place); - -private: - void showEvent(QShowEvent *event) override; - void refresh(); - - QVBoxLayout *destinations_layout; - DestinationWidget *current_widget; - DestinationWidget *home_widget; - DestinationWidget *work_widget; - std::vector widgets; - - // FrogPilot variables - QLabel *subtitle; - - WifiManager *wifi; - -signals: - void closeSettings(); -}; - -class DestinationWidget : public QPushButton { - Q_OBJECT -public: - explicit DestinationWidget(QWidget *parent = nullptr); - void set(const QJsonObject &location, bool current = false); - void unset(const QString &label, bool current = false); - -signals: - void actionClicked(); - void navigateTo(const QJsonObject &destination); - -private: - struct NavIcons { - QPixmap home, work, favorite, recent, directions; - }; - - static NavIcons icons() { - static NavIcons nav_icons { - loadPixmap("../assets/navigation/icon_home.svg", {48, 48}), - loadPixmap("../assets/navigation/icon_work.svg", {48, 48}), - loadPixmap("../assets/navigation/icon_favorite.svg", {48, 48}), - loadPixmap("../assets/navigation/icon_recent.svg", {48, 48}), - loadPixmap("../assets/navigation/icon_directions.svg", {48, 48}), - }; - return nav_icons; - } - -private: - QLabel *icon, *title, *subtitle; - QPushButton *action; - QJsonObject dest; -}; diff --git a/selfdrive/ui/qt/network/networking.cc b/selfdrive/ui/qt/network/networking.cc deleted file mode 100644 index 9f4598f..0000000 --- a/selfdrive/ui/qt/network/networking.cc +++ /dev/null @@ -1,384 +0,0 @@ -#include "selfdrive/ui/qt/network/networking.h" - -#include - -#include -#include -#include - -#include "selfdrive/ui/ui.h" -#include "selfdrive/ui/qt/qt_window.h" -#include "selfdrive/ui/qt/util.h" -#include "selfdrive/ui/qt/widgets/controls.h" -#include "selfdrive/ui/qt/widgets/scrollview.h" - -static const int ICON_WIDTH = 49; - -// Networking functions - -Networking::Networking(QWidget* parent, bool show_advanced) : QFrame(parent) { - main_layout = new QStackedLayout(this); - - wifi = new WifiManager(this); - connect(wifi, &WifiManager::refreshSignal, this, &Networking::refresh); - connect(wifi, &WifiManager::wrongPassword, this, &Networking::wrongPassword); - - wifiScreen = new QWidget(this); - QVBoxLayout* vlayout = new QVBoxLayout(wifiScreen); - vlayout->setContentsMargins(20, 20, 20, 20); - if (show_advanced) { - QPushButton* advancedSettings = new QPushButton(tr("Advanced")); - advancedSettings->setObjectName("advanced_btn"); - advancedSettings->setStyleSheet("margin-right: 30px;"); - advancedSettings->setFixedSize(400, 100); - connect(advancedSettings, &QPushButton::clicked, [=]() { main_layout->setCurrentWidget(an); }); - vlayout->addSpacing(10); - vlayout->addWidget(advancedSettings, 0, Qt::AlignRight); - vlayout->addSpacing(10); - } - - wifiWidget = new WifiUI(this, wifi); - wifiWidget->setObjectName("wifiWidget"); - connect(wifiWidget, &WifiUI::connectToNetwork, this, &Networking::connectToNetwork); - - ScrollView *wifiScroller = new ScrollView(wifiWidget, this); - wifiScroller->setVerticalScrollBarPolicy(Qt::ScrollBarAsNeeded); - vlayout->addWidget(wifiScroller, 1); - main_layout->addWidget(wifiScreen); - - an = new AdvancedNetworking(this, wifi); - connect(an, &AdvancedNetworking::backPress, [=]() { main_layout->setCurrentWidget(wifiScreen); }); - connect(an, &AdvancedNetworking::requestWifiScreen, [=]() { main_layout->setCurrentWidget(wifiScreen); }); - main_layout->addWidget(an); - - QPalette pal = palette(); - pal.setColor(QPalette::Window, QColor(0x29, 0x29, 0x29)); - setAutoFillBackground(true); - setPalette(pal); - - setStyleSheet(R"( - #wifiWidget > QPushButton, #back_btn, #advanced_btn { - font-size: 50px; - margin: 0px; - padding: 15px; - border-width: 0; - border-radius: 30px; - color: #dddddd; - background-color: #393939; - } - #back_btn:pressed, #advanced_btn:pressed { - background-color: #4a4a4a; - } - )"); - main_layout->setCurrentWidget(wifiScreen); -} - -void Networking::refresh() { - wifiWidget->refresh(); - an->refresh(); -} - -void Networking::connectToNetwork(const Network n) { - if (wifi->isKnownConnection(n.ssid)) { - wifi->activateWifiConnection(n.ssid); - } else if (n.security_type == SecurityType::OPEN) { - wifi->connect(n); - } else if (n.security_type == SecurityType::WPA) { - QString pass = InputDialog::getText(tr("Enter password"), this, tr("for \"%1\"").arg(QString::fromUtf8(n.ssid)), true, 8); - if (!pass.isEmpty()) { - wifi->connect(n, pass); - } - } -} - -void Networking::wrongPassword(const QString &ssid) { - if (wifi->seenNetworks.contains(ssid)) { - const Network &n = wifi->seenNetworks.value(ssid); - QString pass = InputDialog::getText(tr("Wrong password"), this, tr("for \"%1\"").arg(QString::fromUtf8(n.ssid)), true, 8); - if (!pass.isEmpty()) { - wifi->connect(n, pass); - } - } -} - -void Networking::showEvent(QShowEvent *event) { - wifi->start(); -} - -void Networking::hideEvent(QHideEvent *event) { - main_layout->setCurrentWidget(wifiScreen); - wifi->stop(); -} - -// AdvancedNetworking functions - -AdvancedNetworking::AdvancedNetworking(QWidget* parent, WifiManager* wifi): QWidget(parent), wifi(wifi) { - - QVBoxLayout* main_layout = new QVBoxLayout(this); - main_layout->setMargin(40); - main_layout->setSpacing(20); - - // Back button - QPushButton* back = new QPushButton(tr("Back")); - back->setObjectName("back_btn"); - back->setFixedSize(400, 100); - connect(back, &QPushButton::clicked, [=]() { emit backPress(); }); - main_layout->addWidget(back, 0, Qt::AlignLeft); - - ListWidget *list = new ListWidget(this); - // Enable tethering layout - tetheringToggle = new ToggleControl(tr("Enable Tethering"), "", "", wifi->isTetheringEnabled()); - list->addItem(tetheringToggle); - QObject::connect(tetheringToggle, &ToggleControl::toggleFlipped, this, &AdvancedNetworking::toggleTethering); - if (params.getBool("TetheringEnabled")) { - tetheringToggle->refresh(); - uiState()->scene.tethering_enabled = true; - } - - // Change tethering password - ButtonControl *editPasswordButton = new ButtonControl(tr("Tethering Password"), tr("EDIT")); - connect(editPasswordButton, &ButtonControl::clicked, [=]() { - QString pass = InputDialog::getText(tr("Enter new tethering password"), this, "", true, 8, wifi->getTetheringPassword()); - if (!pass.isEmpty()) { - wifi->changeTetheringPassword(pass); - } - }); - list->addItem(editPasswordButton); - - // IP address - ipLabel = new LabelControl(tr("IP Address"), wifi->ipv4_address); - list->addItem(ipLabel); - - // SSH keys - list->addItem(new SshToggle()); - list->addItem(new SshControl()); - - // Roaming toggle - const bool roamingEnabled = params.getBool("GsmRoaming"); - roamingToggle = new ToggleControl(tr("Enable Roaming"), "", "", roamingEnabled); - QObject::connect(roamingToggle, &ToggleControl::toggleFlipped, [=](bool state) { - params.putBool("GsmRoaming", state); - wifi->updateGsmSettings(state, QString::fromStdString(params.get("GsmApn")), params.getBool("GsmMetered")); - }); - list->addItem(roamingToggle); - - // APN settings - editApnButton = new ButtonControl(tr("APN Setting"), tr("EDIT")); - connect(editApnButton, &ButtonControl::clicked, [=]() { - const QString cur_apn = QString::fromStdString(params.get("GsmApn")); - QString apn = InputDialog::getText(tr("Enter APN"), this, tr("leave blank for automatic configuration"), false, -1, cur_apn).trimmed(); - - if (apn.isEmpty()) { - params.remove("GsmApn"); - } else { - params.put("GsmApn", apn.toStdString()); - } - wifi->updateGsmSettings(params.getBool("GsmRoaming"), apn, params.getBool("GsmMetered")); - }); - list->addItem(editApnButton); - - // Metered toggle - const bool metered = params.getBool("GsmMetered"); - meteredToggle = new ToggleControl(tr("Cellular Metered"), tr("Prevent large data uploads when on a metered connection"), "", metered); - QObject::connect(meteredToggle, &SshToggle::toggleFlipped, [=](bool state) { - params.putBool("GsmMetered", state); - wifi->updateGsmSettings(params.getBool("GsmRoaming"), QString::fromStdString(params.get("GsmApn")), state); - }); - list->addItem(meteredToggle); - - // Hidden Network - hiddenNetworkButton = new ButtonControl(tr("Hidden Network"), tr("CONNECT")); - connect(hiddenNetworkButton, &ButtonControl::clicked, [=]() { - QString ssid = InputDialog::getText(tr("Enter SSID"), this, "", false, 1); - if (!ssid.isEmpty()) { - QString pass = InputDialog::getText(tr("Enter password"), this, tr("for \"%1\"").arg(ssid), true, -1); - Network hidden_network; - hidden_network.ssid = ssid.toUtf8(); - if (!pass.isEmpty()) { - hidden_network.security_type = SecurityType::WPA; - wifi->connect(hidden_network, pass); - } else { - wifi->connect(hidden_network); - } - emit requestWifiScreen(); - } - }); - list->addItem(hiddenNetworkButton); - - // Set initial config - wifi->updateGsmSettings(roamingEnabled, QString::fromStdString(params.get("GsmApn")), metered); - - connect(uiState(), &UIState::primeTypeChanged, this, [=](PrimeType prime_type) { - bool gsmVisible = prime_type == PrimeType::NONE || prime_type == PrimeType::LITE; - roamingToggle->setVisible(gsmVisible); - editApnButton->setVisible(gsmVisible); - meteredToggle->setVisible(gsmVisible); - }); - - main_layout->addWidget(new ScrollView(list, this)); - main_layout->addStretch(1); -} - -void AdvancedNetworking::refresh() { - ipLabel->setText(wifi->ipv4_address); - tetheringToggle->setEnabled(true); - update(); -} - -void AdvancedNetworking::toggleTethering(bool enabled) { - wifi->setTetheringEnabled(enabled); - tetheringToggle->setEnabled(false); - params.putBool("TetheringEnabled", enabled); - uiState()->scene.tethering_enabled = enabled; -} - -// WifiUI functions - -WifiUI::WifiUI(QWidget *parent, WifiManager* wifi) : QWidget(parent), wifi(wifi) { - QVBoxLayout *main_layout = new QVBoxLayout(this); - main_layout->setContentsMargins(0, 0, 0, 0); - main_layout->setSpacing(0); - - // load imgs - for (const auto &s : {"low", "medium", "high", "full"}) { - QPixmap pix(ASSET_PATH + "/offroad/icon_wifi_strength_" + s + ".svg"); - strengths.push_back(pix.scaledToHeight(68, Qt::SmoothTransformation)); - } - lock = QPixmap(ASSET_PATH + "offroad/icon_lock_closed.svg").scaledToWidth(ICON_WIDTH, Qt::SmoothTransformation); - checkmark = QPixmap(ASSET_PATH + "offroad/icon_checkmark.svg").scaledToWidth(ICON_WIDTH, Qt::SmoothTransformation); - circled_slash = QPixmap(ASSET_PATH + "img_circled_slash.svg").scaledToWidth(ICON_WIDTH, Qt::SmoothTransformation); - - scanningLabel = new QLabel(tr("Scanning for networks...")); - scanningLabel->setStyleSheet("font-size: 65px;"); - main_layout->addWidget(scanningLabel, 0, Qt::AlignCenter); - - wifi_list_widget = new ListWidget(this); - wifi_list_widget->setVisible(false); - main_layout->addWidget(wifi_list_widget); - - setStyleSheet(R"( - QScrollBar::handle:vertical { - min-height: 0px; - border-radius: 4px; - background-color: #8A8A8A; - } - #forgetBtn { - font-size: 32px; - font-weight: 600; - color: #292929; - background-color: #BDBDBD; - border-width: 1px solid #828282; - border-radius: 5px; - padding: 40px; - padding-bottom: 16px; - padding-top: 16px; - } - #forgetBtn:pressed { - background-color: #828282; - } - #connecting { - font-size: 32px; - font-weight: 600; - color: white; - border-radius: 0; - padding: 27px; - padding-left: 43px; - padding-right: 43px; - background-color: black; - } - #ssidLabel { - text-align: left; - border: none; - padding-top: 50px; - padding-bottom: 50px; - } - #ssidLabel:disabled { - color: #696969; - } - )"); -} - -void WifiUI::refresh() { - bool is_empty = wifi->seenNetworks.isEmpty(); - scanningLabel->setVisible(is_empty); - wifi_list_widget->setVisible(!is_empty); - if (is_empty) return; - - setUpdatesEnabled(false); - - const bool is_tethering_enabled = wifi->isTetheringEnabled(); - QList sortedNetworks = wifi->seenNetworks.values(); - std::sort(sortedNetworks.begin(), sortedNetworks.end(), compare_by_strength); - - int n = 0; - for (Network &network : sortedNetworks) { - QPixmap status_icon; - if (network.connected == ConnectedType::CONNECTED) { - status_icon = checkmark; - } else if (network.security_type == SecurityType::UNSUPPORTED) { - status_icon = circled_slash; - } else if (network.security_type == SecurityType::WPA) { - status_icon = lock; - } - bool show_forget_btn = wifi->isKnownConnection(network.ssid) && !is_tethering_enabled; - QPixmap strength = strengths[strengthLevel(network.strength)]; - - auto item = getItem(n++); - item->setItem(network, status_icon, show_forget_btn, strength); - item->setVisible(true); - } - for (; n < wifi_items.size(); ++n) wifi_items[n]->setVisible(false); - - setUpdatesEnabled(true); -} - -WifiItem *WifiUI::getItem(int n) { - auto item = n < wifi_items.size() ? wifi_items[n] : wifi_items.emplace_back(new WifiItem(tr("CONNECTING..."), tr("FORGET"))); - if (!item->parentWidget()) { - QObject::connect(item, &WifiItem::connectToNetwork, this, &WifiUI::connectToNetwork); - QObject::connect(item, &WifiItem::forgotNetwork, [this](const Network n) { - if (ConfirmationDialog::confirm(tr("Forget Wi-Fi Network \"%1\"?").arg(QString::fromUtf8(n.ssid)), tr("Forget"), this)) - wifi->forgetConnection(n.ssid); - }); - wifi_list_widget->addItem(item); - } - return item; -} - -// WifiItem - -WifiItem::WifiItem(const QString &connecting_text, const QString &forget_text, QWidget *parent) : QWidget(parent) { - QHBoxLayout *hlayout = new QHBoxLayout(this); - hlayout->setContentsMargins(44, 0, 73, 0); - hlayout->setSpacing(50); - - hlayout->addWidget(ssidLabel = new ElidedLabel()); - ssidLabel->setObjectName("ssidLabel"); - ssidLabel->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Preferred); - hlayout->addWidget(connecting = new QPushButton(connecting_text), 0, Qt::AlignRight); - connecting->setObjectName("connecting"); - hlayout->addWidget(forgetBtn = new QPushButton(forget_text), 0, Qt::AlignRight); - forgetBtn->setObjectName("forgetBtn"); - hlayout->addWidget(iconLabel = new QLabel(), 0, Qt::AlignRight); - hlayout->addWidget(strengthLabel = new QLabel(), 0, Qt::AlignRight); - - iconLabel->setFixedWidth(ICON_WIDTH); - QObject::connect(forgetBtn, &QPushButton::clicked, [this]() { emit forgotNetwork(network); }); - QObject::connect(ssidLabel, &ElidedLabel::clicked, [this]() { - if (network.connected == ConnectedType::DISCONNECTED) emit connectToNetwork(network); - }); -} - -void WifiItem::setItem(const Network &n, const QPixmap &status_icon, bool show_forget_btn, const QPixmap &strength_icon) { - network = n; - - ssidLabel->setText(n.ssid); - ssidLabel->setEnabled(n.security_type != SecurityType::UNSUPPORTED); - ssidLabel->setFont(InterFont(55, network.connected == ConnectedType::DISCONNECTED ? QFont::Normal : QFont::Bold)); - - connecting->setVisible(n.connected == ConnectedType::CONNECTING); - forgetBtn->setVisible(show_forget_btn); - - iconLabel->setPixmap(status_icon); - strengthLabel->setPixmap(strength_icon); -} diff --git a/selfdrive/ui/qt/network/networking.h b/selfdrive/ui/qt/network/networking.h deleted file mode 100644 index 9b6af00..0000000 --- a/selfdrive/ui/qt/network/networking.h +++ /dev/null @@ -1,101 +0,0 @@ -#pragma once - -#include - -#include "selfdrive/ui/qt/network/wifi_manager.h" -#include "selfdrive/ui/qt/widgets/input.h" -#include "selfdrive/ui/qt/widgets/ssh_keys.h" -#include "selfdrive/ui/qt/widgets/toggle.h" - -class WifiItem : public QWidget { - Q_OBJECT -public: - explicit WifiItem(const QString &connecting_text, const QString &forget_text, QWidget* parent = nullptr); - void setItem(const Network& n, const QPixmap &icon, bool show_forget_btn, const QPixmap &strength); - -signals: - // Cannot pass Network by reference. it may change after the signal is sent. - void connectToNetwork(const Network n); - void forgotNetwork(const Network n); - -protected: - ElidedLabel* ssidLabel; - QPushButton* connecting; - QPushButton* forgetBtn; - QLabel* iconLabel; - QLabel* strengthLabel; - Network network; -}; - -class WifiUI : public QWidget { - Q_OBJECT - -public: - explicit WifiUI(QWidget *parent = 0, WifiManager* wifi = 0); - -private: - WifiItem *getItem(int n); - - WifiManager *wifi = nullptr; - QLabel *scanningLabel = nullptr; - QPixmap lock; - QPixmap checkmark; - QPixmap circled_slash; - QVector strengths; - ListWidget *wifi_list_widget = nullptr; - std::vector wifi_items; - -signals: - void connectToNetwork(const Network n); - -public slots: - void refresh(); -}; - -class AdvancedNetworking : public QWidget { - Q_OBJECT -public: - explicit AdvancedNetworking(QWidget* parent = 0, WifiManager* wifi = 0); - -private: - LabelControl* ipLabel; - ToggleControl* tetheringToggle; - ToggleControl* roamingToggle; - ButtonControl* editApnButton; - ButtonControl* hiddenNetworkButton; - ToggleControl* meteredToggle; - WifiManager* wifi = nullptr; - Params params; - -signals: - void backPress(); - void requestWifiScreen(); - -public slots: - void toggleTethering(bool enabled); - void refresh(); -}; - -class Networking : public QFrame { - Q_OBJECT - -public: - explicit Networking(QWidget* parent = 0, bool show_advanced = true); - WifiManager* wifi = nullptr; - -private: - QStackedLayout* main_layout = nullptr; - QWidget* wifiScreen = nullptr; - AdvancedNetworking* an = nullptr; - WifiUI* wifiWidget; - - void showEvent(QShowEvent* event) override; - void hideEvent(QHideEvent* event) override; - -public slots: - void refresh(); - -private slots: - void connectToNetwork(const Network n); - void wrongPassword(const QString &ssid); -}; diff --git a/selfdrive/ui/qt/network/networkmanager.h b/selfdrive/ui/qt/network/networkmanager.h deleted file mode 100644 index 2896b0f..0000000 --- a/selfdrive/ui/qt/network/networkmanager.h +++ /dev/null @@ -1,47 +0,0 @@ -#pragma once - -/** - * We are using a NetworkManager DBUS API : https://developer.gnome.org/NetworkManager/1.26/spec.html - * */ - -// https://developer.gnome.org/NetworkManager/1.26/nm-dbus-types.html#NM80211ApFlags -const int NM_802_11_AP_FLAGS_NONE = 0x00000000; -const int NM_802_11_AP_FLAGS_PRIVACY = 0x00000001; -const int NM_802_11_AP_FLAGS_WPS = 0x00000002; - -// https://developer.gnome.org/NetworkManager/1.26/nm-dbus-types.html#NM80211ApSecurityFlags -const int NM_802_11_AP_SEC_PAIR_WEP40 = 0x00000001; -const int NM_802_11_AP_SEC_PAIR_WEP104 = 0x00000002; -const int NM_802_11_AP_SEC_GROUP_WEP40 = 0x00000010; -const int NM_802_11_AP_SEC_GROUP_WEP104 = 0x00000020; -const int NM_802_11_AP_SEC_KEY_MGMT_PSK = 0x00000100; -const int NM_802_11_AP_SEC_KEY_MGMT_802_1X = 0x00000200; - -const QString NM_DBUS_PATH = "/org/freedesktop/NetworkManager"; -const QString NM_DBUS_PATH_SETTINGS = "/org/freedesktop/NetworkManager/Settings"; - -const QString NM_DBUS_INTERFACE = "org.freedesktop.NetworkManager"; -const QString NM_DBUS_INTERFACE_PROPERTIES = "org.freedesktop.DBus.Properties"; -const QString NM_DBUS_INTERFACE_SETTINGS = "org.freedesktop.NetworkManager.Settings"; -const QString NM_DBUS_INTERFACE_SETTINGS_CONNECTION = "org.freedesktop.NetworkManager.Settings.Connection"; -const QString NM_DBUS_INTERFACE_DEVICE = "org.freedesktop.NetworkManager.Device"; -const QString NM_DBUS_INTERFACE_DEVICE_WIRELESS = "org.freedesktop.NetworkManager.Device.Wireless"; -const QString NM_DBUS_INTERFACE_ACCESS_POINT = "org.freedesktop.NetworkManager.AccessPoint"; -const QString NM_DBUS_INTERFACE_ACTIVE_CONNECTION = "org.freedesktop.NetworkManager.Connection.Active"; -const QString NM_DBUS_INTERFACE_IP4_CONFIG = "org.freedesktop.NetworkManager.IP4Config"; - -const QString NM_DBUS_SERVICE = "org.freedesktop.NetworkManager"; - -const int NM_DEVICE_STATE_ACTIVATED = 100; -const int NM_DEVICE_STATE_NEED_AUTH = 60; -const int NM_DEVICE_TYPE_WIFI = 2; -const int NM_DEVICE_TYPE_MODEM = 8; -const int NM_DEVICE_STATE_REASON_SUPPLICANT_DISCONNECT = 8; -const int DBUS_TIMEOUT = 100; - -// https://developer-old.gnome.org/NetworkManager/1.26/nm-dbus-types.html#NMMetered -const int NM_METERED_UNKNOWN = 0; -const int NM_METERED_YES = 1; -const int NM_METERED_NO = 2; -const int NM_METERED_GUESS_YES = 3; -const int NM_METERED_GUESS_NO = 4; diff --git a/selfdrive/ui/qt/network/wifi_manager.cc b/selfdrive/ui/qt/network/wifi_manager.cc deleted file mode 100644 index ebb5cb8..0000000 --- a/selfdrive/ui/qt/network/wifi_manager.cc +++ /dev/null @@ -1,493 +0,0 @@ -#include "selfdrive/ui/qt/network/wifi_manager.h" - -#include "selfdrive/ui/ui.h" -#include "selfdrive/ui/qt/widgets/prime.h" - -#include "common/params.h" -#include "common/swaglog.h" -#include "selfdrive/ui/qt/util.h" - -bool compare_by_strength(const Network &a, const Network &b) { - return std::tuple(a.connected, strengthLevel(a.strength), b.ssid) > - std::tuple(b.connected, strengthLevel(b.strength), a.ssid); -} - -template -T call(const QString &path, const QString &interface, const QString &method, Args &&...args) { - QDBusInterface nm = QDBusInterface(NM_DBUS_SERVICE, path, interface, QDBusConnection::systemBus()); - nm.setTimeout(DBUS_TIMEOUT); - QDBusMessage response = nm.call(method, args...); - if constexpr (std::is_same_v) { - return response; - } else if (response.arguments().count() >= 1) { - QVariant vFirst = response.arguments().at(0).value().variant(); - if (vFirst.canConvert()) { - return vFirst.value(); - } - QDebug critical = qCritical(); - critical << "Variant unpacking failure :" << method << ','; - (critical << ... << args); - } - return T(); -} - -template -QDBusPendingCall asyncCall(const QString &path, const QString &interface, const QString &method, Args &&...args) { - QDBusInterface nm = QDBusInterface(NM_DBUS_SERVICE, path, interface, QDBusConnection::systemBus()); - return nm.asyncCall(method, args...); -} - -bool emptyPath(const QString &path) { - return path == "" || path == "/"; -} - -WifiManager::WifiManager(QObject *parent) : QObject(parent) { - qDBusRegisterMetaType(); - qDBusRegisterMetaType(); - - // Set tethering ssid as "weedle" + first 4 characters of a dongle id - tethering_ssid = "weedle"; - if (auto dongle_id = getDongleId()) { - tethering_ssid += "-" + dongle_id->left(4); - } - - adapter = getAdapter(); - if (!adapter.isEmpty()) { - setup(); - } else { - QDBusConnection::systemBus().connect(NM_DBUS_SERVICE, NM_DBUS_PATH, NM_DBUS_INTERFACE, "DeviceAdded", this, SLOT(deviceAdded(QDBusObjectPath))); - } - - timer.callOnTimeout(this, &WifiManager::requestScan); - - initConnections(); -} - -void WifiManager::setup() { - auto bus = QDBusConnection::systemBus(); - bus.connect(NM_DBUS_SERVICE, adapter, NM_DBUS_INTERFACE_DEVICE, "StateChanged", this, SLOT(stateChange(unsigned int, unsigned int, unsigned int))); - bus.connect(NM_DBUS_SERVICE, adapter, NM_DBUS_INTERFACE_PROPERTIES, "PropertiesChanged", this, SLOT(propertyChange(QString, QVariantMap, QStringList))); - - bus.connect(NM_DBUS_SERVICE, NM_DBUS_PATH_SETTINGS, NM_DBUS_INTERFACE_SETTINGS, "ConnectionRemoved", this, SLOT(connectionRemoved(QDBusObjectPath))); - bus.connect(NM_DBUS_SERVICE, NM_DBUS_PATH_SETTINGS, NM_DBUS_INTERFACE_SETTINGS, "NewConnection", this, SLOT(newConnection(QDBusObjectPath))); - - raw_adapter_state = call(adapter, NM_DBUS_INTERFACE_PROPERTIES, "Get", NM_DBUS_INTERFACE_DEVICE, "State"); - activeAp = call(adapter, NM_DBUS_INTERFACE_PROPERTIES, "Get", NM_DBUS_INTERFACE_DEVICE_WIRELESS, "ActiveAccessPoint").path(); - - requestScan(); -} - -void WifiManager::start() { - timer.start(5000); - refreshNetworks(); -} - -void WifiManager::stop() { - timer.stop(); -} - -void WifiManager::refreshNetworks() { - if (adapter.isEmpty() || !timer.isActive()) return; - - QDBusPendingCall pending_call = asyncCall(adapter, NM_DBUS_INTERFACE_DEVICE_WIRELESS, "GetAllAccessPoints"); - QDBusPendingCallWatcher *watcher = new QDBusPendingCallWatcher(pending_call); - QObject::connect(watcher, &QDBusPendingCallWatcher::finished, this, &WifiManager::refreshFinished); -} - -void WifiManager::refreshFinished(QDBusPendingCallWatcher *watcher) { - ipv4_address = getIp4Address(); - seenNetworks.clear(); - - const QDBusReply> wather_reply = *watcher; - for (const QDBusObjectPath &path : wather_reply.value()) { - QDBusReply replay = call(path.path(), NM_DBUS_INTERFACE_PROPERTIES, "GetAll", NM_DBUS_INTERFACE_ACCESS_POINT); - auto properties = replay.value(); - - const QByteArray ssid = properties["Ssid"].toByteArray(); - if (ssid.isEmpty()) continue; - - // May be multiple access points for each SSID. - // Use first for ssid and security type, then update connected status and strength using all - if (!seenNetworks.contains(ssid)) { - seenNetworks[ssid] = {ssid, 0U, ConnectedType::DISCONNECTED, getSecurityType(properties)}; - } - - if (path.path() == activeAp) { - seenNetworks[ssid].connected = (ssid == connecting_to_network) ? ConnectedType::CONNECTING : ConnectedType::CONNECTED; - } - - uint32_t strength = properties["Strength"].toUInt(); - if (seenNetworks[ssid].strength < strength) { - seenNetworks[ssid].strength = strength; - } - } - - emit refreshSignal(); - watcher->deleteLater(); -} - -QString WifiManager::getIp4Address() { - if (raw_adapter_state != NM_DEVICE_STATE_ACTIVATED) return ""; - - for (const auto &p : getActiveConnections()) { - QString type = call(p.path(), NM_DBUS_INTERFACE_PROPERTIES, "Get", NM_DBUS_INTERFACE_ACTIVE_CONNECTION, "Type"); - if (type == "802-11-wireless") { - auto ip4config = call(p.path(), NM_DBUS_INTERFACE_PROPERTIES, "Get", NM_DBUS_INTERFACE_ACTIVE_CONNECTION, "Ip4Config"); - const auto &arr = call(ip4config.path(), NM_DBUS_INTERFACE_PROPERTIES, "Get", NM_DBUS_INTERFACE_IP4_CONFIG, "AddressData"); - QVariantMap path; - arr.beginArray(); - while (!arr.atEnd()) { - arr >> path; - arr.endArray(); - return path.value("address").value(); - } - arr.endArray(); - } - } - return ""; -} - -SecurityType WifiManager::getSecurityType(const QVariantMap &properties) { - int sflag = properties["Flags"].toUInt(); - int wpaflag = properties["WpaFlags"].toUInt(); - int rsnflag = properties["RsnFlags"].toUInt(); - int wpa_props = wpaflag | rsnflag; - - // obtained by looking at flags of networks in the office as reported by an Android phone - const int supports_wpa = NM_802_11_AP_SEC_PAIR_WEP40 | NM_802_11_AP_SEC_PAIR_WEP104 | NM_802_11_AP_SEC_GROUP_WEP40 | NM_802_11_AP_SEC_GROUP_WEP104 | NM_802_11_AP_SEC_KEY_MGMT_PSK; - - if ((sflag == NM_802_11_AP_FLAGS_NONE) || ((sflag & NM_802_11_AP_FLAGS_WPS) && !(wpa_props & supports_wpa))) { - return SecurityType::OPEN; - } else if ((sflag & NM_802_11_AP_FLAGS_PRIVACY) && (wpa_props & supports_wpa) && !(wpa_props & NM_802_11_AP_SEC_KEY_MGMT_802_1X)) { - return SecurityType::WPA; - } else { - LOGW("Unsupported network! sflag: %d, wpaflag: %d, rsnflag: %d", sflag, wpaflag, rsnflag); - return SecurityType::UNSUPPORTED; - } -} - -void WifiManager::connect(const Network &n, const QString &password, const QString &username) { - setCurrentConnecting(n.ssid); - forgetConnection(n.ssid); // Clear all connections that may already exist to the network we are connecting - Connection connection; - connection["connection"]["type"] = "802-11-wireless"; - connection["connection"]["uuid"] = QUuid::createUuid().toString().remove('{').remove('}'); - connection["connection"]["id"] = "openpilot connection " + QString::fromStdString(n.ssid.toStdString()); - connection["connection"]["autoconnect-retries"] = 0; - - connection["802-11-wireless"]["ssid"] = n.ssid; - connection["802-11-wireless"]["mode"] = "infrastructure"; - - if (n.security_type == SecurityType::WPA) { - connection["802-11-wireless-security"]["key-mgmt"] = "wpa-psk"; - connection["802-11-wireless-security"]["auth-alg"] = "open"; - connection["802-11-wireless-security"]["psk"] = password; - } - - connection["ipv4"]["method"] = "auto"; - connection["ipv4"]["dns-priority"] = 600; - connection["ipv6"]["method"] = "ignore"; - - call(NM_DBUS_PATH_SETTINGS, NM_DBUS_INTERFACE_SETTINGS, "AddConnection", QVariant::fromValue(connection)); -} - -void WifiManager::deactivateConnectionBySsid(const QString &ssid) { - for (QDBusObjectPath active_connection : getActiveConnections()) { - auto pth = call(active_connection.path(), NM_DBUS_INTERFACE_PROPERTIES, "Get", NM_DBUS_INTERFACE_ACTIVE_CONNECTION, "SpecificObject"); - if (!emptyPath(pth.path())) { - QString Ssid = get_property(pth.path(), "Ssid"); - if (Ssid == ssid) { - deactivateConnection(active_connection); - return; - } - } - } -} - -void WifiManager::deactivateConnection(const QDBusObjectPath &path) { - asyncCall(NM_DBUS_PATH, NM_DBUS_INTERFACE, "DeactivateConnection", QVariant::fromValue(path)); -} - -QVector WifiManager::getActiveConnections() { - QVector conns; - QDBusObjectPath path; - const QDBusArgument &arr = call(NM_DBUS_PATH, NM_DBUS_INTERFACE_PROPERTIES, "Get", NM_DBUS_INTERFACE, "ActiveConnections"); - arr.beginArray(); - while (!arr.atEnd()) { - arr >> path; - conns.push_back(path); - } - arr.endArray(); - return conns; -} - -bool WifiManager::isKnownConnection(const QString &ssid) { - return !getConnectionPath(ssid).path().isEmpty(); -} - -void WifiManager::forgetConnection(const QString &ssid) { - const QDBusObjectPath &path = getConnectionPath(ssid); - if (!path.path().isEmpty()) { - call(path.path(), NM_DBUS_INTERFACE_SETTINGS_CONNECTION, "Delete"); - } -} - -void WifiManager::setCurrentConnecting(const QString &ssid) { - connecting_to_network = ssid; - for (auto &network : seenNetworks) { - network.connected = (network.ssid == ssid) ? ConnectedType::CONNECTING : ConnectedType::DISCONNECTED; - } - emit refreshSignal(); -} - -uint WifiManager::getAdapterType(const QDBusObjectPath &path) { - return call(path.path(), NM_DBUS_INTERFACE_PROPERTIES, "Get", NM_DBUS_INTERFACE_DEVICE, "DeviceType"); -} - -void WifiManager::requestScan() { - if (!adapter.isEmpty()) { - asyncCall(adapter, NM_DBUS_INTERFACE_DEVICE_WIRELESS, "RequestScan", QVariantMap()); - } -} - -QByteArray WifiManager::get_property(const QString &network_path , const QString &property) { - return call(network_path, NM_DBUS_INTERFACE_PROPERTIES, "Get", NM_DBUS_INTERFACE_ACCESS_POINT, property); -} - -QString WifiManager::getAdapter(const uint adapter_type) { - QDBusReply> response = call(NM_DBUS_PATH, NM_DBUS_INTERFACE, "GetDevices"); - for (const QDBusObjectPath &path : response.value()) { - if (getAdapterType(path) == adapter_type) { - return path.path(); - } - } - return ""; -} - -void WifiManager::stateChange(unsigned int new_state, unsigned int previous_state, unsigned int change_reason) { - raw_adapter_state = new_state; - if (new_state == NM_DEVICE_STATE_NEED_AUTH && change_reason == NM_DEVICE_STATE_REASON_SUPPLICANT_DISCONNECT && !connecting_to_network.isEmpty()) { - forgetConnection(connecting_to_network); - emit wrongPassword(connecting_to_network); - } else if (new_state == NM_DEVICE_STATE_ACTIVATED) { - connecting_to_network = ""; - refreshNetworks(); - } -} - -// https://developer.gnome.org/NetworkManager/stable/gdbus-org.freedesktop.NetworkManager.Device.Wireless.html -void WifiManager::propertyChange(const QString &interface, const QVariantMap &props, const QStringList &invalidated_props) { - if (interface == NM_DBUS_INTERFACE_DEVICE_WIRELESS && props.contains("LastScan")) { - refreshNetworks(); - } else if (interface == NM_DBUS_INTERFACE_DEVICE_WIRELESS && props.contains("ActiveAccessPoint")) { - activeAp = props.value("ActiveAccessPoint").value().path(); - } -} - -void WifiManager::deviceAdded(const QDBusObjectPath &path) { - if (getAdapterType(path) == NM_DEVICE_TYPE_WIFI && emptyPath(adapter)) { - adapter = path.path(); - setup(); - } -} - -void WifiManager::connectionRemoved(const QDBusObjectPath &path) { - knownConnections.remove(path); -} - -void WifiManager::newConnection(const QDBusObjectPath &path) { - Connection settings = getConnectionSettings(path); - if (settings.value("connection").value("type") == "802-11-wireless") { - knownConnections[path] = settings.value("802-11-wireless").value("ssid").toString(); - if (knownConnections[path] != tethering_ssid) { - activateWifiConnection(knownConnections[path]); - } - } -} - -QDBusObjectPath WifiManager::getConnectionPath(const QString &ssid) { - return knownConnections.key(ssid); -} - -Connection WifiManager::getConnectionSettings(const QDBusObjectPath &path) { - return QDBusReply(call(path.path(), NM_DBUS_INTERFACE_SETTINGS_CONNECTION, "GetSettings")).value(); -} - -void WifiManager::initConnections() { - const QDBusReply> response = call(NM_DBUS_PATH_SETTINGS, NM_DBUS_INTERFACE_SETTINGS, "ListConnections"); - for (const QDBusObjectPath &path : response.value()) { - const Connection settings = getConnectionSettings(path); - if (settings.value("connection").value("type") == "802-11-wireless") { - knownConnections[path] = settings.value("802-11-wireless").value("ssid").toString(); - } else if (settings.value("connection").value("id") == "lte") { - lteConnectionPath = path; - } - } -} - -std::optional WifiManager::activateWifiConnection(const QString &ssid) { - const QDBusObjectPath &path = getConnectionPath(ssid); - if (!path.path().isEmpty()) { - setCurrentConnecting(ssid); - return asyncCall(NM_DBUS_PATH, NM_DBUS_INTERFACE, "ActivateConnection", QVariant::fromValue(path), QVariant::fromValue(QDBusObjectPath(adapter)), QVariant::fromValue(QDBusObjectPath("/"))); - } - return std::nullopt; -} - -void WifiManager::activateModemConnection(const QDBusObjectPath &path) { - QString modem = getAdapter(NM_DEVICE_TYPE_MODEM); - if (!path.path().isEmpty() && !modem.isEmpty()) { - asyncCall(NM_DBUS_PATH, NM_DBUS_INTERFACE, "ActivateConnection", QVariant::fromValue(path), QVariant::fromValue(QDBusObjectPath(modem)), QVariant::fromValue(QDBusObjectPath("/"))); - } -} - -// function matches tici/hardware.py -NetworkType WifiManager::currentNetworkType() { - auto primary_conn = call(NM_DBUS_PATH, NM_DBUS_INTERFACE_PROPERTIES, "Get", NM_DBUS_INTERFACE, "PrimaryConnection"); - auto primary_type = call(primary_conn.path(), NM_DBUS_INTERFACE_PROPERTIES, "Get", NM_DBUS_INTERFACE_ACTIVE_CONNECTION, "Type"); - - if (primary_type == "802-3-ethernet") { - return NetworkType::ETHERNET; - } else if (primary_type == "802-11-wireless" && !isTetheringEnabled()) { - return NetworkType::WIFI; - } else { - for (const QDBusObjectPath &conn : getActiveConnections()) { - auto type = call(conn.path(), NM_DBUS_INTERFACE_PROPERTIES, "Get", NM_DBUS_INTERFACE_ACTIVE_CONNECTION, "Type"); - if (type == "gsm") { - return NetworkType::CELL; - } - } - } - return NetworkType::NONE; -} - -void WifiManager::updateGsmSettings(bool roaming, QString apn, bool metered) { - if (!lteConnectionPath.path().isEmpty()) { - bool changes = false; - bool auto_config = apn.isEmpty(); - Connection settings = getConnectionSettings(lteConnectionPath); - if (settings.value("gsm").value("auto-config").toBool() != auto_config) { - qWarning() << "Changing gsm.auto-config to" << auto_config; - settings["gsm"]["auto-config"] = auto_config; - changes = true; - } - - if (settings.value("gsm").value("apn").toString() != apn) { - qWarning() << "Changing gsm.apn to" << apn; - settings["gsm"]["apn"] = apn; - changes = true; - } - - if (settings.value("gsm").value("home-only").toBool() == roaming) { - qWarning() << "Changing gsm.home-only to" << !roaming; - settings["gsm"]["home-only"] = !roaming; - changes = true; - } - - int meteredInt = metered ? NM_METERED_UNKNOWN : NM_METERED_NO; - if (settings.value("connection").value("metered").toInt() != meteredInt) { - qWarning() << "Changing connection.metered to" << meteredInt; - settings["connection"]["metered"] = meteredInt; - changes = true; - } - - if (changes) { - call(lteConnectionPath.path(), NM_DBUS_INTERFACE_SETTINGS_CONNECTION, "UpdateUnsaved", QVariant::fromValue(settings)); // update is temporary - deactivateConnection(lteConnectionPath); - activateModemConnection(lteConnectionPath); - } - } -} - -// Functions for tethering -void WifiManager::addTetheringConnection() { - Connection connection; - connection["connection"]["id"] = "Hotspot"; - connection["connection"]["uuid"] = QUuid::createUuid().toString().remove('{').remove('}'); - connection["connection"]["type"] = "802-11-wireless"; - connection["connection"]["interface-name"] = "wlan0"; - connection["connection"]["autoconnect"] = false; - - connection["802-11-wireless"]["band"] = "bg"; - connection["802-11-wireless"]["mode"] = "ap"; - connection["802-11-wireless"]["ssid"] = tethering_ssid.toUtf8(); - - connection["802-11-wireless-security"]["group"] = QStringList("ccmp"); - connection["802-11-wireless-security"]["key-mgmt"] = "wpa-psk"; - connection["802-11-wireless-security"]["pairwise"] = QStringList("ccmp"); - connection["802-11-wireless-security"]["proto"] = QStringList("rsn"); - connection["802-11-wireless-security"]["psk"] = defaultTetheringPassword; - - connection["ipv4"]["method"] = "shared"; - QVariantMap address; - address["address"] = "192.168.43.1"; - address["prefix"] = 24u; - connection["ipv4"]["address-data"] = QVariant::fromValue(IpConfig() << address); - connection["ipv4"]["gateway"] = "192.168.43.1"; - connection["ipv4"]["route-metric"] = 1100; - connection["ipv6"]["method"] = "ignore"; - - call(NM_DBUS_PATH_SETTINGS, NM_DBUS_INTERFACE_SETTINGS, "AddConnection", QVariant::fromValue(connection)); -} - -void WifiManager::tetheringActivated(QDBusPendingCallWatcher *call) { - int prime_type = uiState()->primeType(); - int ipv4_forward = (prime_type == PrimeType::NONE || prime_type == PrimeType::LITE); - - if (!ipv4_forward) { - QTimer::singleShot(5000, this, [=] { - qWarning() << "net.ipv4.ip_forward = 0"; - std::system("sudo sysctl net.ipv4.ip_forward=0"); - }); - } - call->deleteLater(); -} - -void WifiManager::setTetheringEnabled(bool enabled) { - if (enabled) { - if (!isKnownConnection(tethering_ssid)) { - addTetheringConnection(); - } - - auto pending_call = activateWifiConnection(tethering_ssid); - - if (pending_call) { - QDBusPendingCallWatcher *watcher = new QDBusPendingCallWatcher(*pending_call); - QObject::connect(watcher, &QDBusPendingCallWatcher::finished, this, &WifiManager::tetheringActivated); - } - - } else { - deactivateConnectionBySsid(tethering_ssid); - } -} - -bool WifiManager::isTetheringEnabled() { - if (!emptyPath(activeAp)) { - return get_property(activeAp, "Ssid") == tethering_ssid; - } - return false; -} - -QString WifiManager::getTetheringPassword() { - if (!isKnownConnection(tethering_ssid)) { - addTetheringConnection(); - } - const QDBusObjectPath &path = getConnectionPath(tethering_ssid); - if (!path.path().isEmpty()) { - QDBusReply> response = call(path.path(), NM_DBUS_INTERFACE_SETTINGS_CONNECTION, "GetSecrets", "802-11-wireless-security"); - return response.value().value("802-11-wireless-security").value("psk").toString(); - } - return ""; -} - -void WifiManager::changeTetheringPassword(const QString &newPassword) { - const QDBusObjectPath &path = getConnectionPath(tethering_ssid); - if (!path.path().isEmpty()) { - Connection settings = getConnectionSettings(path); - settings["802-11-wireless-security"]["psk"] = newPassword; - call(path.path(), NM_DBUS_INTERFACE_SETTINGS_CONNECTION, "Update", QVariant::fromValue(settings)); - if (isTetheringEnabled()) { - activateWifiConnection(tethering_ssid); - } - } -} diff --git a/selfdrive/ui/qt/network/wifi_manager.h b/selfdrive/ui/qt/network/wifi_manager.h deleted file mode 100644 index 51d1175..0000000 --- a/selfdrive/ui/qt/network/wifi_manager.h +++ /dev/null @@ -1,102 +0,0 @@ -#pragma once - -#include -#include -#include - -#include "selfdrive/ui/qt/network/networkmanager.h" - -enum class SecurityType { - OPEN, - WPA, - UNSUPPORTED -}; -enum class ConnectedType { - DISCONNECTED, - CONNECTING, - CONNECTED -}; -enum class NetworkType { - NONE, - WIFI, - CELL, - ETHERNET -}; - -typedef QMap Connection; -typedef QVector IpConfig; - -struct Network { - QByteArray ssid; - unsigned int strength; - ConnectedType connected; - SecurityType security_type; -}; -bool compare_by_strength(const Network &a, const Network &b); -inline int strengthLevel(unsigned int strength) { return std::clamp((int)round(strength / 33.), 0, 3); } - -class WifiManager : public QObject { - Q_OBJECT - -public: - QMap seenNetworks; - QMap knownConnections; - QString ipv4_address; - - explicit WifiManager(QObject* parent); - void start(); - void stop(); - void requestScan(); - void forgetConnection(const QString &ssid); - bool isKnownConnection(const QString &ssid); - std::optional activateWifiConnection(const QString &ssid); - NetworkType currentNetworkType(); - void updateGsmSettings(bool roaming, QString apn, bool metered); - void connect(const Network &ssid, const QString &password = {}, const QString &username = {}); - - // Tethering functions - void setTetheringEnabled(bool enabled); - bool isTetheringEnabled(); - void changeTetheringPassword(const QString &newPassword); - QString getIp4Address(); - QString getTetheringPassword(); - -private: - QString adapter; // Path to network manager wifi-device - QTimer timer; - unsigned int raw_adapter_state; // Connection status https://developer.gnome.org/NetworkManager/1.26/nm-dbus-types.html#NMDeviceState - QString connecting_to_network; - QString tethering_ssid; - const QString defaultTetheringPassword = "swagswagcomma"; - QString activeAp; - QDBusObjectPath lteConnectionPath; - - QString getAdapter(const uint = NM_DEVICE_TYPE_WIFI); - uint getAdapterType(const QDBusObjectPath &path); - void deactivateConnectionBySsid(const QString &ssid); - void deactivateConnection(const QDBusObjectPath &path); - QVector getActiveConnections(); - QByteArray get_property(const QString &network_path, const QString &property); - SecurityType getSecurityType(const QVariantMap &properties); - QDBusObjectPath getConnectionPath(const QString &ssid); - Connection getConnectionSettings(const QDBusObjectPath &path); - void initConnections(); - void setup(); - void refreshNetworks(); - void activateModemConnection(const QDBusObjectPath &path); - void addTetheringConnection(); - void setCurrentConnecting(const QString &ssid); - -signals: - void wrongPassword(const QString &ssid); - void refreshSignal(); - -private slots: - void stateChange(unsigned int new_state, unsigned int previous_state, unsigned int change_reason); - void propertyChange(const QString &interface, const QVariantMap &props, const QStringList &invalidated_props); - void deviceAdded(const QDBusObjectPath &path); - void connectionRemoved(const QDBusObjectPath &path); - void newConnection(const QDBusObjectPath &path); - void refreshFinished(QDBusPendingCallWatcher *call); - void tetheringActivated(QDBusPendingCallWatcher *call); -}; diff --git a/selfdrive/ui/qt/offroad/driverview.cc b/selfdrive/ui/qt/offroad/driverview.cc deleted file mode 100644 index df9bb24..0000000 --- a/selfdrive/ui/qt/offroad/driverview.cc +++ /dev/null @@ -1,77 +0,0 @@ -#include "selfdrive/ui/qt/offroad/driverview.h" - -#include -#include - -#include "selfdrive/ui/qt/util.h" - -const int FACE_IMG_SIZE = 130; - -DriverViewWindow::DriverViewWindow(QWidget* parent) : CameraWidget("camerad", VISION_STREAM_DRIVER, true, parent) { - face_img = loadPixmap("../assets/img_driver_face_static.png", {FACE_IMG_SIZE, FACE_IMG_SIZE}); - QObject::connect(this, &CameraWidget::clicked, this, &DriverViewWindow::done); - QObject::connect(device(), &Device::interactiveTimeout, this, [this]() { - if (isVisible()) { - emit done(); - } - }); -} - -void DriverViewWindow::showEvent(QShowEvent* event) { - params.putBool("IsDriverViewEnabled", true); - device()->resetInteractiveTimeout(60); - CameraWidget::showEvent(event); -} - -void DriverViewWindow::hideEvent(QHideEvent* event) { - params.putBool("IsDriverViewEnabled", false); - stopVipcThread(); - CameraWidget::hideEvent(event); -} - -void DriverViewWindow::paintGL() { - CameraWidget::paintGL(); - - std::lock_guard lk(frame_lock); - QPainter p(this); - // startup msg - if (frames.empty()) { - p.setPen(Qt::white); - p.setRenderHint(QPainter::TextAntialiasing); - p.setFont(InterFont(100, QFont::Bold)); - p.drawText(geometry(), Qt::AlignCenter, tr("camera starting")); - return; - } - - const auto &sm = *(uiState()->sm); - cereal::DriverStateV2::Reader driver_state = sm["driverStateV2"].getDriverStateV2(); - bool is_rhd = driver_state.getWheelOnRightProb() > 0.5; - auto driver_data = is_rhd ? driver_state.getRightDriverData() : driver_state.getLeftDriverData(); - - bool face_detected = driver_data.getFaceProb() > 0.7; - if (face_detected) { - auto fxy_list = driver_data.getFacePosition(); - auto std_list = driver_data.getFaceOrientationStd(); - float face_x = fxy_list[0]; - float face_y = fxy_list[1]; - float face_std = std::max(std_list[0], std_list[1]); - - float alpha = 0.7; - if (face_std > 0.15) { - alpha = std::max(0.7 - (face_std-0.15)*3.5, 0.0); - } - const int box_size = 220; - // use approx instead of distort_points - int fbox_x = 1080.0 - 1714.0 * face_x; - int fbox_y = -135.0 + (504.0 + std::abs(face_x)*112.0) + (1205.0 - std::abs(face_x)*724.0) * face_y; - p.setPen(QPen(QColor(255, 255, 255, alpha * 255), 10)); - p.drawRoundedRect(fbox_x - box_size / 2, fbox_y - box_size / 2, box_size, box_size, 35.0, 35.0); - } - - // icon - const int img_offset = 60; - const int img_x = is_rhd ? rect().right() - FACE_IMG_SIZE - img_offset : rect().left() + img_offset; - const int img_y = rect().bottom() - FACE_IMG_SIZE - img_offset; - p.setOpacity(face_detected ? 1.0 : 0.2); - p.drawPixmap(img_x, img_y, face_img); -} diff --git a/selfdrive/ui/qt/offroad/driverview.h b/selfdrive/ui/qt/offroad/driverview.h deleted file mode 100644 index 155e4ed..0000000 --- a/selfdrive/ui/qt/offroad/driverview.h +++ /dev/null @@ -1,21 +0,0 @@ -#pragma once - -#include "selfdrive/ui/qt/widgets/cameraview.h" - -class DriverViewWindow : public CameraWidget { - Q_OBJECT - -public: - explicit DriverViewWindow(QWidget *parent); - -signals: - void done(); - -protected: - void showEvent(QShowEvent *event) override; - void hideEvent(QHideEvent *event) override; - void paintGL() override; - - Params params; - QPixmap face_img; -}; diff --git a/selfdrive/ui/qt/offroad/experimental_mode.cc b/selfdrive/ui/qt/offroad/experimental_mode.cc deleted file mode 100644 index b99220c..0000000 --- a/selfdrive/ui/qt/offroad/experimental_mode.cc +++ /dev/null @@ -1,76 +0,0 @@ -#include "selfdrive/ui/qt/offroad/experimental_mode.h" - -#include -#include -#include -#include -#include - -#include "selfdrive/ui/ui.h" - -ExperimentalModeButton::ExperimentalModeButton(QWidget *parent) : QPushButton(parent) { - chill_pixmap = QPixmap("../assets/img_couch.svg").scaledToWidth(img_width, Qt::SmoothTransformation); - experimental_pixmap = QPixmap("../assets/img_experimental_grey.svg").scaledToWidth(img_width, Qt::SmoothTransformation); - - // go to toggles and expand experimental mode description - connect(this, &QPushButton::clicked, [=]() { emit openSettings(2, "ExperimentalMode"); }); - - setFixedHeight(125); - QHBoxLayout *main_layout = new QHBoxLayout; - main_layout->setContentsMargins(horizontal_padding, 0, horizontal_padding, 0); - - mode_label = new QLabel; - mode_icon = new QLabel; - mode_icon->setSizePolicy(QSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed)); - - main_layout->addWidget(mode_label, 1, Qt::AlignLeft); - main_layout->addWidget(mode_icon, 0, Qt::AlignRight); - - setLayout(main_layout); - - setStyleSheet(R"( - QPushButton { - border: none; - } - - QLabel { - font-size: 45px; - font-weight: 300; - text-align: left; - font-family: JetBrainsMono; - color: #000000; - } - )"); -} - -void ExperimentalModeButton::paintEvent(QPaintEvent *event) { - QPainter p(this); - p.setPen(Qt::NoPen); - p.setRenderHint(QPainter::Antialiasing); - - QPainterPath path; - path.addRoundedRect(rect(), 10, 10); - - // gradient - bool pressed = isDown(); - QLinearGradient gradient(rect().left(), 0, rect().right(), 0); - if (experimental_mode) { - gradient.setColorAt(0, QColor(255, 155, 63, pressed ? 0xcc : 0xff)); - gradient.setColorAt(1, QColor(219, 56, 34, pressed ? 0xcc : 0xff)); - } else { - gradient.setColorAt(0, QColor(20, 255, 171, pressed ? 0xcc : 0xff)); - gradient.setColorAt(1, QColor(35, 149, 255, pressed ? 0xcc : 0xff)); - } - p.fillPath(path, gradient); - - // vertical line - p.setPen(QPen(QColor(0, 0, 0, 0x4d), 3, Qt::SolidLine)); - int line_x = rect().right() - img_width - (2 * horizontal_padding); - p.drawLine(line_x, rect().bottom(), line_x, rect().top()); -} - -void ExperimentalModeButton::showEvent(QShowEvent *event) { - experimental_mode = params.getBool("ExperimentalMode"); - mode_icon->setPixmap(experimental_mode ? experimental_pixmap : chill_pixmap); - mode_label->setText(experimental_mode ? tr("EXPERIMENTAL MODE ON") : tr("CHILL MODE ON")); -} diff --git a/selfdrive/ui/qt/offroad/experimental_mode.h b/selfdrive/ui/qt/offroad/experimental_mode.h deleted file mode 100644 index bfb7638..0000000 --- a/selfdrive/ui/qt/offroad/experimental_mode.h +++ /dev/null @@ -1,31 +0,0 @@ -#pragma once - -#include -#include - -#include "common/params.h" - -class ExperimentalModeButton : public QPushButton { - Q_OBJECT - -public: - explicit ExperimentalModeButton(QWidget* parent = 0); - -signals: - void openSettings(int index = 0, const QString &toggle = ""); - -private: - void showEvent(QShowEvent *event) override; - - Params params; - bool experimental_mode; - int img_width = 100; - int horizontal_padding = 30; - QPixmap experimental_pixmap; - QPixmap chill_pixmap; - QLabel *mode_label; - QLabel *mode_icon; - -protected: - void paintEvent(QPaintEvent *event) override; -}; diff --git a/selfdrive/ui/qt/offroad/onboarding.cc b/selfdrive/ui/qt/offroad/onboarding.cc deleted file mode 100644 index b121905..0000000 --- a/selfdrive/ui/qt/offroad/onboarding.cc +++ /dev/null @@ -1,234 +0,0 @@ -#include "selfdrive/ui/qt/offroad/onboarding.h" - -#include - -#include -#include -#include -#include -#include -#include - -#include "common/util.h" -#include "common/params.h" -#include "selfdrive/ui/qt/util.h" -#include "selfdrive/ui/qt/widgets/input.h" - -TrainingGuide::TrainingGuide(QWidget *parent) : QFrame(parent) { - setAttribute(Qt::WA_OpaquePaintEvent); -} - -void TrainingGuide::mouseReleaseEvent(QMouseEvent *e) { - if (click_timer.elapsed() < 250) { - return; - } - click_timer.restart(); - - auto contains = [this](QRect r, const QPoint &pt) { - if (image.size() != image_raw_size) { - QTransform transform; - transform.translate((width()- image.width()) / 2.0, (height()- image.height()) / 2.0); - transform.scale(image.width() / (float)image_raw_size.width(), image.height() / (float)image_raw_size.height()); - r= transform.mapRect(r); - } - return r.contains(pt); - }; - - if (contains(boundingRect[currentIndex], e->pos())) { - if (currentIndex == 9) { - const QRect yes = QRect(707, 804, 531, 164); - Params().putBool("RecordFront", contains(yes, e->pos())); - } - currentIndex += 1; - } else if (currentIndex == (boundingRect.size() - 2) && contains(boundingRect.last(), e->pos())) { - currentIndex = 0; - } - - if (currentIndex >= (boundingRect.size() - 1)) { - emit completedTraining(); - } else { - update(); - } -} - -void TrainingGuide::showEvent(QShowEvent *event) { - currentIndex = 0; - click_timer.start(); -} - -QImage TrainingGuide::loadImage(int id) { - QImage img(img_path + QString("step%1.png").arg(id)); - image_raw_size = img.size(); - if (image_raw_size != rect().size()) { - img = img.scaled(width(), height(), Qt::KeepAspectRatio, Qt::SmoothTransformation); - } - return img; -} - -void TrainingGuide::paintEvent(QPaintEvent *event) { - QPainter painter(this); - - QRect bg(0, 0, painter.device()->width(), painter.device()->height()); - painter.fillRect(bg, QColor("#000000")); - - image = loadImage(currentIndex); - QRect rect(image.rect()); - rect.moveCenter(bg.center()); - painter.drawImage(rect.topLeft(), image); - - // progress bar - if (currentIndex > 0 && currentIndex < (boundingRect.size() - 2)) { - const int h = 20; - const int w = (currentIndex / (float)(boundingRect.size() - 2)) * width(); - painter.fillRect(QRect(0, height() - h, w, h), QColor("#465BEA")); - } -} - -void TermsPage::showEvent(QShowEvent *event) { - // late init, building QML widget takes 200ms - if (layout()) { - return; - } - - QVBoxLayout *main_layout = new QVBoxLayout(this); - main_layout->setContentsMargins(45, 35, 45, 45); - main_layout->setSpacing(0); - - QLabel *title = new QLabel(tr("Terms & Conditions")); - title->setStyleSheet("font-size: 90px; font-weight: 600;"); - main_layout->addWidget(title); - - main_layout->addSpacing(30); - - QQuickWidget *text = new QQuickWidget(this); - text->setResizeMode(QQuickWidget::SizeRootObjectToView); - text->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding); - text->setAttribute(Qt::WA_AlwaysStackOnTop); - text->setClearColor(QColor("#1B1B1B")); - - QString text_view = util::read_file("../assets/offroad/tc.html").c_str(); - text->rootContext()->setContextProperty("text_view", text_view); - - text->setSource(QUrl::fromLocalFile("qt/offroad/text_view.qml")); - - main_layout->addWidget(text, 1); - main_layout->addSpacing(50); - - QObject *obj = (QObject*)text->rootObject(); - QObject::connect(obj, SIGNAL(scroll()), SLOT(enableAccept())); - - QHBoxLayout* buttons = new QHBoxLayout; - buttons->setMargin(0); - buttons->setSpacing(45); - main_layout->addLayout(buttons); - - QPushButton *decline_btn = new QPushButton(tr("Decline")); - buttons->addWidget(decline_btn); - QObject::connect(decline_btn, &QPushButton::clicked, this, &TermsPage::declinedTerms); - - accept_btn = new QPushButton(tr("Scroll to accept")); - accept_btn->setEnabled(false); - accept_btn->setStyleSheet(R"( - QPushButton { - background-color: #465BEA; - } - QPushButton:pressed { - background-color: #3049F4; - } - QPushButton:disabled { - background-color: #4F4F4F; - } - )"); - buttons->addWidget(accept_btn); - QObject::connect(accept_btn, &QPushButton::clicked, this, &TermsPage::acceptedTerms); -} - -void TermsPage::enableAccept() { - accept_btn->setText(tr("Agree")); - accept_btn->setEnabled(true); -} - -void DeclinePage::showEvent(QShowEvent *event) { - if (layout()) { - return; - } - - QVBoxLayout *main_layout = new QVBoxLayout(this); - main_layout->setMargin(45); - main_layout->setSpacing(40); - - QLabel *text = new QLabel(this); - text->setText(tr("You must accept the Terms and Conditions in order to use openpilot.")); - text->setStyleSheet(R"(font-size: 80px; font-weight: 300; margin: 200px;)"); - text->setWordWrap(true); - main_layout->addWidget(text, 0, Qt::AlignCenter); - - QHBoxLayout* buttons = new QHBoxLayout; - buttons->setSpacing(45); - main_layout->addLayout(buttons); - - QPushButton *back_btn = new QPushButton(tr("Back")); - buttons->addWidget(back_btn); - - QObject::connect(back_btn, &QPushButton::clicked, this, &DeclinePage::getBack); - - QPushButton *uninstall_btn = new QPushButton(tr("Decline, uninstall %1").arg(getBrand())); - uninstall_btn->setStyleSheet("background-color: #B73D3D"); - buttons->addWidget(uninstall_btn); - QObject::connect(uninstall_btn, &QPushButton::clicked, [=]() { - Params().putBool("DoUninstall", true); - }); -} - -void OnboardingWindow::updateActiveScreen() { - if (!accepted_terms) { - setCurrentIndex(0); - } else if (!training_done) { - setCurrentIndex(1); - } else { - emit onboardingDone(); - } -} - -OnboardingWindow::OnboardingWindow(QWidget *parent) : QStackedWidget(parent) { - std::string current_terms_version = params.get("TermsVersion"); - std::string current_training_version = params.get("TrainingVersion"); - accepted_terms = params.get("HasAcceptedTerms") == current_terms_version; - training_done = params.get("CompletedTrainingVersion") == current_training_version; - - TermsPage* terms = new TermsPage(this); - addWidget(terms); - connect(terms, &TermsPage::acceptedTerms, [=]() { - params.put("HasAcceptedTerms", current_terms_version); - accepted_terms = true; - updateActiveScreen(); - }); - connect(terms, &TermsPage::declinedTerms, [=]() { setCurrentIndex(2); }); - - TrainingGuide* tr = new TrainingGuide(this); - addWidget(tr); - connect(tr, &TrainingGuide::completedTraining, [=]() { - training_done = true; - params.put("CompletedTrainingVersion", current_training_version); - updateActiveScreen(); - }); - - DeclinePage* declinePage = new DeclinePage(this); - addWidget(declinePage); - connect(declinePage, &DeclinePage::getBack, [=]() { updateActiveScreen(); }); - - setStyleSheet(R"( - * { - color: white; - background-color: black; - } - QPushButton { - height: 160px; - font-size: 55px; - font-weight: 400; - border-radius: 10px; - background-color: #4F4F4F; - } - )"); - updateActiveScreen(); -} diff --git a/selfdrive/ui/qt/offroad/onboarding.h b/selfdrive/ui/qt/offroad/onboarding.h deleted file mode 100644 index a1b6895..0000000 --- a/selfdrive/ui/qt/offroad/onboarding.h +++ /dev/null @@ -1,110 +0,0 @@ -#pragma once - -#include -#include -#include -#include -#include -#include - -#include "common/params.h" -#include "selfdrive/ui/qt/qt_window.h" - -class TrainingGuide : public QFrame { - Q_OBJECT - -public: - explicit TrainingGuide(QWidget *parent = 0); - -private: - void showEvent(QShowEvent *event) override; - void paintEvent(QPaintEvent *event) override; - void mouseReleaseEvent(QMouseEvent* e) override; - QImage loadImage(int id); - - QImage image; - QSize image_raw_size; - int currentIndex = 0; - - // Bounding boxes for each training guide step - const QRect continueBtn = {1840, 0, 320, 1080}; - QVector boundingRect { - QRect(112, 804, 618, 164), - continueBtn, - continueBtn, - QRect(1641, 558, 210, 313), - QRect(1662, 528, 184, 108), - continueBtn, - QRect(1814, 621, 211, 170), - QRect(1350, 0, 497, 755), - QRect(1540, 386, 468, 238), - QRect(112, 804, 1126, 164), - QRect(1598, 199, 316, 333), - continueBtn, - QRect(1364, 90, 796, 990), - continueBtn, - QRect(1593, 114, 318, 853), - QRect(1379, 511, 391, 243), - continueBtn, - continueBtn, - QRect(630, 804, 626, 164), - QRect(108, 804, 426, 164), - }; - - const QString img_path = "../assets/training/"; - QElapsedTimer click_timer; - -signals: - void completedTraining(); -}; - - -class TermsPage : public QFrame { - Q_OBJECT - -public: - explicit TermsPage(QWidget *parent = 0) : QFrame(parent) {} - -public slots: - void enableAccept(); - -private: - void showEvent(QShowEvent *event) override; - - QPushButton *accept_btn; - -signals: - void acceptedTerms(); - void declinedTerms(); -}; - -class DeclinePage : public QFrame { - Q_OBJECT - -public: - explicit DeclinePage(QWidget *parent = 0) : QFrame(parent) {} - -private: - void showEvent(QShowEvent *event) override; - -signals: - void getBack(); -}; - -class OnboardingWindow : public QStackedWidget { - Q_OBJECT - -public: - explicit OnboardingWindow(QWidget *parent = 0); - inline void showTrainingGuide() { setCurrentIndex(1); } - inline bool completed() const { return accepted_terms && training_done; } - -private: - void updateActiveScreen(); - - Params params; - bool accepted_terms = false, training_done = false; - -signals: - void onboardingDone(); -}; diff --git a/selfdrive/ui/qt/offroad/settings.cc b/selfdrive/ui/qt/offroad/settings.cc deleted file mode 100644 index 45ce7b8..0000000 --- a/selfdrive/ui/qt/offroad/settings.cc +++ /dev/null @@ -1,749 +0,0 @@ -#include "selfdrive/ui/qt/offroad/settings.h" - -#include -#include -#include -#include -#include -#include -#include - -#include -#include - -#include "selfdrive/ui/qt/network/networking.h" - -#include "common/params.h" -#include "common/watchdog.h" -#include "common/util.h" -#include "system/hardware/hw.h" -#include "selfdrive/ui/qt/widgets/controls.h" -#include "selfdrive/ui/qt/widgets/input.h" -#include "selfdrive/ui/qt/widgets/scrollview.h" -#include "selfdrive/ui/qt/widgets/ssh_keys.h" -#include "selfdrive/ui/qt/widgets/toggle.h" -#include "selfdrive/ui/qt/util.h" -#include "selfdrive/ui/qt/qt_window.h" - -#include "selfdrive/frogpilot/navigation/ui/navigation_settings.h" -#include "selfdrive/frogpilot/ui/control_settings.h" -#include "selfdrive/frogpilot/ui/vehicle_settings.h" -#include "selfdrive/frogpilot/ui/visual_settings.h" - -TogglesPanel::TogglesPanel(SettingsWindow *parent) : ListWidget(parent) { - // param, title, desc, icon - std::vector> toggle_defs{ - { - "OpenpilotEnabledToggle", - tr("Enable openpilot"), - tr("Use the openpilot system for adaptive cruise control and lane keep driver assistance. Your attention is required at all times to use this feature. Changing this setting takes effect when the car is powered off."), - "../assets/offroad/icon_openpilot.png", - }, - { - "ExperimentalLongitudinalEnabled", - tr("openpilot Longitudinal Control (Alpha)"), - QString("%1

%2") - .arg(tr("WARNING: openpilot longitudinal control is in alpha for this car and will disable Automatic Emergency Braking (AEB).")) - .arg(tr("On this car, openpilot defaults to the car's built-in ACC instead of openpilot's longitudinal control. " - "Enable this to switch to openpilot longitudinal control. Enabling Experimental mode is recommended when enabling openpilot longitudinal control alpha.")), - "../assets/offroad/icon_speed_limit.png", - }, - { - "ExperimentalMode", - tr("Experimental Mode"), - "", - "../assets/img_experimental_white.svg", - }, - { - "DisengageOnAccelerator", - tr("Disengage on Accelerator Pedal"), - tr("When enabled, pressing the accelerator pedal will disengage openpilot."), - "../assets/offroad/icon_disengage_on_accelerator.svg", - }, - { - "IsLdwEnabled", - tr("Enable Lane Departure Warnings"), - tr("Receive alerts to steer back into the lane when your vehicle drifts over a detected lane line without a turn signal activated while driving over 31 mph (50 km/h)."), - "../assets/offroad/icon_warning.png", - }, - { - "RecordFront", - tr("Record and Upload Driver Camera"), - tr("Upload data from the driver facing camera and help improve the driver monitoring algorithm."), - "../assets/offroad/icon_monitoring.png", - }, - { - "IsMetric", - tr("Use Metric System"), - tr("Display speed in km/h instead of mph."), - "../assets/offroad/icon_metric.png", - }, -#ifdef ENABLE_MAPS - { - "NavSettingTime24h", - tr("Show ETA in 24h Format"), - tr("Use 24h format instead of am/pm"), - "../assets/offroad/icon_metric.png", - }, - { - "NavSettingLeftSide", - tr("Show Map on Left Side of UI"), - tr("Show map on left side when in split screen view."), - "../assets/offroad/icon_road.png", - }, -#endif - }; - - - std::vector longi_button_texts{tr("Aggressive"), tr("Standard"), tr("Relaxed")}; - long_personality_setting = new ButtonParamControl("LongitudinalPersonality", tr("Driving Personality"), - tr("Standard is recommended. In aggressive mode, openpilot will follow lead cars closer and be more aggressive with the gas and brake. " - "In relaxed mode openpilot will stay further away from lead cars."), - "../assets/offroad/icon_speed_limit.png", - longi_button_texts); - for (auto &[param, title, desc, icon] : toggle_defs) { - auto toggle = new ParamControl(param, title, desc, icon, this); - - bool locked = params.getBool((param + "Lock").toStdString()); - toggle->setEnabled(!locked); - - addItem(toggle); - toggles[param.toStdString()] = toggle; - - // insert longitudinal personality after NDOG toggle - if (param == "DisengageOnAccelerator" && !params.getBool("AdjustablePersonalities")) { - addItem(long_personality_setting); - } - } - - // Toggles with confirmation dialogs - toggles["ExperimentalMode"]->setActiveIcon("../assets/img_experimental.svg"); - toggles["ExperimentalMode"]->setConfirmation(true, true); - toggles["ExperimentalLongitudinalEnabled"]->setConfirmation(true, false); - - connect(toggles["ExperimentalLongitudinalEnabled"], &ToggleControl::toggleFlipped, [=]() { - updateToggles(); - }); - - connect(toggles["IsMetric"], &ToggleControl::toggleFlipped, [=]() { - updateMetric(); - }); -} - -void TogglesPanel::expandToggleDescription(const QString ¶m) { - toggles[param.toStdString()]->showDescription(); -} - -void TogglesPanel::showEvent(QShowEvent *event) { - updateToggles(); -} - -void TogglesPanel::updateToggles() { - auto experimental_mode_toggle = toggles["ExperimentalMode"]; - auto op_long_toggle = toggles["ExperimentalLongitudinalEnabled"]; - const QString e2e_description = QString("%1
" - "

%2


" - "%3
" - "

%4


" - "%5
" - "

%6


" - "%7") - .arg(tr("openpilot defaults to driving in chill mode. Experimental mode enables alpha-level features that aren't ready for chill mode. Experimental features are listed below:")) - .arg(tr("End-to-End Longitudinal Control")) - .arg(tr("Let the driving model control the gas and brakes. openpilot will drive as it thinks a human would, including stopping for red lights and stop signs. " - "Since the driving model decides the speed to drive, the set speed will only act as an upper bound. This is an alpha quality feature; " - "mistakes should be expected.")) - .arg(tr("Navigate on openpilot")) - .arg(tr("When navigation has a destination, openpilot will input the map information into the model. This provides useful context for the model and allows openpilot to keep left or right " - "appropriately at forks/exits. Lane change behavior is unchanged and still activated by the driver. This is an alpha quality feature; mistakes should be expected, particularly around " - "exits and forks. These mistakes can include unintended laneline crossings, late exit taking, driving towards dividing barriers in the gore areas, etc.")) - .arg(tr("New Driving Visualization")) - .arg(tr("The driving visualization will transition to the road-facing wide-angle camera at low speeds to better show some turns. The Experimental mode logo will also be shown in the top right corner. " - "When a navigation destination is set and the driving model is using it as input, the driving path on the map will turn green.")); - - const bool is_release = params.getBool("IsReleaseBranch"); - auto cp_bytes = params.get("CarParamsPersistent"); - if (!cp_bytes.empty()) { - AlignedBuffer aligned_buf; - capnp::FlatArrayMessageReader cmsg(aligned_buf.align(cp_bytes.data(), cp_bytes.size())); - cereal::CarParams::Reader CP = cmsg.getRoot(); - - if (!CP.getExperimentalLongitudinalAvailable() || is_release) { - params.remove("ExperimentalLongitudinalEnabled"); - } - op_long_toggle->setVisible(CP.getExperimentalLongitudinalAvailable() && !is_release); - if (hasLongitudinalControl(CP)) { - // normal description and toggle - experimental_mode_toggle->setEnabled(!params.getBool("ConditionalExperimental")); - experimental_mode_toggle->setDescription(e2e_description); - long_personality_setting->setEnabled(true); - } else { - // no long for now - experimental_mode_toggle->setEnabled(false); - long_personality_setting->setEnabled(false); - params.remove("ExperimentalMode"); - - const QString unavailable = tr("Experimental mode is currently unavailable on this car since the car's stock ACC is used for longitudinal control."); - - QString long_desc = unavailable + " " + \ - tr("openpilot longitudinal control may come in a future update."); - if (CP.getExperimentalLongitudinalAvailable()) { - if (is_release) { - long_desc = unavailable + " " + tr("An alpha version of openpilot longitudinal control can be tested, along with Experimental mode, on non-release branches."); - } else { - long_desc = tr("Enable the openpilot longitudinal control (alpha) toggle to allow Experimental mode."); - } - } - experimental_mode_toggle->setDescription("" + long_desc + "

" + e2e_description); - } - - experimental_mode_toggle->refresh(); - } else { - experimental_mode_toggle->setDescription(e2e_description); - op_long_toggle->setVisible(false); - } -} - -DevicePanel::DevicePanel(SettingsWindow *parent) : ListWidget(parent) { - setSpacing(50); - addItem(new LabelControl(tr("Dongle ID"), getDongleId().value_or(tr("N/A")))); - addItem(new LabelControl(tr("Serial"), params.get("HardwareSerial").c_str())); - - // offroad-only buttons - - auto dcamBtn = new ButtonControl(tr("Driver Camera"), tr("PREVIEW"), - tr("Preview the driver facing camera to ensure that driver monitoring has good visibility. (vehicle must be off)")); - connect(dcamBtn, &ButtonControl::clicked, [=]() { emit showDriverView(); }); - addItem(dcamBtn); - - auto resetCalibBtn = new ButtonControl(tr("Reset Calibration"), tr("RESET"), ""); - connect(resetCalibBtn, &ButtonControl::showDescriptionEvent, this, &DevicePanel::updateCalibDescription); - connect(resetCalibBtn, &ButtonControl::clicked, [&]() { - if (ConfirmationDialog::confirm(tr("Are you sure you want to reset calibration?"), tr("Reset"), this)) { - params.remove("CalibrationParams"); - params.remove("LiveTorqueParameters"); - } - }); - addItem(resetCalibBtn); - - auto retrainingBtn = new ButtonControl(tr("Review Training Guide"), tr("REVIEW"), tr("Review the rules, features, and limitations of openpilot")); - connect(retrainingBtn, &ButtonControl::clicked, [=]() { - if (ConfirmationDialog::confirm(tr("Are you sure you want to review the training guide?"), tr("Review"), this)) { - emit reviewTrainingGuide(); - } - }); - addItem(retrainingBtn); - - if (Hardware::TICI()) { - auto regulatoryBtn = new ButtonControl(tr("Regulatory"), tr("VIEW"), ""); - connect(regulatoryBtn, &ButtonControl::clicked, [=]() { - const std::string txt = util::read_file("../assets/offroad/fcc.html"); - ConfirmationDialog::rich(QString::fromStdString(txt), this); - }); - addItem(regulatoryBtn); - } - - auto translateBtn = new ButtonControl(tr("Change Language"), tr("CHANGE"), ""); - connect(translateBtn, &ButtonControl::clicked, [=]() { - QMap langs = getSupportedLanguages(); - QString selection = MultiOptionDialog::getSelection(tr("Select a language"), langs.keys(), langs.key(uiState()->language), this); - if (!selection.isEmpty()) { - // put language setting, exit Qt UI, and trigger fast restart - params.put("LanguageSetting", langs[selection].toStdString()); - qApp->exit(18); - watchdog_kick(0); - } - }); - addItem(translateBtn); - - // Delete driving footage button - auto deleteFootageBtn = new ButtonControl(tr("Delete Driving Data"), tr("DELETE"), tr("This button provides a swift and secure way to permanently delete all " - "stored driving footage and data from your device. Ideal for maintaining privacy or freeing up space.") - ); - connect(deleteFootageBtn, &ButtonControl::clicked, [=]() { - if (!ConfirmationDialog::confirm(tr("Are you sure you want to permanently delete all of your driving footage and data?"), tr("Delete"), this)) return; - std::thread([&] { - deleteFootageBtn->setValue("Deleting footage..."); - std::system("rm -rf /data/media/0/realdata"); - deleteFootageBtn->setValue(""); - }).detach(); - }); - addItem(deleteFootageBtn); - - // Delete long term toggle storage button - auto deleteStorageParamsBtn = new ButtonControl(tr("Delete Toggle Storage Data"), tr("DELETE"), tr("This button provides a swift and secure way to permanently delete all " - "long term stored toggle settings. Ideal for maintaining privacy or freeing up space.") - ); - connect(deleteStorageParamsBtn, &ButtonControl::clicked, [=]() { - if (!ConfirmationDialog::confirm(tr("Are you sure you want to permanently delete all of your long term toggle settings storage?"), tr("Delete"), this)) return; - std::thread([&] { - deleteStorageParamsBtn->setValue("Deleting params..."); - std::system("rm -rf /persist/comma/params"); - deleteStorageParamsBtn->setValue(""); - }).detach(); - }); - addItem(deleteStorageParamsBtn); - - // Backup FrogPilot - std::vector frogpilotBackupOptions{tr("Backup"), tr("Delete"), tr("Restore")}; - FrogPilotButtonsControl *frogpilotBackup = new FrogPilotButtonsControl("FrogPilot Backups", "Backup, delete, or restore your FrogPilot backups.", "", frogpilotBackupOptions); - - connect(frogpilotBackup, &FrogPilotButtonsControl::buttonClicked, [=](int id) { - QDir backupDir("/data/backups"); - - if (id == 0) { - QString nameSelection = InputDialog::getText(tr("Name your backup"), this, "", false, 1); - if (!nameSelection.isEmpty()) { - std::thread([=]() { - frogpilotBackup->setValue("Backing up..."); - - std::string fullBackupPath = backupDir.absolutePath().toStdString() + "/" + nameSelection.toStdString(); - - std::ostringstream commandStream; - commandStream << "mkdir -p " << std::quoted(fullBackupPath) - << " && rsync -av /data/openpilot/ " << std::quoted(fullBackupPath + "/"); - std::string command = commandStream.str(); - - int result = std::system(command.c_str()); - if (result == 0) { - std::cout << "Backup successful to " << fullBackupPath << std::endl; - frogpilotBackup->setValue("Success!"); - std::this_thread::sleep_for(std::chrono::seconds(3)); - frogpilotBackup->setValue(""); - } else { - std::cerr << "Backup failed with error code: " << result << std::endl; - frogpilotBackup->setValue("Failed..."); - std::this_thread::sleep_for(std::chrono::seconds(3)); - frogpilotBackup->setValue(""); - } - }).detach(); - } - } else if (id == 1) { - QStringList backupNames = backupDir.entryList(QDir::Dirs | QDir::NoDotAndDotDot); - - QString selection = MultiOptionDialog::getSelection(tr("Select a backup to delete"), backupNames, "", this); - if (!selection.isEmpty()) { - if (!ConfirmationDialog::confirm(tr("Are you sure you want to delete this backup?"), tr("Delete"), this)) return; - std::thread([=]() { - frogpilotBackup->setValue("Deleting..."); - QDir dirToDelete(backupDir.absoluteFilePath(selection)); - if (dirToDelete.removeRecursively()) { - frogpilotBackup->setValue("Deleted!"); - } else { - frogpilotBackup->setValue("Failed..."); - } - std::this_thread::sleep_for(std::chrono::seconds(3)); - frogpilotBackup->setValue(""); - }).detach(); - } - } else { - QStringList backupNames = backupDir.entryList(QDir::Dirs | QDir::NoDotAndDotDot); - - QString selection = MultiOptionDialog::getSelection(tr("Select a restore point"), backupNames, "", this); - if (!selection.isEmpty()) { - if (!ConfirmationDialog::confirm(tr("Are you sure you want to restore this version of FrogPilot?"), tr("Restore"), this)) return; - std::thread([=]() { - frogpilotBackup->setValue("Restoring..."); - - std::string sourcePath = backupDir.absolutePath().toStdString() + "/" + selection.toStdString(); - std::string targetPath = "/data/safe_staging/finalized"; - std::string consistentFilePath = targetPath + "/.overlay_consistent"; - - std::ostringstream commandStream; - commandStream << "rsync -av --delete --exclude='.overlay_consistent' " << std::quoted(sourcePath + "/") << " " << std::quoted(targetPath + "/"); - std::string command = commandStream.str(); - int result = std::system(command.c_str()); - - if (result == 0) { - std::cout << "Restore successful from " << sourcePath << " to " << targetPath << std::endl; - std::ofstream consistentFile(consistentFilePath); - if (consistentFile) { - consistentFile.close(); - std::cout << ".overlay_consistent file created successfully." << std::endl; - } else { - std::cerr << "Failed to create .overlay_consistent file." << std::endl; - frogpilotBackup->setValue("Failed..."); - std::this_thread::sleep_for(std::chrono::seconds(3)); - frogpilotBackup->setValue(""); - } - Hardware::reboot(); - } else { - std::cerr << "Restore failed with error code: " << result << std::endl; - } - }).detach(); - } - } - }); - addItem(frogpilotBackup); - - // Backup toggles - std::vector toggleBackupOptions{tr("Backup"), tr("Delete"), tr("Restore")}; - FrogPilotButtonsControl *toggleBackup = new FrogPilotButtonsControl("Toggle Backups", "Backup, delete, or restore your toggle backups.", "", toggleBackupOptions); - - connect(toggleBackup, &FrogPilotButtonsControl::buttonClicked, [=](int id) { - QDir backupDir("/data/toggle_backups"); - - if (id == 0) { - QString nameSelection = InputDialog::getText(tr("Name your backup"), this, "", false, 1); - if (!nameSelection.isEmpty()) { - std::thread([=]() { - toggleBackup->setValue("Backing up..."); - - std::string fullBackupPath = backupDir.absolutePath().toStdString() + "/" + nameSelection.toStdString() + "/"; - - std::ostringstream commandStream; - commandStream << "mkdir -p " << std::quoted(fullBackupPath) - << " && rsync -av /data/params/d/ " << std::quoted(fullBackupPath); - std::string command = commandStream.str(); - - int result = std::system(command.c_str()); - if (result == 0) { - std::cout << "Backup successful to " << fullBackupPath << std::endl; - toggleBackup->setValue("Success!"); - std::this_thread::sleep_for(std::chrono::seconds(3)); - toggleBackup->setValue(""); - } else { - std::cerr << "Backup failed with error code: " << result << std::endl; - toggleBackup->setValue("Failed..."); - std::this_thread::sleep_for(std::chrono::seconds(3)); - toggleBackup->setValue(""); - } - }).detach(); - } - } else if (id == 1) { - QStringList backupNames = backupDir.entryList(QDir::Dirs | QDir::NoDotAndDotDot); - - QString selection = MultiOptionDialog::getSelection(tr("Select a backup to delete"), backupNames, "", this); - if (!selection.isEmpty()) { - if (!ConfirmationDialog::confirm(tr("Are you sure you want to delete this backup?"), tr("Delete"), this)) return; - std::thread([=]() { - toggleBackup->setValue("Deleting..."); - QDir dirToDelete(backupDir.absoluteFilePath(selection)); - if (dirToDelete.removeRecursively()) { - toggleBackup->setValue("Deleted!"); - } else { - toggleBackup->setValue("Failed..."); - } - std::this_thread::sleep_for(std::chrono::seconds(3)); - toggleBackup->setValue(""); - }).detach(); - } - } else { - QStringList backupNames = backupDir.entryList(QDir::Dirs | QDir::NoDotAndDotDot); - - QString selection = MultiOptionDialog::getSelection(tr("Select a restore point"), backupNames, "", this); - if (!selection.isEmpty()) { - if (!ConfirmationDialog::confirm(tr("Are you sure you want to restore this toggle backup?"), tr("Restore"), this)) return; - std::thread([=]() { - toggleBackup->setValue("Restoring..."); - - std::string sourcePath = backupDir.absolutePath().toStdString() + "/" + selection.toStdString() + "/"; - std::string targetPath = "/data/params/d/"; - - std::ostringstream commandStream; - commandStream << "rsync -av --delete " << std::quoted(sourcePath) << " " << std::quoted(targetPath); - std::string command = commandStream.str(); - - int result = std::system(command.c_str()); - - if (result == 0) { - std::cout << "Restore successful from " << sourcePath << " to " << targetPath << std::endl; - toggleBackup->setValue("Success!"); - paramsMemory.putBool("FrogPilotTogglesUpdated", true); - std::this_thread::sleep_for(std::chrono::seconds(3)); - toggleBackup->setValue(""); - paramsMemory.putBool("FrogPilotTogglesUpdated", false); - } else { - std::cerr << "Restore failed with error code: " << result << std::endl; - toggleBackup->setValue("Failed..."); - std::this_thread::sleep_for(std::chrono::seconds(3)); - toggleBackup->setValue(""); - } - }).detach(); - } - } - }); - addItem(toggleBackup); - - // Panda flashing button - auto flashPandaBtn = new ButtonControl(tr("Flash Panda"), tr("FLASH"), "Use this button to troubleshoot and update the Panda device's firmware."); - connect(flashPandaBtn, &ButtonControl::clicked, [this]() { - if (!ConfirmationDialog::confirm(tr("Are you sure you want to flash the Panda?"), tr("Flash"), this)) return; - QProcess process; - // Get Panda type - SubMaster &sm = *(uiState()->sm); - auto pandaStates = sm["pandaStates"].getPandaStates(); - // Choose recovery script based on Panda type - if (pandaStates.size() != 0) { - auto pandaType = pandaStates[0].getPandaType(); - bool isRedPanda = (pandaType == cereal::PandaState::PandaType::RED_PANDA || - pandaType == cereal::PandaState::PandaType::RED_PANDA_V2); - QString recoveryScript = isRedPanda ? "./recover.sh" : "./recover.py"; - // Run recovery script and flash Panda - process.setWorkingDirectory("/data/openpilot/panda/board"); - process.start("/bin/sh", QStringList{"-c", recoveryScript}); - process.waitForFinished(); - } - // Run the killall script as a redundancy - process.setWorkingDirectory("/data/openpilot/panda"); - process.start("/bin/sh", QStringList{"-c", "pkill -f boardd; PYTHONPATH=.. python -c \"from panda import Panda; Panda().flash()\""}); - process.waitForFinished(); - Hardware::soft_reboot(); - }); - addItem(flashPandaBtn); - - QObject::connect(uiState(), &UIState::offroadTransition, [=](bool offroad) { - for (auto btn : findChildren()) { - btn->setEnabled(offroad); - } - }); - - // power buttons - QHBoxLayout *power_layout = new QHBoxLayout(); - power_layout->setSpacing(30); - - QPushButton *reboot_btn = new QPushButton(tr("Reboot")); - reboot_btn->setObjectName("reboot_btn"); - power_layout->addWidget(reboot_btn); - QObject::connect(reboot_btn, &QPushButton::clicked, this, &DevicePanel::reboot); - - QPushButton *softreboot_btn = new QPushButton(tr("Soft Reboot")); - softreboot_btn->setObjectName("softreboot_btn"); - power_layout->addWidget(softreboot_btn); - QObject::connect(softreboot_btn, &QPushButton::clicked, this, &DevicePanel::softreboot); - - QPushButton *poweroff_btn = new QPushButton(tr("Power Off")); - poweroff_btn->setObjectName("poweroff_btn"); - power_layout->addWidget(poweroff_btn); - QObject::connect(poweroff_btn, &QPushButton::clicked, this, &DevicePanel::poweroff); - - if (!Hardware::PC()) { - connect(uiState(), &UIState::offroadTransition, poweroff_btn, &QPushButton::setVisible); - } - - setStyleSheet(R"( - #softreboot_btn { height: 120px; border-radius: 15px; background-color: #e2e22c; } - #softreboot_btn:pressed { background-color: #ffe224; } - #reboot_btn { height: 120px; border-radius: 15px; background-color: #e2872c; } - #reboot_btn:pressed { background-color: #ff9724; } - #poweroff_btn { height: 120px; border-radius: 15px; background-color: #E22C2C; } - #poweroff_btn:pressed { background-color: #FF2424; } - )"); - addItem(power_layout); -} - -void DevicePanel::updateCalibDescription() { - QString desc = - tr("openpilot requires the device to be mounted within 4° left or right and " - "within 5° up or 9° down. openpilot is continuously calibrating, resetting is rarely required."); - std::string calib_bytes = params.get("CalibrationParams"); - if (!calib_bytes.empty()) { - try { - AlignedBuffer aligned_buf; - capnp::FlatArrayMessageReader cmsg(aligned_buf.align(calib_bytes.data(), calib_bytes.size())); - auto calib = cmsg.getRoot().getLiveCalibration(); - if (calib.getCalStatus() != cereal::LiveCalibrationData::Status::UNCALIBRATED) { - double pitch = calib.getRpyCalib()[1] * (180 / M_PI); - double yaw = calib.getRpyCalib()[2] * (180 / M_PI); - desc += tr(" Your device is pointed %1° %2 and %3° %4.") - .arg(QString::number(std::abs(pitch), 'g', 1), pitch > 0 ? tr("down") : tr("up"), - QString::number(std::abs(yaw), 'g', 1), yaw > 0 ? tr("left") : tr("right")); - } - } catch (kj::Exception) { - qInfo() << "invalid CalibrationParams"; - } - } - qobject_cast(sender())->setDescription(desc); -} - -void DevicePanel::reboot() { - if (!uiState()->engaged()) { - if (ConfirmationDialog::confirm(tr("Are you sure you want to reboot?"), tr("Reboot"), this)) { - // Check engaged again in case it changed while the dialog was open - if (!uiState()->engaged()) { - params.putBool("DoReboot", true); - } - } - } else { - ConfirmationDialog::alert(tr("Disengage to Reboot"), this); - } -} - -void DevicePanel::softreboot() { - if (!uiState()->engaged()) { - if (ConfirmationDialog::confirm(tr("Are you sure you want to soft reboot?"), tr("Soft Reboot"), this)) { - if (!uiState()->engaged()) { - params.putBool("DoSoftReboot", true); - } - } - } else { - ConfirmationDialog::alert(tr("Disengage to Soft Reboot"), this); - } -} - -void DevicePanel::poweroff() { - if (!uiState()->engaged()) { - if (ConfirmationDialog::confirm(tr("Are you sure you want to power off?"), tr("Power Off"), this)) { - // Check engaged again in case it changed while the dialog was open - if (!uiState()->engaged()) { - params.putBool("DoShutdown", true); - } - } - } else { - ConfirmationDialog::alert(tr("Disengage to Power Off"), this); - } -} - -void SettingsWindow::showEvent(QShowEvent *event) { - setCurrentPanel(0); -} - -void SettingsWindow::setCurrentPanel(int index, const QString ¶m) { - panel_widget->setCurrentIndex(index); - nav_btns->buttons()[index]->setChecked(true); - if (!param.isEmpty()) { - emit expandToggleDescription(param); - } -} - -SettingsWindow::SettingsWindow(QWidget *parent) : QFrame(parent) { - - // setup two main layouts - sidebar_widget = new QWidget; - QVBoxLayout *sidebar_layout = new QVBoxLayout(sidebar_widget); - panel_widget = new QStackedWidget(); - - // close button - QPushButton *close_btn = new QPushButton(tr("← Back")); - close_btn->setStyleSheet(R"( - QPushButton { - font-size: 50px; - padding-bottom: 0px; - border-radius: 25px; - background-color: #292929; - font-weight: 500; - } - QPushButton:pressed { - background-color: #3B3B3B; - } - )"); - close_btn->setFixedSize(300, 125); - sidebar_layout->addSpacing(10); - sidebar_layout->addWidget(close_btn, 0, Qt::AlignRight); - QObject::connect(close_btn, &QPushButton::clicked, [this]() { - if (parentToggleOpen) { - if (subParentToggleOpen) { - closeSubParentToggle(); - } else { - closeParentToggle(); - } - } else { - closeSettings(); - } - }); - - // setup panels - DevicePanel *device = new DevicePanel(this); - QObject::connect(device, &DevicePanel::reviewTrainingGuide, this, &SettingsWindow::reviewTrainingGuide); - QObject::connect(device, &DevicePanel::showDriverView, this, &SettingsWindow::showDriverView); - - TogglesPanel *toggles = new TogglesPanel(this); - QObject::connect(this, &SettingsWindow::expandToggleDescription, toggles, &TogglesPanel::expandToggleDescription); - QObject::connect(toggles, &TogglesPanel::updateMetric, this, &SettingsWindow::updateMetric); - - FrogPilotControlsPanel *frogpilotControls = new FrogPilotControlsPanel(this); - QObject::connect(frogpilotControls, &FrogPilotControlsPanel::closeSubParentToggle, this, [this]() {subParentToggleOpen = false;}); - QObject::connect(frogpilotControls, &FrogPilotControlsPanel::openSubParentToggle, this, [this]() {subParentToggleOpen = true;}); - QObject::connect(frogpilotControls, &FrogPilotControlsPanel::closeParentToggle, this, [this]() {parentToggleOpen = false;}); - QObject::connect(frogpilotControls, &FrogPilotControlsPanel::openParentToggle, this, [this]() {parentToggleOpen = true;}); - - FrogPilotVisualsPanel *frogpilotVisuals = new FrogPilotVisualsPanel(this); - QObject::connect(frogpilotVisuals, &FrogPilotVisualsPanel::closeSubParentToggle, this, [this]() {subParentToggleOpen = false;}); - QObject::connect(frogpilotVisuals, &FrogPilotVisualsPanel::openSubParentToggle, this, [this]() {subParentToggleOpen = true;}); - QObject::connect(frogpilotVisuals, &FrogPilotVisualsPanel::closeParentToggle, this, [this]() {parentToggleOpen = false;}); - QObject::connect(frogpilotVisuals, &FrogPilotVisualsPanel::openParentToggle, this, [this]() {parentToggleOpen = true;}); - - QList> panels = { - {tr("Device"), device}, - {tr("Network"), new Networking(this)}, - {tr("Toggles"), toggles}, - {tr("Software"), new SoftwarePanel(this)}, - {tr("Controls"), frogpilotControls}, - {tr("Navigation"), new FrogPilotNavigationPanel(this)}, - {tr("Vehicles"), new FrogPilotVehiclesPanel(this)}, - {tr("Visuals"), frogpilotVisuals}, - }; - - nav_btns = new QButtonGroup(this); - for (auto &[name, panel] : panels) { - QPushButton *btn = new QPushButton(name); - btn->setCheckable(true); - btn->setChecked(nav_btns->buttons().size() == 0); - btn->setStyleSheet(R"( - QPushButton { - color: grey; - border: none; - background: none; - font-size: 65px; - font-weight: 500; - } - QPushButton:checked { - color: white; - } - QPushButton:pressed { - color: #ADADAD; - } - )"); - btn->setSizePolicy(QSizePolicy::Preferred, QSizePolicy::Expanding); - nav_btns->addButton(btn); - sidebar_layout->addWidget(btn, 0, Qt::AlignRight); - - const int lr_margin = name != tr("Network") ? 50 : 0; // Network panel handles its own margins - panel->setContentsMargins(lr_margin, 25, lr_margin, 25); - - ScrollView *panel_frame = new ScrollView(panel, this); - panel_widget->addWidget(panel_frame); - - if (name == tr("Controls") || name == tr("Visuals")) { - QScrollBar *scrollbar = panel_frame->verticalScrollBar(); - - QObject::connect(scrollbar, &QScrollBar::valueChanged, this, [this](int value) { - if (!parentToggleOpen) { - previousScrollPosition = value; - } - }); - - QObject::connect(scrollbar, &QScrollBar::rangeChanged, this, [this, panel_frame]() { - panel_frame->restorePosition(previousScrollPosition); - }); - } - - QObject::connect(btn, &QPushButton::clicked, [=, w = panel_frame]() { - previousScrollPosition = 0; - btn->setChecked(true); - panel_widget->setCurrentWidget(w); - }); - } - sidebar_layout->setContentsMargins(50, 50, 100, 50); - - // main settings layout, sidebar + main panel - QHBoxLayout *main_layout = new QHBoxLayout(this); - - sidebar_widget->setFixedWidth(500); - main_layout->addWidget(sidebar_widget); - main_layout->addWidget(panel_widget); - - setStyleSheet(R"( - * { - color: white; - font-size: 50px; - } - SettingsWindow { - background-color: black; - } - QStackedWidget, ScrollView { - background-color: #292929; - border-radius: 30px; - } - )"); -} diff --git a/selfdrive/ui/qt/offroad/settings.h b/selfdrive/ui/qt/offroad/settings.h deleted file mode 100644 index 6b58a98..0000000 --- a/selfdrive/ui/qt/offroad/settings.h +++ /dev/null @@ -1,125 +0,0 @@ -#pragma once - -#include -#include - -#include -#include -#include -#include -#include -#include - - -#include "selfdrive/ui/qt/util.h" -#include "selfdrive/ui/qt/widgets/controls.h" -#include "selfdrive/ui/ui.h" - -// ********** settings window + top-level panels ********** -class SettingsWindow : public QFrame { - Q_OBJECT - -public: - explicit SettingsWindow(QWidget *parent = 0); - void setCurrentPanel(int index, const QString ¶m = ""); - -protected: - void showEvent(QShowEvent *event) override; - -signals: - void closeSettings(); - void reviewTrainingGuide(); - void showDriverView(); - void expandToggleDescription(const QString ¶m); - - // FrogPilot signals - void closeParentToggle(); - void closeSubParentToggle(); - void updateMetric(); -private: - QPushButton *sidebar_alert_widget; - QWidget *sidebar_widget; - QButtonGroup *nav_btns; - QStackedWidget *panel_widget; - - // FrogPilot variables - bool parentToggleOpen; - bool subParentToggleOpen; - - int previousScrollPosition; -}; - -class DevicePanel : public ListWidget { - Q_OBJECT -public: - explicit DevicePanel(SettingsWindow *parent); -signals: - void reviewTrainingGuide(); - void showDriverView(); - -private slots: - void poweroff(); - void reboot(); - void softreboot(); - void updateCalibDescription(); - -private: - Params params; - - // FrogPilot variables - Params paramsMemory{"/dev/shm/params"}; -}; - -class TogglesPanel : public ListWidget { - Q_OBJECT -public: - explicit TogglesPanel(SettingsWindow *parent); - void showEvent(QShowEvent *event) override; - -signals: - // FrogPilot signals - void updateMetric(); - -public slots: - void expandToggleDescription(const QString ¶m); - -private: - Params params; - std::map toggles; - ButtonParamControl *long_personality_setting; - - void updateToggles(); -}; - -class SoftwarePanel : public ListWidget { - Q_OBJECT -public: - explicit SoftwarePanel(QWidget* parent = nullptr); - -private: - void showEvent(QShowEvent *event) override; - void updateLabels(); - void checkForUpdates(); - - bool is_onroad = false; - - QLabel *onroadLbl; - LabelControl *versionLbl; - ButtonControl *errorLogBtn; - ButtonControl *installBtn; - ButtonControl *downloadBtn; - ButtonControl *targetBranchBtn; - - Params params; - ParamWatcher *fs_watch; - - // FrogPilot variables - void automaticUpdate(); - - UIScene &scene; - - ButtonControl *updateTime; - - int schedule; - int time; -}; diff --git a/selfdrive/ui/qt/offroad/software_settings.cc b/selfdrive/ui/qt/offroad/software_settings.cc deleted file mode 100644 index da4c707..0000000 --- a/selfdrive/ui/qt/offroad/software_settings.cc +++ /dev/null @@ -1,265 +0,0 @@ -#include "selfdrive/ui/qt/offroad/settings.h" - -#include -#include -#include -#include -#include - -#include -#include -#include - -#include "common/params.h" -#include "common/util.h" -#include "selfdrive/ui/ui.h" -#include "selfdrive/ui/qt/util.h" -#include "selfdrive/ui/qt/widgets/controls.h" -#include "selfdrive/ui/qt/widgets/input.h" -#include "system/hardware/hw.h" - -#include "selfdrive/frogpilot/ui/frogpilot_ui_functions.h" - -void SoftwarePanel::checkForUpdates() { - std::system("pkill -SIGUSR1 -f selfdrive.updated"); -} - -SoftwarePanel::SoftwarePanel(QWidget* parent) : ListWidget(parent), scene(uiState()->scene) { - onroadLbl = new QLabel(tr("Updates are only downloaded while the car is off or in park.")); - onroadLbl->setStyleSheet("font-size: 50px; font-weight: 400; text-align: left; padding-top: 30px; padding-bottom: 30px;"); - addItem(onroadLbl); - - // current version - versionLbl = new LabelControl(tr("Current Version"), ""); - addItem(versionLbl); - - // Update scheduler - std::vector scheduleOptions{tr("Manually"), tr("Daily"), tr("Weekly")}; - FrogPilotButtonParamControl *preferredSchedule = new FrogPilotButtonParamControl("UpdateSchedule", tr("Update Scheduler"), - tr("Choose the frequency to automatically update FrogPilot.\n\n" - "This feature will handle the download, installation, and device reboot for a seamless 'Set and Forget' update experience.\n\n" - "Weekly updates start at midnight every Sunday."), - "", - scheduleOptions); - schedule = params.getInt("UpdateSchedule"); - QObject::connect(preferredSchedule, &FrogPilotButtonParamControl::buttonClicked, [this](int id) { - schedule = id; - updateLabels(); - }); - addItem(preferredSchedule); - - updateTime = new ButtonControl(tr("Update Time"), tr("SELECT")); - QStringList hours; - for (int h = 0; h < 24; h++) { - int displayHour = (h % 12 == 0) ? 12 : h % 12; - QString meridiem = (h < 12) ? "AM" : "PM"; - hours << QString("%1:00 %2").arg(displayHour).arg(meridiem) - << QString("%1:30 %2").arg(displayHour).arg(meridiem); - } - - QObject::connect(updateTime, &ButtonControl::clicked, [=]() { - int currentHourIndex = params.getInt("UpdateTime"); - QString currentHourLabel = hours[currentHourIndex]; - - QString selection = MultiOptionDialog::getSelection(tr("Select a time to automatically update"), hours, currentHourLabel, this); - if (!selection.isEmpty()) { - int selectedHourIndex = hours.indexOf(selection); - params.putInt("UpdateTime", selectedHourIndex); - updateTime->setValue(selection); - } - }); - time = params.getInt("UpdateTime"); - updateTime->setValue(hours[time]); - updateTime->setVisible(schedule != 0); - addItem(updateTime); - - // download update btn - downloadBtn = new ButtonControl(tr("Download"), tr("CHECK")); - connect(downloadBtn, &ButtonControl::clicked, [=]() { - downloadBtn->setEnabled(false); - if (downloadBtn->text() == tr("CHECK")) { - if (schedule == 0) { - params.putBool("ManualUpdateInitiated", true); - } - checkForUpdates(); - } else { - std::system("pkill -SIGHUP -f selfdrive.updated"); - } - }); - addItem(downloadBtn); - - // install update btn - installBtn = new ButtonControl(tr("Install Update"), tr("INSTALL")); - connect(installBtn, &ButtonControl::clicked, [=]() { - installBtn->setEnabled(false); - params.putBool("DoReboot", true); - }); - addItem(installBtn); - - // branch selecting - targetBranchBtn = new ButtonControl(tr("Target Branch"), tr("SELECT")); - connect(targetBranchBtn, &ButtonControl::clicked, [=]() { - auto current = params.get("GitBranch"); - QStringList branches = QString::fromStdString(params.get("UpdaterAvailableBranches")).split(","); - for (QString b : {current.c_str(), "devel-staging", "devel", "nightly", "master-ci", "master"}) { - auto i = branches.indexOf(b); - if (i >= 0) { - branches.removeAt(i); - branches.insert(0, b); - } - } - - QString cur = QString::fromStdString(params.get("UpdaterTargetBranch")); - QString selection = MultiOptionDialog::getSelection(tr("Select a branch"), branches, cur, this); - if (!selection.isEmpty()) { - params.put("UpdaterTargetBranch", selection.toStdString()); - targetBranchBtn->setValue(QString::fromStdString(params.get("UpdaterTargetBranch"))); - checkForUpdates(); - } - }); - if (!params.getBool("IsTestedBranch")) { - addItem(targetBranchBtn); - } - - // uninstall button - auto uninstallBtn = new ButtonControl(tr("Uninstall %1").arg(getBrand()), tr("UNINSTALL")); - connect(uninstallBtn, &ButtonControl::clicked, [&]() { - if (ConfirmationDialog::confirm(tr("Are you sure you want to uninstall?"), tr("Uninstall"), this)) { - params.putBool("DoUninstall", true); - } - }); - addItem(uninstallBtn); - - // error log button - errorLogBtn = new ButtonControl(tr("Error Log"), tr("VIEW"), "View the error log for debugging purposes when openpilot crashes."); - connect(errorLogBtn, &ButtonControl::clicked, [=]() { - std::string txt = util::read_file("/data/community/crashes/error.txt"); - ConfirmationDialog::rich(QString::fromStdString(txt), this); - }); - addItem(errorLogBtn); - - fs_watch = new ParamWatcher(this); - QObject::connect(fs_watch, &ParamWatcher::paramChanged, [=](const QString ¶m_name, const QString ¶m_value) { - updateLabels(); - }); - - connect(uiState(), &UIState::offroadTransition, [=](bool offroad) { - is_onroad = !offroad; - updateLabels(); - }); - - QObject::connect(uiState(), &UIState::uiUpdate, this, &SoftwarePanel::automaticUpdate); - - updateLabels(); -} - -void SoftwarePanel::showEvent(QShowEvent *event) { - // nice for testing on PC - installBtn->setEnabled(true); - - updateLabels(); -} - -void SoftwarePanel::updateLabels() { - // add these back in case the files got removed - fs_watch->addParam("LastUpdateTime"); - fs_watch->addParam("UpdateFailedCount"); - fs_watch->addParam("UpdaterState"); - fs_watch->addParam("UpdateAvailable"); - - if (!isVisible()) { - return; - } - - // updater only runs offroad or when parked - bool parked = scene.parked; - - onroadLbl->setVisible(is_onroad && !parked); - downloadBtn->setVisible(!is_onroad || parked); - - // download update - QString updater_state = QString::fromStdString(params.get("UpdaterState")); - bool failed = std::atoi(params.get("UpdateFailedCount").c_str()) > 0; - if (updater_state != "idle") { - downloadBtn->setEnabled(false); - downloadBtn->setValue(updater_state); - } else { - if (failed && schedule != 0) { - downloadBtn->setText(tr("CHECK")); - downloadBtn->setValue(tr("failed to check for update")); - } else if (params.getBool("UpdaterFetchAvailable")) { - downloadBtn->setText(tr("DOWNLOAD")); - downloadBtn->setValue(tr("update available")); - } else { - QString lastUpdate = tr("never"); - auto tm = params.get("LastUpdateTime"); - if (!tm.empty()) { - lastUpdate = timeAgo(QDateTime::fromString(QString::fromStdString(tm + "Z"), Qt::ISODate)); - } - downloadBtn->setText(tr("CHECK")); - downloadBtn->setValue(tr("up to date, last checked %1").arg(lastUpdate)); - } - downloadBtn->setEnabled(true); - } - targetBranchBtn->setValue(QString::fromStdString(params.get("UpdaterTargetBranch"))); - - // current + new versions - versionLbl->setText(QString::fromStdString(params.get("UpdaterCurrentDescription"))); - versionLbl->setDescription(QString::fromStdString(params.get("UpdaterCurrentReleaseNotes"))); - - installBtn->setVisible((!is_onroad || parked) && params.getBool("UpdateAvailable")); - installBtn->setValue(QString::fromStdString(params.get("UpdaterNewDescription"))); - installBtn->setDescription(QString::fromStdString(params.get("UpdaterNewReleaseNotes"))); - - updateTime->setVisible(params.getInt("UpdateSchedule")); - - update(); -} - -void SoftwarePanel::automaticUpdate() { - // Variable declarations - static bool isDownloadCompleted = false; - static bool updateCheckedToday = false; - - std::time_t currentTimeT = std::chrono::system_clock::to_time_t(std::chrono::system_clock::now()); - std::tm now = *std::localtime(¤tTimeT); - - // Check to make sure we're not onroad and have a WiFi connection - bool isWifiConnected = (*uiState()->sm)["deviceState"].getDeviceState().getNetworkType() == cereal::DeviceState::NetworkType::WIFI; - if (schedule == 0 || is_onroad || !isWifiConnected || isVisible()) return; - - // Reboot if an automatic update was completed - if (isDownloadCompleted) { - if (installBtn->isVisible()) Hardware::reboot(); - return; - } - - // Format "Updated" to a useable format - std::tm lastUpdate; - std::istringstream ss(params.get("Updated")); - ss >> std::get_time(&lastUpdate, "%Y-%m-%d %H:%M:%S"); - std::time_t lastUpdateTimeT = std::mktime(&lastUpdate); - - // Check if an update was already performed today - static int lastCheckedDay = now.tm_yday; - if (lastCheckedDay != now.tm_yday) { - updateCheckedToday = false; - lastCheckedDay = now.tm_yday; - } else if (lastUpdate.tm_yday == now.tm_yday) { - return; - } - - // Check if it's time to update - std::chrono::hours durationSinceLastUpdate = std::chrono::duration_cast(std::chrono::system_clock::now() - std::chrono::system_clock::from_time_t(lastUpdateTimeT)); - int daysSinceLastUpdate = durationSinceLastUpdate.count() / 24; - - if ((schedule == 1 && daysSinceLastUpdate >= 1) || (schedule == 2 && (now.tm_yday / 7) != (std::localtime(&lastUpdateTimeT)->tm_yday / 7))) { - if (downloadBtn->text() == tr("CHECK") && !updateCheckedToday) { - checkForUpdates(); - updateCheckedToday = true; - } else { - std::system("pkill -SIGHUP -f selfdrive.updated"); - isDownloadCompleted = true; - } - } -} diff --git a/selfdrive/ui/qt/onroad.cc b/selfdrive/ui/qt/onroad.cc deleted file mode 100644 index 5f27f64..0000000 --- a/selfdrive/ui/qt/onroad.cc +++ /dev/null @@ -1,1965 +0,0 @@ -#include "selfdrive/ui/qt/onroad.h" - -#include -#include -#include -#include -#include - -#include -#include -#include - -#include "common/swaglog.h" -#include "common/timing.h" -#include "selfdrive/ui/qt/util.h" -#ifdef ENABLE_MAPS -#include "selfdrive/ui/qt/maps/map_helpers.h" -#include "selfdrive/ui/qt/maps/map_panel.h" -#endif - -static void drawIcon(QPainter &p, const QPoint ¢er, const QPixmap &img, const QBrush &bg, float opacity, const int angle = 0) { - p.setRenderHint(QPainter::Antialiasing); - p.setOpacity(1.0); // bg dictates opacity of ellipse - p.setPen(Qt::NoPen); - p.setBrush(bg); - p.drawEllipse(center, btn_size / 2, btn_size / 2); - p.save(); - p.translate(center); - p.rotate(-angle); - p.setOpacity(opacity); - p.drawPixmap(-QPoint(img.width() / 2, img.height() / 2), img); - p.setOpacity(1.0); - p.restore(); -} - -static void drawIconGif(QPainter &p, const QPoint ¢er, const QMovie &img, const QBrush &bg, float opacity) { - p.setRenderHint(QPainter::Antialiasing); - p.setOpacity(1.0); // bg dictates opacity of ellipse - p.setPen(Qt::NoPen); - p.setBrush(bg); - p.drawEllipse(center.x() - btn_size / 2, center.y() - btn_size / 2, btn_size, btn_size); - p.setOpacity(opacity); - QPixmap currentFrame = img.currentPixmap(); - p.drawPixmap(center - QPoint(currentFrame.width() / 2, currentFrame.height() / 2), currentFrame); - p.setOpacity(1.0); -} - -OnroadWindow::OnroadWindow(QWidget *parent) : QWidget(parent), scene(uiState()->scene) { - QVBoxLayout *main_layout = new QVBoxLayout(this); - main_layout->setMargin(UI_BORDER_SIZE); - QStackedLayout *stacked_layout = new QStackedLayout; - stacked_layout->setStackingMode(QStackedLayout::StackAll); - main_layout->addLayout(stacked_layout); - - nvg = new AnnotatedCameraWidget(VISION_STREAM_ROAD, this); - - QWidget * split_wrapper = new QWidget; - split = new QHBoxLayout(split_wrapper); - split->setContentsMargins(0, 0, 0, 0); - split->setSpacing(0); - split->addWidget(nvg); - - if (getenv("DUAL_CAMERA_VIEW")) { - CameraWidget *arCam = new CameraWidget("camerad", VISION_STREAM_ROAD, true, this); - split->insertWidget(0, arCam); - } - - if (getenv("MAP_RENDER_VIEW")) { - CameraWidget *map_render = new CameraWidget("navd", VISION_STREAM_MAP, false, this); - split->insertWidget(0, map_render); - } - - stacked_layout->addWidget(split_wrapper); - - alerts = new OnroadAlerts(this); - alerts->setAttribute(Qt::WA_TransparentForMouseEvents, true); - stacked_layout->addWidget(alerts); - - // setup stacking order - alerts->raise(); - - setAttribute(Qt::WA_OpaquePaintEvent); - QObject::connect(uiState(), &UIState::uiUpdate, this, &OnroadWindow::updateState); - QObject::connect(uiState(), &UIState::offroadTransition, this, &OnroadWindow::offroadTransition); - QObject::connect(uiState(), &UIState::primeChanged, this, &OnroadWindow::primeChanged); - - QObject::connect(&clickTimer, &QTimer::timeout, this, [this]() { - clickTimer.stop(); - QMouseEvent *event = new QMouseEvent(QEvent::MouseButtonPress, timeoutPoint, Qt::LeftButton, Qt::LeftButton, Qt::NoModifier); - QApplication::postEvent(this, event); - }); -} - -void OnroadWindow::updateState(const UIState &s) { - if (!s.scene.started) { - return; - } - - QColor bgColor = bg_colors[s.status]; - Alert alert = Alert::get(*(s.sm), s.scene.started_frame); - alerts->updateAlert(alert); - - if (s.scene.map_on_left || scene.full_map) { - split->setDirection(QBoxLayout::LeftToRight); - } else { - split->setDirection(QBoxLayout::RightToLeft); - } - - nvg->updateState(s); - - if (bg != bgColor) { - // repaint border - bg = bgColor; - update(); - } -} - -void OnroadWindow::mousePressEvent(QMouseEvent* e) { - Params params = Params(); - - // FrogPilot clickable widgets - bool widgetClicked = false; - - // Change cruise control increments button - QRect maxSpeedRect(7, 25, 225, 225); - bool isMaxSpeedClicked = maxSpeedRect.contains(e->pos()); - - // Hide speed button - QRect hideSpeedRect(rect().center().x() - 175, 50, 350, 350); - bool isSpeedClicked = hideSpeedRect.contains(e->pos()); - - // Speed limit confirmation buttons - QSize size = this->size(); - QRect leftRect(0, 0, size.width() / 2, size.height()); - QRect rightRect = leftRect.translated(size.width() / 2, 0); - bool isLeftSideClicked = leftRect.contains(e->pos()) && scene.speed_limit_changed; - bool isRightSideClicked = rightRect.contains(e->pos()) && scene.speed_limit_changed; - - // Speed limit offset button - QRect speedLimitRect(7, 250, 225, 225); - bool isSpeedLimitClicked = speedLimitRect.contains(e->pos()); - - if (isMaxSpeedClicked || isSpeedClicked || isSpeedLimitClicked) { - if (isMaxSpeedClicked && scene.reverse_cruise_ui) { - bool currentReverseCruise = scene.reverse_cruise; - - uiState()->scene.reverse_cruise = !currentReverseCruise; - params.putBoolNonBlocking("ReverseCruise", !currentReverseCruise); - - } else if (isSpeedClicked && scene.hide_speed_ui) { - bool currentHideSpeed = scene.hide_speed; - - uiState()->scene.hide_speed = !currentHideSpeed; - params.putBoolNonBlocking("HideSpeed", !currentHideSpeed); - } else if (isSpeedLimitClicked && scene.show_slc_offset_ui) { - bool currentShowSLCOffset = scene.show_slc_offset; - - uiState()->scene.show_slc_offset = !currentShowSLCOffset; - params.putBoolNonBlocking("ShowSLCOffset", !currentShowSLCOffset); - } - - widgetClicked = true; - } else if (isLeftSideClicked || isRightSideClicked) { - bool slcConfirmed = isLeftSideClicked && !scene.right_hand_drive || isRightSideClicked && scene.right_hand_drive; - paramsMemory.putBool("SLCConfirmed", slcConfirmed); - paramsMemory.putBool("SLCConfirmedPressed", true); - - widgetClicked = true; - // If the click wasn't for anything specific, change the value of "ExperimentalMode" - } else if (scene.experimental_mode_via_screen && e->pos() != timeoutPoint) { - if (clickTimer.isActive()) { - clickTimer.stop(); - - if (scene.conditional_experimental) { - int override_value = (scene.conditional_status >= 1 && scene.conditional_status <= 6) ? 0 : scene.conditional_status >= 7 ? 1 : 2; - paramsMemory.putIntNonBlocking("CEStatus", override_value); - } else { - bool experimentalMode = params.getBool("ExperimentalMode"); - params.putBoolNonBlocking("ExperimentalMode", !experimentalMode); - } - - } else { - clickTimer.start(500); - } - widgetClicked = true; - } - -#ifdef ENABLE_MAPS - if (map != nullptr && !widgetClicked) { - // Switch between map and sidebar when using navigate on openpilot - bool sidebarVisible = geometry().x() > 0; - bool show_map = uiState()->scene.navigate_on_openpilot ? sidebarVisible : !sidebarVisible; - if (!clickTimer.isActive()) { - map->setVisible(show_map && !map->isVisible()); - if (scene.full_map) { - map->setFixedWidth(width()); - } else { - map->setFixedWidth(topWidget(this)->width() / 2 - UI_BORDER_SIZE); - } - } - } -#endif - // propagation event to parent(HomeWindow) - if (!widgetClicked) { - QWidget::mousePressEvent(e); - } -} - -void OnroadWindow::offroadTransition(bool offroad) { -#ifdef ENABLE_MAPS - if (!offroad) { - if (map == nullptr && (uiState()->hasPrime() || !MAPBOX_TOKEN.isEmpty())) { - auto m = new MapPanel(get_mapbox_settings()); - map = m; - - QObject::connect(m, &MapPanel::mapPanelRequested, this, &OnroadWindow::mapPanelRequested); - QObject::connect(nvg->map_settings_btn, &MapSettingsButton::clicked, m, &MapPanel::toggleMapSettings); - QObject::connect(nvg->map_settings_btn_bottom, &MapSettingsButton::clicked, m, &MapPanel::toggleMapSettings); - nvg->map_settings_btn->setEnabled(true); - - m->setFixedWidth(topWidget(this)->width() / 2 - UI_BORDER_SIZE); - split->insertWidget(0, m); - - // hidden by default, made visible when navRoute is published - m->setVisible(false); - } - } -#endif - - alerts->updateAlert({}); -} - -void OnroadWindow::primeChanged(bool prime) { -#ifdef ENABLE_MAPS - if (map && (!prime && MAPBOX_TOKEN.isEmpty())) { - nvg->map_settings_btn->setEnabled(false); - nvg->map_settings_btn->setVisible(false); - map->deleteLater(); - map = nullptr; - } -#endif -} - -void OnroadWindow::paintEvent(QPaintEvent *event) { - QPainter p(this); - p.fillRect(rect(), QColor(bg.red(), bg.green(), bg.blue(), 255)); - - // Draw FPS on screen - if (scene.fps_counter) { - updateFPSCounter(); - - // Format the FPS string - QString fpsDisplayString = QString("FPS: %1 (%2) | Min: %3 | Max: %4 | Avg: %5") - .arg(fps, 0, 'f', 2) - .arg(paramsMemory.getInt("CameraFPS")) - .arg(minFPS, 0, 'f', 2) - .arg(maxFPS, 0, 'f', 2) - .arg(avgFPS, 0, 'f', 2); - - // Configure the text - p.setFont(InterFont(30, QFont::DemiBold)); - p.setRenderHint(QPainter::TextAntialiasing); - p.setPen(Qt::white); - - // Center the text - QRect currentRect = rect(); - int textWidth = p.fontMetrics().horizontalAdvance(fpsDisplayString); - int xPos = (currentRect.width() - textWidth) / 2; - int yPos = currentRect.bottom() - 5; - - // Draw the text - p.drawText(xPos, yPos, fpsDisplayString); - - update(); - } -} - -void OnroadWindow::updateFPSCounter() { - qint64 currentMillis = QDateTime::currentMSecsSinceEpoch(); - std::queue> fpsQueue = std::queue>(); - - minFPS = qMin(minFPS, fps); - maxFPS = qMax(maxFPS, fps); - fpsQueue.push({currentMillis, fps}); - - while (!fpsQueue.empty() && currentMillis - fpsQueue.front().first > 60000) { - fpsQueue.pop(); - } - - if (!fpsQueue.empty()) { - double totalFPS = 0; - std::queue> tempQueue = fpsQueue; - while (!tempQueue.empty()) { - totalFPS += tempQueue.front().second; - tempQueue.pop(); - } - avgFPS = totalFPS / fpsQueue.size(); - } -} - -// ***** onroad widgets ***** - -// OnroadAlerts -void OnroadAlerts::updateAlert(const Alert &a) { - if (!alert.equal(a)) { - alert = a; - update(); - } -} - -void OnroadAlerts::paintEvent(QPaintEvent *event) { - if (alert.size == cereal::ControlsState::AlertSize::NONE || scene.show_driver_camera && alert.status != cereal::ControlsState::AlertStatus::CRITICAL) { - return; - } - - if (scene.hide_alerts && alert.size == cereal::ControlsState::AlertSize::SMALL) { - return; - } - - static std::map alert_heights = { - {cereal::ControlsState::AlertSize::SMALL, 271}, - {cereal::ControlsState::AlertSize::MID, 420}, - {cereal::ControlsState::AlertSize::FULL, height()}, - }; - int h = alert_heights[alert.size]; - - int margin = 40; - int radius = 30; - int offset = scene.always_on_lateral || scene.conditional_experimental || scene.road_name_ui ? 25 : 0; - if (alert.size == cereal::ControlsState::AlertSize::FULL) { - margin = 0; - radius = 0; - offset = 0; - } - QRect r = QRect(0 + margin, height() - h + margin - offset, width() - margin*2, h - margin*2); - - QPainter p(this); - - // draw background + gradient - p.setPen(Qt::NoPen); - p.setCompositionMode(QPainter::CompositionMode_SourceOver); - p.setBrush(QBrush(alert_colors[alert.status])); - p.drawRoundedRect(r, radius, radius); - - QLinearGradient g(0, r.y(), 0, r.bottom()); - g.setColorAt(0, QColor::fromRgbF(0, 0, 0, 0.05)); - g.setColorAt(1, QColor::fromRgbF(0, 0, 0, 0.35)); - - p.setCompositionMode(QPainter::CompositionMode_DestinationOver); - p.setBrush(QBrush(g)); - p.drawRoundedRect(r, radius, radius); - p.setCompositionMode(QPainter::CompositionMode_SourceOver); - - // text - const QPoint c = r.center(); - p.setPen(QColor(0xff, 0xff, 0xff)); - p.setRenderHint(QPainter::TextAntialiasing); - if (alert.size == cereal::ControlsState::AlertSize::SMALL) { - p.setFont(InterFont(74, QFont::DemiBold)); - p.drawText(r, Qt::AlignCenter, alert.text1); - } else if (alert.size == cereal::ControlsState::AlertSize::MID) { - p.setFont(InterFont(88, QFont::Bold)); - p.drawText(QRect(0, c.y() - 125, width(), 150), Qt::AlignHCenter | Qt::AlignTop, alert.text1); - p.setFont(InterFont(66)); - p.drawText(QRect(0, c.y() + 21, width(), 90), Qt::AlignHCenter, alert.text2); - } else if (alert.size == cereal::ControlsState::AlertSize::FULL) { - bool l = alert.text1.length() > 15; - p.setFont(InterFont(l ? 132 : 177, QFont::Bold)); - p.drawText(QRect(0, r.y() + (l ? 240 : 270), width(), 600), Qt::AlignHCenter | Qt::TextWordWrap, alert.text1); - p.setFont(InterFont(88)); - p.drawText(QRect(0, r.height() - (l ? 361 : 420), width(), 300), Qt::AlignHCenter | Qt::TextWordWrap, alert.text2); - } -} - -// ExperimentalButton -ExperimentalButton::ExperimentalButton(QWidget *parent) : experimental_mode(false), engageable(false), QPushButton(parent), scene(uiState()->scene) { - setFixedSize(btn_size, btn_size + 10); - - engage_img = loadPixmap("../assets/img_chffr_wheel.png", {img_size, img_size}); - experimental_img = loadPixmap("../assets/img_experimental.svg", {img_size, img_size}); - QObject::connect(this, &QPushButton::clicked, this, &ExperimentalButton::changeMode); - - // Custom steering wheel images - wheelImages = { - {0, loadPixmap("../assets/img_chffr_wheel.png", {img_size, img_size})}, - {1, loadPixmap("../frogpilot/assets/wheel_images/lexus.png", {img_size, img_size})}, - {2, loadPixmap("../frogpilot/assets/wheel_images/toyota.png", {img_size, img_size})}, - {3, loadPixmap("../frogpilot/assets/wheel_images/frog.png", {img_size, img_size})}, - {4, loadPixmap("../frogpilot/assets/wheel_images/rocket.png", {img_size, img_size})}, - {5, loadPixmap("../frogpilot/assets/wheel_images/hyundai.png", {img_size, img_size})}, - {6, loadPixmap("../frogpilot/assets/wheel_images/stalin.png", {img_size, img_size})}, - {7, loadPixmap("../frogpilot/assets/random_events/images/firefox.png", {img_size, img_size})}, - }; - - wheelImagesGif[1] = new QMovie("../frogpilot/assets/random_events/images/weeb_wheel.gif", QByteArray(), this); - wheelImagesGif[2] = new QMovie("../frogpilot/assets/random_events/images/tree_fiddy.gif", QByteArray(), this); -} - -void ExperimentalButton::changeMode() { - Params paramsMemory = Params("/dev/shm/params"); - - const auto cp = (*uiState()->sm)["carParams"].getCarParams(); - bool can_change = hasLongitudinalControl(cp) && (params.getBool("ExperimentalModeConfirmed") || scene.experimental_mode_via_screen); - if (can_change) { - if (scene.conditional_experimental) { - int override_value = (scene.conditional_status >= 1 && scene.conditional_status <= 4) ? 0 : scene.conditional_status >= 5 ? 3 : 4; - paramsMemory.putIntNonBlocking("ConditionalStatus", override_value); - } else { - params.putBool("ExperimentalMode", !experimental_mode); - } - } -} - -void ExperimentalButton::updateState(const UIState &s, bool leadInfo) { - const auto cs = (*s.sm)["controlsState"].getControlsState(); - bool eng = cs.getEngageable() || cs.getEnabled() || scene.always_on_lateral_active; - if ((cs.getExperimentalMode() != experimental_mode) || (eng != engageable)) { - engageable = eng; - experimental_mode = cs.getExperimentalMode(); - update(); - } - - // FrogPilot variables - firefoxRandomEventTriggered = scene.current_random_event == 1; - treeFiddyRandomEventTriggered = scene.current_random_event == 3; - weebRandomEventTriggered = scene.current_random_event == 2; - rotatingWheel = scene.rotating_wheel; - wheelIcon = scene.wheel_icon; - wheelIconGif = 0; - - y_offset = leadInfo ? 10 : 0; - - if (firefoxRandomEventTriggered) { - static int rotationDegree = 0; - rotationDegree = (rotationDegree + 36) % 360; - steeringAngleDeg = rotationDegree; - wheelIcon = 7; - update(); - - } else if (treeFiddyRandomEventTriggered || weebRandomEventTriggered) { - if (!gifLabel) { - gifLabel = new QLabel(this); - QMovie *movie; - - if (treeFiddyRandomEventTriggered) { - movie = wheelImagesGif[2]; - } else if (weebRandomEventTriggered) { - movie = wheelImagesGif[1]; - } - - if (movie) { - gifLabel->setMovie(movie); - gifLabel->setFixedSize(img_size, img_size); - gifLabel->move((width() - gifLabel->width()) / 2, (height() - gifLabel->height()) / 2 + y_offset); - } - } - if (gifLabel->movie()) { - gifLabel->movie()->start(); - } - gifLabel->show(); - wheelIconGif = weebRandomEventTriggered ? 1 : 2; - update(); - - } else { - if (gifLabel) { - gifLabel->hide(); - } - if (rotatingWheel) { - // Update the icon so the steering wheel rotates in real time - if (steeringAngleDeg != scene.steering_angle_deg) { - steeringAngleDeg = scene.steering_angle_deg; - update(); - } - } else { - steeringAngleDeg = 0; - } - } -} - -void ExperimentalButton::paintEvent(QPaintEvent *event) { - if (wheelIcon < 0) { - return; - } - - QPainter p(this); - // Custom steering wheel icon - engage_img = wheelImages[wheelIcon]; - QPixmap img = wheelIcon ? engage_img : (experimental_mode ? experimental_img : engage_img); - - QMovie *gif = wheelImagesGif[wheelIconGif]; - - QColor background_color = wheelIcon != 0 && !isDown() && engageable ? - (scene.always_on_lateral_active ? QColor(10, 186, 181, 255) : - (scene.conditional_status == 1 ? QColor(255, 246, 0, 255) : - (experimental_mode ? QColor(218, 111, 37, 241) : - (scene.traffic_mode && scene.traffic_mode_active ? QColor(201, 34, 49, 255) : - (scene.navigate_on_openpilot ? QColor(49, 161, 238, 255) : QColor(0, 0, 0, 166)))))) : - QColor(0, 0, 0, 166); - - if (!(scene.show_driver_camera || scene.map_open && scene.full_map)) { - if (wheelIconGif != 0) { - QBrush backgroundBrush(background_color); - drawIconGif(p, QPoint(btn_size / 2, btn_size / 2 + y_offset), *gif, backgroundBrush, 1.0); - } else { - drawIcon(p, QPoint(btn_size / 2, btn_size / 2 + y_offset), img, background_color, (isDown() || !(engageable || scene.always_on_lateral_active)) ? 0.6 : 1.0, steeringAngleDeg); - } - } -} - - -// MapSettingsButton -MapSettingsButton::MapSettingsButton(QWidget *parent) : QPushButton(parent) { - setFixedSize(btn_size, btn_size + 20); - settings_img = loadPixmap("../assets/navigation/icon_directions_outlined.svg", {img_size, img_size}); - - // hidden by default, made visible if map is created (has prime or mapbox token) - setVisible(false); - setEnabled(false); -} - -void MapSettingsButton::paintEvent(QPaintEvent *event) { - QPainter p(this); - drawIcon(p, QPoint(btn_size / 2, btn_size / 2), settings_img, QColor(0, 0, 0, 166), isDown() ? 0.6 : 1.0); -} - - -// Window that shows camera view and variety of info drawn on top -AnnotatedCameraWidget::AnnotatedCameraWidget(VisionStreamType type, QWidget* parent) : fps_filter(UI_FREQ, 3, 1. / UI_FREQ), CameraWidget("camerad", type, true, parent), scene(uiState()->scene) { - pm = std::make_unique>({"uiDebug"}); - - main_layout = new QVBoxLayout(this); - main_layout->setMargin(UI_BORDER_SIZE); - main_layout->setSpacing(0); - - QHBoxLayout *buttons_layout = new QHBoxLayout(); - buttons_layout->setSpacing(0); - - // Neokii screen recorder - recorder_btn = new ScreenRecorder(this); - buttons_layout->addWidget(recorder_btn); - - experimental_btn = new ExperimentalButton(this); - buttons_layout->addWidget(experimental_btn); - - QVBoxLayout *top_right_layout = new QVBoxLayout(); - top_right_layout->setSpacing(0); - top_right_layout->addLayout(buttons_layout); - - pedal_icons = new PedalIcons(this); - top_right_layout->addWidget(pedal_icons, 0, Qt::AlignRight); - - main_layout->addLayout(top_right_layout, 0); - main_layout->setAlignment(top_right_layout, Qt::AlignTop | Qt::AlignRight); - - map_settings_btn = new MapSettingsButton(this); - main_layout->addWidget(map_settings_btn, 0, Qt::AlignBottom | Qt::AlignRight); - - dm_img = loadPixmap("../assets/img_driver_face.png", {img_size + 5, img_size + 5}); - - // Initialize FrogPilot widgets - initializeFrogPilotWidgets(); -} - -void AnnotatedCameraWidget::updateState(const UIState &s) { - const int SET_SPEED_NA = 255; - const SubMaster &sm = *(s.sm); - - const bool cs_alive = sm.alive("controlsState"); - const bool nav_alive = sm.alive("navInstruction") && sm["navInstruction"].getValid(); - const auto cs = sm["controlsState"].getControlsState(); - const auto car_state = sm["carState"].getCarState(); - const auto nav_instruction = sm["navInstruction"].getNavInstruction(); - - // Handle older routes where vCruiseCluster is not set - float v_cruise = cs.getVCruiseCluster() == 0.0 ? cs.getVCruise() : cs.getVCruiseCluster(); - setSpeed = cs_alive ? v_cruise : SET_SPEED_NA; - is_cruise_set = setSpeed > 0 && (int)setSpeed != SET_SPEED_NA; - if (is_cruise_set && !s.scene.is_metric) { - setSpeed *= KM_TO_MILE; - } - - // Handle older routes where vEgoCluster is not set - v_ego_cluster_seen = v_ego_cluster_seen || car_state.getVEgoCluster() != 0.0; - float v_ego = v_ego_cluster_seen && !scene.wheel_speed ? car_state.getVEgoCluster() : car_state.getVEgo(); - speed = cs_alive ? std::max(0.0, v_ego) : 0.0; - speed *= s.scene.is_metric ? MS_TO_KPH : MS_TO_MPH; - - auto speed_limit_sign = nav_instruction.getSpeedLimitSign(); - speedLimit = slcOverridden ? scene.speed_limit_overridden_speed : speedLimitController ? slcSpeedLimit : nav_alive ? nav_instruction.getSpeedLimit() : 0.0; - speedLimit *= (s.scene.is_metric ? MS_TO_KPH : MS_TO_MPH); - if (speedLimitController && !slcOverridden) { - speedLimit = speedLimit - (showSLCOffset ? slcSpeedLimitOffset : 0); - } - - has_us_speed_limit = (nav_alive && speed_limit_sign == cereal::NavInstruction::SpeedLimitSign::MUTCD) || (speedLimitController && !useViennaSLCSign); - has_eu_speed_limit = (nav_alive && speed_limit_sign == cereal::NavInstruction::SpeedLimitSign::VIENNA) || (speedLimitController && useViennaSLCSign); - is_metric = s.scene.is_metric; - speedUnit = s.scene.is_metric ? tr("km/h") : tr("mph"); - hideBottomIcons = (cs.getAlertSize() != cereal::ControlsState::AlertSize::NONE || customSignals && (turnSignalLeft || turnSignalRight)) || fullMapOpen || showDriverCamera; - status = s.status; - - // update engageability/experimental mode button - experimental_btn->updateState(s, leadInfo); - - // update DM icon - auto dm_state = sm["driverMonitoringState"].getDriverMonitoringState(); - dmActive = dm_state.getIsActiveMode(); - rightHandDM = dm_state.getIsRHD(); - // DM icon transition - dm_fade_state = std::clamp(dm_fade_state+0.2*(0.5-dmActive), 0.0, 1.0); - - // hide map settings button for alerts and flip for right hand DM - if (map_settings_btn->isEnabled()) { - map_settings_btn->setVisible(!hideBottomIcons && compass && !scene.hide_map_icon); - main_layout->setAlignment(map_settings_btn, (rightHandDM ? Qt::AlignLeft : Qt::AlignRight) | (compass ? Qt::AlignTop : Qt::AlignBottom)); - } -} - -void AnnotatedCameraWidget::drawHud(QPainter &p) { - p.save(); - - // Header gradient - QLinearGradient bg(0, UI_HEADER_HEIGHT - (UI_HEADER_HEIGHT / 2.5), 0, UI_HEADER_HEIGHT); - bg.setColorAt(0, QColor::fromRgbF(0, 0, 0, 0.45)); - bg.setColorAt(1, QColor::fromRgbF(0, 0, 0, 0)); - p.fillRect(0, 0, width(), UI_HEADER_HEIGHT, bg); - - QString speedLimitStr = (speedLimit > 1) ? QString::number(std::nearbyint(speedLimit)) : "–"; - QString speedLimitOffsetStr = slcSpeedLimitOffset == 0 ? "–" : QString::number(slcSpeedLimitOffset, 'f', 0).prepend(slcSpeedLimitOffset > 0 ? "+" : ""); - QString speedStr = QString::number(std::nearbyint(speed)); - QString setSpeedStr = is_cruise_set ? QString::number(std::nearbyint(setSpeed - cruiseAdjustment)) : "–"; - - if (!(scene.hide_max_speed || showDriverCamera)) { - // Draw outer box + border to contain set speed and speed limit - const int sign_margin = 12; - const int us_sign_height = 186; - const int eu_sign_size = 176; - - const QSize default_size = {172, 204}; - QSize set_speed_size = default_size; - if (is_metric || has_eu_speed_limit) set_speed_size.rwidth() = 200; - if (has_us_speed_limit && speedLimitStr.size() >= 3) set_speed_size.rwidth() = 223; - - if (has_us_speed_limit) set_speed_size.rheight() += us_sign_height + sign_margin; - else if (has_eu_speed_limit) set_speed_size.rheight() += eu_sign_size + sign_margin; - - int top_radius = 32; - int bottom_radius = has_eu_speed_limit ? 100 : 32; - - QRect set_speed_rect(QPoint(60 + (default_size.width() - set_speed_size.width()) / 2, 45), set_speed_size); - if (is_cruise_set && cruiseAdjustment) { - float transition = qBound(0.0f, 4.0f * (cruiseAdjustment / setSpeed), 1.0f); - QColor min = whiteColor(75); - QColor max = vtscControllingCurve ? redColor(75) : greenColor(75); - - p.setPen(QPen(QColor::fromRgbF( - min.redF() + transition * (max.redF() - min.redF()), - min.greenF() + transition * (max.greenF() - min.greenF()), - min.blueF() + transition * (max.blueF() - min.blueF()) - ), 6)); - } else if (scene.reverse_cruise) { - p.setPen(QPen(QColor(0, 150, 255), 6)); - } else if (trafficModeActive) { - p.setPen(QPen(redColor(255), 6)); - } else { - p.setPen(QPen(whiteColor(75), 6)); - } - p.setBrush(blackColor(166)); - drawRoundedRect(p, set_speed_rect, top_radius, top_radius, bottom_radius, bottom_radius); - - // Draw MAX - QColor max_color = QColor(0x80, 0xd8, 0xa6, 0xff); - QColor set_speed_color = whiteColor(); - if (is_cruise_set) { - if (status == STATUS_DISENGAGED) { - max_color = whiteColor(); - } else if (status == STATUS_OVERRIDE) { - max_color = QColor(0x91, 0x9b, 0x95, 0xff); - } else if (speedLimit > 0) { - auto interp_color = [=](QColor c1, QColor c2, QColor c3) { - return speedLimit > 0 ? interpColor(setSpeed, {speedLimit + 5, speedLimit + 15, speedLimit + 25}, {c1, c2, c3}) : c1; - }; - max_color = interp_color(max_color, QColor(0xff, 0xe4, 0xbf), QColor(0xff, 0xbf, 0xbf)); - set_speed_color = interp_color(set_speed_color, QColor(0xff, 0x95, 0x00), QColor(0xff, 0x00, 0x00)); - } - } else { - max_color = QColor(0xa6, 0xa6, 0xa6, 0xff); - set_speed_color = QColor(0x72, 0x72, 0x72, 0xff); - } - p.setFont(InterFont(40, QFont::DemiBold)); - p.setPen(max_color); - p.drawText(set_speed_rect.adjusted(0, 27, 0, 0), Qt::AlignTop | Qt::AlignHCenter, tr("MAX")); - p.setFont(InterFont(90, QFont::Bold)); - p.setPen(set_speed_color); - p.drawText(set_speed_rect.adjusted(0, 77, 0, 0), Qt::AlignTop | Qt::AlignHCenter, setSpeedStr); - - const QRect sign_rect = set_speed_rect.adjusted(sign_margin, default_size.height(), -sign_margin, -sign_margin); - // US/Canada (MUTCD style) sign - if (has_us_speed_limit) { - p.setPen(Qt::NoPen); - p.setBrush(whiteColor()); - p.drawRoundedRect(sign_rect, 24, 24); - p.setPen(QPen(blackColor(), 6)); - p.drawRoundedRect(sign_rect.adjusted(9, 9, -9, -9), 16, 16); - - p.save(); - p.setOpacity(slcOverridden ? 0.25 : 1.0); - if (speedLimitController && showSLCOffset && !slcOverridden) { - p.setFont(InterFont(28, QFont::DemiBold)); - p.drawText(sign_rect.adjusted(0, 22, 0, 0), Qt::AlignTop | Qt::AlignHCenter, tr("LIMIT")); - p.setFont(InterFont(70, QFont::Bold)); - p.drawText(sign_rect.adjusted(0, 51, 0, 0), Qt::AlignTop | Qt::AlignHCenter, speedLimitStr); - p.setFont(InterFont(50, QFont::DemiBold)); - p.drawText(sign_rect.adjusted(0, 120, 0, 0), Qt::AlignTop | Qt::AlignHCenter, speedLimitOffsetStr); - } else { - p.setFont(InterFont(28, QFont::DemiBold)); - p.drawText(sign_rect.adjusted(0, 22, 0, 0), Qt::AlignTop | Qt::AlignHCenter, tr("SPEED")); - p.drawText(sign_rect.adjusted(0, 51, 0, 0), Qt::AlignTop | Qt::AlignHCenter, tr("LIMIT")); - p.setFont(InterFont(70, QFont::Bold)); - p.drawText(sign_rect.adjusted(0, 85, 0, 0), Qt::AlignTop | Qt::AlignHCenter, speedLimitStr); - } - p.restore(); - } - - // EU (Vienna style) sign - if (has_eu_speed_limit) { - p.setPen(Qt::NoPen); - p.setBrush(whiteColor()); - p.drawEllipse(sign_rect); - p.setPen(QPen(Qt::red, 20)); - p.drawEllipse(sign_rect.adjusted(16, 16, -16, -16)); - - p.save(); - p.setOpacity(slcOverridden ? 0.25 : 1.0); - p.setPen(blackColor()); - if (showSLCOffset) { - p.setFont(InterFont((speedLimitStr.size() >= 3) ? 60 : 70, QFont::Bold)); - p.drawText(sign_rect.adjusted(0, -25, 0, 0), Qt::AlignCenter, speedLimitStr); - p.setFont(InterFont(40, QFont::DemiBold)); - p.drawText(sign_rect.adjusted(0, 100, 0, 0), Qt::AlignTop | Qt::AlignHCenter, speedLimitOffsetStr); - } else { - p.setFont(InterFont((speedLimitStr.size() >= 3) ? 60 : 70, QFont::Bold)); - p.drawText(sign_rect, Qt::AlignCenter, speedLimitStr); - } - p.restore(); - } - p.restore(); - } - - // current speed - if (!(scene.hide_speed || fullMapOpen || showDriverCamera)) { - p.setFont(InterFont(176, QFont::Bold)); - drawText(p, rect().center().x(), 210, speedStr); - p.setFont(InterFont(66)); - drawText(p, rect().center().x(), 290, speedUnit, 200); - } - - p.restore(); -} - -void AnnotatedCameraWidget::drawText(QPainter &p, int x, int y, const QString &text, int alpha) { - QRect real_rect = p.fontMetrics().boundingRect(text); - real_rect.moveCenter({x, y - real_rect.height() / 2}); - - p.setPen(QColor(0xff, 0xff, 0xff, alpha)); - p.drawText(real_rect.x(), real_rect.bottom(), text); -} - -void AnnotatedCameraWidget::initializeGL() { - CameraWidget::initializeGL(); - qInfo() << "OpenGL version:" << QString((const char*)glGetString(GL_VERSION)); - qInfo() << "OpenGL vendor:" << QString((const char*)glGetString(GL_VENDOR)); - qInfo() << "OpenGL renderer:" << QString((const char*)glGetString(GL_RENDERER)); - qInfo() << "OpenGL language version:" << QString((const char*)glGetString(GL_SHADING_LANGUAGE_VERSION)); - - prev_draw_t = millis_since_boot(); - setBackgroundColor(bg_colors[STATUS_DISENGAGED]); -} - -void AnnotatedCameraWidget::updateFrameMat() { - CameraWidget::updateFrameMat(); - UIState *s = uiState(); - int w = width(), h = height(); - - s->fb_w = w; - s->fb_h = h; - - // Apply transformation such that video pixel coordinates match video - // 1) Put (0, 0) in the middle of the video - // 2) Apply same scaling as video - // 3) Put (0, 0) in top left corner of video - s->car_space_transform.reset(); - s->car_space_transform.translate(w / 2 - x_offset, h / 2 - y_offset) - .scale(zoom, zoom) - .translate(-intrinsic_matrix.v[2], -intrinsic_matrix.v[5]); -} - -void AnnotatedCameraWidget::drawLaneLines(QPainter &painter, const UIState *s) { - painter.save(); - - SubMaster &sm = *(s->sm); - - // lanelines - for (int i = 0; i < std::size(scene.lane_line_vertices); ++i) { - if (currentHolidayTheme != 0) { - painter.setBrush(std::get<3>(holidayThemeConfiguration[currentHolidayTheme]).begin()->second); - } else if (customColors != 0) { - painter.setBrush(std::get<3>(themeConfiguration[customColors]).begin()->second); - } else { - painter.setBrush(QColor::fromRgbF(1.0, 1.0, 1.0, std::clamp(scene.lane_line_probs[i], 0.0, 0.7))); - } - painter.drawPolygon(scene.lane_line_vertices[i]); - } - - // road edges - for (int i = 0; i < std::size(scene.road_edge_vertices); ++i) { - if (currentHolidayTheme != 0) { - painter.setBrush(std::get<3>(holidayThemeConfiguration[currentHolidayTheme]).begin()->second); - } else if (customColors != 0) { - painter.setBrush(std::get<3>(themeConfiguration[customColors]).begin()->second); - } else { - painter.setBrush(QColor::fromRgbF(1.0, 0, 0, std::clamp(1.0 - scene.road_edge_stds[i], 0.0, 1.0))); - } - painter.drawPolygon(scene.road_edge_vertices[i]); - } - - // paint path - QLinearGradient bg(0, height(), 0, 0); - if (sm["controlsState"].getControlsState().getExperimentalMode() || scene.acceleration_path) { - // The first half of track_vertices are the points for the right side of the path - // and the indices match the positions of accel from uiPlan - const auto &acceleration_const = sm["uiPlan"].getUiPlan().getAccel(); - const int max_len = std::min(scene.track_vertices.length() / 2, acceleration_const.size()); - - // Copy of the acceleration vector - std::vector acceleration; - for (int i = 0; i < acceleration_const.size(); i++) { - acceleration.push_back(acceleration_const[i]); - } - - for (int i = 0; i < max_len; ++i) { - // Some points are out of frame - if (scene.track_vertices[i].y() < 0 || scene.track_vertices[i].y() > height()) continue; - - // Flip so 0 is bottom of frame - float lin_grad_point = (height() - scene.track_vertices[i].y()) / height(); - - // If acceleration is between -0.2 and 0.2, resort to the theme color - if (std::abs(acceleration[i]) < 0.2 && (currentHolidayTheme != 0)) { - const auto &colorMap = std::get<3>(holidayThemeConfiguration[currentHolidayTheme]); - for (const auto &[position, brush] : colorMap) { - bg.setColorAt(position, brush.color()); - } - } else if (std::abs(acceleration[i]) < 0.2 && (customColors != 0)) { - const auto &colorMap = std::get<3>(themeConfiguration[customColors]); - for (const auto &[position, brush] : colorMap) { - bg.setColorAt(position, brush.color()); - } - } else { - // speed up: 120, slow down: 0 - float path_hue = fmax(fmin(60 + acceleration[i] * 35, 120), 0); - // FIXME: painter.drawPolygon can be slow if hue is not rounded - path_hue = int(path_hue * 100 + 0.5) / 100; - - float saturation = fmin(fabs(acceleration[i] * 1.5), 1); - float lightness = util::map_val(saturation, 0.0f, 1.0f, 0.95f, 0.62f); // lighter when grey - float alpha = util::map_val(lin_grad_point, 0.75f / 2.f, 0.75f, 0.4f, 0.0f); // matches previous alpha fade - bg.setColorAt(lin_grad_point, QColor::fromHslF(path_hue / 360., saturation, lightness, alpha)); - - // Skip a point, unless next is last - i += (i + 2) < max_len ? 1 : 0; - } - } - - } else if (currentHolidayTheme != 0) { - const auto &colorMap = std::get<3>(holidayThemeConfiguration[currentHolidayTheme]); - for (const auto &[position, brush] : colorMap) { - bg.setColorAt(position, brush.color()); - } - } else if (customColors != 0) { - const auto &colorMap = std::get<3>(themeConfiguration[customColors]); - for (const auto &[position, brush] : colorMap) { - bg.setColorAt(position, brush.color()); - } - } else { - bg.setColorAt(0.0, QColor::fromHslF(148 / 360., 0.94, 0.51, 0.4)); - bg.setColorAt(0.5, QColor::fromHslF(112 / 360., 1.0, 0.68, 0.35)); - bg.setColorAt(1.0, QColor::fromHslF(112 / 360., 1.0, 0.68, 0.0)); - } - - painter.setBrush(bg); - painter.drawPolygon(scene.track_vertices); - - // Create new path with track vertices and track edge vertices - QPainterPath path; - path.addPolygon(scene.track_vertices); - path.addPolygon(scene.track_edge_vertices); - - // Paint path edges - QLinearGradient pe(0, height(), 0, 0); - if (alwaysOnLateralActive) { - pe.setColorAt(0.0, QColor::fromHslF(178 / 360., 0.90, 0.38, 1.0)); - pe.setColorAt(0.5, QColor::fromHslF(178 / 360., 0.90, 0.38, 0.5)); - pe.setColorAt(1.0, QColor::fromHslF(178 / 360., 0.90, 0.38, 0.1)); - } else if (conditionalStatus == 1 || conditionalStatus == 3) { - pe.setColorAt(0.0, QColor::fromHslF(58 / 360., 1.00, 0.50, 1.0)); - pe.setColorAt(0.5, QColor::fromHslF(58 / 360., 1.00, 0.50, 0.5)); - pe.setColorAt(1.0, QColor::fromHslF(58 / 360., 1.00, 0.50, 0.1)); - } else if (experimentalMode) { - pe.setColorAt(0.0, QColor::fromHslF(25 / 360., 0.71, 0.50, 1.0)); - pe.setColorAt(0.5, QColor::fromHslF(25 / 360., 0.71, 0.50, 0.5)); - pe.setColorAt(1.0, QColor::fromHslF(25 / 360., 0.71, 0.50, 0.1)); - } else if (trafficModeActive) { - pe.setColorAt(0.0, QColor::fromHslF(355 / 360., 0.71, 0.46, 1.0)); - pe.setColorAt(0.5, QColor::fromHslF(355 / 360., 0.71, 0.46, 0.5)); - pe.setColorAt(1.0, QColor::fromHslF(355 / 360., 0.71, 0.46, 0.1)); - } else if (scene.navigate_on_openpilot) { - pe.setColorAt(0.0, QColor::fromHslF(205 / 360., 0.85, 0.56, 1.0)); - pe.setColorAt(0.5, QColor::fromHslF(205 / 360., 0.85, 0.56, 0.5)); - pe.setColorAt(1.0, QColor::fromHslF(205 / 360., 0.85, 0.56, 0.1)); - } else if (currentHolidayTheme != 0) { - const auto &colorMap = std::get<3>(holidayThemeConfiguration[currentHolidayTheme]); - for (const auto &[position, brush] : colorMap) { - QColor darkerColor = brush.color().darker(120); - pe.setColorAt(position, darkerColor); - } - } else if (customColors != 0) { - const auto &colorMap = std::get<3>(themeConfiguration[customColors]); - for (const auto &[position, brush] : colorMap) { - QColor darkerColor = brush.color().darker(120); - pe.setColorAt(position, darkerColor); - } - } else { - pe.setColorAt(0.0, QColor::fromHslF(148 / 360., 0.94, 0.51, 1.0)); - pe.setColorAt(0.5, QColor::fromHslF(112 / 360., 1.00, 0.68, 0.5)); - pe.setColorAt(1.0, QColor::fromHslF(112 / 360., 1.00, 0.68, 0.1)); - } - - painter.setBrush(pe); - painter.drawPath(path); - - // Paint blindspot path - if (scene.blind_spot_path) { - QLinearGradient bs(0, height(), 0, 0); - if (blindSpotLeft || blindSpotRight) { - bs.setColorAt(0.0, QColor::fromHslF(0 / 360., 0.75, 0.50, 0.6)); - bs.setColorAt(0.5, QColor::fromHslF(0 / 360., 0.75, 0.50, 0.4)); - bs.setColorAt(1.0, QColor::fromHslF(0 / 360., 0.75, 0.50, 0.2)); - } - - painter.setBrush(bs); - if (blindSpotLeft) { - painter.drawPolygon(scene.track_adjacent_vertices[4]); - } - if (blindSpotRight) { - painter.drawPolygon(scene.track_adjacent_vertices[5]); - } - } - - // Paint adjacent lane paths - if (scene.adjacent_path && (laneWidthLeft != 0 || laneWidthRight != 0)) { - // Set up the units - double distanceValue = is_metric ? 1.0 : METER_TO_FOOT; - QString unit_d = is_metric ? " meters" : " feet"; - - // Declare the lane width thresholds - constexpr float minLaneWidth = 2.0f; - constexpr float maxLaneWidth = 4.0f; - - // Set gradient colors based on laneWidth and blindspot - auto setGradientColors = [](QLinearGradient &gradient, float laneWidth, bool blindspot) { - // Make the path red for smaller paths or if there's a car in the blindspot and green for larger paths - double hue = (laneWidth < minLaneWidth || laneWidth > maxLaneWidth || blindspot) - ? 0.0 : 120.0 * (laneWidth - minLaneWidth) / (maxLaneWidth - minLaneWidth); - double hue_ratio = hue / 360.0; - gradient.setColorAt(0.0, QColor::fromHslF(hue_ratio, 0.75, 0.50, 0.6)); - gradient.setColorAt(0.5, QColor::fromHslF(hue_ratio, 0.75, 0.50, 0.4)); - gradient.setColorAt(1.0, QColor::fromHslF(hue_ratio, 0.75, 0.50, 0.2)); - }; - - // Paint the lanes - auto paintLane = [&](QPainter &painter, const QPolygonF &lane, float laneWidth, bool blindspot) { - QLinearGradient gradient(0, height(), 0, 0); - setGradientColors(gradient, laneWidth, blindspot); - - painter.setFont(InterFont(30, QFont::DemiBold)); - painter.setBrush(gradient); - painter.setPen(Qt::transparent); - painter.drawPolygon(lane); - painter.setPen(Qt::white); - - QRectF boundingRect = lane.boundingRect(); - if (scene.adjacent_path_metrics) { - painter.drawText(boundingRect.center(), - blindspot ? "Vehicle in blind spot" : - QString("%1%2").arg(laneWidth * distanceValue, 0, 'f', 2).arg(unit_d)); - } - painter.setPen(Qt::NoPen); - }; - - paintLane(painter, scene.track_adjacent_vertices[4], laneWidthLeft, blindSpotLeft); - paintLane(painter, scene.track_adjacent_vertices[5], laneWidthRight, blindSpotRight); - } - - painter.restore(); -} - -void AnnotatedCameraWidget::drawDriverState(QPainter &painter, const UIState *s) { - painter.save(); - - // base icon - int offset = UI_BORDER_SIZE + btn_size / 2; - offset += alwaysOnLateral || conditionalExperimental || roadNameUI ? 25 : 0; - int x = rightHandDM ? width() - offset : offset; - x += onroadAdjustableProfiles ? 250 : 0; - int y = height() - offset; - float opacity = dmActive ? 0.65 : 0.2; - drawIcon(painter, QPoint(x, y), dm_img, blackColor(70), opacity); - - // face - QPointF face_kpts_draw[std::size(default_face_kpts_3d)]; - float kp; - for (int i = 0; i < std::size(default_face_kpts_3d); ++i) { - kp = (scene.face_kpts_draw[i].v[2] - 8) / 120 + 1.0; - face_kpts_draw[i] = QPointF(scene.face_kpts_draw[i].v[0] * kp + x, scene.face_kpts_draw[i].v[1] * kp + y); - } - - painter.setPen(QPen(QColor::fromRgbF(1.0, 1.0, 1.0, opacity), 5.2, Qt::SolidLine, Qt::RoundCap)); - painter.drawPolyline(face_kpts_draw, std::size(default_face_kpts_3d)); - - // tracking arcs - const int arc_l = 133; - const float arc_t_default = 6.7; - const float arc_t_extend = 12.0; - QColor arc_color = QColor::fromRgbF(0.545 - 0.445 * s->engaged(), - 0.545 + 0.4 * s->engaged(), - 0.545 - 0.285 * s->engaged(), - 0.4 * (1.0 - dm_fade_state)); - float delta_x = -scene.driver_pose_sins[1] * arc_l / 2; - float delta_y = -scene.driver_pose_sins[0] * arc_l / 2; - painter.setPen(QPen(arc_color, arc_t_default+arc_t_extend*fmin(1.0, scene.driver_pose_diff[1] * 5.0), Qt::SolidLine, Qt::RoundCap)); - painter.drawArc(QRectF(std::fmin(x + delta_x, x), y - arc_l / 2, fabs(delta_x), arc_l), (scene.driver_pose_sins[1]>0 ? 90 : -90) * 16, 180 * 16); - painter.setPen(QPen(arc_color, arc_t_default+arc_t_extend*fmin(1.0, scene.driver_pose_diff[0] * 5.0), Qt::SolidLine, Qt::RoundCap)); - painter.drawArc(QRectF(x - arc_l / 2, std::fmin(y + delta_y, y), arc_l, fabs(delta_y)), (scene.driver_pose_sins[0]>0 ? 0 : 180) * 16, 180 * 16); - - painter.restore(); -} - -void AnnotatedCameraWidget::drawLead(QPainter &painter, const cereal::RadarState::LeadData::Reader &lead_data, const QPointF &vd) { - painter.save(); - - const float speedBuff = customColors ? 25. : 10.; // Make the center of the chevron appear sooner if a custom theme is active - const float leadBuff = customColors ? 100. : 40.; // Make the center of the chevron appear sooner if a custom theme is active - const float d_rel = lead_data.getDRel(); - const float v_rel = lead_data.getVRel(); - - float fillAlpha = 0; - if (d_rel < leadBuff) { - fillAlpha = 255 * (1.0 - (d_rel / leadBuff)); - if (v_rel < 0) { - fillAlpha += 255 * (-1 * (v_rel / speedBuff)); - } - fillAlpha = (int)(fmin(fillAlpha, 255)); - } - - float sz = std::clamp((25 * 30) / (d_rel / 3 + 30), 15.0f, 30.0f) * 2.35; - float x = std::clamp((float)vd.x(), 0.f, width() - sz / 2); - float y = std::fmin(height() - sz * .6, (float)vd.y()); - - float g_xo = sz / 5; - float g_yo = sz / 10; - - QPointF glow[] = {{x + (sz * 1.35) + g_xo, y + sz + g_yo}, {x, y - g_yo}, {x - (sz * 1.35) - g_xo, y + sz + g_yo}}; - painter.setBrush(QColor(218, 202, 37, 255)); - painter.drawPolygon(glow, std::size(glow)); - - // chevron - QPointF chevron[] = {{x + (sz * 1.25), y + sz}, {x, y}, {x - (sz * 1.25), y + sz}}; - if (currentHolidayTheme != 0) { - painter.setBrush(std::get<3>(holidayThemeConfiguration[currentHolidayTheme]).begin()->second); - } else if (customColors != 0) { - painter.setBrush(std::get<3>(themeConfiguration[customColors]).begin()->second); - } else { - painter.setBrush(redColor(fillAlpha)); - } - painter.drawPolygon(chevron, std::size(chevron)); - - // Add lead info - if (leadInfo) { - // Declare the variables - float lead_speed = std::max(lead_data.getVLead(), 0.0f); // Ensure lead speed doesn't go under 0 m/s cause that's dumb - - // Form the text and center it below the chevron - painter.setPen(Qt::white); - painter.setFont(InterFont(35, QFont::Bold)); - - QString text = QString("%1 %2 | %3 %4") - .arg(qRound(d_rel * distanceConversion)) - .arg(leadDistanceUnit) - .arg(qRound(lead_speed * speedConversion)) - .arg(leadSpeedUnit); - - // Calculate the text starting position - QFontMetrics metrics(painter.font()); - int middle_x = (chevron[2].x() + chevron[0].x()) / 2; - int textWidth = metrics.horizontalAdvance(text); - painter.drawText(middle_x - textWidth / 2, chevron[0].y() + metrics.height() + 5, text); - } - - painter.restore(); -} - -void AnnotatedCameraWidget::paintGL() { -} - -void AnnotatedCameraWidget::paintEvent(QPaintEvent *event) { - UIState *s = uiState(); - SubMaster &sm = *(s->sm); - QPainter painter(this); - const double start_draw_t = millis_since_boot(); - const cereal::ModelDataV2::Reader &model = sm["modelV2"].getModelV2(); - - // draw camera frame - { - std::lock_guard lk(frame_lock); - - if (frames.empty()) { - if (skip_frame_count > 0) { - skip_frame_count--; - qDebug() << "skipping frame, not ready"; - return; - } - } else { - // skip drawing up to this many frames if we're - // missing camera frames. this smooths out the - // transitions from the narrow and wide cameras - skip_frame_count = 5; - } - - // Wide or narrow cam dependent on speed - bool has_wide_cam = available_streams.count(VISION_STREAM_WIDE_ROAD); - if (has_wide_cam && cameraView == 0) { - float v_ego = sm["carState"].getCarState().getVEgo(); - if ((v_ego < 10) || available_streams.size() == 1) { - wide_cam_requested = true; - } else if (v_ego > 15) { - wide_cam_requested = false; - } - wide_cam_requested = wide_cam_requested && sm["controlsState"].getControlsState().getExperimentalMode(); - // for replay of old routes, never go to widecam - wide_cam_requested = wide_cam_requested && s->scene.calibration_wide_valid; - } - CameraWidget::setStreamType(cameraView == 3 || showDriverCamera ? VISION_STREAM_DRIVER : - cameraView == 2 || wide_cam_requested ? VISION_STREAM_WIDE_ROAD : - VISION_STREAM_ROAD); - } - - s->scene.wide_cam = CameraWidget::getStreamType() == VISION_STREAM_WIDE_ROAD; - if (s->scene.calibration_valid) { - auto calib = s->scene.wide_cam ? s->scene.view_from_wide_calib : s->scene.view_from_calib; - CameraWidget::updateCalibration(calib); - } else { - CameraWidget::updateCalibration(DEFAULT_CALIBRATION); - } - painter.beginNativePainting(); - CameraWidget::setFrameId(model.getFrameId()); - CameraWidget::paintGL(); - painter.endNativePainting(); - - painter.setRenderHint(QPainter::Antialiasing); - painter.setPen(Qt::NoPen); - - if (s->scene.world_objects_visible && !showDriverCamera) { - update_model(s, model, sm["uiPlan"].getUiPlan()); - drawLaneLines(painter, s); - - if (s->scene.longitudinal_control && sm.rcv_frame("radarState") > s->scene.started_frame && !scene.hide_lead_marker) { - auto radar_state = sm["radarState"].getRadarState(); - update_leads(s, radar_state, model.getPosition()); - auto lead_one = radar_state.getLeadOne(); - auto lead_two = radar_state.getLeadTwo(); - if (lead_one.getStatus()) { - drawLead(painter, lead_one, s->scene.lead_vertices[0]); - } - if (lead_two.getStatus() && (std::abs(lead_one.getDRel() - lead_two.getDRel()) > 3.0)) { - drawLead(painter, lead_two, s->scene.lead_vertices[1]); - } - } - } - - // DMoji - if (!hideBottomIcons && (sm.rcv_frame("driverStateV2") > s->scene.started_frame)) { - update_dmonitoring(s, sm["driverStateV2"].getDriverStateV2(), dm_fade_state, rightHandDM); - drawDriverState(painter, s); - } - - drawHud(painter); - - double cur_draw_t = millis_since_boot(); - double dt = cur_draw_t - prev_draw_t; - fps = fps_filter.update(1. / dt * 1000); - if (fps < 15) { - LOGW("slow frame rate: %.2f fps", fps); - } - prev_draw_t = cur_draw_t; - - // publish debug msg - MessageBuilder msg; - auto m = msg.initEvent().initUiDebug(); - m.setDrawTimeMillis(cur_draw_t - start_draw_t); - pm->send("uiDebug", msg); - - // Update FrogPilot widgets - updateFrogPilotWidgets(painter); -} - -void AnnotatedCameraWidget::showEvent(QShowEvent *event) { - CameraWidget::showEvent(event); - - ui_update_params(uiState()); - prev_draw_t = millis_since_boot(); -} - -// FrogPilot widgets -void AnnotatedCameraWidget::initializeFrogPilotWidgets() { - bottom_layout = new QHBoxLayout(); - - personality_btn = new PersonalityButton(this); - bottom_layout->addWidget(personality_btn); - - QSpacerItem *spacer = new QSpacerItem(0, 0, QSizePolicy::Expanding, QSizePolicy::Minimum); - bottom_layout->addItem(spacer); - - compass_img = new Compass(this); - bottom_layout->addWidget(compass_img); - - map_settings_btn_bottom = new MapSettingsButton(this); - bottom_layout->addWidget(map_settings_btn_bottom); - - main_layout->addLayout(bottom_layout); - - // Custom themes configuration - themeConfiguration = { - {1, {"frog_theme", 4, QColor(23, 134, 68, 242), {{0.0, QBrush(QColor::fromHslF(144 / 360., 0.71, 0.31, 0.9))}, - {0.5, QBrush(QColor::fromHslF(144 / 360., 0.71, 0.31, 0.5))}, - {1.0, QBrush(QColor::fromHslF(144 / 360., 0.71, 0.31, 0.1))}}}}, - {2, {"tesla_theme", 4, QColor(0, 72, 255, 255), {{0.0, QBrush(QColor::fromHslF(223 / 360., 1.0, 0.5, 0.9))}, - {0.5, QBrush(QColor::fromHslF(223 / 360., 1.0, 0.5, 0.5))}, - {1.0, QBrush(QColor::fromHslF(223 / 360., 1.0, 0.5, 0.1))}}}}, - {3, {"stalin_theme", 6, QColor(255, 0, 0, 255), {{0.0, QBrush(QColor::fromHslF(0 / 360., 1.0, 0.5, 0.9))}, - {0.5, QBrush(QColor::fromHslF(0 / 360., 1.0, 0.5, 0.5))}, - {1.0, QBrush(QColor::fromHslF(0 / 360., 1.0, 0.5, 0.1))}}}}, - }; - - // Holiday themes configuration - holidayThemeConfiguration = { - {1, {"april_fools", 4, QColor(255, 165, 0, 255), {{0.0, QBrush(QColor::fromHslF(39 / 360., 1.0, 0.5, 0.9))}, - {0.5, QBrush(QColor::fromHslF(39 / 360., 1.0, 0.5, 0.5))}, - {1.0, QBrush(QColor::fromHslF(39 / 360., 1.0, 0.5, 0.1))}}}}, - {2, {"christmas", 4, QColor(0, 72, 255, 255), {{0.0, QBrush(QColor::fromHslF(223 / 360., 1.0, 0.5, 0.9))}, - {0.5, QBrush(QColor::fromHslF(223 / 360., 1.0, 0.5, 0.5))}, - {1.0, QBrush(QColor::fromHslF(223 / 360., 1.0, 0.5, 0.1))}}}}, - {3, {"cinco_de_mayo", 6, QColor(255, 0, 0, 255), {{0.0, QBrush(QColor::fromHslF(0 / 360., 1.0, 0.5, 0.9))}, - {0.5, QBrush(QColor::fromHslF(0 / 360., 1.0, 0.5, 0.5))}, - {1.0, QBrush(QColor::fromHslF(0 / 360., 1.0, 0.5, 0.1))}}}}, - {4, {"easter", 4, QColor(200, 150, 200, 255), {{0.0, QBrush(QColor::fromHslF(300 / 360., 0.31, 0.69, 0.9))}, - {0.5, QBrush(QColor::fromHslF(300 / 360., 0.31, 0.69, 0.5))}, - {1.0, QBrush(QColor::fromHslF(300 / 360., 0.31, 0.69, 0.1))}}}}, - {5, {"fourth_of_july", 4, QColor(0, 72, 255, 255), {{0.0, QBrush(QColor::fromHslF(223 / 360., 1.0, 0.5, 0.9))}, - {0.5, QBrush(QColor::fromHslF(223 / 360., 1.0, 0.5, 0.5))}, - {1.0, QBrush(QColor::fromHslF(223 / 360., 1.0, 0.5, 0.1))}}}}, - {6, {"halloween", 6, QColor(255, 0, 0, 255), {{0.0, QBrush(QColor::fromHslF(0 / 360., 1.0, 0.5, 0.9))}, - {0.5, QBrush(QColor::fromHslF(0 / 360., 1.0, 0.5, 0.5))}, - {1.0, QBrush(QColor::fromHslF(0 / 360., 1.0, 0.5, 0.1))}}}}, - {7, {"new_years_day", 4, QColor(23, 134, 68, 242), {{0.0, QBrush(QColor::fromHslF(144 / 360., 0.71, 0.31, 0.9))}, - {0.5, QBrush(QColor::fromHslF(144 / 360., 0.71, 0.31, 0.5))}, - {1.0, QBrush(QColor::fromHslF(144 / 360., 0.71, 0.31, 0.1))}}}}, - {8, {"st_patricks_day", 4, QColor(0, 128, 0, 255), {{0.0, QBrush(QColor::fromHslF(120 / 360., 1.0, 0.25, 0.9))}, - {0.5, QBrush(QColor::fromHslF(120 / 360., 1.0, 0.25, 0.5))}, - {1.0, QBrush(QColor::fromHslF(120 / 360., 1.0, 0.25, 0.1))}}}}, - {9, {"thanksgiving", 6, QColor(255, 0, 0, 255), {{0.0, QBrush(QColor::fromHslF(0 / 360., 1.0, 0.5, 0.9))}, - {0.5, QBrush(QColor::fromHslF(0 / 360., 1.0, 0.5, 0.5))}, - {1.0, QBrush(QColor::fromHslF(0 / 360., 1.0, 0.5, 0.1))}}}}, - {10, {"valentines_day", 4, QColor(23, 134, 68, 242), {{0.0, QBrush(QColor::fromHslF(144 / 360., 0.71, 0.31, 0.9))}, - {0.5, QBrush(QColor::fromHslF(144 / 360., 0.71, 0.31, 0.5))}, - {1.0, QBrush(QColor::fromHslF(144 / 360., 0.71, 0.31, 0.1))}}}}, - {11, {"world_frog_day", 4, QColor(23, 134, 68, 242), {{0.0, QBrush(QColor::fromHslF(144 / 360., 0.71, 0.31, 0.9))}, - {0.5, QBrush(QColor::fromHslF(144 / 360., 0.71, 0.31, 0.5))}, - {1.0, QBrush(QColor::fromHslF(144 / 360., 0.71, 0.31, 0.1))}}}}, - }; - - // Initialize the timer for the turn signal animation - animationTimer = new QTimer(this); - connect(animationTimer, &QTimer::timeout, this, [this] { - animationFrameIndex = (animationFrameIndex + 1) % totalFrames; - }); - - // Initialize the timer for the screen recorder - QTimer *record_timer = new QTimer(this); - connect(record_timer, &QTimer::timeout, this, [this]() { - if (recorder_btn) { - recorder_btn->update_screen(); - } - }); - record_timer->start(1000 / UI_FREQ); -} - -void AnnotatedCameraWidget::updateFrogPilotWidgets(QPainter &p) { - alwaysOnLateral = scene.always_on_lateral && !scene.hide_aol_status_bar; - alwaysOnLateralActive = scene.always_on_lateral_active; - - blindSpotLeft = scene.blind_spot_left; - blindSpotRight = scene.blind_spot_right; - - cameraView = scene.camera_view; - - compass = scene.compass; - - conditionalExperimental = scene.conditional_experimental && !scene.hide_cem_status_bar; - conditionalSpeed = scene.conditional_speed; - conditionalSpeedLead = scene.conditional_speed_lead; - conditionalStatus = scene.conditional_status; - - bool disableSmoothing = vtscControllingCurve ? scene.disable_smoothing_vtsc : scene.disable_smoothing_mtsc; - cruiseAdjustment = disableSmoothing ? fmax(setSpeed - scene.adjusted_cruise, 0) : fmax(0.25 * (setSpeed - scene.adjusted_cruise) + 0.75 * cruiseAdjustment - 1, 0); - vtscControllingCurve = scene.vtsc_controlling_curve; - - customColors = scene.custom_colors; - - experimentalMode = scene.experimental_mode; - - laneWidthLeft = scene.lane_width_left; - laneWidthRight = scene.lane_width_right; - - leadInfo = scene.lead_info; - obstacleDistance = scene.obstacle_distance; - obstacleDistanceStock = scene.obstacle_distance_stock; - - mapOpen = scene.map_open; - fullMapOpen = mapOpen && scene.full_map; - - onroadAdjustableProfiles = scene.personalities_via_screen; - - pedalsOnUI = scene.pedals_on_ui; - - rightHandDrive = scene.right_hand_drive; - - roadNameUI = scene.road_name_ui; - - showDriverCamera = scene.show_driver_camera; - - speedLimitController = scene.speed_limit_controller; - showSLCOffset = speedLimitController && scene.show_slc_offset; - slcOverridden = speedLimitController && scene.speed_limit_overridden; - slcSpeedLimit = scene.speed_limit; - slcSpeedLimitOffset = scene.speed_limit_offset * (is_metric ? MS_TO_KPH : MS_TO_MPH); - useViennaSLCSign = scene.use_vienna_slc_sign; - - trafficModeActive = scene.traffic_mode && scene.traffic_mode_active; - - turnSignalLeft = scene.turn_signal_left; - turnSignalRight = scene.turn_signal_right; - - if (!(showDriverCamera || fullMapOpen)) { - if (leadInfo) { - drawLeadInfo(p); - } - - if (alwaysOnLateral || conditionalExperimental || roadNameUI) { - drawStatusBar(p); - } - - if (customSignals && (turnSignalLeft || turnSignalRight)) { - if (!animationTimer->isActive()) { - animationTimer->start(totalFrames * 11); // 440 milliseconds per loop; syncs up perfectly with my 2019 Lexus ES 350 turn signal clicks - } - drawTurnSignals(p); - } else if (animationTimer->isActive()) { - animationTimer->stop(); - } - - if (scene.speed_limit_changed) { - drawSLCConfirmation(p); - } - } - - bool enableCompass = compass && !hideBottomIcons; - compass_img->setVisible(enableCompass); - if (enableCompass) { - compass_img->updateState(scene.bearing_deg); - bottom_layout->setAlignment(compass_img, (rightHandDM ? Qt::AlignLeft : Qt::AlignRight)); - } - - bool enablePedalIcons = pedalsOnUI && !(fullMapOpen || showDriverCamera); - pedal_icons->setVisible(enablePedalIcons); - if (enablePedalIcons) { - pedal_icons->updateState(); - } - - bool enablePersonalityButton = onroadAdjustableProfiles && !hideBottomIcons; - personality_btn->setVisible(enablePersonalityButton); - if (enablePersonalityButton) { - if (paramsMemory.getBool("PersonalityChangedViaWheel")) { - personality_btn->checkUpdate(); - } - bottom_layout->setAlignment(personality_btn, (rightHandDM ? Qt::AlignRight : Qt::AlignLeft)); - } - - map_settings_btn_bottom->setEnabled(map_settings_btn->isEnabled()); - if (map_settings_btn_bottom->isEnabled()) { - map_settings_btn_bottom->setVisible(!hideBottomIcons && !compass && !scene.hide_map_icon); - bottom_layout->setAlignment(map_settings_btn_bottom, rightHandDM ? Qt::AlignLeft : Qt::AlignRight); - } - - recorder_btn->setVisible(scene.screen_recorder && !(mapOpen || showDriverCamera)); - - // Update the turn signal animation images upon toggle change - if (customSignals != scene.custom_signals || currentHolidayTheme != scene.current_holiday_theme) { - currentHolidayTheme = scene.current_holiday_theme; - customSignals = scene.custom_signals; - - if (currentHolidayTheme != 0) { - auto themeConfigIt = holidayThemeConfiguration.find(currentHolidayTheme); - QString themeConfigKey = themeConfigIt != holidayThemeConfiguration.end() ? std::get<0>(themeConfigIt->second) : ""; - themePath = QString("../frogpilot/assets/holiday_themes/%1/images").arg(themeConfigKey); - availableImages = std::get<1>(themeConfigIt->second); - } else { - auto themeConfigIt = themeConfiguration.find(customSignals); - QString themeConfigKey = themeConfigIt != themeConfiguration.end() ? std::get<0>(themeConfigIt->second) : ""; - themePath = QString("../frogpilot/assets/custom_themes/%1/images").arg(themeConfigKey); - availableImages = std::get<1>(themeConfigIt->second); - } - - for (int i = 1; i <= totalFrames; ++i) { - int imageIndex = ((i - 1) % availableImages) + 1; - QString imagePath = themePath + QString("/turn_signal_%1.png").arg(imageIndex); - imagePaths.push_back(imagePath); - } - - signalImgVector.clear(); - signalImgVector.reserve(2 * imagePaths.size()); // Reserve space for both regular and flipped images - for (const QString &imagePath : imagePaths) { - QPixmap pixmap(imagePath); - signalImgVector.push_back(pixmap); // Regular image - signalImgVector.push_back(pixmap.transformed(QTransform().scale(-1, 1))); // Flipped image - } - - signalImgVector.push_back(QPixmap(themePath + "/turn_signal_1_red.png")); // Regular blindspot image - signalImgVector.push_back(QPixmap(themePath + "/turn_signal_1_red.png").transformed(QTransform().scale(-1, 1))); // Flipped blindspot image - } -} - -Compass::Compass(QWidget *parent) : QWidget(parent) { - setFixedSize(btn_size * 1.5, btn_size * 1.5); - - compassSize = btn_size; - circleOffset = compassSize / 2; - degreeLabelOffset = circleOffset + 25; - innerCompass = compassSize / 2; - - x = (btn_size * 1.5) / 2 + 20; - y = (btn_size * 1.5) / 2; - - compassInnerImg = loadPixmap("../frogpilot/assets/other_images/compass_inner.png", QSize(compassSize / 1.75, compassSize / 1.75)); - - staticElements = QPixmap(size()); - staticElements.fill(Qt::transparent); - QPainter p(&staticElements); - - p.setRenderHints(QPainter::Antialiasing | QPainter::TextAntialiasing); - - // Configure the circles - QPen whitePen(Qt::white, 2); - p.setPen(whitePen); - - // Draw the circle background and white inner circle - p.setOpacity(1.0); - p.setBrush(QColor(0, 0, 0, 100)); - p.drawEllipse(x - circleOffset, y - circleOffset, circleOffset * 2, circleOffset * 2); - - // Draw the white circles - p.setBrush(Qt::NoBrush); - p.drawEllipse(x - (innerCompass + 5), y - (innerCompass + 5), (innerCompass + 5) * 2, (innerCompass + 5) * 2); - p.drawEllipse(x - degreeLabelOffset, y - degreeLabelOffset, degreeLabelOffset * 2, degreeLabelOffset * 2); - - // Draw the black background for the bearing degrees - QPainterPath outerCircle, innerCircle; - outerCircle.addEllipse(x - degreeLabelOffset, y - degreeLabelOffset, degreeLabelOffset * 2, degreeLabelOffset * 2); - innerCircle.addEllipse(x - circleOffset, y - circleOffset, compassSize, compassSize); - p.fillPath(outerCircle.subtracted(innerCircle), Qt::black); - - // Draw the static degree lines - for (int i = 0; i < 360; i += 15) { - bool isCardinalDirection = i % 90 == 0; - int lineLength = isCardinalDirection ? 15 : 10; - p.setPen(QPen(Qt::white, isCardinalDirection ? 3 : 1)); - p.save(); - p.translate(x, y); - p.rotate(i); - p.drawLine(0, -(compassSize / 2 - lineLength), 0, -(compassSize / 2)); - p.restore(); - } -} - -void Compass::updateState(int bearing_deg) { - if (bearingDeg != bearing_deg) { - update(); - bearingDeg = bearing_deg; - } -} - -void Compass::paintEvent(QPaintEvent *event) { - QPainter p(this); - p.setRenderHints(QPainter::Antialiasing | QPainter::TextAntialiasing); - - // Normalize bearingDeg to be in the range [0, 360) - bearingDeg = fmod(bearingDeg, 360); - if (bearingDeg < 0) { - bearingDeg += 360; - } - - // Draw static elements - p.drawPixmap(0, 0, staticElements); - - // Rotate and draw the compassInnerImg image - p.translate(x, y); - p.rotate(bearingDeg); - p.drawPixmap(-compassInnerImg.width() / 2, -compassInnerImg.height() / 2, compassInnerImg); - p.rotate(-bearingDeg); - p.translate(-x, -y); - - // Draw the bearing degree numbers - QFont font = InterFont(10, QFont::Normal); - for (int i = 0; i < 360; i += 15) { - bool isBold = abs(i - bearingDeg) <= 7; - font.setWeight(isBold ? QFont::Bold : QFont::Normal); - p.setFont(font); - p.setPen(QPen(Qt::white, i % 90 == 0 ? 2 : 1)); - - p.save(); - p.translate(x, y); - p.rotate(i); - p.drawLine(0, -(compassSize / 2 - (i % 90 == 0 ? 12 : 8)), 0, -(compassSize / 2)); - p.translate(0, -(compassSize / 2 + 12)); - p.rotate(-i); - p.drawText(QRect(-20, -10, 40, 20), Qt::AlignCenter, QString::number(i)); - p.restore(); - } - - // Draw cardinal directions - p.setFont(InterFont(20, QFont::Bold)); - std::map, int, QColor>> directionInfo = { - {"N", {{292.5, 67.5}, Qt::AlignTop | Qt::AlignHCenter, Qt::white}}, - {"E", {{22.5, 157.5}, Qt::AlignRight | Qt::AlignVCenter, Qt::white}}, - {"S", {{112.5, 247.5}, Qt::AlignBottom | Qt::AlignHCenter, Qt::white}}, - {"W", {{202.5, 337.5}, Qt::AlignLeft | Qt::AlignVCenter, Qt::white}} - }; - int directionOffset = 20; - - for (auto &item : directionInfo) { - QString direction = item.first; - auto &[range, alignmentFlag, color] = item.second; - auto &[minRange, maxRange] = range; - - QRect textRect(x - innerCompass + directionOffset, y - innerCompass + directionOffset, innerCompass * 2 - 2 * directionOffset, innerCompass * 2 - 2 * directionOffset); - - bool isInRange = false; - if (minRange > maxRange) { - isInRange = bearingDeg >= minRange || bearingDeg <= maxRange; - } else { - isInRange = bearingDeg >= minRange && bearingDeg <= maxRange; - } - - p.setOpacity(isInRange ? 1.0 : 0.2); - p.setPen(QPen(color)); - p.drawText(textRect, alignmentFlag, direction); - } -} - -void AnnotatedCameraWidget::drawLeadInfo(QPainter &p) { - // Declare the variables - static QElapsedTimer timer; - static bool isFiveSecondsPassed = false; - constexpr int maxAccelDuration = 5000; - - // Constants for units and conversions - QString accelerationUnit = " m/s²"; - leadDistanceUnit = mapOpen ? "m" : "meters"; - leadSpeedUnit = "m/2"; - - float accelerationConversion = 1.0f; - distanceConversion = 1.0f; - speedConversion = 1.0f; - - if (!scene.use_si) { - if (is_metric) { - // Metric conversion - leadSpeedUnit = "kph"; - speedConversion = MS_TO_KPH; - } else { - // US imperial conversion - accelerationUnit = " ft/s²"; - leadDistanceUnit = mapOpen ? "ft" : "feet"; - leadSpeedUnit = "mph"; - - accelerationConversion = METER_TO_FOOT; - distanceConversion = METER_TO_FOOT; - speedConversion = MS_TO_MPH; - } - } - - // Update acceleration - double currentAcceleration = std::round(scene.acceleration * 100) / 100; - static double maxAcceleration = 0.0; - - if (currentAcceleration > maxAcceleration && (status == STATUS_ENGAGED || status == STATUS_TRAFFIC_MODE_ACTIVE)) { - maxAcceleration = currentAcceleration; - isFiveSecondsPassed = false; - timer.start(); - } else { - isFiveSecondsPassed = timer.hasExpired(maxAccelDuration); - } - - // Construct text segments - auto createText = [&](const QString &title, const double data) { - return title + QString::number(std::round(data * distanceConversion)) + " " + leadDistanceUnit; - }; - - // Create segments for insights - QString accelText = QString("Accel: %1%2") - .arg(currentAcceleration * accelerationConversion, 0, 'f', 2) - .arg(accelerationUnit); - - QString maxAccSuffix = QString(mapOpen ? "" : " - Max: %1%2") - .arg(maxAcceleration * accelerationConversion, 0, 'f', 2) - .arg(accelerationUnit); - - QString obstacleText = createText(mapOpen ? " | Obstacle: " : " | Obstacle Factor: ", obstacleDistance); - QString stopText = createText(mapOpen ? " - Stop: " : " - Stop Factor: ", scene.stopped_equivalence); - QString followText = " = " + createText(mapOpen ? "Follow: " : "Follow Distance: ", scene.desired_follow); - - // Check if the longitudinal toggles have an impact on the driving logics - auto createDiffText = [&](const double data, const double stockData) { - double difference = std::round((data - stockData) * distanceConversion); - return difference != 0 ? QString(" (%1%2)").arg(difference > 0 ? "+" : "").arg(difference) : QString(); - }; - - // Prepare rectangle for insights - p.save(); - QRect insightsRect(rect().left() - 1, rect().top() - 60, rect().width() + 2, 100); - p.setBrush(QColor(0, 0, 0, 150)); - p.drawRoundedRect(insightsRect, 30, 30); - p.setFont(InterFont(30, QFont::DemiBold)); - p.setRenderHint(QPainter::TextAntialiasing); - - // Calculate positioning for text drawing - QRect adjustedRect = insightsRect.adjusted(0, 27, 0, 27); - int textBaseLine = adjustedRect.y() + (adjustedRect.height() + p.fontMetrics().height()) / 2 - p.fontMetrics().descent(); - - // Calculate the entire text width to ensure perfect centering - int totalTextWidth = p.fontMetrics().horizontalAdvance(accelText) - + p.fontMetrics().horizontalAdvance(maxAccSuffix) - + p.fontMetrics().horizontalAdvance(obstacleText) - + p.fontMetrics().horizontalAdvance(createDiffText(obstacleDistance, obstacleDistanceStock)) - + p.fontMetrics().horizontalAdvance(stopText) - + p.fontMetrics().horizontalAdvance(followText); - - int textStartPos = adjustedRect.x() + (adjustedRect.width() - totalTextWidth) / 2; - - // Draw the text - auto drawText = [&](const QString &text, const QColor color) { - p.setPen(color); - p.drawText(textStartPos, textBaseLine, text); - textStartPos += p.fontMetrics().horizontalAdvance(text); - }; - - drawText(accelText, Qt::white); - drawText(maxAccSuffix, isFiveSecondsPassed ? Qt::white : Qt::red); - drawText(obstacleText, Qt::white); - drawText(createDiffText(obstacleDistance, obstacleDistanceStock), (obstacleDistance - obstacleDistanceStock) > 0 ? Qt::green : Qt::red); - drawText(stopText, Qt::white); - drawText(followText, Qt::white); - - p.restore(); -} - -PedalIcons::PedalIcons(QWidget *parent) : QWidget(parent), scene(uiState()->scene) { - setFixedSize(btn_size, btn_size); - - brake_pedal_img = loadPixmap("../frogpilot/assets/other_images/brake_pedal.png", QSize(img_size, img_size)); - gas_pedal_img = loadPixmap("../frogpilot/assets/other_images/gas_pedal.png", QSize(img_size, img_size)); -} - -void PedalIcons::updateState() { - acceleration = scene.acceleration; - - accelerating = acceleration > 0.25; - decelerating = acceleration < -0.25; - - if (accelerating || decelerating) { - update(); - } -} - -void PedalIcons::paintEvent(QPaintEvent *event) { - QPainter p(this); - p.setRenderHint(QPainter::Antialiasing); - - int totalWidth = 2 * img_size; - int startX = (width() - totalWidth) / 2; - - int brakeX = startX + img_size / 2; - int gasX = startX + img_size; - - float brakeOpacity = scene.standstill ? 1.0f : decelerating ? std::max(0.25f, std::abs(acceleration)) : 0.25f; - float gasOpacity = accelerating ? std::max(0.25f, acceleration) : 0.25f; - - p.setOpacity(brakeOpacity); - p.drawPixmap(brakeX, (height() - img_size) / 2, brake_pedal_img); - - p.setOpacity(gasOpacity); - p.drawPixmap(gasX, (height() - img_size) / 2, gas_pedal_img); -} - -void AnnotatedCameraWidget::drawSLCConfirmation(QPainter &p) { - p.save(); - - // Get screen size - QSize size = this->size(); - - // Configure the screen halves - QRect leftRect(0, 0, size.width() / 2, size.height()); - QRect rightRect = leftRect.translated(size.width() / 2, 0); - - // Fill in the screen halves - p.setOpacity(0.5); - p.fillRect(leftRect, rightHandDrive ? redColor() : greenColor()); - p.fillRect(rightRect, rightHandDrive ? greenColor() : redColor()); - p.setOpacity(1.0); - - // Configure the font - p.setFont(InterFont(75, QFont::Bold)); - p.setPen(Qt::white); - - // Configure the text - QString unitText = is_metric ? "kph" : "mph"; - QString speedText = QString::number(std::nearbyint(scene.unconfirmed_speed_limit * (is_metric ? MS_TO_KPH : MS_TO_MPH))) + " " + unitText; - QString confirmText = "Confirm speed limit\n" + speedText; - QString ignoreText = "Ignore speed limit\n" + speedText; - - // Draw the text - p.drawText(leftRect, Qt::AlignCenter | Qt::AlignTop, rightHandDrive ? ignoreText : confirmText); - p.drawText(rightRect, Qt::AlignCenter | Qt::AlignTop, rightHandDrive ? confirmText : ignoreText); - - p.restore(); -} - -PersonalityButton::PersonalityButton(QWidget *parent) : QPushButton(parent), scene(uiState()->scene) { - setFixedSize(btn_size * 1.5, btn_size * 1.5); - - // Configure the profile vector - profile_data = { - {QPixmap("../frogpilot/assets/other_images/aggressive.png"), "Aggressive"}, - {QPixmap("../frogpilot/assets/other_images/standard.png"), "Standard"}, - {QPixmap("../frogpilot/assets/other_images/relaxed.png"), "Relaxed"} - }; - - personalityProfile = params.getInt("LongitudinalPersonality"); - - transitionTimer.start(); - - connect(this, &QPushButton::clicked, this, &PersonalityButton::handleClick); -} - -void PersonalityButton::checkUpdate() { - // Sync with the steering wheel button - personalityProfile = params.getInt("LongitudinalPersonality"); - updateState(); - paramsMemory.putBool("PersonalityChangedViaWheel", false); -} - -void PersonalityButton::handleClick() { - int mapping[] = {2, 0, 1}; - personalityProfile = mapping[personalityProfile]; - - params.putInt("LongitudinalPersonality", personalityProfile); - paramsMemory.putBool("PersonalityChangedViaUI", true); - - updateState(); -} - -void PersonalityButton::updateState() { - // Start the transition - transitionTimer.restart(); -} - -void PersonalityButton::paintEvent(QPaintEvent *) { - // Declare the constants - constexpr qreal fadeDuration = 1000.0; // 1 second - constexpr qreal textDuration = 3000.0; // 3 seconds - - QPainter p(this); - int elapsed = transitionTimer.elapsed(); - qreal textOpacity = qBound(0.0, 1.0 - ((elapsed - textDuration) / fadeDuration), 1.0); - qreal imageOpacity = qBound(0.0, (elapsed - textDuration) / fadeDuration, 1.0); - - // Enable Antialiasing - p.setRenderHints(QPainter::Antialiasing | QPainter::TextAntialiasing); - - // Configure the button - auto &[profile_image, profile_text] = profile_data[personalityProfile]; - QRect rect(0, 0, width(), height() + 95); - - // Draw the profile text with the calculated opacity - if (textOpacity > 0.0) { - p.setOpacity(textOpacity); - p.setFont(InterFont(40, QFont::Bold)); - p.setPen(Qt::white); - p.drawText(rect, Qt::AlignCenter, profile_text); - } - - // Draw the profile image with the calculated opacity - if (imageOpacity > 0.0) { - drawIcon(p, QPoint((btn_size / 2) * 1.25, btn_size / 2 + 95), profile_image, Qt::transparent, imageOpacity); - } -} - -void AnnotatedCameraWidget::drawStatusBar(QPainter &p) { - p.save(); - - // Variable declarations - static QElapsedTimer timer; - static QString lastShownStatus; - - QString newStatus; - - static bool displayStatusText = false; - - constexpr qreal fadeDuration = 1500.0; - constexpr qreal textDuration = 5000.0; - - // Draw status bar - QRect currentRect = rect(); - QRect statusBarRect(currentRect.left() - 1, currentRect.bottom() - 50, currentRect.width() + 2, 100); - p.setBrush(QColor(0, 0, 0, 150)); - p.setOpacity(1.0); - p.drawRoundedRect(statusBarRect, 30, 30); - - std::map conditionalStatusMap = { - {0, "Conditional Experimental Mode ready"}, - {1, "Conditional Experimental overridden"}, - {2, "Experimental Mode manually activated"}, - {3, "Conditional Experimental overridden"}, - {4, "Experimental Mode manually activated"}, - {5, "Conditional Experimental overridden"}, - {6, "Experimental Mode manually activated"}, - {7, "Experimental Mode activated for" + (mapOpen ? " intersection" : QString(" upcoming intersection"))}, - {8, "Experimental Mode activated for" + (mapOpen ? " turn" : QString(" upcoming turn"))}, - {9, "Experimental Mode activated due to" + (mapOpen ? "SLC" : QString(" no speed limit set"))}, - {10, "Experimental Mode activated due to" + (mapOpen ? " speed" : " speed being less than " + QString::number(conditionalSpeedLead) + (is_metric ? " kph" : " mph"))}, - {11, "Experimental Mode activated due to" + (mapOpen ? " speed" : " speed being less than " + QString::number(conditionalSpeed) + (is_metric ? " kph" : " mph"))}, - {12, "Experimental Mode activated for slower lead"}, - {13, "Experimental Mode activated for turn" + (mapOpen ? "" : QString(" / lane change"))}, - {14, "Experimental Mode activated for curve"}, - {15, "Experimental Mode activated for stop" + (mapOpen ? "" : QString(" sign / stop light"))}, - }; - - QString roadName = roadNameUI ? QString::fromStdString(paramsMemory.get("RoadName")) : QString(); - - // Update status text - if (alwaysOnLateralActive) { - newStatus = QString("Always On Lateral active") + (mapOpen ? "" : ". Press the \"Cruise Control\" button to disable"); - } else if (conditionalExperimental) { - newStatus = conditionalStatusMap[status != STATUS_DISENGAGED ? conditionalStatus : 0]; - } - - // Append suffix to the status - QString distanceSuffix = ". Long press the \"distance\" button to revert"; - QString lkasSuffix = ". Double press the \"LKAS\" button to revert"; - QString screenSuffix = ". Double tap the screen to revert"; - - if (!alwaysOnLateralActive && !mapOpen && status != STATUS_DISENGAGED && !newStatus.isEmpty()) { - if (conditionalStatus == 1 || conditionalStatus == 2) { - newStatus += screenSuffix; - } else if (conditionalStatus == 3 || conditionalStatus == 4) { - newStatus += distanceSuffix; - } else if (conditionalStatus == 5 || conditionalStatus == 6) { - newStatus += lkasSuffix; - } - } - - // Check if status has changed or if the road name is empty - if (newStatus != lastShownStatus || roadName.isEmpty()) { - displayStatusText = true; - lastShownStatus = newStatus; - timer.restart(); - } else if (displayStatusText && timer.hasExpired(textDuration + fadeDuration)) { - displayStatusText = false; - } - - // Configure the text - p.setFont(InterFont(40, QFont::Bold)); - p.setPen(Qt::white); - p.setRenderHint(QPainter::TextAntialiasing); - - // Calculate text opacity - static qreal roadNameOpacity; - static qreal statusTextOpacity; - int elapsed = timer.elapsed(); - if (displayStatusText) { - statusTextOpacity = qBound(0.0, 1.0 - (elapsed - textDuration) / fadeDuration, 1.0); - roadNameOpacity = 1.0 - statusTextOpacity; - } else { - roadNameOpacity = qBound(0.0, elapsed / fadeDuration, 1.0); - statusTextOpacity = 0.0; - } - - // Draw the status text - p.setOpacity(statusTextOpacity); - QRect textRect = p.fontMetrics().boundingRect(statusBarRect, Qt::AlignCenter | Qt::TextWordWrap, newStatus); - textRect.moveBottom(statusBarRect.bottom() - 50); - p.drawText(textRect, Qt::AlignCenter | Qt::TextWordWrap, newStatus); - - // Draw the road name with the calculated opacity - if (!roadName.isEmpty()) { - p.setOpacity(roadNameOpacity); - textRect = p.fontMetrics().boundingRect(statusBarRect, Qt::AlignCenter | Qt::TextWordWrap, roadName); - textRect.moveBottom(statusBarRect.bottom() - 50); - p.drawText(textRect, Qt::AlignCenter | Qt::TextWordWrap, roadName); - } - - p.restore(); -} - -void AnnotatedCameraWidget::drawTurnSignals(QPainter &p) { - // Declare the turn signal size - constexpr int signalHeight = 480; - constexpr int signalWidth = 360; - - // Enable Antialiasing - p.setRenderHint(QPainter::Antialiasing); - - // Calculate the vertical position for the turn signals - int baseYPosition = (height() - signalHeight) / 2 + (alwaysOnLateral || conditionalExperimental || roadNameUI ? 225 : 300); - // Calculate the x-coordinates for the turn signals - int leftSignalXPosition = 75 + width() - signalWidth - 300 * (blindSpotLeft ? 0 : animationFrameIndex); - int rightSignalXPosition = -75 + 300 * (blindSpotRight ? 0 : animationFrameIndex); - - // Draw the turn signals - if (animationFrameIndex < signalImgVector.size()) { - auto drawSignal = [&](bool signalActivated, int xPosition, bool flip, bool blindspot) { - if (signalActivated) { - // Get the appropriate image from the signalImgVector - int uniqueImages = signalImgVector.size() / 4; // Each image has a regular, flipped, and two blindspot versions - int index = (blindspot ? 2 * uniqueImages : 2 * animationFrameIndex % totalFrames) + (flip ? 1 : 0); - QPixmap &signal = signalImgVector[index]; - p.drawPixmap(xPosition, baseYPosition, signalWidth, signalHeight, signal); - } - }; - - // Display the animation based on which signal is activated - drawSignal(turnSignalLeft, leftSignalXPosition, false, blindSpotLeft); - drawSignal(turnSignalRight, rightSignalXPosition, true, blindSpotRight); - } -} diff --git a/selfdrive/ui/qt/onroad.h b/selfdrive/ui/qt/onroad.h deleted file mode 100644 index a5e2dc3..0000000 --- a/selfdrive/ui/qt/onroad.h +++ /dev/null @@ -1,330 +0,0 @@ -#pragma once - -#include - -#include -#include -#include -#include -#include - -#include "common/util.h" -#include "selfdrive/ui/ui.h" -#include "selfdrive/ui/qt/widgets/cameraview.h" - -#include "selfdrive/frogpilot/screenrecorder/screenrecorder.h" - -const int btn_size = 192; -const int img_size = (btn_size / 4) * 3; - -// FrogPilot global variables -static double fps; - -// ***** onroad widgets ***** -class OnroadAlerts : public QWidget { - Q_OBJECT - -public: - OnroadAlerts(QWidget *parent = 0) : QWidget(parent), scene(uiState()->scene) {} - void updateAlert(const Alert &a); - -protected: - void paintEvent(QPaintEvent*) override; - -private: - QColor bg; - Alert alert = {}; - - // FrogPilot variables - UIScene &scene; -}; - -class Compass : public QWidget { -public: - explicit Compass(QWidget *parent = nullptr); - - void updateState(int bearing_deg); - -protected: - void paintEvent(QPaintEvent *event) override; - -private: - int bearingDeg; - int circleOffset; - int compassSize; - int degreeLabelOffset; - int innerCompass; - int x; - int y; - QPixmap compassInnerImg; - QPixmap staticElements; -}; - -class ExperimentalButton : public QPushButton { - Q_OBJECT - -public: - explicit ExperimentalButton(QWidget *parent = 0); - void updateState(const UIState &s, bool leadInfo); - -private: - void paintEvent(QPaintEvent *event) override; - void changeMode(); - - Params params; - QPixmap engage_img; - QPixmap experimental_img; - bool experimental_mode; - bool engageable; - - // FrogPilot variables - UIScene &scene; - - QMap wheelImages; - QMap wheelImagesGif; - - QMovie engage_gif; - QLabel *gifLabel; - - bool firefoxRandomEventTriggered; - bool rotatingWheel; - bool treeFiddyRandomEventTriggered; - bool weebRandomEventTriggered; - - int steeringAngleDeg; - int wheelIcon; - int wheelIconGif; - int y_offset; -}; - - -class MapSettingsButton : public QPushButton { - Q_OBJECT - -public: - explicit MapSettingsButton(QWidget *parent = 0); - -private: - void paintEvent(QPaintEvent *event) override; - - QPixmap settings_img; -}; - -class PedalIcons : public QWidget { - Q_OBJECT - -public: - explicit PedalIcons(QWidget *parent = 0); - void updateState(); - -private: - void paintEvent(QPaintEvent *event) override; - - QPixmap brake_pedal_img; - QPixmap gas_pedal_img; - - UIScene &scene; - - bool accelerating; - bool decelerating; - - float acceleration; -}; - -class PersonalityButton : public QPushButton { -public: - explicit PersonalityButton(QWidget *parent = 0); - - void checkUpdate(); - void handleClick(); - void updateState(); - -private: - void paintEvent(QPaintEvent *event) override; - - Params params; - Params paramsMemory{"/dev/shm/params"}; - - UIScene &scene; - - int personalityProfile = 0; - - QElapsedTimer transitionTimer; - - QVector> profile_data; -}; - -// container window for the NVG UI -class AnnotatedCameraWidget : public CameraWidget { - Q_OBJECT - -public: - explicit AnnotatedCameraWidget(VisionStreamType type, QWidget* parent = 0); - void updateState(const UIState &s); - - MapSettingsButton *map_settings_btn; - MapSettingsButton *map_settings_btn_bottom; - -private: - void drawText(QPainter &p, int x, int y, const QString &text, int alpha = 255); - - QVBoxLayout *main_layout; - ExperimentalButton *experimental_btn; - QPixmap dm_img; - float speed; - QString speedUnit; - float setSpeed; - float speedLimit; - bool is_cruise_set = false; - bool is_metric = false; - bool dmActive = false; - bool hideBottomIcons = false; - bool rightHandDM = false; - float dm_fade_state = 1.0; - bool has_us_speed_limit = false; - bool has_eu_speed_limit = false; - bool v_ego_cluster_seen = false; - int status = STATUS_DISENGAGED; - std::unique_ptr pm; - - int skip_frame_count = 0; - bool wide_cam_requested = false; - - // FrogPilot widgets - void initializeFrogPilotWidgets(); - void updateFrogPilotWidgets(QPainter &p); - - void drawLeadInfo(QPainter &p); - void drawSLCConfirmation(QPainter &p); - void drawStatusBar(QPainter &p); - void drawTurnSignals(QPainter &p); - - // FrogPilot variables - Params paramsMemory{"/dev/shm/params"}; - - UIScene &scene; - - Compass *compass_img; - PedalIcons *pedal_icons; - PersonalityButton *personality_btn; - ScreenRecorder *recorder_btn; - - QHBoxLayout *bottom_layout; - - bool alwaysOnLateral; - bool alwaysOnLateralActive; - bool blindSpotLeft; - bool blindSpotRight; - bool compass; - bool conditionalExperimental; - bool experimentalMode; - bool fullMapOpen; - bool leadInfo; - bool mapOpen; - bool onroadAdjustableProfiles; - bool pedalsOnUI; - bool rightHandDrive; - bool roadNameUI; - bool showDriverCamera; - bool showSLCOffset; - bool slcOverridden; - bool speedLimitController; - bool trafficModeActive; - bool turnSignalLeft; - bool turnSignalRight; - bool useViennaSLCSign; - bool vtscControllingCurve; - - float cruiseAdjustment; - float distanceConversion; - float laneWidthLeft; - float laneWidthRight; - float slcSpeedLimit; - float slcSpeedLimitOffset; - float speedConversion; - - int availableImages; - int cameraView; - int conditionalSpeed; - int conditionalSpeedLead; - int conditionalStatus; - int currentHolidayTheme; - int customColors; - int customSignals; - int obstacleDistance; - int obstacleDistanceStock; - int totalFrames = 8; - - QString leadDistanceUnit; - QString leadSpeedUnit; - QString themePath; - QStringList imagePaths; - - size_t animationFrameIndex; - - std::unordered_map>> holidayThemeConfiguration; - std::unordered_map>> themeConfiguration; - std::vector signalImgVector; - - QTimer *animationTimer; - - inline QColor greenColor(int alpha = 242) { return QColor(23, 134, 68, alpha); } - -protected: - void paintGL() override; - void initializeGL() override; - void showEvent(QShowEvent *event) override; - void updateFrameMat() override; - void drawLaneLines(QPainter &painter, const UIState *s); - void drawLead(QPainter &painter, const cereal::RadarState::LeadData::Reader &lead_data, const QPointF &vd); - void drawHud(QPainter &p); - void drawDriverState(QPainter &painter, const UIState *s); - void paintEvent(QPaintEvent *event) override; - inline QColor redColor(int alpha = 255) { return QColor(201, 34, 49, alpha); } - inline QColor whiteColor(int alpha = 255) { return QColor(255, 255, 255, alpha); } - inline QColor blackColor(int alpha = 255) { return QColor(0, 0, 0, alpha); } - - double prev_draw_t = 0; - FirstOrderFilter fps_filter; -}; - -// container for all onroad widgets -class OnroadWindow : public QWidget { - Q_OBJECT - -public: - OnroadWindow(QWidget* parent = 0); - bool isMapVisible() const { return map && map->isVisible(); } - void showMapPanel(bool show) { if (map) map->setVisible(show); } - -signals: - void mapPanelRequested(); - -private: - void paintEvent(QPaintEvent *event); - void mousePressEvent(QMouseEvent* e) override; - OnroadAlerts *alerts; - AnnotatedCameraWidget *nvg; - QColor bg = bg_colors[STATUS_DISENGAGED]; - QWidget *map = nullptr; - QHBoxLayout* split; - - // FrogPilot widgets - void updateFPSCounter(); - - // FrogPilot variables - UIScene &scene; - Params paramsMemory{"/dev/shm/params"}; - - double avgFPS; - double maxFPS = 0.0; - double minFPS = 99.9; - - QPoint timeoutPoint = QPoint(420, 69); - QTimer clickTimer; - -private slots: - void offroadTransition(bool offroad); - void primeChanged(bool prime); - void updateState(const UIState &s); -}; diff --git a/selfdrive/ui/qt/qt_window.cc b/selfdrive/ui/qt/qt_window.cc deleted file mode 100644 index f71cea0..0000000 --- a/selfdrive/ui/qt/qt_window.cc +++ /dev/null @@ -1,34 +0,0 @@ -#include "selfdrive/ui/qt/qt_window.h" - -void setMainWindow(QWidget *w) { - const float scale = util::getenv("SCALE", 1.0f); - const QSize sz = QGuiApplication::primaryScreen()->size(); - - if (Hardware::PC() && scale == 1.0 && !(sz - DEVICE_SCREEN_SIZE).isValid()) { - w->setMinimumSize(QSize(640, 480)); // allow resize smaller than fullscreen - w->setMaximumSize(DEVICE_SCREEN_SIZE); - w->resize(sz); - } else { - w->setFixedSize(DEVICE_SCREEN_SIZE * scale); - } - w->show(); - -#ifdef QCOM2 - QPlatformNativeInterface *native = QGuiApplication::platformNativeInterface(); - wl_surface *s = reinterpret_cast(native->nativeResourceForWindow("surface", w->windowHandle())); - wl_surface_set_buffer_transform(s, WL_OUTPUT_TRANSFORM_270); - wl_surface_commit(s); - w->showFullScreen(); - - // ensure we have a valid eglDisplay, otherwise the ui will silently fail - void *egl = native->nativeResourceForWindow("egldisplay", w->windowHandle()); - assert(egl != nullptr); -#endif -} - - -extern "C" { - void set_main_window(void *w) { - setMainWindow((QWidget*)w); - } -} diff --git a/selfdrive/ui/qt/qt_window.h b/selfdrive/ui/qt/qt_window.h deleted file mode 100644 index 6f16e00..0000000 --- a/selfdrive/ui/qt/qt_window.h +++ /dev/null @@ -1,20 +0,0 @@ -#pragma once - -#include - -#include -#include -#include - -#ifdef QCOM2 -#include -#include -#include -#endif - -#include "system/hardware/hw.h" - -const QString ASSET_PATH = ":/"; -const QSize DEVICE_SCREEN_SIZE = {2160, 1080}; - -void setMainWindow(QWidget *w); diff --git a/selfdrive/ui/qt/request_repeater.cc b/selfdrive/ui/qt/request_repeater.cc deleted file mode 100644 index 7aa7318..0000000 --- a/selfdrive/ui/qt/request_repeater.cc +++ /dev/null @@ -1,27 +0,0 @@ -#include "selfdrive/ui/qt/request_repeater.h" - -RequestRepeater::RequestRepeater(QObject *parent, const QString &requestURL, const QString &cacheKey, - int period, bool while_onroad) : HttpRequest(parent) { - timer = new QTimer(this); - timer->setTimerType(Qt::VeryCoarseTimer); - QObject::connect(timer, &QTimer::timeout, [=]() { - if ((!uiState()->scene.started || while_onroad) && device()->isAwake() && !active()) { - sendRequest(requestURL); - } - }); - - timer->start(period * 1000); - - if (!cacheKey.isEmpty()) { - prevResp = QString::fromStdString(params.get(cacheKey.toStdString())); - if (!prevResp.isEmpty()) { - QTimer::singleShot(500, [=]() { emit requestDone(prevResp, true, QNetworkReply::NoError); }); - } - QObject::connect(this, &HttpRequest::requestDone, [=](const QString &resp, bool success) { - if (success && resp != prevResp) { - params.put(cacheKey.toStdString(), resp.toStdString()); - prevResp = resp; - } - }); - } -} diff --git a/selfdrive/ui/qt/request_repeater.h b/selfdrive/ui/qt/request_repeater.h deleted file mode 100644 index c0e2758..0000000 --- a/selfdrive/ui/qt/request_repeater.h +++ /dev/null @@ -1,15 +0,0 @@ -#pragma once - -#include "common/util.h" -#include "selfdrive/ui/qt/api.h" -#include "selfdrive/ui/ui.h" - -class RequestRepeater : public HttpRequest { -public: - RequestRepeater(QObject *parent, const QString &requestURL, const QString &cacheKey = "", int period = 0, bool while_onroad=false); - -private: - Params params; - QTimer *timer; - QString prevResp; -}; diff --git a/selfdrive/ui/qt/setup/reset.cc b/selfdrive/ui/qt/setup/reset.cc deleted file mode 100644 index c9e0525..0000000 --- a/selfdrive/ui/qt/setup/reset.cc +++ /dev/null @@ -1,134 +0,0 @@ -#include -#include -#include -#include -#include -#include - -#include "selfdrive/ui/qt/qt_window.h" -#include "selfdrive/ui/qt/setup/reset.h" - -#define NVME "/dev/nvme0n1" -#define USERDATA "/dev/disk/by-partlabel/userdata" - -void Reset::doErase() { - // best effort to wipe nvme - std::system("sudo umount " NVME); - std::system("yes | sudo mkfs.ext4 " NVME); - - int rm = std::system("sudo rm -rf /data/*"); - std::system("sudo umount " USERDATA); - int fmt = std::system("yes | sudo mkfs.ext4 " USERDATA); - - if (rm == 0 || fmt == 0) { - std::system("sudo reboot"); - } - body->setText(tr("Reset failed. Reboot to try again.")); - rebootBtn->show(); -} - -void Reset::startReset() { - body->setText(tr("Resetting device...\nThis may take up to a minute.")); - rejectBtn->hide(); - rebootBtn->hide(); - confirmBtn->hide(); -#ifdef __aarch64__ - QTimer::singleShot(100, this, &Reset::doErase); -#endif -} - -void Reset::confirm() { - const QString confirm_txt = tr("Are you sure you want to reset your device?"); - if (body->text() != confirm_txt) { - body->setText(confirm_txt); - } else { - startReset(); - } -} - -Reset::Reset(ResetMode mode, QWidget *parent) : QWidget(parent) { - QVBoxLayout *main_layout = new QVBoxLayout(this); - main_layout->setContentsMargins(45, 220, 45, 45); - main_layout->setSpacing(0); - - QLabel *title = new QLabel(tr("System Reset")); - title->setStyleSheet("font-size: 90px; font-weight: 600;"); - main_layout->addWidget(title, 0, Qt::AlignTop | Qt::AlignLeft); - - main_layout->addSpacing(60); - - body = new QLabel(tr("System reset triggered. Press confirm to erase all content and settings. Press cancel to resume boot.")); - body->setWordWrap(true); - body->setStyleSheet("font-size: 80px; font-weight: light;"); - main_layout->addWidget(body, 1, Qt::AlignTop | Qt::AlignLeft); - - QHBoxLayout *blayout = new QHBoxLayout(); - main_layout->addLayout(blayout); - blayout->setSpacing(50); - - rejectBtn = new QPushButton(tr("Cancel")); - blayout->addWidget(rejectBtn); - QObject::connect(rejectBtn, &QPushButton::clicked, QCoreApplication::instance(), &QCoreApplication::quit); - - rebootBtn = new QPushButton(tr("Reboot")); - blayout->addWidget(rebootBtn); -#ifdef __aarch64__ - QObject::connect(rebootBtn, &QPushButton::clicked, [=]{ - std::system("sudo reboot"); - }); -#endif - - confirmBtn = new QPushButton(tr("Confirm")); - confirmBtn->setStyleSheet(R"( - QPushButton { - background-color: #465BEA; - } - QPushButton:pressed { - background-color: #3049F4; - } - )"); - blayout->addWidget(confirmBtn); - QObject::connect(confirmBtn, &QPushButton::clicked, this, &Reset::confirm); - - bool recover = mode == ResetMode::RECOVER; - rejectBtn->setVisible(!recover); - rebootBtn->setVisible(recover); - if (recover) { - body->setText(tr("Unable to mount data partition. Partition may be corrupted. Press confirm to erase and reset your device.")); - } - - setStyleSheet(R"( - * { - font-family: Inter; - color: white; - background-color: black; - } - QLabel { - margin-left: 140; - } - QPushButton { - height: 160; - font-size: 55px; - font-weight: 400; - border-radius: 10px; - background-color: #333333; - } - QPushButton:pressed { - background-color: #444444; - } - )"); -} - -int main(int argc, char *argv[]) { - ResetMode mode = ResetMode::USER_RESET; - if (argc > 1) { - if (strcmp(argv[1], "--recover") == 0) { - mode = ResetMode::RECOVER; - } - } - - QApplication a(argc, argv); - Reset reset(mode); - setMainWindow(&reset); - return a.exec(); -} diff --git a/selfdrive/ui/qt/setup/reset.h b/selfdrive/ui/qt/setup/reset.h deleted file mode 100644 index 8bf368e..0000000 --- a/selfdrive/ui/qt/setup/reset.h +++ /dev/null @@ -1,26 +0,0 @@ -#include -#include -#include - -enum ResetMode { - USER_RESET, // user initiated a factory reset from openpilot - RECOVER, // userdata is corrupt for some reason, give a chance to recover -}; - -class Reset : public QWidget { - Q_OBJECT - -public: - explicit Reset(ResetMode mode, QWidget *parent = 0); - -private: - QLabel *body; - QPushButton *rejectBtn; - QPushButton *rebootBtn; - QPushButton *confirmBtn; - void doErase(); - void startReset(); - -private slots: - void confirm(); -}; diff --git a/selfdrive/ui/qt/setup/setup.cc b/selfdrive/ui/qt/setup/setup.cc deleted file mode 100644 index 4f2e4f4..0000000 --- a/selfdrive/ui/qt/setup/setup.cc +++ /dev/null @@ -1,399 +0,0 @@ -#include "selfdrive/ui/qt/setup/setup.h" - -#include -#include -#include -#include - -#include -#include -#include - -#include - -#include "common/util.h" -#include "system/hardware/hw.h" -#include "selfdrive/ui/qt/api.h" -#include "selfdrive/ui/qt/qt_window.h" -#include "selfdrive/ui/qt/network/networking.h" -#include "selfdrive/ui/qt/util.h" -#include "selfdrive/ui/qt/widgets/input.h" - -const std::string USER_AGENT = "AGNOSSetup-"; -const QString TEST_URL = "https://openpilot.comma.ai"; - -bool is_elf(char *fname) { - FILE *fp = fopen(fname, "rb"); - if (fp == NULL) { - return false; - } - char buf[4]; - size_t n = fread(buf, 1, 4, fp); - fclose(fp); - return n == 4 && buf[0] == 0x7f && buf[1] == 'E' && buf[2] == 'L' && buf[3] == 'F'; -} - -void Setup::download(QString url) { - // autocomplete incomplete urls - if (QRegularExpression("^([^/.]+)/([^/]+)$").match(url).hasMatch()) { - url.prepend("https://installer.comma.ai/"); - } - - CURL *curl = curl_easy_init(); - if (!curl) { - emit finished(url, tr("Something went wrong. Reboot the device.")); - return; - } - - auto version = util::read_file("/VERSION"); - - struct curl_slist *list = NULL; - list = curl_slist_append(list, ("X-openpilot-serial: " + Hardware::get_serial()).c_str()); - - char tmpfile[] = "/tmp/installer_XXXXXX"; - FILE *fp = fdopen(mkstemp(tmpfile), "w"); - - curl_easy_setopt(curl, CURLOPT_URL, url.toStdString().c_str()); - curl_easy_setopt(curl, CURLOPT_WRITEFUNCTION, NULL); - curl_easy_setopt(curl, CURLOPT_WRITEDATA, fp); - curl_easy_setopt(curl, CURLOPT_VERBOSE, 1L); - curl_easy_setopt(curl, CURLOPT_FOLLOWLOCATION, 1L); - curl_easy_setopt(curl, CURLOPT_USERAGENT, (USER_AGENT + version).c_str()); - curl_easy_setopt(curl, CURLOPT_HTTPHEADER, list); - curl_easy_setopt(curl, CURLOPT_TIMEOUT, 30L); - - int ret = curl_easy_perform(curl); - long res_status = 0; - curl_easy_getinfo(curl, CURLINFO_RESPONSE_CODE, &res_status); - - if (ret != CURLE_OK || res_status != 200) { - emit finished(url, tr("Ensure the entered URL is valid, and the device’s internet connection is good.")); - } else if (!is_elf(tmpfile)) { - emit finished(url, tr("No custom software found at this URL.")); - } else { - rename(tmpfile, "/tmp/installer"); - - FILE *fp_url = fopen("/tmp/installer_url", "w"); - fprintf(fp_url, "%s", url.toStdString().c_str()); - fclose(fp_url); - - emit finished(url); - } - - curl_slist_free_all(list); - curl_easy_cleanup(curl); - fclose(fp); -} - -QWidget * Setup::low_voltage() { - QWidget *widget = new QWidget(); - QVBoxLayout *main_layout = new QVBoxLayout(widget); - main_layout->setContentsMargins(55, 0, 55, 55); - main_layout->setSpacing(0); - - // inner text layout: warning icon, title, and body - QVBoxLayout *inner_layout = new QVBoxLayout(); - inner_layout->setContentsMargins(110, 144, 365, 0); - main_layout->addLayout(inner_layout); - - QLabel *triangle = new QLabel(); - triangle->setPixmap(QPixmap(ASSET_PATH + "offroad/icon_warning.png")); - inner_layout->addWidget(triangle, 0, Qt::AlignTop | Qt::AlignLeft); - inner_layout->addSpacing(80); - - QLabel *title = new QLabel(tr("WARNING: Low Voltage")); - title->setStyleSheet("font-size: 90px; font-weight: 500; color: #FF594F;"); - inner_layout->addWidget(title, 0, Qt::AlignTop | Qt::AlignLeft); - - inner_layout->addSpacing(25); - - QLabel *body = new QLabel(tr("Power your device in a car with a harness or proceed at your own risk.")); - body->setWordWrap(true); - body->setAlignment(Qt::AlignTop | Qt::AlignLeft); - body->setStyleSheet("font-size: 80px; font-weight: 300;"); - inner_layout->addWidget(body); - - inner_layout->addStretch(); - - // power off + continue buttons - QHBoxLayout *blayout = new QHBoxLayout(); - blayout->setSpacing(50); - main_layout->addLayout(blayout, 0); - - QPushButton *poweroff = new QPushButton(tr("Power off")); - poweroff->setObjectName("navBtn"); - blayout->addWidget(poweroff); - QObject::connect(poweroff, &QPushButton::clicked, this, [=]() { - Hardware::poweroff(); - }); - - QPushButton *cont = new QPushButton(tr("Continue")); - cont->setObjectName("navBtn"); - blayout->addWidget(cont); - QObject::connect(cont, &QPushButton::clicked, this, &Setup::nextPage); - - return widget; -} - -QWidget * Setup::getting_started() { - QWidget *widget = new QWidget(); - - QHBoxLayout *main_layout = new QHBoxLayout(widget); - main_layout->setMargin(0); - - QVBoxLayout *vlayout = new QVBoxLayout(); - vlayout->setContentsMargins(165, 280, 100, 0); - main_layout->addLayout(vlayout); - - QLabel *title = new QLabel(tr("Getting Started")); - title->setStyleSheet("font-size: 90px; font-weight: 500;"); - vlayout->addWidget(title, 0, Qt::AlignTop | Qt::AlignLeft); - - vlayout->addSpacing(90); - QLabel *desc = new QLabel(tr("Before we get on the road, let’s finish installation and cover some details.")); - desc->setWordWrap(true); - desc->setStyleSheet("font-size: 80px; font-weight: 300;"); - vlayout->addWidget(desc, 0, Qt::AlignTop | Qt::AlignLeft); - - vlayout->addStretch(); - - QPushButton *btn = new QPushButton(); - btn->setIcon(QIcon(":/img_continue_triangle.svg")); - btn->setIconSize(QSize(54, 106)); - btn->setFixedSize(310, 1080); - btn->setProperty("primary", true); - btn->setStyleSheet("border: none;"); - main_layout->addWidget(btn, 0, Qt::AlignRight); - QObject::connect(btn, &QPushButton::clicked, this, &Setup::nextPage); - - return widget; -} - -QWidget * Setup::network_setup() { - QWidget *widget = new QWidget(); - QVBoxLayout *main_layout = new QVBoxLayout(widget); - main_layout->setContentsMargins(55, 50, 55, 50); - - // title - QLabel *title = new QLabel(tr("Connect to Wi-Fi")); - title->setStyleSheet("font-size: 90px; font-weight: 500;"); - main_layout->addWidget(title, 0, Qt::AlignLeft | Qt::AlignTop); - - main_layout->addSpacing(25); - - // wifi widget - Networking *networking = new Networking(this, false); - networking->setStyleSheet("Networking {background-color: #292929; border-radius: 13px;}"); - main_layout->addWidget(networking, 1); - - main_layout->addSpacing(35); - - // back + continue buttons - QHBoxLayout *blayout = new QHBoxLayout; - main_layout->addLayout(blayout); - blayout->setSpacing(50); - - QPushButton *back = new QPushButton(tr("Back")); - back->setObjectName("navBtn"); - QObject::connect(back, &QPushButton::clicked, this, &Setup::prevPage); - blayout->addWidget(back); - - QPushButton *cont = new QPushButton(); - cont->setObjectName("navBtn"); - cont->setProperty("primary", true); - QObject::connect(cont, &QPushButton::clicked, [=]() { - auto w = currentWidget(); - QTimer::singleShot(0, [=]() { - setCurrentWidget(downloading_widget); - }); - QString url = InputDialog::getText(tr("Enter URL"), this, tr("for Custom Software")); - if (!url.isEmpty()) { - QTimer::singleShot(1000, this, [=]() { - download(url); - }); - } else { - setCurrentWidget(w); - } - }); - blayout->addWidget(cont); - - // setup timer for testing internet connection - HttpRequest *request = new HttpRequest(this, false, 2500); - QObject::connect(request, &HttpRequest::requestDone, [=](const QString &, bool success) { - cont->setEnabled(success); - if (success) { - const bool wifi = networking->wifi->currentNetworkType() == NetworkType::WIFI; - cont->setText(wifi ? tr("Continue") : tr("Continue without Wi-Fi")); - } else { - cont->setText(tr("Waiting for internet")); - } - repaint(); - }); - request->sendRequest(TEST_URL); - QTimer *timer = new QTimer(this); - QObject::connect(timer, &QTimer::timeout, [=]() { - if (!request->active() && cont->isVisible()) { - request->sendRequest(TEST_URL); - } - }); - timer->start(1000); - - return widget; -} - -QWidget * Setup::downloading() { - QWidget *widget = new QWidget(); - QVBoxLayout *main_layout = new QVBoxLayout(widget); - QLabel *txt = new QLabel(tr("Downloading...")); - txt->setStyleSheet("font-size: 90px; font-weight: 500;"); - main_layout->addWidget(txt, 0, Qt::AlignCenter); - return widget; -} - -QWidget * Setup::download_failed(QLabel *url, QLabel *body) { - QWidget *widget = new QWidget(); - QVBoxLayout *main_layout = new QVBoxLayout(widget); - main_layout->setContentsMargins(55, 185, 55, 55); - main_layout->setSpacing(0); - - QLabel *title = new QLabel(tr("Download Failed")); - title->setStyleSheet("font-size: 90px; font-weight: 500;"); - main_layout->addWidget(title, 0, Qt::AlignTop | Qt::AlignLeft); - - main_layout->addSpacing(67); - - url->setWordWrap(true); - url->setAlignment(Qt::AlignTop | Qt::AlignLeft); - url->setStyleSheet("font-family: \"JetBrains Mono\"; font-size: 64px; font-weight: 400; margin-right: 100px;"); - main_layout->addWidget(url); - - main_layout->addSpacing(48); - - body->setWordWrap(true); - body->setAlignment(Qt::AlignTop | Qt::AlignLeft); - body->setStyleSheet("font-size: 80px; font-weight: 300; margin-right: 100px;"); - main_layout->addWidget(body); - - main_layout->addStretch(); - - // reboot + start over buttons - QHBoxLayout *blayout = new QHBoxLayout(); - blayout->setSpacing(50); - main_layout->addLayout(blayout, 0); - - QPushButton *reboot = new QPushButton(tr("Reboot device")); - reboot->setObjectName("navBtn"); - blayout->addWidget(reboot); - QObject::connect(reboot, &QPushButton::clicked, this, [=]() { - Hardware::reboot(); - }); - - QPushButton *restart = new QPushButton(tr("Start over")); - restart->setObjectName("navBtn"); - restart->setProperty("primary", true); - blayout->addWidget(restart); - QObject::connect(restart, &QPushButton::clicked, this, [=]() { - setCurrentIndex(1); - }); - - widget->setStyleSheet(R"( - QLabel { - margin-left: 117; - } - )"); - return widget; -} - -void Setup::prevPage() { - setCurrentIndex(currentIndex() - 1); -} - -void Setup::nextPage() { - setCurrentIndex(currentIndex() + 1); -} - -Setup::Setup(QWidget *parent) : QStackedWidget(parent) { - if (std::getenv("MULTILANG")) { - selectLanguage(); - } - - std::stringstream buffer; - buffer << std::ifstream("/sys/class/hwmon/hwmon1/in1_input").rdbuf(); - float voltage = (float)std::atoi(buffer.str().c_str()) / 1000.; - if (voltage < 7) { - addWidget(low_voltage()); - } - - addWidget(getting_started()); - addWidget(network_setup()); - - downloading_widget = downloading(); - addWidget(downloading_widget); - - QLabel *url_label = new QLabel(); - QLabel *body_label = new QLabel(); - failed_widget = download_failed(url_label, body_label); - addWidget(failed_widget); - - QObject::connect(this, &Setup::finished, [=](const QString &url, const QString &error) { - qDebug() << "finished" << url << error; - if (error.isEmpty()) { - // hide setup on success - QTimer::singleShot(3000, this, &QWidget::hide); - } else { - url_label->setText(url); - body_label->setText(error); - setCurrentWidget(failed_widget); - } - }); - - // TODO: revisit pressed bg color - setStyleSheet(R"( - * { - color: white; - font-family: Inter; - } - Setup { - background-color: black; - } - QPushButton#navBtn { - height: 160; - font-size: 55px; - font-weight: 400; - border-radius: 10px; - background-color: #333333; - } - QPushButton#navBtn:disabled, QPushButton[primary='true']:disabled { - color: #808080; - background-color: #333333; - } - QPushButton#navBtn:pressed { - background-color: #444444; - } - QPushButton[primary='true'], #navBtn[primary='true'] { - background-color: #465BEA; - } - QPushButton[primary='true']:pressed, #navBtn:pressed[primary='true'] { - background-color: #3049F4; - } - )"); -} - -void Setup::selectLanguage() { - QMap langs = getSupportedLanguages(); - QString selection = MultiOptionDialog::getSelection(tr("Select a language"), langs.keys(), "", this); - if (!selection.isEmpty()) { - QString selectedLang = langs[selection]; - Params().put("LanguageSetting", selectedLang.toStdString()); - if (translator.load(":/" + selectedLang)) { - qApp->installTranslator(&translator); - } - } -} - -int main(int argc, char *argv[]) { - QApplication a(argc, argv); - Setup setup; - setMainWindow(&setup); - return a.exec(); -} diff --git a/selfdrive/ui/qt/setup/setup.h b/selfdrive/ui/qt/setup/setup.h deleted file mode 100644 index 8c33acc..0000000 --- a/selfdrive/ui/qt/setup/setup.h +++ /dev/null @@ -1,34 +0,0 @@ -#pragma once - -#include -#include -#include -#include -#include - -class Setup : public QStackedWidget { - Q_OBJECT - -public: - explicit Setup(QWidget *parent = 0); - -private: - void selectLanguage(); - QWidget *low_voltage(); - QWidget *getting_started(); - QWidget *network_setup(); - QWidget *downloading(); - QWidget *download_failed(QLabel *url, QLabel *body); - - QWidget *failed_widget; - QWidget *downloading_widget; - QTranslator translator; - -signals: - void finished(const QString &url, const QString &error = ""); - -public slots: - void nextPage(); - void prevPage(); - void download(QString url); -}; diff --git a/selfdrive/ui/qt/setup/updater.cc b/selfdrive/ui/qt/setup/updater.cc deleted file mode 100644 index ed47590..0000000 --- a/selfdrive/ui/qt/setup/updater.cc +++ /dev/null @@ -1,186 +0,0 @@ -#include -#include -#include - -#include "system/hardware/hw.h" -#include "selfdrive/ui/qt/util.h" -#include "selfdrive/ui/qt/qt_window.h" -#include "selfdrive/ui/qt/setup/updater.h" -#include "selfdrive/ui/qt/network/networking.h" - -Updater::Updater(const QString &updater_path, const QString &manifest_path, QWidget *parent) - : updater(updater_path), manifest(manifest_path), QStackedWidget(parent) { - - assert(updater.size()); - assert(manifest.size()); - - // initial prompt screen - prompt = new QWidget; - { - QVBoxLayout *layout = new QVBoxLayout(prompt); - layout->setContentsMargins(100, 250, 100, 100); - - QLabel *title = new QLabel(tr("Update Required")); - title->setStyleSheet("font-size: 80px; font-weight: bold;"); - layout->addWidget(title); - - layout->addSpacing(75); - - QLabel *desc = new QLabel(tr("An operating system update is required. Connect your device to Wi-Fi for the fastest update experience. The download size is approximately 1GB.")); - desc->setWordWrap(true); - desc->setStyleSheet("font-size: 65px;"); - layout->addWidget(desc); - - layout->addStretch(); - - QHBoxLayout *hlayout = new QHBoxLayout; - hlayout->setSpacing(30); - layout->addLayout(hlayout); - - QPushButton *connect = new QPushButton(tr("Connect to Wi-Fi")); - connect->setObjectName("navBtn"); - QObject::connect(connect, &QPushButton::clicked, [=]() { - setCurrentWidget(wifi); - }); - hlayout->addWidget(connect); - - QPushButton *install = new QPushButton(tr("Install")); - install->setObjectName("navBtn"); - install->setStyleSheet(R"( - QPushButton { - background-color: #465BEA; - } - QPushButton:pressed { - background-color: #3049F4; - } - )"); - QObject::connect(install, &QPushButton::clicked, this, &Updater::installUpdate); - hlayout->addWidget(install); - } - - // wifi connection screen - wifi = new QWidget; - { - QVBoxLayout *layout = new QVBoxLayout(wifi); - layout->setContentsMargins(100, 100, 100, 100); - - Networking *networking = new Networking(this, false); - networking->setStyleSheet("Networking { background-color: #292929; border-radius: 13px; }"); - layout->addWidget(networking, 1); - - QPushButton *back = new QPushButton(tr("Back")); - back->setObjectName("navBtn"); - back->setStyleSheet("padding-left: 60px; padding-right: 60px;"); - QObject::connect(back, &QPushButton::clicked, [=]() { - setCurrentWidget(prompt); - }); - layout->addWidget(back, 0, Qt::AlignLeft); - } - - // progress screen - progress = new QWidget; - { - QVBoxLayout *layout = new QVBoxLayout(progress); - layout->setContentsMargins(150, 330, 150, 150); - layout->setSpacing(0); - - text = new QLabel(tr("Loading...")); - text->setStyleSheet("font-size: 90px; font-weight: 600;"); - layout->addWidget(text, 0, Qt::AlignTop); - - layout->addSpacing(100); - - bar = new QProgressBar(); - bar->setRange(0, 100); - bar->setTextVisible(false); - bar->setFixedHeight(72); - layout->addWidget(bar, 0, Qt::AlignTop); - - layout->addStretch(); - - reboot = new QPushButton(tr("Reboot")); - reboot->setObjectName("navBtn"); - reboot->setStyleSheet("padding-left: 60px; padding-right: 60px;"); - QObject::connect(reboot, &QPushButton::clicked, [=]() { - Hardware::reboot(); - }); - layout->addWidget(reboot, 0, Qt::AlignLeft); - reboot->hide(); - - layout->addStretch(); - } - - addWidget(prompt); - addWidget(wifi); - addWidget(progress); - - setStyleSheet(R"( - * { - color: white; - outline: none; - font-family: Inter; - } - Updater { - color: white; - background-color: black; - } - QPushButton#navBtn { - height: 160; - font-size: 55px; - font-weight: 400; - border-radius: 10px; - background-color: #333333; - } - QPushButton#navBtn:pressed { - background-color: #444444; - } - QProgressBar { - border: none; - background-color: #292929; - } - QProgressBar::chunk { - background-color: #364DEF; - } - )"); -} - -void Updater::installUpdate() { - setCurrentWidget(progress); - QObject::connect(&proc, &QProcess::readyReadStandardOutput, this, &Updater::readProgress); - QObject::connect(&proc, QOverload::of(&QProcess::finished), this, &Updater::updateFinished); - proc.setProcessChannelMode(QProcess::ForwardedErrorChannel); - proc.start(updater, {"--swap", manifest}); -} - -void Updater::readProgress() { - auto lines = QString(proc.readAllStandardOutput()); - for (const QString &line : lines.trimmed().split("\n")) { - auto parts = line.split(":"); - if (parts.size() == 2) { - text->setText(parts[0]); - bar->setValue((int)parts[1].toDouble()); - } else { - qDebug() << line; - } - } - update(); -} - -void Updater::updateFinished(int exitCode, QProcess::ExitStatus exitStatus) { - qDebug() << "finished with " << exitCode; - if (exitCode == 0) { - Hardware::reboot(); - } else { - text->setText(tr("Update failed")); - reboot->show(); - } -} - -int main(int argc, char *argv[]) { - initApp(argc, argv); - QApplication a(argc, argv); - Updater updater(argv[1], argv[2]); - setMainWindow(&updater); - a.installEventFilter(&updater); - return a.exec(); -} diff --git a/selfdrive/ui/qt/setup/updater.h b/selfdrive/ui/qt/setup/updater.h deleted file mode 100644 index ce46c0a..0000000 --- a/selfdrive/ui/qt/setup/updater.h +++ /dev/null @@ -1,29 +0,0 @@ -#pragma once - -#include -#include -#include -#include -#include -#include - -class Updater : public QStackedWidget { - Q_OBJECT - -public: - explicit Updater(const QString &updater_path, const QString &manifest_path, QWidget *parent = 0); - -private slots: - void installUpdate(); - void readProgress(); - void updateFinished(int exitCode, QProcess::ExitStatus exitStatus); - -private: - QProcess proc; - QString updater, manifest; - - QLabel *text; - QProgressBar *bar; - QPushButton *reboot; - QWidget *prompt, *wifi, *progress; -}; diff --git a/selfdrive/ui/qt/sidebar.cc b/selfdrive/ui/qt/sidebar.cc deleted file mode 100644 index 8e04d54..0000000 --- a/selfdrive/ui/qt/sidebar.cc +++ /dev/null @@ -1,331 +0,0 @@ -#include "selfdrive/ui/qt/sidebar.h" - -#include - -#include "selfdrive/ui/qt/util.h" - -void Sidebar::drawMetric(QPainter &p, const QPair &label, QColor c, int y) { - const QRect rect = {30, y, 240, 126}; - - p.setPen(Qt::NoPen); - p.setBrush(QBrush(c)); - p.setClipRect(rect.x() + 4, rect.y(), 18, rect.height(), Qt::ClipOperation::ReplaceClip); - p.drawRoundedRect(QRect(rect.x() + 4, rect.y() + 4, 100, 118), 18, 18); - p.setClipping(false); - - QPen pen = QPen(QColor(0xff, 0xff, 0xff, 0x55)); - pen.setWidth(2); - p.setPen(pen); - p.setBrush(Qt::NoBrush); - p.drawRoundedRect(rect, 20, 20); - - p.setPen(QColor(0xff, 0xff, 0xff)); - p.setFont(InterFont(35, QFont::DemiBold)); - p.drawText(rect.adjusted(22, 0, 0, 0), Qt::AlignCenter, label.first + "\n" + label.second); -} - -Sidebar::Sidebar(QWidget *parent) : QFrame(parent), onroad(false), flag_pressed(false), settings_pressed(false), scene(uiState()->scene) { - home_img = loadPixmap("../assets/images/button_home.png", home_btn.size()); - flag_img = loadPixmap("../assets/images/button_flag.png", home_btn.size()); - settings_img = loadPixmap("../assets/images/button_settings.png", settings_btn.size(), Qt::IgnoreAspectRatio); - - connect(this, &Sidebar::valueChanged, [=] { update(); }); - - setAttribute(Qt::WA_OpaquePaintEvent); - setSizePolicy(QSizePolicy::Fixed, QSizePolicy::Expanding); - setFixedWidth(300); - - QObject::connect(uiState(), &UIState::uiUpdate, this, &Sidebar::updateState); - - pm = std::make_unique>({"userFlag"}); - - // FrogPilot variables - isCPU = params.getBool("ShowCPU"); - isGPU = params.getBool("ShowGPU"); - - isIP = params.getBool("ShowIP"); - - isMemoryUsage = params.getBool("ShowMemoryUsage"); - isStorageLeft = params.getBool("ShowStorageLeft"); - isStorageUsed = params.getBool("ShowStorageUsed"); - - holidayThemeConfiguration = { - {1, {"april_fools", {QColor(255, 165, 0)}}}, - {2, {"christmas", {QColor(0, 72, 255)}}}, - {3, {"cinco_de_mayo", {QColor(255, 0, 0)}}}, - {4, {"easter", {QColor(200, 150, 200)}}}, - {5, {"fourth_of_july", {QColor(0, 72, 255)}}}, - {6, {"halloween", {QColor(255, 0, 0)}}}, - {7, {"new_years_day", {QColor(23, 134, 68)}}}, - {8, {"st_patricks_day", {QColor(0, 128, 0)}}}, - {9, {"thanksgiving", {QColor(255, 0, 0)}}}, - {10, {"valentines_day", {QColor(23, 134, 68)}}}, - {11, {"world_frog_day", {QColor(0, 72, 255)}}}, - }; - - for (auto &[key, themeData] : holidayThemeConfiguration) { - QString &themeName = themeData.first; - QString base = QString("../frogpilot/assets/holiday_themes/%1/images").arg(themeName); - std::vector paths = {base + "/button_home.png", base + "/button_flag.png", base + "/button_settings.png"}; - - home_imgs[key] = loadPixmap(paths[0], home_btn.size()); - flag_imgs[key] = loadPixmap(paths[1], home_btn.size()); - settings_imgs[key] = loadPixmap(paths[2], settings_btn.size(), Qt::IgnoreAspectRatio); - } - - themeConfiguration = { - {0, {"stock", {QColor(255, 255, 255)}}}, - {1, {"frog_theme", {QColor(23, 134, 68)}}}, - {2, {"tesla_theme", {QColor(0, 72, 255)}}}, - {3, {"stalin_theme", {QColor(255, 0, 0)}}} - }; - - for (auto &[key, themeData] : themeConfiguration) { - QString &themeName = themeData.first; - QString base = themeName == "stock" ? "../assets/images" : QString("../frogpilot/assets/custom_themes/%1/images").arg(themeName); - std::vector paths = {base + "/button_home.png", base + "/button_flag.png", base + "/button_settings.png"}; - - home_imgs[key] = loadPixmap(paths[0], home_btn.size()); - flag_imgs[key] = loadPixmap(paths[1], home_btn.size()); - settings_imgs[key] = loadPixmap(paths[2], settings_btn.size(), Qt::IgnoreAspectRatio); - } - - home_img = home_imgs[scene.custom_icons]; - flag_img = flag_imgs[scene.custom_icons]; - settings_img = settings_imgs[scene.custom_icons]; - - currentColors = themeConfiguration[scene.custom_colors].second; -} - -void Sidebar::mousePressEvent(QMouseEvent *event) { - // Declare the click boxes - QRect cpuRect = {30, 496, 240, 126}; - QRect memoryRect = {30, 654, 240, 126}; - QRect networkRect = {30, 196, 240, 126}; - QRect tempRect = {30, 338, 240, 126}; - - static int showChip = 0; - static int showMemory = 0; - static int showNetwork = 0; - static int showTemp = 0; - - // Swap between the respective metrics upon tap - if (cpuRect.contains(event->pos())) { - showChip = (showChip + 1) % 3; - isCPU = (showChip == 1); - isGPU = (showChip == 2); - params.putBoolNonBlocking("ShowCPU", isCPU); - params.putBoolNonBlocking("ShowGPU", isGPU); - update(); - } else if (memoryRect.contains(event->pos())) { - showMemory = (showMemory + 1) % 4; - isMemoryUsage = (showMemory == 1); - isStorageLeft = (showMemory == 2); - isStorageUsed = (showMemory == 3); - params.putBoolNonBlocking("ShowMemoryUsage", isMemoryUsage); - params.putBoolNonBlocking("ShowStorageLeft", isStorageLeft); - params.putBoolNonBlocking("ShowStorageUsed", isStorageUsed); - update(); - } else if (networkRect.contains(event->pos())) { - showNetwork = (showNetwork + 1) % 2; - isIP = (showNetwork == 1); - params.putBoolNonBlocking("ShowIP", isIP); - update(); - } else if (tempRect.contains(event->pos())) { - showTemp = (showTemp + 1) % 3; - scene.fahrenheit = showTemp == 2; - scene.numerical_temp = showTemp != 0; - params.putBoolNonBlocking("Fahrenheit", showTemp == 2); - params.putBoolNonBlocking("NumericalTemp", showTemp != 0); - update(); - } else if (onroad && home_btn.contains(event->pos())) { - flag_pressed = true; - update(); - } else if (settings_btn.contains(event->pos())) { - settings_pressed = true; - update(); - } -} - -void Sidebar::mouseReleaseEvent(QMouseEvent *event) { - if (flag_pressed || settings_pressed) { - flag_pressed = settings_pressed = false; - update(); - } - if (home_btn.contains(event->pos())) { - MessageBuilder msg; - msg.initEvent().initUserFlag(); - pm->send("userFlag", msg); - } else if (settings_btn.contains(event->pos())) { - emit openSettings(); - } -} - -void Sidebar::offroadTransition(bool offroad) { - onroad = !offroad; - update(); -} - -void Sidebar::updateState(const UIState &s) { - if (!isVisible()) return; - - auto &sm = *(s.sm); - - auto deviceState = sm["deviceState"].getDeviceState(); - setProperty("netType", network_type[deviceState.getNetworkType()]); - int strength = (int)deviceState.getNetworkStrength(); - setProperty("netStrength", strength > 0 ? strength + 1 : 0); - - // FrogPilot properties - if (scene.current_holiday_theme != 0) { - home_img = home_imgs[scene.current_holiday_theme]; - flag_img = flag_imgs[scene.current_holiday_theme]; - settings_img = settings_imgs[scene.current_holiday_theme]; - currentColors = holidayThemeConfiguration[scene.current_holiday_theme].second; - } else { - home_img = home_imgs[scene.custom_icons]; - flag_img = flag_imgs[scene.custom_icons]; - settings_img = settings_imgs[scene.custom_icons]; - currentColors = themeConfiguration[scene.custom_colors].second; - } - - auto frogpilotDeviceState = sm["frogpilotDeviceState"].getFrogpilotDeviceState(); - - bool isNumericalTemp = scene.numerical_temp; - - int maxTempC = deviceState.getMaxTempC(); - QString max_temp = scene.fahrenheit ? QString::number(maxTempC * 9 / 5 + 32) + "°F" : QString::number(maxTempC) + "°C"; - QColor theme_color = currentColors[0]; - - // FrogPilot metrics - if (isCPU || isGPU) { - auto cpu_loads = deviceState.getCpuUsagePercent(); - int cpu_usage = std::accumulate(cpu_loads.begin(), cpu_loads.end(), 0) / cpu_loads.size(); - int gpu_usage = deviceState.getGpuUsagePercent(); - - QString cpu = QString::number(cpu_usage) + "%"; - QString gpu = QString::number(gpu_usage) + "%"; - - QString metric = isGPU ? gpu : cpu; - int usage = isGPU ? gpu_usage : cpu_usage; - - ItemStatus cpuStatus = {{tr(isGPU ? "GPU" : "CPU"), metric}, theme_color}; - if (usage >= 85) { - cpuStatus = {{tr(isGPU ? "GPU" : "CPU"), metric}, danger_color}; - } else if (usage >= 70) { - cpuStatus = {{tr(isGPU ? "GPU" : "CPU"), metric}, warning_color}; - } - setProperty("cpuStatus", QVariant::fromValue(cpuStatus)); - } - - if (isMemoryUsage || isStorageLeft || isStorageUsed) { - int memory_usage = deviceState.getMemoryUsagePercent(); - int storage_left = frogpilotDeviceState.getFreeSpace(); - int storage_used = frogpilotDeviceState.getUsedSpace(); - - QString memory = QString::number(memory_usage) + "%"; - QString storage = QString::number(isStorageLeft ? storage_left : storage_used) + " GB"; - - if (isMemoryUsage) { - ItemStatus memoryStatus = {{tr("MEMORY"), memory}, theme_color}; - if (memory_usage >= 85) { - memoryStatus = {{tr("MEMORY"), memory}, danger_color}; - } else if (memory_usage >= 70) { - memoryStatus = {{tr("MEMORY"), memory}, warning_color}; - } - setProperty("memoryStatus", QVariant::fromValue(memoryStatus)); - } else { - ItemStatus storageStatus = {{tr(isStorageLeft ? "LEFT" : "USED"), storage}, theme_color}; - if (10 <= storage_left && storage_left < 25) { - storageStatus = {{tr(isStorageLeft ? "LEFT" : "USED"), storage}, warning_color}; - } else if (storage_left < 10) { - storageStatus = {{tr(isStorageLeft ? "LEFT" : "USED"), storage}, danger_color}; - } - setProperty("storageStatus", QVariant::fromValue(storageStatus)); - } - } - - ItemStatus connectStatus; - auto last_ping = deviceState.getLastAthenaPingTime(); - if (last_ping == 0) { - connectStatus = ItemStatus{{tr("CONNECT"), tr("OFFLINE")}, warning_color}; - } else { - connectStatus = nanos_since_boot() - last_ping < 80e9 - ? ItemStatus{{tr("CONNECT"), tr("ONLINE")}, theme_color} - : ItemStatus{{tr("CONNECT"), tr("ERROR")}, danger_color}; - } - setProperty("connectStatus", QVariant::fromValue(connectStatus)); - - ItemStatus tempStatus = {{tr("TEMP"), isNumericalTemp ? max_temp : tr("HIGH")}, danger_color}; - auto ts = deviceState.getThermalStatus(); - if (ts == cereal::DeviceState::ThermalStatus::GREEN) { - tempStatus = {{tr("TEMP"), isNumericalTemp ? max_temp : tr("GOOD")}, theme_color}; - } else if (ts == cereal::DeviceState::ThermalStatus::YELLOW) { - tempStatus = {{tr("TEMP"), isNumericalTemp ? max_temp : tr("OK")}, warning_color}; - } - setProperty("tempStatus", QVariant::fromValue(tempStatus)); - - ItemStatus pandaStatus = {{tr("VEHICLE"), tr("ONLINE")}, theme_color}; - if (s.scene.pandaType == cereal::PandaState::PandaType::UNKNOWN) { - pandaStatus = {{tr("NO"), tr("PANDA")}, danger_color}; - } else if (s.scene.started && !sm["liveLocationKalman"].getLiveLocationKalman().getGpsOK()) { - pandaStatus = {{tr("GPS"), tr("SEARCH")}, warning_color}; - } - setProperty("pandaStatus", QVariant::fromValue(pandaStatus)); -} - -void Sidebar::paintEvent(QPaintEvent *event) { - QPainter p(this); - p.setPen(Qt::NoPen); - p.setRenderHint(QPainter::Antialiasing); - - p.fillRect(rect(), QColor(57, 57, 57)); - - // buttons - p.setOpacity(settings_pressed ? 0.65 : 1.0); - p.drawPixmap(settings_btn.x(), settings_btn.y(), settings_img); - p.setOpacity(onroad && flag_pressed ? 0.65 : 1.0); - p.drawPixmap(home_btn.x(), home_btn.y(), onroad ? flag_img : home_img); - p.setOpacity(1.0); - - // network - int x = 58; - const QColor gray(0x54, 0x54, 0x54); - p.setFont(InterFont(35)); - - if (isIP) { - p.setPen(QColor(0xff, 0xff, 0xff)); - p.save(); - p.setFont(InterFont(30)); - QRect ipBox = QRect(50, 196, 225, 27); - p.drawText(ipBox, Qt::AlignLeft | Qt::AlignVCenter, uiState()->wifi->getIp4Address()); - p.restore(); - } else { - for (int i = 0; i < 5; ++i) { - p.setBrush(i < net_strength ? Qt::white : gray); - p.drawEllipse(x, 196, 27, 27); - x += 37; - } - p.setPen(QColor(0xff, 0xff, 0xff)); - } - - const QRect r = QRect(50, 247, 100, 50); - p.drawText(r, Qt::AlignCenter, net_type); - - // metrics - drawMetric(p, temp_status.first, temp_status.second, 338); - - if (isCPU || isGPU) { - drawMetric(p, cpu_status.first, cpu_status.second, 496); - } else { - drawMetric(p, panda_status.first, panda_status.second, 496); - } - - if (isMemoryUsage) { - drawMetric(p, memory_status.first, memory_status.second, 654); - } else if (isStorageLeft || isStorageUsed) { - drawMetric(p, storage_status.first, storage_status.second, 654); - } else { - drawMetric(p, connect_status.first, connect_status.second, 654); - } -} diff --git a/selfdrive/ui/qt/sidebar.h b/selfdrive/ui/qt/sidebar.h deleted file mode 100644 index 5fd7f14..0000000 --- a/selfdrive/ui/qt/sidebar.h +++ /dev/null @@ -1,87 +0,0 @@ -#pragma once - -#include - -#include -#include - -#include "selfdrive/ui/ui.h" - -typedef QPair, QColor> ItemStatus; -Q_DECLARE_METATYPE(ItemStatus); - -class Sidebar : public QFrame { - Q_OBJECT - Q_PROPERTY(ItemStatus connectStatus MEMBER connect_status NOTIFY valueChanged); - Q_PROPERTY(ItemStatus pandaStatus MEMBER panda_status NOTIFY valueChanged); - Q_PROPERTY(ItemStatus tempStatus MEMBER temp_status NOTIFY valueChanged); - Q_PROPERTY(QString netType MEMBER net_type NOTIFY valueChanged); - Q_PROPERTY(int netStrength MEMBER net_strength NOTIFY valueChanged); - - // FrogPilot properties - Q_PROPERTY(ItemStatus cpuStatus MEMBER cpu_status NOTIFY valueChanged) - Q_PROPERTY(ItemStatus memoryStatus MEMBER memory_status NOTIFY valueChanged) - Q_PROPERTY(ItemStatus storageStatus MEMBER storage_status NOTIFY valueChanged) - -public: - explicit Sidebar(QWidget* parent = 0); - -signals: - void openSettings(int index = 0, const QString ¶m = ""); - void valueChanged(); - -public slots: - void offroadTransition(bool offroad); - void updateState(const UIState &s); - -protected: - void paintEvent(QPaintEvent *event) override; - void mousePressEvent(QMouseEvent *event) override; - void mouseReleaseEvent(QMouseEvent *event) override; - void drawMetric(QPainter &p, const QPair &label, QColor c, int y); - - QPixmap home_img, flag_img, settings_img; - bool onroad, flag_pressed, settings_pressed; - const QMap network_type = { - {cereal::DeviceState::NetworkType::NONE, tr("--")}, - {cereal::DeviceState::NetworkType::WIFI, tr("Wi-Fi")}, - {cereal::DeviceState::NetworkType::ETHERNET, tr("ETH")}, - {cereal::DeviceState::NetworkType::CELL2_G, tr("2G")}, - {cereal::DeviceState::NetworkType::CELL3_G, tr("3G")}, - {cereal::DeviceState::NetworkType::CELL4_G, tr("LTE")}, - {cereal::DeviceState::NetworkType::CELL5_G, tr("5G")} - }; - - const QRect home_btn = QRect(60, 860, 180, 180); - const QRect settings_btn = QRect(50, 35, 200, 117); - const QColor good_color = QColor(255, 255, 255); - const QColor warning_color = QColor(218, 202, 37); - const QColor danger_color = QColor(201, 34, 49); - - ItemStatus connect_status, panda_status, temp_status; - QString net_type; - int net_strength = 0; - -private: - std::unique_ptr pm; - - // FrogPilot variables - Params params; - UIScene &scene; - - ItemStatus cpu_status, memory_status, storage_status; - - bool isCPU; - bool isGPU; - bool isIP; - bool isMemoryUsage; - bool isStorageLeft; - bool isStorageUsed; - - std::unordered_map>> holidayThemeConfiguration; - std::unordered_map>> themeConfiguration; - std::unordered_map flag_imgs; - std::unordered_map home_imgs; - std::unordered_map settings_imgs; - std::vector currentColors; -}; diff --git a/selfdrive/ui/qt/spinner.cc b/selfdrive/ui/qt/spinner.cc deleted file mode 100644 index 7ca2f1a..0000000 --- a/selfdrive/ui/qt/spinner.cc +++ /dev/null @@ -1,120 +0,0 @@ -#include "selfdrive/ui/qt/spinner.h" - -#include -#include -#include -#include - -#include -#include -#include -#include -#include - -#include "system/hardware/hw.h" -#include "selfdrive/ui/qt/qt_window.h" -#include "selfdrive/ui/qt/util.h" - -TrackWidget::TrackWidget(QWidget *parent) : QWidget(parent) { - setAttribute(Qt::WA_OpaquePaintEvent); - setFixedSize(spinner_size); - - // pre-compute all the track imgs. make this a gif instead? - QPixmap comma_img = loadPixmap("../assets/img_spinner_comma.png", spinner_size); - QPixmap track_img = loadPixmap("../assets/img_spinner_track.png", spinner_size); - - QTransform transform(1, 0, 0, 1, width() / 2, height() / 2); - QPixmap pm(spinner_size); - QPainter p(&pm); - p.setRenderHint(QPainter::SmoothPixmapTransform); - for (int i = 0; i < track_imgs.size(); ++i) { - p.resetTransform(); - p.fillRect(0, 0, spinner_size.width(), spinner_size.height(), Qt::black); - p.drawPixmap(0, 0, comma_img); - p.setTransform(transform.rotate(360 / spinner_fps)); - p.drawPixmap(-width() / 2, -height() / 2, track_img); - track_imgs[i] = pm.copy(); - } - - m_anim.setDuration(1000); - m_anim.setStartValue(0); - m_anim.setEndValue(int(track_imgs.size() -1)); - m_anim.setLoopCount(-1); - m_anim.start(); - connect(&m_anim, SIGNAL(valueChanged(QVariant)), SLOT(update())); -} - -void TrackWidget::paintEvent(QPaintEvent *event) { - QPainter painter(this); - painter.drawPixmap(0, 0, track_imgs[m_anim.currentValue().toInt()]); -} - -// Spinner - -Spinner::Spinner(QWidget *parent) : QWidget(parent) { - QGridLayout *main_layout = new QGridLayout(this); - main_layout->setSpacing(0); - main_layout->setMargin(200); - - main_layout->addWidget(new TrackWidget(this), 0, 0, Qt::AlignHCenter | Qt::AlignVCenter); - - text = new QLabel(); - text->setWordWrap(true); - text->setVisible(false); - text->setAlignment(Qt::AlignCenter); - main_layout->addWidget(text, 1, 0, Qt::AlignHCenter); - - progress_bar = new QProgressBar(); - progress_bar->setRange(5, 100); - progress_bar->setTextVisible(false); - progress_bar->setVisible(false); - progress_bar->setFixedHeight(20); - main_layout->addWidget(progress_bar, 1, 0, Qt::AlignHCenter); - - setStyleSheet(R"( - Spinner { - background-color: black; - } - QLabel { - color: white; - font-size: 80px; - background-color: transparent; - } - QProgressBar { - background-color: #373737; - width: 1000px; - border solid white; - border-radius: 10px; - } - QProgressBar::chunk { - border-radius: 10px; - background-color: rgba(23, 134, 68, 255); - } - )"); - - notifier = new QSocketNotifier(fileno(stdin), QSocketNotifier::Read); - QObject::connect(notifier, &QSocketNotifier::activated, this, &Spinner::update); -} - -void Spinner::update(int n) { - std::string line; - std::getline(std::cin, line); - - if (line.length()) { - bool number = std::all_of(line.begin(), line.end(), ::isdigit); - text->setVisible(!number); - progress_bar->setVisible(number); - text->setText(QString::fromStdString(line)); - if (number) { - progress_bar->setValue(std::stoi(line)); - } - } -} - -int main(int argc, char *argv[]) { - initApp(argc, argv); - QApplication a(argc, argv); - Spinner spinner; - setMainWindow(&spinner); - return a.exec(); -} diff --git a/selfdrive/ui/qt/spinner.h b/selfdrive/ui/qt/spinner.h deleted file mode 100644 index 43d90a7..0000000 --- a/selfdrive/ui/qt/spinner.h +++ /dev/null @@ -1,37 +0,0 @@ -#include - -#include -#include -#include -#include -#include -#include - -constexpr int spinner_fps = 30; -constexpr QSize spinner_size = QSize(360, 360); - -class TrackWidget : public QWidget { - Q_OBJECT -public: - TrackWidget(QWidget *parent = nullptr); - -private: - void paintEvent(QPaintEvent *event) override; - std::array track_imgs; - QVariantAnimation m_anim; -}; - -class Spinner : public QWidget { - Q_OBJECT - -public: - explicit Spinner(QWidget *parent = 0); - -private: - QLabel *text; - QProgressBar *progress_bar; - QSocketNotifier *notifier; - -public slots: - void update(int n); -}; diff --git a/selfdrive/ui/qt/text.cc b/selfdrive/ui/qt/text.cc deleted file mode 100644 index 21ec5ee..0000000 --- a/selfdrive/ui/qt/text.cc +++ /dev/null @@ -1,64 +0,0 @@ -#include -#include -#include -#include -#include -#include - -#include "system/hardware/hw.h" -#include "selfdrive/ui/qt/util.h" -#include "selfdrive/ui/qt/qt_window.h" -#include "selfdrive/ui/qt/widgets/scrollview.h" - -int main(int argc, char *argv[]) { - initApp(argc, argv); - QApplication a(argc, argv); - QWidget window; - setMainWindow(&window); - - QGridLayout *main_layout = new QGridLayout(&window); - main_layout->setMargin(50); - - QLabel *label = new QLabel(argv[1]); - label->setWordWrap(true); - label->setSizePolicy(QSizePolicy::Preferred, QSizePolicy::MinimumExpanding); - ScrollView *scroll = new ScrollView(label); - scroll->setVerticalScrollBarPolicy(Qt::ScrollBarAsNeeded); - main_layout->addWidget(scroll, 0, 0, Qt::AlignTop); - - // Scroll to the bottom - QObject::connect(scroll->verticalScrollBar(), &QAbstractSlider::rangeChanged, [=]() { - scroll->verticalScrollBar()->setValue(scroll->verticalScrollBar()->maximum()); - }); - - QPushButton *btn = new QPushButton(); -#ifdef __aarch64__ - btn->setText(QObject::tr("Reboot")); - QObject::connect(btn, &QPushButton::clicked, [=]() { - Hardware::reboot(); - }); -#else - btn->setText(QObject::tr("Exit")); - QObject::connect(btn, &QPushButton::clicked, &a, &QApplication::quit); -#endif - main_layout->addWidget(btn, 0, 0, Qt::AlignRight | Qt::AlignBottom); - - window.setStyleSheet(R"( - * { - outline: none; - color: white; - background-color: black; - font-size: 60px; - } - QPushButton { - padding: 50px; - padding-right: 100px; - padding-left: 100px; - border: 2px solid white; - border-radius: 20px; - margin-right: 40px; - } - )"); - - return a.exec(); -} diff --git a/selfdrive/ui/qt/util.cc b/selfdrive/ui/qt/util.cc deleted file mode 100644 index a83d353..0000000 --- a/selfdrive/ui/qt/util.cc +++ /dev/null @@ -1,276 +0,0 @@ -#include "selfdrive/ui/qt/util.h" - -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include "common/swaglog.h" -#include "system/hardware/hw.h" - -QString getVersion() { - static QString version = QString::fromStdString(Params().get("Version")); - return version; -} - -QString getBrand() { - return QObject::tr("FrogPilot"); -} - -QString getUserAgent() { - return "openpilot-" + getVersion(); -} - -std::optional getDongleId() { - std::string id = Params().get("DongleId"); - - if (!id.empty() && (id != "UnregisteredDevice")) { - return QString::fromStdString(id); - } else { - return {}; - } -} - -QMap getSupportedLanguages() { - QFile f(":/languages.json"); - f.open(QIODevice::ReadOnly | QIODevice::Text); - QString val = f.readAll(); - - QJsonObject obj = QJsonDocument::fromJson(val.toUtf8()).object(); - QMap map; - for (auto key : obj.keys()) { - map[key] = obj[key].toString(); - } - return map; -} - -QString timeAgo(const QDateTime &date) { - int diff = date.secsTo(QDateTime::currentDateTimeUtc()); - - QString s; - if (diff < 60) { - s = "now"; - } else if (diff < 60 * 60) { - int minutes = diff / 60; - s = QObject::tr("%n minute(s) ago", "", minutes); - } else if (diff < 60 * 60 * 24) { - int hours = diff / (60 * 60); - s = QObject::tr("%n hour(s) ago", "", hours); - } else if (diff < 3600 * 24 * 7) { - int days = diff / (60 * 60 * 24); - s = QObject::tr("%n day(s) ago", "", days); - } else { - s = date.date().toString(); - } - - return s; -} - -void setQtSurfaceFormat() { - QSurfaceFormat fmt; -#ifdef __APPLE__ - fmt.setVersion(3, 2); - fmt.setProfile(QSurfaceFormat::OpenGLContextProfile::CoreProfile); - fmt.setRenderableType(QSurfaceFormat::OpenGL); -#else - fmt.setRenderableType(QSurfaceFormat::OpenGLES); -#endif - fmt.setSamples(16); - fmt.setStencilBufferSize(1); - QSurfaceFormat::setDefaultFormat(fmt); -} - -void sigTermHandler(int s) { - std::signal(s, SIG_DFL); - qApp->quit(); -} - -void initApp(int argc, char *argv[], bool disable_hidpi) { - Hardware::set_display_power(true); - Hardware::set_brightness(65); - - // setup signal handlers to exit gracefully - std::signal(SIGINT, sigTermHandler); - std::signal(SIGTERM, sigTermHandler); - - if (disable_hidpi) { -#ifdef __APPLE__ - // Get the devicePixelRatio, and scale accordingly to maintain 1:1 rendering - QApplication tmp(argc, argv); - qputenv("QT_SCALE_FACTOR", QString::number(1.0 / tmp.devicePixelRatio() ).toLocal8Bit()); -#endif - } - - qputenv("QT_DBL_CLICK_DIST", QByteArray::number(150)); - - // ensure the current dir matches the exectuable's directory - QApplication tmp(argc, argv); - QString appDir = QCoreApplication::applicationDirPath(); - QDir::setCurrent(appDir); - - setQtSurfaceFormat(); -} - -void swagLogMessageHandler(QtMsgType type, const QMessageLogContext &context, const QString &msg) { - static std::map levels = { - {QtMsgType::QtDebugMsg, CLOUDLOG_DEBUG}, - {QtMsgType::QtInfoMsg, CLOUDLOG_INFO}, - {QtMsgType::QtWarningMsg, CLOUDLOG_WARNING}, - {QtMsgType::QtCriticalMsg, CLOUDLOG_ERROR}, - {QtMsgType::QtSystemMsg, CLOUDLOG_ERROR}, - {QtMsgType::QtFatalMsg, CLOUDLOG_CRITICAL}, - }; - - std::string file, function; - if (context.file != nullptr) file = context.file; - if (context.function != nullptr) function = context.function; - - auto bts = msg.toUtf8(); - cloudlog_e(levels[type], file.c_str(), context.line, function.c_str(), "%s", bts.constData()); -} - - -QWidget* topWidget(QWidget* widget) { - while (widget->parentWidget() != nullptr) widget=widget->parentWidget(); - return widget; -} - -QPixmap loadPixmap(const QString &fileName, const QSize &size, Qt::AspectRatioMode aspectRatioMode) { - if (size.isEmpty()) { - return QPixmap(fileName); - } else { - return QPixmap(fileName).scaled(size, aspectRatioMode, Qt::SmoothTransformation); - } -} - -void drawRoundedRect(QPainter &painter, const QRectF &rect, qreal xRadiusTop, qreal yRadiusTop, qreal xRadiusBottom, qreal yRadiusBottom){ - qreal w_2 = rect.width() / 2; - qreal h_2 = rect.height() / 2; - - xRadiusTop = 100 * qMin(xRadiusTop, w_2) / w_2; - yRadiusTop = 100 * qMin(yRadiusTop, h_2) / h_2; - - xRadiusBottom = 100 * qMin(xRadiusBottom, w_2) / w_2; - yRadiusBottom = 100 * qMin(yRadiusBottom, h_2) / h_2; - - qreal x = rect.x(); - qreal y = rect.y(); - qreal w = rect.width(); - qreal h = rect.height(); - - qreal rxx2Top = w*xRadiusTop/100; - qreal ryy2Top = h*yRadiusTop/100; - - qreal rxx2Bottom = w*xRadiusBottom/100; - qreal ryy2Bottom = h*yRadiusBottom/100; - - QPainterPath path; - path.arcMoveTo(x, y, rxx2Top, ryy2Top, 180); - path.arcTo(x, y, rxx2Top, ryy2Top, 180, -90); - path.arcTo(x+w-rxx2Top, y, rxx2Top, ryy2Top, 90, -90); - path.arcTo(x+w-rxx2Bottom, y+h-ryy2Bottom, rxx2Bottom, ryy2Bottom, 0, -90); - path.arcTo(x, y+h-ryy2Bottom, rxx2Bottom, ryy2Bottom, 270, -90); - path.closeSubpath(); - - painter.drawPath(path); -} - -QColor interpColor(float xv, std::vector xp, std::vector fp) { - assert(xp.size() == fp.size()); - - int N = xp.size(); - int hi = 0; - - while (hi < N and xv > xp[hi]) hi++; - int low = hi - 1; - - if (hi == N && xv > xp[low]) { - return fp[fp.size() - 1]; - } else if (hi == 0){ - return fp[0]; - } else { - return QColor( - (xv - xp[low]) * (fp[hi].red() - fp[low].red()) / (xp[hi] - xp[low]) + fp[low].red(), - (xv - xp[low]) * (fp[hi].green() - fp[low].green()) / (xp[hi] - xp[low]) + fp[low].green(), - (xv - xp[low]) * (fp[hi].blue() - fp[low].blue()) / (xp[hi] - xp[low]) + fp[low].blue(), - (xv - xp[low]) * (fp[hi].alpha() - fp[low].alpha()) / (xp[hi] - xp[low]) + fp[low].alpha()); - } -} - -static QHash load_bootstrap_icons() { - QHash icons; - - QFile f(":/bootstrap-icons.svg"); - if (f.open(QIODevice::ReadOnly | QIODevice::Text)) { - QDomDocument xml; - xml.setContent(&f); - QDomNode n = xml.documentElement().firstChild(); - while (!n.isNull()) { - QDomElement e = n.toElement(); - if (!e.isNull() && e.hasAttribute("id")) { - QString svg_str; - QTextStream stream(&svg_str); - n.save(stream, 0); - svg_str.replace("", ""); - icons[e.attribute("id")] = svg_str.toUtf8(); - } - n = n.nextSibling(); - } - } - return icons; -} - -QPixmap bootstrapPixmap(const QString &id) { - static QHash icons = load_bootstrap_icons(); - - QPixmap pixmap; - if (auto it = icons.find(id); it != icons.end()) { - pixmap.loadFromData(it.value(), "svg"); - } - return pixmap; -} - -bool hasLongitudinalControl(const cereal::CarParams::Reader &car_params) { - // Using the experimental longitudinal toggle, returns whether longitudinal control - // will be active without needing a restart of openpilot - return car_params.getExperimentalLongitudinalAvailable() - ? Params().getBool("ExperimentalLongitudinalEnabled") - : car_params.getOpenpilotLongitudinalControl(); -} - -// ParamWatcher - -ParamWatcher::ParamWatcher(QObject *parent) : QObject(parent) { - watcher = new QFileSystemWatcher(this); - QObject::connect(watcher, &QFileSystemWatcher::fileChanged, this, &ParamWatcher::fileChanged); -} - -void ParamWatcher::fileChanged(const QString &path) { - auto param_name = QFileInfo(path).fileName(); - auto param_value = QString::fromStdString(params.get(param_name.toStdString())); - - auto it = params_hash.find(param_name); - bool content_changed = (it == params_hash.end()) || (it.value() != param_value); - params_hash[param_name] = param_value; - // emit signal when the content changes. - if (content_changed) { - emit paramChanged(param_name, param_value); - } -} - -void ParamWatcher::addParam(const QString ¶m_name) { - watcher->addPath(QString::fromStdString(params.getParamPath(param_name.toStdString()))); -} diff --git a/selfdrive/ui/qt/util.h b/selfdrive/ui/qt/util.h deleted file mode 100644 index 2aae97b..0000000 --- a/selfdrive/ui/qt/util.h +++ /dev/null @@ -1,57 +0,0 @@ -#pragma once - -#include -#include - -#include -#include -#include -#include -#include -#include - -#include "cereal/gen/cpp/car.capnp.h" -#include "common/params.h" - -QString getVersion(); -QString getBrand(); -QString getUserAgent(); -std::optional getDongleId(); -QMap getSupportedLanguages(); -void setQtSurfaceFormat(); -void sigTermHandler(int s); -QString timeAgo(const QDateTime &date); -void swagLogMessageHandler(QtMsgType type, const QMessageLogContext &context, const QString &msg); -void initApp(int argc, char *argv[], bool disable_hidpi = true); -QWidget* topWidget(QWidget* widget); -QPixmap loadPixmap(const QString &fileName, const QSize &size = {}, Qt::AspectRatioMode aspectRatioMode = Qt::KeepAspectRatio); -QPixmap bootstrapPixmap(const QString &id); - -void drawRoundedRect(QPainter &painter, const QRectF &rect, qreal xRadiusTop, qreal yRadiusTop, qreal xRadiusBottom, qreal yRadiusBottom); -QColor interpColor(float xv, std::vector xp, std::vector fp); -bool hasLongitudinalControl(const cereal::CarParams::Reader &car_params); - -struct InterFont : public QFont { - InterFont(int pixel_size, QFont::Weight weight = QFont::Normal) : QFont("Inter") { - setPixelSize(pixel_size); - setWeight(weight); - } -}; - -class ParamWatcher : public QObject { - Q_OBJECT - -public: - ParamWatcher(QObject *parent); - void addParam(const QString ¶m_name); - -signals: - void paramChanged(const QString ¶m_name, const QString ¶m_value); - -private: - void fileChanged(const QString &path); - - QFileSystemWatcher *watcher; - QHash params_hash; - Params params; -}; diff --git a/selfdrive/ui/qt/widgets/cameraview.cc b/selfdrive/ui/qt/widgets/cameraview.cc deleted file mode 100644 index 956b953..0000000 --- a/selfdrive/ui/qt/widgets/cameraview.cc +++ /dev/null @@ -1,438 +0,0 @@ -#include "selfdrive/ui/qt/widgets/cameraview.h" - -#ifdef __APPLE__ -#include -#else -#include -#endif - -#include -#include -#include -#include - -#include -#include - -namespace { - -const char frame_vertex_shader[] = -#ifdef __APPLE__ - "#version 330 core\n" -#else - "#version 300 es\n" -#endif - "layout(location = 0) in vec4 aPosition;\n" - "layout(location = 1) in vec2 aTexCoord;\n" - "uniform mat4 uTransform;\n" - "out vec2 vTexCoord;\n" - "void main() {\n" - " gl_Position = uTransform * aPosition;\n" - " vTexCoord = aTexCoord;\n" - "}\n"; - -const char frame_fragment_shader[] = -#ifdef QCOM2 - "#version 300 es\n" - "#extension GL_OES_EGL_image_external_essl3 : enable\n" - "precision mediump float;\n" - "uniform samplerExternalOES uTexture;\n" - "in vec2 vTexCoord;\n" - "out vec4 colorOut;\n" - "void main() {\n" - " colorOut = texture(uTexture, vTexCoord);\n" - "}\n"; -#else -#ifdef __APPLE__ - "#version 330 core\n" -#else - "#version 300 es\n" - "precision mediump float;\n" -#endif - "uniform sampler2D uTextureY;\n" - "uniform sampler2D uTextureUV;\n" - "in vec2 vTexCoord;\n" - "out vec4 colorOut;\n" - "void main() {\n" - " float y = texture(uTextureY, vTexCoord).r;\n" - " vec2 uv = texture(uTextureUV, vTexCoord).rg - 0.5;\n" - " float r = y + 1.402 * uv.y;\n" - " float g = y - 0.344 * uv.x - 0.714 * uv.y;\n" - " float b = y + 1.772 * uv.x;\n" - " colorOut = vec4(r, g, b, 1.0);\n" - "}\n"; -#endif - -mat4 get_driver_view_transform(int screen_width, int screen_height, int stream_width, int stream_height) { - const float driver_view_ratio = 2.0; - const float yscale = stream_height * driver_view_ratio / stream_width; - const float xscale = yscale*screen_height/screen_width*stream_width/stream_height; - mat4 transform = (mat4){{ - xscale, 0.0, 0.0, 0.0, - 0.0, yscale, 0.0, 0.0, - 0.0, 0.0, 1.0, 0.0, - 0.0, 0.0, 0.0, 1.0, - }}; - return transform; -} - -mat4 get_fit_view_transform(float widget_aspect_ratio, float frame_aspect_ratio) { - float zx = 1, zy = 1; - if (frame_aspect_ratio > widget_aspect_ratio) { - zy = widget_aspect_ratio / frame_aspect_ratio; - } else { - zx = frame_aspect_ratio / widget_aspect_ratio; - } - - const mat4 frame_transform = {{ - zx, 0.0, 0.0, 0.0, - 0.0, zy, 0.0, 0.0, - 0.0, 0.0, 1.0, 0.0, - 0.0, 0.0, 0.0, 1.0, - }}; - return frame_transform; -} - -} // namespace - -CameraWidget::CameraWidget(std::string stream_name, VisionStreamType type, bool zoom, QWidget* parent) : - stream_name(stream_name), requested_stream_type(type), zoomed_view(zoom), QOpenGLWidget(parent) { - setAttribute(Qt::WA_OpaquePaintEvent); - qRegisterMetaType>("availableStreams"); - QObject::connect(this, &CameraWidget::vipcThreadConnected, this, &CameraWidget::vipcConnected, Qt::BlockingQueuedConnection); - QObject::connect(this, &CameraWidget::vipcThreadFrameReceived, this, &CameraWidget::vipcFrameReceived, Qt::QueuedConnection); - QObject::connect(this, &CameraWidget::vipcAvailableStreamsUpdated, this, &CameraWidget::availableStreamsUpdated, Qt::QueuedConnection); -} - -CameraWidget::~CameraWidget() { - makeCurrent(); - stopVipcThread(); - if (isValid()) { - glDeleteVertexArrays(1, &frame_vao); - glDeleteBuffers(1, &frame_vbo); - glDeleteBuffers(1, &frame_ibo); - glDeleteBuffers(2, textures); - } - doneCurrent(); -} - -// Qt uses device-independent pixels, depending on platform this may be -// different to what OpenGL uses -int CameraWidget::glWidth() { - return width() * devicePixelRatio(); -} - -int CameraWidget::glHeight() { - return height() * devicePixelRatio(); -} - -void CameraWidget::initializeGL() { - initializeOpenGLFunctions(); - - program = std::make_unique(context()); - bool ret = program->addShaderFromSourceCode(QOpenGLShader::Vertex, frame_vertex_shader); - assert(ret); - ret = program->addShaderFromSourceCode(QOpenGLShader::Fragment, frame_fragment_shader); - assert(ret); - - program->link(); - GLint frame_pos_loc = program->attributeLocation("aPosition"); - GLint frame_texcoord_loc = program->attributeLocation("aTexCoord"); - - auto [x1, x2, y1, y2] = requested_stream_type == VISION_STREAM_DRIVER ? std::tuple(0.f, 1.f, 1.f, 0.f) : std::tuple(1.f, 0.f, 1.f, 0.f); - const uint8_t frame_indicies[] = {0, 1, 2, 0, 2, 3}; - const float frame_coords[4][4] = { - {-1.0, -1.0, x2, y1}, // bl - {-1.0, 1.0, x2, y2}, // tl - { 1.0, 1.0, x1, y2}, // tr - { 1.0, -1.0, x1, y1}, // br - }; - - glGenVertexArrays(1, &frame_vao); - glBindVertexArray(frame_vao); - glGenBuffers(1, &frame_vbo); - glBindBuffer(GL_ARRAY_BUFFER, frame_vbo); - glBufferData(GL_ARRAY_BUFFER, sizeof(frame_coords), frame_coords, GL_STATIC_DRAW); - glEnableVertexAttribArray(frame_pos_loc); - glVertexAttribPointer(frame_pos_loc, 2, GL_FLOAT, GL_FALSE, - sizeof(frame_coords[0]), (const void *)0); - glEnableVertexAttribArray(frame_texcoord_loc); - glVertexAttribPointer(frame_texcoord_loc, 2, GL_FLOAT, GL_FALSE, - sizeof(frame_coords[0]), (const void *)(sizeof(float) * 2)); - glGenBuffers(1, &frame_ibo); - glBindBuffer(GL_ELEMENT_ARRAY_BUFFER, frame_ibo); - glBufferData(GL_ELEMENT_ARRAY_BUFFER, sizeof(frame_indicies), frame_indicies, GL_STATIC_DRAW); - glBindBuffer(GL_ARRAY_BUFFER, 0); - glBindVertexArray(0); - - glUseProgram(program->programId()); - -#ifdef QCOM2 - glUniform1i(program->uniformLocation("uTexture"), 0); -#else - glGenTextures(2, textures); - glUniform1i(program->uniformLocation("uTextureY"), 0); - glUniform1i(program->uniformLocation("uTextureUV"), 1); -#endif -} - -void CameraWidget::showEvent(QShowEvent *event) { - if (!vipc_thread) { - clearFrames(); - vipc_thread = new QThread(); - connect(vipc_thread, &QThread::started, [=]() { vipcThread(); }); - connect(vipc_thread, &QThread::finished, vipc_thread, &QObject::deleteLater); - vipc_thread->start(); - } -} - -void CameraWidget::stopVipcThread() { - makeCurrent(); - if (vipc_thread) { - vipc_thread->requestInterruption(); - vipc_thread->quit(); - vipc_thread->wait(); - vipc_thread = nullptr; - } - -#ifdef QCOM2 - EGLDisplay egl_display = eglGetCurrentDisplay(); - assert(egl_display != EGL_NO_DISPLAY); - for (auto &pair : egl_images) { - eglDestroyImageKHR(egl_display, pair.second); - assert(eglGetError() == EGL_SUCCESS); - } - egl_images.clear(); -#endif -} - -void CameraWidget::availableStreamsUpdated(std::set streams) { - available_streams = streams; -} - -void CameraWidget::updateFrameMat() { - int w = glWidth(), h = glHeight(); - - if (zoomed_view) { - if (active_stream_type == VISION_STREAM_DRIVER) { - if (stream_width > 0 && stream_height > 0) { - frame_mat = get_driver_view_transform(w, h, stream_width, stream_height); - if (uiState()->scene.show_driver_camera) { - frame_mat.v[0] *= -1.0; - } - } - } else { - // Project point at "infinity" to compute x and y offsets - // to ensure this ends up in the middle of the screen - // for narrow come and a little lower for wide cam. - // TODO: use proper perspective transform? - if (active_stream_type == VISION_STREAM_WIDE_ROAD) { - intrinsic_matrix = ECAM_INTRINSIC_MATRIX; - zoom = 2.0; - } else { - intrinsic_matrix = FCAM_INTRINSIC_MATRIX; - zoom = 1.1; - } - const vec3 inf = {{1000., 0., 0.}}; - const vec3 Ep = matvecmul3(calibration, inf); - const vec3 Kep = matvecmul3(intrinsic_matrix, Ep); - - float x_offset_ = (Kep.v[0] / Kep.v[2] - intrinsic_matrix.v[2]) * zoom; - float y_offset_ = (Kep.v[1] / Kep.v[2] - intrinsic_matrix.v[5]) * zoom; - - float max_x_offset = intrinsic_matrix.v[2] * zoom - w / 2 - 5; - float max_y_offset = intrinsic_matrix.v[5] * zoom - h / 2 - 5; - - x_offset = std::clamp(x_offset_, -max_x_offset, max_x_offset); - y_offset = std::clamp(y_offset_, -max_y_offset, max_y_offset); - - float zx = zoom * 2 * intrinsic_matrix.v[2] / w; - float zy = zoom * 2 * intrinsic_matrix.v[5] / h; - const mat4 frame_transform = {{ - zx, 0.0, 0.0, -x_offset / w * 2, - 0.0, zy, 0.0, y_offset / h * 2, - 0.0, 0.0, 1.0, 0.0, - 0.0, 0.0, 0.0, 1.0, - }}; - frame_mat = frame_transform; - } - } else if (stream_width > 0 && stream_height > 0) { - // fit frame to widget size - float widget_aspect_ratio = (float)w / h; - float frame_aspect_ratio = (float)stream_width / stream_height; - frame_mat = get_fit_view_transform(widget_aspect_ratio, frame_aspect_ratio); - } -} - -void CameraWidget::updateCalibration(const mat3 &calib) { - calibration = calib; -} - -void CameraWidget::paintGL() { - glClearColor(bg.redF(), bg.greenF(), bg.blueF(), bg.alphaF()); - glClear(GL_STENCIL_BUFFER_BIT | GL_COLOR_BUFFER_BIT); - - std::lock_guard lk(frame_lock); - if (frames.empty()) return; - - int frame_idx = frames.size() - 1; - - // Always draw latest frame until sync logic is more stable - // for (frame_idx = 0; frame_idx < frames.size() - 1; frame_idx++) { - // if (frames[frame_idx].first == draw_frame_id) break; - // } - - // Log duplicate/dropped frames - if (frames[frame_idx].first == prev_frame_id) { - qDebug() << "Drawing same frame twice" << frames[frame_idx].first; - } else if (frames[frame_idx].first != prev_frame_id + 1) { - qDebug() << "Skipped frame" << frames[frame_idx].first; - } - prev_frame_id = frames[frame_idx].first; - VisionBuf *frame = frames[frame_idx].second; - assert(frame != nullptr); - - updateFrameMat(); - - glViewport(0, 0, glWidth(), glHeight()); - glBindVertexArray(frame_vao); - glUseProgram(program->programId()); - glPixelStorei(GL_UNPACK_ALIGNMENT, 1); - -#ifdef QCOM2 - // no frame copy - glActiveTexture(GL_TEXTURE0); - glEGLImageTargetTexture2DOES(GL_TEXTURE_EXTERNAL_OES, egl_images[frame->idx]); - assert(glGetError() == GL_NO_ERROR); -#else - // fallback to copy - glPixelStorei(GL_UNPACK_ROW_LENGTH, stream_stride); - glActiveTexture(GL_TEXTURE0); - glBindTexture(GL_TEXTURE_2D, textures[0]); - glTexSubImage2D(GL_TEXTURE_2D, 0, 0, 0, stream_width, stream_height, GL_RED, GL_UNSIGNED_BYTE, frame->y); - assert(glGetError() == GL_NO_ERROR); - - glPixelStorei(GL_UNPACK_ROW_LENGTH, stream_stride/2); - glActiveTexture(GL_TEXTURE0 + 1); - glBindTexture(GL_TEXTURE_2D, textures[1]); - glTexSubImage2D(GL_TEXTURE_2D, 0, 0, 0, stream_width/2, stream_height/2, GL_RG, GL_UNSIGNED_BYTE, frame->uv); - assert(glGetError() == GL_NO_ERROR); -#endif - - glUniformMatrix4fv(program->uniformLocation("uTransform"), 1, GL_TRUE, frame_mat.v); - glEnableVertexAttribArray(0); - glDrawElements(GL_TRIANGLES, 6, GL_UNSIGNED_BYTE, (const void *)0); - glDisableVertexAttribArray(0); - glBindVertexArray(0); - glBindTexture(GL_TEXTURE_2D, 0); - glActiveTexture(GL_TEXTURE0); - glPixelStorei(GL_UNPACK_ALIGNMENT, 4); - glPixelStorei(GL_UNPACK_ROW_LENGTH, 0); -} - -void CameraWidget::vipcConnected(VisionIpcClient *vipc_client) { - makeCurrent(); - stream_width = vipc_client->buffers[0].width; - stream_height = vipc_client->buffers[0].height; - stream_stride = vipc_client->buffers[0].stride; - -#ifdef QCOM2 - EGLDisplay egl_display = eglGetCurrentDisplay(); - assert(egl_display != EGL_NO_DISPLAY); - for (auto &pair : egl_images) { - eglDestroyImageKHR(egl_display, pair.second); - } - egl_images.clear(); - - for (int i = 0; i < vipc_client->num_buffers; i++) { // import buffers into OpenGL - int fd = dup(vipc_client->buffers[i].fd); // eglDestroyImageKHR will close, so duplicate - EGLint img_attrs[] = { - EGL_WIDTH, (int)vipc_client->buffers[i].width, - EGL_HEIGHT, (int)vipc_client->buffers[i].height, - EGL_LINUX_DRM_FOURCC_EXT, DRM_FORMAT_NV12, - EGL_DMA_BUF_PLANE0_FD_EXT, fd, - EGL_DMA_BUF_PLANE0_OFFSET_EXT, 0, - EGL_DMA_BUF_PLANE0_PITCH_EXT, (int)vipc_client->buffers[i].stride, - EGL_DMA_BUF_PLANE1_FD_EXT, fd, - EGL_DMA_BUF_PLANE1_OFFSET_EXT, (int)vipc_client->buffers[i].uv_offset, - EGL_DMA_BUF_PLANE1_PITCH_EXT, (int)vipc_client->buffers[i].stride, - EGL_NONE - }; - egl_images[i] = eglCreateImageKHR(egl_display, EGL_NO_CONTEXT, EGL_LINUX_DMA_BUF_EXT, 0, img_attrs); - assert(eglGetError() == EGL_SUCCESS); - } -#else - glBindTexture(GL_TEXTURE_2D, textures[0]); - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR); - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR); - glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_CLAMP_TO_EDGE); - glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_CLAMP_TO_EDGE); - glTexImage2D(GL_TEXTURE_2D, 0, GL_R8, stream_width, stream_height, 0, GL_RED, GL_UNSIGNED_BYTE, nullptr); - assert(glGetError() == GL_NO_ERROR); - - glBindTexture(GL_TEXTURE_2D, textures[1]); - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR); - glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR); - glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_WRAP_S, GL_CLAMP_TO_EDGE); - glTexParameterf(GL_TEXTURE_2D, GL_TEXTURE_WRAP_T, GL_CLAMP_TO_EDGE); - glTexImage2D(GL_TEXTURE_2D, 0, GL_RG8, stream_width/2, stream_height/2, 0, GL_RG, GL_UNSIGNED_BYTE, nullptr); - assert(glGetError() == GL_NO_ERROR); -#endif -} - -void CameraWidget::vipcFrameReceived() { - update(); -} - -void CameraWidget::vipcThread() { - VisionStreamType cur_stream = requested_stream_type; - std::unique_ptr vipc_client; - VisionIpcBufExtra meta_main = {0}; - - while (!QThread::currentThread()->isInterruptionRequested()) { - if (!vipc_client || cur_stream != requested_stream_type) { - clearFrames(); - qDebug().nospace() << "connecting to stream " << requested_stream_type << ", was connected to " << cur_stream; - cur_stream = requested_stream_type; - vipc_client.reset(new VisionIpcClient(stream_name, cur_stream, false)); - } - active_stream_type = cur_stream; - - if (!vipc_client->connected) { - clearFrames(); - auto streams = VisionIpcClient::getAvailableStreams(stream_name, false); - if (streams.empty()) { - QThread::msleep(100); - continue; - } - emit vipcAvailableStreamsUpdated(streams); - - if (!vipc_client->connect(false)) { - QThread::msleep(100); - continue; - } - emit vipcThreadConnected(vipc_client.get()); - } - - if (VisionBuf *buf = vipc_client->recv(&meta_main, 1000)) { - { - std::lock_guard lk(frame_lock); - frames.push_back(std::make_pair(meta_main.frame_id, buf)); - while (frames.size() > FRAME_BUFFER_SIZE) { - frames.pop_front(); - } - } - emit vipcThreadFrameReceived(); - } else { - if (!isVisible()) { - vipc_client->connected = false; - } - } - } -} - -void CameraWidget::clearFrames() { - std::lock_guard lk(frame_lock); - frames.clear(); - available_streams.clear(); -} diff --git a/selfdrive/ui/qt/widgets/cameraview.h b/selfdrive/ui/qt/widgets/cameraview.h deleted file mode 100644 index c97038c..0000000 --- a/selfdrive/ui/qt/widgets/cameraview.h +++ /dev/null @@ -1,103 +0,0 @@ -#pragma once - -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include - -#ifdef QCOM2 -#define EGL_EGLEXT_PROTOTYPES -#define EGL_NO_X11 -#define GL_TEXTURE_EXTERNAL_OES 0x8D65 -#include -#include -#include -#endif - -#include "cereal/visionipc/visionipc_client.h" -#include "system/camerad/cameras/camera_common.h" -#include "selfdrive/ui/ui.h" - -const int FRAME_BUFFER_SIZE = 5; -static_assert(FRAME_BUFFER_SIZE <= YUV_BUFFER_COUNT); - -class CameraWidget : public QOpenGLWidget, protected QOpenGLFunctions { - Q_OBJECT - -public: - using QOpenGLWidget::QOpenGLWidget; - explicit CameraWidget(std::string stream_name, VisionStreamType stream_type, bool zoom, QWidget* parent = nullptr); - ~CameraWidget(); - void setBackgroundColor(const QColor &color) { bg = color; } - void setFrameId(int frame_id) { draw_frame_id = frame_id; } - void setStreamType(VisionStreamType type) { requested_stream_type = type; } - VisionStreamType getStreamType() { return active_stream_type; } - void stopVipcThread(); - -signals: - void clicked(); - void vipcThreadConnected(VisionIpcClient *); - void vipcThreadFrameReceived(); - void vipcAvailableStreamsUpdated(std::set); - -protected: - void paintGL() override; - void initializeGL() override; - void resizeGL(int w, int h) override { updateFrameMat(); } - void showEvent(QShowEvent *event) override; - void mouseReleaseEvent(QMouseEvent *event) override { emit clicked(); } - virtual void updateFrameMat(); - void updateCalibration(const mat3 &calib); - void vipcThread(); - void clearFrames(); - - int glWidth(); - int glHeight(); - - bool zoomed_view; - GLuint frame_vao, frame_vbo, frame_ibo; - GLuint textures[2]; - mat4 frame_mat = {}; - std::unique_ptr program; - QColor bg = QColor("#000000"); - -#ifdef QCOM2 - std::map egl_images; -#endif - - std::string stream_name; - int stream_width = 0; - int stream_height = 0; - int stream_stride = 0; - std::atomic active_stream_type; - std::atomic requested_stream_type; - std::set available_streams; - QThread *vipc_thread = nullptr; - - // Calibration - float x_offset = 0; - float y_offset = 0; - float zoom = 1.0; - mat3 calibration = DEFAULT_CALIBRATION; - mat3 intrinsic_matrix = FCAM_INTRINSIC_MATRIX; - - std::recursive_mutex frame_lock; - std::deque> frames; - uint32_t draw_frame_id = 0; - uint32_t prev_frame_id = 0; - -protected slots: - void vipcConnected(VisionIpcClient *vipc_client); - void vipcFrameReceived(); - void availableStreamsUpdated(std::set streams); -}; - -Q_DECLARE_METATYPE(std::set); diff --git a/selfdrive/ui/qt/widgets/controls.cc b/selfdrive/ui/qt/widgets/controls.cc deleted file mode 100644 index 40dda97..0000000 --- a/selfdrive/ui/qt/widgets/controls.cc +++ /dev/null @@ -1,141 +0,0 @@ -#include "selfdrive/ui/qt/widgets/controls.h" - -#include -#include - -AbstractControl::AbstractControl(const QString &title, const QString &desc, const QString &icon, QWidget *parent) : QFrame(parent) { - QVBoxLayout *main_layout = new QVBoxLayout(this); - main_layout->setMargin(0); - - hlayout = new QHBoxLayout; - hlayout->setMargin(0); - hlayout->setSpacing(20); - - // left icon - icon_label = new QLabel(this); - hlayout->addWidget(icon_label); - if (!icon.isEmpty()) { - icon_pixmap = QPixmap(icon).scaledToWidth(80, Qt::SmoothTransformation); - icon_label->setPixmap(icon_pixmap); - icon_label->setSizePolicy(QSizePolicy(QSizePolicy::Fixed, QSizePolicy::Fixed)); - } - icon_label->setVisible(!icon.isEmpty()); - - // title - title_label = new QPushButton(title); - title_label->setFixedHeight(120); - title_label->setStyleSheet("font-size: 50px; font-weight: 400; text-align: left; border: none;"); - hlayout->addWidget(title_label, 1); - - // value next to control button - value = new ElidedLabel(); - value->setAlignment(Qt::AlignRight | Qt::AlignVCenter); - value->setStyleSheet("color: #aaaaaa"); - hlayout->addWidget(value); - - main_layout->addLayout(hlayout); - - // description - description = new QLabel(desc); - description->setContentsMargins(40, 20, 40, 20); - description->setStyleSheet("font-size: 40px; color: grey"); - description->setWordWrap(true); - description->setVisible(false); - main_layout->addWidget(description); - - connect(title_label, &QPushButton::clicked, [=]() { - if (!description->isVisible()) { - emit showDescriptionEvent(); - } - - if (!description->text().isEmpty()) { - description->setVisible(!description->isVisible()); - } - }); - - main_layout->addStretch(); -} - -void AbstractControl::hideEvent(QHideEvent *e) { - if (description != nullptr) { - description->hide(); - } -} - -// controls - -ButtonControl::ButtonControl(const QString &title, const QString &text, const QString &desc, QWidget *parent) : AbstractControl(title, desc, "", parent) { - btn.setText(text); - btn.setStyleSheet(R"( - QPushButton { - padding: 0; - border-radius: 50px; - font-size: 35px; - font-weight: 500; - color: #E4E4E4; - background-color: #393939; - } - QPushButton:pressed { - background-color: #4a4a4a; - } - QPushButton:disabled { - color: #33E4E4E4; - } - )"); - btn.setFixedSize(250, 100); - QObject::connect(&btn, &QPushButton::clicked, this, &ButtonControl::clicked); - hlayout->addWidget(&btn); -} - -// ElidedLabel - -ElidedLabel::ElidedLabel(QWidget *parent) : ElidedLabel({}, parent) {} - -ElidedLabel::ElidedLabel(const QString &text, QWidget *parent) : QLabel(text.trimmed(), parent) { - setSizePolicy(QSizePolicy::Preferred, QSizePolicy::Preferred); - setMinimumWidth(1); -} - -void ElidedLabel::resizeEvent(QResizeEvent* event) { - QLabel::resizeEvent(event); - lastText_ = elidedText_ = ""; -} - -void ElidedLabel::paintEvent(QPaintEvent *event) { - const QString curText = text(); - if (curText != lastText_) { - elidedText_ = fontMetrics().elidedText(curText, Qt::ElideRight, contentsRect().width()); - lastText_ = curText; - } - - QPainter painter(this); - drawFrame(&painter); - QStyleOption opt; - opt.initFrom(this); - style()->drawItemText(&painter, contentsRect(), alignment(), opt.palette, isEnabled(), elidedText_, foregroundRole()); -} - -// ParamControl - -ParamControl::ParamControl(const QString ¶m, const QString &title, const QString &desc, const QString &icon, QWidget *parent) - : ToggleControl(title, desc, icon, false, parent) { - key = param.toStdString(); - QObject::connect(this, &ParamControl::toggleFlipped, this, &ParamControl::toggleClicked); -} - -void ParamControl::toggleClicked(bool state) { - auto do_confirm = [this]() { - QString content("

" + title_label->text() + "


" - "

" + getDescription() + "

"); - return ConfirmationDialog(content, tr("Enable"), tr("Cancel"), true, this).exec(); - }; - - bool confirmed = store_confirm && params.getBool(key + "Confirmed"); - if (!confirm || confirmed || !state || do_confirm()) { - if (store_confirm && state) params.putBool(key + "Confirmed", true); - params.putBool(key, state); - setIcon(state); - } else { - toggle.togglePosition(); - } -} diff --git a/selfdrive/ui/qt/widgets/controls.h b/selfdrive/ui/qt/widgets/controls.h deleted file mode 100644 index 366376f..0000000 --- a/selfdrive/ui/qt/widgets/controls.h +++ /dev/null @@ -1,293 +0,0 @@ -#pragma once - -#include -#include - -#include -#include -#include -#include -#include -#include - -#include "common/params.h" -#include "selfdrive/ui/qt/widgets/input.h" -#include "selfdrive/ui/qt/widgets/toggle.h" - -class ElidedLabel : public QLabel { - Q_OBJECT - -public: - explicit ElidedLabel(QWidget *parent = 0); - explicit ElidedLabel(const QString &text, QWidget *parent = 0); - -signals: - void clicked(); - -protected: - void paintEvent(QPaintEvent *event) override; - void resizeEvent(QResizeEvent* event) override; - void mouseReleaseEvent(QMouseEvent *event) override { - if (rect().contains(event->pos())) { - emit clicked(); - } - } - QString lastText_, elidedText_; -}; - - -class AbstractControl : public QFrame { - Q_OBJECT - -public: - void setDescription(const QString &desc) { - if (description) description->setText(desc); - } - - void setTitle(const QString &title) { - title_label->setText(title); - } - - void setValue(const QString &val) { - value->setText(val); - } - - const QString getDescription() { - return description->text(); - } - - QLabel *icon_label; - QPixmap icon_pixmap; - -public slots: - void showDescription() { - description->setVisible(true); - } - -signals: - void showDescriptionEvent(); - -protected: - AbstractControl(const QString &title, const QString &desc = "", const QString &icon = "", QWidget *parent = nullptr); - void hideEvent(QHideEvent *e) override; - - QHBoxLayout *hlayout; - QPushButton *title_label; - -private: - ElidedLabel *value; - QLabel *description = nullptr; -}; - -// widget to display a value -class LabelControl : public AbstractControl { - Q_OBJECT - -public: - LabelControl(const QString &title, const QString &text = "", const QString &desc = "", QWidget *parent = nullptr) : AbstractControl(title, desc, "", parent) { - label.setText(text); - label.setAlignment(Qt::AlignRight | Qt::AlignVCenter); - hlayout->addWidget(&label); - } - void setText(const QString &text) { label.setText(text); } - -private: - ElidedLabel label; -}; - -// widget for a button with a label -class ButtonControl : public AbstractControl { - Q_OBJECT - -public: - ButtonControl(const QString &title, const QString &text, const QString &desc = "", QWidget *parent = nullptr); - inline void setText(const QString &text) { btn.setText(text); } - inline QString text() const { return btn.text(); } - -signals: - void clicked(); - -public slots: - void setEnabled(bool enabled) { btn.setEnabled(enabled); } - -private: - QPushButton btn; -}; - -class ToggleControl : public AbstractControl { - Q_OBJECT - -public: - ToggleControl(const QString &title, const QString &desc = "", const QString &icon = "", const bool state = false, QWidget *parent = nullptr) : AbstractControl(title, desc, icon, parent) { - toggle.setFixedSize(150, 100); - if (state) { - toggle.togglePosition(); - } - hlayout->addWidget(&toggle); - QObject::connect(&toggle, &Toggle::stateChanged, this, &ToggleControl::toggleFlipped); - } - - void setVisualOn() { - toggle.togglePosition(); - } - - void setEnabled(bool enabled) { - toggle.setEnabled(enabled); - toggle.update(); - } - - void refresh() { - toggle.togglePosition(); - } - -signals: - void toggleFlipped(bool state); - -protected: - Toggle toggle; -}; - -// widget to toggle params -class ParamControl : public ToggleControl { - Q_OBJECT - -public: - ParamControl(const QString ¶m, const QString &title, const QString &desc, const QString &icon, QWidget *parent = nullptr); - void setConfirmation(bool _confirm, bool _store_confirm) { - confirm = _confirm; - store_confirm = _store_confirm; - } - - void setActiveIcon(const QString &icon) { - active_icon_pixmap = QPixmap(icon).scaledToWidth(80, Qt::SmoothTransformation); - } - - void refresh() { - bool state = params.getBool(key); - if (state != toggle.on) { - toggle.togglePosition(); - setIcon(state); - } - } - - void showEvent(QShowEvent *event) override { - refresh(); - } - -private: - void toggleClicked(bool state); - void setIcon(bool state) { - if (state && !active_icon_pixmap.isNull()) { - icon_label->setPixmap(active_icon_pixmap); - } else if (!icon_pixmap.isNull()) { - icon_label->setPixmap(icon_pixmap); - } - } - - std::string key; - Params params; - QPixmap active_icon_pixmap; - bool confirm = false; - bool store_confirm = false; -}; - -class ButtonParamControl : public AbstractControl { - Q_OBJECT -public: - ButtonParamControl(const QString ¶m, const QString &title, const QString &desc, const QString &icon, - const std::vector &button_texts, const int minimum_button_width = 225) : AbstractControl(title, desc, icon) { - const QString style = R"( - QPushButton { - border-radius: 50px; - font-size: 40px; - font-weight: 500; - height:100px; - padding: 0 25 0 25; - color: #E4E4E4; - background-color: #393939; - } - QPushButton:pressed { - background-color: #4a4a4a; - } - QPushButton:checked:enabled { - background-color: #33Ab4C; - } - QPushButton:disabled { - color: #33E4E4E4; - } - )"; - key = param.toStdString(); - int value = atoi(params.get(key).c_str()); - - button_group = new QButtonGroup(this); - button_group->setExclusive(true); - for (int i = 0; i < button_texts.size(); i++) { - QPushButton *button = new QPushButton(button_texts[i], this); - button->setCheckable(true); - button->setChecked(i == value); - button->setStyleSheet(style); - button->setMinimumWidth(minimum_button_width); - hlayout->addWidget(button); - button_group->addButton(button, i); - } - - QObject::connect(button_group, QOverload::of(&QButtonGroup::buttonToggled), [=](int id, bool checked) { - if (checked) { - params.put(key, std::to_string(id)); - } - }); - } - - void setEnabled(bool enable) { - for (auto btn : button_group->buttons()) { - btn->setEnabled(enable); - } - } - -private: - std::string key; - Params params; - QButtonGroup *button_group; -}; - -class ListWidget : public QWidget { - Q_OBJECT - public: - explicit ListWidget(QWidget *parent = 0) : QWidget(parent), outer_layout(this) { - outer_layout.setMargin(0); - outer_layout.setSpacing(0); - outer_layout.addLayout(&inner_layout); - inner_layout.setMargin(0); - inner_layout.setSpacing(25); // default spacing is 25 - outer_layout.addStretch(); - } - inline void addItem(QWidget *w) { inner_layout.addWidget(w); } - inline void addItem(QLayout *layout) { inner_layout.addLayout(layout); } - inline void setSpacing(int spacing) { inner_layout.setSpacing(spacing); } - -private: - void paintEvent(QPaintEvent *) override { - QPainter p(this); - p.setPen(Qt::gray); - for (int i = 0; i < inner_layout.count() - 1; ++i) { - QWidget *widget = inner_layout.itemAt(i)->widget(); - if (widget == nullptr || widget->isVisible()) { - QRect r = inner_layout.itemAt(i)->geometry(); - int bottom = r.bottom() + inner_layout.spacing() / 2; - p.drawLine(r.left() + 40, bottom, r.right() - 40, bottom); - } - } - } - QVBoxLayout outer_layout; - QVBoxLayout inner_layout; -}; - -// convenience class for wrapping layouts -class LayoutWidget : public QWidget { - Q_OBJECT - -public: - LayoutWidget(QLayout *l, QWidget *parent = nullptr) : QWidget(parent) { - setLayout(l); - } -}; diff --git a/selfdrive/ui/qt/widgets/drive_stats.cc b/selfdrive/ui/qt/widgets/drive_stats.cc deleted file mode 100644 index 208cf17..0000000 --- a/selfdrive/ui/qt/widgets/drive_stats.cc +++ /dev/null @@ -1,105 +0,0 @@ -#include "selfdrive/ui/qt/widgets/drive_stats.h" - -#include -#include -#include -#include - -#include "selfdrive/ui/qt/request_repeater.h" -#include "selfdrive/ui/qt/util.h" - -static QLabel* newLabel(const QString& text, const QString &type) { - QLabel* label = new QLabel(text); - label->setProperty("type", type); - return label; -} - -DriveStats::DriveStats(QWidget* parent) : QFrame(parent) { - metric_ = params.getBool("IsMetric"); - - QVBoxLayout* main_layout = new QVBoxLayout(this); - main_layout->setContentsMargins(50, 25, 50, 20); - - auto add_stats_layouts = [=](const QString &title, StatsLabels& labels, bool FrogPilot=false) { - QGridLayout* grid_layout = new QGridLayout; - grid_layout->setVerticalSpacing(10); - grid_layout->setContentsMargins(0, 10, 0, 10); - - int row = 0; - grid_layout->addWidget(newLabel(title, FrogPilot ? "frogpilot_title" : "title"), row++, 0, 1, 3); - grid_layout->addItem(new QSpacerItem(0, 10), row++, 0, 1, 1); - - grid_layout->addWidget(labels.routes = newLabel("0", "number"), row, 0, Qt::AlignLeft); - grid_layout->addWidget(labels.distance = newLabel("0", "number"), row, 1, Qt::AlignLeft); - grid_layout->addWidget(labels.hours = newLabel("0", "number"), row, 2, Qt::AlignLeft); - - grid_layout->addWidget(newLabel((tr("Drives")), "unit"), row + 1, 0, Qt::AlignLeft); - grid_layout->addWidget(labels.distance_unit = newLabel(getDistanceUnit(), "unit"), row + 1, 1, Qt::AlignLeft); - grid_layout->addWidget(newLabel(tr("Hours"), "unit"), row + 1, 2, Qt::AlignLeft); - - main_layout->addLayout(grid_layout); - main_layout->addStretch(1); - }; - - add_stats_layouts(tr("ALL TIME"), all_); - add_stats_layouts(tr("PAST WEEK"), week_); - add_stats_layouts(tr("FROGPILOT"), frogPilot_, true); - - if (auto dongleId = getDongleId()) { - QString url = CommaApi::BASE_URL + "/v1.1/devices/" + *dongleId + "/stats"; - RequestRepeater* repeater = new RequestRepeater(this, url, "ApiCache_DriveStats", 30); - QObject::connect(repeater, &RequestRepeater::requestDone, this, &DriveStats::parseResponse); - } - - setStyleSheet(R"( - DriveStats { - background-color: #333333; - border-radius: 10px; - } - - QLabel[type="title"] { font-size: 50px; font-weight: 500; } - QLabel[type="frogpilot_title"] { font-size: 50px; font-weight: 500; color: #178643; } - QLabel[type="number"] { font-size: 65px; font-weight: 400; } - QLabel[type="unit"] { font-size: 50px; font-weight: 300; color: #A0A0A0; } - )"); -} - -void DriveStats::updateStats() { - QJsonObject json = stats_.object(); - - auto updateFrogPilot = [this](const QJsonObject& obj, StatsLabels& labels) { - labels.routes->setText(QString::number(params.getInt("FrogPilotDrives"))); - labels.distance->setText(QString::number(int(params.getFloat("FrogPilotKilometers") * (metric_ ? 1 : KM_TO_MILE)))); - labels.distance_unit->setText(getDistanceUnit()); - labels.hours->setText(QString::number(int(params.getFloat("FrogPilotMinutes") / 60))); - }; - - updateFrogPilot(json["frogpilot"].toObject(), frogPilot_); - - auto update = [=](const QJsonObject& obj, StatsLabels& labels) { - labels.routes->setText(QString::number((int)obj["routes"].toDouble())); - labels.distance->setText(QString::number(int(obj["distance"].toDouble() * (metric_ ? MILE_TO_KM : 1)))); - labels.distance_unit->setText(getDistanceUnit()); - labels.hours->setText(QString::number((int)(obj["minutes"].toDouble() / 60))); - }; - - update(json["all"].toObject(), all_); - update(json["week"].toObject(), week_); -} - -void DriveStats::parseResponse(const QString& response, bool success) { - if (!success) return; - - QJsonDocument doc = QJsonDocument::fromJson(response.trimmed().toUtf8()); - if (doc.isNull()) { - qDebug() << "JSON Parse failed on getting past drives statistics"; - return; - } - stats_ = doc; - updateStats(); -} - -void DriveStats::showEvent(QShowEvent* event) { - metric_ = params.getBool("IsMetric"); - updateStats(); -} diff --git a/selfdrive/ui/qt/widgets/drive_stats.h b/selfdrive/ui/qt/widgets/drive_stats.h deleted file mode 100644 index aa9f711..0000000 --- a/selfdrive/ui/qt/widgets/drive_stats.h +++ /dev/null @@ -1,28 +0,0 @@ -#pragma once - -#include -#include - -#include "common/params.h" - -class DriveStats : public QFrame { - Q_OBJECT - -public: - explicit DriveStats(QWidget* parent = 0); - -private: - void showEvent(QShowEvent *event) override; - void updateStats(); - inline QString getDistanceUnit() const { return metric_ ? tr("KM") : tr("Miles"); } - - bool metric_; - Params params; - QJsonDocument stats_; - struct StatsLabels { - QLabel *routes, *distance, *distance_unit, *hours; - } all_, week_, frogPilot_; - -private slots: - void parseResponse(const QString &response, bool success); -}; diff --git a/selfdrive/ui/qt/widgets/input.cc b/selfdrive/ui/qt/widgets/input.cc deleted file mode 100644 index 4ff0de2..0000000 --- a/selfdrive/ui/qt/widgets/input.cc +++ /dev/null @@ -1,336 +0,0 @@ -#include "selfdrive/ui/qt/widgets/input.h" - -#include -#include - -#include "system/hardware/hw.h" -#include "selfdrive/ui/qt/util.h" -#include "selfdrive/ui/qt/qt_window.h" -#include "selfdrive/ui/qt/widgets/scrollview.h" - - -DialogBase::DialogBase(QWidget *parent) : QDialog(parent) { - Q_ASSERT(parent != nullptr); - parent->installEventFilter(this); - - setStyleSheet(R"( - * { - outline: none; - color: white; - font-family: Inter; - } - DialogBase { - background-color: black; - } - QPushButton { - height: 160; - font-size: 55px; - font-weight: 400; - border-radius: 10px; - color: white; - background-color: #333333; - } - QPushButton:pressed { - background-color: #444444; - } - )"); -} - -bool DialogBase::eventFilter(QObject *o, QEvent *e) { - if (o == parent() && e->type() == QEvent::Hide) { - reject(); - } - return QDialog::eventFilter(o, e); -} - -int DialogBase::exec() { - setMainWindow(this); - return QDialog::exec(); -} - -InputDialog::InputDialog(const QString &title, QWidget *parent, const QString &subtitle, bool secret) : DialogBase(parent) { - main_layout = new QVBoxLayout(this); - main_layout->setContentsMargins(50, 55, 50, 50); - main_layout->setSpacing(0); - - // build header - QHBoxLayout *header_layout = new QHBoxLayout(); - - QVBoxLayout *vlayout = new QVBoxLayout; - header_layout->addLayout(vlayout); - label = new QLabel(title, this); - label->setStyleSheet("font-size: 90px; font-weight: bold;"); - vlayout->addWidget(label, 1, Qt::AlignTop | Qt::AlignLeft); - - if (!subtitle.isEmpty()) { - sublabel = new QLabel(subtitle, this); - sublabel->setStyleSheet("font-size: 55px; font-weight: light; color: #BDBDBD;"); - vlayout->addWidget(sublabel, 1, Qt::AlignTop | Qt::AlignLeft); - } - - QPushButton* cancel_btn = new QPushButton(tr("Cancel")); - cancel_btn->setFixedSize(386, 125); - cancel_btn->setStyleSheet(R"( - QPushButton { - font-size: 48px; - border-radius: 10px; - color: #E4E4E4; - background-color: #333333; - } - QPushButton:pressed { - background-color: #444444; - } - )"); - header_layout->addWidget(cancel_btn, 0, Qt::AlignRight); - QObject::connect(cancel_btn, &QPushButton::clicked, this, &InputDialog::reject); - QObject::connect(cancel_btn, &QPushButton::clicked, this, &InputDialog::cancel); - - main_layout->addLayout(header_layout); - - // text box - main_layout->addStretch(2); - - QWidget *textbox_widget = new QWidget; - textbox_widget->setObjectName("textbox"); - QHBoxLayout *textbox_layout = new QHBoxLayout(textbox_widget); - textbox_layout->setContentsMargins(50, 0, 50, 0); - - textbox_widget->setStyleSheet(R"( - #textbox { - margin-left: 50px; - margin-right: 50px; - border-radius: 0; - border-bottom: 3px solid #BDBDBD; - } - * { - border: none; - font-size: 80px; - font-weight: light; - background-color: transparent; - } - )"); - - line = new QLineEdit(); - line->setStyleSheet("lineedit-password-character: 8226; lineedit-password-mask-delay: 1500;"); - textbox_layout->addWidget(line, 1); - - if (secret) { - eye_btn = new QPushButton(); - eye_btn->setCheckable(true); - eye_btn->setFixedSize(150, 120); - QObject::connect(eye_btn, &QPushButton::toggled, [=](bool checked) { - if (checked) { - eye_btn->setIcon(QIcon(ASSET_PATH + "img_eye_closed.svg")); - eye_btn->setIconSize(QSize(81, 54)); - line->setEchoMode(QLineEdit::Password); - } else { - eye_btn->setIcon(QIcon(ASSET_PATH + "img_eye_open.svg")); - eye_btn->setIconSize(QSize(81, 44)); - line->setEchoMode(QLineEdit::Normal); - } - }); - eye_btn->toggle(); - eye_btn->setChecked(false); - textbox_layout->addWidget(eye_btn); - } - - main_layout->addWidget(textbox_widget, 0, Qt::AlignBottom); - main_layout->addSpacing(25); - - k = new Keyboard(this); - QObject::connect(k, &Keyboard::emitEnter, this, &InputDialog::handleEnter); - QObject::connect(k, &Keyboard::emitBackspace, this, [=]() { - line->backspace(); - }); - QObject::connect(k, &Keyboard::emitKey, this, [=](const QString &key) { - line->insert(key.left(1)); - }); - - main_layout->addWidget(k, 2, Qt::AlignBottom); -} - -QString InputDialog::getText(const QString &prompt, QWidget *parent, const QString &subtitle, - bool secret, int minLength, const QString &defaultText) { - InputDialog d = InputDialog(prompt, parent, subtitle, secret); - d.line->setText(defaultText); - d.setMinLength(minLength); - const int ret = d.exec(); - return ret ? d.text() : QString(); -} - -QString InputDialog::text() { - return line->text(); -} - -void InputDialog::show() { - setMainWindow(this); -} - -void InputDialog::handleEnter() { - if (line->text().length() >= minLength) { - done(QDialog::Accepted); - emitText(line->text()); - } else { - setMessage(tr("Need at least %n character(s)!", "", minLength), false); - } -} - -void InputDialog::setMessage(const QString &message, bool clearInputField) { - label->setText(message); - if (clearInputField) { - line->setText(""); - } -} - -void InputDialog::setMinLength(int length) { - minLength = length; -} - -// ConfirmationDialog - -ConfirmationDialog::ConfirmationDialog(const QString &prompt_text, const QString &confirm_text, const QString &cancel_text, - const bool rich, QWidget *parent) : DialogBase(parent) { - QFrame *container = new QFrame(this); - container->setStyleSheet(R"( - QFrame { background-color: #1B1B1B; color: #C9C9C9; } - #confirm_btn { background-color: #465BEA; } - #confirm_btn:pressed { background-color: #3049F4; } - )"); - QVBoxLayout *main_layout = new QVBoxLayout(container); - main_layout->setContentsMargins(32, rich ? 32 : 120, 32, 32); - - QLabel *prompt = new QLabel(prompt_text, this); - prompt->setWordWrap(true); - prompt->setAlignment(rich ? Qt::AlignLeft : Qt::AlignHCenter); - prompt->setStyleSheet((rich ? "font-size: 42px; font-weight: light;" : "font-size: 70px; font-weight: bold;") + QString(" margin: 45px;")); - main_layout->addWidget(rich ? (QWidget*)new ScrollView(prompt, this) : (QWidget*)prompt, 1, Qt::AlignTop); - - // cancel + confirm buttons - QHBoxLayout *btn_layout = new QHBoxLayout(); - btn_layout->setSpacing(30); - main_layout->addLayout(btn_layout); - - if (cancel_text.length()) { - QPushButton* cancel_btn = new QPushButton(cancel_text); - btn_layout->addWidget(cancel_btn); - QObject::connect(cancel_btn, &QPushButton::clicked, this, &ConfirmationDialog::reject); - } - - if (confirm_text.length()) { - QPushButton* confirm_btn = new QPushButton(confirm_text); - confirm_btn->setObjectName("confirm_btn"); - btn_layout->addWidget(confirm_btn); - QObject::connect(confirm_btn, &QPushButton::clicked, this, &ConfirmationDialog::accept); - } - - QVBoxLayout *outer_layout = new QVBoxLayout(this); - int margin = rich ? 100 : 200; - outer_layout->setContentsMargins(margin, margin, margin, margin); - outer_layout->addWidget(container); -} - -bool ConfirmationDialog::alert(const QString &prompt_text, QWidget *parent) { - ConfirmationDialog d = ConfirmationDialog(prompt_text, tr("Ok"), "", false, parent); - return d.exec(); -} - -bool ConfirmationDialog::confirm(const QString &prompt_text, const QString &confirm_text, QWidget *parent) { - ConfirmationDialog d = ConfirmationDialog(prompt_text, confirm_text, tr("Cancel"), false, parent); - return d.exec(); -} - -bool ConfirmationDialog::rich(const QString &prompt_text, QWidget *parent) { - ConfirmationDialog d = ConfirmationDialog(prompt_text, tr("Ok"), "", true, parent); - return d.exec(); -} - -// MultiOptionDialog - -MultiOptionDialog::MultiOptionDialog(const QString &prompt_text, const QStringList &l, const QString ¤t, QWidget *parent) : DialogBase(parent) { - QFrame *container = new QFrame(this); - container->setStyleSheet(R"( - QFrame { background-color: #1B1B1B; } - #confirm_btn[enabled="false"] { background-color: #2B2B2B; } - #confirm_btn:enabled { background-color: #465BEA; } - #confirm_btn:enabled:pressed { background-color: #3049F4; } - )"); - - QVBoxLayout *main_layout = new QVBoxLayout(container); - main_layout->setContentsMargins(55, 50, 55, 50); - - QLabel *title = new QLabel(prompt_text, this); - title->setStyleSheet("font-size: 70px; font-weight: 500;"); - main_layout->addWidget(title, 0, Qt::AlignLeft | Qt::AlignTop); - main_layout->addSpacing(25); - - QWidget *listWidget = new QWidget(this); - QVBoxLayout *listLayout = new QVBoxLayout(listWidget); - listLayout->setSpacing(20); - listWidget->setStyleSheet(R"( - QPushButton { - height: 135; - padding: 0px 50px; - text-align: left; - font-size: 55px; - font-weight: 300; - border-radius: 10px; - background-color: #4F4F4F; - } - QPushButton:checked { background-color: #465BEA; } - )"); - - QButtonGroup *group = new QButtonGroup(listWidget); - group->setExclusive(true); - - QPushButton *confirm_btn = new QPushButton(tr("Select")); - confirm_btn->setObjectName("confirm_btn"); - confirm_btn->setEnabled(false); - - for (const QString &s : l) { - QPushButton *selectionLabel = new QPushButton(s); - selectionLabel->setCheckable(true); - selectionLabel->setChecked(s == current); - QObject::connect(selectionLabel, &QPushButton::toggled, [=](bool checked) { - if (checked) selection = s; - if (selection != current) { - confirm_btn->setEnabled(true); - } else { - confirm_btn->setEnabled(false); - } - }); - - group->addButton(selectionLabel); - listLayout->addWidget(selectionLabel); - } - // add stretch to keep buttons spaced correctly - listLayout->addStretch(1); - - ScrollView *scroll_view = new ScrollView(listWidget, this); - scroll_view->setVerticalScrollBarPolicy(Qt::ScrollBarAsNeeded); - - main_layout->addWidget(scroll_view); - main_layout->addSpacing(35); - - // cancel + confirm buttons - QHBoxLayout *blayout = new QHBoxLayout; - main_layout->addLayout(blayout); - blayout->setSpacing(50); - - QPushButton *cancel_btn = new QPushButton(tr("Cancel")); - QObject::connect(cancel_btn, &QPushButton::clicked, this, &ConfirmationDialog::reject); - QObject::connect(confirm_btn, &QPushButton::clicked, this, &ConfirmationDialog::accept); - blayout->addWidget(cancel_btn); - blayout->addWidget(confirm_btn); - - QVBoxLayout *outer_layout = new QVBoxLayout(this); - outer_layout->setContentsMargins(50, 50, 50, 50); - outer_layout->addWidget(container); -} - -QString MultiOptionDialog::getSelection(const QString &prompt_text, const QStringList &l, const QString ¤t, QWidget *parent) { - MultiOptionDialog d = MultiOptionDialog(prompt_text, l, current, parent); - if (d.exec()) { - return d.selection; - } - return ""; -} diff --git a/selfdrive/ui/qt/widgets/input.h b/selfdrive/ui/qt/widgets/input.h deleted file mode 100644 index 089e54e..0000000 --- a/selfdrive/ui/qt/widgets/input.h +++ /dev/null @@ -1,71 +0,0 @@ -#pragma once - -#include -#include -#include -#include -#include -#include - -#include "selfdrive/ui/qt/widgets/keyboard.h" - - -class DialogBase : public QDialog { - Q_OBJECT - -protected: - DialogBase(QWidget *parent); - bool eventFilter(QObject *o, QEvent *e) override; - -public slots: - int exec() override; -}; - -class InputDialog : public DialogBase { - Q_OBJECT - -public: - explicit InputDialog(const QString &title, QWidget *parent, const QString &subtitle = "", bool secret = false); - static QString getText(const QString &title, QWidget *parent, const QString &subtitle = "", - bool secret = false, int minLength = -1, const QString &defaultText = ""); - QString text(); - void setMessage(const QString &message, bool clearInputField = true); - void setMinLength(int length); - void show(); - -private: - int minLength; - QLineEdit *line; - Keyboard *k; - QLabel *label; - QLabel *sublabel; - QVBoxLayout *main_layout; - QPushButton *eye_btn; - -private slots: - void handleEnter(); - -signals: - void cancel(); - void emitText(const QString &text); -}; - -class ConfirmationDialog : public DialogBase { - Q_OBJECT - -public: - explicit ConfirmationDialog(const QString &prompt_text, const QString &confirm_text, - const QString &cancel_text, const bool rich, QWidget* parent); - static bool alert(const QString &prompt_text, QWidget *parent); - static bool confirm(const QString &prompt_text, const QString &confirm_text, QWidget *parent); - static bool rich(const QString &prompt_text, QWidget *parent); -}; - -class MultiOptionDialog : public DialogBase { - Q_OBJECT - -public: - explicit MultiOptionDialog(const QString &prompt_text, const QStringList &l, const QString ¤t, QWidget *parent); - static QString getSelection(const QString &prompt_text, const QStringList &l, const QString ¤t, QWidget *parent); - QString selection; -}; diff --git a/selfdrive/ui/qt/widgets/keyboard.cc b/selfdrive/ui/qt/widgets/keyboard.cc deleted file mode 100644 index 370e9a5..0000000 --- a/selfdrive/ui/qt/widgets/keyboard.cc +++ /dev/null @@ -1,167 +0,0 @@ -#include "selfdrive/ui/qt/widgets/keyboard.h" - -#include - -#include -#include -#include -#include -#include - -const QString BACKSPACE_KEY = "⌫"; -const QString ENTER_KEY = "→"; - -const QMap KEY_STRETCH = {{" ", 5}, {ENTER_KEY, 2}}; - -const QStringList CONTROL_BUTTONS = {"↑", "↓", "ABC", "#+=", "123", BACKSPACE_KEY, ENTER_KEY}; - -const float key_spacing_vertical = 20; -const float key_spacing_horizontal = 15; - -KeyButton::KeyButton(const QString &text, QWidget *parent) : QPushButton(text, parent) { - setAttribute(Qt::WA_AcceptTouchEvents); - setFocusPolicy(Qt::NoFocus); -} - -bool KeyButton::event(QEvent *event) { - if (event->type() == QEvent::TouchBegin || event->type() == QEvent::TouchEnd) { - QTouchEvent *touchEvent = static_cast(event); - if (!touchEvent->touchPoints().empty()) { - const QEvent::Type mouseType = event->type() == QEvent::TouchBegin ? QEvent::MouseButtonPress : QEvent::MouseButtonRelease; - QMouseEvent mouseEvent(mouseType, touchEvent->touchPoints().front().pos(), Qt::LeftButton, Qt::LeftButton, Qt::NoModifier); - QPushButton::event(&mouseEvent); - event->accept(); - parentWidget()->update(); - return true; - } - } - return QPushButton::event(event); -} - -KeyboardLayout::KeyboardLayout(QWidget* parent, const std::vector>& layout) : QWidget(parent) { - QVBoxLayout* main_layout = new QVBoxLayout(this); - main_layout->setMargin(0); - main_layout->setSpacing(0); - - QButtonGroup* btn_group = new QButtonGroup(this); - QObject::connect(btn_group, SIGNAL(buttonClicked(QAbstractButton*)), parent, SLOT(handleButton(QAbstractButton*))); - - for (const auto &s : layout) { - QHBoxLayout *hlayout = new QHBoxLayout; - hlayout->setSpacing(0); - - if (main_layout->count() == 1) { - hlayout->addSpacing(90); - } - - for (const QString &p : s) { - KeyButton* btn = new KeyButton(p); - if (p == BACKSPACE_KEY) { - btn->setAutoRepeat(true); - } else if (p == ENTER_KEY) { - btn->setStyleSheet(R"( - QPushButton { - background-color: #465BEA; - } - QPushButton:pressed { - background-color: #444444; - } - )"); - } - btn->setFixedHeight(135 + key_spacing_vertical); - btn_group->addButton(btn); - hlayout->addWidget(btn, KEY_STRETCH.value(p, 1)); - } - - if (main_layout->count() == 1) { - hlayout->addSpacing(90); - } - - main_layout->addLayout(hlayout); - } - - setStyleSheet(QString(R"( - QPushButton { - font-size: 75px; - margin-left: %1px; - margin-right: %1px; - margin-top: %2px; - margin-bottom: %2px; - padding: 0px; - border-radius: 10px; - color: #dddddd; - background-color: #444444; - } - QPushButton:pressed { - background-color: #333333; - } - )").arg(key_spacing_vertical / 2).arg(key_spacing_horizontal / 2)); -} - -Keyboard::Keyboard(QWidget *parent) : QFrame(parent) { - main_layout = new QStackedLayout(this); - main_layout->setMargin(0); - - // lowercase - std::vector> lowercase = { - {"q", "w", "e", "r", "t", "y", "u", "i", "o", "p"}, - {"a", "s", "d", "f", "g", "h", "j", "k", "l"}, - {"↑", "z", "x", "c", "v", "b", "n", "m", BACKSPACE_KEY}, - {"123", " ", ".", ENTER_KEY}, - }; - main_layout->addWidget(new KeyboardLayout(this, lowercase)); - - // uppercase - std::vector> uppercase = { - {"Q", "W", "E", "R", "T", "Y", "U", "I", "O", "P"}, - {"A", "S", "D", "F", "G", "H", "J", "K", "L"}, - {"↓", "Z", "X", "C", "V", "B", "N", "M", BACKSPACE_KEY}, - {"123", " ", ".", ENTER_KEY}, - }; - main_layout->addWidget(new KeyboardLayout(this, uppercase)); - - // numbers + specials - std::vector> numbers = { - {"1", "2", "3", "4", "5", "6", "7", "8", "9", "0"}, - {"-", "/", ":", ";", "(", ")", "$", "&&", "@", "\""}, - {"#+=", ".", ",", "?", "!", "`", BACKSPACE_KEY}, - {"ABC", " ", ".", ENTER_KEY}, - }; - main_layout->addWidget(new KeyboardLayout(this, numbers)); - - // extra specials - std::vector> specials = { - {"[", "]", "{", "}", "#", "%", "^", "*", "+", "="}, - {"_", "\\", "|", "~", "<", ">", "€", "£", "¥", "•"}, - {"123", ".", ",", "?", "!", "'", BACKSPACE_KEY}, - {"ABC", " ", ".", ENTER_KEY}, - }; - main_layout->addWidget(new KeyboardLayout(this, specials)); - - main_layout->setCurrentIndex(0); -} - -void Keyboard::handleButton(QAbstractButton* btn) { - const QString &key = btn->text(); - if (CONTROL_BUTTONS.contains(key)) { - if (key == "↓" || key == "ABC") { - main_layout->setCurrentIndex(0); - } else if (key == "↑") { - main_layout->setCurrentIndex(1); - } else if (key == "123") { - main_layout->setCurrentIndex(2); - } else if (key == "#+=") { - main_layout->setCurrentIndex(3); - } else if (key == ENTER_KEY) { - main_layout->setCurrentIndex(0); - emit emitEnter(); - } else if (key == BACKSPACE_KEY) { - emit emitBackspace(); - } - } else { - if ("A" <= key && key <= "Z") { - main_layout->setCurrentIndex(0); - } - emit emitKey(key); - } -} diff --git a/selfdrive/ui/qt/widgets/keyboard.h b/selfdrive/ui/qt/widgets/keyboard.h deleted file mode 100644 index efc02d0..0000000 --- a/selfdrive/ui/qt/widgets/keyboard.h +++ /dev/null @@ -1,40 +0,0 @@ -#pragma once - -#include - -#include -#include -#include - -class KeyButton : public QPushButton { - Q_OBJECT - -public: - KeyButton(const QString &text, QWidget *parent = 0); - bool event(QEvent *event) override; -}; - -class KeyboardLayout : public QWidget { - Q_OBJECT - -public: - explicit KeyboardLayout(QWidget* parent, const std::vector>& layout); -}; - -class Keyboard : public QFrame { - Q_OBJECT - -public: - explicit Keyboard(QWidget *parent = 0); - -private: - QStackedLayout* main_layout; - -private slots: - void handleButton(QAbstractButton* m_button); - -signals: - void emitKey(const QString &s); - void emitBackspace(); - void emitEnter(); -}; diff --git a/selfdrive/ui/qt/widgets/offroad_alerts.cc b/selfdrive/ui/qt/widgets/offroad_alerts.cc deleted file mode 100644 index 2848ffe..0000000 --- a/selfdrive/ui/qt/widgets/offroad_alerts.cc +++ /dev/null @@ -1,140 +0,0 @@ -#include "selfdrive/ui/qt/widgets/offroad_alerts.h" - -#include -#include -#include -#include - -#include -#include -#include - -#include "common/util.h" -#include "system/hardware/hw.h" -#include "selfdrive/ui/qt/widgets/scrollview.h" - -AbstractAlert::AbstractAlert(bool hasRebootBtn, QWidget *parent) : QFrame(parent) { - QVBoxLayout *main_layout = new QVBoxLayout(this); - main_layout->setMargin(50); - main_layout->setSpacing(30); - - QWidget *widget = new QWidget; - scrollable_layout = new QVBoxLayout(widget); - widget->setStyleSheet("background-color: transparent;"); - main_layout->addWidget(new ScrollView(widget)); - - // bottom footer, dismiss + reboot buttons - QHBoxLayout *footer_layout = new QHBoxLayout(); - main_layout->addLayout(footer_layout); - - QPushButton *dismiss_btn = new QPushButton(tr("Close")); - dismiss_btn->setFixedSize(400, 125); - footer_layout->addWidget(dismiss_btn, 0, Qt::AlignBottom | Qt::AlignLeft); - QObject::connect(dismiss_btn, &QPushButton::clicked, this, &AbstractAlert::dismiss); - - disable_check_btn = new QPushButton(tr("Disable Internet Check")); - disable_check_btn->setVisible(false); - disable_check_btn->setFixedSize(625, 125); - footer_layout->addWidget(disable_check_btn, 1, Qt::AlignBottom | Qt::AlignCenter); - QObject::connect(disable_check_btn, &QPushButton::clicked, [=]() { - params.putBool("SnoozeUpdate", true); - params.putBool("OfflineMode", true); - params.putBool("FiredTheBabysitter", true); - }); - QObject::connect(disable_check_btn, &QPushButton::clicked, this, &AbstractAlert::dismiss); - disable_check_btn->setStyleSheet(R"(color: white; background-color: #4F4F4F;)"); - - snooze_btn = new QPushButton(tr("Snooze Update")); - snooze_btn->setVisible(false); - snooze_btn->setFixedSize(550, 125); - footer_layout->addWidget(snooze_btn, 0, Qt::AlignBottom | Qt::AlignRight); - QObject::connect(snooze_btn, &QPushButton::clicked, [=]() { - params.putBool("SnoozeUpdate", true); - }); - QObject::connect(snooze_btn, &QPushButton::clicked, this, &AbstractAlert::dismiss); - snooze_btn->setStyleSheet(R"(color: white; background-color: #4F4F4F;)"); - - if (hasRebootBtn) { - QPushButton *rebootBtn = new QPushButton(tr("Reboot and Update")); - rebootBtn->setFixedSize(600, 125); - footer_layout->addWidget(rebootBtn, 0, Qt::AlignBottom | Qt::AlignRight); - QObject::connect(rebootBtn, &QPushButton::clicked, [=]() { Hardware::reboot(); }); - } - - setStyleSheet(R"( - * { - font-size: 48px; - color: white; - } - QFrame { - border-radius: 30px; - background-color: #393939; - } - QPushButton { - color: black; - font-weight: 500; - border-radius: 30px; - background-color: white; - } - )"); -} - -int OffroadAlert::refresh() { - // build widgets for each offroad alert on first refresh - if (alerts.empty()) { - QString json = util::read_file("../controls/lib/alerts_offroad.json").c_str(); - QJsonObject obj = QJsonDocument::fromJson(json.toUtf8()).object(); - - // descending sort labels by severity - std::vector> sorted; - for (auto it = obj.constBegin(); it != obj.constEnd(); ++it) { - sorted.push_back({it.key().toStdString(), it.value()["severity"].toInt()}); - } - std::sort(sorted.begin(), sorted.end(), [=](auto &l, auto &r) { return l.second > r.second; }); - - for (auto &[key, severity] : sorted) { - QLabel *l = new QLabel(this); - alerts[key] = l; - l->setMargin(60); - l->setWordWrap(true); - l->setStyleSheet(QString("background-color: %1").arg(severity ? "#E22C2C" : "#292929")); - scrollable_layout->addWidget(l); - } - scrollable_layout->addStretch(1); - } - - int alertCount = 0; - for (const auto &[key, label] : alerts) { - QString text; - std::string bytes = params.get(key); - if (bytes.size()) { - auto doc_par = QJsonDocument::fromJson(bytes.c_str()); - text = tr(doc_par["text"].toString().toUtf8().data()); - auto extra = doc_par["extra"].toString(); - if (!extra.isEmpty()) { - text = text.arg(extra); - } - } - label->setText(text); - label->setVisible(!text.isEmpty()); - alertCount += !text.isEmpty(); - } - disable_check_btn->setVisible(!alerts["Offroad_ConnectivityNeeded"]->text().isEmpty()); - snooze_btn->setVisible(!alerts["Offroad_ConnectivityNeeded"]->text().isEmpty()); - return alertCount; -} - -UpdateAlert::UpdateAlert(QWidget *parent) : AbstractAlert(true, parent) { - releaseNotes = new QLabel(this); - releaseNotes->setWordWrap(true); - releaseNotes->setAlignment(Qt::AlignTop); - scrollable_layout->addWidget(releaseNotes); -} - -bool UpdateAlert::refresh() { - bool updateAvailable = params.getBool("UpdateAvailable"); - if (updateAvailable) { - releaseNotes->setText(params.get("UpdaterNewReleaseNotes").c_str()); - } - return updateAvailable; -} diff --git a/selfdrive/ui/qt/widgets/offroad_alerts.h b/selfdrive/ui/qt/widgets/offroad_alerts.h deleted file mode 100644 index abeafd2..0000000 --- a/selfdrive/ui/qt/widgets/offroad_alerts.h +++ /dev/null @@ -1,47 +0,0 @@ -#pragma once - -#include -#include - -#include -#include -#include - -#include "common/params.h" - -class AbstractAlert : public QFrame { - Q_OBJECT - -protected: - AbstractAlert(bool hasRebootBtn, QWidget *parent = nullptr); - - QPushButton *disable_check_btn; - QPushButton *snooze_btn; - QVBoxLayout *scrollable_layout; - Params params; - -signals: - void dismiss(); -}; - -class UpdateAlert : public AbstractAlert { - Q_OBJECT - -public: - UpdateAlert(QWidget *parent = 0); - bool refresh(); - -private: - QLabel *releaseNotes = nullptr; -}; - -class OffroadAlert : public AbstractAlert { - Q_OBJECT - -public: - explicit OffroadAlert(QWidget *parent = 0) : AbstractAlert(false, parent) {} - int refresh(); - -private: - std::map alerts; -}; diff --git a/selfdrive/ui/qt/widgets/prime.cc b/selfdrive/ui/qt/widgets/prime.cc deleted file mode 100644 index 324d6cf..0000000 --- a/selfdrive/ui/qt/widgets/prime.cc +++ /dev/null @@ -1,283 +0,0 @@ -#include "selfdrive/ui/qt/widgets/prime.h" - -#include -#include -#include -#include -#include -#include -#include -#include - -#include - -#include "selfdrive/ui/qt/request_repeater.h" -#include "selfdrive/ui/qt/util.h" -#include "selfdrive/ui/qt/qt_window.h" -#include "selfdrive/ui/qt/widgets/wifi.h" - -using qrcodegen::QrCode; - -PairingQRWidget::PairingQRWidget(QWidget* parent) : QWidget(parent) { - timer = new QTimer(this); - connect(timer, &QTimer::timeout, this, &PairingQRWidget::refresh); -} - -void PairingQRWidget::showEvent(QShowEvent *event) { - refresh(); - timer->start(5 * 60 * 1000); - device()->setOffroadBrightness(100); -} - -void PairingQRWidget::hideEvent(QHideEvent *event) { - timer->stop(); - device()->setOffroadBrightness(BACKLIGHT_OFFROAD); -} - -void PairingQRWidget::refresh() { - QString pairToken = CommaApi::create_jwt({{"pair", true}}); - QString qrString = "https://connect.comma.ai/?pair=" + pairToken; - this->updateQrCode(qrString); - update(); -} - -void PairingQRWidget::updateQrCode(const QString &text) { - QrCode qr = QrCode::encodeText(text.toUtf8().data(), QrCode::Ecc::LOW); - qint32 sz = qr.getSize(); - QImage im(sz, sz, QImage::Format_RGB32); - - QRgb black = qRgb(0, 0, 0); - QRgb white = qRgb(255, 255, 255); - for (int y = 0; y < sz; y++) { - for (int x = 0; x < sz; x++) { - im.setPixel(x, y, qr.getModule(x, y) ? black : white); - } - } - - // Integer division to prevent anti-aliasing - int final_sz = ((width() / sz) - 1) * sz; - img = QPixmap::fromImage(im.scaled(final_sz, final_sz, Qt::KeepAspectRatio), Qt::MonoOnly); -} - -void PairingQRWidget::paintEvent(QPaintEvent *e) { - QPainter p(this); - p.fillRect(rect(), Qt::white); - - QSize s = (size() - img.size()) / 2; - p.drawPixmap(s.width(), s.height(), img); -} - - -PairingPopup::PairingPopup(QWidget *parent) : DialogBase(parent) { - QHBoxLayout *hlayout = new QHBoxLayout(this); - hlayout->setContentsMargins(0, 0, 0, 0); - hlayout->setSpacing(0); - - setStyleSheet("PairingPopup { background-color: #E0E0E0; }"); - - // text - QVBoxLayout *vlayout = new QVBoxLayout(); - vlayout->setContentsMargins(85, 70, 50, 70); - vlayout->setSpacing(50); - hlayout->addLayout(vlayout, 1); - { - QPushButton *close = new QPushButton(QIcon(":/icons/close.svg"), "", this); - close->setIconSize(QSize(80, 80)); - close->setStyleSheet("border: none;"); - vlayout->addWidget(close, 0, Qt::AlignLeft); - QObject::connect(close, &QPushButton::clicked, this, &QDialog::reject); - - vlayout->addSpacing(30); - - QLabel *title = new QLabel(tr("Pair your device to your comma account"), this); - title->setStyleSheet("font-size: 75px; color: black;"); - title->setWordWrap(true); - vlayout->addWidget(title); - - QLabel *instructions = new QLabel(QString(R"( -
    -
  1. %1
  2. -
  3. %2
  4. -
  5. %3
  6. -
- )").arg(tr("Go to https://connect.comma.ai on your phone")) - .arg(tr("Click \"add new device\" and scan the QR code on the right")) - .arg(tr("Bookmark connect.comma.ai to your home screen to use it like an app")), this); - - instructions->setStyleSheet("font-size: 47px; font-weight: bold; color: black;"); - instructions->setWordWrap(true); - vlayout->addWidget(instructions); - - vlayout->addStretch(); - } - - // QR code - PairingQRWidget *qr = new PairingQRWidget(this); - hlayout->addWidget(qr, 1); -} - - -PrimeUserWidget::PrimeUserWidget(QWidget *parent) : QFrame(parent) { - setObjectName("primeWidget"); - QVBoxLayout *mainLayout = new QVBoxLayout(this); - mainLayout->setContentsMargins(56, 40, 56, 40); - mainLayout->setSpacing(20); - - QLabel *subscribed = new QLabel(tr("✓ SUBSCRIBED")); - subscribed->setStyleSheet("font-size: 41px; font-weight: bold; color: #86FF4E;"); - mainLayout->addWidget(subscribed); - - QLabel *commaPrime = new QLabel(tr("comma prime")); - commaPrime->setStyleSheet("font-size: 75px; font-weight: bold;"); - mainLayout->addWidget(commaPrime); -} - - -PrimeAdWidget::PrimeAdWidget(QWidget* parent) : QFrame(parent) { - QVBoxLayout *main_layout = new QVBoxLayout(this); - main_layout->setContentsMargins(80, 90, 80, 60); - main_layout->setSpacing(0); - - QLabel *upgrade = new QLabel(tr("Upgrade Now")); - upgrade->setStyleSheet("font-size: 75px; font-weight: bold;"); - main_layout->addWidget(upgrade, 0, Qt::AlignTop); - main_layout->addSpacing(50); - - QLabel *description = new QLabel(tr("Become a comma prime member at connect.comma.ai")); - description->setStyleSheet("font-size: 56px; font-weight: light; color: white;"); - description->setWordWrap(true); - main_layout->addWidget(description, 0, Qt::AlignTop); - - main_layout->addStretch(); - - QLabel *features = new QLabel(tr("PRIME FEATURES:")); - features->setStyleSheet("font-size: 41px; font-weight: bold; color: #E5E5E5;"); - main_layout->addWidget(features, 0, Qt::AlignBottom); - main_layout->addSpacing(30); - - QVector bullets = {tr("Remote access"), tr("24/7 LTE connectivity"), tr("1 year of drive storage"), tr("Turn-by-turn navigation")}; - for (auto &b : bullets) { - const QString check = " "; - QLabel *l = new QLabel(check + b); - l->setAlignment(Qt::AlignLeft); - l->setStyleSheet("font-size: 50px; margin-bottom: 15px;"); - main_layout->addWidget(l, 0, Qt::AlignBottom); - } - - setStyleSheet(R"( - PrimeAdWidget { - border-radius: 10px; - background-color: #333333; - } - )"); -} - - -SetupWidget::SetupWidget(QWidget* parent) : QFrame(parent) { - mainLayout = new QStackedWidget; - - // Unpaired, registration prompt layout - - QFrame* finishRegistration = new QFrame; - finishRegistration->setObjectName("primeWidget"); - QVBoxLayout* finishRegistationLayout = new QVBoxLayout(finishRegistration); - finishRegistationLayout->setSpacing(38); - finishRegistationLayout->setContentsMargins(64, 48, 64, 48); - - QLabel* registrationTitle = new QLabel(tr("Finish Setup")); - registrationTitle->setStyleSheet("font-size: 75px; font-weight: bold;"); - finishRegistationLayout->addWidget(registrationTitle); - - QLabel* registrationDescription = new QLabel(tr("Pair your device with comma connect (connect.comma.ai) and claim your comma prime offer.")); - registrationDescription->setWordWrap(true); - registrationDescription->setStyleSheet("font-size: 50px; font-weight: light;"); - finishRegistationLayout->addWidget(registrationDescription); - - finishRegistationLayout->addStretch(); - - QPushButton* pair = new QPushButton(tr("Pair device")); - pair->setStyleSheet(R"( - QPushButton { - font-size: 55px; - font-weight: 500; - border-radius: 10px; - background-color: #465BEA; - padding: 64px; - } - QPushButton:pressed { - background-color: #3049F4; - } - )"); - finishRegistationLayout->addWidget(pair); - - popup = new PairingPopup(this); - QObject::connect(pair, &QPushButton::clicked, popup, &PairingPopup::exec); - - mainLayout->addWidget(finishRegistration); - - // build stacked layout - QVBoxLayout *outer_layout = new QVBoxLayout(this); - outer_layout->setContentsMargins(0, 0, 0, 0); - outer_layout->addWidget(mainLayout); - - QWidget *content = new QWidget; - QVBoxLayout *content_layout = new QVBoxLayout(content); - content_layout->setContentsMargins(0, 0, 0, 0); - content_layout->setSpacing(30); - - primeUser = new PrimeUserWidget; - content_layout->addWidget(primeUser); - - WiFiPromptWidget *wifi_prompt = new WiFiPromptWidget; - QObject::connect(wifi_prompt, &WiFiPromptWidget::openSettings, this, &SetupWidget::openSettings); - content_layout->addWidget(wifi_prompt); - content_layout->addStretch(); - - mainLayout->addWidget(content); - - primeUser->setVisible(uiState()->primeType()); - mainLayout->setCurrentIndex(1); - - setStyleSheet(R"( - #primeWidget { - border-radius: 10px; - background-color: #333333; - } - )"); - - // Retain size while hidden - QSizePolicy sp_retain = sizePolicy(); - sp_retain.setRetainSizeWhenHidden(true); - setSizePolicy(sp_retain); - - // set up API requests - if (auto dongleId = getDongleId()) { - QString url = CommaApi::BASE_URL + "/v1.1/devices/" + *dongleId + "/"; - RequestRepeater* repeater = new RequestRepeater(this, url, "ApiCache_Device", 5); - - QObject::connect(repeater, &RequestRepeater::requestDone, this, &SetupWidget::replyFinished); - } -} - -void SetupWidget::replyFinished(const QString &response, bool success) { - if (!success) return; - - QJsonDocument doc = QJsonDocument::fromJson(response.toUtf8()); - if (doc.isNull()) { - qDebug() << "JSON Parse failed on getting pairing and prime status"; - return; - } - - QJsonObject json = doc.object(); - PrimeType prime_type = static_cast(json["prime_type"].toInt()); - uiState()->setPrimeType(prime_type); - - if (!json["is_paired"].toBool()) { - mainLayout->setCurrentIndex(0); - } else { - popup->reject(); - - primeUser->setVisible(prime_type); - mainLayout->setCurrentIndex(1); - } -} diff --git a/selfdrive/ui/qt/widgets/prime.h b/selfdrive/ui/qt/widgets/prime.h deleted file mode 100644 index 63341c4..0000000 --- a/selfdrive/ui/qt/widgets/prime.h +++ /dev/null @@ -1,73 +0,0 @@ -#pragma once - -#include -#include -#include -#include - -#include "selfdrive/ui/qt/widgets/input.h" - -// pairing QR code -class PairingQRWidget : public QWidget { - Q_OBJECT - -public: - explicit PairingQRWidget(QWidget* parent = 0); - void paintEvent(QPaintEvent*) override; - -private: - QPixmap img; - QTimer *timer; - void updateQrCode(const QString &text); - void showEvent(QShowEvent *event) override; - void hideEvent(QHideEvent *event) override; - -private slots: - void refresh(); -}; - - -// pairing popup widget -class PairingPopup : public DialogBase { - Q_OBJECT - -public: - explicit PairingPopup(QWidget* parent); -}; - - -// widget for paired users with prime -class PrimeUserWidget : public QFrame { - Q_OBJECT - -public: - explicit PrimeUserWidget(QWidget* parent = 0); -}; - - -// widget for paired users without prime -class PrimeAdWidget : public QFrame { - Q_OBJECT -public: - explicit PrimeAdWidget(QWidget* parent = 0); -}; - - -// container widget -class SetupWidget : public QFrame { - Q_OBJECT - -public: - explicit SetupWidget(QWidget* parent = 0); - -signals: - void openSettings(int index = 0, const QString ¶m = ""); - -private: - PairingPopup *popup; - QStackedWidget *mainLayout; - PrimeUserWidget *primeUser; - -private slots: - void replyFinished(const QString &response, bool success); -}; diff --git a/selfdrive/ui/qt/widgets/scrollview.cc b/selfdrive/ui/qt/widgets/scrollview.cc deleted file mode 100644 index 2846007..0000000 --- a/selfdrive/ui/qt/widgets/scrollview.cc +++ /dev/null @@ -1,53 +0,0 @@ -#include "selfdrive/ui/qt/widgets/scrollview.h" - -#include -#include - -// TODO: disable horizontal scrolling and resize - -ScrollView::ScrollView(QWidget *w, QWidget *parent) : QScrollArea(parent) { - setWidget(w); - setWidgetResizable(true); - setVerticalScrollBarPolicy(Qt::ScrollBarAlwaysOff); - setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOff); - setStyleSheet("background-color: transparent; border:none"); - - QString style = R"( - QScrollBar:vertical { - border: none; - background: transparent; - width: 10px; - margin: 0; - } - QScrollBar::handle:vertical { - min-height: 0px; - border-radius: 5px; - background-color: white; - } - QScrollBar::add-line:vertical, QScrollBar::sub-line:vertical { - height: 0px; - } - QScrollBar::add-page:vertical, QScrollBar::sub-page:vertical { - background: none; - } - )"; - verticalScrollBar()->setStyleSheet(style); - horizontalScrollBar()->setStyleSheet(style); - - QScroller *scroller = QScroller::scroller(this->viewport()); - QScrollerProperties sp = scroller->scrollerProperties(); - - sp.setScrollMetric(QScrollerProperties::VerticalOvershootPolicy, QVariant::fromValue(QScrollerProperties::OvershootAlwaysOff)); - sp.setScrollMetric(QScrollerProperties::HorizontalOvershootPolicy, QVariant::fromValue(QScrollerProperties::OvershootAlwaysOff)); - sp.setScrollMetric(QScrollerProperties::MousePressEventDelay, 0.01); - scroller->grabGesture(this->viewport(), QScroller::LeftMouseButtonGesture); - scroller->setScrollerProperties(sp); -} - -void ScrollView::restorePosition(int previousScrollPosition) { - verticalScrollBar()->setValue(previousScrollPosition); -} - -void ScrollView::hideEvent(QHideEvent *e) { - verticalScrollBar()->setValue(0); -} diff --git a/selfdrive/ui/qt/widgets/scrollview.h b/selfdrive/ui/qt/widgets/scrollview.h deleted file mode 100644 index 1e67bbe..0000000 --- a/selfdrive/ui/qt/widgets/scrollview.h +++ /dev/null @@ -1,15 +0,0 @@ -#pragma once - -#include - -class ScrollView : public QScrollArea { - Q_OBJECT - -public: - explicit ScrollView(QWidget *w = nullptr, QWidget *parent = nullptr); - - // FrogPilot functions - void restorePosition(int previousScrollPosition); -protected: - void hideEvent(QHideEvent *e) override; -}; diff --git a/selfdrive/ui/qt/widgets/ssh_keys.cc b/selfdrive/ui/qt/widgets/ssh_keys.cc deleted file mode 100644 index 2674395..0000000 --- a/selfdrive/ui/qt/widgets/ssh_keys.cc +++ /dev/null @@ -1,64 +0,0 @@ -#include "selfdrive/ui/qt/widgets/ssh_keys.h" - -#include "common/params.h" -#include "selfdrive/ui/qt/api.h" -#include "selfdrive/ui/qt/widgets/input.h" - -SshControl::SshControl() : - ButtonControl(tr("SSH Keys"), "", tr("Warning: This grants SSH access to all public keys in your GitHub settings. Never enter a GitHub username " - "other than your own. A comma employee will NEVER ask you to add their GitHub username.")) { - - QObject::connect(this, &ButtonControl::clicked, [=]() { - if (text() == tr("ADD")) { - QString username = InputDialog::getText(tr("Enter your GitHub username"), this); - if (username.length() > 0) { - setText(tr("LOADING")); - setEnabled(false); - getUserKeys(username); - } - } else { - params.remove("GithubUsername"); - params.remove("GithubSshKeys"); - refresh(); - } - }); - - refresh(); -} - -void SshControl::refresh() { - QString param = QString::fromStdString(params.get("GithubSshKeys")); - if (param.length()) { - setValue(QString::fromStdString(params.get("GithubUsername"))); - setText(tr("REMOVE")); - } else { - setValue(""); - setText(tr("ADD")); - } - setEnabled(true); -} - -void SshControl::getUserKeys(const QString &username) { - HttpRequest *request = new HttpRequest(this, false); - QObject::connect(request, &HttpRequest::requestDone, [=](const QString &resp, bool success) { - if (success) { - if (!resp.isEmpty()) { - params.put("GithubUsername", username.toStdString()); - params.put("GithubSshKeys", resp.toStdString()); - } else { - ConfirmationDialog::alert(tr("Username '%1' has no keys on GitHub").arg(username), this); - } - } else { - if (request->timeout()) { - ConfirmationDialog::alert(tr("Request timed out"), this); - } else { - ConfirmationDialog::alert(tr("Username '%1' doesn't exist on GitHub").arg(username), this); - } - } - - refresh(); - request->deleteLater(); - }); - - request->sendRequest("https://github.com/" + username + ".keys"); -} diff --git a/selfdrive/ui/qt/widgets/ssh_keys.h b/selfdrive/ui/qt/widgets/ssh_keys.h deleted file mode 100644 index 920bd65..0000000 --- a/selfdrive/ui/qt/widgets/ssh_keys.h +++ /dev/null @@ -1,32 +0,0 @@ -#pragma once - -#include - -#include "system/hardware/hw.h" -#include "selfdrive/ui/qt/widgets/controls.h" - -// SSH enable toggle -class SshToggle : public ToggleControl { - Q_OBJECT - -public: - SshToggle() : ToggleControl(tr("Enable SSH"), "", "", Hardware::get_ssh_enabled()) { - QObject::connect(this, &SshToggle::toggleFlipped, [=](bool state) { - Hardware::set_ssh_enabled(state); - }); - } -}; - -// SSH key management widget -class SshControl : public ButtonControl { - Q_OBJECT - -public: - SshControl(); - -private: - Params params; - - void refresh(); - void getUserKeys(const QString &username); -}; diff --git a/selfdrive/ui/qt/widgets/toggle.cc b/selfdrive/ui/qt/widgets/toggle.cc deleted file mode 100644 index 82302ad..0000000 --- a/selfdrive/ui/qt/widgets/toggle.cc +++ /dev/null @@ -1,83 +0,0 @@ -#include "selfdrive/ui/qt/widgets/toggle.h" - -#include - -Toggle::Toggle(QWidget *parent) : QAbstractButton(parent), -_height(80), -_height_rect(60), -on(false), -_anim(new QPropertyAnimation(this, "offset_circle", this)) -{ - _radius = _height / 2; - _x_circle = _radius; - _y_circle = _radius; - _y_rect = (_height - _height_rect)/2; - circleColor = QColor(0xffffff); // placeholder - green = QColor(0xffffff); // placeholder - setEnabled(true); -} - -void Toggle::paintEvent(QPaintEvent *e) { - this->setFixedHeight(_height); - QPainter p(this); - p.setPen(Qt::NoPen); - p.setRenderHint(QPainter::Antialiasing, true); - - // Draw toggle background left - p.setBrush(green); - p.drawRoundedRect(QRect(0, _y_rect, _x_circle + _radius, _height_rect), _height_rect/2, _height_rect/2); - - // Draw toggle background right - p.setBrush(QColor(0x393939)); - p.drawRoundedRect(QRect(_x_circle - _radius, _y_rect, width() - (_x_circle - _radius), _height_rect), _height_rect/2, _height_rect/2); - - // Draw toggle circle - p.setBrush(circleColor); - p.drawEllipse(QRectF(_x_circle - _radius, _y_circle - _radius, 2 * _radius, 2 * _radius)); -} - -void Toggle::mouseReleaseEvent(QMouseEvent *e) { - if (!enabled) { - return; - } - const int left = _radius; - const int right = width() - _radius; - if ((_x_circle != left && _x_circle != right) || !this->rect().contains(e->localPos().toPoint())) { - // If mouse release isn't in rect or animation is running, don't parse touch events - return; - } - if (e->button() & Qt::LeftButton) { - togglePosition(); - emit stateChanged(on); - } -} - -void Toggle::togglePosition() { - on = !on; - const int left = _radius; - const int right = width() - _radius; - _anim->setStartValue(on ? left + immediateOffset : right - immediateOffset); - _anim->setEndValue(on ? right : left); - _anim->setDuration(animation_duration); - _anim->start(); - repaint(); -} - -void Toggle::enterEvent(QEvent *e) { - QAbstractButton::enterEvent(e); -} - -bool Toggle::getEnabled() { - return enabled; -} - -void Toggle::setEnabled(bool value) { - enabled = value; - if (value) { - circleColor.setRgb(0xfafafa); - green.setRgb(0x33ab4c); - } else { - circleColor.setRgb(0x888888); - green.setRgb(0x227722); - } -} diff --git a/selfdrive/ui/qt/widgets/toggle.h b/selfdrive/ui/qt/widgets/toggle.h deleted file mode 100644 index e7263a0..0000000 --- a/selfdrive/ui/qt/widgets/toggle.h +++ /dev/null @@ -1,44 +0,0 @@ -#pragma once - -#include -#include -#include - -class Toggle : public QAbstractButton { - Q_OBJECT - Q_PROPERTY(int offset_circle READ offset_circle WRITE set_offset_circle CONSTANT) - -public: - Toggle(QWidget* parent = nullptr); - void togglePosition(); - bool on; - int animation_duration = 150; - int immediateOffset = 0; - int offset_circle() const { - return _x_circle; - } - - void set_offset_circle(int o) { - _x_circle = o; - update(); - } - bool getEnabled(); - void setEnabled(bool value); - -protected: - void paintEvent(QPaintEvent*) override; - void mouseReleaseEvent(QMouseEvent*) override; - void enterEvent(QEvent*) override; - -private: - QColor circleColor; - QColor green; - bool enabled = true; - int _x_circle, _y_circle; - int _height, _radius; - int _height_rect, _y_rect; - QPropertyAnimation *_anim = nullptr; - -signals: - void stateChanged(bool new_state); -}; diff --git a/selfdrive/ui/qt/widgets/wifi.cc b/selfdrive/ui/qt/widgets/wifi.cc deleted file mode 100644 index 95beab4..0000000 --- a/selfdrive/ui/qt/widgets/wifi.cc +++ /dev/null @@ -1,132 +0,0 @@ -#include "selfdrive/ui/qt/widgets/wifi.h" - -#include -#include -#include -#include - -WiFiPromptWidget::WiFiPromptWidget(QWidget *parent) : QFrame(parent) { - stack = new QStackedLayout(this); - - // Setup Wi-Fi - QFrame *setup = new QFrame; - QVBoxLayout *setup_layout = new QVBoxLayout(setup); - setup_layout->setContentsMargins(56, 40, 56, 40); - setup_layout->setSpacing(20); - { - QHBoxLayout *title_layout = new QHBoxLayout; - title_layout->setSpacing(32); - { - QLabel *icon = new QLabel; - QPixmap pixmap("../assets/offroad/icon_wifi_strength_full.svg"); - icon->setPixmap(pixmap.scaledToWidth(80, Qt::SmoothTransformation)); - title_layout->addWidget(icon); - - QLabel *title = new QLabel(tr("Setup Wi-Fi")); - title->setStyleSheet("font-size: 64px; font-weight: 600;"); - title_layout->addWidget(title); - title_layout->addStretch(); - } - setup_layout->addLayout(title_layout); - - QLabel *desc = new QLabel(tr("Connect to Wi-Fi to upload driving data and help improve openpilot")); - desc->setStyleSheet("font-size: 40px; font-weight: 400;"); - desc->setWordWrap(true); - setup_layout->addWidget(desc); - - QPushButton *settings_btn = new QPushButton(tr("Open Settings")); - connect(settings_btn, &QPushButton::clicked, [=]() { emit openSettings(1); }); - settings_btn->setStyleSheet(R"( - QPushButton { - font-size: 48px; - font-weight: 500; - border-radius: 10px; - background-color: #465BEA; - padding: 32px; - } - QPushButton:pressed { - background-color: #3049F4; - } - )"); - setup_layout->addWidget(settings_btn); - } - stack->addWidget(setup); - - // Uploading data - QWidget *uploading = new QWidget; - QVBoxLayout *uploading_layout = new QVBoxLayout(uploading); - uploading_layout->setContentsMargins(64, 56, 64, 56); - uploading_layout->setSpacing(36); - { - QHBoxLayout *title_layout = new QHBoxLayout; - { - QLabel *title = new QLabel(tr("Ready to upload")); - title->setStyleSheet("font-size: 64px; font-weight: 600;"); - title->setWordWrap(true); - title->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Minimum); - title_layout->addWidget(title); - title_layout->addStretch(); - - QLabel *icon = new QLabel; - QPixmap pixmap("../assets/offroad/icon_wifi_uploading.svg"); - icon->setPixmap(pixmap.scaledToWidth(120, Qt::SmoothTransformation)); - title_layout->addWidget(icon); - } - uploading_layout->addLayout(title_layout); - - QLabel *desc = new QLabel(tr("Training data will be pulled periodically while your device is on Wi-Fi")); - desc->setStyleSheet("font-size: 48px; font-weight: 400;"); - desc->setWordWrap(true); - uploading_layout->addWidget(desc); - } - stack->addWidget(uploading); - - QWidget *notUploading = new QWidget; - QVBoxLayout *not_uploading_layout = new QVBoxLayout(notUploading); - not_uploading_layout->setContentsMargins(64, 56, 64, 56); - not_uploading_layout->setSpacing(36); - { - QHBoxLayout *title_layout = new QHBoxLayout; - { - QLabel *title = new QLabel(tr("Uploading disabled")); - title->setStyleSheet("font-size: 64px; font-weight: 600;"); - title->setWordWrap(true); - title->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Minimum); - title_layout->addWidget(title); - title_layout->addStretch(); - - QLabel *icon = new QLabel; - QPixmap pixmap("../assets/offroad/icon_wifi_uploading_disabled.svg"); - icon->setPixmap(pixmap.scaledToWidth(120, Qt::SmoothTransformation)); - title_layout->addWidget(icon); - } - not_uploading_layout->addLayout(title_layout); - - QLabel *desc = new QLabel(tr("Training data wont be pulled periodically until you disable the 'Disable Uploading' toggle")); - desc->setStyleSheet("font-size: 48px; font-weight: 400;"); - desc->setWordWrap(true); - not_uploading_layout->addWidget(desc); - } - stack->addWidget(notUploading); - - setStyleSheet(R"( - WiFiPromptWidget { - background-color: #333333; - border-radius: 10px; - } - )"); - - QObject::connect(uiState(), &UIState::uiUpdate, this, &WiFiPromptWidget::updateState); -} - -void WiFiPromptWidget::updateState(const UIState &s) { - if (!isVisible()) return; - - auto &sm = *(s.sm); - - auto network_type = sm["deviceState"].getDeviceState().getNetworkType(); - auto uploading = network_type == cereal::DeviceState::NetworkType::WIFI || - network_type == cereal::DeviceState::NetworkType::ETHERNET; - auto uploading_disabled = params.getBool("NoUploads"); - stack->setCurrentIndex(uploading_disabled ? 2 : uploading ? 1 : 0); -} diff --git a/selfdrive/ui/qt/widgets/wifi.h b/selfdrive/ui/qt/widgets/wifi.h deleted file mode 100644 index e15c4b0..0000000 --- a/selfdrive/ui/qt/widgets/wifi.h +++ /dev/null @@ -1,27 +0,0 @@ -#pragma once - -#include -#include -#include - -#include "selfdrive/ui/ui.h" - -class WiFiPromptWidget : public QFrame { - Q_OBJECT - -public: - explicit WiFiPromptWidget(QWidget* parent = 0); - -private: - // FrogPilot variables - Params params; - -signals: - void openSettings(int index = 0, const QString ¶m = ""); - -public slots: - void updateState(const UIState &s); - -protected: - QStackedLayout *stack; -}; diff --git a/selfdrive/ui/qt/window.cc b/selfdrive/ui/qt/window.cc deleted file mode 100644 index 4e4bd36..0000000 --- a/selfdrive/ui/qt/window.cc +++ /dev/null @@ -1,103 +0,0 @@ -#include "selfdrive/ui/qt/window.h" - -#include - -#include "system/hardware/hw.h" - -MainWindow::MainWindow(QWidget *parent) : QWidget(parent) { - main_layout = new QStackedLayout(this); - main_layout->setMargin(0); - - homeWindow = new HomeWindow(this); - main_layout->addWidget(homeWindow); - QObject::connect(homeWindow, &HomeWindow::openSettings, this, &MainWindow::openSettings); - QObject::connect(homeWindow, &HomeWindow::closeSettings, this, &MainWindow::closeSettings); - - settingsWindow = new SettingsWindow(this); - main_layout->addWidget(settingsWindow); - QObject::connect(settingsWindow, &SettingsWindow::closeSettings, this, &MainWindow::closeSettings); - QObject::connect(settingsWindow, &SettingsWindow::reviewTrainingGuide, [=]() { - onboardingWindow->showTrainingGuide(); - main_layout->setCurrentWidget(onboardingWindow); - }); - QObject::connect(settingsWindow, &SettingsWindow::showDriverView, [=] { - homeWindow->showDriverView(true); - }); - - onboardingWindow = new OnboardingWindow(this); - main_layout->addWidget(onboardingWindow); - QObject::connect(onboardingWindow, &OnboardingWindow::onboardingDone, [=]() { - main_layout->setCurrentWidget(homeWindow); - }); - if (!onboardingWindow->completed()) { - main_layout->setCurrentWidget(onboardingWindow); - } - - QObject::connect(uiState(), &UIState::offroadTransition, [=](bool offroad) { - if (!offroad) { - closeSettings(); - } - }); - QObject::connect(device(), &Device::interactiveTimeout, [=]() { - if (main_layout->currentWidget() == settingsWindow) { - closeSettings(); - } - }); - - // load fonts - QFontDatabase::addApplicationFont("../assets/fonts/Inter-Black.ttf"); - QFontDatabase::addApplicationFont("../assets/fonts/Inter-Bold.ttf"); - QFontDatabase::addApplicationFont("../assets/fonts/Inter-ExtraBold.ttf"); - QFontDatabase::addApplicationFont("../assets/fonts/Inter-ExtraLight.ttf"); - QFontDatabase::addApplicationFont("../assets/fonts/Inter-Medium.ttf"); - QFontDatabase::addApplicationFont("../assets/fonts/Inter-Regular.ttf"); - QFontDatabase::addApplicationFont("../assets/fonts/Inter-SemiBold.ttf"); - QFontDatabase::addApplicationFont("../assets/fonts/Inter-Thin.ttf"); - QFontDatabase::addApplicationFont("../assets/fonts/JetBrainsMono-Medium.ttf"); - - // no outline to prevent the focus rectangle - setStyleSheet(R"( - * { - font-family: Inter; - outline: none; - } - )"); - setAttribute(Qt::WA_NoSystemBackground); -} - -void MainWindow::openSettings(int index, const QString ¶m) { - main_layout->setCurrentWidget(settingsWindow); - settingsWindow->setCurrentPanel(index, param); -} - -void MainWindow::closeSettings() { - main_layout->setCurrentWidget(homeWindow); - - if (uiState()->scene.started) { - // Map is always shown when using navigate on openpilot - if (uiState()->scene.navigate_on_openpilot) { - homeWindow->showMapPanel(true); - } else { - homeWindow->showSidebar(params.getBool("Sidebar")); - } - } -} - -bool MainWindow::eventFilter(QObject *obj, QEvent *event) { - bool ignore = false; - switch (event->type()) { - case QEvent::TouchBegin: - case QEvent::TouchUpdate: - case QEvent::TouchEnd: - case QEvent::MouseButtonPress: - case QEvent::MouseMove: { - // ignore events when device is awakened by resetInteractiveTimeout - ignore = !device()->isAwake(); - device()->resetInteractiveTimeout(uiState()->scene.screen_timeout, uiState()->scene.screen_timeout_onroad); - break; - } - default: - break; - } - return ignore; -} diff --git a/selfdrive/ui/qt/window.h b/selfdrive/ui/qt/window.h deleted file mode 100644 index f1389c2..0000000 --- a/selfdrive/ui/qt/window.h +++ /dev/null @@ -1,28 +0,0 @@ -#pragma once - -#include -#include - -#include "selfdrive/ui/qt/home.h" -#include "selfdrive/ui/qt/offroad/onboarding.h" -#include "selfdrive/ui/qt/offroad/settings.h" - -class MainWindow : public QWidget { - Q_OBJECT - -public: - explicit MainWindow(QWidget *parent = 0); - -private: - bool eventFilter(QObject *obj, QEvent *event) override; - void openSettings(int index = 0, const QString ¶m = ""); - void closeSettings(); - - QStackedLayout *main_layout; - HomeWindow *homeWindow; - SettingsWindow *settingsWindow; - OnboardingWindow *onboardingWindow; - - // FrogPilot variables - Params params; -}; diff --git a/selfdrive/ui/soundd.py b/selfdrive/ui/soundd.py index 4df3147..8954c09 100644 --- a/selfdrive/ui/soundd.py +++ b/selfdrive/ui/soundd.py @@ -46,12 +46,12 @@ sound_list: Dict[int, Tuple[str, Optional[int], float]] = { AudibleAlert.angry: ("angry.wav", 1, MAX_VOLUME), AudibleAlert.fart: ("fart.wav", 1, MAX_VOLUME), AudibleAlert.firefox: ("firefox.wav", 1, MAX_VOLUME), - AudibleAlert.noice: ("noice.wav", 1, MAX_VOLUME), AudibleAlert.nessie: ("nessie.wav", 1, MAX_VOLUME), + AudibleAlert.noice: ("noice.wav", 1, MAX_VOLUME), AudibleAlert.uwu: ("uwu.wav", 1, MAX_VOLUME), # Other - AudibleAlert.goat: ("goat.wav", 1, MAX_VOLUME), + AudibleAlert.goat: ("goat.wav", None, MAX_VOLUME), } def check_controls_timeout_alert(sm): @@ -72,9 +72,16 @@ class Soundd: self.random_events_directory = BASEDIR + "/selfdrive/frogpilot/assets/random_events/sounds/" - self.update_frogpilot_params() + self.random_events_map = { + AudibleAlert.angry: MAX_VOLUME, + AudibleAlert.fart: MAX_VOLUME, + AudibleAlert.firefox: MAX_VOLUME, + AudibleAlert.nessie: MAX_VOLUME, + AudibleAlert.noice: MAX_VOLUME, + AudibleAlert.uwu: MAX_VOLUME, + } - self.load_sounds() + self.update_frogpilot_params() self.current_alert = AudibleAlert.none self.current_volume = MIN_VOLUME @@ -89,12 +96,18 @@ class Soundd: # Load all sounds for sound in sound_list: + if sound == AudibleAlert.goat and not self.goat_scream: + continue + filename, play_count, volume = sound_list[sound] - if os.path.exists(os.path.join(self.random_events_directory, filename)): + if sound in self.random_events_map: wavefile = wave.open(self.random_events_directory + filename, 'r') else: - wavefile = wave.open(self.sound_directory + filename, 'r') + try: + wavefile = wave.open(self.sound_directory + filename, 'r') + except FileNotFoundError: + wavefile = wave.open(BASEDIR + "/selfdrive/assets/sounds/" + filename, 'r') assert wavefile.getnchannels() == 1 assert wavefile.getsampwidth() == 2 @@ -163,44 +176,40 @@ class Soundd: sm = messaging.SubMaster(['controlsState', 'microphone']) - with self.get_stream(sd) as stream: - rk = Ratekeeper(20) + try: + with self.get_stream(sd) as stream: + rk = Ratekeeper(20) - cloudlog.info(f"soundd stream started: {stream.samplerate=} {stream.channels=} {stream.dtype=} {stream.device=}, {stream.blocksize=}") - while True: - sm.update(0) + cloudlog.info(f"soundd stream started: {stream.samplerate=} {stream.channels=} {stream.dtype=} {stream.device=}, {stream.blocksize=}") + while True: + sm.update(0) - if sm.updated['microphone'] and self.current_alert == AudibleAlert.none and not self.alert_volume_control: # only update volume filter when not playing alert - self.spl_filter_weighted.update(sm["microphone"].soundPressureWeightedDb) - self.current_volume = self.calculate_volume(float(self.spl_filter_weighted.x)) + if sm.updated['microphone'] and self.current_alert == AudibleAlert.none and not self.alert_volume_control: # only update volume filter when not playing alert + self.spl_filter_weighted.update(sm["microphone"].soundPressureWeightedDb) + self.current_volume = self.calculate_volume(float(self.spl_filter_weighted.x)) - elif self.alert_volume_control and self.current_alert in self.volume_map: - self.current_volume = self.volume_map[self.current_alert] / 100.0 + elif self.alert_volume_control and self.current_alert in self.volume_map: + self.current_volume = self.volume_map[self.current_alert] / 100.0 - # Increase the volume for Random Events - elif self.current_alert in self.random_events_map: - self.current_volume = self.random_events_map[self.current_alert] + # Increase the volume for Random Events + elif self.current_alert in self.random_events_map: + self.current_volume = self.random_events_map[self.current_alert] - self.get_audible_alert(sm) + self.get_audible_alert(sm) - rk.keep_time() + rk.keep_time() - assert stream.active + if not stream.active: + raise AssertionError("Stream is not active") - # Update FrogPilot parameters - if self.params_memory.get_bool("FrogPilotTogglesUpdated"): - self.update_frogpilot_params() + # Update FrogPilot parameters + if self.params_memory.get_bool("FrogPilotTogglesUpdated"): + self.update_frogpilot_params() + + except AssertionError: + pass def update_frogpilot_params(self): - self.random_events_map = { - AudibleAlert.angry: MAX_VOLUME, - AudibleAlert.fart: MAX_VOLUME, - AudibleAlert.firefox: MAX_VOLUME, - AudibleAlert.nessie: MAX_VOLUME, - AudibleAlert.noice: MAX_VOLUME, - AudibleAlert.uwu: MAX_VOLUME, - } - self.alert_volume_control = self.params.get_bool("AlertVolumeControl") self.volume_map = { @@ -215,11 +224,12 @@ class Soundd: AudibleAlert.warningSoft: self.params.get_int("WarningSoftVolume"), AudibleAlert.warningImmediate: self.params.get_int("WarningImmediateVolume"), - AudibleAlert.goat: self.params.get_int("WarningSoftVolume"), + AudibleAlert.goat: self.params.get_int("PromptVolume"), } custom_theme = self.params.get_bool("CustomTheme") custom_sounds = self.params.get_int("CustomSounds") if custom_theme else 0 + self.goat_scream = custom_sounds == 1 and self.params.get_bool("GoatScream") theme_configuration = { 1: "frog_theme", @@ -247,9 +257,10 @@ class Soundd: if current_holiday_theme != 0: theme_name = holiday_theme_configuration.get(current_holiday_theme) self.sound_directory = BASEDIR + ("/selfdrive/frogpilot/assets/holiday_themes/" + theme_name + "/sounds/") + self.goat_scream = False else: theme_name = theme_configuration.get(custom_sounds) - self.sound_directory = BASEDIR + ("/selfdrive/frogpilot/assets/custom_themes/" + theme_name + "/sounds/" if custom_sounds else "/selfdrive/assets/sounds/") + self.sound_directory = BASEDIR + ("/selfdrive/frogpilot/assets/custom_themes/" + theme_name + "/sounds/" if custom_sounds != 0 else "/selfdrive/assets/sounds/") self.load_sounds() diff --git a/selfdrive/ui/tests/test_translations.py b/selfdrive/ui/tests/test_translations.py deleted file mode 100755 index 9ba9054..0000000 --- a/selfdrive/ui/tests/test_translations.py +++ /dev/null @@ -1,134 +0,0 @@ -#!/usr/bin/env python3 -import json -import os -import re -import unittest -import shutil -import tempfile -import xml.etree.ElementTree as ET -import string -import requests -from parameterized import parameterized_class - -from openpilot.selfdrive.ui.update_translations import TRANSLATIONS_DIR, LANGUAGES_FILE, update_translations - -with open(LANGUAGES_FILE, "r") as f: - translation_files = json.load(f) - -UNFINISHED_TRANSLATION_TAG = "" not in cur_translations, - f"{self.file} ({self.name}) translation file has obsolete translations. Run selfdrive/ui/update_translations.py --vanish to remove them") - - def test_finished_translations(self): - """ - Tests ran on each translation marked "finished" - Plural: - - that any numerus (plural) translations have all plural forms non-empty - - that the correct format specifier is used (%n) - Non-plural: - - that translation is not empty - - that translation format arguments are consistent - """ - tr_xml = ET.parse(os.path.join(TRANSLATIONS_DIR, f"{self.file}.ts")) - - for context in tr_xml.getroot(): - for message in context.iterfind("message"): - translation = message.find("translation") - source_text = message.find("source").text - - # Do not test unfinished translations - if translation.get("type") == "unfinished": - continue - - if message.get("numerus") == "yes": - numerusform = [t.text for t in translation.findall("numerusform")] - - for nf in numerusform: - self.assertIsNotNone(nf, f"Ensure all plural translation forms are completed: {source_text}") - self.assertIn("%n", nf, "Ensure numerus argument (%n) exists in translation.") - self.assertIsNone(FORMAT_ARG.search(nf), "Plural translations must use %n, not %1, %2, etc.: {}".format(numerusform)) - - else: - self.assertIsNotNone(translation.text, f"Ensure translation is completed: {source_text}") - - source_args = FORMAT_ARG.findall(source_text) - translation_args = FORMAT_ARG.findall(translation.text) - self.assertEqual(sorted(source_args), sorted(translation_args), - f"Ensure format arguments are consistent: `{source_text}` vs. `{translation.text}`") - - def test_no_locations(self): - for line in self._read_translation_file(TRANSLATIONS_DIR, self.file).splitlines(): - self.assertFalse(line.strip().startswith(LOCATION_TAG), - f"Line contains location tag: {line.strip()}, remove all line numbers.") - - def test_entities_error(self): - cur_translations = self._read_translation_file(TRANSLATIONS_DIR, self.file) - matches = re.findall(r'@(\w+);', cur_translations) - self.assertEqual(len(matches), 0, f"The string(s) {matches} were found with '@' instead of '&'") - - def test_bad_language(self): - IGNORED_WORDS = {'pédale'} - - match = re.search(r'_([a-zA-Z]{2,3})', self.file) - assert match, f"{self.name} - could not parse language" - - response = requests.get(f"https://raw.githubusercontent.com/LDNOOBW/List-of-Dirty-Naughty-Obscene-and-Otherwise-Bad-Words/master/{match.group(1)}") - response.raise_for_status() - - banned_words = {line.strip() for line in response.text.splitlines()} - - for context in ET.parse(os.path.join(TRANSLATIONS_DIR, f"{self.file}.ts")).getroot(): - for message in context.iterfind("message"): - translation = message.find("translation") - if translation.get("type") == "unfinished": - continue - - translation_text = " ".join([t.text for t in translation.findall("numerusform")]) if message.get("numerus") == "yes" else translation.text - - if not translation_text: - continue - - words = set(translation_text.translate(str.maketrans('', '', string.punctuation + '%n')).lower().split()) - bad_words_found = words & (banned_words - IGNORED_WORDS) - assert not bad_words_found, f"Bad language found in {self.name}: '{translation_text}'. Bad word(s): {', '.join(bad_words_found)}" - - -if __name__ == "__main__": - unittest.main() diff --git a/selfdrive/ui/translations/main_ar.qm b/selfdrive/ui/translations/main_ar.qm new file mode 100644 index 0000000..145ccff Binary files /dev/null and b/selfdrive/ui/translations/main_ar.qm differ diff --git a/selfdrive/ui/translations/main_ar.ts b/selfdrive/ui/translations/main_ar.ts index eb6a580..eb9a7f2 100644 --- a/selfdrive/ui/translations/main_ar.ts +++ b/selfdrive/ui/translations/main_ar.ts @@ -15,6 +15,10 @@ Reboot and Update إعادة التشغيل والتحديث + + Disable Internet Check + + AdvancedNetworking @@ -293,6 +297,117 @@ Review مراجعة + + Delete Driving Data + + + + DELETE + + + + This button provides a swift and secure way to permanently delete all stored driving footage and data from your device. Ideal for maintaining privacy or freeing up space. + + + + Are you sure you want to permanently delete all of your driving footage and data? + + + + Delete + + + + Delete Toggle Storage Data + + + + This button provides a swift and secure way to permanently delete all long term stored toggle settings. Ideal for maintaining privacy or freeing up space. + + + + Are you sure you want to permanently delete all of your long term toggle settings storage? + + + + Backup + + + + Restore + + + + Name your backup + + + + Select a backup to delete + + + + Are you sure you want to delete this backup? + + + + Select a restore point + + + + Are you sure you want to restore this version of FrogPilot? + + + + Are you sure you want to restore this toggle backup? + + + + Flash Panda + + + + FLASH + + + + Are you sure you want to flash the Panda? + + + + Flash + + + + + DriveStats + + Drives + + + + Hours + + + + ALL TIME + + + + PAST WEEK + + + + FROGPILOT + + + + KM + + + + Miles + + DriverViewWindow @@ -362,6 +477,10 @@ Manage at connect.comma.ai الإدارة في connect.comma.ai + + Manage at %1 + + MapWindow @@ -564,7 +683,7 @@ openpilot - openpilot + openpilot %n minute(s) ago @@ -615,6 +734,10 @@ ft قدم + + FrogPilot + + Reset @@ -661,7 +784,7 @@ This may take up to a minute. SettingsWindow × - × + × Device @@ -679,6 +802,26 @@ This may take up to a minute. Software البرنامج + + ← Back + + + + Controls + + + + Navigation + + + + Vehicles + + + + Visuals + + Setup @@ -860,6 +1003,10 @@ This may take up to a minute. 5G 5G + + MEMORY + + SoftwarePanel @@ -881,7 +1028,7 @@ This may take up to a minute. Updates are only downloaded while the car is off. - يتم تحميل التحديثات فقط عندما تكون السيارة متوقفة. + يتم تحميل التحديثات فقط عندما تكون السيارة متوقفة. Current Version @@ -935,6 +1082,50 @@ This may take up to a minute. up to date, last checked %1 أحدث نسخة، آخر تحقق %1 + + Updates are only downloaded while the car is off or in park. + + + + Manually + + + + Daily + + + + Weekly + + + + Update Scheduler + + + + Choose the frequency to automatically update FrogPilot. + +This feature will handle the download, installation, and device reboot for a seamless 'Set and Forget' update experience. + +Weekly updates start at midnight every Sunday. + + + + Update Time + + + + Select a time to automatically update + + + + Error Log + + + + VIEW + عرض + SshControl @@ -1197,6 +1388,14 @@ This may take up to a minute. Training data will be pulled periodically while your device is on Wi-Fi سيتم سحب بيانات التدريب دورياً عندما يكون جهازك متصل بشبكة واي فاي + + Uploading disabled + + + + Training data wont be pulled periodically until you disable the 'Disable Uploading' toggle + + WifiUI diff --git a/selfdrive/ui/translations/main_de.qm b/selfdrive/ui/translations/main_de.qm new file mode 100644 index 0000000..f09c931 Binary files /dev/null and b/selfdrive/ui/translations/main_de.qm differ diff --git a/selfdrive/ui/translations/main_de.ts b/selfdrive/ui/translations/main_de.ts index 6d814b9..9946993 100644 --- a/selfdrive/ui/translations/main_de.ts +++ b/selfdrive/ui/translations/main_de.ts @@ -15,6 +15,10 @@ Reboot and Update Aktualisieren und neu starten + + Disable Internet Check + + AdvancedNetworking @@ -293,6 +297,117 @@ Review Überprüfen + + Delete Driving Data + + + + DELETE + + + + This button provides a swift and secure way to permanently delete all stored driving footage and data from your device. Ideal for maintaining privacy or freeing up space. + + + + Are you sure you want to permanently delete all of your driving footage and data? + + + + Delete + + + + Delete Toggle Storage Data + + + + This button provides a swift and secure way to permanently delete all long term stored toggle settings. Ideal for maintaining privacy or freeing up space. + + + + Are you sure you want to permanently delete all of your long term toggle settings storage? + + + + Backup + + + + Restore + + + + Name your backup + + + + Select a backup to delete + + + + Are you sure you want to delete this backup? + + + + Select a restore point + + + + Are you sure you want to restore this version of FrogPilot? + + + + Are you sure you want to restore this toggle backup? + + + + Flash Panda + + + + FLASH + + + + Are you sure you want to flash the Panda? + + + + Flash + + + + + DriveStats + + Drives + + + + Hours + + + + ALL TIME + + + + PAST WEEK + + + + FROGPILOT + + + + KM + + + + Miles + + DriverViewWindow @@ -358,6 +473,10 @@ Manage at connect.comma.ai + + Manage at %1 + + MapWindow @@ -559,7 +678,7 @@ openpilot - openpilot + openpilot %n minute(s) ago @@ -598,6 +717,10 @@ ft fuß + + FrogPilot + + Reset @@ -643,7 +766,7 @@ This may take up to a minute. SettingsWindow × - x + x Device @@ -661,6 +784,26 @@ This may take up to a minute. Software Software + + ← Back + + + + Controls + + + + Navigation + + + + Vehicles + + + + Visuals + + Setup @@ -843,6 +986,10 @@ This may take up to a minute. 5G 5G + + MEMORY + + SoftwarePanel @@ -865,7 +1012,7 @@ This may take up to a minute. Updates are only downloaded while the car is off. - Updates werden nur heruntergeladen, wenn das Auto aus ist. + Updates werden nur heruntergeladen, wenn das Auto aus ist. Current Version @@ -919,6 +1066,50 @@ This may take up to a minute. never + + Updates are only downloaded while the car is off or in park. + + + + Manually + + + + Daily + + + + Weekly + + + + Update Scheduler + + + + Choose the frequency to automatically update FrogPilot. + +This feature will handle the download, installation, and device reboot for a seamless 'Set and Forget' update experience. + +Weekly updates start at midnight every Sunday. + + + + Update Time + + + + Select a time to automatically update + + + + Error Log + + + + VIEW + ANSEHEN + SshControl @@ -1183,6 +1374,14 @@ This may take up to a minute. Training data will be pulled periodically while your device is on Wi-Fi + + Uploading disabled + + + + Training data wont be pulled periodically until you disable the 'Disable Uploading' toggle + + WifiUI diff --git a/selfdrive/ui/translations/main_en.qm b/selfdrive/ui/translations/main_en.qm new file mode 100644 index 0000000..dab9f0e Binary files /dev/null and b/selfdrive/ui/translations/main_en.qm differ diff --git a/selfdrive/ui/translations/main_fr.qm b/selfdrive/ui/translations/main_fr.qm new file mode 100644 index 0000000..065a72d Binary files /dev/null and b/selfdrive/ui/translations/main_fr.qm differ diff --git a/selfdrive/ui/translations/main_fr.ts b/selfdrive/ui/translations/main_fr.ts index cd96c46..531b8a9 100644 --- a/selfdrive/ui/translations/main_fr.ts +++ b/selfdrive/ui/translations/main_fr.ts @@ -15,6 +15,10 @@ Reboot and Update Redémarrer et mettre à jour + + Disable Internet Check + + AdvancedNetworking @@ -293,6 +297,117 @@ Disengage to Power Off Désengager pour éteindre + + Delete Driving Data + + + + DELETE + + + + This button provides a swift and secure way to permanently delete all stored driving footage and data from your device. Ideal for maintaining privacy or freeing up space. + + + + Are you sure you want to permanently delete all of your driving footage and data? + + + + Delete + + + + Delete Toggle Storage Data + + + + This button provides a swift and secure way to permanently delete all long term stored toggle settings. Ideal for maintaining privacy or freeing up space. + + + + Are you sure you want to permanently delete all of your long term toggle settings storage? + + + + Backup + + + + Restore + + + + Name your backup + + + + Select a backup to delete + + + + Are you sure you want to delete this backup? + + + + Select a restore point + + + + Are you sure you want to restore this version of FrogPilot? + + + + Are you sure you want to restore this toggle backup? + + + + Flash Panda + + + + FLASH + + + + Are you sure you want to flash the Panda? + + + + Flash + + + + + DriveStats + + Drives + + + + Hours + + + + ALL TIME + + + + PAST WEEK + + + + FROGPILOT + + + + KM + + + + Miles + + DriverViewWindow @@ -358,6 +473,10 @@ Manage at connect.comma.ai Gérer sur connect.comma.ai + + Manage at %1 + + MapWindow @@ -560,7 +679,7 @@ openpilot - openpilot + openpilot %n minute(s) ago @@ -599,6 +718,10 @@ ft ft + + FrogPilot + + Reset @@ -645,7 +768,7 @@ Cela peut prendre jusqu'à une minute. SettingsWindow × - × + × Device @@ -663,6 +786,26 @@ Cela peut prendre jusqu'à une minute. Software Logiciel + + ← Back + + + + Controls + + + + Navigation + + + + Vehicles + + + + Visuals + + Setup @@ -844,12 +987,16 @@ Cela peut prendre jusqu'à une minute. 5G 5G + + MEMORY + + SoftwarePanel Updates are only downloaded while the car is off. - Les MàJ sont téléchargées uniquement si la voiture est éteinte. + Les MàJ sont téléchargées uniquement si la voiture est éteinte. Current Version @@ -919,6 +1066,50 @@ Cela peut prendre jusqu'à une minute. up to date, last checked %1 à jour, dernière vérification %1 + + Updates are only downloaded while the car is off or in park. + + + + Manually + + + + Daily + + + + Weekly + + + + Update Scheduler + + + + Choose the frequency to automatically update FrogPilot. + +This feature will handle the download, installation, and device reboot for a seamless 'Set and Forget' update experience. + +Weekly updates start at midnight every Sunday. + + + + Update Time + + + + Select a time to automatically update + + + + Error Log + + + + VIEW + VOIR + SshControl @@ -1181,6 +1372,14 @@ Cela peut prendre jusqu'à une minute. Training data will be pulled periodically while your device is on Wi-Fi Les données d'entraînement seront envoyées périodiquement lorsque votre appareil est connecté au réseau Wi-Fi + + Uploading disabled + + + + Training data wont be pulled periodically until you disable the 'Disable Uploading' toggle + + WifiUI diff --git a/selfdrive/ui/translations/main_ja.qm b/selfdrive/ui/translations/main_ja.qm new file mode 100644 index 0000000..50c53e8 Binary files /dev/null and b/selfdrive/ui/translations/main_ja.qm differ diff --git a/selfdrive/ui/translations/main_ja.ts b/selfdrive/ui/translations/main_ja.ts index d07c7d5..65fabe9 100644 --- a/selfdrive/ui/translations/main_ja.ts +++ b/selfdrive/ui/translations/main_ja.ts @@ -15,6 +15,10 @@ Reboot and Update 再起動してアップデート + + Disable Internet Check + + AdvancedNetworking @@ -293,6 +297,117 @@ Review 確認 + + Delete Driving Data + + + + DELETE + + + + This button provides a swift and secure way to permanently delete all stored driving footage and data from your device. Ideal for maintaining privacy or freeing up space. + + + + Are you sure you want to permanently delete all of your driving footage and data? + + + + Delete + + + + Delete Toggle Storage Data + + + + This button provides a swift and secure way to permanently delete all long term stored toggle settings. Ideal for maintaining privacy or freeing up space. + + + + Are you sure you want to permanently delete all of your long term toggle settings storage? + + + + Backup + + + + Restore + + + + Name your backup + + + + Select a backup to delete + + + + Are you sure you want to delete this backup? + + + + Select a restore point + + + + Are you sure you want to restore this version of FrogPilot? + + + + Are you sure you want to restore this toggle backup? + + + + Flash Panda + + + + FLASH + + + + Are you sure you want to flash the Panda? + + + + Flash + + + + + DriveStats + + Drives + + + + Hours + + + + ALL TIME + + + + PAST WEEK + + + + FROGPILOT + + + + KM + + + + Miles + + DriverViewWindow @@ -357,6 +472,10 @@ Manage at connect.comma.ai + + Manage at %1 + + MapWindow @@ -558,7 +677,7 @@ openpilot - openpilot + openpilot %n minute(s) ago @@ -594,6 +713,10 @@ ft フィート + + FrogPilot + + Reset @@ -639,7 +762,7 @@ This may take up to a minute. SettingsWindow × - × + × Device @@ -657,6 +780,26 @@ This may take up to a minute. Software ソフトウェア + + ← Back + + + + Controls + + + + Navigation + + + + Vehicles + + + + Visuals + + Setup @@ -838,12 +981,16 @@ This may take up to a minute. 5G 5G + + MEMORY + + SoftwarePanel Updates are only downloaded while the car is off. - 車の電源がオフの間のみ、アップデートのダウンロードが行われます。 + 車の電源がオフの間のみ、アップデートのダウンロードが行われます。 Current Version @@ -913,6 +1060,50 @@ This may take up to a minute. never + + Updates are only downloaded while the car is off or in park. + + + + Manually + + + + Daily + + + + Weekly + + + + Update Scheduler + + + + Choose the frequency to automatically update FrogPilot. + +This feature will handle the download, installation, and device reboot for a seamless 'Set and Forget' update experience. + +Weekly updates start at midnight every Sunday. + + + + Update Time + + + + Select a time to automatically update + + + + Error Log + + + + VIEW + 見る + SshControl @@ -1175,6 +1366,14 @@ This may take up to a minute. Training data will be pulled periodically while your device is on Wi-Fi + + Uploading disabled + + + + Training data wont be pulled periodically until you disable the 'Disable Uploading' toggle + + WifiUI diff --git a/selfdrive/ui/translations/main_ko.qm b/selfdrive/ui/translations/main_ko.qm new file mode 100644 index 0000000..f51916c Binary files /dev/null and b/selfdrive/ui/translations/main_ko.qm differ diff --git a/selfdrive/ui/translations/main_ko.ts b/selfdrive/ui/translations/main_ko.ts index a903978..a1b178a 100644 --- a/selfdrive/ui/translations/main_ko.ts +++ b/selfdrive/ui/translations/main_ko.ts @@ -15,6 +15,10 @@ Reboot and Update 업데이트 및 재부팅 + + Disable Internet Check + + AdvancedNetworking @@ -293,6 +297,117 @@ Review 다시보기 + + Delete Driving Data + + + + DELETE + + + + This button provides a swift and secure way to permanently delete all stored driving footage and data from your device. Ideal for maintaining privacy or freeing up space. + + + + Are you sure you want to permanently delete all of your driving footage and data? + + + + Delete + + + + Delete Toggle Storage Data + + + + This button provides a swift and secure way to permanently delete all long term stored toggle settings. Ideal for maintaining privacy or freeing up space. + + + + Are you sure you want to permanently delete all of your long term toggle settings storage? + + + + Backup + + + + Restore + + + + Name your backup + + + + Select a backup to delete + + + + Are you sure you want to delete this backup? + + + + Select a restore point + + + + Are you sure you want to restore this version of FrogPilot? + + + + Are you sure you want to restore this toggle backup? + + + + Flash Panda + + + + FLASH + + + + Are you sure you want to flash the Panda? + + + + Flash + + + + + DriveStats + + Drives + + + + Hours + + + + ALL TIME + + + + PAST WEEK + + + + FROGPILOT + + + + KM + + + + Miles + + DriverViewWindow @@ -357,6 +472,10 @@ Manage at connect.comma.ai connect.comma.ai에서 관리하세요 + + Manage at %1 + + MapWindow @@ -559,7 +678,7 @@ openpilot - openpilot + openpilot %n minute(s) ago @@ -595,6 +714,10 @@ ft ft + + FrogPilot + + Reset @@ -641,7 +764,7 @@ This may take up to a minute. SettingsWindow × - × + × Device @@ -659,6 +782,26 @@ This may take up to a minute. Software 소프트웨어 + + ← Back + + + + Controls + + + + Navigation + + + + Vehicles + + + + Visuals + + Setup @@ -840,12 +983,16 @@ This may take up to a minute. 5G 5G + + MEMORY + + SoftwarePanel Updates are only downloaded while the car is off. - 업데이트는 차량 시동이 꺼졌을 때 다운로드됩니다. + 업데이트는 차량 시동이 꺼졌을 때 다운로드됩니다. Current Version @@ -915,6 +1062,50 @@ This may take up to a minute. never 업데이트 안함 + + Updates are only downloaded while the car is off or in park. + + + + Manually + + + + Daily + + + + Weekly + + + + Update Scheduler + + + + Choose the frequency to automatically update FrogPilot. + +This feature will handle the download, installation, and device reboot for a seamless 'Set and Forget' update experience. + +Weekly updates start at midnight every Sunday. + + + + Update Time + + + + Select a time to automatically update + + + + Error Log + + + + VIEW + 보기 + SshControl @@ -1177,6 +1368,14 @@ This may take up to a minute. Training data will be pulled periodically while your device is on Wi-Fi 기기가 Wi-Fi에 연결되어 있는 동안 트레이닝 데이터를 주기적으로 전송합니다 + + Uploading disabled + + + + Training data wont be pulled periodically until you disable the 'Disable Uploading' toggle + + WifiUI diff --git a/selfdrive/ui/translations/main_pt-BR.qm b/selfdrive/ui/translations/main_pt-BR.qm new file mode 100644 index 0000000..7dde67a Binary files /dev/null and b/selfdrive/ui/translations/main_pt-BR.qm differ diff --git a/selfdrive/ui/translations/main_pt-BR.ts b/selfdrive/ui/translations/main_pt-BR.ts index fce5a8a..d45133a 100644 --- a/selfdrive/ui/translations/main_pt-BR.ts +++ b/selfdrive/ui/translations/main_pt-BR.ts @@ -15,6 +15,10 @@ Reboot and Update Reiniciar e Atualizar + + Disable Internet Check + + AdvancedNetworking @@ -293,6 +297,117 @@ Review Revisar + + Delete Driving Data + + + + DELETE + + + + This button provides a swift and secure way to permanently delete all stored driving footage and data from your device. Ideal for maintaining privacy or freeing up space. + + + + Are you sure you want to permanently delete all of your driving footage and data? + + + + Delete + + + + Delete Toggle Storage Data + + + + This button provides a swift and secure way to permanently delete all long term stored toggle settings. Ideal for maintaining privacy or freeing up space. + + + + Are you sure you want to permanently delete all of your long term toggle settings storage? + + + + Backup + + + + Restore + + + + Name your backup + + + + Select a backup to delete + + + + Are you sure you want to delete this backup? + + + + Select a restore point + + + + Are you sure you want to restore this version of FrogPilot? + + + + Are you sure you want to restore this toggle backup? + + + + Flash Panda + + + + FLASH + + + + Are you sure you want to flash the Panda? + + + + Flash + + + + + DriveStats + + Drives + + + + Hours + + + + ALL TIME + + + + PAST WEEK + + + + FROGPILOT + + + + KM + + + + Miles + + DriverViewWindow @@ -358,6 +473,10 @@ Manage at connect.comma.ai Gerencie em connect.comma.ai + + Manage at %1 + + MapWindow @@ -560,7 +679,7 @@ openpilot - openpilot + openpilot %n minute(s) ago @@ -599,6 +718,10 @@ ft pés + + FrogPilot + + Reset @@ -645,7 +768,7 @@ Isso pode levar até um minuto. SettingsWindow × - × + × Device @@ -663,6 +786,26 @@ Isso pode levar até um minuto. Software Software + + ← Back + + + + Controls + + + + Navigation + + + + Vehicles + + + + Visuals + + Setup @@ -844,12 +987,16 @@ Isso pode levar até um minuto. 5G 5G + + MEMORY + + SoftwarePanel Updates are only downloaded while the car is off. - Atualizações baixadas durante o motor desligado. + Atualizações baixadas durante o motor desligado. Current Version @@ -919,6 +1066,50 @@ Isso pode levar até um minuto. never nunca + + Updates are only downloaded while the car is off or in park. + + + + Manually + + + + Daily + + + + Weekly + + + + Update Scheduler + + + + Choose the frequency to automatically update FrogPilot. + +This feature will handle the download, installation, and device reboot for a seamless 'Set and Forget' update experience. + +Weekly updates start at midnight every Sunday. + + + + Update Time + + + + Select a time to automatically update + + + + Error Log + + + + VIEW + VER + SshControl @@ -1181,6 +1372,14 @@ Isso pode levar até um minuto. Training data will be pulled periodically while your device is on Wi-Fi Os dados de treinamento serão extraídos periodicamente enquanto o dispositivo estiver no Wi-Fi + + Uploading disabled + + + + Training data wont be pulled periodically until you disable the 'Disable Uploading' toggle + + WifiUI diff --git a/selfdrive/ui/translations/main_th.qm b/selfdrive/ui/translations/main_th.qm new file mode 100644 index 0000000..29a4ad2 Binary files /dev/null and b/selfdrive/ui/translations/main_th.qm differ diff --git a/selfdrive/ui/translations/main_th.ts b/selfdrive/ui/translations/main_th.ts index f4d097b..8cd55f3 100644 --- a/selfdrive/ui/translations/main_th.ts +++ b/selfdrive/ui/translations/main_th.ts @@ -15,6 +15,10 @@ Reboot and Update รีบูตและอัปเดต + + Disable Internet Check + + AdvancedNetworking @@ -293,6 +297,117 @@ Review ทบทวน + + Delete Driving Data + + + + DELETE + + + + This button provides a swift and secure way to permanently delete all stored driving footage and data from your device. Ideal for maintaining privacy or freeing up space. + + + + Are you sure you want to permanently delete all of your driving footage and data? + + + + Delete + + + + Delete Toggle Storage Data + + + + This button provides a swift and secure way to permanently delete all long term stored toggle settings. Ideal for maintaining privacy or freeing up space. + + + + Are you sure you want to permanently delete all of your long term toggle settings storage? + + + + Backup + + + + Restore + + + + Name your backup + + + + Select a backup to delete + + + + Are you sure you want to delete this backup? + + + + Select a restore point + + + + Are you sure you want to restore this version of FrogPilot? + + + + Are you sure you want to restore this toggle backup? + + + + Flash Panda + + + + FLASH + + + + Are you sure you want to flash the Panda? + + + + Flash + + + + + DriveStats + + Drives + + + + Hours + + + + ALL TIME + + + + PAST WEEK + + + + FROGPILOT + + + + KM + + + + Miles + + DriverViewWindow @@ -357,6 +472,10 @@ Manage at connect.comma.ai จัดการได้ที่ connect.comma.ai + + Manage at %1 + + MapWindow @@ -559,7 +678,7 @@ openpilot - openpilot + openpilot %n minute(s) ago @@ -595,6 +714,10 @@ ft ฟุต + + FrogPilot + + Reset @@ -641,7 +764,7 @@ This may take up to a minute. SettingsWindow × - × + × Device @@ -659,6 +782,26 @@ This may take up to a minute. Software ซอฟต์แวร์ + + ← Back + + + + Controls + + + + Navigation + + + + Vehicles + + + + Visuals + + Setup @@ -840,6 +983,10 @@ This may take up to a minute. 5G 5G + + MEMORY + + SoftwarePanel @@ -861,7 +1008,7 @@ This may take up to a minute. Updates are only downloaded while the car is off. - ตัวอัปเดตจะดำเนินการดาวน์โหลดเมื่อรถดับเครื่องยนต์อยู่เท่านั้น + ตัวอัปเดตจะดำเนินการดาวน์โหลดเมื่อรถดับเครื่องยนต์อยู่เท่านั้น Current Version @@ -915,6 +1062,50 @@ This may take up to a minute. up to date, last checked %1 ล่าสุดแล้ว ตรวจสอบครั้งสุดท้ายเมื่อ %1 + + Updates are only downloaded while the car is off or in park. + + + + Manually + + + + Daily + + + + Weekly + + + + Update Scheduler + + + + Choose the frequency to automatically update FrogPilot. + +This feature will handle the download, installation, and device reboot for a seamless 'Set and Forget' update experience. + +Weekly updates start at midnight every Sunday. + + + + Update Time + + + + Select a time to automatically update + + + + Error Log + + + + VIEW + ดู + SshControl @@ -1177,6 +1368,14 @@ This may take up to a minute. Training data will be pulled periodically while your device is on Wi-Fi ข้อมูลการฝึกฝนจะถูกดึงเป็นระยะระหว่างที่อุปกรณ์ของคุณเชื่อมต่อกับ Wi-Fi + + Uploading disabled + + + + Training data wont be pulled periodically until you disable the 'Disable Uploading' toggle + + WifiUI diff --git a/selfdrive/ui/translations/main_tr.qm b/selfdrive/ui/translations/main_tr.qm new file mode 100644 index 0000000..b3629ee Binary files /dev/null and b/selfdrive/ui/translations/main_tr.qm differ diff --git a/selfdrive/ui/translations/main_tr.ts b/selfdrive/ui/translations/main_tr.ts index ec6f71f..2c957e0 100644 --- a/selfdrive/ui/translations/main_tr.ts +++ b/selfdrive/ui/translations/main_tr.ts @@ -15,6 +15,10 @@ Reboot and Update Güncelle ve Yeniden başlat + + Disable Internet Check + + AdvancedNetworking @@ -293,6 +297,117 @@ Review + + Delete Driving Data + + + + DELETE + + + + This button provides a swift and secure way to permanently delete all stored driving footage and data from your device. Ideal for maintaining privacy or freeing up space. + + + + Are you sure you want to permanently delete all of your driving footage and data? + + + + Delete + + + + Delete Toggle Storage Data + + + + This button provides a swift and secure way to permanently delete all long term stored toggle settings. Ideal for maintaining privacy or freeing up space. + + + + Are you sure you want to permanently delete all of your long term toggle settings storage? + + + + Backup + + + + Restore + + + + Name your backup + + + + Select a backup to delete + + + + Are you sure you want to delete this backup? + + + + Select a restore point + + + + Are you sure you want to restore this version of FrogPilot? + + + + Are you sure you want to restore this toggle backup? + + + + Flash Panda + + + + FLASH + + + + Are you sure you want to flash the Panda? + + + + Flash + + + + + DriveStats + + Drives + + + + Hours + + + + ALL TIME + + + + PAST WEEK + + + + FROGPILOT + + + + KM + + + + Miles + + DriverViewWindow @@ -357,6 +472,10 @@ Manage at connect.comma.ai + + Manage at %1 + + MapWindow @@ -558,7 +677,7 @@ openpilot - openpilot + openpilot %n minute(s) ago @@ -594,6 +713,10 @@ ft ft + + FrogPilot + + Reset @@ -639,7 +762,7 @@ This may take up to a minute. SettingsWindow × - x + x Device @@ -657,6 +780,26 @@ This may take up to a minute. Software Yazılım + + ← Back + + + + Controls + + + + Navigation + + + + Vehicles + + + + Visuals + + Setup @@ -838,6 +981,10 @@ This may take up to a minute. 5G 5G + + MEMORY + + SoftwarePanel @@ -857,10 +1004,6 @@ This may take up to a minute. CHECK KONTROL ET - - Updates are only downloaded while the car is off. - - Current Version @@ -913,6 +1056,50 @@ This may take up to a minute. up to date, last checked %1 + + Updates are only downloaded while the car is off or in park. + + + + Manually + + + + Daily + + + + Weekly + + + + Update Scheduler + + + + Choose the frequency to automatically update FrogPilot. + +This feature will handle the download, installation, and device reboot for a seamless 'Set and Forget' update experience. + +Weekly updates start at midnight every Sunday. + + + + Update Time + + + + Select a time to automatically update + + + + Error Log + + + + VIEW + BAK + SshControl @@ -1175,6 +1362,14 @@ This may take up to a minute. Training data will be pulled periodically while your device is on Wi-Fi + + Uploading disabled + + + + Training data wont be pulled periodically until you disable the 'Disable Uploading' toggle + + WifiUI diff --git a/selfdrive/ui/translations/main_zh-CHS.qm b/selfdrive/ui/translations/main_zh-CHS.qm new file mode 100644 index 0000000..2355145 Binary files /dev/null and b/selfdrive/ui/translations/main_zh-CHS.qm differ diff --git a/selfdrive/ui/translations/main_zh-CHS.ts b/selfdrive/ui/translations/main_zh-CHS.ts index 91f55c6..3fd0f7b 100644 --- a/selfdrive/ui/translations/main_zh-CHS.ts +++ b/selfdrive/ui/translations/main_zh-CHS.ts @@ -15,6 +15,10 @@ Reboot and Update 重启并更新 + + Disable Internet Check + + AdvancedNetworking @@ -293,6 +297,117 @@ Review 预览 + + Delete Driving Data + + + + DELETE + + + + This button provides a swift and secure way to permanently delete all stored driving footage and data from your device. Ideal for maintaining privacy or freeing up space. + + + + Are you sure you want to permanently delete all of your driving footage and data? + + + + Delete + + + + Delete Toggle Storage Data + + + + This button provides a swift and secure way to permanently delete all long term stored toggle settings. Ideal for maintaining privacy or freeing up space. + + + + Are you sure you want to permanently delete all of your long term toggle settings storage? + + + + Backup + + + + Restore + + + + Name your backup + + + + Select a backup to delete + + + + Are you sure you want to delete this backup? + + + + Select a restore point + + + + Are you sure you want to restore this version of FrogPilot? + + + + Are you sure you want to restore this toggle backup? + + + + Flash Panda + + + + FLASH + + + + Are you sure you want to flash the Panda? + + + + Flash + + + + + DriveStats + + Drives + + + + Hours + + + + ALL TIME + + + + PAST WEEK + + + + FROGPILOT + + + + KM + + + + Miles + + DriverViewWindow @@ -357,6 +472,10 @@ Manage at connect.comma.ai 请在 connect.comma.ai 上管理 + + Manage at %1 + + MapWindow @@ -559,7 +678,7 @@ openpilot - openpilot + openpilot %n minute(s) ago @@ -595,6 +714,10 @@ ft ft + + FrogPilot + + Reset @@ -641,7 +764,7 @@ This may take up to a minute. SettingsWindow × - × + × Device @@ -659,6 +782,26 @@ This may take up to a minute. Software 软件 + + ← Back + + + + Controls + + + + Navigation + + + + Vehicles + + + + Visuals + + Setup @@ -840,12 +983,16 @@ This may take up to a minute. 5G 5G + + MEMORY + + SoftwarePanel Updates are only downloaded while the car is off. - 车辆熄火时才能下载升级文件。 + 车辆熄火时才能下载升级文件。 Current Version @@ -915,6 +1062,50 @@ This may take up to a minute. never 从未更新 + + Updates are only downloaded while the car is off or in park. + + + + Manually + + + + Daily + + + + Weekly + + + + Update Scheduler + + + + Choose the frequency to automatically update FrogPilot. + +This feature will handle the download, installation, and device reboot for a seamless 'Set and Forget' update experience. + +Weekly updates start at midnight every Sunday. + + + + Update Time + + + + Select a time to automatically update + + + + Error Log + + + + VIEW + 查看 + SshControl @@ -1177,6 +1368,14 @@ This may take up to a minute. Training data will be pulled periodically while your device is on Wi-Fi 训练数据将定期通过 Wi-Fi 上载 + + Uploading disabled + + + + Training data wont be pulled periodically until you disable the 'Disable Uploading' toggle + + WifiUI diff --git a/selfdrive/ui/translations/main_zh-CHT.qm b/selfdrive/ui/translations/main_zh-CHT.qm new file mode 100644 index 0000000..6db3b36 Binary files /dev/null and b/selfdrive/ui/translations/main_zh-CHT.qm differ diff --git a/selfdrive/ui/translations/main_zh-CHT.ts b/selfdrive/ui/translations/main_zh-CHT.ts index e8c8854..56c447b 100644 --- a/selfdrive/ui/translations/main_zh-CHT.ts +++ b/selfdrive/ui/translations/main_zh-CHT.ts @@ -15,6 +15,10 @@ Reboot and Update 重啟並更新 + + Disable Internet Check + + AdvancedNetworking @@ -293,6 +297,117 @@ Review 回顧 + + Delete Driving Data + + + + DELETE + + + + This button provides a swift and secure way to permanently delete all stored driving footage and data from your device. Ideal for maintaining privacy or freeing up space. + + + + Are you sure you want to permanently delete all of your driving footage and data? + + + + Delete + + + + Delete Toggle Storage Data + + + + This button provides a swift and secure way to permanently delete all long term stored toggle settings. Ideal for maintaining privacy or freeing up space. + + + + Are you sure you want to permanently delete all of your long term toggle settings storage? + + + + Backup + + + + Restore + + + + Name your backup + + + + Select a backup to delete + + + + Are you sure you want to delete this backup? + + + + Select a restore point + + + + Are you sure you want to restore this version of FrogPilot? + + + + Are you sure you want to restore this toggle backup? + + + + Flash Panda + + + + FLASH + + + + Are you sure you want to flash the Panda? + + + + Flash + + + + + DriveStats + + Drives + + + + Hours + + + + ALL TIME + + + + PAST WEEK + + + + FROGPILOT + + + + KM + + + + Miles + + DriverViewWindow @@ -357,6 +472,10 @@ Manage at connect.comma.ai 請在 connect.comma.ai 上管理 + + Manage at %1 + + MapWindow @@ -559,7 +678,7 @@ openpilot - openpilot + openpilot %n minute(s) ago @@ -595,6 +714,10 @@ ft ft + + FrogPilot + + Reset @@ -641,7 +764,7 @@ This may take up to a minute. SettingsWindow × - × + × Device @@ -659,6 +782,26 @@ This may take up to a minute. Software 軟體 + + ← Back + + + + Controls + + + + Navigation + + + + Vehicles + + + + Visuals + + Setup @@ -840,12 +983,16 @@ This may take up to a minute. 5G 5G + + MEMORY + + SoftwarePanel Updates are only downloaded while the car is off. - 系統更新只會在熄火時下載。 + 系統更新只會在熄火時下載。 Current Version @@ -915,6 +1062,50 @@ This may take up to a minute. never 從未更新 + + Updates are only downloaded while the car is off or in park. + + + + Manually + + + + Daily + + + + Weekly + + + + Update Scheduler + + + + Choose the frequency to automatically update FrogPilot. + +This feature will handle the download, installation, and device reboot for a seamless 'Set and Forget' update experience. + +Weekly updates start at midnight every Sunday. + + + + Update Time + + + + Select a time to automatically update + + + + Error Log + + + + VIEW + 觀看 + SshControl @@ -1177,6 +1368,14 @@ This may take up to a minute. Training data will be pulled periodically while your device is on Wi-Fi 訓練數據將定期經過 Wi-Fi 上傳 + + Uploading disabled + + + + Training data wont be pulled periodically until you disable the 'Disable Uploading' toggle + + WifiUI diff --git a/selfdrive/ui/ui b/selfdrive/ui/ui new file mode 100755 index 0000000..514fd83 Binary files /dev/null and b/selfdrive/ui/ui differ diff --git a/selfdrive/ui/ui.cc b/selfdrive/ui/ui.cc deleted file mode 100644 index 6ad5ab9..0000000 --- a/selfdrive/ui/ui.cc +++ /dev/null @@ -1,601 +0,0 @@ -#include "selfdrive/ui/ui.h" - -#include -#include -#include - -#include - -#include "common/transformations/orientation.hpp" -#include "common/params.h" -#include "common/swaglog.h" -#include "common/util.h" -#include "common/watchdog.h" -#include "system/hardware/hw.h" -#define BACKLIGHT_DT 0.05 -#define BACKLIGHT_TS 10.00 - -// Projects a point in car to space to the corresponding point in full frame -// image space. -static bool calib_frame_to_full_frame(const UIState *s, float in_x, float in_y, float in_z, QPointF *out) { - const float margin = 500.0f; - const QRectF clip_region{-margin, -margin, s->fb_w + 2 * margin, s->fb_h + 2 * margin}; - - const vec3 pt = (vec3){{in_x, in_y, in_z}}; - const vec3 Ep = matvecmul3(s->scene.wide_cam ? s->scene.view_from_wide_calib : s->scene.view_from_calib, pt); - const vec3 KEp = matvecmul3(s->scene.wide_cam ? ECAM_INTRINSIC_MATRIX : FCAM_INTRINSIC_MATRIX, Ep); - - // Project. - QPointF point = s->car_space_transform.map(QPointF{KEp.v[0] / KEp.v[2], KEp.v[1] / KEp.v[2]}); - if (clip_region.contains(point)) { - *out = point; - return true; - } - return false; -} - -int get_path_length_idx(const cereal::XYZTData::Reader &line, const float path_height) { - const auto line_x = line.getX(); - int max_idx = 0; - for (int i = 1; i < line_x.size() && line_x[i] <= path_height; ++i) { - max_idx = i; - } - return max_idx; -} - -void update_leads(UIState *s, const cereal::RadarState::Reader &radar_state, const cereal::XYZTData::Reader &line) { - for (int i = 0; i < 2; ++i) { - auto lead_data = (i == 0) ? radar_state.getLeadOne() : radar_state.getLeadTwo(); - if (lead_data.getStatus()) { - float z = line.getZ()[get_path_length_idx(line, lead_data.getDRel())]; - calib_frame_to_full_frame(s, lead_data.getDRel(), -lead_data.getYRel(), z + 1.22, &s->scene.lead_vertices[i]); - } - } -} - -void update_line_data(const UIState *s, const cereal::XYZTData::Reader &line, - float y_off, float z_off, QPolygonF *pvd, int max_idx, bool allow_invert=true) { - const auto line_x = line.getX(), line_y = line.getY(), line_z = line.getZ(); - QPolygonF left_points, right_points; - left_points.reserve(max_idx + 1); - right_points.reserve(max_idx + 1); - - for (int i = 0; i <= max_idx; i++) { - // highly negative x positions are drawn above the frame and cause flickering, clip to zy plane of camera - if (line_x[i] < 0) continue; - QPointF left, right; - bool l = calib_frame_to_full_frame(s, line_x[i], line_y[i] - y_off, line_z[i] + z_off, &left); - bool r = calib_frame_to_full_frame(s, line_x[i], line_y[i] + y_off, line_z[i] + z_off, &right); - if (l && r) { - // For wider lines the drawn polygon will "invert" when going over a hill and cause artifacts - if (!allow_invert && left_points.size() && left.y() > left_points.back().y()) { - continue; - } - left_points.push_back(left); - right_points.push_front(right); - } - } - *pvd = left_points + right_points; -} - -void update_model(UIState *s, - const cereal::ModelDataV2::Reader &model, - const cereal::UiPlan::Reader &plan) { - UIScene &scene = s->scene; - auto plan_position = plan.getPosition(); - if (plan_position.getX().size() < model.getPosition().getX().size()) { - plan_position = model.getPosition(); - } - float max_distance = scene.unlimited_road_ui_length ? *(plan_position.getX().end() - 1) : - std::clamp(*(plan_position.getX().end() - 1), - MIN_DRAW_DISTANCE, MAX_DRAW_DISTANCE); - - // update lane lines - const auto lane_lines = model.getLaneLines(); - const auto lane_line_probs = model.getLaneLineProbs(); - int max_idx = get_path_length_idx(lane_lines[0], max_distance); - for (int i = 0; i < std::size(scene.lane_line_vertices); i++) { - scene.lane_line_probs[i] = lane_line_probs[i]; - update_line_data(s, lane_lines[i], scene.model_ui ? scene.lane_line_width * scene.lane_line_probs[i] : 0.025 * scene.lane_line_probs[i], 0, &scene.lane_line_vertices[i], max_idx); - } - - // update road edges - const auto road_edges = model.getRoadEdges(); - const auto road_edge_stds = model.getRoadEdgeStds(); - for (int i = 0; i < std::size(scene.road_edge_vertices); i++) { - scene.road_edge_stds[i] = road_edge_stds[i]; - update_line_data(s, road_edges[i], scene.model_ui ? scene.road_edge_width : 0.025, 0, &scene.road_edge_vertices[i], max_idx); - } - - // update path - float path; - - if (scene.dynamic_path_width) { - float multiplier = scene.enabled ? 1.0f : scene.always_on_lateral_active ? 0.75f : 0.50f; - path = scene.path_width * multiplier; - } else { - path = scene.path_width; - } - - auto lead_one = (*s->sm)["radarState"].getRadarState().getLeadOne(); - if (lead_one.getStatus()) { - const float lead_d = lead_one.getDRel() * 2.; - max_distance = std::clamp((float)(lead_d - fmin(lead_d * 0.35, 10.)), 0.0f, max_distance); - } - max_idx = get_path_length_idx(plan_position, max_distance); - update_line_data(s, plan_position, scene.model_ui ? path * (1 - scene.path_edge_width / 100) : 0.9, 1.22, &scene.track_vertices, max_idx, false); - - // Update path edges - update_line_data(s, plan_position, scene.model_ui ? path : 0, 1.22, &scene.track_edge_vertices, max_idx, false); - - // Update adjacent paths - for (int i = 4; i <= 5; i++) { - update_line_data(s, lane_lines[i], scene.blind_spot_path ? (i == 4 ? scene.lane_width_left : scene.lane_width_right) / 2.0f : 0, 0, &scene.track_adjacent_vertices[i], max_idx); - } -} - -void update_dmonitoring(UIState *s, const cereal::DriverStateV2::Reader &driverstate, float dm_fade_state, bool is_rhd) { - UIScene &scene = s->scene; - const auto driver_orient = is_rhd ? driverstate.getRightDriverData().getFaceOrientation() : driverstate.getLeftDriverData().getFaceOrientation(); - for (int i = 0; i < std::size(scene.driver_pose_vals); i++) { - float v_this = (i == 0 ? (driver_orient[i] < 0 ? 0.7 : 0.9) : 0.4) * driver_orient[i]; - scene.driver_pose_diff[i] = fabs(scene.driver_pose_vals[i] - v_this); - scene.driver_pose_vals[i] = 0.8 * v_this + (1 - 0.8) * scene.driver_pose_vals[i]; - scene.driver_pose_sins[i] = sinf(scene.driver_pose_vals[i]*(1.0-dm_fade_state)); - scene.driver_pose_coss[i] = cosf(scene.driver_pose_vals[i]*(1.0-dm_fade_state)); - } - - const mat3 r_xyz = (mat3){{ - scene.driver_pose_coss[1]*scene.driver_pose_coss[2], - scene.driver_pose_coss[1]*scene.driver_pose_sins[2], - -scene.driver_pose_sins[1], - - -scene.driver_pose_sins[0]*scene.driver_pose_sins[1]*scene.driver_pose_coss[2] - scene.driver_pose_coss[0]*scene.driver_pose_sins[2], - -scene.driver_pose_sins[0]*scene.driver_pose_sins[1]*scene.driver_pose_sins[2] + scene.driver_pose_coss[0]*scene.driver_pose_coss[2], - -scene.driver_pose_sins[0]*scene.driver_pose_coss[1], - - scene.driver_pose_coss[0]*scene.driver_pose_sins[1]*scene.driver_pose_coss[2] - scene.driver_pose_sins[0]*scene.driver_pose_sins[2], - scene.driver_pose_coss[0]*scene.driver_pose_sins[1]*scene.driver_pose_sins[2] + scene.driver_pose_sins[0]*scene.driver_pose_coss[2], - scene.driver_pose_coss[0]*scene.driver_pose_coss[1], - }}; - - // transform vertices - for (int kpi = 0; kpi < std::size(default_face_kpts_3d); kpi++) { - vec3 kpt_this = default_face_kpts_3d[kpi]; - kpt_this = matvecmul3(r_xyz, kpt_this); - scene.face_kpts_draw[kpi] = (vec3){{(float)kpt_this.v[0], (float)kpt_this.v[1], (float)(kpt_this.v[2] * (1.0-dm_fade_state) + 8 * dm_fade_state)}}; - } -} - -static void update_sockets(UIState *s) { - s->sm->update(0); -} - -static void update_state(UIState *s) { - SubMaster &sm = *(s->sm); - UIScene &scene = s->scene; - - if (sm.updated("liveCalibration")) { - auto live_calib = sm["liveCalibration"].getLiveCalibration(); - auto rpy_list = live_calib.getRpyCalib(); - auto wfde_list = live_calib.getWideFromDeviceEuler(); - Eigen::Vector3d rpy; - Eigen::Vector3d wfde; - if (rpy_list.size() == 3) rpy << rpy_list[0], rpy_list[1], rpy_list[2]; - if (wfde_list.size() == 3) wfde << wfde_list[0], wfde_list[1], wfde_list[2]; - Eigen::Matrix3d device_from_calib = euler2rot(rpy); - Eigen::Matrix3d wide_from_device = euler2rot(wfde); - Eigen::Matrix3d view_from_device; - view_from_device << 0, 1, 0, - 0, 0, 1, - 1, 0, 0; - Eigen::Matrix3d view_from_calib = view_from_device * device_from_calib; - Eigen::Matrix3d view_from_wide_calib = view_from_device * wide_from_device * device_from_calib; - for (int i = 0; i < 3; i++) { - for (int j = 0; j < 3; j++) { - scene.view_from_calib.v[i*3 + j] = view_from_calib(i, j); - scene.view_from_wide_calib.v[i*3 + j] = view_from_wide_calib(i, j); - } - } - scene.calibration_valid = live_calib.getCalStatus() == cereal::LiveCalibrationData::Status::CALIBRATED; - scene.calibration_wide_valid = wfde_list.size() == 3; - } - if (sm.updated("pandaStates")) { - auto pandaStates = sm["pandaStates"].getPandaStates(); - if (pandaStates.size() > 0) { - scene.pandaType = pandaStates[0].getPandaType(); - - if (scene.pandaType != cereal::PandaState::PandaType::UNKNOWN) { - scene.ignition = false; - for (const auto& pandaState : pandaStates) { - scene.ignition |= pandaState.getIgnitionLine() || pandaState.getIgnitionCan(); - } - } - } - } else if ((s->sm->frame - s->sm->rcv_frame("pandaStates")) > 5*UI_FREQ) { - scene.pandaType = cereal::PandaState::PandaType::UNKNOWN; - } - if (sm.updated("carParams")) { - scene.longitudinal_control = sm["carParams"].getCarParams().getOpenpilotLongitudinalControl(); - } - if (sm.updated("carState")) { - auto carState = sm["carState"].getCarState(); - if (scene.blind_spot_path || scene.custom_signals) { - scene.blind_spot_left = carState.getLeftBlindspot(); - scene.blind_spot_right = carState.getRightBlindspot(); - } - if (scene.custom_signals) { - scene.turn_signal_left = carState.getLeftBlinker(); - scene.turn_signal_right = carState.getRightBlinker(); - } - if (scene.driver_camera) { - scene.show_driver_camera = carState.getGearShifter() == cereal::CarState::GearShifter::REVERSE; - } - if (scene.lead_info || scene.pedals_on_ui) { - scene.acceleration = carState.getAEgo(); - } - if (scene.pedals_on_ui) { - scene.standstill = carState.getStandstill(); - } - if (scene.rotating_wheel) { - scene.steering_angle_deg = carState.getSteeringAngleDeg(); - } - scene.parked = carState.getGearShifter() == cereal::CarState::GearShifter::PARK; - } - if (sm.updated("controlsState")) { - auto controlsState = sm["controlsState"].getControlsState(); - scene.enabled = controlsState.getEnabled(); - scene.experimental_mode = controlsState.getExperimentalMode(); - } - if (sm.updated("driverMonitoringState")) { - auto driverMonitoringState = sm["driverMonitoringState"].getDriverMonitoringState(); - scene.right_hand_drive = driverMonitoringState.getIsRHD(); - } - if (sm.updated("frogpilotCarControl")) { - auto frogpilotCarControl = sm["frogpilotCarControl"].getFrogpilotCarControl(); - if (scene.always_on_lateral) { - scene.always_on_lateral_active = !scene.enabled && frogpilotCarControl.getAlwaysOnLateral(); - } - if (scene.speed_limit_controller) { - scene.speed_limit_changed = frogpilotCarControl.getSpeedLimitChanged(); - } - } - if (sm.updated("frogpilotPlan")) { - auto frogpilotPlan = sm["frogpilotPlan"].getFrogpilotPlan(); - if (scene.blind_spot_path) { - scene.lane_width_left = frogpilotPlan.getLaneWidthLeft(); - scene.lane_width_right = frogpilotPlan.getLaneWidthRight(); - } - if (scene.lead_info) { - scene.desired_follow = frogpilotPlan.getDesiredFollowDistance(); - scene.obstacle_distance = frogpilotPlan.getSafeObstacleDistance(); - scene.obstacle_distance_stock = frogpilotPlan.getSafeObstacleDistanceStock(); - scene.stopped_equivalence = frogpilotPlan.getStoppedEquivalenceFactor(); - } - if (scene.speed_limit_controller) { - scene.speed_limit = frogpilotPlan.getSlcSpeedLimit(); - scene.speed_limit_offset = frogpilotPlan.getSlcSpeedLimitOffset(); - scene.speed_limit_overridden = frogpilotPlan.getSlcOverridden(); - scene.speed_limit_overridden_speed = frogpilotPlan.getSlcOverriddenSpeed(); - scene.unconfirmed_speed_limit = frogpilotPlan.getUnconfirmedSlcSpeedLimit(); - } - scene.adjusted_cruise = frogpilotPlan.getAdjustedCruise(); - scene.vtsc_controlling_curve = frogpilotPlan.getVtscControllingCurve(); - } - if (sm.updated("liveLocationKalman")) { - auto liveLocationKalman = sm["liveLocationKalman"].getLiveLocationKalman(); - if (scene.compass) { - auto orientation = liveLocationKalman.getCalibratedOrientationNED(); - if (orientation.getValid()) { - scene.bearing_deg = RAD2DEG(orientation.getValue()[2]); - } - } - } - if (sm.updated("wideRoadCameraState")) { - auto cam_state = sm["wideRoadCameraState"].getWideRoadCameraState(); - float scale = (cam_state.getSensor() == cereal::FrameData::ImageSensor::AR0231) ? 6.0f : 1.0f; - scene.light_sensor = std::max(100.0f - scale * cam_state.getExposureValPercent(), 0.0f); - } - scene.started = sm["deviceState"].getDeviceState().getStarted() && scene.ignition; - - scene.world_objects_visible = scene.world_objects_visible || - (scene.started && - sm.rcv_frame("liveCalibration") > scene.started_frame && - sm.rcv_frame("modelV2") > scene.started_frame && - sm.rcv_frame("uiPlan") > scene.started_frame); -} - -void ui_update_params(UIState *s) { - auto params = Params(); - s->scene.is_metric = params.getBool("IsMetric"); - s->scene.map_on_left = params.getBool("NavSettingLeftSide"); -} - -void ui_update_frogpilot_params(UIState *s) { - ui_update_params(s); - - Params params = Params(); - UIScene &scene = s->scene; - - scene.always_on_lateral = params.getBool("AlwaysOnLateral"); - scene.hide_aol_status_bar = scene.always_on_lateral && params.getBool("HideAOLStatusBar"); - - scene.camera_view = params.getInt("CameraView"); - scene.compass = params.getBool("Compass"); - - scene.conditional_experimental = params.getBool("ConditionalExperimental"); - scene.conditional_speed = scene.conditional_experimental ? params.getInt("CESpeed") : 0; - scene.conditional_speed_lead = scene.conditional_experimental ? params.getInt("CESpeedLead") : 0; - scene.hide_cem_status_bar = scene.conditional_experimental && params.getBool("HideCEMStatusBar"); - - bool custom_onroad_ui = params.getBool("CustomUI"); - scene.acceleration_path = custom_onroad_ui && params.getBool("AccelerationPath"); - scene.adjacent_path = custom_onroad_ui && params.getBool("AdjacentPath"); - scene.adjacent_path_metrics = scene.adjacent_path && params.getBool("AdjacentPathMetrics"); - scene.blind_spot_path = custom_onroad_ui && params.getBool("BlindSpotPath"); - scene.fps_counter = custom_onroad_ui && params.getBool("FPSCounter"); - scene.lead_info = custom_onroad_ui && params.getBool("LeadInfo"); - scene.use_si = scene.lead_info && params.getBool("UseSI"); - scene.pedals_on_ui = custom_onroad_ui && params.getBool("PedalsOnUI"); - scene.road_name_ui = custom_onroad_ui && params.getBool("RoadNameUI"); - - bool custom_theme = params.getBool("CustomTheme"); - scene.custom_colors = custom_theme ? params.getInt("CustomColors") : 0; - scene.custom_icons = custom_theme ? params.getInt("CustomIcons") : 0; - scene.custom_signals = custom_theme ? params.getInt("CustomSignals") : 0; - scene.holiday_themes = custom_theme && params.getBool("HolidayThemes"); - - scene.disable_smoothing_mtsc = params.getBool("DisableMTSCSmoothing"); - scene.disable_smoothing_vtsc = params.getBool("DisableVTSCSmoothing"); - scene.driver_camera = params.getBool("DriverCamera"); - scene.experimental_mode_via_screen = params.getBool("ExperimentalModeViaScreen") && params.getBool("ExperimentalModeActivation"); - scene.fahrenheit = params.getBool("Fahrenheit"); - - bool longitudinal_tune = params.getBool("LongitudinalTune"); - scene.traffic_mode = longitudinal_tune && params.getBool("TrafficMode"); - - scene.model_ui = params.getBool("ModelUI"); - scene.dynamic_path_width = scene.model_ui && params.getBool("DynamicPathWidth"); - scene.hide_lead_marker = scene.model_ui && params.getBool("HideLeadMarker"); - scene.lane_line_width = params.getInt("LaneLinesWidth") * (scene.is_metric ? 1.0f : INCH_TO_CM) / 200.0f; - scene.path_edge_width = params.getInt("PathEdgeWidth"); - scene.path_width = params.getInt("PathWidth") / 10.0f * (scene.is_metric ? 1.0f : FOOT_TO_METER) / 2.0f; - scene.road_edge_width = params.getInt("RoadEdgesWidth") * (scene.is_metric ? 1.0f : INCH_TO_CM) / 200.0f; - scene.unlimited_road_ui_length = scene.model_ui && params.getBool("UnlimitedLength"); - - scene.numerical_temp = params.getBool("NumericalTemp"); - - bool quality_of_life_controls = params.getBool("QOLControls"); - scene.reverse_cruise = quality_of_life_controls && params.getBool("ReverseCruise"); - scene.reverse_cruise_ui = scene.reverse_cruise && params.getBool("ReverseCruiseUI"); - - bool quality_of_life_visuals = params.getBool("QOLVisuals"); - scene.full_map = quality_of_life_visuals && params.getBool("FullMap"); - scene.hide_speed = quality_of_life_visuals && params.getBool("HideSpeed"); - scene.hide_speed_ui = scene.hide_speed && params.getBool("HideSpeedUI"); - scene.map_style = quality_of_life_visuals ? params.getInt("MapStyle") : 0; - scene.wheel_speed = quality_of_life_visuals && params.getBool("WheelSpeed"); - - scene.personalities_via_screen = params.getBool("PersonalitiesViaScreen") && params.getBool("AdjustablePersonalities"); - scene.random_events = params.getBool("RandomEvents"); - scene.rotating_wheel = params.getBool("RotatingWheel"); - - bool screen_management = params.getBool("ScreenManagement"); - bool hide_ui_elements = screen_management && params.getBool("HideUIElements"); - scene.hide_alerts = hide_ui_elements && params.getBool("HideAlerts"); - scene.hide_map_icon = hide_ui_elements && params.getBool("HideMapIcon"); - scene.hide_max_speed = hide_ui_elements && params.getBool("HideMaxSpeed"); - scene.screen_brightness = screen_management ? params.getInt("ScreenBrightness") : 101; - scene.screen_brightness_onroad = screen_management ? params.getInt("ScreenBrightnessOnroad") : 101; - scene.screen_recorder = screen_management && params.getBool("ScreenRecorder"); - scene.screen_timeout = screen_management ? params.getInt("ScreenTimeout") : 30; - scene.screen_timeout_onroad = screen_management ? params.getInt("ScreenTimeoutOnroad") : 10; - scene.standby_mode = screen_management && params.getBool("StandbyMode"); - - scene.speed_limit_controller = params.getBool("SpeedLimitController"); - scene.show_slc_offset = scene.speed_limit_controller && params.getBool("ShowSLCOffset"); - scene.show_slc_offset_ui = scene.speed_limit_controller && params.getBool("ShowSLCOffsetUI"); - scene.use_vienna_slc_sign = scene.speed_limit_controller && params.getBool("UseVienna"); - - scene.wheel_icon = params.getInt("WheelIcon"); -} - -void UIState::updateStatus() { - if (scene.started && sm->updated("controlsState")) { - auto controls_state = (*sm)["controlsState"].getControlsState(); - auto state = controls_state.getState(); - if (state == cereal::ControlsState::OpenpilotState::PRE_ENABLED || state == cereal::ControlsState::OpenpilotState::OVERRIDING) { - status = STATUS_OVERRIDE; - } else if (scene.always_on_lateral_active) { - status = STATUS_ALWAYS_ON_LATERAL_ACTIVE; - } else if (scene.traffic_mode_active) { - status = STATUS_TRAFFIC_MODE_ACTIVE; - } else { - status = controls_state.getEnabled() ? STATUS_ENGAGED : STATUS_DISENGAGED; - } - - // Trigger standby mode on alerts and status changes - scene.active_alert = controls_state.getAlertStatus() != cereal::ControlsState::AlertStatus::NORMAL; - scene.status_changed = status != previous_status; - - previous_status = status; - } - - // Handle onroad/offroad transition - if (scene.started != started_prev || sm->frame == 1) { - if (scene.started) { - status = STATUS_DISENGAGED; - scene.started_frame = sm->frame; - } - started_prev = scene.started; - scene.world_objects_visible = false; - emit offroadTransition(!scene.started); - wifi->setTetheringEnabled(scene.started && scene.tethering_enabled); - } -} - -UIState::UIState(QObject *parent) : QObject(parent) { - sm = std::make_unique>({ - "modelV2", "controlsState", "liveCalibration", "radarState", "deviceState", - "pandaStates", "carParams", "driverMonitoringState", "carState", "liveLocationKalman", "driverStateV2", - "wideRoadCameraState", "managerState", "navInstruction", "navRoute", "uiPlan", - "frogpilotCarControl", "frogpilotDeviceState", "frogpilotPlan", - }); - - Params params; - language = QString::fromStdString(params.get("LanguageSetting")); - auto prime_value = params.get("PrimeType"); - if (!prime_value.empty()) { - prime_type = static_cast(std::atoi(prime_value.c_str())); - } - - // update timer - timer = new QTimer(this); - QObject::connect(timer, &QTimer::timeout, this, &UIState::update); - timer->start(1000 / UI_FREQ); - - wifi = new WifiManager(this); - - ui_update_frogpilot_params(this); -} - -void UIState::update() { - update_sockets(this); - update_state(this); - updateStatus(); - - if (sm->frame % UI_FREQ == 0) { - watchdog_kick(nanos_since_boot()); - } - emit uiUpdate(*this); - - // Update FrogPilot variables when they are changed - Params paramsMemory{"/dev/shm/params"}; - if (paramsMemory.getBool("FrogPilotTogglesUpdated")) { - std::thread updateFrogPilotParams(ui_update_frogpilot_params, this); - updateFrogPilotParams.detach(); - } - - // FrogPilot live variables that need to be constantly checked - scene.conditional_status = scene.conditional_experimental ? paramsMemory.getInt("CEStatus") : 0; - scene.current_holiday_theme = scene.holiday_themes ? paramsMemory.getInt("CurrentHolidayTheme") : 0; - scene.current_random_event = scene.random_events ? paramsMemory.getInt("CurrentRandomEvent") : 0; - scene.traffic_mode_active = scene.conditional_experimental && scene.enabled && paramsMemory.getBool("TrafficModeActive"); -} - -void UIState::setPrimeType(PrimeType type) { - if (type != prime_type) { - bool prev_prime = hasPrime(); - - prime_type = type; - Params().put("PrimeType", std::to_string(prime_type)); - emit primeTypeChanged(prime_type); - - bool prime = hasPrime(); - if (prev_prime != prime) { - emit primeChanged(prime); - } - } -} - -Device::Device(QObject *parent) : brightness_filter(BACKLIGHT_OFFROAD, BACKLIGHT_TS, BACKLIGHT_DT), QObject(parent) { - setAwake(true); - resetInteractiveTimeout(); - - QObject::connect(uiState(), &UIState::uiUpdate, this, &Device::update); -} - -void Device::update(const UIState &s) { - updateBrightness(s); - updateWakefulness(s); -} - -void Device::setAwake(bool on) { - if (on != awake) { - awake = on; - Hardware::set_display_power(awake); - LOGD("setting display power %d", awake); - emit displayPowerChanged(awake); - } -} - -void Device::resetInteractiveTimeout(int timeout, int timeout_onroad) { - if (timeout == -1) { - timeout = (ignition_on ? 10 : 30); - } else { - timeout = (ignition_on ? timeout_onroad : timeout); - } - interactive_timeout = timeout * UI_FREQ; -} - -void Device::updateBrightness(const UIState &s) { - float clipped_brightness = offroad_brightness; - if (s.scene.started) { - clipped_brightness = s.scene.light_sensor; - - // CIE 1931 - https://www.photonstophotos.net/GeneralTopics/Exposure/Psychometric_Lightness_and_Gamma.htm - if (clipped_brightness <= 8) { - clipped_brightness = (clipped_brightness / 903.3); - } else { - clipped_brightness = std::pow((clipped_brightness + 16.0) / 116.0, 3.0); - } - - // Scale back to 10% to 100% - clipped_brightness = std::clamp(100.0f * clipped_brightness, 10.0f, 100.0f); - } - - int brightness = brightness_filter.update(clipped_brightness); - if (!awake) { - brightness = 0; - } else if (s.scene.started && s.scene.screen_brightness_onroad != 101) { - // Bring the screen brightness up to 5% upon screen tap - brightness = interactive_timeout > 0 ? fmax(5, s.scene.screen_brightness_onroad) : s.scene.screen_brightness_onroad; - } else if (s.scene.screen_brightness != 101) { - brightness = fmax(5, s.scene.screen_brightness); - } - - if (brightness != last_brightness) { - if (!brightness_future.isRunning()) { - brightness_future = QtConcurrent::run(Hardware::set_brightness, brightness); - last_brightness = brightness; - } - } -} - -void Device::updateWakefulness(const UIState &s) { - bool ignition_state_changed = s.scene.ignition != ignition_on; - ignition_on = s.scene.ignition; - - if (ignition_on && s.scene.standby_mode) { - if (s.scene.active_alert || s.scene.speed_limit_changed || s.scene.status_changed) { - resetInteractiveTimeout(s.scene.screen_timeout, s.scene.screen_timeout_onroad); - } - } - - if (ignition_state_changed) { - // Instantly turn off the screen if the onroad brightness is set to 0% - if (ignition_on && s.scene.screen_brightness_onroad == 0 && !s.scene.standby_mode) { - resetInteractiveTimeout(0, 0); - } else { - resetInteractiveTimeout(s.scene.screen_timeout, s.scene.screen_timeout_onroad); - } - } else if (interactive_timeout > 0 && --interactive_timeout == 0) { - emit interactiveTimeout(); - } - - if (s.scene.screen_brightness_onroad != 0) { - setAwake(s.scene.ignition || interactive_timeout > 0); - } else { - setAwake(interactive_timeout > 0); - } -} - -UIState *uiState() { - static UIState ui_state; - return &ui_state; -} - -Device *device() { - static Device _device; - return &_device; -} diff --git a/selfdrive/ui/ui.h b/selfdrive/ui/ui.h deleted file mode 100644 index 8302854..0000000 --- a/selfdrive/ui/ui.h +++ /dev/null @@ -1,378 +0,0 @@ -#pragma once - -#include -#include -#include - -#include -#include -#include -#include -#include -#include - -#include "cereal/messaging/messaging.h" -#include "common/mat.h" -#include "common/params.h" -#include "common/timing.h" -#include "selfdrive/ui/qt/network/wifi_manager.h" -#include "system/hardware/hw.h" - -const int UI_BORDER_SIZE = 30; -const int UI_HEADER_HEIGHT = 420; - -const int UI_FREQ = 20; // Hz -const int BACKLIGHT_OFFROAD = 50; -typedef cereal::CarControl::HUDControl::AudibleAlert AudibleAlert; - -const float MIN_DRAW_DISTANCE = 10.0; -const float MAX_DRAW_DISTANCE = 100.0; -constexpr mat3 DEFAULT_CALIBRATION = {{ 0.0, 1.0, 0.0, 0.0, 0.0, 1.0, 1.0, 0.0, 0.0 }}; -constexpr mat3 FCAM_INTRINSIC_MATRIX = (mat3){{2648.0, 0.0, 1928.0 / 2, - 0.0, 2648.0, 1208.0 / 2, - 0.0, 0.0, 1.0}}; -// tici ecam focal probably wrong? magnification is not consistent across frame -// Need to retrain model before this can be changed -constexpr mat3 ECAM_INTRINSIC_MATRIX = (mat3){{567.0, 0.0, 1928.0 / 2, - 0.0, 567.0, 1208.0 / 2, - 0.0, 0.0, 1.0}}; - - -constexpr vec3 default_face_kpts_3d[] = { - {-5.98, -51.20, 8.00}, {-17.64, -49.14, 8.00}, {-23.81, -46.40, 8.00}, {-29.98, -40.91, 8.00}, {-32.04, -37.49, 8.00}, - {-34.10, -32.00, 8.00}, {-36.16, -21.03, 8.00}, {-36.16, 6.40, 8.00}, {-35.47, 10.51, 8.00}, {-32.73, 19.43, 8.00}, - {-29.30, 26.29, 8.00}, {-24.50, 33.83, 8.00}, {-19.01, 41.37, 8.00}, {-14.21, 46.17, 8.00}, {-12.16, 47.54, 8.00}, - {-4.61, 49.60, 8.00}, {4.99, 49.60, 8.00}, {12.53, 47.54, 8.00}, {14.59, 46.17, 8.00}, {19.39, 41.37, 8.00}, - {24.87, 33.83, 8.00}, {29.67, 26.29, 8.00}, {33.10, 19.43, 8.00}, {35.84, 10.51, 8.00}, {36.53, 6.40, 8.00}, - {36.53, -21.03, 8.00}, {34.47, -32.00, 8.00}, {32.42, -37.49, 8.00}, {30.36, -40.91, 8.00}, {24.19, -46.40, 8.00}, - {18.02, -49.14, 8.00}, {6.36, -51.20, 8.00}, {-5.98, -51.20, 8.00}, -}; - -struct Alert { - QString text1; - QString text2; - QString type; - cereal::ControlsState::AlertSize size; - cereal::ControlsState::AlertStatus status; - AudibleAlert sound; - - bool equal(const Alert &a2) { - return text1 == a2.text1 && text2 == a2.text2 && type == a2.type && sound == a2.sound; - } - - static Alert get(const SubMaster &sm, uint64_t started_frame) { - const cereal::ControlsState::Reader &cs = sm["controlsState"].getControlsState(); - const uint64_t controls_frame = sm.rcv_frame("controlsState"); - - Alert alert = {}; - if (controls_frame >= started_frame) { // Don't get old alert. - alert = {cs.getAlertText1().cStr(), cs.getAlertText2().cStr(), - cs.getAlertType().cStr(), cs.getAlertSize(), - cs.getAlertStatus(), - cs.getAlertSound()}; - } - - if (!sm.updated("controlsState") && (sm.frame - started_frame) > 5 * UI_FREQ) { - const int CONTROLS_TIMEOUT = 5; - const int controls_missing = (nanos_since_boot() - sm.rcv_time("controlsState")) / 1e9; - - // Handle controls timeout - if (std::ifstream("/data/community/crashes/error.txt")) { - alert = {"openpilot crashed", "Please post the error log in the FrogPilot Discord!", - "controlsWaiting", cereal::ControlsState::AlertSize::MID, - cereal::ControlsState::AlertStatus::NORMAL, - Params().getBool("RandomEvents") ? AudibleAlert::FART : AudibleAlert::NONE}; - } else if (controls_frame < started_frame) { - // car is started, but controlsState hasn't been seen at all - alert = {"openpilot Unavailable", "Waiting for controls to start", - "controlsWaiting", cereal::ControlsState::AlertSize::MID, - cereal::ControlsState::AlertStatus::NORMAL, - AudibleAlert::NONE}; - } else if (controls_missing > CONTROLS_TIMEOUT && !Hardware::PC()) { - // car is started, but controls is lagging or died - if (cs.getEnabled() && (controls_missing - CONTROLS_TIMEOUT) < 10) { - alert = {"TAKE CONTROL IMMEDIATELY", "Controls Unresponsive", - "controlsUnresponsive", cereal::ControlsState::AlertSize::FULL, - cereal::ControlsState::AlertStatus::CRITICAL, - AudibleAlert::WARNING_IMMEDIATE}; - } else { - alert = {"Controls Unresponsive", "Reboot Device", - "controlsUnresponsivePermanent", cereal::ControlsState::AlertSize::MID, - cereal::ControlsState::AlertStatus::NORMAL, - AudibleAlert::NONE}; - } - } - } - return alert; - } -}; - -typedef enum UIStatus { - STATUS_DISENGAGED, - STATUS_OVERRIDE, - STATUS_ENGAGED, - - // FrogPilot statuses - STATUS_ALWAYS_ON_LATERAL_ACTIVE, - STATUS_TRAFFIC_MODE_ACTIVE, -} UIStatus; - -enum PrimeType { - UNKNOWN = -1, - NONE = 0, - MAGENTA = 1, - LITE = 2, - BLUE = 3, - MAGENTA_NEW = 4, - PURPLE = 5, -}; - -const QColor bg_colors [] = { - [STATUS_DISENGAGED] = QColor(0x17, 0x33, 0x49, 0xc8), - [STATUS_OVERRIDE] = QColor(0x91, 0x9b, 0x95, 0xf1), - [STATUS_ENGAGED] = QColor(0x17, 0x86, 0x44, 0xf1), - - // FrogPilot colors - [STATUS_ALWAYS_ON_LATERAL_ACTIVE] = QColor(0x0a, 0xba, 0xb5, 0xf1), - [STATUS_TRAFFIC_MODE_ACTIVE] = QColor(0xc9, 0x22, 0x31, 0xf1), -}; - -static std::map alert_colors = { - {cereal::ControlsState::AlertStatus::NORMAL, QColor(0x15, 0x15, 0x15, 0xf1)}, - {cereal::ControlsState::AlertStatus::USER_PROMPT, QColor(0xDA, 0x6F, 0x25, 0xf1)}, - {cereal::ControlsState::AlertStatus::CRITICAL, QColor(0xC9, 0x22, 0x31, 0xf1)}, - {cereal::ControlsState::AlertStatus::FROGPILOT, QColor(0x17, 0x86, 0x44, 0xf1)}, -}; - -typedef struct UIScene { - bool calibration_valid = false; - bool calibration_wide_valid = false; - bool wide_cam = true; - mat3 view_from_calib = DEFAULT_CALIBRATION; - mat3 view_from_wide_calib = DEFAULT_CALIBRATION; - cereal::PandaState::PandaType pandaType; - - // modelV2 - float lane_line_probs[4]; - float road_edge_stds[2]; - QPolygonF track_vertices; - QPolygonF lane_line_vertices[4]; - QPolygonF road_edge_vertices[2]; - - // lead - QPointF lead_vertices[2]; - - // DMoji state - float driver_pose_vals[3]; - float driver_pose_diff[3]; - float driver_pose_sins[3]; - float driver_pose_coss[3]; - vec3 face_kpts_draw[std::size(default_face_kpts_3d)]; - - bool navigate_on_openpilot = false; - - float light_sensor; - bool started, ignition, is_metric, map_on_left, longitudinal_control; - bool world_objects_visible = false; - uint64_t started_frame; - - // FrogPilot variables - bool acceleration_path; - bool active_alert; - bool adjacent_path; - bool adjacent_path_metrics; - bool always_on_lateral; - bool always_on_lateral_active; - bool blind_spot_left; - bool blind_spot_path; - bool blind_spot_right; - bool compass; - bool conditional_experimental; - bool disable_smoothing_mtsc; - bool disable_smoothing_vtsc; - bool driver_camera; - bool dynamic_path_width; - bool enabled; - bool experimental_mode; - bool experimental_mode_via_screen; - bool fahrenheit; - bool fps_counter; - bool full_map; - bool hide_alerts; - bool hide_aol_status_bar; - bool hide_cem_status_bar; - bool hide_lead_marker; - bool hide_map_icon; - bool hide_max_speed; - bool hide_speed; - bool hide_speed_ui; - bool holiday_themes; - bool lead_info; - bool map_open; - bool model_ui; - bool numerical_temp; - bool parked; - bool pedals_on_ui; - bool personalities_via_screen; - bool random_events; - bool reverse_cruise; - bool reverse_cruise_ui; - bool right_hand_drive; - bool road_name_ui; - bool rotating_wheel; - bool screen_recorder; - bool show_driver_camera; - bool show_slc_offset; - bool show_slc_offset_ui; - bool speed_limit_changed; - bool speed_limit_controller; - bool speed_limit_overridden; - bool standby_mode; - bool standstill; - bool status_changed; - bool tethering_enabled; - bool traffic_mode; - bool traffic_mode_active; - bool turn_signal_left; - bool turn_signal_right; - bool unlimited_road_ui_length; - bool use_si; - bool use_vienna_slc_sign; - bool vtsc_controlling_curve; - bool wheel_speed; - - float acceleration; - float adjusted_cruise; - float lane_line_width; - float lane_width_left; - float lane_width_right; - float path_edge_width; - float path_width; - float road_edge_width; - float speed_limit; - float speed_limit_offset; - float speed_limit_overridden_speed; - float unconfirmed_speed_limit; - - int bearing_deg; - int camera_view; - int conditional_speed; - int conditional_speed_lead; - int conditional_status; - int current_holiday_theme; - int current_random_event; - int custom_colors; - int custom_icons; - int custom_signals; - int desired_follow; - int map_style; - int obstacle_distance; - int obstacle_distance_stock; - int screen_brightness; - int screen_brightness_onroad; - int screen_timeout; - int screen_timeout_onroad; - int steering_angle_deg; - int stopped_equivalence; - int wheel_icon; - - QPolygonF track_adjacent_vertices[6]; - QPolygonF track_edge_vertices; - -} UIScene; - -class UIState : public QObject { - Q_OBJECT - -public: - UIState(QObject* parent = 0); - void updateStatus(); - inline bool engaged() const { - return scene.started && (*sm)["controlsState"].getControlsState().getEnabled(); - } - - void setPrimeType(PrimeType type); - inline PrimeType primeType() const { return prime_type; } - inline bool hasPrime() const { return prime_type != PrimeType::UNKNOWN && prime_type != PrimeType::NONE; } - - int fb_w = 0, fb_h = 0; - - std::unique_ptr sm; - - UIStatus status; - UIScene scene = {}; - - QString language; - - QTransform car_space_transform; - - // FrogPilot variables - WifiManager *wifi = nullptr; - - UIStatus previous_status; - -signals: - void uiUpdate(const UIState &s); - void offroadTransition(bool offroad); - void primeChanged(bool prime); - void primeTypeChanged(PrimeType prime_type); - -private slots: - void update(); - -private: - QTimer *timer; - bool started_prev = false; - PrimeType prime_type = PrimeType::UNKNOWN; -}; - -UIState *uiState(); - -// device management class -class Device : public QObject { - Q_OBJECT - -public: - Device(QObject *parent = 0); - bool isAwake() { return awake; } - void setOffroadBrightness(int brightness) { - offroad_brightness = std::clamp(brightness, 0, 100); - } - -private: - bool awake = false; - int interactive_timeout = 0; - bool ignition_on = false; - - int offroad_brightness = BACKLIGHT_OFFROAD; - int last_brightness = 0; - FirstOrderFilter brightness_filter; - QFuture brightness_future; - - void updateBrightness(const UIState &s); - void updateWakefulness(const UIState &s); - void setAwake(bool on); - -signals: - void displayPowerChanged(bool on); - void interactiveTimeout(); - -public slots: - void resetInteractiveTimeout(int timeout = -1, int timeout_onroad = -1); - void update(const UIState &s); -}; - -Device *device(); - -void ui_update_params(UIState *s); -int get_path_length_idx(const cereal::XYZTData::Reader &line, const float path_height); -void update_model(UIState *s, - const cereal::ModelDataV2::Reader &model, - const cereal::UiPlan::Reader &plan); -void update_dmonitoring(UIState *s, const cereal::DriverStateV2::Reader &driverstate, float dm_fade_state, bool is_rhd); -void update_leads(UIState *s, const cereal::RadarState::Reader &radar_state, const cereal::XYZTData::Reader &line); -void update_line_data(const UIState *s, const cereal::XYZTData::Reader &line, - float y_off, float z_off, QPolygonF *pvd, int max_idx, bool allow_invert); - -// FrogPilot functions -void ui_update_frogpilot_params(UIState *s); diff --git a/selfdrive/ui/watch3.cc b/selfdrive/ui/watch3.cc deleted file mode 100644 index ec35c29..0000000 --- a/selfdrive/ui/watch3.cc +++ /dev/null @@ -1,34 +0,0 @@ -#include -#include - -#include "selfdrive/ui/qt/qt_window.h" -#include "selfdrive/ui/qt/util.h" -#include "selfdrive/ui/qt/widgets/cameraview.h" - -int main(int argc, char *argv[]) { - initApp(argc, argv); - - QApplication a(argc, argv); - QWidget w; - setMainWindow(&w); - - QVBoxLayout *layout = new QVBoxLayout(&w); - layout->setMargin(0); - layout->setSpacing(0); - - { - QHBoxLayout *hlayout = new QHBoxLayout(); - layout->addLayout(hlayout); - hlayout->addWidget(new CameraWidget("navd", VISION_STREAM_MAP, false)); - hlayout->addWidget(new CameraWidget("camerad", VISION_STREAM_ROAD, false)); - } - - { - QHBoxLayout *hlayout = new QHBoxLayout(); - layout->addLayout(hlayout); - hlayout->addWidget(new CameraWidget("camerad", VISION_STREAM_DRIVER, false)); - hlayout->addWidget(new CameraWidget("camerad", VISION_STREAM_WIDE_ROAD, false)); - } - - return a.exec(); -} diff --git a/system/camerad/SConscript b/system/camerad/SConscript deleted file mode 100644 index 8f19e7e..0000000 --- a/system/camerad/SConscript +++ /dev/null @@ -1,10 +0,0 @@ -Import('env', 'arch', 'cereal', 'messaging', 'common', 'gpucommon', 'visionipc') - -libs = ['m', 'pthread', common, 'jpeg', 'OpenCL', 'yuv', cereal, messaging, 'zmq', 'capnp', 'kj', visionipc, gpucommon, 'atomic'] - -camera_obj = env.Object(['cameras/camera_qcom2.cc', 'cameras/camera_common.cc', 'cameras/camera_util.cc', - 'sensors/ar0231.cc', 'sensors/ox03c10.cc', 'sensors/os04c10.cc']) -env.Program('camerad', ['main.cc', camera_obj], LIBS=libs) - -if GetOption("extras") and arch == "x86_64": - env.Program('test/test_ae_gray', ['test/test_ae_gray.cc', camera_obj], LIBS=libs) diff --git a/system/camerad/camerad b/system/camerad/camerad new file mode 100755 index 0000000..b89994d Binary files /dev/null and b/system/camerad/camerad differ diff --git a/system/camerad/cameras/camera_common.cc b/system/camerad/cameras/camera_common.cc deleted file mode 100644 index 91c6d44..0000000 --- a/system/camerad/cameras/camera_common.cc +++ /dev/null @@ -1,347 +0,0 @@ -#include "system/camerad/cameras/camera_common.h" - -#include -#include - -#include "third_party/libyuv/include/libyuv.h" -#include - -#include "common/clutil.h" -#include "common/swaglog.h" -#include "common/util.h" -#include "third_party/linux/include/msm_media_info.h" - -#include "system/camerad/cameras/camera_qcom2.h" -#ifdef QCOM2 -#include "CL/cl_ext_qcom.h" -#endif - -ExitHandler do_exit; - -class Debayer { -public: - Debayer(cl_device_id device_id, cl_context context, const CameraBuf *b, const CameraState *s, int buf_width, int uv_offset) { - char args[4096]; - const SensorInfo *ci = s->ci.get(); - snprintf(args, sizeof(args), - "-cl-fast-relaxed-math -cl-denorms-are-zero " - "-DFRAME_WIDTH=%d -DFRAME_HEIGHT=%d -DFRAME_STRIDE=%d -DFRAME_OFFSET=%d " - "-DRGB_WIDTH=%d -DRGB_HEIGHT=%d -DYUV_STRIDE=%d -DUV_OFFSET=%d " - "-DIS_OX=%d -DCAM_NUM=%d%s", - ci->frame_width, ci->frame_height, ci->frame_stride, ci->frame_offset, - b->rgb_width, b->rgb_height, buf_width, uv_offset, - ci->image_sensor == cereal::FrameData::ImageSensor::OX03C10, s->camera_num, s->camera_num==1 ? " -DVIGNETTING" : ""); - const char *cl_file = "cameras/real_debayer.cl"; - cl_program prg_debayer = cl_program_from_file(context, device_id, cl_file, args); - krnl_ = CL_CHECK_ERR(clCreateKernel(prg_debayer, "debayer10", &err)); - CL_CHECK(clReleaseProgram(prg_debayer)); - } - - void queue(cl_command_queue q, cl_mem cam_buf_cl, cl_mem buf_cl, int width, int height, cl_event *debayer_event) { - CL_CHECK(clSetKernelArg(krnl_, 0, sizeof(cl_mem), &cam_buf_cl)); - CL_CHECK(clSetKernelArg(krnl_, 1, sizeof(cl_mem), &buf_cl)); - - const size_t globalWorkSize[] = {size_t(width / 2), size_t(height / 2)}; - const int debayer_local_worksize = 16; - const size_t localWorkSize[] = {debayer_local_worksize, debayer_local_worksize}; - CL_CHECK(clEnqueueNDRangeKernel(q, krnl_, 2, NULL, globalWorkSize, localWorkSize, 0, 0, debayer_event)); - } - - ~Debayer() { - CL_CHECK(clReleaseKernel(krnl_)); - } - -private: - cl_kernel krnl_; -}; - -void CameraBuf::init(cl_device_id device_id, cl_context context, CameraState *s, VisionIpcServer * v, int frame_cnt, VisionStreamType type) { - vipc_server = v; - stream_type = type; - frame_buf_count = frame_cnt; - - const SensorInfo *ci = s->ci.get(); - // RAW frame - const int frame_size = (ci->frame_height + ci->extra_height) * ci->frame_stride; - camera_bufs = std::make_unique(frame_buf_count); - camera_bufs_metadata = std::make_unique(frame_buf_count); - - for (int i = 0; i < frame_buf_count; i++) { - camera_bufs[i].allocate(frame_size); - camera_bufs[i].init_cl(device_id, context); - } - LOGD("allocated %d CL buffers", frame_buf_count); - - rgb_width = ci->frame_width; - rgb_height = ci->frame_height; - - int nv12_width = VENUS_Y_STRIDE(COLOR_FMT_NV12, rgb_width); - int nv12_height = VENUS_Y_SCANLINES(COLOR_FMT_NV12, rgb_height); - assert(nv12_width == VENUS_UV_STRIDE(COLOR_FMT_NV12, rgb_width)); - assert(nv12_height/2 == VENUS_UV_SCANLINES(COLOR_FMT_NV12, rgb_height)); - size_t nv12_size = 2346 * nv12_width; // comes from v4l2_format.fmt.pix_mp.plane_fmt[0].sizeimage - size_t nv12_uv_offset = nv12_width * nv12_height; - vipc_server->create_buffers_with_sizes(stream_type, YUV_BUFFER_COUNT, false, rgb_width, rgb_height, nv12_size, nv12_width, nv12_uv_offset); - LOGD("created %d YUV vipc buffers with size %dx%d", YUV_BUFFER_COUNT, nv12_width, nv12_height); - - debayer = new Debayer(device_id, context, this, s, nv12_width, nv12_uv_offset); - - const cl_queue_properties props[] = {0}; //CL_QUEUE_PRIORITY_KHR, CL_QUEUE_PRIORITY_HIGH_KHR, 0}; - q = CL_CHECK_ERR(clCreateCommandQueueWithProperties(context, device_id, props, &err)); -} - -CameraBuf::~CameraBuf() { - for (int i = 0; i < frame_buf_count; i++) { - camera_bufs[i].free(); - } - if (debayer) delete debayer; - if (q) CL_CHECK(clReleaseCommandQueue(q)); -} - -bool CameraBuf::acquire() { - if (!safe_queue.try_pop(cur_buf_idx, 50)) return false; - - if (camera_bufs_metadata[cur_buf_idx].frame_id == -1) { - LOGE("no frame data? wtf"); - return false; - } - - cur_frame_data = camera_bufs_metadata[cur_buf_idx]; - cur_yuv_buf = vipc_server->get_buffer(stream_type); - cur_camera_buf = &camera_bufs[cur_buf_idx]; - - double start_time = millis_since_boot(); - cl_event event; - debayer->queue(q, camera_bufs[cur_buf_idx].buf_cl, cur_yuv_buf->buf_cl, rgb_width, rgb_height, &event); - clWaitForEvents(1, &event); - CL_CHECK(clReleaseEvent(event)); - cur_frame_data.processing_time = (millis_since_boot() - start_time) / 1000.0; - - VisionIpcBufExtra extra = { - cur_frame_data.frame_id, - cur_frame_data.timestamp_sof, - cur_frame_data.timestamp_eof, - }; - cur_yuv_buf->set_frame_id(cur_frame_data.frame_id); - vipc_server->send(cur_yuv_buf, &extra); - - return true; -} - -void CameraBuf::queue(size_t buf_idx) { - safe_queue.push(buf_idx); -} - -// common functions - -void fill_frame_data(cereal::FrameData::Builder &framed, const FrameMetadata &frame_data, CameraState *c) { - framed.setFrameId(frame_data.frame_id); - framed.setRequestId(frame_data.request_id); - framed.setTimestampEof(frame_data.timestamp_eof); - framed.setTimestampSof(frame_data.timestamp_sof); - framed.setIntegLines(frame_data.integ_lines); - framed.setGain(frame_data.gain); - framed.setHighConversionGain(frame_data.high_conversion_gain); - framed.setMeasuredGreyFraction(frame_data.measured_grey_fraction); - framed.setTargetGreyFraction(frame_data.target_grey_fraction); - framed.setProcessingTime(frame_data.processing_time); - - const float ev = c->cur_ev[frame_data.frame_id % 3]; - const float perc = util::map_val(ev, c->ci->min_ev, c->ci->max_ev, 0.0f, 100.0f); - framed.setExposureValPercent(perc); - framed.setSensor(c->ci->image_sensor); -} - -kj::Array get_raw_frame_image(const CameraBuf *b) { - const uint8_t *dat = (const uint8_t *)b->cur_camera_buf->addr; - - kj::Array frame_image = kj::heapArray(b->cur_camera_buf->len); - uint8_t *resized_dat = frame_image.begin(); - - memcpy(resized_dat, dat, b->cur_camera_buf->len); - - return kj::mv(frame_image); -} - -static kj::Array yuv420_to_jpeg(const CameraBuf *b, int thumbnail_width, int thumbnail_height) { - int downscale = b->cur_yuv_buf->width / thumbnail_width; - assert(downscale * thumbnail_height == b->cur_yuv_buf->height); - int in_stride = b->cur_yuv_buf->stride; - - // make the buffer big enough. jpeg_write_raw_data requires 16-pixels aligned height to be used. - std::unique_ptr buf(new uint8_t[(thumbnail_width * ((thumbnail_height + 15) & ~15) * 3) / 2]); - uint8_t *y_plane = buf.get(); - uint8_t *u_plane = y_plane + thumbnail_width * thumbnail_height; - uint8_t *v_plane = u_plane + (thumbnail_width * thumbnail_height) / 4; - { - // subsampled conversion from nv12 to yuv - for (int hy = 0; hy < thumbnail_height/2; hy++) { - for (int hx = 0; hx < thumbnail_width/2; hx++) { - int ix = hx * downscale + (downscale-1)/2; - int iy = hy * downscale + (downscale-1)/2; - y_plane[(hy*2 + 0)*thumbnail_width + (hx*2 + 0)] = b->cur_yuv_buf->y[(iy*2 + 0) * in_stride + ix*2 + 0]; - y_plane[(hy*2 + 0)*thumbnail_width + (hx*2 + 1)] = b->cur_yuv_buf->y[(iy*2 + 0) * in_stride + ix*2 + 1]; - y_plane[(hy*2 + 1)*thumbnail_width + (hx*2 + 0)] = b->cur_yuv_buf->y[(iy*2 + 1) * in_stride + ix*2 + 0]; - y_plane[(hy*2 + 1)*thumbnail_width + (hx*2 + 1)] = b->cur_yuv_buf->y[(iy*2 + 1) * in_stride + ix*2 + 1]; - u_plane[hy*thumbnail_width/2 + hx] = b->cur_yuv_buf->uv[iy*in_stride + ix*2 + 0]; - v_plane[hy*thumbnail_width/2 + hx] = b->cur_yuv_buf->uv[iy*in_stride + ix*2 + 1]; - } - } - } - - struct jpeg_compress_struct cinfo; - struct jpeg_error_mgr jerr; - cinfo.err = jpeg_std_error(&jerr); - jpeg_create_compress(&cinfo); - - uint8_t *thumbnail_buffer = nullptr; - size_t thumbnail_len = 0; - jpeg_mem_dest(&cinfo, &thumbnail_buffer, &thumbnail_len); - - cinfo.image_width = thumbnail_width; - cinfo.image_height = thumbnail_height; - cinfo.input_components = 3; - - jpeg_set_defaults(&cinfo); - jpeg_set_colorspace(&cinfo, JCS_YCbCr); - // configure sampling factors for yuv420. - cinfo.comp_info[0].h_samp_factor = 2; // Y - cinfo.comp_info[0].v_samp_factor = 2; - cinfo.comp_info[1].h_samp_factor = 1; // U - cinfo.comp_info[1].v_samp_factor = 1; - cinfo.comp_info[2].h_samp_factor = 1; // V - cinfo.comp_info[2].v_samp_factor = 1; - cinfo.raw_data_in = TRUE; - - jpeg_set_quality(&cinfo, 50, TRUE); - jpeg_start_compress(&cinfo, TRUE); - - JSAMPROW y[16], u[8], v[8]; - JSAMPARRAY planes[3]{y, u, v}; - - for (int line = 0; line < cinfo.image_height; line += 16) { - for (int i = 0; i < 16; ++i) { - y[i] = y_plane + (line + i) * cinfo.image_width; - if (i % 2 == 0) { - int offset = (cinfo.image_width / 2) * ((i + line) / 2); - u[i / 2] = u_plane + offset; - v[i / 2] = v_plane + offset; - } - } - jpeg_write_raw_data(&cinfo, planes, 16); - } - - jpeg_finish_compress(&cinfo); - jpeg_destroy_compress(&cinfo); - - kj::Array dat = kj::heapArray(thumbnail_buffer, thumbnail_len); - free(thumbnail_buffer); - return dat; -} - -static void publish_thumbnail(PubMaster *pm, const CameraBuf *b) { - auto thumbnail = yuv420_to_jpeg(b, b->rgb_width / 4, b->rgb_height / 4); - if (thumbnail.size() == 0) return; - - MessageBuilder msg; - auto thumbnaild = msg.initEvent().initThumbnail(); - thumbnaild.setFrameId(b->cur_frame_data.frame_id); - thumbnaild.setTimestampEof(b->cur_frame_data.timestamp_eof); - thumbnaild.setThumbnail(thumbnail); - - pm->send("thumbnail", msg); -} - -float set_exposure_target(const CameraBuf *b, int x_start, int x_end, int x_skip, int y_start, int y_end, int y_skip) { - int lum_med; - uint32_t lum_binning[256] = {0}; - const uint8_t *pix_ptr = b->cur_yuv_buf->y; - - unsigned int lum_total = 0; - for (int y = y_start; y < y_end; y += y_skip) { - for (int x = x_start; x < x_end; x += x_skip) { - uint8_t lum = pix_ptr[(y * b->rgb_width) + x]; - lum_binning[lum]++; - lum_total += 1; - } - } - - // Find mean lumimance value - unsigned int lum_cur = 0; - for (lum_med = 255; lum_med >= 0; lum_med--) { - lum_cur += lum_binning[lum_med]; - - if (lum_cur >= lum_total / 2) { - break; - } - } - - return lum_med / 256.0; -} - -void *processing_thread(MultiCameraState *cameras, CameraState *cs, process_thread_cb callback) { - const char *thread_name = nullptr; - if (cs == &cameras->road_cam) { - thread_name = "RoadCamera"; - } else if (cs == &cameras->driver_cam) { - thread_name = "DriverCamera"; - } else { - thread_name = "WideRoadCamera"; - } - util::set_thread_name(thread_name); - - uint32_t cnt = 0; - while (!do_exit) { - if (!cs->buf.acquire()) continue; - - callback(cameras, cs, cnt); - - if (cs == &(cameras->road_cam) && cameras->pm && cnt % 100 == 3) { - // this takes 10ms??? - publish_thumbnail(cameras->pm, &(cs->buf)); - } - ++cnt; - } - return NULL; -} - -std::thread start_process_thread(MultiCameraState *cameras, CameraState *cs, process_thread_cb callback) { - return std::thread(processing_thread, cameras, cs, callback); -} - -void camerad_thread() { - cl_device_id device_id = cl_get_device_id(CL_DEVICE_TYPE_DEFAULT); -#ifdef QCOM2 - const cl_context_properties props[] = {CL_CONTEXT_PRIORITY_HINT_QCOM, CL_PRIORITY_HINT_HIGH_QCOM, 0}; - cl_context context = CL_CHECK_ERR(clCreateContext(props, 1, &device_id, NULL, NULL, &err)); -#else - cl_context context = CL_CHECK_ERR(clCreateContext(NULL, 1, &device_id, NULL, NULL, &err)); -#endif - - { - MultiCameraState cameras = {}; - VisionIpcServer vipc_server("camerad", device_id, context); - - cameras_open(&cameras); - cameras_init(&vipc_server, &cameras, device_id, context); - - vipc_server.start_listener(); - - cameras_run(&cameras); - } - - CL_CHECK(clReleaseContext(context)); -} - -int open_v4l_by_name_and_index(const char name[], int index, int flags) { - for (int v4l_index = 0; /**/; ++v4l_index) { - std::string v4l_name = util::read_file(util::string_format("/sys/class/video4linux/v4l-subdev%d/name", v4l_index)); - if (v4l_name.empty()) return -1; - if (v4l_name.find(name) == 0) { - if (index == 0) { - return HANDLE_EINTR(open(util::string_format("/dev/v4l-subdev%d", v4l_index).c_str(), flags)); - } - index--; - } - } -} diff --git a/system/camerad/cameras/camera_common.h b/system/camerad/cameras/camera_common.h deleted file mode 100644 index f98691e..0000000 --- a/system/camerad/cameras/camera_common.h +++ /dev/null @@ -1,87 +0,0 @@ -#pragma once - -#include -#include -#include - -#include "cereal/messaging/messaging.h" -#include "cereal/visionipc/visionipc_server.h" -#include "common/queue.h" - -const int YUV_BUFFER_COUNT = 20; - -enum CameraType { - RoadCam = 0, - DriverCam, - WideRoadCam -}; - -// for debugging -const bool env_disable_road = getenv("DISABLE_ROAD") != NULL; -const bool env_disable_wide_road = getenv("DISABLE_WIDE_ROAD") != NULL; -const bool env_disable_driver = getenv("DISABLE_DRIVER") != NULL; -const bool env_debug_frames = getenv("DEBUG_FRAMES") != NULL; -const bool env_log_raw_frames = getenv("LOG_RAW_FRAMES") != NULL; -const bool env_ctrl_exp_from_params = getenv("CTRL_EXP_FROM_PARAMS") != NULL; - -typedef struct FrameMetadata { - uint32_t frame_id; - uint32_t request_id; - - // Timestamps - uint64_t timestamp_sof; - uint64_t timestamp_eof; - - // Exposure - unsigned int integ_lines; - bool high_conversion_gain; - float gain; - float measured_grey_fraction; - float target_grey_fraction; - - float processing_time; -} FrameMetadata; - -struct MultiCameraState; -class CameraState; -class Debayer; - -class CameraBuf { -private: - VisionIpcServer *vipc_server; - Debayer *debayer = nullptr; - VisionStreamType stream_type; - int cur_buf_idx; - SafeQueue safe_queue; - int frame_buf_count; - -public: - cl_command_queue q; - FrameMetadata cur_frame_data; - VisionBuf *cur_yuv_buf; - VisionBuf *cur_camera_buf; - std::unique_ptr camera_bufs; - std::unique_ptr camera_bufs_metadata; - int rgb_width, rgb_height; - - CameraBuf() = default; - ~CameraBuf(); - void init(cl_device_id device_id, cl_context context, CameraState *s, VisionIpcServer * v, int frame_cnt, VisionStreamType type); - bool acquire(); - void queue(size_t buf_idx); -}; - -typedef void (*process_thread_cb)(MultiCameraState *s, CameraState *c, int cnt); - -void fill_frame_data(cereal::FrameData::Builder &framed, const FrameMetadata &frame_data, CameraState *c); -kj::Array get_raw_frame_image(const CameraBuf *b); -float set_exposure_target(const CameraBuf *b, int x_start, int x_end, int x_skip, int y_start, int y_end, int y_skip); -std::thread start_process_thread(MultiCameraState *cameras, CameraState *cs, process_thread_cb callback); - -void cameras_init(VisionIpcServer *v, MultiCameraState *s, cl_device_id device_id, cl_context ctx); -void cameras_open(MultiCameraState *s); -void cameras_run(MultiCameraState *s); -void cameras_close(MultiCameraState *s); -void camerad_thread(); - -int open_v4l_by_name_and_index(const char name[], int index = 0, int flags = O_RDWR | O_NONBLOCK); diff --git a/system/camerad/cameras/camera_qcom2.cc b/system/camerad/cameras/camera_qcom2.cc deleted file mode 100644 index b27b070..0000000 --- a/system/camerad/cameras/camera_qcom2.cc +++ /dev/null @@ -1,1021 +0,0 @@ -#include "system/camerad/cameras/camera_qcom2.h" - -#include -#include - -#include -#include -#include -#include -#include -#include -#include - -#include "media/cam_defs.h" -#include "media/cam_isp.h" -#include "media/cam_isp_ife.h" -#include "media/cam_req_mgr.h" -#include "media/cam_sensor_cmn_header.h" -#include "media/cam_sync.h" -#include "common/swaglog.h" - -const int MIPI_SETTLE_CNT = 33; // Calculated by camera_freqs.py - -// For debugging: -// echo "4294967295" > /sys/module/cam_debug_util/parameters/debug_mdl - -extern ExitHandler do_exit; - -int CameraState::clear_req_queue() { - struct cam_req_mgr_flush_info req_mgr_flush_request = {0}; - req_mgr_flush_request.session_hdl = session_handle; - req_mgr_flush_request.link_hdl = link_handle; - req_mgr_flush_request.flush_type = CAM_REQ_MGR_FLUSH_TYPE_ALL; - int ret; - ret = do_cam_control(multi_cam_state->video0_fd, CAM_REQ_MGR_FLUSH_REQ, &req_mgr_flush_request, sizeof(req_mgr_flush_request)); - // LOGD("flushed all req: %d", ret); - return ret; -} - -// ************** high level camera helpers **************** - -void CameraState::sensors_start() { - if (!enabled) return; - LOGD("starting sensor %d", camera_num); - sensors_i2c(ci->start_reg_array.data(), ci->start_reg_array.size(), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, ci->data_word); -} - -void CameraState::sensors_poke(int request_id) { - uint32_t cam_packet_handle = 0; - int size = sizeof(struct cam_packet); - auto pkt = mm.alloc(size, &cam_packet_handle); - pkt->num_cmd_buf = 0; - pkt->kmd_cmd_buf_index = -1; - pkt->header.size = size; - pkt->header.op_code = CAM_SENSOR_PACKET_OPCODE_SENSOR_NOP; - pkt->header.request_id = request_id; - - int ret = device_config(sensor_fd, session_handle, sensor_dev_handle, cam_packet_handle); - if (ret != 0) { - LOGE("** sensor %d FAILED poke, disabling", camera_num); - enabled = false; - return; - } -} - -void CameraState::sensors_i2c(const struct i2c_random_wr_payload* dat, int len, int op_code, bool data_word) { - // LOGD("sensors_i2c: %d", len); - uint32_t cam_packet_handle = 0; - int size = sizeof(struct cam_packet)+sizeof(struct cam_cmd_buf_desc)*1; - auto pkt = mm.alloc(size, &cam_packet_handle); - pkt->num_cmd_buf = 1; - pkt->kmd_cmd_buf_index = -1; - pkt->header.size = size; - pkt->header.op_code = op_code; - struct cam_cmd_buf_desc *buf_desc = (struct cam_cmd_buf_desc *)&pkt->payload; - - buf_desc[0].size = buf_desc[0].length = sizeof(struct i2c_rdwr_header) + len*sizeof(struct i2c_random_wr_payload); - buf_desc[0].type = CAM_CMD_BUF_I2C; - - auto i2c_random_wr = mm.alloc(buf_desc[0].size, (uint32_t*)&buf_desc[0].mem_handle); - i2c_random_wr->header.count = len; - i2c_random_wr->header.op_code = 1; - i2c_random_wr->header.cmd_type = CAMERA_SENSOR_CMD_TYPE_I2C_RNDM_WR; - i2c_random_wr->header.data_type = data_word ? CAMERA_SENSOR_I2C_TYPE_WORD : CAMERA_SENSOR_I2C_TYPE_BYTE; - i2c_random_wr->header.addr_type = CAMERA_SENSOR_I2C_TYPE_WORD; - memcpy(i2c_random_wr->random_wr_payload, dat, len*sizeof(struct i2c_random_wr_payload)); - - int ret = device_config(sensor_fd, session_handle, sensor_dev_handle, cam_packet_handle); - if (ret != 0) { - LOGE("** sensor %d FAILED i2c, disabling", camera_num); - enabled = false; - return; - } -} - -static cam_cmd_power *power_set_wait(cam_cmd_power *power, int16_t delay_ms) { - cam_cmd_unconditional_wait *unconditional_wait = (cam_cmd_unconditional_wait *)((char *)power + (sizeof(struct cam_cmd_power) + (power->count - 1) * sizeof(struct cam_power_settings))); - unconditional_wait->cmd_type = CAMERA_SENSOR_CMD_TYPE_WAIT; - unconditional_wait->delay = delay_ms; - unconditional_wait->op_code = CAMERA_SENSOR_WAIT_OP_SW_UCND; - return (struct cam_cmd_power *)(unconditional_wait + 1); -} - -int CameraState::sensors_init() { - uint32_t cam_packet_handle = 0; - int size = sizeof(struct cam_packet)+sizeof(struct cam_cmd_buf_desc)*2; - auto pkt = mm.alloc(size, &cam_packet_handle); - pkt->num_cmd_buf = 2; - pkt->kmd_cmd_buf_index = -1; - pkt->header.op_code = 0x1000000 | CAM_SENSOR_PACKET_OPCODE_SENSOR_PROBE; - pkt->header.size = size; - struct cam_cmd_buf_desc *buf_desc = (struct cam_cmd_buf_desc *)&pkt->payload; - - buf_desc[0].size = buf_desc[0].length = sizeof(struct cam_cmd_i2c_info) + sizeof(struct cam_cmd_probe); - buf_desc[0].type = CAM_CMD_BUF_LEGACY; - auto i2c_info = mm.alloc(buf_desc[0].size, (uint32_t*)&buf_desc[0].mem_handle); - auto probe = (struct cam_cmd_probe *)(i2c_info.get() + 1); - - probe->camera_id = camera_num; - i2c_info->slave_addr = ci->getSlaveAddress(camera_num); - // 0(I2C_STANDARD_MODE) = 100khz, 1(I2C_FAST_MODE) = 400khz - //i2c_info->i2c_freq_mode = I2C_STANDARD_MODE; - i2c_info->i2c_freq_mode = I2C_FAST_MODE; - i2c_info->cmd_type = CAMERA_SENSOR_CMD_TYPE_I2C_INFO; - - probe->data_type = CAMERA_SENSOR_I2C_TYPE_WORD; - probe->addr_type = CAMERA_SENSOR_I2C_TYPE_WORD; - probe->op_code = 3; // don't care? - probe->cmd_type = CAMERA_SENSOR_CMD_TYPE_PROBE; - probe->reg_addr = ci->probe_reg_addr; - probe->expected_data = ci->probe_expected_data; - probe->data_mask = 0; - - //buf_desc[1].size = buf_desc[1].length = 148; - buf_desc[1].size = buf_desc[1].length = 196; - buf_desc[1].type = CAM_CMD_BUF_I2C; - auto power_settings = mm.alloc(buf_desc[1].size, (uint32_t*)&buf_desc[1].mem_handle); - - // power on - struct cam_cmd_power *power = power_settings.get(); - power->count = 4; - power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_UP; - power->power_settings[0].power_seq_type = 3; // clock?? - power->power_settings[1].power_seq_type = 1; // analog - power->power_settings[2].power_seq_type = 2; // digital - power->power_settings[3].power_seq_type = 8; // reset low - power = power_set_wait(power, 1); - - // set clock - power->count = 1; - power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_UP; - power->power_settings[0].power_seq_type = 0; - power->power_settings[0].config_val_low = ci->mclk_frequency; - power = power_set_wait(power, 1); - - // reset high - power->count = 1; - power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_UP; - power->power_settings[0].power_seq_type = 8; - power->power_settings[0].config_val_low = 1; - // wait 650000 cycles @ 19.2 mhz = 33.8 ms - power = power_set_wait(power, 34); - - // probe happens here - - // disable clock - power->count = 1; - power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_DOWN; - power->power_settings[0].power_seq_type = 0; - power->power_settings[0].config_val_low = 0; - power = power_set_wait(power, 1); - - // reset high - power->count = 1; - power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_DOWN; - power->power_settings[0].power_seq_type = 8; - power->power_settings[0].config_val_low = 1; - power = power_set_wait(power, 1); - - // reset low - power->count = 1; - power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_DOWN; - power->power_settings[0].power_seq_type = 8; - power->power_settings[0].config_val_low = 0; - power = power_set_wait(power, 1); - - // power off - power->count = 3; - power->cmd_type = CAMERA_SENSOR_CMD_TYPE_PWR_DOWN; - power->power_settings[0].power_seq_type = 2; - power->power_settings[1].power_seq_type = 1; - power->power_settings[2].power_seq_type = 3; - - int ret = do_cam_control(sensor_fd, CAM_SENSOR_PROBE_CMD, (void *)(uintptr_t)cam_packet_handle, 0); - LOGD("probing the sensor: %d", ret); - return ret; -} - -void CameraState::config_isp(int io_mem_handle, int fence, int request_id, int buf0_mem_handle, int buf0_offset) { - uint32_t cam_packet_handle = 0; - int size = sizeof(struct cam_packet)+sizeof(struct cam_cmd_buf_desc)*2; - if (io_mem_handle != 0) { - size += sizeof(struct cam_buf_io_cfg); - } - auto pkt = mm.alloc(size, &cam_packet_handle); - pkt->num_cmd_buf = 2; - pkt->kmd_cmd_buf_index = 0; - // YUV has kmd_cmd_buf_offset = 1780 - // I guess this is the ISP command - // YUV also has patch_offset = 0x1030 and num_patches = 10 - - if (io_mem_handle != 0) { - pkt->io_configs_offset = sizeof(struct cam_cmd_buf_desc)*pkt->num_cmd_buf; - pkt->num_io_configs = 1; - } - - if (io_mem_handle != 0) { - pkt->header.op_code = 0xf000001; - pkt->header.request_id = request_id; - } else { - pkt->header.op_code = 0xf000000; - } - pkt->header.size = size; - struct cam_cmd_buf_desc *buf_desc = (struct cam_cmd_buf_desc *)&pkt->payload; - struct cam_buf_io_cfg *io_cfg = (struct cam_buf_io_cfg *)((char*)&pkt->payload + pkt->io_configs_offset); - - // TODO: support MMU - buf_desc[0].size = 65624; - buf_desc[0].length = 0; - buf_desc[0].type = CAM_CMD_BUF_DIRECT; - buf_desc[0].meta_data = 3; - buf_desc[0].mem_handle = buf0_mem_handle; - buf_desc[0].offset = buf0_offset; - - // parsed by cam_isp_packet_generic_blob_handler - struct isp_packet { - uint32_t type_0; - cam_isp_resource_hfr_config resource_hfr; - - uint32_t type_1; - cam_isp_clock_config clock; - uint64_t extra_rdi_hz[3]; - - uint32_t type_2; - cam_isp_bw_config bw; - struct cam_isp_bw_vote extra_rdi_vote[6]; - } __attribute__((packed)) tmp; - memset(&tmp, 0, sizeof(tmp)); - - tmp.type_0 = CAM_ISP_GENERIC_BLOB_TYPE_HFR_CONFIG; - tmp.type_0 |= sizeof(cam_isp_resource_hfr_config) << 8; - static_assert(sizeof(cam_isp_resource_hfr_config) == 0x20); - tmp.resource_hfr = { - .num_ports = 1, // 10 for YUV (but I don't think we need them) - .port_hfr_config[0] = { - .resource_type = CAM_ISP_IFE_OUT_RES_RDI_0, // CAM_ISP_IFE_OUT_RES_FULL for YUV - .subsample_pattern = 1, - .subsample_period = 0, - .framedrop_pattern = 1, - .framedrop_period = 0, - }}; - - tmp.type_1 = CAM_ISP_GENERIC_BLOB_TYPE_CLOCK_CONFIG; - tmp.type_1 |= (sizeof(cam_isp_clock_config) + sizeof(tmp.extra_rdi_hz)) << 8; - static_assert((sizeof(cam_isp_clock_config) + sizeof(tmp.extra_rdi_hz)) == 0x38); - tmp.clock = { - .usage_type = 1, // dual mode - .num_rdi = 4, - .left_pix_hz = 404000000, - .right_pix_hz = 404000000, - .rdi_hz[0] = 404000000, - }; - - - tmp.type_2 = CAM_ISP_GENERIC_BLOB_TYPE_BW_CONFIG; - tmp.type_2 |= (sizeof(cam_isp_bw_config) + sizeof(tmp.extra_rdi_vote)) << 8; - static_assert((sizeof(cam_isp_bw_config) + sizeof(tmp.extra_rdi_vote)) == 0xe0); - tmp.bw = { - .usage_type = 1, // dual mode - .num_rdi = 4, - .left_pix_vote = { - .resource_id = 0, - .cam_bw_bps = 450000000, - .ext_bw_bps = 450000000, - }, - .rdi_vote[0] = { - .resource_id = 0, - .cam_bw_bps = 8706200000, - .ext_bw_bps = 8706200000, - }, - }; - - static_assert(offsetof(struct isp_packet, type_2) == 0x60); - - buf_desc[1].size = sizeof(tmp); - buf_desc[1].offset = io_mem_handle != 0 ? 0x60 : 0; - buf_desc[1].length = buf_desc[1].size - buf_desc[1].offset; - buf_desc[1].type = CAM_CMD_BUF_GENERIC; - buf_desc[1].meta_data = CAM_ISP_PACKET_META_GENERIC_BLOB_COMMON; - auto buf2 = mm.alloc(buf_desc[1].size, (uint32_t*)&buf_desc[1].mem_handle); - memcpy(buf2.get(), &tmp, sizeof(tmp)); - - if (io_mem_handle != 0) { - io_cfg[0].mem_handle[0] = io_mem_handle; - io_cfg[0].planes[0] = (struct cam_plane_cfg){ - .width = ci->frame_width, - .height = ci->frame_height + ci->extra_height, - .plane_stride = ci->frame_stride, - .slice_height = ci->frame_height + ci->extra_height, - .meta_stride = 0x0, // YUV has meta(stride=0x400, size=0x5000) - .meta_size = 0x0, - .meta_offset = 0x0, - .packer_config = 0x0, // 0xb for YUV - .mode_config = 0x0, // 0x9ef for YUV - .tile_config = 0x0, - .h_init = 0x0, - .v_init = 0x0, - }; - io_cfg[0].format = ci->mipi_format; // CAM_FORMAT_UBWC_TP10 for YUV - io_cfg[0].color_space = CAM_COLOR_SPACE_BASE; // CAM_COLOR_SPACE_BT601_FULL for YUV - io_cfg[0].color_pattern = 0x5; // 0x0 for YUV - io_cfg[0].bpp = (ci->mipi_format == CAM_FORMAT_MIPI_RAW_10 ? 0xa : 0xc); // bits per pixel - io_cfg[0].resource_type = CAM_ISP_IFE_OUT_RES_RDI_0; // CAM_ISP_IFE_OUT_RES_FULL for YUV - io_cfg[0].fence = fence; - io_cfg[0].direction = CAM_BUF_OUTPUT; - io_cfg[0].subsample_pattern = 0x1; - io_cfg[0].framedrop_pattern = 0x1; - } - - int ret = device_config(multi_cam_state->isp_fd, session_handle, isp_dev_handle, cam_packet_handle); - assert(ret == 0); - if (ret != 0) { - LOGE("isp config failed"); - } -} - -void CameraState::enqueue_buffer(int i, bool dp) { - int ret; - int request_id = request_ids[i]; - - if (buf_handle[i] && sync_objs[i]) { - // wait - struct cam_sync_wait sync_wait = {0}; - sync_wait.sync_obj = sync_objs[i]; - sync_wait.timeout_ms = 50; // max dt tolerance, typical should be 23 - ret = do_cam_control(multi_cam_state->cam_sync_fd, CAM_SYNC_WAIT, &sync_wait, sizeof(sync_wait)); - if (ret != 0) { - LOGE("failed to wait for sync: %d %d", ret, sync_wait.sync_obj); - // TODO: handle frame drop cleanly - } - - buf.camera_bufs_metadata[i].timestamp_eof = (uint64_t)nanos_since_boot(); // set true eof - if (dp) buf.queue(i); - - // destroy old output fence - struct cam_sync_info sync_destroy = {0}; - sync_destroy.sync_obj = sync_objs[i]; - ret = do_cam_control(multi_cam_state->cam_sync_fd, CAM_SYNC_DESTROY, &sync_destroy, sizeof(sync_destroy)); - if (ret != 0) { - LOGE("failed to destroy sync object: %d %d", ret, sync_destroy.sync_obj); - } - } - - // create output fence - struct cam_sync_info sync_create = {0}; - strcpy(sync_create.name, "NodeOutputPortFence"); - ret = do_cam_control(multi_cam_state->cam_sync_fd, CAM_SYNC_CREATE, &sync_create, sizeof(sync_create)); - if (ret != 0) { - LOGE("failed to create fence: %d %d", ret, sync_create.sync_obj); - } - sync_objs[i] = sync_create.sync_obj; - - // schedule request with camera request manager - struct cam_req_mgr_sched_request req_mgr_sched_request = {0}; - req_mgr_sched_request.session_hdl = session_handle; - req_mgr_sched_request.link_hdl = link_handle; - req_mgr_sched_request.req_id = request_id; - ret = do_cam_control(multi_cam_state->video0_fd, CAM_REQ_MGR_SCHED_REQ, &req_mgr_sched_request, sizeof(req_mgr_sched_request)); - if (ret != 0) { - LOGE("failed to schedule cam mgr request: %d %d", ret, request_id); - } - - // poke sensor, must happen after schedule - sensors_poke(request_id); - - // submit request to the ife - config_isp(buf_handle[i], sync_objs[i], request_id, buf0_handle, 65632*(i+1)); -} - -void CameraState::enqueue_req_multi(int start, int n, bool dp) { - for (int i=start; idc_gain_min_weight; - gain_idx = ci->analog_gain_rec_idx; - exposure_time = 5; - cur_ev[0] = cur_ev[1] = cur_ev[2] = (1 + dc_gain_weight * (ci->dc_gain_factor-1) / ci->dc_gain_max_weight) * ci->sensor_analog_gains[gain_idx] * exposure_time; -} - -void CameraState::camera_map_bufs(MultiCameraState *s) { - for (int i = 0; i < FRAME_BUF_COUNT; i++) { - // configure ISP to put the image in place - struct cam_mem_mgr_map_cmd mem_mgr_map_cmd = {0}; - mem_mgr_map_cmd.mmu_hdls[0] = s->device_iommu; - mem_mgr_map_cmd.num_hdl = 1; - mem_mgr_map_cmd.flags = CAM_MEM_FLAG_HW_READ_WRITE; - mem_mgr_map_cmd.fd = buf.camera_bufs[i].fd; - int ret = do_cam_control(s->video0_fd, CAM_REQ_MGR_MAP_BUF, &mem_mgr_map_cmd, sizeof(mem_mgr_map_cmd)); - LOGD("map buf req: (fd: %d) 0x%x %d", buf.camera_bufs[i].fd, mem_mgr_map_cmd.out.buf_handle, ret); - buf_handle[i] = mem_mgr_map_cmd.out.buf_handle; - } - enqueue_req_multi(1, FRAME_BUF_COUNT, 0); -} - -void CameraState::camera_init(MultiCameraState *s, VisionIpcServer * v, cl_device_id device_id, cl_context ctx, VisionStreamType yuv_type) { - if (!enabled) return; - - LOGD("camera init %d", camera_num); - request_id_last = 0; - skipped = true; - - buf.init(device_id, ctx, this, v, FRAME_BUF_COUNT, yuv_type); - camera_map_bufs(s); -} - -void CameraState::camera_open(MultiCameraState *multi_cam_state_, int camera_num_, bool enabled_) { - multi_cam_state = multi_cam_state_; - camera_num = camera_num_; - enabled = enabled_; - if (!enabled) return; - - int ret; - sensor_fd = open_v4l_by_name_and_index("cam-sensor-driver", camera_num); - assert(sensor_fd >= 0); - LOGD("opened sensor for %d", camera_num); - - // init memorymanager for this camera - mm.init(multi_cam_state->video0_fd); - - LOGD("-- Probing sensor %d", camera_num); - - auto init_sensor_lambda = [this](SensorInfo *sensor) { - ci.reset(sensor); - int ret = sensors_init(); - if (ret == 0) { - sensor_set_parameters(); - } - return ret == 0; - }; - - // Try different sensors one by one until it success. - if (!init_sensor_lambda(new AR0231) && - !init_sensor_lambda(new OX03C10) && - !init_sensor_lambda(new OS04C10)) { - LOGE("** sensor %d FAILED bringup, disabling", camera_num); - enabled = false; - return; - } - LOGD("-- Probing sensor %d success", camera_num); - - // create session - struct cam_req_mgr_session_info session_info = {}; - ret = do_cam_control(multi_cam_state->video0_fd, CAM_REQ_MGR_CREATE_SESSION, &session_info, sizeof(session_info)); - LOGD("get session: %d 0x%X", ret, session_info.session_hdl); - session_handle = session_info.session_hdl; - - // access the sensor - LOGD("-- Accessing sensor"); - auto sensor_dev_handle_ = device_acquire(sensor_fd, session_handle, nullptr); - assert(sensor_dev_handle_); - sensor_dev_handle = *sensor_dev_handle_; - LOGD("acquire sensor dev"); - - LOG("-- Configuring sensor"); - sensors_i2c(ci->init_reg_array.data(), ci->init_reg_array.size(), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, ci->data_word); - - // NOTE: to be able to disable road and wide road, we still have to configure the sensor over i2c - // If you don't do this, the strobe GPIO is an output (even in reset it seems!) - if (!enabled) return; - - struct cam_isp_in_port_info in_port_info = { - .res_type = (uint32_t[]){CAM_ISP_IFE_IN_RES_PHY_0, CAM_ISP_IFE_IN_RES_PHY_1, CAM_ISP_IFE_IN_RES_PHY_2}[camera_num], - - .lane_type = CAM_ISP_LANE_TYPE_DPHY, - .lane_num = 4, - .lane_cfg = 0x3210, - - .vc = 0x0, - .dt = ci->frame_data_type, - .format = ci->mipi_format, - - .test_pattern = 0x2, // 0x3? - .usage_type = 0x0, - - .left_start = 0, - .left_stop = ci->frame_width - 1, - .left_width = ci->frame_width, - - .right_start = 0, - .right_stop = ci->frame_width - 1, - .right_width = ci->frame_width, - - .line_start = 0, - .line_stop = ci->frame_height + ci->extra_height - 1, - .height = ci->frame_height + ci->extra_height, - - .pixel_clk = 0x0, - .batch_size = 0x0, - .dsp_mode = CAM_ISP_DSP_MODE_NONE, - .hbi_cnt = 0x0, - .custom_csid = 0x0, - - .num_out_res = 0x1, - .data[0] = (struct cam_isp_out_port_info){ - .res_type = CAM_ISP_IFE_OUT_RES_RDI_0, - .format = ci->mipi_format, - .width = ci->frame_width, - .height = ci->frame_height + ci->extra_height, - .comp_grp_id = 0x0, .split_point = 0x0, .secure_mode = 0x0, - }, - }; - struct cam_isp_resource isp_resource = { - .resource_id = CAM_ISP_RES_ID_PORT, - .handle_type = CAM_HANDLE_USER_POINTER, - .res_hdl = (uint64_t)&in_port_info, - .length = sizeof(in_port_info), - }; - - auto isp_dev_handle_ = device_acquire(multi_cam_state->isp_fd, session_handle, &isp_resource); - assert(isp_dev_handle_); - isp_dev_handle = *isp_dev_handle_; - LOGD("acquire isp dev"); - - csiphy_fd = open_v4l_by_name_and_index("cam-csiphy-driver", camera_num); - assert(csiphy_fd >= 0); - LOGD("opened csiphy for %d", camera_num); - - struct cam_csiphy_acquire_dev_info csiphy_acquire_dev_info = {.combo_mode = 0}; - auto csiphy_dev_handle_ = device_acquire(csiphy_fd, session_handle, &csiphy_acquire_dev_info); - assert(csiphy_dev_handle_); - csiphy_dev_handle = *csiphy_dev_handle_; - LOGD("acquire csiphy dev"); - - // config ISP - alloc_w_mmu_hdl(multi_cam_state->video0_fd, 984480, (uint32_t*)&buf0_handle, 0x20, CAM_MEM_FLAG_HW_READ_WRITE | CAM_MEM_FLAG_KMD_ACCESS | - CAM_MEM_FLAG_UMD_ACCESS | CAM_MEM_FLAG_CMD_BUF_TYPE, multi_cam_state->device_iommu, multi_cam_state->cdm_iommu); - config_isp(0, 0, 1, buf0_handle, 0); - - // config csiphy - LOG("-- Config CSI PHY"); - { - uint32_t cam_packet_handle = 0; - int size = sizeof(struct cam_packet)+sizeof(struct cam_cmd_buf_desc)*1; - auto pkt = mm.alloc(size, &cam_packet_handle); - pkt->num_cmd_buf = 1; - pkt->kmd_cmd_buf_index = -1; - pkt->header.size = size; - struct cam_cmd_buf_desc *buf_desc = (struct cam_cmd_buf_desc *)&pkt->payload; - - buf_desc[0].size = buf_desc[0].length = sizeof(struct cam_csiphy_info); - buf_desc[0].type = CAM_CMD_BUF_GENERIC; - - auto csiphy_info = mm.alloc(buf_desc[0].size, (uint32_t*)&buf_desc[0].mem_handle); - csiphy_info->lane_mask = 0x1f; - csiphy_info->lane_assign = 0x3210;// skip clk. How is this 16 bit for 5 channels?? - csiphy_info->csiphy_3phase = 0x0; // no 3 phase, only 2 conductors per lane - csiphy_info->combo_mode = 0x0; - csiphy_info->lane_cnt = 0x4; - csiphy_info->secure_mode = 0x0; - csiphy_info->settle_time = MIPI_SETTLE_CNT * 200000000ULL; - csiphy_info->data_rate = 48000000; // Calculated by camera_freqs.py - - int ret_ = device_config(csiphy_fd, session_handle, csiphy_dev_handle, cam_packet_handle); - assert(ret_ == 0); - } - - // link devices - LOG("-- Link devices"); - struct cam_req_mgr_link_info req_mgr_link_info = {0}; - req_mgr_link_info.session_hdl = session_handle; - req_mgr_link_info.num_devices = 2; - req_mgr_link_info.dev_hdls[0] = isp_dev_handle; - req_mgr_link_info.dev_hdls[1] = sensor_dev_handle; - ret = do_cam_control(multi_cam_state->video0_fd, CAM_REQ_MGR_LINK, &req_mgr_link_info, sizeof(req_mgr_link_info)); - link_handle = req_mgr_link_info.link_hdl; - LOGD("link: %d session: 0x%X isp: 0x%X sensors: 0x%X link: 0x%X", ret, session_handle, isp_dev_handle, sensor_dev_handle, link_handle); - - struct cam_req_mgr_link_control req_mgr_link_control = {0}; - req_mgr_link_control.ops = CAM_REQ_MGR_LINK_ACTIVATE; - req_mgr_link_control.session_hdl = session_handle; - req_mgr_link_control.num_links = 1; - req_mgr_link_control.link_hdls[0] = link_handle; - ret = do_cam_control(multi_cam_state->video0_fd, CAM_REQ_MGR_LINK_CONTROL, &req_mgr_link_control, sizeof(req_mgr_link_control)); - LOGD("link control: %d", ret); - - ret = device_control(csiphy_fd, CAM_START_DEV, session_handle, csiphy_dev_handle); - LOGD("start csiphy: %d", ret); - ret = device_control(multi_cam_state->isp_fd, CAM_START_DEV, session_handle, isp_dev_handle); - LOGD("start isp: %d", ret); - assert(ret == 0); - - // TODO: this is unneeded, should we be doing the start i2c in a different way? - //ret = device_control(sensor_fd, CAM_START_DEV, session_handle, sensor_dev_handle); - //LOGD("start sensor: %d", ret); -} - -void cameras_init(VisionIpcServer *v, MultiCameraState *s, cl_device_id device_id, cl_context ctx) { - s->driver_cam.camera_init(s, v, device_id, ctx, VISION_STREAM_DRIVER); - s->road_cam.camera_init(s, v, device_id, ctx, VISION_STREAM_ROAD); - s->wide_road_cam.camera_init(s, v, device_id, ctx, VISION_STREAM_WIDE_ROAD); - - s->pm = new PubMaster({"roadCameraState", "driverCameraState", "wideRoadCameraState", "thumbnail"}); -} - -void cameras_open(MultiCameraState *s) { - int ret; - - LOG("-- Opening devices"); - // video0 is req_mgr, the target of many ioctls - s->video0_fd = HANDLE_EINTR(open("/dev/v4l/by-path/platform-soc:qcom_cam-req-mgr-video-index0", O_RDWR | O_NONBLOCK)); - assert(s->video0_fd >= 0); - LOGD("opened video0"); - - // video1 is cam_sync, the target of some ioctls - s->cam_sync_fd = HANDLE_EINTR(open("/dev/v4l/by-path/platform-cam_sync-video-index0", O_RDWR | O_NONBLOCK)); - assert(s->cam_sync_fd >= 0); - LOGD("opened video1 (cam_sync)"); - - // looks like there's only one of these - s->isp_fd = open_v4l_by_name_and_index("cam-isp"); - assert(s->isp_fd >= 0); - LOGD("opened isp"); - - // query icp for MMU handles - LOG("-- Query ICP for MMU handles"); - struct cam_isp_query_cap_cmd isp_query_cap_cmd = {0}; - struct cam_query_cap_cmd query_cap_cmd = {0}; - query_cap_cmd.handle_type = 1; - query_cap_cmd.caps_handle = (uint64_t)&isp_query_cap_cmd; - query_cap_cmd.size = sizeof(isp_query_cap_cmd); - ret = do_cam_control(s->isp_fd, CAM_QUERY_CAP, &query_cap_cmd, sizeof(query_cap_cmd)); - assert(ret == 0); - LOGD("using MMU handle: %x", isp_query_cap_cmd.device_iommu.non_secure); - LOGD("using MMU handle: %x", isp_query_cap_cmd.cdm_iommu.non_secure); - s->device_iommu = isp_query_cap_cmd.device_iommu.non_secure; - s->cdm_iommu = isp_query_cap_cmd.cdm_iommu.non_secure; - - // subscribe - LOG("-- Subscribing"); - struct v4l2_event_subscription sub = {0}; - sub.type = V4L_EVENT_CAM_REQ_MGR_EVENT; - sub.id = V4L_EVENT_CAM_REQ_MGR_SOF_BOOT_TS; - ret = HANDLE_EINTR(ioctl(s->video0_fd, VIDIOC_SUBSCRIBE_EVENT, &sub)); - LOGD("req mgr subscribe: %d", ret); - - s->driver_cam.camera_open(s, 2, !env_disable_driver); - LOGD("driver camera opened"); - s->road_cam.camera_open(s, 1, !env_disable_road); - LOGD("road camera opened"); - s->wide_road_cam.camera_open(s, 0, !env_disable_wide_road); - LOGD("wide road camera opened"); -} - -void CameraState::camera_close() { - int ret; - - // stop devices - LOG("-- Stop devices %d", camera_num); - - if (enabled) { - // ret = device_control(sensor_fd, CAM_STOP_DEV, session_handle, sensor_dev_handle); - // LOGD("stop sensor: %d", ret); - ret = device_control(multi_cam_state->isp_fd, CAM_STOP_DEV, session_handle, isp_dev_handle); - LOGD("stop isp: %d", ret); - ret = device_control(csiphy_fd, CAM_STOP_DEV, session_handle, csiphy_dev_handle); - LOGD("stop csiphy: %d", ret); - // link control stop - LOG("-- Stop link control"); - struct cam_req_mgr_link_control req_mgr_link_control = {0}; - req_mgr_link_control.ops = CAM_REQ_MGR_LINK_DEACTIVATE; - req_mgr_link_control.session_hdl = session_handle; - req_mgr_link_control.num_links = 1; - req_mgr_link_control.link_hdls[0] = link_handle; - ret = do_cam_control(multi_cam_state->video0_fd, CAM_REQ_MGR_LINK_CONTROL, &req_mgr_link_control, sizeof(req_mgr_link_control)); - LOGD("link control stop: %d", ret); - - // unlink - LOG("-- Unlink"); - struct cam_req_mgr_unlink_info req_mgr_unlink_info = {0}; - req_mgr_unlink_info.session_hdl = session_handle; - req_mgr_unlink_info.link_hdl = link_handle; - ret = do_cam_control(multi_cam_state->video0_fd, CAM_REQ_MGR_UNLINK, &req_mgr_unlink_info, sizeof(req_mgr_unlink_info)); - LOGD("unlink: %d", ret); - - // release devices - LOGD("-- Release devices"); - ret = device_control(multi_cam_state->isp_fd, CAM_RELEASE_DEV, session_handle, isp_dev_handle); - LOGD("release isp: %d", ret); - ret = device_control(csiphy_fd, CAM_RELEASE_DEV, session_handle, csiphy_dev_handle); - LOGD("release csiphy: %d", ret); - - for (int i = 0; i < FRAME_BUF_COUNT; i++) { - release(multi_cam_state->video0_fd, buf_handle[i]); - } - LOGD("released buffers"); - } - - ret = device_control(sensor_fd, CAM_RELEASE_DEV, session_handle, sensor_dev_handle); - LOGD("release sensor: %d", ret); - - // destroyed session - struct cam_req_mgr_session_info session_info = {.session_hdl = session_handle}; - ret = do_cam_control(multi_cam_state->video0_fd, CAM_REQ_MGR_DESTROY_SESSION, &session_info, sizeof(session_info)); - LOGD("destroyed session %d: %d", camera_num, ret); -} - -void cameras_close(MultiCameraState *s) { - s->driver_cam.camera_close(); - s->road_cam.camera_close(); - s->wide_road_cam.camera_close(); - - delete s->pm; -} - -void CameraState::handle_camera_event(void *evdat) { - if (!enabled) return; - struct cam_req_mgr_message *event_data = (struct cam_req_mgr_message *)evdat; - assert(event_data->session_hdl == session_handle); - assert(event_data->u.frame_msg.link_hdl == link_handle); - - uint64_t timestamp = event_data->u.frame_msg.timestamp; - int main_id = event_data->u.frame_msg.frame_id; - int real_id = event_data->u.frame_msg.request_id; - - if (real_id != 0) { // next ready - if (real_id == 1) {idx_offset = main_id;} - int buf_idx = (real_id - 1) % FRAME_BUF_COUNT; - - // check for skipped frames - if (main_id > frame_id_last + 1 && !skipped) { - LOGE("camera %d realign", camera_num); - clear_req_queue(); - enqueue_req_multi(real_id + 1, FRAME_BUF_COUNT - 1, 0); - skipped = true; - } else if (main_id == frame_id_last + 1) { - skipped = false; - } - - // check for dropped requests - if (real_id > request_id_last + 1) { - LOGE("camera %d dropped requests %d %d", camera_num, real_id, request_id_last); - enqueue_req_multi(request_id_last + 1 + FRAME_BUF_COUNT, real_id - (request_id_last + 1), 0); - } - - // metas - frame_id_last = main_id; - request_id_last = real_id; - - auto &meta_data = buf.camera_bufs_metadata[buf_idx]; - meta_data.frame_id = main_id - idx_offset; - meta_data.request_id = real_id; - meta_data.timestamp_sof = timestamp; - exp_lock.lock(); - meta_data.gain = analog_gain_frac * (1 + dc_gain_weight * (ci->dc_gain_factor-1) / ci->dc_gain_max_weight); - meta_data.high_conversion_gain = dc_gain_enabled; - meta_data.integ_lines = exposure_time; - meta_data.measured_grey_fraction = measured_grey_fraction; - meta_data.target_grey_fraction = target_grey_fraction; - exp_lock.unlock(); - - // dispatch - enqueue_req_multi(real_id + FRAME_BUF_COUNT, 1, 1); - } else { // not ready - if (main_id > frame_id_last + 10) { - LOGE("camera %d reset after half second of no response", camera_num); - clear_req_queue(); - enqueue_req_multi(request_id_last + 1, FRAME_BUF_COUNT, 0); - frame_id_last = main_id; - skipped = true; - } - } -} - -void CameraState::update_exposure_score(float desired_ev, int exp_t, int exp_g_idx, float exp_gain) { - float score = ci->getExposureScore(desired_ev, exp_t, exp_g_idx, exp_gain, gain_idx); - if (score < best_ev_score) { - new_exp_t = exp_t; - new_exp_g = exp_g_idx; - best_ev_score = score; - } -} - -void CameraState::set_camera_exposure(float grey_frac) { - if (!enabled) return; - const float dt = 0.05; - - const float ts_grey = 10.0; - const float ts_ev = 0.05; - - const float k_grey = (dt / ts_grey) / (1.0 + dt / ts_grey); - const float k_ev = (dt / ts_ev) / (1.0 + dt / ts_ev); - - // It takes 3 frames for the commanded exposure settings to take effect. The first frame is already started by the time - // we reach this function, the other 2 are due to the register buffering in the sensor. - // Therefore we use the target EV from 3 frames ago, the grey fraction that was just measured was the result of that control action. - // TODO: Lower latency to 2 frames, by using the histogram outputted by the sensor we can do AE before the debayering is complete - - const float cur_ev_ = cur_ev[buf.cur_frame_data.frame_id % 3]; - - // Scale target grey between 0.1 and 0.4 depending on lighting conditions - float new_target_grey = std::clamp(0.4 - 0.3 * log2(1.0 + ci->target_grey_factor*cur_ev_) / log2(6000.0), 0.1, 0.4); - float target_grey = (1.0 - k_grey) * target_grey_fraction + k_grey * new_target_grey; - - float desired_ev = std::clamp(cur_ev_ * target_grey / grey_frac, ci->min_ev, ci->max_ev); - float k = (1.0 - k_ev) / 3.0; - desired_ev = (k * cur_ev[0]) + (k * cur_ev[1]) + (k * cur_ev[2]) + (k_ev * desired_ev); - - best_ev_score = 1e6; - new_exp_g = 0; - new_exp_t = 0; - - // Hysteresis around high conversion gain - // We usually want this on since it results in lower noise, but turn off in very bright day scenes - bool enable_dc_gain = dc_gain_enabled; - if (!enable_dc_gain && target_grey < ci->dc_gain_on_grey) { - enable_dc_gain = true; - dc_gain_weight = ci->dc_gain_min_weight; - } else if (enable_dc_gain && target_grey > ci->dc_gain_off_grey) { - enable_dc_gain = false; - dc_gain_weight = ci->dc_gain_max_weight; - } - - if (enable_dc_gain && dc_gain_weight < ci->dc_gain_max_weight) {dc_gain_weight += 1;} - if (!enable_dc_gain && dc_gain_weight > ci->dc_gain_min_weight) {dc_gain_weight -= 1;} - - std::string gain_bytes, time_bytes; - if (env_ctrl_exp_from_params) { - gain_bytes = params.get("CameraDebugExpGain"); - time_bytes = params.get("CameraDebugExpTime"); - } - - if (gain_bytes.size() > 0 && time_bytes.size() > 0) { - // Override gain and exposure time - gain_idx = std::stoi(gain_bytes); - exposure_time = std::stoi(time_bytes); - - new_exp_g = gain_idx; - new_exp_t = exposure_time; - enable_dc_gain = false; - } else { - // Simple brute force optimizer to choose sensor parameters - // to reach desired EV - for (int g = std::max((int)ci->analog_gain_min_idx, gain_idx - 1); g <= std::min((int)ci->analog_gain_max_idx, gain_idx + 1); g++) { - float gain = ci->sensor_analog_gains[g] * (1 + dc_gain_weight * (ci->dc_gain_factor-1) / ci->dc_gain_max_weight); - - // Compute optimal time for given gain - int t = std::clamp(int(std::round(desired_ev / gain)), ci->exposure_time_min, ci->exposure_time_max); - - // Only go below recommended gain when absolutely necessary to not overexpose - if (g < ci->analog_gain_rec_idx && t > 20 && g < gain_idx) { - continue; - } - - update_exposure_score(desired_ev, t, g, gain); - } - } - - exp_lock.lock(); - - measured_grey_fraction = grey_frac; - target_grey_fraction = target_grey; - - analog_gain_frac = ci->sensor_analog_gains[new_exp_g]; - gain_idx = new_exp_g; - exposure_time = new_exp_t; - dc_gain_enabled = enable_dc_gain; - - float gain = analog_gain_frac * (1 + dc_gain_weight * (ci->dc_gain_factor-1) / ci->dc_gain_max_weight); - cur_ev[buf.cur_frame_data.frame_id % 3] = exposure_time * gain; - - exp_lock.unlock(); - - // Processing a frame takes right about 50ms, so we need to wait a few ms - // so we don't send i2c commands around the frame start. - int ms = (nanos_since_boot() - buf.cur_frame_data.timestamp_sof) / 1000000; - if (ms < 60) { - util::sleep_for(60 - ms); - } - // LOGE("ae - camera %d, cur_t %.5f, sof %.5f, dt %.5f", camera_num, 1e-9 * nanos_since_boot(), 1e-9 * buf.cur_frame_data.timestamp_sof, 1e-9 * (nanos_since_boot() - buf.cur_frame_data.timestamp_sof)); - - auto exp_reg_array = ci->getExposureRegisters(exposure_time, new_exp_g, dc_gain_enabled); - sensors_i2c(exp_reg_array.data(), exp_reg_array.size(), CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, ci->data_word); -} - -static void process_driver_camera(MultiCameraState *s, CameraState *c, int cnt) { - c->set_camera_exposure(set_exposure_target(&c->buf, 96, 1832, 2, 242, 1148, 4)); - - MessageBuilder msg; - auto framed = msg.initEvent().initDriverCameraState(); - framed.setFrameType(cereal::FrameData::FrameType::FRONT); - fill_frame_data(framed, c->buf.cur_frame_data, c); - - c->ci->processRegisters(c, framed); - s->pm->send("driverCameraState", msg); -} - -void process_road_camera(MultiCameraState *s, CameraState *c, int cnt) { - const CameraBuf *b = &c->buf; - - MessageBuilder msg; - auto framed = c == &s->road_cam ? msg.initEvent().initRoadCameraState() : msg.initEvent().initWideRoadCameraState(); - fill_frame_data(framed, b->cur_frame_data, c); - if (env_log_raw_frames && c == &s->road_cam && cnt % 100 == 5) { // no overlap with qlog decimation - framed.setImage(get_raw_frame_image(b)); - } - LOGT(c->buf.cur_frame_data.frame_id, "%s: Image set", c == &s->road_cam ? "RoadCamera" : "WideRoadCamera"); - - c->ci->processRegisters(c, framed); - s->pm->send(c == &s->road_cam ? "roadCameraState" : "wideRoadCameraState", msg); - - const auto [x, y, w, h] = (c == &s->wide_road_cam) ? std::tuple(96, 250, 1734, 524) : std::tuple(96, 160, 1734, 986); - const int skip = 2; - c->set_camera_exposure(set_exposure_target(b, x, x + w, skip, y, y + h, skip)); -} - -void cameras_run(MultiCameraState *s) { - // FrogPilot variables - Params paramsMemory{"/dev/shm/params"}; - const std::chrono::seconds fpsUpdateInterval(1); - std::chrono::steady_clock::time_point startTime = std::chrono::steady_clock::now(); - int frameCount = 0; - - LOG("-- Starting threads"); - std::vector threads; - if (s->driver_cam.enabled) threads.push_back(start_process_thread(s, &s->driver_cam, process_driver_camera)); - if (s->road_cam.enabled) threads.push_back(start_process_thread(s, &s->road_cam, process_road_camera)); - if (s->wide_road_cam.enabled) threads.push_back(start_process_thread(s, &s->wide_road_cam, process_road_camera)); - - // start devices - LOG("-- Starting devices"); - s->driver_cam.sensors_start(); - s->road_cam.sensors_start(); - s->wide_road_cam.sensors_start(); - - // poll events - LOG("-- Dequeueing Video events"); - while (!do_exit) { - struct pollfd fds[1] = {{0}}; - - fds[0].fd = s->video0_fd; - fds[0].events = POLLPRI; - - int ret = poll(fds, std::size(fds), 1000); - if (ret < 0) { - if (errno == EINTR || errno == EAGAIN) continue; - LOGE("poll failed (%d - %d)", ret, errno); - break; - } - - if (!fds[0].revents) continue; - - struct v4l2_event ev = {0}; - ret = HANDLE_EINTR(ioctl(fds[0].fd, VIDIOC_DQEVENT, &ev)); - if (ret == 0) { - if (ev.type == V4L_EVENT_CAM_REQ_MGR_EVENT) { - struct cam_req_mgr_message *event_data = (struct cam_req_mgr_message *)ev.u.data; - if (env_debug_frames) { - printf("sess_hdl 0x%6X, link_hdl 0x%6X, frame_id %lu, req_id %lu, timestamp %.2f ms, sof_status %d\n", event_data->session_hdl, event_data->u.frame_msg.link_hdl, - event_data->u.frame_msg.frame_id, event_data->u.frame_msg.request_id, event_data->u.frame_msg.timestamp/1e6, event_data->u.frame_msg.sof_status); - } - - // for debugging - //do_exit = do_exit || event_data->u.frame_msg.frame_id > (30*20); - - // Increment frame count - frameCount++; - - // Calculate and display FPS every second - std::chrono::steady_clock::time_point currentTime = std::chrono::steady_clock::now(); - if (currentTime - startTime >= fpsUpdateInterval) { - double fps = static_cast(frameCount) / std::chrono::duration(currentTime - startTime).count(); - paramsMemory.putIntNonBlocking("CameraFPS", fps / 3); - - // Reset counter and timer - frameCount = 0; - startTime = currentTime; - } - - if (event_data->session_hdl == s->road_cam.session_handle) { - s->road_cam.handle_camera_event(event_data); - } else if (event_data->session_hdl == s->wide_road_cam.session_handle) { - s->wide_road_cam.handle_camera_event(event_data); - } else if (event_data->session_hdl == s->driver_cam.session_handle) { - s->driver_cam.handle_camera_event(event_data); - } else { - LOGE("Unknown vidioc event source"); - assert(false); - } - } else { - LOGE("unhandled event %d\n", ev.type); - } - } else { - LOGE("VIDIOC_DQEVENT failed, errno=%d", errno); - } - } - - LOG(" ************** STOPPING **************"); - - for (auto &t : threads) t.join(); - - cameras_close(s); -} diff --git a/system/camerad/cameras/camera_qcom2.h b/system/camerad/cameras/camera_qcom2.h deleted file mode 100644 index 47ca578..0000000 --- a/system/camerad/cameras/camera_qcom2.h +++ /dev/null @@ -1,98 +0,0 @@ -#pragma once - -#include -#include - -#include "system/camerad/cameras/camera_common.h" -#include "system/camerad/cameras/camera_util.h" -#include "system/camerad/sensors/sensor.h" -#include "common/params.h" -#include "common/util.h" - -#define FRAME_BUF_COUNT 4 - -class CameraState { -public: - MultiCameraState *multi_cam_state; - std::unique_ptr ci; - bool enabled; - - std::mutex exp_lock; - - int exposure_time; - bool dc_gain_enabled; - int dc_gain_weight; - int gain_idx; - float analog_gain_frac; - - float cur_ev[3]; - float best_ev_score; - int new_exp_g; - int new_exp_t; - - float measured_grey_fraction; - float target_grey_fraction; - - unique_fd sensor_fd; - unique_fd csiphy_fd; - - int camera_num; - - void handle_camera_event(void *evdat); - void update_exposure_score(float desired_ev, int exp_t, int exp_g_idx, float exp_gain); - void set_camera_exposure(float grey_frac); - - void sensors_start(); - - void camera_open(MultiCameraState *multi_cam_state, int camera_num, bool enabled); - void sensor_set_parameters(); - void camera_map_bufs(MultiCameraState *s); - void camera_init(MultiCameraState *s, VisionIpcServer *v, cl_device_id device_id, cl_context ctx, VisionStreamType yuv_type); - void camera_close(); - - int32_t session_handle; - int32_t sensor_dev_handle; - int32_t isp_dev_handle; - int32_t csiphy_dev_handle; - - int32_t link_handle; - - int buf0_handle; - int buf_handle[FRAME_BUF_COUNT]; - int sync_objs[FRAME_BUF_COUNT]; - int request_ids[FRAME_BUF_COUNT]; - int request_id_last; - int frame_id_last; - int idx_offset; - bool skipped; - - CameraBuf buf; - MemoryManager mm; - - void config_isp(int io_mem_handle, int fence, int request_id, int buf0_mem_handle, int buf0_offset); - void enqueue_req_multi(int start, int n, bool dp); - void enqueue_buffer(int i, bool dp); - int clear_req_queue(); - - int sensors_init(); - void sensors_poke(int request_id); - void sensors_i2c(const struct i2c_random_wr_payload* dat, int len, int op_code, bool data_word); - -private: - // for debugging - Params params; -}; - -typedef struct MultiCameraState { - unique_fd video0_fd; - unique_fd cam_sync_fd; - unique_fd isp_fd; - int device_iommu; - int cdm_iommu; - - CameraState road_cam; - CameraState wide_road_cam; - CameraState driver_cam; - - PubMaster *pm; -} MultiCameraState; diff --git a/system/camerad/cameras/camera_util.cc b/system/camerad/cameras/camera_util.cc deleted file mode 100644 index 4fe3899..0000000 --- a/system/camerad/cameras/camera_util.cc +++ /dev/null @@ -1,138 +0,0 @@ -#include "system/camerad/cameras/camera_util.h" - -#include - -#include - -#include -#include - -#include "common/swaglog.h" -#include "common/util.h" - -// ************** low level camera helpers **************** -int do_cam_control(int fd, int op_code, void *handle, int size) { - struct cam_control camcontrol = {0}; - camcontrol.op_code = op_code; - camcontrol.handle = (uint64_t)handle; - if (size == 0) { - camcontrol.size = 8; - camcontrol.handle_type = CAM_HANDLE_MEM_HANDLE; - } else { - camcontrol.size = size; - camcontrol.handle_type = CAM_HANDLE_USER_POINTER; - } - - int ret = HANDLE_EINTR(ioctl(fd, VIDIOC_CAM_CONTROL, &camcontrol)); - if (ret == -1) { - LOGE("VIDIOC_CAM_CONTROL error: op_code %d - errno %d", op_code, errno); - } - return ret; -} - -std::optional device_acquire(int fd, int32_t session_handle, void *data, uint32_t num_resources) { - struct cam_acquire_dev_cmd cmd = { - .session_handle = session_handle, - .handle_type = CAM_HANDLE_USER_POINTER, - .num_resources = (uint32_t)(data ? num_resources : 0), - .resource_hdl = (uint64_t)data, - }; - int err = do_cam_control(fd, CAM_ACQUIRE_DEV, &cmd, sizeof(cmd)); - return err == 0 ? std::make_optional(cmd.dev_handle) : std::nullopt; -} - -int device_config(int fd, int32_t session_handle, int32_t dev_handle, uint64_t packet_handle) { - struct cam_config_dev_cmd cmd = { - .session_handle = session_handle, - .dev_handle = dev_handle, - .packet_handle = packet_handle, - }; - return do_cam_control(fd, CAM_CONFIG_DEV, &cmd, sizeof(cmd)); -} - -int device_control(int fd, int op_code, int session_handle, int dev_handle) { - // start stop and release are all the same - struct cam_start_stop_dev_cmd cmd { .session_handle = session_handle, .dev_handle = dev_handle }; - return do_cam_control(fd, op_code, &cmd, sizeof(cmd)); -} - -void *alloc_w_mmu_hdl(int video0_fd, int len, uint32_t *handle, int align, int flags, int mmu_hdl, int mmu_hdl2) { - struct cam_mem_mgr_alloc_cmd mem_mgr_alloc_cmd = {0}; - mem_mgr_alloc_cmd.len = len; - mem_mgr_alloc_cmd.align = align; - mem_mgr_alloc_cmd.flags = flags; - mem_mgr_alloc_cmd.num_hdl = 0; - if (mmu_hdl != 0) { - mem_mgr_alloc_cmd.mmu_hdls[0] = mmu_hdl; - mem_mgr_alloc_cmd.num_hdl++; - } - if (mmu_hdl2 != 0) { - mem_mgr_alloc_cmd.mmu_hdls[1] = mmu_hdl2; - mem_mgr_alloc_cmd.num_hdl++; - } - - do_cam_control(video0_fd, CAM_REQ_MGR_ALLOC_BUF, &mem_mgr_alloc_cmd, sizeof(mem_mgr_alloc_cmd)); - *handle = mem_mgr_alloc_cmd.out.buf_handle; - - void *ptr = NULL; - if (mem_mgr_alloc_cmd.out.fd > 0) { - ptr = mmap(NULL, len, PROT_READ | PROT_WRITE, MAP_SHARED, mem_mgr_alloc_cmd.out.fd, 0); - assert(ptr != MAP_FAILED); - } - - // LOGD("allocated: %x %d %llx mapped %p", mem_mgr_alloc_cmd.out.buf_handle, mem_mgr_alloc_cmd.out.fd, mem_mgr_alloc_cmd.out.vaddr, ptr); - - return ptr; -} - -void release(int video0_fd, uint32_t handle) { - int ret; - struct cam_mem_mgr_release_cmd mem_mgr_release_cmd = {0}; - mem_mgr_release_cmd.buf_handle = handle; - - ret = do_cam_control(video0_fd, CAM_REQ_MGR_RELEASE_BUF, &mem_mgr_release_cmd, sizeof(mem_mgr_release_cmd)); - assert(ret == 0); -} - -void release_fd(int video0_fd, uint32_t handle) { - // handle to fd - close(handle>>16); - release(video0_fd, handle); -} - -void *MemoryManager::alloc_buf(int size, uint32_t *handle) { - lock.lock(); - void *ptr; - if (!cached_allocations[size].empty()) { - ptr = cached_allocations[size].front(); - cached_allocations[size].pop(); - *handle = handle_lookup[ptr]; - } else { - ptr = alloc_w_mmu_hdl(video0_fd, size, handle); - handle_lookup[ptr] = *handle; - size_lookup[ptr] = size; - } - lock.unlock(); - memset(ptr, 0, size); - return ptr; -} - -void MemoryManager::free(void *ptr) { - lock.lock(); - cached_allocations[size_lookup[ptr]].push(ptr); - lock.unlock(); -} - -MemoryManager::~MemoryManager() { - for (auto& x : cached_allocations) { - while (!x.second.empty()) { - void *ptr = x.second.front(); - x.second.pop(); - LOGD("freeing cached allocation %p with size %d", ptr, size_lookup[ptr]); - munmap(ptr, size_lookup[ptr]); - release_fd(video0_fd, handle_lookup[ptr]); - handle_lookup.erase(ptr); - size_lookup.erase(ptr); - } - } -} diff --git a/system/camerad/cameras/camera_util.h b/system/camerad/cameras/camera_util.h deleted file mode 100644 index 891ce3e..0000000 --- a/system/camerad/cameras/camera_util.h +++ /dev/null @@ -1,39 +0,0 @@ -#pragma once - -#include -#include -#include -#include -#include -#include - -#include - -std::optional device_acquire(int fd, int32_t session_handle, void *data, uint32_t num_resources=1); -int device_config(int fd, int32_t session_handle, int32_t dev_handle, uint64_t packet_handle); -int device_control(int fd, int op_code, int session_handle, int dev_handle); -int do_cam_control(int fd, int op_code, void *handle, int size); -void *alloc_w_mmu_hdl(int video0_fd, int len, uint32_t *handle, int align = 8, int flags = CAM_MEM_FLAG_KMD_ACCESS | CAM_MEM_FLAG_UMD_ACCESS | CAM_MEM_FLAG_CMD_BUF_TYPE, - int mmu_hdl = 0, int mmu_hdl2 = 0); -void release(int video0_fd, uint32_t handle); - -class MemoryManager { - public: - void init(int _video0_fd) { video0_fd = _video0_fd; } - ~MemoryManager(); - - template - auto alloc(int len, uint32_t *handle) { - return std::unique_ptr>((T*)alloc_buf(len, handle), [this](void *ptr) { this->free(ptr); }); - } - - private: - void *alloc_buf(int len, uint32_t *handle); - void free(void *ptr); - - std::mutex lock; - std::map handle_lookup; - std::map size_lookup; - std::map > cached_allocations; - int video0_fd; -}; diff --git a/system/camerad/main.cc b/system/camerad/main.cc deleted file mode 100644 index 19de21c..0000000 --- a/system/camerad/main.cc +++ /dev/null @@ -1,23 +0,0 @@ -#include "system/camerad/cameras/camera_common.h" - -#include - -#include "common/params.h" -#include "common/util.h" -#include "system/hardware/hw.h" - -int main(int argc, char *argv[]) { - if (Hardware::PC()) { - printf("exiting, camerad is not meant to run on PC\n"); - return 0; - } - - int ret; - ret = util::set_realtime_priority(53); - assert(ret == 0); - ret = util::set_core_affinity({6}); - assert(ret == 0 || Params().getBool("IsOffroad")); // failure ok while offroad due to offlining cores - - camerad_thread(); - return 0; -} diff --git a/system/camerad/sensors/ar0231.cc b/system/camerad/sensors/ar0231.cc deleted file mode 100644 index 1ca4b3f..0000000 --- a/system/camerad/sensors/ar0231.cc +++ /dev/null @@ -1,171 +0,0 @@ -#include - -#include "common/swaglog.h" -#include "system/camerad/cameras/camera_common.h" -#include "system/camerad/cameras/camera_qcom2.h" -#include "system/camerad/sensors/sensor.h" - -namespace { - -const size_t AR0231_REGISTERS_HEIGHT = 2; -// TODO: this extra height is universal and doesn't apply per camera -const size_t AR0231_STATS_HEIGHT = 2 + 8; - -const float sensor_analog_gains_AR0231[] = { - 1.0 / 8.0, 2.0 / 8.0, 2.0 / 7.0, 3.0 / 7.0, // 0, 1, 2, 3 - 3.0 / 6.0, 4.0 / 6.0, 4.0 / 5.0, 5.0 / 5.0, // 4, 5, 6, 7 - 5.0 / 4.0, 6.0 / 4.0, 6.0 / 3.0, 7.0 / 3.0, // 8, 9, 10, 11 - 7.0 / 2.0, 8.0 / 2.0, 8.0 / 1.0}; // 12, 13, 14, 15 = bypass - -std::map> ar0231_build_register_lut(CameraState *c, uint8_t *data) { - // This function builds a lookup table from register address, to a pair of indices in the - // buffer where to read this address. The buffer contains padding bytes, - // as well as markers to indicate the type of the next byte. - // - // 0xAA is used to indicate the MSB of the address, 0xA5 for the LSB of the address. - // Every byte of data (MSB and LSB) is preceded by 0x5A. Specifying an address is optional - // for contiguous ranges. See page 27-29 of the AR0231 Developer guide for more information. - - int max_i[] = {1828 / 2 * 3, 1500 / 2 * 3}; - auto get_next_idx = [](int cur_idx) { - return (cur_idx % 3 == 1) ? cur_idx + 2 : cur_idx + 1; // Every third byte is padding - }; - - std::map> registers; - for (int register_row = 0; register_row < 2; register_row++) { - uint8_t *registers_raw = data + c->ci->frame_stride * register_row; - assert(registers_raw[0] == 0x0a); // Start of line - - int value_tag_count = 0; - int first_val_idx = 0; - uint16_t cur_addr = 0; - - for (int i = 1; i <= max_i[register_row]; i = get_next_idx(get_next_idx(i))) { - int val_idx = get_next_idx(i); - - uint8_t tag = registers_raw[i]; - uint16_t val = registers_raw[val_idx]; - - if (tag == 0xAA) { // Register MSB tag - cur_addr = val << 8; - } else if (tag == 0xA5) { // Register LSB tag - cur_addr |= val; - cur_addr -= 2; // Next value tag will increment address again - } else if (tag == 0x5A) { // Value tag - - // First tag - if (value_tag_count % 2 == 0) { - cur_addr += 2; - first_val_idx = val_idx; - } else { - registers[cur_addr] = std::make_pair(first_val_idx + c->ci->frame_stride * register_row, val_idx + c->ci->frame_stride * register_row); - } - - value_tag_count++; - } - } - } - return registers; -} - -float ar0231_parse_temp_sensor(uint16_t calib1, uint16_t calib2, uint16_t data_reg) { - // See AR0231 Developer Guide - page 36 - float slope = (125.0 - 55.0) / ((float)calib1 - (float)calib2); - float t0 = 55.0 - slope * (float)calib2; - return t0 + slope * (float)data_reg; -} - -} // namespace - -AR0231::AR0231() { - image_sensor = cereal::FrameData::ImageSensor::AR0231; - data_word = true; - frame_width = FRAME_WIDTH; - frame_height = FRAME_HEIGHT; - frame_stride = FRAME_STRIDE; - extra_height = AR0231_REGISTERS_HEIGHT + AR0231_STATS_HEIGHT; - - registers_offset = 0; - frame_offset = AR0231_REGISTERS_HEIGHT; - stats_offset = AR0231_REGISTERS_HEIGHT + FRAME_HEIGHT; - - start_reg_array.assign(std::begin(start_reg_array_ar0231), std::end(start_reg_array_ar0231)); - init_reg_array.assign(std::begin(init_array_ar0231), std::end(init_array_ar0231)); - probe_reg_addr = 0x3000; - probe_expected_data = 0x354; - mipi_format = CAM_FORMAT_MIPI_RAW_12; - frame_data_type = 0x12; // Changing stats to 0x2C doesn't work, so change pixels to 0x12 instead - mclk_frequency = 19200000; //Hz - - dc_gain_factor = 2.5; - dc_gain_min_weight = 0; - dc_gain_max_weight = 1; - dc_gain_on_grey = 0.2; - dc_gain_off_grey = 0.3; - exposure_time_min = 2; // with HDR, fastest ss - exposure_time_max = 0x0855; // with HDR, slowest ss, 40ms - analog_gain_min_idx = 0x1; // 0.25x - analog_gain_rec_idx = 0x6; // 0.8x - analog_gain_max_idx = 0xD; // 4.0x - analog_gain_cost_delta = 0; - analog_gain_cost_low = 0.1; - analog_gain_cost_high = 5.0; - for (int i = 0; i <= analog_gain_max_idx; i++) { - sensor_analog_gains[i] = sensor_analog_gains_AR0231[i]; - } - min_ev = exposure_time_min * sensor_analog_gains[analog_gain_min_idx]; - max_ev = exposure_time_max * dc_gain_factor * sensor_analog_gains[analog_gain_max_idx]; - target_grey_factor = 1.0; -} - -void AR0231::processRegisters(CameraState *c, cereal::FrameData::Builder &framed) const { - const uint8_t expected_preamble[] = {0x0a, 0xaa, 0x55, 0x20, 0xa5, 0x55}; - uint8_t *data = (uint8_t *)c->buf.cur_camera_buf->addr + c->ci->registers_offset; - - if (memcmp(data, expected_preamble, std::size(expected_preamble)) != 0) { - LOGE("unexpected register data found"); - return; - } - - if (ar0231_register_lut.empty()) { - ar0231_register_lut = ar0231_build_register_lut(c, data); - } - std::map registers; - for (uint16_t addr : {0x2000, 0x2002, 0x20b0, 0x20b2, 0x30c6, 0x30c8, 0x30ca, 0x30cc}) { - auto offset = ar0231_register_lut[addr]; - registers[addr] = ((uint16_t)data[offset.first] << 8) | data[offset.second]; - } - - uint32_t frame_id = ((uint32_t)registers[0x2000] << 16) | registers[0x2002]; - framed.setFrameIdSensor(frame_id); - - float temp_0 = ar0231_parse_temp_sensor(registers[0x30c6], registers[0x30c8], registers[0x20b0]); - float temp_1 = ar0231_parse_temp_sensor(registers[0x30ca], registers[0x30cc], registers[0x20b2]); - framed.setTemperaturesC({temp_0, temp_1}); -} - - -std::vector AR0231::getExposureRegisters(int exposure_time, int new_exp_g, bool dc_gain_enabled) const { - uint16_t analog_gain_reg = 0xFF00 | (new_exp_g << 4) | new_exp_g; - return { - {0x3366, analog_gain_reg}, - {0x3362, (uint16_t)(dc_gain_enabled ? 0x1 : 0x0)}, - {0x3012, (uint16_t)exposure_time}, - }; -} - -int AR0231::getSlaveAddress(int port) const { - assert(port >= 0 && port <= 2); - return (int[]){0x20, 0x30, 0x20}[port]; -} - -float AR0231::getExposureScore(float desired_ev, int exp_t, int exp_g_idx, float exp_gain, int gain_idx) const { - // Cost of ev diff - float score = std::abs(desired_ev - (exp_t * exp_gain)) * 10; - // Cost of absolute gain - float m = exp_g_idx > analog_gain_rec_idx ? analog_gain_cost_high : analog_gain_cost_low; - score += std::abs(exp_g_idx - (int)analog_gain_rec_idx) * m; - // Cost of changing gain - score += std::abs(exp_g_idx - gain_idx) * (score + 1.0) / 10.0; - return score; -} diff --git a/system/camerad/sensors/ar0231_registers.h b/system/camerad/sensors/ar0231_registers.h deleted file mode 100644 index 6c4c251..0000000 --- a/system/camerad/sensors/ar0231_registers.h +++ /dev/null @@ -1,119 +0,0 @@ -#pragma once - -const struct i2c_random_wr_payload start_reg_array_ar0231[] = {{0x301A, 0x91C}}; -const struct i2c_random_wr_payload stop_reg_array_ar0231[] = {{0x301A, 0x918}}; - -const struct i2c_random_wr_payload init_array_ar0231[] = { - {0x301A, 0x0018}, // RESET_REGISTER - - // CLOCK Settings - // input clock is 19.2 / 2 * 0x37 = 528 MHz - // pixclk is 528 / 6 = 88 MHz - // full roll time is 1000/(PIXCLK/(LINE_LENGTH_PCK*FRAME_LENGTH_LINES)) = 39.99 ms - // img roll time is 1000/(PIXCLK/(LINE_LENGTH_PCK*Y_OUTPUT_CONTROL)) = 22.85 ms - {0x302A, 0x0006}, // VT_PIX_CLK_DIV - {0x302C, 0x0001}, // VT_SYS_CLK_DIV - {0x302E, 0x0002}, // PRE_PLL_CLK_DIV - {0x3030, 0x0037}, // PLL_MULTIPLIER - {0x3036, 0x000C}, // OP_PIX_CLK_DIV - {0x3038, 0x0001}, // OP_SYS_CLK_DIV - - // FORMAT - {0x3040, 0xC000}, // READ_MODE - {0x3004, 0x0000}, // X_ADDR_START_ - {0x3008, 0x0787}, // X_ADDR_END_ - {0x3002, 0x0000}, // Y_ADDR_START_ - {0x3006, 0x04B7}, // Y_ADDR_END_ - {0x3032, 0x0000}, // SCALING_MODE - {0x30A2, 0x0001}, // X_ODD_INC_ - {0x30A6, 0x0001}, // Y_ODD_INC_ - {0x3402, 0x0788}, // X_OUTPUT_CONTROL - {0x3404, 0x04B8}, // Y_OUTPUT_CONTROL - {0x3064, 0x1982}, // SMIA_TEST - {0x30BA, 0x11F2}, // DIGITAL_CTRL - - // Enable external trigger and disable GPIO outputs - {0x30CE, 0x0120}, // SLAVE_SH_SYNC_MODE | FRAME_START_MODE - {0x340A, 0xE0}, // GPIO3_INPUT_DISABLE | GPIO2_INPUT_DISABLE | GPIO1_INPUT_DISABLE - {0x340C, 0x802}, // GPIO_HIDRV_EN | GPIO0_ISEL=2 - - // Readout timing - {0x300C, 0x0672}, // LINE_LENGTH_PCK (valid for 3-exposure HDR) - {0x300A, 0x0855}, // FRAME_LENGTH_LINES - {0x3042, 0x0000}, // EXTRA_DELAY - - // Readout Settings - {0x31AE, 0x0204}, // SERIAL_FORMAT, 4-lane MIPI - {0x31AC, 0x0C0C}, // DATA_FORMAT_BITS, 12 -> 12 - {0x3342, 0x1212}, // MIPI_F1_PDT_EDT - {0x3346, 0x1212}, // MIPI_F2_PDT_EDT - {0x334A, 0x1212}, // MIPI_F3_PDT_EDT - {0x334E, 0x1212}, // MIPI_F4_PDT_EDT - {0x3344, 0x0011}, // MIPI_F1_VDT_VC - {0x3348, 0x0111}, // MIPI_F2_VDT_VC - {0x334C, 0x0211}, // MIPI_F3_VDT_VC - {0x3350, 0x0311}, // MIPI_F4_VDT_VC - {0x31B0, 0x0053}, // FRAME_PREAMBLE - {0x31B2, 0x003B}, // LINE_PREAMBLE - {0x301A, 0x001C}, // RESET_REGISTER - - // Noise Corrections - {0x3092, 0x0C24}, // ROW_NOISE_CONTROL - {0x337A, 0x0C80}, // DBLC_SCALE0 - {0x3370, 0x03B1}, // DBLC - {0x3044, 0x0400}, // DARK_CONTROL - - // Enable temperature sensor - {0x30B4, 0x0007}, // TEMPSENS0_CTRL_REG - {0x30B8, 0x0007}, // TEMPSENS1_CTRL_REG - - // Enable dead pixel correction using - // the 1D line correction scheme - {0x31E0, 0x0003}, - - // HDR Settings - {0x3082, 0x0004}, // OPERATION_MODE_CTRL - {0x3238, 0x0444}, // EXPOSURE_RATIO - - {0x1008, 0x0361}, // FINE_INTEGRATION_TIME_MIN - {0x100C, 0x0589}, // FINE_INTEGRATION_TIME2_MIN - {0x100E, 0x07B1}, // FINE_INTEGRATION_TIME3_MIN - {0x1010, 0x0139}, // FINE_INTEGRATION_TIME4_MIN - - // TODO: do these have to be lower than LINE_LENGTH_PCK? - {0x3014, 0x08CB}, // FINE_INTEGRATION_TIME_ - {0x321E, 0x0894}, // FINE_INTEGRATION_TIME2 - - {0x31D0, 0x0000}, // COMPANDING, no good in 10 bit? - {0x33DA, 0x0000}, // COMPANDING - {0x318E, 0x0200}, // PRE_HDR_GAIN_EN - - // DLO Settings - {0x3100, 0x4000}, // DLO_CONTROL0 - {0x3280, 0x0CCC}, // T1 G1 - {0x3282, 0x0CCC}, // T1 R - {0x3284, 0x0CCC}, // T1 B - {0x3286, 0x0CCC}, // T1 G2 - {0x3288, 0x0FA0}, // T2 G1 - {0x328A, 0x0FA0}, // T2 R - {0x328C, 0x0FA0}, // T2 B - {0x328E, 0x0FA0}, // T2 G2 - - // Initial Gains - {0x3022, 0x0001}, // GROUPED_PARAMETER_HOLD_ - {0x3366, 0xFF77}, // ANALOG_GAIN (1x) - - {0x3060, 0x3333}, // ANALOG_COLOR_GAIN - - {0x3362, 0x0000}, // DC GAIN - - {0x305A, 0x00F8}, // red gain - {0x3058, 0x0122}, // blue gain - {0x3056, 0x009A}, // g1 gain - {0x305C, 0x009A}, // g2 gain - - {0x3022, 0x0000}, // GROUPED_PARAMETER_HOLD_ - - // Initial Integration Time - {0x3012, 0x0005}, -}; diff --git a/system/camerad/sensors/os04c10.cc b/system/camerad/sensors/os04c10.cc deleted file mode 100644 index 449e06b..0000000 --- a/system/camerad/sensors/os04c10.cc +++ /dev/null @@ -1,105 +0,0 @@ -#include "system/camerad/sensors/sensor.h" - -namespace { - -const float sensor_analog_gains_OS04C10[] = { - 1.0, 1.0625, 1.125, 1.1875, 1.25, 1.3125, 1.375, 1.4375, 1.5, 1.5625, 1.6875, - 1.8125, 1.9375, 2.0, 2.125, 2.25, 2.375, 2.5, 2.625, 2.75, 2.875, 3.0, - 3.125, 3.375, 3.625, 3.875, 4.0, 4.25, 4.5, 4.75, 5.0, 5.25, 5.5, - 5.75, 6.0, 6.25, 6.5, 7.0, 7.5, 8.0, 8.5, 9.0, 9.5, 10.0, - 10.5, 11.0, 11.5, 12.0, 12.5, 13.0, 13.5, 14.0, 14.5, 15.0, 15.5}; - -const uint32_t os04c10_analog_gains_reg[] = { - 0x100, 0x110, 0x120, 0x130, 0x140, 0x150, 0x160, 0x170, 0x180, 0x190, 0x1B0, - 0x1D0, 0x1F0, 0x200, 0x220, 0x240, 0x260, 0x280, 0x2A0, 0x2C0, 0x2E0, 0x300, - 0x320, 0x360, 0x3A0, 0x3E0, 0x400, 0x440, 0x480, 0x4C0, 0x500, 0x540, 0x580, - 0x5C0, 0x600, 0x640, 0x680, 0x700, 0x780, 0x800, 0x880, 0x900, 0x980, 0xA00, - 0xA80, 0xB00, 0xB80, 0xC00, 0xC80, 0xD00, 0xD80, 0xE00, 0xE80, 0xF00, 0xF80}; - -const uint32_t VS_TIME_MIN_OS04C10 = 1; -//const uint32_t VS_TIME_MAX_OS04C10 = 34; // vs < 35 - -} // namespace - -OS04C10::OS04C10() { - image_sensor = cereal::FrameData::ImageSensor::OS04C10; - data_word = false; - - frame_width = 1920; - frame_height = 1080; - frame_stride = (1920*10/8); - - /* - frame_width = 0xa80; - frame_height = 0x5f0; - frame_stride = 0xd20; - */ - - extra_height = 0; - frame_offset = 0; - - start_reg_array.assign(std::begin(start_reg_array_os04c10), std::end(start_reg_array_os04c10)); - init_reg_array.assign(std::begin(init_array_os04c10), std::end(init_array_os04c10)); - probe_reg_addr = 0x300a; - probe_expected_data = 0x5304; - mipi_format = CAM_FORMAT_MIPI_RAW_10; - frame_data_type = 0x2b; - mclk_frequency = 24000000; // Hz - - dc_gain_factor = 7.32; - dc_gain_min_weight = 1; // always on is fine - dc_gain_max_weight = 1; - dc_gain_on_grey = 0.9; - dc_gain_off_grey = 1.0; - exposure_time_min = 2; // 1x - exposure_time_max = 2016; - analog_gain_min_idx = 0x0; - analog_gain_rec_idx = 0x0; // 1x - analog_gain_max_idx = 0x36; - analog_gain_cost_delta = -1; - analog_gain_cost_low = 0.4; - analog_gain_cost_high = 6.4; - for (int i = 0; i <= analog_gain_max_idx; i++) { - sensor_analog_gains[i] = sensor_analog_gains_OS04C10[i]; - } - min_ev = (exposure_time_min + VS_TIME_MIN_OS04C10) * sensor_analog_gains[analog_gain_min_idx]; - max_ev = exposure_time_max * dc_gain_factor * sensor_analog_gains[analog_gain_max_idx]; - target_grey_factor = 0.01; -} - -std::vector OS04C10::getExposureRegisters(int exposure_time, int new_exp_g, bool dc_gain_enabled) const { - // t_HCG&t_LCG + t_VS on LPD, t_SPD on SPD - uint32_t hcg_time = exposure_time; - //uint32_t lcg_time = hcg_time; - //uint32_t spd_time = std::min(std::max((uint32_t)exposure_time, (exposure_time_max + VS_TIME_MAX_OS04C10) / 3), exposure_time_max + VS_TIME_MAX_OS04C10); - //uint32_t vs_time = std::min(std::max((uint32_t)exposure_time / 40, VS_TIME_MIN_OS04C10), VS_TIME_MAX_OS04C10); - - uint32_t real_gain = os04c10_analog_gains_reg[new_exp_g]; - - hcg_time = 100; - real_gain = 0x320; - - return { - {0x3501, hcg_time>>8}, {0x3502, hcg_time&0xFF}, - //{0x3581, lcg_time>>8}, {0x3582, lcg_time&0xFF}, - //{0x3541, spd_time>>8}, {0x3542, spd_time&0xFF}, - //{0x35c2, vs_time&0xFF}, - - {0x3508, real_gain>>8}, {0x3509, real_gain&0xFF}, - }; -} - -int OS04C10::getSlaveAddress(int port) const { - assert(port >= 0 && port <= 2); - return (int[]){0x6C, 0x20, 0x6C}[port]; -} - -float OS04C10::getExposureScore(float desired_ev, int exp_t, int exp_g_idx, float exp_gain, int gain_idx) const { - float score = std::abs(desired_ev - (exp_t * exp_gain)); - float m = exp_g_idx > analog_gain_rec_idx ? analog_gain_cost_high : analog_gain_cost_low; - score += std::abs(exp_g_idx - (int)analog_gain_rec_idx) * m; - score += ((1 - analog_gain_cost_delta) + - analog_gain_cost_delta * (exp_g_idx - analog_gain_min_idx) / (analog_gain_max_idx - analog_gain_min_idx)) * - std::abs(exp_g_idx - gain_idx) * 5.0; - return score; -} diff --git a/system/camerad/sensors/os04c10_registers.h b/system/camerad/sensors/os04c10_registers.h deleted file mode 100644 index ad91a02..0000000 --- a/system/camerad/sensors/os04c10_registers.h +++ /dev/null @@ -1,298 +0,0 @@ -#pragma once - -const struct i2c_random_wr_payload start_reg_array_os04c10[] = {{0x100, 1}}; -const struct i2c_random_wr_payload stop_reg_array_os04c10[] = {{0x100, 0}}; - -const struct i2c_random_wr_payload init_array_os04c10[] = { - // OS04C10_AA_00_02_17_wAO_1920x1080_MIPI728Mbps_Linear12bit_20FPS_4Lane_MCLK24MHz - {0x0103, 0x01}, - {0x0301, 0x84}, - {0x0303, 0x01}, - {0x0305, 0x5b}, - {0x0306, 0x01}, - {0x0307, 0x17}, - {0x0323, 0x04}, - {0x0324, 0x01}, - {0x0325, 0x62}, - {0x3012, 0x06}, - {0x3013, 0x02}, - {0x3016, 0x72}, - {0x3021, 0x03}, - {0x3106, 0x21}, - {0x3107, 0xa1}, - {0x3500, 0x00}, - {0x3501, 0x00}, - {0x3502, 0x40}, - {0x3503, 0x88}, - {0x3508, 0x07}, - {0x3509, 0xc0}, - {0x350a, 0x04}, - {0x350b, 0x00}, - {0x350c, 0x07}, - {0x350d, 0xc0}, - {0x350e, 0x04}, - {0x350f, 0x00}, - {0x3510, 0x00}, - {0x3511, 0x00}, - {0x3512, 0x20}, - {0x3624, 0x00}, - {0x3625, 0x4c}, - {0x3660, 0x00}, - {0x3666, 0xa5}, - {0x3667, 0xa5}, - {0x366a, 0x64}, - {0x3673, 0x0d}, - {0x3672, 0x0d}, - {0x3671, 0x0d}, - {0x3670, 0x0d}, - {0x3685, 0x00}, - {0x3694, 0x0d}, - {0x3693, 0x0d}, - {0x3692, 0x0d}, - {0x3691, 0x0d}, - {0x3696, 0x4c}, - {0x3697, 0x4c}, - {0x3698, 0x40}, - {0x3699, 0x80}, - {0x369a, 0x18}, - {0x369b, 0x1f}, - {0x369c, 0x14}, - {0x369d, 0x80}, - {0x369e, 0x40}, - {0x369f, 0x21}, - {0x36a0, 0x12}, - {0x36a1, 0x5d}, - {0x36a2, 0x66}, - {0x370a, 0x00}, - {0x370e, 0x0c}, - {0x3710, 0x00}, - {0x3713, 0x00}, - {0x3725, 0x02}, - {0x372a, 0x03}, - {0x3738, 0xce}, - {0x3748, 0x00}, - {0x374a, 0x00}, - {0x374c, 0x00}, - {0x374e, 0x00}, - {0x3756, 0x00}, - {0x3757, 0x0e}, - {0x3767, 0x00}, - {0x3771, 0x00}, - {0x377b, 0x20}, - {0x377c, 0x00}, - {0x377d, 0x0c}, - {0x3781, 0x03}, - {0x3782, 0x00}, - {0x3789, 0x14}, - {0x3795, 0x02}, - {0x379c, 0x00}, - {0x379d, 0x00}, - {0x37b8, 0x04}, - {0x37ba, 0x03}, - {0x37bb, 0x00}, - {0x37bc, 0x04}, - {0x37be, 0x08}, - {0x37c4, 0x11}, - {0x37c5, 0x80}, - {0x37c6, 0x14}, - {0x37c7, 0x08}, - {0x37da, 0x11}, - {0x381f, 0x08}, - {0x3829, 0x03}, - {0x3881, 0x00}, - {0x3888, 0x04}, - {0x388b, 0x00}, - {0x3c80, 0x10}, - {0x3c86, 0x00}, - {0x3c8c, 0x20}, - {0x3c9f, 0x01}, - {0x3d85, 0x1b}, - {0x3d8c, 0x71}, - {0x3d8d, 0xe2}, - {0x3f00, 0x0b}, - {0x3f06, 0x04}, - {0x400a, 0x01}, - {0x400b, 0x50}, - {0x400e, 0x08}, - {0x4043, 0x7e}, - {0x4045, 0x7e}, - {0x4047, 0x7e}, - {0x4049, 0x7e}, - {0x4090, 0x14}, - {0x40b0, 0x00}, - {0x40b1, 0x00}, - {0x40b2, 0x00}, - {0x40b3, 0x00}, - {0x40b4, 0x00}, - {0x40b5, 0x00}, - {0x40b7, 0x00}, - {0x40b8, 0x00}, - {0x40b9, 0x00}, - {0x40ba, 0x00}, - {0x4301, 0x00}, - {0x4303, 0x00}, - {0x4502, 0x04}, - {0x4503, 0x00}, - {0x4504, 0x06}, - {0x4506, 0x00}, - {0x4507, 0x64}, - {0x4803, 0x00}, - {0x480c, 0x32}, - {0x480e, 0x00}, - {0x4813, 0x00}, - {0x4819, 0x70}, - {0x481f, 0x30}, - {0x4823, 0x3f}, - {0x4825, 0x30}, - {0x4833, 0x10}, - {0x484b, 0x07}, - {0x488b, 0x00}, - {0x4d00, 0x04}, - {0x4d01, 0xad}, - {0x4d02, 0xbc}, - {0x4d03, 0xa1}, - {0x4d04, 0x1f}, - {0x4d05, 0x4c}, - {0x4d0b, 0x01}, - {0x4e00, 0x2a}, - {0x4e0d, 0x00}, - {0x5001, 0x09}, - {0x5004, 0x00}, - {0x5080, 0x04}, - {0x5036, 0x00}, - {0x5180, 0x70}, - {0x5181, 0x10}, - {0x520a, 0x03}, - {0x520b, 0x06}, - {0x520c, 0x0c}, - {0x580b, 0x0f}, - {0x580d, 0x00}, - {0x580f, 0x00}, - {0x5820, 0x00}, - {0x5821, 0x00}, - {0x301c, 0xf8}, - {0x301e, 0xb4}, - {0x301f, 0xd0}, - {0x3022, 0x01}, - {0x3109, 0xe7}, - {0x3600, 0x00}, - {0x3610, 0x65}, - {0x3611, 0x85}, - {0x3613, 0x3a}, - {0x3615, 0x60}, - {0x3621, 0x90}, - {0x3620, 0x0c}, - {0x3629, 0x00}, - {0x3661, 0x04}, - {0x3664, 0x70}, - {0x3665, 0x00}, - {0x3681, 0xa6}, - {0x3682, 0x53}, - {0x3683, 0x2a}, - {0x3684, 0x15}, - {0x3700, 0x2a}, - {0x3701, 0x12}, - {0x3703, 0x28}, - {0x3704, 0x0e}, - {0x3706, 0x4a}, - {0x3709, 0x4a}, - {0x370b, 0xa2}, - {0x370c, 0x01}, - {0x370f, 0x04}, - {0x3714, 0x24}, - {0x3716, 0x04}, - {0x3719, 0x11}, - {0x371a, 0x1e}, - {0x3720, 0x00}, - {0x3724, 0x13}, - {0x373f, 0xb0}, - {0x3741, 0x4a}, - {0x3743, 0x4a}, - {0x3745, 0x4a}, - {0x3747, 0x4a}, - {0x3749, 0xa2}, - {0x374b, 0xa2}, - {0x374d, 0xa2}, - {0x374f, 0xa2}, - {0x3755, 0x10}, - {0x376c, 0x00}, - {0x378d, 0x30}, - {0x3790, 0x4a}, - {0x3791, 0xa2}, - {0x3798, 0x40}, - {0x379e, 0x00}, - {0x379f, 0x04}, - {0x37a1, 0x10}, - {0x37a2, 0x1e}, - {0x37a8, 0x10}, - {0x37a9, 0x1e}, - {0x37ac, 0xa0}, - {0x37b9, 0x01}, - {0x37bd, 0x01}, - {0x37bf, 0x26}, - {0x37c0, 0x11}, - {0x37c2, 0x04}, - {0x37cd, 0x19}, - {0x37e0, 0x08}, - {0x37e6, 0x04}, - {0x37e5, 0x02}, - {0x37e1, 0x0c}, - {0x3737, 0x04}, - {0x37d8, 0x02}, - {0x37e2, 0x10}, - {0x3739, 0x10}, - {0x3662, 0x10}, - {0x37e4, 0x20}, - {0x37e3, 0x08}, - {0x37d9, 0x08}, - {0x4040, 0x00}, - {0x4041, 0x07}, - {0x4008, 0x02}, - {0x4009, 0x0d}, - {0x3800, 0x01}, - {0x3801, 0x80}, - {0x3802, 0x00}, - {0x3803, 0xdc}, - {0x3804, 0x09}, - {0x3805, 0x0f}, - {0x3806, 0x05}, - {0x3807, 0x23}, - {0x3808, 0x07}, - {0x3809, 0x80}, - {0x380a, 0x04}, - {0x380b, 0x38}, - {0x380c, 0x04}, - {0x380d, 0x2e}, - {0x380e, 0x12}, - {0x380f, 0x70}, - {0x3811, 0x08}, - {0x3813, 0x08}, - {0x3814, 0x01}, - {0x3815, 0x01}, - {0x3816, 0x01}, - {0x3817, 0x01}, - {0x3820, 0xB0}, - {0x3821, 0x00}, - {0x3880, 0x25}, - {0x3882, 0x20}, - {0x3c91, 0x0b}, - {0x3c94, 0x45}, - {0x3cad, 0x00}, - {0x3cae, 0x00}, - {0x4000, 0xf3}, - {0x4001, 0x60}, - {0x4003, 0x40}, - {0x4300, 0xff}, - {0x4302, 0x0f}, - {0x4305, 0x83}, - {0x4505, 0x84}, - {0x4809, 0x1e}, - {0x480a, 0x04}, - {0x4837, 0x15}, - {0x4c00, 0x08}, - {0x4c01, 0x08}, - {0x4c04, 0x00}, - {0x4c05, 0x00}, - {0x5000, 0xf9}, - {0x3c8c, 0x10}, -}; diff --git a/system/camerad/sensors/ox03c10.cc b/system/camerad/sensors/ox03c10.cc deleted file mode 100644 index 1f06098..0000000 --- a/system/camerad/sensors/ox03c10.cc +++ /dev/null @@ -1,94 +0,0 @@ -#include "system/camerad/sensors/sensor.h" - -namespace { - -const float sensor_analog_gains_OX03C10[] = { - 1.0, 1.0625, 1.125, 1.1875, 1.25, 1.3125, 1.375, 1.4375, 1.5, 1.5625, 1.6875, - 1.8125, 1.9375, 2.0, 2.125, 2.25, 2.375, 2.5, 2.625, 2.75, 2.875, 3.0, - 3.125, 3.375, 3.625, 3.875, 4.0, 4.25, 4.5, 4.75, 5.0, 5.25, 5.5, - 5.75, 6.0, 6.25, 6.5, 7.0, 7.5, 8.0, 8.5, 9.0, 9.5, 10.0, - 10.5, 11.0, 11.5, 12.0, 12.5, 13.0, 13.5, 14.0, 14.5, 15.0, 15.5}; - -const uint32_t ox03c10_analog_gains_reg[] = { - 0x100, 0x110, 0x120, 0x130, 0x140, 0x150, 0x160, 0x170, 0x180, 0x190, 0x1B0, - 0x1D0, 0x1F0, 0x200, 0x220, 0x240, 0x260, 0x280, 0x2A0, 0x2C0, 0x2E0, 0x300, - 0x320, 0x360, 0x3A0, 0x3E0, 0x400, 0x440, 0x480, 0x4C0, 0x500, 0x540, 0x580, - 0x5C0, 0x600, 0x640, 0x680, 0x700, 0x780, 0x800, 0x880, 0x900, 0x980, 0xA00, - 0xA80, 0xB00, 0xB80, 0xC00, 0xC80, 0xD00, 0xD80, 0xE00, 0xE80, 0xF00, 0xF80}; - -const uint32_t VS_TIME_MIN_OX03C10 = 1; -const uint32_t VS_TIME_MAX_OX03C10 = 34; // vs < 35 - -} // namespace - -OX03C10::OX03C10() { - image_sensor = cereal::FrameData::ImageSensor::OX03C10; - data_word = false; - frame_width = FRAME_WIDTH; - frame_height = FRAME_HEIGHT; - frame_stride = FRAME_STRIDE; // (0xa80*12//8) - extra_height = 16; // top 2 + bot 14 - frame_offset = 2; - - start_reg_array.assign(std::begin(start_reg_array_ox03c10), std::end(start_reg_array_ox03c10)); - init_reg_array.assign(std::begin(init_array_ox03c10), std::end(init_array_ox03c10)); - probe_reg_addr = 0x300a; - probe_expected_data = 0x5803; - mipi_format = CAM_FORMAT_MIPI_RAW_12; - frame_data_type = 0x2c; // one is 0x2a, two are 0x2b - mclk_frequency = 24000000; //Hz - - dc_gain_factor = 7.32; - dc_gain_min_weight = 1; // always on is fine - dc_gain_max_weight = 1; - dc_gain_on_grey = 0.9; - dc_gain_off_grey = 1.0; - exposure_time_min = 2; // 1x - exposure_time_max = 2016; - analog_gain_min_idx = 0x0; - analog_gain_rec_idx = 0x0; // 1x - analog_gain_max_idx = 0x36; - analog_gain_cost_delta = -1; - analog_gain_cost_low = 0.4; - analog_gain_cost_high = 6.4; - for (int i = 0; i <= analog_gain_max_idx; i++) { - sensor_analog_gains[i] = sensor_analog_gains_OX03C10[i]; - } - min_ev = (exposure_time_min + VS_TIME_MIN_OX03C10) * sensor_analog_gains[analog_gain_min_idx]; - max_ev = exposure_time_max * dc_gain_factor * sensor_analog_gains[analog_gain_max_idx]; - target_grey_factor = 0.01; -} - -std::vector OX03C10::getExposureRegisters(int exposure_time, int new_exp_g, bool dc_gain_enabled) const { - // t_HCG&t_LCG + t_VS on LPD, t_SPD on SPD - uint32_t hcg_time = exposure_time; - uint32_t lcg_time = hcg_time; - uint32_t spd_time = std::min(std::max((uint32_t)exposure_time, (exposure_time_max + VS_TIME_MAX_OX03C10) / 3), exposure_time_max + VS_TIME_MAX_OX03C10); - uint32_t vs_time = std::min(std::max((uint32_t)exposure_time / 40, VS_TIME_MIN_OX03C10), VS_TIME_MAX_OX03C10); - - uint32_t real_gain = ox03c10_analog_gains_reg[new_exp_g]; - - return { - {0x3501, hcg_time>>8}, {0x3502, hcg_time&0xFF}, - {0x3581, lcg_time>>8}, {0x3582, lcg_time&0xFF}, - {0x3541, spd_time>>8}, {0x3542, spd_time&0xFF}, - {0x35c2, vs_time&0xFF}, - - {0x3508, real_gain>>8}, {0x3509, real_gain&0xFF}, - }; -} - -int OX03C10::getSlaveAddress(int port) const { - assert(port >= 0 && port <= 2); - return (int[]){0x6C, 0x20, 0x6C}[port]; -} - -float OX03C10::getExposureScore(float desired_ev, int exp_t, int exp_g_idx, float exp_gain, int gain_idx) const { - float score = std::abs(desired_ev - (exp_t * exp_gain)); - float m = exp_g_idx > analog_gain_rec_idx ? analog_gain_cost_high : analog_gain_cost_low; - score += std::abs(exp_g_idx - (int)analog_gain_rec_idx) * m; - score += ((1 - analog_gain_cost_delta) + - analog_gain_cost_delta * (exp_g_idx - analog_gain_min_idx) / (analog_gain_max_idx - analog_gain_min_idx)) * - std::abs(exp_g_idx - gain_idx) * 5.0; - return score; -} diff --git a/system/camerad/sensors/ox03c10_registers.h b/system/camerad/sensors/ox03c10_registers.h deleted file mode 100644 index 575a2cb..0000000 --- a/system/camerad/sensors/ox03c10_registers.h +++ /dev/null @@ -1,761 +0,0 @@ -#pragma once - -const struct i2c_random_wr_payload start_reg_array_ox03c10[] = {{0x100, 1}}; -const struct i2c_random_wr_payload stop_reg_array_ox03c10[] = {{0x100, 0}}; - -const struct i2c_random_wr_payload init_array_ox03c10[] = { - {0x103, 1}, - {0x107, 1}, - - // X3C_1920x1280_60fps_HDR4_LFR_PWL12_mipi1200 - - // TPM - {0x4d5a, 0x1a}, {0x4d09, 0xff}, {0x4d09, 0xdf}, - - /*) - // group 4 - {0x3208, 0x04}, - {0x4620, 0x04}, - {0x3208, 0x14}, - - // group 5 - {0x3208, 0x05}, - {0x4620, 0x04}, - {0x3208, 0x15}, - - // group 2 - {0x3208, 0x02}, - {0x3507, 0x00}, - {0x3208, 0x12}, - - // delay launch group 2 - {0x3208, 0xa2},*/ - - // PLL setup - {0x0301, 0xc8}, // pll1_divs, pll1_predivp, pll1_divpix - {0x0303, 0x01}, // pll1_prediv - {0x0304, 0x01}, {0x0305, 0x2c}, // pll1_loopdiv = 300 - {0x0306, 0x04}, // pll1_divmipi = 4 - {0x0307, 0x01}, // pll1_divm = 1 - {0x0316, 0x00}, - {0x0317, 0x00}, - {0x0318, 0x00}, - {0x0323, 0x05}, // pll2_prediv - {0x0324, 0x01}, {0x0325, 0x2c}, // pll2_divp = 300 - - // SCLK/PCLK - {0x0400, 0xe0}, {0x0401, 0x80}, - {0x0403, 0xde}, {0x0404, 0x34}, - {0x0405, 0x3b}, {0x0406, 0xde}, - {0x0407, 0x08}, - {0x0408, 0xe0}, {0x0409, 0x7f}, - {0x040a, 0xde}, {0x040b, 0x34}, - {0x040c, 0x47}, {0x040d, 0xd8}, - {0x040e, 0x08}, - - // xchk - {0x2803, 0xfe}, {0x280b, 0x00}, {0x280c, 0x79}, - - // SC ctrl - {0x3001, 0x03}, // io_pad_oen - {0x3002, 0xfc}, // io_pad_oen - {0x3005, 0x80}, // io_pad_out - {0x3007, 0x01}, // io_pad_sel - {0x3008, 0x80}, // io_pad_sel - - // FSIN first frame - /* - {0x3009, 0x2}, - {0x3015, 0x2}, - {0x3822, 0x20}, - {0x3823, 0x58}, - - {0x3826, 0x0}, {0x3827, 0x8}, - {0x3881, 0x4}, - - {0x3882, 0x8}, {0x3883, 0x0D}, - {0x3836, 0x1F}, {0x3837, 0x40}, - */ - - // FSIN with external pulses - {0x3009, 0x2}, - {0x3015, 0x2}, - {0x383E, 0x80}, - {0x3881, 0x4}, - {0x3882, 0x8}, {0x3883, 0x0D}, - {0x3836, 0x1F}, {0x3837, 0x40}, - - {0x3892, 0x44}, - {0x3823, 0x48}, - - {0x3012, 0x41}, // SC_PHY_CTRL = 4 lane MIPI - {0x3020, 0x05}, // SC_CTRL_20 - - // this is not in the datasheet, listed as RSVD - // but the camera doesn't work without it - {0x3700, 0x28}, {0x3701, 0x15}, {0x3702, 0x19}, {0x3703, 0x23}, - {0x3704, 0x0a}, {0x3705, 0x00}, {0x3706, 0x3e}, {0x3707, 0x0d}, - {0x3708, 0x50}, {0x3709, 0x5a}, {0x370a, 0x00}, {0x370b, 0x96}, - {0x3711, 0x11}, {0x3712, 0x13}, {0x3717, 0x02}, {0x3718, 0x73}, - {0x372c, 0x40}, {0x3733, 0x01}, {0x3738, 0x36}, {0x3739, 0x36}, - {0x373a, 0x25}, {0x373b, 0x25}, {0x373f, 0x21}, {0x3740, 0x21}, - {0x3741, 0x21}, {0x3742, 0x21}, {0x3747, 0x28}, {0x3748, 0x28}, - {0x3749, 0x19}, {0x3755, 0x1a}, {0x3756, 0x0a}, {0x3757, 0x1c}, - {0x3765, 0x19}, {0x3766, 0x05}, {0x3767, 0x05}, {0x3768, 0x13}, - {0x376c, 0x07}, {0x3778, 0x20}, {0x377c, 0xc8}, {0x3781, 0x02}, - {0x3783, 0x02}, {0x379c, 0x58}, {0x379e, 0x00}, {0x379f, 0x00}, - {0x37a0, 0x00}, {0x37bc, 0x22}, {0x37c0, 0x01}, {0x37c4, 0x3e}, - {0x37c5, 0x3e}, {0x37c6, 0x2a}, {0x37c7, 0x28}, {0x37c8, 0x02}, - {0x37c9, 0x12}, {0x37cb, 0x29}, {0x37cd, 0x29}, {0x37d2, 0x00}, - {0x37d3, 0x73}, {0x37d6, 0x00}, {0x37d7, 0x6b}, {0x37dc, 0x00}, - {0x37df, 0x54}, {0x37e2, 0x00}, {0x37e3, 0x00}, {0x37f8, 0x00}, - {0x37f9, 0x01}, {0x37fa, 0x00}, {0x37fb, 0x19}, - - // also RSVD - {0x3c03, 0x01}, {0x3c04, 0x01}, {0x3c06, 0x21}, {0x3c08, 0x01}, - {0x3c09, 0x01}, {0x3c0a, 0x01}, {0x3c0b, 0x21}, {0x3c13, 0x21}, - {0x3c14, 0x82}, {0x3c16, 0x13}, {0x3c21, 0x00}, {0x3c22, 0xf3}, - {0x3c37, 0x12}, {0x3c38, 0x31}, {0x3c3c, 0x00}, {0x3c3d, 0x03}, - {0x3c44, 0x16}, {0x3c5c, 0x8a}, {0x3c5f, 0x03}, {0x3c61, 0x80}, - {0x3c6f, 0x2b}, {0x3c70, 0x5f}, {0x3c71, 0x2c}, {0x3c72, 0x2c}, - {0x3c73, 0x2c}, {0x3c76, 0x12}, - - // PEC checks - {0x3182, 0x12}, - - {0x320e, 0x00}, {0x320f, 0x00}, // RSVD - {0x3211, 0x61}, - {0x3215, 0xcd}, - {0x3219, 0x08}, - - {0x3506, 0x20}, {0x3507, 0x00}, // hcg fine exposure - {0x350a, 0x01}, {0x350b, 0x00}, {0x350c, 0x00}, // hcg digital gain - - {0x3586, 0x40}, {0x3587, 0x00}, // lcg fine exposure - {0x358a, 0x01}, {0x358b, 0x00}, {0x358c, 0x00}, // lcg digital gain - - {0x3546, 0x20}, {0x3547, 0x00}, // spd fine exposure - {0x354a, 0x01}, {0x354b, 0x00}, {0x354c, 0x00}, // spd digital gain - - {0x35c6, 0xb0}, {0x35c7, 0x00}, // vs fine exposure - {0x35ca, 0x01}, {0x35cb, 0x00}, {0x35cc, 0x00}, // vs digital gain - - // also RSVD - {0x3600, 0x8f}, {0x3605, 0x16}, {0x3609, 0xf0}, {0x360a, 0x01}, - {0x360e, 0x1d}, {0x360f, 0x10}, {0x3610, 0x70}, {0x3611, 0x3a}, - {0x3612, 0x28}, {0x361a, 0x29}, {0x361b, 0x6c}, {0x361c, 0x0b}, - {0x361d, 0x00}, {0x361e, 0xfc}, {0x362a, 0x00}, {0x364d, 0x0f}, - {0x364e, 0x18}, {0x364f, 0x12}, {0x3653, 0x1c}, {0x3654, 0x00}, - {0x3655, 0x1f}, {0x3656, 0x1f}, {0x3657, 0x0c}, {0x3658, 0x0a}, - {0x3659, 0x14}, {0x365a, 0x18}, {0x365b, 0x14}, {0x365c, 0x10}, - {0x365e, 0x12}, {0x3674, 0x08}, {0x3677, 0x3a}, {0x3678, 0x3a}, - {0x3679, 0x19}, - - // Y_ADDR_START = 4 - {0x3802, 0x00}, {0x3803, 0x04}, - // Y_ADDR_END = 0x50b - {0x3806, 0x05}, {0x3807, 0x0b}, - - // X_OUTPUT_SIZE = 0x780 = 1920 (changed to 1928) - {0x3808, 0x07}, {0x3809, 0x88}, - - // Y_OUTPUT_SIZE = 0x500 = 1280 (changed to 1208) - {0x380a, 0x04}, {0x380b, 0xb8}, - - // horizontal timing 0x447 - {0x380c, 0x04}, {0x380d, 0x47}, - - // rows per frame (was 0x2ae) - // 0x8ae = 53.65 ms - {0x380e, 0x08}, {0x380f, 0x15}, - // this should be triggered by FSIN, not free running - - {0x3810, 0x00}, {0x3811, 0x08}, // x cutoff - {0x3812, 0x00}, {0x3813, 0x04}, // y cutoff - {0x3816, 0x01}, - {0x3817, 0x01}, - {0x381c, 0x18}, - {0x381e, 0x01}, - {0x381f, 0x01}, - - // don't mirror, just flip - {0x3820, 0x04}, - - {0x3821, 0x19}, - {0x3832, 0xF0}, - {0x3834, 0xF0}, - {0x384c, 0x02}, - {0x384d, 0x0d}, - {0x3850, 0x00}, - {0x3851, 0x42}, - {0x3852, 0x00}, - {0x3853, 0x40}, - {0x3858, 0x04}, - {0x388c, 0x02}, - {0x388d, 0x2b}, - - // APC - {0x3b40, 0x05}, {0x3b41, 0x40}, {0x3b42, 0x00}, {0x3b43, 0x90}, - {0x3b44, 0x00}, {0x3b45, 0x20}, {0x3b46, 0x00}, {0x3b47, 0x20}, - {0x3b48, 0x19}, {0x3b49, 0x12}, {0x3b4a, 0x16}, {0x3b4b, 0x2e}, - {0x3b4c, 0x00}, {0x3b4d, 0x00}, - {0x3b86, 0x00}, {0x3b87, 0x34}, {0x3b88, 0x00}, {0x3b89, 0x08}, - {0x3b8a, 0x05}, {0x3b8b, 0x00}, {0x3b8c, 0x07}, {0x3b8d, 0x80}, - {0x3b8e, 0x00}, {0x3b8f, 0x00}, {0x3b92, 0x05}, {0x3b93, 0x00}, - {0x3b94, 0x07}, {0x3b95, 0x80}, {0x3b9e, 0x09}, - - // OTP - {0x3d82, 0x73}, - {0x3d85, 0x05}, - {0x3d8a, 0x03}, - {0x3d8b, 0xff}, - {0x3d99, 0x00}, - {0x3d9a, 0x9f}, - {0x3d9b, 0x00}, - {0x3d9c, 0xa0}, - {0x3da4, 0x00}, - {0x3da7, 0x50}, - - // DTR - {0x420e, 0x6b}, - {0x420f, 0x6e}, - {0x4210, 0x06}, - {0x4211, 0xc1}, - {0x421e, 0x02}, - {0x421f, 0x45}, - {0x4220, 0xe1}, - {0x4221, 0x01}, - {0x4301, 0xff}, - {0x4307, 0x03}, - {0x4308, 0x13}, - {0x430a, 0x13}, - {0x430d, 0x93}, - {0x430f, 0x57}, - {0x4310, 0x95}, - {0x4311, 0x16}, - {0x4316, 0x00}, - - {0x4317, 0x38}, // both embedded rows are enabled - - {0x4319, 0x03}, // spd dcg - {0x431a, 0x00}, // 8 bit mipi - {0x431b, 0x00}, - {0x431d, 0x2a}, - {0x431e, 0x11}, - - {0x431f, 0x20}, // enable PWL (pwl0_en), 12 bits - //{0x431f, 0x00}, // disable PWL - - {0x4320, 0x19}, - {0x4323, 0x80}, - {0x4324, 0x00}, - {0x4503, 0x4e}, - {0x4505, 0x00}, - {0x4509, 0x00}, - {0x450a, 0x00}, - {0x4580, 0xf8}, - {0x4583, 0x07}, - {0x4584, 0x6a}, - {0x4585, 0x08}, - {0x4586, 0x05}, - {0x4587, 0x04}, - {0x4588, 0x73}, - {0x4589, 0x05}, - {0x458a, 0x1f}, - {0x458b, 0x02}, - {0x458c, 0xdc}, - {0x458d, 0x03}, - {0x458e, 0x02}, - {0x4597, 0x07}, - {0x4598, 0x40}, - {0x4599, 0x0e}, - {0x459a, 0x0e}, - {0x459b, 0xfb}, - {0x459c, 0xf3}, - {0x4602, 0x00}, - {0x4603, 0x13}, - {0x4604, 0x00}, - {0x4609, 0x0a}, - {0x460a, 0x30}, - {0x4610, 0x00}, - {0x4611, 0x70}, - {0x4612, 0x01}, - {0x4613, 0x00}, - {0x4614, 0x00}, - {0x4615, 0x70}, - {0x4616, 0x01}, - {0x4617, 0x00}, - - {0x4800, 0x04}, // invert output PCLK - {0x480a, 0x22}, - {0x4813, 0xe4}, - - // mipi - {0x4814, 0x2a}, - {0x4837, 0x0d}, - {0x484b, 0x47}, - {0x484f, 0x00}, - {0x4887, 0x51}, - {0x4d00, 0x4a}, - {0x4d01, 0x18}, - {0x4d05, 0xff}, - {0x4d06, 0x88}, - {0x4d08, 0x63}, - {0x4d09, 0xdf}, - {0x4d15, 0x7d}, - {0x4d1a, 0x20}, - {0x4d30, 0x0a}, - {0x4d31, 0x00}, - {0x4d34, 0x7d}, - {0x4d3c, 0x7d}, - {0x4f00, 0x00}, - {0x4f01, 0x00}, - {0x4f02, 0x00}, - {0x4f03, 0x20}, - {0x4f04, 0xe0}, - {0x6a00, 0x00}, - {0x6a01, 0x20}, - {0x6a02, 0x00}, - {0x6a03, 0x20}, - {0x6a04, 0x02}, - {0x6a05, 0x80}, - {0x6a06, 0x01}, - {0x6a07, 0xe0}, - {0x6a08, 0xcf}, - {0x6a09, 0x01}, - {0x6a0a, 0x40}, - {0x6a20, 0x00}, - {0x6a21, 0x02}, - {0x6a22, 0x00}, - {0x6a23, 0x00}, - {0x6a24, 0x00}, - {0x6a25, 0x00}, - {0x6a26, 0x00}, - {0x6a27, 0x00}, - {0x6a28, 0x00}, - - // isp - {0x5000, 0x8f}, - {0x5001, 0x75}, - {0x5002, 0x7f}, // PWL0 - //{0x5002, 0x3f}, // PWL disable - {0x5003, 0x7a}, - - {0x5004, 0x3e}, - {0x5005, 0x1e}, - {0x5006, 0x1e}, - {0x5007, 0x1e}, - - {0x5008, 0x00}, - {0x500c, 0x00}, - {0x502c, 0x00}, - {0x502e, 0x00}, - {0x502f, 0x00}, - {0x504b, 0x00}, - {0x5053, 0x00}, - {0x505b, 0x00}, - {0x5063, 0x00}, - {0x5070, 0x00}, - {0x5074, 0x04}, - {0x507a, 0x04}, - {0x507b, 0x09}, - {0x5500, 0x02}, - {0x5700, 0x02}, - {0x5900, 0x02}, - {0x6007, 0x04}, - {0x6008, 0x05}, - {0x6009, 0x02}, - {0x600b, 0x08}, - {0x600c, 0x07}, - {0x600d, 0x88}, - {0x6016, 0x00}, - {0x6027, 0x04}, - {0x6028, 0x05}, - {0x6029, 0x02}, - {0x602b, 0x08}, - {0x602c, 0x07}, - {0x602d, 0x88}, - {0x6047, 0x04}, - {0x6048, 0x05}, - {0x6049, 0x02}, - {0x604b, 0x08}, - {0x604c, 0x07}, - {0x604d, 0x88}, - {0x6067, 0x04}, - {0x6068, 0x05}, - {0x6069, 0x02}, - {0x606b, 0x08}, - {0x606c, 0x07}, - {0x606d, 0x88}, - {0x6087, 0x04}, - {0x6088, 0x05}, - {0x6089, 0x02}, - {0x608b, 0x08}, - {0x608c, 0x07}, - {0x608d, 0x88}, - - // 12-bit PWL0 - {0x5e00, 0x00}, - - // m_ndX_exp[0:32] - // 9*2+0xa*3+0xb*2+0xc*2+0xd*2+0xe*2+0xf*2+0x10*2+0x11*2+0x12*4+0x13*3+0x14*3+0x15*3+0x16 = 518 - {0x5e01, 0x09}, - {0x5e02, 0x09}, - {0x5e03, 0x0a}, - {0x5e04, 0x0a}, - {0x5e05, 0x0a}, - {0x5e06, 0x0b}, - {0x5e07, 0x0b}, - {0x5e08, 0x0c}, - {0x5e09, 0x0c}, - {0x5e0a, 0x0d}, - {0x5e0b, 0x0d}, - {0x5e0c, 0x0e}, - {0x5e0d, 0x0e}, - {0x5e0e, 0x0f}, - {0x5e0f, 0x0f}, - {0x5e10, 0x10}, - {0x5e11, 0x10}, - {0x5e12, 0x11}, - {0x5e13, 0x11}, - {0x5e14, 0x12}, - {0x5e15, 0x12}, - {0x5e16, 0x12}, - {0x5e17, 0x12}, - {0x5e18, 0x13}, - {0x5e19, 0x13}, - {0x5e1a, 0x13}, - {0x5e1b, 0x14}, - {0x5e1c, 0x14}, - {0x5e1d, 0x14}, - {0x5e1e, 0x15}, - {0x5e1f, 0x15}, - {0x5e20, 0x15}, - {0x5e21, 0x16}, - - // m_ndY_val[0:32] - // 0x200+0xff+0x100*3+0x80*12+0x40*16 = 4095 - {0x5e22, 0x00}, {0x5e23, 0x02}, {0x5e24, 0x00}, - {0x5e25, 0x00}, {0x5e26, 0x00}, {0x5e27, 0xff}, - {0x5e28, 0x00}, {0x5e29, 0x01}, {0x5e2a, 0x00}, - {0x5e2b, 0x00}, {0x5e2c, 0x01}, {0x5e2d, 0x00}, - {0x5e2e, 0x00}, {0x5e2f, 0x01}, {0x5e30, 0x00}, - {0x5e31, 0x00}, {0x5e32, 0x00}, {0x5e33, 0x80}, - {0x5e34, 0x00}, {0x5e35, 0x00}, {0x5e36, 0x80}, - {0x5e37, 0x00}, {0x5e38, 0x00}, {0x5e39, 0x80}, - {0x5e3a, 0x00}, {0x5e3b, 0x00}, {0x5e3c, 0x80}, - {0x5e3d, 0x00}, {0x5e3e, 0x00}, {0x5e3f, 0x80}, - {0x5e40, 0x00}, {0x5e41, 0x00}, {0x5e42, 0x80}, - {0x5e43, 0x00}, {0x5e44, 0x00}, {0x5e45, 0x80}, - {0x5e46, 0x00}, {0x5e47, 0x00}, {0x5e48, 0x80}, - {0x5e49, 0x00}, {0x5e4a, 0x00}, {0x5e4b, 0x80}, - {0x5e4c, 0x00}, {0x5e4d, 0x00}, {0x5e4e, 0x80}, - {0x5e4f, 0x00}, {0x5e50, 0x00}, {0x5e51, 0x80}, - {0x5e52, 0x00}, {0x5e53, 0x00}, {0x5e54, 0x80}, - {0x5e55, 0x00}, {0x5e56, 0x00}, {0x5e57, 0x40}, - {0x5e58, 0x00}, {0x5e59, 0x00}, {0x5e5a, 0x40}, - {0x5e5b, 0x00}, {0x5e5c, 0x00}, {0x5e5d, 0x40}, - {0x5e5e, 0x00}, {0x5e5f, 0x00}, {0x5e60, 0x40}, - {0x5e61, 0x00}, {0x5e62, 0x00}, {0x5e63, 0x40}, - {0x5e64, 0x00}, {0x5e65, 0x00}, {0x5e66, 0x40}, - {0x5e67, 0x00}, {0x5e68, 0x00}, {0x5e69, 0x40}, - {0x5e6a, 0x00}, {0x5e6b, 0x00}, {0x5e6c, 0x40}, - {0x5e6d, 0x00}, {0x5e6e, 0x00}, {0x5e6f, 0x40}, - {0x5e70, 0x00}, {0x5e71, 0x00}, {0x5e72, 0x40}, - {0x5e73, 0x00}, {0x5e74, 0x00}, {0x5e75, 0x40}, - {0x5e76, 0x00}, {0x5e77, 0x00}, {0x5e78, 0x40}, - {0x5e79, 0x00}, {0x5e7a, 0x00}, {0x5e7b, 0x40}, - {0x5e7c, 0x00}, {0x5e7d, 0x00}, {0x5e7e, 0x40}, - {0x5e7f, 0x00}, {0x5e80, 0x00}, {0x5e81, 0x40}, - {0x5e82, 0x00}, {0x5e83, 0x00}, {0x5e84, 0x40}, - - // disable PWL - /*{0x5e01, 0x18}, {0x5e02, 0x00}, {0x5e03, 0x00}, {0x5e04, 0x00}, - {0x5e05, 0x00}, {0x5e06, 0x00}, {0x5e07, 0x00}, {0x5e08, 0x00}, - {0x5e09, 0x00}, {0x5e0a, 0x00}, {0x5e0b, 0x00}, {0x5e0c, 0x00}, - {0x5e0d, 0x00}, {0x5e0e, 0x00}, {0x5e0f, 0x00}, {0x5e10, 0x00}, - {0x5e11, 0x00}, {0x5e12, 0x00}, {0x5e13, 0x00}, {0x5e14, 0x00}, - {0x5e15, 0x00}, {0x5e16, 0x00}, {0x5e17, 0x00}, {0x5e18, 0x00}, - {0x5e19, 0x00}, {0x5e1a, 0x00}, {0x5e1b, 0x00}, {0x5e1c, 0x00}, - {0x5e1d, 0x00}, {0x5e1e, 0x00}, {0x5e1f, 0x00}, {0x5e20, 0x00}, - {0x5e21, 0x00}, - - {0x5e22, 0x00}, {0x5e23, 0x0f}, {0x5e24, 0xFF},*/ - - {0x4001, 0x2b}, // BLC_CTRL_1 - {0x4008, 0x02}, {0x4009, 0x03}, - {0x4018, 0x12}, - {0x4022, 0x40}, - {0x4023, 0x20}, - - // all black level targets are 0x40 - {0x4026, 0x00}, {0x4027, 0x40}, - {0x4028, 0x00}, {0x4029, 0x40}, - {0x402a, 0x00}, {0x402b, 0x40}, - {0x402c, 0x00}, {0x402d, 0x40}, - - {0x407e, 0xcc}, - {0x407f, 0x18}, - {0x4080, 0xff}, - {0x4081, 0xff}, - {0x4082, 0x01}, - {0x4083, 0x53}, - {0x4084, 0x01}, - {0x4085, 0x2b}, - {0x4086, 0x00}, - {0x4087, 0xb3}, - - {0x4640, 0x40}, - {0x4641, 0x11}, - {0x4642, 0x0e}, - {0x4643, 0xee}, - {0x4646, 0x0f}, - {0x4648, 0x00}, - {0x4649, 0x03}, - - {0x4f00, 0x00}, - {0x4f01, 0x00}, - {0x4f02, 0x80}, - {0x4f03, 0x2c}, - {0x4f04, 0xf8}, - - {0x4d09, 0xff}, - {0x4d09, 0xdf}, - - {0x5003, 0x7a}, - {0x5b80, 0x08}, - {0x5c00, 0x08}, - {0x5c80, 0x00}, - {0x5bbe, 0x12}, - {0x5c3e, 0x12}, - {0x5cbe, 0x12}, - {0x5b8a, 0x80}, - {0x5b8b, 0x80}, - {0x5b8c, 0x80}, - {0x5b8d, 0x80}, - {0x5b8e, 0x60}, - {0x5b8f, 0x80}, - {0x5b90, 0x80}, - {0x5b91, 0x80}, - {0x5b92, 0x80}, - {0x5b93, 0x20}, - {0x5b94, 0x80}, - {0x5b95, 0x80}, - {0x5b96, 0x80}, - {0x5b97, 0x20}, - {0x5b98, 0x00}, - {0x5b99, 0x80}, - {0x5b9a, 0x40}, - {0x5b9b, 0x20}, - {0x5b9c, 0x00}, - {0x5b9d, 0x00}, - {0x5b9e, 0x80}, - {0x5b9f, 0x00}, - {0x5ba0, 0x00}, - {0x5ba1, 0x00}, - {0x5ba2, 0x00}, - {0x5ba3, 0x00}, - {0x5ba4, 0x00}, - {0x5ba5, 0x00}, - {0x5ba6, 0x00}, - {0x5ba7, 0x00}, - {0x5ba8, 0x02}, - {0x5ba9, 0x00}, - {0x5baa, 0x02}, - {0x5bab, 0x76}, - {0x5bac, 0x03}, - {0x5bad, 0x08}, - {0x5bae, 0x00}, - {0x5baf, 0x80}, - {0x5bb0, 0x00}, - {0x5bb1, 0xc0}, - {0x5bb2, 0x01}, - {0x5bb3, 0x00}, - - // m_nNormCombineWeight - {0x5c0a, 0x80}, {0x5c0b, 0x80}, {0x5c0c, 0x80}, {0x5c0d, 0x80}, {0x5c0e, 0x60}, - {0x5c0f, 0x80}, {0x5c10, 0x80}, {0x5c11, 0x80}, {0x5c12, 0x60}, {0x5c13, 0x20}, - {0x5c14, 0x80}, {0x5c15, 0x80}, {0x5c16, 0x80}, {0x5c17, 0x20}, {0x5c18, 0x00}, - {0x5c19, 0x80}, {0x5c1a, 0x40}, {0x5c1b, 0x20}, {0x5c1c, 0x00}, {0x5c1d, 0x00}, - {0x5c1e, 0x80}, {0x5c1f, 0x00}, {0x5c20, 0x00}, {0x5c21, 0x00}, {0x5c22, 0x00}, - {0x5c23, 0x00}, {0x5c24, 0x00}, {0x5c25, 0x00}, {0x5c26, 0x00}, {0x5c27, 0x00}, - - // m_nCombinThreL - {0x5c28, 0x02}, {0x5c29, 0x00}, - {0x5c2a, 0x02}, {0x5c2b, 0x76}, - {0x5c2c, 0x03}, {0x5c2d, 0x08}, - - // m_nCombinThreS - {0x5c2e, 0x00}, {0x5c2f, 0x80}, - {0x5c30, 0x00}, {0x5c31, 0xc0}, - {0x5c32, 0x01}, {0x5c33, 0x00}, - - // m_nNormCombineWeight - {0x5c8a, 0x80}, {0x5c8b, 0x80}, {0x5c8c, 0x80}, {0x5c8d, 0x80}, {0x5c8e, 0x80}, - {0x5c8f, 0x80}, {0x5c90, 0x80}, {0x5c91, 0x80}, {0x5c92, 0x80}, {0x5c93, 0x60}, - {0x5c94, 0x80}, {0x5c95, 0x80}, {0x5c96, 0x80}, {0x5c97, 0x60}, {0x5c98, 0x40}, - {0x5c99, 0x80}, {0x5c9a, 0x80}, {0x5c9b, 0x80}, {0x5c9c, 0x40}, {0x5c9d, 0x00}, - {0x5c9e, 0x80}, {0x5c9f, 0x80}, {0x5ca0, 0x80}, {0x5ca1, 0x20}, {0x5ca2, 0x00}, - {0x5ca3, 0x80}, {0x5ca4, 0x80}, {0x5ca5, 0x00}, {0x5ca6, 0x00}, {0x5ca7, 0x00}, - - {0x5ca8, 0x01}, {0x5ca9, 0x00}, - {0x5caa, 0x02}, {0x5cab, 0x00}, - {0x5cac, 0x03}, {0x5cad, 0x08}, - - {0x5cae, 0x01}, {0x5caf, 0x00}, - {0x5cb0, 0x02}, {0x5cb1, 0x00}, - {0x5cb2, 0x03}, {0x5cb3, 0x08}, - - // combine ISP - {0x5be7, 0x80}, - {0x5bc9, 0x80}, - {0x5bca, 0x80}, - {0x5bcb, 0x80}, - {0x5bcc, 0x80}, - {0x5bcd, 0x80}, - {0x5bce, 0x80}, - {0x5bcf, 0x80}, - {0x5bd0, 0x80}, - {0x5bd1, 0x80}, - {0x5bd2, 0x20}, - {0x5bd3, 0x80}, - {0x5bd4, 0x40}, - {0x5bd5, 0x20}, - {0x5bd6, 0x00}, - {0x5bd7, 0x00}, - {0x5bd8, 0x00}, - {0x5bd9, 0x00}, - {0x5bda, 0x00}, - {0x5bdb, 0x00}, - {0x5bdc, 0x00}, - {0x5bdd, 0x00}, - {0x5bde, 0x00}, - {0x5bdf, 0x00}, - {0x5be0, 0x00}, - {0x5be1, 0x00}, - {0x5be2, 0x00}, - {0x5be3, 0x00}, - {0x5be4, 0x00}, - {0x5be5, 0x00}, - {0x5be6, 0x00}, - - // m_nSPDCombineWeight - {0x5c49, 0x80}, {0x5c4a, 0x80}, {0x5c4b, 0x80}, {0x5c4c, 0x80}, {0x5c4d, 0x40}, - {0x5c4e, 0x80}, {0x5c4f, 0x80}, {0x5c50, 0x80}, {0x5c51, 0x60}, {0x5c52, 0x20}, - {0x5c53, 0x80}, {0x5c54, 0x80}, {0x5c55, 0x80}, {0x5c56, 0x20}, {0x5c57, 0x00}, - {0x5c58, 0x80}, {0x5c59, 0x40}, {0x5c5a, 0x20}, {0x5c5b, 0x00}, {0x5c5c, 0x00}, - {0x5c5d, 0x80}, {0x5c5e, 0x00}, {0x5c5f, 0x00}, {0x5c60, 0x00}, {0x5c61, 0x00}, - {0x5c62, 0x00}, {0x5c63, 0x00}, {0x5c64, 0x00}, {0x5c65, 0x00}, {0x5c66, 0x00}, - - // m_nSPDCombineWeight - {0x5cc9, 0x80}, {0x5cca, 0x80}, {0x5ccb, 0x80}, {0x5ccc, 0x80}, {0x5ccd, 0x80}, - {0x5cce, 0x80}, {0x5ccf, 0x80}, {0x5cd0, 0x80}, {0x5cd1, 0x80}, {0x5cd2, 0x60}, - {0x5cd3, 0x80}, {0x5cd4, 0x80}, {0x5cd5, 0x80}, {0x5cd6, 0x60}, {0x5cd7, 0x40}, - {0x5cd8, 0x80}, {0x5cd9, 0x80}, {0x5cda, 0x80}, {0x5cdb, 0x40}, {0x5cdc, 0x20}, - {0x5cdd, 0x80}, {0x5cde, 0x80}, {0x5cdf, 0x80}, {0x5ce0, 0x20}, {0x5ce1, 0x00}, - {0x5ce2, 0x80}, {0x5ce3, 0x80}, {0x5ce4, 0x80}, {0x5ce5, 0x00}, {0x5ce6, 0x00}, - - {0x5d74, 0x01}, - {0x5d75, 0x00}, - - {0x5d1f, 0x81}, - {0x5d11, 0x00}, - {0x5d12, 0x10}, - {0x5d13, 0x10}, - {0x5d15, 0x05}, - {0x5d16, 0x05}, - {0x5d17, 0x05}, - {0x5d08, 0x03}, - {0x5d09, 0xb6}, - {0x5d0a, 0x03}, - {0x5d0b, 0xb6}, - {0x5d18, 0x03}, - {0x5d19, 0xb6}, - {0x5d62, 0x01}, - {0x5d40, 0x02}, - {0x5d41, 0x01}, - {0x5d63, 0x1f}, - {0x5d64, 0x00}, - {0x5d65, 0x80}, - {0x5d56, 0x00}, - {0x5d57, 0x20}, - {0x5d58, 0x00}, - {0x5d59, 0x20}, - {0x5d5a, 0x00}, - {0x5d5b, 0x0c}, - {0x5d5c, 0x02}, - {0x5d5d, 0x40}, - {0x5d5e, 0x02}, - {0x5d5f, 0x40}, - {0x5d60, 0x03}, - {0x5d61, 0x40}, - {0x5d4a, 0x02}, - {0x5d4b, 0x40}, - {0x5d4c, 0x02}, - {0x5d4d, 0x40}, - {0x5d4e, 0x02}, - {0x5d4f, 0x40}, - {0x5d50, 0x18}, - {0x5d51, 0x80}, - {0x5d52, 0x18}, - {0x5d53, 0x80}, - {0x5d54, 0x18}, - {0x5d55, 0x80}, - {0x5d46, 0x20}, - {0x5d47, 0x00}, - {0x5d48, 0x22}, - {0x5d49, 0x00}, - {0x5d42, 0x20}, - {0x5d43, 0x00}, - {0x5d44, 0x22}, - {0x5d45, 0x00}, - - {0x5004, 0x1e}, - {0x4221, 0x03}, // this is changed from 1 -> 3 - - // DCG exposure coarse - // {0x3501, 0x01}, {0x3502, 0xc8}, - // SPD exposure coarse - // {0x3541, 0x01}, {0x3542, 0xc8}, - // VS exposure coarse - // {0x35c1, 0x00}, {0x35c2, 0x01}, - - // crc reference - {0x420e, 0x66}, {0x420f, 0x5d}, {0x4210, 0xa8}, {0x4211, 0x55}, - // crc stat check - {0x507a, 0x5f}, {0x507b, 0x46}, - - // watchdog control - {0x4f00, 0x00}, {0x4f01, 0x01}, {0x4f02, 0x80}, {0x4f04, 0x2c}, - - // color balance gains - // blue - {0x5280, 0x06}, {0x5281, 0xCB}, // hcg - {0x5480, 0x06}, {0x5481, 0xCB}, // lcg - {0x5680, 0x06}, {0x5681, 0xCB}, // spd - {0x5880, 0x06}, {0x5881, 0xCB}, // vs - - // green(blue) - {0x5282, 0x04}, {0x5283, 0x00}, - {0x5482, 0x04}, {0x5483, 0x00}, - {0x5682, 0x04}, {0x5683, 0x00}, - {0x5882, 0x04}, {0x5883, 0x00}, - - // green(red) - {0x5284, 0x04}, {0x5285, 0x00}, - {0x5484, 0x04}, {0x5485, 0x00}, - {0x5684, 0x04}, {0x5685, 0x00}, - {0x5884, 0x04}, {0x5885, 0x00}, - - // red - {0x5286, 0x08}, {0x5287, 0xDE}, - {0x5486, 0x08}, {0x5487, 0xDE}, - {0x5686, 0x08}, {0x5687, 0xDE}, - {0x5886, 0x08}, {0x5887, 0xDE}, - - // fixed gains - {0x3588, 0x01}, {0x3589, 0x00}, - {0x35c8, 0x01}, {0x35c9, 0x00}, - {0x3548, 0x0F}, {0x3549, 0x00}, - {0x35c1, 0x00}, -}; diff --git a/system/camerad/sensors/sensor.h b/system/camerad/sensors/sensor.h deleted file mode 100644 index 4e2194d..0000000 --- a/system/camerad/sensors/sensor.h +++ /dev/null @@ -1,93 +0,0 @@ -#pragma once - -#include -#include -#include -#include -#include -#include "media/cam_sensor.h" -#include "system/camerad/cameras/camera_common.h" -#include "system/camerad/sensors/ar0231_registers.h" -#include "system/camerad/sensors/ox03c10_registers.h" -#include "system/camerad/sensors/os04c10_registers.h" - -#define ANALOG_GAIN_MAX_CNT 55 -const size_t FRAME_WIDTH = 1928; -const size_t FRAME_HEIGHT = 1208; -const size_t FRAME_STRIDE = 2896; // for 12 bit output. 1928 * 12 / 8 + 4 (alignment) - - -class SensorInfo { -public: - SensorInfo() = default; - virtual std::vector getExposureRegisters(int exposure_time, int new_exp_g, bool dc_gain_enabled) const { return {}; } - virtual float getExposureScore(float desired_ev, int exp_t, int exp_g_idx, float exp_gain, int gain_idx) const {return 0; } - virtual int getSlaveAddress(int port) const { assert(0); } - virtual void processRegisters(CameraState *c, cereal::FrameData::Builder &framed) const {} - - cereal::FrameData::ImageSensor image_sensor = cereal::FrameData::ImageSensor::UNKNOWN; - uint32_t frame_width, frame_height; - uint32_t frame_stride; - uint32_t frame_offset = 0; - uint32_t extra_height = 0; - int registers_offset = -1; - int stats_offset = -1; - - int exposure_time_min; - int exposure_time_max; - - float dc_gain_factor; - int dc_gain_min_weight; - int dc_gain_max_weight; - float dc_gain_on_grey; - float dc_gain_off_grey; - - float sensor_analog_gains[ANALOG_GAIN_MAX_CNT]; - int analog_gain_min_idx; - int analog_gain_max_idx; - int analog_gain_rec_idx; - int analog_gain_cost_delta; - float analog_gain_cost_low; - float analog_gain_cost_high; - float target_grey_factor; - float min_ev; - float max_ev; - - bool data_word; - uint32_t probe_reg_addr; - uint32_t probe_expected_data; - std::vector start_reg_array; - std::vector init_reg_array; - - uint32_t mipi_format; - uint32_t mclk_frequency; - uint32_t frame_data_type; -}; - -class AR0231 : public SensorInfo { -public: - AR0231(); - std::vector getExposureRegisters(int exposure_time, int new_exp_g, bool dc_gain_enabled) const override; - float getExposureScore(float desired_ev, int exp_t, int exp_g_idx, float exp_gain, int gain_idx) const override; - int getSlaveAddress(int port) const override; - void processRegisters(CameraState *c, cereal::FrameData::Builder &framed) const override; - -private: - mutable std::map> ar0231_register_lut; -}; - -class OX03C10 : public SensorInfo { -public: - OX03C10(); - std::vector getExposureRegisters(int exposure_time, int new_exp_g, bool dc_gain_enabled) const override; - float getExposureScore(float desired_ev, int exp_t, int exp_g_idx, float exp_gain, int gain_idx) const override; - int getSlaveAddress(int port) const override; -}; - -class OS04C10 : public SensorInfo { -public: - OS04C10(); - std::vector getExposureRegisters(int exposure_time, int new_exp_g, bool dc_gain_enabled) const override; - float getExposureScore(float desired_ev, int exp_t, int exp_g_idx, float exp_gain, int gain_idx) const override; - int getSlaveAddress(int port) const override; -}; diff --git a/system/camerad/test/.gitignore b/system/camerad/test/.gitignore deleted file mode 100644 index d67473e..0000000 --- a/system/camerad/test/.gitignore +++ /dev/null @@ -1,2 +0,0 @@ -jpegs/ -test_ae_gray diff --git a/system/camerad/test/check_skips.py b/system/camerad/test/check_skips.py deleted file mode 100644 index 0814ce4..0000000 --- a/system/camerad/test/check_skips.py +++ /dev/null @@ -1,27 +0,0 @@ -#!/usr/bin/env python3 -# type: ignore -import cereal.messaging as messaging - -all_sockets = ['roadCameraState', 'driverCameraState', 'wideRoadCameraState'] -prev_id = [None,None,None] -this_id = [None,None,None] -dt = [None,None,None] -num_skipped = [0,0,0] - -if __name__ == "__main__": - sm = messaging.SubMaster(all_sockets) - while True: - sm.update() - - for i in range(len(all_sockets)): - if not sm.updated[all_sockets[i]]: - continue - this_id[i] = sm[all_sockets[i]].frameId - if prev_id[i] is None: - prev_id[i] = this_id[i] - continue - dt[i] = this_id[i] - prev_id[i] - if dt[i] != 1: - num_skipped[i] += dt[i] - 1 - print(all_sockets[i] ,dt[i] - 1, num_skipped[i]) - prev_id[i] = this_id[i] diff --git a/system/camerad/test/get_thumbnails_for_segment.py b/system/camerad/test/get_thumbnails_for_segment.py deleted file mode 100644 index 21409f3..0000000 --- a/system/camerad/test/get_thumbnails_for_segment.py +++ /dev/null @@ -1,24 +0,0 @@ -#!/usr/bin/env python3 -import argparse -import os -from tqdm import tqdm - -from openpilot.tools.lib.logreader import LogReader - -if __name__ == "__main__": - parser = argparse.ArgumentParser() - parser.add_argument("route", help="The route name") - args = parser.parse_args() - - out_path = os.path.join("jpegs", f"{args.route.replace('|', '_').replace('/', '_')}") - os.makedirs(out_path, exist_ok=True) - - lr = LogReader(args.route) - - for msg in tqdm(lr): - if msg.which() == 'thumbnail': - with open(os.path.join(out_path, f"{msg.thumbnail.frameId}.jpg"), 'wb') as f: - f.write(msg.thumbnail.thumbnail) - elif msg.which() == 'navThumbnail': - with open(os.path.join(out_path, f"nav_{msg.navThumbnail.frameId}.jpg"), 'wb') as f: - f.write(msg.navThumbnail.thumbnail) diff --git a/system/camerad/test/stress_restart.sh b/system/camerad/test/stress_restart.sh deleted file mode 100644 index 0445dcb..0000000 --- a/system/camerad/test/stress_restart.sh +++ /dev/null @@ -1,9 +0,0 @@ -#!/bin/sh -cd .. -while :; do - ./camerad & - pid="$!" - sleep 2 - kill -2 $pid - wait $pid -done diff --git a/system/camerad/test/test_ae_gray.cc b/system/camerad/test/test_ae_gray.cc deleted file mode 100644 index 06d7849..0000000 --- a/system/camerad/test/test_ae_gray.cc +++ /dev/null @@ -1,83 +0,0 @@ -#define CATCH_CONFIG_MAIN -#include "catch2/catch.hpp" - -#include - -#include -#include - -#include "common/util.h" -#include "system/camerad/cameras/camera_common.h" - -#define W 240 -#define H 160 - - -#define TONE_SPLITS 3 - -float gts[TONE_SPLITS * TONE_SPLITS * TONE_SPLITS * TONE_SPLITS] = { - 0.917969, 0.917969, 0.375000, 0.917969, 0.375000, 0.375000, 0.187500, 0.187500, 0.187500, 0.917969, - 0.375000, 0.375000, 0.187500, 0.187500, 0.187500, 0.187500, 0.187500, 0.187500, 0.093750, 0.093750, - 0.093750, 0.093750, 0.093750, 0.093750, 0.093750, 0.093750, 0.093750, 0.917969, 0.375000, 0.375000, - 0.187500, 0.187500, 0.187500, 0.187500, 0.187500, 0.187500, 0.093750, 0.093750, 0.093750, 0.093750, - 0.093750, 0.093750, 0.093750, 0.093750, 0.093750, 0.093750, 0.093750, 0.093750, 0.093750, 0.093750, - 0.093750, 0.093750, 0.093750, 0.093750, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, - 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, - 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, - 0.000000}; - - -TEST_CASE("camera.test_set_exposure_target") { - // set up fake camerabuf - CameraBuf cb = {}; - VisionBuf vb = {}; - uint8_t * fb_y = new uint8_t[W*H]; - vb.y = fb_y; - cb.cur_yuv_buf = &vb; - cb.rgb_width = W; - cb.rgb_height = H; - - printf("AE test patterns %dx%d\n", cb.rgb_width, cb.rgb_height); - - // mix of 5 tones - uint8_t l[5] = {0, 24, 48, 96, 235}; // 235 is yuv max - - bool passed = true; - float rtol = 0.05; - // generate pattern and calculate EV - int cnt = 0; - for (int i_0=0; i_0 rtol*evgt) { - passed = false; - } - - // report - printf("%d/%d/%d/%d/%d: ev %f, gt %f, err %f\n", h_0, h_1, h_2, h_3, h_4, ev, evgt, fabs(ev - evgt) / (evgt != 0 ? evgt : 0.00001f)); - cnt++; - } - } - } - } - assert(passed); - - delete[] fb_y; -} diff --git a/system/camerad/test/test_camerad.py b/system/camerad/test/test_camerad.py deleted file mode 100644 index 4081156..0000000 --- a/system/camerad/test/test_camerad.py +++ /dev/null @@ -1,83 +0,0 @@ -#!/usr/bin/env python3 -import pytest -import time -import numpy as np -from flaky import flaky -from collections import defaultdict - -import cereal.messaging as messaging -from cereal import log -from cereal.services import SERVICE_LIST -from openpilot.selfdrive.manager.process_config import managed_processes - -TEST_TIMESPAN = 30 -LAG_FRAME_TOLERANCE = {log.FrameData.ImageSensor.ar0231: 0.5, # ARs use synced pulses for frame starts - log.FrameData.ImageSensor.ox03c10: 1.1} # OXs react to out-of-sync at next frame -FRAME_DELTA_TOLERANCE = {log.FrameData.ImageSensor.ar0231: 1.0, - log.FrameData.ImageSensor.ox03c10: 1.0} - -CAMERAS = ('roadCameraState', 'driverCameraState', 'wideRoadCameraState') - -# TODO: this shouldn't be needed -@flaky(max_runs=3) -@pytest.mark.tici -class TestCamerad: - def setup_method(self): - # run camerad and record logs - managed_processes['camerad'].start() - time.sleep(3) - socks = {c: messaging.sub_sock(c, conflate=False, timeout=100) for c in CAMERAS} - - self.logs = defaultdict(list) - start_time = time.monotonic() - while time.monotonic()- start_time < TEST_TIMESPAN: - for cam, s in socks.items(): - self.logs[cam] += messaging.drain_sock(s) - time.sleep(0.2) - managed_processes['camerad'].stop() - - self.log_by_frame_id = defaultdict(list) - self.sensor_type = None - for cam, msgs in self.logs.items(): - if self.sensor_type is None: - self.sensor_type = getattr(msgs[0], msgs[0].which()).sensor.raw - expected_frames = SERVICE_LIST[cam].frequency * TEST_TIMESPAN - assert expected_frames*0.95 < len(msgs) < expected_frames*1.05, f"unexpected frame count {cam}: {expected_frames=}, got {len(msgs)}" - - dts = np.abs(np.diff([getattr(m, m.which()).timestampSof/1e6 for m in msgs]) - 1000/SERVICE_LIST[cam].frequency) - assert (dts < FRAME_DELTA_TOLERANCE[self.sensor_type]).all(), f"{cam} dts(ms) out of spec: max diff {dts.max()}, 99 percentile {np.percentile(dts, 99)}" - - for m in msgs: - self.log_by_frame_id[getattr(m, m.which()).frameId].append(m) - - # strip beginning and end - for _ in range(3): - mn, mx = min(self.log_by_frame_id.keys()), max(self.log_by_frame_id.keys()) - del self.log_by_frame_id[mn] - del self.log_by_frame_id[mx] - - def test_frame_skips(self): - skips = {} - frame_ids = self.log_by_frame_id.keys() - for frame_id in range(min(frame_ids), max(frame_ids)): - seen_cams = [msg.which() for msg in self.log_by_frame_id[frame_id]] - skip_cams = set(CAMERAS) - set(seen_cams) - if len(skip_cams): - skips[frame_id] = skip_cams - assert len(skips) == 0, f"Found frame skips, missing cameras for the following frames: {skips}" - - def test_frame_sync(self): - frame_times = {frame_id: [getattr(m, m.which()).timestampSof for m in msgs] for frame_id, msgs in self.log_by_frame_id.items()} - diffs = {frame_id: (max(ts) - min(ts))/1e6 for frame_id, ts in frame_times.items()} - - def get_desc(fid, diff): - cam_times = [(m.which(), getattr(m, m.which()).timestampSof/1e6) for m in self.log_by_frame_id[fid]] - return (diff, cam_times) - laggy_frames = {k: get_desc(k, v) for k, v in diffs.items() if v > LAG_FRAME_TOLERANCE[self.sensor_type]} - - def in_tol(diff): - return 50 - LAG_FRAME_TOLERANCE[self.sensor_type] < diff and diff < 50 + LAG_FRAME_TOLERANCE[self.sensor_type] - if len(laggy_frames) != 0 and all( in_tol(laggy_frames[lf][0]) for lf in laggy_frames): - print("TODO: handle camera out of sync") - else: - assert len(laggy_frames) == 0, f"Frames not synced properly: {laggy_frames=}" diff --git a/system/camerad/test/test_exposure.py b/system/camerad/test/test_exposure.py deleted file mode 100644 index 50467f9..0000000 --- a/system/camerad/test/test_exposure.py +++ /dev/null @@ -1,55 +0,0 @@ -#!/usr/bin/env python3 -import time -import unittest -import numpy as np - -from openpilot.selfdrive.test.helpers import with_processes, phone_only -from openpilot.system.camerad.snapshot.snapshot import get_snapshots - -TEST_TIME = 45 -REPEAT = 5 - -class TestCamerad(unittest.TestCase): - @classmethod - def setUpClass(cls): - pass - - def _numpy_rgb2gray(self, im): - ret = np.clip(im[:,:,2] * 0.114 + im[:,:,1] * 0.587 + im[:,:,0] * 0.299, 0, 255).astype(np.uint8) - return ret - - def _is_exposure_okay(self, i, med_mean=None): - if med_mean is None: - med_mean = np.array([[0.2,0.4],[0.2,0.6]]) - h, w = i.shape[:2] - i = i[h//10:9*h//10,w//10:9*w//10] - med_ex, mean_ex = med_mean - i = self._numpy_rgb2gray(i) - i_median = np.median(i) / 255. - i_mean = np.mean(i) / 255. - print([i_median, i_mean]) - return med_ex[0] < i_median < med_ex[1] and mean_ex[0] < i_mean < mean_ex[1] - - @phone_only - @with_processes(['camerad']) - def test_camera_operation(self): - passed = 0 - start = time.time() - while time.time() - start < TEST_TIME and passed < REPEAT: - rpic, dpic = get_snapshots(frame="roadCameraState", front_frame="driverCameraState") - wpic, _ = get_snapshots(frame="wideRoadCameraState") - - res = self._is_exposure_okay(rpic) - res = res and self._is_exposure_okay(dpic) - res = res and self._is_exposure_okay(wpic) - - if passed > 0 and not res: - passed = -passed # fails test if any failure after first sus - break - - passed += int(res) - time.sleep(2) - self.assertGreaterEqual(passed, REPEAT) - -if __name__ == "__main__": - unittest.main() diff --git a/system/hardware/base.h b/system/hardware/base.h deleted file mode 100644 index 6fe65f8..0000000 --- a/system/hardware/base.h +++ /dev/null @@ -1,42 +0,0 @@ -#pragma once - -#include -#include -#include -#include - -#include "cereal/messaging/messaging.h" - -// no-op base hw class -class HardwareNone { -public: - static constexpr float MAX_VOLUME = 0.7; - static constexpr float MIN_VOLUME = 0.2; - - static std::string get_os_version() { return ""; } - static std::string get_name() { return ""; } - static cereal::InitData::DeviceType get_device_type() { return cereal::InitData::DeviceType::UNKNOWN; } - static int get_voltage() { return 0; } - static int get_current() { return 0; } - - static std::string get_serial() { return "cccccc"; } - - static std::map get_init_logs() { - return {}; - } - - static void reboot() {} - static void soft_reboot() {} - static void poweroff() {} - static void set_brightness(int percent) {} - static void set_display_power(bool on) {} - - static bool get_ssh_enabled() { return false; } - static void set_ssh_enabled(bool enabled) {} - - static void config_cpu_rendering(bool offscreen); - - static bool PC() { return false; } - static bool TICI() { return false; } - static bool AGNOS() { return false; } -}; diff --git a/system/hardware/base.py b/system/hardware/base.py index 527518a..7434bb6 100644 --- a/system/hardware/base.py +++ b/system/hardware/base.py @@ -30,10 +30,6 @@ class HardwareBase(ABC): def reboot(self, reason=None): pass - @abstractmethod - def soft_reboot(self): - pass - @abstractmethod def uninstall(self): pass diff --git a/system/hardware/hw.h b/system/hardware/hw.h deleted file mode 100644 index 394807c..0000000 --- a/system/hardware/hw.h +++ /dev/null @@ -1,50 +0,0 @@ -#pragma once - -#include - -#include "system/hardware/base.h" -#include "common/util.h" - -#if QCOM2 -#include "system/hardware/tici/hardware.h" -#define Hardware HardwareTici -#else -#include "system/hardware/pc/hardware.h" -#define Hardware HardwarePC -#endif - -namespace Path { - inline std::string openpilot_prefix() { - return util::getenv("OPENPILOT_PREFIX", ""); - } - - inline std::string comma_home() { - return util::getenv("HOME") + "/.comma" + Path::openpilot_prefix(); - } - - inline std::string log_root() { - if (const char *env = getenv("LOG_ROOT")) { - return env; - } - return Hardware::PC() ? Path::comma_home() + "/media/0/realdata" : "/data/media/0/realdata"; - } - - inline std::string params() { - return util::getenv("PARAMS_ROOT", Hardware::PC() ? (Path::comma_home() + "/params") : "/data/params"); - } - - inline std::string rsa_file() { - return Hardware::PC() ? Path::comma_home() + "/persist/comma/id_rsa" : "/persist/comma/id_rsa"; - } - - inline std::string swaglog_ipc() { - return "ipc:///tmp/logmessage" + Path::openpilot_prefix(); - } - - inline std::string download_cache_root() { - if (const char *env = getenv("COMMA_CACHE")) { - return env; - } - return "/tmp/comma_download_cache" + Path::openpilot_prefix() + "/"; - } -} // namespace Path diff --git a/system/hardware/pc/hardware.h b/system/hardware/pc/hardware.h deleted file mode 100644 index 5dea184..0000000 --- a/system/hardware/pc/hardware.h +++ /dev/null @@ -1,23 +0,0 @@ -#pragma once - -#include - -#include "system/hardware/base.h" - -class HardwarePC : public HardwareNone { -public: - static std::string get_os_version() { return "openpilot for PC"; } - static std::string get_name() { return "pc"; } - static cereal::InitData::DeviceType get_device_type() { return cereal::InitData::DeviceType::PC; } - static bool PC() { return true; } - static bool TICI() { return util::getenv("TICI", 0) == 1; } - static bool AGNOS() { return util::getenv("TICI", 0) == 1; } - - static void config_cpu_rendering(bool offscreen) { - if (offscreen) { - setenv("QT_QPA_PLATFORM", "offscreen", 1); - } - setenv("__GLX_VENDOR_LIBRARY_NAME", "mesa", 1); - setenv("LP_NUM_THREADS", "0", 1); // disable threading so we stay on our assigned CPU - } -}; diff --git a/system/hardware/pc/hardware.py b/system/hardware/pc/hardware.py index 704d65a..719e272 100644 --- a/system/hardware/pc/hardware.py +++ b/system/hardware/pc/hardware.py @@ -19,9 +19,6 @@ class Pc(HardwareBase): def reboot(self, reason=None): print("REBOOT!") - - def soft_reboot(self): - print("SOFT REBOOT!") def uninstall(self): print("uninstall") diff --git a/system/hardware/tici/hardware.h b/system/hardware/tici/hardware.h deleted file mode 100644 index 2d3cc72..0000000 --- a/system/hardware/tici/hardware.h +++ /dev/null @@ -1,113 +0,0 @@ -#pragma once - -#include -#include -#include -#include - -#include "common/params.h" -#include "common/util.h" -#include "system/hardware/base.h" - -class HardwareTici : public HardwareNone { -public: - static constexpr float MAX_VOLUME = 0.9; - static constexpr float MIN_VOLUME = 0.1; - static bool TICI() { return true; } - static bool AGNOS() { return true; } - static std::string get_os_version() { - return "AGNOS " + util::read_file("/VERSION"); - } - - static std::string get_name() { - std::string devicetree_model = util::read_file("/sys/firmware/devicetree/base/model"); - return (devicetree_model.find("tizi") != std::string::npos) ? "tizi" : "tici"; - } - - static cereal::InitData::DeviceType get_device_type() { - return (get_name() == "tizi") ? cereal::InitData::DeviceType::TIZI : cereal::InitData::DeviceType::TICI; - } - - static int get_voltage() { return std::atoi(util::read_file("/sys/class/hwmon/hwmon1/in1_input").c_str()); } - static int get_current() { return std::atoi(util::read_file("/sys/class/hwmon/hwmon1/curr1_input").c_str()); } - - static std::string get_serial() { - static std::string serial(""); - if (serial.empty()) { - std::ifstream stream("/proc/cmdline"); - std::string cmdline; - std::getline(stream, cmdline); - - auto start = cmdline.find("serialno="); - if (start == std::string::npos) { - serial = "cccccc"; - } else { - auto end = cmdline.find(" ", start + 9); - serial = cmdline.substr(start + 9, end - start - 9); - } - } - return serial; - } - - static void reboot() { std::system("sudo reboot"); } - static void soft_reboot() { - std::system("echo 894000.i2c | sudo tee /sys/bus/platform/drivers/i2c_geni/unbind"); - std::this_thread::sleep_for(std::chrono::milliseconds(500)); - std::system("echo 894000.i2c | sudo tee /sys/bus/platform/drivers/i2c_geni/bind"); - std::this_thread::sleep_for(std::chrono::milliseconds(500)); - std::system("sudo systemctl restart comma"); - } - static void poweroff() { std::system("sudo poweroff"); } - static void set_brightness(int percent) { - std::string max = util::read_file("/sys/class/backlight/panel0-backlight/max_brightness"); - - std::ofstream brightness_control("/sys/class/backlight/panel0-backlight/brightness"); - if (brightness_control.is_open()) { - brightness_control << (int)(percent * (std::stof(max)/100.)) << "\n"; - brightness_control.close(); - } - } - static void set_display_power(bool on) { - std::ofstream bl_power_control("/sys/class/backlight/panel0-backlight/bl_power"); - if (bl_power_control.is_open()) { - bl_power_control << (on ? "0" : "4") << "\n"; - bl_power_control.close(); - } - } - - static std::map get_init_logs() { - std::map ret = { - {"/BUILD", util::read_file("/BUILD")}, - {"lsblk", util::check_output("lsblk -o NAME,SIZE,STATE,VENDOR,MODEL,REV,SERIAL")}, - {"SOM ID", util::read_file("/sys/devices/platform/vendor/vendor:gpio-som-id/som_id")}, - }; - - std::string bs = util::check_output("abctl --boot_slot"); - ret["boot slot"] = bs.substr(0, bs.find_first_of("\n")); - - std::string temp = util::read_file("/dev/disk/by-partlabel/ssd"); - temp.erase(temp.find_last_not_of(std::string("\0\r\n", 3))+1); - ret["boot temp"] = temp; - - // TODO: log something from system and boot - for (std::string part : {"xbl", "abl", "aop", "devcfg", "xbl_config"}) { - for (std::string slot : {"a", "b"}) { - std::string partition = part + "_" + slot; - std::string hash = util::check_output("sha256sum /dev/disk/by-partlabel/" + partition); - ret[partition] = hash.substr(0, hash.find_first_of(" ")); - } - } - - return ret; - } - - static bool get_ssh_enabled() { return Params().getBool("SshEnabled"); } - static void set_ssh_enabled(bool enabled) { Params().putBool("SshEnabled", enabled); } - - static void config_cpu_rendering(bool offscreen) { - if (offscreen) { - setenv("QT_QPA_PLATFORM", "eglfs", 1); // offscreen doesn't work with EGL/GLES - } - setenv("LP_NUM_THREADS", "0", 1); // disable threading so we stay on our assigned CPU - } -}; diff --git a/system/hardware/tici/hardware.py b/system/hardware/tici/hardware.py index ae3f086..5bb1032 100644 --- a/system/hardware/tici/hardware.py +++ b/system/hardware/tici/hardware.py @@ -134,14 +134,6 @@ class Tici(HardwareBase): def reboot(self, reason=None): subprocess.check_output(["sudo", "reboot"]) - def soft_reboot(self): - # Reload the touchscreen driver to reset touch_count and avoid triggering a system reset prompt - sudo_write("894000.i2c", "/sys/bus/platform/drivers/i2c_geni/unbind") - time.sleep(0.5) - sudo_write("894000.i2c", "/sys/bus/platform/drivers/i2c_geni/bind") - time.sleep(0.5) - os.system("sudo systemctl restart comma") - def uninstall(self): Path("/data/__system_reset__").touch() os.sync() diff --git a/system/logcatd/SConscript b/system/logcatd/SConscript deleted file mode 100644 index 6bd7c6f..0000000 --- a/system/logcatd/SConscript +++ /dev/null @@ -1,3 +0,0 @@ -Import('env', 'cereal', 'messaging', 'common') - -env.Program('logcatd', 'logcatd_systemd.cc', LIBS=[cereal, messaging, common, 'zmq', 'capnp', 'kj', 'systemd', 'json11']) diff --git a/system/logcatd/logcatd b/system/logcatd/logcatd new file mode 100755 index 0000000..56804f5 Binary files /dev/null and b/system/logcatd/logcatd differ diff --git a/system/logcatd/logcatd_systemd.cc b/system/logcatd/logcatd_systemd.cc deleted file mode 100644 index 54b3782..0000000 --- a/system/logcatd/logcatd_systemd.cc +++ /dev/null @@ -1,75 +0,0 @@ -#include - -#include -#include -#include -#include - -#include "third_party/json11/json11.hpp" - -#include "cereal/messaging/messaging.h" -#include "common/timing.h" -#include "common/util.h" - -ExitHandler do_exit; -int main(int argc, char *argv[]) { - - PubMaster pm({"androidLog"}); - - sd_journal *journal; - int err = sd_journal_open(&journal, 0); - assert(err >= 0); - err = sd_journal_get_fd(journal); // needed so sd_journal_wait() works properly if files rotate - assert(err >= 0); - err = sd_journal_seek_tail(journal); - assert(err >= 0); - - // workaround for bug https://github.com/systemd/systemd/issues/9934 - // call sd_journal_previous_skip after sd_journal_seek_tail (like journalctl -f does) to makes things work. - sd_journal_previous_skip(journal, 1); - - while (!do_exit) { - err = sd_journal_next(journal); - assert(err >= 0); - - // Wait for new message if we didn't receive anything - if (err == 0) { - err = sd_journal_wait(journal, 1000 * 1000); - assert(err >= 0); - continue; // Try again - } - - uint64_t timestamp = 0; - err = sd_journal_get_realtime_usec(journal, ×tamp); - assert(err >= 0); - - const void *data; - size_t length; - std::map kv; - - SD_JOURNAL_FOREACH_DATA(journal, data, length) { - std::string str((char*)data, length); - - // Split "KEY=VALUE"" on "=" and put in map - std::size_t found = str.find("="); - if (found != std::string::npos) { - kv[str.substr(0, found)] = str.substr(found + 1, std::string::npos); - } - } - - MessageBuilder msg; - - // Build message - auto androidEntry = msg.initEvent().initAndroidLog(); - androidEntry.setTs(timestamp); - androidEntry.setMessage(json11::Json(kv).dump()); - if (kv.count("_PID")) androidEntry.setPid(std::atoi(kv["_PID"].c_str())); - if (kv.count("PRIORITY")) androidEntry.setPriority(std::atoi(kv["PRIORITY"].c_str())); - if (kv.count("SYSLOG_IDENTIFIER")) androidEntry.setTag(kv["SYSLOG_IDENTIFIER"]); - - pm.send("androidLog", msg); - } - - sd_journal_close(journal); - return 0; -} diff --git a/system/loggerd/SConscript b/system/loggerd/SConscript deleted file mode 100644 index d4f52fb..0000000 --- a/system/loggerd/SConscript +++ /dev/null @@ -1,27 +0,0 @@ -Import('env', 'arch', 'cereal', 'messaging', 'common', 'visionipc') - -libs = [common, cereal, messaging, visionipc, - 'zmq', 'capnp', 'kj', 'z', - 'avformat', 'avcodec', 'swscale', 'avutil', - 'yuv', 'OpenCL', 'pthread'] - -src = ['logger.cc', 'video_writer.cc', 'encoder/encoder.cc', 'encoder/v4l_encoder.cc'] -if arch != "larch64": - src += ['encoder/ffmpeg_encoder.cc'] - -if arch == "Darwin": - # fix OpenCL - del libs[libs.index('OpenCL')] - env['FRAMEWORKS'] = ['OpenCL'] - # exclude v4l - del src[src.index('encoder/v4l_encoder.cc')] - -logger_lib = env.Library('logger', src) -libs.insert(0, logger_lib) - -env.Program('loggerd', ['loggerd.cc'], LIBS=libs) -env.Program('encoderd', ['encoderd.cc'], LIBS=libs) -env.Program('bootlog.cc', LIBS=libs) - -if GetOption('extras'): - env.Program('tests/test_logger', ['tests/test_runner.cc', 'tests/test_logger.cc'], LIBS=libs + ['curl', 'crypto']) diff --git a/system/loggerd/bootlog b/system/loggerd/bootlog new file mode 100755 index 0000000..4878a24 Binary files /dev/null and b/system/loggerd/bootlog differ diff --git a/system/loggerd/bootlog.cc b/system/loggerd/bootlog.cc deleted file mode 100644 index b8257b6..0000000 --- a/system/loggerd/bootlog.cc +++ /dev/null @@ -1,70 +0,0 @@ -#include -#include - -#include "cereal/messaging/messaging.h" -#include "common/params.h" -#include "common/swaglog.h" -#include "system/loggerd/logger.h" - - -static kj::Array build_boot_log() { - MessageBuilder msg; - auto boot = msg.initEvent().initBoot(); - - boot.setWallTimeNanos(nanos_since_epoch()); - - std::string pstore = "/sys/fs/pstore"; - std::map pstore_map = util::read_files_in_dir(pstore); - - int i = 0; - auto lpstore = boot.initPstore().initEntries(pstore_map.size()); - for (auto& kv : pstore_map) { - auto lentry = lpstore[i]; - lentry.setKey(kv.first); - lentry.setValue(capnp::Data::Reader((const kj::byte*)kv.second.data(), kv.second.size())); - i++; - } - - // Gather output of commands - std::vector bootlog_commands = { - "[ -x \"$(command -v journalctl)\" ] && journalctl", - }; - - if (Hardware::TICI()) { - bootlog_commands.push_back("[ -e /dev/nvme0 ] && sudo nvme smart-log --output-format=json /dev/nvme0"); - } - - auto commands = boot.initCommands().initEntries(bootlog_commands.size()); - for (int j = 0; j < bootlog_commands.size(); j++) { - auto lentry = commands[j]; - - lentry.setKey(bootlog_commands[j]); - - const std::string result = util::check_output(bootlog_commands[j]); - lentry.setValue(capnp::Data::Reader((const kj::byte*)result.data(), result.size())); - } - - boot.setLaunchLog(util::read_file("/tmp/launch_log")); - return capnp::messageToFlatArray(msg); -} - -int main(int argc, char** argv) { - const std::string id = logger_get_identifier("BootCount"); - const std::string path = Path::log_root() + "/boot/" + id; - LOGW("bootlog to %s", path.c_str()); - - // Open bootlog - bool r = util::create_directories(Path::log_root() + "/boot/", 0775); - assert(r); - - RawFile file(path.c_str()); - // Write initdata - file.write(logger_build_init_data().asBytes()); - // Write bootlog - file.write(build_boot_log().asBytes()); - - // Write out bootlog param to match routes with bootlog - Params().put("CurrentBootlog", id.c_str()); - - return 0; -} diff --git a/system/loggerd/encoder/encoder.cc b/system/loggerd/encoder/encoder.cc deleted file mode 100644 index c4bd91b..0000000 --- a/system/loggerd/encoder/encoder.cc +++ /dev/null @@ -1,43 +0,0 @@ -#include "system/loggerd/encoder/encoder.h" - -VideoEncoder::VideoEncoder(const EncoderInfo &encoder_info, int in_width, int in_height) - : encoder_info(encoder_info), in_width(in_width), in_height(in_height) { - - out_width = encoder_info.frame_width > 0 ? encoder_info.frame_width : in_width; - out_height = encoder_info.frame_height > 0 ? encoder_info.frame_height : in_height; - - pm.reset(new PubMaster({encoder_info.publish_name})); -} - -void VideoEncoder::publisher_publish(VideoEncoder *e, int segment_num, uint32_t idx, VisionIpcBufExtra &extra, - unsigned int flags, kj::ArrayPtr header, kj::ArrayPtr dat) { - // broadcast packet - MessageBuilder msg; - auto event = msg.initEvent(true); - auto edat = (event.*(e->encoder_info.init_encode_data_func))(); - auto edata = edat.initIdx(); - struct timespec ts; - timespec_get(&ts, TIME_UTC); - edat.setUnixTimestampNanos((uint64_t)ts.tv_sec*1000000000 + ts.tv_nsec); - edata.setFrameId(extra.frame_id); - edata.setTimestampSof(extra.timestamp_sof); - edata.setTimestampEof(extra.timestamp_eof); - edata.setType(e->encoder_info.encode_type); - edata.setEncodeId(e->cnt++); - edata.setSegmentNum(segment_num); - edata.setSegmentId(idx); - edata.setFlags(flags); - edata.setLen(dat.size()); - edat.setData(dat); - edat.setWidth(out_width); - edat.setHeight(out_height); - if (flags & V4L2_BUF_FLAG_KEYFRAME) edat.setHeader(header); - - uint32_t bytes_size = capnp::computeSerializedSizeInWords(msg) * sizeof(capnp::word); - if (e->msg_cache.size() < bytes_size) { - e->msg_cache.resize(bytes_size); - } - kj::ArrayOutputStream output_stream(kj::ArrayPtr(e->msg_cache.data(), bytes_size)); - capnp::writeMessage(output_stream, msg); - e->pm->send(e->encoder_info.publish_name, e->msg_cache.data(), bytes_size); -} diff --git a/system/loggerd/encoder/encoder.h b/system/loggerd/encoder/encoder.h deleted file mode 100644 index 7c203f9..0000000 --- a/system/loggerd/encoder/encoder.h +++ /dev/null @@ -1,37 +0,0 @@ -#pragma once - -#include -#include -#include -#include -#include - -#include "cereal/messaging/messaging.h" -#include "cereal/visionipc/visionipc.h" -#include "common/queue.h" -#include "system/camerad/cameras/camera_common.h" -#include "system/loggerd/loggerd.h" - -#define V4L2_BUF_FLAG_KEYFRAME 8 - -class VideoEncoder { -public: - VideoEncoder(const EncoderInfo &encoder_info, int in_width, int in_height); - virtual ~VideoEncoder() {} - virtual int encode_frame(VisionBuf* buf, VisionIpcBufExtra *extra) = 0; - virtual void encoder_open(const char* path) = 0; - virtual void encoder_close() = 0; - - void publisher_publish(VideoEncoder *e, int segment_num, uint32_t idx, VisionIpcBufExtra &extra, unsigned int flags, kj::ArrayPtr header, kj::ArrayPtr dat); - -protected: - int in_width, in_height; - int out_width, out_height; - const EncoderInfo encoder_info; - -private: - // total frames encoded - int cnt = 0; - std::unique_ptr pm; - std::vector msg_cache; -}; diff --git a/system/loggerd/encoder/ffmpeg_encoder.cc b/system/loggerd/encoder/ffmpeg_encoder.cc deleted file mode 100644 index 9d992f0..0000000 --- a/system/loggerd/encoder/ffmpeg_encoder.cc +++ /dev/null @@ -1,150 +0,0 @@ -#pragma clang diagnostic ignored "-Wdeprecated-declarations" - -#include "system/loggerd/encoder/ffmpeg_encoder.h" - -#include -#include - -#include -#include -#include - -#define __STDC_CONSTANT_MACROS - -#include "third_party/libyuv/include/libyuv.h" - -extern "C" { -#include -#include -#include -} - -#include "common/swaglog.h" -#include "common/util.h" - -const int env_debug_encoder = (getenv("DEBUG_ENCODER") != NULL) ? atoi(getenv("DEBUG_ENCODER")) : 0; - -FfmpegEncoder::FfmpegEncoder(const EncoderInfo &encoder_info, int in_width, int in_height) - : VideoEncoder(encoder_info, in_width, in_height) { - frame = av_frame_alloc(); - assert(frame); - frame->format = AV_PIX_FMT_YUV420P; - frame->width = out_width; - frame->height = out_height; - frame->linesize[0] = out_width; - frame->linesize[1] = out_width/2; - frame->linesize[2] = out_width/2; - - convert_buf.resize(in_width * in_height * 3 / 2); - - if (in_width != out_width || in_height != out_height) { - downscale_buf.resize(out_width * out_height * 3 / 2); - } -} - -FfmpegEncoder::~FfmpegEncoder() { - encoder_close(); - av_frame_free(&frame); -} - -void FfmpegEncoder::encoder_open(const char* path) { - const AVCodec *codec = avcodec_find_encoder(AV_CODEC_ID_FFVHUFF); - - this->codec_ctx = avcodec_alloc_context3(codec); - assert(this->codec_ctx); - this->codec_ctx->width = frame->width; - this->codec_ctx->height = frame->height; - this->codec_ctx->pix_fmt = AV_PIX_FMT_YUV420P; - this->codec_ctx->time_base = (AVRational){ 1, encoder_info.fps }; - int err = avcodec_open2(this->codec_ctx, codec, NULL); - assert(err >= 0); - - is_open = true; - segment_num++; - counter = 0; -} - -void FfmpegEncoder::encoder_close() { - if (!is_open) return; - - avcodec_free_context(&codec_ctx); - is_open = false; -} - -int FfmpegEncoder::encode_frame(VisionBuf* buf, VisionIpcBufExtra *extra) { - assert(buf->width == this->in_width); - assert(buf->height == this->in_height); - - uint8_t *cy = convert_buf.data(); - uint8_t *cu = cy + in_width * in_height; - uint8_t *cv = cu + (in_width / 2) * (in_height / 2); - libyuv::NV12ToI420(buf->y, buf->stride, - buf->uv, buf->stride, - cy, in_width, - cu, in_width/2, - cv, in_width/2, - in_width, in_height); - - if (downscale_buf.size() > 0) { - uint8_t *out_y = downscale_buf.data(); - uint8_t *out_u = out_y + frame->width * frame->height; - uint8_t *out_v = out_u + (frame->width / 2) * (frame->height / 2); - libyuv::I420Scale(cy, in_width, - cu, in_width/2, - cv, in_width/2, - in_width, in_height, - out_y, frame->width, - out_u, frame->width/2, - out_v, frame->width/2, - frame->width, frame->height, - libyuv::kFilterNone); - frame->data[0] = out_y; - frame->data[1] = out_u; - frame->data[2] = out_v; - } else { - frame->data[0] = cy; - frame->data[1] = cu; - frame->data[2] = cv; - } - frame->pts = counter*50*1000; // 50ms per frame - - int ret = counter; - - int err = avcodec_send_frame(this->codec_ctx, frame); - if (err < 0) { - LOGE("avcodec_send_frame error %d", err); - ret = -1; - } - - AVPacket pkt; - av_init_packet(&pkt); - pkt.data = NULL; - pkt.size = 0; - while (ret >= 0) { - err = avcodec_receive_packet(this->codec_ctx, &pkt); - if (err == AVERROR_EOF) { - break; - } else if (err == AVERROR(EAGAIN)) { - // Encoder might need a few frames on startup to get started. Keep going - ret = 0; - break; - } else if (err < 0) { - LOGE("avcodec_receive_packet error %d", err); - ret = -1; - break; - } - - if (env_debug_encoder) { - printf("%20s got %8d bytes flags %8x idx %4d id %8d\n", encoder_info.publish_name, pkt.size, pkt.flags, counter, extra->frame_id); - } - - publisher_publish(this, segment_num, counter, *extra, - (pkt.flags & AV_PKT_FLAG_KEY) ? V4L2_BUF_FLAG_KEYFRAME : 0, - kj::arrayPtr(pkt.data, (size_t)0), // TODO: get the header - kj::arrayPtr(pkt.data, pkt.size)); - - counter++; - } - av_packet_unref(&pkt); - return ret; -} diff --git a/system/loggerd/encoder/ffmpeg_encoder.h b/system/loggerd/encoder/ffmpeg_encoder.h deleted file mode 100644 index 9e45a3d..0000000 --- a/system/loggerd/encoder/ffmpeg_encoder.h +++ /dev/null @@ -1,34 +0,0 @@ -#pragma once - -#include -#include -#include -#include - -extern "C" { -#include -#include -#include -} - -#include "system/loggerd/encoder/encoder.h" -#include "system/loggerd/loggerd.h" - -class FfmpegEncoder : public VideoEncoder { -public: - FfmpegEncoder(const EncoderInfo &encoder_info, int in_width, int in_height); - ~FfmpegEncoder(); - int encode_frame(VisionBuf* buf, VisionIpcBufExtra *extra); - void encoder_open(const char* path); - void encoder_close(); - -private: - int segment_num = -1; - int counter = 0; - bool is_open = false; - - AVCodecContext *codec_ctx; - AVFrame *frame = NULL; - std::vector convert_buf; - std::vector downscale_buf; -}; diff --git a/system/loggerd/encoder/v4l_encoder.cc b/system/loggerd/encoder/v4l_encoder.cc deleted file mode 100644 index 2bd2863..0000000 --- a/system/loggerd/encoder/v4l_encoder.cc +++ /dev/null @@ -1,326 +0,0 @@ -#include -#include -#include -#include - -#include "system/loggerd/encoder/v4l_encoder.h" -#include "common/util.h" -#include "common/timing.h" - -#include "third_party/libyuv/include/libyuv.h" -#include "third_party/linux/include/msm_media_info.h" - -// has to be in this order -#include "third_party/linux/include/v4l2-controls.h" -#include -#define V4L2_QCOM_BUF_FLAG_CODECCONFIG 0x00020000 -#define V4L2_QCOM_BUF_FLAG_EOS 0x02000000 - -// echo 0x7fffffff > /sys/kernel/debug/msm_vidc/debug_level -const int env_debug_encoder = (getenv("DEBUG_ENCODER") != NULL) ? atoi(getenv("DEBUG_ENCODER")) : 0; - -static void checked_ioctl(int fd, unsigned long request, void *argp) { - int ret = util::safe_ioctl(fd, request, argp); - if (ret != 0) { - LOGE("checked_ioctl failed with error %d (%d %lx %p)", errno, fd, request, argp); - assert(0); - } -} - -static void dequeue_buffer(int fd, v4l2_buf_type buf_type, unsigned int *index=NULL, unsigned int *bytesused=NULL, unsigned int *flags=NULL, struct timeval *timestamp=NULL) { - v4l2_plane plane = {0}; - v4l2_buffer v4l_buf = { - .type = buf_type, - .memory = V4L2_MEMORY_USERPTR, - .m = { .planes = &plane, }, - .length = 1, - }; - checked_ioctl(fd, VIDIOC_DQBUF, &v4l_buf); - - if (index) *index = v4l_buf.index; - if (bytesused) *bytesused = v4l_buf.m.planes[0].bytesused; - if (flags) *flags = v4l_buf.flags; - if (timestamp) *timestamp = v4l_buf.timestamp; - assert(v4l_buf.m.planes[0].data_offset == 0); -} - -static void queue_buffer(int fd, v4l2_buf_type buf_type, unsigned int index, VisionBuf *buf, struct timeval timestamp={}) { - v4l2_plane plane = { - .length = (unsigned int)buf->len, - .m = { .userptr = (unsigned long)buf->addr, }, - .bytesused = (uint32_t)buf->len, - .reserved = {(unsigned int)buf->fd} - }; - - v4l2_buffer v4l_buf = { - .type = buf_type, - .index = index, - .memory = V4L2_MEMORY_USERPTR, - .m = { .planes = &plane, }, - .length = 1, - .flags = V4L2_BUF_FLAG_TIMESTAMP_COPY, - .timestamp = timestamp - }; - - checked_ioctl(fd, VIDIOC_QBUF, &v4l_buf); -} - -static void request_buffers(int fd, v4l2_buf_type buf_type, unsigned int count) { - struct v4l2_requestbuffers reqbuf = { - .type = buf_type, - .memory = V4L2_MEMORY_USERPTR, - .count = count - }; - checked_ioctl(fd, VIDIOC_REQBUFS, &reqbuf); -} - -void V4LEncoder::dequeue_handler(V4LEncoder *e) { - std::string dequeue_thread_name = "dq-"+std::string(e->encoder_info.publish_name); - util::set_thread_name(dequeue_thread_name.c_str()); - - e->segment_num++; - uint32_t idx = -1; - bool exit = false; - - // POLLIN is capture, POLLOUT is frame - struct pollfd pfd; - pfd.events = POLLIN | POLLOUT; - pfd.fd = e->fd; - - // save the header - kj::Array header; - - while (!exit) { - int rc = poll(&pfd, 1, 1000); - if (rc < 0) { - if (errno != EINTR) { - // TODO: exit encoder? - // ignore the error and keep going - LOGE("poll failed (%d - %d)", rc, errno); - } - continue; - } else if (rc == 0) { - LOGE("encoder dequeue poll timeout"); - continue; - } - - if (env_debug_encoder >= 2) { - printf("%20s poll %x at %.2f ms\n", e->encoder_info.publish_name, pfd.revents, millis_since_boot()); - } - - int frame_id = -1; - if (pfd.revents & POLLIN) { - unsigned int bytesused, flags, index; - struct timeval timestamp; - dequeue_buffer(e->fd, V4L2_BUF_TYPE_VIDEO_CAPTURE_MPLANE, &index, &bytesused, &flags, ×tamp); - e->buf_out[index].sync(VISIONBUF_SYNC_FROM_DEVICE); - uint8_t *buf = (uint8_t*)e->buf_out[index].addr; - int64_t ts = timestamp.tv_sec * 1000000 + timestamp.tv_usec; - - // eof packet, we exit - if (flags & V4L2_QCOM_BUF_FLAG_EOS) { - exit = true; - } else if (flags & V4L2_QCOM_BUF_FLAG_CODECCONFIG) { - // save header - header = kj::heapArray(buf, bytesused); - } else { - VisionIpcBufExtra extra = e->extras.pop(); - assert(extra.timestamp_eof/1000 == ts); // stay in sync - frame_id = extra.frame_id; - ++idx; - e->publisher_publish(e, e->segment_num, idx, extra, flags, header, kj::arrayPtr(buf, bytesused)); - } - - if (env_debug_encoder) { - printf("%20s got(%d) %6d bytes flags %8x idx %3d/%4d id %8d ts %ld lat %.2f ms (%lu frames free)\n", - e->encoder_info.publish_name, index, bytesused, flags, e->segment_num, idx, frame_id, ts, millis_since_boot()-(ts/1000.), e->free_buf_in.size()); - } - - // requeue the buffer - queue_buffer(e->fd, V4L2_BUF_TYPE_VIDEO_CAPTURE_MPLANE, index, &e->buf_out[index]); - } - - if (pfd.revents & POLLOUT) { - unsigned int index; - dequeue_buffer(e->fd, V4L2_BUF_TYPE_VIDEO_OUTPUT_MPLANE, &index); - e->free_buf_in.push(index); - } - } -} - -V4LEncoder::V4LEncoder(const EncoderInfo &encoder_info, int in_width, int in_height) - : VideoEncoder(encoder_info, in_width, in_height) { - fd = open("/dev/v4l/by-path/platform-aa00000.qcom_vidc-video-index1", O_RDWR|O_NONBLOCK); - assert(fd >= 0); - - struct v4l2_capability cap; - checked_ioctl(fd, VIDIOC_QUERYCAP, &cap); - LOGD("opened encoder device %s %s = %d", cap.driver, cap.card, fd); - assert(strcmp((const char *)cap.driver, "msm_vidc_driver") == 0); - assert(strcmp((const char *)cap.card, "msm_vidc_venc") == 0); - - struct v4l2_format fmt_out = { - .type = V4L2_BUF_TYPE_VIDEO_CAPTURE_MPLANE, - .fmt = { - .pix_mp = { - // downscales are free with v4l - .width = (unsigned int)(out_width), - .height = (unsigned int)(out_height), - .pixelformat = (encoder_info.encode_type == cereal::EncodeIndex::Type::FULL_H_E_V_C) ? V4L2_PIX_FMT_HEVC : V4L2_PIX_FMT_H264, - .field = V4L2_FIELD_ANY, - .colorspace = V4L2_COLORSPACE_DEFAULT, - } - } - }; - checked_ioctl(fd, VIDIOC_S_FMT, &fmt_out); - - v4l2_streamparm streamparm = { - .type = V4L2_BUF_TYPE_VIDEO_OUTPUT_MPLANE, - .parm = { - .output = { - // TODO: more stuff here? we don't know - .timeperframe = { - .numerator = 1, - .denominator = 20 - } - } - } - }; - checked_ioctl(fd, VIDIOC_S_PARM, &streamparm); - - struct v4l2_format fmt_in = { - .type = V4L2_BUF_TYPE_VIDEO_OUTPUT_MPLANE, - .fmt = { - .pix_mp = { - .width = (unsigned int)in_width, - .height = (unsigned int)in_height, - .pixelformat = V4L2_PIX_FMT_NV12, - .field = V4L2_FIELD_ANY, - .colorspace = V4L2_COLORSPACE_470_SYSTEM_BG, - } - } - }; - checked_ioctl(fd, VIDIOC_S_FMT, &fmt_in); - - LOGD("in buffer size %d, out buffer size %d", - fmt_in.fmt.pix_mp.plane_fmt[0].sizeimage, - fmt_out.fmt.pix_mp.plane_fmt[0].sizeimage); - - // shared ctrls - { - struct v4l2_control ctrls[] = { - { .id = V4L2_CID_MPEG_VIDEO_HEADER_MODE, .value = V4L2_MPEG_VIDEO_HEADER_MODE_SEPARATE}, - { .id = V4L2_CID_MPEG_VIDEO_BITRATE, .value = encoder_info.bitrate}, - { .id = V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL, .value = V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_VBR_CFR}, - { .id = V4L2_CID_MPEG_VIDC_VIDEO_PRIORITY, .value = V4L2_MPEG_VIDC_VIDEO_PRIORITY_REALTIME_DISABLE}, - { .id = V4L2_CID_MPEG_VIDC_VIDEO_IDR_PERIOD, .value = 1}, - }; - for (auto ctrl : ctrls) { - checked_ioctl(fd, VIDIOC_S_CTRL, &ctrl); - } - } - - if (encoder_info.encode_type == cereal::EncodeIndex::Type::FULL_H_E_V_C) { - struct v4l2_control ctrls[] = { - { .id = V4L2_CID_MPEG_VIDC_VIDEO_HEVC_PROFILE, .value = V4L2_MPEG_VIDC_VIDEO_HEVC_PROFILE_MAIN}, - { .id = V4L2_CID_MPEG_VIDC_VIDEO_HEVC_TIER_LEVEL, .value = V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_5}, - { .id = V4L2_CID_MPEG_VIDC_VIDEO_VUI_TIMING_INFO, .value = V4L2_MPEG_VIDC_VIDEO_VUI_TIMING_INFO_ENABLED}, - { .id = V4L2_CID_MPEG_VIDC_VIDEO_NUM_P_FRAMES, .value = 29}, - { .id = V4L2_CID_MPEG_VIDC_VIDEO_NUM_B_FRAMES, .value = 0}, - }; - for (auto ctrl : ctrls) { - checked_ioctl(fd, VIDIOC_S_CTRL, &ctrl); - } - } else { - struct v4l2_control ctrls[] = { - { .id = V4L2_CID_MPEG_VIDEO_H264_PROFILE, .value = V4L2_MPEG_VIDEO_H264_PROFILE_HIGH}, - { .id = V4L2_CID_MPEG_VIDEO_H264_LEVEL, .value = V4L2_MPEG_VIDEO_H264_LEVEL_UNKNOWN}, - { .id = V4L2_CID_MPEG_VIDC_VIDEO_NUM_P_FRAMES, .value = 14}, - { .id = V4L2_CID_MPEG_VIDC_VIDEO_NUM_B_FRAMES, .value = 0}, - { .id = V4L2_CID_MPEG_VIDEO_H264_ENTROPY_MODE, .value = V4L2_MPEG_VIDEO_H264_ENTROPY_MODE_CABAC}, - { .id = V4L2_CID_MPEG_VIDC_VIDEO_H264_CABAC_MODEL, .value = V4L2_CID_MPEG_VIDC_VIDEO_H264_CABAC_MODEL_0}, - { .id = V4L2_CID_MPEG_VIDEO_H264_LOOP_FILTER_MODE, .value = 0}, - { .id = V4L2_CID_MPEG_VIDEO_H264_LOOP_FILTER_ALPHA, .value = 0}, - { .id = V4L2_CID_MPEG_VIDEO_H264_LOOP_FILTER_BETA, .value = 0}, - { .id = V4L2_CID_MPEG_VIDEO_MULTI_SLICE_MODE, .value = 0}, - }; - for (auto ctrl : ctrls) { - checked_ioctl(fd, VIDIOC_S_CTRL, &ctrl); - } - } - - // allocate buffers - request_buffers(fd, V4L2_BUF_TYPE_VIDEO_CAPTURE_MPLANE, BUF_OUT_COUNT); - request_buffers(fd, V4L2_BUF_TYPE_VIDEO_OUTPUT_MPLANE, BUF_IN_COUNT); - - // start encoder - v4l2_buf_type buf_type = V4L2_BUF_TYPE_VIDEO_CAPTURE_MPLANE; - checked_ioctl(fd, VIDIOC_STREAMON, &buf_type); - buf_type = V4L2_BUF_TYPE_VIDEO_OUTPUT_MPLANE; - checked_ioctl(fd, VIDIOC_STREAMON, &buf_type); - - // queue up output buffers - for (unsigned int i = 0; i < BUF_OUT_COUNT; i++) { - buf_out[i].allocate(fmt_out.fmt.pix_mp.plane_fmt[0].sizeimage); - queue_buffer(fd, V4L2_BUF_TYPE_VIDEO_CAPTURE_MPLANE, i, &buf_out[i]); - } - // queue up input buffers - for (unsigned int i = 0; i < BUF_IN_COUNT; i++) { - free_buf_in.push(i); - } -} - -void V4LEncoder::encoder_open(const char* path) { - dequeue_handler_thread = std::thread(V4LEncoder::dequeue_handler, this); - this->is_open = true; - this->counter = 0; -} - -int V4LEncoder::encode_frame(VisionBuf* buf, VisionIpcBufExtra *extra) { - struct timeval timestamp { - .tv_sec = (long)(extra->timestamp_eof/1000000000), - .tv_usec = (long)((extra->timestamp_eof/1000) % 1000000), - }; - - // reserve buffer - int buffer_in = free_buf_in.pop(); - - // push buffer - extras.push(*extra); - //buf->sync(VISIONBUF_SYNC_TO_DEVICE); - queue_buffer(fd, V4L2_BUF_TYPE_VIDEO_OUTPUT_MPLANE, buffer_in, buf, timestamp); - - return this->counter++; -} - -void V4LEncoder::encoder_close() { - if (this->is_open) { - // pop all the frames before closing, then put the buffers back - for (int i = 0; i < BUF_IN_COUNT; i++) free_buf_in.pop(); - for (int i = 0; i < BUF_IN_COUNT; i++) free_buf_in.push(i); - // no frames, stop the encoder - struct v4l2_encoder_cmd encoder_cmd = { .cmd = V4L2_ENC_CMD_STOP }; - checked_ioctl(fd, VIDIOC_ENCODER_CMD, &encoder_cmd); - // join waits for V4L2_QCOM_BUF_FLAG_EOS - dequeue_handler_thread.join(); - assert(extras.empty()); - } - this->is_open = false; -} - -V4LEncoder::~V4LEncoder() { - encoder_close(); - v4l2_buf_type buf_type = V4L2_BUF_TYPE_VIDEO_OUTPUT_MPLANE; - checked_ioctl(fd, VIDIOC_STREAMOFF, &buf_type); - request_buffers(fd, V4L2_BUF_TYPE_VIDEO_OUTPUT_MPLANE, 0); - buf_type = V4L2_BUF_TYPE_VIDEO_CAPTURE_MPLANE; - checked_ioctl(fd, VIDIOC_STREAMOFF, &buf_type); - request_buffers(fd, V4L2_BUF_TYPE_VIDEO_CAPTURE_MPLANE, 0); - close(fd); - - for (int i = 0; i < BUF_OUT_COUNT; i++) { - if (buf_out[i].free() != 0) { - LOGE("Failed to free buffer"); - } - } -} diff --git a/system/loggerd/encoder/v4l_encoder.h b/system/loggerd/encoder/v4l_encoder.h deleted file mode 100644 index 9336bf3..0000000 --- a/system/loggerd/encoder/v4l_encoder.h +++ /dev/null @@ -1,30 +0,0 @@ -#pragma once - -#include "common/queue.h" -#include "system/loggerd/encoder/encoder.h" - -#define BUF_IN_COUNT 7 -#define BUF_OUT_COUNT 6 - -class V4LEncoder : public VideoEncoder { -public: - V4LEncoder(const EncoderInfo &encoder_info, int in_width, int in_height); - ~V4LEncoder(); - int encode_frame(VisionBuf* buf, VisionIpcBufExtra *extra); - void encoder_open(const char* path); - void encoder_close(); -private: - int fd; - - bool is_open = false; - int segment_num = -1; - int counter = 0; - - SafeQueue extras; - - static void dequeue_handler(V4LEncoder *e); - std::thread dequeue_handler_thread; - - VisionBuf buf_out[BUF_OUT_COUNT]; - SafeQueue free_buf_in; -}; diff --git a/system/loggerd/encoderd b/system/loggerd/encoderd new file mode 100755 index 0000000..8637cd6 Binary files /dev/null and b/system/loggerd/encoderd differ diff --git a/system/loggerd/encoderd.cc b/system/loggerd/encoderd.cc deleted file mode 100644 index 1b45df6..0000000 --- a/system/loggerd/encoderd.cc +++ /dev/null @@ -1,161 +0,0 @@ -#include - -#include "system/loggerd/loggerd.h" - -#ifdef QCOM2 -#include "system/loggerd/encoder/v4l_encoder.h" -#define Encoder V4LEncoder -#else -#include "system/loggerd/encoder/ffmpeg_encoder.h" -#define Encoder FfmpegEncoder -#endif - -ExitHandler do_exit; - -struct EncoderdState { - int max_waiting = 0; - - // Sync logic for startup - std::atomic encoders_ready = 0; - std::atomic start_frame_id = 0; - bool camera_ready[WideRoadCam + 1] = {}; - bool camera_synced[WideRoadCam + 1] = {}; -}; - -// Handle initial encoder syncing by waiting for all encoders to reach the same frame id -bool sync_encoders(EncoderdState *s, CameraType cam_type, uint32_t frame_id) { - if (s->camera_synced[cam_type]) return true; - - if (s->max_waiting > 1 && s->encoders_ready != s->max_waiting) { - // add a small margin to the start frame id in case one of the encoders already dropped the next frame - update_max_atomic(s->start_frame_id, frame_id + 2); - if (std::exchange(s->camera_ready[cam_type], true) == false) { - ++s->encoders_ready; - LOGD("camera %d encoder ready", cam_type); - } - return false; - } else { - if (s->max_waiting == 1) update_max_atomic(s->start_frame_id, frame_id); - bool synced = frame_id >= s->start_frame_id; - s->camera_synced[cam_type] = synced; - if (!synced) LOGD("camera %d waiting for frame %d, cur %d", cam_type, (int)s->start_frame_id, frame_id); - return synced; - } -} - - -void encoder_thread(EncoderdState *s, const LogCameraInfo &cam_info) { - util::set_thread_name(cam_info.thread_name); - - std::vector> encoders; - VisionIpcClient vipc_client = VisionIpcClient("camerad", cam_info.stream_type, false); - - int cur_seg = 0; - while (!do_exit) { - if (!vipc_client.connect(false)) { - util::sleep_for(5); - continue; - } - - // init encoders - if (encoders.empty()) { - VisionBuf buf_info = vipc_client.buffers[0]; - LOGW("encoder %s init %zux%zu", cam_info.thread_name, buf_info.width, buf_info.height); - assert(buf_info.width > 0 && buf_info.height > 0); - - for (const auto &encoder_info : cam_info.encoder_infos) { - auto &e = encoders.emplace_back(new Encoder(encoder_info, buf_info.width, buf_info.height)); - e->encoder_open(nullptr); - } - } - - bool lagging = false; - while (!do_exit) { - VisionIpcBufExtra extra; - VisionBuf* buf = vipc_client.recv(&extra); - if (buf == nullptr) continue; - - // detect loop around and drop the frames - if (buf->get_frame_id() != extra.frame_id) { - if (!lagging) { - LOGE("encoder %s lag buffer id: %" PRIu64 " extra id: %d", cam_info.thread_name, buf->get_frame_id(), extra.frame_id); - lagging = true; - } - continue; - } - lagging = false; - - if (!sync_encoders(s, cam_info.type, extra.frame_id)) { - continue; - } - if (do_exit) break; - - // do rotation if required - const int frames_per_seg = SEGMENT_LENGTH * MAIN_FPS; - if (cur_seg >= 0 && extra.frame_id >= ((cur_seg + 1) * frames_per_seg) + s->start_frame_id) { - for (auto &e : encoders) { - e->encoder_close(); - e->encoder_open(NULL); - } - ++cur_seg; - } - - // encode a frame - for (int i = 0; i < encoders.size(); ++i) { - int out_id = encoders[i]->encode_frame(buf, &extra); - - if (out_id == -1) { - LOGE("Failed to encode frame. frame_id: %d", extra.frame_id); - } - } - } - } -} - -template -void encoderd_thread(const LogCameraInfo (&cameras)[N]) { - EncoderdState s; - - std::set streams; - while (!do_exit) { - streams = VisionIpcClient::getAvailableStreams("camerad", false); - if (!streams.empty()) { - break; - } - util::sleep_for(100); - } - - if (!streams.empty()) { - std::vector encoder_threads; - for (auto stream : streams) { - auto it = std::find_if(std::begin(cameras), std::end(cameras), - [stream](auto &cam) { return cam.stream_type == stream; }); - assert(it != std::end(cameras)); - ++s.max_waiting; - encoder_threads.push_back(std::thread(encoder_thread, &s, *it)); - } - - for (auto &t : encoder_threads) t.join(); - } -} - -int main(int argc, char* argv[]) { - if (!Hardware::PC()) { - int ret; - ret = util::set_realtime_priority(52); - assert(ret == 0); - ret = util::set_core_affinity({3}); - assert(ret == 0); - } - if (argc > 1) { - std::string arg1(argv[1]); - if (arg1 == "--stream") { - encoderd_thread(stream_cameras_logged); - } else { - LOGE("Argument '%s' is not supported", arg1.c_str()); - } - } else { - encoderd_thread(cameras_logged); - } - return 0; -} diff --git a/system/loggerd/logger.cc b/system/loggerd/logger.cc deleted file mode 100644 index 7a829a2..0000000 --- a/system/loggerd/logger.cc +++ /dev/null @@ -1,172 +0,0 @@ -#include "system/loggerd/logger.h" - -#include -#include -#include -#include -#include -#include - -#include "common/params.h" -#include "common/swaglog.h" -#include "common/version.h" - -// ***** log metadata ***** -kj::Array logger_build_init_data() { - uint64_t wall_time = nanos_since_epoch(); - - MessageBuilder msg; - auto init = msg.initEvent().initInitData(); - - init.setWallTimeNanos(wall_time); - init.setVersion(COMMA_VERSION); - init.setDirty(!getenv("CLEAN")); - init.setDeviceType(Hardware::get_device_type()); - - // log kernel args - std::ifstream cmdline_stream("/proc/cmdline"); - std::vector kernel_args; - std::string buf; - while (cmdline_stream >> buf) { - kernel_args.push_back(buf); - } - - auto lkernel_args = init.initKernelArgs(kernel_args.size()); - for (int i=0; i params_map = params.readAll(); - - init.setGitCommit(params_map["GitCommit"]); - init.setGitCommitDate(params_map["GitCommitDate"]); - init.setGitBranch(params_map["GitBranch"]); - init.setGitRemote(params_map["GitRemote"]); - init.setPassive(false); - init.setDongleId(params_map["DongleId"]); - - auto lparams = init.initParams().initEntries(params_map.size()); - int j = 0; - for (auto& [key, value] : params_map) { - auto lentry = lparams[j]; - lentry.setKey(key); - if ( !(params.getKeyType(key) & DONT_LOG) ) { - lentry.setValue(capnp::Data::Reader((const kj::byte*)value.data(), value.size())); - } - j++; - } - - // log commands - std::vector log_commands = { - "df -h", // usage for all filesystems - }; - - auto hw_logs = Hardware::get_init_logs(); - - auto commands = init.initCommands().initEntries(log_commands.size() + hw_logs.size()); - for (int i = 0; i < log_commands.size(); i++) { - auto lentry = commands[i]; - - lentry.setKey(log_commands[i]); - - const std::string result = util::check_output(log_commands[i]); - lentry.setValue(capnp::Data::Reader((const kj::byte*)result.data(), result.size())); - } - - int i = log_commands.size(); - for (auto &[key, value] : hw_logs) { - auto lentry = commands[i]; - lentry.setKey(key); - lentry.setValue(capnp::Data::Reader((const kj::byte*)value.data(), value.size())); - i++; - } - - return capnp::messageToFlatArray(msg); -} - -std::string logger_get_route_name() { - char route_name[64] = {'\0'}; - time_t rawtime = time(NULL); - struct tm timeinfo; - localtime_r(&rawtime, &timeinfo); - strftime(route_name, sizeof(route_name), "%Y-%m-%d--%H-%M-%S", &timeinfo); - return route_name; -} - -std::string logger_get_identifier(std::string key) { - // a log identifier is a 32 bit counter, plus a 10 character unique ID. - // e.g. 000001a3--c20ba54385 - - Params params; - uint32_t cnt; - try { - cnt = std::stol(params.get(key)); - } catch (std::exception &e) { - cnt = 0; - } - params.put(key, std::to_string(cnt + 1)); - - std::stringstream ss; - std::random_device rd; - std::mt19937 mt(rd()); - std::uniform_int_distribution dist(0, 15); - for (int i = 0; i < 10; ++i) { - ss << std::hex << dist(mt); - } - - return util::string_format("%08x--%s", cnt, ss.str().c_str()); -} - -static void log_sentinel(LoggerState *log, SentinelType type, int eixt_signal = 0) { - MessageBuilder msg; - auto sen = msg.initEvent().initSentinel(); - sen.setType(type); - sen.setSignal(eixt_signal); - log->write(msg.toBytes(), true); -} - -LoggerState::LoggerState(const std::string &log_root) { - route_name = logger_get_route_name(); - route_path = log_root + "/" + route_name; - init_data = logger_build_init_data(); -} - -LoggerState::~LoggerState() { - if (rlog) { - log_sentinel(this, SentinelType::END_OF_ROUTE, exit_signal); - std::remove(lock_file.c_str()); - } -} - -bool LoggerState::next() { - if (rlog) { - log_sentinel(this, SentinelType::END_OF_SEGMENT); - std::remove(lock_file.c_str()); - } - - segment_path = route_path + "--" + std::to_string(++part); - bool ret = util::create_directories(segment_path, 0775); - assert(ret == true); - - const std::string rlog_path = segment_path + "/rlog"; - lock_file = rlog_path + ".lock"; - std::ofstream{lock_file}; - - rlog.reset(new RawFile(rlog_path)); - qlog.reset(new RawFile(segment_path + "/qlog")); - - // log init data & sentinel type. - write(init_data.asBytes(), true); - log_sentinel(this, part > 0 ? SentinelType::START_OF_SEGMENT : SentinelType::START_OF_ROUTE); - return true; -} - -void LoggerState::write(uint8_t* data, size_t size, bool in_qlog) { - rlog->write(data, size); - if (in_qlog) qlog->write(data, size); -} diff --git a/system/loggerd/logger.h b/system/loggerd/logger.h deleted file mode 100644 index dd3bee1..0000000 --- a/system/loggerd/logger.h +++ /dev/null @@ -1,56 +0,0 @@ -#pragma once - -#include -#include -#include - -#include "cereal/messaging/messaging.h" -#include "common/util.h" -#include "system/hardware/hw.h" - -class RawFile { - public: - RawFile(const std::string &path) { - file = util::safe_fopen(path.c_str(), "wb"); - assert(file != nullptr); - } - ~RawFile() { - util::safe_fflush(file); - int err = fclose(file); - assert(err == 0); - } - inline void write(void* data, size_t size) { - int written = util::safe_fwrite(data, 1, size, file); - assert(written == size); - } - inline void write(kj::ArrayPtr array) { write(array.begin(), array.size()); } - - private: - FILE* file = nullptr; -}; - -typedef cereal::Sentinel::SentinelType SentinelType; - - -class LoggerState { -public: - LoggerState(const std::string& log_root = Path::log_root()); - ~LoggerState(); - bool next(); - void write(uint8_t* data, size_t size, bool in_qlog); - inline int segment() const { return part; } - inline const std::string& segmentPath() const { return segment_path; } - inline const std::string& routeName() const { return route_name; } - inline void write(kj::ArrayPtr bytes, bool in_qlog) { write(bytes.begin(), bytes.size(), in_qlog); } - inline void setExitSignal(int signal) { exit_signal = signal; } - -protected: - int part = -1, exit_signal = 0; - std::string route_path, route_name, segment_path, lock_file; - kj::Array init_data; - std::unique_ptr rlog, qlog; -}; - -kj::Array logger_build_init_data(); -std::string logger_get_route_name(); -std::string logger_get_identifier(std::string key); diff --git a/system/loggerd/loggerd b/system/loggerd/loggerd new file mode 100755 index 0000000..76d96af Binary files /dev/null and b/system/loggerd/loggerd differ diff --git a/system/loggerd/loggerd.cc b/system/loggerd/loggerd.cc deleted file mode 100644 index 3c0ffc1..0000000 --- a/system/loggerd/loggerd.cc +++ /dev/null @@ -1,313 +0,0 @@ -#include - -#include -#include -#include -#include -#include - -#include "common/params.h" -#include "system/loggerd/encoder/encoder.h" -#include "system/loggerd/loggerd.h" -#include "system/loggerd/video_writer.h" - -ExitHandler do_exit; - -struct LoggerdState { - LoggerState logger; - std::atomic last_camera_seen_tms; - std::atomic ready_to_rotate; // count of encoders ready to rotate - int max_waiting = 0; - double last_rotate_tms = 0.; // last rotate time in ms -}; - -void logger_rotate(LoggerdState *s) { - bool ret =s->logger.next(); - assert(ret); - s->ready_to_rotate = 0; - s->last_rotate_tms = millis_since_boot(); - LOGW((s->logger.segment() == 0) ? "logging to %s" : "rotated to %s", s->logger.segmentPath().c_str()); -} - -void rotate_if_needed(LoggerdState *s) { - // all encoders ready, trigger rotation - bool all_ready = s->ready_to_rotate == s->max_waiting; - - // fallback logic to prevent extremely long segments in the case of camera, encoder, etc. malfunctions - bool timed_out = false; - double tms = millis_since_boot(); - double seg_length_secs = (tms - s->last_rotate_tms) / 1000.; - if ((seg_length_secs > SEGMENT_LENGTH) && !LOGGERD_TEST) { - // TODO: might be nice to put these reasons in the sentinel - if ((tms - s->last_camera_seen_tms) > NO_CAMERA_PATIENCE) { - timed_out = true; - LOGE("no camera packets seen. auto rotating"); - } else if (seg_length_secs > SEGMENT_LENGTH*1.2) { - timed_out = true; - LOGE("segment too long. auto rotating"); - } - } - - if (all_ready || timed_out) { - logger_rotate(s); - } -} - -struct RemoteEncoder { - std::unique_ptr writer; - int encoderd_segment_offset; - int current_segment = -1; - std::vector q; - int dropped_frames = 0; - bool recording = false; - bool marked_ready_to_rotate = false; - bool seen_first_packet = false; -}; - -int handle_encoder_msg(LoggerdState *s, Message *msg, std::string &name, struct RemoteEncoder &re, const EncoderInfo &encoder_info) { - int bytes_count = 0; - - // extract the message - capnp::FlatArrayMessageReader cmsg(kj::ArrayPtr((capnp::word *)msg->getData(), msg->getSize() / sizeof(capnp::word))); - auto event = cmsg.getRoot(); - auto edata = (event.*(encoder_info.get_encode_data_func))(); - auto idx = edata.getIdx(); - auto flags = idx.getFlags(); - - // encoderd can have started long before loggerd - if (!re.seen_first_packet) { - re.seen_first_packet = true; - re.encoderd_segment_offset = idx.getSegmentNum(); - LOGD("%s: has encoderd offset %d", name.c_str(), re.encoderd_segment_offset); - } - int offset_segment_num = idx.getSegmentNum() - re.encoderd_segment_offset; - - if (offset_segment_num == s->logger.segment()) { - // loggerd is now on the segment that matches this packet - - // if this is a new segment, we close any possible old segments, move to the new, and process any queued packets - if (re.current_segment != s->logger.segment()) { - if (re.recording) { - re.writer.reset(); - re.recording = false; - } - re.current_segment = s->logger.segment(); - re.marked_ready_to_rotate = false; - // we are in this segment now, process any queued messages before this one - if (!re.q.empty()) { - for (auto &qmsg : re.q) { - bytes_count += handle_encoder_msg(s, qmsg, name, re, encoder_info); - } - re.q.clear(); - } - } - - // if we aren't recording yet, try to start, since we are in the correct segment - if (!re.recording) { - if (flags & V4L2_BUF_FLAG_KEYFRAME) { - // only create on iframe - if (re.dropped_frames) { - // this should only happen for the first segment, maybe - LOGW("%s: dropped %d non iframe packets before init", name.c_str(), re.dropped_frames); - re.dropped_frames = 0; - } - // if we aren't actually recording, don't create the writer - if (encoder_info.record) { - assert(encoder_info.filename != NULL); - re.writer.reset(new VideoWriter(s->logger.segmentPath().c_str(), - encoder_info.filename, idx.getType() != cereal::EncodeIndex::Type::FULL_H_E_V_C, - edata.getWidth(), edata.getHeight(), encoder_info.fps, idx.getType())); - // write the header - auto header = edata.getHeader(); - re.writer->write((uint8_t *)header.begin(), header.size(), idx.getTimestampEof()/1000, true, false); - } - re.recording = true; - } else { - // this is a sad case when we aren't recording, but don't have an iframe - // nothing we can do but drop the frame - delete msg; - ++re.dropped_frames; - return bytes_count; - } - } - - // we have to be recording if we are here - assert(re.recording); - - // if we are actually writing the video file, do so - if (re.writer) { - auto data = edata.getData(); - re.writer->write((uint8_t *)data.begin(), data.size(), idx.getTimestampEof()/1000, false, flags & V4L2_BUF_FLAG_KEYFRAME); - } - - // put it in log stream as the idx packet - MessageBuilder bmsg; - auto evt = bmsg.initEvent(event.getValid()); - evt.setLogMonoTime(event.getLogMonoTime()); - (evt.*(encoder_info.set_encode_idx_func))(idx); - auto new_msg = bmsg.toBytes(); - s->logger.write((uint8_t *)new_msg.begin(), new_msg.size(), true); // always in qlog? - bytes_count += new_msg.size(); - - // free the message, we used it - delete msg; - } else if (offset_segment_num > s->logger.segment()) { - // encoderd packet has a newer segment, this means encoderd has rolled over - if (!re.marked_ready_to_rotate) { - re.marked_ready_to_rotate = true; - ++s->ready_to_rotate; - LOGD("rotate %d -> %d ready %d/%d for %s", - s->logger.segment(), offset_segment_num, - s->ready_to_rotate.load(), s->max_waiting, name.c_str()); - } - // queue up all the new segment messages, they go in after the rotate - re.q.push_back(msg); - } else { - LOGE("%s: encoderd packet has a older segment!!! idx.getSegmentNum():%d s->logger.segment():%d re.encoderd_segment_offset:%d", - name.c_str(), idx.getSegmentNum(), s->logger.segment(), re.encoderd_segment_offset); - // free the message, it's useless. this should never happen - // actually, this can happen if you restart encoderd - re.encoderd_segment_offset = -s->logger.segment(); - delete msg; - } - - return bytes_count; -} - -void handle_user_flag(LoggerdState *s) { - static int prev_segment = -1; - if (s->logger.segment() == prev_segment) return; - - LOGW("preserving %s", s->logger.segmentPath().c_str()); - -#ifdef __APPLE__ - int ret = setxattr(s->logger.segmentPath().c_str(), PRESERVE_ATTR_NAME, &PRESERVE_ATTR_VALUE, 1, 0, 0); -#else - int ret = setxattr(s->logger.segmentPath().c_str(), PRESERVE_ATTR_NAME, &PRESERVE_ATTR_VALUE, 1, 0); -#endif - if (ret) { - LOGE("setxattr %s failed for %s: %s", PRESERVE_ATTR_NAME, s->logger.segmentPath().c_str(), strerror(errno)); - } - - // mark route for uploading - Params params; - std::string routes = Params().get("AthenadRecentlyViewedRoutes"); - params.put("AthenadRecentlyViewedRoutes", routes + "," + s->logger.routeName()); - - prev_segment = s->logger.segment(); -} - -void loggerd_thread() { - // setup messaging - typedef struct ServiceState { - std::string name; - int counter, freq; - bool encoder, user_flag; - } ServiceState; - std::unordered_map service_state; - std::unordered_map remote_encoders; - - std::unique_ptr ctx(Context::create()); - std::unique_ptr poller(Poller::create()); - - // subscribe to all socks - for (const auto& [_, it] : services) { - const bool encoder = util::ends_with(it.name, "EncodeData"); - const bool livestream_encoder = util::starts_with(it.name, "livestream"); - if (!it.should_log && (!encoder || livestream_encoder)) continue; - LOGD("logging %s (on port %d)", it.name.c_str(), it.port); - - SubSocket * sock = SubSocket::create(ctx.get(), it.name); - assert(sock != NULL); - poller->registerSocket(sock); - service_state[sock] = { - .name = it.name, - .counter = 0, - .freq = it.decimation, - .encoder = encoder, - .user_flag = it.name == "userFlag", - }; - } - - LoggerdState s; - // init logger - logger_rotate(&s); - Params().put("CurrentRoute", s.logger.routeName()); - - std::map encoder_infos_dict; - for (const auto &cam : cameras_logged) { - for (const auto &encoder_info : cam.encoder_infos) { - encoder_infos_dict[encoder_info.publish_name] = encoder_info; - s.max_waiting++; - } - } - - uint64_t msg_count = 0, bytes_count = 0; - double start_ts = millis_since_boot(); - while (!do_exit) { - // poll for new messages on all sockets - for (auto sock : poller->poll(1000)) { - if (do_exit) break; - - ServiceState &service = service_state[sock]; - if (service.user_flag) { - handle_user_flag(&s); - } - - // drain socket - int count = 0; - Message *msg = nullptr; - while (!do_exit && (msg = sock->receive(true))) { - const bool in_qlog = service.freq != -1 && (service.counter++ % service.freq == 0); - if (service.encoder) { - s.last_camera_seen_tms = millis_since_boot(); - bytes_count += handle_encoder_msg(&s, msg, service.name, remote_encoders[sock], encoder_infos_dict[service.name]); - } else { - s.logger.write((uint8_t *)msg->getData(), msg->getSize(), in_qlog); - bytes_count += msg->getSize(); - delete msg; - } - - rotate_if_needed(&s); - - if ((++msg_count % 1000) == 0) { - double seconds = (millis_since_boot() - start_ts) / 1000.0; - LOGD("%" PRIu64 " messages, %.2f msg/sec, %.2f KB/sec", msg_count, msg_count / seconds, bytes_count * 0.001 / seconds); - } - - count++; - if (count >= 200) { - LOGD("large volume of '%s' messages", service.name.c_str()); - break; - } - } - } - } - - LOGW("closing logger"); - s.logger.setExitSignal(do_exit.signal); - - if (do_exit.power_failure) { - LOGE("power failure"); - sync(); - LOGE("sync done"); - } - - // messaging cleanup - for (auto &[sock, service] : service_state) delete sock; -} - -int main(int argc, char** argv) { - if (!Hardware::PC()) { - int ret; - ret = util::set_core_affinity({0, 1, 2, 3}); - assert(ret == 0); - // TODO: why does this impact camerad timings? - //ret = util::set_realtime_priority(1); - //assert(ret == 0); - } - - loggerd_thread(); - - return 0; -} diff --git a/system/loggerd/loggerd.h b/system/loggerd/loggerd.h deleted file mode 100644 index 5476148..0000000 --- a/system/loggerd/loggerd.h +++ /dev/null @@ -1,154 +0,0 @@ -#pragma once - -#include - -#include "cereal/messaging/messaging.h" -#include "cereal/services.h" -#include "cereal/visionipc/visionipc_client.h" -#include "system/camerad/cameras/camera_common.h" -#include "system/hardware/hw.h" -#include "common/params.h" -#include "common/swaglog.h" -#include "common/util.h" - -#include "system/loggerd/logger.h" - -constexpr int MAIN_FPS = 20; -const int MAIN_BITRATE = Params().getBool("HigherBitrate") ? 20000000 : 1e7; -const int LIVESTREAM_BITRATE = 1e6; -const int QCAM_BITRATE = 256000; - -#define NO_CAMERA_PATIENCE 500 // fall back to time-based rotation if all cameras are dead - -#define INIT_ENCODE_FUNCTIONS(encode_type) \ - .get_encode_data_func = &cereal::Event::Reader::get##encode_type##Data, \ - .set_encode_idx_func = &cereal::Event::Builder::set##encode_type##Idx, \ - .init_encode_data_func = &cereal::Event::Builder::init##encode_type##Data - -const bool LOGGERD_TEST = getenv("LOGGERD_TEST"); -const int SEGMENT_LENGTH = LOGGERD_TEST ? atoi(getenv("LOGGERD_SEGMENT_LENGTH")) : 60; - -constexpr char PRESERVE_ATTR_NAME[] = "user.preserve"; -constexpr char PRESERVE_ATTR_VALUE = '1'; -class EncoderInfo { -public: - const char *publish_name; - const char *filename = NULL; - bool record = true; - int frame_width = -1; - int frame_height = -1; - int fps = MAIN_FPS; - int bitrate = MAIN_BITRATE; - cereal::EncodeIndex::Type encode_type = Hardware::PC() ? cereal::EncodeIndex::Type::BIG_BOX_LOSSLESS - : cereal::EncodeIndex::Type::FULL_H_E_V_C; - ::cereal::EncodeData::Reader (cereal::Event::Reader::*get_encode_data_func)() const; - void (cereal::Event::Builder::*set_encode_idx_func)(::cereal::EncodeIndex::Reader); - cereal::EncodeData::Builder (cereal::Event::Builder::*init_encode_data_func)(); -}; - -class LogCameraInfo { -public: - const char *thread_name; - int fps = MAIN_FPS; - CameraType type; - VisionStreamType stream_type; - std::vector encoder_infos; -}; - -const EncoderInfo main_road_encoder_info = { - .publish_name = "roadEncodeData", - .filename = "fcamera.hevc", - INIT_ENCODE_FUNCTIONS(RoadEncode), -}; - -const EncoderInfo main_wide_road_encoder_info = { - .publish_name = "wideRoadEncodeData", - .filename = "ecamera.hevc", - INIT_ENCODE_FUNCTIONS(WideRoadEncode), -}; - -const EncoderInfo main_driver_encoder_info = { - .publish_name = "driverEncodeData", - .filename = "dcamera.hevc", - .record = Params().getBool("RecordFront"), - INIT_ENCODE_FUNCTIONS(DriverEncode), -}; - -const EncoderInfo stream_road_encoder_info = { - .publish_name = "livestreamRoadEncodeData", - .encode_type = cereal::EncodeIndex::Type::QCAMERA_H264, - .record = false, - .bitrate = LIVESTREAM_BITRATE, - INIT_ENCODE_FUNCTIONS(LivestreamRoadEncode), -}; - -const EncoderInfo stream_wide_road_encoder_info = { - .publish_name = "livestreamWideRoadEncodeData", - .encode_type = cereal::EncodeIndex::Type::QCAMERA_H264, - .record = false, - .bitrate = LIVESTREAM_BITRATE, - INIT_ENCODE_FUNCTIONS(LivestreamWideRoadEncode), -}; - -const EncoderInfo stream_driver_encoder_info = { - .publish_name = "livestreamDriverEncodeData", - .encode_type = cereal::EncodeIndex::Type::QCAMERA_H264, - .record = false, - .bitrate = LIVESTREAM_BITRATE, - INIT_ENCODE_FUNCTIONS(LivestreamDriverEncode), -}; - -const EncoderInfo qcam_encoder_info = { - .publish_name = "qRoadEncodeData", - .filename = "qcamera.ts", - .bitrate = QCAM_BITRATE, - .encode_type = cereal::EncodeIndex::Type::QCAMERA_H264, - .frame_width = 526, - .frame_height = 330, - INIT_ENCODE_FUNCTIONS(QRoadEncode), -}; - -const LogCameraInfo road_camera_info{ - .thread_name = "road_cam_encoder", - .type = RoadCam, - .stream_type = VISION_STREAM_ROAD, - .encoder_infos = {main_road_encoder_info, qcam_encoder_info} -}; - -const LogCameraInfo wide_road_camera_info{ - .thread_name = "wide_road_cam_encoder", - .type = WideRoadCam, - .stream_type = VISION_STREAM_WIDE_ROAD, - .encoder_infos = {main_wide_road_encoder_info} -}; - -const LogCameraInfo driver_camera_info{ - .thread_name = "driver_cam_encoder", - .type = DriverCam, - .stream_type = VISION_STREAM_DRIVER, - .encoder_infos = {main_driver_encoder_info} -}; - -const LogCameraInfo stream_road_camera_info{ - .thread_name = "road_cam_encoder", - .type = RoadCam, - .stream_type = VISION_STREAM_ROAD, - .encoder_infos = {stream_road_encoder_info} -}; - -const LogCameraInfo stream_wide_road_camera_info{ - .thread_name = "wide_road_cam_encoder", - .type = WideRoadCam, - .stream_type = VISION_STREAM_WIDE_ROAD, - .encoder_infos = {stream_wide_road_encoder_info} -}; - -const LogCameraInfo stream_driver_camera_info{ - .thread_name = "driver_cam_encoder", - .type = DriverCam, - .stream_type = VISION_STREAM_DRIVER, - .encoder_infos = {stream_driver_encoder_info} -}; - -const LogCameraInfo cameras_logged[] = {road_camera_info, wide_road_camera_info, driver_camera_info}; -const LogCameraInfo stream_cameras_logged[] = {stream_road_camera_info, stream_wide_road_camera_info, stream_driver_camera_info}; diff --git a/system/loggerd/video_writer.cc b/system/loggerd/video_writer.cc deleted file mode 100644 index 90b5f1a..0000000 --- a/system/loggerd/video_writer.cc +++ /dev/null @@ -1,112 +0,0 @@ -#pragma clang diagnostic ignored "-Wdeprecated-declarations" -#include - -#include "system/loggerd/video_writer.h" -#include "common/swaglog.h" -#include "common/util.h" - -VideoWriter::VideoWriter(const char *path, const char *filename, bool remuxing, int width, int height, int fps, cereal::EncodeIndex::Type codec) - : remuxing(remuxing) { - vid_path = util::string_format("%s/%s", path, filename); - lock_path = util::string_format("%s/%s.lock", path, filename); - - int lock_fd = HANDLE_EINTR(open(lock_path.c_str(), O_RDWR | O_CREAT, 0664)); - assert(lock_fd >= 0); - close(lock_fd); - - LOGD("encoder_open %s remuxing:%d", this->vid_path.c_str(), this->remuxing); - if (this->remuxing) { - bool raw = (codec == cereal::EncodeIndex::Type::BIG_BOX_LOSSLESS); - avformat_alloc_output_context2(&this->ofmt_ctx, NULL, raw ? "matroska" : NULL, this->vid_path.c_str()); - assert(this->ofmt_ctx); - - // set codec correctly. needed? - assert(codec != cereal::EncodeIndex::Type::FULL_H_E_V_C); - const AVCodec *avcodec = avcodec_find_encoder(raw ? AV_CODEC_ID_FFVHUFF : AV_CODEC_ID_H264); - assert(avcodec); - - this->codec_ctx = avcodec_alloc_context3(avcodec); - assert(this->codec_ctx); - this->codec_ctx->width = width; - this->codec_ctx->height = height; - this->codec_ctx->pix_fmt = AV_PIX_FMT_YUV420P; - this->codec_ctx->time_base = (AVRational){ 1, fps }; - - if (codec == cereal::EncodeIndex::Type::BIG_BOX_LOSSLESS) { - // without this, there's just noise - int err = avcodec_open2(this->codec_ctx, avcodec, NULL); - assert(err >= 0); - } - - this->out_stream = avformat_new_stream(this->ofmt_ctx, raw ? avcodec : NULL); - assert(this->out_stream); - - int err = avio_open(&this->ofmt_ctx->pb, this->vid_path.c_str(), AVIO_FLAG_WRITE); - assert(err >= 0); - - } else { - this->of = util::safe_fopen(this->vid_path.c_str(), "wb"); - assert(this->of); - } -} - -void VideoWriter::write(uint8_t *data, int len, long long timestamp, bool codecconfig, bool keyframe) { - if (of && data) { - size_t written = util::safe_fwrite(data, 1, len, of); - if (written != len) { - LOGE("failed to write file.errno=%d", errno); - } - } - - if (remuxing) { - if (codecconfig) { - if (len > 0) { - codec_ctx->extradata = (uint8_t*)av_mallocz(len + AV_INPUT_BUFFER_PADDING_SIZE); - codec_ctx->extradata_size = len; - memcpy(codec_ctx->extradata, data, len); - } - int err = avcodec_parameters_from_context(out_stream->codecpar, codec_ctx); - assert(err >= 0); - err = avformat_write_header(ofmt_ctx, NULL); - assert(err >= 0); - } else { - // input timestamps are in microseconds - AVRational in_timebase = {1, 1000000}; - - AVPacket pkt; - av_init_packet(&pkt); - pkt.data = data; - pkt.size = len; - - enum AVRounding rnd = static_cast(AV_ROUND_NEAR_INF|AV_ROUND_PASS_MINMAX); - pkt.pts = pkt.dts = av_rescale_q_rnd(timestamp, in_timebase, ofmt_ctx->streams[0]->time_base, rnd); - pkt.duration = av_rescale_q(50*1000, in_timebase, ofmt_ctx->streams[0]->time_base); - - if (keyframe) { - pkt.flags |= AV_PKT_FLAG_KEY; - } - - // TODO: can use av_write_frame for non raw? - int err = av_interleaved_write_frame(ofmt_ctx, &pkt); - if (err < 0) { LOGW("ts encoder write issue len: %d ts: %lld", len, timestamp); } - - av_packet_unref(&pkt); - } - } -} - -VideoWriter::~VideoWriter() { - if (this->remuxing) { - int err = av_write_trailer(this->ofmt_ctx); - if (err != 0) LOGE("av_write_trailer failed %d", err); - avcodec_free_context(&this->codec_ctx); - err = avio_closep(&this->ofmt_ctx->pb); - if (err != 0) LOGE("avio_closep failed %d", err); - avformat_free_context(this->ofmt_ctx); - } else { - util::safe_fflush(this->of); - fclose(this->of); - this->of = nullptr; - } - unlink(this->lock_path.c_str()); -} diff --git a/system/loggerd/video_writer.h b/system/loggerd/video_writer.h deleted file mode 100644 index 1aa758b..0000000 --- a/system/loggerd/video_writer.h +++ /dev/null @@ -1,25 +0,0 @@ -#pragma once - -#include - -extern "C" { -#include -#include -} - -#include "cereal/messaging/messaging.h" - -class VideoWriter { -public: - VideoWriter(const char *path, const char *filename, bool remuxing, int width, int height, int fps, cereal::EncodeIndex::Type codec); - void write(uint8_t *data, int len, long long timestamp, bool codecconfig, bool keyframe); - ~VideoWriter(); -private: - std::string vid_path, lock_path; - FILE *of = nullptr; - - AVCodecContext *codec_ctx; - AVFormatContext *ofmt_ctx; - AVStream *out_stream; - bool remuxing; -}; diff --git a/system/proclogd/SConscript b/system/proclogd/SConscript deleted file mode 100644 index 1f4b767..0000000 --- a/system/proclogd/SConscript +++ /dev/null @@ -1,6 +0,0 @@ -Import('env', 'cereal', 'messaging', 'common') -libs = [cereal, messaging, 'pthread', 'zmq', 'capnp', 'kj', 'common', 'zmq', 'json11'] -env.Program('proclogd', ['main.cc', 'proclog.cc'], LIBS=libs) - -if GetOption('extras'): - env.Program('tests/test_proclog', ['tests/test_proclog.cc', 'proclog.cc'], LIBS=libs) diff --git a/system/proclogd/main.cc b/system/proclogd/main.cc deleted file mode 100644 index 3f8a889..0000000 --- a/system/proclogd/main.cc +++ /dev/null @@ -1,25 +0,0 @@ - -#include - -#include "common/ratekeeper.h" -#include "common/util.h" -#include "system/proclogd/proclog.h" - -ExitHandler do_exit; - -int main(int argc, char **argv) { - setpriority(PRIO_PROCESS, 0, -15); - - RateKeeper rk("proclogd", 0.5); - PubMaster publisher({"procLog"}); - - while (!do_exit) { - MessageBuilder msg; - buildProcLogMessage(msg); - publisher.send("procLog", msg); - - rk.keepTime(); - } - - return 0; -} diff --git a/system/proclogd/proclog.cc b/system/proclogd/proclog.cc deleted file mode 100644 index 09ab4f5..0000000 --- a/system/proclogd/proclog.cc +++ /dev/null @@ -1,239 +0,0 @@ -#include "system/proclogd/proclog.h" - -#include - -#include -#include -#include -#include - -#include "common/swaglog.h" -#include "common/util.h" - -namespace Parser { - -// parse /proc/stat -std::vector cpuTimes(std::istream &stream) { - std::vector cpu_times; - std::string line; - // skip the first line for cpu total - std::getline(stream, line); - while (std::getline(stream, line)) { - if (line.compare(0, 3, "cpu") != 0) break; - - CPUTime t = {}; - std::istringstream iss(line); - if (iss.ignore(3) >> t.id >> t.utime >> t.ntime >> t.stime >> t.itime >> t.iowtime >> t.irqtime >> t.sirqtime) - cpu_times.push_back(t); - } - return cpu_times; -} - -// parse /proc/meminfo -std::unordered_map memInfo(std::istream &stream) { - std::unordered_map mem_info; - std::string line, key; - while (std::getline(stream, line)) { - uint64_t val = 0; - std::istringstream iss(line); - if (iss >> key >> val) { - mem_info[key] = val * 1024; - } - } - return mem_info; -} - -// field position (https://man7.org/linux/man-pages/man5/proc.5.html) -enum StatPos { - pid = 1, - state = 3, - ppid = 4, - utime = 14, - stime = 15, - cutime = 16, - cstime = 17, - priority = 18, - nice = 19, - num_threads = 20, - starttime = 22, - vsize = 23, - rss = 24, - processor = 39, - MAX_FIELD = 52, -}; - -// parse /proc/pid/stat -std::optional procStat(std::string stat) { - // To avoid being fooled by names containing a closing paren, scan backwards. - auto open_paren = stat.find('('); - auto close_paren = stat.rfind(')'); - if (open_paren == std::string::npos || close_paren == std::string::npos || open_paren > close_paren) { - return std::nullopt; - } - - std::string name = stat.substr(open_paren + 1, close_paren - open_paren - 1); - // replace space in name with _ - std::replace(&stat[open_paren], &stat[close_paren], ' ', '_'); - std::istringstream iss(stat); - std::vector v{std::istream_iterator(iss), - std::istream_iterator()}; - try { - if (v.size() != StatPos::MAX_FIELD) { - throw std::invalid_argument("stat"); - } - ProcStat p = { - .name = name, - .pid = stoi(v[StatPos::pid - 1]), - .state = v[StatPos::state - 1][0], - .ppid = stoi(v[StatPos::ppid - 1]), - .utime = stoul(v[StatPos::utime - 1]), - .stime = stoul(v[StatPos::stime - 1]), - .cutime = stol(v[StatPos::cutime - 1]), - .cstime = stol(v[StatPos::cstime - 1]), - .priority = stol(v[StatPos::priority - 1]), - .nice = stol(v[StatPos::nice - 1]), - .num_threads = stol(v[StatPos::num_threads - 1]), - .starttime = stoull(v[StatPos::starttime - 1]), - .vms = stoul(v[StatPos::vsize - 1]), - .rss = stol(v[StatPos::rss - 1]), - .processor = stoi(v[StatPos::processor - 1]), - }; - return p; - } catch (const std::invalid_argument &e) { - LOGE("failed to parse procStat (%s) :%s", e.what(), stat.c_str()); - } catch (const std::out_of_range &e) { - LOGE("failed to parse procStat (%s) :%s", e.what(), stat.c_str()); - } - return std::nullopt; -} - -// return list of PIDs from /proc -std::vector pids() { - std::vector ids; - DIR *d = opendir("/proc"); - assert(d); - char *p_end; - struct dirent *de = NULL; - while ((de = readdir(d))) { - if (de->d_type == DT_DIR) { - int pid = strtol(de->d_name, &p_end, 10); - if (p_end == (de->d_name + strlen(de->d_name))) { - ids.push_back(pid); - } - } - } - closedir(d); - return ids; -} - -// null-delimited cmdline arguments to vector -std::vector cmdline(std::istream &stream) { - std::vector ret; - std::string line; - while (std::getline(stream, line, '\0')) { - if (!line.empty()) { - ret.push_back(line); - } - } - return ret; -} - -const ProcCache &getProcExtraInfo(int pid, const std::string &name) { - static std::unordered_map proc_cache; - ProcCache &cache = proc_cache[pid]; - if (cache.pid != pid || cache.name != name) { - cache.pid = pid; - cache.name = name; - std::string proc_path = "/proc/" + std::to_string(pid); - cache.exe = util::readlink(proc_path + "/exe"); - std::ifstream stream(proc_path + "/cmdline"); - cache.cmdline = cmdline(stream); - } - return cache; -} - -} // namespace Parser - -const double jiffy = sysconf(_SC_CLK_TCK); -const size_t page_size = sysconf(_SC_PAGE_SIZE); - -void buildCPUTimes(cereal::ProcLog::Builder &builder) { - std::ifstream stream("/proc/stat"); - std::vector stats = Parser::cpuTimes(stream); - - auto log_cpu_times = builder.initCpuTimes(stats.size()); - for (int i = 0; i < stats.size(); ++i) { - auto l = log_cpu_times[i]; - const CPUTime &r = stats[i]; - l.setCpuNum(r.id); - l.setUser(r.utime / jiffy); - l.setNice(r.ntime / jiffy); - l.setSystem(r.stime / jiffy); - l.setIdle(r.itime / jiffy); - l.setIowait(r.iowtime / jiffy); - l.setIrq(r.irqtime / jiffy); - l.setSoftirq(r.sirqtime / jiffy); - } -} - -void buildMemInfo(cereal::ProcLog::Builder &builder) { - std::ifstream stream("/proc/meminfo"); - auto mem_info = Parser::memInfo(stream); - - auto mem = builder.initMem(); - mem.setTotal(mem_info["MemTotal:"]); - mem.setFree(mem_info["MemFree:"]); - mem.setAvailable(mem_info["MemAvailable:"]); - mem.setBuffers(mem_info["Buffers:"]); - mem.setCached(mem_info["Cached:"]); - mem.setActive(mem_info["Active:"]); - mem.setInactive(mem_info["Inactive:"]); - mem.setShared(mem_info["Shmem:"]); -} - -void buildProcs(cereal::ProcLog::Builder &builder) { - auto pids = Parser::pids(); - std::vector proc_stats; - proc_stats.reserve(pids.size()); - for (int pid : pids) { - std::string path = "/proc/" + std::to_string(pid) + "/stat"; - if (auto stat = Parser::procStat(util::read_file(path))) { - proc_stats.push_back(*stat); - } - } - - auto procs = builder.initProcs(proc_stats.size()); - for (size_t i = 0; i < proc_stats.size(); i++) { - auto l = procs[i]; - const ProcStat &r = proc_stats[i]; - l.setPid(r.pid); - l.setState(r.state); - l.setPpid(r.ppid); - l.setCpuUser(r.utime / jiffy); - l.setCpuSystem(r.stime / jiffy); - l.setCpuChildrenUser(r.cutime / jiffy); - l.setCpuChildrenSystem(r.cstime / jiffy); - l.setPriority(r.priority); - l.setNice(r.nice); - l.setNumThreads(r.num_threads); - l.setStartTime(r.starttime / jiffy); - l.setMemVms(r.vms); - l.setMemRss((uint64_t)r.rss * page_size); - l.setProcessor(r.processor); - l.setName(r.name); - - const ProcCache &extra_info = Parser::getProcExtraInfo(r.pid, r.name); - l.setExe(extra_info.exe); - auto lcmdline = l.initCmdline(extra_info.cmdline.size()); - for (size_t j = 0; j < lcmdline.size(); j++) { - lcmdline.set(j, extra_info.cmdline[j]); - } - } -} - -void buildProcLogMessage(MessageBuilder &msg) { - auto procLog = msg.initEvent().initProcLog(); - buildProcs(procLog); - buildCPUTimes(procLog); - buildMemInfo(procLog); -} diff --git a/system/proclogd/proclog.h b/system/proclogd/proclog.h deleted file mode 100644 index 49f97cd..0000000 --- a/system/proclogd/proclog.h +++ /dev/null @@ -1,40 +0,0 @@ -#include -#include -#include -#include - -#include "cereal/messaging/messaging.h" - -struct CPUTime { - int id; - unsigned long utime, ntime, stime, itime; - unsigned long iowtime, irqtime, sirqtime; -}; - -struct ProcCache { - int pid; - std::string name, exe; - std::vector cmdline; -}; - -struct ProcStat { - int pid, ppid, processor; - char state; - long cutime, cstime, priority, nice, num_threads, rss; - unsigned long utime, stime, vms; - unsigned long long starttime; - std::string name; -}; - -namespace Parser { - -std::vector pids(); -std::optional procStat(std::string stat); -std::vector cmdline(std::istream &stream); -std::vector cpuTimes(std::istream &stream); -std::unordered_map memInfo(std::istream &stream); -const ProcCache &getProcExtraInfo(int pid, const std::string &name); - -}; // namespace Parser - -void buildProcLogMessage(MessageBuilder &msg); diff --git a/system/proclogd/proclogd b/system/proclogd/proclogd new file mode 100755 index 0000000..fde4f79 Binary files /dev/null and b/system/proclogd/proclogd differ diff --git a/system/sensord/SConscript b/system/sensord/SConscript deleted file mode 100644 index 7974eb0..0000000 --- a/system/sensord/SConscript +++ /dev/null @@ -1,17 +0,0 @@ -Import('env', 'arch', 'common', 'cereal', 'messaging') - -sensors = [ - 'sensors/i2c_sensor.cc', - 'sensors/bmx055_accel.cc', - 'sensors/bmx055_gyro.cc', - 'sensors/bmx055_magn.cc', - 'sensors/bmx055_temp.cc', - 'sensors/lsm6ds3_accel.cc', - 'sensors/lsm6ds3_gyro.cc', - 'sensors/lsm6ds3_temp.cc', - 'sensors/mmc5603nj_magn.cc', -] -libs = [common, cereal, messaging, 'capnp', 'zmq', 'kj', 'pthread'] -if arch == "larch64": - libs.append('i2c') -env.Program('sensord', ['sensors_qcom2.cc'] + sensors, LIBS=libs) diff --git a/system/sensord/sensord b/system/sensord/sensord new file mode 100755 index 0000000..c828d91 Binary files /dev/null and b/system/sensord/sensord differ diff --git a/system/sensord/sensors/bmx055_accel.cc b/system/sensord/sensors/bmx055_accel.cc deleted file mode 100644 index bdb0113..0000000 --- a/system/sensord/sensors/bmx055_accel.cc +++ /dev/null @@ -1,78 +0,0 @@ -#include "system/sensord/sensors/bmx055_accel.h" - -#include - -#include "common/swaglog.h" -#include "common/timing.h" -#include "common/util.h" - -BMX055_Accel::BMX055_Accel(I2CBus *bus) : I2CSensor(bus) {} - -int BMX055_Accel::init() { - int ret = verify_chip_id(BMX055_ACCEL_I2C_REG_ID, {BMX055_ACCEL_CHIP_ID}); - if (ret == -1) return -1; - - ret = set_register(BMX055_ACCEL_I2C_REG_PMU, BMX055_ACCEL_NORMAL_MODE); - if (ret < 0) { - goto fail; - } - // bmx055 accel has a 1.3ms wakeup time from deep suspend mode - util::sleep_for(10); - - // High bandwidth - // ret = set_register(BMX055_ACCEL_I2C_REG_HBW, BMX055_ACCEL_HBW_ENABLE); - // if (ret < 0) { - // goto fail; - // } - - // Low bandwidth - ret = set_register(BMX055_ACCEL_I2C_REG_HBW, BMX055_ACCEL_HBW_DISABLE); - if (ret < 0) { - goto fail; - } - - ret = set_register(BMX055_ACCEL_I2C_REG_BW, BMX055_ACCEL_BW_125HZ); - if (ret < 0) { - goto fail; - } - -fail: - return ret; -} - -int BMX055_Accel::shutdown() { - // enter deep suspend mode (lowest power mode) - int ret = set_register(BMX055_ACCEL_I2C_REG_PMU, BMX055_ACCEL_DEEP_SUSPEND); - if (ret < 0) { - LOGE("Could not move BMX055 ACCEL in deep suspend mode!"); - } - - return ret; -} - -bool BMX055_Accel::get_event(MessageBuilder &msg, uint64_t ts) { - uint64_t start_time = nanos_since_boot(); - uint8_t buffer[6]; - int len = read_register(BMX055_ACCEL_I2C_REG_X_LSB, buffer, sizeof(buffer)); - assert(len == 6); - - // 12 bit = +-2g - float scale = 9.81 * 2.0f / (1 << 11); - float x = -read_12_bit(buffer[0], buffer[1]) * scale; - float y = -read_12_bit(buffer[2], buffer[3]) * scale; - float z = read_12_bit(buffer[4], buffer[5]) * scale; - - auto event = msg.initEvent().initAccelerometer2(); - event.setSource(cereal::SensorEventData::SensorSource::BMX055); - event.setVersion(1); - event.setSensor(SENSOR_ACCELEROMETER); - event.setType(SENSOR_TYPE_ACCELEROMETER); - event.setTimestamp(start_time); - - float xyz[] = {x, y, z}; - auto svec = event.initAcceleration(); - svec.setV(xyz); - svec.setStatus(true); - - return true; -} diff --git a/system/sensord/sensors/bmx055_accel.h b/system/sensord/sensors/bmx055_accel.h deleted file mode 100644 index 2cc316e..0000000 --- a/system/sensord/sensors/bmx055_accel.h +++ /dev/null @@ -1,41 +0,0 @@ -#pragma once - -#include "system/sensord/sensors/i2c_sensor.h" - -// Address of the chip on the bus -#define BMX055_ACCEL_I2C_ADDR 0x18 - -// Registers of the chip -#define BMX055_ACCEL_I2C_REG_ID 0x00 -#define BMX055_ACCEL_I2C_REG_X_LSB 0x02 -#define BMX055_ACCEL_I2C_REG_TEMP 0x08 -#define BMX055_ACCEL_I2C_REG_BW 0x10 -#define BMX055_ACCEL_I2C_REG_PMU 0x11 -#define BMX055_ACCEL_I2C_REG_HBW 0x13 -#define BMX055_ACCEL_I2C_REG_FIFO 0x3F - -// Constants -#define BMX055_ACCEL_CHIP_ID 0xFA - -#define BMX055_ACCEL_HBW_ENABLE 0b10000000 -#define BMX055_ACCEL_HBW_DISABLE 0b00000000 -#define BMX055_ACCEL_DEEP_SUSPEND 0b00100000 -#define BMX055_ACCEL_NORMAL_MODE 0b00000000 - -#define BMX055_ACCEL_BW_7_81HZ 0b01000 -#define BMX055_ACCEL_BW_15_63HZ 0b01001 -#define BMX055_ACCEL_BW_31_25HZ 0b01010 -#define BMX055_ACCEL_BW_62_5HZ 0b01011 -#define BMX055_ACCEL_BW_125HZ 0b01100 -#define BMX055_ACCEL_BW_250HZ 0b01101 -#define BMX055_ACCEL_BW_500HZ 0b01110 -#define BMX055_ACCEL_BW_1000HZ 0b01111 - -class BMX055_Accel : public I2CSensor { - uint8_t get_device_address() {return BMX055_ACCEL_I2C_ADDR;} -public: - BMX055_Accel(I2CBus *bus); - int init(); - bool get_event(MessageBuilder &msg, uint64_t ts = 0); - int shutdown(); -}; diff --git a/system/sensord/sensors/bmx055_gyro.cc b/system/sensord/sensors/bmx055_gyro.cc deleted file mode 100644 index 411b2f4..0000000 --- a/system/sensord/sensors/bmx055_gyro.cc +++ /dev/null @@ -1,88 +0,0 @@ -#include "system/sensord/sensors/bmx055_gyro.h" - -#include -#include - -#include "common/swaglog.h" -#include "common/util.h" - -#define DEG2RAD(x) ((x) * M_PI / 180.0) - - -BMX055_Gyro::BMX055_Gyro(I2CBus *bus) : I2CSensor(bus) {} - -int BMX055_Gyro::init() { - int ret = verify_chip_id(BMX055_GYRO_I2C_REG_ID, {BMX055_GYRO_CHIP_ID}); - if (ret == -1) return -1; - - ret = set_register(BMX055_GYRO_I2C_REG_LPM1, BMX055_GYRO_NORMAL_MODE); - if (ret < 0) { - goto fail; - } - // bmx055 gyro has a 30ms wakeup time from deep suspend mode - util::sleep_for(50); - - // High bandwidth - // ret = set_register(BMX055_GYRO_I2C_REG_HBW, BMX055_GYRO_HBW_ENABLE); - // if (ret < 0) { - // goto fail; - // } - - // Low bandwidth - ret = set_register(BMX055_GYRO_I2C_REG_HBW, BMX055_GYRO_HBW_DISABLE); - if (ret < 0) { - goto fail; - } - - // 116 Hz filter - ret = set_register(BMX055_GYRO_I2C_REG_BW, BMX055_GYRO_BW_116HZ); - if (ret < 0) { - goto fail; - } - - // +- 125 deg/s range - ret = set_register(BMX055_GYRO_I2C_REG_RANGE, BMX055_GYRO_RANGE_125); - if (ret < 0) { - goto fail; - } - -fail: - return ret; -} - -int BMX055_Gyro::shutdown() { - // enter deep suspend mode (lowest power mode) - int ret = set_register(BMX055_GYRO_I2C_REG_LPM1, BMX055_GYRO_DEEP_SUSPEND); - if (ret < 0) { - LOGE("Could not move BMX055 GYRO in deep suspend mode!"); - } - - return ret; -} - -bool BMX055_Gyro::get_event(MessageBuilder &msg, uint64_t ts) { - uint64_t start_time = nanos_since_boot(); - uint8_t buffer[6]; - int len = read_register(BMX055_GYRO_I2C_REG_RATE_X_LSB, buffer, sizeof(buffer)); - assert(len == 6); - - // 16 bit = +- 125 deg/s - float scale = 125.0f / (1 << 15); - float x = -DEG2RAD(read_16_bit(buffer[0], buffer[1]) * scale); - float y = -DEG2RAD(read_16_bit(buffer[2], buffer[3]) * scale); - float z = DEG2RAD(read_16_bit(buffer[4], buffer[5]) * scale); - - auto event = msg.initEvent().initGyroscope2(); - event.setSource(cereal::SensorEventData::SensorSource::BMX055); - event.setVersion(1); - event.setSensor(SENSOR_GYRO_UNCALIBRATED); - event.setType(SENSOR_TYPE_GYROSCOPE_UNCALIBRATED); - event.setTimestamp(start_time); - - float xyz[] = {x, y, z}; - auto svec = event.initGyroUncalibrated(); - svec.setV(xyz); - svec.setStatus(true); - - return true; -} diff --git a/system/sensord/sensors/bmx055_gyro.h b/system/sensord/sensors/bmx055_gyro.h deleted file mode 100644 index 7be3e56..0000000 --- a/system/sensord/sensors/bmx055_gyro.h +++ /dev/null @@ -1,41 +0,0 @@ -#pragma once - -#include "system/sensord/sensors/i2c_sensor.h" - -// Address of the chip on the bus -#define BMX055_GYRO_I2C_ADDR 0x68 - -// Registers of the chip -#define BMX055_GYRO_I2C_REG_ID 0x00 -#define BMX055_GYRO_I2C_REG_RATE_X_LSB 0x02 -#define BMX055_GYRO_I2C_REG_RANGE 0x0F -#define BMX055_GYRO_I2C_REG_BW 0x10 -#define BMX055_GYRO_I2C_REG_LPM1 0x11 -#define BMX055_GYRO_I2C_REG_HBW 0x13 -#define BMX055_GYRO_I2C_REG_FIFO 0x3F - -// Constants -#define BMX055_GYRO_CHIP_ID 0x0F - -#define BMX055_GYRO_HBW_ENABLE 0b10000000 -#define BMX055_GYRO_HBW_DISABLE 0b00000000 -#define BMX055_GYRO_DEEP_SUSPEND 0b00100000 -#define BMX055_GYRO_NORMAL_MODE 0b00000000 - -#define BMX055_GYRO_RANGE_2000 0b000 -#define BMX055_GYRO_RANGE_1000 0b001 -#define BMX055_GYRO_RANGE_500 0b010 -#define BMX055_GYRO_RANGE_250 0b011 -#define BMX055_GYRO_RANGE_125 0b100 - -#define BMX055_GYRO_BW_116HZ 0b0010 - - -class BMX055_Gyro : public I2CSensor { - uint8_t get_device_address() {return BMX055_GYRO_I2C_ADDR;} -public: - BMX055_Gyro(I2CBus *bus); - int init(); - bool get_event(MessageBuilder &msg, uint64_t ts = 0); - int shutdown(); -}; diff --git a/system/sensord/sensors/bmx055_magn.cc b/system/sensord/sensors/bmx055_magn.cc deleted file mode 100644 index 3d0d3d2..0000000 --- a/system/sensord/sensors/bmx055_magn.cc +++ /dev/null @@ -1,256 +0,0 @@ -#include "system/sensord/sensors/bmx055_magn.h" - -#include - -#include -#include -#include - -#include "common/swaglog.h" -#include "common/util.h" - -static int16_t compensate_x(trim_data_t trim_data, int16_t mag_data_x, uint16_t data_rhall) { - uint16_t process_comp_x0 = data_rhall; - int32_t process_comp_x1 = ((int32_t)trim_data.dig_xyz1) * 16384; - uint16_t process_comp_x2 = ((uint16_t)(process_comp_x1 / process_comp_x0)) - ((uint16_t)0x4000); - int16_t retval = ((int16_t)process_comp_x2); - int32_t process_comp_x3 = (((int32_t)retval) * ((int32_t)retval)); - int32_t process_comp_x4 = (((int32_t)trim_data.dig_xy2) * (process_comp_x3 / 128)); - int32_t process_comp_x5 = (int32_t)(((int16_t)trim_data.dig_xy1) * 128); - int32_t process_comp_x6 = ((int32_t)retval) * process_comp_x5; - int32_t process_comp_x7 = (((process_comp_x4 + process_comp_x6) / 512) + ((int32_t)0x100000)); - int32_t process_comp_x8 = ((int32_t)(((int16_t)trim_data.dig_x2) + ((int16_t)0xA0))); - int32_t process_comp_x9 = ((process_comp_x7 * process_comp_x8) / 4096); - int32_t process_comp_x10 = ((int32_t)mag_data_x) * process_comp_x9; - retval = ((int16_t)(process_comp_x10 / 8192)); - retval = (retval + (((int16_t)trim_data.dig_x1) * 8)) / 16; - - return retval; -} - -static int16_t compensate_y(trim_data_t trim_data, int16_t mag_data_y, uint16_t data_rhall) { - uint16_t process_comp_y0 = trim_data.dig_xyz1; - int32_t process_comp_y1 = (((int32_t)trim_data.dig_xyz1) * 16384) / process_comp_y0; - uint16_t process_comp_y2 = ((uint16_t)process_comp_y1) - ((uint16_t)0x4000); - int16_t retval = ((int16_t)process_comp_y2); - int32_t process_comp_y3 = ((int32_t) retval) * ((int32_t)retval); - int32_t process_comp_y4 = ((int32_t)trim_data.dig_xy2) * (process_comp_y3 / 128); - int32_t process_comp_y5 = ((int32_t)(((int16_t)trim_data.dig_xy1) * 128)); - int32_t process_comp_y6 = ((process_comp_y4 + (((int32_t)retval) * process_comp_y5)) / 512); - int32_t process_comp_y7 = ((int32_t)(((int16_t)trim_data.dig_y2) + ((int16_t)0xA0))); - int32_t process_comp_y8 = (((process_comp_y6 + ((int32_t)0x100000)) * process_comp_y7) / 4096); - int32_t process_comp_y9 = (((int32_t)mag_data_y) * process_comp_y8); - retval = (int16_t)(process_comp_y9 / 8192); - retval = (retval + (((int16_t)trim_data.dig_y1) * 8)) / 16; - - return retval; -} - -static int16_t compensate_z(trim_data_t trim_data, int16_t mag_data_z, uint16_t data_rhall) { - int16_t process_comp_z0 = ((int16_t)data_rhall) - ((int16_t) trim_data.dig_xyz1); - int32_t process_comp_z1 = (((int32_t)trim_data.dig_z3) * ((int32_t)(process_comp_z0))) / 4; - int32_t process_comp_z2 = (((int32_t)(mag_data_z - trim_data.dig_z4)) * 32768); - int32_t process_comp_z3 = ((int32_t)trim_data.dig_z1) * (((int16_t)data_rhall) * 2); - int16_t process_comp_z4 = (int16_t)((process_comp_z3 + (32768)) / 65536); - int32_t retval = ((process_comp_z2 - process_comp_z1) / (trim_data.dig_z2 + process_comp_z4)); - - /* saturate result to +/- 2 micro-tesla */ - retval = std::clamp(retval, -32767, 32767); - - /* Conversion of LSB to micro-tesla*/ - retval = retval / 16; - - return (int16_t)retval; -} - -BMX055_Magn::BMX055_Magn(I2CBus *bus) : I2CSensor(bus) {} - -int BMX055_Magn::init() { - uint8_t trim_x1y1[2] = {0}; - uint8_t trim_x2y2[2] = {0}; - uint8_t trim_xy1xy2[2] = {0}; - uint8_t trim_z1[2] = {0}; - uint8_t trim_z2[2] = {0}; - uint8_t trim_z3[2] = {0}; - uint8_t trim_z4[2] = {0}; - uint8_t trim_xyz1[2] = {0}; - - // suspend -> sleep - int ret = set_register(BMX055_MAGN_I2C_REG_PWR_0, 0x01); - if (ret < 0) { - LOGE("Enabling power failed: %d", ret); - goto fail; - } - util::sleep_for(5); // wait until the chip is powered on - - ret = verify_chip_id(BMX055_MAGN_I2C_REG_ID, {BMX055_MAGN_CHIP_ID}); - if (ret == -1) { - goto fail; - } - - // Load magnetometer trim - ret = read_register(BMX055_MAGN_I2C_REG_DIG_X1, trim_x1y1, 2); - if (ret < 0) goto fail; - ret = read_register(BMX055_MAGN_I2C_REG_DIG_X2, trim_x2y2, 2); - if (ret < 0) goto fail; - ret = read_register(BMX055_MAGN_I2C_REG_DIG_XY2, trim_xy1xy2, 2); - if (ret < 0) goto fail; - ret = read_register(BMX055_MAGN_I2C_REG_DIG_Z1_LSB, trim_z1, 2); - if (ret < 0) goto fail; - ret = read_register(BMX055_MAGN_I2C_REG_DIG_Z2_LSB, trim_z2, 2); - if (ret < 0) goto fail; - ret = read_register(BMX055_MAGN_I2C_REG_DIG_Z3_LSB, trim_z3, 2); - if (ret < 0) goto fail; - ret = read_register(BMX055_MAGN_I2C_REG_DIG_Z4_LSB, trim_z4, 2); - if (ret < 0) goto fail; - ret = read_register(BMX055_MAGN_I2C_REG_DIG_XYZ1_LSB, trim_xyz1, 2); - if (ret < 0) goto fail; - - // Read trim data - trim_data.dig_x1 = trim_x1y1[0]; - trim_data.dig_y1 = trim_x1y1[1]; - - trim_data.dig_x2 = trim_x2y2[0]; - trim_data.dig_y2 = trim_x2y2[1]; - - trim_data.dig_xy1 = trim_xy1xy2[1]; // NB: MSB/LSB swapped - trim_data.dig_xy2 = trim_xy1xy2[0]; - - trim_data.dig_z1 = read_16_bit(trim_z1[0], trim_z1[1]); - trim_data.dig_z2 = read_16_bit(trim_z2[0], trim_z2[1]); - trim_data.dig_z3 = read_16_bit(trim_z3[0], trim_z3[1]); - trim_data.dig_z4 = read_16_bit(trim_z4[0], trim_z4[1]); - - trim_data.dig_xyz1 = read_16_bit(trim_xyz1[0], trim_xyz1[1] & 0x7f); - assert(trim_data.dig_xyz1 != 0); - - perform_self_test(); - - // f_max = 1 / (145us * nXY + 500us * NZ + 980us) - // Chose NXY = 7, NZ = 12, which gives 125 Hz, - // and has the same ratio as the high accuracy preset - ret = set_register(BMX055_MAGN_I2C_REG_REPXY, (7 - 1) / 2); - if (ret < 0) { - goto fail; - } - - ret = set_register(BMX055_MAGN_I2C_REG_REPZ, 12 - 1); - if (ret < 0) { - goto fail; - } - - - return 0; - - fail: - return ret; -} - -int BMX055_Magn::shutdown() { - // move to suspend mode - int ret = set_register(BMX055_MAGN_I2C_REG_PWR_0, 0); - if (ret < 0) { - LOGE("Could not move BMX055 MAGN in suspend mode!"); - } - - return ret; -} - -bool BMX055_Magn::perform_self_test() { - uint8_t buffer[8]; - int16_t x, y; - int16_t neg_z, pos_z; - - // Increase z reps for less false positives (~30 Hz ODR) - set_register(BMX055_MAGN_I2C_REG_REPXY, 1); - set_register(BMX055_MAGN_I2C_REG_REPZ, 64 - 1); - - // Clean existing measurement - read_register(BMX055_MAGN_I2C_REG_DATAX_LSB, buffer, sizeof(buffer)); - - uint8_t forced = BMX055_MAGN_FORCED; - - // Negative current - set_register(BMX055_MAGN_I2C_REG_MAG, forced | (uint8_t(0b10) << 6)); - util::sleep_for(100); - - read_register(BMX055_MAGN_I2C_REG_DATAX_LSB, buffer, sizeof(buffer)); - parse_xyz(buffer, &x, &y, &neg_z); - - // Positive current - set_register(BMX055_MAGN_I2C_REG_MAG, forced | (uint8_t(0b11) << 6)); - util::sleep_for(100); - - read_register(BMX055_MAGN_I2C_REG_DATAX_LSB, buffer, sizeof(buffer)); - parse_xyz(buffer, &x, &y, &pos_z); - - // Put back in normal mode - set_register(BMX055_MAGN_I2C_REG_MAG, 0); - - int16_t diff = pos_z - neg_z; - bool passed = (diff > 180) && (diff < 240); - - if (!passed) { - LOGE("self test failed: neg %d pos %d diff %d", neg_z, pos_z, diff); - } - - return passed; -} - -bool BMX055_Magn::parse_xyz(uint8_t buffer[8], int16_t *x, int16_t *y, int16_t *z) { - bool ready = buffer[6] & 0x1; - if (ready) { - int16_t mdata_x = (int16_t) (((int16_t)buffer[1] << 8) | buffer[0]) >> 3; - int16_t mdata_y = (int16_t) (((int16_t)buffer[3] << 8) | buffer[2]) >> 3; - int16_t mdata_z = (int16_t) (((int16_t)buffer[5] << 8) | buffer[4]) >> 1; - uint16_t data_r = (uint16_t) (((uint16_t)buffer[7] << 8) | buffer[6]) >> 2; - assert(data_r != 0); - - *x = compensate_x(trim_data, mdata_x, data_r); - *y = compensate_y(trim_data, mdata_y, data_r); - *z = compensate_z(trim_data, mdata_z, data_r); - } - return ready; -} - - -bool BMX055_Magn::get_event(MessageBuilder &msg, uint64_t ts) { - uint64_t start_time = nanos_since_boot(); - uint8_t buffer[8]; - int16_t _x, _y, x, y, z; - - int len = read_register(BMX055_MAGN_I2C_REG_DATAX_LSB, buffer, sizeof(buffer)); - assert(len == sizeof(buffer)); - - bool parsed = parse_xyz(buffer, &_x, &_y, &z); - if (parsed) { - - auto event = msg.initEvent().initMagnetometer(); - event.setSource(cereal::SensorEventData::SensorSource::BMX055); - event.setVersion(2); - event.setSensor(SENSOR_MAGNETOMETER_UNCALIBRATED); - event.setType(SENSOR_TYPE_MAGNETIC_FIELD_UNCALIBRATED); - event.setTimestamp(start_time); - - // Move magnetometer into same reference frame as accel/gryo - x = -_y; - y = _x; - - // Axis convention - x = -x; - y = -y; - - float xyz[] = {(float)x, (float)y, (float)z}; - auto svec = event.initMagneticUncalibrated(); - svec.setV(xyz); - svec.setStatus(true); - } - - // The BMX055 Magnetometer has no FIFO mode. Self running mode only goes - // up to 30 Hz. Therefore we put in forced mode, and request measurements - // at a 100 Hz. When reading the registers we have to check the ready bit - // To verify the measurement was completed this cycle. - set_register(BMX055_MAGN_I2C_REG_MAG, BMX055_MAGN_FORCED); - - return parsed; -} diff --git a/system/sensord/sensors/bmx055_magn.h b/system/sensord/sensors/bmx055_magn.h deleted file mode 100644 index 15c4e73..0000000 --- a/system/sensord/sensors/bmx055_magn.h +++ /dev/null @@ -1,64 +0,0 @@ -#pragma once -#include - -#include "system/sensord/sensors/i2c_sensor.h" - -// Address of the chip on the bus -#define BMX055_MAGN_I2C_ADDR 0x10 - -// Registers of the chip -#define BMX055_MAGN_I2C_REG_ID 0x40 -#define BMX055_MAGN_I2C_REG_PWR_0 0x4B -#define BMX055_MAGN_I2C_REG_MAG 0x4C -#define BMX055_MAGN_I2C_REG_DATAX_LSB 0x42 -#define BMX055_MAGN_I2C_REG_RHALL_LSB 0x48 -#define BMX055_MAGN_I2C_REG_REPXY 0x51 -#define BMX055_MAGN_I2C_REG_REPZ 0x52 - -#define BMX055_MAGN_I2C_REG_DIG_X1 0x5D -#define BMX055_MAGN_I2C_REG_DIG_Y1 0x5E -#define BMX055_MAGN_I2C_REG_DIG_Z4_LSB 0x62 -#define BMX055_MAGN_I2C_REG_DIG_Z4_MSB 0x63 -#define BMX055_MAGN_I2C_REG_DIG_X2 0x64 -#define BMX055_MAGN_I2C_REG_DIG_Y2 0x65 -#define BMX055_MAGN_I2C_REG_DIG_Z2_LSB 0x68 -#define BMX055_MAGN_I2C_REG_DIG_Z2_MSB 0x69 -#define BMX055_MAGN_I2C_REG_DIG_Z1_LSB 0x6A -#define BMX055_MAGN_I2C_REG_DIG_Z1_MSB 0x6B -#define BMX055_MAGN_I2C_REG_DIG_XYZ1_LSB 0x6C -#define BMX055_MAGN_I2C_REG_DIG_XYZ1_MSB 0x6D -#define BMX055_MAGN_I2C_REG_DIG_Z3_LSB 0x6E -#define BMX055_MAGN_I2C_REG_DIG_Z3_MSB 0x6F -#define BMX055_MAGN_I2C_REG_DIG_XY2 0x70 -#define BMX055_MAGN_I2C_REG_DIG_XY1 0x71 - -// Constants -#define BMX055_MAGN_CHIP_ID 0x32 -#define BMX055_MAGN_FORCED (0b01 << 1) - -struct trim_data_t { - int8_t dig_x1; - int8_t dig_y1; - int8_t dig_x2; - int8_t dig_y2; - uint16_t dig_z1; - int16_t dig_z2; - int16_t dig_z3; - int16_t dig_z4; - uint8_t dig_xy1; - int8_t dig_xy2; - uint16_t dig_xyz1; -}; - - -class BMX055_Magn : public I2CSensor{ - uint8_t get_device_address() {return BMX055_MAGN_I2C_ADDR;} - trim_data_t trim_data = {0}; - bool perform_self_test(); - bool parse_xyz(uint8_t buffer[8], int16_t *x, int16_t *y, int16_t *z); -public: - BMX055_Magn(I2CBus *bus); - int init(); - bool get_event(MessageBuilder &msg, uint64_t ts = 0); - int shutdown(); -}; diff --git a/system/sensord/sensors/bmx055_temp.cc b/system/sensord/sensors/bmx055_temp.cc deleted file mode 100644 index da7b864..0000000 --- a/system/sensord/sensors/bmx055_temp.cc +++ /dev/null @@ -1,31 +0,0 @@ -#include "system/sensord/sensors/bmx055_temp.h" - -#include - -#include "system/sensord/sensors/bmx055_accel.h" -#include "common/swaglog.h" -#include "common/timing.h" - -BMX055_Temp::BMX055_Temp(I2CBus *bus) : I2CSensor(bus) {} - -int BMX055_Temp::init() { - return verify_chip_id(BMX055_ACCEL_I2C_REG_ID, {BMX055_ACCEL_CHIP_ID}) == -1 ? -1 : 0; -} - -bool BMX055_Temp::get_event(MessageBuilder &msg, uint64_t ts) { - uint64_t start_time = nanos_since_boot(); - uint8_t buffer[1]; - int len = read_register(BMX055_ACCEL_I2C_REG_TEMP, buffer, sizeof(buffer)); - assert(len == sizeof(buffer)); - - float temp = 23.0f + int8_t(buffer[0]) / 2.0f; - - auto event = msg.initEvent().initTemperatureSensor(); - event.setSource(cereal::SensorEventData::SensorSource::BMX055); - event.setVersion(1); - event.setType(SENSOR_TYPE_AMBIENT_TEMPERATURE); - event.setTimestamp(start_time); - event.setTemperature(temp); - - return true; -} diff --git a/system/sensord/sensors/bmx055_temp.h b/system/sensord/sensors/bmx055_temp.h deleted file mode 100644 index a2eabae..0000000 --- a/system/sensord/sensors/bmx055_temp.h +++ /dev/null @@ -1,13 +0,0 @@ -#pragma once - -#include "system/sensord/sensors/bmx055_accel.h" -#include "system/sensord/sensors/i2c_sensor.h" - -class BMX055_Temp : public I2CSensor { - uint8_t get_device_address() {return BMX055_ACCEL_I2C_ADDR;} -public: - BMX055_Temp(I2CBus *bus); - int init(); - bool get_event(MessageBuilder &msg, uint64_t ts = 0); - int shutdown() { return 0; } -}; diff --git a/system/sensord/sensors/constants.h b/system/sensord/sensors/constants.h deleted file mode 100644 index c216f83..0000000 --- a/system/sensord/sensors/constants.h +++ /dev/null @@ -1,18 +0,0 @@ -#pragma once - - -#define SENSOR_ACCELEROMETER 1 -#define SENSOR_MAGNETOMETER 2 -#define SENSOR_MAGNETOMETER_UNCALIBRATED 3 -#define SENSOR_GYRO 4 -#define SENSOR_GYRO_UNCALIBRATED 5 -#define SENSOR_LIGHT 7 - -#define SENSOR_TYPE_ACCELEROMETER 1 -#define SENSOR_TYPE_GEOMAGNETIC_FIELD 2 -#define SENSOR_TYPE_GYROSCOPE 4 -#define SENSOR_TYPE_LIGHT 5 -#define SENSOR_TYPE_AMBIENT_TEMPERATURE 13 -#define SENSOR_TYPE_MAGNETIC_FIELD_UNCALIBRATED 14 -#define SENSOR_TYPE_MAGNETIC_FIELD SENSOR_TYPE_GEOMAGNETIC_FIELD -#define SENSOR_TYPE_GYROSCOPE_UNCALIBRATED 16 diff --git a/system/sensord/sensors/i2c_sensor.cc b/system/sensord/sensors/i2c_sensor.cc deleted file mode 100644 index 90220f5..0000000 --- a/system/sensord/sensors/i2c_sensor.cc +++ /dev/null @@ -1,50 +0,0 @@ -#include "system/sensord/sensors/i2c_sensor.h" - -int16_t read_12_bit(uint8_t lsb, uint8_t msb) { - uint16_t combined = (uint16_t(msb) << 8) | uint16_t(lsb & 0xF0); - return int16_t(combined) / (1 << 4); -} - -int16_t read_16_bit(uint8_t lsb, uint8_t msb) { - uint16_t combined = (uint16_t(msb) << 8) | uint16_t(lsb); - return int16_t(combined); -} - -int32_t read_20_bit(uint8_t b2, uint8_t b1, uint8_t b0) { - uint32_t combined = (uint32_t(b0) << 16) | (uint32_t(b1) << 8) | uint32_t(b2); - return int32_t(combined) / (1 << 4); -} - -I2CSensor::I2CSensor(I2CBus *bus, int gpio_nr, bool shared_gpio) : - bus(bus), gpio_nr(gpio_nr), shared_gpio(shared_gpio) {} - -I2CSensor::~I2CSensor() { - if (gpio_fd != -1) { - close(gpio_fd); - } -} - -int I2CSensor::read_register(uint register_address, uint8_t *buffer, uint8_t len) { - return bus->read_register(get_device_address(), register_address, buffer, len); -} - -int I2CSensor::set_register(uint register_address, uint8_t data) { - return bus->set_register(get_device_address(), register_address, data); -} - -int I2CSensor::init_gpio() { - if (shared_gpio || gpio_nr == 0) { - return 0; - } - - gpio_fd = gpiochip_get_ro_value_fd("sensord", GPIOCHIP_INT, gpio_nr); - if (gpio_fd < 0) { - return -1; - } - - return 0; -} - -bool I2CSensor::has_interrupt_enabled() { - return gpio_nr != 0; -} diff --git a/system/sensord/sensors/i2c_sensor.h b/system/sensord/sensors/i2c_sensor.h deleted file mode 100644 index ba100c3..0000000 --- a/system/sensord/sensors/i2c_sensor.h +++ /dev/null @@ -1,51 +0,0 @@ -#pragma once - -#include -#include -#include -#include "cereal/gen/cpp/log.capnp.h" - -#include "common/i2c.h" -#include "common/gpio.h" - -#include "common/swaglog.h" -#include "system/sensord/sensors/constants.h" -#include "system/sensord/sensors/sensor.h" - -int16_t read_12_bit(uint8_t lsb, uint8_t msb); -int16_t read_16_bit(uint8_t lsb, uint8_t msb); -int32_t read_20_bit(uint8_t b2, uint8_t b1, uint8_t b0); - - -class I2CSensor : public Sensor { -private: - I2CBus *bus; - int gpio_nr; - bool shared_gpio; - virtual uint8_t get_device_address() = 0; - -public: - I2CSensor(I2CBus *bus, int gpio_nr = 0, bool shared_gpio = false); - ~I2CSensor(); - int read_register(uint register_address, uint8_t *buffer, uint8_t len); - int set_register(uint register_address, uint8_t data); - int init_gpio(); - bool has_interrupt_enabled(); - virtual int init() = 0; - virtual bool get_event(MessageBuilder &msg, uint64_t ts = 0) = 0; - virtual int shutdown() = 0; - - int verify_chip_id(uint8_t address, const std::vector &expected_ids) { - uint8_t chip_id = 0; - int ret = read_register(address, &chip_id, 1); - if (ret < 0) { - LOGE("Reading chip ID failed: %d", ret); - return -1; - } - for (int i = 0; i < expected_ids.size(); ++i) { - if (chip_id == expected_ids[i]) return chip_id; - } - LOGE("Chip ID wrong. Got: %d, Expected %d", chip_id, expected_ids[0]); - return -1; - } -}; diff --git a/system/sensord/sensors/lsm6ds3_accel.cc b/system/sensord/sensors/lsm6ds3_accel.cc deleted file mode 100644 index 03533e0..0000000 --- a/system/sensord/sensors/lsm6ds3_accel.cc +++ /dev/null @@ -1,250 +0,0 @@ -#include "system/sensord/sensors/lsm6ds3_accel.h" - -#include -#include -#include - -#include "common/swaglog.h" -#include "common/timing.h" -#include "common/util.h" - -LSM6DS3_Accel::LSM6DS3_Accel(I2CBus *bus, int gpio_nr, bool shared_gpio) : - I2CSensor(bus, gpio_nr, shared_gpio) {} - -void LSM6DS3_Accel::wait_for_data_ready() { - uint8_t drdy = 0; - uint8_t buffer[6]; - - do { - read_register(LSM6DS3_ACCEL_I2C_REG_STAT_REG, &drdy, sizeof(drdy)); - drdy &= LSM6DS3_ACCEL_DRDY_XLDA; - } while (drdy == 0); - - read_register(LSM6DS3_ACCEL_I2C_REG_OUTX_L_XL, buffer, sizeof(buffer)); -} - -void LSM6DS3_Accel::read_and_avg_data(float* out_buf) { - uint8_t drdy = 0; - uint8_t buffer[6]; - - float scaling = 0.061f; - if (source == cereal::SensorEventData::SensorSource::LSM6DS3TRC) { - scaling = 0.122f; - } - - for (int i = 0; i < 5; i++) { - do { - read_register(LSM6DS3_ACCEL_I2C_REG_STAT_REG, &drdy, sizeof(drdy)); - drdy &= LSM6DS3_ACCEL_DRDY_XLDA; - } while (drdy == 0); - - int len = read_register(LSM6DS3_ACCEL_I2C_REG_OUTX_L_XL, buffer, sizeof(buffer)); - assert(len == sizeof(buffer)); - - for (int j = 0; j < 3; j++) { - out_buf[j] += (float)read_16_bit(buffer[j*2], buffer[j*2+1]) * scaling; - } - } - - for (int i = 0; i < 3; i++) { - out_buf[i] /= 5.0f; - } -} - -int LSM6DS3_Accel::self_test(int test_type) { - float val_st_off[3] = {0}; - float val_st_on[3] = {0}; - float test_val[3] = {0}; - uint8_t ODR_FS_MO = LSM6DS3_ACCEL_ODR_52HZ; // full scale: +-2g, ODR: 52Hz - - // prepare sensor for self-test - - // enable block data update and automatic increment - int ret = set_register(LSM6DS3_ACCEL_I2C_REG_CTRL3_C, LSM6DS3_ACCEL_IF_INC_BDU); - if (ret < 0) { - return ret; - } - - if (source == cereal::SensorEventData::SensorSource::LSM6DS3TRC) { - ODR_FS_MO = LSM6DS3_ACCEL_FS_4G | LSM6DS3_ACCEL_ODR_52HZ; - } - ret = set_register(LSM6DS3_ACCEL_I2C_REG_CTRL1_XL, ODR_FS_MO); - if (ret < 0) { - return ret; - } - - // wait for stable output, and discard first values - util::sleep_for(100); - wait_for_data_ready(); - read_and_avg_data(val_st_off); - - // enable Self Test positive (or negative) - ret = set_register(LSM6DS3_ACCEL_I2C_REG_CTRL5_C, test_type); - if (ret < 0) { - return ret; - } - - // wait for stable output, and discard first values - util::sleep_for(100); - wait_for_data_ready(); - read_and_avg_data(val_st_on); - - // disable sensor - ret = set_register(LSM6DS3_ACCEL_I2C_REG_CTRL1_XL, 0); - if (ret < 0) { - return ret; - } - - // disable self test - ret = set_register(LSM6DS3_ACCEL_I2C_REG_CTRL5_C, 0); - if (ret < 0) { - return ret; - } - - // calculate the mg values for self test - for (int i = 0; i < 3; i++) { - test_val[i] = fabs(val_st_on[i] - val_st_off[i]); - } - - // verify test result - for (int i = 0; i < 3; i++) { - if ((LSM6DS3_ACCEL_MIN_ST_LIMIT_mg > test_val[i]) || - (test_val[i] > LSM6DS3_ACCEL_MAX_ST_LIMIT_mg)) { - return -1; - } - } - - return ret; -} - -int LSM6DS3_Accel::init() { - uint8_t value = 0; - bool do_self_test = false; - - const char* env_lsm_selftest = std::getenv("LSM_SELF_TEST"); - if (env_lsm_selftest != nullptr && strncmp(env_lsm_selftest, "1", 1) == 0) { - do_self_test = true; - } - - int ret = verify_chip_id(LSM6DS3_ACCEL_I2C_REG_ID, {LSM6DS3_ACCEL_CHIP_ID, LSM6DS3TRC_ACCEL_CHIP_ID}); - if (ret == -1) return -1; - - if (ret == LSM6DS3TRC_ACCEL_CHIP_ID) { - source = cereal::SensorEventData::SensorSource::LSM6DS3TRC; - } - - ret = self_test(LSM6DS3_ACCEL_POSITIVE_TEST); - if (ret < 0) { - LOGE("LSM6DS3 accel positive self-test failed!"); - if (do_self_test) goto fail; - } - - ret = self_test(LSM6DS3_ACCEL_NEGATIVE_TEST); - if (ret < 0) { - LOGE("LSM6DS3 accel negative self-test failed!"); - if (do_self_test) goto fail; - } - - ret = init_gpio(); - if (ret < 0) { - goto fail; - } - - // enable continuous update, and automatic increase - ret = set_register(LSM6DS3_ACCEL_I2C_REG_CTRL3_C, LSM6DS3_ACCEL_IF_INC); - if (ret < 0) { - goto fail; - } - - // TODO: set scale and bandwidth. Default is +- 2G, 50 Hz - ret = set_register(LSM6DS3_ACCEL_I2C_REG_CTRL1_XL, LSM6DS3_ACCEL_ODR_104HZ); - if (ret < 0) { - goto fail; - } - - ret = set_register(LSM6DS3_ACCEL_I2C_REG_DRDY_CFG, LSM6DS3_ACCEL_DRDY_PULSE_MODE); - if (ret < 0) { - goto fail; - } - - // enable data ready interrupt for accel on INT1 - // (without resetting existing interrupts) - ret = read_register(LSM6DS3_ACCEL_I2C_REG_INT1_CTRL, &value, 1); - if (ret < 0) { - goto fail; - } - - value |= LSM6DS3_ACCEL_INT1_DRDY_XL; - ret = set_register(LSM6DS3_ACCEL_I2C_REG_INT1_CTRL, value); - -fail: - return ret; -} - -int LSM6DS3_Accel::shutdown() { - int ret = 0; - - // disable data ready interrupt for accel on INT1 - uint8_t value = 0; - ret = read_register(LSM6DS3_ACCEL_I2C_REG_INT1_CTRL, &value, 1); - if (ret < 0) { - goto fail; - } - - value &= ~(LSM6DS3_ACCEL_INT1_DRDY_XL); - ret = set_register(LSM6DS3_ACCEL_I2C_REG_INT1_CTRL, value); - if (ret < 0) { - LOGE("Could not disable lsm6ds3 acceleration interrupt!"); - goto fail; - } - - // enable power-down mode - value = 0; - ret = read_register(LSM6DS3_ACCEL_I2C_REG_CTRL1_XL, &value, 1); - if (ret < 0) { - goto fail; - } - - value &= 0x0F; - ret = set_register(LSM6DS3_ACCEL_I2C_REG_CTRL1_XL, value); - if (ret < 0) { - LOGE("Could not power-down lsm6ds3 accelerometer!"); - goto fail; - } - -fail: - return ret; -} - -bool LSM6DS3_Accel::get_event(MessageBuilder &msg, uint64_t ts) { - - // INT1 shared with gyro, check STATUS_REG who triggered - uint8_t status_reg = 0; - read_register(LSM6DS3_ACCEL_I2C_REG_STAT_REG, &status_reg, sizeof(status_reg)); - if ((status_reg & LSM6DS3_ACCEL_DRDY_XLDA) == 0) { - return false; - } - - uint8_t buffer[6]; - int len = read_register(LSM6DS3_ACCEL_I2C_REG_OUTX_L_XL, buffer, sizeof(buffer)); - assert(len == sizeof(buffer)); - - float scale = 9.81 * 2.0f / (1 << 15); - float x = read_16_bit(buffer[0], buffer[1]) * scale; - float y = read_16_bit(buffer[2], buffer[3]) * scale; - float z = read_16_bit(buffer[4], buffer[5]) * scale; - - auto event = msg.initEvent().initAccelerometer(); - event.setSource(source); - event.setVersion(1); - event.setSensor(SENSOR_ACCELEROMETER); - event.setType(SENSOR_TYPE_ACCELEROMETER); - event.setTimestamp(ts); - - float xyz[] = {y, -x, z}; - auto svec = event.initAcceleration(); - svec.setV(xyz); - svec.setStatus(true); - - return true; -} diff --git a/system/sensord/sensors/lsm6ds3_accel.h b/system/sensord/sensors/lsm6ds3_accel.h deleted file mode 100644 index 69667cb..0000000 --- a/system/sensord/sensors/lsm6ds3_accel.h +++ /dev/null @@ -1,49 +0,0 @@ -#pragma once - -#include "system/sensord/sensors/i2c_sensor.h" - -// Address of the chip on the bus -#define LSM6DS3_ACCEL_I2C_ADDR 0x6A - -// Registers of the chip -#define LSM6DS3_ACCEL_I2C_REG_DRDY_CFG 0x0B -#define LSM6DS3_ACCEL_I2C_REG_ID 0x0F -#define LSM6DS3_ACCEL_I2C_REG_INT1_CTRL 0x0D -#define LSM6DS3_ACCEL_I2C_REG_CTRL1_XL 0x10 -#define LSM6DS3_ACCEL_I2C_REG_CTRL3_C 0x12 -#define LSM6DS3_ACCEL_I2C_REG_CTRL5_C 0x14 -#define LSM6DS3_ACCEL_I2C_REG_CTR9_XL 0x18 -#define LSM6DS3_ACCEL_I2C_REG_STAT_REG 0x1E -#define LSM6DS3_ACCEL_I2C_REG_OUTX_L_XL 0x28 - -// Constants -#define LSM6DS3_ACCEL_CHIP_ID 0x69 -#define LSM6DS3TRC_ACCEL_CHIP_ID 0x6A -#define LSM6DS3_ACCEL_FS_4G (0b10 << 2) -#define LSM6DS3_ACCEL_ODR_52HZ (0b0011 << 4) -#define LSM6DS3_ACCEL_ODR_104HZ (0b0100 << 4) -#define LSM6DS3_ACCEL_INT1_DRDY_XL 0b1 -#define LSM6DS3_ACCEL_DRDY_XLDA 0b1 -#define LSM6DS3_ACCEL_DRDY_PULSE_MODE (1 << 7) -#define LSM6DS3_ACCEL_IF_INC 0b00000100 -#define LSM6DS3_ACCEL_IF_INC_BDU 0b01000100 -#define LSM6DS3_ACCEL_XYZ_DEN 0b11100000 -#define LSM6DS3_ACCEL_POSITIVE_TEST 0b01 -#define LSM6DS3_ACCEL_NEGATIVE_TEST 0b10 -#define LSM6DS3_ACCEL_MIN_ST_LIMIT_mg 90.0f -#define LSM6DS3_ACCEL_MAX_ST_LIMIT_mg 1700.0f - -class LSM6DS3_Accel : public I2CSensor { - uint8_t get_device_address() {return LSM6DS3_ACCEL_I2C_ADDR;} - cereal::SensorEventData::SensorSource source = cereal::SensorEventData::SensorSource::LSM6DS3; - - // self test functions - int self_test(int test_type); - void wait_for_data_ready(); - void read_and_avg_data(float* val_st_off); -public: - LSM6DS3_Accel(I2CBus *bus, int gpio_nr = 0, bool shared_gpio = false); - int init(); - bool get_event(MessageBuilder &msg, uint64_t ts = 0); - int shutdown(); -}; diff --git a/system/sensord/sensors/lsm6ds3_gyro.cc b/system/sensord/sensors/lsm6ds3_gyro.cc deleted file mode 100644 index 0459b6a..0000000 --- a/system/sensord/sensors/lsm6ds3_gyro.cc +++ /dev/null @@ -1,233 +0,0 @@ -#include "system/sensord/sensors/lsm6ds3_gyro.h" - -#include -#include -#include - -#include "common/swaglog.h" -#include "common/timing.h" -#include "common/util.h" - -#define DEG2RAD(x) ((x) * M_PI / 180.0) - -LSM6DS3_Gyro::LSM6DS3_Gyro(I2CBus *bus, int gpio_nr, bool shared_gpio) : - I2CSensor(bus, gpio_nr, shared_gpio) {} - -void LSM6DS3_Gyro::wait_for_data_ready() { - uint8_t drdy = 0; - uint8_t buffer[6]; - - do { - read_register(LSM6DS3_GYRO_I2C_REG_STAT_REG, &drdy, sizeof(drdy)); - drdy &= LSM6DS3_GYRO_DRDY_GDA; - } while (drdy == 0); - - read_register(LSM6DS3_GYRO_I2C_REG_OUTX_L_G, buffer, sizeof(buffer)); -} - -void LSM6DS3_Gyro::read_and_avg_data(float* out_buf) { - uint8_t drdy = 0; - uint8_t buffer[6]; - - for (int i = 0; i < 5; i++) { - do { - read_register(LSM6DS3_GYRO_I2C_REG_STAT_REG, &drdy, sizeof(drdy)); - drdy &= LSM6DS3_GYRO_DRDY_GDA; - } while (drdy == 0); - - int len = read_register(LSM6DS3_GYRO_I2C_REG_OUTX_L_G, buffer, sizeof(buffer)); - assert(len == sizeof(buffer)); - - for (int j = 0; j < 3; j++) { - out_buf[j] += (float)read_16_bit(buffer[j*2], buffer[j*2+1]) * 70.0f; - } - } - - // calculate the mg average values - for (int i = 0; i < 3; i++) { - out_buf[i] /= 5.0f; - } -} - -int LSM6DS3_Gyro::self_test(int test_type) { - float val_st_off[3] = {0}; - float val_st_on[3] = {0}; - float test_val[3] = {0}; - - // prepare sensor for self-test - - // full scale: 2000dps, ODR: 208Hz - int ret = set_register(LSM6DS3_GYRO_I2C_REG_CTRL2_G, LSM6DS3_GYRO_ODR_208HZ | LSM6DS3_GYRO_FS_2000dps); - if (ret < 0) { - return ret; - } - - // wait for stable output, and discard first values - util::sleep_for(150); - wait_for_data_ready(); - read_and_avg_data(val_st_off); - - // enable Self Test positive (or negative) - ret = set_register(LSM6DS3_GYRO_I2C_REG_CTRL5_C, test_type); - if (ret < 0) { - return ret; - } - - // wait for stable output, and discard first values - util::sleep_for(50); - wait_for_data_ready(); - read_and_avg_data(val_st_on); - - // disable sensor - ret = set_register(LSM6DS3_GYRO_I2C_REG_CTRL2_G, 0); - if (ret < 0) { - return ret; - } - - // disable self test - ret = set_register(LSM6DS3_GYRO_I2C_REG_CTRL5_C, 0); - if (ret < 0) { - return ret; - } - - // calculate the mg values for self test - for (int i = 0; i < 3; i++) { - test_val[i] = fabs(val_st_on[i] - val_st_off[i]); - } - - // verify test result - for (int i = 0; i < 3; i++) { - if ((LSM6DS3_GYRO_MIN_ST_LIMIT_mdps > test_val[i]) || - (test_val[i] > LSM6DS3_GYRO_MAX_ST_LIMIT_mdps)) { - return -1; - } - } - - return ret; -} - -int LSM6DS3_Gyro::init() { - uint8_t value = 0; - bool do_self_test = false; - - const char* env_lsm_selftest =env_lsm_selftest = std::getenv("LSM_SELF_TEST"); - if (env_lsm_selftest != nullptr && strncmp(env_lsm_selftest, "1", 1) == 0) { - do_self_test = true; - } - - int ret = verify_chip_id(LSM6DS3_GYRO_I2C_REG_ID, {LSM6DS3_GYRO_CHIP_ID, LSM6DS3TRC_GYRO_CHIP_ID}); - if (ret == -1) return -1; - - if (ret == LSM6DS3TRC_GYRO_CHIP_ID) { - source = cereal::SensorEventData::SensorSource::LSM6DS3TRC; - } - - ret = init_gpio(); - if (ret < 0) { - goto fail; - } - - ret = self_test(LSM6DS3_GYRO_POSITIVE_TEST); - if (ret < 0) { - LOGE("LSM6DS3 gyro positive self-test failed!"); - if (do_self_test) goto fail; - } - - ret = self_test(LSM6DS3_GYRO_NEGATIVE_TEST); - if (ret < 0) { - LOGE("LSM6DS3 gyro negative self-test failed!"); - if (do_self_test) goto fail; - } - - // TODO: set scale. Default is +- 250 deg/s - ret = set_register(LSM6DS3_GYRO_I2C_REG_CTRL2_G, LSM6DS3_GYRO_ODR_104HZ); - if (ret < 0) { - goto fail; - } - - ret = set_register(LSM6DS3_GYRO_I2C_REG_DRDY_CFG, LSM6DS3_GYRO_DRDY_PULSE_MODE); - if (ret < 0) { - goto fail; - } - - // enable data ready interrupt for gyro on INT1 - // (without resetting existing interrupts) - ret = read_register(LSM6DS3_GYRO_I2C_REG_INT1_CTRL, &value, 1); - if (ret < 0) { - goto fail; - } - - value |= LSM6DS3_GYRO_INT1_DRDY_G; - ret = set_register(LSM6DS3_GYRO_I2C_REG_INT1_CTRL, value); - -fail: - return ret; -} - -int LSM6DS3_Gyro::shutdown() { - int ret = 0; - - // disable data ready interrupt for gyro on INT1 - uint8_t value = 0; - ret = read_register(LSM6DS3_GYRO_I2C_REG_INT1_CTRL, &value, 1); - if (ret < 0) { - goto fail; - } - - value &= ~(LSM6DS3_GYRO_INT1_DRDY_G); - ret = set_register(LSM6DS3_GYRO_I2C_REG_INT1_CTRL, value); - if (ret < 0) { - LOGE("Could not disable lsm6ds3 gyroscope interrupt!"); - goto fail; - } - - // enable power-down mode - value = 0; - ret = read_register(LSM6DS3_GYRO_I2C_REG_CTRL2_G, &value, 1); - if (ret < 0) { - goto fail; - } - - value &= 0x0F; - ret = set_register(LSM6DS3_GYRO_I2C_REG_CTRL2_G, value); - if (ret < 0) { - LOGE("Could not power-down lsm6ds3 gyroscope!"); - goto fail; - } - -fail: - return ret; -} - -bool LSM6DS3_Gyro::get_event(MessageBuilder &msg, uint64_t ts) { - - // INT1 shared with accel, check STATUS_REG who triggered - uint8_t status_reg = 0; - read_register(LSM6DS3_GYRO_I2C_REG_STAT_REG, &status_reg, sizeof(status_reg)); - if ((status_reg & LSM6DS3_GYRO_DRDY_GDA) == 0) { - return false; - } - - uint8_t buffer[6]; - int len = read_register(LSM6DS3_GYRO_I2C_REG_OUTX_L_G, buffer, sizeof(buffer)); - assert(len == sizeof(buffer)); - - float scale = 8.75 / 1000.0; - float x = DEG2RAD(read_16_bit(buffer[0], buffer[1]) * scale); - float y = DEG2RAD(read_16_bit(buffer[2], buffer[3]) * scale); - float z = DEG2RAD(read_16_bit(buffer[4], buffer[5]) * scale); - - auto event = msg.initEvent().initGyroscope(); - event.setSource(source); - event.setVersion(2); - event.setSensor(SENSOR_GYRO_UNCALIBRATED); - event.setType(SENSOR_TYPE_GYROSCOPE_UNCALIBRATED); - event.setTimestamp(ts); - - float xyz[] = {y, -x, z}; - auto svec = event.initGyroUncalibrated(); - svec.setV(xyz); - svec.setStatus(true); - - return true; -} diff --git a/system/sensord/sensors/lsm6ds3_gyro.h b/system/sensord/sensors/lsm6ds3_gyro.h deleted file mode 100644 index adaae62..0000000 --- a/system/sensord/sensors/lsm6ds3_gyro.h +++ /dev/null @@ -1,45 +0,0 @@ -#pragma once - -#include "system/sensord/sensors/i2c_sensor.h" - -// Address of the chip on the bus -#define LSM6DS3_GYRO_I2C_ADDR 0x6A - -// Registers of the chip -#define LSM6DS3_GYRO_I2C_REG_DRDY_CFG 0x0B -#define LSM6DS3_GYRO_I2C_REG_ID 0x0F -#define LSM6DS3_GYRO_I2C_REG_INT1_CTRL 0x0D -#define LSM6DS3_GYRO_I2C_REG_CTRL2_G 0x11 -#define LSM6DS3_GYRO_I2C_REG_CTRL5_C 0x14 -#define LSM6DS3_GYRO_I2C_REG_STAT_REG 0x1E -#define LSM6DS3_GYRO_I2C_REG_OUTX_L_G 0x22 -#define LSM6DS3_GYRO_POSITIVE_TEST (0b01 << 2) -#define LSM6DS3_GYRO_NEGATIVE_TEST (0b11 << 2) - -// Constants -#define LSM6DS3_GYRO_CHIP_ID 0x69 -#define LSM6DS3TRC_GYRO_CHIP_ID 0x6A -#define LSM6DS3_GYRO_FS_2000dps (0b11 << 2) -#define LSM6DS3_GYRO_ODR_104HZ (0b0100 << 4) -#define LSM6DS3_GYRO_ODR_208HZ (0b0101 << 4) -#define LSM6DS3_GYRO_INT1_DRDY_G 0b10 -#define LSM6DS3_GYRO_DRDY_GDA 0b10 -#define LSM6DS3_GYRO_DRDY_PULSE_MODE (1 << 7) -#define LSM6DS3_GYRO_MIN_ST_LIMIT_mdps 150000.0f -#define LSM6DS3_GYRO_MAX_ST_LIMIT_mdps 700000.0f - - -class LSM6DS3_Gyro : public I2CSensor { - uint8_t get_device_address() {return LSM6DS3_GYRO_I2C_ADDR;} - cereal::SensorEventData::SensorSource source = cereal::SensorEventData::SensorSource::LSM6DS3; - - // self test functions - int self_test(int test_type); - void wait_for_data_ready(); - void read_and_avg_data(float* val_st_off); -public: - LSM6DS3_Gyro(I2CBus *bus, int gpio_nr = 0, bool shared_gpio = false); - int init(); - bool get_event(MessageBuilder &msg, uint64_t ts = 0); - int shutdown(); -}; diff --git a/system/sensord/sensors/lsm6ds3_temp.cc b/system/sensord/sensors/lsm6ds3_temp.cc deleted file mode 100644 index f481614..0000000 --- a/system/sensord/sensors/lsm6ds3_temp.cc +++ /dev/null @@ -1,37 +0,0 @@ -#include "system/sensord/sensors/lsm6ds3_temp.h" - -#include - -#include "common/swaglog.h" -#include "common/timing.h" - -LSM6DS3_Temp::LSM6DS3_Temp(I2CBus *bus) : I2CSensor(bus) {} - -int LSM6DS3_Temp::init() { - int ret = verify_chip_id(LSM6DS3_TEMP_I2C_REG_ID, {LSM6DS3_TEMP_CHIP_ID, LSM6DS3TRC_TEMP_CHIP_ID}); - if (ret == -1) return -1; - - if (ret == LSM6DS3TRC_TEMP_CHIP_ID) { - source = cereal::SensorEventData::SensorSource::LSM6DS3TRC; - } - return 0; -} - -bool LSM6DS3_Temp::get_event(MessageBuilder &msg, uint64_t ts) { - uint64_t start_time = nanos_since_boot(); - uint8_t buffer[2]; - int len = read_register(LSM6DS3_TEMP_I2C_REG_OUT_TEMP_L, buffer, sizeof(buffer)); - assert(len == sizeof(buffer)); - - float scale = (source == cereal::SensorEventData::SensorSource::LSM6DS3TRC) ? 256.0f : 16.0f; - float temp = 25.0f + read_16_bit(buffer[0], buffer[1]) / scale; - - auto event = msg.initEvent().initTemperatureSensor(); - event.setSource(source); - event.setVersion(1); - event.setType(SENSOR_TYPE_AMBIENT_TEMPERATURE); - event.setTimestamp(start_time); - event.setTemperature(temp); - - return true; -} diff --git a/system/sensord/sensors/lsm6ds3_temp.h b/system/sensord/sensors/lsm6ds3_temp.h deleted file mode 100644 index 1b5b621..0000000 --- a/system/sensord/sensors/lsm6ds3_temp.h +++ /dev/null @@ -1,26 +0,0 @@ -#pragma once - -#include "system/sensord/sensors/i2c_sensor.h" - -// Address of the chip on the bus -#define LSM6DS3_TEMP_I2C_ADDR 0x6A - -// Registers of the chip -#define LSM6DS3_TEMP_I2C_REG_ID 0x0F -#define LSM6DS3_TEMP_I2C_REG_OUT_TEMP_L 0x20 - -// Constants -#define LSM6DS3_TEMP_CHIP_ID 0x69 -#define LSM6DS3TRC_TEMP_CHIP_ID 0x6A - - -class LSM6DS3_Temp : public I2CSensor { - uint8_t get_device_address() {return LSM6DS3_TEMP_I2C_ADDR;} - cereal::SensorEventData::SensorSource source = cereal::SensorEventData::SensorSource::LSM6DS3; - -public: - LSM6DS3_Temp(I2CBus *bus); - int init(); - bool get_event(MessageBuilder &msg, uint64_t ts = 0); - int shutdown() { return 0; } -}; diff --git a/system/sensord/sensors/mmc5603nj_magn.cc b/system/sensord/sensors/mmc5603nj_magn.cc deleted file mode 100644 index 0e8ba96..0000000 --- a/system/sensord/sensors/mmc5603nj_magn.cc +++ /dev/null @@ -1,108 +0,0 @@ -#include "system/sensord/sensors/mmc5603nj_magn.h" - -#include -#include -#include - -#include "common/swaglog.h" -#include "common/timing.h" -#include "common/util.h" - -MMC5603NJ_Magn::MMC5603NJ_Magn(I2CBus *bus) : I2CSensor(bus) {} - -int MMC5603NJ_Magn::init() { - int ret = verify_chip_id(MMC5603NJ_I2C_REG_ID, {MMC5603NJ_CHIP_ID}); - if (ret == -1) return -1; - - // Set ODR to 0 - ret = set_register(MMC5603NJ_I2C_REG_ODR, 0); - if (ret < 0) { - goto fail; - } - - // Set BW to 0b01 for 1-150 Hz operation - ret = set_register(MMC5603NJ_I2C_REG_INTERNAL_1, 0b01); - if (ret < 0) { - goto fail; - } - -fail: - return ret; -} - -int MMC5603NJ_Magn::shutdown() { - int ret = 0; - - // disable auto reset of measurements - uint8_t value = 0; - ret = read_register(MMC5603NJ_I2C_REG_INTERNAL_0, &value, 1); - if (ret < 0) { - goto fail; - } - - value &= ~(MMC5603NJ_CMM_FREQ_EN | MMC5603NJ_AUTO_SR_EN); - ret = set_register(MMC5603NJ_I2C_REG_INTERNAL_0, value); - if (ret < 0) { - goto fail; - } - - // set ODR to 0 to leave continuous mode - ret = set_register(MMC5603NJ_I2C_REG_ODR, 0); - if (ret < 0) { - goto fail; - } - return ret; - -fail: - LOGE("Could not disable mmc5603nj auto set reset"); - return ret; -} - -void MMC5603NJ_Magn::start_measurement() { - set_register(MMC5603NJ_I2C_REG_INTERNAL_0, 0b01); - util::sleep_for(5); -} - -std::vector MMC5603NJ_Magn::read_measurement() { - int len; - uint8_t buffer[9]; - len = read_register(MMC5603NJ_I2C_REG_XOUT0, buffer, sizeof(buffer)); - assert(len == sizeof(buffer)); - float scale = 1.0 / 16384.0; - float x = (read_20_bit(buffer[6], buffer[1], buffer[0]) * scale) - 32.0; - float y = (read_20_bit(buffer[7], buffer[3], buffer[2]) * scale) - 32.0; - float z = (read_20_bit(buffer[8], buffer[5], buffer[4]) * scale) - 32.0; - std::vector xyz = {x, y, z}; - return xyz; -} - -bool MMC5603NJ_Magn::get_event(MessageBuilder &msg, uint64_t ts) { - uint64_t start_time = nanos_since_boot(); - // SET - RESET cycle - set_register(MMC5603NJ_I2C_REG_INTERNAL_0, MMC5603NJ_SET); - util::sleep_for(5); - MMC5603NJ_Magn::start_measurement(); - std::vector xyz = MMC5603NJ_Magn::read_measurement(); - - set_register(MMC5603NJ_I2C_REG_INTERNAL_0, MMC5603NJ_RESET); - util::sleep_for(5); - MMC5603NJ_Magn::start_measurement(); - std::vector reset_xyz = MMC5603NJ_Magn::read_measurement(); - - auto event = msg.initEvent().initMagnetometer(); - event.setSource(cereal::SensorEventData::SensorSource::MMC5603NJ); - event.setVersion(1); - event.setSensor(SENSOR_MAGNETOMETER_UNCALIBRATED); - event.setType(SENSOR_TYPE_MAGNETIC_FIELD_UNCALIBRATED); - event.setTimestamp(start_time); - - float vals[] = {xyz[0], xyz[1], xyz[2], reset_xyz[0], reset_xyz[1], reset_xyz[2]}; - bool valid = true; - if (std::any_of(std::begin(vals), std::end(vals), [](float val) { return val == -32.0; })) { - valid = false; - } - auto svec = event.initMagneticUncalibrated(); - svec.setV(vals); - svec.setStatus(valid); - return true; -} diff --git a/system/sensord/sensors/mmc5603nj_magn.h b/system/sensord/sensors/mmc5603nj_magn.h deleted file mode 100644 index 9c0fbd2..0000000 --- a/system/sensord/sensors/mmc5603nj_magn.h +++ /dev/null @@ -1,37 +0,0 @@ -#pragma once - -#include - -#include "system/sensord/sensors/i2c_sensor.h" - -// Address of the chip on the bus -#define MMC5603NJ_I2C_ADDR 0x30 - -// Registers of the chip -#define MMC5603NJ_I2C_REG_XOUT0 0x00 -#define MMC5603NJ_I2C_REG_ODR 0x1A -#define MMC5603NJ_I2C_REG_INTERNAL_0 0x1B -#define MMC5603NJ_I2C_REG_INTERNAL_1 0x1C -#define MMC5603NJ_I2C_REG_INTERNAL_2 0x1D -#define MMC5603NJ_I2C_REG_ID 0x39 - -// Constants -#define MMC5603NJ_CHIP_ID 0x10 -#define MMC5603NJ_CMM_FREQ_EN (1 << 7) -#define MMC5603NJ_AUTO_SR_EN (1 << 5) -#define MMC5603NJ_CMM_EN (1 << 4) -#define MMC5603NJ_EN_PRD_SET (1 << 3) -#define MMC5603NJ_SET (1 << 3) -#define MMC5603NJ_RESET (1 << 4) - -class MMC5603NJ_Magn : public I2CSensor { -private: - uint8_t get_device_address() {return MMC5603NJ_I2C_ADDR;} - void start_measurement(); - std::vector read_measurement(); -public: - MMC5603NJ_Magn(I2CBus *bus); - int init(); - bool get_event(MessageBuilder &msg, uint64_t ts = 0); - int shutdown(); -}; diff --git a/system/sensord/sensors/sensor.h b/system/sensord/sensors/sensor.h deleted file mode 100644 index 1b0e3be..0000000 --- a/system/sensord/sensors/sensor.h +++ /dev/null @@ -1,22 +0,0 @@ -#pragma once - -#include "cereal/messaging/messaging.h" - -class Sensor { -public: - int gpio_fd = -1; - uint64_t start_ts = 0; - uint64_t init_delay = 500e6; // default dealy 500ms - virtual ~Sensor() {} - virtual int init() = 0; - virtual bool get_event(MessageBuilder &msg, uint64_t ts = 0) = 0; - virtual bool has_interrupt_enabled() = 0; - virtual int shutdown() = 0; - - virtual bool is_data_valid(uint64_t current_ts) { - if (start_ts == 0) { - start_ts = current_ts; - } - return (current_ts - start_ts) > init_delay; - } -}; diff --git a/system/sensord/sensors_qcom2.cc b/system/sensord/sensors_qcom2.cc deleted file mode 100644 index 9cbc248..0000000 --- a/system/sensord/sensors_qcom2.cc +++ /dev/null @@ -1,168 +0,0 @@ -#include - -#include -#include -#include -#include -#include -#include - -#include "cereal/services.h" -#include "cereal/messaging/messaging.h" -#include "common/i2c.h" -#include "common/ratekeeper.h" -#include "common/swaglog.h" -#include "common/timing.h" -#include "common/util.h" -#include "system/sensord/sensors/bmx055_accel.h" -#include "system/sensord/sensors/bmx055_gyro.h" -#include "system/sensord/sensors/bmx055_magn.h" -#include "system/sensord/sensors/bmx055_temp.h" -#include "system/sensord/sensors/constants.h" -#include "system/sensord/sensors/lsm6ds3_accel.h" -#include "system/sensord/sensors/lsm6ds3_gyro.h" -#include "system/sensord/sensors/lsm6ds3_temp.h" -#include "system/sensord/sensors/mmc5603nj_magn.h" - -#define I2C_BUS_IMU 1 - -ExitHandler do_exit; - -void interrupt_loop(std::vector> sensors) { - PubMaster pm({"gyroscope", "accelerometer"}); - - int fd = -1; - for (auto &[sensor, msg_name] : sensors) { - if (sensor->has_interrupt_enabled()) { - fd = sensor->gpio_fd; - break; - } - } - - struct pollfd fd_list[1] = {0}; - fd_list[0].fd = fd; - fd_list[0].events = POLLIN | POLLPRI; - - while (!do_exit) { - int err = poll(fd_list, 1, 100); - if (err == -1) { - if (errno == EINTR) { - continue; - } - return; - } else if (err == 0) { - LOGE("poll timed out"); - continue; - } - - if ((fd_list[0].revents & (POLLIN | POLLPRI)) == 0) { - LOGE("no poll events set"); - continue; - } - - // Read all events - struct gpioevent_data evdata[16]; - err = read(fd, evdata, sizeof(evdata)); - if (err < 0 || err % sizeof(*evdata) != 0) { - LOGE("error reading event data %d", err); - continue; - } - - int num_events = err / sizeof(*evdata); - uint64_t offset = nanos_since_epoch() - nanos_since_boot(); - uint64_t ts = evdata[num_events - 1].timestamp - offset; - - for (auto &[sensor, msg_name] : sensors) { - if (!sensor->has_interrupt_enabled()) { - continue; - } - - MessageBuilder msg; - if (!sensor->get_event(msg, ts)) { - continue; - } - - if (!sensor->is_data_valid(ts)) { - continue; - } - - pm.send(msg_name.c_str(), msg); - } - } -} - -void polling_loop(Sensor *sensor, std::string msg_name) { - PubMaster pm({msg_name.c_str()}); - RateKeeper rk(msg_name, services.at(msg_name).frequency); - while (!do_exit) { - MessageBuilder msg; - if (sensor->get_event(msg) && sensor->is_data_valid(nanos_since_boot())) { - pm.send(msg_name.c_str(), msg); - } - rk.keepTime(); - } -} - -int sensor_loop(I2CBus *i2c_bus_imu) { - // Sensor init - std::vector> sensors_init = { - {new BMX055_Accel(i2c_bus_imu), "accelerometer2"}, - {new BMX055_Gyro(i2c_bus_imu), "gyroscope2"}, - {new BMX055_Magn(i2c_bus_imu), "magnetometer"}, - {new BMX055_Temp(i2c_bus_imu), "temperatureSensor2"}, - - {new LSM6DS3_Accel(i2c_bus_imu, GPIO_LSM_INT), "accelerometer"}, - {new LSM6DS3_Gyro(i2c_bus_imu, GPIO_LSM_INT, true), "gyroscope"}, - {new LSM6DS3_Temp(i2c_bus_imu), "temperatureSensor"}, - - {new MMC5603NJ_Magn(i2c_bus_imu), "magnetometer"}, - }; - - // Initialize sensors - std::vector threads; - for (auto &[sensor, msg_name] : sensors_init) { - int err = sensor->init(); - if (err < 0) { - continue; - } - - if (!sensor->has_interrupt_enabled()) { - threads.emplace_back(polling_loop, sensor, msg_name); - } - } - - // increase interrupt quality by pinning interrupt and process to core 1 - setpriority(PRIO_PROCESS, 0, -18); - util::set_core_affinity({1}); - - // TODO: get the IRQ number from gpiochip - std::string irq_path = "/proc/irq/336/smp_affinity_list"; - if (!util::file_exists(irq_path)) { - irq_path = "/proc/irq/335/smp_affinity_list"; - } - std::system(util::string_format("sudo su -c 'echo 1 > %s'", irq_path.c_str()).c_str()); - - // thread for reading events via interrupts - threads.emplace_back(&interrupt_loop, std::ref(sensors_init)); - - // wait for all threads to finish - for (auto &t : threads) { - t.join(); - } - - for (auto &[sensor, msg_name] : sensors_init) { - sensor->shutdown(); - delete sensor; - } - return 0; -} - -int main(int argc, char *argv[]) { - try { - auto i2c_bus_imu = std::make_unique(I2C_BUS_IMU); - return sensor_loop(i2c_bus_imu.get()); - } catch (std::exception &e) { - LOGE("I2CBus init failed"); - return -1; - } -} diff --git a/system/ubloxd/SConscript b/system/ubloxd/SConscript deleted file mode 100644 index 67d9856..0000000 --- a/system/ubloxd/SConscript +++ /dev/null @@ -1,20 +0,0 @@ -Import('env', 'common', 'cereal', 'messaging') - -loc_libs = [cereal, messaging, 'zmq', common, 'capnp', 'kj', 'kaitai', 'pthread'] - -if GetOption('kaitai'): - generated = Dir('generated').srcnode().abspath - cmd = f"kaitai-struct-compiler --target cpp_stl --outdir {generated} $SOURCES" - env.Command(['generated/ubx.cpp', 'generated/ubx.h'], 'ubx.ksy', cmd) - env.Command(['generated/gps.cpp', 'generated/gps.h'], 'gps.ksy', cmd) - glonass = env.Command(['generated/glonass.cpp', 'generated/glonass.h'], 'glonass.ksy', cmd) - - # kaitai issue: https://github.com/kaitai-io/kaitai_struct/issues/910 - patch = env.Command(None, 'glonass_fix.patch', 'git apply $SOURCES') - env.Depends(patch, glonass) - -glonass_obj = env.Object('generated/glonass.cpp') -env.Program("ubloxd", ["ubloxd.cc", "ublox_msg.cc", "generated/ubx.cpp", "generated/gps.cpp", glonass_obj], LIBS=loc_libs) - -if GetOption('extras'): - env.Program("tests/test_glonass_runner", ['tests/test_glonass_runner.cc', 'tests/test_glonass_kaitai.cc', glonass_obj], LIBS=[loc_libs]) \ No newline at end of file diff --git a/system/ubloxd/generated/glonass.h b/system/ubloxd/generated/glonass.h deleted file mode 100644 index 19867ba..0000000 --- a/system/ubloxd/generated/glonass.h +++ /dev/null @@ -1,375 +0,0 @@ -#ifndef GLONASS_H_ -#define GLONASS_H_ - -// This is a generated file! Please edit source .ksy file and use kaitai-struct-compiler to rebuild - -#include "kaitai/kaitaistruct.h" -#include - -#if KAITAI_STRUCT_VERSION < 9000L -#error "Incompatible Kaitai Struct C++/STL API: version 0.9 or later is required" -#endif - -class glonass_t : public kaitai::kstruct { - -public: - class string_4_t; - class string_non_immediate_t; - class string_5_t; - class string_1_t; - class string_2_t; - class string_3_t; - - glonass_t(kaitai::kstream* p__io, kaitai::kstruct* p__parent = 0, glonass_t* p__root = 0); - -private: - void _read(); - void _clean_up(); - -public: - ~glonass_t(); - - class string_4_t : public kaitai::kstruct { - - public: - - string_4_t(kaitai::kstream* p__io, glonass_t* p__parent = 0, glonass_t* p__root = 0); - - private: - void _read(); - void _clean_up(); - - public: - ~string_4_t(); - - private: - bool f_tau_n; - int32_t m_tau_n; - - public: - int32_t tau_n(); - - private: - bool f_delta_tau_n; - int32_t m_delta_tau_n; - - public: - int32_t delta_tau_n(); - - private: - bool m_tau_n_sign; - uint64_t m_tau_n_value; - bool m_delta_tau_n_sign; - uint64_t m_delta_tau_n_value; - uint64_t m_e_n; - uint64_t m_not_used_1; - bool m_p4; - uint64_t m_f_t; - uint64_t m_not_used_2; - uint64_t m_n_t; - uint64_t m_n; - uint64_t m_m; - glonass_t* m__root; - glonass_t* m__parent; - - public: - bool tau_n_sign() const { return m_tau_n_sign; } - uint64_t tau_n_value() const { return m_tau_n_value; } - bool delta_tau_n_sign() const { return m_delta_tau_n_sign; } - uint64_t delta_tau_n_value() const { return m_delta_tau_n_value; } - uint64_t e_n() const { return m_e_n; } - uint64_t not_used_1() const { return m_not_used_1; } - bool p4() const { return m_p4; } - uint64_t f_t() const { return m_f_t; } - uint64_t not_used_2() const { return m_not_used_2; } - uint64_t n_t() const { return m_n_t; } - uint64_t n() const { return m_n; } - uint64_t m() const { return m_m; } - glonass_t* _root() const { return m__root; } - glonass_t* _parent() const { return m__parent; } - }; - - class string_non_immediate_t : public kaitai::kstruct { - - public: - - string_non_immediate_t(kaitai::kstream* p__io, glonass_t* p__parent = 0, glonass_t* p__root = 0); - - private: - void _read(); - void _clean_up(); - - public: - ~string_non_immediate_t(); - - private: - uint64_t m_data_1; - uint64_t m_data_2; - glonass_t* m__root; - glonass_t* m__parent; - - public: - uint64_t data_1() const { return m_data_1; } - uint64_t data_2() const { return m_data_2; } - glonass_t* _root() const { return m__root; } - glonass_t* _parent() const { return m__parent; } - }; - - class string_5_t : public kaitai::kstruct { - - public: - - string_5_t(kaitai::kstream* p__io, glonass_t* p__parent = 0, glonass_t* p__root = 0); - - private: - void _read(); - void _clean_up(); - - public: - ~string_5_t(); - - private: - uint64_t m_n_a; - uint64_t m_tau_c; - bool m_not_used; - uint64_t m_n_4; - uint64_t m_tau_gps; - bool m_l_n; - glonass_t* m__root; - glonass_t* m__parent; - - public: - uint64_t n_a() const { return m_n_a; } - uint64_t tau_c() const { return m_tau_c; } - bool not_used() const { return m_not_used; } - uint64_t n_4() const { return m_n_4; } - uint64_t tau_gps() const { return m_tau_gps; } - bool l_n() const { return m_l_n; } - glonass_t* _root() const { return m__root; } - glonass_t* _parent() const { return m__parent; } - }; - - class string_1_t : public kaitai::kstruct { - - public: - - string_1_t(kaitai::kstream* p__io, glonass_t* p__parent = 0, glonass_t* p__root = 0); - - private: - void _read(); - void _clean_up(); - - public: - ~string_1_t(); - - private: - bool f_x_vel; - int32_t m_x_vel; - - public: - int32_t x_vel(); - - private: - bool f_x_accel; - int32_t m_x_accel; - - public: - int32_t x_accel(); - - private: - bool f_x; - int32_t m_x; - - public: - int32_t x(); - - private: - uint64_t m_not_used; - uint64_t m_p1; - uint64_t m_t_k; - bool m_x_vel_sign; - uint64_t m_x_vel_value; - bool m_x_accel_sign; - uint64_t m_x_accel_value; - bool m_x_sign; - uint64_t m_x_value; - glonass_t* m__root; - glonass_t* m__parent; - - public: - uint64_t not_used() const { return m_not_used; } - uint64_t p1() const { return m_p1; } - uint64_t t_k() const { return m_t_k; } - bool x_vel_sign() const { return m_x_vel_sign; } - uint64_t x_vel_value() const { return m_x_vel_value; } - bool x_accel_sign() const { return m_x_accel_sign; } - uint64_t x_accel_value() const { return m_x_accel_value; } - bool x_sign() const { return m_x_sign; } - uint64_t x_value() const { return m_x_value; } - glonass_t* _root() const { return m__root; } - glonass_t* _parent() const { return m__parent; } - }; - - class string_2_t : public kaitai::kstruct { - - public: - - string_2_t(kaitai::kstream* p__io, glonass_t* p__parent = 0, glonass_t* p__root = 0); - - private: - void _read(); - void _clean_up(); - - public: - ~string_2_t(); - - private: - bool f_y_vel; - int32_t m_y_vel; - - public: - int32_t y_vel(); - - private: - bool f_y_accel; - int32_t m_y_accel; - - public: - int32_t y_accel(); - - private: - bool f_y; - int32_t m_y; - - public: - int32_t y(); - - private: - uint64_t m_b_n; - bool m_p2; - uint64_t m_t_b; - uint64_t m_not_used; - bool m_y_vel_sign; - uint64_t m_y_vel_value; - bool m_y_accel_sign; - uint64_t m_y_accel_value; - bool m_y_sign; - uint64_t m_y_value; - glonass_t* m__root; - glonass_t* m__parent; - - public: - uint64_t b_n() const { return m_b_n; } - bool p2() const { return m_p2; } - uint64_t t_b() const { return m_t_b; } - uint64_t not_used() const { return m_not_used; } - bool y_vel_sign() const { return m_y_vel_sign; } - uint64_t y_vel_value() const { return m_y_vel_value; } - bool y_accel_sign() const { return m_y_accel_sign; } - uint64_t y_accel_value() const { return m_y_accel_value; } - bool y_sign() const { return m_y_sign; } - uint64_t y_value() const { return m_y_value; } - glonass_t* _root() const { return m__root; } - glonass_t* _parent() const { return m__parent; } - }; - - class string_3_t : public kaitai::kstruct { - - public: - - string_3_t(kaitai::kstream* p__io, glonass_t* p__parent = 0, glonass_t* p__root = 0); - - private: - void _read(); - void _clean_up(); - - public: - ~string_3_t(); - - private: - bool f_gamma_n; - int32_t m_gamma_n; - - public: - int32_t gamma_n(); - - private: - bool f_z_vel; - int32_t m_z_vel; - - public: - int32_t z_vel(); - - private: - bool f_z_accel; - int32_t m_z_accel; - - public: - int32_t z_accel(); - - private: - bool f_z; - int32_t m_z; - - public: - int32_t z(); - - private: - bool m_p3; - bool m_gamma_n_sign; - uint64_t m_gamma_n_value; - bool m_not_used; - uint64_t m_p; - bool m_l_n; - bool m_z_vel_sign; - uint64_t m_z_vel_value; - bool m_z_accel_sign; - uint64_t m_z_accel_value; - bool m_z_sign; - uint64_t m_z_value; - glonass_t* m__root; - glonass_t* m__parent; - - public: - bool p3() const { return m_p3; } - bool gamma_n_sign() const { return m_gamma_n_sign; } - uint64_t gamma_n_value() const { return m_gamma_n_value; } - bool not_used() const { return m_not_used; } - uint64_t p() const { return m_p; } - bool l_n() const { return m_l_n; } - bool z_vel_sign() const { return m_z_vel_sign; } - uint64_t z_vel_value() const { return m_z_vel_value; } - bool z_accel_sign() const { return m_z_accel_sign; } - uint64_t z_accel_value() const { return m_z_accel_value; } - bool z_sign() const { return m_z_sign; } - uint64_t z_value() const { return m_z_value; } - glonass_t* _root() const { return m__root; } - glonass_t* _parent() const { return m__parent; } - }; - -private: - bool m_idle_chip; - uint64_t m_string_number; - kaitai::kstruct* m_data; - uint64_t m_hamming_code; - uint64_t m_pad_1; - uint64_t m_superframe_number; - uint64_t m_pad_2; - uint64_t m_frame_number; - glonass_t* m__root; - kaitai::kstruct* m__parent; - -public: - bool idle_chip() const { return m_idle_chip; } - uint64_t string_number() const { return m_string_number; } - kaitai::kstruct* data() const { return m_data; } - uint64_t hamming_code() const { return m_hamming_code; } - uint64_t pad_1() const { return m_pad_1; } - uint64_t superframe_number() const { return m_superframe_number; } - uint64_t pad_2() const { return m_pad_2; } - uint64_t frame_number() const { return m_frame_number; } - glonass_t* _root() const { return m__root; } - kaitai::kstruct* _parent() const { return m__parent; } -}; - -#endif // GLONASS_H_ diff --git a/system/ubloxd/generated/gps.h b/system/ubloxd/generated/gps.h deleted file mode 100644 index 9dfc503..0000000 --- a/system/ubloxd/generated/gps.h +++ /dev/null @@ -1,359 +0,0 @@ -#ifndef GPS_H_ -#define GPS_H_ - -// This is a generated file! Please edit source .ksy file and use kaitai-struct-compiler to rebuild - -#include "kaitai/kaitaistruct.h" -#include - -#if KAITAI_STRUCT_VERSION < 9000L -#error "Incompatible Kaitai Struct C++/STL API: version 0.9 or later is required" -#endif - -class gps_t : public kaitai::kstruct { - -public: - class subframe_1_t; - class subframe_3_t; - class subframe_4_t; - class how_t; - class tlm_t; - class subframe_2_t; - - gps_t(kaitai::kstream* p__io, kaitai::kstruct* p__parent = 0, gps_t* p__root = 0); - -private: - void _read(); - void _clean_up(); - -public: - ~gps_t(); - - class subframe_1_t : public kaitai::kstruct { - - public: - - subframe_1_t(kaitai::kstream* p__io, gps_t* p__parent = 0, gps_t* p__root = 0); - - private: - void _read(); - void _clean_up(); - - public: - ~subframe_1_t(); - - private: - bool f_af_0; - int32_t m_af_0; - - public: - int32_t af_0(); - - private: - uint64_t m_week_no; - uint64_t m_code; - uint64_t m_sv_accuracy; - uint64_t m_sv_health; - uint64_t m_iodc_msb; - bool m_l2_p_data_flag; - uint64_t m_reserved1; - uint64_t m_reserved2; - uint64_t m_reserved3; - uint64_t m_reserved4; - int8_t m_t_gd; - uint8_t m_iodc_lsb; - uint16_t m_t_oc; - int8_t m_af_2; - int16_t m_af_1; - bool m_af_0_sign; - uint64_t m_af_0_value; - uint64_t m_reserved5; - gps_t* m__root; - gps_t* m__parent; - - public: - uint64_t week_no() const { return m_week_no; } - uint64_t code() const { return m_code; } - uint64_t sv_accuracy() const { return m_sv_accuracy; } - uint64_t sv_health() const { return m_sv_health; } - uint64_t iodc_msb() const { return m_iodc_msb; } - bool l2_p_data_flag() const { return m_l2_p_data_flag; } - uint64_t reserved1() const { return m_reserved1; } - uint64_t reserved2() const { return m_reserved2; } - uint64_t reserved3() const { return m_reserved3; } - uint64_t reserved4() const { return m_reserved4; } - int8_t t_gd() const { return m_t_gd; } - uint8_t iodc_lsb() const { return m_iodc_lsb; } - uint16_t t_oc() const { return m_t_oc; } - int8_t af_2() const { return m_af_2; } - int16_t af_1() const { return m_af_1; } - bool af_0_sign() const { return m_af_0_sign; } - uint64_t af_0_value() const { return m_af_0_value; } - uint64_t reserved5() const { return m_reserved5; } - gps_t* _root() const { return m__root; } - gps_t* _parent() const { return m__parent; } - }; - - class subframe_3_t : public kaitai::kstruct { - - public: - - subframe_3_t(kaitai::kstream* p__io, gps_t* p__parent = 0, gps_t* p__root = 0); - - private: - void _read(); - void _clean_up(); - - public: - ~subframe_3_t(); - - private: - bool f_omega_dot; - int32_t m_omega_dot; - - public: - int32_t omega_dot(); - - private: - bool f_idot; - int32_t m_idot; - - public: - int32_t idot(); - - private: - int16_t m_c_ic; - int32_t m_omega_0; - int16_t m_c_is; - int32_t m_i_0; - int16_t m_c_rc; - int32_t m_omega; - bool m_omega_dot_sign; - uint64_t m_omega_dot_value; - uint8_t m_iode; - bool m_idot_sign; - uint64_t m_idot_value; - uint64_t m_reserved; - gps_t* m__root; - gps_t* m__parent; - - public: - int16_t c_ic() const { return m_c_ic; } - int32_t omega_0() const { return m_omega_0; } - int16_t c_is() const { return m_c_is; } - int32_t i_0() const { return m_i_0; } - int16_t c_rc() const { return m_c_rc; } - int32_t omega() const { return m_omega; } - bool omega_dot_sign() const { return m_omega_dot_sign; } - uint64_t omega_dot_value() const { return m_omega_dot_value; } - uint8_t iode() const { return m_iode; } - bool idot_sign() const { return m_idot_sign; } - uint64_t idot_value() const { return m_idot_value; } - uint64_t reserved() const { return m_reserved; } - gps_t* _root() const { return m__root; } - gps_t* _parent() const { return m__parent; } - }; - - class subframe_4_t : public kaitai::kstruct { - - public: - class ionosphere_data_t; - - subframe_4_t(kaitai::kstream* p__io, gps_t* p__parent = 0, gps_t* p__root = 0); - - private: - void _read(); - void _clean_up(); - - public: - ~subframe_4_t(); - - class ionosphere_data_t : public kaitai::kstruct { - - public: - - ionosphere_data_t(kaitai::kstream* p__io, gps_t::subframe_4_t* p__parent = 0, gps_t* p__root = 0); - - private: - void _read(); - void _clean_up(); - - public: - ~ionosphere_data_t(); - - private: - int8_t m_a0; - int8_t m_a1; - int8_t m_a2; - int8_t m_a3; - int8_t m_b0; - int8_t m_b1; - int8_t m_b2; - int8_t m_b3; - gps_t* m__root; - gps_t::subframe_4_t* m__parent; - - public: - int8_t a0() const { return m_a0; } - int8_t a1() const { return m_a1; } - int8_t a2() const { return m_a2; } - int8_t a3() const { return m_a3; } - int8_t b0() const { return m_b0; } - int8_t b1() const { return m_b1; } - int8_t b2() const { return m_b2; } - int8_t b3() const { return m_b3; } - gps_t* _root() const { return m__root; } - gps_t::subframe_4_t* _parent() const { return m__parent; } - }; - - private: - uint64_t m_data_id; - uint64_t m_page_id; - ionosphere_data_t* m_body; - bool n_body; - - public: - bool _is_null_body() { body(); return n_body; }; - - private: - gps_t* m__root; - gps_t* m__parent; - - public: - uint64_t data_id() const { return m_data_id; } - uint64_t page_id() const { return m_page_id; } - ionosphere_data_t* body() const { return m_body; } - gps_t* _root() const { return m__root; } - gps_t* _parent() const { return m__parent; } - }; - - class how_t : public kaitai::kstruct { - - public: - - how_t(kaitai::kstream* p__io, gps_t* p__parent = 0, gps_t* p__root = 0); - - private: - void _read(); - void _clean_up(); - - public: - ~how_t(); - - private: - uint64_t m_tow_count; - bool m_alert; - bool m_anti_spoof; - uint64_t m_subframe_id; - uint64_t m_reserved; - gps_t* m__root; - gps_t* m__parent; - - public: - uint64_t tow_count() const { return m_tow_count; } - bool alert() const { return m_alert; } - bool anti_spoof() const { return m_anti_spoof; } - uint64_t subframe_id() const { return m_subframe_id; } - uint64_t reserved() const { return m_reserved; } - gps_t* _root() const { return m__root; } - gps_t* _parent() const { return m__parent; } - }; - - class tlm_t : public kaitai::kstruct { - - public: - - tlm_t(kaitai::kstream* p__io, gps_t* p__parent = 0, gps_t* p__root = 0); - - private: - void _read(); - void _clean_up(); - - public: - ~tlm_t(); - - private: - std::string m_preamble; - uint64_t m_tlm; - bool m_integrity_status; - bool m_reserved; - gps_t* m__root; - gps_t* m__parent; - - public: - std::string preamble() const { return m_preamble; } - uint64_t tlm() const { return m_tlm; } - bool integrity_status() const { return m_integrity_status; } - bool reserved() const { return m_reserved; } - gps_t* _root() const { return m__root; } - gps_t* _parent() const { return m__parent; } - }; - - class subframe_2_t : public kaitai::kstruct { - - public: - - subframe_2_t(kaitai::kstream* p__io, gps_t* p__parent = 0, gps_t* p__root = 0); - - private: - void _read(); - void _clean_up(); - - public: - ~subframe_2_t(); - - private: - uint8_t m_iode; - int16_t m_c_rs; - int16_t m_delta_n; - int32_t m_m_0; - int16_t m_c_uc; - int32_t m_e; - int16_t m_c_us; - uint32_t m_sqrt_a; - uint16_t m_t_oe; - bool m_fit_interval_flag; - uint64_t m_aoda; - uint64_t m_reserved; - gps_t* m__root; - gps_t* m__parent; - - public: - uint8_t iode() const { return m_iode; } - int16_t c_rs() const { return m_c_rs; } - int16_t delta_n() const { return m_delta_n; } - int32_t m_0() const { return m_m_0; } - int16_t c_uc() const { return m_c_uc; } - int32_t e() const { return m_e; } - int16_t c_us() const { return m_c_us; } - uint32_t sqrt_a() const { return m_sqrt_a; } - uint16_t t_oe() const { return m_t_oe; } - bool fit_interval_flag() const { return m_fit_interval_flag; } - uint64_t aoda() const { return m_aoda; } - uint64_t reserved() const { return m_reserved; } - gps_t* _root() const { return m__root; } - gps_t* _parent() const { return m__parent; } - }; - -private: - tlm_t* m_tlm; - how_t* m_how; - kaitai::kstruct* m_body; - bool n_body; - -public: - bool _is_null_body() { body(); return n_body; }; - -private: - gps_t* m__root; - kaitai::kstruct* m__parent; - -public: - tlm_t* tlm() const { return m_tlm; } - how_t* how() const { return m_how; } - kaitai::kstruct* body() const { return m_body; } - gps_t* _root() const { return m__root; } - kaitai::kstruct* _parent() const { return m__parent; } -}; - -#endif // GPS_H_ diff --git a/system/ubloxd/generated/ubx.h b/system/ubloxd/generated/ubx.h deleted file mode 100644 index 0221084..0000000 --- a/system/ubloxd/generated/ubx.h +++ /dev/null @@ -1,484 +0,0 @@ -#ifndef UBX_H_ -#define UBX_H_ - -// This is a generated file! Please edit source .ksy file and use kaitai-struct-compiler to rebuild - -#include "kaitai/kaitaistruct.h" -#include -#include - -#if KAITAI_STRUCT_VERSION < 9000L -#error "Incompatible Kaitai Struct C++/STL API: version 0.9 or later is required" -#endif - -class ubx_t : public kaitai::kstruct { - -public: - class rxm_rawx_t; - class rxm_sfrbx_t; - class nav_sat_t; - class nav_pvt_t; - class mon_hw2_t; - class mon_hw_t; - - enum gnss_type_t { - GNSS_TYPE_GPS = 0, - GNSS_TYPE_SBAS = 1, - GNSS_TYPE_GALILEO = 2, - GNSS_TYPE_BEIDOU = 3, - GNSS_TYPE_IMES = 4, - GNSS_TYPE_QZSS = 5, - GNSS_TYPE_GLONASS = 6 - }; - - ubx_t(kaitai::kstream* p__io, kaitai::kstruct* p__parent = 0, ubx_t* p__root = 0); - -private: - void _read(); - void _clean_up(); - -public: - ~ubx_t(); - - class rxm_rawx_t : public kaitai::kstruct { - - public: - class measurement_t; - - rxm_rawx_t(kaitai::kstream* p__io, ubx_t* p__parent = 0, ubx_t* p__root = 0); - - private: - void _read(); - void _clean_up(); - - public: - ~rxm_rawx_t(); - - class measurement_t : public kaitai::kstruct { - - public: - - measurement_t(kaitai::kstream* p__io, ubx_t::rxm_rawx_t* p__parent = 0, ubx_t* p__root = 0); - - private: - void _read(); - void _clean_up(); - - public: - ~measurement_t(); - - private: - double m_pr_mes; - double m_cp_mes; - float m_do_mes; - gnss_type_t m_gnss_id; - uint8_t m_sv_id; - std::string m_reserved2; - uint8_t m_freq_id; - uint16_t m_lock_time; - uint8_t m_cno; - uint8_t m_pr_stdev; - uint8_t m_cp_stdev; - uint8_t m_do_stdev; - uint8_t m_trk_stat; - std::string m_reserved3; - ubx_t* m__root; - ubx_t::rxm_rawx_t* m__parent; - - public: - double pr_mes() const { return m_pr_mes; } - double cp_mes() const { return m_cp_mes; } - float do_mes() const { return m_do_mes; } - gnss_type_t gnss_id() const { return m_gnss_id; } - uint8_t sv_id() const { return m_sv_id; } - std::string reserved2() const { return m_reserved2; } - uint8_t freq_id() const { return m_freq_id; } - uint16_t lock_time() const { return m_lock_time; } - uint8_t cno() const { return m_cno; } - uint8_t pr_stdev() const { return m_pr_stdev; } - uint8_t cp_stdev() const { return m_cp_stdev; } - uint8_t do_stdev() const { return m_do_stdev; } - uint8_t trk_stat() const { return m_trk_stat; } - std::string reserved3() const { return m_reserved3; } - ubx_t* _root() const { return m__root; } - ubx_t::rxm_rawx_t* _parent() const { return m__parent; } - }; - - private: - double m_rcv_tow; - uint16_t m_week; - int8_t m_leap_s; - uint8_t m_num_meas; - uint8_t m_rec_stat; - std::string m_reserved1; - std::vector* m_meas; - ubx_t* m__root; - ubx_t* m__parent; - std::vector* m__raw_meas; - std::vector* m__io__raw_meas; - - public: - double rcv_tow() const { return m_rcv_tow; } - uint16_t week() const { return m_week; } - int8_t leap_s() const { return m_leap_s; } - uint8_t num_meas() const { return m_num_meas; } - uint8_t rec_stat() const { return m_rec_stat; } - std::string reserved1() const { return m_reserved1; } - std::vector* meas() const { return m_meas; } - ubx_t* _root() const { return m__root; } - ubx_t* _parent() const { return m__parent; } - std::vector* _raw_meas() const { return m__raw_meas; } - std::vector* _io__raw_meas() const { return m__io__raw_meas; } - }; - - class rxm_sfrbx_t : public kaitai::kstruct { - - public: - - rxm_sfrbx_t(kaitai::kstream* p__io, ubx_t* p__parent = 0, ubx_t* p__root = 0); - - private: - void _read(); - void _clean_up(); - - public: - ~rxm_sfrbx_t(); - - private: - gnss_type_t m_gnss_id; - uint8_t m_sv_id; - std::string m_reserved1; - uint8_t m_freq_id; - uint8_t m_num_words; - std::string m_reserved2; - uint8_t m_version; - std::string m_reserved3; - std::vector* m_body; - ubx_t* m__root; - ubx_t* m__parent; - - public: - gnss_type_t gnss_id() const { return m_gnss_id; } - uint8_t sv_id() const { return m_sv_id; } - std::string reserved1() const { return m_reserved1; } - uint8_t freq_id() const { return m_freq_id; } - uint8_t num_words() const { return m_num_words; } - std::string reserved2() const { return m_reserved2; } - uint8_t version() const { return m_version; } - std::string reserved3() const { return m_reserved3; } - std::vector* body() const { return m_body; } - ubx_t* _root() const { return m__root; } - ubx_t* _parent() const { return m__parent; } - }; - - class nav_sat_t : public kaitai::kstruct { - - public: - class nav_t; - - nav_sat_t(kaitai::kstream* p__io, ubx_t* p__parent = 0, ubx_t* p__root = 0); - - private: - void _read(); - void _clean_up(); - - public: - ~nav_sat_t(); - - class nav_t : public kaitai::kstruct { - - public: - - nav_t(kaitai::kstream* p__io, ubx_t::nav_sat_t* p__parent = 0, ubx_t* p__root = 0); - - private: - void _read(); - void _clean_up(); - - public: - ~nav_t(); - - private: - gnss_type_t m_gnss_id; - uint8_t m_sv_id; - uint8_t m_cno; - int8_t m_elev; - int16_t m_azim; - int16_t m_pr_res; - uint32_t m_flags; - ubx_t* m__root; - ubx_t::nav_sat_t* m__parent; - - public: - gnss_type_t gnss_id() const { return m_gnss_id; } - uint8_t sv_id() const { return m_sv_id; } - uint8_t cno() const { return m_cno; } - int8_t elev() const { return m_elev; } - int16_t azim() const { return m_azim; } - int16_t pr_res() const { return m_pr_res; } - uint32_t flags() const { return m_flags; } - ubx_t* _root() const { return m__root; } - ubx_t::nav_sat_t* _parent() const { return m__parent; } - }; - - private: - uint32_t m_itow; - uint8_t m_version; - uint8_t m_num_svs; - std::string m_reserved; - std::vector* m_svs; - ubx_t* m__root; - ubx_t* m__parent; - std::vector* m__raw_svs; - std::vector* m__io__raw_svs; - - public: - uint32_t itow() const { return m_itow; } - uint8_t version() const { return m_version; } - uint8_t num_svs() const { return m_num_svs; } - std::string reserved() const { return m_reserved; } - std::vector* svs() const { return m_svs; } - ubx_t* _root() const { return m__root; } - ubx_t* _parent() const { return m__parent; } - std::vector* _raw_svs() const { return m__raw_svs; } - std::vector* _io__raw_svs() const { return m__io__raw_svs; } - }; - - class nav_pvt_t : public kaitai::kstruct { - - public: - - nav_pvt_t(kaitai::kstream* p__io, ubx_t* p__parent = 0, ubx_t* p__root = 0); - - private: - void _read(); - void _clean_up(); - - public: - ~nav_pvt_t(); - - private: - uint32_t m_i_tow; - uint16_t m_year; - uint8_t m_month; - uint8_t m_day; - uint8_t m_hour; - uint8_t m_min; - uint8_t m_sec; - uint8_t m_valid; - uint32_t m_t_acc; - int32_t m_nano; - uint8_t m_fix_type; - uint8_t m_flags; - uint8_t m_flags2; - uint8_t m_num_sv; - int32_t m_lon; - int32_t m_lat; - int32_t m_height; - int32_t m_h_msl; - uint32_t m_h_acc; - uint32_t m_v_acc; - int32_t m_vel_n; - int32_t m_vel_e; - int32_t m_vel_d; - int32_t m_g_speed; - int32_t m_head_mot; - int32_t m_s_acc; - uint32_t m_head_acc; - uint16_t m_p_dop; - uint8_t m_flags3; - std::string m_reserved1; - int32_t m_head_veh; - int16_t m_mag_dec; - uint16_t m_mag_acc; - ubx_t* m__root; - ubx_t* m__parent; - - public: - uint32_t i_tow() const { return m_i_tow; } - uint16_t year() const { return m_year; } - uint8_t month() const { return m_month; } - uint8_t day() const { return m_day; } - uint8_t hour() const { return m_hour; } - uint8_t min() const { return m_min; } - uint8_t sec() const { return m_sec; } - uint8_t valid() const { return m_valid; } - uint32_t t_acc() const { return m_t_acc; } - int32_t nano() const { return m_nano; } - uint8_t fix_type() const { return m_fix_type; } - uint8_t flags() const { return m_flags; } - uint8_t flags2() const { return m_flags2; } - uint8_t num_sv() const { return m_num_sv; } - int32_t lon() const { return m_lon; } - int32_t lat() const { return m_lat; } - int32_t height() const { return m_height; } - int32_t h_msl() const { return m_h_msl; } - uint32_t h_acc() const { return m_h_acc; } - uint32_t v_acc() const { return m_v_acc; } - int32_t vel_n() const { return m_vel_n; } - int32_t vel_e() const { return m_vel_e; } - int32_t vel_d() const { return m_vel_d; } - int32_t g_speed() const { return m_g_speed; } - int32_t head_mot() const { return m_head_mot; } - int32_t s_acc() const { return m_s_acc; } - uint32_t head_acc() const { return m_head_acc; } - uint16_t p_dop() const { return m_p_dop; } - uint8_t flags3() const { return m_flags3; } - std::string reserved1() const { return m_reserved1; } - int32_t head_veh() const { return m_head_veh; } - int16_t mag_dec() const { return m_mag_dec; } - uint16_t mag_acc() const { return m_mag_acc; } - ubx_t* _root() const { return m__root; } - ubx_t* _parent() const { return m__parent; } - }; - - class mon_hw2_t : public kaitai::kstruct { - - public: - - enum config_source_t { - CONFIG_SOURCE_FLASH = 102, - CONFIG_SOURCE_OTP = 111, - CONFIG_SOURCE_CONFIG_PINS = 112, - CONFIG_SOURCE_ROM = 113 - }; - - mon_hw2_t(kaitai::kstream* p__io, ubx_t* p__parent = 0, ubx_t* p__root = 0); - - private: - void _read(); - void _clean_up(); - - public: - ~mon_hw2_t(); - - private: - int8_t m_ofs_i; - uint8_t m_mag_i; - int8_t m_ofs_q; - uint8_t m_mag_q; - config_source_t m_cfg_source; - std::string m_reserved1; - uint32_t m_low_lev_cfg; - std::string m_reserved2; - uint32_t m_post_status; - std::string m_reserved3; - ubx_t* m__root; - ubx_t* m__parent; - - public: - int8_t ofs_i() const { return m_ofs_i; } - uint8_t mag_i() const { return m_mag_i; } - int8_t ofs_q() const { return m_ofs_q; } - uint8_t mag_q() const { return m_mag_q; } - config_source_t cfg_source() const { return m_cfg_source; } - std::string reserved1() const { return m_reserved1; } - uint32_t low_lev_cfg() const { return m_low_lev_cfg; } - std::string reserved2() const { return m_reserved2; } - uint32_t post_status() const { return m_post_status; } - std::string reserved3() const { return m_reserved3; } - ubx_t* _root() const { return m__root; } - ubx_t* _parent() const { return m__parent; } - }; - - class mon_hw_t : public kaitai::kstruct { - - public: - - enum antenna_status_t { - ANTENNA_STATUS_INIT = 0, - ANTENNA_STATUS_DONTKNOW = 1, - ANTENNA_STATUS_OK = 2, - ANTENNA_STATUS_SHORT = 3, - ANTENNA_STATUS_OPEN = 4 - }; - - enum antenna_power_t { - ANTENNA_POWER_FALSE = 0, - ANTENNA_POWER_TRUE = 1, - ANTENNA_POWER_DONTKNOW = 2 - }; - - mon_hw_t(kaitai::kstream* p__io, ubx_t* p__parent = 0, ubx_t* p__root = 0); - - private: - void _read(); - void _clean_up(); - - public: - ~mon_hw_t(); - - private: - uint32_t m_pin_sel; - uint32_t m_pin_bank; - uint32_t m_pin_dir; - uint32_t m_pin_val; - uint16_t m_noise_per_ms; - uint16_t m_agc_cnt; - antenna_status_t m_a_status; - antenna_power_t m_a_power; - uint8_t m_flags; - std::string m_reserved1; - uint32_t m_used_mask; - std::string m_vp; - uint8_t m_jam_ind; - std::string m_reserved2; - uint32_t m_pin_irq; - uint32_t m_pull_h; - uint32_t m_pull_l; - ubx_t* m__root; - ubx_t* m__parent; - - public: - uint32_t pin_sel() const { return m_pin_sel; } - uint32_t pin_bank() const { return m_pin_bank; } - uint32_t pin_dir() const { return m_pin_dir; } - uint32_t pin_val() const { return m_pin_val; } - uint16_t noise_per_ms() const { return m_noise_per_ms; } - uint16_t agc_cnt() const { return m_agc_cnt; } - antenna_status_t a_status() const { return m_a_status; } - antenna_power_t a_power() const { return m_a_power; } - uint8_t flags() const { return m_flags; } - std::string reserved1() const { return m_reserved1; } - uint32_t used_mask() const { return m_used_mask; } - std::string vp() const { return m_vp; } - uint8_t jam_ind() const { return m_jam_ind; } - std::string reserved2() const { return m_reserved2; } - uint32_t pin_irq() const { return m_pin_irq; } - uint32_t pull_h() const { return m_pull_h; } - uint32_t pull_l() const { return m_pull_l; } - ubx_t* _root() const { return m__root; } - ubx_t* _parent() const { return m__parent; } - }; - -private: - bool f_checksum; - uint16_t m_checksum; - -public: - uint16_t checksum(); - -private: - std::string m_magic; - uint16_t m_msg_type; - uint16_t m_length; - kaitai::kstruct* m_body; - bool n_body; - -public: - bool _is_null_body() { body(); return n_body; }; - -private: - ubx_t* m__root; - kaitai::kstruct* m__parent; - -public: - std::string magic() const { return m_magic; } - uint16_t msg_type() const { return m_msg_type; } - uint16_t length() const { return m_length; } - kaitai::kstruct* body() const { return m_body; } - ubx_t* _root() const { return m__root; } - kaitai::kstruct* _parent() const { return m__parent; } -}; - -#endif // UBX_H_ diff --git a/system/ubloxd/ublox_msg.cc b/system/ubloxd/ublox_msg.cc deleted file mode 100644 index 7b4505d..0000000 --- a/system/ubloxd/ublox_msg.cc +++ /dev/null @@ -1,524 +0,0 @@ -#include "system/ubloxd/ublox_msg.h" - -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include "common/swaglog.h" - -const double gpsPi = 3.1415926535898; -#define UBLOX_MSG_SIZE(hdr) (*(uint16_t *)&hdr[4]) - -inline static bool bit_to_bool(uint8_t val, int shifts) { - return (bool)(val & (1 << shifts)); -} - -inline int UbloxMsgParser::needed_bytes() { - // Msg header incomplete? - if (bytes_in_parse_buf < ublox::UBLOX_HEADER_SIZE) - return ublox::UBLOX_HEADER_SIZE + ublox::UBLOX_CHECKSUM_SIZE - bytes_in_parse_buf; - uint16_t needed = UBLOX_MSG_SIZE(msg_parse_buf) + ublox::UBLOX_HEADER_SIZE + ublox::UBLOX_CHECKSUM_SIZE; - // too much data - if (needed < (uint16_t)bytes_in_parse_buf) - return -1; - return needed - (uint16_t)bytes_in_parse_buf; -} - -inline bool UbloxMsgParser::valid_cheksum() { - uint8_t ck_a = 0, ck_b = 0; - for (int i = 2; i < bytes_in_parse_buf - ublox::UBLOX_CHECKSUM_SIZE; i++) { - ck_a = (ck_a + msg_parse_buf[i]) & 0xFF; - ck_b = (ck_b + ck_a) & 0xFF; - } - if (ck_a != msg_parse_buf[bytes_in_parse_buf - 2]) { - LOGD("Checksum a mismatch: %02X, %02X", ck_a, msg_parse_buf[6]); - return false; - } - if (ck_b != msg_parse_buf[bytes_in_parse_buf - 1]) { - LOGD("Checksum b mismatch: %02X, %02X", ck_b, msg_parse_buf[7]); - return false; - } - return true; -} - -inline bool UbloxMsgParser::valid() { - return bytes_in_parse_buf >= ublox::UBLOX_HEADER_SIZE + ublox::UBLOX_CHECKSUM_SIZE && - needed_bytes() == 0 && valid_cheksum(); -} - -inline bool UbloxMsgParser::valid_so_far() { - if (bytes_in_parse_buf > 0 && msg_parse_buf[0] != ublox::PREAMBLE1) { - return false; - } - if (bytes_in_parse_buf > 1 && msg_parse_buf[1] != ublox::PREAMBLE2) { - return false; - } - if (needed_bytes() == 0 && !valid()) { - return false; - } - return true; -} - -bool UbloxMsgParser::add_data(float log_time, const uint8_t *incoming_data, uint32_t incoming_data_len, size_t &bytes_consumed) { - last_log_time = log_time; - int needed = needed_bytes(); - if (needed > 0) { - bytes_consumed = std::min((uint32_t)needed, incoming_data_len); - // Add data to buffer - memcpy(msg_parse_buf + bytes_in_parse_buf, incoming_data, bytes_consumed); - bytes_in_parse_buf += bytes_consumed; - } else { - bytes_consumed = incoming_data_len; - } - - // Validate msg format, detect invalid header and invalid checksum. - while (!valid_so_far() && bytes_in_parse_buf != 0) { - // Corrupted msg, drop a byte. - bytes_in_parse_buf -= 1; - if (bytes_in_parse_buf > 0) - memmove(&msg_parse_buf[0], &msg_parse_buf[1], bytes_in_parse_buf); - } - - // There is redundant data at the end of buffer, reset the buffer. - if (needed_bytes() == -1) { - bytes_in_parse_buf = 0; - } - return valid(); -} - - -std::pair> UbloxMsgParser::gen_msg() { - std::string dat = data(); - kaitai::kstream stream(dat); - - ubx_t ubx_message(&stream); - auto body = ubx_message.body(); - - switch (ubx_message.msg_type()) { - case 0x0107: - return {"gpsLocationExternal", gen_nav_pvt(static_cast(body))}; - case 0x0213: // UBX-RXM-SFRB (Broadcast Navigation Data Subframe) - return {"ubloxGnss", gen_rxm_sfrbx(static_cast(body))}; - case 0x0215: // UBX-RXM-RAW (Multi-GNSS Raw Measurement Data) - return {"ubloxGnss", gen_rxm_rawx(static_cast(body))}; - case 0x0a09: - return {"ubloxGnss", gen_mon_hw(static_cast(body))}; - case 0x0a0b: - return {"ubloxGnss", gen_mon_hw2(static_cast(body))}; - case 0x0135: - return {"ubloxGnss", gen_nav_sat(static_cast(body))}; - default: - LOGE("Unknown message type %x", ubx_message.msg_type()); - return {"ubloxGnss", kj::Array()}; - } -} - - -kj::Array UbloxMsgParser::gen_nav_pvt(ubx_t::nav_pvt_t *msg) { - MessageBuilder msg_builder; - auto gpsLoc = msg_builder.initEvent().initGpsLocationExternal(); - gpsLoc.setSource(cereal::GpsLocationData::SensorSource::UBLOX); - gpsLoc.setFlags(msg->flags()); - gpsLoc.setLatitude(msg->lat() * 1e-07); - gpsLoc.setLongitude(msg->lon() * 1e-07); - gpsLoc.setAltitude(msg->height() * 1e-03); - gpsLoc.setSpeed(msg->g_speed() * 1e-03); - gpsLoc.setBearingDeg(msg->head_mot() * 1e-5); - gpsLoc.setAccuracy(msg->h_acc() * 1e-03); - std::tm timeinfo = std::tm(); - timeinfo.tm_year = msg->year() - 1900; - timeinfo.tm_mon = msg->month() - 1; - timeinfo.tm_mday = msg->day(); - timeinfo.tm_hour = msg->hour(); - timeinfo.tm_min = msg->min(); - timeinfo.tm_sec = msg->sec(); - - std::time_t utc_tt = timegm(&timeinfo); - gpsLoc.setUnixTimestampMillis(utc_tt * 1e+03 + msg->nano() * 1e-06); - float f[] = { msg->vel_n() * 1e-03f, msg->vel_e() * 1e-03f, msg->vel_d() * 1e-03f }; - gpsLoc.setVNED(f); - gpsLoc.setVerticalAccuracy(msg->v_acc() * 1e-03); - gpsLoc.setSpeedAccuracy(msg->s_acc() * 1e-03); - gpsLoc.setBearingAccuracyDeg(msg->head_acc() * 1e-05); - return capnp::messageToFlatArray(msg_builder); -} - -kj::Array UbloxMsgParser::parse_gps_ephemeris(ubx_t::rxm_sfrbx_t *msg) { - // GPS subframes are packed into 10x 4 bytes, each containing 3 actual bytes - // We will first need to separate the data from the padding and parity - auto body = *msg->body(); - assert(body.size() == 10); - - std::string subframe_data; - subframe_data.reserve(30); - for (uint32_t word : body) { - word = word >> 6; // TODO: Verify parity - subframe_data.push_back(word >> 16); - subframe_data.push_back(word >> 8); - subframe_data.push_back(word >> 0); - } - - // Collect subframes in map and parse when we have all the parts - { - kaitai::kstream stream(subframe_data); - gps_t subframe(&stream); - - int subframe_id = subframe.how()->subframe_id(); - if (subframe_id > 3 || subframe_id < 1) { - // dont parse almanac subframes - return kj::Array(); - } - gps_subframes[msg->sv_id()][subframe_id] = subframe_data; - } - - // publish if subframes 1-3 have been collected - if (gps_subframes[msg->sv_id()].size() == 3) { - MessageBuilder msg_builder; - auto eph = msg_builder.initEvent().initUbloxGnss().initEphemeris(); - eph.setSvId(msg->sv_id()); - - int iode_s2 = 0; - int iode_s3 = 0; - int iodc_lsb = 0; - int week; - - // Subframe 1 - { - kaitai::kstream stream(gps_subframes[msg->sv_id()][1]); - gps_t subframe(&stream); - gps_t::subframe_1_t* subframe_1 = static_cast(subframe.body()); - - // Each message is incremented to be greater or equal than week 1877 (2015-12-27). - // To skip this use the current_time argument - week = subframe_1->week_no(); - week += 1024; - if (week < 1877) { - week += 1024; - } - //eph.setGpsWeek(subframe_1->week_no()); - eph.setTgd(subframe_1->t_gd() * pow(2, -31)); - eph.setToc(subframe_1->t_oc() * pow(2, 4)); - eph.setAf2(subframe_1->af_2() * pow(2, -55)); - eph.setAf1(subframe_1->af_1() * pow(2, -43)); - eph.setAf0(subframe_1->af_0() * pow(2, -31)); - eph.setSvHealth(subframe_1->sv_health()); - eph.setTowCount(subframe.how()->tow_count()); - iodc_lsb = subframe_1->iodc_lsb(); - } - - // Subframe 2 - { - kaitai::kstream stream(gps_subframes[msg->sv_id()][2]); - gps_t subframe(&stream); - gps_t::subframe_2_t* subframe_2 = static_cast(subframe.body()); - - // GPS week refers to current week, the ephemeris can be valid for the next - // if toe equals 0, this can be verified by the TOW count if it is within the - // last 2 hours of the week (gps ephemeris valid for 4hours) - if (subframe_2->t_oe() == 0 and subframe.how()->tow_count()*6 >= (SECS_IN_WEEK - 2*SECS_IN_HR)){ - week += 1; - } - eph.setCrs(subframe_2->c_rs() * pow(2, -5)); - eph.setDeltaN(subframe_2->delta_n() * pow(2, -43) * gpsPi); - eph.setM0(subframe_2->m_0() * pow(2, -31) * gpsPi); - eph.setCuc(subframe_2->c_uc() * pow(2, -29)); - eph.setEcc(subframe_2->e() * pow(2, -33)); - eph.setCus(subframe_2->c_us() * pow(2, -29)); - eph.setA(pow(subframe_2->sqrt_a() * pow(2, -19), 2.0)); - eph.setToe(subframe_2->t_oe() * pow(2, 4)); - iode_s2 = subframe_2->iode(); - } - - // Subframe 3 - { - kaitai::kstream stream(gps_subframes[msg->sv_id()][3]); - gps_t subframe(&stream); - gps_t::subframe_3_t* subframe_3 = static_cast(subframe.body()); - - eph.setCic(subframe_3->c_ic() * pow(2, -29)); - eph.setOmega0(subframe_3->omega_0() * pow(2, -31) * gpsPi); - eph.setCis(subframe_3->c_is() * pow(2, -29)); - eph.setI0(subframe_3->i_0() * pow(2, -31) * gpsPi); - eph.setCrc(subframe_3->c_rc() * pow(2, -5)); - eph.setOmega(subframe_3->omega() * pow(2, -31) * gpsPi); - eph.setOmegaDot(subframe_3->omega_dot() * pow(2, -43) * gpsPi); - eph.setIode(subframe_3->iode()); - eph.setIDot(subframe_3->idot() * pow(2, -43) * gpsPi); - iode_s3 = subframe_3->iode(); - } - - eph.setToeWeek(week); - eph.setTocWeek(week); - - gps_subframes[msg->sv_id()].clear(); - if (iodc_lsb != iode_s2 || iodc_lsb != iode_s3) { - // data set cutover, reject ephemeris - return kj::Array(); - } - return capnp::messageToFlatArray(msg_builder); - } - return kj::Array(); -} - -kj::Array UbloxMsgParser::parse_glonass_ephemeris(ubx_t::rxm_sfrbx_t *msg) { - // This parser assumes that no 2 satellites of the same frequency - // can be in view at the same time - auto body = *msg->body(); - assert(body.size() == 4); - { - std::string string_data; - string_data.reserve(16); - for (uint32_t word : body) { - for (int i = 3; i >= 0; i--) - string_data.push_back(word >> 8*i); - } - - kaitai::kstream stream(string_data); - glonass_t gl_string(&stream); - int string_number = gl_string.string_number(); - if (string_number < 1 || string_number > 5 || gl_string.idle_chip()) { - // dont parse non immediate data, idle_chip == 0 - return kj::Array(); - } - - // Check if new string either has same superframe_id or log transmission times make sense - bool superframe_unknown = false; - bool needs_clear = false; - for (int i = 1; i <= 5; i++) { - if (glonass_strings[msg->freq_id()].find(i) == glonass_strings[msg->freq_id()].end()) - continue; - if (glonass_string_superframes[msg->freq_id()][i] == 0 || gl_string.superframe_number() == 0) { - superframe_unknown = true; - } else if (glonass_string_superframes[msg->freq_id()][i] != gl_string.superframe_number()) { - needs_clear = true; - } - // Check if string times add up to being from the same frame - // If superframe is known this is redundant - // Strings are sent 2s apart and frames are 30s apart - if (superframe_unknown && - std::abs((glonass_string_times[msg->freq_id()][i] - 2.0 * i) - (last_log_time - 2.0 * string_number)) > 10) - needs_clear = true; - } - if (needs_clear) { - glonass_strings[msg->freq_id()].clear(); - glonass_string_superframes[msg->freq_id()].clear(); - glonass_string_times[msg->freq_id()].clear(); - } - glonass_strings[msg->freq_id()][string_number] = string_data; - glonass_string_superframes[msg->freq_id()][string_number] = gl_string.superframe_number(); - glonass_string_times[msg->freq_id()][string_number] = last_log_time; - } - if (msg->sv_id() == 255) { - // data can be decoded before identifying the SV number, in this case 255 - // is returned, which means "unknown" (ublox p32) - return kj::Array(); - } - - // publish if strings 1-5 have been collected - if (glonass_strings[msg->freq_id()].size() != 5) { - return kj::Array(); - } - - MessageBuilder msg_builder; - auto eph = msg_builder.initEvent().initUbloxGnss().initGlonassEphemeris(); - eph.setSvId(msg->sv_id()); - eph.setFreqNum(msg->freq_id() - 7); - - uint16_t current_day = 0; - uint16_t tk = 0; - - // string number 1 - { - kaitai::kstream stream(glonass_strings[msg->freq_id()][1]); - glonass_t gl_stream(&stream); - glonass_t::string_1_t* data = static_cast(gl_stream.data()); - - eph.setP1(data->p1()); - tk = data->t_k(); - eph.setTkDEPRECATED(tk); - eph.setXVel(data->x_vel() * pow(2, -20)); - eph.setXAccel(data->x_accel() * pow(2, -30)); - eph.setX(data->x() * pow(2, -11)); - } - - // string number 2 - { - kaitai::kstream stream(glonass_strings[msg->freq_id()][2]); - glonass_t gl_stream(&stream); - glonass_t::string_2_t* data = static_cast(gl_stream.data()); - - eph.setSvHealth(data->b_n()>>2); // MSB indicates health - eph.setP2(data->p2()); - eph.setTb(data->t_b()); - eph.setYVel(data->y_vel() * pow(2, -20)); - eph.setYAccel(data->y_accel() * pow(2, -30)); - eph.setY(data->y() * pow(2, -11)); - } - - // string number 3 - { - kaitai::kstream stream(glonass_strings[msg->freq_id()][3]); - glonass_t gl_stream(&stream); - glonass_t::string_3_t* data = static_cast(gl_stream.data()); - - eph.setP3(data->p3()); - eph.setGammaN(data->gamma_n() * pow(2, -40)); - eph.setSvHealth(eph.getSvHealth() | data->l_n()); - eph.setZVel(data->z_vel() * pow(2, -20)); - eph.setZAccel(data->z_accel() * pow(2, -30)); - eph.setZ(data->z() * pow(2, -11)); - } - - // string number 4 - { - kaitai::kstream stream(glonass_strings[msg->freq_id()][4]); - glonass_t gl_stream(&stream); - glonass_t::string_4_t* data = static_cast(gl_stream.data()); - - current_day = data->n_t(); - eph.setNt(current_day); - eph.setTauN(data->tau_n() * pow(2, -30)); - eph.setDeltaTauN(data->delta_tau_n() * pow(2, -30)); - eph.setAge(data->e_n()); - eph.setP4(data->p4()); - eph.setSvURA(glonass_URA_lookup.at(data->f_t())); - if (msg->sv_id() != data->n()) { - LOGE("SV_ID != SLOT_NUMBER: %d %" PRIu64, msg->sv_id(), data->n()); - } - eph.setSvType(data->m()); - } - - // string number 5 - { - kaitai::kstream stream(glonass_strings[msg->freq_id()][5]); - glonass_t gl_stream(&stream); - glonass_t::string_5_t* data = static_cast(gl_stream.data()); - - // string5 parsing is only needed to get the year, this can be removed and - // the year can be fetched later in laika (note rollovers and leap year) - eph.setN4(data->n_4()); - int tk_seconds = SECS_IN_HR * ((tk>>7) & 0x1F) + SECS_IN_MIN * ((tk>>1) & 0x3F) + (tk & 0x1) * 30; - eph.setTkSeconds(tk_seconds); - } - - glonass_strings[msg->freq_id()].clear(); - return capnp::messageToFlatArray(msg_builder); -} - - -kj::Array UbloxMsgParser::gen_rxm_sfrbx(ubx_t::rxm_sfrbx_t *msg) { - switch (msg->gnss_id()) { - case ubx_t::gnss_type_t::GNSS_TYPE_GPS: - return parse_gps_ephemeris(msg); - case ubx_t::gnss_type_t::GNSS_TYPE_GLONASS: - return parse_glonass_ephemeris(msg); - default: - return kj::Array(); - } -} - -kj::Array UbloxMsgParser::gen_rxm_rawx(ubx_t::rxm_rawx_t *msg) { - MessageBuilder msg_builder; - auto mr = msg_builder.initEvent().initUbloxGnss().initMeasurementReport(); - mr.setRcvTow(msg->rcv_tow()); - mr.setGpsWeek(msg->week()); - mr.setLeapSeconds(msg->leap_s()); - mr.setGpsWeek(msg->week()); - - auto mb = mr.initMeasurements(msg->num_meas()); - auto measurements = *msg->meas(); - for (int8_t i = 0; i < msg->num_meas(); i++) { - mb[i].setSvId(measurements[i]->sv_id()); - mb[i].setPseudorange(measurements[i]->pr_mes()); - mb[i].setCarrierCycles(measurements[i]->cp_mes()); - mb[i].setDoppler(measurements[i]->do_mes()); - mb[i].setGnssId(measurements[i]->gnss_id()); - mb[i].setGlonassFrequencyIndex(measurements[i]->freq_id()); - mb[i].setLocktime(measurements[i]->lock_time()); - mb[i].setCno(measurements[i]->cno()); - mb[i].setPseudorangeStdev(0.01 * (pow(2, (measurements[i]->pr_stdev() & 15)))); // weird scaling, might be wrong - mb[i].setCarrierPhaseStdev(0.004 * (measurements[i]->cp_stdev() & 15)); - mb[i].setDopplerStdev(0.002 * (pow(2, (measurements[i]->do_stdev() & 15)))); // weird scaling, might be wrong - - auto ts = mb[i].initTrackingStatus(); - auto trk_stat = measurements[i]->trk_stat(); - ts.setPseudorangeValid(bit_to_bool(trk_stat, 0)); - ts.setCarrierPhaseValid(bit_to_bool(trk_stat, 1)); - ts.setHalfCycleValid(bit_to_bool(trk_stat, 2)); - ts.setHalfCycleSubtracted(bit_to_bool(trk_stat, 3)); - } - - mr.setNumMeas(msg->num_meas()); - auto rs = mr.initReceiverStatus(); - rs.setLeapSecValid(bit_to_bool(msg->rec_stat(), 0)); - rs.setClkReset(bit_to_bool(msg->rec_stat(), 2)); - return capnp::messageToFlatArray(msg_builder); -} - -kj::Array UbloxMsgParser::gen_nav_sat(ubx_t::nav_sat_t *msg) { - MessageBuilder msg_builder; - auto sr = msg_builder.initEvent().initUbloxGnss().initSatReport(); - sr.setITow(msg->itow()); - - auto svs = sr.initSvs(msg->num_svs()); - auto svs_data = *msg->svs(); - for (int8_t i = 0; i < msg->num_svs(); i++) { - svs[i].setSvId(svs_data[i]->sv_id()); - svs[i].setGnssId(svs_data[i]->gnss_id()); - svs[i].setFlagsBitfield(svs_data[i]->flags()); - } - - return capnp::messageToFlatArray(msg_builder); -} - -kj::Array UbloxMsgParser::gen_mon_hw(ubx_t::mon_hw_t *msg) { - MessageBuilder msg_builder; - auto hwStatus = msg_builder.initEvent().initUbloxGnss().initHwStatus(); - hwStatus.setNoisePerMS(msg->noise_per_ms()); - hwStatus.setFlags(msg->flags()); - hwStatus.setAgcCnt(msg->agc_cnt()); - hwStatus.setAStatus((cereal::UbloxGnss::HwStatus::AntennaSupervisorState) msg->a_status()); - hwStatus.setAPower((cereal::UbloxGnss::HwStatus::AntennaPowerStatus) msg->a_power()); - hwStatus.setJamInd(msg->jam_ind()); - return capnp::messageToFlatArray(msg_builder); -} - -kj::Array UbloxMsgParser::gen_mon_hw2(ubx_t::mon_hw2_t *msg) { - MessageBuilder msg_builder; - auto hwStatus = msg_builder.initEvent().initUbloxGnss().initHwStatus2(); - hwStatus.setOfsI(msg->ofs_i()); - hwStatus.setMagI(msg->mag_i()); - hwStatus.setOfsQ(msg->ofs_q()); - hwStatus.setMagQ(msg->mag_q()); - - switch (msg->cfg_source()) { - case ubx_t::mon_hw2_t::config_source_t::CONFIG_SOURCE_ROM: - hwStatus.setCfgSource(cereal::UbloxGnss::HwStatus2::ConfigSource::ROM); - break; - case ubx_t::mon_hw2_t::config_source_t::CONFIG_SOURCE_OTP: - hwStatus.setCfgSource(cereal::UbloxGnss::HwStatus2::ConfigSource::OTP); - break; - case ubx_t::mon_hw2_t::config_source_t::CONFIG_SOURCE_CONFIG_PINS: - hwStatus.setCfgSource(cereal::UbloxGnss::HwStatus2::ConfigSource::CONFIGPINS); - break; - case ubx_t::mon_hw2_t::config_source_t::CONFIG_SOURCE_FLASH: - hwStatus.setCfgSource(cereal::UbloxGnss::HwStatus2::ConfigSource::FLASH); - break; - default: - hwStatus.setCfgSource(cereal::UbloxGnss::HwStatus2::ConfigSource::UNDEFINED); - break; - } - - hwStatus.setLowLevCfg(msg->low_lev_cfg()); - hwStatus.setPostStatus(msg->post_status()); - - return capnp::messageToFlatArray(msg_builder); -} diff --git a/system/ubloxd/ublox_msg.h b/system/ubloxd/ublox_msg.h deleted file mode 100644 index d21760e..0000000 --- a/system/ubloxd/ublox_msg.h +++ /dev/null @@ -1,131 +0,0 @@ -#pragma once - -#include -#include -#include -#include -#include -#include -#include - -#include "cereal/messaging/messaging.h" -#include "common/util.h" -#include "system/ubloxd/generated/gps.h" -#include "system/ubloxd/generated/glonass.h" -#include "system/ubloxd/generated/ubx.h" - -using namespace std::string_literals; - -const int SECS_IN_MIN = 60; -const int SECS_IN_HR = 60 * SECS_IN_MIN; -const int SECS_IN_DAY = 24 * SECS_IN_HR; -const int SECS_IN_WEEK = 7 * SECS_IN_DAY; - -// protocol constants -namespace ublox { - const uint8_t PREAMBLE1 = 0xb5; - const uint8_t PREAMBLE2 = 0x62; - - const int UBLOX_HEADER_SIZE = 6; - const int UBLOX_CHECKSUM_SIZE = 2; - const int UBLOX_MAX_MSG_SIZE = 65536; - - struct ubx_mga_ini_time_utc_t { - uint8_t type; - uint8_t version; - uint8_t ref; - int8_t leapSecs; - uint16_t year; - uint8_t month; - uint8_t day; - uint8_t hour; - uint8_t minute; - uint8_t second; - uint8_t reserved1; - uint32_t ns; - uint16_t tAccS; - uint16_t reserved2; - uint32_t tAccNs; - } __attribute__((packed)); - - inline std::string ubx_add_checksum(const std::string &msg) { - assert(msg.size() > 2); - - uint8_t ck_a = 0, ck_b = 0; - for (int i = 2; i < msg.size(); i++) { - ck_a = (ck_a + msg[i]) & 0xFF; - ck_b = (ck_b + ck_a) & 0xFF; - } - - std::string r = msg; - r.push_back(ck_a); - r.push_back(ck_b); - return r; - } - - inline std::string build_ubx_mga_ini_time_utc(struct tm time) { - ublox::ubx_mga_ini_time_utc_t payload = { - .type = 0x10, - .version = 0x0, - .ref = 0x0, - .leapSecs = -128, // Unknown - .year = (uint16_t)(1900 + time.tm_year), - .month = (uint8_t)(1 + time.tm_mon), - .day = (uint8_t)time.tm_mday, - .hour = (uint8_t)time.tm_hour, - .minute = (uint8_t)time.tm_min, - .second = (uint8_t)time.tm_sec, - .reserved1 = 0x0, - .ns = 0, - .tAccS = 30, - .reserved2 = 0x0, - .tAccNs = 0, - }; - assert(sizeof(payload) == 24); - - std::string msg = "\xb5\x62\x13\x40\x18\x00"s; - msg += std::string((char*)&payload, sizeof(payload)); - - return ubx_add_checksum(msg); - } -} - -class UbloxMsgParser { - public: - bool add_data(float log_time, const uint8_t *incoming_data, uint32_t incoming_data_len, size_t &bytes_consumed); - inline void reset() {bytes_in_parse_buf = 0;} - inline int needed_bytes(); - inline std::string data() {return std::string((const char*)msg_parse_buf, bytes_in_parse_buf);} - - std::pair> gen_msg(); - kj::Array gen_nav_pvt(ubx_t::nav_pvt_t *msg); - kj::Array gen_rxm_sfrbx(ubx_t::rxm_sfrbx_t *msg); - kj::Array gen_rxm_rawx(ubx_t::rxm_rawx_t *msg); - kj::Array gen_mon_hw(ubx_t::mon_hw_t *msg); - kj::Array gen_mon_hw2(ubx_t::mon_hw2_t *msg); - kj::Array gen_nav_sat(ubx_t::nav_sat_t *msg); - - private: - inline bool valid_cheksum(); - inline bool valid(); - inline bool valid_so_far(); - - kj::Array parse_gps_ephemeris(ubx_t::rxm_sfrbx_t *msg); - kj::Array parse_glonass_ephemeris(ubx_t::rxm_sfrbx_t *msg); - - std::unordered_map> gps_subframes; - - float last_log_time = 0.0; - size_t bytes_in_parse_buf = 0; - uint8_t msg_parse_buf[ublox::UBLOX_HEADER_SIZE + ublox::UBLOX_MAX_MSG_SIZE]; - - // user range accuracy in meters - const std::unordered_map glonass_URA_lookup = - {{ 0, 1}, { 1, 2}, { 2, 2.5}, { 3, 4}, { 4, 5}, {5, 7}, - { 6, 10}, { 7, 12}, { 8, 14}, { 9, 16}, {10, 32}, - {11, 64}, {12, 128}, {13, 256}, {14, 512}, {15, 1024}}; - - std::unordered_map> glonass_strings; - std::unordered_map> glonass_string_times; - std::unordered_map> glonass_string_superframes; -}; diff --git a/system/ubloxd/ubloxd b/system/ubloxd/ubloxd new file mode 100755 index 0000000..dfbd92d Binary files /dev/null and b/system/ubloxd/ubloxd differ diff --git a/system/ubloxd/ubloxd.cc b/system/ubloxd/ubloxd.cc deleted file mode 100644 index 668c1a7..0000000 --- a/system/ubloxd/ubloxd.cc +++ /dev/null @@ -1,65 +0,0 @@ -#include - -#include - -#include "cereal/messaging/messaging.h" -#include "common/swaglog.h" -#include "common/util.h" -#include "system/ubloxd/ublox_msg.h" - -ExitHandler do_exit; -using namespace ublox; - -int main() { - LOGW("starting ubloxd"); - AlignedBuffer aligned_buf; - UbloxMsgParser parser; - - PubMaster pm({"ubloxGnss", "gpsLocationExternal"}); - - std::unique_ptr context(Context::create()); - std::unique_ptr subscriber(SubSocket::create(context.get(), "ubloxRaw")); - assert(subscriber != NULL); - subscriber->setTimeout(100); - - - while (!do_exit) { - std::unique_ptr msg(subscriber->receive()); - if (!msg) { - if (errno == EINTR) { - do_exit = true; - } - continue; - } - - capnp::FlatArrayMessageReader cmsg(aligned_buf.align(msg.get())); - cereal::Event::Reader event = cmsg.getRoot(); - auto ubloxRaw = event.getUbloxRaw(); - float log_time = 1e-9 * event.getLogMonoTime(); - - const uint8_t *data = ubloxRaw.begin(); - size_t len = ubloxRaw.size(); - size_t bytes_consumed = 0; - - while (bytes_consumed < len && !do_exit) { - size_t bytes_consumed_this_time = 0U; - if (parser.add_data(log_time, data + bytes_consumed, (uint32_t)(len - bytes_consumed), bytes_consumed_this_time)) { - - try { - auto ublox_msg = parser.gen_msg(); - if (ublox_msg.second.size() > 0) { - auto bytes = ublox_msg.second.asBytes(); - pm.send(ublox_msg.first.c_str(), bytes.begin(), bytes.size()); - } - } catch (const std::exception& e) { - LOGE("Error parsing ublox message %s", e.what()); - } - - parser.reset(); - } - bytes_consumed += bytes_consumed_this_time; - } - } - - return 0; -} diff --git a/third_party/SConscript b/third_party/SConscript deleted file mode 100644 index e5bbfaa..0000000 --- a/third_party/SConscript +++ /dev/null @@ -1,6 +0,0 @@ -Import('env') - -env.Library('json11', ['json11/json11.cpp'], CCFLAGS=env['CCFLAGS'] + ['-Wno-unqualified-std-cast-call']) -env.Append(CPPPATH=[Dir('json11')]) - -env.Library('kaitai', ['kaitai/kaitaistream.cpp'], CPPDEFINES=['KS_STR_ENCODING_NONE']) diff --git a/third_party/acados/acados_template/c_templates_tera/acados_sim_solver.in.h b/third_party/acados/acados_template/c_templates_tera/acados_sim_solver.in.h deleted file mode 100644 index 59aee62..0000000 --- a/third_party/acados/acados_template/c_templates_tera/acados_sim_solver.in.h +++ /dev/null @@ -1,101 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - -#ifndef ACADOS_SIM_{{ model.name }}_H_ -#define ACADOS_SIM_{{ model.name }}_H_ - -#include "acados_c/sim_interface.h" -#include "acados_c/external_function_interface.h" - -#define {{ model.name | upper }}_NX {{ dims.nx }} -#define {{ model.name | upper }}_NZ {{ dims.nz }} -#define {{ model.name | upper }}_NU {{ dims.nu }} -#define {{ model.name | upper }}_NP {{ dims.np }} - -#ifdef __cplusplus -extern "C" { -#endif - - -// ** capsule for solver data ** -typedef struct sim_solver_capsule -{ - // acados objects - sim_in *acados_sim_in; - sim_out *acados_sim_out; - sim_solver *acados_sim_solver; - sim_opts *acados_sim_opts; - sim_config *acados_sim_config; - void *acados_sim_dims; - - /* external functions */ - // ERK - external_function_param_{{ model.dyn_ext_fun_type }} * sim_forw_vde_casadi; - external_function_param_{{ model.dyn_ext_fun_type }} * sim_vde_adj_casadi; - external_function_param_{{ model.dyn_ext_fun_type }} * sim_expl_ode_fun_casadi; - external_function_param_{{ model.dyn_ext_fun_type }} * sim_expl_ode_hess; - - // IRK - external_function_param_{{ model.dyn_ext_fun_type }} * sim_impl_dae_fun; - external_function_param_{{ model.dyn_ext_fun_type }} * sim_impl_dae_fun_jac_x_xdot_z; - external_function_param_{{ model.dyn_ext_fun_type }} * sim_impl_dae_jac_x_xdot_u_z; - external_function_param_{{ model.dyn_ext_fun_type }} * sim_impl_dae_hess; - - // GNSF - external_function_param_{{ model.dyn_ext_fun_type }} * sim_gnsf_phi_fun; - external_function_param_{{ model.dyn_ext_fun_type }} * sim_gnsf_phi_fun_jac_y; - external_function_param_{{ model.dyn_ext_fun_type }} * sim_gnsf_phi_jac_y_uhat; - external_function_param_{{ model.dyn_ext_fun_type }} * sim_gnsf_f_lo_jac_x1_x1dot_u_z; - external_function_param_{{ model.dyn_ext_fun_type }} * sim_gnsf_get_matrices_fun; - -} sim_solver_capsule; - - -ACADOS_SYMBOL_EXPORT int {{ model.name }}_acados_sim_create(sim_solver_capsule *capsule); -ACADOS_SYMBOL_EXPORT int {{ model.name }}_acados_sim_solve(sim_solver_capsule *capsule); -ACADOS_SYMBOL_EXPORT int {{ model.name }}_acados_sim_free(sim_solver_capsule *capsule); -ACADOS_SYMBOL_EXPORT int {{ model.name }}_acados_sim_update_params(sim_solver_capsule *capsule, double *value, int np); - -ACADOS_SYMBOL_EXPORT sim_config * {{ model.name }}_acados_get_sim_config(sim_solver_capsule *capsule); -ACADOS_SYMBOL_EXPORT sim_in * {{ model.name }}_acados_get_sim_in(sim_solver_capsule *capsule); -ACADOS_SYMBOL_EXPORT sim_out * {{ model.name }}_acados_get_sim_out(sim_solver_capsule *capsule); -ACADOS_SYMBOL_EXPORT void * {{ model.name }}_acados_get_sim_dims(sim_solver_capsule *capsule); -ACADOS_SYMBOL_EXPORT sim_opts * {{ model.name }}_acados_get_sim_opts(sim_solver_capsule *capsule); -ACADOS_SYMBOL_EXPORT sim_solver * {{ model.name }}_acados_get_sim_solver(sim_solver_capsule *capsule); - - -ACADOS_SYMBOL_EXPORT sim_solver_capsule * {{ model.name }}_acados_sim_solver_create_capsule(void); -ACADOS_SYMBOL_EXPORT int {{ model.name }}_acados_sim_solver_free_capsule(sim_solver_capsule *capsule); - -#ifdef __cplusplus -} -#endif - -#endif // ACADOS_SIM_{{ model.name }}_H_ diff --git a/third_party/acados/acados_template/c_templates_tera/acados_solver.in.h b/third_party/acados/acados_template/c_templates_tera/acados_solver.in.h deleted file mode 100644 index 5cf38aa..0000000 --- a/third_party/acados/acados_template/c_templates_tera/acados_solver.in.h +++ /dev/null @@ -1,241 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - -#ifndef ACADOS_SOLVER_{{ model.name }}_H_ -#define ACADOS_SOLVER_{{ model.name }}_H_ - -#include "acados/utils/types.h" - -#include "acados_c/ocp_nlp_interface.h" -#include "acados_c/external_function_interface.h" - -#define {{ model.name | upper }}_NX {{ dims.nx }} -#define {{ model.name | upper }}_NZ {{ dims.nz }} -#define {{ model.name | upper }}_NU {{ dims.nu }} -#define {{ model.name | upper }}_NP {{ dims.np }} -#define {{ model.name | upper }}_NBX {{ dims.nbx }} -#define {{ model.name | upper }}_NBX0 {{ dims.nbx_0 }} -#define {{ model.name | upper }}_NBU {{ dims.nbu }} -#define {{ model.name | upper }}_NSBX {{ dims.nsbx }} -#define {{ model.name | upper }}_NSBU {{ dims.nsbu }} -#define {{ model.name | upper }}_NSH {{ dims.nsh }} -#define {{ model.name | upper }}_NSG {{ dims.nsg }} -#define {{ model.name | upper }}_NSPHI {{ dims.nsphi }} -#define {{ model.name | upper }}_NSHN {{ dims.nsh_e }} -#define {{ model.name | upper }}_NSGN {{ dims.nsg_e }} -#define {{ model.name | upper }}_NSPHIN {{ dims.nsphi_e }} -#define {{ model.name | upper }}_NSBXN {{ dims.nsbx_e }} -#define {{ model.name | upper }}_NS {{ dims.ns }} -#define {{ model.name | upper }}_NSN {{ dims.ns_e }} -#define {{ model.name | upper }}_NG {{ dims.ng }} -#define {{ model.name | upper }}_NBXN {{ dims.nbx_e }} -#define {{ model.name | upper }}_NGN {{ dims.ng_e }} -#define {{ model.name | upper }}_NY0 {{ dims.ny_0 }} -#define {{ model.name | upper }}_NY {{ dims.ny }} -#define {{ model.name | upper }}_NYN {{ dims.ny_e }} -#define {{ model.name | upper }}_N {{ dims.N }} -#define {{ model.name | upper }}_NH {{ dims.nh }} -#define {{ model.name | upper }}_NPHI {{ dims.nphi }} -#define {{ model.name | upper }}_NHN {{ dims.nh_e }} -#define {{ model.name | upper }}_NPHIN {{ dims.nphi_e }} -#define {{ model.name | upper }}_NR {{ dims.nr }} - -#ifdef __cplusplus -extern "C" { -#endif - -{%- if not solver_options.custom_update_filename %} - {%- set custom_update_filename = "" %} -{% else %} - {%- set custom_update_filename = solver_options.custom_update_filename %} -{%- endif %} - -// ** capsule for solver data ** -typedef struct {{ model.name }}_solver_capsule -{ - // acados objects - ocp_nlp_in *nlp_in; - ocp_nlp_out *nlp_out; - ocp_nlp_out *sens_out; - ocp_nlp_solver *nlp_solver; - void *nlp_opts; - ocp_nlp_plan_t *nlp_solver_plan; - ocp_nlp_config *nlp_config; - ocp_nlp_dims *nlp_dims; - - // number of expected runtime parameters - unsigned int nlp_np; - - /* external functions */ - // dynamics -{% if solver_options.integrator_type == "ERK" %} - external_function_param_casadi *forw_vde_casadi; - external_function_param_casadi *expl_ode_fun; -{% if solver_options.hessian_approx == "EXACT" %} - external_function_param_casadi *hess_vde_casadi; -{%- endif %} -{% elif solver_options.integrator_type == "IRK" %} - external_function_param_{{ model.dyn_ext_fun_type }} *impl_dae_fun; - external_function_param_{{ model.dyn_ext_fun_type }} *impl_dae_fun_jac_x_xdot_z; - external_function_param_{{ model.dyn_ext_fun_type }} *impl_dae_jac_x_xdot_u_z; -{% if solver_options.hessian_approx == "EXACT" %} - external_function_param_{{ model.dyn_ext_fun_type }} *impl_dae_hess; -{%- endif %} -{% elif solver_options.integrator_type == "LIFTED_IRK" %} - external_function_param_{{ model.dyn_ext_fun_type }} *impl_dae_fun; - external_function_param_{{ model.dyn_ext_fun_type }} *impl_dae_fun_jac_x_xdot_u; -{% elif solver_options.integrator_type == "GNSF" %} - external_function_param_casadi *gnsf_phi_fun; - external_function_param_casadi *gnsf_phi_fun_jac_y; - external_function_param_casadi *gnsf_phi_jac_y_uhat; - external_function_param_casadi *gnsf_f_lo_jac_x1_x1dot_u_z; - external_function_param_casadi *gnsf_get_matrices_fun; -{% elif solver_options.integrator_type == "DISCRETE" %} - external_function_param_{{ model.dyn_ext_fun_type }} *discr_dyn_phi_fun; - external_function_param_{{ model.dyn_ext_fun_type }} *discr_dyn_phi_fun_jac_ut_xt; -{%- if solver_options.hessian_approx == "EXACT" %} - external_function_param_{{ model.dyn_ext_fun_type }} *discr_dyn_phi_fun_jac_ut_xt_hess; -{%- endif %} -{%- endif %} - - - // cost -{% if cost.cost_type == "NONLINEAR_LS" %} - external_function_param_casadi *cost_y_fun; - external_function_param_casadi *cost_y_fun_jac_ut_xt; - external_function_param_casadi *cost_y_hess; -{% elif cost.cost_type == "CONVEX_OVER_NONLINEAR" %} - external_function_param_casadi *conl_cost_fun; - external_function_param_casadi *conl_cost_fun_jac_hess; -{%- elif cost.cost_type == "EXTERNAL" %} - external_function_param_{{ cost.cost_ext_fun_type }} *ext_cost_fun; - external_function_param_{{ cost.cost_ext_fun_type }} *ext_cost_fun_jac; - external_function_param_{{ cost.cost_ext_fun_type }} *ext_cost_fun_jac_hess; -{% endif %} - -{% if cost.cost_type_0 == "NONLINEAR_LS" %} - external_function_param_casadi cost_y_0_fun; - external_function_param_casadi cost_y_0_fun_jac_ut_xt; - external_function_param_casadi cost_y_0_hess; -{% elif cost.cost_type_0 == "CONVEX_OVER_NONLINEAR" %} - external_function_param_casadi conl_cost_0_fun; - external_function_param_casadi conl_cost_0_fun_jac_hess; -{% elif cost.cost_type_0 == "EXTERNAL" %} - external_function_param_{{ cost.cost_ext_fun_type_0 }} ext_cost_0_fun; - external_function_param_{{ cost.cost_ext_fun_type_0 }} ext_cost_0_fun_jac; - external_function_param_{{ cost.cost_ext_fun_type_0 }} ext_cost_0_fun_jac_hess; -{%- endif %} - -{% if cost.cost_type_e == "NONLINEAR_LS" %} - external_function_param_casadi cost_y_e_fun; - external_function_param_casadi cost_y_e_fun_jac_ut_xt; - external_function_param_casadi cost_y_e_hess; -{% elif cost.cost_type_e == "CONVEX_OVER_NONLINEAR" %} - external_function_param_casadi conl_cost_e_fun; - external_function_param_casadi conl_cost_e_fun_jac_hess; -{% elif cost.cost_type_e == "EXTERNAL" %} - external_function_param_{{ cost.cost_ext_fun_type_e }} ext_cost_e_fun; - external_function_param_{{ cost.cost_ext_fun_type_e }} ext_cost_e_fun_jac; - external_function_param_{{ cost.cost_ext_fun_type_e }} ext_cost_e_fun_jac_hess; -{%- endif %} - - // constraints -{%- if constraints.constr_type == "BGP" %} - external_function_param_casadi *phi_constraint; -{% elif constraints.constr_type == "BGH" and dims.nh > 0 %} - external_function_param_casadi *nl_constr_h_fun_jac; - external_function_param_casadi *nl_constr_h_fun; -{%- if solver_options.hessian_approx == "EXACT" %} - external_function_param_casadi *nl_constr_h_fun_jac_hess; -{%- endif %} -{%- endif %} - - -{% if constraints.constr_type_e == "BGP" %} - external_function_param_casadi phi_e_constraint; -{% elif constraints.constr_type_e == "BGH" and dims.nh_e > 0 %} - external_function_param_casadi nl_constr_h_e_fun_jac; - external_function_param_casadi nl_constr_h_e_fun; -{%- if solver_options.hessian_approx == "EXACT" %} - external_function_param_casadi nl_constr_h_e_fun_jac_hess; -{%- endif %} -{%- endif %} - -{%- if custom_update_filename != "" %} - void * custom_update_memory; -{%- endif %} - -} {{ model.name }}_solver_capsule; - -ACADOS_SYMBOL_EXPORT {{ model.name }}_solver_capsule * {{ model.name }}_acados_create_capsule(void); -ACADOS_SYMBOL_EXPORT int {{ model.name }}_acados_free_capsule({{ model.name }}_solver_capsule *capsule); - -ACADOS_SYMBOL_EXPORT int {{ model.name }}_acados_create({{ model.name }}_solver_capsule * capsule); - -ACADOS_SYMBOL_EXPORT int {{ model.name }}_acados_reset({{ model.name }}_solver_capsule* capsule, int reset_qp_solver_mem); - -/** - * Generic version of {{ model.name }}_acados_create which allows to use a different number of shooting intervals than - * the number used for code generation. If new_time_steps=NULL and n_time_steps matches the number used for code - * generation, the time-steps from code generation is used. - */ -ACADOS_SYMBOL_EXPORT int {{ model.name }}_acados_create_with_discretization({{ model.name }}_solver_capsule * capsule, int n_time_steps, double* new_time_steps); -/** - * Update the time step vector. Number N must be identical to the currently set number of shooting nodes in the - * nlp_solver_plan. Returns 0 if no error occurred and a otherwise a value other than 0. - */ -ACADOS_SYMBOL_EXPORT int {{ model.name }}_acados_update_time_steps({{ model.name }}_solver_capsule * capsule, int N, double* new_time_steps); -/** - * This function is used for updating an already initialized solver with a different number of qp_cond_N. - */ -ACADOS_SYMBOL_EXPORT int {{ model.name }}_acados_update_qp_solver_cond_N({{ model.name }}_solver_capsule * capsule, int qp_solver_cond_N); -ACADOS_SYMBOL_EXPORT int {{ model.name }}_acados_update_params({{ model.name }}_solver_capsule * capsule, int stage, double *value, int np); -ACADOS_SYMBOL_EXPORT int {{ model.name }}_acados_update_params_sparse({{ model.name }}_solver_capsule * capsule, int stage, int *idx, double *p, int n_update); - -ACADOS_SYMBOL_EXPORT int {{ model.name }}_acados_solve({{ model.name }}_solver_capsule * capsule); -ACADOS_SYMBOL_EXPORT int {{ model.name }}_acados_free({{ model.name }}_solver_capsule * capsule); -ACADOS_SYMBOL_EXPORT void {{ model.name }}_acados_print_stats({{ model.name }}_solver_capsule * capsule); -ACADOS_SYMBOL_EXPORT int {{ model.name }}_acados_custom_update({{ model.name }}_solver_capsule* capsule, double* data, int data_len); - - -ACADOS_SYMBOL_EXPORT ocp_nlp_in *{{ model.name }}_acados_get_nlp_in({{ model.name }}_solver_capsule * capsule); -ACADOS_SYMBOL_EXPORT ocp_nlp_out *{{ model.name }}_acados_get_nlp_out({{ model.name }}_solver_capsule * capsule); -ACADOS_SYMBOL_EXPORT ocp_nlp_out *{{ model.name }}_acados_get_sens_out({{ model.name }}_solver_capsule * capsule); -ACADOS_SYMBOL_EXPORT ocp_nlp_solver *{{ model.name }}_acados_get_nlp_solver({{ model.name }}_solver_capsule * capsule); -ACADOS_SYMBOL_EXPORT ocp_nlp_config *{{ model.name }}_acados_get_nlp_config({{ model.name }}_solver_capsule * capsule); -ACADOS_SYMBOL_EXPORT void *{{ model.name }}_acados_get_nlp_opts({{ model.name }}_solver_capsule * capsule); -ACADOS_SYMBOL_EXPORT ocp_nlp_dims *{{ model.name }}_acados_get_nlp_dims({{ model.name }}_solver_capsule * capsule); -ACADOS_SYMBOL_EXPORT ocp_nlp_plan_t *{{ model.name }}_acados_get_nlp_plan({{ model.name }}_solver_capsule * capsule); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_SOLVER_{{ model.name }}_H_ diff --git a/third_party/acados/acados_template/c_templates_tera/constraints.in.h b/third_party/acados/acados_template/c_templates_tera/constraints.in.h deleted file mode 100644 index d71ce5c..0000000 --- a/third_party/acados/acados_template/c_templates_tera/constraints.in.h +++ /dev/null @@ -1,110 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - -#ifndef {{ model.name }}_CONSTRAINTS -#define {{ model.name }}_CONSTRAINTS - -#ifdef __cplusplus -extern "C" { -#endif - -{% if dims.nphi > 0 %} -int {{ model.name }}_phi_constraint(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_phi_constraint_work(int *, int *, int *, int *); -const int *{{ model.name }}_phi_constraint_sparsity_in(int); -const int *{{ model.name }}_phi_constraint_sparsity_out(int); -int {{ model.name }}_phi_constraint_n_in(void); -int {{ model.name }}_phi_constraint_n_out(void); -{% endif %} - -{% if dims.nphi_e > 0 %} -int {{ model.name }}_phi_e_constraint(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_phi_e_constraint_work(int *, int *, int *, int *); -const int *{{ model.name }}_phi_e_constraint_sparsity_in(int); -const int *{{ model.name }}_phi_e_constraint_sparsity_out(int); -int {{ model.name }}_phi_e_constraint_n_in(void); -int {{ model.name }}_phi_e_constraint_n_out(void); -{% endif %} - -{% if dims.nh > 0 %} -int {{ model.name }}_constr_h_fun_jac_uxt_zt(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_constr_h_fun_jac_uxt_zt_work(int *, int *, int *, int *); -const int *{{ model.name }}_constr_h_fun_jac_uxt_zt_sparsity_in(int); -const int *{{ model.name }}_constr_h_fun_jac_uxt_zt_sparsity_out(int); -int {{ model.name }}_constr_h_fun_jac_uxt_zt_n_in(void); -int {{ model.name }}_constr_h_fun_jac_uxt_zt_n_out(void); - -int {{ model.name }}_constr_h_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_constr_h_fun_work(int *, int *, int *, int *); -const int *{{ model.name }}_constr_h_fun_sparsity_in(int); -const int *{{ model.name }}_constr_h_fun_sparsity_out(int); -int {{ model.name }}_constr_h_fun_n_in(void); -int {{ model.name }}_constr_h_fun_n_out(void); - -{% if solver_options.hessian_approx == "EXACT" -%} -int {{ model.name }}_constr_h_fun_jac_uxt_zt_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_constr_h_fun_jac_uxt_zt_hess_work(int *, int *, int *, int *); -const int *{{ model.name }}_constr_h_fun_jac_uxt_zt_hess_sparsity_in(int); -const int *{{ model.name }}_constr_h_fun_jac_uxt_zt_hess_sparsity_out(int); -int {{ model.name }}_constr_h_fun_jac_uxt_zt_hess_n_in(void); -int {{ model.name }}_constr_h_fun_jac_uxt_zt_hess_n_out(void); -{% endif %} -{% endif %} - -{% if dims.nh_e > 0 %} -int {{ model.name }}_constr_h_e_fun_jac_uxt_zt(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_constr_h_e_fun_jac_uxt_zt_work(int *, int *, int *, int *); -const int *{{ model.name }}_constr_h_e_fun_jac_uxt_zt_sparsity_in(int); -const int *{{ model.name }}_constr_h_e_fun_jac_uxt_zt_sparsity_out(int); -int {{ model.name }}_constr_h_e_fun_jac_uxt_zt_n_in(void); -int {{ model.name }}_constr_h_e_fun_jac_uxt_zt_n_out(void); - -int {{ model.name }}_constr_h_e_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_constr_h_e_fun_work(int *, int *, int *, int *); -const int *{{ model.name }}_constr_h_e_fun_sparsity_in(int); -const int *{{ model.name }}_constr_h_e_fun_sparsity_out(int); -int {{ model.name }}_constr_h_e_fun_n_in(void); -int {{ model.name }}_constr_h_e_fun_n_out(void); - -{% if solver_options.hessian_approx == "EXACT" -%} -int {{ model.name }}_constr_h_e_fun_jac_uxt_zt_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_constr_h_e_fun_jac_uxt_zt_hess_work(int *, int *, int *, int *); -const int *{{ model.name }}_constr_h_e_fun_jac_uxt_zt_hess_sparsity_in(int); -const int *{{ model.name }}_constr_h_e_fun_jac_uxt_zt_hess_sparsity_out(int); -int {{ model.name }}_constr_h_e_fun_jac_uxt_zt_hess_n_in(void); -int {{ model.name }}_constr_h_e_fun_jac_uxt_zt_hess_n_out(void); -{% endif %} -{% endif %} - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // {{ model.name }}_CONSTRAINTS diff --git a/third_party/acados/acados_template/c_templates_tera/cost.in.h b/third_party/acados/acados_template/c_templates_tera/cost.in.h deleted file mode 100644 index 45eb09c..0000000 --- a/third_party/acados/acados_template/c_templates_tera/cost.in.h +++ /dev/null @@ -1,238 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef {{ model.name }}_COST -#define {{ model.name }}_COST - -#ifdef __cplusplus -extern "C" { -#endif - - -// Cost at initial shooting node -{% if cost.cost_type_0 == "NONLINEAR_LS" %} -int {{ model.name }}_cost_y_0_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_y_0_fun_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_y_0_fun_sparsity_in(int); -const int *{{ model.name }}_cost_y_0_fun_sparsity_out(int); -int {{ model.name }}_cost_y_0_fun_n_in(void); -int {{ model.name }}_cost_y_0_fun_n_out(void); - -int {{ model.name }}_cost_y_0_fun_jac_ut_xt(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_y_0_fun_jac_ut_xt_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_y_0_fun_jac_ut_xt_sparsity_in(int); -const int *{{ model.name }}_cost_y_0_fun_jac_ut_xt_sparsity_out(int); -int {{ model.name }}_cost_y_0_fun_jac_ut_xt_n_in(void); -int {{ model.name }}_cost_y_0_fun_jac_ut_xt_n_out(void); - -int {{ model.name }}_cost_y_0_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_y_0_hess_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_y_0_hess_sparsity_in(int); -const int *{{ model.name }}_cost_y_0_hess_sparsity_out(int); -int {{ model.name }}_cost_y_0_hess_n_in(void); -int {{ model.name }}_cost_y_0_hess_n_out(void); -{% elif cost.cost_type_0 == "CONVEX_OVER_NONLINEAR" %} - -int {{ model.name }}_conl_cost_0_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_conl_cost_0_fun_work(int *, int *, int *, int *); -const int *{{ model.name }}_conl_cost_0_fun_sparsity_in(int); -const int *{{ model.name }}_conl_cost_0_fun_sparsity_out(int); -int {{ model.name }}_conl_cost_0_fun_n_in(void); -int {{ model.name }}_conl_cost_0_fun_n_out(void); - -int {{ model.name }}_conl_cost_0_fun_jac_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_conl_cost_0_fun_jac_hess_work(int *, int *, int *, int *); -const int *{{ model.name }}_conl_cost_0_fun_jac_hess_sparsity_in(int); -const int *{{ model.name }}_conl_cost_0_fun_jac_hess_sparsity_out(int); -int {{ model.name }}_conl_cost_0_fun_jac_hess_n_in(void); -int {{ model.name }}_conl_cost_0_fun_jac_hess_n_out(void); - -{% elif cost.cost_type_0 == "EXTERNAL" %} - {%- if cost.cost_ext_fun_type_0 == "casadi" %} -int {{ model.name }}_cost_ext_cost_0_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_ext_cost_0_fun_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_ext_cost_0_fun_sparsity_in(int); -const int *{{ model.name }}_cost_ext_cost_0_fun_sparsity_out(int); -int {{ model.name }}_cost_ext_cost_0_fun_n_in(void); -int {{ model.name }}_cost_ext_cost_0_fun_n_out(void); - -int {{ model.name }}_cost_ext_cost_0_fun_jac_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_ext_cost_0_fun_jac_hess_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_ext_cost_0_fun_jac_hess_sparsity_in(int); -const int *{{ model.name }}_cost_ext_cost_0_fun_jac_hess_sparsity_out(int); -int {{ model.name }}_cost_ext_cost_0_fun_jac_hess_n_in(void); -int {{ model.name }}_cost_ext_cost_0_fun_jac_hess_n_out(void); - -int {{ model.name }}_cost_ext_cost_0_fun_jac(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_ext_cost_0_fun_jac_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_ext_cost_0_fun_jac_sparsity_in(int); -const int *{{ model.name }}_cost_ext_cost_0_fun_jac_sparsity_out(int); -int {{ model.name }}_cost_ext_cost_0_fun_jac_n_in(void); -int {{ model.name }}_cost_ext_cost_0_fun_jac_n_out(void); - {%- else %} -int {{ cost.cost_function_ext_cost_0 }}(void **, void **, void *); - {%- endif %} -{% endif %} - - -// Cost at path shooting node -{% if cost.cost_type == "NONLINEAR_LS" %} -int {{ model.name }}_cost_y_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_y_fun_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_y_fun_sparsity_in(int); -const int *{{ model.name }}_cost_y_fun_sparsity_out(int); -int {{ model.name }}_cost_y_fun_n_in(void); -int {{ model.name }}_cost_y_fun_n_out(void); - -int {{ model.name }}_cost_y_fun_jac_ut_xt(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_y_fun_jac_ut_xt_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_y_fun_jac_ut_xt_sparsity_in(int); -const int *{{ model.name }}_cost_y_fun_jac_ut_xt_sparsity_out(int); -int {{ model.name }}_cost_y_fun_jac_ut_xt_n_in(void); -int {{ model.name }}_cost_y_fun_jac_ut_xt_n_out(void); - -int {{ model.name }}_cost_y_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_y_hess_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_y_hess_sparsity_in(int); -const int *{{ model.name }}_cost_y_hess_sparsity_out(int); -int {{ model.name }}_cost_y_hess_n_in(void); -int {{ model.name }}_cost_y_hess_n_out(void); - -{% elif cost.cost_type == "CONVEX_OVER_NONLINEAR" %} -int {{ model.name }}_conl_cost_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_conl_cost_fun_work(int *, int *, int *, int *); -const int *{{ model.name }}_conl_cost_fun_sparsity_in(int); -const int *{{ model.name }}_conl_cost_fun_sparsity_out(int); -int {{ model.name }}_conl_cost_fun_n_in(void); -int {{ model.name }}_conl_cost_fun_n_out(void); - -int {{ model.name }}_conl_cost_fun_jac_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_conl_cost_fun_jac_hess_work(int *, int *, int *, int *); -const int *{{ model.name }}_conl_cost_fun_jac_hess_sparsity_in(int); -const int *{{ model.name }}_conl_cost_fun_jac_hess_sparsity_out(int); -int {{ model.name }}_conl_cost_fun_jac_hess_n_in(void); -int {{ model.name }}_conl_cost_fun_jac_hess_n_out(void); -{% elif cost.cost_type == "EXTERNAL" %} - {%- if cost.cost_ext_fun_type == "casadi" %} -int {{ model.name }}_cost_ext_cost_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_ext_cost_fun_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_ext_cost_fun_sparsity_in(int); -const int *{{ model.name }}_cost_ext_cost_fun_sparsity_out(int); -int {{ model.name }}_cost_ext_cost_fun_n_in(void); -int {{ model.name }}_cost_ext_cost_fun_n_out(void); - -int {{ model.name }}_cost_ext_cost_fun_jac_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_ext_cost_fun_jac_hess_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_ext_cost_fun_jac_hess_sparsity_in(int); -const int *{{ model.name }}_cost_ext_cost_fun_jac_hess_sparsity_out(int); -int {{ model.name }}_cost_ext_cost_fun_jac_hess_n_in(void); -int {{ model.name }}_cost_ext_cost_fun_jac_hess_n_out(void); - -int {{ model.name }}_cost_ext_cost_fun_jac(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_ext_cost_fun_jac_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_ext_cost_fun_jac_sparsity_in(int); -const int *{{ model.name }}_cost_ext_cost_fun_jac_sparsity_out(int); -int {{ model.name }}_cost_ext_cost_fun_jac_n_in(void); -int {{ model.name }}_cost_ext_cost_fun_jac_n_out(void); - {%- else %} -int {{ cost.cost_function_ext_cost }}(void **, void **, void *); - {%- endif %} -{% endif %} - -// Cost at terminal shooting node -{% if cost.cost_type_e == "NONLINEAR_LS" %} -int {{ model.name }}_cost_y_e_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_y_e_fun_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_y_e_fun_sparsity_in(int); -const int *{{ model.name }}_cost_y_e_fun_sparsity_out(int); -int {{ model.name }}_cost_y_e_fun_n_in(void); -int {{ model.name }}_cost_y_e_fun_n_out(void); - -int {{ model.name }}_cost_y_e_fun_jac_ut_xt(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_y_e_fun_jac_ut_xt_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_y_e_fun_jac_ut_xt_sparsity_in(int); -const int *{{ model.name }}_cost_y_e_fun_jac_ut_xt_sparsity_out(int); -int {{ model.name }}_cost_y_e_fun_jac_ut_xt_n_in(void); -int {{ model.name }}_cost_y_e_fun_jac_ut_xt_n_out(void); - -int {{ model.name }}_cost_y_e_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_y_e_hess_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_y_e_hess_sparsity_in(int); -const int *{{ model.name }}_cost_y_e_hess_sparsity_out(int); -int {{ model.name }}_cost_y_e_hess_n_in(void); -int {{ model.name }}_cost_y_e_hess_n_out(void); -{% elif cost.cost_type_e == "CONVEX_OVER_NONLINEAR" %} -int {{ model.name }}_conl_cost_e_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_conl_cost_e_fun_work(int *, int *, int *, int *); -const int *{{ model.name }}_conl_cost_e_fun_sparsity_in(int); -const int *{{ model.name }}_conl_cost_e_fun_sparsity_out(int); -int {{ model.name }}_conl_cost_e_fun_n_in(void); -int {{ model.name }}_conl_cost_e_fun_n_out(void); - -int {{ model.name }}_conl_cost_e_fun_jac_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_conl_cost_e_fun_jac_hess_work(int *, int *, int *, int *); -const int *{{ model.name }}_conl_cost_e_fun_jac_hess_sparsity_in(int); -const int *{{ model.name }}_conl_cost_e_fun_jac_hess_sparsity_out(int); -int {{ model.name }}_conl_cost_e_fun_jac_hess_n_in(void); -int {{ model.name }}_conl_cost_e_fun_jac_hess_n_out(void); -{% elif cost.cost_type_e == "EXTERNAL" %} - {%- if cost.cost_ext_fun_type_e == "casadi" %} -int {{ model.name }}_cost_ext_cost_e_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_ext_cost_e_fun_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_ext_cost_e_fun_sparsity_in(int); -const int *{{ model.name }}_cost_ext_cost_e_fun_sparsity_out(int); -int {{ model.name }}_cost_ext_cost_e_fun_n_in(void); -int {{ model.name }}_cost_ext_cost_e_fun_n_out(void); - -int {{ model.name }}_cost_ext_cost_e_fun_jac_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_ext_cost_e_fun_jac_hess_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_ext_cost_e_fun_jac_hess_sparsity_in(int); -const int *{{ model.name }}_cost_ext_cost_e_fun_jac_hess_sparsity_out(int); -int {{ model.name }}_cost_ext_cost_e_fun_jac_hess_n_in(void); -int {{ model.name }}_cost_ext_cost_e_fun_jac_hess_n_out(void); - -int {{ model.name }}_cost_ext_cost_e_fun_jac(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_cost_ext_cost_e_fun_jac_work(int *, int *, int *, int *); -const int *{{ model.name }}_cost_ext_cost_e_fun_jac_sparsity_in(int); -const int *{{ model.name }}_cost_ext_cost_e_fun_jac_sparsity_out(int); -int {{ model.name }}_cost_ext_cost_e_fun_jac_n_in(void); -int {{ model.name }}_cost_ext_cost_e_fun_jac_n_out(void); - {%- else %} -int {{ cost.cost_function_ext_cost_e }}(void **, void **, void *); - {%- endif %} -{% endif %} - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // {{ model.name }}_COST diff --git a/third_party/acados/acados_template/c_templates_tera/model.in.h b/third_party/acados/acados_template/c_templates_tera/model.in.h deleted file mode 100644 index e5059df..0000000 --- a/third_party/acados/acados_template/c_templates_tera/model.in.h +++ /dev/null @@ -1,218 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - -#ifndef {{ model.name }}_MODEL -#define {{ model.name }}_MODEL - -#ifdef __cplusplus -extern "C" { -#endif - -{%- if solver_options.hessian_approx %} - {%- set hessian_approx = solver_options.hessian_approx %} -{%- elif solver_options.sens_hess %} - {%- set hessian_approx = "EXACT" %} -{%- else %} - {%- set hessian_approx = "GAUSS_NEWTON" %} -{%- endif %} - -{% if solver_options.integrator_type == "IRK" or solver_options.integrator_type == "LIFTED_IRK" %} - {% if model.dyn_ext_fun_type == "casadi" %} -// implicit ODE: function -int {{ model.name }}_impl_dae_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_impl_dae_fun_work(int *, int *, int *, int *); -const int *{{ model.name }}_impl_dae_fun_sparsity_in(int); -const int *{{ model.name }}_impl_dae_fun_sparsity_out(int); -int {{ model.name }}_impl_dae_fun_n_in(void); -int {{ model.name }}_impl_dae_fun_n_out(void); - -// implicit ODE: function + jacobians -int {{ model.name }}_impl_dae_fun_jac_x_xdot_z(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_impl_dae_fun_jac_x_xdot_z_work(int *, int *, int *, int *); -const int *{{ model.name }}_impl_dae_fun_jac_x_xdot_z_sparsity_in(int); -const int *{{ model.name }}_impl_dae_fun_jac_x_xdot_z_sparsity_out(int); -int {{ model.name }}_impl_dae_fun_jac_x_xdot_z_n_in(void); -int {{ model.name }}_impl_dae_fun_jac_x_xdot_z_n_out(void); - -// implicit ODE: jacobians only -int {{ model.name }}_impl_dae_jac_x_xdot_u_z(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_impl_dae_jac_x_xdot_u_z_work(int *, int *, int *, int *); -const int *{{ model.name }}_impl_dae_jac_x_xdot_u_z_sparsity_in(int); -const int *{{ model.name }}_impl_dae_jac_x_xdot_u_z_sparsity_out(int); -int {{ model.name }}_impl_dae_jac_x_xdot_u_z_n_in(void); -int {{ model.name }}_impl_dae_jac_x_xdot_u_z_n_out(void); - -// implicit ODE - for lifted_irk -int {{ model.name }}_impl_dae_fun_jac_x_xdot_u(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_impl_dae_fun_jac_x_xdot_u_work(int *, int *, int *, int *); -const int *{{ model.name }}_impl_dae_fun_jac_x_xdot_u_sparsity_in(int); -const int *{{ model.name }}_impl_dae_fun_jac_x_xdot_u_sparsity_out(int); -int {{ model.name }}_impl_dae_fun_jac_x_xdot_u_n_in(void); -int {{ model.name }}_impl_dae_fun_jac_x_xdot_u_n_out(void); - - {%- if hessian_approx == "EXACT" %} -// implicit ODE - hessian -int {{ model.name }}_impl_dae_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_impl_dae_hess_work(int *, int *, int *, int *); -const int *{{ model.name }}_impl_dae_hess_sparsity_in(int); -const int *{{ model.name }}_impl_dae_hess_sparsity_out(int); -int {{ model.name }}_impl_dae_hess_n_in(void); -int {{ model.name }}_impl_dae_hess_n_out(void); - {% endif %} - {% else %}{# ext_fun_type #} - {%- if hessian_approx == "EXACT" %} -int {{ model.dyn_impl_dae_hess }}(void **, void **, void *); - {% endif %} -int {{ model.dyn_impl_dae_fun_jac }}(void **, void **, void *); -int {{ model.dyn_impl_dae_jac }}(void **, void **, void *); -int {{ model.dyn_impl_dae_fun }}(void **, void **, void *); - {% endif %}{# ext_fun_type #} - -{% elif solver_options.integrator_type == "GNSF" %} -/* GNSF Functions */ - {% if model.gnsf.purely_linear != 1 %} -// phi_fun -int {{ model.name }}_gnsf_phi_fun(const double** arg, double** res, int* iw, double* w, void *mem); -int {{ model.name }}_gnsf_phi_fun_work(int *, int *, int *, int *); -const int *{{ model.name }}_gnsf_phi_fun_sparsity_in(int); -const int *{{ model.name }}_gnsf_phi_fun_sparsity_out(int); -int {{ model.name }}_gnsf_phi_fun_n_in(void); -int {{ model.name }}_gnsf_phi_fun_n_out(void); - -// phi_fun_jac_y -int {{ model.name }}_gnsf_phi_fun_jac_y(const double** arg, double** res, int* iw, double* w, void *mem); -int {{ model.name }}_gnsf_phi_fun_jac_y_work(int *, int *, int *, int *); -const int *{{ model.name }}_gnsf_phi_fun_jac_y_sparsity_in(int); -const int *{{ model.name }}_gnsf_phi_fun_jac_y_sparsity_out(int); -int {{ model.name }}_gnsf_phi_fun_jac_y_n_in(void); -int {{ model.name }}_gnsf_phi_fun_jac_y_n_out(void); - -// phi_jac_y_uhat -int {{ model.name }}_gnsf_phi_jac_y_uhat(const double** arg, double** res, int* iw, double* w, void *mem); -int {{ model.name }}_gnsf_phi_jac_y_uhat_work(int *, int *, int *, int *); -const int *{{ model.name }}_gnsf_phi_jac_y_uhat_sparsity_in(int); -const int *{{ model.name }}_gnsf_phi_jac_y_uhat_sparsity_out(int); -int {{ model.name }}_gnsf_phi_jac_y_uhat_n_in(void); -int {{ model.name }}_gnsf_phi_jac_y_uhat_n_out(void); - {% if model.gnsf.nontrivial_f_LO == 1 %} -// f_lo_fun_jac_x1k1uz -int {{ model.name }}_gnsf_f_lo_fun_jac_x1k1uz(const double** arg, double** res, int* iw, double* w, void *mem); -int {{ model.name }}_gnsf_f_lo_fun_jac_x1k1uz_work(int *, int *, int *, int *); -const int *{{ model.name }}_gnsf_f_lo_fun_jac_x1k1uz_sparsity_in(int); -const int *{{ model.name }}_gnsf_f_lo_fun_jac_x1k1uz_sparsity_out(int); -int {{ model.name }}_gnsf_f_lo_fun_jac_x1k1uz_n_in(void); -int {{ model.name }}_gnsf_f_lo_fun_jac_x1k1uz_n_out(void); - {%- endif %} - {%- endif %} -// used to import model matrices -int {{ model.name }}_gnsf_get_matrices_fun(const double** arg, double** res, int* iw, double* w, void *mem); -int {{ model.name }}_gnsf_get_matrices_fun_work(int *, int *, int *, int *); -const int *{{ model.name }}_gnsf_get_matrices_fun_sparsity_in(int); -const int *{{ model.name }}_gnsf_get_matrices_fun_sparsity_out(int); -int {{ model.name }}_gnsf_get_matrices_fun_n_in(void); -int {{ model.name }}_gnsf_get_matrices_fun_n_out(void); - -{% elif solver_options.integrator_type == "ERK" %} -/* explicit ODE */ - -// explicit ODE -int {{ model.name }}_expl_ode_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_expl_ode_fun_work(int *, int *, int *, int *); -const int *{{ model.name }}_expl_ode_fun_sparsity_in(int); -const int *{{ model.name }}_expl_ode_fun_sparsity_out(int); -int {{ model.name }}_expl_ode_fun_n_in(void); -int {{ model.name }}_expl_ode_fun_n_out(void); - -// explicit forward VDE -int {{ model.name }}_expl_vde_forw(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_expl_vde_forw_work(int *, int *, int *, int *); -const int *{{ model.name }}_expl_vde_forw_sparsity_in(int); -const int *{{ model.name }}_expl_vde_forw_sparsity_out(int); -int {{ model.name }}_expl_vde_forw_n_in(void); -int {{ model.name }}_expl_vde_forw_n_out(void); - -// explicit adjoint VDE -int {{ model.name }}_expl_vde_adj(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_expl_vde_adj_work(int *, int *, int *, int *); -const int *{{ model.name }}_expl_vde_adj_sparsity_in(int); -const int *{{ model.name }}_expl_vde_adj_sparsity_out(int); -int {{ model.name }}_expl_vde_adj_n_in(void); -int {{ model.name }}_expl_vde_adj_n_out(void); - -{%- if hessian_approx == "EXACT" %} -int {{ model.name }}_expl_ode_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_expl_ode_hess_work(int *, int *, int *, int *); -const int *{{ model.name }}_expl_ode_hess_sparsity_in(int); -const int *{{ model.name }}_expl_ode_hess_sparsity_out(int); -int {{ model.name }}_expl_ode_hess_n_in(void); -int {{ model.name }}_expl_ode_hess_n_out(void); -{%- endif %} - -{% elif solver_options.integrator_type == "DISCRETE" %} - -{% if model.dyn_ext_fun_type == "casadi" %} -int {{ model.name }}_dyn_disc_phi_fun(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_dyn_disc_phi_fun_work(int *, int *, int *, int *); -const int *{{ model.name }}_dyn_disc_phi_fun_sparsity_in(int); -const int *{{ model.name }}_dyn_disc_phi_fun_sparsity_out(int); -int {{ model.name }}_dyn_disc_phi_fun_n_in(void); -int {{ model.name }}_dyn_disc_phi_fun_n_out(void); - -int {{ model.name }}_dyn_disc_phi_fun_jac(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_dyn_disc_phi_fun_jac_work(int *, int *, int *, int *); -const int *{{ model.name }}_dyn_disc_phi_fun_jac_sparsity_in(int); -const int *{{ model.name }}_dyn_disc_phi_fun_jac_sparsity_out(int); -int {{ model.name }}_dyn_disc_phi_fun_jac_n_in(void); -int {{ model.name }}_dyn_disc_phi_fun_jac_n_out(void); - -{%- if hessian_approx == "EXACT" %} -int {{ model.name }}_dyn_disc_phi_fun_jac_hess(const real_t** arg, real_t** res, int* iw, real_t* w, void *mem); -int {{ model.name }}_dyn_disc_phi_fun_jac_hess_work(int *, int *, int *, int *); -const int *{{ model.name }}_dyn_disc_phi_fun_jac_hess_sparsity_in(int); -const int *{{ model.name }}_dyn_disc_phi_fun_jac_hess_sparsity_out(int); -int {{ model.name }}_dyn_disc_phi_fun_jac_hess_n_in(void); -int {{ model.name }}_dyn_disc_phi_fun_jac_hess_n_out(void); -{%- endif %} -{% else %} - {%- if hessian_approx == "EXACT" %} -int {{ model.dyn_disc_fun_jac_hess }}(void **, void **, void *); - {% endif %} -int {{ model.dyn_disc_fun_jac }}(void **, void **, void *); -int {{ model.dyn_disc_fun }}(void **, void **, void *); -{% endif %} - - -{% endif %} - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // {{ model.name }}_MODEL diff --git a/third_party/acados/acados_template/custom_update_templates/custom_update_function_zoro_template.in.h b/third_party/acados/acados_template/custom_update_templates/custom_update_function_zoro_template.in.h deleted file mode 100644 index 9611ea2..0000000 --- a/third_party/acados/acados_template/custom_update_templates/custom_update_function_zoro_template.in.h +++ /dev/null @@ -1,44 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - -#include "acados_solver_{{ model.name }}.h" - -// Called at the end of solver creation. -// This is allowed to allocate memory and store the pointer to it into capsule->custom_update_memory. -int custom_update_init_function({{ model.name }}_solver_capsule* capsule); - - -// Custom update function that can be called between solver calls -int custom_update_function({{ model.name }}_solver_capsule* capsule, double* data, int data_len); - - -// Called just before destroying the solver. -// Responsible to free allocated memory, stored at capsule->custom_update_memory. -int custom_update_terminate_function({{ model.name }}_solver_capsule* capsule); diff --git a/third_party/acados/include/acados/dense_qp/dense_qp_common.h b/third_party/acados/include/acados/dense_qp/dense_qp_common.h deleted file mode 100644 index 2a9a974..0000000 --- a/third_party/acados/include/acados/dense_qp/dense_qp_common.h +++ /dev/null @@ -1,147 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_DENSE_QP_DENSE_QP_COMMON_H_ -#define ACADOS_DENSE_QP_DENSE_QP_COMMON_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// hpipm -#include "hpipm/include/hpipm_d_dense_qp.h" -#include "hpipm/include/hpipm_d_dense_qp_res.h" -#include "hpipm/include/hpipm_d_dense_qp_sol.h" -// acados -#include "acados/utils/types.h" - -typedef struct d_dense_qp_dim dense_qp_dims; -typedef struct d_dense_qp dense_qp_in; -typedef struct d_dense_qp_sol dense_qp_out; -typedef struct d_dense_qp_res dense_qp_res; -typedef struct d_dense_qp_res_ws dense_qp_res_ws; - - - -#ifndef QP_SOLVER_CONFIG_ -#define QP_SOLVER_CONFIG_ -typedef struct -{ - void (*dims_set)(void *config_, void *dims_, const char *field, const int* value); - acados_size_t (*opts_calculate_size)(void *config, void *dims); - void *(*opts_assign)(void *config, void *dims, void *raw_memory); - void (*opts_initialize_default)(void *config, void *dims, void *args); - void (*opts_update)(void *config, void *dims, void *args); - void (*opts_set)(void *config_, void *opts_, const char *field, void* value); - acados_size_t (*memory_calculate_size)(void *config, void *dims, void *args); - void *(*memory_assign)(void *config, void *dims, void *args, void *raw_memory); - void (*memory_get)(void *config_, void *mem_, const char *field, void* value); - acados_size_t (*workspace_calculate_size)(void *config, void *dims, void *args); - int (*evaluate)(void *config, void *qp_in, void *qp_out, void *args, void *mem, void *work); - void (*eval_sens)(void *config, void *qp_in, void *qp_out, void *opts, void *mem, void *work); -} qp_solver_config; -#endif - - - -#ifndef QP_INFO_ -#define QP_INFO_ -typedef struct -{ - double solve_QP_time; - double condensing_time; - double interface_time; - double total_time; - int num_iter; - int t_computed; -} qp_info; -#endif - - - -/* config */ -// -acados_size_t dense_qp_solver_config_calculate_size(); -// -qp_solver_config *dense_qp_solver_config_assign(void *raw_memory); - -/* dims */ -// -acados_size_t dense_qp_dims_calculate_size(); -// -dense_qp_dims *dense_qp_dims_assign(void *raw_memory); -// -void dense_qp_dims_set(void *config_, void *dims_, const char *field, const int* value); -// - -/* in */ -// -acados_size_t dense_qp_in_calculate_size(dense_qp_dims *dims); -// -dense_qp_in *dense_qp_in_assign(dense_qp_dims *dims, void *raw_memory); - -/* out */ -// -acados_size_t dense_qp_out_calculate_size(dense_qp_dims *dims); -// -dense_qp_out *dense_qp_out_assign(dense_qp_dims *dims, void *raw_memory); -// -void dense_qp_out_get(dense_qp_out *out, const char *field, void *value); - -/* res */ -// -acados_size_t dense_qp_res_calculate_size(dense_qp_dims *dims); -// -dense_qp_res *dense_qp_res_assign(dense_qp_dims *dims, void *raw_memory); -// -acados_size_t dense_qp_res_workspace_calculate_size(dense_qp_dims *dims); -// -dense_qp_res_ws *dense_qp_res_workspace_assign(dense_qp_dims *dims, void *raw_memory); -// -void dense_qp_compute_t(dense_qp_in *qp_in, dense_qp_out *qp_out); -// -void dense_qp_res_compute(dense_qp_in *qp_in, dense_qp_out *qp_out, dense_qp_res *qp_res, dense_qp_res_ws *res_ws); -// -void dense_qp_res_compute_nrm_inf(dense_qp_res *qp_res, double res[4]); - -/* misc */ -// -void dense_qp_stack_slacks_dims(dense_qp_dims *in, dense_qp_dims *out); -// -void dense_qp_stack_slacks(dense_qp_in *in, dense_qp_in *out); -// -void dense_qp_unstack_slacks(dense_qp_out *in, dense_qp_in *qp_out, dense_qp_out *out); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_DENSE_QP_DENSE_QP_COMMON_H_ diff --git a/third_party/acados/include/acados/dense_qp/dense_qp_daqp.h b/third_party/acados/include/acados/dense_qp/dense_qp_daqp.h deleted file mode 100644 index b262089..0000000 --- a/third_party/acados/include/acados/dense_qp/dense_qp_daqp.h +++ /dev/null @@ -1,110 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_DENSE_QP_DENSE_QP_DAQP_H_ -#define ACADOS_DENSE_QP_DENSE_QP_DAQP_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// blasfeo -#include "blasfeo/include/blasfeo_common.h" - -// daqp -#include "daqp/include/types.h" - -// acados -#include "acados/dense_qp/dense_qp_common.h" -#include "acados/utils/types.h" - - -typedef struct dense_qp_daqp_opts_ -{ - DAQPSettings* daqp_opts; - int warm_start; -} dense_qp_daqp_opts; - - -typedef struct dense_qp_daqp_memory_ -{ - double* lb_tmp; - double* ub_tmp; - int* idxb; - int* idxv_to_idxb; - int* idxs; - int* idxdaqp_to_idxs; - - double* Zl; - double* Zu; - double* zl; - double* zu; - double* d_ls; - double* d_us; - - double time_qp_solver_call; - int iter; - DAQPWorkspace * daqp_work; - -} dense_qp_daqp_memory; - -// opts -acados_size_t dense_qp_daqp_opts_calculate_size(void *config, dense_qp_dims *dims); -// -void *dense_qp_daqp_opts_assign(void *config, dense_qp_dims *dims, void *raw_memory); -// -void dense_qp_daqp_opts_initialize_default(void *config, dense_qp_dims *dims, void *opts_); -// -void dense_qp_daqp_opts_update(void *config, dense_qp_dims *dims, void *opts_); -// -// memory -acados_size_t dense_qp_daqp_workspace_calculate_size(void *config, dense_qp_dims *dims, void *opts_); -// -void *dense_qp_daqp_workspace_assign(void *config, dense_qp_dims *dims, void *raw_memory); -// -acados_size_t dense_qp_daqp_memory_calculate_size(void *config, dense_qp_dims *dims, void *opts_); -// -void *dense_qp_daqp_memory_assign(void *config, dense_qp_dims *dims, void *opts_, void *raw_memory); -// -// functions -int dense_qp_daqp(void *config, dense_qp_in *qp_in, dense_qp_out *qp_out, void *opts_, void *memory_, void *work_); -// -void dense_qp_daqp_eval_sens(void *config_, void *qp_in, void *qp_out, void *opts_, void *mem_, void *work_); -// -void dense_qp_daqp_memory_reset(void *config_, void *qp_in, void *qp_out, void *opts_, void *mem_, void *work_); -// -void dense_qp_daqp_config_initialize_default(void *config_); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_DENSE_QP_DENSE_QP_DAQP_H_ diff --git a/third_party/acados/include/acados/dense_qp/dense_qp_hpipm.h b/third_party/acados/include/acados/dense_qp/dense_qp_hpipm.h deleted file mode 100644 index 136279d..0000000 --- a/third_party/acados/include/acados/dense_qp/dense_qp_hpipm.h +++ /dev/null @@ -1,91 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_DENSE_QP_DENSE_QP_HPIPM_H_ -#define ACADOS_DENSE_QP_DENSE_QP_HPIPM_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// hpipm -#include "hpipm/include/hpipm_d_dense_qp.h" -#include "hpipm/include/hpipm_d_dense_qp_ipm.h" -#include "hpipm/include/hpipm_d_dense_qp_sol.h" -// acados -#include "acados/dense_qp/dense_qp_common.h" -#include "acados/utils/types.h" - - - -typedef struct dense_qp_hpipm_opts_ -{ - struct d_dense_qp_ipm_arg *hpipm_opts; -} dense_qp_hpipm_opts; - - - -typedef struct dense_qp_hpipm_memory_ -{ - struct d_dense_qp_ipm_ws *hpipm_workspace; - double time_qp_solver_call; - int iter; - -} dense_qp_hpipm_memory; - - - -// -acados_size_t dense_qp_hpipm_opts_calculate_size(void *config, void *dims); -// -void *dense_qp_hpipm_opts_assign(void *config, void *dims, void *raw_memory); -// -void dense_qp_hpipm_opts_initialize_default(void *config, void *dims, void *opts_); -// -void dense_qp_hpipm_opts_update(void *config, void *dims, void *opts_); -// -acados_size_t dense_qp_hpipm_calculate_memory_size(void *dims, void *opts_); -// -void *dense_qp_hpipm_assign_memory(void *dims, void *opts_, void *raw_memory); -// -acados_size_t dense_qp_hpipm_calculate_workspace_size(void *dims, void *opts_); -// -int dense_qp_hpipm(void *config, void *qp_in, void *qp_out, void *opts_, void *mem_, void *work_); -// -void dense_qp_hpipm_eval_sens(void *config_, void *qp_in, void *qp_out, void *opts_, void *mem_, void *work_); -// -void dense_qp_hpipm_config_initialize_default(void *config_); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_DENSE_QP_DENSE_QP_HPIPM_H_ diff --git a/third_party/acados/include/acados/dense_qp/dense_qp_ooqp.h b/third_party/acados/include/acados/dense_qp/dense_qp_ooqp.h deleted file mode 100644 index d051cb1..0000000 --- a/third_party/acados/include/acados/dense_qp/dense_qp_ooqp.h +++ /dev/null @@ -1,125 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_DENSE_QP_DENSE_QP_OOQP_H_ -#define ACADOS_DENSE_QP_DENSE_QP_OOQP_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include "acados/dense_qp/dense_qp_common.h" -#include "acados/utils/types.h" - -enum dense_qp_ooqp_termination_code -{ - DENSE_SUCCESSFUL_TERMINATION = 0, - DENSE_NOT_FINISHED, - DENSE_MAX_ITS_EXCEEDED, - DENSE_INFEASIBLE, - DENSE_UNKNOWN -}; - -typedef struct dense_qp_ooqp_opts_ -{ - int printLevel; - int useDiagonalWeights; // TODO(dimitris): implement option - int fixHessian; - int fixDynamics; - int fixInequalities; -} dense_qp_ooqp_opts; - -typedef struct dense_qp_ooqp_workspace_ -{ - double *x; - double *gamma; - double *phi; - double *y; - double *z; - double *lambda; - double *pi; - double objectiveValue; -} dense_qp_ooqp_workspace; - -typedef struct dense_qp_ooqp_memory_ -{ - int firstRun; - int nx; - int my; - int mz; - double *c; - double *dQ; - double *xlow; - char *ixlow; - double *xupp; - char *ixupp; - double *dA; - double *bA; - double *dC; - double *clow; - char *iclow; - double *cupp; - char *icupp; - double time_qp_solver_call; - int iter; - -} dense_qp_ooqp_memory; - -// -acados_size_t dense_qp_ooqp_opts_calculate_size(void *config_, dense_qp_dims *dims); -// -void *dense_qp_ooqp_opts_assign(void *config_, dense_qp_dims *dims, void *raw_memory); -// -void dense_qp_ooqp_opts_initialize_default(void *config_, dense_qp_dims *dims, void *opts_); -// -void dense_qp_ooqp_opts_update(void *config_, dense_qp_dims *dims, void *opts_); -// -acados_size_t dense_qp_ooqp_memory_calculate_size(void *config_, dense_qp_dims *dims, void *opts_); -// -void *dense_qp_ooqp_memory_assign(void *config_, dense_qp_dims *dims, void *opts_, - void *raw_memory); -// -acados_size_t dense_qp_ooqp_workspace_calculate_size(void *config_, dense_qp_dims *dims, void *opts_); -// -int dense_qp_ooqp(void *config_, dense_qp_in *qp_in, dense_qp_out *qp_out, void *opts_, - void *memory_, void *work_); -// -void dense_qp_ooqp_destroy(void *mem_, void *work); -// -void dense_qp_ooqp_eval_sens(void *config_, void *qp_in, void *qp_out, void *opts_, void *mem_, void *work_); -// -void dense_qp_ooqp_config_initialize_default(void *config_); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_DENSE_QP_DENSE_QP_OOQP_H_ diff --git a/third_party/acados/include/acados/dense_qp/dense_qp_qore.h b/third_party/acados/include/acados/dense_qp/dense_qp_qore.h deleted file mode 100644 index 392e472..0000000 --- a/third_party/acados/include/acados/dense_qp/dense_qp_qore.h +++ /dev/null @@ -1,124 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_DENSE_QP_DENSE_QP_QORE_H_ -#define ACADOS_DENSE_QP_DENSE_QP_QORE_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// qore -#include "qore/QPSOLVER_DENSE/include/qpsolver_dense.h" -// acados -#include "acados/dense_qp/dense_qp_common.h" -#include "acados/utils/types.h" - -typedef struct dense_qp_qore_opts_ -{ - int nsmax; // maximum size of Schur complement - int print_freq; // print frequency, - // prtfreq < 0: disable printing; - // prtfreq == 0: print on each call and include working set changes; - // prtfreq > 0: print on every prtfreq seconds, but do not include working set - // changes; - int warm_start; // warm start with updated matrices H and C - int warm_strategy; // 0: ramp-up from zero homotopy; 1: setup homotopy from the previous - // solution - int hot_start; // hot start with unchanged matrices H and C - int max_iter; // maximum number of iterations - int compute_t; // compute t in qp_out (to have correct residuals in NLP) -} dense_qp_qore_opts; - -typedef struct dense_qp_qore_memory_ -{ - double *H; - double *HH; - double *g; - double *gg; - double *Zl; - double *Zu; - double *zl; - double *zu; - double *A; - double *b; - double *C; - double *CC; - double *Ct; - double *CCt; - double *d_lb0; - double *d_ub0; - double *d_lb; - double *d_ub; - double *d_lg; - double *d_ug; - double *d_ls; - double *d_us; - double *lb; - double *ub; - int *idxb; - int *idxb_stacked; - int *idxs; - double *prim_sol; - double *dual_sol; - QoreProblemDense *QP; - int num_iter; - dense_qp_in *qp_stacked; - double time_qp_solver_call; - int iter; - -} dense_qp_qore_memory; - -acados_size_t dense_qp_qore_opts_calculate_size(void *config, dense_qp_dims *dims); -// -void *dense_qp_qore_opts_assign(void *config, dense_qp_dims *dims, void *raw_memory); -// -void dense_qp_qore_opts_initialize_default(void *config, dense_qp_dims *dims, void *opts_); -// -void dense_qp_qore_opts_update(void *config, dense_qp_dims *dims, void *opts_); -// -acados_size_t dense_qp_qore_memory_calculate_size(void *config, dense_qp_dims *dims, void *opts_); -// -void *dense_qp_qore_memory_assign(void *config, dense_qp_dims *dims, void *opts_, void *raw_memory); -// -acados_size_t dense_qp_qore_workspace_calculate_size(void *config, dense_qp_dims *dims, void *opts_); -// -int dense_qp_qore(void *config, dense_qp_in *qp_in, dense_qp_out *qp_out, void *opts_, void *memory_, void *work_); -// -void dense_qp_qore_eval_sens(void *config_, void *qp_in, void *qp_out, void *opts_, void *mem_, void *work_); -// -void dense_qp_qore_config_initialize_default(void *config); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_DENSE_QP_DENSE_QP_QORE_H_ diff --git a/third_party/acados/include/acados/dense_qp/dense_qp_qpoases.h b/third_party/acados/include/acados/dense_qp/dense_qp_qpoases.h deleted file mode 100644 index 0e13d3e..0000000 --- a/third_party/acados/include/acados/dense_qp/dense_qp_qpoases.h +++ /dev/null @@ -1,126 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_DENSE_QP_DENSE_QP_QPOASES_H_ -#define ACADOS_DENSE_QP_DENSE_QP_QPOASES_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// blasfeo -#include "blasfeo/include/blasfeo_common.h" - -// acados -#include "acados/dense_qp/dense_qp_common.h" -#include "acados/utils/types.h" - -typedef struct dense_qp_qpoases_opts_ -{ - double max_cputime; // maximum cpu time in seconds - int max_nwsr; // maximum number of working set recalculations - int warm_start; // warm start with dual_sol in memory - int use_precomputed_cholesky; - int hotstart; // this option requires constant data matrices! (eg linear MPC, inexact schemes - // with frozen sensitivities) - int set_acado_opts; // use same options as in acado code generation - int compute_t; // compute t in qp_out (to have correct residuals in NLP) - double tolerance; // terminationTolerance -} dense_qp_qpoases_opts; - -typedef struct dense_qp_qpoases_memory_ -{ - double *H; - double *HH; - double *R; - double *g; - double *gg; - double *Zl; - double *Zu; - double *zl; - double *zu; - double *A; - double *b; - double *d_lb0; - double *d_ub0; - double *d_lb; - double *d_ub; - double *C; - double *CC; - double *d_lg0; - double *d_ug0; - double *d_lg; - double *d_ug; - double *d_ls; - double *d_us; - int *idxb; - int *idxb_stacked; - int *idxs; - double *prim_sol; - double *dual_sol; - void *QPB; // NOTE(giaf): cast to QProblemB to use - void *QP; // NOTE(giaf): cast to QProblem to use - double cputime; // cputime of qpoases - int nwsr; // performed number of working set recalculations - int first_it; // to be used with hotstart - dense_qp_in *qp_stacked; - double time_qp_solver_call; // equal to cputime - int iter; - -} dense_qp_qpoases_memory; - -acados_size_t dense_qp_qpoases_opts_calculate_size(void *config, dense_qp_dims *dims); -// -void *dense_qp_qpoases_opts_assign(void *config, dense_qp_dims *dims, void *raw_memory); -// -void dense_qp_qpoases_opts_initialize_default(void *config, dense_qp_dims *dims, void *opts_); -// -void dense_qp_qpoases_opts_update(void *config, dense_qp_dims *dims, void *opts_); -// -acados_size_t dense_qp_qpoases__memorycalculate_size(void *config, dense_qp_dims *dims, void *opts_); -// -void *dense_qp_qpoases_memory_assign(void *config, dense_qp_dims *dims, void *opts_, void *raw_memory); -// -acados_size_t dense_qp_qpoases_workspace_calculate_size(void *config, dense_qp_dims *dims, void *opts_); -// -int dense_qp_qpoases(void *config, dense_qp_in *qp_in, dense_qp_out *qp_out, void *opts_, void *memory_, void *work_); -// -void dense_qp_qpoases_eval_sens(void *config_, void *qp_in, void *qp_out, void *opts_, void *mem_, void *work_); -// -void dense_qp_qpoases_memory_reset(void *config_, void *qp_in, void *qp_out, void *opts_, void *mem_, void *work_); -// -void dense_qp_qpoases_config_initialize_default(void *config_); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_DENSE_QP_DENSE_QP_QPOASES_H_ diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_common.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_common.h deleted file mode 100644 index ba97db9..0000000 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_common.h +++ /dev/null @@ -1,446 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - - -/// \defgroup ocp_nlp ocp_nlp -/// @{ -/// @} - -/// \defgroup ocp_nlp_solver ocp_nlp_solver -/// @{ -/// @} - -/// \ingroup ocp_nlp -/// @{ - -/// \ingroup ocp_nlp_solver -/// @{ - -/// \defgroup ocp_nlp_common ocp_nlp_common -/// @{ - -#ifndef ACADOS_OCP_NLP_OCP_NLP_COMMON_H_ -#define ACADOS_OCP_NLP_OCP_NLP_COMMON_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include "acados/ocp_nlp/ocp_nlp_constraints_common.h" -#include "acados/ocp_nlp/ocp_nlp_cost_common.h" -#include "acados/ocp_nlp/ocp_nlp_dynamics_common.h" -#include "acados/ocp_nlp/ocp_nlp_reg_common.h" -#include "acados/ocp_qp/ocp_qp_common.h" -#include "acados/ocp_qp/ocp_qp_xcond_solver.h" -#include "acados/sim/sim_common.h" -#include "acados/utils/external_function_generic.h" -#include "acados/utils/types.h" - - - -/************************************************ - * config - ************************************************/ - -typedef struct ocp_nlp_config -{ - int N; // number of stages - - // solver-specific implementations of memory management functions - acados_size_t (*opts_calculate_size)(void *config, void *dims); - void *(*opts_assign)(void *config, void *dims, void *raw_memory); - void (*opts_initialize_default)(void *config, void *dims, void *opts_); - void (*opts_update)(void *config, void *dims, void *opts_); - acados_size_t (*memory_calculate_size)(void *config, void *dims, void *opts_); - void *(*memory_assign)(void *config, void *dims, void *opts_, void *raw_memory); - acados_size_t (*workspace_calculate_size)(void *config, void *dims, void *opts_); - void (*opts_set)(void *config_, void *opts_, const char *field, void* value); - void (*opts_set_at_stage)(void *config_, void *opts_, size_t stage, const char *field, void* value); - // evaluate solver // TODO rename into solve - int (*evaluate)(void *config, void *dims, void *nlp_in, void *nlp_out, void *opts_, void *mem, void *work); - void (*eval_param_sens)(void *config, void *dims, void *opts_, void *mem, void *work, - char *field, int stage, int index, void *sens_nlp_out); - // prepare memory - int (*precompute)(void *config, void *dims, void *nlp_in, void *nlp_out, void *opts_, void *mem, void *work); - void (*memory_reset_qp_solver)(void *config, void *dims, void *nlp_in, void *nlp_out, void *opts_, void *mem, void *work); - // initalize this struct with default values - void (*config_initialize_default)(void *config); - // general getter - void (*get)(void *config_, void *dims, void *mem_, const char *field, void *return_value_); - void (*opts_get)(void *config_, void *dims, void *opts_, const char *field, void *return_value_); - void (*work_get)(void *config_, void *dims, void *work_, const char *field, void *return_value_); - // config structs of submodules - ocp_qp_xcond_solver_config *qp_solver; // TODO rename xcond_solver - ocp_nlp_dynamics_config **dynamics; - ocp_nlp_cost_config **cost; - ocp_nlp_constraints_config **constraints; - ocp_nlp_reg_config *regularize; - -} ocp_nlp_config; - -// -acados_size_t ocp_nlp_config_calculate_size(int N); -// -ocp_nlp_config *ocp_nlp_config_assign(int N, void *raw_memory); - - - -/************************************************ - * dims - ************************************************/ - -/// Structure to store dimensions/number of variables. -typedef struct ocp_nlp_dims -{ - void **cost; - void **dynamics; - void **constraints; - ocp_qp_xcond_solver_dims *qp_solver; // xcond solver instead ?? - ocp_nlp_reg_dims *regularize; - - int *nv; // number of primal variables (states+controls+slacks) - int *nx; // number of differential states - int *nu; // number of inputs - int *ni; // number of two-sided inequality constraints: nb+ng+nh+ns - int *nz; // number of algebraic variables - int *ns; // number of slack variables - int N; // number of shooting nodes - - void *raw_memory; // Pointer to allocated memory, to be used for freeing -} ocp_nlp_dims; - -// -acados_size_t ocp_nlp_dims_calculate_size(void *config); -// -ocp_nlp_dims *ocp_nlp_dims_assign(void *config, void *raw_memory); - -/// Sets the dimension of optimization variables -/// (states, constrols, algebraic variables, slack variables). -/// -/// \param config_ The configuration struct. -/// \param dims_ The dimension struct. -/// \param field The type of optimization variables, either nx, nu, nz, or ns. -/// \param value_array Number of variables for each stage. -void ocp_nlp_dims_set_opt_vars(void *config_, void *dims_, - const char *field, const void* value_array); - -/// Sets the dimensions of constraints functions for a stage -/// (bounds on states, bounds on controls, equality constraints, -/// inequality constraints). -/// -/// \param config_ The configuration struct. -/// \param dims_ The dimension struct. -/// \param stage Stage number. -/// \param field The type of constraint/bound, either nbx, nbu, ng, or nh. -/// \param value_field Number of constraints/bounds for the given stage. -void ocp_nlp_dims_set_constraints(void *config_, void *dims_, int stage, - const char *field, const void* value_field); - -/// Sets the dimensions of the cost terms for a stage. -/// -/// \param config_ The configuration struct. -/// \param dims_ The dimension struct. -/// \param stage Stage number. -/// \param field Type of cost term, can be eiter ny. -/// \param value_field Number of cost terms/residuals for the given stage. -void ocp_nlp_dims_set_cost(void *config_, void *dims_, int stage, const char *field, - const void* value_field); - -/// Sets the dimensions of the dynamics for a stage. -/// -/// \param config_ The configuration struct. -/// \param dims_ The dimension struct. -/// \param stage Stage number. -/// \param field TBD -/// \param value TBD -void ocp_nlp_dims_set_dynamics(void *config_, void *dims_, int stage, const char *field, - const void* value); - -/************************************************ - * Inputs - ************************************************/ - -/// Struct for storing the inputs of an OCP NLP solver -typedef struct ocp_nlp_in -{ - /// Length of sampling intervals/timesteps. - double *Ts; - - /// Pointers to cost functions (TBC). - void **cost; - - /// Pointers to dynamics functions (TBC). - void **dynamics; - - /// Pointers to constraints functions (TBC). - void **constraints; - - /// Pointer to allocated memory, to be used for freeing. - void *raw_memory; - -} ocp_nlp_in; - -// -acados_size_t ocp_nlp_in_calculate_size_self(int N); -// -acados_size_t ocp_nlp_in_calculate_size(ocp_nlp_config *config, ocp_nlp_dims *dims); -// -ocp_nlp_in *ocp_nlp_in_assign_self(int N, void *raw_memory); -// -ocp_nlp_in *ocp_nlp_in_assign(ocp_nlp_config *config, ocp_nlp_dims *dims, void *raw_memory); - - -/************************************************ - * out - ************************************************/ - -typedef struct ocp_nlp_out -{ - struct blasfeo_dvec *ux; // NOTE: this contains [u; x; s_l; s_u]! - rename to uxs? - struct blasfeo_dvec *z; // algebraic vairables - struct blasfeo_dvec *pi; // multipliers for dynamics - struct blasfeo_dvec *lam; // inequality mulitpliers - struct blasfeo_dvec *t; // slack variables corresponding to evaluation of all inequalities (at the solution) - - // NOTE: the inequalities are internally organized in the following order: - // [ lbu lbx lg lh lphi ubu ubx ug uh uphi; lsbu lsbx lsg lsh lsphi usbu usbx usg ush usphi] - double inf_norm_res; - - void *raw_memory; // Pointer to allocated memory, to be used for freeing - -} ocp_nlp_out; - -// -acados_size_t ocp_nlp_out_calculate_size(ocp_nlp_config *config, ocp_nlp_dims *dims); -// -ocp_nlp_out *ocp_nlp_out_assign(ocp_nlp_config *config, ocp_nlp_dims *dims, - void *raw_memory); - - - -/************************************************ - * options - ************************************************/ - -/// Globalization types -typedef enum -{ - FIXED_STEP, - MERIT_BACKTRACKING, -} ocp_nlp_globalization_t; - -typedef struct ocp_nlp_opts -{ - ocp_qp_xcond_solver_opts *qp_solver_opts; // xcond solver opts instead ??? - void *regularize; - void **dynamics; // dynamics_opts - void **cost; // cost_opts - void **constraints; // constraints_opts - double step_length; // step length in case of FIXED_STEP - double levenberg_marquardt; // LM factor to be added to the hessian before regularization - int reuse_workspace; - int num_threads; - int print_level; - - // TODO: move to separate struct? - ocp_nlp_globalization_t globalization; - int full_step_dual; - int line_search_use_sufficient_descent; - int globalization_use_SOC; - double alpha_min; - double alpha_reduction; - double eps_sufficient_descent; -} ocp_nlp_opts; - -// -acados_size_t ocp_nlp_opts_calculate_size(void *config, void *dims); -// -void *ocp_nlp_opts_assign(void *config, void *dims, void *raw_memory); -// -void ocp_nlp_opts_initialize_default(void *config, void *dims, void *opts); -// -void ocp_nlp_opts_update(void *config, void *dims, void *opts); -// -void ocp_nlp_opts_set(void *config_, void *opts_, const char *field, void* value); -// -void ocp_nlp_opts_set_at_stage(void *config, void *opts, int stage, const char *field, void *value); - - -/************************************************ - * residuals - ************************************************/ - -typedef struct ocp_nlp_res -{ - struct blasfeo_dvec *res_stat; // stationarity - struct blasfeo_dvec *res_eq; // dynamics - struct blasfeo_dvec *res_ineq; // inequality constraints - struct blasfeo_dvec *res_comp; // complementarity - struct blasfeo_dvec tmp; // tmp - double inf_norm_res_stat; - double inf_norm_res_eq; - double inf_norm_res_ineq; - double inf_norm_res_comp; - acados_size_t memsize; -} ocp_nlp_res; - -// -acados_size_t ocp_nlp_res_calculate_size(ocp_nlp_dims *dims); -// -ocp_nlp_res *ocp_nlp_res_assign(ocp_nlp_dims *dims, void *raw_memory); -// -void ocp_nlp_res_get_inf_norm(ocp_nlp_res *res, double *out); - -/************************************************ - * memory - ************************************************/ - -typedef struct ocp_nlp_memory -{ -// void *qp_solver_mem; // xcond solver mem instead ??? - ocp_qp_xcond_solver_memory *qp_solver_mem; // xcond solver mem instead ??? - void *regularize_mem; - void **dynamics; // dynamics memory - void **cost; // cost memory - void **constraints; // constraints memory - - // residuals - ocp_nlp_res *nlp_res; - - // qp in & out - ocp_qp_in *qp_in; - ocp_qp_out *qp_out; - // QP stuff not entering the qp_in struct - struct blasfeo_dmat *dzduxt; // dzdux transposed - struct blasfeo_dvec *z_alg; // z_alg, output algebraic variables - - struct blasfeo_dvec *cost_grad; - struct blasfeo_dvec *ineq_fun; - struct blasfeo_dvec *ineq_adj; - struct blasfeo_dvec *dyn_fun; - struct blasfeo_dvec *dyn_adj; - - double cost_value; - - bool *set_sim_guess; // indicate if there is new explicitly provided guess for integration variables - struct blasfeo_dvec *sim_guess; - - int *sqp_iter; // pointer to iteration number - -} ocp_nlp_memory; - -// -acados_size_t ocp_nlp_memory_calculate_size(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_opts *opts); -// -ocp_nlp_memory *ocp_nlp_memory_assign(ocp_nlp_config *config, ocp_nlp_dims *dims, - ocp_nlp_opts *opts, void *raw_memory); - - - -/************************************************ - * workspace - ************************************************/ - -typedef struct ocp_nlp_workspace -{ - - void *qp_work; - void **dynamics; // dynamics_workspace - void **cost; // cost_workspace - void **constraints; // constraints_workspace - - // for globalization: -> move to module?! - ocp_nlp_out *tmp_nlp_out; - ocp_nlp_out *weight_merit_fun; - struct blasfeo_dvec tmp_nxu; - struct blasfeo_dvec tmp_ni; - struct blasfeo_dvec dxnext_dy; - -} ocp_nlp_workspace; - -// -acados_size_t ocp_nlp_workspace_calculate_size(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_opts *opts); -// -ocp_nlp_workspace *ocp_nlp_workspace_assign(ocp_nlp_config *config, ocp_nlp_dims *dims, - ocp_nlp_opts *opts, ocp_nlp_memory *mem, void *raw_memory); - - - -/************************************************ - * function - ************************************************/ - -void ocp_nlp_alias_memory_to_submodules(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in, - ocp_nlp_out *out, ocp_nlp_opts *opts, ocp_nlp_memory *mem, ocp_nlp_workspace *work); -// -void ocp_nlp_initialize_submodules(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in, - ocp_nlp_out *out, ocp_nlp_opts *opts, ocp_nlp_memory *mem, ocp_nlp_workspace *work); -// -void ocp_nlp_approximate_qp_matrices(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in, - ocp_nlp_out *out, ocp_nlp_opts *opts, ocp_nlp_memory *mem, ocp_nlp_workspace *work); -// -void ocp_nlp_approximate_qp_vectors_sqp(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in, - ocp_nlp_out *out, ocp_nlp_opts *opts, ocp_nlp_memory *mem, ocp_nlp_workspace *work); -// -void ocp_nlp_embed_initial_value(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in, - ocp_nlp_out *out, ocp_nlp_opts *opts, ocp_nlp_memory *mem, ocp_nlp_workspace *work); -// -void ocp_nlp_update_variables_sqp(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in, - ocp_nlp_out *out, ocp_nlp_opts *opts, ocp_nlp_memory *mem, ocp_nlp_workspace *work, double alpha); -// -int ocp_nlp_precompute_common(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in, - ocp_nlp_out *out, ocp_nlp_opts *opts, ocp_nlp_memory *mem, ocp_nlp_workspace *work); -// -double ocp_nlp_line_search(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in, - ocp_nlp_out *out, ocp_nlp_opts *opts, ocp_nlp_memory *mem, ocp_nlp_workspace *work, - int check_early_termination); -// -double ocp_nlp_evaluate_merit_fun(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in, - ocp_nlp_out *out, ocp_nlp_opts *opts, ocp_nlp_memory *mem, ocp_nlp_workspace *work); -// -void ocp_nlp_initialize_t_slacks(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in, - ocp_nlp_out *out, ocp_nlp_opts *opts, ocp_nlp_memory *mem, ocp_nlp_workspace *work); -// -void ocp_nlp_res_compute(ocp_nlp_dims *dims, ocp_nlp_in *in, ocp_nlp_out *out, - ocp_nlp_res *res, ocp_nlp_memory *mem); -// -void ocp_nlp_cost_compute(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in, - ocp_nlp_out *out, ocp_nlp_opts *opts, ocp_nlp_memory *mem, ocp_nlp_workspace *work); - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_NLP_OCP_NLP_COMMON_H_ -/// @} -/// @} -/// @} diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_constraints_bgh.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_constraints_bgh.h deleted file mode 100644 index 9dbf16f..0000000 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_constraints_bgh.h +++ /dev/null @@ -1,238 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -/// \addtogroup ocp_nlp -/// @{ -/// \addtogroup ocp_nlp_constraints -/// @{ - -#ifndef ACADOS_OCP_NLP_OCP_NLP_CONSTRAINTS_BGH_H_ -#define ACADOS_OCP_NLP_OCP_NLP_CONSTRAINTS_BGH_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// acados -#include "acados/ocp_qp/ocp_qp_common.h" -#include "acados/ocp_nlp/ocp_nlp_constraints_common.h" -#include "acados/utils/external_function_generic.h" -#include "acados/utils/types.h" - - - -/************************************************ - * dims - ************************************************/ - -typedef struct -{ - int nx; - int nu; - int nz; - int nb; // nbx + nbu - int nbu; // number of input box constraints - int nbx; // number of state box constraints - int ng; // number of general linear constraints - int nh; // number of nonlinear path constraints - int ns; // nsbu + nsbx + nsg + nsh - int nsbu; // number of softened input bounds - int nsbx; // number of softened state bounds - int nsg; // number of softened general linear constraints - int nsh; // number of softened nonlinear constraints - int nbue; // number of input box constraints which are equality - int nbxe; // number of state box constraints which are equality - int nge; // number of general linear constraints which are equality - int nhe; // number of nonlinear path constraints which are equality -} ocp_nlp_constraints_bgh_dims; - -// -acados_size_t ocp_nlp_constraints_bgh_dims_calculate_size(void *config); -// -void *ocp_nlp_constraints_bgh_dims_assign(void *config, void *raw_memory); -// -void ocp_nlp_constraints_bgh_dims_get(void *config_, void *dims_, const char *field, int* value); -// -void ocp_nlp_constraints_bgh_dims_set(void *config_, void *dims_, - const char *field, const int* value); - - -/************************************************ - * model - ************************************************/ - -typedef struct -{ - int *idxb; - int *idxs; - int *idxe; - struct blasfeo_dvec d; // gathers bounds - struct blasfeo_dmat DCt; // general linear constraint matrix - // lg <= [D, C] * [u; x] <= ug - external_function_generic *nl_constr_h_fun; // nonlinear: lh <= h(x,u) <= uh - external_function_generic *nl_constr_h_fun_jac; // nonlinear: lh <= h(x,u) <= uh - external_function_generic *nl_constr_h_fun_jac_hess; // nonlinear: lh <= h(x,u) <= uh -} ocp_nlp_constraints_bgh_model; - -// -acados_size_t ocp_nlp_constraints_bgh_model_calculate_size(void *config, void *dims); -// -void *ocp_nlp_constraints_bgh_model_assign(void *config, void *dims, void *raw_memory); -// -int ocp_nlp_constraints_bgh_model_set(void *config_, void *dims_, - void *model_, const char *field, void *value); - -// -void ocp_nlp_constraints_bgh_model_get(void *config_, void *dims_, - void *model_, const char *field, void *value); - - -/************************************************ - * options - ************************************************/ - -typedef struct -{ - int compute_adj; - int compute_hess; -} ocp_nlp_constraints_bgh_opts; - -// -acados_size_t ocp_nlp_constraints_bgh_opts_calculate_size(void *config, void *dims); -// -void *ocp_nlp_constraints_bgh_opts_assign(void *config, void *dims, void *raw_memory); -// -void ocp_nlp_constraints_bgh_opts_initialize_default(void *config, void *dims, void *opts); -// -void ocp_nlp_constraints_bgh_opts_update(void *config, void *dims, void *opts); -// -void ocp_nlp_constraints_bgh_opts_set(void *config, void *opts, char *field, void *value); - - - -/************************************************ - * memory - ************************************************/ - -typedef struct -{ - struct blasfeo_dvec fun; - struct blasfeo_dvec adj; - struct blasfeo_dvec *ux; // pointer to ux in nlp_out - struct blasfeo_dvec *tmp_ux; // pointer to ux in tmp_nlp_out - struct blasfeo_dvec *lam; // pointer to lam in nlp_out - struct blasfeo_dvec *tmp_lam;// pointer to lam in tmp_nlp_out - struct blasfeo_dvec *z_alg; // pointer to z_alg in ocp_nlp memory - struct blasfeo_dmat *DCt; // pointer to DCt in qp_in - struct blasfeo_dmat *RSQrq; // pointer to RSQrq in qp_in - struct blasfeo_dmat *dzduxt; // pointer to dzduxt in ocp_nlp memory - int *idxb; // pointer to idxb[ii] in qp_in - int *idxs_rev; // pointer to idxs_rev[ii] in qp_in - int *idxe; // pointer to idxe[ii] in qp_in -} ocp_nlp_constraints_bgh_memory; - -// -acados_size_t ocp_nlp_constraints_bgh_memory_calculate_size(void *config, void *dims, void *opts); -// -void *ocp_nlp_constraints_bgh_memory_assign(void *config, void *dims, void *opts, void *raw_memory); -// -struct blasfeo_dvec *ocp_nlp_constraints_bgh_memory_get_fun_ptr(void *memory_); -// -struct blasfeo_dvec *ocp_nlp_constraints_bgh_memory_get_adj_ptr(void *memory_); -// -void ocp_nlp_constraints_bgh_memory_set_ux_ptr(struct blasfeo_dvec *ux, void *memory_); -// -void ocp_nlp_constraints_bgh_memory_set_tmp_ux_ptr(struct blasfeo_dvec *tmp_ux, void *memory_); -// -void ocp_nlp_constraints_bgh_memory_set_lam_ptr(struct blasfeo_dvec *lam, void *memory_); -// -void ocp_nlp_constraints_bgh_memory_set_tmp_lam_ptr(struct blasfeo_dvec *tmp_lam, void *memory_); -// -void ocp_nlp_constraints_bgh_memory_set_DCt_ptr(struct blasfeo_dmat *DCt, void *memory); -// -void ocp_nlp_constraints_bgh_memory_set_RSQrq_ptr(struct blasfeo_dmat *RSQrq, void *memory_); -// -void ocp_nlp_constraints_bgh_memory_set_z_alg_ptr(struct blasfeo_dvec *z_alg, void *memory_); -// -void ocp_nlp_constraints_bgh_memory_set_dzduxt_ptr(struct blasfeo_dmat *dzduxt, void *memory_); -// -void ocp_nlp_constraints_bgh_memory_set_idxb_ptr(int *idxb, void *memory_); -// -void ocp_nlp_constraints_bgh_memory_set_idxs_rev_ptr(int *idxs_rev, void *memory_); -// -void ocp_nlp_constraints_bgh_memory_set_idxe_ptr(int *idxe, void *memory_); - - - -/************************************************ - * workspace - ************************************************/ - -typedef struct -{ - struct blasfeo_dmat tmp_nv_nv; - struct blasfeo_dmat tmp_nz_nh; - struct blasfeo_dmat tmp_nv_nh; - struct blasfeo_dmat tmp_nz_nv; - struct blasfeo_dmat hess_z; - struct blasfeo_dvec tmp_ni; - struct blasfeo_dvec tmp_nh; -} ocp_nlp_constraints_bgh_workspace; - -// -acados_size_t ocp_nlp_constraints_bgh_workspace_calculate_size(void *config, void *dims, void *opts); - -/* functions */ - -// -void ocp_nlp_constraints_bgh_config_initialize_default(void *config); -// -void ocp_nlp_constraints_bgh_initialize(void *config, void *dims, void *model, void *opts, - void *mem, void *work); -// -void ocp_nlp_constraints_bgh_update_qp_matrices(void *config_, void *dims, void *model_, - void *opts_, void *memory_, void *work_); - -// -void ocp_nlp_constraints_bgh_compute_fun(void *config_, void *dims, void *model_, - void *opts_, void *memory_, void *work_); -// -void ocp_nlp_constraints_bgh_bounds_update(void *config_, void *dims, void *model_, - void *opts_, void *memory_, void *work_); - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_NLP_OCP_NLP_CONSTRAINTS_BGH_H_ -/// @} -/// @} diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_constraints_bgp.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_constraints_bgp.h deleted file mode 100644 index eb05edf..0000000 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_constraints_bgp.h +++ /dev/null @@ -1,218 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -/// \addtogroup ocp_nlp -/// @{ -/// \addtogroup ocp_nlp_constraints -/// @{ - -#ifndef ACADOS_OCP_NLP_OCP_NLP_CONSTRAINTS_BGP_H_ -#define ACADOS_OCP_NLP_OCP_NLP_CONSTRAINTS_BGP_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// acados -#include "acados/ocp_qp/ocp_qp_common.h" -#include "acados/ocp_nlp/ocp_nlp_constraints_common.h" -#include "acados/utils/external_function_generic.h" -#include "acados/utils/types.h" - - - -/* dims */ - -typedef struct -{ - int nx; - int nu; - int nz; - int nb; // nbx + nbu - int nbu; - int nbx; - int ng; // number of general linear constraints - int nphi; // dimension of convex outer part - int ns; // nsbu + nsbx + nsg + nsphi - int nsbu; // number of softened input bounds - int nsbx; // number of softened state bounds - int nsg; // number of softened general linear constraints - int nsphi; // number of softened nonlinear constraints - int nr; // dimension of nonlinear function in convex_over_nonlinear constraint - int nbue; // number of input box constraints which are equality - int nbxe; // number of state box constraints which are equality - int nge; // number of general linear constraints which are equality - int nphie; // number of nonlinear path constraints which are equality -} ocp_nlp_constraints_bgp_dims; - -// -acados_size_t ocp_nlp_constraints_bgp_dims_calculate_size(void *config); -// -void *ocp_nlp_constraints_bgp_dims_assign(void *config, void *raw_memory); -// -void ocp_nlp_constraints_bgp_dims_get(void *config_, void *dims_, const char *field, int* value); - - -/* model */ - -typedef struct -{ - // ocp_nlp_constraints_bgp_dims *dims; - int *idxb; - int *idxs; - int *idxe; - struct blasfeo_dvec d; - struct blasfeo_dmat DCt; - external_function_generic *nl_constr_phi_o_r_fun_phi_jac_ux_z_phi_hess_r_jac_ux; - external_function_generic *nl_constr_phi_o_r_fun; - external_function_generic *nl_constr_r_fun_jac; -} ocp_nlp_constraints_bgp_model; - -// -acados_size_t ocp_nlp_constraints_bgp_calculate_size(void *config, void *dims); -// -void *ocp_nlp_constraints_bgp_assign(void *config, void *dims, void *raw_memory); -// -int ocp_nlp_constraints_bgp_model_set(void *config_, void *dims_, - void *model_, const char *field, void *value); -// -void ocp_nlp_constraints_bgp_model_get(void *config_, void *dims_, - void *model_, const char *field, void *value); - -/* options */ - -typedef struct -{ - int compute_adj; - int compute_hess; -} ocp_nlp_constraints_bgp_opts; - -// -acados_size_t ocp_nlp_constraints_bgp_opts_calculate_size(void *config, void *dims); -// -void *ocp_nlp_constraints_bgp_opts_assign(void *config, void *dims, void *raw_memory); -// -void ocp_nlp_constraints_bgp_opts_initialize_default(void *config, void *dims, void *opts); -// -void ocp_nlp_constraints_bgp_opts_update(void *config, void *dims, void *opts); -// -void ocp_nlp_constraints_bgp_opts_set(void *config, void *opts, char *field, void *value); - -/* memory */ - -typedef struct -{ - struct blasfeo_dvec fun; - struct blasfeo_dvec adj; - struct blasfeo_dvec *ux; // pointer to ux in nlp_out - struct blasfeo_dvec *tmp_ux; // pointer to ux in tmp_nlp_out - struct blasfeo_dvec *lam; // pointer to lam in nlp_out - struct blasfeo_dvec *tmp_lam;// pointer to lam in tmp_nlp_out - struct blasfeo_dvec *z_alg; // pointer to z_alg in ocp_nlp memory - struct blasfeo_dmat *DCt; // pointer to DCt in qp_in - struct blasfeo_dmat *RSQrq; // pointer to RSQrq in qp_in - struct blasfeo_dmat *dzduxt; // pointer to dzduxt in ocp_nlp memory - int *idxb; // pointer to idxb[ii] in qp_in - int *idxs_rev; // pointer to idxs_rev[ii] in qp_in - int *idxe; // pointer to idxe[ii] in qp_in -} ocp_nlp_constraints_bgp_memory; - -// -acados_size_t ocp_nlp_constraints_bgp_memory_calculate_size(void *config, void *dims, void *opts); -// -void *ocp_nlp_constraints_bgp_memory_assign(void *config, void *dims, void *opts, - void *raw_memory); -// -struct blasfeo_dvec *ocp_nlp_constraints_bgp_memory_get_fun_ptr(void *memory_); -// -struct blasfeo_dvec *ocp_nlp_constraints_bgp_memory_get_adj_ptr(void *memory_); -// -void ocp_nlp_constraints_bgp_memory_set_ux_ptr(struct blasfeo_dvec *ux, void *memory_); -// -void ocp_nlp_constraints_bgp_memory_set_tmp_ux_ptr(struct blasfeo_dvec *tmp_ux, void *memory_); -// -void ocp_nlp_constraints_bgp_memory_set_lam_ptr(struct blasfeo_dvec *lam, void *memory_); -// -void ocp_nlp_constraints_bgp_memory_set_tmp_lam_ptr(struct blasfeo_dvec *tmp_lam, void *memory_); -// -void ocp_nlp_constraints_bgp_memory_set_DCt_ptr(struct blasfeo_dmat *DCt, void *memory); -// -void ocp_nlp_constraints_bgp_memory_set_z_alg_ptr(struct blasfeo_dvec *z_alg, void *memory_); -// -void ocp_nlp_constraints_bgp_memory_set_dzduxt_ptr(struct blasfeo_dmat *dzduxt, void *memory_); -// -void ocp_nlp_constraints_bgp_memory_set_idxb_ptr(int *idxb, void *memory_); -// -void ocp_nlp_constraints_bgp_memory_set_idxs_rev_ptr(int *idxs_rev, void *memory_); -// -void ocp_nlp_constraints_bgh_memory_set_idxe_ptr(int *idxe, void *memory_); - -/* workspace */ - -typedef struct -{ - struct blasfeo_dvec tmp_ni; - struct blasfeo_dmat jac_r_ux_tran; - struct blasfeo_dmat tmp_nr_nphi_nr; - struct blasfeo_dmat tmp_nv_nr; - struct blasfeo_dmat tmp_nv_nphi; - struct blasfeo_dmat tmp_nz_nphi; -} ocp_nlp_constraints_bgp_workspace; - -// -acados_size_t ocp_nlp_constraints_bgp_workspace_calculate_size(void *config, void *dims, void *opts); - -/* functions */ - -// -void ocp_nlp_constraints_bgp_config_initialize_default(void *config); -// -void ocp_nlp_constraints_bgp_initialize(void *config, void *dims, void *model, - void *opts, void *mem, void *work); -// -void ocp_nlp_constraints_bgp_update_qp_matrices(void *config_, void *dims, - void *model_, void *opts_, void *memory_, void *work_); -// -void ocp_nlp_constraints_bgp_compute_fun(void *config_, void *dims, - void *model_, void *opts_, void *memory_, void *work_); -// -void ocp_nlp_constraints_bgp_bounds_update(void *config_, void *dims, void *model_, - void *opts_, void *memory_, void *work_); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_NLP_OCP_NLP_CONSTRAINTS_BGP_H_ -/// @} -/// @} diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_constraints_common.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_constraints_common.h deleted file mode 100644 index bb73c46..0000000 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_constraints_common.h +++ /dev/null @@ -1,108 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -/// \ingroup ocp_nlp -/// @{ - -/// \defgroup ocp_nlp_constraints ocp_nlp_constraints -/// @{ - -#ifndef ACADOS_OCP_NLP_OCP_NLP_CONSTRAINTS_COMMON_H_ -#define ACADOS_OCP_NLP_OCP_NLP_CONSTRAINTS_COMMON_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// acados -#include "acados/ocp_qp/ocp_qp_common.h" -#include "acados/utils/external_function_generic.h" -#include "acados/utils/types.h" - - - -/************************************************ - * config - ************************************************/ - -typedef struct -{ - acados_size_t (*dims_calculate_size)(void *config); - void *(*dims_assign)(void *config, void *raw_memory); - acados_size_t (*model_calculate_size)(void *config, void *dims); - void *(*model_assign)(void *config, void *dims, void *raw_memory); - int (*model_set)(void *config_, void *dims_, void *model_, const char *field, void *value); - void (*model_get)(void *config_, void *dims_, void *model_, const char *field, void *value); - acados_size_t (*opts_calculate_size)(void *config, void *dims); - void *(*opts_assign)(void *config, void *dims, void *raw_memory); - void (*opts_initialize_default)(void *config, void *dims, void *opts); - void (*opts_update)(void *config, void *dims, void *opts); - void (*opts_set)(void *config, void *opts, char *field, void *value); - acados_size_t (*memory_calculate_size)(void *config, void *dims, void *opts); - struct blasfeo_dvec *(*memory_get_fun_ptr)(void *memory); - struct blasfeo_dvec *(*memory_get_adj_ptr)(void *memory); - void (*memory_set_ux_ptr)(struct blasfeo_dvec *ux, void *memory); - void (*memory_set_tmp_ux_ptr)(struct blasfeo_dvec *tmp_ux, void *memory); - void (*memory_set_lam_ptr)(struct blasfeo_dvec *lam, void *memory); - void (*memory_set_tmp_lam_ptr)(struct blasfeo_dvec *tmp_lam, void *memory); - void (*memory_set_DCt_ptr)(struct blasfeo_dmat *DCt, void *memory); - void (*memory_set_RSQrq_ptr)(struct blasfeo_dmat *RSQrq, void *memory); - void (*memory_set_z_alg_ptr)(struct blasfeo_dvec *z_alg, void *memory); - void (*memory_set_dzdux_tran_ptr)(struct blasfeo_dmat *dzduxt, void *memory); - void (*memory_set_idxb_ptr)(int *idxb, void *memory); - void (*memory_set_idxs_rev_ptr)(int *idxs_rev, void *memory); - void (*memory_set_idxe_ptr)(int *idxe, void *memory); - void *(*memory_assign)(void *config, void *dims, void *opts, void *raw_memory); - acados_size_t (*workspace_calculate_size)(void *config, void *dims, void *opts); - void (*initialize)(void *config, void *dims, void *model, void *opts, void *mem, void *work); - void (*update_qp_matrices)(void *config, void *dims, void *model, void *opts, void *mem, void *work); - void (*compute_fun)(void *config, void *dims, void *model, void *opts, void *mem, void *work); - void (*bounds_update)(void *config, void *dims, void *model, void *opts, void *mem, void *work); - void (*config_initialize_default)(void *config); - // dimension setters - void (*dims_set)(void *config_, void *dims_, const char *field, const int *value); - void (*dims_get)(void *config_, void *dims_, const char *field, int* value); -} ocp_nlp_constraints_config; - -// -acados_size_t ocp_nlp_constraints_config_calculate_size(); -// -ocp_nlp_constraints_config *ocp_nlp_constraints_config_assign(void *raw_memory); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_NLP_OCP_NLP_CONSTRAINTS_COMMON_H_ -/// @} -/// @} diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_common.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_common.h deleted file mode 100644 index eb40564..0000000 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_common.h +++ /dev/null @@ -1,107 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -/// -/// \defgroup ocp_nlp_cost ocp_nlp_cost -/// - -/// \addtogroup ocp_nlp_cost ocp_nlp_cost -/// @{ -/// \addtogroup ocp_nlp_cost_common ocp_nlp_cost_common -/// @{ - -#ifndef ACADOS_OCP_NLP_OCP_NLP_COST_COMMON_H_ -#define ACADOS_OCP_NLP_OCP_NLP_COST_COMMON_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// acados -#include "acados/utils/external_function_generic.h" -#include "acados/utils/types.h" - - - -/************************************************ - * config - ************************************************/ - -typedef struct -{ - acados_size_t (*dims_calculate_size)(void *config); - void *(*dims_assign)(void *config, void *raw_memory); - void (*dims_set)(void *config_, void *dims_, const char *field, int *value); - void (*dims_get)(void *config_, void *dims_, const char *field, int *value); - acados_size_t (*model_calculate_size)(void *config, void *dims); - void *(*model_assign)(void *config, void *dims, void *raw_memory); - int (*model_set)(void *config_, void *dims_, void *model_, const char *field, void *value_); - acados_size_t (*opts_calculate_size)(void *config, void *dims); - void *(*opts_assign)(void *config, void *dims, void *raw_memory); - void (*opts_initialize_default)(void *config, void *dims, void *opts); - void (*opts_update)(void *config, void *dims, void *opts); - void (*opts_set)(void *config, void *opts, const char *field, void *value); - acados_size_t (*memory_calculate_size)(void *config, void *dims, void *opts); - double *(*memory_get_fun_ptr)(void *memory); - struct blasfeo_dvec *(*memory_get_grad_ptr)(void *memory); - void (*memory_set_ux_ptr)(struct blasfeo_dvec *ux, void *memory); - void (*memory_set_tmp_ux_ptr)(struct blasfeo_dvec *tmp_ux, void *memory); - void (*memory_set_z_alg_ptr)(struct blasfeo_dvec *z_alg, void *memory); - void (*memory_set_dzdux_tran_ptr)(struct blasfeo_dmat *dzdux, void *memory); - void (*memory_set_RSQrq_ptr)(struct blasfeo_dmat *RSQrq, void *memory); - void (*memory_set_Z_ptr)(struct blasfeo_dvec *Z, void *memory); - void *(*memory_assign)(void *config, void *dims, void *opts, void *raw_memory); - acados_size_t (*workspace_calculate_size)(void *config, void *dims, void *opts); - void (*initialize)(void *config_, void *dims, void *model_, void *opts_, void *mem_, void *work_); - - // computes the function value, gradient and hessian (approximation) of the cost function - void (*update_qp_matrices)(void *config_, void *dims, void *model_, void *opts_, void *mem_, void *work_); - // computes the cost function value (intended for globalization) - void (*compute_fun)(void *config_, void *dims, void *model_, void *opts_, void *mem_, void *work_); - void (*config_initialize_default)(void *config); - void (*precompute)(void *config_, void *dims_, void *model_, void *opts_, void *memory_, void *work_); - -} ocp_nlp_cost_config; - -// -acados_size_t ocp_nlp_cost_config_calculate_size(); -// -ocp_nlp_cost_config *ocp_nlp_cost_config_assign(void *raw_memory); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_NLP_OCP_NLP_COST_COMMON_H_ -/// @} -/// @} diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_conl.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_conl.h deleted file mode 100644 index 2eb3f5d..0000000 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_conl.h +++ /dev/null @@ -1,207 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -/// \addtogroup ocp_nlp -/// @{ -/// \addtogroup ocp_nlp_cost ocp_nlp_cost -/// @{ -/// \addtogroup ocp_nlp_cost_conl ocp_nlp_cost_conl -/// \brief This module implements convex-over-nonlinear costs of the form -/// \f$\min_{x,u,z} \psi(y(x,u,z,p) - y_{\text{ref}}, p)\f$, - - -#ifndef ACADOS_OCP_NLP_OCP_NLP_COST_CONL_H_ -#define ACADOS_OCP_NLP_OCP_NLP_COST_CONL_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// blasfeo -#include "blasfeo/include/blasfeo_common.h" - -// acados -#include "acados/ocp_nlp/ocp_nlp_cost_common.h" -#include "acados/utils/external_function_generic.h" -#include "acados/utils/types.h" - - - -/************************************************ - * dims - ************************************************/ - -typedef struct -{ - int nx; // number of states - int nz; // number of algebraic variables - int nu; // number of inputs - int ny; // number of outputs - int ns; // number of slacks -} ocp_nlp_cost_conl_dims; - -// -acados_size_t ocp_nlp_cost_conl_dims_calculate_size(void *config); -// -void *ocp_nlp_cost_conl_dims_assign(void *config, void *raw_memory); -// -void ocp_nlp_cost_conl_dims_initialize(void *config, void *dims, int nx, int nu, int ny, int ns, int nz); -// -void ocp_nlp_cost_conl_dims_set(void *config_, void *dims_, const char *field, int* value); -// -void ocp_nlp_cost_conl_dims_get(void *config_, void *dims_, const char *field, int* value); - - - -/************************************************ - * model - ************************************************/ - -typedef struct -{ - // slack penalty has the form z^T * s + .5 * s^T * Z * s - external_function_generic *conl_cost_fun; - external_function_generic *conl_cost_fun_jac_hess; - struct blasfeo_dvec y_ref; - struct blasfeo_dvec Z; // diagonal Hessian of slacks as vector - struct blasfeo_dvec z; // gradient of slacks as vector - double scaling; -} ocp_nlp_cost_conl_model; - -// -acados_size_t ocp_nlp_cost_conl_model_calculate_size(void *config, void *dims); -// -void *ocp_nlp_cost_conl_model_assign(void *config, void *dims, void *raw_memory); -// -int ocp_nlp_cost_conl_model_set(void *config_, void *dims_, void *model_, const char *field, void *value_); - - - -/************************************************ - * options - ************************************************/ - -typedef struct -{ - bool gauss_newton_hess; // dummy options, we always use a gauss-newton hessian -} ocp_nlp_cost_conl_opts; - -// -acados_size_t ocp_nlp_cost_conl_opts_calculate_size(void *config, void *dims); -// -void *ocp_nlp_cost_conl_opts_assign(void *config, void *dims, void *raw_memory); -// -void ocp_nlp_cost_conl_opts_initialize_default(void *config, void *dims, void *opts); -// -void ocp_nlp_cost_conl_opts_update(void *config, void *dims, void *opts); -// -void ocp_nlp_cost_conl_opts_set(void *config, void *opts, const char *field, void *value); - - - -/************************************************ - * memory - ************************************************/ -typedef struct -{ - struct blasfeo_dvec grad; // gradient of cost function - struct blasfeo_dvec *ux; // pointer to ux in nlp_out - struct blasfeo_dvec *tmp_ux; // pointer to ux in tmp_nlp_out - struct blasfeo_dmat *RSQrq; // pointer to RSQrq in qp_in - struct blasfeo_dvec *Z; // pointer to Z in qp_in - struct blasfeo_dvec *z_alg; ///< pointer to z in sim_out - struct blasfeo_dmat *dzdux_tran; ///< pointer to sensitivity of a wrt ux in sim_out - double fun; ///< value of the cost function -} ocp_nlp_cost_conl_memory; - -// -acados_size_t ocp_nlp_cost_conl_memory_calculate_size(void *config, void *dims, void *opts); -// -void *ocp_nlp_cost_conl_memory_assign(void *config, void *dims, void *opts, void *raw_memory); -// -double *ocp_nlp_cost_conl_memory_get_fun_ptr(void *memory_); -// -struct blasfeo_dvec *ocp_nlp_cost_conl_memory_get_grad_ptr(void *memory_); -// -void ocp_nlp_cost_conl_memory_set_RSQrq_ptr(struct blasfeo_dmat *RSQrq, void *memory); -// -void ocp_nlp_cost_conl_memory_set_Z_ptr(struct blasfeo_dvec *Z, void *memory); -// -void ocp_nlp_cost_conl_memory_set_ux_ptr(struct blasfeo_dvec *ux, void *memory_); -// -void ocp_nlp_cost_conl_memory_set_tmp_ux_ptr(struct blasfeo_dvec *tmp_ux, void *memory_); -// -void ocp_nlp_cost_conl_memory_set_z_alg_ptr(struct blasfeo_dvec *z_alg, void *memory_); -// -void ocp_nlp_cost_conl_memory_set_dzdux_tran_ptr(struct blasfeo_dmat *dzdux_tran, void *memory_); - -/************************************************ - * workspace - ************************************************/ - -typedef struct -{ - struct blasfeo_dmat W; // hessian of outer loss function - struct blasfeo_dmat W_chol; // cholesky factor of hessian of outer loss function - struct blasfeo_dmat Jt_ux; // jacobian of inner residual function - struct blasfeo_dmat Jt_ux_tilde; // jacobian of inner residual function plus gradient contribution of algebraic variables - struct blasfeo_dmat Jt_z; // jacobian of inner residual function wrt algebraic variables - struct blasfeo_dmat tmp_nv_ny; - struct blasfeo_dvec tmp_ny; - struct blasfeo_dvec tmp_2ns; -} ocp_nlp_cost_conl_workspace; - -// -acados_size_t ocp_nlp_cost_conl_workspace_calculate_size(void *config, void *dims, void *opts); - -/************************************************ - * functions - ************************************************/ - -// -void ocp_nlp_cost_conl_precompute(void *config_, void *dims_, void *model_, void *opts_, void *memory_, void *work_); -// -void ocp_nlp_cost_conl_config_initialize_default(void *config); -// -void ocp_nlp_cost_conl_initialize(void *config_, void *dims, void *model_, void *opts_, void *mem_, void *work_); -// -void ocp_nlp_cost_conl_update_qp_matrices(void *config_, void *dims, void *model_, void *opts_, void *memory_, void *work_); -// -void ocp_nlp_cost_conl_compute_fun(void *config_, void *dims, void *model_, void *opts_, void *memory_, void *work_); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_NLP_OCP_NLP_COST_CONL_H_ -/// @} -/// @} -/// @} diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_external.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_external.h deleted file mode 100644 index 7895827..0000000 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_external.h +++ /dev/null @@ -1,187 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_OCP_NLP_OCP_NLP_COST_EXTERNAL_H_ -#define ACADOS_OCP_NLP_OCP_NLP_COST_EXTERNAL_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// blasfeo -#include "blasfeo/include/blasfeo_common.h" - -// acados -#include "acados/ocp_nlp/ocp_nlp_cost_common.h" -#include "acados/utils/external_function_generic.h" -#include "acados/utils/types.h" - -/************************************************ - * dims - ************************************************/ - -typedef struct -{ - int nx; // number of states - int nz; // number of algebraic variables - int nu; // number of inputs - int ns; // number of slacks -} ocp_nlp_cost_external_dims; - -// -acados_size_t ocp_nlp_cost_external_dims_calculate_size(void *config); -// -void *ocp_nlp_cost_external_dims_assign(void *config, void *raw_memory); -// -void ocp_nlp_cost_external_dims_set(void *config_, void *dims_, const char *field, int* value); -// -void ocp_nlp_cost_external_dims_get(void *config_, void *dims_, const char *field, int* value); - -/************************************************ - * model - ************************************************/ - -typedef struct -{ - external_function_generic *ext_cost_fun; // function - external_function_generic *ext_cost_fun_jac_hess; // function, gradient and hessian - external_function_generic *ext_cost_fun_jac; // function, gradient - struct blasfeo_dvec Z; - struct blasfeo_dvec z; - struct blasfeo_dmat numerical_hessian; // custom hessian approximation - double scaling; -} ocp_nlp_cost_external_model; - -// -acados_size_t ocp_nlp_cost_external_model_calculate_size(void *config, void *dims); -// -void *ocp_nlp_cost_external_model_assign(void *config, void *dims, void *raw_memory); - - - -/************************************************ - * options - ************************************************/ - -typedef struct -{ - int use_numerical_hessian; // > 0 indicating custom hessian is used instead of CasADi evaluation -} ocp_nlp_cost_external_opts; - -// -acados_size_t ocp_nlp_cost_external_opts_calculate_size(void *config, void *dims); -// -void *ocp_nlp_cost_external_opts_assign(void *config, void *dims, void *raw_memory); -// -void ocp_nlp_cost_external_opts_initialize_default(void *config, void *dims, void *opts); -// -void ocp_nlp_cost_external_opts_update(void *config, void *dims, void *opts); -// -void ocp_nlp_cost_external_opts_set(void *config, void *opts, const char *field, void *value); - - - -/************************************************ - * memory - ************************************************/ - -typedef struct -{ - struct blasfeo_dvec grad; // gradient of cost function - struct blasfeo_dvec *ux; // pointer to ux in nlp_out - struct blasfeo_dvec *tmp_ux; // pointer to tmp_ux in nlp_out - struct blasfeo_dmat *RSQrq; // pointer to RSQrq in qp_in - struct blasfeo_dvec *Z; // pointer to Z in qp_in - struct blasfeo_dvec *z_alg; ///< pointer to z in sim_out - struct blasfeo_dmat *dzdux_tran; ///< pointer to sensitivity of a wrt ux in sim_out - double fun; ///< value of the cost function -} ocp_nlp_cost_external_memory; - -// -acados_size_t ocp_nlp_cost_external_memory_calculate_size(void *config, void *dims, void *opts); -// -void *ocp_nlp_cost_external_memory_assign(void *config, void *dims, void *opts, void *raw_memory); -// -double *ocp_nlp_cost_external_memory_get_fun_ptr(void *memory_); -// -struct blasfeo_dvec *ocp_nlp_cost_external_memory_get_grad_ptr(void *memory_); -// -void ocp_nlp_cost_external_memory_set_RSQrq_ptr(struct blasfeo_dmat *RSQrq, void *memory); -// -void ocp_nlp_cost_ls_memory_set_Z_ptr(struct blasfeo_dvec *Z, void *memory); -// -void ocp_nlp_cost_external_memory_set_ux_ptr(struct blasfeo_dvec *ux, void *memory_); -// -void ocp_nlp_cost_external_memory_set_tmp_ux_ptr(struct blasfeo_dvec *tmp_ux, void *memory_); -// -void ocp_nlp_cost_external_memory_set_z_alg_ptr(struct blasfeo_dvec *z_alg, void *memory_); -// -void ocp_nlp_cost_external_memory_set_dzdux_tran_ptr(struct blasfeo_dmat *dzdux_tran, void *memory_); - -/************************************************ - * workspace - ************************************************/ - -typedef struct -{ - struct blasfeo_dmat tmp_nunx_nunx; - struct blasfeo_dmat tmp_nz_nz; - struct blasfeo_dmat tmp_nz_nunx; - struct blasfeo_dvec tmp_nunxnz; - struct blasfeo_dvec tmp_2ns; // temporary vector of dimension 2*ns -} ocp_nlp_cost_external_workspace; - -// -acados_size_t ocp_nlp_cost_external_workspace_calculate_size(void *config, void *dims, void *opts); - -/************************************************ - * functions - ************************************************/ - -// -void ocp_nlp_cost_external_precompute(void *config_, void *dims_, void *model_, void *opts_, void *memory_, void *work_); -// -void ocp_nlp_cost_external_config_initialize_default(void *config); -// -void ocp_nlp_cost_external_initialize(void *config_, void *dims, void *model_, - void *opts_, void *mem_, void *work_); -// -void ocp_nlp_cost_external_update_qp_matrices(void *config_, void *dims, void *model_, - void *opts_, void *memory_, void *work_); -// -void ocp_nlp_cost_external_compute_fun(void *config_, void *dims, void *model_, - void *opts_, void *memory_, void *work_); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_NLP_OCP_NLP_COST_EXTERNAL_H_ diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_ls.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_ls.h deleted file mode 100644 index 801e9a5..0000000 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_ls.h +++ /dev/null @@ -1,243 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -/// \addtogroup ocp_nlp -/// @{ -/// \addtogroup ocp_nlp_cost ocp_nlp_cost -/// @{ -/// \addtogroup ocp_nlp_cost_ls ocp_nlp_cost_ls -/// \brief This module implements linear-least squares costs of the form -/// \f$\min_{x,u,z} \| V_x x + V_u u + V_z z - y_{\text{ref}}\|_W^2\f$. -/// @{ - - - -#ifndef ACADOS_OCP_NLP_OCP_NLP_COST_LS_H_ -#define ACADOS_OCP_NLP_OCP_NLP_COST_LS_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// blasfeo -#include "blasfeo/include/blasfeo_common.h" - -// acados -#include "acados/ocp_nlp/ocp_nlp_cost_common.h" -#include "acados/utils/external_function_generic.h" -#include "acados/utils/types.h" - - -//////////////////////////////////////////////////////////////////////////////// -// dims // -//////////////////////////////////////////////////////////////////////////////// - -typedef struct -{ - int nx; // number of states - int nz; // number of algebraic variables - int nu; // number of inputs - int ny; // number of outputs - int ns; // number of slacks -} ocp_nlp_cost_ls_dims; - - -/// Calculate the size of the ocp_nlp_cost_ls_dims struct -/// -/// \param[in] config_ structure containing configuration of ocp_nlp_cost -/// module -/// \param[out] [] -/// \return \c size of ocp_nlp_dims struct -acados_size_t ocp_nlp_cost_ls_dims_calculate_size(void *config); - - -/// Assign memory pointed to by raw_memory to ocp_nlp-cost_ls dims struct -/// -/// \param[in] config structure containing configuration of ocp_nlp_cost -/// module -/// \param[in] raw_memory pointer to memory location -/// \param[out] [] -/// \return dims -void *ocp_nlp_cost_ls_dims_assign(void *config, void *raw_memory); -// -void ocp_nlp_cost_ls_dims_set(void *config_, void *dims_, const char *field, int* value); -// -void ocp_nlp_cost_ls_dims_get(void *config_, void *dims_, const char *field, int* value); - - -//////////////////////////////////////////////////////////////////////////////// -// model // -//////////////////////////////////////////////////////////////////////////////// - - -/// structure containing the data describing the linear least-square cost -typedef struct -{ - // slack penalty has the form z^T * s + .5 * s^T * Z * s - struct blasfeo_dmat Cyt; ///< output matrix: Cy * [u,x] = y; in transposed form - struct blasfeo_dmat Vz; ///< Vz in ls cost Vx*x + Vu*u + Vz*z - struct blasfeo_dmat W; ///< ls norm corresponding to this matrix - struct blasfeo_dvec y_ref; ///< yref - struct blasfeo_dvec Z; ///< diagonal Hessian of slacks as vector (lower and upper) - struct blasfeo_dvec z; ///< gradient of slacks as vector (lower and upper) - double scaling; - int W_changed; ///< flag indicating whether W has changed and needs to be refactorized - int Cyt_or_scaling_changed; ///< flag indicating whether Cyt or scaling has changed and Hessian needs to be recomputed -} ocp_nlp_cost_ls_model; - -// -acados_size_t ocp_nlp_cost_ls_model_calculate_size(void *config, void *dims); -// -void *ocp_nlp_cost_ls_model_assign(void *config, void *dims, void *raw_memory); -// -int ocp_nlp_cost_ls_model_set(void *config_, void *dims_, void *model_, - const char *field, void *value_); - - - -//////////////////////////////////////////////////////////////////////////////// -// options // -//////////////////////////////////////////////////////////////////////////////// - - - -typedef struct -{ - int dummy; // struct can't be void -} ocp_nlp_cost_ls_opts; - -// -acados_size_t ocp_nlp_cost_ls_opts_calculate_size(void *config, void *dims); -// -void *ocp_nlp_cost_ls_opts_assign(void *config, void *dims, void *raw_memory); -// -void ocp_nlp_cost_ls_opts_initialize_default(void *config, void *dims, void *opts); -// -void ocp_nlp_cost_ls_opts_update(void *config, void *dims, void *opts); -// -void ocp_nlp_cost_ls_opts_set(void *config, void *opts, const char *field, void *value); - - - -//////////////////////////////////////////////////////////////////////////////// -// memory // -//////////////////////////////////////////////////////////////////////////////// - - - -/// structure containing the memory associated with cost_ls component -/// of the ocp_nlp module -typedef struct -{ - struct blasfeo_dmat hess; ///< hessian of cost function - struct blasfeo_dmat W_chol; ///< cholesky factor of weight matrix - struct blasfeo_dvec res; ///< ls residual r(x) - struct blasfeo_dvec grad; ///< gradient of cost function - struct blasfeo_dvec *ux; ///< pointer to ux in nlp_out - struct blasfeo_dvec *tmp_ux; ///< pointer to ux in tmp_nlp_out - struct blasfeo_dvec *z_alg; ///< pointer to z in sim_out - struct blasfeo_dmat *dzdux_tran; ///< pointer to sensitivity of a wrt ux in sim_out - struct blasfeo_dmat *RSQrq; ///< pointer to RSQrq in qp_in - struct blasfeo_dvec *Z; ///< pointer to Z in qp_in - double fun; ///< value of the cost function -} ocp_nlp_cost_ls_memory; - -// -acados_size_t ocp_nlp_cost_ls_memory_calculate_size(void *config, void *dims, void *opts); -// -void *ocp_nlp_cost_ls_memory_assign(void *config, void *dims, void *opts, void *raw_memory); -// -double *ocp_nlp_cost_ls_memory_get_fun_ptr(void *memory_); -// -struct blasfeo_dvec *ocp_nlp_cost_ls_memory_get_grad_ptr(void *memory_); -// -void ocp_nlp_cost_ls_memory_set_RSQrq_ptr(struct blasfeo_dmat *RSQrq, void *memory); -// -void ocp_nlp_cost_ls_memory_set_Z_ptr(struct blasfeo_dvec *Z, void *memory); -// -void ocp_nlp_cost_ls_memory_set_ux_ptr(struct blasfeo_dvec *ux, void *memory_); -// -void ocp_nlp_cost_ls_memory_set_tmp_ux_ptr(struct blasfeo_dvec *tmp_ux, void *memory_); -// -void ocp_nlp_cost_ls_memory_set_z_alg_ptr(struct blasfeo_dvec *z_alg, void *memory_); -// -void ocp_nlp_cost_ls_memory_set_dzdux_tran_ptr(struct blasfeo_dmat *dzdux_tran, void *memory_); - - - -//////////////////////////////////////////////////////////////////////////////// -// workspace // -//////////////////////////////////////////////////////////////////////////////// - - - -typedef struct -{ - struct blasfeo_dmat tmp_nv_ny; // temporary matrix of dimensions nv, ny - struct blasfeo_dmat Cyt_tilde; // updated Cyt (after z elimination) - struct blasfeo_dmat dzdux_tran; // derivatives of z wrt u and x (tran) - struct blasfeo_dvec tmp_ny; // temporary vector of dimension ny - struct blasfeo_dvec tmp_2ns; // temporary vector of dimension ny - struct blasfeo_dvec tmp_nz; // temporary vector of dimension nz - struct blasfeo_dvec y_ref_tilde; // updated y_ref (after z elimination) -} ocp_nlp_cost_ls_workspace; - -// -acados_size_t ocp_nlp_cost_ls_workspace_calculate_size(void *config, void *dims, void *opts); - - - -//////////////////////////////////////////////////////////////////////////////// -// functions // -//////////////////////////////////////////////////////////////////////////////// - - -// computations that are done once when solver is created -void ocp_nlp_cost_ls_precompute(void *config_, void *dims_, void *model_, void *opts_, void *memory_, void *work_); -// -void ocp_nlp_cost_ls_config_initialize_default(void *config); -// -void ocp_nlp_cost_ls_initialize(void *config_, void *dims, void *model_, void *opts_, - void *mem_, void *work_); -// -void ocp_nlp_cost_ls_update_qp_matrices(void *config_, void *dims, void *model_, - void *opts_, void *memory_, void *work_); -// -void ocp_nlp_cost_ls_compute_fun(void *config_, void *dims, void *model_, void *opts_, void *memory_, void *work_); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_NLP_OCP_NLP_COST_LS_H_ -/// @} -/// @} -/// @} diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_nls.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_nls.h deleted file mode 100644 index 5ec68cf..0000000 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_cost_nls.h +++ /dev/null @@ -1,211 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -/// \addtogroup ocp_nlp -/// @{ -/// \addtogroup ocp_nlp_cost ocp_nlp_cost -/// @{ -/// \addtogroup ocp_nlp_cost_nls ocp_nlp_cost_nls -/// \brief This module implements nonlinear-least squares costs of the form -/// \f$\min_{x,u,z} \| y(x,u,z,p) - y_{\text{ref}} \|_W^2\f$, - -#ifndef ACADOS_OCP_NLP_OCP_NLP_COST_NLS_H_ -#define ACADOS_OCP_NLP_OCP_NLP_COST_NLS_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// blasfeo -#include "blasfeo/include/blasfeo_common.h" - -// acados -#include "acados/ocp_nlp/ocp_nlp_cost_common.h" -#include "acados/utils/external_function_generic.h" -#include "acados/utils/types.h" - - - -/************************************************ - * dims - ************************************************/ - -typedef struct -{ - int nx; // number of states - int nz; // number of algebraic variables - int nu; // number of inputs - int ny; // number of outputs - int ns; // number of slacks -} ocp_nlp_cost_nls_dims; - -// -acados_size_t ocp_nlp_cost_nls_dims_calculate_size(void *config); -// -void *ocp_nlp_cost_nls_dims_assign(void *config, void *raw_memory); -// -void ocp_nlp_cost_nls_dims_set(void *config_, void *dims_, const char *field, int* value); -// -void ocp_nlp_cost_nls_dims_get(void *config_, void *dims_, const char *field, int* value); - - - -/************************************************ - * model - ************************************************/ - -typedef struct -{ - // nonliner function nls_y(x,u) replaces Cy * [x,u] in ls_cost - // slack penalty has the form z^T * s + .5 * s^T * Z * s - external_function_generic *nls_y_fun; // evaluation of nls function - external_function_generic *nls_y_fun_jac; // evaluation nls function and jacobian - external_function_generic *nls_y_hess; // hessian*seeds of nls residuals - struct blasfeo_dmat W; // - struct blasfeo_dvec y_ref; - struct blasfeo_dvec Z; // diagonal Hessian of slacks as vector - struct blasfeo_dvec z; // gradient of slacks as vector - double scaling; - int W_changed; ///< flag indicating whether W has changed and needs to be refactorized -} ocp_nlp_cost_nls_model; - -// -acados_size_t ocp_nlp_cost_nls_model_calculate_size(void *config, void *dims); -// -void *ocp_nlp_cost_nls_model_assign(void *config, void *dims, void *raw_memory); -// -int ocp_nlp_cost_nls_model_set(void *config_, void *dims_, void *model_, const char *field, void *value_); - - - -/************************************************ - * options - ************************************************/ - -typedef struct -{ - bool gauss_newton_hess; // gauss-newton hessian approximation -} ocp_nlp_cost_nls_opts; - -// -acados_size_t ocp_nlp_cost_nls_opts_calculate_size(void *config, void *dims); -// -void *ocp_nlp_cost_nls_opts_assign(void *config, void *dims, void *raw_memory); -// -void ocp_nlp_cost_nls_opts_initialize_default(void *config, void *dims, void *opts); -// -void ocp_nlp_cost_nls_opts_update(void *config, void *dims, void *opts); -// -void ocp_nlp_cost_nls_opts_set(void *config, void *opts, const char *field, void *value); - - - -/************************************************ - * memory - ************************************************/ - -typedef struct -{ - struct blasfeo_dmat W_chol; // cholesky factor of weight matrix - struct blasfeo_dmat Jt; // jacobian of nls fun - struct blasfeo_dvec res; // nls residual r(x) - struct blasfeo_dvec grad; // gradient of cost function - struct blasfeo_dvec *ux; // pointer to ux in nlp_out - struct blasfeo_dvec *tmp_ux; // pointer to ux in tmp_nlp_out - struct blasfeo_dmat *RSQrq; // pointer to RSQrq in qp_in - struct blasfeo_dvec *Z; // pointer to Z in qp_in - struct blasfeo_dvec *z_alg; ///< pointer to z in sim_out - struct blasfeo_dmat *dzdux_tran; ///< pointer to sensitivity of a wrt ux in sim_out - double fun; ///< value of the cost function -} ocp_nlp_cost_nls_memory; - -// -acados_size_t ocp_nlp_cost_nls_memory_calculate_size(void *config, void *dims, void *opts); -// -void *ocp_nlp_cost_nls_memory_assign(void *config, void *dims, void *opts, void *raw_memory); -// -double *ocp_nlp_cost_nls_memory_get_fun_ptr(void *memory_); -// -struct blasfeo_dvec *ocp_nlp_cost_nls_memory_get_grad_ptr(void *memory_); -// -void ocp_nlp_cost_nls_memory_set_RSQrq_ptr(struct blasfeo_dmat *RSQrq, void *memory); -// -void ocp_nlp_cost_nls_memory_set_Z_ptr(struct blasfeo_dvec *Z, void *memory); -// -void ocp_nlp_cost_nls_memory_set_ux_ptr(struct blasfeo_dvec *ux, void *memory_); -// -void ocp_nlp_cost_nls_memory_set_tmp_ux_ptr(struct blasfeo_dvec *tmp_ux, void *memory_); -// -void ocp_nlp_cost_nls_memory_set_z_alg_ptr(struct blasfeo_dvec *z_alg, void *memory_); -// -void ocp_nlp_cost_nls_memory_set_dzdux_tran_ptr(struct blasfeo_dmat *dzdux_tran, void *memory_); - -/************************************************ - * workspace - ************************************************/ - -typedef struct -{ - struct blasfeo_dmat tmp_nv_ny; - struct blasfeo_dmat tmp_nv_nv; - struct blasfeo_dmat Vz; - struct blasfeo_dmat Cyt_tilde; - struct blasfeo_dvec tmp_ny; - struct blasfeo_dvec tmp_2ns; - struct blasfeo_dvec tmp_nz; -} ocp_nlp_cost_nls_workspace; - -// -acados_size_t ocp_nlp_cost_nls_workspace_calculate_size(void *config, void *dims, void *opts); - -/************************************************ - * functions - ************************************************/ - -// -void ocp_nlp_cost_nls_precompute(void *config_, void *dims_, void *model_, void *opts_, void *memory_, void *work_); -// -void ocp_nlp_cost_nls_config_initialize_default(void *config); -// -void ocp_nlp_cost_nls_initialize(void *config_, void *dims, void *model_, void *opts_, void *mem_, void *work_); -// -void ocp_nlp_cost_nls_update_qp_matrices(void *config_, void *dims, void *model_, void *opts_, void *memory_, void *work_); -// -void ocp_nlp_cost_nls_compute_fun(void *config_, void *dims, void *model_, void *opts_, void *memory_, void *work_); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_NLP_OCP_NLP_COST_NLS_H_ -/// @} -/// @} -/// @} diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_dynamics_common.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_dynamics_common.h deleted file mode 100644 index 43fe71b..0000000 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_dynamics_common.h +++ /dev/null @@ -1,119 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -/// \ingroup ocp_nlp -/// @{ - -/// \defgroup ocp_nlp_dynamics ocp_nlp_dynamics -/// @{ - -#ifndef ACADOS_OCP_NLP_OCP_NLP_DYNAMICS_COMMON_H_ -#define ACADOS_OCP_NLP_OCP_NLP_DYNAMICS_COMMON_H_ - -#ifdef __cplusplus -extern "C" { -#endif - - - -// blasfeo -#include "blasfeo/include/blasfeo_common.h" - -// acados -#include "acados/sim/sim_common.h" -#include "acados/utils/external_function_generic.h" -#include "acados/utils/types.h" - - - -/************************************************ - * config - ************************************************/ - -typedef struct -{ - void (*config_initialize_default)(void *config); - sim_config *sim_solver; - /* dims */ - acados_size_t (*dims_calculate_size)(void *config); - void *(*dims_assign)(void *config, void *raw_memory); - void (*dims_set)(void *config_, void *dims_, const char *field, int *value); - void (*dims_get)(void *config_, void *dims_, const char *field, int* value); - /* model */ - acados_size_t (*model_calculate_size)(void *config, void *dims); - void *(*model_assign)(void *config, void *dims, void *raw_memory); - void (*model_set)(void *config_, void *dims_, void *model_, const char *field, void *value_); - /* opts */ - acados_size_t (*opts_calculate_size)(void *config, void *dims); - void *(*opts_assign)(void *config, void *dims, void *raw_memory); - void (*opts_initialize_default)(void *config, void *dims, void *opts); - void (*opts_set)(void *config_, void *opts_, const char *field, void *value); - void (*opts_update)(void *config, void *dims, void *opts); - /* memory */ - acados_size_t (*memory_calculate_size)(void *config, void *dims, void *opts); - void *(*memory_assign)(void *config, void *dims, void *opts, void *raw_memory); - // get shooting node gap x_next(x_n, u_n) - x_{n+1} - struct blasfeo_dvec *(*memory_get_fun_ptr)(void *memory_); - struct blasfeo_dvec *(*memory_get_adj_ptr)(void *memory_); - void (*memory_set_ux_ptr)(struct blasfeo_dvec *ux, void *memory_); - void (*memory_set_tmp_ux_ptr)(struct blasfeo_dvec *tmp_ux, void *memory_); - void (*memory_set_ux1_ptr)(struct blasfeo_dvec *ux1, void *memory_); - void (*memory_set_tmp_ux1_ptr)(struct blasfeo_dvec *tmp_ux1, void *memory_); - void (*memory_set_pi_ptr)(struct blasfeo_dvec *pi, void *memory_); - void (*memory_set_tmp_pi_ptr)(struct blasfeo_dvec *tmp_pi, void *memory_); - void (*memory_set_BAbt_ptr)(struct blasfeo_dmat *BAbt, void *memory_); - void (*memory_set_RSQrq_ptr)(struct blasfeo_dmat *RSQrq, void *memory_); - void (*memory_set_dzduxt_ptr)(struct blasfeo_dmat *mat, void *memory_); - void (*memory_set_sim_guess_ptr)(struct blasfeo_dvec *vec, bool *bool_ptr, void *memory_); - void (*memory_set_z_alg_ptr)(struct blasfeo_dvec *vec, void *memory_); - void (*memory_get)(void *config, void *dims, void *mem, const char *field, void* value); - /* workspace */ - acados_size_t (*workspace_calculate_size)(void *config, void *dims, void *opts); - void (*initialize)(void *config_, void *dims, void *model_, void *opts_, void *mem_, void *work_); - void (*update_qp_matrices)(void *config_, void *dims, void *model_, void *opts_, void *mem_, void *work_); - void (*compute_fun)(void *config_, void *dims, void *model_, void *opts_, void *mem_, void *work_); - int (*precompute)(void *config_, void *dims, void *model_, void *opts_, void *mem_, void *work_); -} ocp_nlp_dynamics_config; - -// -acados_size_t ocp_nlp_dynamics_config_calculate_size(); -// -ocp_nlp_dynamics_config *ocp_nlp_dynamics_config_assign(void *raw_memory); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_NLP_OCP_NLP_DYNAMICS_COMMON_H_ -/// @} -/// @} diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_dynamics_cont.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_dynamics_cont.h deleted file mode 100644 index 3afdc9f..0000000 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_dynamics_cont.h +++ /dev/null @@ -1,209 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -/// \addtogroup ocp_nlp -/// @{ -/// \addtogroup ocp_nlp_dynamics -/// @{ - -#ifndef ACADOS_OCP_NLP_OCP_NLP_DYNAMICS_CONT_H_ -#define ACADOS_OCP_NLP_OCP_NLP_DYNAMICS_CONT_H_ - -#ifdef __cplusplus -extern "C" { -#endif - - - -// blasfeo -#include "blasfeo/include/blasfeo_common.h" - -// acados -#include "acados/ocp_nlp/ocp_nlp_dynamics_common.h" -#include "acados/utils/external_function_generic.h" -#include "acados/utils/types.h" -#include "acados_c/sim_interface.h" - - - -/************************************************ - * dims - ************************************************/ - -typedef struct -{ - void *sim; - int nx; // number of states at the current stage - int nz; // number of algebraic states at the current stage - int nu; // number of inputs at the current stage - int nx1; // number of states at the next stage - int nu1; // number of inputes at the next stage -} ocp_nlp_dynamics_cont_dims; - -// -acados_size_t ocp_nlp_dynamics_cont_dims_calculate_size(void *config); -// -void *ocp_nlp_dynamics_cont_dims_assign(void *config, void *raw_memory); -// -void ocp_nlp_dynamics_cont_dims_set(void *config_, void *dims_, const char *field, int* value); - -/************************************************ - * options - ************************************************/ - -typedef struct -{ - void *sim_solver; - int compute_adj; - int compute_hess; -} ocp_nlp_dynamics_cont_opts; - -// -acados_size_t ocp_nlp_dynamics_cont_opts_calculate_size(void *config, void *dims); -// -void *ocp_nlp_dynamics_cont_opts_assign(void *config, void *dims, void *raw_memory); -// -void ocp_nlp_dynamics_cont_opts_initialize_default(void *config, void *dims, void *opts); -// -void ocp_nlp_dynamics_cont_opts_update(void *config, void *dims, void *opts); -// -void ocp_nlp_dynamics_cont_opts_set(void *config, void *opts, const char *field, void* value); - - - -/************************************************ - * memory - ************************************************/ - -typedef struct -{ - struct blasfeo_dvec fun; - struct blasfeo_dvec adj; - struct blasfeo_dvec *ux; // pointer to ux in nlp_out at current stage - struct blasfeo_dvec *tmp_ux; // pointer to ux in tmp_nlp_out at current stage - struct blasfeo_dvec *ux1; // pointer to ux in nlp_out at next stage - struct blasfeo_dvec *tmp_ux1; // pointer to ux in tmp_nlp_out at next stage - struct blasfeo_dvec *pi; // pointer to pi in nlp_out at current stage - struct blasfeo_dvec *tmp_pi; // pointer to pi in tmp_nlp_out at current stage - struct blasfeo_dmat *BAbt; // pointer to BAbt in qp_in - struct blasfeo_dmat *RSQrq; // pointer to RSQrq in qp_in - struct blasfeo_dvec *z_alg; // pointer to output z at t = 0 - bool *set_sim_guess; // indicate if initialization for integrator is set from outside - struct blasfeo_dvec *sim_guess; // initializations for integrator - // struct blasfeo_dvec *z; // pointer to (input) z in nlp_out at current stage - struct blasfeo_dmat *dzduxt; // pointer to dzdux transposed - void *sim_solver; // sim solver memory -} ocp_nlp_dynamics_cont_memory; - -// -acados_size_t ocp_nlp_dynamics_cont_memory_calculate_size(void *config, void *dims, void *opts); -// -void *ocp_nlp_dynamics_cont_memory_assign(void *config, void *dims, void *opts, void *raw_memory); -// -struct blasfeo_dvec *ocp_nlp_dynamics_cont_memory_get_fun_ptr(void *memory); -// -struct blasfeo_dvec *ocp_nlp_dynamics_cont_memory_get_adj_ptr(void *memory); -// -void ocp_nlp_dynamics_cont_memory_set_ux_ptr(struct blasfeo_dvec *ux, void *memory); -// -void ocp_nlp_dynamics_cont_memory_set_tmp_ux_ptr(struct blasfeo_dvec *tmp_ux, void *memory); -// -void ocp_nlp_dynamics_cont_memory_set_ux1_ptr(struct blasfeo_dvec *ux1, void *memory); -// -void ocp_nlp_dynamics_cont_memory_set_tmp_ux1_ptr(struct blasfeo_dvec *tmp_ux1, void *memory); -// -void ocp_nlp_dynamics_cont_memory_set_pi_ptr(struct blasfeo_dvec *pi, void *memory); -// -void ocp_nlp_dynamics_cont_memory_set_tmp_pi_ptr(struct blasfeo_dvec *tmp_pi, void *memory); -// -void ocp_nlp_dynamics_cont_memory_set_BAbt_ptr(struct blasfeo_dmat *BAbt, void *memory); - - - -/************************************************ - * workspace - ************************************************/ - -typedef struct -{ - struct blasfeo_dmat hess; - sim_in *sim_in; - sim_out *sim_out; - void *sim_solver; // sim solver workspace -} ocp_nlp_dynamics_cont_workspace; - -acados_size_t ocp_nlp_dynamics_cont_workspace_calculate_size(void *config, void *dims, void *opts); - - - -/************************************************ - * model - ************************************************/ - -typedef struct -{ - void *sim_model; - // double *state_transition; // TODO - double T; // simulation time -} ocp_nlp_dynamics_cont_model; - -// -acados_size_t ocp_nlp_dynamics_cont_model_calculate_size(void *config, void *dims); -// -void *ocp_nlp_dynamics_cont_model_assign(void *config, void *dims, void *raw_memory); -// -void ocp_nlp_dynamics_cont_model_set(void *config_, void *dims_, void *model_, const char *field, void *value); - - - -/************************************************ - * functions - ************************************************/ - -// -void ocp_nlp_dynamics_cont_config_initialize_default(void *config); -// -void ocp_nlp_dynamics_cont_initialize(void *config_, void *dims, void *model_, void *opts, void *mem, void *work_); -// -void ocp_nlp_dynamics_cont_update_qp_matrices(void *config_, void *dims, void *model_, void *opts, void *mem, void *work_); -// -void ocp_nlp_dynamics_cont_compute_fun(void *config_, void *dims, void *model_, void *opts, void *mem, void *work_); -// -int ocp_nlp_dynamics_cont_precompute(void *config_, void *dims, void *model_, void *opts_, void *mem_, void *work_); - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_NLP_OCP_NLP_DYNAMICS_CONT_H_ -/// @} -/// @} diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_dynamics_disc.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_dynamics_disc.h deleted file mode 100644 index 6ea26a7..0000000 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_dynamics_disc.h +++ /dev/null @@ -1,192 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -/// \addtogroup ocp_nlp -/// @{ -/// \addtogroup ocp_nlp_dynamics -/// @{ - -#ifndef ACADOS_OCP_NLP_OCP_NLP_DYNAMICS_DISC_H_ -#define ACADOS_OCP_NLP_OCP_NLP_DYNAMICS_DISC_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// blasfeo -#include "blasfeo/include/blasfeo_common.h" - -// acados -#include "acados/ocp_nlp/ocp_nlp_dynamics_common.h" -#include "acados/utils/external_function_generic.h" -#include "acados/utils/types.h" - -/************************************************ - * dims - ************************************************/ - -typedef struct -{ - int nx; // number of states at the current stage - int nu; // number of inputs at the current stage - int nx1; // number of states at the next stage - int nu1; // number of inputes at the next stage -} ocp_nlp_dynamics_disc_dims; - -// -acados_size_t ocp_nlp_dynamics_disc_dims_calculate_size(void *config); -// -void *ocp_nlp_dynamics_disc_dims_assign(void *config, void *raw_memory); -// -void ocp_nlp_dynamics_disc_dims_set(void *config_, void *dims_, const char *dim, int* value); - - -/************************************************ - * options - ************************************************/ - -typedef struct -{ - int compute_adj; - int compute_hess; -} ocp_nlp_dynamics_disc_opts; - -// -acados_size_t ocp_nlp_dynamics_disc_opts_calculate_size(void *config, void *dims); -// -void *ocp_nlp_dynamics_disc_opts_assign(void *config, void *dims, void *raw_memory); -// -void ocp_nlp_dynamics_disc_opts_initialize_default(void *config, void *dims, void *opts); -// -void ocp_nlp_dynamics_disc_opts_update(void *config, void *dims, void *opts); -// -int ocp_nlp_dynamics_disc_precompute(void *config_, void *dims, void *model_, void *opts_, - void *mem_, void *work_); - - -/************************************************ - * memory - ************************************************/ - -typedef struct -{ - struct blasfeo_dvec fun; - struct blasfeo_dvec adj; - struct blasfeo_dvec *ux; // pointer to ux in nlp_out at current stage - struct blasfeo_dvec *tmp_ux; // pointer to ux in tmp_nlp_out at current stage - struct blasfeo_dvec *ux1; // pointer to ux in nlp_out at next stage - struct blasfeo_dvec *tmp_ux1;// pointer to ux in tmp_nlp_out at next stage - struct blasfeo_dvec *pi; // pointer to pi in nlp_out at current stage - struct blasfeo_dvec *tmp_pi; // pointer to pi in tmp_nlp_out at current stage - struct blasfeo_dmat *BAbt; // pointer to BAbt in qp_in - struct blasfeo_dmat *RSQrq; // pointer to RSQrq in qp_in -} ocp_nlp_dynamics_disc_memory; - -// -acados_size_t ocp_nlp_dynamics_disc_memory_calculate_size(void *config, void *dims, void *opts); -// -void *ocp_nlp_dynamics_disc_memory_assign(void *config, void *dims, void *opts, void *raw_memory); -// -struct blasfeo_dvec *ocp_nlp_dynamics_disc_memory_get_fun_ptr(void *memory); -// -struct blasfeo_dvec *ocp_nlp_dynamics_disc_memory_get_adj_ptr(void *memory); -// -void ocp_nlp_dynamics_disc_memory_set_ux_ptr(struct blasfeo_dvec *ux, void *memory); -// -void ocp_nlp_dynamics_disc_memory_set_tmp_ux_ptr(struct blasfeo_dvec *tmp_ux, void *memory); -// -void ocp_nlp_dynamics_disc_memory_set_ux1_ptr(struct blasfeo_dvec *ux1, void *memory); -// -void ocp_nlp_dynamics_disc_memory_set_tmp_ux1_ptr(struct blasfeo_dvec *tmp_ux1, void *memory); -// -void ocp_nlp_dynamics_disc_memory_set_pi_ptr(struct blasfeo_dvec *pi, void *memory); -// -void ocp_nlp_dynamics_disc_memory_set_tmp_pi_ptr(struct blasfeo_dvec *tmp_pi, void *memory); -// -void ocp_nlp_dynamics_disc_memory_set_BAbt_ptr(struct blasfeo_dmat *BAbt, void *memory); - - - -/************************************************ - * workspace - ************************************************/ - -typedef struct -{ - struct blasfeo_dmat tmp_nv_nv; -} ocp_nlp_dynamics_disc_workspace; - -acados_size_t ocp_nlp_dynamics_disc_workspace_calculate_size(void *config, void *dims, void *opts); - - - -/************************************************ - * model - ************************************************/ - -typedef struct -{ - external_function_generic *disc_dyn_fun; - external_function_generic *disc_dyn_fun_jac; - external_function_generic *disc_dyn_fun_jac_hess; -} ocp_nlp_dynamics_disc_model; - -// -acados_size_t ocp_nlp_dynamics_disc_model_calculate_size(void *config, void *dims); -// -void *ocp_nlp_dynamics_disc_model_assign(void *config, void *dims, void *raw_memory); -// -void ocp_nlp_dynamics_disc_model_set(void *config_, void *dims_, void *model_, const char *field, void *value); - - - -/************************************************ - * functions - ************************************************/ - -// -void ocp_nlp_dynamics_disc_config_initialize_default(void *config); -// -void ocp_nlp_dynamics_disc_initialize(void *config_, void *dims, void *model_, void *opts, void *mem, void *work_); -// -void ocp_nlp_dynamics_disc_update_qp_matrices(void *config_, void *dims, void *model_, void *opts, void *mem, void *work_); -// -void ocp_nlp_dynamics_disc_compute_fun(void *config_, void *dims, void *model_, void *opts, void *mem, void *work_); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_NLP_OCP_NLP_DYNAMICS_DISC_H_ -/// @} -/// @} diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_common.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_common.h deleted file mode 100644 index 9388f3f..0000000 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_common.h +++ /dev/null @@ -1,122 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -/// \ingroup ocp_nlp -/// @{ - -/// \defgroup ocp_nlp_reg ocp_nlp_reg -/// @{ - -#ifndef ACADOS_OCP_NLP_OCP_NLP_REG_COMMON_H_ -#define ACADOS_OCP_NLP_OCP_NLP_REG_COMMON_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include "acados/ocp_qp/ocp_qp_common.h" - - - -/* dims */ - -//typedef ocp_qp_dims ocp_nlp_reg_dims; -typedef struct -{ - int *nx; - int *nu; - int *nbu; - int *nbx; - int *ng; - int N; -} ocp_nlp_reg_dims; - -// -acados_size_t ocp_nlp_reg_dims_calculate_size(int N); -// -ocp_nlp_reg_dims *ocp_nlp_reg_dims_assign(int N, void *raw_memory); -// -void ocp_nlp_reg_dims_set(void *config_, ocp_nlp_reg_dims *dims, int stage, char *field, int* value); - - - -/* config */ - -typedef struct -{ - /* dims */ - acados_size_t (*dims_calculate_size)(int N); - ocp_nlp_reg_dims *(*dims_assign)(int N, void *raw_memory); - void (*dims_set)(void *config, ocp_nlp_reg_dims *dims, int stage, char *field, int *value); - /* opts */ - acados_size_t (*opts_calculate_size)(void); - void *(*opts_assign)(void *raw_memory); - void (*opts_initialize_default)(void *config, ocp_nlp_reg_dims *dims, void *opts); - void (*opts_set)(void *config, ocp_nlp_reg_dims *dims, void *opts, char *field, void* value); - /* memory */ - acados_size_t (*memory_calculate_size)(void *config, ocp_nlp_reg_dims *dims, void *opts); - void *(*memory_assign)(void *config, ocp_nlp_reg_dims *dims, void *opts, void *raw_memory); - void (*memory_set)(void *config, ocp_nlp_reg_dims *dims, void *memory, char *field, void* value); - void (*memory_set_RSQrq_ptr)(ocp_nlp_reg_dims *dims, struct blasfeo_dmat *mat, void *memory); - void (*memory_set_rq_ptr)(ocp_nlp_reg_dims *dims, struct blasfeo_dvec *vec, void *memory); - void (*memory_set_BAbt_ptr)(ocp_nlp_reg_dims *dims, struct blasfeo_dmat *mat, void *memory); - void (*memory_set_b_ptr)(ocp_nlp_reg_dims *dims, struct blasfeo_dvec *vec, void *memory); - void (*memory_set_idxb_ptr)(ocp_nlp_reg_dims *dims, int **idxb, void *memory); - void (*memory_set_DCt_ptr)(ocp_nlp_reg_dims *dims, struct blasfeo_dmat *mat, void *memory); - void (*memory_set_ux_ptr)(ocp_nlp_reg_dims *dims, struct blasfeo_dvec *vec, void *memory); - void (*memory_set_pi_ptr)(ocp_nlp_reg_dims *dims, struct blasfeo_dvec *vec, void *memory); - void (*memory_set_lam_ptr)(ocp_nlp_reg_dims *dims, struct blasfeo_dvec *vec, void *memory); - /* functions */ - void (*regularize_hessian)(void *config, ocp_nlp_reg_dims *dims, void *opts, void *memory); - void (*correct_dual_sol)(void *config, ocp_nlp_reg_dims *dims, void *opts, void *memory); -} ocp_nlp_reg_config; - -// -acados_size_t ocp_nlp_reg_config_calculate_size(void); -// -void *ocp_nlp_reg_config_assign(void *raw_memory); - - - -/* regularization help functions */ -void acados_reconstruct_A(int dim, double *A, double *V, double *d); -void acados_mirror(int dim, double *A, double *V, double *d, double *e, double epsilon); -void acados_project(int dim, double *A, double *V, double *d, double *e, double epsilon); - - - -#ifdef __cplusplus -} -#endif - -#endif // ACADOS_OCP_NLP_OCP_NLP_REG_COMMON_H_ -/// @} -/// @} diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_convexify.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_convexify.h deleted file mode 100644 index cb52352..0000000 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_convexify.h +++ /dev/null @@ -1,146 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -/// \addtogroup ocp_nlp -/// @{ -/// \addtogroup ocp_nlp_reg -/// @{ - -#ifndef ACADOS_OCP_NLP_OCP_NLP_REG_CONVEXIFY_H_ -#define ACADOS_OCP_NLP_OCP_NLP_REG_CONVEXIFY_H_ - -#ifdef __cplusplus -extern "C" { -#endif - - - -// blasfeo -#include "blasfeo/include/blasfeo_common.h" - -// acados -#include "acados/ocp_nlp/ocp_nlp_reg_common.h" - - - -/************************************************ - * dims - ************************************************/ - -// use the functions in ocp_nlp_reg_common - -/************************************************ - * options - ************************************************/ - -typedef struct -{ - double delta; - double epsilon; -// double gamma; // 0.0 -} ocp_nlp_reg_convexify_opts; - -// -acados_size_t ocp_nlp_reg_convexify_opts_calculate_size(void); -// -void *ocp_nlp_reg_convexify_opts_assign(void *raw_memory); -// -void ocp_nlp_reg_convexify_opts_initialize_default(void *config_, ocp_nlp_reg_dims *dims, void *opts_); -// -void ocp_nlp_reg_convexify_opts_set(void *config_, ocp_nlp_reg_dims *dims, void *opts_, char *field, void* value); - - - -/************************************************ - * memory - ************************************************/ - -typedef struct { - double *R; - double *V; // TODO move to workspace - double *d; // TODO move to workspace - double *e; // TODO move to workspace - double *reg_hess; // TODO move to workspace - - struct blasfeo_dmat Q_tilde; - struct blasfeo_dmat Q_bar; - struct blasfeo_dmat BAQ; - struct blasfeo_dmat L; - struct blasfeo_dmat delta_eye; - struct blasfeo_dmat St_copy; - - struct blasfeo_dmat *original_RSQrq; - struct blasfeo_dmat tmp_RSQ; - - struct blasfeo_dvec tmp_nuxM; - struct blasfeo_dvec tmp_nbgM; - -// struct blasfeo_dvec grad; -// struct blasfeo_dvec b2; - - // giaf's - struct blasfeo_dmat **RSQrq; // pointer to RSQrq in qp_in - struct blasfeo_dvec **rq; // pointer to rq in qp_in - struct blasfeo_dmat **BAbt; // pointer to BAbt in qp_in - struct blasfeo_dvec **b; // pointer to b in qp_in - struct blasfeo_dmat **DCt; // pointer to DCt in qp_in - struct blasfeo_dvec **ux; // pointer to ux in qp_out - struct blasfeo_dvec **pi; // pointer to pi in qp_out - struct blasfeo_dvec **lam; // pointer to lam in qp_out - int **idxb; // pointer to idxb in qp_in - -} ocp_nlp_reg_convexify_memory; - -// -acados_size_t ocp_nlp_reg_convexify_calculate_memory_size(void *config, ocp_nlp_reg_dims *dims, void *opts); -// -void *ocp_nlp_reg_convexify_assign_memory(void *config, ocp_nlp_reg_dims *dims, void *opts, void *raw_memory); - -/************************************************ - * workspace - ************************************************/ - - // TODO - -/************************************************ - * functions - ************************************************/ - -// -void ocp_nlp_reg_convexify_config_initialize_default(ocp_nlp_reg_config *config); - -#ifdef __cplusplus -} -#endif - -#endif // ACADOS_OCP_NLP_OCP_NLP_REG_CONVEXIFY_H_ -/// @} -/// @} diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_mirror.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_mirror.h deleted file mode 100644 index 84a023c..0000000 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_mirror.h +++ /dev/null @@ -1,121 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -/// \addtogroup ocp_nlp -/// @{ -/// \addtogroup ocp_nlp_reg -/// @{ - -#ifndef ACADOS_OCP_NLP_OCP_NLP_REG_MIRROR_H_ -#define ACADOS_OCP_NLP_OCP_NLP_REG_MIRROR_H_ - -#ifdef __cplusplus -extern "C" { -#endif - - - -// blasfeo -#include "blasfeo/include/blasfeo_common.h" - -// acados -#include "acados/ocp_nlp/ocp_nlp_reg_common.h" - - - -/************************************************ - * dims - ************************************************/ - -// use the functions in ocp_nlp_reg_common - -/************************************************ - * options - ************************************************/ - -typedef struct -{ - double epsilon; -} ocp_nlp_reg_mirror_opts; - -// -acados_size_t ocp_nlp_reg_mirror_opts_calculate_size(void); -// -void *ocp_nlp_reg_mirror_opts_assign(void *raw_memory); -// -void ocp_nlp_reg_mirror_opts_initialize_default(void *config_, ocp_nlp_reg_dims *dims, void *opts_); -// -void ocp_nlp_reg_mirror_opts_set(void *config_, ocp_nlp_reg_dims *dims, void *opts_, char *field, void* value); - - - -/************************************************ - * memory - ************************************************/ - -typedef struct -{ - double *reg_hess; // TODO move to workspace - double *V; // TODO move to workspace - double *d; // TODO move to workspace - double *e; // TODO move to workspace - - // giaf's - struct blasfeo_dmat **RSQrq; // pointer to RSQrq in qp_in -} ocp_nlp_reg_mirror_memory; - -// -acados_size_t ocp_nlp_reg_mirror_memory_calculate_size(void *config, ocp_nlp_reg_dims *dims, void *opts); -// -void *ocp_nlp_reg_mirror_memory_assign(void *config, ocp_nlp_reg_dims *dims, void *opts, void *raw_memory); - -/************************************************ - * workspace - ************************************************/ - - // TODO - -/************************************************ - * functions - ************************************************/ - -// -void ocp_nlp_reg_mirror_config_initialize_default(ocp_nlp_reg_config *config); - - - -#ifdef __cplusplus -} -#endif - -#endif // ACADOS_OCP_NLP_OCP_NLP_REG_MIRROR_H_ -/// @} -/// @} diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_noreg.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_noreg.h deleted file mode 100644 index b571f3b..0000000 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_noreg.h +++ /dev/null @@ -1,106 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -/// \addtogroup ocp_nlp -/// @{ -/// \addtogroup ocp_nlp_reg -/// @{ - -#ifndef ACADOS_OCP_NLP_OCP_NLP_REG_NOREG_H_ -#define ACADOS_OCP_NLP_OCP_NLP_REG_NOREG_H_ - -#ifdef __cplusplus -extern "C" { -#endif - - - -// blasfeo -#include "blasfeo/include/blasfeo_common.h" - -// acados -#include "acados/ocp_nlp/ocp_nlp_reg_common.h" - - - -/************************************************ - * dims - ************************************************/ - -// use the functions in ocp_nlp_reg_common - - -/************************************************ - * options - ************************************************/ - -// -acados_size_t ocp_nlp_reg_noreg_opts_calculate_size(void); -// -void *ocp_nlp_reg_noreg_opts_assign(void *raw_memory); -// -void ocp_nlp_reg_noreg_opts_initialize_default(void *config_, ocp_nlp_reg_dims *dims, void *opts_); -// -void ocp_nlp_reg_noreg_opts_set(void *config_, ocp_nlp_reg_dims *dims, void *opts_, char *field, void* value); - - - -/************************************************ - * memory - ************************************************/ -// -acados_size_t ocp_nlp_reg_noreg_memory_calculate_size(void *config, ocp_nlp_reg_dims *dims, void *opts); -// -void *ocp_nlp_reg_noreg_memory_assign(void *config, ocp_nlp_reg_dims *dims, void *opts, void *raw_memory); - -/************************************************ - * workspace - ************************************************/ - -// not needed - -/************************************************ - * functions - ************************************************/ - -// -void ocp_nlp_reg_noreg_config_initialize_default(ocp_nlp_reg_config *config); - - - -#ifdef __cplusplus -} -#endif - -#endif // ACADOS_OCP_NLP_OCP_NLP_REG_NOREG_H_ - -/// @} -/// @} diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_project.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_project.h deleted file mode 100644 index 682ea20..0000000 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_project.h +++ /dev/null @@ -1,121 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -/// \addtogroup ocp_nlp -/// @{ -/// \addtogroup ocp_nlp_reg -/// @{ - -#ifndef ACADOS_OCP_NLP_OCP_NLP_REG_PROJECT_H_ -#define ACADOS_OCP_NLP_OCP_NLP_REG_PROJECT_H_ - -#ifdef __cplusplus -extern "C" { -#endif - - - -// blasfeo -#include "blasfeo/include/blasfeo_common.h" - -// acados -#include "acados/ocp_nlp/ocp_nlp_reg_common.h" - - - -/************************************************ - * dims - ************************************************/ - -// use the functions in ocp_nlp_reg_common - -/************************************************ - * options - ************************************************/ - -typedef struct -{ - double epsilon; -} ocp_nlp_reg_project_opts; - -// -acados_size_t ocp_nlp_reg_project_opts_calculate_size(void); -// -void *ocp_nlp_reg_project_opts_assign(void *raw_memory); -// -void ocp_nlp_reg_project_opts_initialize_default(void *config_, ocp_nlp_reg_dims *dims, void *opts_); -// -void ocp_nlp_reg_project_opts_set(void *config_, ocp_nlp_reg_dims *dims, void *opts_, char *field, void* value); - - - -/************************************************ - * memory - ************************************************/ - -typedef struct -{ - double *reg_hess; // TODO move to workspace - double *V; // TODO move to workspace - double *d; // TODO move to workspace - double *e; // TODO move to workspace - - // giaf's - struct blasfeo_dmat **RSQrq; // pointer to RSQrq in qp_in -} ocp_nlp_reg_project_memory; - -// -acados_size_t ocp_nlp_reg_project_memory_calculate_size(void *config, ocp_nlp_reg_dims *dims, void *opts); -// -void *ocp_nlp_reg_project_memory_assign(void *config, ocp_nlp_reg_dims *dims, void *opts, void *raw_memory); - -/************************************************ - * workspace - ************************************************/ - - // TODO - -/************************************************ - * functions - ************************************************/ - -// -void ocp_nlp_reg_project_config_initialize_default(ocp_nlp_reg_config *config); - - - -#ifdef __cplusplus -} -#endif - -#endif // ACADOS_OCP_NLP_OCP_NLP_REG_PROJECT_H_ -/// @} -/// @} diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_project_reduc_hess.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_project_reduc_hess.h deleted file mode 100644 index 7e12952..0000000 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_reg_project_reduc_hess.h +++ /dev/null @@ -1,132 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -/// \addtogroup ocp_nlp -/// @{ -/// \addtogroup ocp_nlp_reg -/// @{ - -#ifndef ACADOS_OCP_NLP_OCP_NLP_REG_PROJECT_REDUC_HESS_H_ -#define ACADOS_OCP_NLP_OCP_NLP_REG_PROJECT_REDUC_HESS_H_ - -#ifdef __cplusplus -extern "C" { -#endif - - - -// blasfeo -#include "blasfeo/include/blasfeo_common.h" - -// acados -#include "acados/ocp_nlp/ocp_nlp_reg_common.h" - - - -/************************************************ - * dims - ************************************************/ - -// use the functions in ocp_nlp_reg_common - -/************************************************ - * options - ************************************************/ - -typedef struct -{ - double thr_eig; - double min_eig; - double min_pivot; - int pivoting; -} ocp_nlp_reg_project_reduc_hess_opts; - -// -acados_size_t ocp_nlp_reg_project_reduc_hess_opts_calculate_size(void); -// -void *ocp_nlp_reg_project_reduc_hess_opts_assign(void *raw_memory); -// -void ocp_nlp_reg_project_reduc_hess_opts_initialize_default(void *config_, ocp_nlp_reg_dims *dims, void *opts_); -// -void ocp_nlp_reg_project_reduc_hess_opts_set(void *config_, ocp_nlp_reg_dims *dims, void *opts_, char *field, void* value); - - - -/************************************************ - * memory - ************************************************/ - -typedef struct -{ - double *reg_hess; // TODO move to workspace - double *V; // TODO move to workspace - double *d; // TODO move to workspace - double *e; // TODO move to workspace - - // giaf's - struct blasfeo_dmat L; // TODO move to workspace - struct blasfeo_dmat L2; // TODO move to workspace - struct blasfeo_dmat L3; // TODO move to workspace - struct blasfeo_dmat Ls; // TODO move to workspace - struct blasfeo_dmat P; // TODO move to workspace - struct blasfeo_dmat AL; // TODO move to workspace - - struct blasfeo_dmat **RSQrq; // pointer to RSQrq in qp_in - struct blasfeo_dmat **BAbt; // pointer to RSQrq in qp_in -} ocp_nlp_reg_project_reduc_hess_memory; - -// -acados_size_t ocp_nlp_reg_project_reduc_hess_memory_calculate_size(void *config, ocp_nlp_reg_dims *dims, void *opts); -// -void *ocp_nlp_reg_project_reduc_hess_memory_assign(void *config, ocp_nlp_reg_dims *dims, void *opts, void *raw_memory); - -/************************************************ - * workspace - ************************************************/ - - // TODO - -/************************************************ - * functions - ************************************************/ - -// -void ocp_nlp_reg_project_reduc_hess_config_initialize_default(ocp_nlp_reg_config *config); - - - -#ifdef __cplusplus -} -#endif - -#endif // ACADOS_OCP_NLP_OCP_NLP_REG_PROJECT_REDUC_HESS_H_ -/// @} -/// @} diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_sqp.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_sqp.h deleted file mode 100644 index fdb9641..0000000 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_sqp.h +++ /dev/null @@ -1,170 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -/// \addtogroup ocp_nlp -/// @{ -/// \addtogroup ocp_nlp_solver -/// @{ -/// \addtogroup ocp_nlp_sqp ocp_nlp_sqp -/// @{ - -#ifndef ACADOS_OCP_NLP_OCP_NLP_SQP_H_ -#define ACADOS_OCP_NLP_OCP_NLP_SQP_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// acados -#include "acados/ocp_nlp/ocp_nlp_common.h" -#include "acados/utils/types.h" - - - -/************************************************ - * options - ************************************************/ - -typedef struct -{ - ocp_nlp_opts *nlp_opts; - double tol_stat; // exit tolerance on stationarity condition - double tol_eq; // exit tolerance on equality constraints - double tol_ineq; // exit tolerance on inequality constraints - double tol_comp; // exit tolerance on complementarity condition - int max_iter; - int ext_qp_res; // compute external QP residuals (i.e. at SQP level) at each SQP iteration (for debugging) - int qp_warm_start; // qp_warm_start in all but the first sqp iterations - bool warm_start_first_qp; // to set qp_warm_start in first iteration - int rti_phase; // only phase 0 at the moment - int initialize_t_slacks; // 0-false or 1-true - -} ocp_nlp_sqp_opts; - -// -acados_size_t ocp_nlp_sqp_opts_calculate_size(void *config, void *dims); -// -void *ocp_nlp_sqp_opts_assign(void *config, void *dims, void *raw_memory); -// -void ocp_nlp_sqp_opts_initialize_default(void *config, void *dims, void *opts); -// -void ocp_nlp_sqp_opts_update(void *config, void *dims, void *opts); -// -void ocp_nlp_sqp_opts_set(void *config_, void *opts_, const char *field, void* value); -// -void ocp_nlp_sqp_opts_set_at_stage(void *config_, void *opts_, size_t stage, const char *field, void* value); - - - -/************************************************ - * memory - ************************************************/ - -typedef struct -{ - // nlp memory - ocp_nlp_memory *nlp_mem; - - double time_qp_sol; - double time_qp_solver_call; - double time_qp_xcond; - double time_lin; - double time_reg; - double time_tot; - double time_glob; - double time_sim; - double time_sim_la; - double time_sim_ad; - double time_solution_sensitivities; - - // statistics - double *stat; - int stat_m; - int stat_n; - - int status; - int sqp_iter; - -} ocp_nlp_sqp_memory; - -// -acados_size_t ocp_nlp_sqp_memory_calculate_size(void *config, void *dims, void *opts_); -// -void *ocp_nlp_sqp_memory_assign(void *config, void *dims, void *opts_, void *raw_memory); -// -void ocp_nlp_sqp_memory_reset_qp_solver(void *config_, void *dims_, void *nlp_in_, void *nlp_out_, - void *opts_, void *mem_, void *work_); - - -/************************************************ - * workspace - ************************************************/ - -typedef struct -{ - ocp_nlp_workspace *nlp_work; - - // temp QP in & out (to be used as workspace in param sens) - ocp_qp_in *tmp_qp_in; - ocp_qp_out *tmp_qp_out; - - // qp residuals - ocp_qp_res *qp_res; - ocp_qp_res_ws *qp_res_ws; - -} ocp_nlp_sqp_workspace; - -// -acados_size_t ocp_nlp_sqp_workspace_calculate_size(void *config, void *dims, void *opts_); - - - -/************************************************ - * functions - ************************************************/ - -// -int ocp_nlp_sqp(void *config, void *dims, void *nlp_in, void *nlp_out, - void *args, void *mem, void *work_); -// -void ocp_nlp_sqp_config_initialize_default(void *config_); -// -int ocp_nlp_sqp_precompute(void *config_, void *dims_, void *nlp_in_, void *nlp_out_, - void *opts_, void *mem_, void *work_); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_NLP_OCP_NLP_SQP_H_ -/// @} -/// @} -/// @} diff --git a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_sqp_rti.h b/third_party/acados/include/acados/ocp_nlp/ocp_nlp_sqp_rti.h deleted file mode 100644 index 364d0f4..0000000 --- a/third_party/acados/include/acados/ocp_nlp/ocp_nlp_sqp_rti.h +++ /dev/null @@ -1,163 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -/// \addtogroup ocp_nlp -/// @{ -/// \addtogroup ocp_nlp_solver -/// @{ -/// \addtogroup ocp_nlp_sqp_rti ocp_nlp_sqp_rti -/// @{ - -#ifndef ACADOS_OCP_NLP_OCP_NLP_SQP_RTI_H_ -#define ACADOS_OCP_NLP_OCP_NLP_SQP_RTI_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// acados -#include "acados/ocp_nlp/ocp_nlp_common.h" -#include "acados/utils/types.h" - - - -/************************************************ - * options - ************************************************/ - -typedef struct -{ - ocp_nlp_opts *nlp_opts; - int compute_dual_sol; - int ext_qp_res; // compute external QP residuals (i.e. at SQP level) at each SQP iteration (for debugging) - int qp_warm_start; // NOTE: this is not actually setting the warm_start! Just for compatibility with sqp. - bool warm_start_first_qp; // to set qp_warm_start in first iteration - int rti_phase; // phase of RTI. Possible values 1 (preparation), 2 (feedback) 0 (both) - -} ocp_nlp_sqp_rti_opts; - -// -acados_size_t ocp_nlp_sqp_rti_opts_calculate_size(void *config_, void *dims_); -// -void *ocp_nlp_sqp_rti_opts_assign(void *config_, void *dims_, void *raw_memory); -// -void ocp_nlp_sqp_rti_opts_initialize_default(void *config_, void *dims_, void *opts_); -// -void ocp_nlp_sqp_rti_opts_update(void *config_, void *dims_, void *opts_); -// -void ocp_nlp_sqp_rti_opts_set(void *config_, void *opts_, const char *field, void* value); -// -void ocp_nlp_sqp_rti_opts_set_at_stage(void *config_, void *opts_, size_t stage, - const char *field, void* value); - - - -/************************************************ - * memory - ************************************************/ - -typedef struct -{ - // nlp memory - ocp_nlp_memory *nlp_mem; - - double time_qp_sol; - double time_qp_solver_call; - double time_qp_xcond; - double time_lin; - double time_reg; - double time_tot; - double time_glob; - double time_solution_sensitivities; - - // statistics - double *stat; - int stat_m; - int stat_n; - - int status; - -} ocp_nlp_sqp_rti_memory; - -// -acados_size_t ocp_nlp_sqp_rti_memory_calculate_size(void *config_, void *dims_, void *opts_); -// -void *ocp_nlp_sqp_rti_memory_assign(void *config_, void *dims_, void *opts_, - void *raw_memory); - - - -/************************************************ - * workspace - ************************************************/ - -typedef struct -{ - ocp_nlp_workspace *nlp_work; - - // temp QP in & out (to be used as workspace in param sens) - ocp_qp_in *tmp_qp_in; - ocp_qp_out *tmp_qp_out; - - // qp residuals - ocp_qp_res *qp_res; - ocp_qp_res_ws *qp_res_ws; - - -} ocp_nlp_sqp_rti_workspace; - -// -acados_size_t ocp_nlp_sqp_rti_workspace_calculate_size(void *config_, void *dims_, void *opts_); - - - -/************************************************ - * functions - ************************************************/ -// -int ocp_nlp_sqp_rti(void *config_, void *dims_, void *nlp_in_, void *nlp_out_, - void *opts_, void *mem_, void *work_); -// -void ocp_nlp_sqp_rti_config_initialize_default(void *config_); -// -int ocp_nlp_sqp_rti_precompute(void *config_, void *dims_, - void *nlp_in_, void *nlp_out_, void *opts_, void *mem_, void *work_); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_NLP_OCP_NLP_SQP_RTI_H_ -/// @} -/// @} -/// @} diff --git a/third_party/acados/include/acados/ocp_qp/ocp_qp_common.h b/third_party/acados/include/acados/ocp_qp/ocp_qp_common.h deleted file mode 100644 index d1a4563..0000000 --- a/third_party/acados/include/acados/ocp_qp/ocp_qp_common.h +++ /dev/null @@ -1,180 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_OCP_QP_OCP_QP_COMMON_H_ -#define ACADOS_OCP_QP_OCP_QP_COMMON_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// hpipm -#include "hpipm/include/hpipm_d_ocp_qp.h" -#include "hpipm/include/hpipm_d_ocp_qp_dim.h" -#include "hpipm/include/hpipm_d_ocp_qp_res.h" -#include "hpipm/include/hpipm_d_ocp_qp_sol.h" -// acados -#include "acados/utils/types.h" - - - -typedef struct d_ocp_qp_dim ocp_qp_dims; -typedef struct d_ocp_qp ocp_qp_in; -typedef struct d_ocp_qp_sol ocp_qp_out; -typedef struct d_ocp_qp_res ocp_qp_res; -typedef struct d_ocp_qp_res_ws ocp_qp_res_ws; - - - -#ifndef QP_SOLVER_CONFIG_ -#define QP_SOLVER_CONFIG_ -typedef struct -{ - void (*dims_set)(void *config_, void *dims_, int stage, const char *field, int* value); - acados_size_t (*opts_calculate_size)(void *config, void *dims); - void *(*opts_assign)(void *config, void *dims, void *raw_memory); - void (*opts_initialize_default)(void *config, void *dims, void *opts); - void (*opts_update)(void *config, void *dims, void *opts); - void (*opts_set)(void *config_, void *opts_, const char *field, void* value); - acados_size_t (*memory_calculate_size)(void *config, void *dims, void *opts); - void *(*memory_assign)(void *config, void *dims, void *opts, void *raw_memory); - void (*memory_get)(void *config_, void *mem_, const char *field, void* value); - acados_size_t (*workspace_calculate_size)(void *config, void *dims, void *opts); - int (*evaluate)(void *config, void *qp_in, void *qp_out, void *opts, void *mem, void *work); - void (*memory_reset)(void *config, void *qp_in, void *qp_out, void *opts, void *mem, void *work); - void (*eval_sens)(void *config, void *qp_in, void *qp_out, void *opts, void *mem, void *work); -} qp_solver_config; -#endif - - - -typedef struct -{ - acados_size_t (*dims_calculate_size)(void *config, int N); - void *(*dims_assign)(void *config, int N, void *raw_memory); - void (*dims_set)(void *config, void *dims_, int stage, const char *field, int* value); - void (*dims_get)(void *config, void *dims, const char *field, void* value); - // TODO add config everywhere !!!!! - acados_size_t (*opts_calculate_size)(void *dims); - void *(*opts_assign)(void *dims, void *raw_memory); - void (*opts_initialize_default)(void *dims, void *opts); - void (*opts_update)(void *dims, void *opts); - void (*opts_set)(void *opts_, const char *field, void* value); - acados_size_t (*memory_calculate_size)(void *dims, void *opts); - void *(*memory_assign)(void *dims, void *opts, void *raw_memory); - void (*memory_get)(void *config, void *mem, const char *field, void* value); - acados_size_t (*workspace_calculate_size)(void *dims, void *opts); - int (*condensing)(void *qp_in, void *qp_out, void *opts, void *mem, void *work); - int (*condensing_rhs)(void *qp_in, void *qp_out, void *opts, void *mem, void *work); - int (*expansion)(void *qp_in, void *qp_out, void *opts, void *mem, void *work); -} ocp_qp_xcond_config; - - - -/// Struct containing metrics of the qp solver. -#ifndef QP_INFO_ -#define QP_INFO_ -typedef struct -{ - double solve_QP_time; - double condensing_time; - double interface_time; - double total_time; - int num_iter; - int t_computed; -} qp_info; -#endif - - - -/* config */ -// -acados_size_t ocp_qp_solver_config_calculate_size(); -// -qp_solver_config *ocp_qp_solver_config_assign(void *raw_memory); -// -acados_size_t ocp_qp_condensing_config_calculate_size(); -// -ocp_qp_xcond_config *ocp_qp_condensing_config_assign(void *raw_memory); - - -/* dims */ -// -acados_size_t ocp_qp_dims_calculate_size(int N); -// -ocp_qp_dims *ocp_qp_dims_assign(int N, void *raw_memory); -// -void ocp_qp_dims_set(void *config_, void *dims, int stage, const char *field, int* value); -// -void ocp_qp_dims_get(void *config_, void *dims, int stage, const char *field, int* value); - - -/* in */ -// -acados_size_t ocp_qp_in_calculate_size(ocp_qp_dims *dims); -// -ocp_qp_in *ocp_qp_in_assign(ocp_qp_dims *dims, void *raw_memory); - - -/* out */ -// -acados_size_t ocp_qp_out_calculate_size(ocp_qp_dims *dims); -// -ocp_qp_out *ocp_qp_out_assign(ocp_qp_dims *dims, void *raw_memory); - -/* res */ -// -acados_size_t ocp_qp_res_calculate_size(ocp_qp_dims *dims); -// -ocp_qp_res *ocp_qp_res_assign(ocp_qp_dims *dims, void *raw_memory); -// -acados_size_t ocp_qp_res_workspace_calculate_size(ocp_qp_dims *dims); -// -ocp_qp_res_ws *ocp_qp_res_workspace_assign(ocp_qp_dims *dims, void *raw_memory); -// -void ocp_qp_res_compute(ocp_qp_in *qp_in, ocp_qp_out *qp_out, ocp_qp_res *qp_res, ocp_qp_res_ws *res_ws); -// -void ocp_qp_res_compute_nrm_inf(ocp_qp_res *qp_res, double res[4]); - - -/* misc */ -// -void ocp_qp_stack_slacks_dims(ocp_qp_dims *in, ocp_qp_dims *out); -// -void ocp_qp_stack_slacks(ocp_qp_in *in, ocp_qp_in *out); -// -void ocp_qp_compute_t(ocp_qp_in *qp_in, ocp_qp_out *qp_out); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_QP_OCP_QP_COMMON_H_ diff --git a/third_party/acados/include/acados/ocp_qp/ocp_qp_common_frontend.h b/third_party/acados/include/acados/ocp_qp/ocp_qp_common_frontend.h deleted file mode 100644 index f65f602..0000000 --- a/third_party/acados/include/acados/ocp_qp/ocp_qp_common_frontend.h +++ /dev/null @@ -1,118 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_OCP_QP_OCP_QP_COMMON_FRONTEND_H_ -#define ACADOS_OCP_QP_OCP_QP_COMMON_FRONTEND_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include "acados/ocp_qp/ocp_qp_common.h" - -typedef struct -{ - int N; - int *nx; - int *nu; - int *nb; - int *nc; - double **A; - double **B; - double **b; - double **Q; - double **S; - double **R; - double **q; - double **r; - int **idxb; - double **lb; - double **ub; - double **Cx; - double **Cu; - double **lc; - double **uc; -} colmaj_ocp_qp_in; - -typedef struct -{ - double **x; - double **u; - double **pi; - double **lam; -} colmaj_ocp_qp_out; - -typedef struct -{ - double **res_r; - double **res_q; - double **res_ls; - double **res_us; - double **res_b; - double **res_d_lb; - double **res_d_ub; - double **res_d_lg; - double **res_d_ug; - double **res_d_ls; - double **res_d_us; - double **res_m_lb; - double **res_m_ub; - double **res_m_lg; - double **res_m_ug; - double **res_m_ls; - double **res_m_us; - double res_nrm_inf[4]; -} colmaj_ocp_qp_res; - -// -acados_size_t colmaj_ocp_qp_in_calculate_size(ocp_qp_dims *dims); -// -char *assign_colmaj_ocp_qp_in(ocp_qp_dims *dims, colmaj_ocp_qp_in **qp_in, void *ptr); -// -acados_size_t colmaj_ocp_qp_out_calculate_size(ocp_qp_dims *dims); -// -char *assign_colmaj_ocp_qp_out(ocp_qp_dims *dims, colmaj_ocp_qp_out **qp_out, void *ptr); -// -acados_size_t colmaj_ocp_qp_res_calculate_size(ocp_qp_dims *dims); -// -char *assign_colmaj_ocp_qp_res(ocp_qp_dims *dims, colmaj_ocp_qp_res **qp_res, void *ptr); -// -void convert_colmaj_to_ocp_qp_in(colmaj_ocp_qp_in *cm_qp_in, ocp_qp_in *qp_in); -// -void convert_ocp_qp_out_to_colmaj(ocp_qp_out *qp_out, colmaj_ocp_qp_out *cm_qp_out); -// -void convert_ocp_qp_res_to_colmaj(ocp_qp_res *qp_res, colmaj_ocp_qp_res *cm_qp_res); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_QP_OCP_QP_COMMON_FRONTEND_H_ diff --git a/third_party/acados/include/acados/ocp_qp/ocp_qp_full_condensing.h b/third_party/acados/include/acados/ocp_qp/ocp_qp_full_condensing.h deleted file mode 100644 index d23e658..0000000 --- a/third_party/acados/include/acados/ocp_qp/ocp_qp_full_condensing.h +++ /dev/null @@ -1,114 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_OCP_QP_OCP_QP_FULL_CONDENSING_H_ -#define ACADOS_OCP_QP_OCP_QP_FULL_CONDENSING_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// hpipm -#include "hpipm/include/hpipm_d_ocp_qp_red.h" -// acados -#include "acados/dense_qp/dense_qp_common.h" -#include "acados/ocp_qp/ocp_qp_common.h" -#include "acados/utils/types.h" - - - -typedef struct -{ - ocp_qp_dims *orig_dims; - ocp_qp_dims *red_dims; // dims of reduced qp - dense_qp_dims *fcond_dims; -} ocp_qp_full_condensing_dims; - - - -typedef struct ocp_qp_full_condensing_opts_ -{ - struct d_cond_qp_arg *hpipm_cond_opts; - struct d_ocp_qp_reduce_eq_dof_arg *hpipm_red_opts; -// dense_qp_dims *fcond_dims; // TODO(all): move to dims - int cond_hess; // 0 cond only rhs, 1 cond hess + rhs - int expand_dual_sol; // 0 primal sol only, 1 primal + dual sol - int ric_alg; - int mem_qp_in; // allocate qp_in in memory -} ocp_qp_full_condensing_opts; - - - -typedef struct ocp_qp_full_condensing_memory_ -{ - struct d_cond_qp_ws *hpipm_cond_work; - struct d_ocp_qp_reduce_eq_dof_ws *hpipm_red_work; - // in memory - dense_qp_in *fcond_qp_in; - dense_qp_out *fcond_qp_out; - ocp_qp_in *red_qp; // reduced qp - ocp_qp_out *red_sol; // reduced qp sol - // only pointer - ocp_qp_in *ptr_qp_in; - qp_info *qp_out_info; // info in fcond_qp_in - double time_qp_xcond; -} ocp_qp_full_condensing_memory; - - - -// -acados_size_t ocp_qp_full_condensing_opts_calculate_size(void *dims); -// -void *ocp_qp_full_condensing_opts_assign(void *dims, void *raw_memory); -// -void ocp_qp_full_condensing_opts_initialize_default(void *dims, void *opts_); -// -void ocp_qp_full_condensing_opts_update(void *dims, void *opts_); -// -void ocp_qp_full_condensing_opts_set(void *opts_, const char *field, void* value); -// -acados_size_t ocp_qp_full_condensing_memory_calculate_size(void *dims, void *opts_); -// -void *ocp_qp_full_condensing_memory_assign(void *dims, void *opts_, void *raw_memory); -// -acados_size_t ocp_qp_full_condensing_workspace_calculate_size(void *dims, void *opts_); -// -int ocp_qp_full_condensing(void *in, void *out, void *opts, void *mem, void *work); -// -int ocp_qp_full_expansion(void *in, void *out, void *opts, void *mem, void *work); -// -void ocp_qp_full_condensing_config_initialize_default(void *config_); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_QP_OCP_QP_FULL_CONDENSING_H_ diff --git a/third_party/acados/include/acados/ocp_qp/ocp_qp_hpipm.h b/third_party/acados/include/acados/ocp_qp/ocp_qp_hpipm.h deleted file mode 100644 index 261606b..0000000 --- a/third_party/acados/include/acados/ocp_qp/ocp_qp_hpipm.h +++ /dev/null @@ -1,100 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_OCP_QP_OCP_QP_HPIPM_H_ -#define ACADOS_OCP_QP_OCP_QP_HPIPM_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// hpipm -#include "hpipm/include/hpipm_d_ocp_qp_ipm.h" -// acados -#include "acados/ocp_qp/ocp_qp_common.h" -#include "acados/utils/types.h" - - - -// struct of arguments to the solver -// TODO(roversch): why not make this a typedef of the underlying struct? -typedef struct ocp_qp_hpipm_opts_ -{ - struct d_ocp_qp_ipm_arg *hpipm_opts; -} ocp_qp_hpipm_opts; - - - -// TODO(roversch): why not make this a typedef of the underlying struct? -// struct of the solver memory -typedef struct ocp_qp_hpipm_memory_ -{ - struct d_ocp_qp_ipm_ws *hpipm_workspace; - double time_qp_solver_call; - int iter; - int status; - -} ocp_qp_hpipm_memory; - - - -// -acados_size_t ocp_qp_hpipm_opts_calculate_size(void *config, void *dims); -// -void *ocp_qp_hpipm_opts_assign(void *config, void *dims, void *raw_memory); -// -void ocp_qp_hpipm_opts_initialize_default(void *config, void *dims, void *opts_); -// -void ocp_qp_hpipm_opts_update(void *config, void *dims, void *opts_); -// -void ocp_qp_hpipm_opts_set(void *config_, void *opts_, const char *field, void *value); -// -acados_size_t ocp_qp_hpipm_memory_calculate_size(void *config, void *dims, void *opts_); -// -void *ocp_qp_hpipm_memory_assign(void *config, void *dims, void *opts_, void *raw_memory); -// -acados_size_t ocp_qp_hpipm_workspace_calculate_size(void *config, void *dims, void *opts_); -// -int ocp_qp_hpipm(void *config, void *qp_in, void *qp_out, void *opts_, void *mem_, void *work_); -// -void ocp_qp_hpipm_memory_reset(void *config_, void *qp_in_, void *qp_out_, void *opts_, void *mem_, void *work_); -// -void ocp_qp_hpipm_eval_sens(void *config, void *qp_in, void *qp_out, void *opts_, void *mem_, void *work_); -// -void ocp_qp_hpipm_config_initialize_default(void *config); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_QP_OCP_QP_HPIPM_H_ diff --git a/third_party/acados/include/acados/ocp_qp/ocp_qp_hpmpc.h b/third_party/acados/include/acados/ocp_qp/ocp_qp_hpmpc.h deleted file mode 100644 index 8db53a2..0000000 --- a/third_party/acados/include/acados/ocp_qp/ocp_qp_hpmpc.h +++ /dev/null @@ -1,127 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_OCP_QP_OCP_QP_HPMPC_H_ -#define ACADOS_OCP_QP_OCP_QP_HPMPC_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include "acados/ocp_qp/ocp_qp_common.h" -#include "acados/utils/types.h" - -typedef enum hpmpc_options_t_ { HPMPC_DEFAULT_ARGUMENTS } hpmpc_options_t; - -typedef struct ocp_qp_hpmpc_opts_ -{ - double tol; - int max_iter; - double mu0; - double alpha_min; - int warm_start; - int N2; // horizion length of the partially condensed problem - - // partial tightening - double sigma_mu; - int N; - int M; -} ocp_qp_hpmpc_opts; - -// struct of the solver memory -typedef struct ocp_qp_hpmpc_memory_ -{ - struct blasfeo_dvec *hpi; - double *stats; - - // workspace - void *hpmpc_work; // raw workspace - - // partial tightening-specific (init of extra variables) - struct blasfeo_dvec *lam0; - struct blasfeo_dvec *ux0; - struct blasfeo_dvec *pi0; - struct blasfeo_dvec *t0; - - // 2. workspace - struct blasfeo_dmat *hsL; - struct blasfeo_dmat *hsric_work_mat; - struct blasfeo_dmat sLxM; - struct blasfeo_dmat sPpM; - - struct blasfeo_dvec *hsQx; - struct blasfeo_dvec *hsqx; - struct blasfeo_dvec *hstinv; - struct blasfeo_dvec *hsrq; - struct blasfeo_dvec *hsdux; - - struct blasfeo_dvec *hsdlam; - struct blasfeo_dvec *hsdt; - struct blasfeo_dvec *hsdpi; - struct blasfeo_dvec *hslamt; - - struct blasfeo_dvec *hsPb; - - void *work_ric; - - int out_iter; - - double time_qp_solver_call; - int iter; - int status; - -} ocp_qp_hpmpc_memory; - -acados_size_t ocp_qp_hpmpc_opts_calculate_size(void *config_, ocp_qp_dims *dims); -// -void *ocp_qp_hpmpc_opts_assign(void *config_, ocp_qp_dims *dims, void *raw_memory); -// -void ocp_qp_hpmpc_opts_initialize_default(void *config_, ocp_qp_dims *dims, void *opts_); -// -void ocp_qp_hpmpc_opts_update(void *config_, ocp_qp_dims *dims, void *opts_); -// -acados_size_t ocp_qp_hpmpc_memory_calculate_size(void *config_, ocp_qp_dims *dims, void *opts_); -// -void *ocp_qp_hpmpc_memory_assign(void *config_, ocp_qp_dims *dims, void *opts_, void *raw_memory); -// -acados_size_t ocp_qp_hpmpc_workspace_calculate_size(void *config_, ocp_qp_dims *dims, void *opts_); -// -int ocp_qp_hpmpc(void *config_, void *qp_in, void *qp_out, void *opts_, void *mem_, void *work_); -// -void ocp_qp_hpmpc_eval_sens(void *config_, void *qp_in, void *qp_out, void *opts_, void *mem_, void *work_); -// -void ocp_qp_hpmpc_config_initialize_default(void *config_); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_QP_OCP_QP_HPMPC_H_ diff --git a/third_party/acados/include/acados/ocp_qp/ocp_qp_ooqp.h b/third_party/acados/include/acados/ocp_qp/ocp_qp_ooqp.h deleted file mode 100644 index a535503..0000000 --- a/third_party/acados/include/acados/ocp_qp/ocp_qp_ooqp.h +++ /dev/null @@ -1,144 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_OCP_QP_OCP_QP_OOQP_H_ -#define ACADOS_OCP_QP_OCP_QP_OOQP_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include "acados/ocp_qp/ocp_qp_common.h" -#include "acados/utils/types.h" - -enum ocp_qp_ooqp_termination_code -{ - SPARSE_SUCCESSFUL_TERMINATION = 0, - SPARSE_NOT_FINISHED, - SPARSE_MAX_ITS_EXCEEDED, - SPARSE_INFEASIBLE, - SPARSE_UNKNOWN -}; - -typedef struct ocp_qp_ooqp_opts_ -{ - int printLevel; - int useDiagonalWeights; // TODO(dimitris): implement option - int fixHessian; - int fixHessianSparsity; - int fixDynamics; - int fixDynamicsSparsity; - int fixInequalities; - int fixInequalitiesSparsity; -} ocp_qp_ooqp_opts; - -typedef struct ocp_qp_ooqp_workspace_ -{ - double *x; - double *gamma; - double *phi; - double *y; - double *z; - double *lambda; - double *pi; - double objectiveValue; - int *tmpInt; // temporary vector to sort indicies sparse matrices - double *tmpReal; // temporary vector to sort data of sparse matrices - // int ierr; -} ocp_qp_ooqp_workspace; - -typedef struct ocp_qp_ooqp_memory_ -{ - int firstRun; - double *c; - int nx; - int *irowQ; - int nnzQ; - int *jcolQ; - int *orderQ; - double *dQ; - double *xlow; - char *ixlow; - double *xupp; - char *ixupp; - int *irowA; - int nnzA; - int *jcolA; - int *orderA; - double *dA; - double *bA; - int my; - int *irowC; - int nnzC; - int *jcolC; - int *orderC; - double *dC; - double *clow; - int mz; - char *iclow; - double *cupp; - char *icupp; - int nnz; // max(nnzQ, nnzA, nnzC) - double time_qp_solver_call; - int iter; - int status; - -} ocp_qp_ooqp_memory; - -// -acados_size_t ocp_qp_ooqp_opts_calculate_size(void *config_, ocp_qp_dims *dims); -// -void *ocp_qp_ooqp_opts_assign(void *config_, ocp_qp_dims *dims, void *raw_memory); -// -void ocp_qp_ooqp_opts_initialize_default(void *config_, ocp_qp_dims *dims, void *opts_); -// -void ocp_qp_ooqp_opts_update(void *config_, ocp_qp_dims *dims, void *opts_); -// -acados_size_t ocp_qp_ooqp_memory_calculate_size(void *config_, ocp_qp_dims *dims, void *opts_); -// -void *ocp_qp_ooqp_memory_assign(void *config_, ocp_qp_dims *dims, void *opts_, void *raw_memory); -// -acados_size_t ocp_qp_ooqp_workspace_calculate_size(void *config_, ocp_qp_dims *dims, void *opts_); -// -int ocp_qp_ooqp(void *config_, ocp_qp_in *qp_in, ocp_qp_out *qp_out, void *opts_, void *memory_, - void *work_); -// -void ocp_qp_ooqp_destroy(void *mem_, void *work); -// -void ocp_qp_ooqp_eval_sens(void *config_, void *qp_in, void *qp_out, void *opts_, void *mem_, void *work_); -// -void ocp_qp_ooqp_config_initialize_default(void *config_); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_QP_OCP_QP_OOQP_H_ diff --git a/third_party/acados/include/acados/ocp_qp/ocp_qp_osqp.h b/third_party/acados/include/acados/ocp_qp/ocp_qp_osqp.h deleted file mode 100644 index 51df1b1..0000000 --- a/third_party/acados/include/acados/ocp_qp/ocp_qp_osqp.h +++ /dev/null @@ -1,103 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_OCP_QP_OCP_QP_OSQP_H_ -#define ACADOS_OCP_QP_OCP_QP_OSQP_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// osqp -#include "osqp/include/types.h" - -// acados -#include "acados/ocp_qp/ocp_qp_common.h" -#include "acados/utils/types.h" - -typedef struct ocp_qp_osqp_opts_ -{ - OSQPSettings *osqp_opts; -} ocp_qp_osqp_opts; - - -typedef struct ocp_qp_osqp_memory_ -{ - c_int first_run; - - c_float *q; - c_float *l; - c_float *u; - - c_int P_nnzmax; - c_int *P_i; - c_int *P_p; - c_float *P_x; - - c_int A_nnzmax; - c_int *A_i; - c_int *A_p; - c_float *A_x; - - OSQPData *osqp_data; - OSQPWorkspace *osqp_work; - - double time_qp_solver_call; - int iter; - int status; - -} ocp_qp_osqp_memory; - -acados_size_t ocp_qp_osqp_opts_calculate_size(void *config, void *dims); -// -void *ocp_qp_osqp_opts_assign(void *config, void *dims, void *raw_memory); -// -void ocp_qp_osqp_opts_initialize_default(void *config, void *dims, void *opts_); -// -void ocp_qp_osqp_opts_update(void *config, void *dims, void *opts_); -// -acados_size_t ocp_qp_osqp_memory_calculate_size(void *config, void *dims, void *opts_); -// -void *ocp_qp_osqp_memory_assign(void *config, void *dims, void *opts_, void *raw_memory); -// -acados_size_t ocp_qp_osqp_workspace_calculate_size(void *config, void *dims, void *opts_); -// -int ocp_qp_osqp(void *config, void *qp_in, void *qp_out, void *opts_, void *mem_, void *work_); -// -void ocp_qp_osqp_eval_sens(void *config_, void *qp_in, void *qp_out, void *opts_, void *mem_, void *work_); -// -void ocp_qp_osqp_config_initialize_default(void *config); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_QP_OCP_QP_OSQP_H_ diff --git a/third_party/acados/include/acados/ocp_qp/ocp_qp_partial_condensing.h b/third_party/acados/include/acados/ocp_qp/ocp_qp_partial_condensing.h deleted file mode 100644 index 844f604..0000000 --- a/third_party/acados/include/acados/ocp_qp/ocp_qp_partial_condensing.h +++ /dev/null @@ -1,120 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_OCP_QP_OCP_QP_PARTIAL_CONDENSING_H_ -#define ACADOS_OCP_QP_OCP_QP_PARTIAL_CONDENSING_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// hpipm -#include "hpipm/include/hpipm_d_ocp_qp_red.h" -// acados -#include "acados/ocp_qp/ocp_qp_common.h" - - - -typedef struct -{ - ocp_qp_dims *orig_dims; - ocp_qp_dims *red_dims; // dims of reduced qp - ocp_qp_dims *pcond_dims; - int *block_size; - int N2; - int N2_bkp; -} ocp_qp_partial_condensing_dims; - - - -typedef struct ocp_qp_partial_condensing_opts_ -{ - struct d_part_cond_qp_arg *hpipm_pcond_opts; - struct d_ocp_qp_reduce_eq_dof_arg *hpipm_red_opts; -// ocp_qp_dims *pcond_dims; // TODO(all): move to dims -// int *block_size; - int N2; - int N2_bkp; -// int expand_dual_sol; // 0 primal sol only, 1 primal + dual sol - int ric_alg; - int mem_qp_in; // allocate qp_in in memory -} ocp_qp_partial_condensing_opts; - - - -typedef struct ocp_qp_partial_condensing_memory_ -{ - struct d_part_cond_qp_ws *hpipm_pcond_work; - struct d_ocp_qp_reduce_eq_dof_ws *hpipm_red_work; - // in memory - ocp_qp_in *pcond_qp_in; - ocp_qp_out *pcond_qp_out; - ocp_qp_in *red_qp; // reduced qp - ocp_qp_out *red_sol; // reduced qp sol - // only pointer - ocp_qp_in *ptr_qp_in; - ocp_qp_in *ptr_pcond_qp_in; - qp_info *qp_out_info; // info in pcond_qp_in - double time_qp_xcond; -} ocp_qp_partial_condensing_memory; - - - -// -acados_size_t ocp_qp_partial_condensing_opts_calculate_size(void *dims); -// -void *ocp_qp_partial_condensing_opts_assign(void *dims, void *raw_memory); -// -void ocp_qp_partial_condensing_opts_initialize_default(void *dims, void *opts_); -// -void ocp_qp_partial_condensing_opts_update(void *dims, void *opts_); -// -void ocp_qp_partial_condensing_opts_set(void *opts_, const char *field, void* value); -// -acados_size_t ocp_qp_partial_condensing_memory_calculate_size(void *dims, void *opts_); -// -void *ocp_qp_partial_condensing_memory_assign(void *dims, void *opts, void *raw_memory); -// -acados_size_t ocp_qp_partial_condensing_workspace_calculate_size(void *dims, void *opts_); -// -int ocp_qp_partial_condensing(void *in, void *out, void *opts, void *mem, void *work); -// -int ocp_qp_partial_expansion(void *in, void *out, void *opts, void *mem, void *work); -// -void ocp_qp_partial_condensing_config_initialize_default(void *config_); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_QP_OCP_QP_PARTIAL_CONDENSING_H_ diff --git a/third_party/acados/include/acados/ocp_qp/ocp_qp_qpdunes.h b/third_party/acados/include/acados/ocp_qp/ocp_qp_qpdunes.h deleted file mode 100644 index 3b875ca..0000000 --- a/third_party/acados/include/acados/ocp_qp/ocp_qp_qpdunes.h +++ /dev/null @@ -1,119 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_OCP_QP_OCP_QP_QPDUNES_H_ -#define ACADOS_OCP_QP_OCP_QP_QPDUNES_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include "qpDUNES.h" - -#include "acados/ocp_qp/ocp_qp_common.h" -#include "acados/utils/types.h" - -typedef enum qpdunes_options_t_ { - QPDUNES_DEFAULT_ARGUMENTS, - QPDUNES_LINEAR_MPC, // TODO(dimitris): partly implemented - QPDUNES_NONLINEAR_MPC, // TODO(dimitris): not implemented yet - QPDUNES_ACADO_SETTINGS -} qpdunes_options_t; - -typedef enum { QPDUNES_WITH_QPOASES, QPDUNES_WITH_CLIPPING } qpdunes_stage_qp_solver_t; - -typedef struct ocp_qp_qpdunes_opts_ -{ - qpOptions_t options; - qpdunes_stage_qp_solver_t stageQpSolver; - int warmstart; // warmstart = 0: all multipliers set to zero, warmstart = 1: use previous mult. - bool isLinearMPC; -} ocp_qp_qpdunes_opts; - -typedef struct ocp_qp_qpdunes_memory_ -{ - int firstRun; - int nx; - int nu; - int nz; - int nDmax; // max(dims->ng) - qpData_t qpData; - double time_qp_solver_call; - int iter; - int status; - -} ocp_qp_qpdunes_memory; - -typedef struct ocp_qp_qpdunes_workspace_ -{ - double *H; - double *Q; - double *R; - double *S; - double *g; - double *ABt; - double *b; - double *Ct; - double *lc; - double *uc; - double *zLow; - double *zUpp; -} ocp_qp_qpdunes_workspace; - -// -acados_size_t ocp_qp_qpdunes_opts_calculate_size(void *config_, ocp_qp_dims *dims); -// -void *ocp_qp_qpdunes_opts_assign(void *config_, ocp_qp_dims *dims, void *raw_memory); -// -void ocp_qp_qpdunes_opts_initialize_default(void *config_, ocp_qp_dims *dims, void *opts_); -// -void ocp_qp_qpdunes_opts_update(void *config_, ocp_qp_dims *dims, void *opts_); -// -acados_size_t ocp_qp_qpdunes_memory_calculate_size(void *config_, ocp_qp_dims *dims, void *opts_); -// -void *ocp_qp_qpdunes_memory_assign(void *config_, ocp_qp_dims *dims, void *opts_, void *raw_memory); -// -acados_size_t ocp_qp_qpdunes_workspace_calculate_size(void *config_, ocp_qp_dims *dims, void *opts_); -// -int ocp_qp_qpdunes(void *config_, ocp_qp_in *qp_in, ocp_qp_out *qp_out, void *opts_, void *memory_, - void *work_); -// -void ocp_qp_qpdunes_free_memory(void *mem_); -// -void ocp_qp_qpdunes_eval_sens(void *config_, void *qp_in, void *qp_out, void *opts_, void *mem_, void *work_); -// -void ocp_qp_qpdunes_config_initialize_default(void *config_); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_QP_OCP_QP_QPDUNES_H_ diff --git a/third_party/acados/include/acados/ocp_qp/ocp_qp_xcond_solver.h b/third_party/acados/include/acados/ocp_qp/ocp_qp_xcond_solver.h deleted file mode 100644 index a78bc65..0000000 --- a/third_party/acados/include/acados/ocp_qp/ocp_qp_xcond_solver.h +++ /dev/null @@ -1,150 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_OCP_QP_OCP_QP_PARTIAL_CONDENSING_SOLVER_H_ -#define ACADOS_OCP_QP_OCP_QP_PARTIAL_CONDENSING_SOLVER_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// acados -#include "acados/ocp_qp/ocp_qp_common.h" -#include "acados/utils/types.h" - - - -typedef struct -{ - ocp_qp_dims *orig_dims; - void *xcond_dims; -} ocp_qp_xcond_solver_dims; - - - -typedef struct ocp_qp_xcond_solver_opts_ -{ - void *xcond_opts; - void *qp_solver_opts; -} ocp_qp_xcond_solver_opts; - - - -typedef struct ocp_qp_xcond_solver_memory_ -{ - void *xcond_memory; - void *solver_memory; - void *xcond_qp_in; - void *xcond_qp_out; -} ocp_qp_xcond_solver_memory; - - - -typedef struct ocp_qp_xcond_solver_workspace_ -{ - void *xcond_work; - void *qp_solver_work; -} ocp_qp_xcond_solver_workspace; - - - -typedef struct -{ - acados_size_t (*dims_calculate_size)(void *config, int N); - ocp_qp_xcond_solver_dims *(*dims_assign)(void *config, int N, void *raw_memory); - void (*dims_set)(void *config_, ocp_qp_xcond_solver_dims *dims, int stage, const char *field, int* value); - void (*dims_get)(void *config_, ocp_qp_xcond_solver_dims *dims, int stage, const char *field, int* value); - acados_size_t (*opts_calculate_size)(void *config, ocp_qp_xcond_solver_dims *dims); - void *(*opts_assign)(void *config, ocp_qp_xcond_solver_dims *dims, void *raw_memory); - void (*opts_initialize_default)(void *config, ocp_qp_xcond_solver_dims *dims, void *opts); - void (*opts_update)(void *config, ocp_qp_xcond_solver_dims *dims, void *opts); - void (*opts_set)(void *config_, void *opts_, const char *field, void* value); - acados_size_t (*memory_calculate_size)(void *config, ocp_qp_xcond_solver_dims *dims, void *opts); - void *(*memory_assign)(void *config, ocp_qp_xcond_solver_dims *dims, void *opts, void *raw_memory); - void (*memory_get)(void *config_, void *mem_, const char *field, void* value); - void (*memory_reset)(void *config, ocp_qp_xcond_solver_dims *dims, ocp_qp_in *qp_in, ocp_qp_out *qp_out, void *opts, void *mem, void *work); - acados_size_t (*workspace_calculate_size)(void *config, ocp_qp_xcond_solver_dims *dims, void *opts); - int (*evaluate)(void *config, ocp_qp_xcond_solver_dims *dims, ocp_qp_in *qp_in, ocp_qp_out *qp_out, void *opts, void *mem, void *work); - void (*eval_sens)(void *config, ocp_qp_xcond_solver_dims *dims, ocp_qp_in *param_qp_in, ocp_qp_out *sens_qp_out, void *opts, void *mem, void *work); - qp_solver_config *qp_solver; // either ocp_qp_solver or dense_solver - ocp_qp_xcond_config *xcond; -} ocp_qp_xcond_solver_config; // pcond - partial condensing or fcond - full condensing - - - -/* config */ -// -acados_size_t ocp_qp_xcond_solver_config_calculate_size(); -// -ocp_qp_xcond_solver_config *ocp_qp_xcond_solver_config_assign(void *raw_memory); - -/* dims */ -// -acados_size_t ocp_qp_xcond_solver_dims_calculate_size(void *config, int N); -// -ocp_qp_xcond_solver_dims *ocp_qp_xcond_solver_dims_assign(void *config, int N, void *raw_memory); -// -void ocp_qp_xcond_solver_dims_set_(void *config, ocp_qp_xcond_solver_dims *dims, int stage, const char *field, int* value); - -/* opts */ -// -acados_size_t ocp_qp_xcond_solver_opts_calculate_size(void *config, ocp_qp_xcond_solver_dims *dims); -// -void *ocp_qp_xcond_solver_opts_assign(void *config, ocp_qp_xcond_solver_dims *dims, void *raw_memory); -// -void ocp_qp_xcond_solver_opts_initialize_default(void *config, ocp_qp_xcond_solver_dims *dims, void *opts_); -// -void ocp_qp_xcond_solver_opts_update(void *config, ocp_qp_xcond_solver_dims *dims, void *opts_); -// -void ocp_qp_xcond_solver_opts_set_(void *config_, void *opts_, const char *field, void* value); - -/* memory */ -// -acados_size_t ocp_qp_xcond_solver_memory_calculate_size(void *config, ocp_qp_xcond_solver_dims *dims, void *opts_); -// -void *ocp_qp_xcond_solver_memory_assign(void *config, ocp_qp_xcond_solver_dims *dims, void *opts_, void *raw_memory); - -/* workspace */ -// -acados_size_t ocp_qp_xcond_solver_workspace_calculate_size(void *config, ocp_qp_xcond_solver_dims *dims, void *opts_); - -/* config */ -// -int ocp_qp_xcond_solver(void *config, ocp_qp_xcond_solver_dims *dims, ocp_qp_in *qp_in, ocp_qp_out *qp_out, void *opts_, void *mem_, void *work_); - -// -void ocp_qp_xcond_solver_config_initialize_default(void *config_); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_OCP_QP_OCP_QP_PARTIAL_CONDENSING_SOLVER_H_ diff --git a/third_party/acados/include/acados/sim/sim_collocation_utils.h b/third_party/acados/include/acados/sim/sim_collocation_utils.h deleted file mode 100644 index 045d165..0000000 --- a/third_party/acados/include/acados/sim/sim_collocation_utils.h +++ /dev/null @@ -1,97 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_SIM_SIM_COLLOCATION_UTILS_H_ -#define ACADOS_SIM_SIM_COLLOCATION_UTILS_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include "acados/utils/types.h" - - - -// enum Newton_type_collocation -// { -// exact = 0, -// simplified_in, -// simplified_inis -// }; - - - -// typedef struct -// { -// enum Newton_type_collocation type; -// double *eig; -// double *low_tria; -// bool single; -// bool freeze; - -// double *transf1; -// double *transf2; - -// double *transf1_T; -// double *transf2_T; -// } Newton_scheme; - - -typedef enum -{ - GAUSS_LEGENDRE, - GAUSS_RADAU_IIA, -} sim_collocation_type; - - -// -// acados_size_t gauss_legendre_nodes_work_calculate_size(int ns); -// -// void gauss_legendre_nodes(int ns, double *nodes, void *raw_memory); -// -// acados_size_t gauss_simplified_work_calculate_size(int ns); -// // -// void gauss_simplified(int ns, Newton_scheme *scheme, void *work); -// -acados_size_t butcher_tableau_work_calculate_size(int ns); -// -// void calculate_butcher_tableau_from_nodes(int ns, double *nodes, double *b, double *A, void *work); -// -void calculate_butcher_tableau(int ns, sim_collocation_type collocation_type, double *c_vec, - double *b_vec, double *A_mat, void *work); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_SIM_SIM_COLLOCATION_UTILS_H_ diff --git a/third_party/acados/include/acados/sim/sim_common.h b/third_party/acados/include/acados/sim/sim_common.h deleted file mode 100644 index c4bbd6e..0000000 --- a/third_party/acados/include/acados/sim/sim_common.h +++ /dev/null @@ -1,221 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_SIM_SIM_COMMON_H_ -#define ACADOS_SIM_SIM_COMMON_H_ - -#include - -#include "acados/sim/sim_collocation_utils.h" -#include "acados/utils/timing.h" -#include "acados/utils/types.h" - -#include "acados/utils/external_function_generic.h" - -// maximum number of integration stages -#define NS_MAX 15 - - - -typedef enum -{ - // ERK and LIFTED_ERK - EXPL_ODE_FUN, - EXPL_ODE_HES, // wrt x and u ??? - EXPL_VDE_FOR, - EXPL_VDE_ADJ, - // IRK - IMPL_ODE_FUN, - IMPL_ODE_FUN_JAC_X_XDOT, - IMPL_ODE_JAC_X_XDOT_U, - IMPL_ODE_FUN_JAC_X_XDOT_U, - IMPL_ODE_HESS, - // gnsf - PHI_FUN, - PHI_FUN_JAC_Y, - PHI_JAC_Y_UHAT, - LO_FUN, - GET_GNSF_MATRICES -} sim_function_t; - - - -typedef struct -{ - void *dims; - - double *x; // x[NX] - initial state value for simulation - double *u; // u[NU] - control - constant over simulation time - - double *S_forw; // forward seed [Sx, Su] - double *S_adj; // backward seed - - bool identity_seed; // indicating if S_forw = [eye(nx), zeros(nx x nu)] - - void *model; - - double T; // simulation time - -} sim_in; - - - -typedef struct -{ - double CPUtime; // in seconds - double LAtime; // in seconds - double ADtime; // in seconds - -} sim_info; - - - -typedef struct -{ - double *xn; // xn[NX] - double *S_forw; // S_forw[NX*(NX+NU)] - double *S_adj; // - double *S_hess; // - - double *zn; // z - algebraic variables - reported at start of simulation interval - double *S_algebraic; // sensitivities of reported value of algebraic variables w.r.t. - // initial stat & control (x_n,u) - - double *grad; // gradient correction - - sim_info *info; - -} sim_out; - - - -typedef struct -{ - int ns; // number of integration stages - - int num_steps; - int num_forw_sens; - - int tableau_size; // check that is consistent with ns - // only update when butcher tableau is changed - // kind of private -> no setter! - double *A_mat; - double *c_vec; - double *b_vec; - - bool sens_forw; - bool sens_adj; - bool sens_hess; - - bool output_z; // 1 -- if zn should be computed - bool sens_algebraic; // 1 -- if S_algebraic should be computed - bool exact_z_output; // 1 -- if z, S_algebraic should be computed exactly, extra Newton iterations - sim_collocation_type collocation_type; - - // for explicit integrators: newton_iter == 0 && scheme == NULL - // && jac_reuse=false - int newton_iter; - bool jac_reuse; - // Newton_scheme *scheme; - - double newton_tol; // optinally used in implicit integrators - - // workspace - void *work; - -} sim_opts; - - - -typedef struct -{ - int (*evaluate)(void *config_, sim_in *in, sim_out *out, void *opts, void *mem, void *work); - int (*precompute)(void *config_, sim_in *in, sim_out *out, void *opts, void *mem, void *work); - // opts - acados_size_t (*opts_calculate_size)(void *config_, void *dims); - void *(*opts_assign)(void *config_, void *dims, void *raw_memory); - void (*opts_initialize_default)(void *config_, void *dims, void *opts); - void (*opts_update)(void *config_, void *dims, void *opts); - void (*opts_set)(void *config_, void *opts_, const char *field, void *value); - void (*opts_get)(void *config_, void *opts_, const char *field, void *value); - // mem - acados_size_t (*memory_calculate_size)(void *config, void *dims, void *opts); - void *(*memory_assign)(void *config, void *dims, void *opts, void *raw_memory); - int (*memory_set)(void *config, void *dims, void *mem, const char *field, void *value); - int (*memory_set_to_zero)(void *config, void *dims, void *opts, void *mem, const char *field); - void (*memory_get)(void *config, void *dims, void *mem, const char *field, void *value); - // work - acados_size_t (*workspace_calculate_size)(void *config, void *dims, void *opts); - // model - acados_size_t (*model_calculate_size)(void *config, void *dims); - void *(*model_assign)(void *config, void *dims, void *raw_memory); - int (*model_set)(void *model, const char *field, void *value); - // config - void (*config_initialize_default)(void *config); - // dims - acados_size_t (*dims_calculate_size)(); - void *(*dims_assign)(void *config, void *raw_memory); - void (*dims_set)(void *config, void *dims, const char *field, const int *value); - void (*dims_get)(void *config, void *dims, const char *field, int *value); - -} sim_config; - - - -/* config */ -// -acados_size_t sim_config_calculate_size(); -// -sim_config *sim_config_assign(void *raw_memory); - -/* in */ -// -acados_size_t sim_in_calculate_size(void *config, void *dims); -// -sim_in *sim_in_assign(void *config, void *dims, void *raw_memory); -// -int sim_in_set_(void *config_, void *dims_, sim_in *in, const char *field, void *value); - -/* out */ -// -acados_size_t sim_out_calculate_size(void *config, void *dims); -// -sim_out *sim_out_assign(void *config, void *dims, void *raw_memory); -// -int sim_out_get_(void *config, void *dims, sim_out *out, const char *field, void *value); - -/* opts */ -// -void sim_opts_set_(sim_opts *opts, const char *field, void *value); -// -void sim_opts_get_(sim_config *config, sim_opts *opts, const char *field, void *value); - -#endif // ACADOS_SIM_SIM_COMMON_H_ diff --git a/third_party/acados/include/acados/sim/sim_erk_integrator.h b/third_party/acados/include/acados/sim/sim_erk_integrator.h deleted file mode 100644 index fd46cb4..0000000 --- a/third_party/acados/include/acados/sim/sim_erk_integrator.h +++ /dev/null @@ -1,140 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_SIM_SIM_ERK_INTEGRATOR_H_ -#define ACADOS_SIM_SIM_ERK_INTEGRATOR_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include "acados/sim/sim_common.h" -#include "acados/utils/types.h" - - - -typedef struct -{ - int nx; - int nu; - int nz; -} sim_erk_dims; - - - -typedef struct -{ - /* external functions */ - // explicit ode - external_function_generic *expl_ode_fun; - // hessian explicit ode - external_function_generic *expl_ode_hes; - // forward explicit vde - external_function_generic *expl_vde_for; - // adjoint explicit vde - external_function_generic *expl_vde_adj; - -} erk_model; - - - -typedef struct -{ - // memory - double time_sim; - double time_ad; - double time_la; - - // workspace structs -} sim_erk_memory; - - - -typedef struct -{ - // workspace mem - double *rhs_forw_in; // x + S + p - - double *K_traj; // (stages*nX) or (steps*stages*nX) for adj - double *out_forw_traj; // S or (steps+1)*nX for adj - - double *rhs_adj_in; - double *out_adj_tmp; - double *adj_traj; - -} sim_erk_workspace; - - - -// dims -acados_size_t sim_erk_dims_calculate_size(); -void *sim_erk_dims_assign(void *config_, void *raw_memory); -void sim_erk_dims_set(void *config_, void *dims_, const char *field, const int* value); -void sim_erk_dims_get(void *config_, void *dims_, const char *field, int* value); - -// model -acados_size_t sim_erk_model_calculate_size(void *config, void *dims); -void *sim_erk_model_assign(void *config, void *dims, void *raw_memory); -int sim_erk_model_set(void *model, const char *field, void *value); - -// opts -acados_size_t sim_erk_opts_calculate_size(void *config, void *dims); -// -void sim_erk_opts_update(void *config_, void *dims, void *opts_); -// -void *sim_erk_opts_assign(void *config, void *dims, void *raw_memory); -// -void sim_erk_opts_initialize_default(void *config, void *dims, void *opts_); -// -void sim_erk_opts_set(void *config_, void *opts_, const char *field, void *value); - - -// memory -acados_size_t sim_erk_memory_calculate_size(void *config, void *dims, void *opts_); -// -void *sim_erk_memory_assign(void *config, void *dims, void *opts_, void *raw_memory); -// -int sim_erk_memory_set(void *config_, void *dims_, void *mem_, const char *field, void *value); - - -// workspace -acados_size_t sim_erk_workspace_calculate_size(void *config, void *dims, void *opts_); - -// -int sim_erk(void *config, sim_in *in, sim_out *out, void *opts_, void *mem_, void *work_); -// -void sim_erk_config_initialize_default(void *config); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_SIM_SIM_ERK_INTEGRATOR_H_ diff --git a/third_party/acados/include/acados/sim/sim_gnsf.h b/third_party/acados/include/acados/sim/sim_gnsf.h deleted file mode 100644 index 404532a..0000000 --- a/third_party/acados/include/acados/sim/sim_gnsf.h +++ /dev/null @@ -1,364 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_SIM_SIM_GNSF_H_ -#define ACADOS_SIM_SIM_GNSF_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include - -#include "acados/utils/timing.h" -#include "acados/utils/types.h" -#include "acados/sim/sim_common.h" - -#include "blasfeo/include/blasfeo_common.h" -// #include "blasfeo/include/blasfeo_d_aux.h" -// #include "blasfeo/include/blasfeo_d_aux_ext_dep.h" -// #include "blasfeo/include/blasfeo_d_blas.h" -// #include "blasfeo/include/blasfeo_d_kernel.h" -// #include "blasfeo/include/blasfeo_i_aux_ext_dep.h" -// #include "blasfeo/include/blasfeo_target.h" - -/* -GNSF - Generalized Nonlinear Static Feedback Model -has the following form -https://github.com/acados/acados/files/3359595/gnsf_structure_blo.pdf - -Details on the algorithm can be found in master thesis of Jonathan Frey, -which presents a slightly different format without the terms B_LO, c_LO. -https://github.com/acados/acados/files/2318322/gnsf_structure.pdf -https://cdn.syscop.de/publications/Frey2018.pdf -https://cdn.syscop.de/publications/Frey2019.pdf -*/ - -typedef struct -{ - int nx; // total number of differential states - int nu; // total number of inputs - int nz; // total number of algebraic states - int nx1; // number of differential states in NSF part - int nz1; // number of algebraic states in NSF part - int n_out; // output dimension of phi - int ny; // dimension of first input of phi - int nuhat; // dimension of second input of phi - -} sim_gnsf_dims; - - - -typedef struct -{ - /* external functions */ - // phi: nonlinearity function - external_function_generic *phi_fun; - external_function_generic *phi_fun_jac_y; - external_function_generic *phi_jac_y_uhat; - - // f_lo: linear output function - external_function_generic *f_lo_fun_jac_x1_x1dot_u_z; - - // to import model matrices - external_function_generic *get_gnsf_matrices; - - // flag indicating, if model defining matrices are imported via external (casadi) function, - // [default]: true -> auto; - bool auto_import_gnsf; - - // booleans from structure detection - bool nontrivial_f_LO; // indicates if f_LO is constant zero function - bool fully_linear; // indicates if model is fully linear LOS - - /* model defining matrices */ - // TODO: add setters to set manually - double *A; - double *B; - double *C; - double *E; - - double *L_x; - double *L_xdot; - double *L_z; - double *L_u; - - double *A_LO; - double *B_LO; - double *E_LO; - - /* constant vector */ - double *c; - double *c_LO; - - // permutation vector - to have GNSF order of x, z within sim_gnsf only - int *ipiv_x; - int *ipiv_z; - - double *ipiv_x_double; - double *ipiv_z_double; - -} gnsf_model; - - - -// pre_workspace - workspace used in the precomputation phase -typedef struct -{ - struct blasfeo_dmat E11; - struct blasfeo_dmat E12; - struct blasfeo_dmat E21; - struct blasfeo_dmat E22; - - struct blasfeo_dmat A1; - struct blasfeo_dmat A2; - struct blasfeo_dmat B1; - struct blasfeo_dmat B2; - struct blasfeo_dmat C1; - struct blasfeo_dmat C2; - - struct blasfeo_dmat AA1; - struct blasfeo_dmat AA2; - struct blasfeo_dmat BB1; - struct blasfeo_dmat BB2; - struct blasfeo_dmat CC1; - struct blasfeo_dmat CC2; - struct blasfeo_dmat DD1; - struct blasfeo_dmat DD2; - struct blasfeo_dmat EE1; - struct blasfeo_dmat EE2; - - struct blasfeo_dmat QQ1; - - struct blasfeo_dmat LLZ; - struct blasfeo_dmat LLx; - struct blasfeo_dmat LLK; - - int *ipivEE1; // index of pivot vector - int *ipivEE2; - int *ipivQQ1; - - // for algebraic sensitivity propagation - struct blasfeo_dmat Q1; - - // for constant term in NSF - struct blasfeo_dvec cc1; - struct blasfeo_dvec cc2; - -} gnsf_pre_workspace; - - - -// workspace -typedef struct -{ - double *Z_work; // used to perform computations to get out->zn - - int *ipiv; // index of pivot vector - - struct blasfeo_dvec *vv_traj; - struct blasfeo_dvec *yy_traj; - struct blasfeo_dmat *f_LO_jac_traj; - - struct blasfeo_dvec K2_val; - struct blasfeo_dvec x0_traj; - struct blasfeo_dvec res_val; - struct blasfeo_dvec u0; - struct blasfeo_dvec lambda; - struct blasfeo_dvec lambda_old; - - struct blasfeo_dvec yyu; - struct blasfeo_dvec yyss; - - struct blasfeo_dvec K1_val; - struct blasfeo_dvec f_LO_val; - struct blasfeo_dvec x1_stage_val; - struct blasfeo_dvec Z1_val; - - struct blasfeo_dvec K1u; - struct blasfeo_dvec Zu; - struct blasfeo_dvec ALOtimesx02; - struct blasfeo_dvec BLOtimesu0; - - struct blasfeo_dvec uhat; - - struct blasfeo_dmat J_r_vv; - struct blasfeo_dmat J_r_x1u; - - struct blasfeo_dmat dK1_dx1; - struct blasfeo_dmat dK1_du; - struct blasfeo_dmat dZ_dx1; - struct blasfeo_dmat dZ_du; - struct blasfeo_dmat J_G2_K1; - - struct blasfeo_dmat dK2_dx1; - struct blasfeo_dmat dK2_dvv; - struct blasfeo_dmat dxf_dwn; - struct blasfeo_dmat S_forw_new; - struct blasfeo_dmat S_algebraic_aux; - - struct blasfeo_dmat dPsi_dvv; - struct blasfeo_dmat dPsi_dx; - struct blasfeo_dmat dPsi_du; - - struct blasfeo_dmat dPHI_dyuhat; - struct blasfeo_dvec z0; - - // memory only available if (opts->sens_algebraic) - // struct blasfeo_dvec y_one_stage; - // struct blasfeo_dvec x0dot_1; - // struct blasfeo_dmat dz10_dx1u; // (nz1) * (nx1+nu); - // struct blasfeo_dmat dr0_dvv0; // (n_out * n_out) - // struct blasfeo_dmat f_LO_jac0; // (nx2+nz2) * (2*nx1 + nz1 + nu) - // struct blasfeo_dmat sens_z2_rhs; // (nx2 + nz2) * (nx1 + nu) - // int *ipiv_vv0; - -} gnsf_workspace; - - - -// memory -typedef struct -{ - bool first_call; - - // simulation time for one step - double dt; - - // (scaled) butcher table - double *A_dt; - double *b_dt; - double *c_butcher; - - // value used to initialize integration variables - corresponding to value of phi - double *phi_guess; // n_out - - struct blasfeo_dmat S_forw; - struct blasfeo_dmat S_algebraic; - - // precomputed matrices - struct blasfeo_dmat KKv; - struct blasfeo_dmat KKx; - struct blasfeo_dmat KKu; - - struct blasfeo_dmat YYv; - struct blasfeo_dmat YYx; - struct blasfeo_dmat YYu; - - struct blasfeo_dmat ZZv; - struct blasfeo_dmat ZZx; - struct blasfeo_dmat ZZu; - - struct blasfeo_dmat ALO; - struct blasfeo_dmat BLO; - struct blasfeo_dmat M2_LU; - int *ipivM2; - - struct blasfeo_dmat dK2_dx2; - struct blasfeo_dmat dK2_du; - struct blasfeo_dmat dx2f_dx2u; - - struct blasfeo_dmat Lu; - - // precomputed vectors for constant term in NSF - struct blasfeo_dvec KK0; - struct blasfeo_dvec YY0; - struct blasfeo_dvec ZZ0; - - // for algebraic sensitivities only; - // struct blasfeo_dmat *Z0x; - // struct blasfeo_dmat *Z0u; - // struct blasfeo_dmat *Z0v; - - // struct blasfeo_dmat *Y0x; - // struct blasfeo_dmat *Y0u; - // struct blasfeo_dmat *Y0v; - - // struct blasfeo_dmat *K0x; - // struct blasfeo_dmat *K0u; - // struct blasfeo_dmat *K0v; - - // struct blasfeo_dmat *ELO_LU; - // int *ipiv_ELO; - // struct blasfeo_dmat *ELO_inv_ALO; - - // struct blasfeo_dmat *Lx; - // struct blasfeo_dmat *Lxdot; - // struct blasfeo_dmat *Lz; - - double time_sim; - double time_ad; - double time_la; - -} sim_gnsf_memory; - - - -// gnsf dims -acados_size_t sim_gnsf_dims_calculate_size(); -void *sim_gnsf_dims_assign(void *config_, void *raw_memory); - -// get & set functions -void sim_gnsf_dims_set(void *config_, void *dims_, const char *field, const int *value); -void sim_gnsf_dims_get(void *config_, void *dims_, const char *field, int* value); - -// opts -acados_size_t sim_gnsf_opts_calculate_size(void *config, void *dims); -void *sim_gnsf_opts_assign(void *config, void *dims, void *raw_memory); -void sim_gnsf_opts_initialize_default(void *config, void *dims, void *opts_); -void sim_gnsf_opts_update(void *config_, void *dims, void *opts_); -void sim_gnsf_opts_set(void *config_, void *opts_, const char *field, void *value); - -// model -acados_size_t sim_gnsf_model_calculate_size(void *config, void *dims_); -void *sim_gnsf_model_assign(void *config, void *dims_, void *raw_memory); -int sim_gnsf_model_set(void *model_, const char *field, void *value); - -// precomputation -int sim_gnsf_precompute(void *config_, sim_in *in, sim_out *out, void *opts_, void *mem_, - void *work_); - -// workspace & memory -acados_size_t sim_gnsf_workspace_calculate_size(void *config, void *dims_, void *args); -acados_size_t sim_gnsf_memory_calculate_size(void *config, void *dims_, void *opts_); -void *sim_gnsf_memory_assign(void *config, void *dims_, void *opts_, void *raw_memory); - -// interface -void sim_gnsf_config_initialize_default(void *config_); - -// integrator -int sim_gnsf(void *config, sim_in *in, sim_out *out, void *opts, void *mem_, void *work_); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_SIM_SIM_GNSF_H_ diff --git a/third_party/acados/include/acados/sim/sim_irk_integrator.h b/third_party/acados/include/acados/sim/sim_irk_integrator.h deleted file mode 100644 index 5090aa0..0000000 --- a/third_party/acados/include/acados/sim/sim_irk_integrator.h +++ /dev/null @@ -1,183 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_SIM_SIM_IRK_INTEGRATOR_H_ -#define ACADOS_SIM_SIM_IRK_INTEGRATOR_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include "acados/sim/sim_common.h" -#include "acados/utils/types.h" - -#include "blasfeo/include/blasfeo_common.h" - -typedef struct -{ - int nx; - int nu; - int nz; - -} sim_irk_dims; - - - -typedef struct -{ - /* external functions */ - // implicit fun - can either be fully implicit ode or dae - // - i.e. dae has z as additional last argument & nz > 0 - external_function_generic *impl_ode_fun; - // implicit ode & jac_x & jax_xdot & jac_z - external_function_generic *impl_ode_fun_jac_x_xdot_z; - // jax_x & jac_xdot & jac_u & jac_z of implicit ode - external_function_generic *impl_ode_jac_x_xdot_u_z; - // hessian of implicit ode: - external_function_generic *impl_ode_hess; -} irk_model; - - - -typedef struct -{ - struct blasfeo_dvec *rG; // residuals of G (nx*ns) - struct blasfeo_dvec *K; // internal K variables ((nx+nz)*ns) - struct blasfeo_dvec *xt; // temporary x - struct blasfeo_dvec *xn; // x at each integration step - struct blasfeo_dvec xtdot; // temporary xdot - - struct blasfeo_dvec *lambda; // adjoint sensitivities (nx + nu) - struct blasfeo_dvec *lambdaK; // auxiliary variable ((nx+nz)*ns) for adjoint propagation - - struct blasfeo_dmat df_dx; // temporary Jacobian of ode w.r.t x (nx+nz, nx) - struct blasfeo_dmat df_dxdot; // temporary Jacobian of ode w.r.t xdot (nx+nz, nx) - struct blasfeo_dmat df_du; // temporary Jacobian of ode w.r.t u (nx+nz, nu) - struct blasfeo_dmat df_dz; // temporary Jacobian of ode w.r.t z (nx+nz, nu) - - /* NOTE: the memory allocation corresponding to the following fields is CONDITIONAL */ - - // only allocated if (opts->sens_algebraic || opts->output_z) - int *ipiv_one_stage; // index of pivot vector (nx + nz) - double *Z_work; // used to perform computations to get out->zn (ns) - - // df_dxdotz, dk0_dxu, only allocated if (opts->sens_algebraic && opts->exact_z_output) - // used for algebraic sensitivity generation - struct blasfeo_dmat df_dxdotz; // temporary Jacobian of ode w.r.t. xdot,z (nx+nz, nx+nz); - struct blasfeo_dmat dk0_dxu; // intermediate result, (nx+nz, nx+nu) - - // dK_dxu: if (!opts->sens_hess) - single blasfeo_dmat that is reused - // if ( opts->sens_hess) - array of (num_steps) blasfeo_dmat - // to store intermediate results - struct blasfeo_dmat *dK_dxu; // jacobian of (K,Z) over x and u ((nx+nz)*ns, nx+nu); - - // S_forw: if (!opts->sens_hess) - single blasfeo_dmat that is reused - // if ( opts->sens_hess) - array of (num_steps + 1) blasfeo_dmat - // to store intermediate results - struct blasfeo_dmat *S_forw; // forward sensitivities (nx, nx+nu) - - // dG_dxu: if (!opts->sens_hess) - single blasfeo_dmat that is reused - // if ( opts->sens_hess) - array of blasfeo_dmat to store intermediate results - struct blasfeo_dmat *dG_dxu; // jacobian of G over x and u ((nx+nz)*ns, nx+nu) - - // dG_dK: if (!opts->sens_hess) - single blasfeo_dmat that is reused - // if ( opts->sens_hess) - array of blasfeo_dmat to store intermediate results - struct blasfeo_dmat *dG_dK; // jacobian of G over K ((nx+nz)*ns, (nx+nz)*ns) - - // ipiv: index of pivot vector - // if (!opts->sens_hess) - array (ns * (nx + nz)) that is reused - // if ( opts->sens_hess) - array (ns * (nx + nz)) * num_steps, to store all - // pivot vectors for dG_dxu - int *ipiv; // index of pivot vector - - // xn_traj, K_traj only available if( opts->sens_adj || opts->sens_hess ) - struct blasfeo_dvec *xn_traj; // xn trajectory - struct blasfeo_dvec *K_traj; // K trajectory - - /* the following variables are only available if (opts->sens_hess) */ - // For Hessian propagation - struct blasfeo_dmat Hess; // temporary Hessian (nx + nu, nx + nu) - // output of impl_ode_hess - struct blasfeo_dmat f_hess; // size: (nx + nu, nx + nu) - struct blasfeo_dmat dxkzu_dw0; // size (2*nx + nu + nz) x (nx + nu) - struct blasfeo_dmat tmp_dxkzu_dw0; // size (2*nx + nu + nz) x (nx + nu) - -} sim_irk_workspace; - - -typedef struct -{ - double *xdot; // xdot[NX] - initialization for state derivatives k within the integrator - double *z; // z[NZ] - initialization for algebraic variables z - - double time_sim; - double time_ad; - double time_la; -} sim_irk_memory; - - -// get & set functions -void sim_irk_dims_set(void *config_, void *dims_, const char *field, const int *value); -void sim_irk_dims_get(void *config_, void *dims_, const char *field, int* value); - -// dims -acados_size_t sim_irk_dims_calculate_size(); -void *sim_irk_dims_assign(void *config_, void *raw_memory); - -// model -acados_size_t sim_irk_model_calculate_size(void *config, void *dims); -void *sim_irk_model_assign(void *config, void *dims, void *raw_memory); -int sim_irk_model_set(void *model, const char *field, void *value); - -// opts -acados_size_t sim_irk_opts_calculate_size(void *config, void *dims); -void *sim_irk_opts_assign(void *config, void *dims, void *raw_memory); -void sim_irk_opts_initialize_default(void *config, void *dims, void *opts_); -void sim_irk_opts_update(void *config_, void *dims, void *opts_); -void sim_irk_opts_set(void *config_, void *opts_, const char *field, void *value); - -// memory -acados_size_t sim_irk_memory_calculate_size(void *config, void *dims, void *opts_); -void *sim_irk_memory_assign(void *config, void *dims, void *opts_, void *raw_memory); -int sim_irk_memory_set(void *config_, void *dims_, void *mem_, const char *field, void *value); - -// workspace -acados_size_t sim_irk_workspace_calculate_size(void *config, void *dims, void *opts_); -void sim_irk_config_initialize_default(void *config); - -// main -int sim_irk(void *config, sim_in *in, sim_out *out, void *opts_, void *mem_, void *work_); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_SIM_SIM_IRK_INTEGRATOR_H_ diff --git a/third_party/acados/include/acados/sim/sim_lifted_irk_integrator.h b/third_party/acados/include/acados/sim/sim_lifted_irk_integrator.h deleted file mode 100644 index e60bb80..0000000 --- a/third_party/acados/include/acados/sim/sim_lifted_irk_integrator.h +++ /dev/null @@ -1,157 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_SIM_SIM_LIFTED_IRK_INTEGRATOR_H_ -#define ACADOS_SIM_SIM_LIFTED_IRK_INTEGRATOR_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include "acados/sim/sim_common.h" -#include "acados/utils/types.h" - -typedef struct -{ - int nx; - int nu; - int nz; -} sim_lifted_irk_dims; - - - -typedef struct -{ - /* external functions */ - // implicit ode - external_function_generic *impl_ode_fun; - // implicit ode & jax_x & jac_xdot & jac_u implicit ode - external_function_generic *impl_ode_fun_jac_x_xdot_u; - -} lifted_irk_model; - - - -typedef struct -{ - - struct blasfeo_dmat *J_temp_x; // temporary Jacobian of ode w.r.t x (nx, nx) - struct blasfeo_dmat *J_temp_xdot; // temporary Jacobian of ode w.r.t xdot (nx, nx) - struct blasfeo_dmat *J_temp_u; // temporary Jacobian of ode w.r.t u (nx, nu) - - struct blasfeo_dvec *rG; // residuals of G (nx*ns) - struct blasfeo_dvec *xt; // temporary x - struct blasfeo_dvec *xn; // x at each integration step (for evaluations) - struct blasfeo_dvec *xn_out; // x at each integration step (output) - struct blasfeo_dvec *dxn; // dx at each integration step - struct blasfeo_dvec *w; // stacked x and u - - int *ipiv; // index of pivot vector - -} sim_lifted_irk_workspace; - - - -typedef struct -{ - // memory for lifted integrators - struct blasfeo_dmat *S_forw; // forward sensitivities - struct blasfeo_dmat *JGK; // jacobian of G over K (nx*ns, nx*ns) - struct blasfeo_dmat *JGf; // jacobian of G over x and u (nx*ns, nx+nu); - struct blasfeo_dmat *JKf; // jacobian of K over x and u (nx*ns, nx+nu); - - struct blasfeo_dvec *K; // internal variables (nx*ns) - struct blasfeo_dvec *x; // states (nx) -- for expansion step - struct blasfeo_dvec *u; // controls (nu) -- for expansion step - - int update_sens; - // int init_K; - - double time_sim; - double time_ad; - double time_la; - -} sim_lifted_irk_memory; - - - -/* dims */ -void sim_lifted_irk_dims_set(void *config_, void *dims_, const char *field, const int *value); -void sim_lifted_irk_dims_get(void *config_, void *dims_, const char *field, int* value); - -acados_size_t sim_lifted_irk_dims_calculate_size(); -// -void *sim_lifted_irk_dims_assign(void* config_, void *raw_memory); - -/* model */ -// -acados_size_t sim_lifted_irk_model_calculate_size(void *config, void *dims); -// -void *sim_lifted_irk_model_assign(void *config, void *dims, void *raw_memory); -// -int sim_lifted_irk_model_set(void *model_, const char *field, void *value); - -/* opts */ -// -acados_size_t sim_lifted_irk_opts_calculate_size(void *config, void *dims); -// -void *sim_lifted_irk_opts_assign(void *config, void *dims, void *raw_memory); -// -void sim_lifted_irk_opts_initialize_default(void *config, void *dims, void *opts_); -// -void sim_lifted_irk_opts_update(void *config_, void *dims, void *opts_); -// -void sim_lifted_irk_opts_set(void *config_, void *opts_, const char *field, void *value); - -/* memory */ -// -acados_size_t sim_lifted_irk_memory_calculate_size(void *config, void *dims, void *opts_); -// -void *sim_lifted_irk_memory_assign(void *config, void *dims, void *opts_, void *raw_memory); - -/* workspace */ -// -acados_size_t sim_lifted_irk_workspace_calculate_size(void *config, void *dims, void *opts_); -// -void sim_lifted_irk_config_initialize_default(void *config); - -/* solver */ -// -int sim_lifted_irk(void *config, sim_in *in, sim_out *out, void *opts_, - void *mem_, void *work_); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_SIM_SIM_LIFTED_IRK_INTEGRATOR_H_ diff --git a/third_party/acados/include/acados/utils/external_function_generic.h b/third_party/acados/include/acados/utils/external_function_generic.h deleted file mode 100644 index 1e68dc1..0000000 --- a/third_party/acados/include/acados/utils/external_function_generic.h +++ /dev/null @@ -1,242 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_UTILS_EXTERNAL_FUNCTION_GENERIC_H_ -#define ACADOS_UTILS_EXTERNAL_FUNCTION_GENERIC_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include "acados/utils/types.h" - -/************************************************ - * generic external function - ************************************************/ - -// type of arguments -typedef enum { - COLMAJ, - BLASFEO_DMAT, - BLASFEO_DVEC, - COLMAJ_ARGS, - BLASFEO_DMAT_ARGS, - BLASFEO_DVEC_ARGS, - IGNORE_ARGUMENT -} ext_fun_arg_t; - -struct colmaj_args -{ - double *A; - int lda; -}; - -struct blasfeo_dmat_args -{ - struct blasfeo_dmat *A; - int ai; - int aj; -}; - -struct blasfeo_dvec_args -{ - struct blasfeo_dvec *x; - int xi; -}; - -// prototype of an external function -typedef struct -{ - // public members (have to be before private ones) - void (*evaluate)(void *, ext_fun_arg_t *, void **, ext_fun_arg_t *, void **); - // private members - // ..... -} external_function_generic; - - - -/************************************************ - * generic external parametric function - ************************************************/ - -// prototype of a parametric external function -typedef struct -{ - // public members for core (have to be before private ones) - void (*evaluate)(void *, ext_fun_arg_t *, void **, ext_fun_arg_t *, void **); - // public members for interfaces - void (*get_nparam)(void *, int *); - void (*set_param)(void *, double *); - void (*set_param_sparse)(void *, int n_update, int *idx, double *); - // private members - void *ptr_ext_mem; // pointer to external memory - int (*fun)(void **, void **, void *); - double *p; // parameters - int np; // number of parameters - // ..... -} external_function_param_generic; - -// -acados_size_t external_function_param_generic_struct_size(); -// -void external_function_param_generic_set_fun(external_function_param_generic *fun, void *value); -// -acados_size_t external_function_param_generic_calculate_size(external_function_param_generic *fun, int np); -// -void external_function_param_generic_assign(external_function_param_generic *fun, void *mem); -// -void external_function_param_generic_wrapper(void *self, ext_fun_arg_t *type_in, void **in, ext_fun_arg_t *type_out, void **out); -// -void external_function_param_generic_get_nparam(void *self, int *np); -// -void external_function_param_generic_set_param(void *self, double *p); - - -/************************************************ - * casadi external function - ************************************************/ - -typedef struct -{ - // public members (have to be the same as in the prototype, and before the private ones) - void (*evaluate)(void *, ext_fun_arg_t *, void **, ext_fun_arg_t *, void **); - // private members - void *ptr_ext_mem; // pointer to external memory - int (*casadi_fun)(const double **, double **, int *, double *, void *); - int (*casadi_work)(int *, int *, int *, int *); - const int *(*casadi_sparsity_in)(int); - const int *(*casadi_sparsity_out)(int); - int (*casadi_n_in)(void); - int (*casadi_n_out)(void); - double **args; - double **res; - double *w; - int *iw; - int *args_size; // size of args[i] - int *res_size; // size of res[i] - int args_num; // number of args arrays - int args_size_tot; // total size of args arrays - int res_num; // number of res arrays - int res_size_tot; // total size of res arrays - int in_num; // number of input arrays - int out_num; // number of output arrays - int iw_size; // number of ints for worksapce - int w_size; // number of doubles for workspace -} external_function_casadi; - -// -acados_size_t external_function_casadi_struct_size(); -// -void external_function_casadi_set_fun(external_function_casadi *fun, void *value); -// -void external_function_casadi_set_work(external_function_casadi *fun, void *value); -// -void external_function_casadi_set_sparsity_in(external_function_casadi *fun, void *value); -// -void external_function_casadi_set_sparsity_out(external_function_casadi *fun, void *value); -// -void external_function_casadi_set_n_in(external_function_casadi *fun, void *value); -// -void external_function_casadi_set_n_out(external_function_casadi *fun, void *value); -// -acados_size_t external_function_casadi_calculate_size(external_function_casadi *fun); -// -void external_function_casadi_assign(external_function_casadi *fun, void *mem); -// -void external_function_casadi_wrapper(void *self, ext_fun_arg_t *type_in, void **in, - ext_fun_arg_t *type_out, void **out); - -/************************************************ - * casadi external parametric function - ************************************************/ - -typedef struct -{ - // public members for core (have to be the same as in the prototype, and before the private ones) - void (*evaluate)(void *, ext_fun_arg_t *, void **, ext_fun_arg_t *, void **); - // public members for interfaces - void (*get_nparam)(void *, int *); - void (*set_param)(void *, double *); - void (*set_param_sparse)(void *, int n_update, int *idx, double *); - // private members - void *ptr_ext_mem; // pointer to external memory - int (*casadi_fun)(const double **, double **, int *, double *, void *); - int (*casadi_work)(int *, int *, int *, int *); - const int *(*casadi_sparsity_in)(int); - const int *(*casadi_sparsity_out)(int); - int (*casadi_n_in)(void); - int (*casadi_n_out)(void); - double **args; - double **res; - double *w; - int *iw; - int *args_size; // size of args[i] - int *res_size; // size of res[i] - int args_num; // number of args arrays - int args_size_tot; // total size of args arrays - int res_num; // number of res arrays - int res_size_tot; // total size of res arrays - int in_num; // number of input arrays - int out_num; // number of output arrays - int iw_size; // number of ints for worksapce - int w_size; // number of doubles for workspace - int np; // number of parameters -} external_function_param_casadi; - -// -acados_size_t external_function_param_casadi_struct_size(); -// -void external_function_param_casadi_set_fun(external_function_param_casadi *fun, void *value); -// -void external_function_param_casadi_set_work(external_function_param_casadi *fun, void *value); -// -void external_function_param_casadi_set_sparsity_in(external_function_param_casadi *fun, void *value); -// -void external_function_param_casadi_set_sparsity_out(external_function_param_casadi *fun, void *value); -// -void external_function_param_casadi_set_n_in(external_function_param_casadi *fun, void *value); -// -void external_function_param_casadi_set_n_out(external_function_param_casadi *fun, void *value); -// -acados_size_t external_function_param_casadi_calculate_size(external_function_param_casadi *fun, int np); -// -void external_function_param_casadi_assign(external_function_param_casadi *fun, void *mem); -// -void external_function_param_casadi_wrapper(void *self, ext_fun_arg_t *type_in, void **in, - ext_fun_arg_t *type_out, void **out); -// -void external_function_param_casadi_get_nparam(void *self, int *np); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_UTILS_EXTERNAL_FUNCTION_GENERIC_H_ diff --git a/third_party/acados/include/acados/utils/math.h b/third_party/acados/include/acados/utils/math.h deleted file mode 100644 index 7156a82..0000000 --- a/third_party/acados/include/acados/utils/math.h +++ /dev/null @@ -1,103 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - -#ifndef ACADOS_UTILS_MATH_H_ -#define ACADOS_UTILS_MATH_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include "acados/utils/types.h" - -#if defined(__MABX2__) -double fmax(double a, double b); -int isnan(double x); -#endif - -#define MIN(a,b) (((a)<(b))?(a):(b)) -#define MAX(a,b) (((a)>(b))?(a):(b)) - -void dgemm_nn_3l(int m, int n, int k, double *A, int lda, double *B, int ldb, double *C, int ldc); -// void dgemv_n_3l(int m, int n, double *A, int lda, double *x, double *y); -// void dgemv_t_3l(int m, int n, double *A, int lda, double *x, double *y); -// void dcopy_3l(int n, double *x, int incx, double *y, int incy); -void daxpy_3l(int n, double da, double *dx, double *dy); -void dscal_3l(int n, double da, double *dx); -double twonormv(int n, double *ptrv); - -/* copies a matrix into another matrix */ -void dmcopy(int row, int col, double *ptrA, int lda, double *ptrB, int ldb); - -/* solution of a system of linear equations */ -void dgesv_3l(int n, int nrhs, double *A, int lda, int *ipiv, double *B, int ldb, int *info); - -/* matrix exponential */ -void expm(int row, double *A); - -int idamax_3l(int n, double *x); - -void dswap_3l(int n, double *x, int incx, double *y, int incy); - -void dger_3l(int m, int n, double alpha, double *x, int incx, double *y, int incy, double *A, - int lda); - -void dgetf2_3l(int m, int n, double *A, int lda, int *ipiv, int *info); - -void dlaswp_3l(int n, double *A, int lda, int k1, int k2, int *ipiv); - -void dtrsm_l_l_n_u_3l(int m, int n, double *A, int lda, double *B, int ldb); - -void dgetrs_3l(int n, int nrhs, double *A, int lda, int *ipiv, double *B, int ldb); - -void dgesv_3l(int n, int nrhs, double *A, int lda, int *ipiv, double *B, int ldb, int *info); - -double onenorm(int row, int col, double *ptrA); - -// double twonormv(int n, double *ptrv); - -void padeapprox(int m, int row, double *A); - -void expm(int row, double *A); - -// void d_compute_qp_size_ocp2dense_rev(int N, int *nx, int *nu, int *nb, int **hidxb, int *ng, -// int *nvd, int *ned, int *nbd, int *ngd); - -void acados_eigen_decomposition(int dim, double *A, double *V, double *d, double *e); - -double minimum_of_doubles(double *x, int n); - -void neville_algorithm(double xx, int n, double *x, double *Q, double *out); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_UTILS_MATH_H_ diff --git a/third_party/acados/include/acados/utils/mem.h b/third_party/acados/include/acados/utils/mem.h deleted file mode 100644 index 681a371..0000000 --- a/third_party/acados/include/acados/utils/mem.h +++ /dev/null @@ -1,110 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_UTILS_MEM_H_ -#define ACADOS_UTILS_MEM_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include -#include - -#include "types.h" - -// blasfeo -#include "blasfeo/include/blasfeo_d_aux.h" -#include "blasfeo/include/blasfeo_d_aux_ext_dep.h" - -// TODO(dimitris): probably does not belong here -typedef struct -{ - int (*fun)(void *); - acados_size_t (*calculate_args_size)(void *); - void *(*assign_args)(void *); - void (*initialize_default_args)(void *); - acados_size_t (*calculate_memory_size)(void *); - void *(*assign_memory)(void *); - acados_size_t (*calculate_workspace_size)(void *); -} module_solver; - -// make int counter of memory multiple of a number (typically 8 or 64) -void make_int_multiple_of(acados_size_t num, acados_size_t *size); - -// align char pointer to number (typically 8 for pointers and doubles, -// 64 for blasfeo structs) and return offset -int align_char_to(int num, char **c_ptr); - -// switch between malloc and calloc (for valgrinding) -void *acados_malloc(size_t nitems, acados_size_t size); - -// uses always calloc -void *acados_calloc(size_t nitems, acados_size_t size); - -// allocate vector of pointers to vectors of doubles and advance pointer -void assign_and_advance_double_ptrs(int n, double ***v, char **ptr); - -// allocate vector of pointers to vectors of ints and advance pointer -void assign_and_advance_int_ptrs(int n, int ***v, char **ptr); - -// allocate vector of pointers to strvecs and advance pointer -void assign_and_advance_blasfeo_dvec_structs(int n, struct blasfeo_dvec **sv, char **ptr); - -// allocate vector of pointers to strmats and advance pointer -void assign_and_advance_blasfeo_dmat_structs(int n, struct blasfeo_dmat **sm, char **ptr); - -// allocate vector of pointers to vector of pointers to strmats and advance pointer -void assign_and_advance_blasfeo_dmat_ptrs(int n, struct blasfeo_dmat ***sm, char **ptr); - -// allocate vector of chars and advance pointer -void assign_and_advance_char(int n, char **v, char **ptr); - -// allocate vector of ints and advance pointer -void assign_and_advance_int(int n, int **v, char **ptr); - -// allocate vector of bools and advance pointer -void assign_and_advance_bool(int n, bool **v, char **ptr); - -// allocate vector of doubles and advance pointer -void assign_and_advance_double(int n, double **v, char **ptr); - -// allocate strvec and advance pointer -void assign_and_advance_blasfeo_dvec_mem(int n, struct blasfeo_dvec *sv, char **ptr); - -// allocate strmat and advance pointer -void assign_and_advance_blasfeo_dmat_mem(int m, int n, struct blasfeo_dmat *sA, char **ptr); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_UTILS_MEM_H_ diff --git a/third_party/acados/include/acados/utils/print.h b/third_party/acados/include/acados/utils/print.h deleted file mode 100644 index 824d3ce..0000000 --- a/third_party/acados/include/acados/utils/print.h +++ /dev/null @@ -1,110 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_UTILS_PRINT_H_ -#define ACADOS_UTILS_PRINT_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include "acados/dense_qp/dense_qp_common.h" -#include "acados/ocp_nlp/ocp_nlp_common.h" -#include "acados/ocp_qp/ocp_qp_common.h" -#include "acados/ocp_qp/ocp_qp_common_frontend.h" -#include "acados/utils/types.h" - -// void print_matrix(char *file_name, const real_t *matrix, const int_t nrows, const int_t ncols); - -// void print_matrix_name(char *file_name, char *name, const real_t *matrix, const int_t nrows, -// const int_t ncols); - -// void print_int_matrix(char *file_name, const int_t *matrix, const int_t nrows, const int_t ncols); - -// void print_array(char *file_name, real_t *array, int_t size); - -// void print_int_array(char *file_name, const int_t *array, int_t size); - -void read_matrix(const char *file_name, real_t *array, const int_t nrows, const int_t ncols); - -void write_double_vector_to_txt(real_t *vec, int_t n, const char *fname); - -// ocp nlp -// TODO(andrea): inconsistent naming -void ocp_nlp_dims_print(ocp_nlp_dims *dims); -// TODO(andrea): inconsistent naming -void ocp_nlp_out_print(ocp_nlp_dims *dims, ocp_nlp_out *nlp_out); -// TODO(andrea): inconsistent naming -void ocp_nlp_res_print(ocp_nlp_dims *dims, ocp_nlp_res *nlp_res); - -// ocp qp -// TODO: move printing routines below that print qp structures to HPIPM! -void print_ocp_qp_dims(ocp_qp_dims *dims); - -// void print_dense_qp_dims(dense_qp_dims *dims); - -void print_ocp_qp_in(ocp_qp_in *qp_in); - -void print_ocp_qp_in_to_file(FILE *file, ocp_qp_in *qp_in); - -void print_ocp_qp_out(ocp_qp_out *qp_out); - -void print_ocp_qp_out_to_file(FILE *file, ocp_qp_out *qp_out); - -void print_ocp_qp_res(ocp_qp_res *qp_res); - -void print_dense_qp_in(dense_qp_in *qp_in); -// void print_ocp_qp_in_to_string(char string_out[], ocp_qp_in *qp_in); - -// void print_ocp_qp_out_to_string(char string_out[], ocp_qp_out *qp_out); - -// void print_colmaj_ocp_qp_in(colmaj_ocp_qp_in *qp); - -// void print_colmaj_ocp_qp_in_to_file(colmaj_ocp_qp_in *qp); - -// void print_colmaj_ocp_qp_out(char *filename, colmaj_ocp_qp_in *qp, colmaj_ocp_qp_out *out); - -void print_qp_info(qp_info *info); - -// void acados_warning(char warning_string[]); - -// void acados_error(char error_string[]); - -// void acados_not_implemented(char feature_string[]); - -// blasfeo -// void print_blasfeo_target(); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_UTILS_PRINT_H_ diff --git a/third_party/acados/include/acados/utils/strsep.h b/third_party/acados/include/acados/utils/strsep.h deleted file mode 100644 index 62bdfb4..0000000 --- a/third_party/acados/include/acados/utils/strsep.h +++ /dev/null @@ -1,69 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_UTILS_STRSEP_H_ -#define ACADOS_UTILS_STRSEP_H_ - -#ifdef __cplusplus -#include -#define STD(x) std::x -namespace std -{ -#else -#include -#define STD(x) x -#endif - -char* strsep_acados(char** stringp, const char* delim) -{ - char* result; - - if ((stringp == NULL) || (*stringp == NULL)) return NULL; - - result = *stringp; - - while (**stringp && !STD(strchr)(delim, **stringp)) ++*stringp; - - if (**stringp) - *(*stringp)++ = '\0'; - else - *stringp = NULL; - - return result; -} - -#ifdef __cplusplus -} // namespace std -#endif - -#undef STD - -#endif // ACADOS_UTILS_STRSEP_H_ diff --git a/third_party/acados/include/acados/utils/timing.h b/third_party/acados/include/acados/utils/timing.h deleted file mode 100644 index b095593..0000000 --- a/third_party/acados/include/acados/utils/timing.h +++ /dev/null @@ -1,122 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_UTILS_TIMING_H_ -#define ACADOS_UTILS_TIMING_H_ - -#include "acados/utils/types.h" - -#ifdef __cplusplus -extern "C" { -#endif - -#ifdef MEASURE_TIMINGS -#if (defined _WIN32 || defined _WIN64) && !(defined __MINGW32__ || defined __MINGW64__) - -/* Use Windows QueryPerformanceCounter for timing. */ -#include - -/** A structure for keeping internal timer data. */ -typedef struct acados_timer_ -{ - LARGE_INTEGER tic; - LARGE_INTEGER toc; - LARGE_INTEGER freq; -} acados_timer; - -#elif defined(__APPLE__) - -#include - -/** A structure for keeping internal timer data. */ -typedef struct acados_timer_ -{ - uint64_t tic; - uint64_t toc; - mach_timebase_info_data_t tinfo; -} acados_timer; - -#elif defined(__MABX2__) - -#include - -typedef struct acados_timer_ -{ - double time; -} acados_timer; - -#else - -/* Use POSIX clock_gettime() for timing on non-Windows machines. */ -#include - -#if (__STDC_VERSION__ >= 199901L) && !(defined __MINGW32__ || defined __MINGW64__) // C99 Mode - -#include -#include - -typedef struct acados_timer_ -{ - struct timeval tic; - struct timeval toc; -} acados_timer; - -#else // ANSI C Mode - -/** A structure for keeping internal timer data. */ -typedef struct acados_timer_ -{ - struct timespec tic; - struct timespec toc; -} acados_timer; - -#endif // __STDC_VERSION__ >= 199901L - -#endif // (defined _WIN32 || defined _WIN64) - -#else - -// Dummy type when timings are off -typedef real_t acados_timer; - -#endif // MEASURE_TIMINGS - -/** A function for measurement of the current time. */ -void acados_tic(acados_timer* t); - -/** A function which returns the elapsed time. */ -real_t acados_toc(acados_timer* t); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_UTILS_TIMING_H_ diff --git a/third_party/acados/include/acados/utils/types.h b/third_party/acados/include/acados/utils/types.h deleted file mode 100644 index a27ef9e..0000000 --- a/third_party/acados/include/acados/utils/types.h +++ /dev/null @@ -1,91 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef ACADOS_UTILS_TYPES_H_ -#define ACADOS_UTILS_TYPES_H_ - -/* Symbol visibility in DLLs */ -#ifndef ACADOS_SYMBOL_EXPORT - #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) - #if defined(STATIC_LINKED) - #define ACADOS_SYMBOL_EXPORT - #else - #define ACADOS_SYMBOL_EXPORT __declspec(dllexport) - #endif - #elif defined(__GNUC__) && ((__GNUC__ >= 4) || (__GNUC__ == 3 && __GNUC_MINOR__ >= 4)) - #define ACADOS_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) - #else - #define ACADOS_SYMBOL_EXPORT - #endif -#endif - -#ifdef __cplusplus -extern "C" { -#endif - -#include -#include - -#define MAX_STR_LEN 256 -#define ACADOS_EPS 1e-12 -#define ACADOS_NEG_INFTY -1.0e9 -#define ACADOS_POS_INFTY +1.0e9 -#define UNUSED(x) ((void)(x)) - - - -typedef double real_t; -typedef int int_t; -typedef size_t acados_size_t; - - -typedef int (*casadi_function_t)(const double** arg, double** res, int* iw, double* w, void* mem); - - - -// enum of return values -enum return_values -{ - ACADOS_SUCCESS, - ACADOS_NAN_DETECTED, - ACADOS_MAXITER, - ACADOS_MINSTEP, - ACADOS_QP_FAILURE, - ACADOS_READY, -}; - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // ACADOS_UTILS_TYPES_H_ diff --git a/third_party/acados/include/acados_c/condensing_interface.h b/third_party/acados/include/acados_c/condensing_interface.h deleted file mode 100644 index b430207..0000000 --- a/third_party/acados/include/acados_c/condensing_interface.h +++ /dev/null @@ -1,81 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef INTERFACES_ACADOS_C_CONDENSING_INTERFACE_H_ -#define INTERFACES_ACADOS_C_CONDENSING_INTERFACE_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include "acados/ocp_qp/ocp_qp_full_condensing.h" -#include "acados/ocp_qp/ocp_qp_partial_condensing.h" - -typedef enum { - PARTIAL_CONDENSING, - FULL_CONDENSING, -} condensing_t; - -typedef struct -{ - condensing_t condensing_type; -} condensing_plan; - -typedef struct -{ - ocp_qp_xcond_config *config; - void *dims; - void *opts; - void *mem; - void *work; -} condensing_module; - -ocp_qp_xcond_config *ocp_qp_condensing_config_create(condensing_plan *plan); -// -void *ocp_qp_condensing_opts_create(ocp_qp_xcond_config *config, void *dims_); -// -acados_size_t ocp_qp_condensing_calculate_size(ocp_qp_xcond_config *config, void *dims_, void *opts_); -// -condensing_module *ocp_qp_condensing_assign(ocp_qp_xcond_config *config, void *dims_, - void *opts_, void *raw_memory); -// -condensing_module *ocp_qp_condensing_create(ocp_qp_xcond_config *config, void *dims_, - void *opts_); -// -int ocp_qp_condense(condensing_module *module, void *qp_in, void *qp_out); -// -int ocp_qp_expand(condensing_module *module, void *qp_in, void *qp_out); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // INTERFACES_ACADOS_C_CONDENSING_INTERFACE_H_ diff --git a/third_party/acados/include/acados_c/dense_qp_interface.h b/third_party/acados/include/acados_c/dense_qp_interface.h deleted file mode 100644 index b3af4bf..0000000 --- a/third_party/acados/include/acados_c/dense_qp_interface.h +++ /dev/null @@ -1,91 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef INTERFACES_ACADOS_C_DENSE_QP_INTERFACE_H_ -#define INTERFACES_ACADOS_C_DENSE_QP_INTERFACE_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include "acados/dense_qp/dense_qp_common.h" - -typedef enum { DENSE_QP_HPIPM, DENSE_QP_QORE, DENSE_QP_QPOASES, DENSE_QP_OOQP, DENSE_QP_DAQP } dense_qp_solver_t; - -typedef struct -{ - dense_qp_solver_t qp_solver; -} dense_qp_solver_plan; - -typedef struct -{ - qp_solver_config *config; - void *dims; - void *opts; - void *mem; - void *work; -} dense_qp_solver; - -qp_solver_config *dense_qp_config_create(dense_qp_solver_plan *plan); -// -dense_qp_dims *dense_qp_dims_create(); -// -dense_qp_in *dense_qp_in_create(qp_solver_config *config, dense_qp_dims *dims); -// -dense_qp_out *dense_qp_out_create(qp_solver_config *config, dense_qp_dims *dims); -// -void *dense_qp_opts_create(qp_solver_config *config, dense_qp_dims *dims); -// -acados_size_t dense_qp_calculate_size(qp_solver_config *config, dense_qp_dims *dims, void *opts_); -// -dense_qp_solver *dense_qp_assign(qp_solver_config *config, dense_qp_dims *dims, void *opts_, - void *raw_memory); -// -dense_qp_solver *dense_qp_create(qp_solver_config *config, dense_qp_dims *dims, void *opts_); -// -int dense_qp_solve(dense_qp_solver *solver, dense_qp_in *qp_in, dense_qp_out *qp_out); -// -void dense_qp_inf_norm_residuals(dense_qp_dims *dims, dense_qp_in *qp_in, dense_qp_out *qp_out, - double *res); -// -bool dense_qp_set_field_double_array(const char *field, double *arr, dense_qp_in *qp_in); -// -bool dense_qp_set_field_int_array(const char *field, int *arr, dense_qp_in *qp_in); -// -bool dense_qp_get_field_double_array(const char *field, dense_qp_in *qp_in, double *arr); -// -bool dense_qp_get_field_int_array(const char *field, dense_qp_in *qp_in, int *arr); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // INTERFACES_ACADOS_C_DENSE_QP_INTERFACE_H_ diff --git a/third_party/acados/include/acados_c/external_function_interface.h b/third_party/acados/include/acados_c/external_function_interface.h deleted file mode 100644 index d4f52db..0000000 --- a/third_party/acados/include/acados_c/external_function_interface.h +++ /dev/null @@ -1,89 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef INTERFACES_ACADOS_C_EXTERNAL_FUNCTION_INTERFACE_H_ -#define INTERFACES_ACADOS_C_EXTERNAL_FUNCTION_INTERFACE_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include "acados/utils/external_function_generic.h" - - - -/************************************************ - * generic external parametric function - ************************************************/ - -// -void external_function_param_generic_create(external_function_param_generic *fun, int np); -// -void external_function_param_generic_free(external_function_param_generic *fun); - - - -/************************************************ - * casadi external function - ************************************************/ - -// -void external_function_casadi_create(external_function_casadi *fun); -// -void external_function_casadi_free(external_function_casadi *fun); -// -void external_function_casadi_create_array(int size, external_function_casadi *funs); -// -void external_function_casadi_free_array(int size, external_function_casadi *funs); - - - -/************************************************ - * casadi external parametric function - ************************************************/ - -// -void external_function_param_casadi_create(external_function_param_casadi *fun, int np); -// -void external_function_param_casadi_free(external_function_param_casadi *fun); -// -void external_function_param_casadi_create_array(int size, external_function_param_casadi *funs, - int np); -// -void external_function_param_casadi_free_array(int size, external_function_param_casadi *funs); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // INTERFACES_ACADOS_C_EXTERNAL_FUNCTION_INTERFACE_H_ diff --git a/third_party/acados/include/acados_c/ocp_nlp_interface.h b/third_party/acados/include/acados_c/ocp_nlp_interface.h deleted file mode 100644 index dd3e596..0000000 --- a/third_party/acados/include/acados_c/ocp_nlp_interface.h +++ /dev/null @@ -1,428 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef INTERFACES_ACADOS_C_OCP_NLP_INTERFACE_H_ -#define INTERFACES_ACADOS_C_OCP_NLP_INTERFACE_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -// acados -#include "acados/ocp_nlp/ocp_nlp_common.h" -#include "acados/ocp_nlp/ocp_nlp_constraints_bgh.h" -#include "acados/sim/sim_erk_integrator.h" -#include "acados/sim/sim_irk_integrator.h" -#include "acados/sim/sim_lifted_irk_integrator.h" -#include "acados/sim/sim_gnsf.h" -#include "acados/utils/types.h" -// acados_c -#include "acados_c/ocp_qp_interface.h" -#include "acados_c/sim_interface.h" - - -/// Solution methods for optimal control problems. -typedef enum -{ - SQP, - SQP_RTI, - INVALID_NLP_SOLVER, -} ocp_nlp_solver_t; - - -/// Types of the cost function. -typedef enum -{ - LINEAR_LS, - NONLINEAR_LS, - CONVEX_OVER_NONLINEAR, - EXTERNAL, - INVALID_COST, -} ocp_nlp_cost_t; - - -/// Types of the system dynamics, discrete or continuous time. -typedef enum -{ - CONTINUOUS_MODEL, - DISCRETE_MODEL, - INVALID_DYNAMICS, -} ocp_nlp_dynamics_t; - - -/// Constraint types -typedef enum -{ - /// Comprises simple bounds, polytopic constraints, - /// general non-linear constraints. - BGH, - - /// Comprises simple bounds, polytopic constraints, - /// general non-linear constraints, and positive definite constraints. - BGP, - - INVALID_CONSTRAINT, -} ocp_nlp_constraints_t; - - -/// Regularization types -typedef enum -{ - NO_REGULARIZE, - MIRROR, - PROJECT, - PROJECT_REDUC_HESS, - CONVEXIFY, - INVALID_REGULARIZE, -} ocp_nlp_reg_t; - - -/// Structure to store the configuration of a non-linear program -typedef struct ocp_nlp_plan_t -{ - /// QP solver configuration. - ocp_qp_solver_plan_t ocp_qp_solver_plan; - - /// Simulation solver configuration for each stage. - sim_solver_plan_t *sim_solver_plan; - - /// Nlp solver type. - ocp_nlp_solver_t nlp_solver; - - /// Regularization type, defaults to no regularization. - ocp_nlp_reg_t regularization; - - /// Cost type for each stage. - ocp_nlp_cost_t *nlp_cost; - - /// Dynamics type for each stage. - ocp_nlp_dynamics_t *nlp_dynamics; - - /// Constraints type for each stage. - ocp_nlp_constraints_t *nlp_constraints; - - /// Horizon length. - int N; - -} ocp_nlp_plan_t; - - -/// Structure to store the state/configuration for the non-linear programming solver -typedef struct ocp_nlp_solver -{ - ocp_nlp_config *config; - void *dims; - void *opts; - void *mem; - void *work; -} ocp_nlp_solver; - - -/// Constructs an empty plan struct (user nlp configuration), all fields are set to a -/// default/invalid state. -/// -/// \param N Horizon length -ACADOS_SYMBOL_EXPORT ocp_nlp_plan_t *ocp_nlp_plan_create(int N); - -/// Destructor for plan struct, frees memory. -/// -/// \param plan_ The plan struct to destroy. -ACADOS_SYMBOL_EXPORT void ocp_nlp_plan_destroy(void* plan_); - - -/// Constructs an nlp configuration struct from a plan. -/// -/// \param plan The plan (user nlp configuration). -ACADOS_SYMBOL_EXPORT ocp_nlp_config *ocp_nlp_config_create(ocp_nlp_plan_t plan); - -/// Desctructor of the nlp configuration. -/// -/// \param config_ The configuration struct. -ACADOS_SYMBOL_EXPORT void ocp_nlp_config_destroy(void *config_); - - -/// Constructs an struct that contains the dimensions of the variables. -/// -/// \param config_ The configuration struct. -ACADOS_SYMBOL_EXPORT ocp_nlp_dims *ocp_nlp_dims_create(void *config_); - -/// Destructor of The dimension struct. -/// -/// \param dims_ The dimension struct. -ACADOS_SYMBOL_EXPORT void ocp_nlp_dims_destroy(void *dims_); - - -/// Constructs an input struct for a non-linear programs. -/// -/// \param config The configuration struct. -/// \param dims The dimension struct. -ACADOS_SYMBOL_EXPORT ocp_nlp_in *ocp_nlp_in_create(ocp_nlp_config *config, ocp_nlp_dims *dims); - -/// Destructor of the inputs struct. -/// -/// \param in The inputs struct. -ACADOS_SYMBOL_EXPORT void ocp_nlp_in_destroy(void *in); - - -/// Sets the sampling times for the given stage. -/// -/// \param config The configuration struct. -/// \param dims The dimension struct. -/// \param in The inputs struct. -/// \param stage Stage number. -/// \param field Has to be "Ts" (TBC other options). -/// \param value The sampling times (floating point). -ACADOS_SYMBOL_EXPORT void ocp_nlp_in_set(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in, int stage, - const char *field, void *value); - -/// -// void ocp_nlp_in_get(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in, int stage, -// const char *field, void *value); - -/// Sets the function pointers to the dynamics functions for the given stage. -/// -/// \param config The configuration struct. -/// \param dims The dimension struct. -/// \param in The inputs struct. -/// \param stage Stage number. -/// \param fun_type The name of the function type, either impl_ode_fun, -/// impl_ode_fun_jac_x_xdot, impl_ode_jac_x_xdot_u (TBC) -/// \param fun_ptr Function pointer to the dynamics function. -ACADOS_SYMBOL_EXPORT int ocp_nlp_dynamics_model_set(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in, - int stage, const char *fun_type, void *fun_ptr); - - -/// Sets the function pointers to the cost functions for the given stage. -/// -/// \param config The configuration struct. -/// \param dims The dimension struct. -/// \param in The inputs struct. -/// \param stage Stage number. -/// \param field The name of the field, either nls_res_jac, -/// y_ref, W (others TBC) -/// \param value Cost values. -ACADOS_SYMBOL_EXPORT int ocp_nlp_cost_model_set(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in, - int stage, const char *field, void *value); - - -/// Sets the function pointers to the constraints functions for the given stage. -/// -/// \param config The configuration struct. -/// \param dims The dimension struct. -/// \param in The inputs struct. -/// \param stage Stage number. -/// \param field The name of the field, either lb, ub (others TBC) -/// \param value Constraints function or values. -ACADOS_SYMBOL_EXPORT int ocp_nlp_constraints_model_set(ocp_nlp_config *config, ocp_nlp_dims *dims, - ocp_nlp_in *in, int stage, const char *field, void *value); - -/// -ACADOS_SYMBOL_EXPORT void ocp_nlp_constraints_model_get(ocp_nlp_config *config, ocp_nlp_dims *dims, - ocp_nlp_in *in, int stage, const char *field, void *value); - -/* out */ - -/// Constructs an output struct for the non-linear program. -/// -/// \param config The configuration struct. -/// \param dims The dimension struct. -ACADOS_SYMBOL_EXPORT ocp_nlp_out *ocp_nlp_out_create(ocp_nlp_config *config, ocp_nlp_dims *dims); - -/// Destructor of the output struct. -/// -/// \param out The output struct. -ACADOS_SYMBOL_EXPORT void ocp_nlp_out_destroy(void *out); - - -/// Sets fields in the output struct of an nlp solver, used to initialize the solver. -/// -/// \param config The configuration struct. -/// \param dims The dimension struct. -/// \param out The output struct. -/// \param stage Stage number. -/// \param field The name of the field, either x, u, pi. -/// \param value Initialization values. -ACADOS_SYMBOL_EXPORT void ocp_nlp_out_set(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_out *out, - int stage, const char *field, void *value); - - -/// Gets values of fields in the output struct of an nlp solver. -/// -/// \param config The configuration struct. -/// \param dims The dimension struct. -/// \param out The output struct. -/// \param stage Stage number. -/// \param field The name of the field, either x, u, z, pi. -/// \param value Pointer to the output memory. -ACADOS_SYMBOL_EXPORT void ocp_nlp_out_get(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_out *out, - int stage, const char *field, void *value); - -// -ACADOS_SYMBOL_EXPORT void ocp_nlp_get_at_stage(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_solver *solver, - int stage, const char *field, void *value); - -// TODO(andrea): remove this once/if the MATLAB interface uses the new setters below? -ACADOS_SYMBOL_EXPORT int ocp_nlp_dims_get_from_attr(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_out *out, - int stage, const char *field); - -ACADOS_SYMBOL_EXPORT void ocp_nlp_constraint_dims_get_from_attr(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_out *out, - int stage, const char *field, int *dims_out); - -ACADOS_SYMBOL_EXPORT void ocp_nlp_cost_dims_get_from_attr(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_out *out, - int stage, const char *field, int *dims_out); - -ACADOS_SYMBOL_EXPORT void ocp_nlp_qp_dims_get_from_attr(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_out *out, - int stage, const char *field, int *dims_out); - -/* opts */ - -/// Creates an options struct for the non-linear program. -/// -/// \param config The configuration struct. -/// \param dims The dimension struct. -ACADOS_SYMBOL_EXPORT void *ocp_nlp_solver_opts_create(ocp_nlp_config *config, ocp_nlp_dims *dims); - -/// Destructor of the options. -/// -/// \param opts The options struct. -ACADOS_SYMBOL_EXPORT void ocp_nlp_solver_opts_destroy(void *opts); - -/// Sets an option. -/// -/// \param config The configuration struct. -/// \param opts_ The options struct. -/// \param field Name of the option. -/// \param value Value of the option. -ACADOS_SYMBOL_EXPORT void ocp_nlp_solver_opts_set(ocp_nlp_config *config, void *opts_, const char *field, void* value); - - -// ACADOS_SYMBOL_EXPORT void ocp_nlp_solver_opts_get(ocp_nlp_config *config, void *opts_, const char *field, void* value); - - -ACADOS_SYMBOL_EXPORT void ocp_nlp_solver_opts_set_at_stage(ocp_nlp_config *config, void *opts_, int stage, const char *field, void* value); - - -/// TBC -/// Updates the options. -/// -/// \param config The configuration struct. -/// \param dims The dimension struct. -/// \param opts_ The options struct. -ACADOS_SYMBOL_EXPORT void ocp_nlp_solver_opts_update(ocp_nlp_config *config, ocp_nlp_dims *dims, void *opts_); - - -/* solver */ - -/// Creates an ocp solver. -/// -/// \param config The configuration struct. -/// \param dims The dimension struct. -/// \param opts_ The options struct. -/// \return The solver. -ACADOS_SYMBOL_EXPORT ocp_nlp_solver *ocp_nlp_solver_create(ocp_nlp_config *config, ocp_nlp_dims *dims, void *opts_); - -/// Destructor of the solver. -/// -/// \param solver The solver struct. -ACADOS_SYMBOL_EXPORT void ocp_nlp_solver_destroy(void *solver); - -/// Solves the optimal control problem. Call ocp_nlp_precompute before -/// calling this functions (TBC). -/// -/// \param solver The solver struct. -/// \param nlp_in The inputs struct. -/// \param nlp_out The output struct. -ACADOS_SYMBOL_EXPORT int ocp_nlp_solve(ocp_nlp_solver *solver, ocp_nlp_in *nlp_in, ocp_nlp_out *nlp_out); - - - -/// Resets the memory of the QP solver -/// -/// \param solver The solver struct. -/// \param nlp_in The inputs struct. -/// \param nlp_out The output struct. -ACADOS_SYMBOL_EXPORT void ocp_nlp_solver_reset_qp_memory(ocp_nlp_solver *solver, ocp_nlp_in *nlp_in, ocp_nlp_out *nlp_out); - - -/// Performs precomputations for the solver. Needs to be called before -/// ocl_nlp_solve (TBC). -/// -/// \param solver The solver struct. -/// \param nlp_in The inputs struct. -/// \param nlp_out The output struct. -ACADOS_SYMBOL_EXPORT int ocp_nlp_precompute(ocp_nlp_solver *solver, ocp_nlp_in *nlp_in, ocp_nlp_out *nlp_out); - - -/// Computes cost function value. -/// -/// \param solver The solver struct. -/// \param nlp_in The inputs struct. -/// \param nlp_out The output struct. -ACADOS_SYMBOL_EXPORT void ocp_nlp_eval_cost(ocp_nlp_solver *solver, ocp_nlp_in *nlp_in, ocp_nlp_out *nlp_out); - - -/// Computes the residuals. -/// -/// \param solver The solver struct. -/// \param nlp_in The inputs struct. -/// \param nlp_out The output struct. -ACADOS_SYMBOL_EXPORT void ocp_nlp_eval_residuals(ocp_nlp_solver *solver, ocp_nlp_in *nlp_in, ocp_nlp_out *nlp_out); - - -// -ACADOS_SYMBOL_EXPORT void ocp_nlp_eval_param_sens(ocp_nlp_solver *solver, char *field, int stage, int index, ocp_nlp_out *sens_nlp_out); - -/* get */ -/// \param config The configuration struct. -/// \param solver The solver struct. -/// \param field Supports "sqp_iter", "status", "nlp_res", "time_tot", ... -/// \param return_value_ Pointer to the output memory. -ACADOS_SYMBOL_EXPORT void ocp_nlp_get(ocp_nlp_config *config, ocp_nlp_solver *solver, - const char *field, void *return_value_); - -/* set */ -/// Sets the initial guesses for the integrator for the given stage. -/// -/// \param config The configuration struct. -/// \param solver The ocp_nlp_solver struct. -/// \param stage Stage number. -/// \param field Supports "z_guess", "xdot_guess" (IRK), "phi_guess" (GNSF-IRK) -/// \param value The initial guess for the algebraic variables in the integrator (if continuous model is used). -ACADOS_SYMBOL_EXPORT void ocp_nlp_set(ocp_nlp_config *config, ocp_nlp_solver *solver, - int stage, const char *field, void *value); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // INTERFACES_ACADOS_C_OCP_NLP_INTERFACE_H_ diff --git a/third_party/acados/include/acados_c/ocp_qp_interface.h b/third_party/acados/include/acados_c/ocp_qp_interface.h deleted file mode 100644 index 3dc3f1a..0000000 --- a/third_party/acados/include/acados_c/ocp_qp_interface.h +++ /dev/null @@ -1,263 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef INTERFACES_ACADOS_C_OCP_QP_INTERFACE_H_ -#define INTERFACES_ACADOS_C_OCP_QP_INTERFACE_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include "acados/ocp_qp/ocp_qp_common.h" -#include "acados/ocp_qp/ocp_qp_xcond_solver.h" - - -/// QP solver types (Enumeration). -/// -/// Full list of fields: -/// PARTIAL_CONDENSING_HPIPM -/// PARTIAL_CONDENSING_HPMPC -/// PARTIAL_CONDENSING_OOQP -/// PARTIAL_CONDENSING_OSQP -/// PARTIAL_CONDENSING_QPDUNES -/// FULL_CONDENSING_HPIPM -/// FULL_CONDENSING_QPOASES -/// FULL_CONDENSING_QORE -/// FULL_CONDENSING_OOQP -/// INVALID_QP_SOLVER -/// -/// Note: In this enumeration the partial condensing solvers have to be -/// specified before the full condensing solvers. -typedef enum { - PARTIAL_CONDENSING_HPIPM, -#ifdef ACADOS_WITH_HPMPC - PARTIAL_CONDENSING_HPMPC, -#else - PARTIAL_CONDENSING_HPMPC_NOT_AVAILABLE, -#endif -#ifdef ACADOS_WITH_OOQP - PARTIAL_CONDENSING_OOQP, -#else - PARTIAL_CONDENSING_OOQP_NOT_AVAILABLE, -#endif -#ifdef ACADOS_WITH_OSQP - PARTIAL_CONDENSING_OSQP, -#else - PARTIAL_CONDENSING_OSQP_NOT_AVAILABLE, -#endif -#ifdef ACADOS_WITH_QPDUNES - PARTIAL_CONDENSING_QPDUNES, -#else - PARTIAL_CONDENSING_QPDUNES_NOT_AVAILABLE, -#endif - FULL_CONDENSING_HPIPM, -#ifdef ACADOS_WITH_QPOASES - FULL_CONDENSING_QPOASES, -#else - FULL_CONDENSING_QPOASES_NOT_AVAILABLE, -#endif -#ifdef ACADOS_WITH_DAQP - FULL_CONDENSING_DAQP, -#else - FULL_CONDENSING_DAQP_NOT_AVAILABLE, -#endif -#ifdef ACADOS_WITH_QORE - FULL_CONDENSING_QORE, -#else - FULL_CONDENSING_QORE_NOT_AVAILABLE, -#endif -#ifdef ACADOS_WITH_OOQP - FULL_CONDENSING_OOQP, -#else - FULL_CONDENSING_OOQP_NOT_AVAILABLE, -#endif - INVALID_QP_SOLVER, -} ocp_qp_solver_t; - - -/// Struct containing qp solver -typedef struct -{ - ocp_qp_solver_t qp_solver; -} ocp_qp_solver_plan_t; - - -/// Linear ocp configuration. -typedef struct -{ - ocp_qp_xcond_solver_config *config; - ocp_qp_xcond_solver_dims *dims; - void *opts; - void *mem; - void *work; -} ocp_qp_solver; - - -/// Initializes the qp solver configuration. -/// TBC should this be private/static - no, used in ocp_nlp -void ocp_qp_xcond_solver_config_initialize_from_plan( - ocp_qp_solver_t solver_name, ocp_qp_xcond_solver_config *solver_config); - -/// Constructs a qp solver config and Initializes with default values. -/// -/// \param plan The qp solver plan struct. -ocp_qp_xcond_solver_config *ocp_qp_xcond_solver_config_create(ocp_qp_solver_plan_t plan); - -/// Destructor for config struct, frees memory. -/// -/// \param config The config object to destroy. -void ocp_qp_xcond_solver_config_free(ocp_qp_xcond_solver_config *config); - - -/// Constructs a struct that contains the dimensions for the variables of the qp. -/// -/// \param N The number of variables. -ocp_qp_dims *ocp_qp_dims_create(int N); - -/// Destructor of The dimension struct. -/// -/// \param dims The dimension struct. -void ocp_qp_dims_free(void *dims); - -// -ocp_qp_xcond_solver_dims *ocp_qp_xcond_solver_dims_create(ocp_qp_xcond_solver_config *config, int N); -// -ocp_qp_xcond_solver_dims *ocp_qp_xcond_solver_dims_create_from_ocp_qp_dims( - ocp_qp_xcond_solver_config *config, ocp_qp_dims *dims); -// -void ocp_qp_xcond_solver_dims_free(ocp_qp_xcond_solver_dims *dims_); - -void ocp_qp_xcond_solver_dims_set(void *config_, ocp_qp_xcond_solver_dims *dims, - int stage, const char *field, int* value); - - -/// Constructs an input object for the qp. -/// -/// \param dims The dimension struct. -ocp_qp_in *ocp_qp_in_create(ocp_qp_dims *dims); - - -void ocp_qp_in_set(ocp_qp_xcond_solver_config *config, ocp_qp_in *in, - int stage, char *field, void *value); - -/// Destructor of the inputs struct. -/// -/// \param in_ The inputs struct. -void ocp_qp_in_free(void *in_); - - -/// Constructs an outputs object for the qp. -/// -/// \param dims The dimension struct. -ocp_qp_out *ocp_qp_out_create(ocp_qp_dims *dims); - -/// Destructor of the output struct. -/// -/// \param out_ The output struct. -void ocp_qp_out_free(void *out_); - - -/// Getter of output struct -void ocp_qp_out_get(ocp_qp_out *out, const char *field, void *value); - - -/// Constructs an options object for the qp. -/// -/// \param config The configuration struct. -/// \param dims The dimension struct. -void *ocp_qp_xcond_solver_opts_create(ocp_qp_xcond_solver_config *config, - ocp_qp_xcond_solver_dims *dims); - -/// Destructor of the options struct. -/// -/// \param opts The options struct to destroy. -void ocp_qp_xcond_solver_opts_free(ocp_qp_xcond_solver_opts *opts); - - -/// Setter of the options struct. -/// -/// \param opts The options struct. -void ocp_qp_xcond_solver_opts_set(ocp_qp_xcond_solver_config *config, - ocp_qp_xcond_solver_opts *opts, const char *field, void* value); - -/// TBC Should be private/static? -acados_size_t ocp_qp_calculate_size(ocp_qp_xcond_solver_config *config, ocp_qp_xcond_solver_dims *dims, void *opts_); - - -/// TBC Reserves memory? TBC Should this be private? -/// -/// \param config The configuration struct. -/// \param dims The dimension struct. -/// \param opts_ The options struct. -/// \param raw_memory Pointer to raw memory to assign to qp solver. -ocp_qp_solver *ocp_qp_assign(ocp_qp_xcond_solver_config *config, ocp_qp_xcond_solver_dims *dims, - void *opts_, void *raw_memory); - -/// Creates a qp solver. Reserves memory. -/// -/// \param config The configuration struct. -/// \param dims The dimension struct. -/// \param opts_ The options struct. -ocp_qp_solver *ocp_qp_create(ocp_qp_xcond_solver_config *config, - ocp_qp_xcond_solver_dims *dims, void *opts_); - - -/// Destroys a qp solver. Frees memory. -/// -/// \param solver The qp solver -void ocp_qp_solver_destroy(ocp_qp_solver *solver); - -void ocp_qp_x_cond_solver_free(ocp_qp_xcond_solver_config *config, - ocp_qp_xcond_solver_dims *dims, void *opts_); - - -/// Solves the qp. -/// -/// \param solver The solver. -/// \param qp_in The inputs struct. -/// \param qp_out The output struct. -int ocp_qp_solve(ocp_qp_solver *solver, ocp_qp_in *qp_in, ocp_qp_out *qp_out); - - -/// Calculates the infinity norm of the residuals. -/// -/// \param dims The dimension struct. -/// \param qp_in The inputs struct. -/// \param qp_out The output struct. -/// \param res Output array for the residuals. -void ocp_qp_inf_norm_residuals(ocp_qp_dims *dims, ocp_qp_in *qp_in, ocp_qp_out *qp_out, - double *res); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // INTERFACES_ACADOS_C_OCP_QP_INTERFACE_H_ diff --git a/third_party/acados/include/acados_c/sim_interface.h b/third_party/acados/include/acados_c/sim_interface.h deleted file mode 100644 index 09a05d6..0000000 --- a/third_party/acados/include/acados_c/sim_interface.h +++ /dev/null @@ -1,137 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -#ifndef INTERFACES_ACADOS_C_SIM_INTERFACE_H_ -#define INTERFACES_ACADOS_C_SIM_INTERFACE_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#include "acados/sim/sim_common.h" - - - -typedef enum -{ - ERK, - IRK, - GNSF, - LIFTED_IRK, - INVALID_SIM_SOLVER, -} sim_solver_t; - - - -typedef struct -{ - sim_solver_t sim_solver; -} sim_solver_plan_t; - - - -typedef struct -{ - sim_config *config; - void *dims; - void *opts; - void *mem; - void *work; -} sim_solver; - - - -/* config */ -// -ACADOS_SYMBOL_EXPORT sim_config *sim_config_create(sim_solver_plan_t plan); -// -ACADOS_SYMBOL_EXPORT void sim_config_destroy(void *config); - -/* dims */ -// -ACADOS_SYMBOL_EXPORT void *sim_dims_create(void *config_); -// -ACADOS_SYMBOL_EXPORT void sim_dims_destroy(void *dims); -// -ACADOS_SYMBOL_EXPORT void sim_dims_set(sim_config *config, void *dims, const char *field, const int* value); -// -ACADOS_SYMBOL_EXPORT void sim_dims_get(sim_config *config, void *dims, const char *field, int* value); -// -ACADOS_SYMBOL_EXPORT void sim_dims_get_from_attr(sim_config *config, void *dims, const char *field, int *dims_out); - -/* in */ -// -ACADOS_SYMBOL_EXPORT sim_in *sim_in_create(sim_config *config, void *dims); -// -ACADOS_SYMBOL_EXPORT void sim_in_destroy(void *out); -// -ACADOS_SYMBOL_EXPORT int sim_in_set(void *config_, void *dims_, sim_in *in, const char *field, void *value); - - -/* out */ -// -ACADOS_SYMBOL_EXPORT sim_out *sim_out_create(sim_config *config, void *dims); -// -ACADOS_SYMBOL_EXPORT void sim_out_destroy(void *out); -// -ACADOS_SYMBOL_EXPORT int sim_out_get(void *config, void *dims, sim_out *out, const char *field, void *value); - -/* opts */ -// -ACADOS_SYMBOL_EXPORT void *sim_opts_create(sim_config *config, void *dims); -// -ACADOS_SYMBOL_EXPORT void sim_opts_destroy(void *opts); -// -ACADOS_SYMBOL_EXPORT void sim_opts_set(sim_config *config, void *opts, const char *field, void *value); -// -ACADOS_SYMBOL_EXPORT void sim_opts_get(sim_config *config, void *opts, const char *field, void *value); - -/* solver */ -// -ACADOS_SYMBOL_EXPORT acados_size_t sim_calculate_size(sim_config *config, void *dims, void *opts_); -// -ACADOS_SYMBOL_EXPORT sim_solver *sim_assign(sim_config *config, void *dims, void *opts_, void *raw_memory); -// -ACADOS_SYMBOL_EXPORT sim_solver *sim_solver_create(sim_config *config, void *dims, void *opts_); -// -ACADOS_SYMBOL_EXPORT void sim_solver_destroy(void *solver); -// -ACADOS_SYMBOL_EXPORT int sim_solve(sim_solver *solver, sim_in *in, sim_out *out); -// -ACADOS_SYMBOL_EXPORT int sim_precompute(sim_solver *solver, sim_in *in, sim_out *out); -// -ACADOS_SYMBOL_EXPORT int sim_solver_set(sim_solver *solver, const char *field, void *value); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // INTERFACES_ACADOS_C_SIM_INTERFACE_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo.h b/third_party/acados/include/blasfeo/include/blasfeo.h deleted file mode 100644 index c854918..0000000 --- a/third_party/acados/include/blasfeo/include/blasfeo.h +++ /dev/null @@ -1,52 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#include "blasfeo_processor_features.h" -#include "blasfeo_target.h" -#include "blasfeo_block_size.h" -#include "blasfeo_stdlib.h" -#include "blasfeo_common.h" -#include "blasfeo_d_aux.h" -#include "blasfeo_d_aux_ext_dep.h" -#include "blasfeo_d_kernel.h" -#include "blasfeo_d_blas.h" -#include "blasfeo_s_aux.h" -#include "blasfeo_s_aux_ext_dep.h" -#include "blasfeo_s_kernel.h" -#include "blasfeo_s_blas.h" -#include "blasfeo_i_aux_ext_dep.h" -#include "blasfeo_v_aux_ext_dep.h" -#include "blasfeo_timing.h" -#include "blasfeo_memory.h" diff --git a/third_party/acados/include/blasfeo/include/blasfeo_block_size.h b/third_party/acados/include/blasfeo/include/blasfeo_block_size.h deleted file mode 100644 index 5d0907a..0000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_block_size.h +++ /dev/null @@ -1,447 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_BLOCK_SIZE_H_ -#define BLASFEO_BLOCK_SIZE_H_ - - - -#define D_EL_SIZE 8 // double precision -#define S_EL_SIZE 4 // single precision - - - -#if defined( TARGET_X64_INTEL_SKYLAKE_X ) -// common -#define CACHE_LINE_SIZE 64 // data cache size: 64 bytes -#define L1_CACHE_SIZE (32*1024) // L1 data cache size: 32 kB, 8-way -#define L2_CACHE_SIZE (256*1024) //(1024*1024) // L2 data cache size: 1 MB ; DTLB1 64*4 kB = 256 kB -#define LLC_CACHE_SIZE (6*1024*1024) //(8*1024*1024) // LLC cache size: 8 MB ; TLB 1536*4 kB = 6 MB -// double -#define D_PS 8 // panel size -#define D_PLD 8 // 4 // GCD of panel length -#define D_M_KERNEL 24 // max kernel size -#define D_N_KERNEL 8 // max kernel size -#define D_KC 128 //256 // 192 -#define D_NC 144 //72 //96 //72 // 120 // 512 -#define D_MC 2400 // 6000 -// single -#define S_PS 16 // panel size -#define S_PLD 4 // GCD of panel length TODO probably 16 when writing assebly -#define S_M_KERNEL 32 // max kernel size -#define S_N_KERNEL 8 // max kernel size -#define S_KC 128 //256 -#define S_NC 128 //144 -#define S_MC 3000 - -#elif defined( TARGET_X64_INTEL_HASWELL ) -// common -#define CACHE_LINE_SIZE 64 // data cache size: 64 bytes -#define L1_CACHE_SIZE (32*1024) // L1 data cache size: 32 kB, 8-way -#define L2_CACHE_SIZE (256*1024) // L2 data cache size: 256 kB ; DTLB1 64*4 kB = 256 kB -#define LLC_CACHE_SIZE (6*1024*1024) // LLC cache size: 6 MB ; TLB 1024*4 kB = 4 MB -// double -#define D_PS 4 // panel size -#define D_PLD 4 // 2 // GCD of panel length -#define D_M_KERNEL 12 // max kernel size -#define D_N_KERNEL 8 // max kernel size -#define D_KC 256 // 192 -#define D_NC 64 //96 //72 // 120 // 512 -#define D_MC 1500 -// single -#define S_PS 8 // panel size -#define S_PLD 4 // 2 // GCD of panel length -#define S_M_KERNEL 24 // max kernel size -#define S_N_KERNEL 8 // max kernel size -#define S_KC 256 -#define S_NC 144 -#define S_MC 3000 - -#elif defined( TARGET_X64_INTEL_SANDY_BRIDGE ) -// common -#define CACHE_LINE_SIZE 64 // data cache size: 64 bytes -#define L1_CACHE_SIZE (32*1024) // L1 data cache size: 32 kB, 8-way -#define L2_CACHE_SIZE (256*1024) // L2 data cache size: 256 kB ; DTLB1 64*4 kB = 256 kB -#define LLC_CACHE_SIZE (4*1024*1024) // LLC cache size: 4 MB ; TLB 1024*4 kB = 4 MB -// double -#define D_PS 4 // panel size -#define D_PLD 4 // 2 // GCD of panel length -#define D_M_KERNEL 8 // max kernel size -#define D_N_KERNEL 4 // max kernel size -#define D_KC 256 //320 //256 //320 -#define D_NC 72 //64 //72 //60 // 120 -#define D_MC 1000 // 800 -// single -#define S_PS 8 // panel size -#define S_PLD 4 // 2 // GCD of panel length -#define S_M_KERNEL 16 // max kernel size -#define S_N_KERNEL 8 // max kernel size -#define S_KC 256 -#define S_NC 144 -#define S_MC 2000 - -#elif defined( TARGET_X64_INTEL_CORE ) -// common -#define CACHE_LINE_SIZE 64 -#define L1_CACHE_SIZE (32*1024) // L1 data cache size: 32 kB -// double -#define D_PS 4 // panel size -#define D_PLD 4 // 2 // GCD of panel length -#define D_M_KERNEL 4 // max kernel size -#define D_N_KERNEL 4 // max kernel size -#define D_KC 256 -#define D_NC 128 // TODO these are just dummy -#define D_MC 3000 // TODO these are just dummy -// single -#define S_PS 4 -#define S_PLD 4 //2 -#define S_M_KERNEL 4 // max kernel size -#define S_N_KERNEL 4 // max kernel size -#define S_KC 256 -#define S_NC 128 // TODO these are just dummy -#define S_MC 3000 // TODO these are just dummy - -#elif defined( TARGET_X64_AMD_BULLDOZER ) -// common -#define CACHE_LINE_SIZE 64 -#define L1_CACHE_SIZE (32*1024) // L1 data cache size: 32 kB -// double -#define D_PS 4 // panel size -#define D_PLD 4 // 2 // GCD of panel length -#define D_M_KERNEL 4 // max kernel size -#define D_N_KERNEL 4 // max kernel size -#define D_KC 256 -#define D_NC 128 // TODO these are just dummy -#define D_MC 3000 // TODO these are just dummy -// single -#define S_PS 4 -#define S_PLD 4 //2 -#define S_M_KERNEL 4 // max kernel size -#define S_N_KERNEL 4 // max kernel size -#define S_KC 256 -#define S_NC 128 // TODO these are just dummy -#define S_MC 3000 // TODO these are just dummy - - -#elif defined( TARGET_X86_AMD_JAGUAR ) -// common -#define CACHE_LINE_SIZE 64 -#define L1_CACHE_SIZE (32*1024) // L1 data cache size: 32 kB -// double -#define D_PS 4 // panel size -#define D_PLD 4 // 2 // GCD of panel length -#define D_M_KERNEL 4 // max kernel size -#define D_N_KERNEL 4 // max kernel size -#define D_KC 256 -#define D_NC 128 // TODO these are just dummy -#define D_MC 3000 // TODO these are just dummy -// single -#define S_PS 4 -#define S_PLD 4 //2 -#define S_M_KERNEL 4 // max kernel size -#define S_N_KERNEL 4 // max kernel size -#define S_KC 256 -#define S_NC 128 // TODO these are just dummy -#define S_MC 3000 // TODO these are just dummy - - -#elif defined( TARGET_X86_AMD_BARCELONA ) -// common -#define CACHE_LINE_SIZE 64 -#define L1_CACHE_SIZE (32*1024) // L1 data cache size: 32 kB -// double -#define D_PS 4 // panel size -#define D_PLD 4 // 2 // GCD of panel length -#define D_M_KERNEL 4 // max kernel size -#define D_N_KERNEL 4 // max kernel size -#define D_KC 256 -#define D_NC 128 // TODO these are just dummy -#define D_MC 3000 // TODO these are just dummy -// single -#define S_PS 4 -#define S_PLD 4 //2 -#define S_M_KERNEL 4 // max kernel size -#define S_N_KERNEL 4 // max kernel size -#define S_KC 256 -#define S_NC 128 // TODO these are just dummy -#define S_MC 3000 // TODO these are just dummy - - -#elif defined(TARGET_ARMV8A_APPLE_M1) -// common -#define CACHE_LINE_SIZE 64 -#define L1_CACHE_SIZE (128*1024) // L1 data cache size (big cores): 64 kB, ?-way ; DTLB1 ? -#define LLC_CACHE_SIZE (12*1024*1024) // LLC (L2) cache size (big cores): 12 MB -// double -#define D_PS 4 // panel size -#define D_PLD 4 // 2 // GCD of panel length -#define D_M_KERNEL 8 // max kernel size -#define D_N_KERNEL 4 // max kernel size -#define D_KC 512 //256 -#define D_NC 128 //256 -#define D_MC 6000 -// single -#define S_PS 4 -#define S_PLD 4 //2 -#define S_M_KERNEL 8 // max kernel size -#define S_N_KERNEL 8 // max kernel size -#define S_KC 512 -#define S_NC 256 -#define S_MC 6000 - - -#elif defined(TARGET_ARMV8A_ARM_CORTEX_A76) -// common -#define CACHE_LINE_SIZE 64 -#define L1_CACHE_SIZE (64*1024) // L1 data cache size: 64 kB, 4-way ; DTLB1 48*4 kB = 192 kB -#define LLC_CACHE_SIZE (1*1024*1024) // LLC cache size: 1 MB -// double -#define D_PS 4 // panel size -#define D_PLD 4 // 2 // GCD of panel length -#define D_M_KERNEL 8 // max kernel size -#define D_N_KERNEL 4 // max kernel size -#define D_KC 512 //256 -#define D_NC 128 //256 -#define D_MC 6000 -// single -#define S_PS 4 -#define S_PLD 4 //2 -#define S_M_KERNEL 8 // max kernel size -#define S_N_KERNEL 8 // max kernel size -#define S_KC 512 -#define S_NC 256 -#define S_MC 6000 - - -#elif defined(TARGET_ARMV8A_ARM_CORTEX_A73) -// common -#define CACHE_LINE_SIZE 64 -#define L1_CACHE_SIZE (32*1024) // L1 data cache size: 32 (64?) kB, 4-way, seen as 8-(16-)way ; DTLB1 48*4 kB = 192 kB -#define LLC_CACHE_SIZE (1*1024*1024) // LLC cache size: 1 MB -// double -#define D_PS 4 // panel size -#define D_PLD 4 // 2 // GCD of panel length -#define D_M_KERNEL 8 // max kernel size -#define D_N_KERNEL 4 // max kernel size -#define D_KC 320 -#define D_NC 256 -#define D_MC 6000 -// single -#define S_PS 4 -#define S_PLD 4 //2 -#define S_M_KERNEL 8 // max kernel size -#define S_N_KERNEL 8 // max kernel size -#define S_KC 256 -#define S_NC 128 // TODO these are just dummy -#define S_MC 3000 // TODO these are just dummy - - -#elif defined(TARGET_ARMV8A_ARM_CORTEX_A57) -// common -#define CACHE_LINE_SIZE 64 -#define L1_CACHE_SIZE (32*1024) // L1 data cache size: 32 kB, 2-way ; DTLB1 32*4 kB = 128 kB -#define LLC_CACHE_SIZE (1*1024*1024) // LLC cache size: 1 MB // 2 MB ??? -// double -#define D_PS 4 // panel size -#define D_PLD 4 // 2 // GCD of panel length -#define D_M_KERNEL 8 // max kernel size -#define D_N_KERNEL 4 // max kernel size -#define D_KC 128 //224 //256 //192 -#define D_NC 72 //40 //36 //48 -#define D_MC (4*192) //512 //488 //600 -// single -#define S_PS 4 -#define S_PLD 4 //2 -#define S_M_KERNEL 8 // max kernel size -#define S_N_KERNEL 8 // max kernel size -#define S_KC 256 -#define S_NC 128 // TODO these are just dummy -#define S_MC 3000 // TODO these are just dummy - - -#elif defined(TARGET_ARMV8A_ARM_CORTEX_A55) -// common -#define CACHE_LINE_SIZE 64 -#define L1_CACHE_SIZE (32*1024) // L1 data cache size: 32 kB, 4-way ; DTLB1 16*4 kB = 64 kB -#define LLC_CACHE_SIZE (512*1024) // LLC cache size: 512 kB -// double -#define D_PS 4 // panel size -#define D_PLD 4 // 2 // GCD of panel length -#define D_M_KERNEL 12 // max kernel size -#define D_N_KERNEL 4 // max kernel size -#define D_KC 224 -#define D_NC 160 -#define D_MC 6000 -// single -#define S_PS 4 -#define S_PLD 4 //2 -#define S_M_KERNEL 8 // max kernel size -#define S_N_KERNEL 8 // max kernel size -#define S_KC 256 -#define S_NC 128 // TODO these are just dummy -#define S_MC 3000 // TODO these are just dummy - - -#elif defined(TARGET_ARMV8A_ARM_CORTEX_A53) -// common -#define CACHE_LINE_SIZE 64 -#define L1_CACHE_SIZE (32*1024) // L1 data cache size: 32 kB, 4-way ??? ; DTLB1 10*4 kB = 40 kB -#define LLC_CACHE_SIZE (256*1024) // LLC cache size: 256 kB -// double -#define D_PS 4 // panel size -#define D_PLD 4 // 2 // GCD of panel length -#define D_M_KERNEL 12 // max kernel size -#define D_N_KERNEL 4 // max kernel size -#define D_KC 160 -#define D_NC 128 -#define D_MC 6000 -// single -#define S_PS 4 -#define S_PLD 4 //2 -#define S_M_KERNEL 8 // max kernel size -#define S_N_KERNEL 8 // max kernel size -#define S_KC 256 -#define S_NC 128 // TODO these are just dummy -#define S_MC 3000 // TODO these are just dummy - - -#elif defined( TARGET_ARMV7A_ARM_CORTEX_A15 ) -// common -#define CACHE_LINE_SIZE 64 -#define L1_CACHE_SIZE (32*1024) // L1 data cache size: 32 kB -// double -#define D_PS 4 // panel size -#define D_PLD 4 // 2 // GCD of panel length -#define D_M_KERNEL 4 // max kernel size -#define D_N_KERNEL 4 // max kernel size -#define D_KC 256 -#define D_NC 128 // TODO these are just dummy -#define D_MC 3000 // TODO these are just dummy -// single -#define S_PS 4 -#define S_PLD 4 //2 -#define S_M_KERNEL 4 // max kernel size -#define S_N_KERNEL 4 // max kernel size -#define S_KC 256 -#define S_NC 128 // TODO these are just dummy -#define S_MC 3000 // TODO these are just dummy - - -#elif defined( TARGET_ARMV7A_ARM_CORTEX_A7 ) -// common -#define CACHE_LINE_SIZE 64 -#define L1_CACHE_SIZE (32*1024) // L1 data cache size: 32 kB -// double -#define D_PS 4 // panel size -#define D_PLD 4 // 2 // GCD of panel length -#define D_M_KERNEL 4 // max kernel size -#define D_N_KERNEL 4 // max kernel size -#define D_KC 256 -#define D_NC 128 // TODO these are just dummy -#define D_MC 3000 // TODO these are just dummy -// single -#define S_PS 4 -#define S_PLD 4 //2 -#define S_M_KERNEL 4 // max kernel size -#define S_N_KERNEL 4 // max kernel size -#define S_KC 256 -#define S_NC 128 // TODO these are just dummy -#define S_MC 3000 // TODO these are just dummy - - -#elif defined( TARGET_ARMV7A_ARM_CORTEX_A9 ) -// common -#define CACHE_LINE_SIZE 32 -#define L1_CACHE_SIZE (32*1024) // L1 data cache size: 32 kB -// double -#define D_PS 4 // panel size -#define D_PLD 4 // 2 // GCD of panel length -#define D_M_KERNEL 4 // max kernel size -#define D_N_KERNEL 4 // max kernel size -#define D_KC 256 -#define D_NC 128 // TODO these are just dummy -#define D_MC 3000 // TODO these are just dummy -// single -#define S_PS 4 -#define S_PLD 4 //2 -#define S_M_KERNEL 4 // max kernel size -#define S_N_KERNEL 4 // max kernel size -#define S_KC 256 -#define S_NC 128 // TODO these are just dummy -#define S_MC 3000 // TODO these are just dummy - - -#elif defined( TARGET_GENERIC ) -// common -#define CACHE_LINE_SIZE 64 -#define L1_CACHE_SIZE (32*1024) // L1 data cache size: 32 kB -// double -#define D_PS 4 // panel size -#define D_PLD 4 // 2 // GCD of panel length -#define D_M_KERNEL 4 // max kernel size -#define D_N_KERNEL 4 // max kernel size -#define D_KC 256 -#define D_NC 128 // TODO these are just dummy -#define D_MC 3000 // TODO these are just dummy - -// single -#define S_PS 4 -#define S_PLD 4 //2 -#define S_M_KERNEL 4 // max kernel size -#define S_N_KERNEL 4 // max kernel size -#define S_KC 256 -#define S_NC 128 // TODO these are just dummy -#define S_MC 3000 // TODO these are just dummy - - -#else -#error "Unknown architecture" -#endif - - - -#define D_CACHE_LINE_EL (CACHE_LINE_SIZE/D_EL_SIZE) -#define D_L1_CACHE_EL (L1_CACHE_SIZE/D_EL_SIZE) -#define D_L2_CACHE_EL (L2_CACHE_SIZE/D_EL_SIZE) -#define D_LLC_CACHE_EL (LLC_CACHE_SIZE/D_EL_SIZE) - -#define S_CACHE_LINE_EL (CACHE_LINE_SIZE/S_EL_SIZE) -#define S_L1_CACHE_EL (L1_CACHE_SIZE/S_EL_SIZE) -#define S_L2_CACHE_EL (L2_CACHE_SIZE/S_EL_SIZE) -#define S_LLC_CACHE_EL (LLC_CACHE_SIZE/S_EL_SIZE) - - - -#endif // BLASFEO_BLOCK_SIZE_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_common.h b/third_party/acados/include/blasfeo/include/blasfeo_common.h deleted file mode 100644 index 03b6c36..0000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_common.h +++ /dev/null @@ -1,274 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_COMMON_H_ -#define BLASFEO_COMMON_H_ - - - -#include "blasfeo_target.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -#if defined(__GNUC__) || defined(__clang__) || defined(__INTEL_COMPILER) || defined(__ICL) || defined(__ICC) || defined(__INTEL_LLVM_COMPILER) -#define ALIGNED(VEC, BYTES) VEC __attribute__ ((aligned ( BYTES ))) -#elif defined (_MSC_VER) -#define ALIGNED(VEC, BYTES) __declspec(align( BYTES )) VEC -#else -#define ALIGNED(VEC, BYTES) VEC -#endif - - - - -#if ( defined(LA_HIGH_PERFORMANCE) & defined(MF_PANELMAJ) ) | ( defined(LA_REFERENCE) & defined(MF_PANELMAJ) ) - -#include "blasfeo_block_size.h" - -// matrix structure -struct blasfeo_dmat - { - double *mem; // pointer to passed chunk of memory - double *pA; // pointer to a pm*pn array of doubles, the first is aligned to cache line size - double *dA; // pointer to a min(m,n) (or max???) array of doubles - int m; // rows - int n; // cols - int pm; // packed number or rows - int cn; // packed number or cols - int use_dA; // flag to tell if dA can be used - int memsize; // size of needed memory - }; - -struct blasfeo_smat - { - float *mem; // pointer to passed chunk of memory - float *pA; // pointer to a pm*pn array of floats, the first is aligned to cache line size - float *dA; // pointer to a min(m,n) (or max???) array of floats - int m; // rows - int n; // cols - int pm; // packed number or rows - int cn; // packed number or cols - int use_dA; // flag to tell if dA can be used - int memsize; // size of needed memory - }; - -// vector structure -struct blasfeo_dvec - { - double *mem; // pointer to passed chunk of memory - double *pa; // pointer to a pm array of doubles, the first is aligned to cache line size - int m; // size - int pm; // packed size - int memsize; // size of needed memory - }; - -struct blasfeo_svec - { - float *mem; // pointer to passed chunk of memory - float *pa; // pointer to a pm array of floats, the first is aligned to cache line size - int m; // size - int pm; // packed size - int memsize; // size of needed memory - }; - -#define BLASFEO_DMATEL(sA,ai,aj) ((sA)->pA[((ai)-((ai)&(D_PS-1)))*(sA)->cn+(aj)*D_PS+((ai)&(D_PS-1))]) -#define BLASFEO_SMATEL(sA,ai,aj) ((sA)->pA[((ai)-((ai)&(S_PS-1)))*(sA)->cn+(aj)*S_PS+((ai)&(S_PS-1))]) -#define BLASFEO_DVECEL(sa,ai) ((sa)->pa[ai]) -#define BLASFEO_SVECEL(sa,ai) ((sa)->pa[ai]) - -#elif ( defined(LA_HIGH_PERFORMANCE) & defined(MF_COLMAJ) ) | ( defined(LA_REFERENCE) & defined(MF_COLMAJ) ) | defined(LA_EXTERNAL_BLAS_WRAPPER) - -// matrix structure -struct blasfeo_dmat - { - double *mem; // pointer to passed chunk of memory - double *pA; // pointer to a m*n array of doubles - double *dA; // pointer to a min(m,n) (or max???) array of doubles - int m; // rows - int n; // cols - int use_dA; // flag to tell if dA can be used - int memsize; // size of needed memory - }; - -struct blasfeo_smat - { - float *mem; // pointer to passed chunk of memory - float *pA; // pointer to a m*n array of floats - float *dA; // pointer to a min(m,n) (or max???) array of floats - int m; // rows - int n; // cols - int use_dA; // flag to tell if dA can be used - int memsize; // size of needed memory - }; - -// vector structure -struct blasfeo_dvec - { - double *mem; // pointer to passed chunk of memory - double *pa; // pointer to a m array of doubles, the first is aligned to cache line size - int m; // size - int memsize; // size of needed memory - }; - -struct blasfeo_svec - { - float *mem; // pointer to passed chunk of memory - float *pa; // pointer to a m array of floats, the first is aligned to cache line size - int m; // size - int memsize; // size of needed memory - }; - -#define BLASFEO_DMATEL(sA,ai,aj) ((sA)->pA[(ai)+(aj)*(sA)->m]) -#define BLASFEO_SMATEL(sA,ai,aj) ((sA)->pA[(ai)+(aj)*(sA)->m]) -#define BLASFEO_DVECEL(sa,ai) ((sa)->pa[ai]) -#define BLASFEO_SVECEL(sa,ai) ((sa)->pa[ai]) - -#else - -#error : wrong LA or MF choice - -#endif - - - -// Explicitly panel-major matrix structure -struct blasfeo_pm_dmat - { - double *mem; // pointer to passed chunk of memory - double *pA; // pointer to a pm*pn array of doubles, the first is aligned to cache line size - double *dA; // pointer to a min(m,n) (or max???) array of doubles - int m; // rows - int n; // cols - int pm; // packed number or rows - int cn; // packed number or cols - int use_dA; // flag to tell if dA can be used - int ps; // panel size - int memsize; // size of needed memory - }; - -struct blasfeo_pm_smat - { - float *mem; // pointer to passed chunk of memory - float *pA; // pointer to a pm*pn array of floats, the first is aligned to cache line size - float *dA; // pointer to a min(m,n) (or max???) array of floats - int m; // rows - int n; // cols - int pm; // packed number or rows - int cn; // packed number or cols - int use_dA; // flag to tell if dA can be used - int ps; // panel size - int memsize; // size of needed memory - }; - -struct blasfeo_pm_dvec - { - double *mem; // pointer to passed chunk of memory - double *pa; // pointer to a pm array of doubles, the first is aligned to cache line size - int m; // size - int pm; // packed size - int memsize; // size of needed memory - }; - -struct blasfeo_pm_svec - { - float *mem; // pointer to passed chunk of memory - float *pa; // pointer to a pm array of floats, the first is aligned to cache line size - int m; // size - int pm; // packed size - int memsize; // size of needed memory - }; - -// Explicitly column-major matrix structure -struct blasfeo_cm_dmat - { - double *mem; // pointer to passed chunk of memory - double *pA; // pointer to a m*n array of doubles - double *dA; // pointer to a min(m,n) (or max???) array of doubles - int m; // rows - int n; // cols - int use_dA; // flag to tell if dA can be used - int memsize; // size of needed memory - }; - -struct blasfeo_cm_smat - { - float *mem; // pointer to passed chunk of memory - float *pA; // pointer to a m*n array of floats - float *dA; // pointer to a min(m,n) (or max???) array of floats - int m; // rows - int n; // cols - int use_dA; // flag to tell if dA can be used - int memsize; // size of needed memory - }; - -struct blasfeo_cm_dvec - { - double *mem; // pointer to passed chunk of memory - double *pa; // pointer to a m array of doubles, the first is aligned to cache line size - int m; // size - int memsize; // size of needed memory - }; - -struct blasfeo_cm_svec - { - float *mem; // pointer to passed chunk of memory - float *pa; // pointer to a m array of floats, the first is aligned to cache line size - int m; // size - int memsize; // size of needed memory - }; - - -#define BLASFEO_PM_DMATEL(sA,ai,aj) ((sA)->pA[((ai)-((ai)&((sA)->ps-1)))*(sA)->cn+(aj)*((sA)->ps)+((ai)&((sA)->ps-1))]) -#define BLASFEO_PM_SMATEL(sA,ai,aj) ((sA)->pA[((ai)-((ai)&((sA)->ps-1)))*(sA)->cn+(aj)*((sA)->ps)+((ai)&((sA)->ps-1))]) -#define BLASFEO_PM_DVECEL(sa,ai) ((sa)->pa[ai]) -#define BLASFEO_PM_SVECEL(sa,ai) ((sa)->pa[ai]) -#define BLASFEO_CM_DMATEL(sA,ai,aj) ((sA)->pA[(ai)+(aj)*(sA)->m]) -#define BLASFEO_CM_SMATEL(sA,ai,aj) ((sA)->pA[(ai)+(aj)*(sA)->m]) -#define BLASFEO_CM_DVECEL(sa,ai) ((sa)->pa[ai]) -#define BLASFEO_CM_SVECEL(sa,ai) ((sa)->pa[ai]) - - - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_COMMON_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_d_aux.h b/third_party/acados/include/blasfeo/include/blasfeo_d_aux.h deleted file mode 100644 index a6d6119..0000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_d_aux.h +++ /dev/null @@ -1,255 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -/* - * auxiliary algebra operations header - * - * include/blasfeo_aux_lib*.h - * - */ - -#ifndef BLASFEO_D_AUX_H_ -#define BLASFEO_D_AUX_H_ - - - -#include - -#include "blasfeo_common.h" -#include "blasfeo_d_aux_old.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - -// --- memory size calculations -// -// returns the memory size (in bytes) needed for a dmat -size_t blasfeo_memsize_dmat(int m, int n); -// returns the memory size (in bytes) needed for the diagonal of a dmat -size_t blasfeo_memsize_diag_dmat(int m, int n); -// returns the memory size (in bytes) needed for a dvec -size_t blasfeo_memsize_dvec(int m); - -// --- creation -// -// create a strmat for a matrix of size m*n by using memory passed by a pointer (pointer is not updated) -void blasfeo_create_dmat(int m, int n, struct blasfeo_dmat *sA, void *memory); -// create a strvec for a vector of size m by using memory passed by a pointer (pointer is not updated) -void blasfeo_create_dvec(int m, struct blasfeo_dvec *sA, void *memory); - -// --- packing -// pack the column-major matrix A into the matrix struct B -void blasfeo_pack_dmat(int m, int n, double *A, int lda, struct blasfeo_dmat *sB, int bi, int bj); -// pack the lower-triangular column-major matrix A into the matrix struct B -void blasfeo_pack_l_dmat(int m, int n, double *A, int lda, struct blasfeo_dmat *sB, int bi, int bj); -// pack the upper-triangular column-major matrix A into the matrix struct B -void blasfeo_pack_u_dmat(int m, int n, double *A, int lda, struct blasfeo_dmat *sB, int bi, int bj); -// transpose and pack the column-major matrix A into the matrix struct B -void blasfeo_pack_tran_dmat(int m, int n, double *A, int lda, struct blasfeo_dmat *sB, int bi, int bj); -// pack the vector x into the vector structure y -void blasfeo_pack_dvec(int m, double *x, int xi, struct blasfeo_dvec *sy, int yi); -// unpack the matrix structure A into the column-major matrix B -void blasfeo_unpack_dmat(int m, int n, struct blasfeo_dmat *sA, int ai, int aj, double *B, int ldb); -// transpose and unpack the matrix structure A into the column-major matrix B -void blasfeo_unpack_tran_dmat(int m, int n, struct blasfeo_dmat *sA, int ai, int aj, double *B, int ldb); -// pack the vector structure x into the vector y -void blasfeo_unpack_dvec(int m, struct blasfeo_dvec *sx, int xi, double *y, int yi); - -// --- cast -// -//void d_cast_mat2strmat(double *A, struct blasfeo_dmat *sA); // TODO -//void d_cast_diag_mat2strmat(double *dA, struct blasfeo_dmat *sA); // TODO -//void d_cast_vec2vecmat(double *a, struct blasfeo_dvec *sx); // TODO - - -// ge -// --- insert/extract -// -// sA[ai, aj] <= a -void blasfeo_dgein1(double a, struct blasfeo_dmat *sA, int ai, int aj); -// <= sA[ai, aj] -double blasfeo_dgeex1(struct blasfeo_dmat *sA, int ai, int aj); - -// --- set -// A <= alpha -void blasfeo_dgese(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj); - -// --- copy / scale -// B <= A -void blasfeo_dgecp(int m, int n, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj); -// A <= alpha*A -void blasfeo_dgesc(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj); -// B <= alpha*A -void blasfeo_dgecpsc(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj); -// B <= A, A lower triangular -void blasfeo_dtrcp_l(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj); -void blasfeo_dtrcpsc_l(int m, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj); -void blasfeo_dtrsc_l(int m, double alpha, struct blasfeo_dmat *sA, int ai, int aj); - -// --- sum -// B <= B + alpha*A -void blasfeo_dgead(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj); -// y <= y + alpha*x -void blasfeo_dvecad(int m, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sy, int yi); - -// --- traspositions -// B <= A' -void blasfeo_dgetr(int m, int n, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj); -// B <= A', A lower triangular -void blasfeo_dtrtr_l(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj); -// B <= A', A upper triangular -void blasfeo_dtrtr_u(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj); - -// dia -// diag(A) += alpha -void blasfeo_ddiare(int kmax, double alpha, struct blasfeo_dmat *sA, int ai, int aj); -// diag(A) <= alpha*x -void blasfeo_ddiain(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dmat *sA, int ai, int aj); -// diag(A)[idx] <= alpha*x -void blasfeo_ddiain_sp(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, int *idx, struct blasfeo_dmat *sD, int di, int dj); -// x <= diag(A) -void blasfeo_ddiaex(int kmax, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi); -// x <= diag(A)[idx] -void blasfeo_ddiaex_sp(int kmax, double alpha, int *idx, struct blasfeo_dmat *sD, int di, int dj, struct blasfeo_dvec *sx, int xi); -// diag(A) += alpha*x -void blasfeo_ddiaad(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dmat *sA, int ai, int aj); -// diag(A)[idx] += alpha*x -void blasfeo_ddiaad_sp(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, int *idx, struct blasfeo_dmat *sD, int di, int dj); -// diag(A)[idx] = y + alpha*x -void blasfeo_ddiaadin_sp(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sy, int yi, int *idx, struct blasfeo_dmat *sD, int di, int dj); - -// row -void blasfeo_drowin(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dmat *sA, int ai, int aj); -void blasfeo_drowex(int kmax, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi); -void blasfeo_drowad(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dmat *sA, int ai, int aj); -void blasfeo_drowad_sp(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, int *idx, struct blasfeo_dmat *sD, int di, int dj); -void blasfeo_drowsw(int kmax, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sC, int ci, int cj); -void blasfeo_drowpe(int kmax, int *ipiv, struct blasfeo_dmat *sA); -void blasfeo_drowpei(int kmax, int *ipiv, struct blasfeo_dmat *sA); - -// col -void blasfeo_dcolex(int kmax, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi); -void blasfeo_dcolin(int kmax, struct blasfeo_dvec *sx, int xi, struct blasfeo_dmat *sA, int ai, int aj); -void blasfeo_dcolad(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dmat *sA, int ai, int aj); -void blasfeo_dcolsc(int kmax, double alpha, struct blasfeo_dmat *sA, int ai, int aj); -void blasfeo_dcolsw(int kmax, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sC, int ci, int cj); -void blasfeo_dcolpe(int kmax, int *ipiv, struct blasfeo_dmat *sA); -void blasfeo_dcolpei(int kmax, int *ipiv, struct blasfeo_dmat *sA); - -// vec -// a <= alpha -void blasfeo_dvecse(int m, double alpha, struct blasfeo_dvec *sx, int xi); -// sx[xi] <= a -void blasfeo_dvecin1(double a, struct blasfeo_dvec *sx, int xi); -// <= sx[xi] -double blasfeo_dvecex1(struct blasfeo_dvec *sx, int xi); -// y <= x -void blasfeo_dveccp(int m, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sy, int yi); -// x <= alpha*x -void blasfeo_dvecsc(int m, double alpha, struct blasfeo_dvec *sx, int xi); -// y <= alpha*x -void blasfeo_dveccpsc(int m, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sy, int yi); -// z[idx] += alpha * x -void blasfeo_dvecad_sp(int m, double alpha, struct blasfeo_dvec *sx, int xi, int *idx, struct blasfeo_dvec *sz, int zi); -// z[idx] <= alpha * x -void blasfeo_dvecin_sp(int m, double alpha, struct blasfeo_dvec *sx, int xi, int *idx, struct blasfeo_dvec *sz, int zi); -// z <= alpha * x[idx] -void blasfeo_dvecex_sp(int m, double alpha, int *idx, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z += alpha * x[idx] -void blasfeo_dvecexad_sp(int m, double alpha, int *idx, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); - -void blasfeo_dveccl(int m, - struct blasfeo_dvec *sxm, int xim, struct blasfeo_dvec *sx, int xi, - struct blasfeo_dvec *sxp, int xip, struct blasfeo_dvec *sz, int zi); - -void blasfeo_dveccl_mask(int m, - struct blasfeo_dvec *sxm, int xim, struct blasfeo_dvec *sx, int xi, - struct blasfeo_dvec *sxp, int xip, struct blasfeo_dvec *sz, int zi, - struct blasfeo_dvec *sm, int mi); - -void blasfeo_dvecze(int m, struct blasfeo_dvec *sm, int mi, struct blasfeo_dvec *sv, int vi, struct blasfeo_dvec *se, int ei); -void blasfeo_dvecnrm_inf(int m, struct blasfeo_dvec *sx, int xi, double *ptr_norm); -void blasfeo_dvecnrm_2(int m, struct blasfeo_dvec *sx, int xi, double *ptr_norm); -void blasfeo_dvecpe(int kmax, int *ipiv, struct blasfeo_dvec *sx, int xi); -void blasfeo_dvecpei(int kmax, int *ipiv, struct blasfeo_dvec *sx, int xi); - - - - - -/* -* Explicitly panel-major matrix format -*/ - -// returns the memory size (in bytes) needed for a dmat -size_t blasfeo_pm_memsize_dmat(int ps, int m, int n); -// create a strmat for a matrix of size m*n by using memory passed by a pointer (pointer is not updated) -void blasfeo_pm_create_dmat(int ps, int m, int n, struct blasfeo_pm_dmat *sA, void *memory); -// print -void blasfeo_pm_print_dmat(int m, int n, struct blasfeo_pm_dmat *sA, int ai, int aj); - - - -/* -* Explicitly panel-major matrix format -*/ - -// returns the memory size (in bytes) needed for a dmat -size_t blasfeo_cm_memsize_dmat(int m, int n); -// create a strmat for a matrix of size m*n by using memory passed by a pointer (pointer is not updated) -void blasfeo_cm_create_dmat(int m, int n, struct blasfeo_pm_dmat *sA, void *memory); - - - -// -// BLAS API helper functions -// - -#if ( defined(BLAS_API) & defined(MF_PANELMAJ) ) -// aux -void blasfeo_cm_dgetr(int m, int n, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj); -#endif - - - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_D_AUX_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_d_aux_ext_dep.h b/third_party/acados/include/blasfeo/include/blasfeo_d_aux_ext_dep.h deleted file mode 100644 index bee9e98..0000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_d_aux_ext_dep.h +++ /dev/null @@ -1,145 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -/* - * auxiliary algebra operation external dependancies header - * - * include/blasfeo_d_aux_ext_dep.h - * - * - dynamic memory allocation - * - print - * - */ - -#ifndef BLASFEO_D_AUX_EXT_DEP_H_ -#define BLASFEO_D_AUX_EXT_DEP_H_ - - - -#include - - - -#include "blasfeo_common.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -#ifdef EXT_DEP - -/* column-major matrices */ - -// dynamically allocate row*col doubles of memory and set accordingly a pointer to double; set allocated memory to zero -void d_zeros(double **pA, int row, int col); -// dynamically allocate row*col doubles of memory aligned to 64-byte boundaries and set accordingly a pointer to double; set allocated memory to zero -void d_zeros_align(double **pA, int row, int col); -// dynamically allocate size bytes of memory aligned to 64-byte boundaries and set accordingly a pointer to double; set allocated memory to zero -void d_zeros_align_bytes(double **pA, int size); -// free the memory allocated by d_zeros -void d_free(double *pA); -// free the memory allocated by d_zeros_align or d_zeros_align_bytes -void d_free_align(double *pA); -// print a column-major matrix -void d_print_mat(int m, int n, double *A, int lda); -// print the transposed of a column-major matrix -void d_print_tran_mat(int row, int col, double *A, int lda); -// print to file a column-major matrix -void d_print_to_file_mat(FILE *file, int row, int col, double *A, int lda); -// print to file a column-major matrix in exponential format -void d_print_to_file_exp_mat(FILE *file, int row, int col, double *A, int lda); -// print to string a column-major matrix -void d_print_to_string_mat(char **buf_out, int row, int col, double *A, int lda); -// print to file the transposed of a column-major matrix -void d_print_tran_to_file_mat(FILE *file, int row, int col, double *A, int lda); -// print to file the transposed of a column-major matrix in exponential format -void d_print_tran_to_file_exp_mat(FILE *file, int row, int col, double *A, int lda); -// print in exponential notation a column-major matrix -void d_print_exp_mat(int m, int n, double *A, int lda); -// print in exponential notation the transposed of a column-major matrix -void d_print_exp_tran_mat(int row, int col, double *A, int lda); - -/* strmat and strvec */ - -// create a strmat for a matrix of size m*n by dynamically allocating memory -void blasfeo_allocate_dmat(int m, int n, struct blasfeo_dmat *sA); -// create a strvec for a vector of size m by dynamically allocating memory -void blasfeo_allocate_dvec(int m, struct blasfeo_dvec *sa); -// free the memory allocated by blasfeo_allocate_dmat -void blasfeo_free_dmat(struct blasfeo_dmat *sA); -// free the memory allocated by blasfeo_allocate_dvec -void blasfeo_free_dvec(struct blasfeo_dvec *sa); -// print a strmat -void blasfeo_print_dmat(int m, int n, struct blasfeo_dmat *sA, int ai, int aj); -// print in exponential notation a strmat -void blasfeo_print_exp_dmat(int m, int n, struct blasfeo_dmat *sA, int ai, int aj); -// print to file a strmat -void blasfeo_print_to_file_dmat(FILE *file, int m, int n, struct blasfeo_dmat *sA, int ai, int aj); -// print to file a strmat in exponential format -void blasfeo_print_to_file_exp_dmat(FILE *file, int m, int n, struct blasfeo_dmat *sA, int ai, int aj); -// print to string a strmat -void blasfeo_print_to_string_dmat(char **buf_out, int m, int n, struct blasfeo_dmat *sA, int ai, int aj); -// print the transposed of a strmat -void blasfeo_print_tran_dmat(int m, int n, struct blasfeo_dmat *sA, int ai, int aj); -// print a strvec -void blasfeo_print_dvec(int m, struct blasfeo_dvec *sa, int ai); -// print in exponential notation a strvec -void blasfeo_print_exp_dvec(int m, struct blasfeo_dvec *sa, int ai); -// print to file a strvec -void blasfeo_print_to_file_dvec(FILE *file, int m, struct blasfeo_dvec *sa, int ai); -// print to string a strvec -void blasfeo_print_to_string_dvec(char **buf_out, int m, struct blasfeo_dvec *sa, int ai); -// print the transposed of a strvec -void blasfeo_print_tran_dvec(int m, struct blasfeo_dvec *sa, int ai); -// print in exponential notation the transposed of a strvec -void blasfeo_print_exp_tran_dvec(int m, struct blasfeo_dvec *sa, int ai); -// print to file the transposed of a strvec -void blasfeo_print_to_file_tran_dvec(FILE *file, int m, struct blasfeo_dvec *sa, int ai); -// print to string the transposed of a strvec -void blasfeo_print_to_string_tran_dvec(char **buf_out, int m, struct blasfeo_dvec *sa, int ai); - -#endif // EXT_DEP - - - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_D_AUX_EXT_DEP_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_d_aux_ext_dep_ref.h b/third_party/acados/include/blasfeo/include/blasfeo_d_aux_ext_dep_ref.h deleted file mode 100644 index 81b811f..0000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_d_aux_ext_dep_ref.h +++ /dev/null @@ -1,84 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -/* - * auxiliary algebra operation external dependancies header - * - * include/blasfeo_d_aux_ext_dep.h - * - * - dynamic memory allocation - * - print - * - */ - -#ifndef BLASFEO_D_AUX_EXT_DEP_REF_H_ -#define BLASFEO_D_AUX_EXT_DEP_REF_H_ - - -#include - -#include "blasfeo_common.h" - -#ifdef __cplusplus -extern "C" { -#endif - -// expose reference BLASFEO for testing -// see blasfeo_d_aux_exp_dep.h for help - -void blasfeo_print_dmat_ref(int m, int n, struct blasfeo_dmat_ref *sA, int ai, int aj); -void blasfeo_allocate_dmat_ref(int m, int n, struct blasfeo_dmat_ref *sA); -void blasfeo_allocate_dvec_ref(int m, struct blasfeo_dvec_ref *sa); -void blasfeo_free_dmat_ref(struct blasfeo_dmat_ref *sA); -void blasfeo_free_dvec_ref(struct blasfeo_dvec_ref *sa); -void blasfeo_print_dmat_ref(int m, int n, struct blasfeo_dmat_ref *sA, int ai, int aj); -void blasfeo_print_exp_dmat_ref(int m, int n, struct blasfeo_dmat_ref *sA, int ai, int aj); -void blasfeo_print_to_file_dmat_ref(FILE *file, int m, int n, struct blasfeo_dmat_ref *sA, int ai, int aj); -void blasfeo_print_to_file_exp_dmat_ref(FILE *file, int m, int n, struct blasfeo_dmat_ref *sA, int ai, int aj); -void blasfeo_print_to_string_dmat_ref(char **buf_out, int m, int n, struct blasfeo_dmat_ref *sA, int ai, int aj); -void blasfeo_print_dvec(int m, struct blasfeo_dvec *sa, int ai); -void blasfeo_print_exp_dvec(int m, struct blasfeo_dvec *sa, int ai); -void blasfeo_print_to_file_dvec(FILE *file, int m, struct blasfeo_dvec *sa, int ai); -void blasfeo_print_to_string_dvec(char **buf_out, int m, struct blasfeo_dvec *sa, int ai); -void blasfeo_print_tran_dvec(int m, struct blasfeo_dvec *sa, int ai); -void blasfeo_print_exp_tran_dvec(int m, struct blasfeo_dvec *sa, int ai); -void blasfeo_print_to_file_tran_dvec(FILE *file, int m, struct blasfeo_dvec *sa, int ai); -void blasfeo_print_to_string_tran_dvec(char **buf_out, int m, struct blasfeo_dvec *sa, int ai); - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_D_AUX_EXT_DEP_REF_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_d_aux_old.h b/third_party/acados/include/blasfeo/include/blasfeo_d_aux_old.h deleted file mode 100644 index 3a1847a..0000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_d_aux_old.h +++ /dev/null @@ -1,75 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -/* - * ----------- TOMOVE - * - * expecting column major matrices - * - */ - -#include "blasfeo_common.h" - - -void dtrcp_l_lib(int m, double alpha, int offsetA, double *A, int sda, int offsetB, double *B, int sdb); -void dgead_lib(int m, int n, double alpha, int offsetA, double *A, int sda, int offsetB, double *B, int sdb); -// TODO remove ??? -void ddiain_sqrt_lib(int kmax, double *x, int offset, double *pD, int sdd); -// TODO ddiaad1 -void ddiareg_lib(int kmax, double reg, int offset, double *pD, int sdd); - - -void dgetr_lib(int m, int n, double alpha, int offsetA, double *pA, int sda, int offsetC, double *pC, int sdc); -void dtrtr_l_lib(int m, double alpha, int offsetA, double *pA, int sda, int offsetC, double *pC, int sdc); -void dtrtr_u_lib(int m, double alpha, int offsetA, double *pA, int sda, int offsetC, double *pC, int sdc); -void ddiaex_lib(int kmax, double alpha, int offset, double *pD, int sdd, double *x); -void ddiaad_lib(int kmax, double alpha, double *x, int offset, double *pD, int sdd); -void ddiain_libsp(int kmax, int *idx, double alpha, double *x, double *pD, int sdd); -void ddiaex_libsp(int kmax, int *idx, double alpha, double *pD, int sdd, double *x); -void ddiaad_libsp(int kmax, int *idx, double alpha, double *x, double *pD, int sdd); -void ddiaadin_libsp(int kmax, int *idx, double alpha, double *x, double *y, double *pD, int sdd); -void drowin_lib(int kmax, double alpha, double *x, double *pD); -void drowex_lib(int kmax, double alpha, double *pD, double *x); -void drowad_lib(int kmax, double alpha, double *x, double *pD); -void drowin_libsp(int kmax, double alpha, int *idx, double *x, double *pD); -void drowad_libsp(int kmax, int *idx, double alpha, double *x, double *pD); -void drowadin_libsp(int kmax, int *idx, double alpha, double *x, double *y, double *pD); -void dcolin_lib(int kmax, double *x, int offset, double *pD, int sdd); -void dcolad_lib(int kmax, double alpha, double *x, int offset, double *pD, int sdd); -void dcolin_libsp(int kmax, int *idx, double *x, double *pD, int sdd); -void dcolad_libsp(int kmax, double alpha, int *idx, double *x, double *pD, int sdd); -void dcolsw_lib(int kmax, int offsetA, double *pA, int sda, int offsetC, double *pC, int sdc); -void dvecin_libsp(int kmax, int *idx, double *x, double *y); -void dvecad_libsp(int kmax, int *idx, double alpha, double *x, double *y); diff --git a/third_party/acados/include/blasfeo/include/blasfeo_d_aux_ref.h b/third_party/acados/include/blasfeo/include/blasfeo_d_aux_ref.h deleted file mode 100644 index 1e007fa..0000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_d_aux_ref.h +++ /dev/null @@ -1,208 +0,0 @@ - -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_D_AUX_REF_H_ -#define BLASFEO_D_AUX_REF_H_ - - - -#include - -#include "blasfeo_common.h" -#include "blasfeo_d_aux_old.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - -// --- memory calculations -// -// returns the memory size (in bytes) needed for a dmat -size_t blasfeo_ref_memsize_dmat(int m, int n); -// returns the memory size (in bytes) needed for the diagonal of a dmat -size_t blasfeo_ref_memsize_diag_dmat(int m, int n); -// returns the memory size (in bytes) needed for a dvec -size_t blasfeo_ref_memsize_dvec(int m); - -// --- creation -// -// create a strmat for a matrix of size m*n by using memory passed by a pointer (pointer is not updated) -void blasfeo_ref_create_dmat(int m, int n, struct blasfeo_dmat *sA, void *memory); -// create a strvec for a vector of size m by using memory passed by a pointer (pointer is not updated) -void blasfeo_ref_create_dvec(int m, struct blasfeo_dvec *sA, void *memory); - -// --- packing -// pack the column-major matrix A into the matrix struct B -void blasfeo_ref_pack_dmat(int m, int n, double *A, int lda, struct blasfeo_dmat *sB, int bi, int bj); -// pack the lower-triangular column-major matrix A into the matrix struct B -void blasfeo_ref_pack_l_dmat(int m, int n, double *A, int lda, struct blasfeo_dmat *sB, int bi, int bj); -// pack the upper-triangular column-major matrix A into the matrix struct B -void blasfeo_ref_pack_u_dmat(int m, int n, double *A, int lda, struct blasfeo_dmat *sB, int bi, int bj); -// transpose and pack the column-major matrix A into the matrix struct B -void blasfeo_ref_pack_tran_dmat(int m, int n, double *A, int lda, struct blasfeo_dmat *sB, int bi, int bj); -// pack the vector x into the vector structure y -void blasfeo_ref_pack_dvec(int m, double *x, int xi, struct blasfeo_dvec *sy, int yi); -// unpack the matrix structure A into the column-major matrix B -void blasfeo_ref_unpack_dmat(int m, int n, struct blasfeo_dmat *sA, int ai, int aj, double *B, int ldb); -// transpose and unpack the matrix structure A into the column-major matrix B -void blasfeo_ref_unpack_tran_dmat(int m, int n, struct blasfeo_dmat *sA, int ai, int aj, double *B, int ldb); -// pack the vector structure x into the vector y -void blasfeo_ref_unpack_dvec(int m, struct blasfeo_dvec *sx, int xi, double *y, int yi); - -// --- cast -// -void ref_d_cast_mat2strmat(double *A, struct blasfeo_dmat *sA); // TODO -void ref_d_cast_diag_mat2strmat(double *dA, struct blasfeo_dmat *sA); // TODO -void ref_d_cast_vec2vecmat(double *a, struct blasfeo_dvec *sx); // TODO - - -// ge -// --- insert/extract -// -// sA[ai, aj] <= a -void blasfeo_ref_dgein1(double a, struct blasfeo_dmat *sA, int ai, int aj); -// <= sA[ai, aj] -double blasfeo_ref_dgeex1(struct blasfeo_dmat *sA, int ai, int aj); - -// --- set -// A <= alpha -void blasfeo_ref_dgese(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj); - -// --- copy / scale -// B <= A -void blasfeo_ref_dgecp(int m, int n, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj); -// A <= alpha*A -void blasfeo_ref_dgesc(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj); -// B <= alpha*A -void blasfeo_ref_dgecpsc(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj); -// B <= A, A lower triangular -void blasfeo_ref_dtrcp_l(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj); -void blasfeo_ref_dtrcpsc_l(int m, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj); -void blasfeo_ref_dtrsc_l(int m, double alpha, struct blasfeo_dmat *sA, int ai, int aj); - -// --- sum -// B <= B + alpha*A -void blasfeo_ref_dgead(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sC, int yi, int cj); -// y <= y + alpha*x -void blasfeo_ref_dvecad(int m, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sy, int yi); - -// --- traspositions -// B <= A' -void blasfeo_ref_dgetr(int m, int n, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj); -// B <= A', A lower triangular -void blasfeo_ref_dtrtr_l(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj); -// B <= A', A upper triangular -void blasfeo_ref_dtrtr_u(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj); - -// dia -// diag(A) += alpha -void blasfeo_ref_ddiare(int kmax, double alpha, struct blasfeo_dmat *sA, int ai, int aj); -// diag(A) <= alpha*x -void blasfeo_ref_ddiain(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dmat *sA, int ai, int aj); -// diag(A)[idx] <= alpha*x -void blasfeo_ref_ddiain_sp(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, int *idx, struct blasfeo_dmat *sD, int di, int dj); -// x <= diag(A) -void blasfeo_ref_ddiaex(int kmax, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi); -// x <= diag(A)[idx] -void blasfeo_ref_ddiaex_sp(int kmax, double alpha, int *idx, struct blasfeo_dmat *sD, int di, int dj, struct blasfeo_dvec *sx, int xi); -// diag(A) += alpha*x -void blasfeo_ref_ddiaad(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dmat *sA, int ai, int aj); -// diag(A)[idx] += alpha*x -void blasfeo_ref_ddiaad_sp(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, int *idx, struct blasfeo_dmat *sD, int di, int dj); -// diag(A)[idx] = y + alpha*x -void blasfeo_ref_ddiaadin_sp(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sy, int yi, int *idx, struct blasfeo_dmat *sD, int di, int dj); - -// row -void blasfeo_ref_drowin(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dmat *sA, int ai, int aj); -void blasfeo_ref_drowex(int kmax, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi); -void blasfeo_ref_drowad(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dmat *sA, int ai, int aj); -void blasfeo_ref_drowad_sp(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, int *idx, struct blasfeo_dmat *sD, int di, int dj); -void blasfeo_ref_drowsw(int kmax, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sC, int ci, int cj); -void blasfeo_ref_drowpe(int kmax, int *ipiv, struct blasfeo_dmat *sA); -void blasfeo_ref_drowpei(int kmax, int *ipiv, struct blasfeo_dmat *sA); - -// col -void blasfeo_ref_dcolex(int kmax, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi); -void blasfeo_ref_dcolin(int kmax, struct blasfeo_dvec *sx, int xi, struct blasfeo_dmat *sA, int ai, int aj); -void blasfeo_ref_dcolad(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dmat *sA, int ai, int aj); -void blasfeo_ref_dcolsc(int kmax, double alpha, struct blasfeo_dmat *sA, int ai, int aj); -void blasfeo_ref_dcolsw(int kmax, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sC, int ci, int cj); -void blasfeo_ref_dcolpe(int kmax, int *ipiv, struct blasfeo_dmat *sA); -void blasfeo_ref_dcolpei(int kmax, int *ipiv, struct blasfeo_dmat *sA); - -// vec -// a <= alpha -void blasfeo_ref_dvecse(int m, double alpha, struct blasfeo_dvec *sx, int xi); -// sx[xi] <= a -void blasfeo_ref_dvecin1(double a, struct blasfeo_dvec *sx, int xi); -// <= sx[xi] -double blasfeo_ref_dvecex1(struct blasfeo_dvec *sx, int xi); -// y <= x -void blasfeo_ref_dveccp(int m, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sy, int yi); -// x <= alpha*x -void blasfeo_ref_dvecsc(int m, double alpha, struct blasfeo_dvec *sx, int xi); -// y <= alpha*x -void blasfeo_ref_dveccpsc(int m, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sy, int yi); -void blasfeo_ref_dvecad_sp(int m, double alpha, struct blasfeo_dvec *sx, int xi, int *idx, struct blasfeo_dvec *sz, int zi); -void blasfeo_ref_dvecin_sp(int m, double alpha, struct blasfeo_dvec *sx, int xi, int *idx, struct blasfeo_dvec *sz, int zi); -void blasfeo_ref_dvecex_sp(int m, double alpha, int *idx, struct blasfeo_dvec *sx, int x, struct blasfeo_dvec *sz, int zi); -// z += alpha * x[idx] -void blasfeo_ref_dvecexad_sp(int m, double alpha, int *idx, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); - -void blasfeo_ref_dveccl(int m, - struct blasfeo_dvec *sxm, int xim, struct blasfeo_dvec *sx, int xi, - struct blasfeo_dvec *sxp, int xip, struct blasfeo_dvec *sz, int zi); - -void blasfeo_ref_dveccl_mask(int m, - struct blasfeo_dvec *sxm, int xim, struct blasfeo_dvec *sx, int xi, - struct blasfeo_dvec *sxp, int xip, struct blasfeo_dvec *sz, int zi, - struct blasfeo_dvec *sm, int mi); - -void blasfeo_ref_dvecze(int m, struct blasfeo_dvec *sm, int mi, struct blasfeo_dvec *sv, int vi, struct blasfeo_dvec *se, int ei); -void blasfeo_ref_dvecnrm_inf(int m, struct blasfeo_dvec *sx, int xi, double *ptr_norm); -void blasfeo_ref_dvecpe(int kmax, int *ipiv, struct blasfeo_dvec *sx, int xi); -void blasfeo_ref_dvecpei(int kmax, int *ipiv, struct blasfeo_dvec *sx, int xi); - - - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_D_AUX_REF_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_d_aux_test.h b/third_party/acados/include/blasfeo/include/blasfeo_d_aux_test.h deleted file mode 100644 index 1c61635..0000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_d_aux_test.h +++ /dev/null @@ -1,226 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -/* - * auxiliary algebra operations header - * - * include/blasfeo_aux_lib*.h - * - */ - -#ifndef BLASFEO_D_AUX_TEST_H_ -#define BLASFEO_D_AUX_TEST_H_ - -#include "blasfeo_common.h" - - -#ifdef __cplusplus -extern "C" { -#endif - -// --- memory calculations -int test_blasfeo_memsize_dmat(int m, int n); -int test_blasfeo_memsize_diag_dmat(int m, int n); -int test_blasfeo_memsize_dvec(int m); - -// --- creation -void test_blasfeo_create_dmat(int m, int n, struct blasfeo_dmat *sA, void *memory); -void test_blasfeo_create_dvec(int m, struct blasfeo_dvec *sA, void *memory); - -// --- conversion -void test_blasfeo_pack_dmat(int m, int n, double *A, int lda, struct blasfeo_dmat *sA, int ai, int aj); -void test_blasfeo_pack_dvec(int m, double *x, int xi, struct blasfeo_dvec *sa, int ai); -void test_blasfeo_pack_tran_dmat(int m, int n, double *A, int lda, struct blasfeo_dmat *sA, int ai, int aj); -void test_blasfeo_unpack_dmat(int m, int n, struct blasfeo_dmat *sA, int ai, int aj, double *A, int lda); -void test_blasfeo_unpack_dvec(int m, struct blasfeo_dvec *sa, int ai, double *x, int xi); -void test_blasfeo_unpack_tran_dmat(int m, int n, struct blasfeo_dmat *sA, int ai, int aj, double *A, int lda); - -// --- cast -void test_d_cast_mat2strmat(double *A, struct blasfeo_dmat *sA); -void test_d_cast_diag_mat2strmat(double *dA, struct blasfeo_dmat *sA); -void test_d_cast_vec2vecmat(double *a, struct blasfeo_dvec *sa); - -// ------ copy / scale - -// B <= A -void test_blasfeo_dgecp(int m, int n, - struct blasfeo_dmat *sA, int ai, int aj, - struct blasfeo_dmat *sB, int bi, int bj); - -// A <= alpha*A -void test_blasfeo_dgesc(int m, int n, - double alpha, - struct blasfeo_dmat *sA, int ai, int aj); - -// B <= alpha*A -void test_blasfeo_dgecpsc(int m, int n, - double alpha, - struct blasfeo_dmat *sA, int ai, int aj, - struct blasfeo_dmat *sB, int bi, int bj); - -// // --- insert/extract -// // -// // <= sA[ai, aj] -// void test_blasfeo_dgein1(double a, struct blasfeo_dmat *sA, int ai, int aj); -// // <= sA[ai, aj] -// double blasfeo_dgeex1(struct blasfeo_dmat *sA, int ai, int aj); -// // sx[xi] <= a -// void test_blasfeo_dvecin1(double a, struct blasfeo_dvec *sx, int xi); -// // <= sx[xi] -// double blasfeo_dvecex1(struct blasfeo_dvec *sx, int xi); -// // A <= alpha - -// // --- set -// void test_blasfeo_dgese(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj); -// // a <= alpha -// void test_blasfeo_dvecse(int m, double alpha, struct blasfeo_dvec *sx, int xi); -// // B <= A - - -// // --- vector -// // y <= x -// void test_blasfeo_dveccp(int m, struct blasfeo_dvec *sa, int ai, struct blasfeo_dvec *sc, int ci); -// // x <= alpha*x -// void test_blasfeo_dvecsc(int m, double alpha, struct blasfeo_dvec *sa, int ai); -// // TODO -// // x <= alpha*x -// void test_blasfeo_dveccpsc(int m, double alpha, struct blasfeo_dvec *sa, int ai, struct blasfeo_dvec *sc, int ci); - - -// // B <= A, A lower triangular -// void test_blasfeo_dtrcp_l(int m, -// struct blasfeo_dmat *sA, int ai, int aj, -// struct blasfeo_dmat *sB, int bi, int bj); - -// void test_blasfeo_dtrcpsc_l(int m, double alpha, -// struct blasfeo_dmat *sA, int ai, int aj, -// struct blasfeo_dmat *sB, int bi, int bj); - -// void test_blasfeo_dtrsc_l(int m, double alpha, -// struct blasfeo_dmat *sA, int ai, int aj); - - -// // B <= B + alpha*A -// void test_blasfeo_dgead(int m, int n, double alpha, -// struct blasfeo_dmat *sA, int ai, int aj, -// struct blasfeo_dmat *sC, int ci, int cj); - -// // y <= y + alpha*x -// void test_blasfeo_dvecad(int m, double alpha, -// struct blasfeo_dvec *sa, int ai, -// struct blasfeo_dvec *sc, int ci); - -// // --- traspositions -// void test_dgetr_lib(int m, int n, double alpha, int offsetA, double *pA, int sda, int offsetC, double *pC, int sdc); -// void test_blasfeo_dgetr(int m, int n, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sC, int ci, int cj); -// void test_dtrtr_l_lib(int m, double alpha, int offsetA, double *pA, int sda, int offsetC, double *pC, int sdc); -// void test_blasfeo_dtrtr_l(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sC, int ci, int cj); -// void test_dtrtr_u_lib(int m, double alpha, int offsetA, double *pA, int sda, int offsetC, double *pC, int sdc); -// void test_blasfeo_dtrtr_u(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sC, int ci, int cj); -// void test_blasfeo_ddiare(int kmax, double alpha, struct blasfeo_dmat *sA, int ai, int aj); -// void test_blasfeo_ddiain(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dmat *sA, int ai, int aj); -// void test_ddiaex_lib(int kmax, double alpha, int offset, double *pD, int sdd, double *x); -// void test_ddiaad_lib(int kmax, double alpha, double *x, int offset, double *pD, int sdd); -// void test_ddiain_libsp(int kmax, int *idx, double alpha, double *x, double *pD, int sdd); -// void test_blasfeo_ddiain_sp(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, int *idx, struct blasfeo_dmat *sD, int di, int dj); -// void test_ddiaex_libsp(int kmax, int *idx, double alpha, double *pD, int sdd, double *x); -// void test_blasfeo_ddiaex(int kmax, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi); -// void test_blasfeo_ddiaex_sp(int kmax, double alpha, int *idx, struct blasfeo_dmat *sD, int di, int dj, struct blasfeo_dvec *sx, int xi); -// void test_blasfeo_ddiaad(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dmat *sA, int ai, int aj); -// void test_ddiaad_libsp(int kmax, int *idx, double alpha, double *x, double *pD, int sdd); -// void test_blasfeo_ddiaad_sp(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, int *idx, struct blasfeo_dmat *sD, int di, int dj); -// void test_ddiaadin_libsp(int kmax, int *idx, double alpha, double *x, double *y, double *pD, int sdd); -// void test_blasfeo_ddiaadin_sp(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sy, int yi, int *idx, struct blasfeo_dmat *sD, int di, int dj); -// void test_drowin_lib(int kmax, double alpha, double *x, double *pD); -// void test_blasfeo_drowin(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dmat *sA, int ai, int aj); -// void test_drowex_lib(int kmax, double alpha, double *pD, double *x); -// void test_blasfeo_drowex(int kmax, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi); -// void test_drowad_lib(int kmax, double alpha, double *x, double *pD); -// void test_blasfeo_drowad(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dmat *sA, int ai, int aj); -// void test_drowin_libsp(int kmax, double alpha, int *idx, double *x, double *pD); -// void test_drowad_libsp(int kmax, int *idx, double alpha, double *x, double *pD); -// void test_blasfeo_drowad_sp(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, int *idx, struct blasfeo_dmat *sD, int di, int dj); -// void test_drowadin_libsp(int kmax, int *idx, double alpha, double *x, double *y, double *pD); -// void test_drowsw_lib(int kmax, double *pA, double *pC); -// void test_blasfeo_drowsw(int kmax, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sC, int ci, int cj); -// void test_blasfeo_drowpe(int kmax, int *ipiv, struct blasfeo_dmat *sA); -// void test_blasfeo_dcolex(int kmax, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi); -// void test_dcolin_lib(int kmax, double *x, int offset, double *pD, int sdd); -// void test_blasfeo_dcolin(int kmax, struct blasfeo_dvec *sx, int xi, struct blasfeo_dmat *sA, int ai, int aj); -// void test_dcolad_lib(int kmax, double alpha, double *x, int offset, double *pD, int sdd); -// void test_dcolin_libsp(int kmax, int *idx, double *x, double *pD, int sdd); -// void test_dcolad_libsp(int kmax, double alpha, int *idx, double *x, double *pD, int sdd); -// void test_dcolsw_lib(int kmax, int offsetA, double *pA, int sda, int offsetC, double *pC, int sdc); -// void test_blasfeo_dcolsw(int kmax, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sC, int ci, int cj); -// void test_blasfeo_dcolpe(int kmax, int *ipiv, struct blasfeo_dmat *sA); -// void test_dvecin_libsp(int kmax, int *idx, double *x, double *y); -// void test_dvecad_libsp(int kmax, int *idx, double alpha, double *x, double *y); -// void test_blasfeo_dvecad_sp(int m, double alpha, struct blasfeo_dvec *sx, int xi, int *idx, struct blasfeo_dvec *sz, int zi); -// void test_blasfeo_dvecin_sp(int m, double alpha, struct blasfeo_dvec *sx, int xi, int *idx, struct blasfeo_dvec *sz, int zi); -// void test_blasfeo_dvecex_sp(int m, double alpha, int *idx, struct blasfeo_dvec *sx, int x, struct blasfeo_dvec *sz, int zi); -// void test_blasfeo_dveccl(int m, struct blasfeo_dvec *sxm, int xim, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sxp, int xip, struct blasfeo_dvec *sz, int zi); -// void test_blasfeo_dveccl_mask(int m, struct blasfeo_dvec *sxm, int xim, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sxp, int xip, struct blasfeo_dvec *sz, int zi, struct blasfeo_dvec *sm, int mi); -// void test_blasfeo_dvecze(int m, struct blasfeo_dvec *sm, int mi, struct blasfeo_dvec *sv, int vi, struct blasfeo_dvec *se, int ei); -// void test_blasfeo_dvecnrm_inf(int m, struct blasfeo_dvec *sx, int xi, double *ptr_norm); -// void test_blasfeo_dvecpe(int kmax, int *ipiv, struct blasfeo_dvec *sx, int xi); -// void test_blasfeo_dvecpei(int kmax, int *ipiv, struct blasfeo_dvec *sx, int xi); - -// ext_dep - -void test_blasfeo_allocate_dmat(int m, int n, struct blasfeo_dmat *sA); -void test_blasfeo_allocate_dvec(int m, struct blasfeo_dvec *sa); - -void test_blasfeo_free_dmat(struct blasfeo_dmat *sA); -void test_blasfeo_free_dvec(struct blasfeo_dvec *sa); - -void test_blasfeo_print_dmat(int m, int n, struct blasfeo_dmat *sA, int ai, int aj); -void test_blasfeo_print_dvec(int m, struct blasfeo_dvec *sa, int ai); -void test_blasfeo_print_tran_dvec(int m, struct blasfeo_dvec *sa, int ai); - -void test_blasfeo_print_to_file_dmat(FILE *file, int m, int n, struct blasfeo_dmat *sA, int ai, int aj); -void test_blasfeo_print_to_file_dvec(FILE *file, int m, struct blasfeo_dvec *sa, int ai); -void test_blasfeo_print_to_file_tran_dvec(FILE *file, int m, struct blasfeo_dvec *sa, int ai); - -void test_blasfeo_print_exp_dmat(int m, int n, struct blasfeo_dmat *sA, int ai, int aj); -void test_blasfeo_print_exp_dvec(int m, struct blasfeo_dvec *sa, int ai); -void test_blasfeo_print_exp_tran_dvec(int m, struct blasfeo_dvec *sa, int ai); - - - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_D_AUX_TEST_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_d_blas.h b/third_party/acados/include/blasfeo/include/blasfeo_d_blas.h deleted file mode 100644 index ea8d006..0000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_d_blas.h +++ /dev/null @@ -1,46 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_D_BLAS_H_ -#define BLASFEO_D_BLAS_H_ - - - -#include "blasfeo_d_blasfeo_api.h" -#include "blasfeo_d_blas_api.h" - - - -#endif // BLASFEO_D_BLAS_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_d_blas_api.h b/third_party/acados/include/blasfeo/include/blasfeo_d_blas_api.h deleted file mode 100644 index 2eab1e4..0000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_d_blas_api.h +++ /dev/null @@ -1,281 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef BLASFEO_D_BLAS_API_H_ -#define BLASFEO_D_BLAS_API_H_ - - - -#include "blasfeo_target.h" - - - -#ifdef BLAS_API -#ifdef CBLAS_API -#ifndef BLASFEO_CBLAS_ENUM -#define BLASFEO_CBLAS_ENUM -#ifdef FORTRAN_BLAS_API -#ifndef CBLAS_H -enum CBLAS_LAYOUT {CblasRowMajor=101, CblasColMajor=102}; -enum CBLAS_TRANSPOSE {CblasNoTrans=111, CblasTrans=112, CblasConjTrans=113}; -enum CBLAS_UPLO {CblasUpper=121, CblasLower=122}; -enum CBLAS_DIAG {CblasNonUnit=131, CblasUnit=132}; -enum CBLAS_SIDE {CblasLeft=141, CblasRight=142}; -#define CBLAS_ORDER CBLAS_LAYOUT /* this for backward compatibility with CBLAS_ORDER */ -#endif // CBLAS_H -#else // FORTRAN_BLAS_API -enum BLASFEO_CBLAS_LAYOUT {BlasfeoCblasRowMajor=101, BlasfeoCblasColMajor=102}; -enum BLASFEO_CBLAS_TRANSPOSE {BlasfeoCblasNoTrans=111, BlasfeoCblasTrans=112, BlasfeoCblasConjTrans=113}; -enum BLASFEO_CBLAS_UPLO {BlasfeoCblasUpper=121, BlasfeoCblasLower=122}; -enum BLASFEO_CBLAS_DIAG {BlasfeoCblasNonUnit=131, BlasfeoCblasUnit=132}; -enum BLASFEO_CBLAS_SIDE {BlasfeoCblasLeft=141, BlasfeoCblasRight=142}; -#define BLASFEO_CBLAS_ORDER BLASFEO_CBLAS_LAYOUT /* this for backward compatibility with BLASFEO_CBLAS_ORDER */ -#endif // FORTRAN_BLAS_API -#endif // BLASFEO_CBLAS_ENUM -#endif // CBLAS_API -#endif // BLAS_API - - -#ifdef __cplusplus -extern "C" { -#endif - - - -#ifdef BLAS_API - - - -#ifdef FORTRAN_BLAS_API - - - -// BLAS 1 -// -void daxpy_(int *n, double *alpha, double *x, int *incx, double *y, int *incy); -// -void dcopy_(int *n, double *x, int *incx, double *y, int *incy); -// -double ddot_(int *n, double *x, int *incx, double *y, int *incy); - -// BLAS 2 -// -void dgemv_(char *tran, int *m, int *n, double *alpha, double *A, int *lda, double *x, int *incx, double *beta, double *y, int *incy); -// -void dsymv_(char *uplo, int *n, double *alpha, double *A, int *lda, double *x, int *incx, double *beta, double *y, int *incy); -// -void dger_(int *m, int *n, double *alpha, double *x, int *incx, double *y, int *incy, double *A, int *lda); - -// BLAS 3 -// -void dgemm_(char *ta, char *tb, int *m, int *n, int *k, double *alpha, double *A, int *lda, double *B, int *ldb, double *beta, double *C, int *ldc); -// -void dsyrk_(char *uplo, char *ta, int *m, int *k, double *alpha, double *A, int *lda, double *beta, double *C, int *ldc); -// -void dtrmm_(char *side, char *uplo, char *transa, char *diag, int *m, int *n, double *alpha, double *A, int *lda, double *B, int *ldb); -// -void dtrsm_(char *side, char *uplo, char *transa, char *diag, int *m, int *n, double *alpha, double *A, int *lda, double *B, int *ldb); -// -void dsyr2k_(char *uplo, char *ta, int *m, int *k, double *alpha, double *A, int *lda, double *B, int *ldb, double *beta, double *C, int *ldc); - - - -// LAPACK -// -void dgesv_(int *m, int *n, double *A, int *lda, int *ipiv, double *B, int *ldb, int *info); -// -void dgetrf_(int *m, int *n, double *A, int *lda, int *ipiv, int *info); -// -void dgetrf_np_(int *m, int *n, double *A, int *lda, int *info); -// -void dgetrs_(char *trans, int *m, int *n, double *A, int *lda, int *ipiv, double *B, int *ldb, int *info); -// -void dlaswp_(int *n, double *A, int *lda, int *k1, int *k2, int *ipiv, int *incx); -// -void dposv_(char *uplo, int *m, int *n, double *A, int *lda, double *B, int *ldb, int *info); -// -void dpotrf_(char *uplo, int *m, double *A, int *lda, int *info); -// -void dpotrs_(char *uplo, int *m, int *n, double *A, int *lda, double *B, int *ldb, int *info); -// -void dtrtrs_(char *uplo, char *trans, char *diag, int *m, int *n, double *A, int *lda, double *B, int *ldb, int *info); - - - -// aux -void dgetr_(int *m, int *n, double *A, int *lda, double *B, int *ldb); - - - -#ifdef CBLAS_API - - - -// CBLAS 1 -// -void cblas_daxpy(const int N, const double alpha, const double *X, const int incX, double *Y, const int incY); -// -void cblas_dswap(const int N, double *X, const int incX, double *Y, const int incY); -// -void cblas_dcopy(const int N, const double *X, const int incX, double *Y, const int incY); - -// CBLAS 2 -// -void cblas_dgemv(const enum CBLAS_LAYOUT layout, const enum CBLAS_TRANSPOSE TransA, const int M, const int N, const int K, const double alpha, const double *A, const int lda, const double *X, const int incX, const double beta, double *Y, const int incY); - -// CBLAS 3 -// -void cblas_dgemm(const enum CBLAS_LAYOUT layout, const enum CBLAS_TRANSPOSE TransA, const enum CBLAS_TRANSPOSE TransB, const int M, const int N, const int K, const double alpha, const double *A, const int lda, const double *B, const int ldb, const double beta, double *C, const int ldc); -// -void cblas_dsyrk(const enum CBLAS_LAYOUT layout, const enum CBLAS_UPLO Uplo, const enum CBLAS_TRANSPOSE Trans, const int N, const int K, const double alpha, const double *A, const int lda, const double beta, double *C, const int ldc); -// -void cblas_dtrmm(const enum CBLAS_LAYOUT layout, const enum CBLAS_SIDE Side, const enum CBLAS_UPLO Uplo, const enum CBLAS_TRANSPOSE TransA, const enum CBLAS_DIAG Diag, const int M, const int N, const double alpha, const double *A, const int lda, double *B, const int ldb); -// -void cblas_dtrsm(const enum CBLAS_LAYOUT layout, const enum CBLAS_SIDE Side, const enum CBLAS_UPLO Uplo, const enum CBLAS_TRANSPOSE TransA, const enum CBLAS_DIAG Diag, const int M, const int N, const double alpha, const double *A, const int lda, double *B, const int ldb); - - - -#endif // CBLAS_API - - - -#else // BLASFEO_API - - - -// BLAS 1 -// -void blasfeo_blas_daxpy(int *n, double *alpha, double *x, int *incx, double *y, int *incy); -// -double blasfeo_blas_ddot(int *n, double *x, int *incx, double *y, int *incy); -// -void blasfeo_blas_dcopy(int *n, double *x, int *incx, double *y, int *incy); - -// BLAS 2 -// -void blasfeo_blas_dgemv(char *trans, int *m, int *n, double *alpha, double *A, int *lda, double *x, int *incx, double *beta, double *y, int *incy); -// -void blasfeo_blas_dsymv(char *uplo, int *n, double *alpha, double *A, int *lda, double *x, int *incx, double *beta, double *y, int *incy); -// -void blasfeo_blas_dger(int *m, int *n, double *alpha, double *x, int *incx, double *y, int *incy, double *A, int *lda); - -// BLAS 3 -// -void blasfeo_blas_dgemm(char *ta, char *tb, int *m, int *n, int *k, double *alpha, double *A, int *lda, double *B, int *ldb, double *beta, double *C, int *ldc); -// -void blasfeo_blas_dsyrk(char *uplo, char *ta, int *m, int *k, double *alpha, double *A, int *lda, double *beta, double *C, int *ldc); -// -void blasfeo_blas_dtrmm(char *side, char *uplo, char *transa, char *diag, int *m, int *n, double *alpha, double *A, int *lda, double *B, int *ldb); -// -void blasfeo_blas_dtrsm(char *side, char *uplo, char *transa, char *diag, int *m, int *n, double *alpha, double *A, int *lda, double *B, int *ldb); -// -void blasfeo_blas_dsyr2k(char *uplo, char *ta, int *m, int *k, double *alpha, double *A, int *lda, double *B, int *ldb, double *beta, double *C, int *ldc); - - - -// LAPACK -// -void blasfeo_lapack_dgesv(int *m, int *n, double *A, int *lda, int *ipiv, double *B, int *ldb, int *info); -// -void blasfeo_lapack_dgetrf(int *m, int *n, double *A, int *lda, int *ipiv, int *info); -// -void blasfeo_lapack_dgetrf_np(int *m, int *n, double *A, int *lda, int *info); -// -void blasfeo_lapack_dgetrs(char *trans, int *m, int *n, double *A, int *lda, int *ipiv, double *B, int *ldb, int *info); -// -void blasfeo_lapack_dlaswp(int *n, double *A, int *lda, int *k1, int *k2, int *ipiv, int *incx); -// -void blasfeo_lapack_dposv(char *uplo, int *m, int *n, double *A, int *lda, double *B, int *ldb, int *info); -// -void blasfeo_lapack_dpotrf(char *uplo, int *m, double *A, int *lda, int *info); -// -void blasfeo_lapack_dpotrs(char *uplo, int *m, int *n, double *A, int *lda, double *B, int *ldb, int *info); -// -void blasfeo_lapack_dtrtrs(char *uplo, char *trans, char *diag, int *m, int *n, double *A, int *lda, double *B, int *ldb, int *info); - - - -// aux -void blasfeo_blas_dgetr(int *m, int *n, double *A, int *lda, double *B, int *ldb); - - - -#ifdef CBLAS_API - - - -// CBLAS 1 -// -void blasfeo_cblas_daxpy(const int N, const double alpha, const double *X, const int incX, double *Y, const int incY); -// -void blasfeo_cblas_dswap(const int N, double *X, const int incX, double *Y, const int incY); -// -void blasfeo_cblas_dcopy(const int N, const double *X, const int incX, double *Y, const int incY); - -// CBLAS 2 -// -void blasfeo_cblas_dgemv(const enum BLASFEO_CBLAS_LAYOUT layout, const enum BLASFEO_CBLAS_TRANSPOSE TransA, const int M, const int N, const double alpha, const double *A, const int lda, const double *X, const int incX, const double beta, double *Y, const int incY); - -// CBLAS 3 -// -void blasfeo_cblas_dgemm(const enum BLASFEO_CBLAS_LAYOUT layout, const enum BLASFEO_CBLAS_TRANSPOSE TransA, const enum BLASFEO_CBLAS_TRANSPOSE TransB, const int M, const int N, const int K, const double alpha, const double *A, const int lda, const double *B, const int ldb, const double beta, double *C, const int ldc); -// -void blasfeo_cblas_dsyrk(const enum BLASFEO_CBLAS_LAYOUT layout, const enum BLASFEO_CBLAS_UPLO Uplo, const enum BLASFEO_CBLAS_TRANSPOSE Trans, const int N, const int K, const double alpha, const double *A, const int lda, const double beta, double *C, const int ldc); -// -void blasfeo_cblas_dtrmm(const enum BLASFEO_CBLAS_LAYOUT layout, const enum BLASFEO_CBLAS_SIDE Side, const enum BLASFEO_CBLAS_UPLO Uplo, const enum BLASFEO_CBLAS_TRANSPOSE TransA, const enum BLASFEO_CBLAS_DIAG Diag, const int M, const int N, const double alpha, const double *A, const int lda, double *B, const int ldb); -// -void blasfeo_cblas_dtrsm(const enum BLASFEO_CBLAS_LAYOUT layout, const enum BLASFEO_CBLAS_SIDE Side, const enum BLASFEO_CBLAS_UPLO Uplo, const enum BLASFEO_CBLAS_TRANSPOSE TransA, const enum BLASFEO_CBLAS_DIAG Diag, const int M, const int N, const double alpha, const double *A, const int lda, double *B, const int ldb); - - - -#endif // CBLAS_API - - - -#endif // BLASFEO_API - - - -#endif // BLAS_API - - - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_D_BLAS_API_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_d_blasfeo_api.h b/third_party/acados/include/blasfeo/include/blasfeo_d_blasfeo_api.h deleted file mode 100644 index 88bb3fc..0000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_d_blasfeo_api.h +++ /dev/null @@ -1,364 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_D_BLASFEO_API_H_ -#define BLASFEO_D_BLASFEO_API_H_ - - - -#include "blasfeo_common.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -// -// level 1 BLAS -// - -// z = y + alpha*x -// z[zi:zi+n] = alpha*x[xi:xi+n] + y[yi:yi+n] -// NB: Different arguments semantic compare to equivalent standard BLAS routine -void blasfeo_daxpy(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); -// z = beta*y + alpha*x -void blasfeo_daxpby(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, double beta, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); -// z = x .* y -void blasfeo_dvecmul(int m, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); -// z += x .* y -void blasfeo_dvecmulacc(int m, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); -// z = x .* y, return sum(z) = x^T * y -double blasfeo_dvecmuldot(int m, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); -// return x^T * y -double blasfeo_ddot(int m, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sy, int yi); -// construct givens plane rotation -void blasfeo_drotg(double a, double b, double *c, double *s); -// apply plane rotation [a b] [c -s; s; c] to the aj0 and aj1 columns of A at row index ai -void blasfeo_dcolrot(int m, struct blasfeo_dmat *sA, int ai, int aj0, int aj1, double c, double s); -// apply plane rotation [c s; -s c] [a; b] to the ai0 and ai1 rows of A at column index aj -void blasfeo_drowrot(int m, struct blasfeo_dmat *sA, int ai0, int ai1, int aj, double c, double s); - - - -// -// level 2 BLAS -// - -// dense - -// z <= beta * y + alpha * A * x -void blasfeo_dgemv_n(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, double beta, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); -// z <= beta * y + alpha * A^T * x -void blasfeo_dgemv_t(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, double beta, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); -// z <= inv( A ) * x, A (m)x(n) -void blasfeo_dtrsv_lnn_mn(int m, int n, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= inv( A^T ) * x, A (m)x(n) -void blasfeo_dtrsv_ltn_mn(int m, int n, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= inv( A ) * x, A (m)x(m) lower, not_transposed, not_unit -void blasfeo_dtrsv_lnn(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= inv( A ) * x, A (m)x(m) lower, not_transposed, unit -void blasfeo_dtrsv_lnu(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= inv( A^T ) * x, A (m)x(m) lower, transposed, not_unit -void blasfeo_dtrsv_ltn(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= inv( A^T ) * x, A (m)x(m) lower, transposed, unit -void blasfeo_dtrsv_ltu(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= inv( A^T ) * x, A (m)x(m) upper, not_transposed, not_unit -void blasfeo_dtrsv_unn(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= inv( A^T ) * x, A (m)x(m) upper, transposed, not_unit -void blasfeo_dtrsv_utn(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= A * x ; A lower triangular -void blasfeo_dtrmv_lnn(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= A * x ; A lower triangular, unit diagonal -void blasfeo_dtrmv_lnu(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= A^T * x ; A lower triangular -void blasfeo_dtrmv_ltn(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= A^T * x ; A lower triangular, unit diagonal -void blasfeo_dtrmv_ltu(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= beta * y + alpha * A * x ; A upper triangular -void blasfeo_dtrmv_unn(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= A^T * x ; A upper triangular -void blasfeo_dtrmv_utn(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z_n <= beta_n * y_n + alpha_n * A * x_n -// z_t <= beta_t * y_t + alpha_t * A^T * x_t -void blasfeo_dgemv_nt(int m, int n, double alpha_n, double alpha_t, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx_n, int xi_n, struct blasfeo_dvec *sx_t, int xi_t, double beta_n, double beta_t, struct blasfeo_dvec *sy_n, int yi_n, struct blasfeo_dvec *sy_t, int yi_t, struct blasfeo_dvec *sz_n, int zi_n, struct blasfeo_dvec *sz_t, int zi_t); -// z <= beta * y + alpha * A * x, where A is symmetric and only the lower triangular patr of A is accessed -void blasfeo_dsymv_l(int m, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, double beta, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); -void blasfeo_dsymv_l_mn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, double beta, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); -// z <= beta * y + alpha * A * x, where A is symmetric and only the upper triangular patr of A is accessed -void blasfeo_dsymv_u(int m, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, double beta, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); -// D = C + alpha * x * y^T -void blasfeo_dger(int m, int n, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sy, int yi, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); - -// diagonal - -// z <= beta * y + alpha * A * x, A diagonal -void blasfeo_dgemv_d(int m, double alpha, struct blasfeo_dvec *sA, int ai, struct blasfeo_dvec *sx, int xi, double beta, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); - - - -// -// level 3 BLAS -// - -// dense - -// D <= beta * C + alpha * A * B -void blasfeo_dgemm_nn(int m, int n, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= beta * C + alpha * A * B^T -void blasfeo_dgemm_nt(int m, int n, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= beta * C + alpha * A^T * B -void blasfeo_dgemm_tn(int m, int n, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= beta * C + alpha * A^T * B^T -void blasfeo_dgemm_tt(int m, int n, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= beta * C + alpha * A * B^T ; C, D lower triangular -void blasfeo_dsyrk_ln(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -void blasfeo_dsyrk_ln_mn(int m, int n, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -#if ( defined(LA_HIGH_PERFORMANCE) & defined(MF_COLMAJ) ) -void blasfeo_dsyrk3_ln(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -#endif -// D <= beta * C + alpha * A^T * B ; C, D lower triangular -void blasfeo_dsyrk_lt(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -#if ( defined(LA_HIGH_PERFORMANCE) & defined(MF_COLMAJ) ) -void blasfeo_dsyrk3_lt(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -#endif -// D <= beta * C + alpha * A * B^T ; C, D upper triangular -void blasfeo_dsyrk_un(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -#if ( defined(LA_HIGH_PERFORMANCE) & defined(MF_COLMAJ) ) -void blasfeo_dsyrk3_un(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -#endif -// D <= beta * C + alpha * A^T * B ; C, D upper triangular -void blasfeo_dsyrk_ut(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -#if ( defined(LA_HIGH_PERFORMANCE) & defined(MF_COLMAJ) ) -void blasfeo_dsyrk3_ut(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -#endif -// D <= alpha * A * B ; A lower triangular -void blasfeo_dtrmm_llnn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A * B ; A lower triangular -void blasfeo_dtrmm_llnu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^T * B ; A lower triangular -void blasfeo_dtrmm_lltn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^T * B ; A lower triangular -void blasfeo_dtrmm_lltu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A * B ; A upper triangular -void blasfeo_dtrmm_lunn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A * B ; A upper triangular -void blasfeo_dtrmm_lunu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^T * B ; A upper triangular -void blasfeo_dtrmm_lutn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^T * B ; A upper triangular -void blasfeo_dtrmm_lutu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A ; A lower triangular -void blasfeo_dtrmm_rlnn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A ; A lower triangular -void blasfeo_dtrmm_rlnu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^T ; A lower triangular -void blasfeo_dtrmm_rltn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^T ; A lower triangular -void blasfeo_dtrmm_rltu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A ; A upper triangular -void blasfeo_dtrmm_runn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A ; A upper triangular -void blasfeo_dtrmm_runu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^T ; A upper triangular -void blasfeo_dtrmm_rutn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^T ; A upper triangular -void blasfeo_dtrmm_rutu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^{-1} * B , with A lower triangular employint explicit inverse of diagonal -// D <= alpha * A^{-1} * B , with A lower triangular employing explicit inverse of diagonal -void blasfeo_dtrsm_llnn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^{-1} * B , with A lower triangular with unit diagonal -void blasfeo_dtrsm_llnu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^{-T} * B , with A lower triangular employing explicit inverse of diagonal -void blasfeo_dtrsm_lltn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^{-T} * B , with A lower triangular with unit diagonal -void blasfeo_dtrsm_lltu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^{-1} * B , with A upper triangular employing explicit inverse of diagonal -void blasfeo_dtrsm_lunn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^{-1} * B , with A upper triangular with unit diagonal -void blasfeo_dtrsm_lunu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^{-T} * B , with A upper triangular employing explicit inverse of diagonal -void blasfeo_dtrsm_lutn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^{-T} * B , with A upper triangular with unit diagonal -void blasfeo_dtrsm_lutu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^{-1} , with A lower triangular employing explicit inverse of diagonal -void blasfeo_dtrsm_rlnn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^{-1} , with A lower triangular with unit diagonal -void blasfeo_dtrsm_rlnu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^{-T} , with A lower triangular employing explicit inverse of diagonal -void blasfeo_dtrsm_rltn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^{-T} , with A lower triangular with unit diagonal -void blasfeo_dtrsm_rltu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^{-1} , with A upper triangular employing explicit inverse of diagonal -void blasfeo_dtrsm_runn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^{-1} , with A upper triangular with unit diagonal -void blasfeo_dtrsm_runu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^{-T} , with A upper triangular employing explicit inverse of diagonal -void blasfeo_dtrsm_rutn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^{-T} , with A upper triangular with unit diagonal -void blasfeo_dtrsm_rutu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= beta * C + alpha * A * B^T + alpha * B * A^T; C, D lower triangular -void blasfeo_dsyr2k_ln(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= beta * C + alpha * A^T * B + alpha * B^T * A; C, D lower triangular -void blasfeo_dsyr2k_lt(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= beta * C + alpha * A * B^T + alpha * B * A^T; C, D upper triangular -void blasfeo_dsyr2k_un(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= beta * C + alpha * A^T * B + alpha * B^T * A; C, D upper triangular -void blasfeo_dsyr2k_ut(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); - -// diagonal - -// D <= alpha * A * B + beta * C, with A diagonal (stored as strvec) -void dgemm_diag_left_lib(int m, int n, double alpha, double *dA, double *pB, int sdb, double beta, double *pC, int sdc, double *pD, int sdd); -void blasfeo_dgemm_dn(int m, int n, double alpha, struct blasfeo_dvec *sA, int ai, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A * B + beta * C, with B diagonal (stored as strvec) -void blasfeo_dgemm_nd(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sB, int bi, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); - - - -// -// LAPACK -// - -// D <= chol( C ) ; C, D lower triangular -void blasfeo_dpotrf_l(int m, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -void blasfeo_dpotrf_l_mn(int m, int n, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= chol( C ) ; C, D upper triangular -void blasfeo_dpotrf_u(int m, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= chol( C + A * B' ) ; C, D lower triangular -// D <= chol( C + A * B^T ) ; C, D lower triangular -void blasfeo_dsyrk_dpotrf_ln(int m, int k, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -void blasfeo_dsyrk_dpotrf_ln_mn(int m, int n, int k, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= lu( C ) ; no pivoting -void blasfeo_dgetrf_np(int m, int n, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= lu( C ) ; row pivoting -void blasfeo_dgetrf_rp(int m, int n, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj, int *ipiv); -// D <= qr( C ) -int blasfeo_dgeqrf_worksize(int m, int n); // in bytes -void blasfeo_dgeqrf(int m, int n, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj, void *work); -// D <= Q factor, where C is the output of the LQ factorization -int blasfeo_dorglq_worksize(int m, int n, int k); // in bytes -void blasfeo_dorglq(int m, int n, int k, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj, void *work); -// D <= lq( C ) -void blasfeo_dgelqf(int m, int n, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj, void *work); -int blasfeo_dgelqf_worksize(int m, int n); // in bytes -// D <= lq( C ), positive diagonal elements -void blasfeo_dgelqf_pd(int m, int n, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj, void *work); -// [L, A] <= lq( [L, A] ), positive diagonal elements, array of matrices, with -// L lower triangular, of size (m)x(m) -// A full, of size (m)x(n1) -void blasfeo_dgelqf_pd_la(int m, int n1, struct blasfeo_dmat *sL, int li, int lj, struct blasfeo_dmat *sA, int ai, int aj, void *work); -// [L, L, A] <= lq( [L, L, A] ), positive diagonal elements, array of matrices, with: -// L lower triangular, of size (m)x(m) -// A full, of size (m)x(n1) -void blasfeo_dgelqf_pd_lla(int m, int n1, struct blasfeo_dmat *sL0, int l0i, int l0j, struct blasfeo_dmat *sL1, int l1i, int l1j, struct blasfeo_dmat *sA, int ai, int aj, void *work); - - - -// -// BLAS API helper functions -// - -#if ( defined(BLAS_API) & defined(MF_PANELMAJ) ) -// BLAS 3 -void blasfeo_cm_dgemm_nn(int m, int n, int k, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, double beta, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dgemm_nt(int m, int n, int k, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, double beta, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dgemm_tn(int m, int n, int k, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, double beta, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dgemm_tt(int m, int n, int k, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, double beta, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dsyrk_ln(int m, int k, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, double beta, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dsyrk_lt(int m, int k, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, double beta, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dsyrk_un(int m, int k, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, double beta, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dsyrk_ut(int m, int k, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, double beta, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dsyrk3_ln(int m, int k, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, double beta, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dsyrk3_lt(int m, int k, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, double beta, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dsyrk3_un(int m, int k, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, double beta, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dsyrk3_ut(int m, int k, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, double beta, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrsm_llnn(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrsm_llnu(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrsm_lltn(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrsm_lltu(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrsm_lunn(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrsm_lunu(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrsm_lutn(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrsm_lutu(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrsm_rlnn(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrsm_rlnu(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrsm_rltn(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrsm_rltu(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrsm_runn(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrsm_runu(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrsm_rutn(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrsm_rutu(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrmm_llnn(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrmm_llnu(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrmm_lltn(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrmm_lltu(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrmm_lunn(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrmm_lunu(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrmm_lutn(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrmm_lutu(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrmm_rlnn(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrmm_rlnu(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrmm_rltn(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrmm_rltu(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrmm_runn(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrmm_runu(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrmm_rutn(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dtrmm_rutu(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dsyr2k_ln(int m, int k, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, double beta, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dsyr2k_lt(int m, int k, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, double beta, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dsyr2k_un(int m, int k, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, double beta, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dsyr2k_ut(int m, int k, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dmat *sB, int bi, int bj, double beta, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj); -// BLAS 2 -void blasfeo_cm_dgemv_n(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dvec *sx, int xi, double beta, struct blasfeo_cm_dvec *sy, int yi, struct blasfeo_cm_dvec *sz, int zi); -void blasfeo_cm_dgemv_t(int m, int n, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dvec *sx, int xi, double beta, struct blasfeo_cm_dvec *sy, int yi, struct blasfeo_cm_dvec *sz, int zi); -void blasfeo_cm_dsymv_l(int m, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dvec *sx, int xi, double beta, struct blasfeo_cm_dvec *sy, int yi, struct blasfeo_cm_dvec *sz, int zi); -void blasfeo_cm_dsymv_u(int m, double alpha, struct blasfeo_cm_dmat *sA, int ai, int aj, struct blasfeo_cm_dvec *sx, int xi, double beta, struct blasfeo_cm_dvec *sy, int yi, struct blasfeo_cm_dvec *sz, int zi); -void blasfeo_cm_dger(int m, int n, double alpha, struct blasfeo_cm_dvec *sx, int xi, struct blasfeo_cm_dvec *sy, int yi, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj); -// LAPACK -void blasfeo_cm_dpotrf_l(int m, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dpotrf_u(int m, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj); -void blasfeo_cm_dgetrf_rp(int m, int n, struct blasfeo_cm_dmat *sC, int ci, int cj, struct blasfeo_cm_dmat *sD, int di, int dj, int *ipiv); -#endif - - - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_D_BLASFEO_API_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_d_blasfeo_api_ref.h b/third_party/acados/include/blasfeo/include/blasfeo_d_blasfeo_api_ref.h deleted file mode 100644 index 141a1f0..0000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_d_blasfeo_api_ref.h +++ /dev/null @@ -1,147 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_D_BLASFEO_API_REF_H_ -#define BLASFEO_D_BLASFEO_API_REF_H_ - -#include "blasfeo_common.h" - - -#ifdef __cplusplus -extern "C" { -#endif - - -// expose reference BLASFEO for testing - -// --- level 1 - -void blasfeo_daxpy_ref(int kmax, double alpha, struct blasfeo_dvec_ref *sx, int xi, struct blasfeo_dvec_ref *sy, int yi, struct blasfeo_dvec_ref *sz, int zi); -void blasfeo_daxpby_ref(int kmax, double alpha, struct blasfeo_dvec_ref *sx, int xi, double beta, struct blasfeo_dvec_ref *sy, int yi, struct blasfeo_dvec_ref *sz, int zi); -void blasfeo_dvecmul_ref(int m, struct blasfeo_dvec_ref *sx, int xi, struct blasfeo_dvec_ref *sy, int yi, struct blasfeo_dvec_ref *sz, int zi); -void blasfeo_dvecmulacc_ref(int m, struct blasfeo_dvec_ref *sx, int xi, struct blasfeo_dvec_ref *sy, int yi, struct blasfeo_dvec_ref *sz, int zi); -double blasfeo_dvecmuldot_ref(int m, struct blasfeo_dvec_ref *sx, int xi, struct blasfeo_dvec_ref *sy, int yi, struct blasfeo_dvec_ref *sz, int zi); -double blasfeo_ddot_ref(int m, struct blasfeo_dvec_ref *sx, int xi, struct blasfeo_dvec_ref *sy, int yi); -void blasfeo_drotg_ref(double a, double b, double *c, double *s); -void blasfeo_dcolrot_ref(int m, struct blasfeo_dmat_ref *sA, int ai, int aj0, int aj1, double c, double s); -void blasfeo_drowrot_ref(int m, struct blasfeo_dmat_ref *sA, int ai0, int ai1, int aj, double c, double s); - - -// --- level 2 - -// dense -void blasfeo_dgemv_n_ref(int m, int n, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dvec_ref *sx, int xi, double beta, struct blasfeo_dvec_ref *sy, int yi, struct blasfeo_dvec_ref *sz, int zi); -void blasfeo_dgemv_t_ref(int m, int n, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dvec_ref *sx, int xi, double beta, struct blasfeo_dvec_ref *sy, int yi, struct blasfeo_dvec_ref *sz, int zi); -void blasfeo_dtrsv_lnn_mn_ref(int m, int n, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dvec_ref *sx, int xi, struct blasfeo_dvec_ref *sz, int zi); -void blasfeo_dtrsv_ltn_mn_ref(int m, int n, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dvec_ref *sx, int xi, struct blasfeo_dvec_ref *sz, int zi); -void blasfeo_dtrsv_lnn_ref(int m, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dvec_ref *sx, int xi, struct blasfeo_dvec_ref *sz, int zi); -void blasfeo_dtrsv_lnu_ref(int m, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dvec_ref *sx, int xi, struct blasfeo_dvec_ref *sz, int zi); -void blasfeo_dtrsv_ltn_ref(int m, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dvec_ref *sx, int xi, struct blasfeo_dvec_ref *sz, int zi); -void blasfeo_dtrsv_ltu_ref(int m, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dvec_ref *sx, int xi, struct blasfeo_dvec_ref *sz, int zi); -void blasfeo_dtrsv_unn_ref(int m, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dvec_ref *sx, int xi, struct blasfeo_dvec_ref *sz, int zi); -void blasfeo_dtrsv_utn_ref(int m, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dvec_ref *sx, int xi, struct blasfeo_dvec_ref *sz, int zi); -void blasfeo_dtrmv_unn_ref(int m, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dvec_ref *sx, int xi, struct blasfeo_dvec_ref *sz, int zi); -void blasfeo_dtrmv_utn_ref(int m, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dvec_ref *sx, int xi, struct blasfeo_dvec_ref *sz, int zi); -void blasfeo_dtrmv_lnn_ref(int m, int n, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dvec_ref *sx, int xi, struct blasfeo_dvec_ref *sz, int zi); -void blasfeo_dtrmv_ltn_ref(int m, int n, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dvec_ref *sx, int xi, struct blasfeo_dvec_ref *sz, int zi); -void blasfeo_dtrmv_lnu_ref(int m, int n, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dvec_ref *sx, int xi, struct blasfeo_dvec_ref *sz, int zi); -void blasfeo_dtrmv_ltu_ref(int m, int n, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dvec_ref *sx, int xi, struct blasfeo_dvec_ref *sz, int zi); -void blasfeo_dgemv_nt_ref(int m, int n, double alpha_n, double alpha_t, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dvec_ref *sx_n, int xi_n, struct blasfeo_dvec_ref *sx_t, int xi_t, double beta_n, double beta_t, struct blasfeo_dvec_ref *sy_n, int yi_n, struct blasfeo_dvec_ref *sy_t, int yi_t, struct blasfeo_dvec_ref *sz_n, int zi_n, struct blasfeo_dvec_ref *sz_t, int zi_t); -void blasfeo_dsymv_l_ref(int m, int n, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dvec_ref *sx, int xi, double beta, struct blasfeo_dvec_ref *sy, int yi, struct blasfeo_dvec_ref *sz, int zi); - -// diagonal -void blasfeo_dgemv_d_ref(int m, double alpha, struct blasfeo_dvec_ref *sA, int ai, struct blasfeo_dvec_ref *sx, int xi, double beta, struct blasfeo_dvec_ref *sy, int yi, struct blasfeo_dvec_ref *sz, int zi); - - -// --- level 3 - -// dense -void blasfeo_dgemm_nn_ref( int m, int n, int k, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, double beta, struct blasfeo_dmat_ref *sC, int ci, int cj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dgemm_nt_ref( int m, int n, int k, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, double beta, struct blasfeo_dmat_ref *sC, int ci, int cj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dgemm_tn_ref(int m, int n, int k, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, double beta, struct blasfeo_dmat_ref *sC, int ci, int cj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dgemm_tt_ref(int m, int n, int k, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, double beta, struct blasfeo_dmat_ref *sC, int ci, int cj, struct blasfeo_dmat_ref *sD, int di, int dj); - -void blasfeo_dsyrk_ln_mn_ref( int m, int n, int k, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, double beta, struct blasfeo_dmat_ref *sC, int ci, int cj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dsyrk_ln_ref( int m, int k, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, double beta, struct blasfeo_dmat_ref *sC, int ci, int cj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dsyrk_lt_ref( int m, int k, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, double beta, struct blasfeo_dmat_ref *sC, int ci, int cj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dsyrk_un_ref( int m, int k, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, double beta, struct blasfeo_dmat_ref *sC, int ci, int cj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dsyrk_ut_ref( int m, int k, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, double beta, struct blasfeo_dmat_ref *sC, int ci, int cj, struct blasfeo_dmat_ref *sD, int di, int dj); - -void blasfeo_dtrmm_rutn_ref( int m, int n, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dtrmm_rlnn_ref( int m, int n, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, struct blasfeo_dmat_ref *sD, int di, int dj); - -void blasfeo_dtrsm_lunu_ref( int m, int n, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dtrsm_lunn_ref( int m, int n, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dtrsm_lutu_ref( int m, int n, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dtrsm_lutn_ref( int m, int n, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dtrsm_llnu_ref( int m, int n, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dtrsm_llnn_ref( int m, int n, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dtrsm_lltu_ref( int m, int n, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dtrsm_lltn_ref( int m, int n, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dtrsm_runu_ref( int m, int n, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dtrsm_runn_ref( int m, int n, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dtrsm_rutu_ref( int m, int n, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dtrsm_rutn_ref( int m, int n, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dtrsm_rlnu_ref( int m, int n, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dtrsm_rlnn_ref( int m, int n, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dtrsm_rltu_ref( int m, int n, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dtrsm_rltn_ref( int m, int n, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, struct blasfeo_dmat_ref *sD, int di, int dj); - -// diagonal -void dgemm_diag_left_lib_ref(int m, int n, double alpha, double *dA, double *pB, int sdb, double beta, double *pC, int sdc, double *pD, int sdd); -void blasfeo_dgemm_dn_ref(int m, int n, double alpha, struct blasfeo_dvec_ref *sA, int ai, struct blasfeo_dmat_ref *sB, int bi, int bj, double beta, struct blasfeo_dmat_ref *sC, int ci, int cj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dgemm_nd_ref(int m, int n, double alpha, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dvec_ref *sB, int bi, double beta, struct blasfeo_dmat_ref *sC, int ci, int cj, struct blasfeo_dmat_ref *sD, int di, int dj); - -// --- lapack - -void blasfeo_dgetrf_nopivot_ref(int m, int n, struct blasfeo_dmat_ref *sC, int ci, int cj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dgetrf_rowpivot_ref(int m, int n, struct blasfeo_dmat_ref *sC, int ci, int cj, struct blasfeo_dmat_ref *sD, int di, int dj, int *ipiv); -void blasfeo_dpotrf_l_ref(int m, struct blasfeo_dmat_ref *sC, int ci, int cj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dpotrf_l_mn_ref(int m, int n, struct blasfeo_dmat_ref *sC, int ci, int cj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dsyrk_dpotrf_ln_ref(int m, int k, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, struct blasfeo_dmat_ref *sC, int ci, int cj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dsyrk_dpotrf_ln_mn_ref(int m, int n, int k, struct blasfeo_dmat_ref *sA, int ai, int aj, struct blasfeo_dmat_ref *sB, int bi, int bj, struct blasfeo_dmat_ref *sC, int ci, int cj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dgetrf_nopivot_ref(int m, int n, struct blasfeo_dmat_ref *sC, int ci, int cj, struct blasfeo_dmat_ref *sD, int di, int dj); -void blasfeo_dgetrf_rowpivot_ref(int m, int n, struct blasfeo_dmat_ref *sC, int ci, int cj, struct blasfeo_dmat_ref *sD, int di, int dj, int *ipiv); -void blasfeo_dgeqrf_ref(int m, int n, struct blasfeo_dmat_ref *sC, int ci, int cj, struct blasfeo_dmat_ref *sD, int di, int dj, void *work); -void blasfeo_dgelqf_ref(int m, int n, struct blasfeo_dmat_ref *sC, int ci, int cj, struct blasfeo_dmat_ref *sD, int di, int dj, void *work); -void blasfeo_dgelqf_pd_ref(int m, int n, struct blasfeo_dmat_ref *sC, int ci, int cj, struct blasfeo_dmat_ref *sD, int di, int dj, void *work); -void blasfeo_dgelqf_pd_la_ref(int m, int n1, struct blasfeo_dmat_ref *sL, int li, int lj, struct blasfeo_dmat_ref *sA, int ai, int aj, void *work); -void blasfeo_dgelqf_pd_lla_ref(int m, int n1, struct blasfeo_dmat_ref *sL0, int l0i, int l0j, struct blasfeo_dmat_ref *sL1, int l1i, int l1j, struct blasfeo_dmat_ref *sA, int ai, int aj, void *work); - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_D_BLASFEO_API_REF_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_d_blasfeo_hp_api.h b/third_party/acados/include/blasfeo/include/blasfeo_d_blasfeo_hp_api.h deleted file mode 100644 index 405733f..0000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_d_blasfeo_hp_api.h +++ /dev/null @@ -1,84 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_D_BLASFEO_HP_API_H_ -#define BLASFEO_D_BLASFEO_HP_API_H_ - - - -#include "blasfeo_common.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -// -// level 3 BLAS -// - -// dense - - -// D <= beta * C + alpha * A^T * B -void blasfeo_hp_dgemm_tn(int m, int n, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= beta * C + alpha * A * B^T; C, D lower triangular -void blasfeo_hp_dsyrk_ln(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= beta * C + alpha * A * A^T ; C, D lower triangular -void blasfeo_hp_dsyrk3_ln(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^{-T} , with A lower triangular -void blasfeo_hp_dtrsm_rltn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); - - -// -// level 2 BLAS -// - -// dense - -// z <= beta * y + alpha * A * x -void blasfeo_hp_dgemv_n(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, double beta, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); - - - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_D_BLASFEO_HP_API_H_ - diff --git a/third_party/acados/include/blasfeo/include/blasfeo_d_blasfeo_ref_api.h b/third_party/acados/include/blasfeo/include/blasfeo_d_blasfeo_ref_api.h deleted file mode 100644 index 1a8b22c..0000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_d_blasfeo_ref_api.h +++ /dev/null @@ -1,283 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_D_BLASFEO_REF_API_H_ -#define BLASFEO_D_BLASFEO_REF_API_H_ - - - -#include "blasfeo_common.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -// -// level 1 BLAS -// - -// z = y + alpha*x -// z[zi:zi+n] = alpha*x[xi:xi+n] + y[yi:yi+n] -// NB: Different arguments semantic compare to equivalent standard BLAS routine -void blasfeo_ref_daxpy(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); -// z = beta*y + alpha*x -void blasfeo_ref_daxpby(int kmax, double alpha, struct blasfeo_dvec *sx, int xi, double beta, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); -// z = x .* y -void blasfeo_ref_dvecmul(int m, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); -// z += x .* y -void blasfeo_ref_dvecmulacc(int m, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); -// z = x .* y, return sum(z) = x^T * y -double blasfeo_ref_dvecmuldot(int m, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); -// return x^T * y -double blasfeo_ref_ddot(int m, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sy, int yi); -// construct givens plane rotation -void blasfeo_ref_drotg(double a, double b, double *c, double *s); -// apply plane rotation [a b] [c -s; s; c] to the aj0 and aj1 columns of A at row index ai -void blasfeo_ref_dcolrot(int m, struct blasfeo_dmat *sA, int ai, int aj0, int aj1, double c, double s); -// apply plane rotation [c s; -s c] [a; b] to the ai0 and ai1 rows of A at column index aj -void blasfeo_ref_drowrot(int m, struct blasfeo_dmat *sA, int ai0, int ai1, int aj, double c, double s); - - - -// -// level 2 BLAS -// - -// dense - -// z <= beta * y + alpha * A * x -void blasfeo_ref_dgemv_n(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, double beta, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); -// z <= beta * y + alpha * A' * x -void blasfeo_ref_dgemv_t(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, double beta, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); -// z <= inv( A ) * x, A (m)x(n) -void blasfeo_ref_dtrsv_lnn_mn(int m, int n, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= inv( A' ) * x, A (m)x(n) -void blasfeo_ref_dtrsv_ltn_mn(int m, int n, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= inv( A ) * x, A (m)x(m) lower, not_transposed, not_unit -void blasfeo_ref_dtrsv_lnn(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= inv( A ) * x, A (m)x(m) lower, not_transposed, unit -void blasfeo_ref_dtrsv_lnu(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= inv( A' ) * x, A (m)x(m) lower, transposed, not_unit -void blasfeo_ref_dtrsv_ltn(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= inv( A' ) * x, A (m)x(m) lower, transposed, unit -void blasfeo_ref_dtrsv_ltu(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= inv( A' ) * x, A (m)x(m) upper, not_transposed, not_unit -void blasfeo_ref_dtrsv_unn(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= inv( A' ) * x, A (m)x(m) upper, transposed, not_unit -void blasfeo_ref_dtrsv_utn(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= A * x ; A lower triangular -void blasfeo_ref_dtrmv_lnn(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= A * x ; A lower triangular, unit diagonal -void blasfeo_ref_dtrmv_lnu(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= A' * x ; A lower triangular -void blasfeo_ref_dtrmv_ltn(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= A' * x ; A lower triangular, unit diagonal -void blasfeo_ref_dtrmv_ltu(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= beta * y + alpha * A * x ; A upper triangular -void blasfeo_ref_dtrmv_unn(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z <= A' * x ; A upper triangular -void blasfeo_ref_dtrmv_utn(int m, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sz, int zi); -// z_n <= beta_n * y_n + alpha_n * A * x_n -// z_t <= beta_t * y_t + alpha_t * A' * x_t -void blasfeo_ref_dgemv_nt(int m, int n, double alpha_n, double alpha_t, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx_n, int xi_n, struct blasfeo_dvec *sx_t, int xi_t, double beta_n, double beta_t, struct blasfeo_dvec *sy_n, int yi_n, struct blasfeo_dvec *sy_t, int yi_t, struct blasfeo_dvec *sz_n, int zi_n, struct blasfeo_dvec *sz_t, int zi_t); -// z <= beta * y + alpha * A * x, where A is symmetric and only the lower triangular patr of A is accessed -void blasfeo_ref_dsymv_l(int m, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, double beta, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); -void blasfeo_ref_dsymv_l_mn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, double beta, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); -// z <= beta * y + alpha * A * x, where A is symmetric and only the upper triangular patr of A is accessed -void blasfeo_ref_dsymv_u(int m, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sx, int xi, double beta, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); -// D = C + alpha * x * y^T -void blasfeo_ref_dger(int m, int n, double alpha, struct blasfeo_dvec *sx, int xi, struct blasfeo_dvec *sy, int yi, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); - -// diagonal - -// z <= beta * y + alpha * A * x, A diagonal -void blasfeo_ref_dgemv_d(int m, double alpha, struct blasfeo_dvec *sA, int ai, struct blasfeo_dvec *sx, int xi, double beta, struct blasfeo_dvec *sy, int yi, struct blasfeo_dvec *sz, int zi); - - - -// -// level 3 BLAS -// - -// dense - -// D <= beta * C + alpha * A * B -void blasfeo_ref_dgemm_nn(int m, int n, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= beta * C + alpha * A * B^T -void blasfeo_ref_dgemm_nt(int m, int n, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= beta * C + alpha * A^T * B -void blasfeo_ref_dgemm_tn(int m, int n, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= beta * C + alpha * A^T * B^T -void blasfeo_ref_dgemm_tt(int m, int n, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= beta * C + alpha * A * B^T ; C, D lower triangular -void blasfeo_ref_dsyrk_ln(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -void blasfeo_ref_dsyrk_ln_mn(int m, int n, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= beta * C + alpha * A^T * B ; C, D lower triangular -void blasfeo_ref_dsyrk_lt(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= beta * C + alpha * A * B^T ; C, D upper triangular -void blasfeo_ref_dsyrk_un(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= beta * C + alpha * A^T * B ; C, D upper triangular -void blasfeo_ref_dsyrk_ut(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A * B ; A lower triangular -void blasfeo_ref_dtrmm_llnn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A * B ; A lower triangular -void blasfeo_ref_dtrmm_llnu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^T * B ; A lower triangular -void blasfeo_ref_dtrmm_lltn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^T * B ; A lower triangular -void blasfeo_ref_dtrmm_lltu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A * B ; A upper triangular -void blasfeo_ref_dtrmm_lunn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A * B ; A upper triangular -void blasfeo_ref_dtrmm_lunu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^T * B ; A upper triangular -void blasfeo_ref_dtrmm_lutn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^T * B ; A upper triangular -void blasfeo_ref_dtrmm_lutu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A ; A lower triangular -void blasfeo_ref_dtrmm_rlnn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A ; A lower triangular -void blasfeo_ref_dtrmm_rlnu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^T ; A lower triangular -void blasfeo_ref_dtrmm_rltn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^T ; A lower triangular -void blasfeo_ref_dtrmm_rltu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A ; A upper triangular -void blasfeo_ref_dtrmm_runn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A ; A upper triangular -void blasfeo_ref_dtrmm_runu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^T ; A upper triangular -void blasfeo_ref_dtrmm_rutn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^T ; A upper triangular -void blasfeo_ref_dtrmm_rutu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^{-1} * B , with A lower triangular employint explicit inverse of diagonal -void blasfeo_ref_dtrsm_llnn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^{-1} * B , with A lower triangular with unit diagonal -void blasfeo_ref_dtrsm_llnu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^{-T} * B , with A lower triangular employint explicit inverse of diagonal -void blasfeo_ref_dtrsm_lltn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^{-T} * B , with A lower triangular with unit diagonal -void blasfeo_ref_dtrsm_lltu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^{-1} * B , with A upper triangular employing explicit inverse of diagonal -void blasfeo_ref_dtrsm_lunn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^{-1} * B , with A upper triangular withunit diagonal -void blasfeo_ref_dtrsm_lunu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^{-T} * B , with A upper triangular employing explicit inverse of diagonal -void blasfeo_ref_dtrsm_lutn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A^{-T} * B , with A upper triangular withunit diagonal -void blasfeo_ref_dtrsm_lutu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^{-1} , with A lower triangular employing explicit inverse of diagonal -void blasfeo_ref_dtrsm_rlnn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^{-1} , with A lower triangular with unit diagonal -void blasfeo_ref_dtrsm_rlnu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^{-T} , with A lower triangular employing explicit inverse of diagonal -void blasfeo_ref_dtrsm_rltn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^{-T} , with A lower triangular with unit diagonal -void blasfeo_ref_dtrsm_rltu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^{-1} , with A upper triangular employing explicit inverse of diagonal -void blasfeo_ref_dtrsm_runn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^{-1} , with A upper triangular with unit diagonal -void blasfeo_ref_dtrsm_runu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^{-T} , with A upper triangular employing explicit inverse of diagonal -void blasfeo_ref_dtrsm_rutn(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * B * A^{-T} , with A upper triangular with unit diagonal -void blasfeo_ref_dtrsm_rutu(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sD, int di, int dj); -// D <= beta * C + alpha * A * B^T + alpha * B * A^T ; C, D lower triangular -void blasfeo_ref_dsyr2k_ln(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= beta * C + alpha * A^T * B + alpha * B^T * A ; C, D lower triangular -void blasfeo_ref_dsyr2k_lt(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= beta * C + alpha * A * B^T + alpha * B * A^T ; C, D upper triangular -void blasfeo_ref_dsyr2k_un(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= beta * C + alpha * A^T * B + alpha * B^T * A ; C, D upper triangular -void blasfeo_ref_dsyr2k_ut(int m, int k, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); - -// diagonal - -// D <= alpha * A * B + beta * C, with A diagonal (stored as strvec) -void dgemm_diag_left_lib(int m, int n, double alpha, double *dA, double *pB, int sdb, double beta, double *pC, int sdc, double *pD, int sdd); -void blasfeo_ref_dgemm_dn(int m, int n, double alpha, struct blasfeo_dvec *sA, int ai, struct blasfeo_dmat *sB, int bi, int bj, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= alpha * A * B + beta * C, with B diagonal (stored as strvec) -void blasfeo_ref_dgemm_nd(int m, int n, double alpha, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dvec *sB, int bi, double beta, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); - - - -// -// LAPACK -// - -// D <= chol( C ) ; C, D lower triangular -void blasfeo_ref_dpotrf_l(int m, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -void blasfeo_ref_dpotrf_l_mn(int m, int n, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= chol( C ) ; C, D upper triangular -void blasfeo_ref_dpotrf_u(int m, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= chol( C + A * B' ) ; C, D lower triangular -void blasfeo_ref_dsyrk_dpotrf_ln(int m, int k, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -void blasfeo_ref_dsyrk_dpotrf_ln_mn(int m, int n, int k, struct blasfeo_dmat *sA, int ai, int aj, struct blasfeo_dmat *sB, int bi, int bj, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= lu( C ) ; no pivoting -void blasfeo_ref_dgetrf_np(int m, int n, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj); -// D <= lu( C ) ; row pivoting -void blasfeo_ref_dgetrf_rp(int m, int n, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj, int *ipiv); -// D <= qr( C ) -int blasfeo_ref_dgeqrf_worksize(int m, int n); // in bytes -void blasfeo_ref_dgeqrf(int m, int n, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj, void *work); -// D <= Q factor, where C is the output of the LQ factorization -int blasfeo_ref_dorglq_worksize(int m, int n, int k); // in bytes -void blasfeo_ref_dorglq(int m, int n, int k, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj, void *work); -// D <= lq( C ) -void blasfeo_ref_dgelqf(int m, int n, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj, void *work); -int blasfeo_ref_dgelqf_worksize(int m, int n); // in bytes -// D <= lq( C ), positive diagonal elements -void blasfeo_ref_dgelqf_pd(int m, int n, struct blasfeo_dmat *sC, int ci, int cj, struct blasfeo_dmat *sD, int di, int dj, void *work); -// [L, A] <= lq( [L, A] ), positive diagonal elements, array of matrices, with -// L lower triangular, of size (m)x(m) -// A full, of size (m)x(n1) -void blasfeo_ref_dgelqf_pd_la(int m, int n1, struct blasfeo_dmat *sL, int li, int lj, struct blasfeo_dmat *sA, int ai, int aj, void *work); -// [L, L, A] <= lq( [L, L, A] ), positive diagonal elements, array of matrices, with: -// L lower triangular, of size (m)x(m) -// A full, of size (m)x(n1) -void blasfeo_ref_dgelqf_pd_lla(int m, int n1, struct blasfeo_dmat *sL0, int l0i, int l0j, struct blasfeo_dmat *sL1, int l1i, int l1j, struct blasfeo_dmat *sA, int ai, int aj, void *work); - - - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_D_BLASFEO_REF_API_H_ - diff --git a/third_party/acados/include/blasfeo/include/blasfeo_d_kernel.h b/third_party/acados/include/blasfeo/include/blasfeo_d_kernel.h deleted file mode 100644 index d20ac38..0000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_d_kernel.h +++ /dev/null @@ -1,1321 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_D_KERNEL_H_ -#define BLASFEO_D_KERNEL_H_ - - - -#include "blasfeo_target.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -// utils -void blasfeo_align_2MB(void *ptr, void **ptr_align); -void blasfeo_align_4096_byte(void *ptr, void **ptr_align); -void blasfeo_align_64_byte(void *ptr, void **ptr_align); - - -// -// lib8 -// - -// 24x8 -void kernel_dgemm_nt_24x8_lib8(int k, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dgemm_nt_24x8_vs_lib8(int k, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, int m1, int n1); // -void kernel_dtrsm_nt_rl_inv_24x8_lib8(int k, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E); // -void kernel_dpotrf_nt_l_24x8_lib8(int k, double *A, int sda, double *B, double *C, int sdc, double *D, int sdd, double *inv_diag_D); -void kernel_dpotrf_nt_l_24x8_vs_lib8(int k, double *A, int sda, double *B, double *C, int sdc, double *D, int sdd, double *inv_diag_D, int m1, int n1); -void kernel_dtrsm_nt_rl_inv_24x8_vs_lib8(int k, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E, int m1, int n1); // -void kernel_dgemm_dtrsm_nt_rl_inv_24x8_lib8(int kp, double *Ap, int sdap, double *Bp, int km_, double *Am, int sdam, double *Bm, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E); -void kernel_dgemm_dtrsm_nt_rl_inv_24x8_vs_lib8(int kp, double *Ap, int sdap, double *Bp, int km_, double *Am, int sdam, double *Bm, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E, int m1, int n1); -void kernel_dsyrk_dpotrf_nt_l_24x8_lib8(int kp, double *Ap, int sdap, double *Bp, int km_, double *Am, int sdam, double *Bm, double *C, int sdc, double *D, int sdd, double *inv_diag_D); -void kernel_dsyrk_dpotrf_nt_l_24x8_vs_lib8(int kp, double *Ap, int sdap, double *Bp, int km_, double *Am, int sdam, double *Bm, double *C, int sdc, double *D, int sdd, double *inv_diag_D, int m1, int n1); -void kernel_dlarfb8_rn_24_lib8(int kmax, double *pV, double *pT, double *pD, int sdd); -// 16x8 -void kernel_dgemm_nt_16x8_lib8(int k, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dgemm_nt_16x8_vs_lib8(int k, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, int m1, int n1); // -void kernel_dgemm_nt_16x8_gen_lib8(int k, double *alpha, double *A, int sda, double *B, double *beta, int offC, double *C, int sdc, int offD, double *D, int sdd, int m0, int m1, int n0, int n1); // -void kernel_dgemm_nn_16x8_lib8(int k, double *alpha, double *A, int sda, int offB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dgemm_nn_16x8_vs_lib8(int k, double *alpha, double *A, int sda, int offB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, int m1, int n1); // -void kernel_dgemm_nn_16x8_gen_lib8(int k, double *alpha, double *A, int sda, int offB, double *B, int sdb, double *beta, int offC, double *C, int sdc, int offD, double *D, int sdd, int m0, int m1, int n0, int n1); // -void kernel_dsyrk_nt_l_16x8_lib8(int k, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dsyrk_nt_l_16x8_vs_lib8(int k, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, int m1, int n1); // -void kernel_dsyrk_nt_l_16x8_gen_lib8(int k, double *alpha, double *A, int sda, double *B, double *beta, int offC, double *C, int sdc, int offD, double *D, int sdd, int m0, int m1, int n0, int n1); // -void kernel_dtrmm_nn_rl_16x8_lib8(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *D, int sdd); -void kernel_dtrmm_nn_rl_16x8_vs_lib8(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *D, int sdd, int m1, int n1); -void kernel_dtrmm_nn_rl_16x8_gen_lib8(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, int offD, double *D, int sdd, int m0, int m1, int n0, int n1); -void kernel_dtrsm_nt_rl_inv_16x8_lib8(int k, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E); // -void kernel_dtrsm_nt_rl_inv_16x8_vs_lib8(int k, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E, int m1, int n1); // -void kernel_dpotrf_nt_l_16x8_lib8(int k, double *A, int sda, double *B, double *C, int sdc, double *D, int sdd, double *inv_diag_D); -void kernel_dpotrf_nt_l_16x8_vs_lib8(int k, double *A, int sda, double *B, double *C, int sdc, double *D, int sdd, double *inv_diag_D, int m1, int n1); -void kernel_dgemm_dtrsm_nt_rl_inv_16x8_lib8(int kp, double *Ap, int sdap, double *Bp, int km_, double *Am, int sdam, double *Bm, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E); -void kernel_dgemm_dtrsm_nt_rl_inv_16x8_vs_lib8(int kp, double *Ap, int sdap, double *Bp, int km_, double *Am, int sdam, double *Bm, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E, int m1, int n1); -void kernel_dsyrk_dpotrf_nt_l_16x8_lib8(int kp, double *Ap, int sdap, double *Bp, int km_, double *Am, int sdam, double *Bm, double *C, int sdc, double *D, int sdd, double *inv_diag_D); -void kernel_dsyrk_dpotrf_nt_l_16x8_vs_lib8(int kp, double *Ap, int sdap, double *Bp, int km_, double *Am, int sdam, double *Bm, double *C, int sdc, double *D, int sdd, double *inv_diag_D, int m1, int n1); -void kernel_dlarfb8_rn_16_lib8(int kmax, double *pV, double *pT, double *pD, int sdd); -void kernel_dlarfb8_rn_la_16_lib8(int n1, double *pVA, double *pT, double *pD, int sdd, double *pA, int sda); -void kernel_dlarfb8_rn_lla_16_lib8(int n0, int n1, double *pVL, double *pVA, double *pT, double *pD, int sdd, double *pL, int sdl, double *pA, int sda); -// 8x16 -void kernel_dgemm_tt_8x16_lib8(int k, double *alpha, int offA, double *A, int sda, double *B, int sdb, double *beta, double *C, double *D); // -void kernel_dgemm_tt_8x16_vs_lib8(int k, double *alpha, int offA, double *A, int sda, double *B, int sdb, double *beta, double *C, double *D, int m1, int n1); // -void kernel_dgemm_tt_8x16_gen_lib8(int k, double *alpha, int offA, double *A, int sda, double *B, int sdb, double *beta, int offC, double *C, int sdc, int offD, double *D, int sdd, int m0, int m1, int n0, int n1); // -void kernel_dgemm_nt_8x16_lib8(int k, double *alpha, double *A, double *B, int sdb, double *beta, double *C, double *D); // -void kernel_dgemm_nt_8x16_vs_lib8(int k, double *alpha, double *A, double *B, int sdb, double *beta, double *C, double *D, int m1, int n1); // -// 8x8 -void kernel_dgemm_nt_8x8_lib8(int k, double *alpha, double *A, double *B, double *beta, double *C, double *D); // -void kernel_dgemm_nt_8x8_vs_lib8(int k, double *alpha, double *A, double *B, double *beta, double *C, double *D, int m1, int n1); // -void kernel_dgemm_nt_8x8_gen_lib8(int k, double *alpha, double *A, double *B, double *beta, int offC, double *C, int sdc, int offD, double *D, int sdd, int m0, int m1, int n0, int n1); // -void kernel_dgemm_nn_8x8_lib8(int k, double *alpha, double *A, int offB, double *B, int sdb, double *beta, double *C, double *D); // -void kernel_dgemm_nn_8x8_vs_lib8(int k, double *alpha, double *A, int offB, double *B, int sdb, double *beta, double *C, double *D, int m1, int n1); // -void kernel_dgemm_nn_8x8_gen_lib8(int k, double *alpha, double *A, int offB, double *B, int sdb, double *beta, int offC, double *C, int sdc, int offD, double *D, int sdd, int m0, int m1, int n0, int n1); // -void kernel_dgemm_tt_8x8_lib8(int k, double *alpha, int offA, double *A, int sda, double *B, double *beta, double *C, double *D); // -void kernel_dgemm_tt_8x8_vs_lib8(int k, double *alpha, int offA, double *A, int sda, double *B, double *beta, double *C, double *D, int m1, int n1); // -void kernel_dgemm_tt_8x8_gen_lib8(int k, double *alpha, int offA, double *A, int sda, double *B, double *beta, int offc, double *C, int sdc, int offD, double *D, int sdd, int m0, int m1, int n0, int n1); // -void kernel_dsyrk_nt_l_8x8_lib8(int k, double *alpha, double *A, double *B, double *beta, double *C, double *D); // -void kernel_dsyrk_nt_l_8x8_vs_lib8(int k, double *alpha, double *A, double *B, double *beta, double *C, double *D, int m1, int n1); // -void kernel_dsyrk_nt_l_8x8_gen_lib8(int k, double *alpha, double *A, double *B, double *beta, int offC, double *C, int sdc, int offD, double *D, int sdd, int m0, int m1, int n0, int n1); // -void kernel_dtrmm_nn_rl_8x8_lib8(int k, double *alpha, double *A, int offsetB, double *B, int sdb, double *D); -void kernel_dtrmm_nn_rl_8x8_vs_lib8(int k, double *alpha, double *A, int offsetB, double *B, int sdb, double *D, int m1, int n1); -void kernel_dtrmm_nn_rl_8x8_gen_lib8(int k, double *alpha, double *A, int offsetB, double *B, int sdb, int offD, double *D, int sdd, int m0, int m1, int n0, int n1); -void kernel_dtrsm_nt_rl_inv_8x8_lib8(int k, double *A, double *B, double *beta, double *C, double *D, double *E, double *inv_diag_E); -void kernel_dtrsm_nt_rl_inv_8x8_vs_lib8(int k, double *A, double *B, double *beta, double *C, double *D, double *E, double *inv_diag_E, int m1, int n1); -void kernel_dpotrf_nt_l_8x8_lib8(int k, double *A, double *B, double *C, double *D, double *inv_diag_D); -void kernel_dpotrf_nt_l_8x8_vs_lib8(int k, double *A, double *B, double *C, double *D, double *inv_diag_D, int m1, int n1); -void kernel_dgemm_dtrsm_nt_rl_inv_8x8_lib8(int kp, double *Ap, double *Bp, int km_, double *Am, double *Bm, double *C, double *D, double *E, double *inv_diag_E); -void kernel_dgemm_dtrsm_nt_rl_inv_8x8_vs_lib8(int kp, double *Ap, double *Bp, int km_, double *Am, double *Bm, double *C, double *D, double *E, double *inv_diag_E, int m1, int n1); -void kernel_dsyrk_dpotrf_nt_l_8x8_lib8(int kp, double *Ap, double *Bp, int km_, double *Am, double *Bm, double *C, double *D, double *inv_diag_D); -void kernel_dsyrk_dpotrf_nt_l_8x8_vs_lib8(int kp, double *Ap, double *Bp, int km_, double *Am, double *Bm, double *C, double *D, double *inv_diag_D, int m1, int n1); -void kernel_dgelqf_vs_lib8(int m, int n, int k, int offD, double *pD, int sdd, double *dD); -void kernel_dgelqf_pd_vs_lib8(int m, int n, int k, int offD, double *pD, int sdd, double *dD); -void kernel_dgelqf_8_lib8(int kmax, double *pD, double *dD); -void kernel_dgelqf_pd_8_lib8(int kmax, double *pD, double *dD); -void kernel_dlarft_8_lib8(int kmax, double *pD, double *dD, double *pT); -void kernel_dlarfb8_rn_8_lib8(int kmax, double *pV, double *pT, double *pD); -void kernel_dlarfb8_rn_8_vs_lib8(int kmax, double *pV, double *pT, double *pD, int m1); -void kernel_dlarfb8_rn_1_lib8(int kmax, double *pV, double *pT, double *pD); -void kernel_dgelqf_dlarft8_8_lib8(int kmax, double *pD, double *dD, double *pT); -void kernel_dgelqf_pd_dlarft8_8_lib8(int kmax, double *pD, double *dD, double *pT); -void kernel_dgelqf_pd_la_vs_lib8(int m, int n1, int k, int offD, double *pD, int sdd, double *dD, int offA, double *pA, int sda); -void kernel_dgelqf_pd_la_dlarft8_8_lib8(int kmax, double *pD, double *dD, double *pA, double *pT); -void kernel_dlarft_la_8_lib8(int n1, double *dD, double *pA, double *pT); -void kernel_dlarfb8_rn_la_8_lib8(int n1, double *pVA, double *pT, double *pD, double *pA); -void kernel_dlarfb8_rn_la_8_vs_lib8(int n1, double *pVA, double *pT, double *pD, double *pA, int m1); -void kernel_dlarfb8_rn_la_1_lib8(int n1, double *pVA, double *pT, double *pD, double *pA); -void kernel_dgelqf_pd_lla_vs_lib8(int m, int n0, int n1, int k, int offD, double *pD, int sdd, double *dD, int offL, double *pL, int sdl, int offA, double *pA, int sda); -void kernel_dgelqf_pd_lla_dlarft8_8_lib8(int n0, int n1, double *pD, double *dD, double *pL, double *pA, double *pT); -void kernel_dlarft_lla_8_lib8(int n0, int n1, double *dD, double *pL, double *pA, double *pT); -void kernel_dlarfb8_rn_lla_8_lib8(int n0, int n1, double *pVL, double *pVA, double *pT, double *pD, double *pL, double *pA); -void kernel_dlarfb8_rn_lla_8_vs_lib8(int n0, int n1, double *pVL, double *pVA, double *pT, double *pD, double *pL, double *pA, int m1); -void kernel_dlarfb8_rn_lla_1_lib8(int n0, int n1, double *pVL, double *pVA, double *pT, double *pD, double *pL, double *pA); - -// panel copy / pack -// 24 -void kernel_dpack_nn_24_lib8(int kmax, double *A, int lda, double *C, int sdc); -void kernel_dpack_nn_24_vs_lib8(int kmax, double *A, int lda, double *C, int sdc, int m1); -// 16 -void kernel_dpacp_nn_16_lib8(int kmax, int offsetA, double *A, int sda, double *B, int sdb); -void kernel_dpacp_nn_16_vs_lib8(int kmax, int offsetA, double *A, int sda, double *B, int sdb, int m1); -void kernel_dpack_nn_16_lib8(int kmax, double *A, int lda, double *C, int sdc); -void kernel_dpack_nn_16_vs_lib8(int kmax, double *A, int lda, double *C, int sdc, int m1); -// 8 -void kernel_dpacp_nn_8_lib8(int kmax, int offsetA, double *A, int sda, double *B); -void kernel_dpacp_nn_8_vs_lib8(int kmax, int offsetA, double *A, int sda, double *B, int m1); -void kernel_dpacp_tn_8_lib8(int kmax, int offsetA, double *A, int sda, double *B); -void kernel_dpacp_tn_8_vs_lib8(int kmax, int offsetA, double *A, int sda, double *B, int m1); -void kernel_dpacp_l_nn_8_lib8(int kmax, int offsetA, double *A, int sda, double *B); -void kernel_dpacp_l_nn_8_vs_lib8(int kmax, int offsetA, double *A, int sda, double *B, int m1); -void kernel_dpacp_l_tn_8_lib8(int kmax, int offsetA, double *A, int sda, double *B); -void kernel_dpacp_l_tn_8_vs_lib8(int kmax, int offsetA, double *A, int sda, double *B, int m1); -void kernel_dpaad_nn_8_lib8(int kmax, double *alpha, int offsetA, double *A, int sda, double *B); -void kernel_dpaad_nn_8_vs_lib8(int kmax, double *alpha, int offsetA, double *A, int sda, double *B, int m1); -void kernel_dpack_nn_8_lib8(int kmax, double *A, int lda, double *C); -void kernel_dpack_nn_8_vs_lib8(int kmax, double *A, int lda, double *C, int m1); -void kernel_dpack_tn_8_lib8(int kmax, double *A, int lda, double *C); -void kernel_dpack_tn_8_vs_lib8(int kmax, double *A, int lda, double *C, int m1); -// 4 -void kernel_dpack_tt_4_lib8(int kmax, double *A, int lda, double *C, int sdc); // TODO offsetC -void kernel_dpack_tt_4_vs_lib8(int kmax, double *A, int lda, double *C, int sdc, int m1); // TODO offsetC - -// level 2 BLAS -// 16 -void kernel_dgemv_n_16_lib8(int k, double *alpha, double *A, int sda, double *x, double *beta, double *y, double *z); -// 8 -void kernel_dgemv_n_8_lib8(int k, double *alpha, double *A, double *x, double *beta, double *y, double *z); -void kernel_dgemv_n_8_vs_lib8(int k, double *alpha, double *A, double *x, double *beta, double *y, double *z, int m1); -//void kernel_dgemv_n_8_gen_lib8(int k, double *alpha, double *A, double *x, double *beta, double *y, double *z, int m0, int m1); -void kernel_dgemv_n_8_gen_lib8(int k, double *alpha, int offsetA, double *A, double *x, double *beta, double *y, double *z, int m1); -void kernel_dgemv_t_8_lib8(int k, double *alpha, int offsetA, double *A, int sda, double *x, double *beta, double *y, double *z); -void kernel_dgemv_t_8_vs_lib8(int k, double *alpha, int offsetA, double *A, int sda, double *x, double *beta, double *y, double *z, int n1); -void kernel_dgemv_nt_8_lib8(int kmax, double *alpha_n, double *alpha_t, int offsetA, double *A, int sda, double *x_n, double *x_t, double *beta_t, double *y_t, double *z_n, double *z_t); -void kernel_dgemv_nt_8_vs_lib8(int kmax, double *alpha_n, double *alpha_t, int offsetA, double *A, int sda, double *x_n, double *x_t, double *beta_t, double *y_t, double *z_n, double *z_t, int n1); -void kernel_dsymv_l_8_lib8(int kmax, double *alpha, double *A, int sda, double *x, double *z); -void kernel_dsymv_l_8_vs_lib8(int kmax, double *alpha, double *A, int sda, double *x, double *z, int n1); -void kernel_dsymv_l_8_gen_lib8(int kmax, double *alpha, int offsetA, double *A, int sda, double *x, double *z, int n1); -void kernel_dtrmv_n_ln_8_lib8(int k, double *A, double *x, double *z); -void kernel_dtrmv_n_ln_8_vs_lib8(int k, double *A, double *x, double *z, int m1); -void kernel_dtrmv_n_ln_8_gen_lib8(int k, int offsetA, double *A, double *x, double *z, int m1); -void kernel_dtrmv_t_ln_8_lib8(int k, double *A, int sda, double *x, double *z); -void kernel_dtrmv_t_ln_8_vs_lib8(int k, double *A, int sda, double *x, double *z, int n1); -void kernel_dtrmv_t_ln_8_gen_lib8(int k, int offsetA, double *A, int sda, double *x, double *z, int n1); -void kernel_dtrsv_n_l_inv_8_lib8(int k, double *A, double *inv_diag_A, double *x, double *z); -void kernel_dtrsv_n_l_inv_8_vs_lib8(int k, double *A, double *inv_diag_A, double *x, double *z, int m1, int n1); -void kernel_dtrsv_t_l_inv_8_lib8(int k, double *A, int sda, double *inv_diag_A, double *x, double *z); -void kernel_dtrsv_t_l_inv_8_vs_lib8(int k, double *A, int sda, double *inv_diag_A, double *x, double *z, int m1, int n1); - - - -// -// lib4 -// - -// level 2 BLAS -// 12 -void kernel_dgemv_n_12_lib4(int k, double *alpha, double *A, int sda, double *x, double *beta, double *y, double *z); -void kernel_dgemv_t_12_lib4(int k, double *alpha, int offsetA, double *A, int sda, double *x, double *beta, double *y, double *z); -// 8 -void kernel_dgemv_n_8_lib4(int k, double *alpha, double *A, int sda, double *x, double *beta, double *y, double *z); -void kernel_dgemv_t_8_lib4(int k, double *alpha, int offsetA, double *A, int sda, double *x, double *beta, double *y, double *z); -void kernel_dtrmv_un_8_lib4(int k, double *A, int sda, double *x, double *z); -// 4 -void kernel_dgemv_n_4_lib4(int k, double *alpha, double *A, double *x, double *beta, double *y, double *z); -void kernel_dgemv_n_4_vs_lib4(int k, double *alpha, double *A, double *x, double *beta, double *y, double *z, int k1); -void kernel_dgemv_n_4_gen_lib4(int kmax, double *alpha, double *A, double *x, double *beta, double *y, double *z, int k0, int k1); -void kernel_dgemv_t_4_lib4(int k, double *alpha, int offsetA, double *A, int sda, double *x, double *beta, double *y, double *z); -void kernel_dgemv_t_4_vs_lib4(int k, double *alpha, int offsetA, double *A, int sda, double *x, double *beta, double *y, double *z, int k1); -void kernel_dtrsv_ln_inv_4_lib4(int k, double *A, double *inv_diag_A, double *x, double *y, double *z); -void kernel_dtrsv_ln_inv_4_vs_lib4(int k, double *A, double *inv_diag_A, double *x, double *y, double *z, int km, int kn); -void kernel_dtrsv_lt_inv_4_lib4(int k, double *A, int sda, double *inv_diag_A, double *x, double *y, double *z); -void kernel_dtrsv_lt_inv_3_lib4(int k, double *A, int sda, double *inv_diag_A, double *x, double *y, double *z); -void kernel_dtrsv_lt_inv_2_lib4(int k, double *A, int sda, double *inv_diag_A, double *x, double *y, double *z); -void kernel_dtrsv_lt_inv_1_lib4(int k, double *A, int sda, double *inv_diag_A, double *x, double *y, double *z); -void kernel_dtrsv_lt_one_4_lib4(int k, double *A, int sda, double *x, double *y, double *z); -void kernel_dtrsv_lt_one_3_lib4(int k, double *A, int sda, double *x, double *y, double *z); -void kernel_dtrsv_lt_one_2_lib4(int k, double *A, int sda, double *x, double *y, double *z); -void kernel_dtrsv_lt_one_1_lib4(int k, double *A, int sda, double *x, double *y, double *z); -void kernel_dtrsv_ln_one_4_vs_lib4(int kmax, double *A, double *x, double *y, double *z, int km, int kn); -void kernel_dtrsv_ln_one_4_lib4(int kmax, double *A, double *x, double *y, double *z); -void kernel_dtrsv_un_inv_4_lib4(int kmax, double *A, double *inv_diag_A, double *x, double *y, double *z); -void kernel_dtrsv_ut_inv_4_lib4(int kmax, double *A, int sda, double *inv_diag_A, double *x, double *y, double *z); -void kernel_dtrsv_ut_inv_4_vs_lib4(int kmax, double *A, int sda, double *inv_diag_A, double *x, double *y, double *z, int m1, int n1); -void kernel_dtrmv_un_4_lib4(int k, double *A, double *x, double *z); -void kernel_dtrmv_ut_4_lib4(int k, double *A, int sda, double *x, double *z); -void kernel_dtrmv_ut_4_vs_lib4(int k, double *A, int sda, double *x, double *z, int km); -void kernel_dgemv_nt_6_lib4(int kmax, double *alpha_n, double *alpha_t, double *A, int sda, double *x_n, double *x_t, double *beta_t, double *y_t, double *z_n, double *z_t); -void kernel_dgemv_nt_4_lib4(int kmax, double *alpha_n, double *alpha_t, double *A, int sda, double *x_n, double *x_t, double *beta_t, double *y_t, double *z_n, double *z_t); -void kernel_dgemv_nt_4_vs_lib4(int kmax, double *alpha_n, double *alpha_t, double *A, int sda, double *x_n, double *x_t, double *beta_t, double *y_t, double *z_n, double *z_t, int km); -void kernel_dsymv_l_4_lib4(int kmax, double *alpha, double *A, int sda, double *x, double *z); -void kernel_dsymv_l_4_gen_lib4(int kmax, double *alpha, int offA, double *A, int sda, double *x, double *z, int km); - - - -// level 3 BLAS -// 12x4 -void kernel_dgemm_nt_12x4_lib4(int k, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dgemm_nt_12x4_vs_lib4(int k, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, int km, int kn); // -void kernel_dgemm_nt_12x4_gen_lib4(int k, double *alpha, double *A, int sda, double *B, double *beta, int offsetC, double *C, int sdc, int offsetD, double *D, int sdd, int m0, int m1, int k0, int k1); -void kernel_dgemm_nn_12x4_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dgemm_nn_12x4_vs_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, int km, int kn); // -void kernel_dgemm_nn_12x4_gen_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, int offsetC, double *C, int sdc, int offsetD, double *D, int sdd, int m0, int m1, int n0, int n1); // -void kernel_dgemm_tt_12x4_lib4(int k, double *alpha, int offsetA, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dgemm_tt_12x4_vs_lib4(int k, double *alpha, int offsetA, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, int m1, int n1); // -void kernel_dsyrk_nn_u_12x4_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dsyrk_nn_u_12x4_vs_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, int m1, int n1); // -void kernel_dsyrk_nt_l_12x4_lib4(int k, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dsyrk_nt_l_12x4_vs_lib4(int k, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, int km, int kn); // -void kernel_dtrmm_nt_ru_12x4_lib4(int k, double *alpha, double *A, int sda, double *B, double *D, int sdd); // -void kernel_dtrmm_nt_ru_12x4_vs_lib4(int k, double *alpha, double *A, int sda, double *B, double *D, int sdd, int km, int kn); // -void kernel_dtrmm_nn_rl_12x4_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *D, int sdd); -void kernel_dtrmm_nn_rl_12x4_vs_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *D, int sdd, int km, int kn); -void kernel_dtrsm_nt_rl_inv_12x4_lib4(int k, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E); -void kernel_dtrsm_nt_rl_inv_12x4_vs_lib4(int k, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E, int km, int kn); -void kernel_dtrsm_nt_rl_one_12x4_lib4(int k, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, double *E); -void kernel_dtrsm_nt_rl_one_12x4_vs_lib4(int k, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, double *E, int km, int kn); -void kernel_dtrsm_nt_ru_inv_12x4_lib4(int k, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E); -void kernel_dtrsm_nt_ru_inv_12x4_vs_lib4(int k, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E, int km, int kn); -void kernel_dtrsm_nt_ru_one_12x4_lib4(int k, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, double *E); -void kernel_dtrsm_nt_ru_one_12x4_vs_lib4(int k, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, double *E, int km, int kn); -void kernel_dtrsm_nn_ru_inv_12x4_lib4(int k, double *A, int sda, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E); -void kernel_dtrsm_nn_ru_inv_12x4_vs_lib4(int k, double *A, int sda, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E, int km, int kn); -void kernel_dtrsm_nn_ll_inv_12x4_lib4(int k, double *A, int sda, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int sde, double *inv_diag_E); -void kernel_dtrsm_nn_ll_inv_12x4_vs_lib4(int k, double *A, int sda, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int sde, double *inv_diag_E, int km, int kn); -void kernel_dtrsm_nn_ll_one_12x4_lib4(int k, double *A, int sda, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int sde); -void kernel_dtrsm_nn_ll_one_12x4_vs_lib4(int k, double *A, int sda, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int sde, int km, int kn); -void kernel_dtrsm_nn_lu_inv_12x4_lib4(int kmax, double *A, int sda, double *B, int sdb, double *C, int sdc, double *D, int sdd, double *E, int sde, double *inv_diag_E); -void kernel_dtrsm_nn_lu_inv_12x4_vs_lib4(int kmax, double *A, int sda, double *B, int sdb, double *C, int sdc, double *D, int sdd, double *E, int sde, double *inv_diag_E, int km, int kn); -// 4x12 -void kernel_dgemm_nt_4x12_lib4(int k, double *alpha, double *A, double *B, int sdb, double *beta, double *C, double *D); // -void kernel_dgemm_nt_4x12_vs_lib4(int k, double *alpha, double *A, double *B, int sdb, double *beta, double *C, double *D, int km, int kn); // -void kernel_dgemm_nn_4x12_lib4(int k, double *alpha, double *A, int offsetB, double *B, int sdb, double *beta, double *C, double *D); // -void kernel_dgemm_nn_4x12_vs_lib4(int k, double *alpha, double *A, int offsetB, double *B, int sdb, double *beta, double *C, double *D, int m1, int n1); // -void kernel_dgemm_tt_4x12_lib4(int k, double *alpha, int offsetA, double *A, int sda, double *B, int sdb, double *beta, double *C, double *D); // -void kernel_dgemm_tt_4x12_vs_lib4(int k, double *alpha, int offsetA, double *A, int sda, double *B, int sdb, double *beta, double *C, double *D, int m1, int n1); // -void kernel_dgemm_tt_4x12_gen_lib4(int k, double *alpha, int offsetA, double *A, int sda, double *B, int sdb, double *beta, int offsetC, double *C, int sdc, int offsetD, double *D, int sdd, int m0, int m1, int n0, int n1); // -void kernel_dtrsm_nt_rl_inv_4x12_lib4(int k, double *A, double *B, int sdb, double *C, double *D, double *E, int sed, double *inv_diag_E); -void kernel_dtrsm_nt_rl_inv_4x12_vs_lib4(int k, double *A, double *B, int sdb, double *C, double *D, double *E, int sed, double *inv_diag_E, int km, int kn); -// 8x8 -void kernel_dgemm_nt_8x8l_lib4(int k, double *alpha, double *A, int sda, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd); // computes [A00 *; A10 A11] -void kernel_dgemm_nt_8x8u_lib4(int k, double *alpha, double *A, int sda, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd); // computes [A00 *; A10 A11] -void kernel_dgemm_nt_8x8l_vs_lib4(int k, double *alpha, double *A, int sda, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, int km, int kn); // computes [A00 *; A10 A11] -void kernel_dgemm_nt_8x8u_vs_lib4(int k, double *alpha, double *A, int sda, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, int km, int kn); // computes [A00 *; A10 A11] -void kernel_dsyrk_nn_u_8x8_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dsyrk_nn_u_8x8_vs_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, int m1, int n1); // -void kernel_dsyrk_nt_l_8x8_lib4(int k, double *alpha, double *A, int sda, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd); // computes [L00 *; A10 L11] -void kernel_dsyrk_nt_l_8x8_vs_lib4(int k, double *alpha, double *A, int sda, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, int km, int kn); // computes [L00 *; A10 L11] -void kernel_dtrsm_nt_rl_inv_8x8l_lib4(int k, double *A, int sda, double *B, int sdb, double *C, int sdc, double *D, int sdd, double *E, int sed, double *inv_diag_E); -void kernel_dtrsm_nt_rl_inv_8x8l_vs_lib4(int k, double *A, int sda, double *B, int sdb, double *C, int sdc, double *D, int sdd, double *E, int sed, double *inv_diag_E, int km, int kn); -void kernel_dtrsm_nt_rl_inv_8x8u_lib4(int k, double *A, int sda, double *B, int sdb, double *C, int sdc, double *D, int sdd, double *E, int sed, double *inv_diag_E); -void kernel_dtrsm_nt_rl_inv_8x8u_vs_lib4(int k, double *A, int sda, double *B, int sdb, double *C, int sdc, double *D, int sdd, double *E, int sed, double *inv_diag_E, int km, int kn); -// 8x4 -void kernel_dgemm_nt_8x4_lib4(int k, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dgemm_nt_8x4_vs_lib4(int k, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, int km, int kn); // -void kernel_dgemm_nt_8x4_gen_lib4(int k, double *alpha, double *A, int sda, double *B, double *beta, int offsetC, double *C, int sdc, int offsetD, double *D, int sdd, int m0, int m1, int k0, int k1); -void kernel_dgemm_nn_8x4_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dgemm_nn_8x4_vs_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, int m1, int n1); // -void kernel_dgemm_nn_8x4_gen_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, int offsetC, double *C, int sdc, int offsetD, double *D, int sdd, int m0, int m1, int n0, int n1); // -void kernel_dgemm_tt_8x4_lib4(int k, double *alpha, int offsetA, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dgemm_tt_8x4_vs_lib4(int k, double *alpha, int offsetA, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, int m1, int n1); // -void kernel_dsyrk_nn_u_8x4_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dsyrk_nn_u_8x4_vs_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, int m1, int n1); // -void kernel_dsyrk_nt_l_8x4_lib4(int k, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dsyrk_nt_l_8x4_vs_lib4(int k, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, int km, int kn); // -void kernel_dsyrk_nt_l_8x4_gen_lib4(int k, double *alpha, double *A, int sda, double *B, double *beta, int offsetC, double *C, int sdc, int offsetD, double *D, int sdd, int m0, int m1, int k0, int k1); -void kernel_dtrmm_nt_ru_8x4_lib4(int k, double *alpha, double *A, int sda, double *B, double *D, int sdd); // -void kernel_dtrmm_nt_ru_8x4_vs_lib4(int k, double *alpha, double *A, int sda, double *B, double *D, int sdd, int km, int kn); // -void kernel_dtrmm_nn_rl_8x4_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *D, int sdd); -void kernel_dtrmm_nn_rl_8x4_vs_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *D, int sdd, int km, int kn); -void kernel_dtrmm_nn_rl_8x4_gen_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, int offsetD, double *D, int sdd, int m0, int m1, int n0, int n1); -void kernel_dtrsm_nt_rl_inv_8x4_vs_lib4(int k, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E, int km, int kn); -void kernel_dtrsm_nt_rl_inv_8x4_lib4(int k, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E); -void kernel_dtrsm_nt_rl_one_8x4_lib4(int k, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, double *E); -void kernel_dtrsm_nt_rl_one_8x4_vs_lib4(int k, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, double *E, int km, int kn); -void kernel_dtrsm_nt_ru_inv_8x4_lib4(int k, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E); -void kernel_dtrsm_nt_ru_inv_8x4_vs_lib4(int k, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E, int km, int kn); -void kernel_dtrsm_nt_ru_one_8x4_lib4(int k, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, double *E); -void kernel_dtrsm_nt_ru_one_8x4_vs_lib4(int k, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd, double *E, int km, int kn); -void kernel_dtrsm_nn_ru_inv_8x4_lib4(int k, double *A, int sda, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E); -void kernel_dtrsm_nn_ru_inv_8x4_vs_lib4(int k, double *A, int sda, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E, int km, int kn); -void kernel_dtrsm_nn_ll_inv_8x4_lib4(int k, double *A, int sda, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int sde, double *inv_diag_E); -void kernel_dtrsm_nn_ll_inv_8x4_vs_lib4(int k, double *A, int sda, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int sde, double *inv_diag_E, int km, int kn); -void kernel_dtrsm_nn_ll_one_8x4_lib4(int k, double *A, int sda, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int sde); -void kernel_dtrsm_nn_ll_one_8x4_vs_lib4(int k, double *A, int sda, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int sde, int km, int kn); -void kernel_dtrsm_nn_lu_inv_8x4_lib4(int kmax, double *A, int sda, double *B, int sdb, double *C, int sdc, double *D, int sdd, double *E, int sde, double *inv_diag_E); -void kernel_dtrsm_nn_lu_inv_8x4_vs_lib4(int kmax, double *A, int sda, double *B, int sdb, double *C, int sdc, double *D, int sdd, double *E, int sde, double *inv_diag_E, int km, int kn); -// 4x8 -void kernel_dgemm_nt_4x8_lib4(int k, double *alpha, double *A, double *B, int sdb, double *beta, double *C, double *D); // -void kernel_dgemm_nt_4x8_vs_lib4(int k, double *alpha, double *A, double *B, int sdb, double *beta, double *C, double *D, int km, int kn); // -void kernel_dgemm_nn_4x8_lib4(int k, double *alpha, double *A, int offsetB, double *B, int sdb, double *beta, double *C, double *D); // -void kernel_dgemm_nn_4x8_vs_lib4(int k, double *alpha, double *A, int offsetB, double *B, int sdb, double *beta, double *C, double *D, int m1, int n1); // -void kernel_dgemm_tt_4x8_lib4(int k, double *alpha, int offsetA, double *A, int sda, double *B, int sdb, double *beta, double *C, double *D); // -void kernel_dgemm_tt_4x8_vs_lib4(int k, double *alpha, int offsetA, double *A, int sda, double *B, int sdb, double *beta, double *C, double *D, int m1, int n1); // -void kernel_dgemm_tt_4x8_gen_lib4(int k, double *alpha, int offsetA, double *A, int sda, double *B, int sdb, double *beta, int offsetC, double *C, int sdc, int offsetD, double *D, int sdd, int m0, int m1, int n0, int n1); // -void kernel_dtrsm_nt_rl_inv_4x8_lib4(int k, double *A, double *B, int sdb, double *C, double *D, double *E, int sed, double *inv_diag_E); -void kernel_dtrsm_nt_rl_inv_4x8_vs_lib4(int k, double *A, double *B, int sdb, double *C, double *D, double *E, int sed, double *inv_diag_E, int km, int kn); -// 8x2 -void kernel_dgemm_nn_8x2_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dgemm_nn_8x2_vs_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, int m1, int n1); // -// 2x8 -void kernel_dgemm_nn_2x8_lib4(int k, double *alpha, double *A, int offsetB, double *B, int sdb, double *beta, double *C, double *D); // -void kernel_dgemm_nn_2x8_vs_lib4(int k, double *alpha, double *A, int offsetB, double *B, int sdb, double *beta, double *C, double *D, int m1, int n1); // -// 10xX -void kernel_dgemm_nn_10x4_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dgemm_nn_10x4_vs_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, int m1, int n1); // -void kernel_dgemm_nn_10x2_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dgemm_nn_10x2_vs_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, int m1, int n1); // -// 6xX -void kernel_dgemm_nn_8x6_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dgemm_nn_8x6_vs_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, int m1, int n1); // -void kernel_dgemm_nn_6x8_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dgemm_nn_6x8_vs_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, int m1, int n1); // -void kernel_dgemm_nn_6x6_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dgemm_nn_6x6_vs_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, int m1, int n1); // -void kernel_dgemm_nn_6x4_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dgemm_nn_6x4_vs_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, int m1, int n1); // -void kernel_dgemm_nn_6x2_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd); // -void kernel_dgemm_nn_6x2_vs_lib4(int k, double *alpha, double *A, int sda, int offsetB, double *B, int sdb, double *beta, double *C, int sdc, double *D, int sdd, int m1, int n1); // -// 4x4 -void kernel_dgemm_nt_4x4_lib4(int k, double *alpha, double *A, double *B, double *beta, double *C, double *D); // -void kernel_dgemm_nt_4x4_vs_lib4(int k, double *alpha, double *A, double *B, double *beta, double *C, double *D, int km, int kn); // -void kernel_dgemm_nt_4x4_gen_lib4(int k, double *alpha, double *A, double *B, double *beta, int offsetC, double *C, int sdc, int offsetD, double *D, int sdd, int m0, int m1, int n0, int n1); -void kernel_dgemm_nn_4x4_lib4(int k, double *alpha, double *A, int offsetB, double *B, int sdb, double *beta, double *C, double *D); // -void kernel_dgemm_nn_4x4_vs_lib4(int k, double *alpha, double *A, int offsetB, double *B, int sdb, double *beta, double *C, double *D, int m1, int n1); // -void kernel_dgemm_nn_4x4_gen_lib4(int k, double *alpha, double *A, int offsetB, double *B, int sdb, double *beta, int offsetC, double *C, int sdc, int offsetD, double *D, int sdd, int m0, int m1, int n0, int n1); // -void kernel_dgemm_tt_4x4_lib4(int k, double *alpha, int offsetA, double *A, int sda, double *B, double *beta, double *C, double *D); // -void kernel_dgemm_tt_4x4_vs_lib4(int k, double *alpha, int offsetA, double *A, int sda, double *B, double *beta, double *C, double *D, int m1, int n1); // -void kernel_dgemm_tt_4x4_gen_lib4(int k, double *alpha, int offsetA, double *A, int sda, double *B, double *beta, int offsetC, double *C, int sdc, int offsetD, double *D, int sdd, int m0, int m1, int n0, int n1); // -void kernel_dsyrk_nn_u_4x4_lib4(int k, double *alpha, double *A, int offsetB, double *B, int sdb, double *beta, double *C, double *D); // -void kernel_dsyrk_nn_u_4x4_vs_lib4(int k, double *alpha, double *A, int offsetB, double *B, int sdb, double *beta, double *C, double *D, int m1, int n1); // -void kernel_dsyrk_nt_l_4x4_lib4(int k, double *alpha, double *A, double *B, double *beta, double *C, double *D); // -void kernel_dsyrk_nt_l_4x4_vs_lib4(int k, double *alpha, double *A, double *B, double *beta, double *C, double *D, int km, int kn); // -void kernel_dsyrk_nt_l_4x4_gen_lib4(int k, double *alpha, double *A, double *B, double *beta, int offsetC, double *C, int sdc, int offsetD, double *D, int sdd, int m0, int m1, int n0, int n1); -void kernel_dsyrk_nt_u_4x4_lib4(int k, double *alpha, double *A, double *B, double *beta, double *C, double *D); // -void kernel_dsyrk_nt_u_4x4_vs_lib4(int k, double *alpha, double *A, double *B, double *beta, double *C, double *D, int km, int kn); // -void kernel_dsyrk_nt_u_4x4_gen_lib4(int k, double *alpha, double *A, double *B, double *beta, int offsetC, double *C, int sdc, int offsetD, double *D, int sdd, int m0, int m1, int n0, int n1); -void kernel_dtrmm_nt_ru_4x4_lib4(int k, double *alpha, double *A, double *B, double *D); // -void kernel_dtrmm_nt_ru_4x4_vs_lib4(int k, double *alpha, double *A, double *B, double *D, int km, int kn); // -void kernel_dtrmm_nn_rl_4x4_lib4(int k, double *alpha, double *A, int offsetB, double *B, int sdb, double *D); -void kernel_dtrmm_nn_rl_4x4_vs_lib4(int k, double *alpha, double *A, int offsetB, double *B, int sdb, double *D, int m1, int n1); -void kernel_dtrmm_nn_rl_4x4_gen_lib4(int k, double *alpha, double *A, int offsetB, double *B, int sdb, int offsetD, double *D, int sdd, int m0, int m1, int n0, int n1); -void kernel_dtrsm_nt_rl_inv_4x4_lib4(int k, double *A, double *B, double *beta, double *C, double *D, double *E, double *inv_diag_E); -void kernel_dtrsm_nt_rl_inv_4x4_vs_lib4(int k, double *A, double *B, double *beta, double *C, double *D, double *E, double *inv_diag_E, int km, int kn); -void kernel_dtrsm_nt_rl_one_4x4_lib4(int k, double *A, double *B, double *beta, double *C, double *D, double *E); -void kernel_dtrsm_nt_rl_one_4x4_vs_lib4(int k, double *A, double *B, double *beta, double *C, double *D, double *E, int km, int kn); -void kernel_dtrsm_nt_ru_inv_4x4_lib4(int k, double *A, double *B, double *beta, double *C, double *D, double *E, double *inv_diag_E); -void kernel_dtrsm_nt_ru_inv_4x4_vs_lib4(int k, double *A, double *B, double *beta, double *C, double *D, double *E, double *inv_diag_E, int km, int kn); -void kernel_dtrsm_nt_ru_one_4x4_lib4(int k, double *A, double *B, double *beta, double *C, double *D, double *E); -void kernel_dtrsm_nt_ru_one_4x4_vs_lib4(int k, double *A, double *B, double *beta, double *C, double *D, double *E, int km, int kn); -void kernel_dtrsm_nn_ru_inv_4x4_lib4(int k, double *A, double *B, int sdb, double *beta, double *C, double *D, double *E, double *inv_diag_E); -void kernel_dtrsm_nn_ru_inv_4x4_vs_lib4(int k, double *A, double *B, int sdb, double *beta, double *C, double *D, double *E, double *inv_diag_E, int km, int kn); -void kernel_dtrsm_nn_ll_inv_4x4_lib4(int k, double *A, double *B, int sdb, double *beta, double *C, double *D, double *E, double *inv_diag_E); -void kernel_dtrsm_nn_ll_inv_4x4_vs_lib4(int k, double *A, double *B, int sdb, double *beta, double *C, double *D, double *E, double *inv_diag_E, int km, int kn); -void kernel_dtrsm_nn_ll_one_4x4_lib4(int k, double *A, double *B, int sdb, double *beta, double *C, double *D, double *E); -void kernel_dtrsm_nn_ll_one_4x4_vs_lib4(int k, double *A, double *B, int sdb, double *beta, double *C, double *D, double *E, int km, int kn); -void kernel_dtrsm_nn_lu_inv_4x4_lib4(int kmax, double *A, double *B, int sdb, double *C, double *D, double *E, double *inv_diag_E); -void kernel_dtrsm_nn_lu_inv_4x4_vs_lib4(int kmax, double *A, double *B, int sdb, double *C, double *D, double *E, double *inv_diag_E, int km, int kn); -void kernel_dtrsm_nn_lu_one_4x4_lib4(int kmax, double *A, double *B, int sdb, double *C, double *D, double *E); -void kernel_dtrsm_nn_lu_one_4x4_vs_lib4(int kmax, double *A, double *B, int sdb, double *C, double *D, double *E, int km, int kn); -// 4x2 -void kernel_dgemm_nn_4x2_lib4(int k, double *alpha, double *A, int offsetB, double *B, int sdb, double *beta, double *C, double *D); // -void kernel_dgemm_nn_4x2_vs_lib4(int k, double *alpha, double *A, int offsetB, double *B, int sdb, double *beta, double *C, double *D, int m1, int n1); // -void kernel_dgemm_nt_4x2_lib4(int k, double *alpha, double *A, double *B, double *beta, double *C, double *D); -void kernel_dgemm_nt_4x2_vs_lib4(int k, double *alpha, double *A, double *B, double *beta, double *C, double *D, int m1, int n1); -void kernel_dsyrk_nt_l_4x2_lib4(int k, double *alpha, double *A, double *B, double *beta, double *C, double *D); // -void kernel_dsyrk_nt_l_4x2_vs_lib4(int k, double *alpha, double *A, double *B, double *beta, double *C, double *D, int km, int kn); // -void kernel_dtrmm_nn_rl_4x2_lib4(int k, double *alpha, double *A, int offsetB, double *B, int sdb, double *D); -void kernel_dtrmm_nn_rl_4x2_vs_lib4(int k, double *alpha, double *A, int offsetB, double *B, int sdb, double *D, int m1, int n1); -void kernel_dtrsm_nt_rl_inv_4x2_lib4(int k, double *A, double *B, double *beta, double *C, double *D, double *E, double *inv_diag_E); -void kernel_dtrsm_nt_rl_inv_4x2_vs_lib4(int k, double *A, double *B, double *beta, double *C, double *D, double *E, double *inv_diag_E, int km, int kn); -// 2x4 -void kernel_dgemm_nn_2x4_lib4(int k, double *alpha, double *A, int offsetB, double *B, int sdb, double *beta, double *C, double *D); // -void kernel_dgemm_nn_2x4_vs_lib4(int k, double *alpha, double *A, int offsetB, double *B, int sdb, double *beta, double *C, double *D, int m1, int n1); // -// 2x2 -void kernel_dgemm_nn_2x2_lib4(int k, double *alpha, double *A, int offsetB, double *B, int sdb, double *beta, double *C, double *D); // -void kernel_dsyrk_nt_l_2x2_lib4(int k, double *alpha, double *A, double *B, double *beta, double *C, double *D); // -void kernel_dsyrk_nt_l_2x2_vs_lib4(int k, double *alpha, double *A, double *B, double *beta, double *C, double *D, int km, int kn); // -// diag -void kernel_dgemm_diag_right_4_a0_lib4(int kmax, double *alpha, double *A, int sda, double *B, double *D, int sdd); -void kernel_dgemm_diag_right_4_lib4(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd); -void kernel_dgemm_diag_right_3_lib4(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd); -void kernel_dgemm_diag_right_2_lib4(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd); -void kernel_dgemm_diag_right_1_lib4(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int sdd); -void kernel_dgemm_diag_left_4_a0_lib4(int kmax, double *alpha, double *A, double *B, double *D); -void kernel_dgemm_diag_left_4_lib4(int kmax, double *alpha, double *A, double *B, double *beta, double *C, double *D); -void kernel_dgemm_diag_left_3_lib4(int kmax, double *alpha, double *A, double *B, double *beta, double *C, double *D); -void kernel_dgemm_diag_left_2_lib4(int kmax, double *alpha, double *A, double *B, double *beta, double *C, double *D); -void kernel_dgemm_diag_left_1_lib4(int kmax, double *alpha, double *A, double *B, double *beta, double *C, double *D); -// low rank update -void kernel_dger4_sub_12r_lib4(int k, double *A, int sda, double *B, double *C, int sdc); -void kernel_dger4_sub_12r_vs_lib4(int k, double *A, int sda, double *B, double *C, int sdc, int km); -void kernel_dger4_sub_8r_lib4(int k, double *A, int sda, double *B, double *C, int sdc); -void kernel_dger4_sub_8r_vs_lib4(int k, double *A, int sda, double *B, double *C, int sdc, int km); -void kernel_dger4_sub_4r_lib4(int n, double *A, double *B, double *C); -void kernel_dger4_sub_4r_vs_lib4(int n, double *A, double *B, double *C, int km); - - - -// LAPACK -// 12x4 -void kernel_dpotrf_nt_l_12x4_lib4(int k, double *A, int sda, double *B, double *C, int sdc, double *D, int sdd, double *inv_diag_D); -void kernel_dpotrf_nt_l_12x4_vs_lib4(int k, double *A, int sda, double *B, double *C, int sdc, double *D, int sdd, double *inv_diag_D, int km, int kn); -void kernel_dgetrf_nn_l_12x4_lib4(int k, double *A, int sda, double *B, int sdb, double *C, int sdc, double *D, int sdd, double *inv_diag_D); -void kernel_dgetrf_nn_l_12x4_vs_lib4(int k, double *A, int sda, double *B, int sdb, double *C, int sdc, double *D, int sdd, double *inv_diag_D, int km, int kn); -void kernel_dgetrf_nn_m_12x4_lib4(int k, double *A, int sda, double *B, int sdb, double *C, int sdc, double *D, int sdd, double *inv_diag_D); -void kernel_dgetrf_nn_m_12x4_vs_lib4(int k, double *A, int sda, double *B, int sdb, double *C, int sdc, double *D, int sdd, double *inv_diag_D, int km, int kn); -void kernel_dgetrf_nn_r_12x4_lib4(int k, double *A, int sda, double *B, int sdb, double *C, int sdc, double *D, int sdd, double *inv_diag_D); -void kernel_dgetrf_nn_r_12x4_vs_lib4(int k, double *A, int sda, double *B, int sdb, double *C, int sdc, double *D, int sdd, double *inv_diag_D, int km, int kn); -void kernel_dgetrf_nt_l_12x4_lib4(int k, double *A, int sda, double *B, double *C, int sdc, double *D, int sdd, double *inv_diag_D); -void kernel_dgetrf_nt_l_12x4_vs_lib4(int k, double *A, int sda, double *B, double *C, int sdc, double *D, int sdd, double *inv_diag_D, int km, int kn); -void kernel_dgetrf_nt_m_12x4_lib4(int k, double *A, int sda, double *B, double *C, int sdc, double *D, int sdd, double *inv_diag_D); -void kernel_dgetrf_nt_m_12x4_vs_lib4(int k, double *A, int sda, double *B, double *C, int sdc, double *D, int sdd, double *inv_diag_D, int km, int kn); -void kernel_dgetrf_nt_r_12x4_lib4(int k, double *A, int sda, double *B, double *C, int sdc, double *D, int sdd, double *inv_diag_D); -void kernel_dgetrf_nt_r_12x4_vs_lib4(int k, double *A, int sda, double *B, double *C, int sdc, double *D, int sdd, double *inv_diag_D, int km, int kn); -// 8x8 -void kernel_dpotrf_nt_l_8x8_lib4(int k, double *A, int sda, double *B, int sdb, double *C, int sdc, double *D, int sdd, double *inv_diag_D); -void kernel_dpotrf_nt_l_8x8_vs_lib4(int k, double *A, int sda, double *B, int sdb, double *C, int sdc, double *D, int sdd, double *inv_diag_D, int km, int kn); -// 8x4 -void kernel_dpotrf_nt_l_8x4_lib4(int k, double *A, int sda, double *B, double *C, int sdc, double *D, int sdd, double *inv_diag_D); -void kernel_dpotrf_nt_l_8x4_vs_lib4(int k, double *A, int sda, double *B, double *C, int sdc, double *D, int sdd, double *inv_diag_D, int km, int kn); -void kernel_dgetrf_nn_l_8x4_lib4(int k, double *A, int sda, double *B, int sdb, double *C, int sdc, double *D, int sdd, double *inv_diag_D); -void kernel_dgetrf_nn_l_8x4_vs_lib4(int k, double *A, int sda, double *B, int sdb, double *C, int sdc, double *D, int sdd, double *inv_diag_D, int km, int kn); -void kernel_dgetrf_nn_r_8x4_lib4(int k, double *A, int sda, double *B, int sdb, double *C, int sdc, double *D, int sdd, double *inv_diag_D); -void kernel_dgetrf_nn_r_8x4_vs_lib4(int k, double *A, int sda, double *B, int sdb, double *C, int sdc, double *D, int sdd, double *inv_diag_D, int km, int kn); -void kernel_dgetrf_nt_l_8x4_lib4(int k, double *A, int sda, double *B, double *C, int sdc, double *D, int sdd, double *inv_diag_D); -void kernel_dgetrf_nt_l_8x4_vs_lib4(int k, double *A, int sda, double *B, double *C, int sdc, double *D, int sdd, double *inv_diag_D, int km, int kn); -void kernel_dgetrf_nt_r_8x4_lib4(int k, double *A, int sda, double *B, double *C, int sdc, double *D, int sdd, double *inv_diag_D); -void kernel_dgetrf_nt_r_8x4_vs_lib4(int k, double *A, int sda, double *B, double *C, int sdc, double *D, int sdd, double *inv_diag_D, int km, int kn); -// 4x4 -void kernel_dpotrf_nt_l_4x4_lib4(int k, double *A, double *B, double *C, double *D, double *inv_diag_D); -void kernel_dpotrf_nt_l_4x4_vs_lib4(int k, double *A, double *B, double *C, double *D, double *inv_diag_D, int km, int kn); -#if defined(TARGET_X64_INTEL_SANDY_BRIDGE) -void kernel_dlauum_nt_4x4_lib4(int k, double *alpha, double *A, double *B, double *beta, double *C, double *D); // -void kernel_dlauum_nt_4x4_vs_lib4(int k, double *alpha, double *A, double *B, double *beta, double *C, double *D, int km, int kn); // -#endif -void kernel_dgetrf_nn_4x4_lib4(int k, double *A, double *B, int sdb, double *C, double *D, double *inv_diag_D); -void kernel_dgetrf_nn_4x4_vs_lib4(int k, double *A, double *B, int sdb, double *C, double *D, double *inv_diag_D, int km, int kn); -void kernel_dgetrf_nt_4x4_lib4(int k, double *A, double *B, double *C, double *D, double *inv_diag_D); -void kernel_dgetrf_nt_4x4_vs_lib4(int k, double *A, double *B, double *C, double *D, double *inv_diag_D, int km, int kn); -void kernel_dgeqrf_4_lib4(int m, double *pD, int sdd, double *dD); -void kernel_dgeqrf_vs_lib4(int m, int n, int k, int offD, double *pD, int sdd, double *dD); -void kernel_dlarf_4_lib4(int m, int n, double *pV, int sdv, double *tau, double *pC, int sdc); // rank-4 reflector -void kernel_dlarf_t_4_lib4(int m, int n, double *pD, int sdd, double *pVt, double *dD, double *pC0, int sdc, double *pW); -void kernel_dgelqf_4_lib4(int n, double *pD, double *dD); -void kernel_dgelqf_vs_lib4(int m, int n, int k, int offD, double *pD, int sdd, double *dD); -void kernel_dlarft_4_lib4(int kmax, double *pD, double *dD, double *pT); -void kernel_dlarft_3_lib4(int kmax, double *pD, double *dD, double *pT); -void kernel_dlarft_2_lib4(int kmax, double *pD, double *dD, double *pT); -void kernel_dlarft_1_lib4(int kmax, double *pD, double *dD, double *pT); -void kernel_dgelqf_dlarft12_12_lib4(int n, double *pD, int sdd, double *dD, double *pT); -void kernel_dgelqf_dlarft4_12_lib4(int n, double *pD, int sdd, double *dD, double *pT); -void kernel_dgelqf_dlarft4_8_lib4(int n, double *pD, int sdd, double *dD, double *pT); -void kernel_dgelqf_dlarft4_4_lib4(int n, double *pD, double *dD, double *pT); -void kernel_dlarfb12_rn_12_lib4(int kmax, double *pV, int sdd, double *pT, double *pD, double *pK); -void kernel_dlarfb12_rn_4_lib4(int kmax, double *pV, int sdd, double *pT, double *pD, double *pK, int km); -void kernel_dlarfb4_rn_12_lib4(int kmax, double *pV, double *pT, double *pD, int sdd); -void kernel_dlarfb4_rn_8_lib4(int kmax, double *pV, double *pT, double *pD, int sdd); -void kernel_dlarfb4_rn_4_lib4(int kmax, double *pV, double *pT, double *pD); -void kernel_dlarfb3_rn_4_lib4(int kmax, double *pV, double *pT, double *pD); -void kernel_dlarfb2_rn_4_lib4(int kmax, double *pV, double *pT, double *pD); -void kernel_dlarfb1_rn_4_lib4(int kmax, double *pV, double *pT, double *pD); -void kernel_dlarfb4_rn_1_lib4(int kmax, double *pV, double *pT, double *pD); -void kernel_dlarfb3_rn_1_lib4(int kmax, double *pV, double *pT, double *pD); -void kernel_dlarfb2_rn_1_lib4(int kmax, double *pV, double *pT, double *pD); -void kernel_dlarfb1_rn_1_lib4(int kmax, double *pV, double *pT, double *pD); -void kernel_dlarfb4_rt_4_lib4(int kmax, double *pV, double *pT, double *pD); -void kernel_dlarfb3_rt_4_lib4(int kmax, double *pV, double *pT, double *pD); -void kernel_dlarfb2_rt_4_lib4(int kmax, double *pV, double *pT, double *pD); -void kernel_dlarfb1_rt_4_lib4(int kmax, double *pV, double *pT, double *pD); -void kernel_dlarfb4_rt_1_lib4(int kmax, double *pV, double *pT, double *pD); -void kernel_dlarfb3_rt_1_lib4(int kmax, double *pV, double *pT, double *pD); -void kernel_dlarfb2_rt_1_lib4(int kmax, double *pV, double *pT, double *pD); -void kernel_dlarfb1_rt_1_lib4(int kmax, double *pV, double *pT, double *pD); -void kernel_dgelqf_pd_dlarft12_12_lib4(int n, double *pD, int sdd, double *dD, double *pT); -void kernel_dgelqf_pd_dlarft4_8_lib4(int n, double *pD, int sdd, double *dD, double *pT); -void kernel_dgelqf_pd_dlarft4_4_lib4(int n, double *pD, double *dD, double *pT); -void kernel_dgelqf_pd_4_lib4(int n, double *pD, double *dD); -void kernel_dgelqf_pd_vs_lib4(int m, int n, int k, int offD, double *pD, int sdd, double *dD); -void kernel_dgelqf_pd_la_vs_lib4(int m, int n1, int k, int offD, double *pD, int sdd, double *dD, int offA, double *pA, int sda); -void kernel_dlarft_4_la_lib4(int n1, double *dD, double *pA, double *pT); -void kernel_dlarfb4_rn_12_la_lib4(int n1, double *pVA, double *pT, double *pD, int sdd, double *pA, int sda); -void kernel_dlarfb4_rn_8_la_lib4(int n1, double *pVA, double *pT, double *pD, int sdd, double *pA, int sda); -void kernel_dlarfb4_rn_4_la_lib4(int n1, double *pVA, double *pT, double *pD, double *pA); -void kernel_dlarfb4_rn_1_la_lib4(int n1, double *pVA, double *pT, double *pD, double *pA); -void kernel_dgelqf_pd_lla_vs_lib4(int m, int n0, int n1, int k, int offD, double *pD, int sdd, double *dD, int offL, double *pL, int sdl, int offA, double *pA, int sda); -void kernel_dlarft_4_lla_lib4(int n0, int n1, double *dD, double *pL, double *pA, double *pT); -void kernel_dlarfb4_rn_12_lla_lib4(int n0, int n1, double *pVL, double *pVA, double *pT, double *pD, int sdd, double *pL, int sdl, double *pA, int sda); -void kernel_dlarfb4_rn_8_lla_lib4(int n0, int n1, double *pVL, double *pVA, double *pT, double *pD, int sdd, double *pL, int sdl, double *pA, int sda); -void kernel_dlarfb4_rn_4_lla_lib4(int n0, int n1, double *pVL, double *pVA, double *pT, double *pD, double *pL, double *pA); -void kernel_dlarfb4_rn_1_lla_lib4(int n0, int n1, double *pVL, double *pVA, double *pT, double *pD, double *pL, double *pA); -// 4x2 -void kernel_dpotrf_nt_l_4x2_lib4(int k, double *A, double *B, double *C, double *D, double *inv_diag_D); -void kernel_dpotrf_nt_l_4x2_vs_lib4(int k, double *A, double *B, double *C, double *D, double *inv_diag_D, int km, int kn); -// 2x2 -void kernel_dpotrf_nt_l_2x2_lib4(int k, double *A, double *B, double *C, double *D, double *inv_diag_D); -void kernel_dpotrf_nt_l_2x2_vs_lib4(int k, double *A, double *B, double *C, double *D, double *inv_diag_D, int km, int kn); -// 12 -void kernel_dgetrf_pivot_12_lib4(int m, double *pA, int sda, double *inv_diag_A, int* ipiv); -void kernel_dgetrf_pivot_12_vs_lib4(int m, double *pA, int sda, double *inv_diag_A, int* ipiv, int n); -// 8 -void kernel_dgetrf_pivot_8_lib4(int m, double *pA, int sda, double *inv_diag_A, int* ipiv); -void kernel_dgetrf_pivot_8_vs_lib4(int m, double *pA, int sda, double *inv_diag_A, int* ipiv, int n); -// 4 -void kernel_dgetrf_pivot_4_lib4(int m, double *pA, int sda, double *inv_diag_A, int* ipiv); -void kernel_dgetrf_pivot_4_vs_lib4(int m, double *pA, int sda, double *inv_diag_A, int* ipiv, int n1); -// vector -void kernel_drowsw_lib4(int kmax, double *pA, double *pC); - - - -// merged routines -// 12x4 -void kernel_dgemm_dtrsm_nt_rl_inv_12x4_lib4(int kp, double *Ap, int sdap, double *Bp, int km_, double *Am, int sdam, double *Bm, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E); -void kernel_dgemm_dtrsm_nt_rl_inv_12x4_vs_lib4(int kp, double *Ap, int sdap, double *Bp, int km_, double *Am, int sdam, double *Bm, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E, int km, int kn); -void kernel_dsyrk_dpotrf_nt_l_12x4_lib4(int kp, double *Ap, int sdap, double *Bp, int km_, double *Am, int sdam, double *Bm, double *C, int sdc, double *D, int sdd, double *inv_diag_D); -void kernel_dsyrk_dpotrf_nt_l_12x4_vs_lib4(int kp, double *Ap, int sdap, double *Bp, int km_, double *Am, int sdam, double *Bm, double *C, int sdc, double *D, int sdd, double *inv_diag_D, int km, int kn); -// 4x12 -void kernel_dgemm_dtrsm_nt_rl_inv_4x12_vs_lib4(int kp, double *Ap, double *Bp, int sdbp, int km_, double *Am, double *Bm, int sdbm, double *C, double *D, double *E, int sde, double *inv_diag_E, int km, int kn); -// 8x8 -void kernel_dsyrk_dpotrf_nt_l_8x8_lib4(int kp, double *Ap, int sdap, double *Bp, int sdbp, int km_, double *Am, int sdam, double *Bm, int sdbm, double *C, int sdc, double *D, int sdd, double *inv_diag_D); -void kernel_dsyrk_dpotrf_nt_l_8x8_vs_lib4(int kp, double *Ap, int sdap, double *Bp, int sdbp, int km_, double *Am, int sdam, double *Bm, int sdbm, double *C, int sdc, double *D, int sdd, double *inv_diag_D, int km, int kn); -void kernel_dgemm_dtrsm_nt_rl_inv_8x8l_vs_lib4(int kp, double *Ap, int sdap, double *Bp, int sdb, int km_, double *Am, int sdam, double *Bm, int sdbm, double *C, int sdc, double *D, int sdd, double *E, int sde, double *inv_diag_E, int km, int kn); -void kernel_dgemm_dtrsm_nt_rl_inv_8x8u_vs_lib4(int kp, double *Ap, int sdap, double *Bp, int sdb, int km_, double *Am, int sdam, double *Bm, int sdbm, double *C, int sdc, double *D, int sdd, double *E, int sde, double *inv_diag_E, int km, int kn); -// 8x4 -void kernel_dgemm_dtrsm_nt_rl_inv_8x4_lib4(int kp, double *Ap, int sdap, double *Bp, int km_, double *Am, int sdam, double *Bm, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E); -void kernel_dgemm_dtrsm_nt_rl_inv_8x4_vs_lib4(int kp, double *Ap, int sdap, double *Bp, int km_, double *Am, int sdam, double *Bm, double *C, int sdc, double *D, int sdd, double *E, double *inv_diag_E, int km, int kn); -void kernel_dsyrk_dpotrf_nt_l_8x4_lib4(int kp, double *Ap, int sdap, double *Bp, int km_, double *Am, int sdam, double *Bm, double *C, int sdc, double *D, int sdd, double *inv_diag_D); -void kernel_dsyrk_dpotrf_nt_l_8x4_vs_lib4(int kp, double *Ap, int sdap, double *Bp, int km_, double *Am, int sdam, double *Bm, double *C, int sdc, double *D, int sdd, double *inv_diag_D, int km, int kn); -// 4x8 -void kernel_dgemm_dtrsm_nt_rl_inv_4x8_vs_lib4(int kp, double *Ap, double *Bp, int sdbp, int km_, double *Am, double *Bm, int sdbm, double *C, double *D, double *E, int sde, double *inv_diag_E, int km, int kn); -// 4x4 -void kernel_dgemm_dtrsm_nt_rl_inv_4x4_lib4(int kp, double *Ap, double *Bp, int km_, double *Am, double *Bm, double *C, double *D, double *E, double *inv_diag_E); -void kernel_dgemm_dtrsm_nt_rl_inv_4x4_vs_lib4(int kp, double *Ap, double *Bp, int km_, double *Am, double *Bm, double *C, double *D, double *E, double *inv_diag_E, int km, int kn); -void kernel_dsyrk_dpotrf_nt_l_4x4_lib4(int kp, double *Ap, double *Bp, int km_, double *Am, double *Bm, double *C, double *D, double *inv_diag_D); -void kernel_dsyrk_dpotrf_nt_l_4x4_vs_lib4(int kp, double *Ap, double *Bp, int km_, double *Am, double *Bm, double *C, double *D, double *inv_diag_D, int km, int kn); -// 4x2 -void kernel_dgemm_dtrsm_nt_rl_inv_4x2_lib4(int kp, double *Ap, double *Bp, int km_, double *Am, double *Bm, double *C, double *D, double *E, double *inv_diag_E); -void kernel_dgemm_dtrsm_nt_rl_inv_4x2_vs_lib4(int kp, double *Ap, double *Bp, int km_, double *Am, double *Bm, double *C, double *D, double *E, double *inv_diag_E, int km, int kn); -void kernel_dsyrk_dpotrf_nt_l_4x2_lib4(int kp, double *Ap, double *Bp, int km_, double *Am, double *Bm, double *C, double *D, double *inv_diag_D); -void kernel_dsyrk_dpotrf_nt_l_4x2_vs_lib4(int kp, double *Ap, double *Bp, int km_, double *Am, double *Bm, double *C, double *D, double *inv_diag_D, int km, int kn); -// 2x2 -void kernel_dsyrk_dpotrf_nt_l_2x2_lib4(int kp, double *Ap, double *Bp, int km_, double *Am, double *Bm, double *C, double *D, double *inv_diag_D); -void kernel_dsyrk_dpotrf_nt_l_2x2_vs_lib4(int kp, double *Ap, double *Bp, int km_, double *Am, double *Bm, double *C, double *D, double *inv_diag_D, int km, int kn); - -/* - * - * Auxiliary routines - * - * cpsc copy and scale, scale - * cp copy - * add - * set and scale - * transpose and scale - * set and scale - * - */ - -// copy and scale -void kernel_dgecpsc_8_0_lib4(int tri, int kmax, double alpha, double *A0, int sda, double *B, int sdb); -void kernel_dgecpsc_8_1_lib4(int tri, int kmax, double alpha, double *A0, int sda, double *B, int sdb); -void kernel_dgecpsc_8_2_lib4(int tri, int kmax, double alpha, double *A0, int sda, double *B, int sdb); -void kernel_dgecpsc_8_3_lib4(int tri, int kmax, double alpha, double *A0, int sda, double *B, int sdb); - -void kernel_dgecpsc_4_0_lib4(int tri, int kmax, double alpha, double *A, double *B); -void kernel_dgecpsc_4_1_lib4(int tri, int kmax, double alpha, double *A0, int sda, double *B); -void kernel_dgecpsc_4_2_lib4(int tri, int kmax, double alpha, double *A0, int sda, double *B); -void kernel_dgecpsc_4_3_lib4(int tri, int kmax, double alpha, double *A0, int sda, double *B); - -void kernel_dgecpsc_3_0_lib4(int tri, int kmax, double alpha, double *A, double *B); -void kernel_dgecpsc_3_2_lib4(int tri, int kmax, double alpha, double *A0, int sda, double *B); -void kernel_dgecpsc_3_3_lib4(int tri, int kmax, double alpha, double *A0, int sda, double *B); - -void kernel_dgecpsc_2_0_lib4(int tri, int kmax, double alpha, double *A, double *B); -void kernel_dgecpsc_2_3_lib4(int tri, int kmax, double alpha, double *A0, int sda, double *B); - -void kernel_dgecpsc_1_0_lib4(int tri, int kmax, double alpha, double *A, double *B); - -// copy only -void kernel_dgecp_8_0_lib4(int tri, int kmax, double *A, int sda, double *B, int sdb); - -void kernel_dgecp_4_0_lib4(int tri, int kmax, double *A, double *B); - -// add -void kernel_dgead_8_0_lib4(int kmax, double alpha, double *A0, int sda, double *B, int sdb); -void kernel_dgead_8_1_lib4(int kmax, double alpha, double *A0, int sda, double *B, int sdb); -void kernel_dgead_8_2_lib4(int kmax, double alpha, double *A0, int sda, double *B, int sdb); -void kernel_dgead_8_3_lib4(int kmax, double alpha, double *A0, int sda, double *B, int sdb); -void kernel_dgead_4_0_lib4(int kmax, double alpha, double *A, double *B); -void kernel_dgead_4_1_lib4(int kmax, double alpha, double *A0, int sda, double *B); -void kernel_dgead_4_2_lib4(int kmax, double alpha, double *A0, int sda, double *B); -void kernel_dgead_4_3_lib4(int kmax, double alpha, double *A0, int sda, double *B); -void kernel_dgead_3_0_lib4(int kmax, double alpha, double *A, double *B); -void kernel_dgead_3_2_lib4(int kmax, double alpha, double *A0, int sda, double *B); -void kernel_dgead_3_3_lib4(int kmax, double alpha, double *A0, int sda, double *B); -void kernel_dgead_2_0_lib4(int kmax, double alpha, double *A, double *B); -void kernel_dgead_2_3_lib4(int kmax, double alpha, double *A0, int sda, double *B); -void kernel_dgead_1_0_lib4(int kmax, double alpha, double *A, double *B); - -// set -void kernel_dgeset_4_lib4(int kmax, double alpha, double *A); -void kernel_dtrset_4_lib4(int kmax, double alpha, double *A); - -// traspose -void kernel_dgetr_8_lib4(int tri, int kmax, int kna, double alpha, double *A, int sda, double *C, int sdc); -void kernel_dgetr_4_lib4(int tri, int kmax, int kna, double alpha, double *A, double *C, int sdc); -void kernel_dgetr_3_lib4(int tri, int kmax, int kna, double alpha, double *A, double *C, int sdc); -void kernel_dgetr_2_lib4(int tri, int kmax, int kna, double alpha, double *A, double *C, int sdc); -void kernel_dgetr_1_lib4(int tri, int kmax, int kna, double alpha, double *A, double *C, int sdc); -void kernel_dgetr_4_0_lib4(int m, double *A, int sda, double *B); - - - -// pack -// 12 -void kernel_dpack_nn_12_lib4(int kmax, double *A, int lda, double *B, int sdb); -void kernel_dpack_nn_12_vs_lib4(int kmax, double *A, int lda, double *B, int sdb, int m1); -void kernel_dpack_tt_12_lib4(int kmax, double *A, int lda, double *B, int sdb); -// 8 -void kernel_dpack_nn_8_lib4(int kmax, double *A, int lda, double *B, int sdb); -void kernel_dpack_nn_8_vs_lib4(int kmax, double *A, int lda, double *B, int sdb, int m1); -void kernel_dpack_tt_8_lib4(int kmax, double *A, int lda, double *B, int sdb); -// 4 -void kernel_dpack_nn_4_lib4(int kmax, double *A, int lda, double *B); -void kernel_dpack_nn_4_vs_lib4(int kmax, double *A, int lda, double *B, int m1); -void kernel_dpack_tn_4_p0_lib4(int kmax, double *A, int lda, double *B); -void kernel_dpack_tn_4_lib4(int kmax, double *A, int lda, double *B); -void kernel_dpack_tn_4_vs_lib4(int kmax, double *A, int lda, double *B, int m1); -void kernel_dpack_tt_4_lib4(int kmax, double *A, int lda, double *B, int sdb); -void kernel_dpack_tt_4_vs_lib4(int kmax, double *A, int lda, double *B, int sdb, int m1); -// unpack -// 12 -void kernel_dunpack_nn_12_lib4(int kmax, double *A, int sda, double *B, int ldb); -void kernel_dunpack_nn_12_vs_lib4(int kmax, double *A, int sda, double *B, int ldb, int m1); -void kernel_dunpack_tt_12_lib4(int kmax, double *A, int sda, double *B, int ldb); -// 8 -void kernel_dunpack_nn_8_lib4(int kmax, double *A, int sda, double *B, int ldb); -void kernel_dunpack_nn_8_vs_lib4(int kmax, double *A, int sda, double *B, int ldb, int m1); -void kernel_dunpack_tt_8_lib4(int kmax, double *A, int sda, double *B, int ldb); -// 4 -void kernel_dunpack_nn_4_lib4(int kmax, double *A, double *B, int ldb); -void kernel_dunpack_nn_4_vs_lib4(int kmax, double *A, double *B, int ldb, int m1); -void kernel_dunpack_nt_4_lib4(int kmax, double *A, double *B, int ldb); -void kernel_dunpack_nt_4_vs_lib4(int kmax, double *A, double *B, int ldb, int m1); -void kernel_dunpack_tt_4_lib4(int kmax, double *A, int sda, double *B, int ldb); - -// panel copy -// 12 -void kernel_dpacp_nn_12_lib4(int kmax, int offsetA, double *A, int sda, double *B, int sdb); -void kernel_dpacp_nn_12_vs_lib4(int kmax, int offsetA, double *A, int sda, double *B, int sdb, int m1); -// 8 -void kernel_dpacp_nn_8_lib4(int kmax, int offsetA, double *A, int sda, double *B, int sdb); -void kernel_dpacp_nn_8_vs_lib4(int kmax, int offsetA, double *A, int sda, double *B, int sdb, int m1); -// 4 -void kernel_dpacp_nt_4_lib4(int kmax, double *A, int offsetB, double *B, int sdb); -void kernel_dpacp_tn_4_lib4(int kmax, int offsetA, double *A, int sda, double *B); -void kernel_dpacp_nn_4_lib4(int kmax, int offsetA, double *A, int sda, double *B); -void kernel_dpacp_nn_4_vs_lib4(int kmax, int offsetA, double *A, int sda, double *B, int m1); - - - -/************************************************ -* BLAS API kernels -************************************************/ - -//#if defined(BLAS_API) - -// A, B panel-major bs=4; C, D column-major -// 12x4 -void kernel_dgemm_nt_12x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_12x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_nt_12x4_p0_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *A_p, double *B_p); -void kernel_dsyrk_nt_l_12x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dsyrk_nt_l_12x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dsyrk_nt_u_12x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dsyrk_nt_u_12x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dger2k_nt_12x4_lib44cc(int kmax, double *alpha, double *A0, int sda0, double *B0, double *A1, int sda1, double *B1, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dger2k_nt_12x4_vs_lib44cc(int kmax, double *alpha, double *A0, int sda0, double *B0, double *A1, int sda1, double *B1, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dsyr2k_nt_l_12x4_lib44cc(int kmax, double *alpha, double *A0, int sda0, double *B0, double *A1, int sda1, double *B1, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dsyr2k_nt_l_12x4_vs_lib44cc(int kmax, double *alpha, double *A0, int sda0, double *B0, double *A1, int sda1, double *B1, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_12x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_rl_12x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_one_12x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_rl_one_12x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_12x4_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nt_ru_12x4_vs_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_12x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_ru_12x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_one_12x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_ru_one_12x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrsm_nt_ll_inv_12x4_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, int sde, double *inv_diag_E); -void kernel_dtrsm_nt_ll_inv_12x4_vs_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, int sde, double *inv_diag_E, int km, int kn); -void kernel_dtrsm_nt_rl_inv_12x4_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *dE); -void kernel_dtrsm_nt_rl_inv_12x4_vs_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *dE, int m1, int n1); -void kernel_dtrsm_nt_rl_inv_12x4_lib44ccc(int kmax, double *A, int sda, double *B, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE); -void kernel_dtrsm_nt_rl_inv_12x4_vs_lib44ccc(int kmax, double *A, int sda, double *B, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nt_rl_one_12x4_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E); -void kernel_dtrsm_nt_rl_one_12x4_vs_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, int m1, int n1); -void kernel_dtrsm_nt_ru_inv_12x4_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *dE); -void kernel_dtrsm_nt_ru_inv_12x4_vs_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *dE, int m1, int n1); -void kernel_dtrsm_nt_ru_one_12x4_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E); -void kernel_dtrsm_nt_ru_one_12x4_vs_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, int m1, int n1); -void kernel_dpotrf_nt_l_12x4_lib44cc(int kmax, double *A, int sda, double *B, double *C, int ldc, double *D, int ldd, double *dD); -void kernel_dpotrf_nt_l_12x4_vs_lib44cc(int kmax, double *A, int sda, double *B, double *C, int ldc, double *D, int ldd, double *dD, int m1, int n1); -// 4x12 -void kernel_dgemm_nt_4x12_lib44cc(int kmax, double *alpha, double *A, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_4x12_vs_lib44cc(int kmax, double *alpha, double *A, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_nt_4x12_p0_vs_lib44cc(int kmax, double *alpha, double *A, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1, double *A_p, double *B_p); -void kernel_dtrmm_nt_rl_4x12_tran_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nt_rl_4x12_tran_vs_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_one_4x12_tran_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nt_rl_one_4x12_tran_vs_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_4x12_tran_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nt_ru_4x12_tran_vs_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_one_4x12_tran_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nt_ru_one_4x12_tran_vs_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -// 8x8 -void kernel_dsyrk_nt_l_8x8_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dsyrk_nt_l_8x8_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dsyrk_nt_u_8x8_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dsyrk_nt_u_8x8_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dger2k_nt_8x8_lib44cc(int kmax, double *alpha, double *A0, int sda0, double *B0, int sdb0, double *A1, int sda1, double *B1, int sdb1, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dger2k_nt_8x8_vs_lib44cc(int kmax, double *alpha, double *A0, int sda0, double *B0, int sdb0, double *A1, int sda1, double *B1, int sdb1, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dsyr2k_nt_l_8x8_lib44cc(int kmax, double *alpha, double *A0, int sda0, double *B0, int sdb0, double *A1, int sda1, double *B1, int sdb1, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dsyr2k_nt_l_8x8_vs_lib44cc(int kmax, double *alpha, double *A0, int sda0, double *B0, int sdb0, double *A1, int sda1, double *B1, int sdb1, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dpotrf_nt_l_8x8_lib44cc(int kmax, double *A, int sda, double *B, int sdb, double *C, int ldc, double *D, int ldd, double *dD); -void kernel_dpotrf_nt_l_8x8_vs_lib44cc(int kmax, double *A, int sda, double *B, int sdb, double *C, int ldc, double *D, int ldd, double *dD, int m1, int n1); -// 8x4 -void kernel_dgemm_nt_8x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_8x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_nt_8x4_p0_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *A_p, double *B_p); -void kernel_dgemm_nt_8x4_p_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *A_p); -void kernel_dsyrk_nt_l_8x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dsyrk_nt_l_8x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dsyrk_nt_u_8x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dsyrk_nt_u_8x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dger2k_nt_8x4_lib44cc(int kmax, double *alpha, double *A0, int sda0, double *B0, double *A1, int sda1, double *B1, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dger2k_nt_8x4_vs_lib44cc(int kmax, double *alpha, double *A0, int sda0, double *B0, double *A1, int sda1, double *B1, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dsyr2k_nt_l_8x4_lib44cc(int kmax, double *alpha, double *A0, int sda0, double *B0, double *A1, int sda1, double *B1, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dsyr2k_nt_l_8x4_vs_lib44cc(int kmax, double *alpha, double *A0, int sda0, double *B0, double *A1, int sda1, double *B1, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_8x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_rl_8x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_one_8x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_rl_one_8x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_8x4_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nt_ru_8x4_vs_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_8x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_ru_8x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_one_8x4_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_ru_one_8x4_vs_lib44cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrsm_nt_ll_inv_8x4_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, int sde, double *inv_diag_E); -void kernel_dtrsm_nt_ll_inv_8x4_vs_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, int sde, double *inv_diag_E, int km, int kn); -void kernel_dtrsm_nt_rl_inv_8x4_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *dE); -void kernel_dtrsm_nt_rl_inv_8x4_vs_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *dE, int m1, int n1); -void kernel_dtrsm_nt_rl_inv_8x4_lib44ccc(int kmax, double *A, int sda, double *B, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE); -void kernel_dtrsm_nt_rl_inv_8x4_vs_lib44ccc(int kmax, double *A, int sda, double *B, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nt_rl_one_8x4_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E); -void kernel_dtrsm_nt_rl_one_8x4_vs_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, int m1, int n1); -void kernel_dtrsm_nt_ru_inv_8x4_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *dE); -void kernel_dtrsm_nt_ru_inv_8x4_vs_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *dE, int m1, int n1); -void kernel_dtrsm_nt_ru_one_8x4_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E); -void kernel_dtrsm_nt_ru_one_8x4_vs_lib44cc4(int kmax, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, int m1, int n1); -void kernel_dpotrf_nt_l_8x4_lib44cc(int kmax, double *A, int sda, double *B, double *C, int ldc, double *D, int ldd, double *dD); -void kernel_dpotrf_nt_l_8x4_vs_lib44cc(int kmax, double *A, int sda, double *B, double *C, int ldc, double *D, int ldd, double *dD, int m1, int n1); -// 4x8 -void kernel_dgemm_nt_4x8_lib44cc(int kmax, double *alpha, double *A, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_4x8_vs_lib44cc(int kmax, double *alpha, double *A, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_4x8_tran_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nt_rl_4x8_tran_vs_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_one_4x8_tran_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nt_rl_one_4x8_tran_vs_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_4x8_tran_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nt_ru_4x8_tran_vs_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_one_4x8_tran_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nt_ru_one_4x8_tran_vs_lib444c(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -// 4x4 -void kernel_dgemm_nt_4x4_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_4x4_vs_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dsyrk_nt_l_4x4_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dsyrk_nt_l_4x4_vs_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dsyrk_nt_u_4x4_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dsyrk_nt_u_4x4_vs_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dger2k_nt_4x4_lib44cc(int kmax, double *alpha, double *A0, double *B0, double *A1, double *B1, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dger2k_nt_4x4_vs_lib44cc(int kmax, double *alpha, double *A0, double *B0, double *A1, double *B1, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dsyr2k_nt_l_4x4_lib44cc(int kmax, double *alpha, double *A0, double *B0, double *A1, double *B1, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dsyr2k_nt_l_4x4_vs_lib44cc(int kmax, double *alpha, double *A0, double *B0, double *A1, double *B1, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_4x4_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_rl_4x4_vs_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_4x4_tran_lib444c(int kmax, double *alpha, double *A, double *B, double *beta, double *C, double *D, int ldd); -void kernel_dtrmm_nt_rl_4x4_tran_vs_lib444c(int kmax, double *alpha, double *A, double *B, double *beta, double *C, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_one_4x4_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_rl_one_4x4_vs_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_one_4x4_tran_lib444c(int kmax, double *alpha, double *A, double *B, double *beta, double *C, double *D, int ldd); -void kernel_dtrmm_nt_rl_one_4x4_tran_vs_lib444c(int kmax, double *alpha, double *A, double *B, double *beta, double *C, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_4x4_lib444c(int kmax, double *alpha, double *A, double *B, double *beta, double *C, double *D, int ldd); -void kernel_dtrmm_nt_ru_4x4_vs_lib444c(int kmax, double *alpha, double *A, double *B, double *beta, double *C, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_4x4_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_ru_4x4_vs_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_4x4_tran_lib444c(int kmax, double *alpha, double *A, double *B, double *beta, double *C, double *D, int ldd); -void kernel_dtrmm_nt_ru_4x4_tran_vs_lib444c(int kmax, double *alpha, double *A, double *B, double *beta, double *C, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_one_4x4_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_ru_one_4x4_vs_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_one_4x4_tran_lib444c(int kmax, double *alpha, double *A, double *B, double *beta, double *C, double *D, int ldd); -void kernel_dtrmm_nt_ru_one_4x4_tran_vs_lib444c(int kmax, double *alpha, double *A, double *B, double *beta, double *C, double *D, int ldd, int m1, int n1); -void kernel_dtrsm_nt_ll_inv_4x4_lib44cc4(int kmax, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *inv_diag_E); -void kernel_dtrsm_nt_ll_inv_4x4_vs_lib44cc4(int kmax, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *inv_diag_E, int km, int kn); -void kernel_dtrsm_nt_rl_inv_4x4_lib44cc4(int kmax, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *dE); -void kernel_dtrsm_nt_rl_inv_4x4_vs_lib44cc4(int kmax, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *dE, int m1, int n1); -void kernel_dtrsm_nt_rl_inv_4x4_lib44ccc(int kmax, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE); -void kernel_dtrsm_nt_rl_inv_4x4_vs_lib44ccc(int kmax, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nt_rl_one_4x4_lib44cc4(int kmax, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E); -void kernel_dtrsm_nt_rl_one_4x4_vs_lib44cc4(int kmax, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, int m1, int n1); -void kernel_dtrsm_nt_ru_inv_4x4_lib44cc4(int kmax, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *dE); -void kernel_dtrsm_nt_ru_inv_4x4_vs_lib44cc4(int kmax, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *dE, int m1, int n1); -void kernel_dtrsm_nt_ru_one_4x4_lib44cc4(int kmax, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E); -void kernel_dtrsm_nt_ru_one_4x4_vs_lib44cc4(int kmax, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, double *E, int m1, int n1); -void kernel_dpotrf_nt_l_4x4_lib44cc(int kmax, double *A, double *B, double *C, int ldc, double *D, int ldd, double *dD); -void kernel_dpotrf_nt_l_4x4_vs_lib44cc(int kmax, double *A, double *B, double *C, int ldc, double *D, int ldd, double *dD, int m1, int n1); -// 4x2 -void kernel_dgemm_nt_4x2_lib44cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd); - -// A panel-major bs=4; B, C, D column-major -// 12x4 -void kernel_dgemm_nn_12x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nn_12x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_nt_12x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_12x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dsyrk_nt_l_12x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dsyrk_nt_l_12x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dger2k_nt_12x4_lib4ccc(int kmax, double *alpha, double *A0, int sda0, double *B0, int ldb0, double *A1, int sda1, double *B1, int ldb1, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dger2k_nt_12x4_vs_lib4ccc(int kmax, double *alpha, double *A0, int sda0, double *B0, int ldb0, double *A1, int sda1, double *B1, int ldb1, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_rl_12x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nn_rl_12x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_rl_one_12x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nn_rl_one_12x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_ru_12x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nn_ru_12x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_ru_one_12x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nn_ru_one_12x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_12x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_rl_12x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_one_12x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_rl_one_12x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_12x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_ru_12x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_one_12x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_ru_one_12x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrsm_nn_ll_inv_12x4_lib4ccc4(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int sde, double *inv_diag_E); -void kernel_dtrsm_nn_ll_inv_12x4_vs_lib4ccc4(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int sde, double *inv_diag_E, int km, int kn); -void kernel_dtrsm_nn_ll_one_12x4_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde); -void kernel_dtrsm_nn_ll_one_12x4_vs_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, int m1, int n1); -void kernel_dtrsm_nn_rl_inv_12x4_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE); -void kernel_dtrsm_nn_rl_inv_12x4_vs_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nn_rl_one_12x4_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde); -void kernel_dtrsm_nn_rl_one_12x4_vs_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, int m1, int n1); -void kernel_dtrsm_nt_rl_inv_12x4_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE); -void kernel_dtrsm_nt_rl_inv_12x4_vs_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nt_rl_one_12x4_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde); -void kernel_dtrsm_nt_rl_one_12x4_vs_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, int m1, int n1); -void kernel_dtrsm_nn_ru_inv_12x4_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE); -void kernel_dtrsm_nn_ru_inv_12x4_vs_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nn_ru_one_12x4_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde); -void kernel_dtrsm_nn_ru_one_12x4_vs_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, int m1, int n1); -void kernel_dtrsm_nt_ru_inv_12x4_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE); -void kernel_dtrsm_nt_ru_inv_12x4_vs_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nt_ru_one_12x4_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde); -void kernel_dtrsm_nt_ru_one_12x4_vs_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, int m1, int n1); -void kernel_dgetrf_nn_l_12x4_lib4ccc(int kmax, double *A, int sda, double *B, int ldb, double *C, int ldc, double *D, int ldd, double *diag); -void kernel_dgetrf_nn_l_12x4_vs_lib4ccc(int kmax, double *A, int sda, double *B, int ldb, double *C, int ldc, double *D, int ldd, double *diag, int m1, int n1); -void kernel_dgetrf_nn_m_12x4_lib4ccc(int kmax, double *A, int sda, double *B, int ldb, double *C, int ldc, double *D, int ldd, double *diag); -void kernel_dgetrf_nn_m_12x4_vs_lib4ccc(int kmax, double *A, int sda, double *B, int ldb, double *C, int ldc, double *D, int ldd, double *diag, int m1, int n1); -void kernel_dgetrf_nn_r_12x4_lib4ccc(int kmax, double *A, int sda, double *B, int ldb, double *C, int ldc, double *D, int ldd, double *diag); -void kernel_dgetrf_nn_r_12x4_vs_lib4ccc(int kmax, double *A, int sda, double *B, int ldb, double *C, int ldc, double *D, int ldd, double *diag, int m1, int n1); -// 4x12 -void kernel_dgemm_nn_4x12_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nn_4x12_vs_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_nt_4x12_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_4x12_vs_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_rl_4x12_tran_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nn_rl_4x12_tran_vs_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_rl_one_4x12_tran_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nn_rl_one_4x12_tran_vs_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_ru_4x12_tran_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nn_ru_4x12_tran_vs_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_ru_one_4x12_tran_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nn_ru_one_4x12_tran_vs_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_4x12_tran_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nt_rl_4x12_tran_vs_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_one_4x12_tran_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nt_rl_one_4x12_tran_vs_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_4x12_tran_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nt_ru_4x12_tran_vs_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_one_4x12_tran_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nt_ru_one_4x12_tran_vs_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -// 8x4 -void kernel_dgemm_nn_8x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nn_8x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_nt_8x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_8x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dsyrk_nt_l_8x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dsyrk_nt_l_8x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dger2k_nt_8x4_lib4ccc(int kmax, double *alpha, double *A0, int sda0, double *B0, int ldb0, double *A1, int sda1, double *B1, int ldb1, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dger2k_nt_8x4_vs_lib4ccc(int kmax, double *alpha, double *A0, int sda0, double *B0, int ldb0, double *A1, int sda1, double *B1, int ldb1, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_rl_8x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nn_rl_8x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_rl_one_8x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nn_rl_one_8x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_ru_8x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nn_ru_8x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_ru_one_8x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nn_ru_one_8x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_8x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_rl_8x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_one_8x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_rl_one_8x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_8x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_ru_8x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_one_8x4_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_ru_one_8x4_vs_lib4ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrsm_nn_ll_inv_8x4_lib4ccc4(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int sde, double *inv_diag_E); -void kernel_dtrsm_nn_ll_inv_8x4_vs_lib4ccc4(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int sde, double *inv_diag_E, int km, int kn); -void kernel_dtrsm_nn_ll_one_8x4_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde); -void kernel_dtrsm_nn_ll_one_8x4_vs_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, int m1, int n1); -void kernel_dtrsm_nn_rl_inv_8x4_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE); -void kernel_dtrsm_nn_rl_inv_8x4_vs_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nn_rl_one_8x4_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde); -void kernel_dtrsm_nn_rl_one_8x4_vs_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, int m1, int n1); -void kernel_dtrsm_nt_rl_inv_8x4_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE); -void kernel_dtrsm_nt_rl_inv_8x4_vs_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nt_rl_one_8x4_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde); -void kernel_dtrsm_nt_rl_one_8x4_vs_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, int m1, int n1); -void kernel_dtrsm_nn_ru_inv_8x4_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE); -void kernel_dtrsm_nn_ru_inv_8x4_vs_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nn_ru_one_8x4_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde); -void kernel_dtrsm_nn_ru_one_8x4_vs_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, int m1, int n1); -void kernel_dtrsm_nt_ru_inv_8x4_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE); -void kernel_dtrsm_nt_ru_inv_8x4_vs_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nt_ru_one_8x4_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde); -void kernel_dtrsm_nt_ru_one_8x4_vs_lib4cccc(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, int m1, int n1); -void kernel_dgetrf_nn_l_8x4_lib4ccc(int kmax, double *A, int sda, double *B, int ldb, double *C, int ldc, double *D, int ldd, double *diag); -void kernel_dgetrf_nn_l_8x4_vs_lib4ccc(int kmax, double *A, int sda, double *B, int ldb, double *C, int ldc, double *D, int ldd, double *diag, int m1, int n1); -void kernel_dgetrf_nn_r_8x4_lib4ccc(int kmax, double *A, int sda, double *B, int ldb, double *C, int ldc, double *D, int ldd, double *diag); -void kernel_dgetrf_nn_r_8x4_vs_lib4ccc(int kmax, double *A, int sda, double *B, int ldb, double *C, int ldc, double *D, int ldd, double *diag, int m1, int n1); -// 4x8 -void kernel_dgemm_nn_4x8_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nn_4x8_vs_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_nt_4x8_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_4x8_vs_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_rl_4x8_tran_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nn_rl_4x8_tran_vs_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_rl_one_4x8_tran_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nn_rl_one_4x8_tran_vs_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_ru_4x8_tran_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nn_ru_4x8_tran_vs_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_ru_one_4x8_tran_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nn_ru_one_4x8_tran_vs_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_4x8_tran_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nt_rl_4x8_tran_vs_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_one_4x8_tran_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nt_rl_one_4x8_tran_vs_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_4x8_tran_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nt_ru_4x8_tran_vs_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_one_4x8_tran_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd); -void kernel_dtrmm_nt_ru_one_4x8_tran_vs_lib4c4c(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int ldd, int m1, int n1); -// 4x4 -void kernel_dgemm_nn_4x4_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nn_4x4_vs_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_nt_4x4_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_4x4_vs_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dsyrk_nt_l_4x4_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dsyrk_nt_l_4x4_vs_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dger2k_nt_4x4_lib4ccc(int kmax, double *alpha, double *A0, double *B0, int ldb0, double *A1, double *B1, int ldb1, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dger2k_nt_4x4_vs_lib4ccc(int kmax, double *alpha, double *A0, double *B0, int ldb0, double *A1, double *B1, int ldb1, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_rl_4x4_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nn_rl_4x4_vs_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_rl_4x4_tran_lib4c4c(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, double *D, int ldd); -void kernel_dtrmm_nn_rl_4x4_tran_vs_lib4c4c(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_rl_one_4x4_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nn_rl_one_4x4_vs_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_rl_one_4x4_tran_lib4c4c(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, double *D, int ldd); -void kernel_dtrmm_nn_rl_one_4x4_tran_vs_lib4c4c(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_ru_4x4_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nn_ru_4x4_vs_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_ru_4x4_tran_lib4c4c(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, double *D, int ldd); -void kernel_dtrmm_nn_ru_4x4_tran_vs_lib4c4c(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_ru_one_4x4_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nn_ru_one_4x4_vs_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nn_ru_one_4x4_tran_lib4c4c(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, double *D, int ldd); -void kernel_dtrmm_nn_ru_one_4x4_tran_vs_lib4c4c(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_4x4_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_rl_4x4_vs_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_4x4_tran_lib4c4c(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, double *D, int ldd); -void kernel_dtrmm_nt_rl_4x4_tran_vs_lib4c4c(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_one_4x4_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_rl_one_4x4_vs_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_rl_one_4x4_tran_lib4c4c(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, double *D, int ldd); -void kernel_dtrmm_nt_rl_one_4x4_tran_vs_lib4c4c(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_4x4_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_ru_4x4_vs_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_4x4_tran_lib4c4c(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, double *D, int ldd); -void kernel_dtrmm_nt_ru_4x4_tran_vs_lib4c4c(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_one_4x4_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dtrmm_nt_ru_one_4x4_vs_lib4ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dtrmm_nt_ru_one_4x4_tran_lib4c4c(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, double *D, int ldd); -void kernel_dtrmm_nt_ru_one_4x4_tran_vs_lib4c4c(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, double *D, int ldd, int m1, int n1); -void kernel_dtrsm_nn_ll_inv_4x4_lib4ccc4(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *inv_diag_E); -void kernel_dtrsm_nn_ll_inv_4x4_vs_lib4ccc4(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, double *inv_diag_E, int km, int kn); -void kernel_dtrsm_nn_ll_one_4x4_lib4cccc(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde); -void kernel_dtrsm_nn_ll_one_4x4_vs_lib4cccc(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, int m1, int n1); -void kernel_dtrsm_nn_rl_inv_4x4_lib4cccc(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE); -void kernel_dtrsm_nn_rl_inv_4x4_vs_lib4cccc(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nn_rl_one_4x4_lib4cccc(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde); -void kernel_dtrsm_nn_rl_one_4x4_vs_lib4cccc(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, int m1, int n1); -void kernel_dtrsm_nt_rl_inv_4x4_lib4cccc(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE); -void kernel_dtrsm_nt_rl_inv_4x4_vs_lib4cccc(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nt_rl_one_4x4_lib4cccc(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde); -void kernel_dtrsm_nt_rl_one_4x4_vs_lib4cccc(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, int m1, int n1); -void kernel_dtrsm_nn_ru_inv_4x4_lib4cccc(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE); -void kernel_dtrsm_nn_ru_inv_4x4_vs_lib4cccc(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nn_ru_one_4x4_lib4cccc(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde); -void kernel_dtrsm_nn_ru_one_4x4_vs_lib4cccc(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, int m1, int n1); -void kernel_dtrsm_nt_ru_inv_4x4_lib4cccc(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE); -void kernel_dtrsm_nt_ru_inv_4x4_vs_lib4cccc(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nt_ru_one_4x4_lib4cccc(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde); -void kernel_dtrsm_nt_ru_one_4x4_vs_lib4cccc(int kmax, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, double *E, int lde, int m1, int n1); -void kernel_dgetrf_nn_4x4_lib4ccc(int kmax, double *A, double *B, int ldb, double *C, int ldc, double *D, int ldd, double *diag); -void kernel_dgetrf_nn_4x4_vs_lib4ccc(int kmax, double *A, double *B, int ldb, double *C, int ldc, double *D, int ldd, double *diag, int m1, int n1); - -// B panel-major bs=4; A, C, D column-major -// 12x4 -void kernel_dgemm_nt_12x4_libc4cc(int kmax, double *alpha, double *A, int lda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_12x4_vs_libc4cc(int kmax, double *alpha, double *A, int lda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_tt_12x4_libc4cc(int kmax, double *alpha, double *A, int lda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_tt_12x4_vs_libc4cc(int kmax, double *alpha, double *A, int lda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -// 4x12 -void kernel_dgemm_nt_4x12_libc4cc(int kmax, double *alpha, double *A, int lda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_4x12_vs_libc4cc(int kmax, double *alpha, double *A, int lda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_tt_4x12_libc4cc(int kmax, double *alpha, double *A, int lda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_tt_4x12_vs_libc4cc(int kmax, double *alpha, double *A, int lda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -// 8x4 -void kernel_dgemm_nt_8x4_libc4cc(int kmax, double *alpha, double *A, int lda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_8x4_vs_libc4cc(int kmax, double *alpha, double *A, int lda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_tt_8x4_libc4cc(int kmax, double *alpha, double *A, int lda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_tt_8x4_vs_libc4cc(int kmax, double *alpha, double *A, int lda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -// 4x8 -void kernel_dgemm_nt_4x8_libc4cc(int kmax, double *alpha, double *A, int lda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_4x8_vs_libc4cc(int kmax, double *alpha, double *A, int lda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_tt_4x8_libc4cc(int kmax, double *alpha, double *A, int lda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_tt_4x8_vs_libc4cc(int kmax, double *alpha, double *A, int lda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -// 4x4 -void kernel_dgemm_nt_4x4_libc4cc(int kmax, double *alpha, double *A, int lda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_4x4_vs_libc4cc(int kmax, double *alpha, double *A, int lda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_tt_4x4_libc4cc(int kmax, double *alpha, double *A, int lda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_tt_4x4_vs_libc4cc(int kmax, double *alpha, double *A, int lda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); - -// A, C, D panel-major; B, E column-major -// TODO merge with above -// 12x4 -void kernel_dtrsm_nn_rl_inv_12x4_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, double *dE); -void kernel_dtrsm_nn_rl_inv_12x4_vs_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nn_rl_one_12x4_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde); -void kernel_dtrsm_nn_rl_one_12x4_vs_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, int m1, int n1); -void kernel_dtrsm_nn_ru_inv_12x4_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, double *dE); -void kernel_dtrsm_nn_ru_inv_12x4_vs_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nn_ru_one_12x4_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde); -void kernel_dtrsm_nn_ru_one_12x4_vs_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, int m1, int n1); -void kernel_dtrsm_nt_rl_inv_12x4_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, double *dE); -void kernel_dtrsm_nt_rl_inv_12x4_vs_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nt_rl_one_12x4_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde); -void kernel_dtrsm_nt_rl_one_12x4_vs_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, int m1, int n1); -void kernel_dtrsm_nt_ru_inv_12x4_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, double *dE); -void kernel_dtrsm_nt_ru_inv_12x4_vs_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nt_ru_one_12x4_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde); -void kernel_dtrsm_nt_ru_one_12x4_vs_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, int m1, int n1); -// 8x4 -void kernel_dtrsm_nn_rl_inv_8x4_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, double *dE); -void kernel_dtrsm_nn_rl_inv_8x4_vs_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nn_rl_one_8x4_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde); -void kernel_dtrsm_nn_rl_one_8x4_vs_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, int m1, int n1); -void kernel_dtrsm_nn_ru_inv_8x4_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, double *dE); -void kernel_dtrsm_nn_ru_inv_8x4_vs_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nn_ru_one_8x4_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde); -void kernel_dtrsm_nn_ru_one_8x4_vs_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, int m1, int n1); -void kernel_dtrsm_nt_rl_inv_8x4_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, double *dE); -void kernel_dtrsm_nt_rl_inv_8x4_vs_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nt_rl_one_8x4_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde); -void kernel_dtrsm_nt_rl_one_8x4_vs_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, int m1, int n1); -void kernel_dtrsm_nt_ru_inv_8x4_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, double *dE); -void kernel_dtrsm_nt_ru_inv_8x4_vs_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nt_ru_one_8x4_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde); -void kernel_dtrsm_nt_ru_one_8x4_vs_lib4c44c(int kmax, double *A, int sda, double *B, int ldb, double *beta, double *C, int sdc, double *D, int sdd, double *E, int lde, int m1, int n1); -// 4x4 -void kernel_dtrsm_nn_rl_inv_4x4_lib4c44c(int kmax, double *A, double *B, int ldb, double *beta, double *C, double *D, double *E, int lde, double *dE); -void kernel_dtrsm_nn_rl_inv_4x4_vs_lib4c44c(int kmax, double *A, double *B, int ldb, double *beta, double *C, double *D, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nn_rl_one_4x4_lib4c44c(int kmax, double *A, double *B, int ldb, double *beta, double *C, double *D, double *E, int lde); -void kernel_dtrsm_nn_rl_one_4x4_vs_lib4c44c(int kmax, double *A, double *B, int ldb, double *beta, double *C, double *D, double *E, int lde, int m1, int n1); -void kernel_dtrsm_nn_ru_inv_4x4_lib4c44c(int kmax, double *A, double *B, int ldb, double *beta, double *C, double *D, double *E, int lde, double *dE); -void kernel_dtrsm_nn_ru_inv_4x4_vs_lib4c44c(int kmax, double *A, double *B, int ldb, double *beta, double *C, double *D, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nn_ru_one_4x4_lib4c44c(int kmax, double *A, double *B, int ldb, double *beta, double *C, double *D, double *E, int lde); -void kernel_dtrsm_nn_ru_one_4x4_vs_lib4c44c(int kmax, double *A, double *B, int ldb, double *beta, double *C, double *D, double *E, int lde, int m1, int n1); -void kernel_dtrsm_nt_rl_inv_4x4_lib4c44c(int kmax, double *A, double *B, int ldb, double *beta, double *C, double *D, double *E, int lde, double *dE); -void kernel_dtrsm_nt_rl_inv_4x4_vs_lib4c44c(int kmax, double *A, double *B, int ldb, double *beta, double *C, double *D, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nt_rl_one_4x4_lib4c44c(int kmax, double *A, double *B, int ldb, double *beta, double *C, double *D, double *E, int lde); -void kernel_dtrsm_nt_rl_one_4x4_vs_lib4c44c(int kmax, double *A, double *B, int ldb, double *beta, double *C, double *D, double *E, int lde, int m1, int n1); -void kernel_dtrsm_nt_ru_inv_4x4_lib4c44c(int kmax, double *A, double *B, int ldb, double *beta, double *C, double *D, double *E, int lde, double *dE); -void kernel_dtrsm_nt_ru_inv_4x4_vs_lib4c44c(int kmax, double *A, double *B, int ldb, double *beta, double *C, double *D, double *E, int lde, double *dE, int m1, int n1); -void kernel_dtrsm_nt_ru_one_4x4_lib4c44c(int kmax, double *A, double *B, int ldb, double *beta, double *C, double *D, double *E, int lde); -void kernel_dtrsm_nt_ru_one_4x4_vs_lib4c44c(int kmax, double *A, double *B, int ldb, double *beta, double *C, double *D, double *E, int lde, int m1, int n1); - -// A, B, C, D column-major -// 12x4 -void kernel_dgemm_nn_12x4_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nn_12x4_vs_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_nt_12x4_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_12x4_vs_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_tt_12x4_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_tt_12x4_vs_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -// 4x12 -void kernel_dgemm_nn_4x12_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nn_4x12_vs_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_nt_4x12_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_4x12_vs_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_tt_4x12_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_tt_4x12_vs_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -// 8x4 -void kernel_dgemm_nn_8x4_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nn_8x4_vs_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_nt_8x4_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_8x4_vs_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_tt_8x4_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_tt_8x4_vs_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -// 4x8 -void kernel_dgemm_nn_4x8_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nn_4x8_vs_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_nt_4x8_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_4x8_vs_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_tt_4x8_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_tt_4x8_vs_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -// 4x4 -void kernel_dgemm_nn_4x4_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nn_4x4_vs_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_nt_4x4_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_4x4_vs_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_tt_4x4_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_tt_4x4_vs_libcccc(int kmax, double *alpha, double *A, int lda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); - -// A column-major -// 12 -void kernel_dgetrf_pivot_12_lib(int m, double *pA, int lda, double *inv_diag_A, int* ipiv); -void kernel_dgetrf_pivot_12_vs_lib(int m, double *pA, int lda, double *inv_diag_A, int* ipiv, int n); -// 8 -void kernel_dgetrf_pivot_8_lib(int m, double *pA, int lda, double *inv_diag_A, int* ipiv); -void kernel_dgetrf_pivot_8_vs_lib(int m, double *pA, int lda, double *inv_diag_A, int* ipiv, int n); -// 4 -void kernel_dgetrf_pivot_4_lib(int m, double *pA, int lda, double *inv_diag_A, int* ipiv); -void kernel_dgetrf_pivot_4_vs_lib(int m, double *pA, int lda, double *inv_diag_A, int* ipiv, int n); - -// vector -void kernel_ddot_11_lib(int n, double *x, double *y, double *res); -void kernel_daxpy_11_lib(int n, double *alpha, double *x, double *y); -void kernel_drowsw_lib(int kmax, double *pA, int lda, double *pC, int ldc); - -//#endif // BLAS_API - - - -// larger kernels -// 12 -void kernel_dgemm_nt_12xn_p0_lib44cc(int n, int k, double *alpha, double *A, int sda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, double *A_p, double *B_p); -void kernel_dgemm_nt_12xn_pl_lib44cc(int n, int k, double *alpha, double *A, int sda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, double *A_p, double *B_p); -void kernel_dgemm_nt_mx12_p0_lib44cc(int m, int k, double *alpha, double *A, int sda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, double *A_p, double *B_p); -// 8 -void kernel_dgemm_nt_8xn_p0_lib44cc(int n, int k, double *alpha, double *A, int sda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, double *A_p, double *B_p); - - - -// A, B panel-major bs=8; C, D column-major -// 24x8 -void kernel_dgemm_nt_24x8_lib88cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_24x8_vs_lib88cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -// 16x8 -void kernel_dgemm_nt_16x8_lib88cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_16x8_vs_lib88cc(int kmax, double *alpha, double *A, int sda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -// 8x8 -void kernel_dgemm_nt_8x8_lib88cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_8x8_vs_lib88cc(int kmax, double *alpha, double *A, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); - -// A, panel-major bs=8; B, C, D column-major -// 24x8 -void kernel_dgemm_nt_24x8_lib8ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_24x8_vs_lib8ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_nn_24x8_lib8ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nn_24x8_vs_lib8ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -// 16x8 -void kernel_dgemm_nt_16x8_lib8ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_16x8_vs_lib8ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_nn_16x8_lib8ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nn_16x8_vs_lib8ccc(int kmax, double *alpha, double *A, int sda, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -// 8x8 -void kernel_dgemm_nt_8x8_lib8ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_8x8_vs_lib8ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_nn_8x8_lib8ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nn_8x8_vs_lib8ccc(int kmax, double *alpha, double *A, double *B, int ldb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); - -// B, panel-major bs=8; A, C, D column-major -// 8x24 -void kernel_dgemm_nt_8x24_libc8cc(int kmax, double *alpha, double *A, int lda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_8x24_vs_libc8cc(int kmax, double *alpha, double *A, int lda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_tt_8x24_libc8cc(int kmax, double *alpha, double *A, int lda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_tt_8x24_vs_libc8cc(int kmax, double *alpha, double *A, int lda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -// 8x16 -void kernel_dgemm_nt_8x16_libc8cc(int kmax, double *alpha, double *A, int lda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_8x16_vs_libc8cc(int kmax, double *alpha, double *A, int lda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_tt_8x16_libc8cc(int kmax, double *alpha, double *A, int lda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_tt_8x16_vs_libc8cc(int kmax, double *alpha, double *A, int lda, double *B, int sdb, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -// 8x8 -void kernel_dgemm_nt_8x8_libc8cc(int kmax, double *alpha, double *A, int lda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_nt_8x8_vs_libc8cc(int kmax, double *alpha, double *A, int lda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); -void kernel_dgemm_tt_8x8_libc8cc(int kmax, double *alpha, double *A, int lda, double *B, double *beta, double *C, int ldc, double *D, int ldd); -void kernel_dgemm_tt_8x8_vs_libc8cc(int kmax, double *alpha, double *A, int lda, double *B, double *beta, double *C, int ldc, double *D, int ldd, int m1, int n1); - - -// level 2 BLAS -void kernel_dgemv_n_4_libc(int kmax, double *alpha, double *A, int lda, double *x, double *z); -void kernel_dgemv_n_4_vs_libc(int kmax, double *alpha, double *A, int lda, double *x, double *z, int km); -void kernel_dgemv_t_4_libc(int kmax, double *alpha, double *A, int lda, double *x, double *beta, double *y, double *z); -void kernel_dgemv_t_4_vs_libc(int kmax, double *alpha, double *A, int lda, double *x, double *beta, double *y, double *z, int km); -void kernel_dsymv_l_4_libc(int kmax, double *alpha, double *A, int lda, double *x, double *z); -void kernel_dsymv_l_4_vs_libc(int kmax, double *alpha, double *A, int lda, double *x, double *z, int km); -void kernel_dsymv_u_4_libc(int kmax, double *alpha, double *A, int lda, double *x, double *z); -void kernel_dsymv_u_4_vs_libc(int kmax, double *alpha, double *A, int lda, double *x, double *z, int km); -void kernel_dger_4_libc(int kmax, double *alpha, double *x, double *y, double *C, int ldc, double *D, int ldd); -void kernel_dger_4_vs_libc(int kmax, double *alpha, double *x, double *y, double *C, int ldc, double *D, int ldd, int km); - - - -// aux -void kernel_dvecld_inc1(int kmax, double *x); -void kernel_dveccp_inc1(int kmax, double *x, double *y); - -//void kernel_dgetr_nt_8_p0_lib(int kmax, double *A, int lda, double *C, int ldc, double *Ap, double *Bp); -//void kernel_dgetr_nt_8_lib(int kmax, double *A, int lda, double *C, int ldc); -//void kernel_dgetr_nt_4_lib(int kmax, double *A, int lda, double *C, int ldc); -void kernel_dgetr_tn_8_p0_lib(int kmax, double *A, int lda, double *C, int ldc, double *Ap, double *Bp); -void kernel_dgetr_tn_8_lib(int kmax, double *A, int lda, double *C, int ldc); -void kernel_dgetr_tn_4_lib(int kmax, double *A, int lda, double *C, int ldc); -void kernel_dgetr_tn_4_vs_lib(int kmax, double *A, int lda, double *C, int ldc, int m1); - - -// building blocks for blocked algorithms -// -void blasfeo_hp_dgemm_nt_m2(int m, int n, int k, double alpha, double *pA, int sda, double *pB, int sdb, double beta, double *C, int ldc, double *D, int ldd); -void blasfeo_hp_dgemm_nt_n2(int m, int n, int k, double alpha, double *pA, int sda, double *pB, int sdb, double beta, double *C, int ldc, double *D, int ldd); -// -void kernel_dpack_buffer_fn(int m, int n, double *A, int lda, double *pA, int sda); -void kernel_dpack_buffer_ft(int m, int n, double *A, int lda, double *pA, int sda); -void kernel_dpack_buffer_ln(int m, double *A, int lda, double *pA, int sda); -void kernel_dpack_buffer_lt(int m, double *A, int lda, double *pA, int sda); -void kernel_dpack_buffer_ut(int m, double *A, int lda, double *pA, int sda); - - - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_D_KERNEL_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_i_aux_ext_dep.h b/third_party/acados/include/blasfeo/include/blasfeo_i_aux_ext_dep.h deleted file mode 100644 index 74c3fb5..0000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_i_aux_ext_dep.h +++ /dev/null @@ -1,69 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_I_AUX_EXT_DEP_H_ -#define BLASFEO_I_AUX_EXT_DEP_H_ - - - -#include "blasfeo_target.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -#ifdef EXT_DEP - -// i_aux_extern_depend_lib -void int_zeros(int **pA, int row, int col); -void int_zeros_align(int **pA, int row, int col); -void int_free(int *pA); -void int_free_align(int *pA); -void int_print_mat(int row, int col, int *A, int lda); -int int_print_to_string_mat(char **buf_out, int row, int col, int *A, int lda); - -#endif // EXT_DEP - - - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_I_AUX_EXT_DEP_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_m_aux.h b/third_party/acados/include/blasfeo/include/blasfeo_m_aux.h deleted file mode 100644 index 6248853..0000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_m_aux.h +++ /dev/null @@ -1,57 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_M_AUX_H_ -#define BLASFEO_M_AUX_H_ - -#include "blasfeo_common.h" - -#ifdef __cplusplus -extern "C" { -#endif - - - -void blasfeo_cvt_d2s_vec(int m, struct blasfeo_dvec *vd, int vdi, struct blasfeo_svec *vs, int vsi); -void blasfeo_cvt_s2d_vec(int m, struct blasfeo_svec *vs, int vsi, struct blasfeo_dvec *vd, int vdi); -void blasfeo_cvt_d2s_mat(int m, int n, struct blasfeo_dmat *Md, int mid, int nid, struct blasfeo_smat *Ms, int mis, int nis); -void blasfeo_cvt_s2d_mat(int m, int n, struct blasfeo_smat *Ms, int mis, int nis, struct blasfeo_dmat *Md, int mid, int nid); - - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_M_AUX_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_memory.h b/third_party/acados/include/blasfeo/include/blasfeo_memory.h deleted file mode 100644 index da4e7fa..0000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_memory.h +++ /dev/null @@ -1,62 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2020 by Gianluca Frison. * -* All rights reserved. * -* * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - -#ifndef BLASFEO_MEMORY_H_ -#define BLASFEO_MEMORY_H_ - -#ifdef __cplusplus -extern "C" { -#endif - - - -// -int blasfeo_is_init(); -// -void blasfeo_init(); -// -void blasfeo_quit(); -// -void *blasfeo_get_buffer(); - - - - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_MEMORY_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_naming.h b/third_party/acados/include/blasfeo/include/blasfeo_naming.h deleted file mode 100644 index c289443..0000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_naming.h +++ /dev/null @@ -1,77 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - -/* - * ----------- Naming conventions - * - * (precision)(data) - * - * 1) d(double) - * s(single) - * - * 2) ge(general) - * tr(triangular) - * vec(vector) - * row(row) - * col(column) - * dia(diagonal) - * - * 3) se(set) - * cp(copy) - * sc(scale) - * ad(add) - * tr(transpose) - * in(insert) - * ex(extract) - * pe(premute) - * sw(swap) - * - * f(factorization) - * - * lqf(LQ factorization) - * qrf (factorization) - * trf (LU factorization using partial pivoting with row interchanges.) - * - * 4) _l(lower) / _u(upper) - * _lib8 (hp implementation, 8 rows kernel) - * _lib4 (hp implementation, 4 rows kernel) - * _lib0 (hp interface with reference implentation) - * _lib (reference implementation) - * _libref (reference implementation with dedicated namespace) - * - * 5) _sp(sparse) - * _exp(exponential format) - */ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_processor_features.h b/third_party/acados/include/blasfeo/include/blasfeo_processor_features.h deleted file mode 100644 index 67a0a4d..0000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_processor_features.h +++ /dev/null @@ -1,88 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Ian McInerney * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_PROCESSOR_FEATURES_H_ -#define BLASFEO_PROCESSOR_FEATURES_H_ - -/** - * Flags to indicate the different processor features - */ -//enum -//{ -// // x86-64 CPU features -// BLASFEO_PROCESSOR_FEATURE_AVX = 0x0001, /// AVX instruction set -// BLASFEO_PROCESSOR_FEATURE_AVX2 = 0x0002, /// AVX2 instruction set -// BLASFEO_PROCESSOR_FEATURE_FMA = 0x0004, /// FMA instruction set -// BLASFEO_PROCESSOR_FEATURE_SSE3 = 0x0008, /// SSE3 instruction set -// -// // ARM CPU features -// BLASFEO_PROCESSOR_FEATURE_VFPv3 = 0x0100, /// VFPv3 instruction set -// BLASFEO_PROCESSOR_FEATURE_NEON = 0x0100, /// NEON instruction set -// BLASFEO_PROCESSOR_FEATURE_VFPv4 = 0x0100, /// VFPv4 instruction set -// BLASFEO_PROCESSOR_FEATURE_NEONv2 = 0x0100, /// NEONv2 instruction set -//} BLASFEO_PROCESSOR_FEATURES; - -/** - * Test the features that this processor provides against what the library was compiled with. - * - * @param features - Pointer to an integer to store the supported feature set (using the flags in the BLASFEO_PROCESSOR_FEATURES enum) - * @return 0 if current processor doesn't support all features required for this library, 1 otherwise - */ -int blasfeo_processor_cpu_features( int* features ); - -/** - * Test the features that this processor provides against what the library was compiled with. - * - * @param features - Pointer to an integer to store the supported feature set (using the flags in the BLASFEO_PROCESSOR_FEATURES enum) - * @return 0 if current processor doesn't support all features required for this library, 1 otherwise - */ -void blasfeo_processor_library_features( int* features ); - -/** - * Create a string listing the features the current processor supports. - * - * @param features - Flags from the BLASFEO_PROCESSOR_FEATURES enum indicating the features supported - * @param featureString - Character array to store the feature string in - */ -void blasfeo_processor_feature_string( int features, char* featureString ); - -/** - * Get a string listing the processor features that this library version needs to run. - * - * @param featureString - Character array to store the feature string in - */ -void blasfeo_processor_library_string( char* featureString ); - -#endif // BLASFEO_PROCESSOR_FEATURES_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_s_aux.h b/third_party/acados/include/blasfeo/include/blasfeo_s_aux.h deleted file mode 100644 index f43f5e8..0000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_s_aux.h +++ /dev/null @@ -1,168 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_S_AUX_H_ -#define BLASFEO_S_AUX_H_ - - - -#include - -#include "blasfeo_s_aux_old.h" -#include "blasfeo_common.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - -/************************************************ -* d_aux_lib.c -************************************************/ - -// returns the memory size (in bytes) needed for a smat -size_t blasfeo_memsize_smat(int m, int n); -size_t blasfeo_memsize_smat_ps(int ps, int m, int n); -// returns the memory size (in bytes) needed for the diagonal of a smat -size_t blasfeo_memsize_diag_smat(int m, int n); -// returns the memory size (in bytes) needed for a svec -size_t blasfeo_memsize_svec(int m); -// create a strmat for a matrix of size m*n by using memory passed by a pointer (pointer is not updated) -void blasfeo_create_smat(int m, int n, struct blasfeo_smat *sA, void *memory); -void blasfeo_create_smat_ps(int ps, int m, int n, struct blasfeo_smat *sA, void *memory); -// create a strvec for a vector of size m by using memory passed by a pointer (pointer is not updated) -void blasfeo_create_svec(int m, struct blasfeo_svec *sA, void *memory); -void blasfeo_pack_smat(int m, int n, float *A, int lda, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_pack_l_smat(int m, int n, float *A, int lda, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_pack_u_smat(int m, int n, float *A, int lda, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_pack_tran_smat(int m, int n, float *A, int lda, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_pack_svec(int m, float *x, int xi, struct blasfeo_svec *sa, int ai); -void blasfeo_unpack_smat(int m, int n, struct blasfeo_smat *sA, int ai, int aj, float *A, int lda); -void blasfeo_unpack_tran_smat(int m, int n, struct blasfeo_smat *sA, int ai, int aj, float *A, int lda); -void blasfeo_unpack_svec(int m, struct blasfeo_svec *sa, int ai, float *x, int xi); -//void s_cast_mat2strmat(float *A, struct blasfeo_smat *sA); -//void s_cast_diag_mat2strmat(float *dA, struct blasfeo_smat *sA); -//void s_cast_vec2vecmat(float *a, struct blasfeo_svec *sa); - -// ge -void blasfeo_sgese(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_sgecpsc(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -void blasfeo_sgecp(int m, int n, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -void blasfeo_sgesc(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_sgein1(float a, struct blasfeo_smat *sA, int ai, int aj); -float blasfeo_sgeex1(struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_sgead(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -void blasfeo_sgetr(int m, int n, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -// tr -void blasfeo_strcp_l(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -void blasfeo_strtr_l(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -void blasfeo_strtr_u(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -// dia -void blasfeo_sdiare(int kmax, float alpha, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_sdiaex(int kmax, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi); -void blasfeo_sdiain(int kmax, float alpha, struct blasfeo_svec *sx, int xi, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_sdiain_sp(int kmax, float alpha, struct blasfeo_svec *sx, int xi, int *idx, struct blasfeo_smat *sD, int di, int dj); -void blasfeo_sdiaex_sp(int kmax, float alpha, int *idx, struct blasfeo_smat *sD, int di, int dj, struct blasfeo_svec *sx, int xi); -void blasfeo_sdiaad(int kmax, float alpha, struct blasfeo_svec *sx, int xi, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_sdiaad_sp(int kmax, float alpha, struct blasfeo_svec *sx, int xi, int *idx, struct blasfeo_smat *sD, int di, int dj); -void blasfeo_sdiaadin_sp(int kmax, float alpha, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sy, int yi, int *idx, struct blasfeo_smat *sD, int di, int dj); -// row -void blasfeo_srowin(int kmax, float alpha, struct blasfeo_svec *sx, int xi, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_srowex(int kmax, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi); -void blasfeo_srowad(int kmax, float alpha, struct blasfeo_svec *sx, int xi, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_srowad_sp(int kmax, float alpha, struct blasfeo_svec *sx, int xi, int *idx, struct blasfeo_smat *sD, int di, int dj); -void blasfeo_srowsw(int kmax, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -void blasfeo_srowpe(int kmax, int *ipiv, struct blasfeo_smat *sA); -void blasfeo_srowpei(int kmax, int *ipiv, struct blasfeo_smat *sA); -// col -void blasfeo_scolex(int kmax, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi); -void blasfeo_scolin(int kmax, struct blasfeo_svec *sx, int xi, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_scolad(int kmax, float alpha, struct blasfeo_svec *sx, int xi, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_scolsc(int kmax, float alpha, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_scolsw(int kmax, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -void blasfeo_scolpe(int kmax, int *ipiv, struct blasfeo_smat *sA); -void blasfeo_scolpei(int kmax, int *ipiv, struct blasfeo_smat *sA); -// vec -void blasfeo_svecse(int m, float alpha, struct blasfeo_svec *sx, int xi); -void blasfeo_sveccp(int m, struct blasfeo_svec *sa, int ai, struct blasfeo_svec *sc, int ci); -void blasfeo_svecsc(int m, float alpha, struct blasfeo_svec *sa, int ai); -void blasfeo_sveccpsc(int m, float alpha, struct blasfeo_svec *sa, int ai, struct blasfeo_svec *sc, int ci); -void blasfeo_svecad(int m, float alpha, struct blasfeo_svec *sa, int ai, struct blasfeo_svec *sc, int ci); -void blasfeo_svecin1(float a, struct blasfeo_svec *sx, int xi); -float blasfeo_svecex1(struct blasfeo_svec *sx, int xi); -void blasfeo_svecad_sp(int m, float alpha, struct blasfeo_svec *sx, int xi, int *idx, struct blasfeo_svec *sz, int zi); -void blasfeo_svecin_sp(int m, float alpha, struct blasfeo_svec *sx, int xi, int *idx, struct blasfeo_svec *sz, int zi); -void blasfeo_svecex_sp(int m, float alpha, int *idx, struct blasfeo_svec *sx, int x, struct blasfeo_svec *sz, int zi); -// z += alpha * x[idx] -void blasfeo_svecexad_sp(int m, double alpha, int *idx, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -void blasfeo_sveccl(int m, struct blasfeo_svec *sxm, int xim, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sxp, int xip, struct blasfeo_svec *sz, int zi); -void blasfeo_sveccl_mask(int m, struct blasfeo_svec *sxm, int xim, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sxp, int xip, struct blasfeo_svec *sz, int zi, struct blasfeo_svec *sm, int mi); -void blasfeo_svecze(int m, struct blasfeo_svec *sm, int mi, struct blasfeo_svec *sv, int vi, struct blasfeo_svec *se, int ei); -void blasfeo_svecnrm_inf(int m, struct blasfeo_svec *sx, int xi, float *ptr_norm); -void blasfeo_svecnrm_2(int m, struct blasfeo_svec *sx, int xi, float *ptr_norm); -void blasfeo_svecpe(int kmax, int *ipiv, struct blasfeo_svec *sx, int xi); -void blasfeo_svecpei(int kmax, int *ipiv, struct blasfeo_svec *sx, int xi); - - - -/* -* Explicitly panel-major matrix format -*/ - -// returns the memory size (in bytes) needed for a dmat -size_t blasfeo_pm_memsize_smat(int ps, int m, int n); -// create a strmat for a matrix of size m*n by using memory passed by a pointer (pointer is not updated) -void blasfeo_pm_create_smat(int ps, int m, int n, struct blasfeo_pm_smat *sA, void *memory); - - - -/* -* Explicitly column-major matrix format -*/ - -// returns the memory size (in bytes) needed for a dmat -size_t blasfeo_cm_memsize_smat(int m, int n); -// create a strmat for a matrix of size m*n by using memory passed by a pointer (pointer is not updated) -void blasfeo_cm_create_smat(int m, int n, struct blasfeo_pm_smat *sA, void *memory); - - - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_S_AUX_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_s_aux_ext_dep.h b/third_party/acados/include/blasfeo/include/blasfeo_s_aux_ext_dep.h deleted file mode 100644 index 5209d20..0000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_s_aux_ext_dep.h +++ /dev/null @@ -1,141 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_S_AUX_EXT_DEP_H_ -#define BLASFEO_S_AUX_EXT_DEP_H_ - - - -#include - - - -#include "blasfeo_common.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -#ifdef EXT_DEP - -/************************************************ -* s_aux_extern_depend_lib.c -************************************************/ - -/* column-major matrices */ - -// dynamically allocate row*col floats of memory and set accordingly a pointer to float; set allocated memory to zero -void s_zeros(float **pA, int row, int col); -// dynamically allocate row*col floats of memory aligned to 64-byte boundaries and set accordingly a pointer to float; set allocated memory to zero -void s_zeros_align(float **pA, int row, int col); -// dynamically allocate size bytes of memory aligned to 64-byte boundaries and set accordingly a pointer to float; set allocated memory to zero -void s_zeros_align_bytes(float **pA, int size); -// free the memory allocated by d_zeros -void s_free(float *pA); -// free the memory allocated by d_zeros_align or d_zeros_align_bytes -void s_free_align(float *pA); -// print a column-major matrix -void s_print_mat(int m, int n, float *A, int lda); -// print the transposed of a column-major matrix -void s_print_tran_mat(int row, int col, float *A, int lda); -// print to file a column-major matrix -void s_print_to_file_mat(FILE *file, int row, int col, float *A, int lda); -// print to file a column-major matrix in exponential format -void s_print_to_file_exp_mat(FILE *file, int row, int col, float *A, int lda); -// print to string a column-major matrix -void s_print_to_string_mat(char **buf_out, int row, int col, float *A, int lda); -// print to file the transposed of a column-major matrix -void s_print_tran_to_file_mat(FILE *file, int row, int col, float *A, int lda); -// print to file the transposed of a column-major matrix in exponential format -void s_print_tran_to_file_exp_mat(FILE *file, int row, int col, float *A, int lda); -// print in exponential notation a column-major matrix -void s_print_exp_mat(int m, int n, float *A, int lda); -// print in exponential notation the transposed of a column-major matrix -void s_print_exp_tran_mat(int row, int col, float *A, int lda); - -/* strmat and strvec */ - -// create a strmat for a matrix of size m*n by dynamically allocating memory -void blasfeo_allocate_smat(int m, int n, struct blasfeo_smat *sA); -// create a strvec for a vector of size m by dynamically allocating memory -void blasfeo_allocate_svec(int m, struct blasfeo_svec *sa); -// free the memory allocated by blasfeo_allocate_dmat -void blasfeo_free_smat(struct blasfeo_smat *sA); -// free the memory allocated by blasfeo_allocate_dvec -void blasfeo_free_svec(struct blasfeo_svec *sa); -// print a strmat -void blasfeo_print_smat(int m, int n, struct blasfeo_smat *sA, int ai, int aj); -// print in exponential notation a strmat -void blasfeo_print_exp_smat(int m, int n, struct blasfeo_smat *sA, int ai, int aj); -// print to file a strmat -void blasfeo_print_to_file_smat(FILE *file, int m, int n, struct blasfeo_smat *sA, int ai, int aj); -// print to file a strmat in exponential format -void blasfeo_print_to_file_exp_smat(FILE *file, int m, int n, struct blasfeo_smat *sA, int ai, int aj); -// print to string a strmat -void blasfeo_print_to_string_smat(char **buf_out, int m, int n, struct blasfeo_smat *sA, int ai, int aj); -// print the transpose of a strmat -void blasfeo_print_tran_smat(int m, int n, struct blasfeo_smat *sA, int ai, int aj); -// print a strvec -void blasfeo_print_svec(int m, struct blasfeo_svec *sa, int ai); -// print in exponential notation a strvec -void blasfeo_print_exp_svec(int m, struct blasfeo_svec *sa, int ai); -// print to file a strvec -void blasfeo_print_to_file_svec(FILE *file, int m, struct blasfeo_svec *sa, int ai); -// print to string a strvec -void blasfeo_print_to_string_svec(char **buf_out, int m, struct blasfeo_svec *sa, int ai); -// print the transposed of a strvec -void blasfeo_print_tran_svec(int m, struct blasfeo_svec *sa, int ai); -// print in exponential notation the transposed of a strvec -void blasfeo_print_exp_tran_svec(int m, struct blasfeo_svec *sa, int ai); -// print to file the transposed of a strvec -void blasfeo_print_to_file_tran_svec(FILE *file, int m, struct blasfeo_svec *sa, int ai); -// print to string the transposed of a strvec -void blasfeo_print_to_string_tran_svec(char **buf_out, int m, struct blasfeo_svec *sa, int ai); - -#endif // EXT_DEP - - - -#ifdef __cplusplus -} -#endif - - - -#endif // BLASFEO_S_AUX_EXT_DEP_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_s_aux_ext_dep_ref.h b/third_party/acados/include/blasfeo/include/blasfeo_s_aux_ext_dep_ref.h deleted file mode 100644 index 6640e20..0000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_s_aux_ext_dep_ref.h +++ /dev/null @@ -1,82 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_S_AUX_EXT_DEP_REF_H_ -#define BLASFEO_S_AUX_EXT_DEP_REF_H_ - -#if defined(EXT_DEP) - - - -#include - -#include "blasfeo_common.h" - -#ifdef __cplusplus -extern "C" { -#endif - -// expose reference BLASFEO for testing -// see blasfeo_s_aux_exp_dep.h for help - -void blasfeo_print_smat_ref(int m, int n, struct blasfeo_smat_ref *sA, int ai, int aj); -void blasfeo_allocate_smat_ref(int m, int n, struct blasfeo_smat_ref *sA); -void blasfeo_allocate_svec_ref(int m, struct blasfeo_svec_ref *sa); -void blasfeo_free_smat_ref(struct blasfeo_smat_ref *sA); -void blasfeo_free_svec_ref(struct blasfeo_svec_ref *sa); -void blasfeo_print_smat_ref(int m, int n, struct blasfeo_smat_ref *sA, int ai, int aj); -void blasfeo_print_exp_smat_ref(int m, int n, struct blasfeo_smat_ref *sA, int ai, int aj); -void blasfeo_print_to_file_smat_ref(FILE *file, int m, int n, struct blasfeo_smat_ref *sA, int ai, int aj); -void blasfeo_print_to_file_exp_smat_ref(FILE *file, int m, int n, struct blasfeo_smat_ref *sA, int ai, int aj); -void blasfeo_print_to_string_smat_ref(char **buf_out, int m, int n, struct blasfeo_smat_ref *sA, int ai, int aj); -void blasfeo_print_svec(int m, struct blasfeo_svec *sa, int ai); -void blasfeo_print_exp_svec(int m, struct blasfeo_svec *sa, int ai); -void blasfeo_print_to_file_svec(FILE *file, int m, struct blasfeo_svec *sa, int ai); -void blasfeo_print_to_string_svec(char **buf_out, int m, struct blasfeo_svec *sa, int ai); -void blasfeo_print_tran_svec(int m, struct blasfeo_svec *sa, int ai); -void blasfeo_print_exp_tran_svec(int m, struct blasfeo_svec *sa, int ai); -void blasfeo_print_to_file_tran_svec(FILE *file, int m, struct blasfeo_svec *sa, int ai); -void blasfeo_print_to_string_tran_svec(char **buf_out, int m, struct blasfeo_svec *sa, int ai); - - -#ifdef __cplusplus -} -#endif - - - -#endif // EXT_DEP - -#endif // BLASFEO_S_AUX_EXT_DEP_REF_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_s_aux_old.h b/third_party/acados/include/blasfeo/include/blasfeo_s_aux_old.h deleted file mode 100644 index 5c6db37..0000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_s_aux_old.h +++ /dev/null @@ -1,64 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -// TODO remove -// -void strcp_l_lib(int m, float alpha, int offsetA, float *A, int sda, int offsetB, float *B, int sdb); -void sgead_lib(int m, int n, float alpha, int offsetA, float *A, int sda, int offsetB, float *B, int sdb); -void sgetr_lib(int m, int n, float alpha, int offsetA, float *pA, int sda, int offsetC, float *pC, int sdc); -void strtr_l_lib(int m, float alpha, int offsetA, float *pA, int sda, int offsetC, float *pC, int sdc); -void strtr_u_lib(int m, float alpha, int offsetA, float *pA, int sda, int offsetC, float *pC, int sdc); -void sdiareg_lib(int kmax, float reg, int offset, float *pD, int sdd); -void sdiain_sqrt_lib(int kmax, float *x, int offset, float *pD, int sdd); -void sdiaex_lib(int kmax, float alpha, int offset, float *pD, int sdd, float *x); -void sdiaad_lib(int kmax, float alpha, float *x, int offset, float *pD, int sdd); -void sdiain_libsp(int kmax, int *idx, float alpha, float *x, float *pD, int sdd); -void sdiaex_libsp(int kmax, int *idx, float alpha, float *pD, int sdd, float *x); -void sdiaad_libsp(int kmax, int *idx, float alpha, float *x, float *pD, int sdd); -void sdiaadin_libsp(int kmax, int *idx, float alpha, float *x, float *y, float *pD, int sdd); -void srowin_lib(int kmax, float alpha, float *x, float *pD); -void srowex_lib(int kmax, float alpha, float *pD, float *x); -void srowad_lib(int kmax, float alpha, float *x, float *pD); -void srowin_libsp(int kmax, float alpha, int *idx, float *x, float *pD); -void srowad_libsp(int kmax, int *idx, float alpha, float *x, float *pD); -void srowadin_libsp(int kmax, int *idx, float alpha, float *x, float *y, float *pD); -void srowsw_lib(int kmax, float *pA, float *pC); -void scolin_lib(int kmax, float *x, int offset, float *pD, int sdd); -void scolad_lib(int kmax, float alpha, float *x, int offset, float *pD, int sdd); -void scolin_libsp(int kmax, int *idx, float *x, float *pD, int sdd); -void scolad_libsp(int kmax, float alpha, int *idx, float *x, float *pD, int sdd); -void scolsw_lib(int kmax, int offsetA, float *pA, int sda, int offsetC, float *pC, int sdc); -void svecin_libsp(int kmax, int *idx, float *x, float *y); -void svecad_libsp(int kmax, int *idx, float alpha, float *x, float *y); diff --git a/third_party/acados/include/blasfeo/include/blasfeo_s_aux_ref.h b/third_party/acados/include/blasfeo/include/blasfeo_s_aux_ref.h deleted file mode 100644 index 998e1d8..0000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_s_aux_ref.h +++ /dev/null @@ -1,147 +0,0 @@ - -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_S_AUX_REF_H_ -#define BLASFEO_S_AUX_REF_H_ - - - -#include - -#include "blasfeo_s_aux_old.h" -#include "blasfeo_common.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - -/************************************************ -* d_aux_lib.c -************************************************/ - -// returns the memory size (in bytes) needed for a smat -size_t blasfeo_ref_memsize_smat(int m, int n); -size_t blasfeo_ref_memsize_smat_ps(int ps, int m, int n); -// returns the memory size (in bytes) needed for the diagonal of a smat -size_t blasfeo_ref_memsize_diag_smat(int m, int n); -// returns the memory size (in bytes) needed for a svec -size_t blasfeo_ref_memsize_svec(int m); -// create a strmat for a matrix of size m*n by using memory passed by a pointer (pointer is not updated) -void blasfeo_ref_create_smat(int m, int n, struct blasfeo_smat *sA, void *memory); -void blasfeo_ref_create_smat_ps(int ps, int m, int n, struct blasfeo_smat *sA, void *memory); -// create a strvec for a vector of size m by using memory passed by a pointer (pointer is not updated) -void blasfeo_ref_create_svec(int m, struct blasfeo_svec *sA, void *memory); -void blasfeo_ref_pack_smat(int m, int n, float *A, int lda, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_ref_pack_l_smat(int m, int n, float *A, int lda, struct blasfeo_smat *sB, int bi, int bj); -void blasfeo_ref_pack_l_smat(int m, int n, float *A, int lda, struct blasfeo_smat *sB, int bi, int bj); -void blasfeo_ref_pack_tran_smat(int m, int n, float *A, int lda, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_ref_pack_svec(int m, float *x, int xi, struct blasfeo_svec *sa, int ai); -void blasfeo_ref_unpack_smat(int m, int n, struct blasfeo_smat *sA, int ai, int aj, float *A, int lda); -void blasfeo_ref_unpack_tran_smat(int m, int n, struct blasfeo_smat *sA, int ai, int aj, float *A, int lda); -void blasfeo_ref_unpack_svec(int m, struct blasfeo_svec *sa, int ai, float *x, int xi); -void ref_s_cast_mat2strmat(float *A, struct blasfeo_smat *sA); -void ref_s_cast_diag_mat2strmat(float *dA, struct blasfeo_smat *sA); -void ref_s_cast_vec2vecmat(float *a, struct blasfeo_svec *sa); - -// ge -void blasfeo_ref_sgese(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_ref_sgecpsc(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -void blasfeo_ref_sgecp(int m, int n, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -void blasfeo_ref_sgesc(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_ref_sgein1(float a, struct blasfeo_smat *sA, int ai, int aj); -float blasfeo_ref_sgeex1(struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_ref_sgead(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -void blasfeo_ref_sgetr(int m, int n, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -// tr -void blasfeo_ref_strcp_l(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -void blasfeo_ref_strtr_l(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -void blasfeo_ref_strtr_u(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -// dia -void blasfeo_ref_sdiare(int kmax, float alpha, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_ref_sdiaex(int kmax, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi); -void blasfeo_ref_sdiain(int kmax, float alpha, struct blasfeo_svec *sx, int xi, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_ref_sdiain_sp(int kmax, float alpha, struct blasfeo_svec *sx, int xi, int *idx, struct blasfeo_smat *sD, int di, int dj); -void blasfeo_ref_sdiaex_sp(int kmax, float alpha, int *idx, struct blasfeo_smat *sD, int di, int dj, struct blasfeo_svec *sx, int xi); -void blasfeo_ref_sdiaad(int kmax, float alpha, struct blasfeo_svec *sx, int xi, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_ref_sdiaad_sp(int kmax, float alpha, struct blasfeo_svec *sx, int xi, int *idx, struct blasfeo_smat *sD, int di, int dj); -void blasfeo_ref_sdiaadin_sp(int kmax, float alpha, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sy, int yi, int *idx, struct blasfeo_smat *sD, int di, int dj); -// row -void blasfeo_ref_srowin(int kmax, float alpha, struct blasfeo_svec *sx, int xi, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_ref_srowex(int kmax, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi); -void blasfeo_ref_srowad(int kmax, float alpha, struct blasfeo_svec *sx, int xi, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_ref_srowad_sp(int kmax, float alpha, struct blasfeo_svec *sx, int xi, int *idx, struct blasfeo_smat *sD, int di, int dj); -void blasfeo_ref_srowsw(int kmax, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -void blasfeo_ref_srowpe(int kmax, int *ipiv, struct blasfeo_smat *sA); -void blasfeo_ref_srowpei(int kmax, int *ipiv, struct blasfeo_smat *sA); -// col -void blasfeo_ref_scolex(int kmax, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi); -void blasfeo_ref_scolin(int kmax, struct blasfeo_svec *sx, int xi, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_ref_scolad(int kmax, float alpha, struct blasfeo_svec *sx, int xi, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_ref_scolsc(int kmax, float alpha, struct blasfeo_smat *sA, int ai, int aj); -void blasfeo_ref_scolsw(int kmax, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -void blasfeo_ref_scolpe(int kmax, int *ipiv, struct blasfeo_smat *sA); -void blasfeo_ref_scolpei(int kmax, int *ipiv, struct blasfeo_smat *sA); -// vec -void blasfeo_ref_svecse(int m, float alpha, struct blasfeo_svec *sx, int xi); -void blasfeo_ref_sveccp(int m, struct blasfeo_svec *sa, int ai, struct blasfeo_svec *sc, int ci); -void blasfeo_ref_svecsc(int m, float alpha, struct blasfeo_svec *sa, int ai); -void blasfeo_ref_sveccpsc(int m, float alpha, struct blasfeo_svec *sa, int ai, struct blasfeo_svec *sc, int ci); -void blasfeo_ref_svecad(int m, float alpha, struct blasfeo_svec *sa, int ai, struct blasfeo_svec *sc, int ci); -void blasfeo_ref_svecin1(float a, struct blasfeo_svec *sx, int xi); -float blasfeo_ref_svecex1(struct blasfeo_svec *sx, int xi); -void blasfeo_ref_svecad_sp(int m, float alpha, struct blasfeo_svec *sx, int xi, int *idx, struct blasfeo_svec *sz, int zi); -void blasfeo_ref_svecin_sp(int m, float alpha, struct blasfeo_svec *sx, int xi, int *idx, struct blasfeo_svec *sz, int zi); -void blasfeo_ref_svecex_sp(int m, float alpha, int *idx, struct blasfeo_svec *sx, int x, struct blasfeo_svec *sz, int zi); -// z += alpha * x[idx] -void blasfeo_ref_svecexad_sp(int m, double alpha, int *idx, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -void blasfeo_ref_sveccl(int m, struct blasfeo_svec *sxm, int xim, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sxp, int xip, struct blasfeo_svec *sz, int zi); -void blasfeo_ref_sveccl_mask(int m, struct blasfeo_svec *sxm, int xim, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sxp, int xip, struct blasfeo_svec *sz, int zi, struct blasfeo_svec *sm, int mi); -void blasfeo_ref_svecze(int m, struct blasfeo_svec *sm, int mi, struct blasfeo_svec *sv, int vi, struct blasfeo_svec *se, int ei); -void blasfeo_ref_svecnrm_inf(int m, struct blasfeo_svec *sx, int xi, float *ptr_norm); -void blasfeo_ref_svecpe(int kmax, int *ipiv, struct blasfeo_svec *sx, int xi); -void blasfeo_ref_svecpei(int kmax, int *ipiv, struct blasfeo_svec *sx, int xi); - - - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_S_AUX_REF_H_ - diff --git a/third_party/acados/include/blasfeo/include/blasfeo_s_aux_test.h b/third_party/acados/include/blasfeo/include/blasfeo_s_aux_test.h deleted file mode 100644 index 08d9a14..0000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_s_aux_test.h +++ /dev/null @@ -1,177 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_S_AUX_TEST_H_ -#define BLASFEO_S_AUX_TEST_H_ - -#include - -#include "blasfeo_common.h" - -#ifdef __cplusplus -extern "C" { -#endif - - - -/************************************************ -* d_aux_lib.c -************************************************/ - -int test_blasfeo_memsize_smat(int m, int n); -int test_blasfeo_memsize_diag_smat(int m, int n); -int test_blasfeo_memsize_svec(int m); - -void test_blasfeo_create_smat(int m, int n, struct blasfeo_smat *sA, void *memory); -void test_blasfeo_create_svec(int m, struct blasfeo_svec *sA, void *memory); - -void test_blasfeo_pack_smat(int m, int n, float *A, int lda, struct blasfeo_smat *sA, int ai, int aj); -void test_blasfeo_pack_svec(int m, float *x, int xi, struct blasfeo_svec *sa, int ai); -void test_blasfeo_pack_tran_smat(int m, int n, float *A, int lda, struct blasfeo_smat *sA, int ai, int aj); -void test_blasfeo_unpack_smat(int m, int n, struct blasfeo_smat *sA, int ai, int aj, float *A, int lda); -void test_blasfeo_unpack_svec(int m, struct blasfeo_svec *sa, int ai, float *x, int xi); -void test_blasfeo_unpack_tran_smat(int m, int n, struct blasfeo_smat *sA, int ai, int aj, float *A, int lda); - -void test_s_cast_mat2strmat(float *A, struct blasfeo_smat *sA); -void test_s_cast_diag_mat2strmat(float *dA, struct blasfeo_smat *sA); -void test_s_cast_vec2vecmat(float *a, struct blasfeo_svec *sa); -// copy and scale -void test_blasfeo_sgecpsc(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -void test_blasfeo_sgecp(int m, int n, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -void test_blasfeo_sgesc(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj); - -// void test_blasfeo_sgein1(float a, struct blasfeo_smat *sA, int ai, int aj); -// float test_blasfeo_sgeex1(struct blasfeo_smat *sA, int ai, int aj); -// void test_blasfeo_svecin1(float a, struct blasfeo_svec *sx, int xi); -// float test_blasfeo_svecex1(struct blasfeo_svec *sx, int xi); - -// // A <= alpha -// void test_blasfeo_sgese(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj); -// // a <= alpha -// void test_blasfeo_svecse(int m, float alpha, struct blasfeo_svec *sx, int xi); - - -// void test_blasfeo_sveccp(int m, struct blasfeo_svec *sa, int ai, struct blasfeo_svec *sc, int ci); -// void test_blasfeo_svecsc(int m, float alpha, struct blasfeo_svec *sa, int ai); - -// void test_strcp_l_lib(int m, float alpha, int offsetA, float *A, int sda, int offsetB, float *B, int sdb); -// void test_blasfeo_strcp_l(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); - -// void test_sgead_lib(int m, int n, float alpha, int offsetA, float *A, int sda, int offsetB, float *B, int sdb); -// void test_blasfeo_sgead(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -// void test_blasfeo_svecad(int m, float alpha, struct blasfeo_svec *sa, int ai, struct blasfeo_svec *sc, int ci); - -// void test_sgetr_lib(int m, int n, float alpha, int offsetA, float *pA, int sda, int offsetC, float *pC, int sdc); -// void test_blasfeo_sgetr(int m, int n, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); - -// void test_strtr_l_lib(int m, float alpha, int offsetA, float *pA, int sda, int offsetC, float *pC, int sdc); -// void test_blasfeo_strtr_l(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -// void test_strtr_u_lib(int m, float alpha, int offsetA, float *pA, int sda, int offsetC, float *pC, int sdc); -// void test_blasfeo_strtr_u(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); - -// void test_sdiareg_lib(int kmax, float reg, int offset, float *pD, int sdd); -// void test_blasfeo_sdiaex(int kmax, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi); -// void test_blasfeo_sdiain(int kmax, float alpha, struct blasfeo_svec *sx, int xi, struct blasfeo_smat *sA, int ai, int aj); -// void test_sdiain_sqrt_lib(int kmax, float *x, int offset, float *pD, int sdd); -// void test_sdiaex_lib(int kmax, float alpha, int offset, float *pD, int sdd, float *x); -// void test_sdiaad_lib(int kmax, float alpha, float *x, int offset, float *pD, int sdd); -// void test_sdiain_libsp(int kmax, int *idx, float alpha, float *x, float *pD, int sdd); -// void test_blasfeo_sdiain_sp(int kmax, float alpha, struct blasfeo_svec *sx, int xi, int *idx, struct blasfeo_smat *sD, int di, int dj); -// void test_sdiaex_libsp(int kmax, int *idx, float alpha, float *pD, int sdd, float *x); -// void test_blasfeo_sdiaex_sp(int kmax, float alpha, int *idx, struct blasfeo_smat *sD, int di, int dj, struct blasfeo_svec *sx, int xi); -// void test_blasfeo_sdiaad(int kmax, float alpha, struct blasfeo_svec *sx, int xi, struct blasfeo_smat *sA, int ai, int aj); -// void test_sdiaad_libsp(int kmax, int *idx, float alpha, float *x, float *pD, int sdd); -// void test_blasfeo_sdiaad_sp(int kmax, float alpha, struct blasfeo_svec *sx, int xi, int *idx, struct blasfeo_smat *sD, int di, int dj); -// void test_sdiaadin_libsp(int kmax, int *idx, float alpha, float *x, float *y, float *pD, int sdd); -// void test_blasfeo_sdiaadin_sp(int kmax, float alpha, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sy, int yi, int *idx, struct blasfeo_smat *sD, int di, int dj); -// void test_srowin_lib(int kmax, float alpha, float *x, float *pD); -// void test_blasfeo_srowin(int kmax, float alpha, struct blasfeo_svec *sx, int xi, struct blasfeo_smat *sA, int ai, int aj); -// void test_srowex_lib(int kmax, float alpha, float *pD, float *x); -// void test_blasfeo_srowex(int kmax, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi); -// void test_srowad_lib(int kmax, float alpha, float *x, float *pD); -// void test_blasfeo_srowad(int kmax, float alpha, struct blasfeo_svec *sx, int xi, struct blasfeo_smat *sA, int ai, int aj); -// void test_srowin_libsp(int kmax, float alpha, int *idx, float *x, float *pD); -// void test_srowad_libsp(int kmax, int *idx, float alpha, float *x, float *pD); -// void test_blasfeo_srowad_sp(int kmax, float alpha, struct blasfeo_svec *sx, int xi, int *idx, struct blasfeo_smat *sD, int di, int dj); -// void test_srowadin_libsp(int kmax, int *idx, float alpha, float *x, float *y, float *pD); -// void test_srowsw_lib(int kmax, float *pA, float *pC); -// void test_blasfeo_srowsw(int kmax, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -// void test_blasfeo_srowpe(int kmax, int *ipiv, struct blasfeo_smat *sA); -// void test_scolin_lib(int kmax, float *x, int offset, float *pD, int sdd); -// void test_blasfeo_scolin(int kmax, struct blasfeo_svec *sx, int xi, struct blasfeo_smat *sA, int ai, int aj); -// void test_scolad_lib(int kmax, float alpha, float *x, int offset, float *pD, int sdd); -// void test_scolin_libsp(int kmax, int *idx, float *x, float *pD, int sdd); -// void test_scolad_libsp(int kmax, float alpha, int *idx, float *x, float *pD, int sdd); -// void test_scolsw_lib(int kmax, int offsetA, float *pA, int sda, int offsetC, float *pC, int sdc); -// void test_blasfeo_scolsw(int kmax, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sC, int ci, int cj); -// void test_blasfeo_scolpe(int kmax, int *ipiv, struct blasfeo_smat *sA); -// void test_svecin_libsp(int kmax, int *idx, float *x, float *y); -// void test_svecad_libsp(int kmax, int *idx, float alpha, float *x, float *y); -// void test_blasfeo_svecad_sp(int m, float alpha, struct blasfeo_svec *sx, int xi, int *idx, struct blasfeo_svec *sz, int zi); -// void test_blasfeo_svecin_sp(int m, float alpha, struct blasfeo_svec *sx, int xi, int *idx, struct blasfeo_svec *sz, int zi); -// void test_blasfeo_svecex_sp(int m, float alpha, int *idx, struct blasfeo_svec *sx, int x, struct blasfeo_svec *sz, int zi); -// void test_blasfeo_sveccl(int m, struct blasfeo_svec *sxm, int xim, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sxp, int xip, struct blasfeo_svec *sz, int zi); -// void test_blasfeo_sveccl_mask(int m, struct blasfeo_svec *sxm, int xim, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sxp, int xip, struct blasfeo_svec *sz, int zi, struct blasfeo_svec *sm, int mi); -// void test_blasfeo_svecze(int m, struct blasfeo_svec *sm, int mi, struct blasfeo_svec *sv, int vi, struct blasfeo_svec *se, int ei); -// void test_blasfeo_svecnrm_inf(int m, struct blasfeo_svec *sx, int xi, float *ptr_norm); -// void test_blasfeo_svecpe(int kmax, int *ipiv, struct blasfeo_svec *sx, int xi); - - -// ext_dep - -void test_blasfeo_allocate_smat(int m, int n, struct blasfeo_smat *sA); -void test_blasfeo_allocate_svec(int m, struct blasfeo_svec *sa); - -void test_blasfeo_free_smat(struct blasfeo_smat *sA); -void test_blasfeo_free_svec(struct blasfeo_svec *sa); - -void test_blasfeo_print_smat(int m, int n, struct blasfeo_smat *sA, int ai, int aj); -void test_blasfeo_print_svec(int m, struct blasfeo_svec *sa, int ai); -void test_blasfeo_print_tran_svec(int m, struct blasfeo_svec *sa, int ai); - -void test_blasfeo_print_to_file_smat(FILE *file, int m, int n, struct blasfeo_smat *sA, int ai, int aj); -void test_blasfeo_print_to_file_svec(FILE *file, int m, struct blasfeo_svec *sa, int ai); -void test_blasfeo_print_to_file_tran_svec(FILE *file, int m, struct blasfeo_svec *sa, int ai); - -void test_blasfeo_print_exp_smat(int m, int n, struct blasfeo_smat *sA, int ai, int aj); -void test_blasfeo_print_exp_svec(int m, struct blasfeo_svec *sa, int ai); -void test_blasfeo_print_exp_tran_svec(int m, struct blasfeo_svec *sa, int ai); - - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_S_AUX_TEST_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_s_blas.h b/third_party/acados/include/blasfeo/include/blasfeo_s_blas.h deleted file mode 100644 index 200f1f5..0000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_s_blas.h +++ /dev/null @@ -1,46 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_S_BLAS_H_ -#define BLASFEO_S_BLAS_H_ - - - -#include "blasfeo_s_blasfeo_api.h" -#include "blasfeo_s_blas_api.h" - - - -#endif // BLASFEO_S_BLAS_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_s_blas_api.h b/third_party/acados/include/blasfeo/include/blasfeo_s_blas_api.h deleted file mode 100644 index cf2b3e0..0000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_s_blas_api.h +++ /dev/null @@ -1,182 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef BLASFEO_S_BLAS_API_H_ -#define BLASFEO_S_BLAS_API_H_ - - - -#include "blasfeo_target.h" - - - -#ifdef BLAS_API -#ifdef CBLAS_API -#ifndef BLASFEO_CBLAS_ENUM -#define BLASFEO_CBLAS_ENUM -#ifdef FORTRAN_BLAS_API -#ifndef CBLAS_H -enum CBLAS_ORDER {CblasRowMajor=101, CblasColMajor=102}; -enum CBLAS_TRANSPOSE {CblasNoTrans=111, CblasTrans=112, CblasConjTrans=113}; -enum CBLAS_UPLO {CblasUpper=121, CblasLower=122}; -enum CBLAS_DIAG {CblasNonUnit=131, CblasUnit=132}; -enum CBLAS_SIDE {CblasLeft=141, CblasRight=142}; -#endif // CBLAS_H -#else // FORTRAN_BLAS_API -enum BLASFEO_CBLAS_ORDER {CblasRowMajor=101, CblasColMajor=102}; -enum BLASFEO_CBLAS_TRANSPOSE {CblasNoTrans=111, CblasTrans=112, CblasConjTrans=113}; -enum BLASFEO_CBLAS_UPLO {CblasUpper=121, CblasLower=122}; -enum BLASFEO_CBLAS_DIAG {CblasNonUnit=131, CblasUnit=132}; -enum BLASFEO_CBLAS_SIDE {CblasLeft=141, CblasRight=142}; -#endif // FORTRAN_BLAS_API -#endif // BLASFEO_CBLAS_ENUM -#endif // CBLAS_API -#endif // BLAS_API - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -#ifdef BLAS_API - - - -#ifdef FORTRAN_BLAS_API - - - -// BLAS 1 -// -void saxpy_(int *n, float *alpha, float *x, int *incx, float *y, int *incy); -// -float sdot_(int *n, float *x, int *incx, float *y, int *incy); - -// BLAS 3 -// -void sgemm_(char *ta, char *tb, int *m, int *n, int *k, float *alpha, float *A, int *lda, float *B, int *ldb, float *beta, float *C, int *ldc); -// -void strsm_(char *side, char *uplo, char *transa, char *diag, int *m, int *n, float *alpha, float *A, int *lda, float *B, int *ldb); - - - -// LAPACK -// -void spotrf_(char *uplo, int *m, float *A, int *lda, int *info); - - - -#ifdef CBLAS_API - - - -// CBLAS 1 -// -void cblas_saxpy(const int N, const float alpha, const float *X, const int incX, float *Y, const int incY); - -// CBLAS 3 -// -void cblas_sgemm(const enum CBLAS_ORDER Order, const enum CBLAS_TRANSPOSE TransA, const enum CBLAS_TRANSPOSE TransB, const int M, const int N, const int K, const float alpha, const float *A, const int lda, const float *B, const int ldb, const float beta, float *C, const int ldc); -// -void cblas_strsm(const enum CBLAS_ORDER Order, const enum CBLAS_SIDE Side, const enum CBLAS_UPLO Uplo, const enum CBLAS_TRANSPOSE TransA, const enum CBLAS_DIAG Diag, const int M, const int N, const float alpha, const float *A, const int lda, float *B, const int ldb); - - - -#endif // CBLAS_API - - - -#else // BLASFEO_API - - - -// BLAS 1 -// -void blasfeo_blas_saxpy(int *n, float *alpha, float *x, int *incx, float *y, int *incy); -// -float blasfeo_blas_sdot(int *n, float *x, int *incx, float *y, int *incy); - -// BLAS 3 -// -void blasfeo_blas_sgemm(char *ta, char *tb, int *m, int *n, int *k, float *alpha, float *A, int *lda, float *B, int *ldb, float *beta, float *C, int *ldc); -// -void blasfeo_blas_strsm(char *side, char *uplo, char *transa, char *diag, int *m, int *n, float *alpha, float *A, int *lda, float *B, int *ldb); - - - -// LAPACK -// -void blasfeo_lapack_spotrf(char *uplo, int *m, float *A, int *lda, int *info); - - - -#ifdef CBLAS_API - - - -// CBLAS 1 -// -void blasfeo_cblas_saxpy(const int N, const float alpha, const float *X, const int incX, float *Y, const int incY); - -// CBLAS 3 -// -void blasfeo_cblas_sgemm(const enum BLASFEO_CBLAS_ORDER Order, const enum BLASFEO_CBLAS_TRANSPOSE TransA, const enum BLASFEO_CBLAS_TRANSPOSE TransB, const int M, const int N, const int K, const float alpha, const float *A, const int lda, const float *B, const int ldb, const float beta, float *C, const int ldc); -// -void blasfeo_cblas_strsm(const enum BLASFEO_CBLAS_ORDER Order, const enum BLASFEO_CBLAS_SIDE Side, const enum BLASFEO_CBLAS_UPLO Uplo, const enum BLASFEO_CBLAS_TRANSPOSE TransA, const enum BLASFEO_CBLAS_DIAG Diag, const int M, const int N, const float alpha, const float *A, const int lda, float *B, const int ldb); - - - -#endif // CBLAS_API - - - -#endif // BLASFEO_API - - - -#endif // BLAS_API - - - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_S_BLAS_API_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_s_blasfeo_api.h b/third_party/acados/include/blasfeo/include/blasfeo_s_blasfeo_api.h deleted file mode 100644 index 8b98104..0000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_s_blasfeo_api.h +++ /dev/null @@ -1,284 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_S_BLASFEO_API_H_ -#define BLASFEO_S_BLASFEO_API_H_ - - - -#include "blasfeo_common.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - -// -// level 1 BLAS -// - -// z = y + alpha*x -void blasfeo_saxpy(int kmax, float alpha, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); -// z = beta*y + alpha*x -void blasfeo_saxpby(int kmax, float alpha, struct blasfeo_svec *sx, int xi, float beta, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); -// z = x .* y -void blasfeo_svecmul(int m, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); -// z += x .* y -void blasfeo_svecmulacc(int m, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); -// z = x .* y, return sum(z) = x^T * y -float blasfeo_svecmuldot(int m, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); -// return x^T * y -float blasfeo_sdot(int m, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sy, int yi); -// construct givens plane rotation -void blasfeo_srotg(float a, float b, float *c, float *s); -// apply plane rotation [a b] [c -s; s; c] to the aj0 and aj1 columns of A at row index ai -void blasfeo_scolrot(int m, struct blasfeo_smat *sA, int ai, int aj0, int aj1, float c, float s); -// apply plane rotation [c s; -s c] [a; b] to the ai0 and ai1 rows of A at column index aj -void blasfeo_srowrot(int m, struct blasfeo_smat *sA, int ai0, int ai1, int aj, float c, float s); - - - -// -// level 2 BLAS -// - -// dense - -// z <= beta * y + alpha * A * x -void blasfeo_sgemv_n(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, float beta, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); -// z <= beta * y + alpha * A' * x -void blasfeo_sgemv_t(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, float beta, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); -// z <= inv( A ) * x, A (m)x(n) -void blasfeo_strsv_lnn_mn(int m, int n, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= inv( A' ) * x, A (m)x(n) -void blasfeo_strsv_ltn_mn(int m, int n, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= inv( A ) * x, A (m)x(m) lower, not_transposed, not_unit -void blasfeo_strsv_lnn(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= inv( A ) * x, A (m)x(m) lower, not_transposed, unit -void blasfeo_strsv_lnu(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= inv( A' ) * x, A (m)x(m) lower, transposed, not_unit -void blasfeo_strsv_ltn(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= inv( A' ) * x, A (m)x(m) lower, transposed, unit -void blasfeo_strsv_ltu(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= inv( A' ) * x, A (m)x(m) upper, not_transposed, not_unit -void blasfeo_strsv_unn(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= inv( A' ) * x, A (m)x(m) upper, transposed, not_unit -void blasfeo_strsv_utn(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= A * x ; A lower triangular -void blasfeo_strmv_lnn(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= A * x ; A lower triangular, unit diagonal -void blasfeo_strmv_lnu(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= A' * x ; A lower triangular -void blasfeo_strmv_ltn(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= A' * x ; A lower triangular, unit diagonal -void blasfeo_strmv_ltu(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= beta * y + alpha * A * x ; A upper triangular -void blasfeo_strmv_unn(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= A' * x ; A upper triangular -void blasfeo_strmv_utn(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z_n <= beta_n * y_n + alpha_n * A * x_n -// z_t <= beta_t * y_t + alpha_t * A' * x_t -void blasfeo_sgemv_nt(int m, int n, float alpha_n, float alpha_t, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx_n, int xi_n, struct blasfeo_svec *sx_t, int xi_t, float beta_n, float beta_t, struct blasfeo_svec *sy_n, int yi_n, struct blasfeo_svec *sy_t, int yi_t, struct blasfeo_svec *sz_n, int zi_n, struct blasfeo_svec *sz_t, int zi_t); -// z <= beta * y + alpha * A * x, where A is symmetric and only the lower triangular patr of A is accessed -void blasfeo_ssymv_l(int m, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, float beta, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); -void blasfeo_ssymv_l_mn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, float beta, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); -// z <= beta * y + alpha * A * x, where A is symmetric and only the upper triangular patr of A is accessed -void blasfeo_ssymv_u(int m, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, float beta, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); -// D = C + alpha * x * y^T -void blasfeo_sger(int m, int n, float alpha, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sy, int yi, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); - -// diagonal - -// z <= beta * y + alpha * A * x, A diagonal -void blasfeo_sgemv_d(int m, float alpha, struct blasfeo_svec *sA, int ai, struct blasfeo_svec *sx, int xi, float beta, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); - - - -// -// level 3 BLAS -// - -// dense - -// D <= beta * C + alpha * A * B -void blasfeo_sgemm_nn(int m, int n, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= beta * C + alpha * A * B^T -void blasfeo_sgemm_nt(int m, int n, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= beta * C + alpha * A^T * B -void blasfeo_sgemm_tn(int m, int n, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= beta * C + alpha * A^T * B -void blasfeo_sgemm_tt(int m, int n, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= beta * C + alpha * A * B^T ; C, D lower triangular -void blasfeo_ssyrk_ln(int m, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -void blasfeo_ssyrk_ln_mn(int m, int n, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= beta * C + alpha * A^T * B ; C, D lower triangular -void blasfeo_ssyrk_lt(int m, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= beta * C + alpha * A * B^T ; C, D upper triangular -void blasfeo_ssyrk_un(int m, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= beta * C + alpha * A^T * B ; C, D upper triangular -void blasfeo_ssyrk_ut(int m, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * B * A^T ; B upper triangular -void blasfeo_strmm_rutn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * B * A ; A lower triangular -void blasfeo_strmm_rlnn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * A^{-1} * B , with A lower triangular employint explicit inverse of diagonal -void blasfeo_strsm_llnn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * A^{-1} * B , with A lower triangular with unit diagonal -void blasfeo_strsm_llnu(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * A^{-T} * B , with A lower triangular employint explicit inverse of diagonal -void blasfeo_strsm_lltn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * A^{-T} * B , with A lower triangular with unit diagonal -void blasfeo_strsm_lltu(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * A^{-1} * B , with A upper triangular employing explicit inverse of diagonal -void blasfeo_strsm_lunn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * A^{-1} * B , with A upper triangular withunit diagonal -void blasfeo_strsm_lunu(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * A^{-T} * B , with A upper triangular employing explicit inverse of diagonal -void blasfeo_strsm_lutn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * A^{-T} * B , with A upper triangular withunit diagonal -void blasfeo_strsm_lutu(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * B * A^{-1} , with A lower triangular employing explicit inverse of diagonal -void blasfeo_strsm_rlnn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * B * A^{-1} , with A lower triangular with unit diagonal -void blasfeo_strsm_rlnu(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * B * A^{-T} , with A lower triangular employing explicit inverse of diagonal -void blasfeo_strsm_rltn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * B * A^{-T} , with A lower triangular with unit diagonal -void blasfeo_strsm_rltu(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * B * A^{-1} , with A upper triangular employing explicit inverse of diagonal -void blasfeo_strsm_runn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * B * A^{-1} , with A upper triangular with unit diagonal -void blasfeo_strsm_runu(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * B * A^{-T} , with A upper triangular employing explicit inverse of diagonal -void blasfeo_strsm_rutn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * B * A^{-T} , with A upper triangular with unit diagonal -void blasfeo_strsm_rutu(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= beta * C + alpha * A * B^T + alpha * B * A^T; C, D lower triangular -void blasfeo_ssyr2k_ln(int m, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= beta * C + alpha * A^T * B + alpha * B^T * A; C, D lower triangular -void blasfeo_ssyr2k_lt(int m, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= beta * C + alpha * A * B^T + alpha * B * A^T; C, D upper triangular -void blasfeo_ssyr2k_un(int m, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= beta * C + alpha * A^T * B + alpha * B^T * A; C, D upper triangular -void blasfeo_ssyr2k_ut(int m, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); - -// diagonal - -// D <= alpha * A * B + beta * C, with A diagonal (stored as strvec) -void sgemm_diag_left_ib(int m, int n, float alpha, float *dA, float *pB, int sdb, float beta, float *pC, int sdc, float *pD, int sdd); -void blasfeo_sgemm_dn(int m, int n, float alpha, struct blasfeo_svec *sA, int ai, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * A * B + beta * C, with B diagonal (stored as strvec) -void blasfeo_sgemm_nd(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sB, int bi, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); - - - -// -// LAPACK -// - -// D <= chol( C ) ; C, D lower triangular -void blasfeo_spotrf_l(int m, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -void blasfeo_spotrf_l_mn(int m, int n, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= chol( C ) ; C, D upper triangular -void blasfeo_spotrf_u(int m, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= chol( C + A * B' ) ; C, D lower triangular -void blasfeo_ssyrk_spotrf_ln(int m, int k, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -void blasfeo_ssyrk_spotrf_ln_mn(int m, int n, int k, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= lu( C ) ; no pivoting -void blasfeo_sgetrf_np(int m, int n, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= lu( C ) ; row pivoting -void blasfeo_sgetrf_rp(int m, int n, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj, int *ipiv); -// D <= qr( C ) -void blasfeo_sgeqrf(int m, int n, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj, void *work); -int blasfeo_sgeqrf_worksize(int m, int n); // in bytes -// D <= Q factor, where C is the output of the LQ factorization -int blasfeo_sorglq_worksize(int m, int n, int k); // in bytes -void blasfeo_sorglq(int m, int n, int k, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj, void *work); -// D <= lq( C ) -void blasfeo_sgelqf(int m, int n, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj, void *work); -int blasfeo_sgelqf_worksize(int m, int n); // in bytes -// D <= lq( C ), positive diagonal elements -void blasfeo_sgelqf_pd(int m, int n, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj, void *work); -// [L, A] <= lq( [L, A] ), positive diagonal elements, array of matrices, with -// L lower triangular, of size (m)x(m) -// A full, of size (m)x(n1) -void blasfeo_sgelqf_pd_la(int m, int n1, struct blasfeo_smat *sL, int li, int lj, struct blasfeo_smat *sA, int ai, int aj, void *work); -// [L, L, A] <= lq( [L, L, A] ), positive diagonal elements, array of matrices, with: -// L lower triangular, of size (m)x(m) -// A full, of size (m)x(n1) -void blasfeo_sgelqf_pd_lla(int m, int n1, struct blasfeo_smat *sL0, int l0i, int l0j, struct blasfeo_smat *sL1, int l1i, int l1j, struct blasfeo_smat *sA, int ai, int aj, void *work); - - - - -// -// BLAS API helper functions -// - -#if ( defined(BLAS_API) & defined(MF_PANELMAJ) ) -// BLAS 3 -void blasfeo_cm_sgemm_nn(int m, int n, int k, float alpha, struct blasfeo_cm_smat *sA, int ai, int aj, struct blasfeo_cm_smat *sB, int bi, int bj, float beta, struct blasfeo_cm_smat *sC, int ci, int cj, struct blasfeo_cm_smat *sD, int di, int dj); -void blasfeo_cm_sgemm_nt(int m, int n, int k, float alpha, struct blasfeo_cm_smat *sA, int ai, int aj, struct blasfeo_cm_smat *sB, int bi, int bj, float beta, struct blasfeo_cm_smat *sC, int ci, int cj, struct blasfeo_cm_smat *sD, int di, int dj); -void blasfeo_cm_sgemm_tn(int m, int n, int k, float alpha, struct blasfeo_cm_smat *sA, int ai, int aj, struct blasfeo_cm_smat *sB, int bi, int bj, float beta, struct blasfeo_cm_smat *sC, int ci, int cj, struct blasfeo_cm_smat *sD, int di, int dj); -void blasfeo_cm_sgemm_tt(int m, int n, int k, float alpha, struct blasfeo_cm_smat *sA, int ai, int aj, struct blasfeo_cm_smat *sB, int bi, int bj, float beta, struct blasfeo_cm_smat *sC, int ci, int cj, struct blasfeo_cm_smat *sD, int di, int dj); -void blasfeo_cm_strsm_llnn(int m, int n, float alpha, struct blasfeo_cm_smat *sA, int ai, int aj, struct blasfeo_cm_smat *sB, int bi, int bj, struct blasfeo_cm_smat *sD, int di, int dj); -void blasfeo_cm_strsm_llnu(int m, int n, float alpha, struct blasfeo_cm_smat *sA, int ai, int aj, struct blasfeo_cm_smat *sB, int bi, int bj, struct blasfeo_cm_smat *sD, int di, int dj); -void blasfeo_cm_strsm_lltn(int m, int n, float alpha, struct blasfeo_cm_smat *sA, int ai, int aj, struct blasfeo_cm_smat *sB, int bi, int bj, struct blasfeo_cm_smat *sD, int di, int dj); -void blasfeo_cm_strsm_lltu(int m, int n, float alpha, struct blasfeo_cm_smat *sA, int ai, int aj, struct blasfeo_cm_smat *sB, int bi, int bj, struct blasfeo_cm_smat *sD, int di, int dj); -void blasfeo_cm_strsm_lunn(int m, int n, float alpha, struct blasfeo_cm_smat *sA, int ai, int aj, struct blasfeo_cm_smat *sB, int bi, int bj, struct blasfeo_cm_smat *sD, int di, int dj); -void blasfeo_cm_strsm_lunu(int m, int n, float alpha, struct blasfeo_cm_smat *sA, int ai, int aj, struct blasfeo_cm_smat *sB, int bi, int bj, struct blasfeo_cm_smat *sD, int di, int dj); -void blasfeo_cm_strsm_lutn(int m, int n, float alpha, struct blasfeo_cm_smat *sA, int ai, int aj, struct blasfeo_cm_smat *sB, int bi, int bj, struct blasfeo_cm_smat *sD, int di, int dj); -void blasfeo_cm_strsm_lutu(int m, int n, float alpha, struct blasfeo_cm_smat *sA, int ai, int aj, struct blasfeo_cm_smat *sB, int bi, int bj, struct blasfeo_cm_smat *sD, int di, int dj); -void blasfeo_cm_strsm_rlnn(int m, int n, float alpha, struct blasfeo_cm_smat *sA, int ai, int aj, struct blasfeo_cm_smat *sB, int bi, int bj, struct blasfeo_cm_smat *sD, int di, int dj); -void blasfeo_cm_strsm_rlnu(int m, int n, float alpha, struct blasfeo_cm_smat *sA, int ai, int aj, struct blasfeo_cm_smat *sB, int bi, int bj, struct blasfeo_cm_smat *sD, int di, int dj); -void blasfeo_cm_strsm_rltn(int m, int n, float alpha, struct blasfeo_cm_smat *sA, int ai, int aj, struct blasfeo_cm_smat *sB, int bi, int bj, struct blasfeo_cm_smat *sD, int di, int dj); -void blasfeo_cm_strsm_rltu(int m, int n, float alpha, struct blasfeo_cm_smat *sA, int ai, int aj, struct blasfeo_cm_smat *sB, int bi, int bj, struct blasfeo_cm_smat *sD, int di, int dj); -void blasfeo_cm_strsm_runn(int m, int n, float alpha, struct blasfeo_cm_smat *sA, int ai, int aj, struct blasfeo_cm_smat *sB, int bi, int bj, struct blasfeo_cm_smat *sD, int di, int dj); -void blasfeo_cm_strsm_runu(int m, int n, float alpha, struct blasfeo_cm_smat *sA, int ai, int aj, struct blasfeo_cm_smat *sB, int bi, int bj, struct blasfeo_cm_smat *sD, int di, int dj); -void blasfeo_cm_strsm_rutn(int m, int n, float alpha, struct blasfeo_cm_smat *sA, int ai, int aj, struct blasfeo_cm_smat *sB, int bi, int bj, struct blasfeo_cm_smat *sD, int di, int dj); -void blasfeo_cm_strsm_rutu(int m, int n, float alpha, struct blasfeo_cm_smat *sA, int ai, int aj, struct blasfeo_cm_smat *sB, int bi, int bj, struct blasfeo_cm_smat *sD, int di, int dj); -// LAPACK -void blasfeo_cm_spotrf_l(int m, struct blasfeo_cm_smat *sC, int ci, int cj, struct blasfeo_cm_smat *sD, int di, int dj); -void blasfeo_cm_spotrf_u(int m, struct blasfeo_cm_smat *sC, int ci, int cj, struct blasfeo_cm_smat *sD, int di, int dj); -#endif - - - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_S_BLASFEO_API_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_s_blasfeo_api_ref.h b/third_party/acados/include/blasfeo/include/blasfeo_s_blasfeo_api_ref.h deleted file mode 100644 index f429a79..0000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_s_blasfeo_api_ref.h +++ /dev/null @@ -1,135 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_S_BLASFEO_API_REF_H_ -#define BLASFEO_S_BLASFEO_API_REF_H_ - -#include "blasfeo_common.h" - - -#ifdef __cplusplus -extern "C" { -#endif - - -// expose reference BLASFEO for testing - -// --- level 1 - -void blasfeo_saxpy_ref(int kmax, float alpha, struct blasfeo_svec_ref *sx, int xi, struct blasfeo_svec_ref *sy, int yi, struct blasfeo_svec_ref *sz, int zi); -void blasfeo_saxpby_ref(int kmax, float alpha, struct blasfeo_svec_ref *sx, int xi, float beta, struct blasfeo_svec_ref *sy, int yi, struct blasfeo_svec_ref *sz, int zi); -void blasfeo_svecmul_ref(int m, struct blasfeo_svec_ref *sx, int xi, struct blasfeo_svec_ref *sy, int yi, struct blasfeo_svec_ref *sz, int zi); -void blasfeo_svecmulacc_ref(int m, struct blasfeo_svec_ref *sx, int xi, struct blasfeo_svec_ref *sy, int yi, struct blasfeo_svec_ref *sz, int zi); -float blasfeo_svecmuldot_ref(int m, struct blasfeo_svec_ref *sx, int xi, struct blasfeo_svec_ref *sy, int yi, struct blasfeo_svec_ref *sz, int zi); -float blasfeo_sdot_ref(int m, struct blasfeo_svec_ref *sx, int xi, struct blasfeo_svec_ref *sy, int yi); -void blasfeo_srotg_ref(float a, float b, float *c, float *s); -void blasfeo_scolrot_ref(int m, struct blasfeo_smat_ref *sA, int ai, int aj0, int aj1, float c, float s); -void blasfeo_srowrot_ref(int m, struct blasfeo_smat_ref *sA, int ai0, int ai1, int aj, float c, float s); - - -// --- level 2 - -// dense -void blasfeo_sgemv_n_ref(int m, int n, float alpha, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_svec_ref *sx, int xi, float beta, struct blasfeo_svec_ref *sy, int yi, struct blasfeo_svec_ref *sz, int zi); -void blasfeo_sgemv_t_ref(int m, int n, float alpha, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_svec_ref *sx, int xi, float beta, struct blasfeo_svec_ref *sy, int yi, struct blasfeo_svec_ref *sz, int zi); -void blasfeo_strsv_lnn_mn_ref(int m, int n, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_svec_ref *sx, int xi, struct blasfeo_svec_ref *sz, int zi); -void blasfeo_strsv_ltn_mn_ref(int m, int n, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_svec_ref *sx, int xi, struct blasfeo_svec_ref *sz, int zi); -void blasfeo_strsv_lnn_ref(int m, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_svec_ref *sx, int xi, struct blasfeo_svec_ref *sz, int zi); -void blasfeo_strsv_lnu_ref(int m, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_svec_ref *sx, int xi, struct blasfeo_svec_ref *sz, int zi); -void blasfeo_strsv_ltn_ref(int m, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_svec_ref *sx, int xi, struct blasfeo_svec_ref *sz, int zi); -void blasfeo_strsv_ltu_ref(int m, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_svec_ref *sx, int xi, struct blasfeo_svec_ref *sz, int zi); -void blasfeo_strsv_unn_ref(int m, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_svec_ref *sx, int xi, struct blasfeo_svec_ref *sz, int zi); -void blasfeo_strsv_utn_ref(int m, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_svec_ref *sx, int xi, struct blasfeo_svec_ref *sz, int zi); -void blasfeo_strmv_unn_ref(int m, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_svec_ref *sx, int xi, struct blasfeo_svec_ref *sz, int zi); -void blasfeo_strmv_utn_ref(int m, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_svec_ref *sx, int xi, struct blasfeo_svec_ref *sz, int zi); -void blasfeo_strmv_lnn_ref(int m, int n, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_svec_ref *sx, int xi, struct blasfeo_svec_ref *sz, int zi); -void blasfeo_strmv_ltn_ref(int m, int n, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_svec_ref *sx, int xi, struct blasfeo_svec_ref *sz, int zi); -void blasfeo_strmv_lnu_ref(int m, int n, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_svec_ref *sx, int xi, struct blasfeo_svec_ref *sz, int zi); -void blasfeo_strmv_ltu_ref(int m, int n, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_svec_ref *sx, int xi, struct blasfeo_svec_ref *sz, int zi); -void blasfeo_sgemv_nt_ref(int m, int n, float alpha_n, float alpha_t, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_svec_ref *sx_n, int xi_n, struct blasfeo_svec_ref *sx_t, int xi_t, float beta_n, float beta_t, struct blasfeo_svec_ref *sy_n, int yi_n, struct blasfeo_svec_ref *sy_t, int yi_t, struct blasfeo_svec_ref *sz_n, int zi_n, struct blasfeo_svec_ref *sz_t, int zi_t); -void blasfeo_ssymv_l_ref(int m, int n, float alpha, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_svec_ref *sx, int xi, float beta, struct blasfeo_svec_ref *sy, int yi, struct blasfeo_svec_ref *sz, int zi); - -// diagonal -void blasfeo_sgemv_d_ref(int m, float alpha, struct blasfeo_svec_ref *sA, int ai, struct blasfeo_svec_ref *sx, int xi, float beta, struct blasfeo_svec_ref *sy, int yi, struct blasfeo_svec_ref *sz, int zi); - - -// --- level 3 - -// dense -void blasfeo_sgemm_nn_ref( int m, int n, int k, float alpha, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_smat_ref *sB, int bi, int bj, float beta, struct blasfeo_smat_ref *sC, int ci, int cj, struct blasfeo_smat_ref *sD, int di, int dj); -void blasfeo_sgemm_nt_ref( int m, int n, int k, float alpha, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_smat_ref *sB, int bi, int bj, float beta, struct blasfeo_smat_ref *sC, int ci, int cj, struct blasfeo_smat_ref *sD, int di, int dj); -void blasfeo_sgemm_tn_ref(int m, int n, int k, float alpha, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_smat_ref *sB, int bi, int bj, float beta, struct blasfeo_smat_ref *sC, int ci, int cj, struct blasfeo_smat_ref *sD, int di, int dj); -void blasfeo_sgemm_tt_ref(int m, int n, int k, float alpha, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_smat_ref *sB, int bi, int bj, float beta, struct blasfeo_smat_ref *sC, int ci, int cj, struct blasfeo_smat_ref *sD, int di, int dj); - -void blasfeo_ssyrk_ln_mn_ref( int m, int n, int k, float alpha, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_smat_ref *sB, int bi, int bj, float beta, struct blasfeo_smat_ref *sC, int ci, int cj, struct blasfeo_smat_ref *sD, int di, int dj); -void blasfeo_ssyrk_ln_ref( int m, int k, float alpha, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_smat_ref *sB, int bi, int bj, float beta, struct blasfeo_smat_ref *sC, int ci, int cj, struct blasfeo_smat_ref *sD, int di, int dj); -void blasfeo_ssyrk_lt_ref( int m, int k, float alpha, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_smat_ref *sB, int bi, int bj, float beta, struct blasfeo_smat_ref *sC, int ci, int cj, struct blasfeo_smat_ref *sD, int di, int dj); -void blasfeo_ssyrk_un_ref( int m, int k, float alpha, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_smat_ref *sB, int bi, int bj, float beta, struct blasfeo_smat_ref *sC, int ci, int cj, struct blasfeo_smat_ref *sD, int di, int dj); -void blasfeo_ssyrk_ut_ref( int m, int k, float alpha, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_smat_ref *sB, int bi, int bj, float beta, struct blasfeo_smat_ref *sC, int ci, int cj, struct blasfeo_smat_ref *sD, int di, int dj); - -void blasfeo_strmm_rutn_ref( int m, int n, float alpha, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_smat_ref *sB, int bi, int bj, struct blasfeo_smat_ref *sD, int di, int dj); -void blasfeo_strmm_rlnn_ref( int m, int n, float alpha, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_smat_ref *sB, int bi, int bj, struct blasfeo_smat_ref *sD, int di, int dj); -void blasfeo_strsm_rltn_ref( int m, int n, float alpha, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_smat_ref *sB, int bi, int bj, struct blasfeo_smat_ref *sD, int di, int dj); -void blasfeo_strsm_rltu_ref( int m, int n, float alpha, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_smat_ref *sB, int bi, int bj, struct blasfeo_smat_ref *sD, int di, int dj); -void blasfeo_strsm_rutn_ref( int m, int n, float alpha, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_smat_ref *sB, int bi, int bj, struct blasfeo_smat_ref *sD, int di, int dj); -void blasfeo_strsm_llnu_ref( int m, int n, float alpha, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_smat_ref *sB, int bi, int bj, struct blasfeo_smat_ref *sD, int di, int dj); -void blasfeo_strsm_lunn_ref( int m, int n, float alpha, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_smat_ref *sB, int bi, int bj, struct blasfeo_smat_ref *sD, int di, int dj); - -// diagonal -void dgemm_diag_left_lib_ref(int m, int n, float alpha, float *dA, float *pB, int sdb, float beta, float *pC, int sdc, float *pD, int sdd); -void blasfeo_sgemm_dn_ref(int m, int n, float alpha, struct blasfeo_svec_ref *sA, int ai, struct blasfeo_smat_ref *sB, int bi, int bj, float beta, struct blasfeo_smat_ref *sC, int ci, int cj, struct blasfeo_smat_ref *sD, int di, int dj); -void blasfeo_sgemm_nd_ref(int m, int n, float alpha, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_svec_ref *sB, int bi, float beta, struct blasfeo_smat_ref *sC, int ci, int cj, struct blasfeo_smat_ref *sD, int di, int dj); - -// --- lapack - -void blasfeo_sgetrf_nopivot_ref(int m, int n, struct blasfeo_smat_ref *sC, int ci, int cj, struct blasfeo_smat_ref *sD, int di, int dj); -void blasfeo_sgetrf_rowpivot_ref(int m, int n, struct blasfeo_smat_ref *sC, int ci, int cj, struct blasfeo_smat_ref *sD, int di, int dj, int *ipiv); -void blasfeo_spotrf_l_ref(int m, struct blasfeo_smat_ref *sC, int ci, int cj, struct blasfeo_smat_ref *sD, int di, int dj); -void blasfeo_spotrf_l_mn_ref(int m, int n, struct blasfeo_smat_ref *sC, int ci, int cj, struct blasfeo_smat_ref *sD, int di, int dj); -void blasfeo_ssyrk_dpotrf_ln_ref(int m, int k, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_smat_ref *sB, int bi, int bj, struct blasfeo_smat_ref *sC, int ci, int cj, struct blasfeo_smat_ref *sD, int di, int dj); -void blasfeo_ssyrk_dpotrf_ln_mn_ref(int m, int n, int k, struct blasfeo_smat_ref *sA, int ai, int aj, struct blasfeo_smat_ref *sB, int bi, int bj, struct blasfeo_smat_ref *sC, int ci, int cj, struct blasfeo_smat_ref *sD, int di, int dj); -void blasfeo_sgetrf_nopivot_ref(int m, int n, struct blasfeo_smat_ref *sC, int ci, int cj, struct blasfeo_smat_ref *sD, int di, int dj); -void blasfeo_sgetrf_rowpivot_ref(int m, int n, struct blasfeo_smat_ref *sC, int ci, int cj, struct blasfeo_smat_ref *sD, int di, int dj, int *ipiv); -void blasfeo_sgeqrf_ref(int m, int n, struct blasfeo_smat_ref *sC, int ci, int cj, struct blasfeo_smat_ref *sD, int di, int dj, void *work); -void blasfeo_sgelqf_ref(int m, int n, struct blasfeo_smat_ref *sC, int ci, int cj, struct blasfeo_smat_ref *sD, int di, int dj, void *work); -void blasfeo_sgelqf_pd_ref(int m, int n, struct blasfeo_smat_ref *sC, int ci, int cj, struct blasfeo_smat_ref *sD, int di, int dj, void *work); -void blasfeo_sgelqf_pd_la_ref(int m, int n1, struct blasfeo_smat_ref *sL, int li, int lj, struct blasfeo_smat_ref *sA, int ai, int aj, void *work); -void blasfeo_sgelqf_pd_lla_ref(int m, int n1, struct blasfeo_smat_ref *sL0, int l0i, int l0j, struct blasfeo_smat_ref *sL1, int l1i, int l1j, struct blasfeo_smat_ref *sA, int ai, int aj, void *work); - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_S_BLASFEO_API_REF_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_s_blasfeo_ref_api.h b/third_party/acados/include/blasfeo/include/blasfeo_s_blasfeo_ref_api.h deleted file mode 100644 index 17cb179..0000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_s_blasfeo_ref_api.h +++ /dev/null @@ -1,252 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_S_BLASFEO_REF_API_H_ -#define BLASFEO_S_BLASFEO_REF_API_H_ - - - -#include "blasfeo_common.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - -// -// level 1 BLAS -// - -// z = y + alpha*x -void blasfeo_ref_saxpy(int kmax, float alpha, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); -// z = beta*y + alpha*x -void blasfeo_ref_saxpby(int kmax, float alpha, struct blasfeo_svec *sx, int xi, float beta, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); -// z = x .* y -void blasfeo_ref_svecmul(int m, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); -// z += x .* y -void blasfeo_ref_svecmulacc(int m, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); -// z = x .* y, return sum(z) = x^T * y -float blasfeo_ref_svecmuldot(int m, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); -// return x^T * y -float blasfeo_ref_sdot(int m, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sy, int yi); -// construct givens plane rotation -void blasfeo_ref_srotg(float a, float b, float *c, float *s); -// apply plane rotation [a b] [c -s; s; c] to the aj0 and aj1 columns of A at row index ai -void blasfeo_ref_scolrot(int m, struct blasfeo_smat *sA, int ai, int aj0, int aj1, float c, float s); -// apply plane rotation [c s; -s c] [a; b] to the ai0 and ai1 rows of A at column index aj -void blasfeo_ref_srowrot(int m, struct blasfeo_smat *sA, int ai0, int ai1, int aj, float c, float s); - - - -// -// level 2 BLAS -// - -// dense - -// z <= beta * y + alpha * A * x -void blasfeo_ref_sgemv_n(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, float beta, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); -// z <= beta * y + alpha * A' * x -void blasfeo_ref_sgemv_t(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, float beta, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); -// z <= inv( A ) * x, A (m)x(n) -void blasfeo_ref_strsv_lnn_mn(int m, int n, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= inv( A' ) * x, A (m)x(n) -void blasfeo_ref_strsv_ltn_mn(int m, int n, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= inv( A ) * x, A (m)x(m) lower, not_transposed, not_unit -void blasfeo_ref_strsv_lnn(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= inv( A ) * x, A (m)x(m) lower, not_transposed, unit -void blasfeo_ref_strsv_lnu(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= inv( A' ) * x, A (m)x(m) lower, transposed, not_unit -void blasfeo_ref_strsv_ltn(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= inv( A' ) * x, A (m)x(m) lower, transposed, unit -void blasfeo_ref_strsv_ltu(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= inv( A' ) * x, A (m)x(m) upper, not_transposed, not_unit -void blasfeo_ref_strsv_unn(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= inv( A' ) * x, A (m)x(m) upper, transposed, not_unit -void blasfeo_ref_strsv_utn(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= A * x ; A lower triangular -void blasfeo_ref_strmv_lnn(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= A * x ; A lower triangular, unit diagonal -void blasfeo_ref_strmv_lnu(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= A' * x ; A lower triangular -void blasfeo_ref_strmv_ltn(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= A' * x ; A lower triangular, unit diagonal -void blasfeo_ref_strmv_ltu(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= beta * y + alpha * A * x ; A upper triangular -void blasfeo_ref_strmv_unn(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z <= A' * x ; A upper triangular -void blasfeo_ref_strmv_utn(int m, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sz, int zi); -// z_n <= beta_n * y_n + alpha_n * A * x_n -// z_t <= beta_t * y_t + alpha_t * A' * x_t -void blasfeo_ref_sgemv_nt(int m, int n, float alpha_n, float alpha_t, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx_n, int xi_n, struct blasfeo_svec *sx_t, int xi_t, float beta_n, float beta_t, struct blasfeo_svec *sy_n, int yi_n, struct blasfeo_svec *sy_t, int yi_t, struct blasfeo_svec *sz_n, int zi_n, struct blasfeo_svec *sz_t, int zi_t); -// z <= beta * y + alpha * A * x, where A is symmetric and only the lower triangular patr of A is accessed -void blasfeo_ref_ssymv_l(int m, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, float beta, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); -void blasfeo_ref_ssymv_l_mn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, float beta, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); -// z <= beta * y + alpha * A * x, where A is symmetric and only the upper triangular patr of A is accessed -void blasfeo_ref_ssymv_u(int m, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sx, int xi, float beta, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); -// D = C + alpha * x * y^T -void blasfeo_ref_sger(int m, int n, float alpha, struct blasfeo_svec *sx, int xi, struct blasfeo_svec *sy, int yi, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); - -// diagonal - -// z <= beta * y + alpha * A * x, A diagonal -void blasfeo_ref_sgemv_d(int m, float alpha, struct blasfeo_svec *sA, int ai, struct blasfeo_svec *sx, int xi, float beta, struct blasfeo_svec *sy, int yi, struct blasfeo_svec *sz, int zi); - - - -// -// level 3 BLAS -// - -// dense - -// D <= beta * C + alpha * A * B -void blasfeo_ref_sgemm_nn(int m, int n, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= beta * C + alpha * A * B^T -void blasfeo_ref_sgemm_nt(int m, int n, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= beta * C + alpha * A^T * B -void blasfeo_ref_sgemm_tn(int m, int n, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= beta * C + alpha * A^T * B -void blasfeo_ref_sgemm_tt(int m, int n, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= beta * C + alpha * A * B^T ; C, D lower triangular -void blasfeo_ref_ssyrk_ln(int m, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -void blasfeo_ref_ssyrk_ln_mn(int m, int n, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= beta * C + alpha * A^T * B ; C, D lower triangular -void blasfeo_ref_ssyrk_lt(int m, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= beta * C + alpha * A * B^T ; C, D upper triangular -void blasfeo_ref_ssyrk_un(int m, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= beta * C + alpha * A^T * B ; C, D upper triangular -void blasfeo_ref_ssyrk_ut(int m, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * B * A^T ; B upper triangular -void blasfeo_ref_strmm_rutn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * B * A ; A lower triangular -void blasfeo_ref_strmm_rlnn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * A^{-1} * B , with A lower triangular employint explicit inverse of diagonal -void blasfeo_ref_strsm_llnn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * A^{-1} * B , with A lower triangular with unit diagonal -void blasfeo_ref_strsm_llnu(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * A^{-T} * B , with A lower triangular employint explicit inverse of diagonal -void blasfeo_ref_strsm_lltn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * A^{-T} * B , with A lower triangular with unit diagonal -void blasfeo_ref_strsm_lltu(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * A^{-1} * B , with A upper triangular employing explicit inverse of diagonal -void blasfeo_ref_strsm_lunn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * A^{-1} * B , with A upper triangular withunit diagonal -void blasfeo_ref_strsm_lunu(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * A^{-T} * B , with A upper triangular employing explicit inverse of diagonal -void blasfeo_ref_strsm_lutn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * A^{-T} * B , with A upper triangular withunit diagonal -void blasfeo_ref_strsm_lutu(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * B * A^{-1} , with A lower triangular employing explicit inverse of diagonal -void blasfeo_ref_strsm_rlnn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * B * A^{-1} , with A lower triangular with unit diagonal -void blasfeo_ref_strsm_rlnu(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * B * A^{-T} , with A lower triangular employing explicit inverse of diagonal -void blasfeo_ref_strsm_rltn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * B * A^{-T} , with A lower triangular with unit diagonal -void blasfeo_ref_strsm_rltu(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * B * A^{-1} , with A upper triangular employing explicit inverse of diagonal -void blasfeo_ref_strsm_runn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * B * A^{-1} , with A upper triangular with unit diagonal -void blasfeo_ref_strsm_runu(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * B * A^{-T} , with A upper triangular employing explicit inverse of diagonal -void blasfeo_ref_strsm_rutn(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * B * A^{-T} , with A upper triangular with unit diagonal -void blasfeo_ref_strsm_rutu(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sD, int di, int dj); -// D <= beta * C + alpha * A * B^T + alpha * B * A^T ; C, D lower triangular -void blasfeo_ref_ssyr2k_ln(int m, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= beta * C + alpha * A^T * B + alpha * B^T * A ; C, D lower triangular -void blasfeo_ref_ssyr2k_lt(int m, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= beta * C + alpha * A * B^T + alpha * B * A^T ; C, D upper triangular -void blasfeo_ref_ssyr2k_un(int m, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= beta * C + alpha * A^T * B + alpha * B^T * A ; C, D upper triangular -void blasfeo_ref_ssyr2k_ut(int m, int k, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); - -// diagonal - -// D <= alpha * A * B + beta * C, with A diagonal (stored as strvec) -void sgemm_diag_left_ib(int m, int n, float alpha, float *dA, float *pB, int sdb, float beta, float *pC, int sdc, float *pD, int sdd); -void blasfeo_ref_sgemm_dn(int m, int n, float alpha, struct blasfeo_svec *sA, int ai, struct blasfeo_smat *sB, int bi, int bj, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= alpha * A * B + beta * C, with B diagonal (stored as strvec) -void blasfeo_ref_sgemm_nd(int m, int n, float alpha, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_svec *sB, int bi, float beta, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); - - - -// -// LAPACK -// - -// D <= chol( C ) ; C, D lower triangular -void blasfeo_ref_spotrf_l(int m, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -void blasfeo_ref_spotrf_l_mn(int m, int n, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= chol( C ) ; C, D upper triangular -void blasfeo_ref_spotrf_u(int m, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= chol( C + A * B' ) ; C, D lower triangular -void blasfeo_ref_ssyrk_spotrf_ln(int m, int k, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -void blasfeo_ref_ssyrk_spotrf_ln_mn(int m, int n, int k, struct blasfeo_smat *sA, int ai, int aj, struct blasfeo_smat *sB, int bi, int bj, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= lu( C ) ; no pivoting -void blasfeo_ref_sgetrf_np(int m, int n, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj); -// D <= lu( C ) ; row pivoting -void blasfeo_ref_sgetrf_rp(int m, int n, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj, int *ipiv); -// D <= qr( C ) -void blasfeo_ref_sgeqrf(int m, int n, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj, void *work); -int blasfeo_ref_sgeqrf_worksize(int m, int n); // in bytes -// D <= Q factor, where C is the output of the LQ factorization -int blasfeo_ref_sorglq_worksize(int m, int n, int k); // in bytes -void blasfeo_ref_sorglq(int m, int n, int k, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj, void *work); -// D <= lq( C ) -void blasfeo_ref_sgelqf(int m, int n, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj, void *work); -int blasfeo_ref_sgelqf_worksize(int m, int n); // in bytes -// D <= lq( C ), positive diagonal elements -void blasfeo_ref_sgelqf_pd(int m, int n, struct blasfeo_smat *sC, int ci, int cj, struct blasfeo_smat *sD, int di, int dj, void *work); -// [L, A] <= lq( [L, A] ), positive diagonal elements, array of matrices, with -// L lower triangular, of size (m)x(m) -// A full, of size (m)x(n1) -void blasfeo_ref_sgelqf_pd_la(int m, int n1, struct blasfeo_smat *sL, int li, int lj, struct blasfeo_smat *sA, int ai, int aj, void *work); -// [L, L, A] <= lq( [L, L, A] ), positive diagonal elements, array of matrices, with: -// L lower triangular, of size (m)x(m) -// A full, of size (m)x(n1) -void blasfeo_ref_sgelqf_pd_lla(int m, int n1, struct blasfeo_smat *sL0, int l0i, int l0j, struct blasfeo_smat *sL1, int l1i, int l1j, struct blasfeo_smat *sA, int ai, int aj, void *work); - - - - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_S_BLASFEO_REF_API_H_ - diff --git a/third_party/acados/include/blasfeo/include/blasfeo_s_kernel.h b/third_party/acados/include/blasfeo/include/blasfeo_s_kernel.h deleted file mode 100644 index 99d2b28..0000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_s_kernel.h +++ /dev/null @@ -1,692 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_S_KERNEL_H_ -#define BLASFEO_S_KERNEL_H_ - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -// utils -void blasfeo_align_2MB(void *ptr, void **ptr_align); -void blasfeo_align_4096_byte(void *ptr, void **ptr_align); -void blasfeo_align_64_byte(void *ptr, void **ptr_align); - - - -// -// lib8 -// - -// 24x4 -void kernel_sgemm_nt_24x4_lib8(int k, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd); -void kernel_sgemm_nt_24x4_vs_lib8(int k, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd, int km, int kn); -void kernel_sgemm_nt_24x4_gen_lib8(int k, float *alpha, float *A, int sda, float *B, float *beta, int offsetC, float *C, int sdc, int offsetD, float *D, int sdd, int m0, int m1, int n0, int n1); -void kernel_sgemm_nn_24x4_lib8(int k, float *alpha, float *A, int sda, int offsetB, float *B, int sdb, float *beta, float *C, int sdc, float *D, int sdd); -void kernel_sgemm_nn_24x4_vs_lib8(int k, float *alpha, float *A, int sda, int offsetB, float *B, int sdb, float *beta, float *C, int sdc, float *D, int sdd, int km, int kn); -void kernel_sgemm_nn_24x4_gen_lib8(int k, float *alpha, float *A, int sda, int offsetB, float *B, int sdb, float *beta, int offsetC, float *C, int sdc, int offsetD, float *D, int sdd, int m0, int m1, int n0, int n1); -void kernel_ssyrk_nt_l_24x4_lib8(int k, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd); -void kernel_ssyrk_nt_l_24x4_vs_lib8(int k, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd, int km, int kn); -void kernel_ssyrk_nt_l_20x4_lib8(int k, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd); -void kernel_ssyrk_nt_l_20x4_vs_lib8(int k, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd, int km, int kn); -void kernel_spotrf_nt_l_24x4_lib8(int k, float *A, int sda, float *B, float *C, int sdc, float *D, int sdd, float *inv_diag_D); -void kernel_spotrf_nt_l_24x4_vs_lib8(int k, float *A, int sda, float *B, float *C, int sdc, float *D, int sdd, float *inv_diag_D, int km, int kn); -void kernel_spotrf_nt_l_20x4_lib8(int k, float *A, int sda, float *B, float *C, int sdc, float *D, int sdd, float *inv_diag_D); -void kernel_spotrf_nt_l_20x4_vs_lib8(int k, float *A, int sda, float *B, float *C, int sdc, float *D, int sdd, float *inv_diag_D, int km, int kn); -void kernel_strsm_nt_rl_inv_24x4_lib8(int k, float *A, int sda, float *B, float *C, int sdc, float *D, int sdd, float *E, float *inv_diag_E); -void kernel_strsm_nt_rl_inv_24x4_vs_lib8(int k, float *A, int sda, float *B, float *C, int sdc, float *D, int sdd, float *E, float *inv_diag_E, int km, int kn); -void kernel_sgemm_strsm_nt_rl_inv_24x4_lib8(int kp, float *Ap, int sdap, float *Bp, int km_, float *Am, int sdam, float *Bm, float *C, int sdc, float *D, int sdd, float *E, float *inv_diag_E); -void kernel_sgemm_strsm_nt_rl_inv_24x4_vs_lib8(int kp, float *Ap, int sdap, float *Bp, int km_, float *Am, int sdam, float *Bm, float *C, int sdc, float *D, int sdd, float *E, float *inv_diag_E, int km, int kn); -void kernel_ssyrk_spotrf_nt_l_20x4_vs_lib8(int kp, float *Ap, int sdap, float *Bp, int km_, float *Am, int sdam, float *Bm, float *C, int sdc, float *D, int sdd, float *inv_diag_D, int km, int kn); -void kernel_ssyrk_spotrf_nt_l_20x4_lib8(int kp, float *Ap, int sdap, float *Bp, int km_, float *Am, int sdam, float *Bm, float *C, int sdc, float *D, int sdd, float *inv_diag_D); -void kernel_ssyrk_spotrf_nt_l_24x4_vs_lib8(int kp, float *Ap, int sdap, float *Bp, int km_, float *Am, int sdam, float *Bm, float *C, int sdc, float *D, int sdd, float *inv_diag_D, int km, int kn); -void kernel_ssyrk_spotrf_nt_l_24x4_lib8(int kp, float *Ap, int sdap, float *Bp, int km_, float *Am, int sdam, float *Bm, float *C, int sdc, float *D, int sdd, float *inv_diag_D); -void kernel_strmm_nn_rl_24x4_lib8(int k, float *alpha, float *A, int sda, int offsetB, float *B, int sdb, float *D, int sdd); -void kernel_strmm_nn_rl_24x4_vs_lib8(int k, float *alpha, float *A, int sda, int offsetB, float *B, int sdb, float *D, int sdd, int km, int kn); - -// 16x8 -void kernel_sgemm_nt_16x8_lib8(int k, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd, float *spil); - -// 16x4 -void kernel_sgemm_nt_16x4_lib8(int k, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd); -void kernel_sgemm_nt_16x4_vs_lib8(int k, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd, int km, int kn); -void kernel_sgemm_nt_16x4_gen_lib8(int k, float *alpha, float *A, int sda, float *B, float *beta, int offsetC, float *C, int sdc, int offsetD, float *D, int sdd, int m0, int m1, int n0, int n1); -void kernel_sgemm_nn_16x4_lib8(int k, float *alpha, float *A, int sda, int offsetB, float *B, int sdb, float *beta, float *C, int sdc, float *D, int sdd); -void kernel_sgemm_nn_16x4_vs_lib8(int k, float *alpha, float *A, int sda, int offsetB, float *B, int sdb, float *beta, float *C, int sdc, float *D, int sdd, int km, int kn); -void kernel_sgemm_nn_16x4_gen_lib8(int k, float *alpha, float *A, int sda, int offsetB, float *B, int sdb, float *beta, int offsetC, float *C, int sdc, int offsetD, float *D, int sdd, int m0, int m1, int n0, int n1); -void kernel_ssyrk_nt_l_16x4_lib8(int k, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd); -void kernel_ssyrk_nt_l_16x4_vs_lib8(int k, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd, int km, int kn); -void kernel_ssyrk_nt_l_12x4_lib8(int k, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd); -void kernel_ssyrk_nt_l_12x4_vs_lib8(int k, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd, int km, int kn); -void kernel_spotrf_nt_l_16x4_lib8(int k, float *A, int sda, float *B, float *C, int sdc, float *D, int sdd, float *inv_diag_D); -void kernel_spotrf_nt_l_16x4_vs_lib8(int k, float *A, int sda, float *B, float *C, int sdc, float *D, int sdd, float *inv_diag_D, int km, int kn); -void kernel_spotrf_nt_l_12x4_lib8(int k, float *A, int sda, float *B, float *C, int sdc, float *D, int sdd, float *inv_diag_D); -void kernel_spotrf_nt_l_12x4_vs_lib8(int k, float *A, int sda, float *B, float *C, int sdc, float *D, int sdd, float *inv_diag_D, int km, int kn); -void kernel_strsm_nt_rl_inv_16x4_lib8(int k, float *A, int sda, float *B, float *C, int sdc, float *D, int sdd, float *E, float *inv_diag_E); -void kernel_strsm_nt_rl_inv_16x4_vs_lib8(int k, float *A, int sda, float *B, float *C, int sdc, float *D, int sdd, float *E, float *inv_diag_E, int km, int kn); -void kernel_sgemm_strsm_nt_rl_inv_16x4_lib8(int kp, float *Ap, int sdap, float *Bp, int km_, float *Am, int sdam, float *Bm, float *C, int sdc, float *D, int sdd, float *E, float *inv_diag_E); -void kernel_sgemm_strsm_nt_rl_inv_16x4_vs_lib8(int kp, float *Ap, int sdap, float *Bp, int km_, float *Am, int sdam, float *Bm, float *C, int sdc, float *D, int sdd, float *E, float *inv_diag_E, int km, int kn); -void kernel_ssyrk_spotrf_nt_l_12x4_vs_lib8(int kp, float *Ap, int sdap, float *Bp, int km_, float *Am, int sdam, float *Bm, float *C, int sdc, float *D, int sdd, float *inv_diag_D, int km, int kn); -void kernel_ssyrk_spotrf_nt_l_12x4_lib8(int kp, float *Ap, int sdap, float *Bp, int km_, float *Am, int sdam, float *Bm, float *C, int sdc, float *D, int sdd, float *inv_diag_D); -void kernel_ssyrk_spotrf_nt_l_16x4_vs_lib8(int kp, float *Ap, int sdap, float *Bp, int km_, float *Am, int sdam, float *Bm, float *C, int sdc, float *D, int sdd, float *inv_diag_D, int km, int kn); -void kernel_ssyrk_spotrf_nt_l_16x4_lib8(int kp, float *Ap, int sdap, float *Bp, int km_, float *Am, int sdam, float *Bm, float *C, int sdc, float *D, int sdd, float *inv_diag_D); -void kernel_strmm_nn_rl_16x4_lib8(int k, float *alpha, float *A, int sda, int offsetB, float *B, int sdb, float *D, int sdd); -void kernel_strmm_nn_rl_16x4_vs_lib8(int k, float *alpha, float *A, int sda, int offsetB, float *B, int sdb, float *D, int sdd, int km, int kn); -void kernel_strmm_nn_rl_16x4_gen_lib8(int k, float *alpha, float *A, int sda, int offsetB, float *B, int sdb, int offsetD, float *D, int sdd, int m0, int m1, int n0, int n1); - -// 8x8 -void kernel_sgemm_nt_8x8_lib8(int k, float *alpha, float *A, float *B, float *beta, float *C, float *D); -void kernel_sgemm_nt_8x8_vs_lib8(int k, float *alpha, float *A, float *B, float *beta, float *C, float *D, int km, int kn); -void kernel_sgemm_nt_8x8_gen_lib8(int k, float *alpha, float *A, float *B, float *beta, int offsetC, float *C, int sdc, int offsetD, float *D, int sdd, int m0, int m1, int n0, int n1); -void kernel_sgemm_nn_8x8_lib8(int k, float *alpha, float *A, int offsetB, float *B, int sdb, float *beta, float *C, float *D); -void kernel_sgemm_nn_8x8_vs_lib8(int k, float *alpha, float *A, int offsetB, float *B, int sdb, float *beta, float *C, float *D, int km, int kn); -void kernel_sgemm_nn_8x8_gen_lib8(int k, float *alpha, float *A, int offsetB, float *B, int sdb, float *beta, int offsetC, float *C, int sdc, int offsetD, float *D, int sdd, int m0, int m1, int n0, int n1); -void kernel_ssyrk_nt_l_8x8_lib8(int k, float *alpha, float *A, float *B, float *beta, float *C, float *D); -void kernel_ssyrk_nt_l_8x8_vs_lib8(int k, float *alpha, float *A, float *B, float *beta, float *C, float *D, int km, int kn); -void kernel_spotrf_nt_l_8x8_lib8(int k, float *A, float *B, float *C, float *D, float *inv_diag_D); -void kernel_spotrf_nt_l_8x8_vs_lib8(int k, float *A, float *B, float *C, float *D, float *inv_diag_D, int km, int kn); -void kernel_strsm_nt_rl_inv_8x8_lib8(int k, float *A, float *B, float *C, float *D, float *E, float *inv_diag_E); -void kernel_strsm_nt_rl_inv_8x8_vs_lib8(int k, float *A, float *B, float *C, float *D, float *E, float *inv_diag_E, int km, int kn); -void kernel_sgemm_strsm_nt_rl_inv_8x8_lib8(int kp, float *Ap, float *Bp, int km_, float *Am, float *Bm, float *C, float *D, float *E, float *inv_diag_E); -void kernel_sgemm_strsm_nt_rl_inv_8x8_vs_lib8(int kp, float *Ap, float *Bp, int km_, float *Am, float *Bm, float *C, float *D, float *E, float *inv_diag_E, int km, int kn); -void kernel_ssyrk_spotrf_nt_l_8x8_vs_lib8(int kp, float *Ap, float *Bp, int km_, float *Am, float *Bm, float *C, float *D, float *inv_diag_D, int km, int kn); -void kernel_ssyrk_spotrf_nt_l_8x8_lib8(int kp, float *Ap, float *Bp, int km_, float *Am, float *Bm, float *C, float *D, float *inv_diag_D); - -// 8x4 -void kernel_sgemm_nt_8x4_lib8(int k, float *alpha, float *A, float *B, float *beta, float *C, float *D); -void kernel_sgemm_nt_8x4_vs_lib8(int k, float *alpha, float *A, float *B, float *beta, float *C, float *D, int km, int kn); -void kernel_sgemm_nt_8x4_gen_lib8(int k, float *alpha, float *A, float *B, float *beta, int offsetC, float *C, int sdc, int offsetD, float *D, int sdd, int m0, int m1, int n0, int n1); -void kernel_sgemm_nn_8x4_lib8(int k, float *alpha, float *A, int offsetB, float *B, int sdb, float *beta, float *C, float *D); -void kernel_sgemm_nn_8x4_vs_lib8(int k, float *alpha, float *A, int offsetB, float *B, int sdb, float *beta, float *C, float *D, int km, int kn); -void kernel_sgemm_nn_8x4_gen_lib8(int k, float *alpha, float *A, int offsetB, float *B, int sdb, float *beta, int offsetC, float *C, int sdc, int offsetD, float *D, int sdd, int m0, int m1, int n0, int n1); -//void kernel_ssyrk_nt_l_8x4_lib8(int k, float *alpha, float *A, float *B, float *beta, float *C, float *D); -void kernel_ssyrk_nt_l_8x4_vs_lib8(int k, float *alpha, float *A, float *B, float *beta, float *C, float *D, int km, int kn); -void kernel_spotrf_nt_l_8x4_lib8(int k, float *A, float *B, float *C, float *D, float *inv_diag_D); -void kernel_spotrf_nt_l_8x4_vs_lib8(int k, float *A, float *B, float *C, float *D, float *inv_diag_D, int km, int kn); -void kernel_strsm_nt_rl_inv_8x4_lib8(int k, float *A, float *B, float *C, float *D, float *E, float *inv_diag_E); -void kernel_strsm_nt_rl_inv_8x4_vs_lib8(int k, float *A, float *B, float *C, float *D, float *E, float *inv_diag_E, int km, int kn); -void kernel_sgemm_strsm_nt_rl_inv_8x4_lib8(int kp, float *Ap, float *Bp, int km_, float *Am, float *Bm, float *C, float *D, float *E, float *inv_diag_E); -void kernel_sgemm_strsm_nt_rl_inv_8x4_vs_lib8(int kp, float *Ap, float *Bp, int km_, float *Am, float *Bm, float *C, float *D, float *E, float *inv_diag_E, int km, int kn); -void kernel_ssyrk_spotrf_nt_l_8x4_vs_lib8(int kp, float *Ap, float *Bp, int km_, float *Am, float *Bm, float *C, float *D, float *inv_diag_D, int km, int kn); -void kernel_ssyrk_spotrf_nt_l_8x4_lib8(int kp, float *Ap, float *Bp, int km_, float *Am, float *Bm, float *C, float *D, float *inv_diag_D); -void kernel_strmm_nn_rl_8x4_lib8(int k, float *alpha, float *A, int offsetB, float *B, int sdb, float *D); -void kernel_strmm_nn_rl_8x4_vs_lib8(int k, float *alpha, float *A, int offsetB, float *B, int sdb, float *D, int km, int kn); -void kernel_strmm_nn_rl_8x4_gen_lib8(int k, float *alpha, float *A, int offsetB, float *B, int sdb, int offsetD, float *D, int sdd, int m0, int m1, int n0, int n1); -void kernel_strmm_nt_ru_8x4_lib8(int k, float *alpha, float *A, float *B, float *D); -void kernel_strmm_nt_ru_8x4_vs_lib8(int k, float *alpha, float *A, float *B, float *D, int km, int kn); - -// 4x8 -void kernel_sgemm_nt_4x8_lib8(int k, float *alpha, float *A, float *B, float *beta, float *C, float *D); -void kernel_sgemm_nt_4x8_vs_lib8(int k, float *alpha, float *A, float *B, float *beta, float *C, float *D, int km, int kn); -void kernel_sgemm_nt_4x8_gen_lib8(int k, float *alpha, float *A, float *B, float *beta, int offsetC, float *C, int sdc, int offsetD, float *D, int sdd, int m0, int m1, int n0, int n1); -void kernel_strsm_nt_rl_inv_4x8_lib8(int k, float *A, float *B, float *C, float *D, float *E, float *inv_diag_E); -void kernel_strsm_nt_rl_inv_4x8_vs_lib8(int k, float *A, float *B, float *C, float *D, float *E, float *inv_diag_E, int km, int kn); - -// 8 -void kernel_sgemv_n_8_lib8(int k, float *alpha, float *A, float *x, float *beta, float *y, float *z); -void kernel_sgemv_n_8_vs_lib8(int k, float *alpha, float *A, float *x, float *beta, float *y, float *z, int k1); -void kernel_sgemv_n_8_gen_lib8(int kmax, float *alpha, float *A, float *x, float *beta, float *y, float *z, int k0, int k1); -void kernel_sgemv_t_8_lib8(int k, float *alpha, int offsetA, float *A, int sda, float *x, float *beta, float *y, float *z); -void kernel_sgemv_t_8_vs_lib8(int k, float *alpha, int offsetA, float *A, int sda, float *x, float *beta, float *y, float *z, int k1); -void kernel_sgemv_t_4_lib8(int k, float *alpha, int offsetA, float *A, int sda, float *x, float *beta, float *y, float *z); -void kernel_sgemv_t_4_vs_lib8(int k, float *alpha, int offsetA, float *A, int sda, float *x, float *beta, float *y, float *z, int k1); -void kernel_strsv_ln_inv_8_lib8(int k, float *A, float *inv_diag_A, float *x, float *y, float *z); -void kernel_strsv_ln_inv_8_vs_lib8(int k, float *A, float *inv_diag_A, float *x, float *y, float *z, int km, int kn); -void kernel_strsv_lt_inv_8_lib8(int k, float *A, int sda, float *inv_diag_A, float *x, float *y, float *z); -void kernel_strsv_lt_inv_8_vs_lib8(int k, float *A, int sda, float *inv_diag_A, float *x, float *y, float *z, int km, int kn); -void kernel_sgemv_nt_4_lib8(int kmax, float *alpha_n, float *alpha_t, float *A, int sda, float *x_n, float *x_t, float *beta_t, float *y_t, float *z_n, float *z_t); -void kernel_sgemv_nt_4_vs_lib8(int kmax, float *alpha_n, float *alpha_t, float *A, int sda, float *x_n, float *x_t, float *beta_t, float *y_t, float *z_n, float *z_t, int km); -void kernel_ssymv_l_4l_lib8(int kmax, float *alpha, float *A, int sda, float *x, float *z); -void kernel_ssymv_l_4r_lib8(int kmax, float *alpha, float *A, int sda, float *x, float *z); -void kernel_ssymv_l_4l_gen_lib8(int kmax, float *alpha, int offA, float *A, int sda, float *x, float *z, int km); -void kernel_ssymv_l_4r_gen_lib8(int kmax, float *alpha, int offA, float *A, int sda, float *x, float *z, int km); - -// -------- aux - -// ---- copy - -// lib4 -// -void kernel_sgecpsc_4_0_lib4(int kmax, float *alpha, float *A, float *B); -void kernel_sgecp_4_0_lib4(int kmax, float *A, float *B); - -void kernel_sgecpsc_4_1_lib4(int kmax, float *alpha, float *A0, int sda, float *B); -void kernel_sgecp_4_1_lib4(int kmax, float *A0, int sda, float *B); -void kernel_sgecpsc_4_2_lib4(int kmax, float *alpha, float *A0, int sda, float *B); -void kernel_sgecp_4_2_lib4(int kmax, float *A0, int sda, float *B); -void kernel_sgecpsc_4_3_lib4(int kmax, float *alpha, float *A0, int sda, float *B); -void kernel_sgecp_4_3_lib4(int kmax, float *A0, int sda, float *B); - -void kernel_sgecpsc_3_0_lib4(int kmax, float *alpha, float *A, float *B); -void kernel_sgecp_3_0_lib4(int kmax, float *A, float *B); -void kernel_sgecpsc_3_2_lib4(int kmax, float *alpha, float *A0, int sda, float *B); -void kernel_sgecp_3_2_lib4(int kmax, float *A0, int sda, float *B); -void kernel_sgecpsc_3_3_lib4(int kmax, float *alpha, float *A0, int sda, float *B); -void kernel_sgecp_3_3_lib4(int kmax, float *A0, int sda, float *B); - -void kernel_sgecpsc_2_0_lib4(int kmax, float *alpha, float *A, float *B); -void kernel_sgecp_2_0_lib4(int kmax, float *A, float *B); -void kernel_sgecpsc_2_3_lib4(int kmax, float *alpha, float *A0, int sda, float *B); -void kernel_sgecp_2_3_lib4(int kmax, float *A0, int sda, float *B); - -void kernel_sgecpsc_1_0_lib4(int kmax, float *alpha, float *A, float *B); -void kernel_sgecp_1_0_lib4(int kmax, float *A, float *B); - -// lib8 -// -void kernel_sgecp_8_0_lib8(int m, float *A, float *B); -void kernel_sgecp_8_0_gen_lib8(int m, float *A, float *B, int m1); -void kernel_sgecp_8_0_gen_u_lib8(int m, float *A, float *B, int m1); - -void kernel_sgesc_8_0_lib8(int m, float *alpha, float *A); -void kernel_sgesc_8_0_gen_lib8(int m, float *alpha, float *A, int m1); -void kernel_sgesc_8_0_gen_u_lib8(int m, float *alpha, float *A, int m1); - -void kernel_sgecpsc_8_0_lib8(int m, float *alpha, float *A, float *B); -void kernel_sgecpsc_8_0_gen_lib8(int m, float *alpha, float *A, float *B, int m1); -void kernel_sgecpsc_8_0_gen_u_lib8(int m, float *alpha, float *A, float *B, int m1); - -void kernel_sgecp_8_1_lib8(int m, float *A, int sda, float *B); -void kernel_sgecp_8_1_gen_lib8(int m, float *A, int sda, float *B, int m1); -void kernel_sgecpsc_8_1_lib8(int m, float *alpha, float *A, int sda, float *B); -void kernel_sgecpsc_8_1_gen_lib8(int m, float *alpha, float *A, int sda, float *B, int m1); - -void kernel_sgecp_8_2_lib8(int m, float *A, int sda, float *B); -void kernel_sgecp_8_2_gen_lib8(int m, float *A, int sda, float *B, int m1); -void kernel_sgecpsc_8_2_lib8(int m, float *alpha, float *A, int sda, float *B); -void kernel_sgecpsc_8_2_gen_lib8(int m, float *alpha, float *A, int sda, float *B, int m1); - -void kernel_sgecp_8_3_lib8(int m, float *A, int sda, float *B); -void kernel_sgecp_8_3_gen_lib8(int m, float *A, int sda, float *B, int m1); -void kernel_sgecpsc_8_3_lib8(int m, float *alpha, float *A, int sda, float *B); -void kernel_sgecpsc_8_3_gen_lib8(int m, float *alpha, float *A, int sda, float *B, int m1); - -void kernel_sgecp_8_4_lib8(int m, float *A, int sda, float *B); -void kernel_sgecp_8_4_gen_lib8(int m, float *A, int sda, float *B, int m1); -void kernel_sgecpsc_8_4_lib8(int m, float *alpha, float *A, int sda, float *B); -void kernel_sgecpsc_8_4_gen_lib8(int m, float *alpha, float *A, int sda, float *B, int m1); - -void kernel_sgecp_8_5_lib8(int m, float *A, int sda, float *B); -void kernel_sgecp_8_5_gen_lib8(int m, float *A, int sda, float *B, int m1); -void kernel_sgecpsc_8_5_lib8(int m, float *alpha, float *A, int sda, float *B); -void kernel_sgecpsc_8_5_gen_lib8(int m, float *alpha, float *A, int sda, float *B, int m1); - -void kernel_sgecp_8_6_lib8(int m, float *A, int sda, float *B); -void kernel_sgecp_8_6_gen_lib8(int m, float *A, int sda, float *B, int m1); -void kernel_sgecpsc_8_6_lib8(int m, float *alpha, float *A, int sda, float *B); -void kernel_sgecpsc_8_6_gen_lib8(int m, float *alpha, float *A, int sda, float *B, int m1); - -void kernel_sgecp_8_7_lib8(int m, float *A, int sda, float *B); -void kernel_sgecp_8_7_gen_lib8(int m, float *A, int sda, float *B, int m1); -void kernel_sgecpsc_8_7_lib8(int m, float *alpha, float *A, int sda, float *B); -void kernel_sgecpsc_8_7_gen_lib8(int m, float *alpha, float *A, int sda, float *B, int m1); - -// transpose -// -void kernel_sgetr_8_0_lib8(int m, float *A, int sda, float *B); -void kernel_sgetr_8_0_gen_lib8(int m, float *A, int sda, float *B, int m1); -void kernel_sgetr_8_1_lib8(int m, float *A, int sda, float *B); -void kernel_sgetr_8_1_gen_lib8(int m, float *A, int sda, float *B, int m1); -void kernel_sgetr_8_2_lib8(int m, float *A, int sda, float *B); -void kernel_sgetr_8_2_gen_lib8(int m, float *A, int sda, float *B, int m1); -void kernel_sgetr_8_3_lib8(int m, float *A, int sda, float *B); -void kernel_sgetr_8_3_gen_lib8(int m, float *A, int sda, float *B, int m1); -void kernel_sgetr_8_4_lib8(int m, float *A, int sda, float *B); -void kernel_sgetr_8_4_gen_lib8(int m, float *A, int sda, float *B, int m1); -void kernel_sgetr_8_5_lib8(int m, float *A, int sda, float *B); -void kernel_sgetr_8_5_gen_lib8(int m, float *A, int sda, float *B, int m1); -void kernel_sgetr_8_6_lib8(int m, float *A, int sda, float *B); -void kernel_sgetr_8_6_gen_lib8(int m, float *A, int sda, float *B, int m1); -void kernel_sgetr_8_7_lib8(int m, float *A, int sda, float *B); -void kernel_sgetr_8_7_gen_lib8(int m, float *A, int sda, float *B, int m1); - -// add -// -void kernel_sgead_8_0_lib8(int m, float *alpha, float *A, float *B); -void kernel_sgead_8_0_gen_lib8(int m, float *alpha, float *A, float *B, int m1); -void kernel_sgead_8_1_lib8(int m, float *alpha, float *A, int sda, float *B); -void kernel_sgead_8_1_gen_lib8(int m, float *alpha, float *A, int sda, float *B, int m1); -void kernel_sgead_8_2_lib8(int m, float *alpha, float *A, int sda, float *B); -void kernel_sgead_8_2_gen_lib8(int m, float *alpha, float *A, int sda, float *B, int m1); -void kernel_sgead_8_3_lib8(int m, float *alpha, float *A, int sda, float *B); -void kernel_sgead_8_3_gen_lib8(int m, float *alpha, float *A, int sda, float *B, int m1); -void kernel_sgead_8_4_lib8(int m, float *alpha, float *A, int sda, float *B); -void kernel_sgead_8_4_gen_lib8(int m, float *alpha, float *A, int sda, float *B, int m1); -void kernel_sgead_8_5_lib8(int m, float *alpha, float *A, int sda, float *B); -void kernel_sgead_8_5_gen_lib8(int m, float *alpha, float *A, int sda, float *B, int m1); -void kernel_sgead_8_6_lib8(int m, float *alpha, float *A, int sda, float *B); -void kernel_sgead_8_6_gen_lib8(int m, float *alpha, float *A, int sda, float *B, int m1); -void kernel_sgead_8_7_lib8(int m, float *alpha, float *A, int sda, float *B); -void kernel_sgead_8_7_gen_lib8(int m, float *alpha, float *A, int sda, float *B, int m1); - - -// -// lib4 -// - - - -// level 2 BLAS -// 4 -void kernel_sgemv_n_4_lib4(int k, float *alpha, float *A, float *x, float *beta, float *y, float *z); -void kernel_sgemv_n_4_vs_lib4(int k, float *alpha, float *A, float *x, float *beta, float *y, float *z, int k1); -void kernel_sgemv_n_4_gen_lib4(int kmax, float *alpha, float *A, float *x, float *beta, float *y, float *z, int k0, int k1); -void kernel_sgemv_t_4_lib4(int k, float *alpha, int offsetA, float *A, int sda, float *x, float *beta, float *y, float *z); -void kernel_sgemv_t_4_vs_lib4(int k, float *alpha, int offsetA, float *A, int sda, float *x, float *beta, float *y, float *z, int k1); -void kernel_strsv_ln_inv_4_lib4(int k, float *A, float *inv_diag_A, float *x, float *y, float *z); -void kernel_strsv_ln_inv_4_vs_lib4(int k, float *A, float *inv_diag_A, float *x, float *y, float *z, int km, int kn); -void kernel_strsv_lt_inv_4_lib4(int k, float *A, int sda, float *inv_diag_A, float *x, float *y, float *z); -void kernel_strsv_lt_inv_3_lib4(int k, float *A, int sda, float *inv_diag_A, float *x, float *y, float *z); -void kernel_strsv_lt_inv_2_lib4(int k, float *A, int sda, float *inv_diag_A, float *x, float *y, float *z); -void kernel_strsv_lt_inv_1_lib4(int k, float *A, int sda, float *inv_diag_A, float *x, float *y, float *z); -void kernel_strmv_un_4_lib4(int k, float *A, float *x, float *z); -void kernel_strmv_ut_4_lib4(int k, float *A, int sda, float *x, float *z); -void kernel_strmv_ut_4_vs_lib4(int k, float *A, int sda, float *x, float *z, int km); -void kernel_sgemv_nt_6_lib4(int kmax, float *alpha_n, float *alpha_t, float *A, int sda, float *x_n, float *x_t, float *beta_t, float *y_t, float *z_n, float *z_t); -void kernel_sgemv_nt_4_lib4(int kmax, float *alpha_n, float *alpha_t, float *A, int sda, float *x_n, float *x_t, float *beta_t, float *y_t, float *z_n, float *z_t); -void kernel_sgemv_nt_4_vs_lib4(int kmax, float *alpha_n, float *alpha_t, float *A, int sda, float *x_n, float *x_t, float *beta_t, float *y_t, float *z_n, float *z_t, int km); -void kernel_ssymv_l_4_lib4(int kmax, float *alpha, float *A, int sda, float *x_n, float *z_n); -void kernel_ssymv_l_4_gen_lib4(int kmax, float *alpha, int offA, float *A, int sda, float *x_n, float *z_n, int km); - - - -// level 3 BLAS -// 12x4 -void kernel_sgemm_nt_16x4_lib4(int k, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd); // -void kernel_sgemm_nt_16x4_vs_lib4(int k, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd, int m1, int n1); // -void kernel_strsm_nt_rl_inv_16x4_lib4(int k, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd, float *E, float *inv_diag_E); -void kernel_strsm_nt_rl_inv_16x4_vs_lib4(int k, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd, float *E, float *inv_diag_E, int m1, int n1); -// 12x4 -void kernel_sgemm_nt_12x4_lib4(int k, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd); // -void kernel_sgemm_nt_12x4_vs_lib4(int k, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd, int m1, int n1); // -void kernel_strsm_nt_rl_inv_12x4_lib4(int k, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd, float *E, float *inv_diag_E); -void kernel_strsm_nt_rl_inv_12x4_vs_lib4(int k, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd, float *E, float *inv_diag_E, int m1, int n1); -// 8x8 -void kernel_sgemm_nt_8x8_lib4(int k, float *alpha, float *A, int sda, float *B, int sdb, float *beta, float *C, int sdc, float *D, int sdd); // -void kernel_sgemm_nt_8x8_vs_lib4(int k, float *alpha, float *A, int sda, float *B, int sdb, float *beta, float *C, int sdc, float *D, int sdd, int m1, int n1); // -void kernel_sgemm_nn_8x8_lib4(int k, float *alpha, float *A, int sda, int offsetB, float *B, int sdb, float *beta, float *C, int sdc, float *D, int sdd); // -void kernel_sgemm_nn_8x8_vs_lib4(int k, float *alpha, float *A, int sda, int offsetB, float *B, int sdb, float *beta, float *C, int sdc, float *D, int sdd, int m1, int n1); // -// 8x4 -void kernel_sgemm_nt_8x4_lib4(int k, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd); // -void kernel_sgemm_nt_8x4_vs_lib4(int k, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd, int m1, int n1); // -void kernel_sgemm_nn_8x4_lib4(int k, float *alpha, float *A, int sda, int offsetB, float *B, int sdb, float *beta, float *C, int sdc, float *D, int sdd); // -void kernel_sgemm_nn_8x4_vs_lib4(int k, float *alpha, float *A, int sda, int offsetB, float *B, int sdb, float *beta, float *C, int sdc, float *D, int sdd, int m1, int n1); // -void kernel_ssyrk_nt_l_8x4_lib4(int k, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd); // -void kernel_ssyrk_nt_l_8x4_vs_lib4(int k, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd, int km, int kn); // -void kernel_strsm_nt_rl_inv_8x4_lib4(int k, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd, float *E, float *inv_diag_E); -void kernel_strsm_nt_rl_inv_8x4_vs_lib4(int k, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd, float *E, float *inv_diag_E, int m1, int n1); -// 4x4 -void kernel_sgemm_nt_4x4_lib4(int k, float *alpha, float *A, float *B, float *beta, float *C, float *D); // -void kernel_sgemm_nt_4x4_vs_lib4(int k, float *alpha, float *A, float *B, float *beta, float *C, float *D, int km, int kn); // -void kernel_sgemm_nt_4x4_gen_lib4(int k, float *alpha, float *A, float *B, float *beta, int offsetC, float *C, int sdc, int offsetD, float *D, int sdd, int m0, int m1, int k0, int k1); -void kernel_sgemm_nn_4x4_lib4(int k, float *alpha, float *A, int offsetB, float *B, int sdb, float *beta, float *C, float *D); // -void kernel_sgemm_nn_4x4_vs_lib4(int k, float *alpha, float *A, int offsetB, float *B, int sdb, float *beta, float *C, float *D, int km, int kn); // -void kernel_sgemm_nn_4x4_gen_lib4(int k, float *alpha, float *A, int offsetB, float *B, int sdb, float *beta, int offsetC, float *C, int sdc, int offsetD, float *D, int sdd, int m0, int m1, int n0, int n1); // -void kernel_ssyrk_nt_l_4x4_lib4(int k, float *alpha, float *A, float *B, float *beta, float *C, float *D); // -void kernel_ssyrk_nt_l_4x4_vs_lib4(int k, float *alpha, float *A, float *B, float *beta, float *C, float *D, int km, int kn); // -void kernel_ssyrk_nt_l_4x4_gen_lib4(int k, float *alpha, float *A, float *B, float *beta, int offsetC, float *C, int sdc, int offsetD, float *D, int sdd, int m0, int m1, int n0, int n1); -void kernel_strmm_nt_ru_4x4_lib4(int k, float *alpha, float *A, float *B, float *D); // -void kernel_strmm_nt_ru_4x4_vs_lib4(int k, float *alpha, float *A, float *B, float *D, int km, int kn); // -void kernel_strmm_nn_rl_4x4_lib4(int k, float *alpha, float *A, int offsetB, float *B, int sdb, float *D); -void kernel_strmm_nn_rl_4x4_gen_lib4(int k, float *alpha, float *A, int offsetB, float *B, int sdb, int offsetD, float *D, int sdd, int m0, int m1, int n0, int n1); -void kernel_strsm_nt_rl_inv_4x4_lib4(int k, float *A, float *B, float *beta, float *C, float *D, float *E, float *inv_diag_E); -void kernel_strsm_nt_rl_inv_4x4_vs_lib4(int k, float *A, float *B, float *beta, float *C, float *D, float *E, float *inv_diag_E, int km, int kn); -void kernel_strsm_nt_rl_one_4x4_lib4(int k, float *A, float *B, float *beta, float *C, float *D, float *E); -void kernel_strsm_nt_rl_one_4x4_vs_lib4(int k, float *A, float *B, float *beta, float *C, float *D, float *E, int km, int kn); -void kernel_strsm_nt_ru_inv_4x4_lib4(int k, float *A, float *B, float *beta, float *C, float *D, float *E, float *inv_diag_E); -void kernel_strsm_nt_ru_inv_4x4_vs_lib4(int k, float *A, float *B, float *beta, float *C, float *D, float *E, float *inv_diag_E, int km, int kn); -void kernel_strsm_nt_ru_one_4x4_lib4(int k, float *A, float *B, float *beta, float *C, float *D, float *E); -void kernel_strsm_nt_ru_one_4x4_vs_lib4(int k, float *A, float *B, float *beta, float *C, float *D, float *E, int km, int kn); -void kernel_strsm_nn_ru_inv_4x4_lib4(int k, float *A, float *B, int sdb, float *beta, float *C, float *D, float *E, float *inv_diag_E); -void kernel_strsm_nn_ru_inv_4x4_vs_lib4(int k, float *A, float *B, int sdb, float *beta, float *C, float *D, float *E, float *inv_diag_E, int km, int kn); -void kernel_strsm_nn_ll_one_4x4_lib4(int k, float *A, float *B, int sdb, float *C, float *D, float *E); -void kernel_strsm_nn_ll_one_4x4_vs_lib4(int k, float *A, float *B, int sdb, float *C, float *D, float *E, int km, int kn); -void kernel_strsm_nn_lu_inv_4x4_lib4(int kmax, float *A, float *B, int sdb, float *C, float *D, float *E, float *inv_diag_E); -void kernel_strsm_nn_lu_inv_4x4_vs_lib4(int kmax, float *A, float *B, int sdb, float *C, float *D, float *E, float *inv_diag_E, int km, int kn); -// diag -void kernel_sgemm_diag_right_4_a0_lib4(int kmax, float *alpha, float *A, int sda, float *B, float *D, int sdd); -void kernel_sgemm_diag_right_4_lib4(int kmax, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd); -void kernel_sgemm_diag_right_3_lib4(int kmax, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd); -void kernel_sgemm_diag_right_2_lib4(int kmax, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd); -void kernel_sgemm_diag_right_1_lib4(int kmax, float *alpha, float *A, int sda, float *B, float *beta, float *C, int sdc, float *D, int sdd); -void kernel_sgemm_diag_left_4_a0_lib4(int kmax, float *alpha, float *A, float *B, float *D); -void kernel_sgemm_diag_left_4_lib4(int kmax, float *alpha, float *A, float *B, float *beta, float *C, float *D); -void kernel_sgemm_diag_left_3_lib4(int kmax, float *alpha, float *A, float *B, float *beta, float *C, float *D); -void kernel_sgemm_diag_left_2_lib4(int kmax, float *alpha, float *A, float *B, float *beta, float *C, float *D); -void kernel_sgemm_diag_left_1_lib4(int kmax, float *alpha, float *A, float *B, float *beta, float *C, float *D); - - - -// LAPACK -// 16x4 -void kernel_spotrf_nt_l_16x4_lib4(int k, float *A, int sda, float *B, float *C, int sdc, float *D, int sdd, float *inv_diag_D); -void kernel_spotrf_nt_l_16x4_vs_lib4(int k, float *A, int sda, float *B, float *C, int sdc, float *D, int sdd, float *inv_diag_D, int m1, int n1); -// 12x4 -void kernel_spotrf_nt_l_12x4_lib4(int k, float *A, int sda, float *B, float *C, int sdc, float *D, int sdd, float *inv_diag_D); -void kernel_spotrf_nt_l_12x4_vs_lib4(int k, float *A, int sda, float *B, float *C, int sdc, float *D, int sdd, float *inv_diag_D, int m1, int n1); -// 8x4 -void kernel_spotrf_nt_l_8x4_lib4(int k, float *A, int sda, float *B, float *C, int sdc, float *D, int sdd, float *inv_diag_D); -void kernel_spotrf_nt_l_8x4_vs_lib4(int k, float *A, int sda, float *B, float *C, int sdc, float *D, int sdd, float *inv_diag_D, int m1, int n1); -// 4x4 -void kernel_spotrf_nt_l_4x4_lib4(int k, float *A, float *B, float *C, float *D, float *inv_diag_D); -void kernel_spotrf_nt_l_4x4_vs_lib4(int k, float *A, float *B, float *C, float *D, float *inv_diag_D, int km, int kn); -void kernel_sgetrf_nn_4x4_lib4(int k, float *A, float *B, int sdb, float *C, float *D, float *inv_diag_D); -void kernel_sgetrf_nn_4x4_vs_lib4(int k, float *A, float *B, int sdb, float *C, float *D, float *inv_diag_D, int km, int kn); -void kernel_sgetrf_pivot_4_lib4(int m, float *pA, int sda, float *inv_diag_A, int* ipiv); -void kernel_sgetrf_pivot_4_vs_lib4(int m, int n, float *pA, int sda, float *inv_diag_A, int* ipiv); - - - -// merged routines -// 4x4 -void kernel_sgemm_strsm_nt_rl_inv_4x4_lib4(int kp, float *Ap, float *Bp, int km_, float *Am, float *Bm, float *C, float *D, float *E, float *inv_diag_E); -void kernel_sgemm_strsm_nt_rl_inv_4x4_vs_lib4(int kp, float *Ap, float *Bp, int km_, float *Am, float *Bm, float *C, float *D, float *E, float *inv_diag_E, int km, int kn); -void kernel_ssyrk_spotrf_nt_l_4x4_vs_lib4(int kp, float *Ap, float *Bp, int km_, float *Am, float *Bm, float *C, float *D, float *inv_diag_D, int km, int kn); -void kernel_ssyrk_spotrf_nt_l_4x4_lib4(int kp, float *Ap, float *Bp, int km_, float *Am, float *Bm, float *C, float *D, float *inv_diag_D); - - - -// auxiliary routines -void kernel_strcp_l_4_0_lib4(int kmax, float *A, float *B); -void kernel_strcp_l_4_1_lib4(int kmax, float *A0, int sda, float *B); -void kernel_strcp_l_4_2_lib4(int kmax, float *A0, int sda, float *B); -void kernel_strcp_l_4_3_lib4(int kmax, float *A0, int sda, float *B); -void kernel_strcp_l_3_0_lib4(int kmax, float *A, float *B); -void kernel_strcp_l_3_2_lib4(int kmax, float *A0, int sda, float *B); -void kernel_strcp_l_3_3_lib4(int kmax, float *A0, int sda, float *B); -void kernel_strcp_l_2_0_lib4(int kmax, float *A, float *B); -void kernel_strcp_l_2_3_lib4(int kmax, float *A0, int sda, float *B); -void kernel_strcp_l_1_0_lib4(int kmax, float *A, float *B); -void kernel_sgead_4_0_lib4(int kmax, float *alpha, float *A, float *B); -void kernel_sgead_4_1_lib4(int kmax, float *alpha, float *A0, int sda, float *B); -void kernel_sgead_4_2_lib4(int kmax, float *alpha, float *A0, int sda, float *B); -void kernel_sgead_4_3_lib4(int kmax, float *alpha, float *A0, int sda, float *B); -void kernel_sgead_3_0_lib4(int kmax, float *alpha, float *A, float *B); -void kernel_sgead_3_2_lib4(int kmax, float *alpha, float *A0, int sda, float *B); -void kernel_sgead_3_3_lib4(int kmax, float *alpha, float *A0, int sda, float *B); -void kernel_sgead_2_0_lib4(int kmax, float *alpha, float *A, float *B); -void kernel_sgead_2_3_lib4(int kmax, float *alpha, float *A0, int sda, float *B); -void kernel_sgead_1_0_lib4(int kmax, float *alpha, float *A, float *B); -// TODO -void kernel_sgeset_4_lib4(int kmax, float alpha, float *A); -void kernel_strset_4_lib4(int kmax, float alpha, float *A); -void kernel_sgetr_4_lib4(int tri, int kmax, int kna, float alpha, float *A, float *C, int sdc); -void kernel_sgetr_3_lib4(int tri, int kmax, int kna, float alpha, float *A, float *C, int sdc); -void kernel_sgetr_2_lib4(int tri, int kmax, int kna, float alpha, float *A, float *C, int sdc); -void kernel_sgetr_1_lib4(int tri, int kmax, int kna, float alpha, float *A, float *C, int sdc); - - - -// pack -// 24 lib 8 -void kernel_spack_nn_24_lib8(int kmax, float *A, int lda, float *B, int sdb); -void kernel_spack_nn_24_vs_lib8(int kmax, float *A, int lda, float *B, int sdb, int m1); -// 16 lib 8 -void kernel_spack_nn_16_lib8(int kmax, float *A, int lda, float *B, int sdb); -void kernel_spack_nn_16_vs_lib8(int kmax, float *A, int lda, float *B, int sdb, int m1); -// 8 lib 8 -void kernel_spack_nn_8_lib8(int kmax, float *A, int lda, float *B); -void kernel_spack_nn_8_vs_lib8(int kmax, float *A, int lda, float *B, int m1); -void kernel_spack_tn_8_lib8(int kmax, float *A, int lda, float *B); -void kernel_spack_tn_8_vs_lib8(int kmax, float *A, int lda, float *B, int m1); -void kernel_spack_tt_8_lib8(int kmax, float *A, int lda, float *B, int sdb); -void kernel_spack_tt_8_vs_lib8(int kmax, float *A, int lda, float *B, int sdb, int m1); -// 8 lib 4 -void kernel_spack_nn_8_lib4(int kmax, float *A, int lda, float *B, int sdb); -void kernel_spack_nn_8_vs_lib4(int kmax, float *A, int lda, float *B, int sdb, int m1); -//void kernel_spack_tt_8_lib4(int kmax, float *A, int lda, float *B, int sdb); -// 4 -void kernel_spack_nn_4_lib4(int kmax, float *A, int lda, float *B); -void kernel_spack_nn_4_vs_lib4(int kmax, float *A, int lda, float *B, int m1); -void kernel_spack_tn_4_lib4(int kmax, float *A, int lda, float *B); -void kernel_spack_tn_4_vs_lib4(int kmax, float *A, int lda, float *B, int m1); -void kernel_spack_tt_4_lib4(int kmax, float *A, int lda, float *B, int sdb); -void kernel_spack_tt_4_vs_lib4(int kmax, float *A, int lda, float *B, int sdb, int m1); -// unpack -// 8 -void kernel_sunpack_nn_8_lib4(int kmax, float *A, int sda, float *B, int ldb); -void kernel_sunpack_nn_8_vs_lib4(int kmax, float *A, int sda, float *B, int ldb, int m1); -//void kernel_sunpack_tt_8_lib4(int kmax, float *A, int sda, float *B, int ldb); -// 4 -void kernel_sunpack_nn_4_lib4(int kmax, float *A, float *B, int ldb); -void kernel_sunpack_nn_4_vs_lib4(int kmax, float *A, float *B, int ldb, int m1); -void kernel_sunpack_nt_4_lib4(int kmax, float *A, float *B, int ldb); -void kernel_sunpack_nt_4_vs_lib4(int kmax, float *A, float *B, int ldb, int m1); -void kernel_sunpack_tt_4_lib4(int kmax, float *A, int sda, float *B, int ldb); - -// panel copy -// 4 -void kernel_spacp_nt_4_lib4(int kmax, float *A, int offsetB, float *B, int sdb); -void kernel_spacp_tn_4_lib4(int kmax, int offsetA, float *A, int sda, float *B); -void kernel_spacp_nn_4_lib4(int kmax, int offsetA, float *A, int sda, float *B); -void kernel_spacp_nn_4_vs_lib4(int kmax, int offsetA, float *A, int sda, float *B, int m1); - - - -/************************************************ -* BLAS API kernels -************************************************/ - -//#if defined(BLAS_API) - -// A, B panel-major bs=8; C, D column-major -// 24x4 -void kernel_sgemm_nt_24x4_lib88cc(int kmax, float *alpha, float *A, int sda, float *B, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nt_24x4_vs_lib88cc(int kmax, float *alpha, float *A, int sda, float *B, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -// 16x4 -void kernel_sgemm_nt_16x4_lib88cc(int kmax, float *alpha, float *A, int sda, float *B, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nt_16x4_vs_lib88cc(int kmax, float *alpha, float *A, int sda, float *B, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -// 8x8 -void kernel_sgemm_nt_8x8_lib88cc(int kmax, float *alpha, float *A, float *B, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nt_8x8_vs_lib88cc(int kmax, float *alpha, float *A, float *B, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -void kernel_spotrf_nt_l_8x8_lib88cc(int kmax, float *A, float *B, float *C, int ldc, float *D, int ldd, float *dD); -void kernel_spotrf_nt_l_8x8_vs_lib88cc(int kmax, float *A, float *B, float *C, int ldc, float *D, int ldd, float *dD, int m1, int n1); -void kernel_strsm_nt_rl_inv_8x8_lib88ccc(int kmax, float *A, float *B, float *C, int ldc, float *D, int ldd, float *E, int lde, float *dE); -void kernel_strsm_nt_rl_inv_8x8_vs_lib88ccc(int kmax, float *A, float *B, float *C, int ldc, float *D, int ldd, float *E, int lde, float *dE, int m1, int n1); -// 8x4 -void kernel_sgemm_nt_8x4_lib88cc(int kmax, float *alpha, float *A, float *B, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nt_8x4_vs_lib88cc(int kmax, float *alpha, float *A, float *B, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); - -// A, B panel-major bs=4; C, D column-major -// 8x8 -void kernel_sgemm_nt_8x8_lib44cc(int kmax, float *alpha, float *A, int sda, float *B, int sdb, float *beta, float *C, int ldc, float *D, int ldd); -// 8x4 -void kernel_sgemm_nt_8x4_lib44cc(int kmax, float *alpha, float *A, int sda, float *B, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nt_8x4_vs_lib44cc(int kmax, float *alpha, float *A, int sda, float *B, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -void kernel_spotrf_nt_l_8x4_lib44cc(int kmax, float *A, int sda, float *B, float *C, int ldc, float *D, int ldd, float *dD); -void kernel_strsm_nt_rl_inv_8x4_lib44ccc(int kmax, float *A, int sda, float *B, float *beta, float *C, int ldc, float *D, int ldd, float *E, int lde, float *dE); -void kernel_strsm_nt_rl_inv_8x4_vs_lib44ccc(int kmax, float *A, int sda, float *B, float *beta, float *C, int ldc, float *D, int ldd, float *E, int lde, float *dE, int m1, int n1); -// 4x4 -void kernel_sgemm_nt_4x4_lib44cc(int kmax, float *alpha, float *A, float *B, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nt_4x4_vs_lib44cc(int kmax, float *alpha, float *A, float *B, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -void kernel_strsm_nt_rl_inv_4x4_lib44cc4(int kmax, float *A, float *B, float *beta, float *C, int ldc, float *D, int ldd, float *E, float *dE); -void kernel_strsm_nt_rl_inv_4x4_vs_lib44cc4(int kmax, float *A, float *B, float *beta, float *C, int ldc, float *D, int ldd, float *E, float *dE, int m1, int n1); -void kernel_strsm_nt_rl_inv_4x4_lib44ccc(int kmax, float *A, float *B, float *beta, float *C, int ldc, float *D, int ldd, float *E, int lde, float *dE); -void kernel_strsm_nt_rl_inv_4x4_vs_lib44ccc(int kmax, float *A, float *B, float *beta, float *C, int ldc, float *D, int ldd, float *E, int lde, float *dE, int m1, int n1); -void kernel_strsm_nt_rl_one_4x4_lib44cc4(int kmax, float *A, float *B, float *beta, float *C, int ldc, float *D, int ldd, float *E); -void kernel_strsm_nt_rl_one_4x4_vs_lib44cc4(int kmax, float *A, float *B, float *beta, float *C, int ldc, float *D, int ldd, float *E, int m1, int n1); -void kernel_strsm_nt_ru_inv_4x4_lib44cc4(int kmax, float *A, float *B, float *beta, float *C, int ldc, float *D, int ldd, float *E, float *dE); -void kernel_strsm_nt_ru_inv_4x4_vs_lib44cc4(int kmax, float *A, float *B, float *beta, float *C, int ldc, float *D, int ldd, float *E, float *dE, int m1, int n1); -void kernel_strsm_nt_ru_one_4x4_lib44cc4(int kmax, float *A, float *B, float *beta, float *C, int ldc, float *D, int ldd, float *E); -void kernel_strsm_nt_ru_one_4x4_vs_lib44cc4(int kmax, float *A, float *B, float *beta, float *C, int ldc, float *D, int ldd, float *E, int m1, int n1); -void kernel_spotrf_nt_l_4x4_lib44cc(int kmax, float *A, float *B, float *C, int ldc, float *D, int ldd, float *dD); -void kernel_spotrf_nt_l_4x4_vs_lib44cc(int kmax, float *A, float *B, float *C, int ldc, float *D, int ldd, float *dD, int m1, int n1); - -// B panel-major bs=8; A, C, D column-major -// 4x24 -void kernel_sgemm_nt_4x24_libc8cc(int kmax, float *alpha, float *A, int lda, float *B, int sdb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nt_4x24_vs_libc8cc(int kmax, float *alpha, float *A, int lda, float *B, int sdb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -void kernel_sgemm_tt_4x24_libc8cc(int kmax, float *alpha, float *A, int lda, float *B, int sdb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_tt_4x24_vs_libc8cc(int kmax, float *alpha, float *A, int lda, float *B, int sdb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -// 4x16 -void kernel_sgemm_nt_4x16_libc8cc(int kmax, float *alpha, float *A, int lda, float *B, int sdb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nt_4x16_vs_libc8cc(int kmax, float *alpha, float *A, int lda, float *B, int sdb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -void kernel_sgemm_tt_4x16_libc8cc(int kmax, float *alpha, float *A, int lda, float *B, int sdb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_tt_4x16_vs_libc8cc(int kmax, float *alpha, float *A, int lda, float *B, int sdb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -// 8x8 -void kernel_sgemm_nt_8x8_libc8cc(int kmax, float *alpha, float *A, int lda, float *B, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nt_8x8_vs_libc8cc(int kmax, float *alpha, float *A, int lda, float *B, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -void kernel_sgemm_tt_8x8_libc8cc(int kmax, float *alpha, float *A, int lda, float *B, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_tt_8x8_vs_libc8cc(int kmax, float *alpha, float *A, int lda, float *B, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -// 4x8 -void kernel_sgemm_nt_4x8_libc8cc(int kmax, float *alpha, float *A, int lda, float *B, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nt_4x8_vs_libc8cc(int kmax, float *alpha, float *A, int lda, float *B, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -void kernel_sgemm_tt_4x8_libc8cc(int kmax, float *alpha, float *A, int lda, float *B, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_tt_4x8_vs_libc8cc(int kmax, float *alpha, float *A, int lda, float *B, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); - -// B panel-major bs=4; A, C, D column-major -// 8x8 -void kernel_sgemm_nt_8x8_libc4cc(int kmax, float *alpha, float *A, int lda, float *B, int sdb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nt_8x8_vs_libc4cc(int kmax, float *alpha, float *A, int lda, float *B, int sdb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -void kernel_sgemm_tt_8x8_libc4cc(int kmax, float *alpha, float *A, int lda, float *B, int sdb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_tt_8x8_vs_libc4cc(int kmax, float *alpha, float *A, int lda, float *B, int sdb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -// 4x8 -void kernel_sgemm_nt_4x8_libc4cc(int kmax, float *alpha, float *A, int lda, float *B, int sdb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nt_4x8_vs_libc4cc(int kmax, float *alpha, float *A, int lda, float *B, int sdb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -void kernel_sgemm_tt_4x8_libc4cc(int kmax, float *alpha, float *A, int lda, float *B, int sdb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_tt_4x8_vs_libc4cc(int kmax, float *alpha, float *A, int lda, float *B, int sdb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -// 4x4 -void kernel_sgemm_nt_4x4_libc4cc(int kmax, float *alpha, float *A, int lda, float *B, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nt_4x4_vs_libc4cc(int kmax, float *alpha, float *A, int lda, float *B, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -void kernel_sgemm_tt_4x4_libc4cc(int kmax, float *alpha, float *A, int lda, float *B, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_tt_4x4_vs_libc4cc(int kmax, float *alpha, float *A, int lda, float *B, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); - -// A panel-major bs=8; B, C, D column-major -// 24x4 -void kernel_sgemm_nn_24x4_lib8ccc(int kmax, float *alpha, float *A, int lda, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nn_24x4_vs_lib8ccc(int kmax, float *alpha, float *A, int lda, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -void kernel_sgemm_nt_24x4_lib8ccc(int kmax, float *alpha, float *A, int lda, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nt_24x4_vs_lib8ccc(int kmax, float *alpha, float *A, int lda, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -// 16x4 -void kernel_sgemm_nn_16x4_lib8ccc(int kmax, float *alpha, float *A, int lda, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nn_16x4_vs_lib8ccc(int kmax, float *alpha, float *A, int lda, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -void kernel_sgemm_nt_16x4_lib8ccc(int kmax, float *alpha, float *A, int lda, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nt_16x4_vs_lib8ccc(int kmax, float *alpha, float *A, int lda, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -// 8x8 -void kernel_sgemm_nn_8x8_lib8ccc(int kmax, float *alpha, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nn_8x8_vs_lib8ccc(int kmax, float *alpha, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -void kernel_sgemm_nt_8x8_lib8ccc(int kmax, float *alpha, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nt_8x8_vs_lib8ccc(int kmax, float *alpha, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -// 8x4 -void kernel_sgemm_nn_8x4_lib8ccc(int kmax, float *alpha, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nn_8x4_vs_lib8ccc(int kmax, float *alpha, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -void kernel_sgemm_nt_8x4_lib8ccc(int kmax, float *alpha, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nt_8x4_vs_lib8ccc(int kmax, float *alpha, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); - -// A panel-major bs=4; B, C, D column-major -// 8x8 -void kernel_sgemm_nn_8x8_lib4ccc(int kmax, float *alpha, float *A, int sda, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nt_8x8_lib4ccc(int kmax, float *alpha, float *A, int sda, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd); -// 8x4 -void kernel_sgemm_nn_8x4_lib4ccc(int kmax, float *alpha, float *A, int sda, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nn_8x4_vs_lib4ccc(int kmax, float *alpha, float *A, int sda, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -void kernel_sgemm_nt_8x4_lib4ccc(int kmax, float *alpha, float *A, int sda, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nt_8x4_vs_lib4ccc(int kmax, float *alpha, float *A, int sda, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -// 4x4 -void kernel_sgemm_nn_4x4_lib4ccc(int kmax, float *alpha, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nn_4x4_vs_lib4ccc(int kmax, float *alpha, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -void kernel_sgemm_nt_4x4_lib4ccc(int kmax, float *alpha, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nt_4x4_vs_lib4ccc(int kmax, float *alpha, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -void kernel_strsm_nn_rl_inv_4x4_lib4cccc(int kmax, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, float *E, int lde, float *dE); -void kernel_strsm_nn_rl_inv_4x4_vs_lib4cccc(int kmax, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, float *E, int lde, float *dE, int m1, int n1); -void kernel_strsm_nn_rl_one_4x4_lib4cccc(int kmax, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, float *E, int lde); -void kernel_strsm_nn_rl_one_4x4_vs_lib4cccc(int kmax, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, float *E, int lde, int m1, int n1); -void kernel_strsm_nt_rl_inv_4x4_lib4cccc(int kmax, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, float *E, int lde, float *dE); -void kernel_strsm_nt_rl_inv_4x4_vs_lib4cccc(int kmax, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, float *E, int lde, float *dE, int m1, int n1); -void kernel_strsm_nt_rl_one_4x4_lib4cccc(int kmax, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, float *E, int lde); -void kernel_strsm_nt_rl_one_4x4_vs_lib4cccc(int kmax, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, float *E, int lde, int m1, int n1); -void kernel_strsm_nn_ru_inv_4x4_lib4cccc(int kmax, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, float *E, int lde, float *dE); -void kernel_strsm_nn_ru_inv_4x4_vs_lib4cccc(int kmax, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, float *E, int lde, float *dE, int m1, int n1); -void kernel_strsm_nn_ru_one_4x4_lib4cccc(int kmax, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, float *E, int lde); -void kernel_strsm_nn_ru_one_4x4_vs_lib4cccc(int kmax, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, float *E, int lde, int m1, int n1); -void kernel_strsm_nt_ru_inv_4x4_lib4cccc(int kmax, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, float *E, int lde, float *dE); -void kernel_strsm_nt_ru_inv_4x4_vs_lib4cccc(int kmax, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, float *E, int lde, float *dE, int m1, int n1); -void kernel_strsm_nt_ru_one_4x4_lib4cccc(int kmax, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, float *E, int lde); -void kernel_strsm_nt_ru_one_4x4_vs_lib4cccc(int kmax, float *A, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, float *E, int lde, int m1, int n1); - -// A, C, D panel-major; B, E column-major -// TODO merge with above -// 4x4 -void kernel_strsm_nn_rl_inv_4x4_lib4c44c(int kmax, float *A, float *B, int ldb, float *beta, float *C, float *D, float *E, int lde, float *dE); -void kernel_strsm_nn_rl_inv_4x4_vs_lib4c44c(int kmax, float *A, float *B, int ldb, float *beta, float *C, float *D, float *E, int lde, float *dE, int m1, int n1); -void kernel_strsm_nn_rl_one_4x4_lib4c44c(int kmax, float *A, float *B, int ldb, float *beta, float *C, float *D, float *E, int lde); -void kernel_strsm_nn_rl_one_4x4_vs_lib4c44c(int kmax, float *A, float *B, int ldb, float *beta, float *C, float *D, float *E, int lde, int m1, int n1); -void kernel_strsm_nn_ru_inv_4x4_lib4c44c(int kmax, float *A, float *B, int ldb, float *beta, float *C, float *D, float *E, int lde, float *dE); -void kernel_strsm_nn_ru_inv_4x4_vs_lib4c44c(int kmax, float *A, float *B, int ldb, float *beta, float *C, float *D, float *E, int lde, float *dE, int m1, int n1); -void kernel_strsm_nn_ru_one_4x4_lib4c44c(int kmax, float *A, float *B, int ldb, float *beta, float *C, float *D, float *E, int lde); -void kernel_strsm_nn_ru_one_4x4_vs_lib4c44c(int kmax, float *A, float *B, int ldb, float *beta, float *C, float *D, float *E, int lde, int m1, int n1); -void kernel_strsm_nt_rl_inv_4x4_lib4c44c(int kmax, float *A, float *B, int ldb, float *beta, float *C, float *D, float *E, int lde, float *dE); -void kernel_strsm_nt_rl_inv_4x4_vs_lib4c44c(int kmax, float *A, float *B, int ldb, float *beta, float *C, float *D, float *E, int lde, float *dE, int m1, int n1); -void kernel_strsm_nt_rl_one_4x4_lib4c44c(int kmax, float *A, float *B, int ldb, float *beta, float *C, float *D, float *E, int lde); -void kernel_strsm_nt_rl_one_4x4_vs_lib4c44c(int kmax, float *A, float *B, int ldb, float *beta, float *C, float *D, float *E, int lde, int m1, int n1); -void kernel_strsm_nt_ru_inv_4x4_lib4c44c(int kmax, float *A, float *B, int ldb, float *beta, float *C, float *D, float *E, int lde, float *dE); -void kernel_strsm_nt_ru_inv_4x4_vs_lib4c44c(int kmax, float *A, float *B, int ldb, float *beta, float *C, float *D, float *E, int lde, float *dE, int m1, int n1); -void kernel_strsm_nt_ru_one_4x4_lib4c44c(int kmax, float *A, float *B, int ldb, float *beta, float *C, float *D, float *E, int lde); -void kernel_strsm_nt_ru_one_4x4_vs_lib4c44c(int kmax, float *A, float *B, int ldb, float *beta, float *C, float *D, float *E, int lde, int m1, int n1); - -// A, B, C, D column-major -void kernel_sgemm_nn_4x4_libcccc(int kmax, float *alpha, float *A, int lda, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nn_4x4_vs_libcccc(int kmax, float *alpha, float *A, int lda, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -void kernel_sgemm_nt_4x4_libcccc(int kmax, float *alpha, float *A, int lda, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_nt_4x4_vs_libcccc(int kmax, float *alpha, float *A, int lda, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); -void kernel_sgemm_tt_4x4_libcccc(int kmax, float *alpha, float *A, int lda, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd); -void kernel_sgemm_tt_4x4_vs_libcccc(int kmax, float *alpha, float *A, int lda, float *B, int ldb, float *beta, float *C, int ldc, float *D, int ldd, int m1, int n1); - -// vector -void kernel_sdot_11_lib(int n, float *x, float *y, float *res); -void kernel_saxpy_11_lib(int n, float *alpha, float *x, float *y); - - -//#endif // BLAS_API - - - -// larger kernels -// 24 -void kernel_sgemm_nt_24xn_p0_lib88cc(int n, int k, float *alpha, float *A, int sda, float *B, int sdb, float *beta, float *C, int ldc, float *D, int ldd, float *A_p, float *B_p); - - - - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_S_KERNEL_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_stdlib.h b/third_party/acados/include/blasfeo/include/blasfeo_stdlib.h deleted file mode 100644 index 9bd248b..0000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_stdlib.h +++ /dev/null @@ -1,62 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_STDLIB_H_ -#define BLASFEO_STDLIB_H_ - -#ifdef __cplusplus -extern "C" { -#endif - - - -#include - -// -void blasfeo_malloc(void **ptr, size_t size); -// -void blasfeo_malloc_align(void **ptr, size_t size); -// -void blasfeo_free(void *ptr); -// -void blasfeo_free_align(void *ptr); - - - -#ifdef __cplusplus -} -#endif - -#endif // BLASFEO_STDLIB_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_target.h b/third_party/acados/include/blasfeo/include/blasfeo_target.h deleted file mode 100644 index 51f617a..0000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_target.h +++ /dev/null @@ -1,73 +0,0 @@ -#ifndef TARGET_X64_INTEL_HASWELL -#define TARGET_X64_INTEL_HASWELL -#endif - -#ifndef TARGET_NEED_FEATURE_AVX2 -#define TARGET_NEED_FEATURE_AVX2 1 -#endif - -#ifndef TARGET_NEED_FEATURE_FMA -#define TARGET_NEED_FEATURE_FMA 1 -#endif - -#ifndef TARGET_NEED_FEATURE_SSE3 -/* #undef TARGET_NEED_FEATURE_SSE3 */ -#endif - -#ifndef TARGET_NEED_FEATURE_AVX -/* #undef TARGET_NEED_FEATURE_AVX */ -#endif - -#ifndef TARGET_NEED_FEATURE_VFPv3 -/* #undef TARGET_NEED_FEATURE_VFPv3 */ -#endif - -#ifndef TARGET_NEED_FEATURE_NEON -/* #undef TARGET_NEED_FEATURE_NEON */ -#endif - -#ifndef TARGET_NEED_FEATURE_VFPv4 -/* #undef TARGET_NEED_FEATURE_VFPv4 */ -#endif - -#ifndef TARGET_NEED_FEATURE_NEONv2 -/* #undef TARGET_NEED_FEATURE_NEONv2 */ -#endif - -#ifndef LA_HIGH_PERFORMANCE -#define LA_HIGH_PERFORMANCE -#endif - -#ifndef MF_PANELMAJ -#define MF_PANELMAJ -#endif - -#ifndef EXT_DEP -#define ON 1 -#define OFF 0 -#if ON==ON -#define EXT_DEP -#endif -#undef ON -#undef OFF -#endif - -#ifndef BLAS_API -#define ON 1 -#define OFF 0 -#if OFF==ON -#define BLAS_API -#endif -#undef ON -#undef OFF -#endif - -#ifndef FORTRAN_BLAS_API -#define ON 1 -#define OFF 0 -#if OFF==ON -#define FORTRAN_BLAS_API -#endif -#undef ON -#undef OFF -#endif diff --git a/third_party/acados/include/blasfeo/include/blasfeo_timing.h b/third_party/acados/include/blasfeo/include/blasfeo_timing.h deleted file mode 100644 index 5671b88..0000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_timing.h +++ /dev/null @@ -1,114 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_TIMING_H_ -#define BLASFEO_TIMING_H_ - -//#include - -#if (defined _WIN32 || defined _WIN64) && !(defined __MINGW32__ || defined __MINGW64__) - - /* Use Windows QueryPerformanceCounter for timing. */ - #include - - /** A structure for keeping internal timer data. */ - typedef struct blasfeo_timer_ { - LARGE_INTEGER tic; - LARGE_INTEGER toc; - LARGE_INTEGER freq; - } blasfeo_timer; - -#elif(defined __APPLE__) - - #include - - /** A structure for keeping internal timer data. */ - typedef struct blasfeo_timer_ { - uint64_t tic; - uint64_t toc; - mach_timebase_info_data_t tinfo; - } blasfeo_timer; - -#elif(defined __DSPACE__) - - #include - - typedef struct blasfeo_timer_ { - double time; - } blasfeo_timer; - -#elif(defined __XILINX_NONE_ELF__ || defined __XILINX_ULTRASCALE_NONE_ELF_JAILHOUSE__) - - #include "xtime_l.h" - - typedef struct blasfeo_timer_ { - uint64_t tic; - uint64_t toc; - } blasfeo_timer; - -#else - - /* Use POSIX clock_gettime() for timing on non-Windows machines. */ - #include - - #if __STDC_VERSION__ >= 199901L // C99 Mode - - #include - #include - - typedef struct blasfeo_timer_ { - struct timeval tic; - struct timeval toc; - } blasfeo_timer; - - #else // ANSI C Mode - - /** A structure for keeping internal timer data. */ - typedef struct blasfeo_timer_ { - struct timespec tic; - struct timespec toc; - } blasfeo_timer; - - #endif // __STDC_VERSION__ >= 199901L - -#endif // (defined _WIN32 || defined _WIN64) - -/** A function for measurement of the current time. */ -void blasfeo_tic(blasfeo_timer* t); - -/** A function which returns the elapsed time. */ -double blasfeo_toc(blasfeo_timer* t); - -#endif // BLASFEO_TIMING_H_ diff --git a/third_party/acados/include/blasfeo/include/blasfeo_v_aux_ext_dep.h b/third_party/acados/include/blasfeo/include/blasfeo_v_aux_ext_dep.h deleted file mode 100644 index 1598551..0000000 --- a/third_party/acados/include/blasfeo/include/blasfeo_v_aux_ext_dep.h +++ /dev/null @@ -1,83 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef BLASFEO_V_AUX_EXT_DEP_H_ -#define BLASFEO_V_AUX_EXT_DEP_H_ - - - -#include "blasfeo_target.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -/************************************************ -* d_aux_extern_depend_lib.c -************************************************/ - -#ifdef EXT_DEP - -void v_zeros(void **ptrA, int size); -// dynamically allocate size bytes of memory aligned to 64-byte boundaries and set accordingly a pointer to void; set allocated memory to zero -void v_zeros_align(void **ptrA, int size); -// free the memory allocated by v_zeros -void v_free(void *ptrA); -// free the memory allocated by v_zeros_aligned -void v_free_align(void *ptrA); -// dynamically allocate size bytes of memory and set accordingly a pointer to char; set allocated memory to zero -void c_zeros(char **ptrA, int size); -// dynamically allocate size bytes of memory aligned to 64-byte boundaries and set accordingly a pointer to char; set allocated memory to zero -void c_zeros_align(char **ptrA, int size); -// free the memory allocated by c_zeros -void c_free(char *ptrA); -// free the memory allocated by c_zeros_aligned -void c_free_align(char *ptrA); - -#endif // EXT_DEP - - - -#ifdef __cplusplus -} -#endif - - - -#endif // BLASFEO_V_AUX_EXT_DEP_H_ diff --git a/third_party/acados/include/blasfeo/include/d_blas.h b/third_party/acados/include/blasfeo/include/d_blas.h deleted file mode 100644 index ffd2578..0000000 --- a/third_party/acados/include/blasfeo/include/d_blas.h +++ /dev/null @@ -1,78 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifdef __cplusplus -extern "C" { -#endif - - - -// headers to reference BLAS and LAPACK routines employed in BLASFEO WR - -// level 1 -double ddot_(int *m, double *x, int *incx, double *y, int *incy); -void dcopy_(int *m, double *x, int *incx, double *y, int *incy); -void daxpy_(int *m, double *alpha, double *x, int *incx, double *y, int *incy); -void dscal_(int *m, double *alpha, double *x, int *incx); -void drot_(int *m, double *x, int *incx, double *y, int *incy, double *c, double *s); -void drotg_(double *a, double *b, double *c, double *s); - -// level 2 -void dgemv_(char *ta, int *m, int *n, double *alpha, double *A, int *lda, double *x, int *incx, double *beta, double *y, int *incy); -void dsymv_(char *uplo, int *m, double *alpha, double *A, int *lda, double *x, int *incx, double *beta, double *y, int *incy); -void dtrmv_(char *uplo, char *trans, char *diag, int *n, double *A, int *lda, double *x, int *incx); -void dtrsv_(char *uplo, char *trans, char *diag, int *n, double *A, int *lda, double *x, int *incx); -void dger_(int *m, int *n, double *alpha, double *x, int *incx, double *y, int *incy, double *A, int *lda); - -// level 3 -void dgemm_(char *ta, char *tb, int *m, int *n, int *k, double *alpha, double *A, int *lda, double *B, int *ldb, double *beta, double *C, int *ldc); -void dsyrk_(char *uplo, char *trans, int *n, int *k, double *alpha, double *A, int *lda, double *beta, double *C, int *ldc); -void dtrmm_(char *side, char *uplo, char *trans, char *diag, int *m, int *n, double *alpha, double *A, int *lda, double *B, int *ldb); -void dtrsm_(char *side, char *uplo, char *trans, char *diag, int *m, int *n, double *alpha, double *A, int *lda, double *B, int *ldb); -void dsyr2k_(char *uplo, char *trans, int *n, int *k, double *alpha, double *A, int *lda, double *B, int *ldb, double *beta, double *C, int *ldc); - -// lapack -void dpotrf_(char *uplo, int *m, double *A, int *lda, int *info); -void dgetrf_(int *m, int *n, double *A, int *lda, int *ipiv, int *info); -void dgeqrf_(int *m, int *n, double *A, int *lda, double *tau, double *work, int *lwork, int *info); -void dgeqr2_(int *m, int *n, double *A, int *lda, double *tau, double *work, int *info); -void dgelqf_(int *m, int *n, double *A, int *lda, double *tau, double *work, int *lwork, int *info); -void dorglq_(int *m, int *n, int *k, double *A, int *lda, double *tau, double *work, int *lwork, int *info); - - - -#ifdef __cplusplus -} -#endif diff --git a/third_party/acados/include/blasfeo/include/d_blas_64.h b/third_party/acados/include/blasfeo/include/d_blas_64.h deleted file mode 100644 index 4f40d00..0000000 --- a/third_party/acados/include/blasfeo/include/d_blas_64.h +++ /dev/null @@ -1,73 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifdef __cplusplus -extern "C" { -#endif - - - -// headers to reference BLAS and LAPACK routines employed in BLASFEO WR - -// level 1 -double ddot_(long long *m, double *x, long long *incx, double *y, long long *incy); -void dcopy_(long long *m, double *x, long long *incx, double *y, long long *incy); -void daxpy_(long long *m, double *alpha, double *x, long long *incx, double *y, long long *incy); -void dscal_(long long *m, double *alpha, double *x, long long *incx); - -// level 2 -void dgemv_(char *ta, long long *m, long long *n, double *alpha, double *A, long long *lda, double *x, long long *incx, double *beta, double *y, long long *incy); -void dsymv_(char *uplo, long long *m, double *alpha, double *A, long long *lda, double *x, long long *incx, double *beta, double *y, long long *incy); -void dtrmv_(char *uplo, char *trans, char *diag, long long *n, double *A, long long *lda, double *x, long long *incx); -void dtrsv_(char *uplo, char *trans, char *diag, long long *n, double *A, long long *lda, double *x, long long *incx); -void dger_(long long *m, long long *n, double *alpha, double *x, long long *incx, double *y, long long *incy, double *A, long long *lda); - -// level 3 -void dgemm_(char *ta, char *tb, long long *m, long long *n, long long *k, double *alpha, double *A, long long *lda, double *B, long long *ldb, double *beta, double *C, long long *ldc); -void dsyrk_(char *uplo, char *trans, long long *n, long long *k, double *alpha, double *A, long long *lda, double *beta, double *C, long long *ldc); -void dtrmm_(char *side, char *uplo, char *trans, char *diag, long long *m, long long *n, double *alpha, double *A, long long *lda, double *B, long long *ldb); -void dtrsm_(char *side, char *uplo, char *trans, char *diag, long long *m, long long *n, double *alpha, double *A, long long *lda, double *B, long long *ldb); - -// lapack -void dpotrf_(char *uplo, long long *m, double *A, long long *lda, long long *info); -void dgetrf_(long long *m, long long *n, double *A, long long *lda, long long *ipiv, long long *info); -void dgeqrf_(long long *m, long long *n, double *A, long long *lda, double *tau, double *work, long long *lwork, long long *info); -void dgeqr2_(long long *m, long long *n, double *A, long long *lda, double *tau, double *work, long long *info); - - - -#ifdef __cplusplus -} -#endif diff --git a/third_party/acados/include/blasfeo/include/s_blas.h b/third_party/acados/include/blasfeo/include/s_blas.h deleted file mode 100644 index 3b299ce..0000000 --- a/third_party/acados/include/blasfeo/include/s_blas.h +++ /dev/null @@ -1,78 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifdef __cplusplus -extern "C" { -#endif - - - -// headers to reference BLAS and LAPACK routines employed in BLASFEO WR - -// level 1 -float sdot_(int *m, float *x, int *incx, float *y, int *incy); -void scopy_(int *m, float *x, int *incx, float *y, int *incy); -void saxpy_(int *m, float *alpha, float *x, int *incx, float *y, int *incy); -void sscal_(int *m, float *alpha, float *x, int *incx); -void srot_(int *m, float *x, int *incx, float *y, int *incy, float *c, float *s); -void srotg_(float *a, float *b, float *c, float *s); - -// level 2 -void sgemv_(char *ta, int *m, int *n, float *alpha, float *A, int *lda, float *x, int *incx, float *beta, float *y, int *incy); -void ssymv_(char *uplo, int *m, float *alpha, float *A, int *lda, float *x, int *incx, float *beta, float *y, int *incy); -void strmv_(char *uplo, char *trans, char *diag, int *n, float *A, int *lda, float *x, int *incx); -void strsv_(char *uplo, char *trans, char *diag, int *n, float *A, int *lda, float *x, int *incx); -void sger_(int *m, int *n, float *alpha, float *x, int *incx, float *y, int *incy, float *A, int *lda); - -// level 3 -void sgemm_(char *ta, char *tb, int *m, int *n, int *k, float *alpha, float *A, int *lda, float *B, int *ldb, float *beta, float *C, int *ldc); -void ssyrk_(char *uplo, char *trans, int *n, int *k, float *alpha, float *A, int *lda, float *beta, float *C, int *ldc); -void strmm_(char *side, char *uplo, char *transa, char *diag, int *m, int *n, float *alpha, float *A, int *lda, float *B, int *ldb); -void strsm_(char *side, char *uplo, char *transa, char *diag, int *m, int *n, float *alpha, float *A, int *lda, float *B, int *ldb); -void ssyr2k_(char *uplo, char *trans, int *n, int *k, float *alpha, float *A, int *lda, float *B, int *ldb, float *beta, float *C, int *ldc); - -// lapack -void spotrf_(char *uplo, int *m, float *A, int *lda, int *info); -void sgetrf_(int *m, int *n, float *A, int *lda, int *ipiv, int *info); -void sgeqrf_(int *m, int *n, float *A, int *lda, float *tau, float *work, int *lwork, int *info); -void sgeqr2_(int *m, int *n, float *A, int *lda, float *tau, float *work, int *info); -void sgelqf_(int *m, int *n, float *A, int *lda, float *tau, float *work, int *lwork, int *info); -void sorglq_(int *m, int *n, int *k, float *A, int *lda, float *tau, float *work, int *lwork, int *info); - - - -#ifdef __cplusplus -} -#endif diff --git a/third_party/acados/include/blasfeo/include/s_blas_64.h b/third_party/acados/include/blasfeo/include/s_blas_64.h deleted file mode 100644 index b9efab6..0000000 --- a/third_party/acados/include/blasfeo/include/s_blas_64.h +++ /dev/null @@ -1,73 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of BLASFEO. * -* * -* BLASFEO -- BLAS For Embedded Optimization. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifdef __cplusplus -extern "C" { -#endif - - - -// headers to reference BLAS and LAPACK routines employed in BLASFEO WR - -// level 1 -float sdot_(long long *m, float *x, long long *incx, float *y, long long *incy); -void scopy_(long long *m, float *x, long long *incx, float *y, long long *incy); -void saxpy_(long long *m, float *alpha, float *x, long long *incx, float *y, long long *incy); -void sscal_(long long *m, float *alpha, float *x, long long *incx); - -// level 2 -void sgemv_(char *ta, long long *m, long long *n, float *alpha, float *A, long long *lda, float *x, long long *incx, float *beta, float *y, long long *incy); -void ssymv_(char *uplo, long long *m, float *alpha, float *A, long long *lda, float *x, long long *incx, float *beta, float *y, long long *incy); -void strmv_(char *uplo, char *trans, char *diag, long long *n, float *A, long long *lda, float *x, long long *incx); -void strsv_(char *uplo, char *trans, char *diag, long long *n, float *A, long long *lda, float *x, long long *incx); -void sger_(long long *m, long long *n, float *alpha, float *x, long long *incx, float *y, long long *incy, float *A, long long *lda); - -// level 3 -void sgemm_(char *ta, char *tb, long long *m, long long *n, long long *k, float *alpha, float *A, long long *lda, float *B, long long *ldb, float *beta, float *C, long long *ldc); -void ssyrk_(char *uplo, char *trans, long long *n, long long *k, float *alpha, float *A, long long *lda, float *beta, float *C, long long *ldc); -void strmm_(char *side, char *uplo, char *transa, char *diag, long long *m, long long *n, float *alpha, float *A, long long *lda, float *B, long long *ldb); -void strsm_(char *side, char *uplo, char *transa, char *diag, long long *m, long long *n, float *alpha, float *A, long long *lda, float *B, long long *ldb); - -// lapack -void spotrf_(char *uplo, long long *m, float *A, long long *lda, long long *info); -void sgetrf_(long long *m, long long *n, float *A, long long *lda, long long *ipiv, long long *info); -void sgeqrf_(long long *m, long long *n, float *A, long long *lda, float *tau, float *work, long long *lwork, long long *info); -void sgeqr2_(long long *m, long long *n, float *A, long long *lda, float *tau, float *work, long long *info); - - - -#ifdef __cplusplus -} -#endif diff --git a/third_party/acados/include/hpipm/include/hpipm_aux_mem.h b/third_party/acados/include/hpipm/include/hpipm_aux_mem.h deleted file mode 100644 index 7bd3d7e..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_aux_mem.h +++ /dev/null @@ -1,52 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_AUX_MEM_H_ -#define HPIPM_AUX_MEM_H_ - -#include "hpipm_common.h" - -#ifdef __cplusplus -extern "C" { -#endif - -void hpipm_zero_memset(hpipm_size_t memsize, void *mem); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // HPIPM_AUX_MEM_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_aux_string.h b/third_party/acados/include/hpipm/include/hpipm_aux_string.h deleted file mode 100644 index 804cba5..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_aux_string.h +++ /dev/null @@ -1,50 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_AUX_STRING_H_ -#define HPIPM_AUX_STRING_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -#define MAX_STR_LEN 5 -int hpipm_strcmp(char *str1, char *str2); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // HPIPM_AUX_STRING_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_common.h b/third_party/acados/include/hpipm/include/hpipm_common.h deleted file mode 100644 index 0cc96a7..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_common.h +++ /dev/null @@ -1,76 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_COMMON_H_ -#define HPIPM_COMMON_H_ - -#include - -#ifdef __cplusplus -extern "C" { -#endif - -typedef size_t hpipm_size_t; - -enum hpipm_mode - { - SPEED_ABS, // focus on speed, absolute IPM formulation - SPEED, // focus on speed, relative IPM formulation - BALANCE, // balanced mode, relative IPM formulation - ROBUST, // focus on robustness, relative IPM formulation - }; - -enum hpipm_status - { - SUCCESS, // found solution satisfying accuracy tolerance - MAX_ITER, // maximum iteration number reached - MIN_STEP, // minimum step length reached - NAN_SOL, // NaN in solution detected - INCONS_EQ, // unconsistent equality constraints - }; - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_COMMON_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_cast_qcqp.h b/third_party/acados/include/hpipm/include/hpipm_d_cast_qcqp.h deleted file mode 100644 index 0e4c41f..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_cast_qcqp.h +++ /dev/null @@ -1,71 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_D_CAST_QCQP_H_ -#define HPIPM_D_CAST_QCQP_H_ - - - -#include -#include - -#include "hpipm_d_dense_qcqp.h" -#include "hpipm_d_dense_qcqp_sol.h" -#include "hpipm_d_ocp_qcqp.h" -#include "hpipm_d_ocp_qcqp_dim.h" -#include "hpipm_d_ocp_qcqp_sol.h" - -#ifdef __cplusplus -extern "C" { -#endif - - - -// -void d_cast_qcqp_compute_dim(struct d_ocp_qcqp_dim *ocp_dim, struct d_dense_qcqp_dim *dense_dim); -// -void d_cast_qcqp_cond(struct d_ocp_qcqp *ocp_qp, struct d_dense_qcqp *dense_qp); - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_D_CAST_QCQP_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_cond.h b/third_party/acados/include/hpipm/include/hpipm_d_cond.h deleted file mode 100644 index 5900a2a..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_cond.h +++ /dev/null @@ -1,135 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_D_COND_H_ -#define HPIPM_D_COND_H_ - - - -#include -#include - -#include "hpipm_d_dense_qp.h" -#include "hpipm_d_dense_qp_sol.h" -#include "hpipm_d_ocp_qp.h" -#include "hpipm_d_ocp_qp_dim.h" -#include "hpipm_d_ocp_qp_sol.h" - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_cond_qp_arg - { - int cond_last_stage; // condense last stage - int cond_alg; // condensing algorithm: 0 N2-nx3, 1 N3-nx2 - int comp_prim_sol; // primal solution (v) - int comp_dual_sol_eq; // dual solution equality constr (pi) - int comp_dual_sol_ineq; // dual solution inequality constr (lam t) - int square_root_alg; // square root algorithm (faster but requires RSQ>0) - hpipm_size_t memsize; - }; - - - -struct d_cond_qp_ws - { - struct blasfeo_dmat *Gamma; - struct blasfeo_dmat *GammaQ; - struct blasfeo_dmat *L; - struct blasfeo_dmat *Lx; - struct blasfeo_dmat *AL; - struct blasfeo_dvec *Gammab; - struct blasfeo_dvec *l; - struct blasfeo_dvec *tmp_nbgM; - struct blasfeo_dvec *tmp_nuxM; - int bs; // block size - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_cond_qp_arg_memsize(); -// -void d_cond_qp_arg_create(struct d_cond_qp_arg *cond_arg, void *mem); -// -void d_cond_qp_arg_set_default(struct d_cond_qp_arg *cond_arg); -// condensing algorithm: 0 N2-nx3, 1 N3-nx2 -void d_cond_qp_arg_set_cond_alg(int cond_alg, struct d_cond_qp_arg *cond_arg); -// set riccati-like algorithm: 0 classical, 1 square-root -void d_cond_qp_arg_set_ric_alg(int ric_alg, struct d_cond_qp_arg *cond_arg); -// condense last stage: 0 last stage disregarded, 1 last stage condensed too -void d_cond_qp_arg_set_cond_last_stage(int cond_last_stage, struct d_cond_qp_arg *cond_arg); -// -void d_cond_qp_arg_set_comp_prim_sol(int value, struct d_cond_qp_arg *cond_arg); -// -void d_cond_qp_arg_set_comp_dual_sol_eq(int value, struct d_cond_qp_arg *cond_arg); -// -void d_cond_qp_arg_set_comp_dual_sol_ineq(int value, struct d_cond_qp_arg *cond_arg); - -// -void d_cond_qp_compute_dim(struct d_ocp_qp_dim *ocp_dim, struct d_dense_qp_dim *dense_dim); -// -hpipm_size_t d_cond_qp_ws_memsize(struct d_ocp_qp_dim *ocp_dim, struct d_cond_qp_arg *cond_arg); -// -void d_cond_qp_ws_create(struct d_ocp_qp_dim *ocp_dim, struct d_cond_qp_arg *cond_arg, struct d_cond_qp_ws *cond_ws, void *mem); -// -void d_cond_qp_cond(struct d_ocp_qp *ocp_qp, struct d_dense_qp *dense_qp, struct d_cond_qp_arg *cond_arg, struct d_cond_qp_ws *cond_ws); -// -void d_cond_qp_cond_lhs(struct d_ocp_qp *ocp_qp, struct d_dense_qp *dense_qp, struct d_cond_qp_arg *cond_arg, struct d_cond_qp_ws *cond_ws); -// -void d_cond_qp_cond_rhs(struct d_ocp_qp *ocp_qp, struct d_dense_qp *dense_qp, struct d_cond_qp_arg *cond_arg, struct d_cond_qp_ws *cond_ws); -// -void d_cond_qp_expand_sol(struct d_ocp_qp *ocp_qp, struct d_dense_qp_sol *dense_qp_sol, struct d_ocp_qp_sol *ocp_qp_sol, struct d_cond_qp_arg *cond_arg, struct d_cond_qp_ws *cond_ws); -// TODO remove -void d_cond_qp_expand_primal_sol(struct d_ocp_qp *ocp_qp, struct d_dense_qp_sol *dense_qp_sol, struct d_ocp_qp_sol *ocp_qp_sol, struct d_cond_qp_arg *cond_arg, struct d_cond_qp_ws *cond_ws); - -// -void d_cond_qp_update(int *idxc, struct d_ocp_qp *ocp_qp, struct d_dense_qp *dense_qp, struct d_cond_qp_arg *cond_arg, struct d_cond_qp_ws *cond_ws); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_D_COND_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_cond_aux.h b/third_party/acados/include/hpipm/include/hpipm_d_cond_aux.h deleted file mode 100644 index 73afba3..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_cond_aux.h +++ /dev/null @@ -1,92 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_D_COND_AUX_H_ -#define HPIPM_D_COND_AUX_H_ - - - -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -// -void d_cond_BAbt(struct d_ocp_qp *ocp_qp, struct blasfeo_dmat *BAbt2, struct blasfeo_dvec *b, struct d_cond_qp_arg *cond_arg, struct d_cond_qp_ws *cond_ws); -// -void d_cond_BAt(struct d_ocp_qp *ocp_qp, struct blasfeo_dmat *BAbt2, struct d_cond_qp_arg *cond_arg, struct d_cond_qp_ws *cond_ws); -// -void d_cond_b(struct d_ocp_qp *ocp_qp, struct blasfeo_dvec *b, struct d_cond_qp_arg *cond_arg, struct d_cond_qp_ws *cond_ws); -// -void d_cond_RSQrq(struct d_ocp_qp *ocp_qp, struct blasfeo_dmat *RSQrq2, struct blasfeo_dvec *rq, struct d_cond_qp_arg *cond_arg, struct d_cond_qp_ws *cond_ws); -// -void d_cond_RSQ(struct d_ocp_qp *ocp_qp, struct blasfeo_dmat *RSQrq2, struct d_cond_qp_arg *cond_arg, struct d_cond_qp_ws *cond_ws); -// -void d_cond_rq(struct d_ocp_qp *ocp_qp, struct blasfeo_dvec *rq, struct d_cond_qp_arg *cond_arg, struct d_cond_qp_ws *cond_ws); -// -void d_cond_DCtd(struct d_ocp_qp *ocp_qp, int *idxb2, struct blasfeo_dmat *DCt2, struct blasfeo_dvec *d2, struct blasfeo_dvec *d_mask2, int *idxs_rev2, struct blasfeo_dvec *Z2, struct blasfeo_dvec *z, struct d_cond_qp_arg *cond_arg, struct d_cond_qp_ws *cond_ws); -// -void d_cond_DCt(struct d_ocp_qp *ocp_qp, int *idxb2, struct blasfeo_dmat *DCt2, int *idxs_rev2, struct blasfeo_dvec *Z2, struct d_cond_qp_arg *cond_arg, struct d_cond_qp_ws *cond_ws); -// -void d_cond_d(struct d_ocp_qp *ocp_qp, struct blasfeo_dvec *d2, struct blasfeo_dvec *d_mask2, struct blasfeo_dvec *z, struct d_cond_qp_arg *cond_arg, struct d_cond_qp_ws *cond_ws); -// -void d_expand_sol(struct d_ocp_qp *ocp_qp, struct d_dense_qp_sol *dense_qp_sol, struct d_ocp_qp_sol *ocp_qp_so, struct d_cond_qp_arg *cond_arg, struct d_cond_qp_ws *cond_ws); -// -void d_expand_primal_sol(struct d_ocp_qp *ocp_qp, struct d_dense_qp_sol *dense_qp_sol, struct d_ocp_qp_sol *ocp_qp_so, struct d_cond_qp_arg *cond_arg, struct d_cond_qp_ws *cond_ws); - -// -void d_update_cond_BAbt(int *idxc, struct d_ocp_qp *ocp_qp, struct blasfeo_dmat *BAbt2, struct blasfeo_dvec *b, struct d_cond_qp_arg *cond_arg, struct d_cond_qp_ws *cond_ws); -// -void d_update_cond_RSQrq_N2nx3(int *idxc, struct d_ocp_qp *ocp_qp, struct blasfeo_dmat *RSQrq2, struct blasfeo_dvec *rq, struct d_cond_qp_arg *cond_arg, struct d_cond_qp_ws *cond_ws); -// -void d_update_cond_DCtd(int *idxc, struct d_ocp_qp *ocp_qp, int *idxb2, struct blasfeo_dmat *DCt2, struct blasfeo_dvec *d2, int *idxs2, struct blasfeo_dvec *Z2, struct blasfeo_dvec *z, struct d_cond_qp_arg *cond_arg, struct d_cond_qp_ws *cond_ws); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_D_COND_AUX_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_cond_qcqp.h b/third_party/acados/include/hpipm/include/hpipm_d_cond_qcqp.h deleted file mode 100644 index 266567b..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_cond_qcqp.h +++ /dev/null @@ -1,129 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_D_COND_QCQP_H_ -#define HPIPM_D_COND_QCQP_H_ - - - -#include -#include - -#include "hpipm_d_dense_qcqp.h" -#include "hpipm_d_dense_qcqp_sol.h" -#include "hpipm_d_ocp_qcqp.h" -#include "hpipm_d_ocp_qcqp_dim.h" -#include "hpipm_d_ocp_qcqp_sol.h" - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_cond_qcqp_arg - { - struct d_cond_qp_arg *qp_arg; - int cond_last_stage; // condense last stage -// int cond_variant; // TODO - int comp_prim_sol; // primal solution (v) - int comp_dual_sol_eq; // dual solution equality constr (pi) - int comp_dual_sol_ineq; // dual solution equality constr (lam t) - int square_root_alg; // square root algorithm (faster but requires RSQ>0) - hpipm_size_t memsize; - }; - - - -struct d_cond_qcqp_ws - { - struct d_cond_qp_ws *qp_ws; - struct blasfeo_dmat *hess_array; // TODO remove - struct blasfeo_dmat *zero_hess; // TODO remove - struct blasfeo_dvec *grad_array; // TODO remove - struct blasfeo_dvec *zero_grad; // TODO remove - struct blasfeo_dvec *tmp_nvc; - struct blasfeo_dvec *tmp_nuxM; - struct blasfeo_dmat *GammaQ; - struct blasfeo_dmat *tmp_DCt; - struct blasfeo_dmat *tmp_nuM_nxM; -// struct blasfeo_dvec *d_qp; -// struct blasfeo_dvec *d_mask_qp; - hpipm_size_t memsize; - }; - - -// -hpipm_size_t d_cond_qcqp_arg_memsize(); -// -void d_cond_qcqp_arg_create(struct d_cond_qcqp_arg *cond_arg, void *mem); -// -void d_cond_qcqp_arg_set_default(struct d_cond_qcqp_arg *cond_arg); -// set riccati-like algorithm: 0 classical, 1 square-root -void d_cond_qcqp_arg_set_ric_alg(int ric_alg, struct d_cond_qcqp_arg *cond_arg); -// condense last stage: 0 last stage disregarded, 1 last stage condensed too -void d_cond_qcqp_arg_set_cond_last_stage(int cond_last_stage, struct d_cond_qcqp_arg *cond_arg); - -// -void d_cond_qcqp_compute_dim(struct d_ocp_qcqp_dim *ocp_dim, struct d_dense_qcqp_dim *dense_dim); -// -hpipm_size_t d_cond_qcqp_ws_memsize(struct d_ocp_qcqp_dim *ocp_dim, struct d_cond_qcqp_arg *cond_arg); -// -void d_cond_qcqp_ws_create(struct d_ocp_qcqp_dim *ocp_dim, struct d_cond_qcqp_arg *cond_arg, struct d_cond_qcqp_ws *cond_ws, void *mem); -// -void d_cond_qcqp_qc(struct d_ocp_qcqp *ocp_qp, struct blasfeo_dmat *Hq2, int *Hq_nzero2, struct blasfeo_dmat *Ct2, struct blasfeo_dvec *d2, struct d_cond_qcqp_arg *cond_arg, struct d_cond_qcqp_ws *cond_ws); -// -void d_cond_qcqp_qc_lhs(struct d_ocp_qcqp *ocp_qp, struct blasfeo_dmat *Hq2, int *Hq_nzero2, struct blasfeo_dmat *Ct2, struct d_cond_qcqp_arg *cond_arg, struct d_cond_qcqp_ws *cond_ws); -// -void d_cond_qcqp_qc_rhs(struct d_ocp_qcqp *ocp_qp, struct blasfeo_dvec *d2, struct d_cond_qcqp_arg *cond_arg, struct d_cond_qcqp_ws *cond_ws); -// -void d_cond_qcqp_cond(struct d_ocp_qcqp *ocp_qp, struct d_dense_qcqp *dense_qp, struct d_cond_qcqp_arg *cond_arg, struct d_cond_qcqp_ws *cond_ws); -// -void d_cond_qcqp_cond_rhs(struct d_ocp_qcqp *ocp_qp, struct d_dense_qcqp *dense_qp, struct d_cond_qcqp_arg *cond_arg, struct d_cond_qcqp_ws *cond_ws); -// -void d_cond_qcqp_cond_lhs(struct d_ocp_qcqp *ocp_qp, struct d_dense_qcqp *dense_qp, struct d_cond_qcqp_arg *cond_arg, struct d_cond_qcqp_ws *cond_ws); -// -void d_cond_qcqp_expand_sol(struct d_ocp_qcqp *ocp_qp, struct d_dense_qcqp_sol *dense_qp_sol, struct d_ocp_qcqp_sol *ocp_qp_sol, struct d_cond_qcqp_arg *cond_arg, struct d_cond_qcqp_ws *cond_ws); - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_D_COND_QCQP_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_core_qp_ipm.h b/third_party/acados/include/hpipm/include/hpipm_d_core_qp_ipm.h deleted file mode 100644 index f39d9a9..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_core_qp_ipm.h +++ /dev/null @@ -1,101 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_CORE_QP_IPM_ -#define HPIPM_D_CORE_QP_IPM_ - -#include "hpipm_common.h" - -#ifdef __cplusplus -extern "C" { -#endif - -struct d_core_qp_ipm_workspace - { - double *v; // primal variables - double *pi; // equality constraints multipliers - double *lam; // inequality constraints multipliers - double *t; // inequality constraints slacks - double *t_inv; // inverse of t - double *v_bkp; // backup of primal variables - double *pi_bkp; // backup of equality constraints multipliers - double *lam_bkp; // backup of inequality constraints multipliers - double *t_bkp; // backup of inequality constraints slacks - double *dv; // step in v - double *dpi; // step in pi - double *dlam; // step in lam - double *dt; // step in t - double *res_g; // q-residuals - double *res_b; // b-residuals - double *res_d; // d-residuals - double *res_m; // m-residuals - double *res_m_bkp; // m-residuals - double *Gamma; // Hessian update - double *gamma; // gradient update - double alpha; // step length - double alpha_prim; // step length - double alpha_dual; // step length - double sigma; // centering XXX - double mu; // duality measuere - double mu_aff; // affine duality measuere - double nc_inv; // 1.0/nc, where nc is the total number of inequality constraints - double nc_mask_inv; // 1.0/nc_mask - double lam_min; // min value in lam vector - double t_min; // min value in t vector - double t_min_inv; // inverse of min value in t vector - double tau_min; // min value of barrier parameter - int nv; // number of primal variables - int ne; // number of equality constraints - int nc; // (twice the) number of (two-sided) inequality constraints - int nc_mask; // total number of ineq constr after masking - int split_step; // use different step for primal and dual variables - int t_lam_min; // clip t and lam also in solution, or only in Gamma computation - hpipm_size_t memsize; // memory size (in bytes) of workspace - }; - - - -// -hpipm_size_t d_memsize_core_qp_ipm(int nv, int ne, int nc); -// -void d_create_core_qp_ipm(int nv, int ne, int nc, struct d_core_qp_ipm_workspace *workspace, void *mem); -// -void d_core_qp_ipm(struct d_core_qp_ipm_workspace *workspace); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // HPIPM_D_CORE_QP_IPM_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_core_qp_ipm_aux.h b/third_party/acados/include/hpipm/include/hpipm_d_core_qp_ipm_aux.h deleted file mode 100644 index 30cc824..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_core_qp_ipm_aux.h +++ /dev/null @@ -1,68 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_CORE_QP_IPM_AUX_ -#define HPIPM_S_CORE_QP_IPM_AUX_ - -#ifdef __cplusplus -extern "C" { -#endif - -// -void d_compute_Gamma_gamma_qp(double *res_d, double *res_m, struct d_core_qp_ipm_workspace *rws); -// -void d_compute_gamma_qp(double *res_d, double *res_m, struct d_core_qp_ipm_workspace *rws); -// -void d_compute_lam_t_qp(double *res_d, double *res_m, double *dlam, double *dt, struct d_core_qp_ipm_workspace *rws); -// -void d_compute_alpha_qp(struct d_core_qp_ipm_workspace *rws); -// -void d_update_var_qp(struct d_core_qp_ipm_workspace *rws); -// -void d_compute_mu_aff_qp(struct d_core_qp_ipm_workspace *rws); -// -void d_backup_res_m(struct d_core_qp_ipm_workspace *rws); -// -void d_compute_centering_correction_qp(struct d_core_qp_ipm_workspace *rws); -// -void d_compute_centering_qp(struct d_core_qp_ipm_workspace *rws); -// -void d_compute_tau_min_qp(struct d_core_qp_ipm_workspace *rws); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // HPIPM_S_CORE_QP_IPM_AUX_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_dense_qcqp.h b/third_party/acados/include/hpipm/include/hpipm_d_dense_qcqp.h deleted file mode 100644 index 3da5716..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_dense_qcqp.h +++ /dev/null @@ -1,199 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_D_DENSE_QCQP_H_ -#define HPIPM_D_DENSE_QCQP_H_ - - - -#include -#include - -#include "hpipm_d_dense_qcqp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_dense_qcqp - { - struct d_dense_qcqp_dim *dim; - struct blasfeo_dmat *Hv; // hessian of cost & vector work space - struct blasfeo_dmat *A; // equality constraint matrix - struct blasfeo_dmat *Ct; // inequality constraints matrix - struct blasfeo_dmat *Hq; // hessians of quadratic constraints - struct blasfeo_dvec *gz; // gradient of cost & gradient of slacks - struct blasfeo_dvec *b; // equality constraint vector - struct blasfeo_dvec *d; // inequality constraints vector - struct blasfeo_dvec *d_mask; // inequality constraints mask vector - struct blasfeo_dvec *m; // rhs of complementarity condition - struct blasfeo_dvec *Z; // (diagonal) hessian of slacks - int *idxb; // indices of box constrained variables within [u; x] - int *idxs_rev; // index of soft constraints (reverse storage) - int *Hq_nzero; // for each int, the last 3 bits ...abc, {a,b,c}=0 => {R,S,Q}=0 - hpipm_size_t memsize; // memory size in bytes - }; - - - -// -hpipm_size_t d_dense_qcqp_memsize(struct d_dense_qcqp_dim *dim); -// -void d_dense_qcqp_create(struct d_dense_qcqp_dim *dim, struct d_dense_qcqp *qp, void *memory); - -// -void d_dense_qcqp_set(char *field, void *value, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_H(double *H, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_g(double *g, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_A(double *A, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_b(double *b, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_idxb(int *idxb, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_lb(double *lb, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_lb_mask(double *lb, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_ub(double *ub, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_ub_mask(double *ub, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_C(double *C, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_lg(double *lg, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_lg_mask(double *lg, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_ug(double *ug, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_ug_mask(double *ug, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_Hq(double *Hq, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_gq(double *gq, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_uq(double *uq, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_uq_mask(double *uq, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_idxs(int *idxs, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_idxs_rev(int *idxs_rev, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_Zl(double *Zl, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_Zu(double *Zu, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_zl(double *zl, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_zu(double *zu, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_ls(double *ls, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_ls_mask(double *ls, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_us(double *us, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_set_us_mask(double *us, struct d_dense_qcqp *qp); - -// getters (COLMAJ) - -void d_dense_qcqp_get_H(struct d_dense_qcqp *qp, double *H); -// -void d_dense_qcqp_get_g(struct d_dense_qcqp *qp, double *g); -// -void d_dense_qcqp_get_A(struct d_dense_qcqp *qp, double *A); -// -void d_dense_qcqp_get_b(struct d_dense_qcqp *qp, double *b); -// -void d_dense_qcqp_get_idxb(struct d_dense_qcqp *qp, int *idxb); -// -void d_dense_qcqp_get_lb(struct d_dense_qcqp *qp, double *lb); -// -void d_dense_qcqp_get_lb_mask(struct d_dense_qcqp *qp, double *lb); -// -void d_dense_qcqp_get_ub(struct d_dense_qcqp *qp, double *ub); -// -void d_dense_qcqp_get_ub_mask(struct d_dense_qcqp *qp, double *ub); -// -void d_dense_qcqp_get_C(struct d_dense_qcqp *qp, double *C); -// -void d_dense_qcqp_get_lg(struct d_dense_qcqp *qp, double *lg); -// -void d_dense_qcqp_get_lg_mask(struct d_dense_qcqp *qp, double *lg); -// -void d_dense_qcqp_get_ug(struct d_dense_qcqp *qp, double *ug); -// -void d_dense_qcqp_get_ug_mask(struct d_dense_qcqp *qp, double *ug); -// -void d_dense_qcqp_get_idxs(struct d_dense_qcqp *qp, int *idxs); -// -void d_dense_qcqp_get_idxs_rev(struct d_dense_qcqp *qp, int *idxs_rev); -// -void d_dense_qcqp_get_Zl(struct d_dense_qcqp *qp, double *Zl); -// -void d_dense_qcqp_get_Zu(struct d_dense_qcqp *qp, double *Zu); -// -void d_dense_qcqp_get_zl(struct d_dense_qcqp *qp, double *zl); -// -void d_dense_qcqp_get_zu(struct d_dense_qcqp *qp, double *zu); -// -void d_dense_qcqp_get_ls(struct d_dense_qcqp *qp, double *ls); -// -void d_dense_qcqp_get_ls_mask(struct d_dense_qcqp *qp, double *ls); -// -void d_dense_qcqp_get_us(struct d_dense_qcqp *qp, double *us); -// -void d_dense_qcqp_get_us_mask(struct d_dense_qcqp *qp, double *us); - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_D_DENSE_QCQP_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_dense_qcqp_dim.h b/third_party/acados/include/hpipm/include/hpipm_d_dense_qcqp_dim.h deleted file mode 100644 index fa8c574..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_dense_qcqp_dim.h +++ /dev/null @@ -1,98 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_DENSE_QCQP_DIM_H_ -#define HPIPM_D_DENSE_QCQP_DIM_H_ - -#include "hpipm_common.h" - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_dense_qcqp_dim - { - struct d_dense_qp_dim *qp_dim; // dim of qp approximation - int nv; // number of variables - int ne; // number of equality constraints - int nb; // number of box constraints - int ng; // number of general constraints - int nq; // number of quadratic constraints - int nsb; // number of softened box constraints - int nsg; // number of softened general constraints - int nsq; // number of softened quadratic constraints - int ns; // number of softened constraints (nsb+nsg+nsq) TODO number of slacks - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_dense_qcqp_dim_memsize(); -// -void d_dense_qcqp_dim_create(struct d_dense_qcqp_dim *dim, void *memory); -// -void d_dense_qcqp_dim_set(char *field_name, int value, struct d_dense_qcqp_dim *dim); -// -void d_dense_qcqp_dim_set_nv(int value, struct d_dense_qcqp_dim *dim); -// -void d_dense_qcqp_dim_set_ne(int value, struct d_dense_qcqp_dim *dim); -// -void d_dense_qcqp_dim_set_nb(int value, struct d_dense_qcqp_dim *dim); -// -void d_dense_qcqp_dim_set_ng(int value, struct d_dense_qcqp_dim *dim); -// -void d_dense_qcqp_dim_set_nq(int value, struct d_dense_qcqp_dim *dim); -// -void d_dense_qcqp_dim_set_nsb(int value, struct d_dense_qcqp_dim *dim); -// -void d_dense_qcqp_dim_set_nsg(int value, struct d_dense_qcqp_dim *dim); -// -void d_dense_qcqp_dim_set_nsq(int value, struct d_dense_qcqp_dim *dim); -// -void d_dense_qcqp_dim_set_ns(int value, struct d_dense_qcqp_dim *dim); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_D_DENSE_QCQP_DIM_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_dense_qcqp_ipm.h b/third_party/acados/include/hpipm/include/hpipm_d_dense_qcqp_ipm.h deleted file mode 100644 index fa3f98f..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_dense_qcqp_ipm.h +++ /dev/null @@ -1,193 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_D_DENSE_QCQP_IPM_H_ -#define HPIPM_D_DENSE_QCQP_IPM_H_ - - - -#include -#include - -#include -#include -#include -#include -#include - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_dense_qcqp_ipm_arg - { - struct d_dense_qp_ipm_arg *qp_arg; - double mu0; // initial value for duality measure - double alpha_min; // exit cond on step length - double res_g_max; // exit cond on inf norm of residuals - double res_b_max; // exit cond on inf norm of residuals - double res_d_max; // exit cond on inf norm of residuals - double res_m_max; // exit cond on inf norm of residuals - double reg_prim; // reg of primal hessian - double reg_dual; // reg of dual hessian - double lam_min; // min value in lam vector - double t_min; // min value in t vector - int iter_max; // exit cond in iter number - int stat_max; // iterations saved in stat - int pred_corr; // Mehrotra's predictor-corrector IPM algirthm - int cond_pred_corr; // conditional Mehrotra's predictor-corrector - int scale; // scale hessian - int itref_pred_max; // max number of iterative refinement steps for predictor step - int itref_corr_max; // max number of iterative refinement steps for corrector step - int warm_start; // 0 no warm start, 1 warm start primal sol, 2 warm start primal and dual sol - int lq_fact; // 0 syrk+potrf, 1 mix, 2 lq - int abs_form; // absolute IPM formulation - int comp_res_exit; // compute residuals on exit (only for abs_form==1) - int comp_res_pred; // compute residuals of prediction - int split_step; // use different step for primal and dual variables - int t_lam_min; // clip t and lam: 0 no, 1 in Gamma computation, 2 in solution - int mode; - hpipm_size_t memsize; - }; - - - -struct d_dense_qcqp_ipm_ws - { - struct d_dense_qp_ipm_ws *qp_ws; - struct d_dense_qp *qp; - struct d_dense_qp_sol *qp_sol; - struct d_dense_qcqp_res_ws *qcqp_res_ws; - struct d_dense_qcqp_res *qcqp_res; - struct blasfeo_dvec *tmp_nv; - int iter; // iteration number - int status; - hpipm_size_t memsize; // memory size (in bytes) of workspace - }; - - - -// -hpipm_size_t d_dense_qcqp_ipm_arg_memsize(struct d_dense_qcqp_dim *dim); -// -void d_dense_qcqp_ipm_arg_create(struct d_dense_qcqp_dim *dim, struct d_dense_qcqp_ipm_arg *arg, void *mem); -// -void d_dense_qcqp_ipm_arg_set_default(enum hpipm_mode mode, struct d_dense_qcqp_ipm_arg *arg); -// -void d_dense_qcqp_ipm_arg_set(char *field, void *value, struct d_dense_qcqp_ipm_arg *arg); -// -void d_dense_qcqp_ipm_arg_set_iter_max(int *iter_max, struct d_dense_qcqp_ipm_arg *arg); -// -void d_dense_qcqp_ipm_arg_set_alpha_min(double *alpha_min, struct d_dense_qcqp_ipm_arg *arg); -// -void d_dense_qcqp_ipm_arg_set_mu0(double *mu0, struct d_dense_qcqp_ipm_arg *arg); -// -void d_dense_qcqp_ipm_arg_set_tol_stat(double *tol_stat, struct d_dense_qcqp_ipm_arg *arg); -// -void d_dense_qcqp_ipm_arg_set_tol_eq(double *tol_eq, struct d_dense_qcqp_ipm_arg *arg); -// -void d_dense_qcqp_ipm_arg_set_tol_ineq(double *tol_ineq, struct d_dense_qcqp_ipm_arg *arg); -// -void d_dense_qcqp_ipm_arg_set_tol_comp(double *tol_comp, struct d_dense_qcqp_ipm_arg *arg); -// -void d_dense_qcqp_ipm_arg_set_reg_prim(double *reg, struct d_dense_qcqp_ipm_arg *arg); -// -void d_dense_qcqp_ipm_arg_set_reg_dual(double *reg, struct d_dense_qcqp_ipm_arg *arg); -// -void d_dense_qcqp_ipm_arg_set_warm_start(int *warm_start, struct d_dense_qcqp_ipm_arg *arg); -// -void d_dense_qcqp_ipm_arg_set_pred_corr(int *pred_corr, struct d_dense_qcqp_ipm_arg *arg); -// -void d_dense_qcqp_ipm_arg_set_cond_pred_corr(int *cond_pred_corr, struct d_dense_qcqp_ipm_arg *arg); -// -void d_dense_qcqp_ipm_arg_set_comp_res_pred(int *comp_res_pred, struct d_dense_qcqp_ipm_arg *arg); -// -void d_dense_qcqp_ipm_arg_set_comp_res_exit(int *comp_res_exit, struct d_dense_qcqp_ipm_arg *arg); -// -void d_dense_qcqp_ipm_arg_set_lam_min(double *value, struct d_dense_qcqp_ipm_arg *arg); -// -void d_dense_qcqp_ipm_arg_set_t_min(double *value, struct d_dense_qcqp_ipm_arg *arg); -// -void d_dense_qcqp_ipm_arg_set_split_step(int *value, struct d_dense_qcqp_ipm_arg *arg); -// -void d_dense_qcqp_ipm_arg_set_t_lam_min(int *value, struct d_dense_qcqp_ipm_arg *arg); - -// -hpipm_size_t d_dense_qcqp_ipm_ws_memsize(struct d_dense_qcqp_dim *qp_dim, struct d_dense_qcqp_ipm_arg *arg); -// -void d_dense_qcqp_ipm_ws_create(struct d_dense_qcqp_dim *qp_dim, struct d_dense_qcqp_ipm_arg *arg, struct d_dense_qcqp_ipm_ws *ws, void *mem); -// -void d_dense_qcqp_ipm_get(char *field, struct d_dense_qcqp_ipm_ws *ws, void *value); -// -void d_dense_qcqp_ipm_get_status(struct d_dense_qcqp_ipm_ws *ws, int *status); -// -void d_dense_qcqp_ipm_get_iter(struct d_dense_qcqp_ipm_ws *ws, int *iter); -// -void d_dense_qcqp_ipm_get_max_res_stat(struct d_dense_qcqp_ipm_ws *ws, double *res_stat); -// -void d_dense_qcqp_ipm_get_max_res_eq(struct d_dense_qcqp_ipm_ws *ws, double *res_eq); -// -void d_dense_qcqp_ipm_get_max_res_ineq(struct d_dense_qcqp_ipm_ws *ws, double *res_ineq); -// -void d_dense_qcqp_ipm_get_max_res_comp(struct d_dense_qcqp_ipm_ws *ws, double *res_comp); -// -void d_dense_qcqp_ipm_get_stat(struct d_dense_qcqp_ipm_ws *ws, double **stat); -// -void d_dense_qcqp_ipm_get_stat_m(struct d_dense_qcqp_ipm_ws *ws, int *stat_m); -// -void d_dense_qcqp_init_var(struct d_dense_qcqp *qp, struct d_dense_qcqp_sol *qp_sol, struct d_dense_qcqp_ipm_arg *arg, struct d_dense_qcqp_ipm_ws *ws); -// -void d_dense_qcqp_ipm_solve(struct d_dense_qcqp *qp, struct d_dense_qcqp_sol *qp_sol, struct d_dense_qcqp_ipm_arg *arg, struct d_dense_qcqp_ipm_ws *ws); -#if 0 -// -void d_dense_qcqp_ipm_predict(struct d_dense_qcqp *qp, struct d_dense_qcqp_sol *qp_sol, struct d_dense_qcqp_ipm_arg *arg, struct d_dense_qcqp_ipm_ws *ws); -// -void d_dense_qcqp_ipm_sens(struct d_dense_qcqp *qp, struct d_dense_qcqp_sol *qp_sol, struct d_dense_qcqp_ipm_arg *arg, struct d_dense_qcqp_ipm_ws *ws); -#endif - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_D_DENSE_QCQP_IPM_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_dense_qcqp_res.h b/third_party/acados/include/hpipm/include/hpipm_d_dense_qcqp_res.h deleted file mode 100644 index a76f162..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_dense_qcqp_res.h +++ /dev/null @@ -1,107 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_DENSE_QCQP_RES_H_ -#define HPIPM_D_DENSE_QCQP_RES_H_ - - - -#include -#include - -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_dense_qcqp_res - { - struct d_dense_qcqp_dim *dim; - struct blasfeo_dvec *res_g; // q-residuals - struct blasfeo_dvec *res_b; // b-residuals - struct blasfeo_dvec *res_d; // d-residuals - struct blasfeo_dvec *res_m; // m-residuals - double res_max[4]; // infinity norm of residuals - double res_mu; // mu-residual - hpipm_size_t memsize; - }; - - - -struct d_dense_qcqp_res_ws - { - struct blasfeo_dvec *tmp_nv; // work space of size nv - struct blasfeo_dvec *tmp_nbgq; // work space of size nbM+ngM+nqM - struct blasfeo_dvec *tmp_ns; // work space of size nsM - struct blasfeo_dvec *q_fun; // value for evaluation of quadr constr - struct blasfeo_dvec *q_adj; // value for adjoint of quadr constr - int use_q_fun; // reuse cached value for evaluation of quadr constr - int use_q_adj; // reuse cached value for adjoint of quadr constr - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_dense_qcqp_res_memsize(struct d_dense_qcqp_dim *dim); -// -void d_dense_qcqp_res_create(struct d_dense_qcqp_dim *dim, struct d_dense_qcqp_res *res, void *mem); -// -hpipm_size_t d_dense_qcqp_res_ws_memsize(struct d_dense_qcqp_dim *dim); -// -void d_dense_qcqp_res_ws_create(struct d_dense_qcqp_dim *dim, struct d_dense_qcqp_res_ws *workspace, void *mem); -// -void d_dense_qcqp_res_compute(struct d_dense_qcqp *qp, struct d_dense_qcqp_sol *qp_sol, struct d_dense_qcqp_res *res, struct d_dense_qcqp_res_ws *ws); -// -void d_dense_qcqp_res_compute_inf_norm(struct d_dense_qcqp_res *res); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - -#endif // HPIPM_D_DENSE_QCQP_RES_H_ - - - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_dense_qcqp_sol.h b/third_party/acados/include/hpipm/include/hpipm_d_dense_qcqp_sol.h deleted file mode 100644 index 6c697a8..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_dense_qcqp_sol.h +++ /dev/null @@ -1,85 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_D_DENSE_QCQP_SOL_H_ -#define HPIPM_D_DENSE_QCQP_SOL_H_ - - - -#include -#include - -#include "hpipm_d_dense_qcqp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_dense_qcqp_sol - { - struct d_dense_qcqp_dim *dim; - struct blasfeo_dvec *v; - struct blasfeo_dvec *pi; - struct blasfeo_dvec *lam; - struct blasfeo_dvec *t; - void *misc; - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_dense_qcqp_sol_memsize(struct d_dense_qcqp_dim *dim); -// -void d_dense_qcqp_sol_create(struct d_dense_qcqp_dim *dim, struct d_dense_qcqp_sol *qp_sol, void *memory); -// -void d_dense_qcqp_sol_get_v(struct d_dense_qcqp_sol *qp_sol, double *v); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_D_DENSE_QCQP_SOL_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_dense_qcqp_utils.h b/third_party/acados/include/hpipm/include/hpipm_d_dense_qcqp_utils.h deleted file mode 100644 index a34218b..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_dense_qcqp_utils.h +++ /dev/null @@ -1,82 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_DENSE_QCQP_UTILS_H_ -#define HPIPM_D_DENSE_QCQP_UTILS_H_ - - - -#include -#include - -#include "hpipm_d_dense_qcqp_dim.h" -#include "hpipm_d_dense_qcqp.h" -#include "hpipm_d_dense_qcqp_sol.h" -//#include "hpipm_d_dense_qcqp_ipm.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -// -void d_dense_qcqp_dim_print(struct d_dense_qcqp_dim *qp_dim); -// -//void d_dense_qcqp_dim_codegen(char *file_name, char *mode, struct d_dense_qcqp_dim *qp_dim); -// -void d_dense_qcqp_print(struct d_dense_qcqp_dim *qp_dim, struct d_dense_qcqp *qp); -// -//void d_dense_qcqp_codegen(char *file_name, char *mode, struct d_dense_qcqp_dim *qp_dim, struct d_dense_qcqp *qp); -// -void d_dense_qcqp_sol_print(struct d_dense_qcqp_dim *qp_dim, struct d_dense_qcqp_sol *dense_qcqp_sol); -// -//void d_dense_qcqp_ipm_arg_codegen(char *file_name, char *mode, struct d_dense_qcqp_dim *qp_dim, struct d_dense_qcqp_ipm_arg *arg); -// -void d_dense_qcqp_res_print(struct d_dense_qcqp_dim *qp_dim, struct d_dense_qcqp_res *dense_qcqp_res); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_D_DENSE_QCQP_UTILS_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_dense_qp.h b/third_party/acados/include/hpipm/include/hpipm_d_dense_qp.h deleted file mode 100644 index 02fba5a..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_dense_qp.h +++ /dev/null @@ -1,207 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_D_DENSE_QP_H_ -#define HPIPM_D_DENSE_QP_H_ - - - -#include -#include - -#include "hpipm_d_dense_qp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_dense_qp - { - struct d_dense_qp_dim *dim; - struct blasfeo_dmat *Hv; // hessian of cost & vector work space - struct blasfeo_dmat *A; // equality constraint matrix - struct blasfeo_dmat *Ct; // inequality constraints matrix - struct blasfeo_dvec *gz; // gradient of cost & gradient of slacks - struct blasfeo_dvec *b; // equality constraint vector - struct blasfeo_dvec *d; // inequality constraints vector - struct blasfeo_dvec *d_mask; // inequality constraints mask vector - struct blasfeo_dvec *m; // rhs of complementarity condition - struct blasfeo_dvec *Z; // (diagonal) hessian of slacks - int *idxb; // indices of box constrained variables within [u; x] - int *idxs_rev; // index of soft constraints (reverse storage) - hpipm_size_t memsize; // memory size in bytes - }; - - - -// -hpipm_size_t d_dense_qp_memsize(struct d_dense_qp_dim *dim); -// -void d_dense_qp_create(struct d_dense_qp_dim *dim, struct d_dense_qp *qp, void *memory); - -// setters - colmaj -// -void d_dense_qp_set_all(double *H, double *g, double *A, double *b, int *idxb, double *d_lb, double *d_ub, double *C, double *d_lg, double *d_ug, double *Zl, double *Zu, double *zl, double *zu, int *idxs, double *d_ls, double *d_us, struct d_dense_qp *qp); -// -void d_dense_qp_get_all(struct d_dense_qp *qp, double *H, double *g, double *A, double *b, int *idxb, double *d_lb, double *d_ub, double *C, double *d_lg, double *d_ug, double *Zl, double *Zu, double *zl, double *zu, int *idxs, double *d_ls, double *d_us); -// -void d_dense_qp_set(char *field, void *value, struct d_dense_qp *qp); -// -void d_dense_qp_set_H(double *H, struct d_dense_qp *qp); -// -void d_dense_qp_set_g(double *g, struct d_dense_qp *qp); -// -void d_dense_qp_set_A(double *A, struct d_dense_qp *qp); -// -void d_dense_qp_set_b(double *b, struct d_dense_qp *qp); -// -void d_dense_qp_set_idxb(int *idxb, struct d_dense_qp *qp); -// -void d_dense_qp_set_Jb(double *Jb, struct d_dense_qp *qp); -// -void d_dense_qp_set_lb(double *lb, struct d_dense_qp *qp); -// -void d_dense_qp_set_lb_mask(double *lb, struct d_dense_qp *qp); -// -void d_dense_qp_set_ub(double *ub, struct d_dense_qp *qp); -// -void d_dense_qp_set_ub_mask(double *ub, struct d_dense_qp *qp); -// -void d_dense_qp_set_C(double *C, struct d_dense_qp *qp); -// -void d_dense_qp_set_lg(double *lg, struct d_dense_qp *qp); -// -void d_dense_qp_set_lg_mask(double *lg, struct d_dense_qp *qp); -// -void d_dense_qp_set_ug(double *ug, struct d_dense_qp *qp); -// -void d_dense_qp_set_ug_mask(double *ug, struct d_dense_qp *qp); -// -void d_dense_qp_set_idxs(int *idxs, struct d_dense_qp *qp); -// -void d_dense_qp_set_idxs_rev(int *idxs_rev, struct d_dense_qp *qp); -// -void d_dense_qp_set_Jsb(double *Jsb, struct d_dense_qp *qp); -// -void d_dense_qp_set_Jsg(double *Jsg, struct d_dense_qp *qp); -// -void d_dense_qp_set_Zl(double *Zl, struct d_dense_qp *qp); -// -void d_dense_qp_set_Zu(double *Zu, struct d_dense_qp *qp); -// -void d_dense_qp_set_zl(double *zl, struct d_dense_qp *qp); -// -void d_dense_qp_set_zu(double *zu, struct d_dense_qp *qp); -// -void d_dense_qp_set_ls(double *ls, struct d_dense_qp *qp); -// -void d_dense_qp_set_ls_mask(double *ls, struct d_dense_qp *qp); -// -void d_dense_qp_set_us(double *us, struct d_dense_qp *qp); -// -void d_dense_qp_set_us_mask(double *us, struct d_dense_qp *qp); - -// getters - colmaj -// -void d_dense_qp_get_H(struct d_dense_qp *qp, double *H); -// -void d_dense_qp_get_g(struct d_dense_qp *qp, double *g); -// -void d_dense_qp_get_A(struct d_dense_qp *qp, double *A); -// -void d_dense_qp_get_b(struct d_dense_qp *qp, double *b); -// -void d_dense_qp_get_idxb(struct d_dense_qp *qp, int *idxb); -// -void d_dense_qp_get_lb(struct d_dense_qp *qp, double *lb); -// -void d_dense_qp_get_lb_mask(struct d_dense_qp *qp, double *lb); -// -void d_dense_qp_get_ub(struct d_dense_qp *qp, double *ub); -// -void d_dense_qp_get_ub_mask(struct d_dense_qp *qp, double *ub); -// -void d_dense_qp_get_C(struct d_dense_qp *qp, double *C); -// -void d_dense_qp_get_lg(struct d_dense_qp *qp, double *lg); -// -void d_dense_qp_get_lg_mask(struct d_dense_qp *qp, double *lg); -// -void d_dense_qp_get_ug(struct d_dense_qp *qp, double *ug); -// -void d_dense_qp_get_ug_mask(struct d_dense_qp *qp, double *ug); -// -void d_dense_qp_get_idxs(struct d_dense_qp *qp, int *idxs); -// -void d_dense_qp_get_idxs_rev(struct d_dense_qp *qp, int *idxs_rev); -// -void d_dense_qp_get_Zl(struct d_dense_qp *qp, double *Zl); -// -void d_dense_qp_get_Zu(struct d_dense_qp *qp, double *Zu); -// -void d_dense_qp_get_zl(struct d_dense_qp *qp, double *zl); -// -void d_dense_qp_get_zu(struct d_dense_qp *qp, double *zu); -// -void d_dense_qp_get_ls(struct d_dense_qp *qp, double *ls); -// -void d_dense_qp_get_ls_mask(struct d_dense_qp *qp, double *ls); -// -void d_dense_qp_get_us(struct d_dense_qp *qp, double *us); -// -void d_dense_qp_get_us_mask(struct d_dense_qp *qp, double *us); - -// setters - rowmaj -// -void d_dense_qp_set_all_rowmaj(double *H, double *g, double *A, double *b, int *idxb, double *d_lb, double *d_ub, double *C, double *d_lg, double *d_ug, double *Zl, double *Zu, double *zl, double *zu, int *idxs, double *d_ls, double *d_us, struct d_dense_qp *qp); - -// getters - rowmaj -// -void d_dense_qp_get_all_rowmaj(struct d_dense_qp *qp, double *H, double *g, double *A, double *b, int *idxb, double *d_lb, double *d_ub, double *C, double *d_lg, double *d_ug, double *Zl, double *Zu, double *zl, double *zu, int *idxs, double *d_ls, double *d_us); - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_D_DENSE_QP_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_dense_qp_dim.h b/third_party/acados/include/hpipm/include/hpipm_d_dense_qp_dim.h deleted file mode 100644 index 98a551f..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_dense_qp_dim.h +++ /dev/null @@ -1,92 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_DENSE_QP_DIM_H_ -#define HPIPM_D_DENSE_QP_DIM_H_ - -#include "hpipm_common.h" - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_dense_qp_dim - { - int nv; // number of variables - int ne; // number of equality constraints - int nb; // number of box constraints - int ng; // number of general constraints - int nsb; // number of softened box constraints - int nsg; // number of softened general constraints - int ns; // number of softened constraints (nsb+nsg) - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_dense_qp_dim_memsize(); -// -void d_dense_qp_dim_create(struct d_dense_qp_dim *qp_dim, void *memory); -// -void d_dense_qp_dim_set_all(int nv, int ne, int nb, int ng, int nsb, int nsg, struct d_dense_qp_dim *dim); -// -void d_dense_qp_dim_set(char *field_name, int value, struct d_dense_qp_dim *dim); -// -void d_dense_qp_dim_set_nv(int value, struct d_dense_qp_dim *dim); -// -void d_dense_qp_dim_set_ne(int value, struct d_dense_qp_dim *dim); -// -void d_dense_qp_dim_set_nb(int value, struct d_dense_qp_dim *dim); -// -void d_dense_qp_dim_set_ng(int value, struct d_dense_qp_dim *dim); -// -void d_dense_qp_dim_set_nsb(int value, struct d_dense_qp_dim *dim); -// -void d_dense_qp_dim_set_nsg(int value, struct d_dense_qp_dim *dim); -// -void d_dense_qp_dim_set_ns(int value, struct d_dense_qp_dim *dim); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_D_DENSE_QP_DIM_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_dense_qp_ipm.h b/third_party/acados/include/hpipm/include/hpipm_d_dense_qp_ipm.h deleted file mode 100644 index e6e5d5d..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_dense_qp_ipm.h +++ /dev/null @@ -1,260 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_D_DENSE_QP_IPM_H_ -#define HPIPM_D_DENSE_QP_IPM_H_ - - - -#include -#include - -#include -#include -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_dense_qp_ipm_arg - { - double mu0; // initial value for duality measure - double alpha_min; // exit cond on step length - double res_g_max; // exit cond on inf norm of residuals - double res_b_max; // exit cond on inf norm of residuals - double res_d_max; // exit cond on inf norm of residuals - double res_m_max; // exit cond on inf norm of residuals - double reg_prim; // reg of primal hessian - double reg_dual; // reg of dual hessian - double lam_min; // min value in lam vector - double t_min; // min value in t vector - double tau_min; // min value of barrier parameter - int iter_max; // exit cond in iter number - int stat_max; // iterations saved in stat - int pred_corr; // Mehrotra's predictor-corrector IPM algirthm - int cond_pred_corr; // conditional Mehrotra's predictor-corrector - int scale; // scale hessian - int itref_pred_max; // max number of iterative refinement steps for predictor step - int itref_corr_max; // max number of iterative refinement steps for corrector step - int warm_start; // 0 no warm start, 1 warm start primal sol, 2 warm start primal and dual sol - int lq_fact; // 0 syrk+potrf, 1 mix, 2 lq - int abs_form; // absolute IPM formulation - int comp_res_exit; // compute residuals on exit (only for abs_form==1) - int comp_res_pred; // compute residuals of prediction - int kkt_fact_alg; // 0 null-space, 1 schur-complement - int remove_lin_dep_eq; // 0 do not, 1 do check and remove linearly dependent equality constraints - int compute_obj; // compute obj on exit - int split_step; // use different steps for primal and dual variables - int t_lam_min; // clip t and lam: 0 no, 1 in Gamma computation, 2 in solution - int mode; - hpipm_size_t memsize; - }; - - - -struct d_dense_qp_ipm_ws - { - struct d_core_qp_ipm_workspace *core_workspace; - struct d_dense_qp_res_ws *res_ws; - struct d_dense_qp_sol *sol_step; - struct d_dense_qp_sol *sol_itref; - struct d_dense_qp *qp_step; - struct d_dense_qp *qp_itref; - struct d_dense_qp_res *res; - struct d_dense_qp_res *res_itref; - struct d_dense_qp_res *res_step; - struct blasfeo_dvec *Gamma; // - struct blasfeo_dvec *gamma; // - struct blasfeo_dvec *Zs_inv; // - struct blasfeo_dmat *Lv; // - struct blasfeo_dmat *AL; // - struct blasfeo_dmat *Le; // - struct blasfeo_dmat *Ctx; // - struct blasfeo_dvec *lv; // - struct blasfeo_dvec *sv; // scale for Lv - struct blasfeo_dvec *se; // scale for Le - struct blasfeo_dvec *tmp_nbg; // work space of size nb+ng - struct blasfeo_dvec *tmp_ns; // work space of size ns - struct blasfeo_dmat *lq0; - struct blasfeo_dmat *lq1; - struct blasfeo_dvec *tmp_m; - struct blasfeo_dmat *A_LQ; - struct blasfeo_dmat *A_Q; - struct blasfeo_dmat *Zt; - struct blasfeo_dmat *ZtH; - struct blasfeo_dmat *ZtHZ; - struct blasfeo_dvec *xy; - struct blasfeo_dvec *Yxy; - struct blasfeo_dvec *xz; - struct blasfeo_dvec *tmp_nv; - struct blasfeo_dvec *tmp_2ns; - struct blasfeo_dvec *tmp_nv2ns; - struct blasfeo_dmat *A_li; // A of linearly independent equality constraints - struct blasfeo_dvec *b_li; // b of linearly independent equality constraints - struct blasfeo_dmat *A_bkp; // pointer to backup A - struct blasfeo_dvec *b_bkp; // pointer to backup b - struct blasfeo_dmat *Ab_LU; - double *stat; // convergence statistics - int *ipiv_v; - int *ipiv_e; - int *ipiv_e1; - void *lq_work0; - void *lq_work1; - void *lq_work_null; - void *orglq_work_null; - int iter; // iteration number - int stat_max; // iterations saved in stat - int stat_m; // numer of recorded stat per ipm iter - int scale; - int use_hess_fact; - int use_A_fact; - int status; - int lq_fact; // cache from arg - int mask_constr; // use constr mask - int ne_li; // number of linearly independent equality constraints - int ne_bkp; // ne backup - hpipm_size_t memsize; // memory size (in bytes) of workspace - }; - - - -// -hpipm_size_t d_dense_qp_ipm_arg_memsize(struct d_dense_qp_dim *dim); -// -void d_dense_qp_ipm_arg_create(struct d_dense_qp_dim *dim, struct d_dense_qp_ipm_arg *arg, void *mem); -// -void d_dense_qp_ipm_arg_set_default(enum hpipm_mode mode, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_arg_set(char *field, void *value, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_arg_set_iter_max(int *iter_max, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_arg_set_alpha_min(double *alpha_min, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_arg_set_mu0(double *mu0, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_arg_set_tol_stat(double *tol_stat, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_arg_set_tol_eq(double *tol_eq, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_arg_set_tol_ineq(double *tol_ineq, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_arg_set_tol_comp(double *tol_comp, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_arg_set_reg_prim(double *reg, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_arg_set_reg_dual(double *reg, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_arg_set_warm_start(int *warm_start, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_arg_set_pred_corr(int *pred_corr, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_arg_set_cond_pred_corr(int *cond_pred_corr, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_arg_set_comp_res_pred(int *comp_res_pred, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_arg_set_comp_res_exit(int *comp_res_exit, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_arg_set_lam_min(double *value, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_arg_set_t_min(double *value, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_arg_set_tau_min(double *value, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_arg_set_kkt_fact_alg(int *value, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_arg_set_remove_lin_dep_eq(int *value, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_arg_set_compute_obj(int *value, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_arg_set_t_lam_min(int *value, struct d_dense_qp_ipm_arg *arg); - -// -void d_dense_qp_ipm_arg_set_split_step(int *value, struct d_dense_qp_ipm_arg *arg); - -// -hpipm_size_t d_dense_qp_ipm_ws_memsize(struct d_dense_qp_dim *qp_dim, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_ipm_ws_create(struct d_dense_qp_dim *qp_dim, struct d_dense_qp_ipm_arg *arg, struct d_dense_qp_ipm_ws *ws, void *mem); -// -void d_dense_qp_ipm_get(char *field, struct d_dense_qp_ipm_ws *ws, void *value); -// -void d_dense_qp_ipm_get_status(struct d_dense_qp_ipm_ws *ws, int *status); -// -void d_dense_qp_ipm_get_iter(struct d_dense_qp_ipm_ws *ws, int *iter); -// -void d_dense_qp_ipm_get_max_res_stat(struct d_dense_qp_ipm_ws *ws, double *res_stat); -// -void d_dense_qp_ipm_get_max_res_eq(struct d_dense_qp_ipm_ws *ws, double *res_eq); -// -void d_dense_qp_ipm_get_max_res_ineq(struct d_dense_qp_ipm_ws *ws, double *res_ineq); -// -void d_dense_qp_ipm_get_max_res_comp(struct d_dense_qp_ipm_ws *ws, double *res_comp); -// -void d_dense_qp_ipm_get_stat(struct d_dense_qp_ipm_ws *ws, double **stat); -// -void d_dense_qp_ipm_get_stat_m(struct d_dense_qp_ipm_ws *ws, int *stat_m); -// -void d_dense_qp_init_var(struct d_dense_qp *qp, struct d_dense_qp_sol *qp_sol, struct d_dense_qp_ipm_arg *arg, struct d_dense_qp_ipm_ws *ws); -// -void d_dense_qp_ipm_abs_step(int kk, struct d_dense_qp *qp, struct d_dense_qp_sol *qp_sol, struct d_dense_qp_ipm_arg *arg, struct d_dense_qp_ipm_ws *ws); -// -void d_dense_qp_ipm_delta_step(int kk, struct d_dense_qp *qp, struct d_dense_qp_sol *qp_sol, struct d_dense_qp_ipm_arg *arg, struct d_dense_qp_ipm_ws *ws); -// -void d_dense_qp_ipm_solve(struct d_dense_qp *qp, struct d_dense_qp_sol *qp_sol, struct d_dense_qp_ipm_arg *arg, struct d_dense_qp_ipm_ws *ws); -// -void d_dense_qp_ipm_predict(struct d_dense_qp *qp, struct d_dense_qp_sol *qp_sol, struct d_dense_qp_ipm_arg *arg, struct d_dense_qp_ipm_ws *ws); -// -void d_dense_qp_ipm_sens(struct d_dense_qp *qp, struct d_dense_qp_sol *qp_sol, struct d_dense_qp_ipm_arg *arg, struct d_dense_qp_ipm_ws *ws); -// -void d_dense_qp_compute_step_length(struct d_dense_qp *qp, struct d_dense_qp_sol *qp_sol, struct d_dense_qp_ipm_arg *arg, struct d_dense_qp_ipm_ws *ws); - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_D_DENSE_QP_IPM_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_dense_qp_kkt.h b/third_party/acados/include/hpipm/include/hpipm_d_dense_qp_kkt.h deleted file mode 100644 index 6d05779..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_dense_qp_kkt.h +++ /dev/null @@ -1,72 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_D_DENSE_QP_KKT_H_ -#define HPIPM_D_DENSE_QP_KKT_H_ - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -// -void d_fact_solve_kkt_unconstr_dense_qp(struct d_dense_qp *qp, struct d_dense_qp_sol *qp_sol, struct d_dense_qp_ipm_arg *arg, struct d_dense_qp_ipm_ws *ws); -// -void d_fact_solve_kkt_step_dense_qp(struct d_dense_qp *qp, struct d_dense_qp_sol *qp_sol, struct d_dense_qp_ipm_arg *arg, struct d_dense_qp_ipm_ws *ws); -// -void d_fact_lq_solve_kkt_step_dense_qp(struct d_dense_qp *qp, struct d_dense_qp_sol *qp_sol, struct d_dense_qp_ipm_arg *arg, struct d_dense_qp_ipm_ws *ws); -// -void d_solve_kkt_step_dense_qp(struct d_dense_qp *qp, struct d_dense_qp_sol *qp_sol, struct d_dense_qp_ipm_arg *arg, struct d_dense_qp_ipm_ws *ws); -// -void d_dense_qp_remove_lin_dep_eq(struct d_dense_qp *qp, struct d_dense_qp_ipm_arg *arg, struct d_dense_qp_ipm_ws *ws); -// -void d_dense_qp_restore_lin_dep_eq(struct d_dense_qp *qp, struct d_dense_qp_ipm_arg *arg, struct d_dense_qp_ipm_ws *ws); -// -void d_dense_qp_compute_obj(struct d_dense_qp *qp, struct d_dense_qp_sol *qp_sol, struct d_dense_qp_ipm_arg *arg, struct d_dense_qp_ipm_ws *ws); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_D_DENSE_QP_KKT_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_dense_qp_res.h b/third_party/acados/include/hpipm/include/hpipm_d_dense_qp_res.h deleted file mode 100644 index 7c20232..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_dense_qp_res.h +++ /dev/null @@ -1,105 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_DENSE_QP_RES_H_ -#define HPIPM_D_DENSE_QP_RES_H_ - - - -#include -#include - -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_dense_qp_res - { - struct d_dense_qp_dim *dim; - struct blasfeo_dvec *res_g; // q-residuals - struct blasfeo_dvec *res_b; // b-residuals - struct blasfeo_dvec *res_d; // d-residuals - struct blasfeo_dvec *res_m; // m-residuals - double res_max[4]; // max of residuals - double res_mu; // mu-residual - hpipm_size_t memsize; - }; - - - -struct d_dense_qp_res_ws - { - struct blasfeo_dvec *tmp_nbg; // work space of size nbM+ngM - struct blasfeo_dvec *tmp_ns; // work space of size nsM - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_dense_qp_res_memsize(struct d_dense_qp_dim *dim); -// -void d_dense_qp_res_create(struct d_dense_qp_dim *dim, struct d_dense_qp_res *res, void *mem); -// -hpipm_size_t d_dense_qp_res_ws_memsize(struct d_dense_qp_dim *dim); -// -void d_dense_qp_res_ws_create(struct d_dense_qp_dim *dim, struct d_dense_qp_res_ws *workspace, void *mem); -// -void d_dense_qp_res_compute(struct d_dense_qp *qp, struct d_dense_qp_sol *qp_sol, struct d_dense_qp_res *res, struct d_dense_qp_res_ws *ws); -// -void d_dense_qp_res_compute_lin(struct d_dense_qp *qp, struct d_dense_qp_sol *qp_sol, struct d_dense_qp_sol *qp_step, struct d_dense_qp_res *res, struct d_dense_qp_res_ws *ws); -// -void d_dense_qp_res_compute_inf_norm(struct d_dense_qp_res *res); -// -void d_dense_qp_res_get_all(struct d_dense_qp_res *res, double *res_g, double *res_ls, double *res_us, double *res_b, double *res_d_lb, double *res_d_ub, double *res_d_lg, double *res_d_ug, double *res_d_ls, double *res_d_us, double *res_m_lb, double *res_m_ub, double *res_m_lg, double *res_m_ug, double *res_m_ls, double *res_m_us); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - -#endif // HPIPM_D_DENSE_QP_RES_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_dense_qp_sol.h b/third_party/acados/include/hpipm/include/hpipm_d_dense_qp_sol.h deleted file mode 100644 index aaa3fdb..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_dense_qp_sol.h +++ /dev/null @@ -1,94 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_D_DENSE_QP_SOL_H_ -#define HPIPM_D_DENSE_QP_SOL_H_ - - - -#include -#include - -#include "hpipm_d_dense_qp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_dense_qp_sol - { - struct d_dense_qp_dim *dim; - struct blasfeo_dvec *v; - struct blasfeo_dvec *pi; - struct blasfeo_dvec *lam; - struct blasfeo_dvec *t; - void *misc; - double obj; - int valid_obj; - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_dense_qp_sol_memsize(struct d_dense_qp_dim *dim); -// -void d_dense_qp_sol_create(struct d_dense_qp_dim *dim, struct d_dense_qp_sol *qp_sol, void *memory); -// -void d_dense_qp_sol_get_all(struct d_dense_qp_sol *qp_sol, double *v, double *ls, double *us, double *pi, double *lam_lb, double *lam_ub, double *lam_lg, double *lam_ug, double *lam_ls, double *lam_us); -// -void d_dense_qp_sol_get(char *field, struct d_dense_qp_sol *sol, void *value); -// -void d_dense_qp_sol_get_v(struct d_dense_qp_sol *sol, double *v); -// -void d_dense_qp_sol_get_valid_obj(struct d_dense_qp_sol *sol, int *valid_obj); -// -void d_dense_qp_sol_get_obj(struct d_dense_qp_sol *sol, double *obj); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_D_DENSE_QP_SOL_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_dense_qp_utils.h b/third_party/acados/include/hpipm/include/hpipm_d_dense_qp_utils.h deleted file mode 100644 index ccb77aa..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_dense_qp_utils.h +++ /dev/null @@ -1,83 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_DENSE_QP_UTILS_H_ -#define HPIPM_D_DENSE_QP_UTILS_H_ - - - -#include -#include - -#include "hpipm_d_dense_qp_dim.h" -#include "hpipm_d_dense_qp.h" -#include "hpipm_d_dense_qp_sol.h" -#include "hpipm_d_dense_qp_ipm.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -// -void d_dense_qp_dim_print(struct d_dense_qp_dim *qp_dim); -// -//void d_dense_qp_dim_codegen(char *file_name, char *mode, struct d_dense_qp_dim *qp_dim); -// -void d_dense_qp_print(struct d_dense_qp_dim *qp_dim, struct d_dense_qp *qp); -// -//void d_dense_qp_codegen(char *file_name, char *mode, struct d_dense_qp_dim *qp_dim, struct d_dense_qp *qp); -// -void d_dense_qp_sol_print(struct d_dense_qp_dim *qp_dim, struct d_dense_qp_sol *dense_qp_sol); -// -//void d_dense_qp_ipm_arg_codegen(char *file_name, char *mode, struct d_dense_qp_dim *qp_dim, struct d_dense_qp_ipm_arg *arg); -// -void d_dense_qp_res_print(struct d_dense_qp_dim *qp_dim, struct d_dense_qp_res *dense_qp_res); -// -void d_dense_qp_arg_print(struct d_dense_qp_dim *qp_dim, struct d_dense_qp_ipm_arg *qp_ipm_arg); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_D_DENSE_QP_UTILS_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qcqp.h b/third_party/acados/include/hpipm/include/hpipm_d_ocp_qcqp.h deleted file mode 100644 index 240c9b0..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qcqp.h +++ /dev/null @@ -1,303 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_OCP_QCQP_H_ -#define HPIPM_D_OCP_QCQP_H_ - - - -#include -#include - -#include "hpipm_d_ocp_qcqp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_ocp_qcqp - { - struct d_ocp_qcqp_dim *dim; - struct blasfeo_dmat *BAbt; // dynamics matrix & vector work space - struct blasfeo_dmat *RSQrq; // hessian of cost & vector work space - struct blasfeo_dmat *DCt; // inequality constraints matrix - struct blasfeo_dmat **Hq; // hessians of quadratic constraints - struct blasfeo_dvec *b; // dynamics vector - struct blasfeo_dvec *rqz; // gradient of cost & gradient of slacks - struct blasfeo_dvec *d; // inequality constraints vector - struct blasfeo_dvec *d_mask; // inequality constraints mask vector - struct blasfeo_dvec *m; // rhs of complementarity condition - struct blasfeo_dvec *Z; // (diagonal) hessian of slacks - int **idxb; // indices of box constrained variables within [u; x] - int **idxs_rev; // index of soft constraints (reverse storage) - int **Hq_nzero; // for each int, the last 3 bits ...abc, {a,b,c}=0 => {R,S,Q}=0 - hpipm_size_t memsize; // memory size in bytes - }; - - - -// -hpipm_size_t d_ocp_qcqp_strsize(); -// -hpipm_size_t d_ocp_qcqp_memsize(struct d_ocp_qcqp_dim *dim); -// -void d_ocp_qcqp_create(struct d_ocp_qcqp_dim *dim, struct d_ocp_qcqp *qp, void *memory); -// -void d_ocp_qcqp_copy_all(struct d_ocp_qcqp *qp_orig, struct d_ocp_qcqp *qp_dest); - -// setters -// -void d_ocp_qcqp_set_all_zero(struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_rhs_zero(struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set(char *field_name, int stage, void *value, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_el(char *field_name, int stage, int index, void *value, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_A(int stage, double *mat, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_B(int stage, double *mat, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_b(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_Q(int stage, double *mat, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_S(int stage, double *mat, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_R(int stage, double *mat, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_q(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_r(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_lb(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_lb_mask(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_ub(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_ub_mask(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_lbx(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_lbx_mask(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_el_lbx(int stage, int index, double *elem, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_ubx(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_ubx_mask(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_el_ubx(int stage, int index, double *elem, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_lbu(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_lbu_mask(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_ubu(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_ubu_mask(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_idxb(int stage, int *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_idxbx(int stage, int *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_Jbx(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_idxbu(int stage, int *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_Jbu(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_C(int stage, double *mat, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_D(int stage, double *mat, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_lg(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_lg_mask(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_ug(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_ug_mask(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_Qq(int stage, double *mat, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_Sq(int stage, double *mat, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_Rq(int stage, double *mat, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_qq(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_rq(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_uq(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_uq_mask(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_Zl(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_Zu(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_zl(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_zu(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_lls(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_lls_mask(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_lus(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_lus_mask(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_idxs(int stage, int *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_idxs_rev(int stage, int *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_Jsbu(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_Jsbx(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_Jsg(int stage, double *vec, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_set_Jsq(int stage, double *vec, struct d_ocp_qcqp *qp); - -// getters -// -void d_ocp_qcqp_get(char *field, int stage, struct d_ocp_qcqp *qp, void *value); -// -void d_ocp_qcqp_get_A(int stage, struct d_ocp_qcqp *qp, double *mat); -// -void d_ocp_qcqp_get_B(int stage, struct d_ocp_qcqp *qp, double *mat); -// -void d_ocp_qcqp_get_b(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_Q(int stage, struct d_ocp_qcqp *qp, double *mat); -// -void d_ocp_qcqp_get_S(int stage, struct d_ocp_qcqp *qp, double *mat); -// -void d_ocp_qcqp_get_R(int stage, struct d_ocp_qcqp *qp, double *mat); -// -void d_ocp_qcqp_get_q(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_r(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_ub(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_ub_mask(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_lb(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_lb_mask(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_lbx(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_lbx_mask(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_ubx(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_ubx_mask(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_lbu(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_lbu_mask(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_ubu(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_ubu_mask(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_idxb(int stage, struct d_ocp_qcqp *qp, int *vec); -// -//void d_ocp_qcqp_get_idxbx(int stage, struct d_ocp_qcqp *qp, int *vec); -// -//void d_ocp_qcqp_get_Jbx(int stage, struct d_ocp_qcqp *qp, double *vec); -// -//void d_ocp_qcqp_get_idxbu(int stage, struct d_ocp_qcqp *qp, int *vec); -// -//void d_ocp_qcqp_get_Jbu(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_C(int stage, struct d_ocp_qcqp *qp, double *mat); -// -void d_ocp_qcqp_get_D(int stage, struct d_ocp_qcqp *qp, double *mat); -// -void d_ocp_qcqp_get_lg(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_lg_mask(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_ug(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_ug_mask(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_Zl(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_Zu(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_zl(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_zu(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_lls(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_lls_mask(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_lus(int stage, struct d_ocp_qcqp *qp, double *vec); -// -void d_ocp_qcqp_get_lus_mask(int stage, struct d_ocp_qcqp *qp, double *vec); -// XXX only valid if there is one slack per softed constraint !!! -void d_ocp_qcqp_get_idxs(int stage, struct d_ocp_qcqp *qp, int *vec); -// -void d_ocp_qcqp_get_idxs_rev(int stage, struct d_ocp_qcqp *qp, int *vec); -// -//void d_ocp_qcqp_get_Jsbu(int stage, struct d_ocp_qcqp *qp, float *vec); -// -//void d_ocp_qcqp_get_Jsbx(int stage, struct d_ocp_qcqp *qp, float *vec); -// -//void d_ocp_qcqp_get_Jsg(int stage, struct d_ocp_qcqp *qp, float *vec); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_D_OCP_QCQP_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qcqp_dim.h b/third_party/acados/include/hpipm/include/hpipm_d_ocp_qcqp_dim.h deleted file mode 100644 index 268628a..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qcqp_dim.h +++ /dev/null @@ -1,118 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_OCP_QCQP_DIM_H_ -#define HPIPM_D_OCP_QCQP_DIM_H_ - -#include "hpipm_common.h" - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_ocp_qcqp_dim - { - struct d_ocp_qp_dim *qp_dim; // dim of qp approximation - int *nx; // number of states - int *nu; // number of inputs - int *nb; // number of box constraints - int *nbx; // number of (two-sided) state box constraints - int *nbu; // number of (two-sided) input box constraints - int *ng; // number of (two-sided) general constraints - int *nq; // number of (upper) quadratic constraints - int *ns; // number of soft constraints - int *nsbx; // number of (two-sided) soft state box constraints - int *nsbu; // number of (two-sided) soft input box constraints - int *nsg; // number of (two-sided) soft general constraints - int *nsq; // number of (upper) soft quadratic constraints - int N; // horizon length - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_ocp_qcqp_dim_strsize(); -// -hpipm_size_t d_ocp_qcqp_dim_memsize(int N); -// -void d_ocp_qcqp_dim_create(int N, struct d_ocp_qcqp_dim *qp_dim, void *memory); -// -void d_ocp_qcqp_dim_copy_all(struct d_ocp_qcqp_dim *dim_orig, struct d_ocp_qcqp_dim *dim_dest); -// -void d_ocp_qcqp_dim_set(char *field, int stage, int value, struct d_ocp_qcqp_dim *dim); -// -void d_ocp_qcqp_dim_set_nx(int stage, int value, struct d_ocp_qcqp_dim *dim); -// -void d_ocp_qcqp_dim_set_nu(int stage, int value, struct d_ocp_qcqp_dim *dim); -// -void d_ocp_qcqp_dim_set_nbx(int stage, int value, struct d_ocp_qcqp_dim *dim); -// -void d_ocp_qcqp_dim_set_nbu(int stage, int value, struct d_ocp_qcqp_dim *dim); -// -void d_ocp_qcqp_dim_set_ng(int stage, int value, struct d_ocp_qcqp_dim *dim); -// -void d_ocp_qcqp_dim_set_nq(int stage, int value, struct d_ocp_qcqp_dim *dim); -// -void d_ocp_qcqp_dim_set_ns(int stage, int value, struct d_ocp_qcqp_dim *dim); -// -void d_ocp_qcqp_dim_set_nsbx(int stage, int value, struct d_ocp_qcqp_dim *dim); -// -void d_ocp_qcqp_dim_set_nsbu(int stage, int value, struct d_ocp_qcqp_dim *dim); -// -void d_ocp_qcqp_dim_set_nsg(int stage, int value, struct d_ocp_qcqp_dim *dim); -// -void d_ocp_qcqp_dim_set_nsq(int stage, int value, struct d_ocp_qcqp_dim *dim); -// -void d_ocp_qcqp_dim_get(struct d_ocp_qcqp_dim *dim, char *field, int stage, int *value); -// -void d_ocp_qcqp_dim_get_N(struct d_ocp_qcqp_dim *dim, int *value); -// -void d_ocp_qcqp_dim_get_nx(struct d_ocp_qcqp_dim *dim, int stage, int *value); -// -void d_ocp_qcqp_dim_get_nu(struct d_ocp_qcqp_dim *dim, int stage, int *value); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_D_OCP_QCQP_DIM_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qcqp_ipm.h b/third_party/acados/include/hpipm/include/hpipm_d_ocp_qcqp_ipm.h deleted file mode 100644 index 99f2329..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qcqp_ipm.h +++ /dev/null @@ -1,190 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_OCP_QCQP_IPM_H_ -#define HPIPM_D_OCP_QCQP_IPM_H_ - - - -#include -#include - -#include -#include -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_ocp_qcqp_ipm_arg - { - struct d_ocp_qp_ipm_arg *qp_arg; - double mu0; // initial value for complementarity slackness - double alpha_min; // exit cond on step length - double res_g_max; // exit cond on inf norm of residuals - double res_b_max; // exit cond on inf norm of residuals - double res_d_max; // exit cond on inf norm of residuals - double res_m_max; // exit cond on inf norm of residuals - double reg_prim; // reg of primal hessian - double lam_min; // min value in lam vector - double t_min; // min value in t vector - int iter_max; // exit cond in iter number - int stat_max; // iterations saved in stat - int pred_corr; // use Mehrotra's predictor-corrector IPM algirthm - int cond_pred_corr; // conditional Mehrotra's predictor-corrector - int itref_pred_max; // max number of iterative refinement steps for predictor step - int itref_corr_max; // max number of iterative refinement steps for corrector step - int warm_start; // 0 no warm start, 1 warm start primal sol, 2 warm start primal and dual sol - int square_root_alg; // 0 classical Riccati, 1 square-root Riccati - int lq_fact; // 0 syrk+potrf, 1 mix, 2 lq (for square_root_alg==1) - int abs_form; // absolute IPM formulation - int comp_dual_sol_eq; // dual solution of equality constrains (only for abs_form==1) - int comp_res_exit; // compute residuals on exit (only for abs_form==1 and comp_dual_sol_eq==1) - int comp_res_pred; // compute residuals of prediction - int split_step; // use different step for primal and dual variables - int t_lam_min; // clip t and lam: 0 no, 1 in Gamma computation, 2 in solution - int mode; - hpipm_size_t memsize; - }; - - - -struct d_ocp_qcqp_ipm_ws - { - struct d_ocp_qp_ipm_ws *qp_ws; - struct d_ocp_qp *qp; - struct d_ocp_qp_sol *qp_sol; - struct d_ocp_qcqp_res_ws *qcqp_res_ws; - struct d_ocp_qcqp_res *qcqp_res; - struct blasfeo_dvec *tmp_nuxM; - int iter; // iteration number - int status; - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_ocp_qcqp_ipm_arg_strsize(); -// -hpipm_size_t d_ocp_qcqp_ipm_arg_memsize(struct d_ocp_qcqp_dim *ocp_dim); -// -void d_ocp_qcqp_ipm_arg_create(struct d_ocp_qcqp_dim *ocp_dim, struct d_ocp_qcqp_ipm_arg *arg, void *mem); -// -void d_ocp_qcqp_ipm_arg_set_default(enum hpipm_mode mode, struct d_ocp_qcqp_ipm_arg *arg); -// -void d_ocp_qcqp_ipm_arg_set(char *field, void *value, struct d_ocp_qcqp_ipm_arg *arg); -// set maximum number of iterations -void d_ocp_qcqp_ipm_arg_set_iter_max(int *value, struct d_ocp_qcqp_ipm_arg *arg); -// set minimum step lenght -void d_ocp_qcqp_ipm_arg_set_alpha_min(double *value, struct d_ocp_qcqp_ipm_arg *arg); -// set initial value of barrier parameter -void d_ocp_qcqp_ipm_arg_set_mu0(double *value, struct d_ocp_qcqp_ipm_arg *arg); -// set exit tolerance on stationarity condition -void d_ocp_qcqp_ipm_arg_set_tol_stat(double *value, struct d_ocp_qcqp_ipm_arg *arg); -// set exit tolerance on equality constr -void d_ocp_qcqp_ipm_arg_set_tol_eq(double *value, struct d_ocp_qcqp_ipm_arg *arg); -// set exit tolerance on inequality constr -void d_ocp_qcqp_ipm_arg_set_tol_ineq(double *value, struct d_ocp_qcqp_ipm_arg *arg); -// set exit tolerance on complementarity condition -void d_ocp_qcqp_ipm_arg_set_tol_comp(double *value, struct d_ocp_qcqp_ipm_arg *arg); -// set regularization of primal variables -void d_ocp_qcqp_ipm_arg_set_reg_prim(double *value, struct d_ocp_qcqp_ipm_arg *arg); -// set warm start: 0 no warm start, 1 primal var -void d_ocp_qcqp_ipm_arg_set_warm_start(int *value, struct d_ocp_qcqp_ipm_arg *arg); -// Mehrotra's predictor-corrector IPM algorithm: 0 no predictor-corrector, 1 use predictor-corrector -void d_ocp_qcqp_ipm_arg_set_pred_corr(int *value, struct d_ocp_qcqp_ipm_arg *arg); -// conditional predictor-corrector: 0 no conditinal predictor-corrector, 1 conditional predictor-corrector -void d_ocp_qcqp_ipm_arg_set_cond_pred_corr(int *value, struct d_ocp_qcqp_ipm_arg *arg); -// set riccati algorithm: 0 classic, 1 square-root -void d_ocp_qcqp_ipm_arg_set_ric_alg(int *value, struct d_ocp_qcqp_ipm_arg *arg); -// compute residuals after solution -void d_ocp_qcqp_ipm_arg_set_comp_res_exit(int *value, struct d_ocp_qcqp_ipm_arg *arg); -// compute residuals of prediction -void d_ocp_qcqp_ipm_arg_set_comp_res_pred(int *value, struct d_ocp_qcqp_ipm_arg *arg); -// min value of lam in the solution -void d_ocp_qcqp_ipm_arg_set_lam_min(double *value, struct d_ocp_qcqp_ipm_arg *arg); -// min value of t in the solution -void d_ocp_qcqp_ipm_arg_set_t_min(double *value, struct d_ocp_qcqp_ipm_arg *arg); -// use different step for primal and dual variables -void d_ocp_qcqp_ipm_arg_set_split_step(int *value, struct d_ocp_qcqp_ipm_arg *arg); -// clip t and lam: 0 no, 1 in Gamma computation, 2 in solution -void d_ocp_qcqp_ipm_arg_set_t_lam_min(int *value, struct d_ocp_qcqp_ipm_arg *arg); - -// -hpipm_size_t d_ocp_qcqp_ipm_ws_strsize(); -// -hpipm_size_t d_ocp_qcqp_ipm_ws_memsize(struct d_ocp_qcqp_dim *ocp_dim, struct d_ocp_qcqp_ipm_arg *arg); -// -void d_ocp_qcqp_ipm_ws_create(struct d_ocp_qcqp_dim *ocp_dim, struct d_ocp_qcqp_ipm_arg *arg, struct d_ocp_qcqp_ipm_ws *ws, void *mem); -// -void d_ocp_qcqp_ipm_get(char *field, struct d_ocp_qcqp_ipm_ws *ws, void *value); -// -void d_ocp_qcqp_ipm_get_status(struct d_ocp_qcqp_ipm_ws *ws, int *status); -// -void d_ocp_qcqp_ipm_get_iter(struct d_ocp_qcqp_ipm_ws *ws, int *iter); -// -void d_ocp_qcqp_ipm_get_max_res_stat(struct d_ocp_qcqp_ipm_ws *ws, double *res_stat); -// -void d_ocp_qcqp_ipm_get_max_res_eq(struct d_ocp_qcqp_ipm_ws *ws, double *res_eq); -// -void d_ocp_qcqp_ipm_get_max_res_ineq(struct d_ocp_qcqp_ipm_ws *ws, double *res_ineq); -// -void d_ocp_qcqp_ipm_get_max_res_comp(struct d_ocp_qcqp_ipm_ws *ws, double *res_comp); -// -void d_ocp_qcqp_ipm_get_stat(struct d_ocp_qcqp_ipm_ws *ws, double **stat); -// -void d_ocp_qcqp_ipm_get_stat_m(struct d_ocp_qcqp_ipm_ws *ws, int *stat_m); -// -void d_ocp_qcqp_init_var(struct d_ocp_qcqp *qp, struct d_ocp_qcqp_sol *qp_sol, struct d_ocp_qcqp_ipm_arg *arg, struct d_ocp_qcqp_ipm_ws *ws); -// -void d_ocp_qcqp_ipm_solve(struct d_ocp_qcqp *qp, struct d_ocp_qcqp_sol *qp_sol, struct d_ocp_qcqp_ipm_arg *arg, struct d_ocp_qcqp_ipm_ws *ws); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - -#endif // HPIPM_D_OCP_QCQP_IPM_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qcqp_res.h b/third_party/acados/include/hpipm/include/hpipm_d_ocp_qcqp_res.h deleted file mode 100644 index 077f134..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qcqp_res.h +++ /dev/null @@ -1,114 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_OCP_QCQP_RES_H_ -#define HPIPM_D_OCP_QCQP_RES_H_ - - - -#include -#include - -#include -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_ocp_qcqp_res - { - struct d_ocp_qcqp_dim *dim; - struct blasfeo_dvec *res_g; // q-residuals - struct blasfeo_dvec *res_b; // b-residuals - struct blasfeo_dvec *res_d; // d-residuals - struct blasfeo_dvec *res_m; // m-residuals - double res_max[4]; // max of residuals - double res_mu; // mu-residual - hpipm_size_t memsize; - }; - - - -struct d_ocp_qcqp_res_ws - { - struct blasfeo_dvec *tmp_nuxM; // work space of size nuM+nxM - struct blasfeo_dvec *tmp_nbgqM; // work space of size nbM+ngM+nqM - struct blasfeo_dvec *tmp_nsM; // work space of size nsM - struct blasfeo_dvec *q_fun; // value for evaluation of quadr constr - struct blasfeo_dvec *q_adj; // value for adjoint of quadr constr - int use_q_fun; // reuse cached value for evaluation of quadr constr - int use_q_adj; // reuse cached value for adjoint of quadr constr - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_ocp_qcqp_res_memsize(struct d_ocp_qcqp_dim *ocp_dim); -// -void d_ocp_qcqp_res_create(struct d_ocp_qcqp_dim *ocp_dim, struct d_ocp_qcqp_res *res, void *mem); -// -hpipm_size_t d_ocp_qcqp_res_ws_memsize(struct d_ocp_qcqp_dim *ocp_dim); -// -void d_ocp_qcqp_res_ws_create(struct d_ocp_qcqp_dim *ocp_dim, struct d_ocp_qcqp_res_ws *workspace, void *mem); -// -void d_ocp_qcqp_res_compute(struct d_ocp_qcqp *qp, struct d_ocp_qcqp_sol *qp_sol, struct d_ocp_qcqp_res *res, struct d_ocp_qcqp_res_ws *ws); -// -void d_ocp_qcqp_res_compute_inf_norm(struct d_ocp_qcqp_res *res); -// -void d_ocp_qcqp_res_get_max_res_stat(struct d_ocp_qcqp_res *res, double *value); -// -void d_ocp_qcqp_res_get_max_res_eq(struct d_ocp_qcqp_res *res, double *value); -// -void d_ocp_qcqp_res_get_max_res_ineq(struct d_ocp_qcqp_res *res, double *value); -// -void d_ocp_qcqp_res_get_max_res_comp(struct d_ocp_qcqp_res *res, double *value); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - -#endif // HPIPM_D_OCP_QCQP_RES_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qcqp_sol.h b/third_party/acados/include/hpipm/include/hpipm_d_ocp_qcqp_sol.h deleted file mode 100644 index 68adbfc..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qcqp_sol.h +++ /dev/null @@ -1,114 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_OCP_QCQP_SOL_H_ -#define HPIPM_D_OCP_QCQP_SOL_H_ - - - -#include -#include - -#include "hpipm_d_ocp_qcqp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_ocp_qcqp_sol - { - struct d_ocp_qcqp_dim *dim; - struct blasfeo_dvec *ux; - struct blasfeo_dvec *pi; - struct blasfeo_dvec *lam; - struct blasfeo_dvec *t; - hpipm_size_t memsize; // memory size in bytes - }; - - - -// -hpipm_size_t d_ocp_qcqp_sol_strsize(); -// -hpipm_size_t d_ocp_qcqp_sol_memsize(struct d_ocp_qcqp_dim *dim); -// -void d_ocp_qcqp_sol_create(struct d_ocp_qcqp_dim *dim, struct d_ocp_qcqp_sol *qp_sol, void *memory); -// -void d_ocp_qcqp_sol_copy_all(struct d_ocp_qcqp_sol *qp_sol_orig, struct d_ocp_qcqp_sol *qp_sol_dest); -// -void d_ocp_qcqp_sol_get(char *field, int stage, struct d_ocp_qcqp_sol *qp_sol, double *vec); -// -void d_ocp_qcqp_sol_get_u(int stage, struct d_ocp_qcqp_sol *qp_sol, double *vec); -// -void d_ocp_qcqp_sol_get_x(int stage, struct d_ocp_qcqp_sol *qp_sol, double *vec); -// -void d_ocp_qcqp_sol_get_sl(int stage, struct d_ocp_qcqp_sol *qp_sol, double *vec); -// -void d_ocp_qcqp_sol_get_su(int stage, struct d_ocp_qcqp_sol *qp_sol, double *vec); -// -void d_ocp_qcqp_sol_get_pi(int stage, struct d_ocp_qcqp_sol *qp_sol, double *vec); -// -void d_ocp_qcqp_sol_get_lam_lb(int stage, struct d_ocp_qcqp_sol *qp_sol, double *vec); -// -void d_ocp_qcqp_sol_get_lam_ub(int stage, struct d_ocp_qcqp_sol *qp_sol, double *vec); -// -void d_ocp_qcqp_sol_get_lam_lg(int stage, struct d_ocp_qcqp_sol *qp_sol, double *vec); -// -void d_ocp_qcqp_sol_get_lam_ug(int stage, struct d_ocp_qcqp_sol *qp_sol, double *vec); -// -void d_ocp_qcqp_sol_set(char *field, int stage, double *vec, struct d_ocp_qcqp_sol *qp_sol); -// -void d_ocp_qcqp_sol_set_u(int stage, double *vec, struct d_ocp_qcqp_sol *qp_sol); -// -void d_ocp_qcqp_sol_set_x(int stage, double *vec, struct d_ocp_qcqp_sol *qp_sol); -// -void d_ocp_qcqp_sol_set_sl(int stage, double *vec, struct d_ocp_qcqp_sol *qp_sol); -// -void d_ocp_qcqp_sol_set_su(int stage, double *vec, struct d_ocp_qcqp_sol *qp_sol); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_D_OCP_QCQP_SOL_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qcqp_utils.h b/third_party/acados/include/hpipm/include/hpipm_d_ocp_qcqp_utils.h deleted file mode 100644 index 00248f1..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qcqp_utils.h +++ /dev/null @@ -1,81 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_OCP_QCQP_UTILS_H_ -#define HPIPM_D_OCP_QCQP_UTILS_H_ - - - -#include -#include - -#include "hpipm_d_ocp_qcqp_dim.h" -#include "hpipm_d_ocp_qp.h" -#include "hpipm_d_ocp_qcqp_sol.h" -#include "hpipm_d_ocp_qcqp_ipm.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -// -void d_ocp_qcqp_dim_print(struct d_ocp_qcqp_dim *qcqp_dim); -// -void d_ocp_qcqp_dim_codegen(char *file_name, char *mode, struct d_ocp_qcqp_dim *qcqp_dim); -// -void d_ocp_qcqp_print(struct d_ocp_qcqp_dim *qcqp_dim, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_codegen(char *file_name, char *mode, struct d_ocp_qcqp_dim *qcqp_dim, struct d_ocp_qcqp *qp); -// -void d_ocp_qcqp_sol_print(struct d_ocp_qcqp_dim *qcqp_dim, struct d_ocp_qcqp_sol *ocp_qcqp_sol); -// -void d_ocp_qcqp_ipm_arg_codegen(char *file_name, char *mode, struct d_ocp_qcqp_dim *qcqp_dim, struct d_ocp_qcqp_ipm_arg *arg); -// -void d_ocp_qcqp_res_print(struct d_ocp_qcqp_dim *qcqp_dim, struct d_ocp_qcqp_res *ocp_qcqp_res); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_D_OCP_QCQP_UTILS_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp.h b/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp.h deleted file mode 100644 index ca26cdb..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp.h +++ /dev/null @@ -1,306 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_OCP_QP_H_ -#define HPIPM_D_OCP_QP_H_ - - - -#include -#include - -#include "hpipm_d_ocp_qp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_ocp_qp - { - struct d_ocp_qp_dim *dim; - struct blasfeo_dmat *BAbt; // dynamics matrix & vector work space - struct blasfeo_dmat *RSQrq; // hessian of cost & vector work space - struct blasfeo_dmat *DCt; // inequality constraints matrix - struct blasfeo_dvec *b; // dynamics vector - struct blasfeo_dvec *rqz; // gradient of cost & gradient of slacks - struct blasfeo_dvec *d; // inequality constraints vector - struct blasfeo_dvec *d_mask; // inequality constraints mask vector - struct blasfeo_dvec *m; // rhs of complementarity condition - struct blasfeo_dvec *Z; // (diagonal) hessian of slacks - int **idxb; // indices of box constrained variables within [u; x] - int **idxs_rev; // index of soft constraints (reverse storage) - int **idxe; // indices of constraints within [bu, bx, g] that are equalities, subset of [0, ..., nbu+nbx+ng-1] - int *diag_H_flag; // flag the fact that Hessian is diagonal - hpipm_size_t memsize; // memory size in bytes - }; - - - -// -hpipm_size_t d_ocp_qp_strsize(); -// -hpipm_size_t d_ocp_qp_memsize(struct d_ocp_qp_dim *dim); -// -void d_ocp_qp_create(struct d_ocp_qp_dim *dim, struct d_ocp_qp *qp, void *memory); -// -void d_ocp_qp_copy_all(struct d_ocp_qp *qp_orig, struct d_ocp_qp *qp_dest); - -// setters -// -void d_ocp_qp_set_all_zero(struct d_ocp_qp *qp); -// -void d_ocp_qp_set_rhs_zero(struct d_ocp_qp *qp); -// -void d_ocp_qp_set_all(double **A, double **B, double **b, double **Q, double **S, double **R, double **q, double **r, int **idxbx, double **lbx, double **ubx, int **idxbu, double **lbu, double **ubu, double **C, double **D, double **lg, double **ug, double **Zl, double **Zu, double **zl, double **zu, int **idxs, double **ls, double **us, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_all_rowmaj(double **A, double **B, double **b, double **Q, double **S, double **R, double **q, double **r, int **idxbx, double **lbx, double **ubx, int **idxbu, double **lbu, double **ubu, double **C, double **D, double **lg, double **ug, double **Zl, double **Zu, double **zl, double **zu, int **idxs, double **ls, double **us, struct d_ocp_qp *qp); -// -void d_ocp_qp_set(char *field_name, int stage, void *value, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_el(char *field_name, int stage, int index, void *value, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_A(int stage, double *mat, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_B(int stage, double *mat, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_b(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_Q(int stage, double *mat, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_S(int stage, double *mat, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_R(int stage, double *mat, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_q(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_r(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_lb(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_lb_mask(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_ub(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_ub_mask(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_lbx(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_lbx_mask(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_el_lbx(int stage, int index, double *elem, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_ubx(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_ubx_mask(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_el_ubx(int stage, int index, double *elem, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_lbu(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_lbu_mask(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_ubu(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_ubu_mask(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_idxb(int stage, int *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_idxbx(int stage, int *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_Jbx(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_idxbu(int stage, int *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_Jbu(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_C(int stage, double *mat, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_D(int stage, double *mat, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_lg(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_lg_mask(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_ug(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_ug_mask(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_Zl(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_Zu(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_zl(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_zu(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_lls(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_lls_mask(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_lus(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_lus_mask(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_idxs(int stage, int *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_idxs_rev(int stage, int *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_Jsbu(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_Jsbx(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_Jsg(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_idxe(int stage, int *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_idxbxe(int stage, int *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_idxbue(int stage, int *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_idxge(int stage, int *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_Jbxe(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_Jbue(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_Jge(int stage, double *vec, struct d_ocp_qp *qp); -// -void d_ocp_qp_set_diag_H_flag(int stage, int *value, struct d_ocp_qp *qp); - -// getters -// -void d_ocp_qp_get(char *field, int stage, struct d_ocp_qp *qp, void *value); -// -void d_ocp_qp_get_A(int stage, struct d_ocp_qp *qp, double *mat); -// -void d_ocp_qp_get_B(int stage, struct d_ocp_qp *qp, double *mat); -// -void d_ocp_qp_get_b(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_Q(int stage, struct d_ocp_qp *qp, double *mat); -// -void d_ocp_qp_get_S(int stage, struct d_ocp_qp *qp, double *mat); -// -void d_ocp_qp_get_R(int stage, struct d_ocp_qp *qp, double *mat); -// -void d_ocp_qp_get_q(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_r(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_ub(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_ub_mask(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_lb(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_lb_mask(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_lbx(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_lbx_mask(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_ubx(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_ubx_mask(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_lbu(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_lbu_mask(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_ubu(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_ubu_mask(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_idxb(int stage, struct d_ocp_qp *qp, int *vec); -// -//void d_ocp_qp_get_idxbx(int stage, struct d_ocp_qp *qp, int *vec); -// -//void d_ocp_qp_get_Jbx(int stage, struct d_ocp_qp *qp, double *vec); -// -//void d_ocp_qp_get_idxbu(int stage, struct d_ocp_qp *qp, int *vec); -// -//void d_ocp_qp_get_Jbu(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_C(int stage, struct d_ocp_qp *qp, double *mat); -// -void d_ocp_qp_get_D(int stage, struct d_ocp_qp *qp, double *mat); -// -void d_ocp_qp_get_lg(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_lg_mask(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_ug(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_ug_mask(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_Zl(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_Zu(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_zl(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_zu(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_lls(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_lls_mask(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_lus(int stage, struct d_ocp_qp *qp, double *vec); -// -void d_ocp_qp_get_lus_mask(int stage, struct d_ocp_qp *qp, double *vec); -// XXX only valid if there is one slack per softed constraint !!! -void d_ocp_qp_get_idxs(int stage, struct d_ocp_qp *qp, int *vec); -// -void d_ocp_qp_get_idxs_rev(int stage, struct d_ocp_qp *qp, int *vec); -// -//void d_ocp_qp_get_Jsbu(int stage, struct d_ocp_qp *qp, float *vec); -// -//void d_ocp_qp_get_Jsbx(int stage, struct d_ocp_qp *qp, float *vec); -// -//void d_ocp_qp_get_Jsg(int stage, struct d_ocp_qp *qp, float *vec); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_D_OCP_QP_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp_dim.h b/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp_dim.h deleted file mode 100644 index dcfb801..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp_dim.h +++ /dev/null @@ -1,142 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_OCP_QP_DIM_H_ -#define HPIPM_D_OCP_QP_DIM_H_ - -#include "hpipm_common.h" - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_ocp_qp_dim - { - int *nx; // number of states - int *nu; // number of inputs - int *nb; // number of box constraints - int *nbx; // number of state box constraints - int *nbu; // number of input box constraints - int *ng; // number of general constraints - int *ns; // number of soft constraints - int *nsbx; // number of soft state box constraints - int *nsbu; // number of soft input box constraints - int *nsg; // number of soft general constraints - int *nbxe; // number of state box constraints which are equality - int *nbue; // number of input box constraints which are equality - int *nge; // number of general constraints which are equality - int N; // horizon length - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_ocp_qp_dim_strsize(); -// -hpipm_size_t d_ocp_qp_dim_memsize(int N); -// -void d_ocp_qp_dim_create(int N, struct d_ocp_qp_dim *qp_dim, void *memory); -// -void d_ocp_qp_dim_copy_all(struct d_ocp_qp_dim *dim_orig, struct d_ocp_qp_dim *dim_dest); -// -void d_ocp_qp_dim_set_all(int *nx, int *nu, int *nbx, int *nbu, int *ng, int *nsbx, int *nsbu, int *nsg, struct d_ocp_qp_dim *dim); -// -void d_ocp_qp_dim_set(char *field, int stage, int value, struct d_ocp_qp_dim *dim); -// -void d_ocp_qp_dim_set_nx(int stage, int value, struct d_ocp_qp_dim *dim); -// -void d_ocp_qp_dim_set_nu(int stage, int value, struct d_ocp_qp_dim *dim); -// -void d_ocp_qp_dim_set_nbx(int stage, int value, struct d_ocp_qp_dim *dim); -// -void d_ocp_qp_dim_set_nbu(int stage, int value, struct d_ocp_qp_dim *dim); -// -void d_ocp_qp_dim_set_ng(int stage, int value, struct d_ocp_qp_dim *dim); -// -void d_ocp_qp_dim_set_ns(int stage, int value, struct d_ocp_qp_dim *dim); -// -void d_ocp_qp_dim_set_nsbx(int stage, int value, struct d_ocp_qp_dim *dim); -// -void d_ocp_qp_dim_set_nsbu(int stage, int value, struct d_ocp_qp_dim *dim); -// -void d_ocp_qp_dim_set_nsg(int stage, int value, struct d_ocp_qp_dim *dim); -// -void d_ocp_qp_dim_set_nbxe(int stage, int value, struct d_ocp_qp_dim *dim); -// -void d_ocp_qp_dim_set_nbue(int stage, int value, struct d_ocp_qp_dim *dim); -// -void d_ocp_qp_dim_set_nge(int stage, int value, struct d_ocp_qp_dim *dim); -// -void d_ocp_qp_dim_get(struct d_ocp_qp_dim *dim, char *field, int stage, int *value); -// -void d_ocp_qp_dim_get_N(struct d_ocp_qp_dim *dim, int *value); -// -void d_ocp_qp_dim_get_nx(struct d_ocp_qp_dim *dim, int stage, int *value); -// -void d_ocp_qp_dim_get_nu(struct d_ocp_qp_dim *dim, int stage, int *value); -// -void d_ocp_qp_dim_get_nbx(struct d_ocp_qp_dim *dim, int stage, int *value); -// -void d_ocp_qp_dim_get_nbu(struct d_ocp_qp_dim *dim, int stage, int *value); -// -void d_ocp_qp_dim_get_ng(struct d_ocp_qp_dim *dim, int stage, int *value); -// -void d_ocp_qp_dim_get_ns(struct d_ocp_qp_dim *dim, int stage, int *value); -// -void d_ocp_qp_dim_get_nsbx(struct d_ocp_qp_dim *dim, int stage, int *value); -// -void d_ocp_qp_dim_get_nsbu(struct d_ocp_qp_dim *dim, int stage, int *value); -// -void d_ocp_qp_dim_get_nsg(struct d_ocp_qp_dim *dim, int stage, int *value); -// -void d_ocp_qp_dim_get_nbxe(struct d_ocp_qp_dim *dim, int stage, int *value); -// -void d_ocp_qp_dim_get_nbue(struct d_ocp_qp_dim *dim, int stage, int *value); -// -void d_ocp_qp_dim_get_nge(struct d_ocp_qp_dim *dim, int stage, int *value); - - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_D_OCP_QP_DIM_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp_ipm.h b/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp_ipm.h deleted file mode 100644 index d2a2833..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp_ipm.h +++ /dev/null @@ -1,250 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_OCP_QP_IPM_H_ -#define HPIPM_D_OCP_QP_IPM_H_ - - - -#include -#include - -#include -#include -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_ocp_qp_ipm_arg - { - double mu0; // initial value for complementarity slackness - double alpha_min; // exit cond on step length - double res_g_max; // exit cond on inf norm of residuals - double res_b_max; // exit cond on inf norm of residuals - double res_d_max; // exit cond on inf norm of residuals - double res_m_max; // exit cond on inf norm of residuals - double reg_prim; // reg of primal hessian - double lam_min; // min value in lam vector - double t_min; // min value in t vector - double tau_min; // min value of barrier parameter - int iter_max; // exit cond in iter number - int stat_max; // iterations saved in stat - int pred_corr; // use Mehrotra's predictor-corrector IPM algirthm - int cond_pred_corr; // conditional Mehrotra's predictor-corrector - int itref_pred_max; // max number of iterative refinement steps for predictor step - int itref_corr_max; // max number of iterative refinement steps for corrector step - int warm_start; // 0 no warm start, 1 warm start primal sol, 2 warm start primal and dual sol - int square_root_alg; // 0 classical Riccati, 1 square-root Riccati - int lq_fact; // 0 syrk+potrf, 1 mix, 2 lq (for square_root_alg==1) - int abs_form; // absolute IPM formulation - int comp_dual_sol_eq; // dual solution of equality constraints (only for abs_form==1) - int comp_res_exit; // compute residuals on exit (only for abs_form==1 and comp_dual_sol_eq==1) - int comp_res_pred; // compute residuals of prediction - int split_step; // use different steps for primal and dual variables - int var_init_scheme; // variables initialization scheme - int t_lam_min; // clip t and lam: 0 no, 1 in Gamma computation, 2 in solution - int mode; - hpipm_size_t memsize; - }; - - - -struct d_ocp_qp_ipm_ws - { - double qp_res[4]; // infinity norm of residuals - struct d_core_qp_ipm_workspace *core_workspace; - struct d_ocp_qp_dim *dim; // cache dim - struct d_ocp_qp_res_ws *res_workspace; - struct d_ocp_qp_sol *sol_step; - struct d_ocp_qp_sol *sol_itref; - struct d_ocp_qp *qp_step; - struct d_ocp_qp *qp_itref; - struct d_ocp_qp_res *res_itref; - struct d_ocp_qp_res *res; - struct blasfeo_dvec *Gamma; // hessian update - struct blasfeo_dvec *gamma; // hessian update - struct blasfeo_dvec *tmp_nuxM; // work space of size nxM - struct blasfeo_dvec *tmp_nbgM; // work space of size nbM+ngM - struct blasfeo_dvec *tmp_nsM; // work space of size nsM - struct blasfeo_dvec *Pb; // Pb - struct blasfeo_dvec *Zs_inv; - struct blasfeo_dvec *tmp_m; - struct blasfeo_dvec *l; // cache linear part for _get_ric_xxx - struct blasfeo_dmat *L; - struct blasfeo_dmat *Ls; - struct blasfeo_dmat *P; - struct blasfeo_dmat *Lh; - struct blasfeo_dmat *AL; - struct blasfeo_dmat *lq0; - struct blasfeo_dmat *tmp_nxM_nxM; - double *stat; // convergence statistics - int *use_hess_fact; - void *lq_work0; - int iter; // iteration number - int stat_max; // iterations saved in stat - int stat_m; // number of recorded stat per IPM iter - int use_Pb; - int status; // solver status - int square_root_alg; // cache from arg - int lq_fact; // cache from arg - int mask_constr; // use constr mask - int valid_ric_vec; // meaningful riccati vectors - int valid_ric_p; // form of riccati p: 0 p*inv(L), 1 p - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_ocp_qp_ipm_arg_strsize(); -// -hpipm_size_t d_ocp_qp_ipm_arg_memsize(struct d_ocp_qp_dim *ocp_dim); -// -void d_ocp_qp_ipm_arg_create(struct d_ocp_qp_dim *ocp_dim, struct d_ocp_qp_ipm_arg *arg, void *mem); -// -void d_ocp_qp_ipm_arg_set_default(enum hpipm_mode mode, struct d_ocp_qp_ipm_arg *arg); -// -void d_ocp_qp_ipm_arg_set(char *field, void *value, struct d_ocp_qp_ipm_arg *arg); -// set maximum number of iterations -void d_ocp_qp_ipm_arg_set_iter_max(int *iter_max, struct d_ocp_qp_ipm_arg *arg); -// set minimum step lenght -void d_ocp_qp_ipm_arg_set_alpha_min(double *alpha_min, struct d_ocp_qp_ipm_arg *arg); -// set initial value of barrier parameter -void d_ocp_qp_ipm_arg_set_mu0(double *mu0, struct d_ocp_qp_ipm_arg *arg); -// set exit tolerance on stationarity condition -void d_ocp_qp_ipm_arg_set_tol_stat(double *tol_stat, struct d_ocp_qp_ipm_arg *arg); -// set exit tolerance on equality constr -void d_ocp_qp_ipm_arg_set_tol_eq(double *tol_eq, struct d_ocp_qp_ipm_arg *arg); -// set exit tolerance on inequality constr -void d_ocp_qp_ipm_arg_set_tol_ineq(double *tol_ineq, struct d_ocp_qp_ipm_arg *arg); -// set exit tolerance on complementarity condition -void d_ocp_qp_ipm_arg_set_tol_comp(double *tol_comp, struct d_ocp_qp_ipm_arg *arg); -// set regularization of primal variables -void d_ocp_qp_ipm_arg_set_reg_prim(double *tol_comp, struct d_ocp_qp_ipm_arg *arg); -// set warm start: 0 no warm start, 1 primal var -void d_ocp_qp_ipm_arg_set_warm_start(int *warm_start, struct d_ocp_qp_ipm_arg *arg); -// Mehrotra's predictor-corrector IPM algorithm: 0 no predictor-corrector, 1 use predictor-corrector -void d_ocp_qp_ipm_arg_set_pred_corr(int *pred_corr, struct d_ocp_qp_ipm_arg *arg); -// conditional predictor-corrector: 0 no conditinal predictor-corrector, 1 conditional predictor-corrector -void d_ocp_qp_ipm_arg_set_cond_pred_corr(int *value, struct d_ocp_qp_ipm_arg *arg); -// set riccati algorithm: 0 classic, 1 square-root -void d_ocp_qp_ipm_arg_set_ric_alg(int *value, struct d_ocp_qp_ipm_arg *arg); -// dual solution of equality constraints (only for abs_form==1) -void d_ocp_qp_ipm_arg_set_comp_dual_sol_eq(int *value, struct d_ocp_qp_ipm_arg *arg); -// compute residuals after solution -void d_ocp_qp_ipm_arg_set_comp_res_exit(int *value, struct d_ocp_qp_ipm_arg *arg); -// compute residuals of prediction -void d_ocp_qp_ipm_arg_set_comp_res_pred(int *value, struct d_ocp_qp_ipm_arg *arg); -// min value of lam in the solution -void d_ocp_qp_ipm_arg_set_lam_min(double *value, struct d_ocp_qp_ipm_arg *arg); -// min value of t in the solution -void d_ocp_qp_ipm_arg_set_t_min(double *value, struct d_ocp_qp_ipm_arg *arg); -// min value of tau in the solution -void d_ocp_qp_ipm_arg_set_tau_min(double *value, struct d_ocp_qp_ipm_arg *arg); -// set split step: 0 same step, 1 different step for primal and dual variables -void d_ocp_qp_ipm_arg_set_split_step(int *value, struct d_ocp_qp_ipm_arg *arg); -// variables initialization scheme -void d_ocp_qp_ipm_arg_set_var_init_scheme(int *value, struct d_ocp_qp_ipm_arg *arg); -// clip t and lam: 0 no, 1 in Gamma computation, 2 in solution -void d_ocp_qp_ipm_arg_set_t_lam_min(int *value, struct d_ocp_qp_ipm_arg *arg); - -// -hpipm_size_t d_ocp_qp_ipm_ws_strsize(); -// -hpipm_size_t d_ocp_qp_ipm_ws_memsize(struct d_ocp_qp_dim *ocp_dim, struct d_ocp_qp_ipm_arg *arg); -// -void d_ocp_qp_ipm_ws_create(struct d_ocp_qp_dim *ocp_dim, struct d_ocp_qp_ipm_arg *arg, struct d_ocp_qp_ipm_ws *ws, void *mem); -// -void d_ocp_qp_ipm_get(char *field, struct d_ocp_qp_ipm_ws *ws, void *value); -// -void d_ocp_qp_ipm_get_status(struct d_ocp_qp_ipm_ws *ws, int *status); -// -void d_ocp_qp_ipm_get_iter(struct d_ocp_qp_ipm_ws *ws, int *iter); -// -void d_ocp_qp_ipm_get_max_res_stat(struct d_ocp_qp_ipm_ws *ws, double *res_stat); -// -void d_ocp_qp_ipm_get_max_res_eq(struct d_ocp_qp_ipm_ws *ws, double *res_eq); -// -void d_ocp_qp_ipm_get_max_res_ineq(struct d_ocp_qp_ipm_ws *ws, double *res_ineq); -// -void d_ocp_qp_ipm_get_max_res_comp(struct d_ocp_qp_ipm_ws *ws, double *res_comp); -// -void d_ocp_qp_ipm_get_stat(struct d_ocp_qp_ipm_ws *ws, double **stat); -// -void d_ocp_qp_ipm_get_stat_m(struct d_ocp_qp_ipm_ws *ws, int *stat_m); -// -void d_ocp_qp_ipm_get_ric_Lr(struct d_ocp_qp *qp, struct d_ocp_qp_ipm_arg *arg, struct d_ocp_qp_ipm_ws *ws, int stage, double *Lr); -// -void d_ocp_qp_ipm_get_ric_Ls(struct d_ocp_qp *qp, struct d_ocp_qp_ipm_arg *arg, struct d_ocp_qp_ipm_ws *ws, int stage, double *Ls); -// -void d_ocp_qp_ipm_get_ric_P(struct d_ocp_qp *qp, struct d_ocp_qp_ipm_arg *arg, struct d_ocp_qp_ipm_ws *ws, int stage, double *P); -// -void d_ocp_qp_ipm_get_ric_lr(struct d_ocp_qp *qp, struct d_ocp_qp_ipm_arg *arg, struct d_ocp_qp_ipm_ws *ws, int stage, double *lr); -// -void d_ocp_qp_ipm_get_ric_p(struct d_ocp_qp *qp, struct d_ocp_qp_ipm_arg *arg, struct d_ocp_qp_ipm_ws *ws, int stage, double *p); -// feedback control gain in the form u = K x + k -void d_ocp_qp_ipm_get_ric_K(struct d_ocp_qp *qp, struct d_ocp_qp_ipm_arg *arg, struct d_ocp_qp_ipm_ws *ws, int stage, double *K); -// feedback control gain in the form u = K x + k -void d_ocp_qp_ipm_get_ric_k(struct d_ocp_qp *qp, struct d_ocp_qp_ipm_arg *arg, struct d_ocp_qp_ipm_ws *ws, int stage, double *k); -// -void d_ocp_qp_init_var(struct d_ocp_qp *qp, struct d_ocp_qp_sol *qp_sol, struct d_ocp_qp_ipm_arg *arg, struct d_ocp_qp_ipm_ws *ws); -// -void d_ocp_qp_ipm_abs_step(int kk, struct d_ocp_qp *qp, struct d_ocp_qp_sol *qp_sol, struct d_ocp_qp_ipm_arg *arg, struct d_ocp_qp_ipm_ws *ws); -// -void d_ocp_qp_ipm_delta_step(int kk, struct d_ocp_qp *qp, struct d_ocp_qp_sol *qp_sol, struct d_ocp_qp_ipm_arg *arg, struct d_ocp_qp_ipm_ws *ws); -// -void d_ocp_qp_ipm_solve(struct d_ocp_qp *qp, struct d_ocp_qp_sol *qp_sol, struct d_ocp_qp_ipm_arg *arg, struct d_ocp_qp_ipm_ws *ws); -// -void d_ocp_qp_ipm_predict(struct d_ocp_qp *qp, struct d_ocp_qp_sol *qp_sol, struct d_ocp_qp_ipm_arg *arg, struct d_ocp_qp_ipm_ws *ws); -// -void d_ocp_qp_ipm_sens(struct d_ocp_qp *qp, struct d_ocp_qp_sol *qp_sol, struct d_ocp_qp_ipm_arg *arg, struct d_ocp_qp_ipm_ws *ws); - - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - -#endif // HPIPM_D_OCP_QP_IPM_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp_kkt.h b/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp_kkt.h deleted file mode 100644 index 19dcec3..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp_kkt.h +++ /dev/null @@ -1,66 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_OCP_QP_KKT_H_ -#define HPIPM_D_OCP_QP_KKT_H_ - -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - -// -void d_ocp_qp_fact_solve_kkt_unconstr(struct d_ocp_qp *qp, struct d_ocp_qp_sol *qp_sol, struct d_ocp_qp_ipm_arg *arg, struct d_ocp_qp_ipm_ws *ws); -// -void d_ocp_qp_fact_solve_kkt_step(struct d_ocp_qp *qp, struct d_ocp_qp_sol *qp_sol, struct d_ocp_qp_ipm_arg *arg, struct d_ocp_qp_ipm_ws *ws); -// -void d_ocp_qp_fact_lq_solve_kkt_step(struct d_ocp_qp *qp, struct d_ocp_qp_sol *qp_sol, struct d_ocp_qp_ipm_arg *arg, struct d_ocp_qp_ipm_ws *ws); -// -void d_ocp_qp_solve_kkt_step(struct d_ocp_qp *qp, struct d_ocp_qp_sol *qp_sol, struct d_ocp_qp_ipm_arg *arg, struct d_ocp_qp_ipm_ws *ws); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - -#endif // HPIPM_D_OCP_QP_KKT_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp_red.h b/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp_red.h deleted file mode 100644 index f0482b0..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp_red.h +++ /dev/null @@ -1,117 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_OCP_QP_RED_H_ -#define HPIPM_D_OCP_QP_RED_H_ - - - -#include -#include - -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_ocp_qp_reduce_eq_dof_arg - { - double lam_min; - double t_min; - int alias_unchanged; // do not keep copy unchanged stage - int comp_prim_sol; // primal solution (v) - int comp_dual_sol_eq; // dual solution equality constr (pi) - int comp_dual_sol_ineq; // dual solution inequality constr (lam t) - hpipm_size_t memsize; // memory size in bytes - }; - - - -struct d_ocp_qp_reduce_eq_dof_ws - { - struct blasfeo_dvec *tmp_nuxM; - struct blasfeo_dvec *tmp_nbgM; - int *e_imask_ux; - int *e_imask_d; - hpipm_size_t memsize; // memory size in bytes - }; - - - -// -void d_ocp_qp_dim_reduce_eq_dof(struct d_ocp_qp_dim *dim, struct d_ocp_qp_dim *dim_red); -// -hpipm_size_t d_ocp_qp_reduce_eq_dof_arg_memsize(); -// -void d_ocp_qp_reduce_eq_dof_arg_create(struct d_ocp_qp_reduce_eq_dof_arg *arg, void *mem); -// -void d_ocp_qp_reduce_eq_dof_arg_set_default(struct d_ocp_qp_reduce_eq_dof_arg *arg); -// -void d_ocp_qp_reduce_eq_dof_arg_set_alias_unchanged(struct d_ocp_qp_reduce_eq_dof_arg *arg, int value); -// -void d_ocp_qp_reduce_eq_dof_arg_set_comp_prim_sol(struct d_ocp_qp_reduce_eq_dof_arg *arg, int value); -// -void d_ocp_qp_reduce_eq_dof_arg_set_comp_dual_sol_eq(struct d_ocp_qp_reduce_eq_dof_arg *arg, int value); -// -void d_ocp_qp_reduce_eq_dof_arg_set_comp_dual_sol_ineq(struct d_ocp_qp_reduce_eq_dof_arg *arg, int value); -// -hpipm_size_t d_ocp_qp_reduce_eq_dof_ws_memsize(struct d_ocp_qp_dim *dim); -// -void d_ocp_qp_reduce_eq_dof_ws_create(struct d_ocp_qp_dim *dim, struct d_ocp_qp_reduce_eq_dof_ws *work, void *mem); -// -void d_ocp_qp_reduce_eq_dof(struct d_ocp_qp *qp, struct d_ocp_qp *qp_red, struct d_ocp_qp_reduce_eq_dof_arg *arg, struct d_ocp_qp_reduce_eq_dof_ws *work); -// -void d_ocp_qp_reduce_eq_dof_lhs(struct d_ocp_qp *qp, struct d_ocp_qp *qp_red, struct d_ocp_qp_reduce_eq_dof_arg *arg, struct d_ocp_qp_reduce_eq_dof_ws *work); -// -void d_ocp_qp_reduce_eq_dof_rhs(struct d_ocp_qp *qp, struct d_ocp_qp *qp_red, struct d_ocp_qp_reduce_eq_dof_arg *arg, struct d_ocp_qp_reduce_eq_dof_ws *work); -// -void d_ocp_qp_restore_eq_dof(struct d_ocp_qp *qp, struct d_ocp_qp_sol *qp_sol_red, struct d_ocp_qp_sol *qp_sol, struct d_ocp_qp_reduce_eq_dof_arg *arg, struct d_ocp_qp_reduce_eq_dof_ws *work); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_D_OCP_QP_RED_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp_res.h b/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp_res.h deleted file mode 100644 index 061c572..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp_res.h +++ /dev/null @@ -1,112 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_OCP_QP_RES_H_ -#define HPIPM_D_OCP_QP_RES_H_ - - - -#include -#include - -#include -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_ocp_qp_res - { - struct d_ocp_qp_dim *dim; - struct blasfeo_dvec *res_g; // q-residuals - struct blasfeo_dvec *res_b; // b-residuals - struct blasfeo_dvec *res_d; // d-residuals - struct blasfeo_dvec *res_m; // m-residuals - double res_max[4]; // max of residuals - double res_mu; // mu-residual - hpipm_size_t memsize; - }; - - - -struct d_ocp_qp_res_ws - { - struct blasfeo_dvec *tmp_nbgM; // work space of size nbM+ngM - struct blasfeo_dvec *tmp_nsM; // work space of size nsM - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_ocp_qp_res_memsize(struct d_ocp_qp_dim *ocp_dim); -// -void d_ocp_qp_res_create(struct d_ocp_qp_dim *ocp_dim, struct d_ocp_qp_res *res, void *mem); -// -hpipm_size_t d_ocp_qp_res_ws_memsize(struct d_ocp_qp_dim *ocp_dim); -// -void d_ocp_qp_res_ws_create(struct d_ocp_qp_dim *ocp_dim, struct d_ocp_qp_res_ws *workspace, void *mem); -// -void d_ocp_qp_res_compute(struct d_ocp_qp *qp, struct d_ocp_qp_sol *qp_sol, struct d_ocp_qp_res *res, struct d_ocp_qp_res_ws *ws); -// -void d_ocp_qp_res_compute_lin(struct d_ocp_qp *qp, struct d_ocp_qp_sol *qp_sol, struct d_ocp_qp_sol *qp_step, struct d_ocp_qp_res *res, struct d_ocp_qp_res_ws *ws); -// -void d_ocp_qp_res_compute_inf_norm(struct d_ocp_qp_res *res); -// -void d_ocp_qp_res_get_all(struct d_ocp_qp_res *res, double **res_r, double **res_q, double **res_ls, double **res_us, double **res_b, double **res_d_lb, double **res_d_ub, double **res_d_lg, double **res_d_ug, double **res_d_ls, double **res_d_us, double **res_m_lb, double **res_m_ub, double **res_m_lg, double **res_m_ug, double **res_m_ls, double **res_m_us); -// -void d_ocp_qp_res_get_max_res_stat(struct d_ocp_qp_res *res, double *value); -// -void d_ocp_qp_res_get_max_res_eq(struct d_ocp_qp_res *res, double *value); -// -void d_ocp_qp_res_get_max_res_ineq(struct d_ocp_qp_res *res, double *value); -// -void d_ocp_qp_res_get_max_res_comp(struct d_ocp_qp_res *res, double *value); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - -#endif // HPIPM_D_OCP_QP_RES_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp_sol.h b/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp_sol.h deleted file mode 100644 index eb91f3a..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp_sol.h +++ /dev/null @@ -1,128 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_OCP_QP_SOL_H_ -#define HPIPM_D_OCP_QP_SOL_H_ - - - -#include -#include - -#include "hpipm_d_ocp_qp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_ocp_qp_sol - { - struct d_ocp_qp_dim *dim; - struct blasfeo_dvec *ux; - struct blasfeo_dvec *pi; - struct blasfeo_dvec *lam; - struct blasfeo_dvec *t; - void *misc; - hpipm_size_t memsize; // memory size in bytes - }; - - - -// -hpipm_size_t d_ocp_qp_sol_strsize(); -// -hpipm_size_t d_ocp_qp_sol_memsize(struct d_ocp_qp_dim *dim); -// -void d_ocp_qp_sol_create(struct d_ocp_qp_dim *dim, struct d_ocp_qp_sol *qp_sol, void *memory); -// -void d_ocp_qp_sol_copy_all(struct d_ocp_qp_sol *qp_sol_orig, struct d_ocp_qp_sol *qp_sol_dest); -// -void d_ocp_qp_sol_get_all(struct d_ocp_qp_sol *qp_sol, double **u, double **x, double **ls, double **us, double **pi, double **lam_lb, double **lam_ub, double **lam_lg, double **lam_ug, double **lam_ls, double **lam_us); -// -void d_ocp_qp_sol_get_all_rowmaj(struct d_ocp_qp_sol *qp_sol, double **u, double **x, double **ls, double **us, double **pi, double **lam_lb, double **lam_ub, double **lam_lg, double **lam_ug, double **lam_ls, double **lam_us); -// -void d_ocp_qp_sol_set_all(double **u, double **x, double **ls, double **us, double **pi, double **lam_lb, double **lam_ub, double **lam_lg, double **lam_ug, double **lam_ls, double **lam_us, struct d_ocp_qp_sol *qp_sol); -// -void d_ocp_qp_sol_get(char *field, int stage, struct d_ocp_qp_sol *qp_sol, double *vec); -// -void d_ocp_qp_sol_get_u(int stage, struct d_ocp_qp_sol *qp_sol, double *vec); -// -void d_ocp_qp_sol_get_x(int stage, struct d_ocp_qp_sol *qp_sol, double *vec); -// -void d_ocp_qp_sol_get_sl(int stage, struct d_ocp_qp_sol *qp_sol, double *vec); -// -void d_ocp_qp_sol_get_su(int stage, struct d_ocp_qp_sol *qp_sol, double *vec); -// -void d_ocp_qp_sol_get_pi(int stage, struct d_ocp_qp_sol *qp_sol, double *vec); -// -void d_ocp_qp_sol_get_lam_lb(int stage, struct d_ocp_qp_sol *qp_sol, double *vec); -// -void d_ocp_qp_sol_get_lam_lbu(int stage, struct d_ocp_qp_sol *qp_sol, double *vec); -// -void d_ocp_qp_sol_get_lam_lbx(int stage, struct d_ocp_qp_sol *qp_sol, double *vec); -// -void d_ocp_qp_sol_get_lam_ub(int stage, struct d_ocp_qp_sol *qp_sol, double *vec); -// -void d_ocp_qp_sol_get_lam_ubu(int stage, struct d_ocp_qp_sol *qp_sol, double *vec); -// -void d_ocp_qp_sol_get_lam_ubx(int stage, struct d_ocp_qp_sol *qp_sol, double *vec); -// -void d_ocp_qp_sol_get_lam_lg(int stage, struct d_ocp_qp_sol *qp_sol, double *vec); -// -void d_ocp_qp_sol_get_lam_ug(int stage, struct d_ocp_qp_sol *qp_sol, double *vec); -// -void d_ocp_qp_sol_set(char *field, int stage, double *vec, struct d_ocp_qp_sol *qp_sol); -// -void d_ocp_qp_sol_set_u(int stage, double *vec, struct d_ocp_qp_sol *qp_sol); -// -void d_ocp_qp_sol_set_x(int stage, double *vec, struct d_ocp_qp_sol *qp_sol); -// -void d_ocp_qp_sol_set_sl(int stage, double *vec, struct d_ocp_qp_sol *qp_sol); -// -void d_ocp_qp_sol_set_su(int stage, double *vec, struct d_ocp_qp_sol *qp_sol); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_D_OCP_QP_SOL_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp_utils.h b/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp_utils.h deleted file mode 100644 index 217e9d9..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_ocp_qp_utils.h +++ /dev/null @@ -1,82 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_OCP_QP_UTILS_H_ -#define HPIPM_D_OCP_QP_UTILS_H_ - - - -#include -#include - -#include "hpipm_d_ocp_qp_dim.h" -#include "hpipm_d_ocp_qp.h" -#include "hpipm_d_ocp_qp_sol.h" -#include "hpipm_d_ocp_qp_ipm.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -// -void d_ocp_qp_dim_print(struct d_ocp_qp_dim *qp_dim); -// -void d_ocp_qp_dim_codegen(char *file_name, char *mode, struct d_ocp_qp_dim *qp_dim); -// -void d_ocp_qp_print(struct d_ocp_qp_dim *qp_dim, struct d_ocp_qp *qp); -// -void d_ocp_qp_codegen(char *file_name, char *mode, struct d_ocp_qp_dim *qp_dim, struct d_ocp_qp *qp); -// -void d_ocp_qp_sol_print(struct d_ocp_qp_dim *qp_dim, struct d_ocp_qp_sol *ocp_qp_sol); -// -void d_ocp_qp_ipm_arg_print(struct d_ocp_qp_dim *qp_dim, struct d_ocp_qp_ipm_arg *arg); -// -void d_ocp_qp_ipm_arg_codegen(char *file_name, char *mode, struct d_ocp_qp_dim *qp_dim, struct d_ocp_qp_ipm_arg *arg); -// -void d_ocp_qp_res_print(struct d_ocp_qp_dim *qp_dim, struct d_ocp_qp_res *ocp_qp_res); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_D_OCP_QP_UTILS_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_part_cond.h b/third_party/acados/include/hpipm/include/hpipm_d_part_cond.h deleted file mode 100644 index 1c5f785..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_part_cond.h +++ /dev/null @@ -1,115 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_D_PART_COND_H_ -#define HPIPM_D_PART_COND_H_ - - - -#include -#include - -#include "hpipm_common.h" -#include "hpipm_d_cond.h" - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_part_cond_qp_arg - { - struct d_cond_qp_arg *cond_arg; - int N2; - hpipm_size_t memsize; - }; - - - -struct d_part_cond_qp_ws - { - struct d_cond_qp_ws *cond_workspace; - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_part_cond_qp_arg_memsize(int N2); -// -void d_part_cond_qp_arg_create(int N2, struct d_part_cond_qp_arg *cond_arg, void *mem); -// -void d_part_cond_qp_arg_set_default(struct d_part_cond_qp_arg *cond_arg); -// set riccati-like algorithm: 0 classical, 1 squre-root -void d_part_cond_qp_arg_set_ric_alg(int ric_alg, struct d_part_cond_qp_arg *cond_arg); -// -void d_part_cond_qp_arg_set_comp_prim_sol(int value, struct d_part_cond_qp_arg *cond_arg); -// -void d_part_cond_qp_arg_set_comp_dual_sol_eq(int value, struct d_part_cond_qp_arg *cond_arg); -// -void d_part_cond_qp_arg_set_comp_dual_sol_ineq(int value, struct d_part_cond_qp_arg *cond_arg); - -// -void d_part_cond_qp_compute_block_size(int N, int N2, int *block_size); -// -void d_part_cond_qp_compute_dim(struct d_ocp_qp_dim *ocp_dim, int *block_size, struct d_ocp_qp_dim *part_dense_dim); -// -hpipm_size_t d_part_cond_qp_ws_memsize(struct d_ocp_qp_dim *ocp_dim, int *block_size, struct d_ocp_qp_dim *part_dense_dim, struct d_part_cond_qp_arg *cond_arg); -// -void d_part_cond_qp_ws_create(struct d_ocp_qp_dim *ocp_dim, int *block_size, struct d_ocp_qp_dim *part_dense_dim, struct d_part_cond_qp_arg *cond_arg, struct d_part_cond_qp_ws *cond_ws, void *mem); -// -void d_part_cond_qp_cond(struct d_ocp_qp *ocp_qp, struct d_ocp_qp *part_dense_qp, struct d_part_cond_qp_arg *cond_arg, struct d_part_cond_qp_ws *cond_ws); -// -void d_part_cond_qp_cond_lhs(struct d_ocp_qp *ocp_qp, struct d_ocp_qp *part_dense_qp, struct d_part_cond_qp_arg *cond_arg, struct d_part_cond_qp_ws *cond_ws); -// -void d_part_cond_qp_cond_rhs(struct d_ocp_qp *ocp_qp, struct d_ocp_qp *part_dense_qp, struct d_part_cond_qp_arg *cond_arg, struct d_part_cond_qp_ws *cond_ws); -// -void d_part_cond_qp_expand_sol(struct d_ocp_qp *ocp_qp, struct d_ocp_qp *part_dense_qp, struct d_ocp_qp_sol *part_dense_qp_sol, struct d_ocp_qp_sol *ocp_qp_sol, struct d_part_cond_qp_arg *cond_arg, struct d_part_cond_qp_ws *cond_ws); - -// -void d_part_cond_qp_update(int *idxc, struct d_ocp_qp *ocp_qp, struct d_ocp_qp *part_dense_qp, struct d_part_cond_qp_arg *cond_arg, struct d_part_cond_qp_ws *cond_ws); - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_D_PART_COND_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_part_cond_qcqp.h b/third_party/acados/include/hpipm/include/hpipm_d_part_cond_qcqp.h deleted file mode 100644 index 2d6624e..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_part_cond_qcqp.h +++ /dev/null @@ -1,106 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_D_PART_COND_QCQP_H_ -#define HPIPM_D_PART_COND_QCQP_H_ - - - -#include -#include - -#include "hpipm_d_cond_qcqp.h" - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_part_cond_qcqp_arg - { - struct d_cond_qcqp_arg *cond_arg; - int N2; - hpipm_size_t memsize; - }; - - - -struct d_part_cond_qcqp_ws - { - struct d_cond_qcqp_ws *cond_ws; - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_part_cond_qcqp_arg_memsize(int N2); -// -void d_part_cond_qcqp_arg_create(int N2, struct d_part_cond_qcqp_arg *cond_arg, void *mem); -// -void d_part_cond_qcqp_arg_set_default(struct d_part_cond_qcqp_arg *cond_arg); -// set riccati-like algorithm: 0 classical, 1 squre-root -void d_part_cond_qcqp_arg_set_ric_alg(int ric_alg, struct d_part_cond_qcqp_arg *cond_arg); - -// -void d_part_cond_qcqp_compute_block_size(int N, int N2, int *block_size); -// -void d_part_cond_qcqp_compute_dim(struct d_ocp_qcqp_dim *ocp_dim, int *block_size, struct d_ocp_qcqp_dim *part_dense_dim); -// -hpipm_size_t d_part_cond_qcqp_ws_memsize(struct d_ocp_qcqp_dim *ocp_dim, int *block_size, struct d_ocp_qcqp_dim *part_dense_dim, struct d_part_cond_qcqp_arg *cond_arg); -// -void d_part_cond_qcqp_ws_create(struct d_ocp_qcqp_dim *ocp_dim, int *block_size, struct d_ocp_qcqp_dim *part_dense_dim, struct d_part_cond_qcqp_arg *cond_arg, struct d_part_cond_qcqp_ws *cond_ws, void *mem); -// -void d_part_cond_qcqp_cond(struct d_ocp_qcqp *ocp_qp, struct d_ocp_qcqp *part_dense_qp, struct d_part_cond_qcqp_arg *cond_arg, struct d_part_cond_qcqp_ws *cond_ws); -// -void d_part_cond_qcqp_cond_lhs(struct d_ocp_qcqp *ocp_qp, struct d_ocp_qcqp *part_dense_qp, struct d_part_cond_qcqp_arg *cond_arg, struct d_part_cond_qcqp_ws *cond_ws); -// -void d_part_cond_qcqp_cond_rhs(struct d_ocp_qcqp *ocp_qp, struct d_ocp_qcqp *part_dense_qp, struct d_part_cond_qcqp_arg *cond_arg, struct d_part_cond_qcqp_ws *cond_ws); -// -void d_part_cond_qcqp_expand_sol(struct d_ocp_qcqp *ocp_qp, struct d_ocp_qcqp *part_dense_qp, struct d_ocp_qcqp_sol *part_dense_qp_sol, struct d_ocp_qcqp_sol *ocp_qp_sol, struct d_part_cond_qcqp_arg *cond_arg, struct d_part_cond_qcqp_ws *cond_ws); - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_D_PART_COND_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_sim_erk.h b/third_party/acados/include/hpipm/include/hpipm_d_sim_erk.h deleted file mode 100644 index 320b66b..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_sim_erk.h +++ /dev/null @@ -1,122 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_SIM_ERK_H_ -#define HPIPM_D_SIM_ERK_H_ - -#include "hpipm_common.h" - -#ifdef __cplusplus -extern "C" { -#endif - -struct d_sim_erk_arg - { - struct d_sim_rk_data *rk_data; // integrator data - double h; // step size - int steps; // number of steps -// int for_sens; // compute adjoint sensitivities -// int adj_sens; // compute adjoint sensitivities - hpipm_size_t memsize; - }; - - - -struct d_sim_erk_ws - { - void (*ode)(int t, double *x, double *p, void *ode_args, double *xdot); // function pointer to ode - void (*vde_for)(int t, double *x, double *p, void *ode_args, double *xdot); // function pointer to forward vde - void (*vde_adj)(int t, double *adj_in, void *ode_args, double *adj_out); // function pointer to adjoint vde - void *ode_args; // pointer to ode args - struct d_sim_erk_arg *erk_arg; // erk arg - double *K; // internal variables - double *x_for; // states and forward sensitivities - double *x_traj; // states at all steps - double *l; // adjoint sensitivities - double *p; // parameter - double *x_tmp; // temporary states and forward sensitivities - double *adj_in; - double *adj_tmp; - int nx; // number of states - int np; // number of parameters - int nf; // number of forward sensitivities - int na; // number of adjoint sensitivities - int nf_max; // max number of forward sensitivities - int na_max; // max number of adjoint sensitivities - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_sim_erk_arg_memsize(); -// -void d_sim_erk_arg_create(struct d_sim_erk_arg *erk_arg, void *mem); -// -void d_sim_erk_arg_set_all(struct d_sim_rk_data *rk_data, double h, int steps, struct d_sim_erk_arg *erk_arg); - -// -hpipm_size_t d_sim_erk_ws_memsize(struct d_sim_erk_arg *erk_arg, int nx, int np, int nf_max, int na_max); -// -void d_sim_erk_ws_create(struct d_sim_erk_arg *erk_arg, int nx, int np, int nf_max, int na_max, struct d_sim_erk_ws *work, void *memory); -// -void d_sim_erk_ws_set_all(int nf, int na, double *x, double *fs, double *bs, double *p, void (*ode)(int t, double *x, double *p, void *ode_args, double *xdot), void (*vde_for)(int t, double *x, double *p, void *ode_args, double *xdot), void (*vde_adj)(int t, double *adj_in, void *ode_args, double *adj_out), void *ode_args, struct d_sim_erk_ws *work); -// number of directions for forward sensitivities -void d_sim_erk_ws_set_nf(int *nf, struct d_sim_erk_ws *work); -// parameters (e.g. inputs) -void d_sim_erk_ws_set_p(double *p, struct d_sim_erk_ws *work); -// state -void d_sim_erk_ws_set_x(double *x, struct d_sim_erk_ws *work); -// forward sensitivities -void d_sim_erk_ws_set_fs(double *fs, struct d_sim_erk_ws *work); -// ode funtion -void d_sim_erk_ws_set_ode(void (*ode)(int t, double *x, double *p, void *ode_args, double *xdot), struct d_sim_erk_ws *work); -// forward vde function -void d_sim_erk_ws_set_vde_for(void (*ode)(int t, double *x, double *p, void *ode_args, double *xdot), struct d_sim_erk_ws *work); -// ode_args, passed straight to the ode/vde_for/vde_adj functions -void d_sim_erk_ws_set_ode_args(void *ode_args, struct d_sim_erk_ws *work); -// state -void d_sim_erk_ws_get_x(struct d_sim_erk_ws *work, double *x); -// forward sensitivities -void d_sim_erk_ws_get_fs(struct d_sim_erk_ws *work, double *fs); -// -void d_sim_erk_solve(struct d_sim_erk_arg *arg, struct d_sim_erk_ws *work); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // HPIPM_D_SIM_ERK_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_sim_rk.h b/third_party/acados/include/hpipm/include/hpipm_d_sim_rk.h deleted file mode 100644 index a50dcbb..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_sim_rk.h +++ /dev/null @@ -1,71 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_SIM_RK_H_ -#define HPIPM_D_SIM_RK_H_ - -#include "hpipm_common.h" - -#ifdef __cplusplus -extern "C" { -#endif - -struct d_sim_rk_data - { - double *A_rk; // A in butcher tableau - double *B_rk; // b in butcher tableau - double *C_rk; // c in butcher tableau - int expl; // erk vs irk - int ns; // number of stages - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_sim_rk_data_memsize(int ns); -// -void d_sim_rk_data_create(int ns, struct d_sim_rk_data *rk_data, void *memory); -// -void d_sim_rk_data_init_default(char *field, struct d_sim_rk_data *rk_data); -// -void d_sim_rk_data_set_all(int expl, double *A_rk, double *B_rk, double *C_rk, struct d_sim_rk_data *rk_data); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // HPIPM_D_SIM_RK_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qcqp.h b/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qcqp.h deleted file mode 100644 index f36b51a..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qcqp.h +++ /dev/null @@ -1,213 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_TREE_OCP_QCQP_H_ -#define HPIPM_D_TREE_OCP_QCQP_H_ - - - -#include -#include - -#include "hpipm_common.h" -#include "hpipm_d_tree_ocp_qcqp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_tree_ocp_qcqp - { - struct d_tree_ocp_qcqp_dim *dim; - struct blasfeo_dmat *BAbt; // Nn-1 - struct blasfeo_dmat *RSQrq; // Nn - struct blasfeo_dmat *DCt; // Nn - struct blasfeo_dmat **Hq; // Nn - struct blasfeo_dvec *b; // Nn-1 - struct blasfeo_dvec *rqz; // Nn - struct blasfeo_dvec *d; // Nn - struct blasfeo_dvec *d_mask; // Nn - struct blasfeo_dvec *m; // Nn - struct blasfeo_dvec *Z; // Nn - int **idxb; // indices of box constrained variables within [u; x] // Nn - int **idxs_rev; // index of soft constraints - hpipm_size_t memsize; // memory size in bytes - }; - - - -// -hpipm_size_t d_tree_ocp_qcqp_memsize(struct d_tree_ocp_qcqp_dim *dim); -// -void d_tree_ocp_qcqp_create(struct d_tree_ocp_qcqp_dim *dim, struct d_tree_ocp_qcqp *qp, void *memory); -// -void d_tree_ocp_qcqp_set_all(double **A, double **B, double **b, double **Q, double **S, double **R, double **q, double **r, int **idxb, double **d_lb, double **d_ub, double **C, double **D, double **d_lg, double **d_ug, double **Zl, double **Zu, double **zl, double **zu, int **idxs, double **d_ls, double **d_us, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set(char *field_name, int node_edge, void *value, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_A(int edge, double *mat, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_B(int edge, double *mat, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_b(int edge, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_Q(int node, double *mat, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_S(int node, double *mat, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_R(int node, double *mat, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_q(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_r(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_lb(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_lb_mask(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_ub(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_ub_mask(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_lbx(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_lbx_mask(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_ubx(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_ubx_mask(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_lbu(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_lbu_mask(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_ubu(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_ubu_mask(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_idxb(int node, int *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_idxbx(int node, int *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_Jbx(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_idxbu(int node, int *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_Jbu(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_C(int node, double *mat, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_D(int node, double *mat, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_lg(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_lg_mask(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_ug(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_ug_mask(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_Qq(int node, double *mat, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_Sq(int node, double *mat, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_Rq(int node, double *mat, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_qq(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_rq(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_uq(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_uq_mask(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_Zl(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_Zu(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_zl(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_zu(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_lls(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_lls_mask(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_lus(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_lus_mask(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_idxs(int node, int *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_idxs_rev(int node, int *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_Jsbu(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_Jsbx(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_Jsg(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_set_Jsq(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -//void d_tree_ocp_qcqp_set_idxe(int node, int *vec, struct d_tree_ocp_qcqp *qp); -// -//void d_tree_ocp_qcqp_set_idxbxe(int node, int *vec, struct d_tree_ocp_qcqp *qp); -// -//void d_tree_ocp_qcqp_set_idxbue(int node, int *vec, struct d_tree_ocp_qcqp *qp); -// -//void d_tree_ocp_qcqp_set_idxge(int node, int *vec, struct d_tree_ocp_qcqp *qp); -// -//void d_tree_ocp_qcqp_set_Jbxe(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -//void d_tree_ocp_qcqp_set_Jbue(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -//void d_tree_ocp_qcqp_set_Jge(int node, double *vec, struct d_tree_ocp_qcqp *qp); -// -//void d_tree_ocp_qcqp_set_diag_H_flag(int node, int *value, struct d_tree_ocp_qcqp *qp); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_D_TREE_OCP_QCQP_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qcqp_dim.h b/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qcqp_dim.h deleted file mode 100644 index 257b82b..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qcqp_dim.h +++ /dev/null @@ -1,117 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_TREE_OCP_QCQP_DIM_H_ -#define HPIPM_D_TREE_OCP_QCQP_DIM_H_ - -#include "hpipm_common.h" - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_tree_ocp_qcqp_dim - { - struct d_tree_ocp_qp_dim *qp_dim; // dim of qp approximation - struct tree *ttree; // tree describing node conndection - int *nx; // number of states // Nn - int *nu; // number of inputs // Nn - int *nb; // number of box constraints // Nn - int *nbx; // number of state box constraints // Nn - int *nbu; // number of input box constraints // Nn - int *ng; // number of general constraints // Nn - int *nq; // number of (upper) quadratic constraints - int *ns; // number of soft constraints // Nn - int *nsbx; // number of soft state box constraints - int *nsbu; // number of soft input box constraints - int *nsg; // number of soft general constraints - int *nsq; // number of (upper) soft quadratic constraints - int Nn; // number of nodes - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_tree_ocp_qcqp_dim_strsize(); -// -hpipm_size_t d_tree_ocp_qcqp_dim_memsize(int Nn); -// -void d_tree_ocp_qcqp_dim_create(int Nn, struct d_tree_ocp_qcqp_dim *qp_dim, void *memory); -// -void d_tree_ocp_qcqp_dim_set_tree(struct tree *ttree, struct d_tree_ocp_qcqp_dim *dim); -// -void d_tree_ocp_qcqp_dim_set(char *field, int stage, int value, struct d_tree_ocp_qcqp_dim *dim); -// -void d_tree_ocp_qcqp_dim_set_nx(int stage, int value, struct d_tree_ocp_qcqp_dim *dim); -// -void d_tree_ocp_qcqp_dim_set_nu(int stage, int value, struct d_tree_ocp_qcqp_dim *dim); -// -void d_tree_ocp_qcqp_dim_set_nbx(int stage, int value, struct d_tree_ocp_qcqp_dim *dim); -// -void d_tree_ocp_qcqp_dim_set_nbu(int stage, int value, struct d_tree_ocp_qcqp_dim *dim); -// -void d_tree_ocp_qcqp_dim_set_ng(int stage, int value, struct d_tree_ocp_qcqp_dim *dim); -// -void d_tree_ocp_qcqp_dim_set_nq(int stage, int value, struct d_tree_ocp_qcqp_dim *dim); -// -void d_tree_ocp_qcqp_dim_set_ns(int stage, int value, struct d_tree_ocp_qcqp_dim *dim); -// -void d_tree_ocp_qcqp_dim_set_nsbx(int stage, int value, struct d_tree_ocp_qcqp_dim *dim); -// -void d_tree_ocp_qcqp_dim_set_nsbu(int stage, int value, struct d_tree_ocp_qcqp_dim *dim); -// -void d_tree_ocp_qcqp_dim_set_nsg(int stage, int value, struct d_tree_ocp_qcqp_dim *dim); -// -void d_tree_ocp_qcqp_dim_set_nsq(int stage, int value, struct d_tree_ocp_qcqp_dim *dim); -// -//void d_tree_ocp_qcqp_dim_set_nbxe(int stage, int value, struct d_tree_ocp_qcqp_dim *dim); -// -//void d_tree_ocp_qcqp_dim_set_nbue(int stage, int value, struct d_tree_ocp_qcqp_dim *dim); -// -//void d_tree_ocp_qcqp_dim_set_nge(int stage, int value, struct d_tree_ocp_qcqp_dim *dim); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_D_TREE_OCP_QCQP_DIM_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qcqp_ipm.h b/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qcqp_ipm.h deleted file mode 100644 index 4a0fed1..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qcqp_ipm.h +++ /dev/null @@ -1,191 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_TREE_OCP_QCQP_IPM_H_ -#define HPIPM_D_TREE_OCP_QCQP_IPM_H_ - - - -#include -#include - -#include -#include -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_tree_ocp_qcqp_ipm_arg - { - struct d_tree_ocp_qp_ipm_arg *qp_arg; - double mu0; // initial value for complementarity slackness - double alpha_min; // exit cond on step length - double res_g_max; // exit cond on inf norm of residuals - double res_b_max; // exit cond on inf norm of residuals - double res_d_max; // exit cond on inf norm of residuals - double res_m_max; // exit cond on inf norm of residuals - double reg_prim; // reg of primal hessian - double lam_min; // min value in lam vector - double t_min; // min value in t vector - int iter_max; // exit cond in iter number - int stat_max; // iterations saved in stat - int pred_corr; // use Mehrotra's predictor-corrector IPM algirthm - int cond_pred_corr; // conditional Mehrotra's predictor-corrector - int itref_pred_max; // max number of iterative refinement steps for predictor step - int itref_corr_max; // max number of iterative refinement steps for corrector step - int warm_start; // 0 no warm start, 1 warm start primal sol, 2 warm start primal and dual sol -// int square_root_alg; // 0 classical Riccati, 1 square-root Riccati - int lq_fact; // 0 syrk+potrf, 1 mix, 2 lq (for square_root_alg==1) - int abs_form; // absolute IPM formulation - int comp_dual_sol_eq; // dual solution of equality constrains (only for abs_form==1) - int comp_res_exit; // compute residuals on exit (only for abs_form==1 and comp_dual_sol_eq==1) -// int comp_res_pred; // compute residuals of prediction - int split_step; // use different step for primal and dual variables - int t_lam_min; // clip t and lam: 0 no, 1 in Gamma computation, 2 in solution - int mode; - hpipm_size_t memsize; - }; - - - -struct d_tree_ocp_qcqp_ipm_ws - { - struct d_tree_ocp_qp_ipm_ws *qp_ws; - struct d_tree_ocp_qp *qp; - struct d_tree_ocp_qp_sol *qp_sol; - struct d_tree_ocp_qcqp_res_ws *qcqp_res_ws; - struct d_tree_ocp_qcqp_res *qcqp_res; - struct blasfeo_dvec *tmp_nuxM; - int iter; // iteration number - int status; - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_tree_ocp_qcqp_ipm_arg_strsize(); -// -hpipm_size_t d_tree_ocp_qcqp_ipm_arg_memsize(struct d_tree_ocp_qcqp_dim *ocp_dim); -// -void d_tree_ocp_qcqp_ipm_arg_create(struct d_tree_ocp_qcqp_dim *ocp_dim, struct d_tree_ocp_qcqp_ipm_arg *arg, void *mem); -// -void d_tree_ocp_qcqp_ipm_arg_set_default(enum hpipm_mode mode, struct d_tree_ocp_qcqp_ipm_arg *arg); -// -void d_tree_ocp_qcqp_ipm_arg_set(char *field, void *value, struct d_tree_ocp_qcqp_ipm_arg *arg); -// set maximum number of iterations -void d_tree_ocp_qcqp_ipm_arg_set_iter_max(int *value, struct d_tree_ocp_qcqp_ipm_arg *arg); -// set minimum step lenght -void d_tree_ocp_qcqp_ipm_arg_set_alpha_min(double *value, struct d_tree_ocp_qcqp_ipm_arg *arg); -// set initial value of barrier parameter -void d_tree_ocp_qcqp_ipm_arg_set_mu0(double *value, struct d_tree_ocp_qcqp_ipm_arg *arg); -// set exit tolerance on stationarity condition -void d_tree_ocp_qcqp_ipm_arg_set_tol_stat(double *value, struct d_tree_ocp_qcqp_ipm_arg *arg); -// set exit tolerance on equality constr -void d_tree_ocp_qcqp_ipm_arg_set_tol_eq(double *value, struct d_tree_ocp_qcqp_ipm_arg *arg); -// set exit tolerance on inequality constr -void d_tree_ocp_qcqp_ipm_arg_set_tol_ineq(double *value, struct d_tree_ocp_qcqp_ipm_arg *arg); -// set exit tolerance on complementarity condition -void d_tree_ocp_qcqp_ipm_arg_set_tol_comp(double *value, struct d_tree_ocp_qcqp_ipm_arg *arg); -// set regularization of primal variables -void d_tree_ocp_qcqp_ipm_arg_set_reg_prim(double *value, struct d_tree_ocp_qcqp_ipm_arg *arg); -// set warm start: 0 no warm start, 1 primal var -void d_tree_ocp_qcqp_ipm_arg_set_warm_start(int *value, struct d_tree_ocp_qcqp_ipm_arg *arg); -// Mehrotra's predictor-corrector IPM algorithm: 0 no predictor-corrector, 1 use predictor-corrector -void d_tree_ocp_qcqp_ipm_arg_set_pred_corr(int *value, struct d_tree_ocp_qcqp_ipm_arg *arg); -// conditional predictor-corrector: 0 no conditinal predictor-corrector, 1 conditional predictor-corrector -void d_tree_ocp_qcqp_ipm_arg_set_cond_pred_corr(int *value, struct d_tree_ocp_qcqp_ipm_arg *arg); -// set riccati algorithm: 0 classic, 1 square-root -//void d_tree_ocp_qcqp_ipm_arg_set_ric_alg(int *value, struct d_tree_ocp_qcqp_ipm_arg *arg); -// compute residuals after solution -void d_tree_ocp_qcqp_ipm_arg_set_comp_res_exit(int *value, struct d_tree_ocp_qcqp_ipm_arg *arg); -// compute residuals of prediction -//void d_tree_ocp_qcqp_ipm_arg_set_comp_res_pred(int *value, struct d_tree_ocp_qcqp_ipm_arg *arg); -// min value of lam in the solution -void d_tree_ocp_qcqp_ipm_arg_set_lam_min(double *value, struct d_tree_ocp_qcqp_ipm_arg *arg); -// min value of t in the solution -void d_tree_ocp_qcqp_ipm_arg_set_t_min(double *value, struct d_tree_ocp_qcqp_ipm_arg *arg); -// use different step for primal and dual variables -void d_tree_ocp_qcqp_ipm_arg_set_split_step(int *value, struct d_tree_ocp_qcqp_ipm_arg *arg); -// clip t and lam: 0 no, 1 in Gamma computation, 2 in solution -void d_tree_ocp_qcqp_ipm_arg_set_t_lam_min(int *value, struct d_tree_ocp_qcqp_ipm_arg *arg); - -// -hpipm_size_t d_tree_ocp_qcqp_ipm_ws_strsize(); -// -hpipm_size_t d_tree_ocp_qcqp_ipm_ws_memsize(struct d_tree_ocp_qcqp_dim *ocp_dim, struct d_tree_ocp_qcqp_ipm_arg *arg); -// -void d_tree_ocp_qcqp_ipm_ws_create(struct d_tree_ocp_qcqp_dim *ocp_dim, struct d_tree_ocp_qcqp_ipm_arg *arg, struct d_tree_ocp_qcqp_ipm_ws *ws, void *mem); -// -void d_tree_ocp_qcqp_ipm_get(char *field, struct d_tree_ocp_qcqp_ipm_ws *ws, void *value); -// -void d_tree_ocp_qcqp_ipm_get_status(struct d_tree_ocp_qcqp_ipm_ws *ws, int *status); -// -void d_tree_ocp_qcqp_ipm_get_iter(struct d_tree_ocp_qcqp_ipm_ws *ws, int *iter); -// -void d_tree_ocp_qcqp_ipm_get_max_res_stat(struct d_tree_ocp_qcqp_ipm_ws *ws, double *res_stat); -// -void d_tree_ocp_qcqp_ipm_get_max_res_eq(struct d_tree_ocp_qcqp_ipm_ws *ws, double *res_eq); -// -void d_tree_ocp_qcqp_ipm_get_max_res_ineq(struct d_tree_ocp_qcqp_ipm_ws *ws, double *res_ineq); -// -void d_tree_ocp_qcqp_ipm_get_max_res_comp(struct d_tree_ocp_qcqp_ipm_ws *ws, double *res_comp); -// -void d_tree_ocp_qcqp_ipm_get_stat(struct d_tree_ocp_qcqp_ipm_ws *ws, double **stat); -// -void d_tree_ocp_qcqp_ipm_get_stat_m(struct d_tree_ocp_qcqp_ipm_ws *ws, int *stat_m); -// -void d_tree_ocp_qcqp_init_var(struct d_tree_ocp_qcqp *qp, struct d_tree_ocp_qcqp_sol *qp_sol, struct d_tree_ocp_qcqp_ipm_arg *arg, struct d_tree_ocp_qcqp_ipm_ws *ws); -// -void d_tree_ocp_qcqp_ipm_solve(struct d_tree_ocp_qcqp *qp, struct d_tree_ocp_qcqp_sol *qp_sol, struct d_tree_ocp_qcqp_ipm_arg *arg, struct d_tree_ocp_qcqp_ipm_ws *ws); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - -#endif // HPIPM_D_TREE_OCP_QCQP_IPM_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qcqp_res.h b/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qcqp_res.h deleted file mode 100644 index 69eebb1..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qcqp_res.h +++ /dev/null @@ -1,108 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_TREE_OCP_QCQP_RES_H_ -#define HPIPM_D_TREE_OCP_QCQP_RES_H_ - - - -#include -#include - -#include -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_tree_ocp_qcqp_res - { - struct d_tree_ocp_qcqp_dim *dim; - struct blasfeo_dvec *res_g; // q-residuals - struct blasfeo_dvec *res_b; // b-residuals - struct blasfeo_dvec *res_d; // d-residuals - struct blasfeo_dvec *res_m; // m-residuals - double res_max[4]; // max of residuals - double res_mu; // mu-residual - hpipm_size_t memsize; - }; - - - -struct d_tree_ocp_qcqp_res_ws - { - struct blasfeo_dvec *tmp_nuxM; // work space of size nuM+nxM - struct blasfeo_dvec *tmp_nbgqM; // work space of size nbM+ngM+nqM - struct blasfeo_dvec *tmp_nsM; // work space of size nsM - struct blasfeo_dvec *q_fun; // value for evaluation of quadr constr - struct blasfeo_dvec *q_adj; // value for adjoint of quadr constr - int use_q_fun; // reuse cached value for evaluation of quadr constr - int use_q_adj; // reuse cached value for adjoint of quadr constr - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_tree_ocp_qcqp_res_memsize(struct d_tree_ocp_qcqp_dim *ocp_dim); -// -void d_tree_ocp_qcqp_res_create(struct d_tree_ocp_qcqp_dim *ocp_dim, struct d_tree_ocp_qcqp_res *res, void *mem); -// -hpipm_size_t d_tree_ocp_qcqp_res_ws_memsize(struct d_tree_ocp_qcqp_dim *ocp_dim); -// -void d_tree_ocp_qcqp_res_ws_create(struct d_tree_ocp_qcqp_dim *ocp_dim, struct d_tree_ocp_qcqp_res_ws *ws, void *mem); -// -void d_tree_ocp_qcqp_res_compute(struct d_tree_ocp_qcqp *qp, struct d_tree_ocp_qcqp_sol *qp_sol, struct d_tree_ocp_qcqp_res *res, struct d_tree_ocp_qcqp_res_ws *ws); -// -void d_tree_ocp_qcqp_res_compute_inf_norm(struct d_tree_ocp_qcqp_res *res); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - -#endif // HPIPM_D_TREE_OCP_QCQP_RES_H_ - - - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qcqp_sol.h b/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qcqp_sol.h deleted file mode 100644 index cde8de5..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qcqp_sol.h +++ /dev/null @@ -1,99 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_TREE_OCP_QCQP_SOL_H_ -#define HPIPM_D_TREE_OCP_QCQP_SOL_H_ - - - -#include -#include - -#include "hpipm_d_tree_ocp_qcqp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - -struct d_tree_ocp_qcqp_sol - { - struct d_tree_ocp_qcqp_dim *dim; - struct blasfeo_dvec *ux; - struct blasfeo_dvec *pi; - struct blasfeo_dvec *lam; - struct blasfeo_dvec *t; - void *misc; - hpipm_size_t memsize; // memory size in bytes - }; - - - -// -hpipm_size_t d_tree_ocp_qcqp_sol_memsize(struct d_tree_ocp_qcqp_dim *dim); -// -void d_tree_ocp_qcqp_sol_create(struct d_tree_ocp_qcqp_dim *dim, struct d_tree_ocp_qcqp_sol *qp_sol, void *memory); -// -void d_tree_ocp_qcqp_sol_get(char *field, int node_edge, struct d_tree_ocp_qcqp_sol *qp_sol, double *vec); -// -void d_tree_ocp_qcqp_sol_get_u(int node, struct d_tree_ocp_qcqp_sol *qp_sol, double *vec); -// -void d_tree_ocp_qcqp_sol_get_x(int node, struct d_tree_ocp_qcqp_sol *qp_sol, double *vec); -// -void d_tree_ocp_qcqp_sol_get_sl(int node, struct d_tree_ocp_qcqp_sol *qp_sol, double *vec); -// -void d_tree_ocp_qcqp_sol_get_su(int node, struct d_tree_ocp_qcqp_sol *qp_sol, double *vec); -// -void d_tree_ocp_qcqp_sol_get_pi(int edge, struct d_tree_ocp_qcqp_sol *qp_sol, double *vec); -// -void d_tree_ocp_qcqp_sol_get_lam_lb(int node, struct d_tree_ocp_qcqp_sol *qp_sol, double *vec); -// -void d_tree_ocp_qcqp_sol_get_lam_ub(int node, struct d_tree_ocp_qcqp_sol *qp_sol, double *vec); -// -void d_tree_ocp_qcqp_sol_get_lam_lg(int node, struct d_tree_ocp_qcqp_sol *qp_sol, double *vec); -// -void d_tree_ocp_qcqp_sol_get_lam_ug(int node, struct d_tree_ocp_qcqp_sol *qp_sol, double *vec); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_D_TREE_OCP_QCQP_SOL_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qcqp_utils.h b/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qcqp_utils.h deleted file mode 100644 index 5ef04fc..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qcqp_utils.h +++ /dev/null @@ -1,84 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_TREE_OCP_QP_UTILS_H_ -#define HPIPM_D_TREE_OCP_QP_UTILS_H_ - - - -#include -#include - -#include "hpipm_d_tree_ocp_qcqp_dim.h" -#include "hpipm_d_tree_ocp_qcqp.h" -#include "hpipm_d_tree_ocp_qcqp_sol.h" -#include "hpipm_d_tree_ocp_qcqp_ipm.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -// -void d_tree_ocp_qcqp_dim_print(struct d_tree_ocp_qcqp_dim *qp_dim); -// -//void d_tree_ocp_qcqp_dim_codegen(char *file_name, char *mode, struct d_tree_ocp_qcqp_dim *qp_dim); -// -void d_tree_ocp_qcqp_print(struct d_tree_ocp_qcqp_dim *qp_dim, struct d_tree_ocp_qcqp *qp); -// -//void d_tree_ocp_qcqp_codegen(char *file_name, char *mode, struct d_tree_ocp_qcqp_dim *qp_dim, struct d_tree_ocp_qcqp *qp); -// -void d_tree_ocp_qcqp_sol_print(struct d_tree_ocp_qcqp_dim *qp_dim, struct d_tree_ocp_qcqp_sol *ocp_qcqp_sol); -// -void d_tree_ocp_qcqp_ipm_arg_print(struct d_tree_ocp_qcqp_dim *qp_dim, struct d_tree_ocp_qcqp_ipm_arg *arg); -// -//void d_tree_ocp_qcqp_ipm_arg_codegen(char *file_name, char *mode, struct d_tree_ocp_qcqp_dim *qp_dim, struct d_tree_ocp_qcqp_ipm_arg *arg); -// -void d_tree_ocp_qcqp_res_print(struct d_tree_ocp_qcqp_dim *qp_dim, struct d_tree_ocp_qcqp_res *ocp_qcqp_res); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_D_TREE_OCP_QP_UTILS_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qp.h b/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qp.h deleted file mode 100644 index 1666ad7..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qp.h +++ /dev/null @@ -1,195 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_TREE_OCP_QP_H_ -#define HPIPM_D_TREE_OCP_QP_H_ - - - -#include -#include - -#include "hpipm_d_tree_ocp_qp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_tree_ocp_qp - { - struct d_tree_ocp_qp_dim *dim; - struct blasfeo_dmat *BAbt; // Nn-1 - struct blasfeo_dmat *RSQrq; // Nn - struct blasfeo_dmat *DCt; // Nn - struct blasfeo_dvec *b; // Nn-1 - struct blasfeo_dvec *rqz; // Nn - struct blasfeo_dvec *d; // Nn - struct blasfeo_dvec *d_mask; // Nn - struct blasfeo_dvec *m; // Nn - struct blasfeo_dvec *Z; // Nn - int **idxb; // indices of box constrained variables within [u; x] // Nn -// int **idxs; // index of soft constraints - int **idxs_rev; // index of soft constraints - hpipm_size_t memsize; // memory size in bytes - }; - - - -// -hpipm_size_t d_tree_ocp_qp_memsize(struct d_tree_ocp_qp_dim *dim); -// -void d_tree_ocp_qp_create(struct d_tree_ocp_qp_dim *dim, struct d_tree_ocp_qp *qp, void *memory); -// -void d_tree_ocp_qp_set_all(double **A, double **B, double **b, double **Q, double **S, double **R, double **q, double **r, int **idxb, double **d_lb, double **d_ub, double **C, double **D, double **d_lg, double **d_ug, double **Zl, double **Zu, double **zl, double **zu, int **idxs, double **d_ls, double **d_us, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set(char *field_name, int node_edge, void *value, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_A(int edge, double *mat, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_B(int edge, double *mat, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_b(int edge, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_Q(int node, double *mat, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_S(int node, double *mat, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_R(int node, double *mat, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_q(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_r(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_lb(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_lb_mask(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_ub(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_ub_mask(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_lbx(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_lbx_mask(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_ubx(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_ubx_mask(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_lbu(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_lbu_mask(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_ubu(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_ubu_mask(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_idxb(int node, int *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_idxbx(int node, int *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_Jbx(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_idxbu(int node, int *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_Jbu(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_C(int node, double *mat, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_D(int node, double *mat, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_lg(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_lg_mask(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_ug(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_ug_mask(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_Zl(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_Zu(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_zl(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_zu(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_lls(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_lls_mask(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_lus(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_lus_mask(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_idxs(int node, int *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_idxs_rev(int node, int *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_Jsbu(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_Jsbx(int node, double *vec, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_set_Jsg(int node, double *vec, struct d_tree_ocp_qp *qp); -// -//void d_tree_ocp_qp_set_idxe(int node, int *vec, struct d_tree_ocp_qp *qp); -// -//void d_tree_ocp_qp_set_idxbxe(int node, int *vec, struct d_tree_ocp_qp *qp); -// -//void d_tree_ocp_qp_set_idxbue(int node, int *vec, struct d_tree_ocp_qp *qp); -// -//void d_tree_ocp_qp_set_idxge(int node, int *vec, struct d_tree_ocp_qp *qp); -// -//void d_tree_ocp_qp_set_Jbxe(int node, double *vec, struct d_tree_ocp_qp *qp); -// -//void d_tree_ocp_qp_set_Jbue(int node, double *vec, struct d_tree_ocp_qp *qp); -// -//void d_tree_ocp_qp_set_Jge(int node, double *vec, struct d_tree_ocp_qp *qp); -// -//void d_tree_ocp_qp_set_diag_H_flag(int node, int *value, struct d_tree_ocp_qp *qp); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_D_TREE_OCP_QP_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qp_dim.h b/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qp_dim.h deleted file mode 100644 index 659b664..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qp_dim.h +++ /dev/null @@ -1,111 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_TREE_OCP_QP_DIM_H_ -#define HPIPM_D_TREE_OCP_QP_DIM_H_ - -#include "hpipm_common.h" - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_tree_ocp_qp_dim - { - struct tree *ttree; // tree describing node conndection - int *nx; // number of states // Nn - int *nu; // number of inputs // Nn - int *nb; // number of box constraints // Nn - int *nbx; // number of state box constraints // Nn - int *nbu; // number of input box constraints // Nn - int *ng; // number of general constraints // Nn - int *ns; // number of soft constraints // Nn - int *nsbx; // number of soft state box constraints - int *nsbu; // number of soft input box constraints - int *nsg; // number of soft general constraints - int Nn; // number of nodes - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_tree_ocp_qp_dim_strsize(); -// -hpipm_size_t d_tree_ocp_qp_dim_memsize(int Nn); -// -void d_tree_ocp_qp_dim_create(int Nn, struct d_tree_ocp_qp_dim *qp_dim, void *memory); -// -void d_tree_ocp_qp_dim_set_all(struct tree *ttree, int *nx, int *nu, int *nbx, int *nbu, int *ng, int *nsbx, int *nsbu, int *nsg, struct d_tree_ocp_qp_dim *dim); -// -void d_tree_ocp_qp_dim_set_tree(struct tree *ttree, struct d_tree_ocp_qp_dim *dim); -// -void d_tree_ocp_qp_dim_set(char *field, int stage, int value, struct d_tree_ocp_qp_dim *dim); -// -void d_tree_ocp_qp_dim_set_nx(int stage, int value, struct d_tree_ocp_qp_dim *dim); -// -void d_tree_ocp_qp_dim_set_nu(int stage, int value, struct d_tree_ocp_qp_dim *dim); -// -void d_tree_ocp_qp_dim_set_nbx(int stage, int value, struct d_tree_ocp_qp_dim *dim); -// -void d_tree_ocp_qp_dim_set_nbu(int stage, int value, struct d_tree_ocp_qp_dim *dim); -// -void d_tree_ocp_qp_dim_set_ng(int stage, int value, struct d_tree_ocp_qp_dim *dim); -// -void d_tree_ocp_qp_dim_set_ns(int stage, int value, struct d_tree_ocp_qp_dim *dim); -// -void d_tree_ocp_qp_dim_set_nsbx(int stage, int value, struct d_tree_ocp_qp_dim *dim); -// -void d_tree_ocp_qp_dim_set_nsbu(int stage, int value, struct d_tree_ocp_qp_dim *dim); -// -void d_tree_ocp_qp_dim_set_nsg(int stage, int value, struct d_tree_ocp_qp_dim *dim); -// -void d_tree_ocp_qp_dim_set_nbxe(int stage, int value, struct d_tree_ocp_qp_dim *dim); -// -void d_tree_ocp_qp_dim_set_nbue(int stage, int value, struct d_tree_ocp_qp_dim *dim); -// -void d_tree_ocp_qp_dim_set_nge(int stage, int value, struct d_tree_ocp_qp_dim *dim); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_D_TREE_OCP_QP_DIM_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qp_ipm.h b/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qp_ipm.h deleted file mode 100644 index fb63420..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qp_ipm.h +++ /dev/null @@ -1,209 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_D_TREE_OCP_QP_IPM_H_ -#define HPIPM_D_TREE_OCP_QP_IPM_H_ - - - -#include -#include - -#include -#include -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_tree_ocp_qp_ipm_arg - { - double mu0; // initial value for duality measure - double alpha_min; // exit cond on step length - double res_g_max; // exit cond on inf norm of residuals - double res_b_max; // exit cond on inf norm of residuals - double res_d_max; // exit cond on inf norm of residuals - double res_m_max; // exit cond on inf norm of residuals - double reg_prim; // reg of primal hessian - double lam_min; // min value in lam vector - double t_min; // min value in t vector - double tau_min; // min value of barrier parameter - int iter_max; // exit cond in iter number - int stat_max; // iterations saved in stat - int pred_corr; // use Mehrotra's predictor-corrector IPM algirthm - int cond_pred_corr; // conditional Mehrotra's predictor-corrector - int itref_pred_max; // max number of iterative refinement steps for predictor step - int itref_corr_max; // max number of iterative refinement steps for corrector step - int warm_start; // 0 no warm start, 1 warm start primal sol, 2 warm start primal and dual sol - int lq_fact; // 0 syrk+potrf, 1 mix, 2 lq - int abs_form; // absolute IPM formulation - int comp_dual_sol_eq; // dual solution (only for abs_form==1) - int comp_res_exit; // compute residuals on exit (only for abs_form==1 and comp_dual_sol==1) - int split_step; // use different steps for primal and dual variables - int t_lam_min; // clip t and lam: 0 no, 1 in Gamma computation, 2 in solution - int mode; - hpipm_size_t memsize; - }; - - - -struct d_tree_ocp_qp_ipm_ws - { - struct d_core_qp_ipm_workspace *core_workspace; - struct d_tree_ocp_qp_res_ws *res_workspace; - struct d_tree_ocp_qp_sol *sol_step; - struct d_tree_ocp_qp_sol *sol_itref; - struct d_tree_ocp_qp *qp_step; - struct d_tree_ocp_qp *qp_itref; - struct d_tree_ocp_qp_res *res_itref; - struct d_tree_ocp_qp_res *res; - struct blasfeo_dvec *Gamma; // hessian update - struct blasfeo_dvec *gamma; // hessian update - struct blasfeo_dvec *tmp_nxM; // work space of size nxM - struct blasfeo_dvec *tmp_nbgM; // work space of size nbgM - struct blasfeo_dvec *tmp_nsM; // work space of size nsM - struct blasfeo_dvec *Pb; // Pb - struct blasfeo_dvec *Zs_inv; - struct blasfeo_dmat *L; - struct blasfeo_dmat *Lh; - struct blasfeo_dmat *AL; - struct blasfeo_dmat *lq0; - struct blasfeo_dvec *tmp_m; - double *stat; // convergence statistics - int *use_hess_fact; - void *lq_work0; - double qp_res[4]; // infinity norm of residuals - int iter; // iteration number - int stat_max; // iterations saved in stat - int stat_m; // number of recorded stat per IPM iter - int use_Pb; - int status; // solver status - int lq_fact; // cache from arg - int mask_constr; // use constr mask - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_tree_ocp_qp_ipm_arg_memsize(struct d_tree_ocp_qp_dim *dim); -// -void d_tree_ocp_qp_ipm_arg_create(struct d_tree_ocp_qp_dim *dim, struct d_tree_ocp_qp_ipm_arg *arg, void *mem); -// -void d_tree_ocp_qp_ipm_arg_set_default(enum hpipm_mode mode, struct d_tree_ocp_qp_ipm_arg *arg); -// -void d_tree_ocp_qp_ipm_arg_set_iter_max(int *iter_max, struct d_tree_ocp_qp_ipm_arg *arg); -// -void d_tree_ocp_qp_ipm_arg_set_alpha_min(double *alpha_min, struct d_tree_ocp_qp_ipm_arg *arg); -// -void d_tree_ocp_qp_ipm_arg_set_mu0(double *mu0, struct d_tree_ocp_qp_ipm_arg *arg); -// -void d_tree_ocp_qp_ipm_arg_set_tol_stat(double *tol_stat, struct d_tree_ocp_qp_ipm_arg *arg); -// -void d_tree_ocp_qp_ipm_arg_set_tol_eq(double *tol_eq, struct d_tree_ocp_qp_ipm_arg *arg); -// -void d_tree_ocp_qp_ipm_arg_set_tol_ineq(double *tol_ineq, struct d_tree_ocp_qp_ipm_arg *arg); -// -void d_tree_ocp_qp_ipm_arg_set_tol_comp(double *tol_comp, struct d_tree_ocp_qp_ipm_arg *arg); -// -void d_tree_ocp_qp_ipm_arg_set_reg_prim(double *reg, struct d_tree_ocp_qp_ipm_arg *arg); -// -void d_tree_ocp_qp_ipm_arg_set_warm_start(int *warm_start, struct d_tree_ocp_qp_ipm_arg *arg); -// -void d_tree_ocp_qp_ipm_arg_set_pred_corr(int *pred_corr, struct d_tree_ocp_qp_ipm_arg *arg); -// -void d_tree_ocp_qp_ipm_arg_set_cond_pred_corr(int *value, struct d_tree_ocp_qp_ipm_arg *arg); -// -void d_tree_ocp_qp_ipm_arg_set_comp_dual_sol_eq(int *value, struct d_tree_ocp_qp_ipm_arg *arg); -// -void d_tree_ocp_qp_ipm_arg_set_comp_res_exit(int *value, struct d_tree_ocp_qp_ipm_arg *arg); -// -void d_tree_ocp_qp_ipm_arg_set_lam_min(double *value, struct d_tree_ocp_qp_ipm_arg *arg); -// -void d_tree_ocp_qp_ipm_arg_set_t_min(double *value, struct d_tree_ocp_qp_ipm_arg *arg); -// -void d_tree_ocp_qp_ipm_arg_set_tau_min(double *value, struct d_tree_ocp_qp_ipm_arg *arg); -// -void d_tree_ocp_qp_ipm_arg_set_split_step(int *value, struct d_tree_ocp_qp_ipm_arg *arg); -// -void d_tree_ocp_qp_ipm_arg_set_t_lam_min(int *value, struct d_tree_ocp_qp_ipm_arg *arg); - -// -hpipm_size_t d_tree_ocp_qp_ipm_ws_memsize(struct d_tree_ocp_qp_dim *dim, struct d_tree_ocp_qp_ipm_arg *arg); -// -void d_tree_ocp_qp_ipm_ws_create(struct d_tree_ocp_qp_dim *dim, struct d_tree_ocp_qp_ipm_arg *arg, struct d_tree_ocp_qp_ipm_ws *ws, void *mem); -// -void d_tree_ocp_qp_ipm_get_status(struct d_tree_ocp_qp_ipm_ws *ws, int *status); -// -void d_tree_ocp_qp_ipm_get_iter(struct d_tree_ocp_qp_ipm_ws *ws, int *iter); -// -void d_tree_ocp_qp_ipm_get_max_res_stat(struct d_tree_ocp_qp_ipm_ws *ws, double *res_stat); -// -void d_tree_ocp_qp_ipm_get_max_res_eq(struct d_tree_ocp_qp_ipm_ws *ws, double *res_eq); -// -void d_tree_ocp_qp_ipm_get_max_res_ineq(struct d_tree_ocp_qp_ipm_ws *ws, double *res_ineq); -// -void d_tree_ocp_qp_ipm_get_max_res_comp(struct d_tree_ocp_qp_ipm_ws *ws, double *res_comp); -// -void d_tree_ocp_qp_ipm_get_stat(struct d_tree_ocp_qp_ipm_ws *ws, double **stat); -// -void d_tree_ocp_qp_ipm_get_stat_m(struct d_tree_ocp_qp_ipm_ws *ws, int *stat_m); -// -void d_tree_ocp_qp_init_var(struct d_tree_ocp_qp *qp, struct d_tree_ocp_qp_sol *qp_sol, struct d_tree_ocp_qp_ipm_arg *arg, struct d_tree_ocp_qp_ipm_ws *ws); -// -void d_tree_ocp_qp_ipm_abs_step(int kk, struct d_tree_ocp_qp *qp, struct d_tree_ocp_qp_sol *qp_sol, struct d_tree_ocp_qp_ipm_arg *arg, struct d_tree_ocp_qp_ipm_ws *ws); -// -void d_tree_ocp_qp_ipm_delta_step(int kk, struct d_tree_ocp_qp *qp, struct d_tree_ocp_qp_sol *qp_sol, struct d_tree_ocp_qp_ipm_arg *arg, struct d_tree_ocp_qp_ipm_ws *ws); -// -void d_tree_ocp_qp_ipm_solve(struct d_tree_ocp_qp *qp, struct d_tree_ocp_qp_sol *qp_sol, struct d_tree_ocp_qp_ipm_arg *arg, struct d_tree_ocp_qp_ipm_ws *ws); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_D_TREE_OCP_QP_IPM_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qp_kkt.h b/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qp_kkt.h deleted file mode 100644 index 4afd52f..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qp_kkt.h +++ /dev/null @@ -1,52 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifdef __cplusplus -extern "C" { -#endif - - -// -void d_tree_ocp_qp_fact_solve_kkt_unconstr(struct d_tree_ocp_qp *qp, struct d_tree_ocp_qp_sol *qp_sol, struct d_tree_ocp_qp_ipm_arg *arg, struct d_tree_ocp_qp_ipm_ws *ws); -// -void d_tree_ocp_qp_fact_solve_kkt_step(struct d_tree_ocp_qp *qp, struct d_tree_ocp_qp_sol *qp_sol, struct d_tree_ocp_qp_ipm_arg *arg, struct d_tree_ocp_qp_ipm_ws *ws); -// -void d_tree_ocp_qp_fact_lq_solve_kkt_step(struct d_tree_ocp_qp *qp, struct d_tree_ocp_qp_sol *qp_sol, struct d_tree_ocp_qp_ipm_arg *arg, struct d_tree_ocp_qp_ipm_ws *ws); -// -void d_tree_ocp_qp_solve_kkt_step(struct d_tree_ocp_qp *qp, struct d_tree_ocp_qp_sol *qp_sol, struct d_tree_ocp_qp_ipm_arg *arg, struct d_tree_ocp_qp_ipm_ws *ws); - -#ifdef __cplusplus -} /* extern "C" */ -#endif diff --git a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qp_res.h b/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qp_res.h deleted file mode 100644 index fe49908..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qp_res.h +++ /dev/null @@ -1,106 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_TREE_OCP_QP_RES_H_ -#define HPIPM_D_TREE_OCP_QP_RES_H_ - - - -#include -#include - -#include -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct d_tree_ocp_qp_res - { - struct d_tree_ocp_qp_dim *dim; - struct blasfeo_dvec *res_g; // q-residuals - struct blasfeo_dvec *res_b; // b-residuals - struct blasfeo_dvec *res_d; // d-residuals - struct blasfeo_dvec *res_m; // m-residuals - double res_max[4]; // max of residuals - double res_mu; // mu-residual - hpipm_size_t memsize; - }; - - - -struct d_tree_ocp_qp_res_ws - { - struct blasfeo_dvec *tmp_nbgM; // work space of size nbM+ngM - struct blasfeo_dvec *tmp_nsM; // work space of size nsM - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t d_tree_ocp_qp_res_memsize(struct d_tree_ocp_qp_dim *ocp_dim); -// -void d_tree_ocp_qp_res_create(struct d_tree_ocp_qp_dim *ocp_dim, struct d_tree_ocp_qp_res *res, void *mem); -// -hpipm_size_t d_tree_ocp_qp_res_ws_memsize(struct d_tree_ocp_qp_dim *ocp_dim); -// -void d_tree_ocp_qp_res_ws_create(struct d_tree_ocp_qp_dim *ocp_dim, struct d_tree_ocp_qp_res_ws *ws, void *mem); -// -void d_tree_ocp_qp_res_get_all(struct d_tree_ocp_qp_res *res, double **res_r, double **res_q, double **res_ls, double **res_us, double **res_b, double **res_d_lb, double **res_d_ub, double **res_d_lg, double **res_d_ug, double **res_d_ls, double **res_d_us, double **res_m_lb, double **res_m_ub, double **res_m_lg, double **res_m_ug, double **res_m_ls, double **res_m_us); -// -void d_tree_ocp_qp_res_compute(struct d_tree_ocp_qp *qp, struct d_tree_ocp_qp_sol *qp_sol, struct d_tree_ocp_qp_res *res, struct d_tree_ocp_qp_res_ws *ws); -// -void d_tree_ocp_qp_res_compute_lin(struct d_tree_ocp_qp *qp, struct d_tree_ocp_qp_sol *qp_sol, struct d_tree_ocp_qp_sol *qp_step, struct d_tree_ocp_qp_res *res, struct d_tree_ocp_qp_res_ws *ws); -// -void d_tree_ocp_qp_res_compute_inf_norm(struct d_tree_ocp_qp_res *res); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - -#endif // HPIPM_D_TREE_OCP_QP_RES_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qp_sol.h b/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qp_sol.h deleted file mode 100644 index 343d5e8..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qp_sol.h +++ /dev/null @@ -1,100 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_TREE_OCP_QP_SOL_H_ -#define HPIPM_D_TREE_OCP_QP_SOL_H_ - - - -#include -#include - -#include "hpipm_d_tree_ocp_qp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - -struct d_tree_ocp_qp_sol - { - struct d_tree_ocp_qp_dim *dim; - struct blasfeo_dvec *ux; - struct blasfeo_dvec *pi; - struct blasfeo_dvec *lam; - struct blasfeo_dvec *t; - void *misc; - hpipm_size_t memsize; // memory size in bytes - }; - - - -// -hpipm_size_t d_tree_ocp_qp_sol_memsize(struct d_tree_ocp_qp_dim *dim); -// -void d_tree_ocp_qp_sol_create(struct d_tree_ocp_qp_dim *dim, struct d_tree_ocp_qp_sol *qp_sol, void *memory); -// -void d_tree_ocp_qp_sol_get_all(struct d_tree_ocp_qp *qp, struct d_tree_ocp_qp_sol *qp_sol, double **u, double **x, double **ls, double **us, double **pi, double **lam_lb, double **lam_ub, double **lam_lg, double **lam_ug, double **lam_ls, double **lam_us); -// -void d_tree_ocp_qp_sol_get(char *field, int node_edge, struct d_tree_ocp_qp_sol *qp_sol, double *vec); -// -void d_tree_ocp_qp_sol_get_u(int node, struct d_tree_ocp_qp_sol *qp_sol, double *vec); -// -void d_tree_ocp_qp_sol_get_x(int node, struct d_tree_ocp_qp_sol *qp_sol, double *vec); -// -void d_tree_ocp_qp_sol_get_sl(int node, struct d_tree_ocp_qp_sol *qp_sol, double *vec); -// -void d_tree_ocp_qp_sol_get_su(int node, struct d_tree_ocp_qp_sol *qp_sol, double *vec); -// -void d_tree_ocp_qp_sol_get_pi(int edge, struct d_tree_ocp_qp_sol *qp_sol, double *vec); -// -void d_tree_ocp_qp_sol_get_lam_lb(int node, struct d_tree_ocp_qp_sol *qp_sol, double *vec); -// -void d_tree_ocp_qp_sol_get_lam_ub(int node, struct d_tree_ocp_qp_sol *qp_sol, double *vec); -// -void d_tree_ocp_qp_sol_get_lam_lg(int node, struct d_tree_ocp_qp_sol *qp_sol, double *vec); -// -void d_tree_ocp_qp_sol_get_lam_ug(int node, struct d_tree_ocp_qp_sol *qp_sol, double *vec); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_D_TREE_OCP_QP_SOL_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qp_utils.h b/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qp_utils.h deleted file mode 100644 index b689fdc..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_d_tree_ocp_qp_utils.h +++ /dev/null @@ -1,83 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_D_TREE_OCP_QP_UTILS_H_ -#define HPIPM_D_TREE_OCP_QP_UTILS_H_ - - - -#include -#include - -#include "hpipm_d_tree_ocp_qp_dim.h" -#include "hpipm_d_tree_ocp_qp.h" -#include "hpipm_d_tree_ocp_qp_sol.h" -#include "hpipm_d_tree_ocp_qp_ipm.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -// -void d_tree_ocp_qp_dim_print(struct d_tree_ocp_qp_dim *qp_dim); -// -//void d_tree_ocp_qp_dim_codegen(char *file_name, char *mode, struct d_tree_ocp_qp_dim *qp_dim); -// -void d_tree_ocp_qp_print(struct d_tree_ocp_qp_dim *qp_dim, struct d_tree_ocp_qp *qp); -// -//void d_tree_ocp_qp_codegen(char *file_name, char *mode, struct d_tree_ocp_qp_dim *qp_dim, struct d_tree_ocp_qp *qp); -// -void d_tree_ocp_qp_sol_print(struct d_tree_ocp_qp_dim *qp_dim, struct d_tree_ocp_qp_sol *ocp_qp_sol); -// -void d_tree_ocp_qp_ipm_arg_print(struct d_tree_ocp_qp_dim *qp_dim, struct d_tree_ocp_qp_ipm_arg *arg); -// -//void d_tree_ocp_qp_ipm_arg_codegen(char *file_name, char *mode, struct d_tree_ocp_qp_dim *qp_dim, struct d_tree_ocp_qp_ipm_arg *arg); -// -void d_tree_ocp_qp_res_print(struct d_tree_ocp_qp_dim *qp_dim, struct d_tree_ocp_qp_res *ocp_qp_res); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_D_TREE_OCP_QP_UTILS_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_m_dense_qp.h b/third_party/acados/include/hpipm/include/hpipm_m_dense_qp.h deleted file mode 100644 index 8bc1010..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_m_dense_qp.h +++ /dev/null @@ -1,68 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - - -#ifndef HPIPM_M_DENSE_QP_H_ -#define HPIPM_M_DENSE_QP_H_ - - - -#include -#include - -#include "hpipm_d_dense_qp.h" -#include "hpipm_s_dense_qp.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -void cvt_d2s_dense_qp(struct d_dense_qp *qpd, struct s_dense_qp *qps); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_M_DENSE_QP_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_m_dense_qp_dim.h b/third_party/acados/include/hpipm/include/hpipm_m_dense_qp_dim.h deleted file mode 100644 index 4610321..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_m_dense_qp_dim.h +++ /dev/null @@ -1,68 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - - -#ifndef HPIPM_M_DENSE_QP_DIM_H_ -#define HPIPM_M_DENSE_QP_DIM_H_ - - - -#include -#include - -#include "hpipm_d_dense_qp_dim.h" -#include "hpipm_s_dense_qp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -void cvt_d2s_dense_qp_dim(struct d_dense_qp_dim *qpd, struct s_dense_qp_dim *qps); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_M_DENSE_QP_DIM_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_m_ocp_qp.h b/third_party/acados/include/hpipm/include/hpipm_m_ocp_qp.h deleted file mode 100644 index 95c3dad..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_m_ocp_qp.h +++ /dev/null @@ -1,49 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#include -#include - -#ifdef __cplusplus -extern "C" { -#endif - -void m_cvt_d_ocp_qp_to_s_ocp_qp(struct d_ocp_qp *d_qp, struct s_ocp_qp *s_qp); - -#ifdef __cplusplus -} /* extern "C" */ -#endif diff --git a/third_party/acados/include/hpipm/include/hpipm_m_ocp_qp_ipm_hard.h b/third_party/acados/include/hpipm/include/hpipm_m_ocp_qp_ipm_hard.h deleted file mode 100644 index 1c44ace..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_m_ocp_qp_ipm_hard.h +++ /dev/null @@ -1,115 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#include -#include - -#ifdef __cplusplus -extern "C" { -#endif - - -struct m_ipm_hard_ocp_qp_workspace - { - struct d_ipm_hard_core_qp_workspace *core_workspace; - struct blasfeo_dvec *dux; - struct blasfeo_dvec *dpi; - struct blasfeo_dvec *dt_lb; - struct blasfeo_dvec *dt_lg; - struct blasfeo_svec *sdux; // XXX - struct blasfeo_svec *sdpi; // XXX - struct blasfeo_dvec *res_g; // q-residuals - struct blasfeo_dvec *res_b; // b-residuals - struct blasfeo_dvec *res_d; // d-residuals XXX remove ??? - struct blasfeo_dvec *res_d_lb; // d-residuals - struct blasfeo_dvec *res_d_ub; // d-residuals - struct blasfeo_dvec *res_d_lg; // d-residuals - struct blasfeo_dvec *res_d_ug; // d-residuals - struct blasfeo_dvec *res_m; // m-residuals - struct blasfeo_dvec *res_m_lb; // m-residuals - struct blasfeo_dvec *res_m_ub; // m-residuals - struct blasfeo_dvec *res_m_lg; // m-residuals - struct blasfeo_dvec *res_m_ug; // m-residuals - struct blasfeo_svec *sres_g; // q-residuals // XXX - struct blasfeo_svec *sres_b; // b-residuals // XXX - struct blasfeo_dvec *Qx_lb; // hessian update - struct blasfeo_dvec *Qx_lg; // hessian update - struct blasfeo_dvec *qx_lb; // gradient update - struct blasfeo_dvec *qx_lg; // gradient update - struct blasfeo_svec *sQx_lb; // hessian update // XXX - struct blasfeo_svec *sQx_lg; // hessian update // XXX - struct blasfeo_svec *sqx_lb; // gradient update // XXX - struct blasfeo_svec *sqx_lg; // gradient update // XXX - struct blasfeo_dvec *tmp_nbM; // work space of size nbM - struct blasfeo_svec *tmp_nxM; // work space of size nxM // XXX - struct blasfeo_dvec *tmp_ngM; // work space of size ngM - struct blasfeo_svec *Pb; // Pb // XXX - struct blasfeo_smat *L; // XXX - struct blasfeo_smat *AL; // XXX - struct blasfeo_svec *sSx; // scaling - struct blasfeo_svec *sSi; // scaling inverted - double *stat; // convergence statistics - double res_mu; // mu-residual - int iter; // iteration number - int compute_Pb; - int scale; - }; - - - -struct m_ipm_hard_ocp_qp_arg - { - double alpha_min; // exit cond on step length - double mu_max; // exit cond on duality measure - double mu0; // initial value for duality measure - int iter_max; // exit cond in iter number - }; - - - -// -hpipm_size_t m_memsize_ipm_hard_ocp_qp(struct d_ocp_qp *d_qp, struct s_ocp_qp *s_qp, struct m_ipm_hard_ocp_qp_arg *arg); -// -void m_create_ipm_hard_ocp_qp(struct d_ocp_qp *d_qp, struct s_ocp_qp *s_qp, struct m_ipm_hard_ocp_qp_arg *arg, struct m_ipm_hard_ocp_qp_workspace *ws, void *mem); -// -void m_solve_ipm_hard_ocp_qp(struct d_ocp_qp *d_qp, struct s_ocp_qp *s_qp, struct d_ocp_qp_sol *qp_sol, struct m_ipm_hard_ocp_qp_workspace *ws); -// -void m_solve_ipm2_hard_ocp_qp(struct d_ocp_qp *d_qp, struct s_ocp_qp *s_qp, struct d_ocp_qp_sol *qp_sol, struct m_ipm_hard_ocp_qp_workspace *ws); - -#ifdef __cplusplus -} /* extern "C" */ -#endif diff --git a/third_party/acados/include/hpipm/include/hpipm_m_ocp_qp_kkt.h b/third_party/acados/include/hpipm/include/hpipm_m_ocp_qp_kkt.h deleted file mode 100644 index 032fe95..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_m_ocp_qp_kkt.h +++ /dev/null @@ -1,45 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifdef __cplusplus -extern "C" { -#endif - -void m_fact_solve_kkt_step_hard_ocp_qp(struct d_ocp_qp *d_qp, struct s_ocp_qp *s_qp, struct m_ipm_hard_ocp_qp_workspace *ws); -void m_solve_kkt_step_hard_ocp_qp(struct d_ocp_qp *d_qp, struct s_ocp_qp *s_qp, struct m_ipm_hard_ocp_qp_workspace *ws); - -#ifdef __cplusplus -} /* extern "C" */ -#endif diff --git a/third_party/acados/include/hpipm/include/hpipm_s_cast_qcqp.h b/third_party/acados/include/hpipm/include/hpipm_s_cast_qcqp.h deleted file mode 100644 index ba01ecb..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_cast_qcqp.h +++ /dev/null @@ -1,72 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_S_CAST_QCQP_H_ -#define HPIPM_S_CAST_QCQP_H_ - - - -#include -#include - -#include "hpipm_s_dense_qcqp.h" -#include "hpipm_s_dense_qcqp_sol.h" -#include "hpipm_s_ocp_qcqp.h" -#include "hpipm_s_ocp_qcqp_dim.h" -#include "hpipm_s_ocp_qcqp_sol.h" - -#ifdef __cplusplus -extern "C" { -#endif - - - -// -void s_cast_qcqp_compute_dim(struct s_ocp_qcqp_dim *ocp_dim, struct s_dense_qcqp_dim *dense_dim); -// -void s_cast_qcqp_cond(struct s_ocp_qcqp *ocp_qp, struct s_dense_qcqp *dense_qp); - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_S_CAST_QCQP_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_cond.h b/third_party/acados/include/hpipm/include/hpipm_s_cond.h deleted file mode 100644 index 3011679..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_cond.h +++ /dev/null @@ -1,137 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_S_COND_H_ -#define HPIPM_S_COND_H_ - - - -#include -#include - -#include "hpipm_s_dense_qp.h" -#include "hpipm_s_dense_qp_sol.h" -#include "hpipm_s_ocp_qp.h" -#include "hpipm_s_ocp_qp_dim.h" -#include "hpipm_s_ocp_qp_sol.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_cond_qp_arg - { - int cond_last_stage; // condense last stage - int cond_alg; // condensing algorithm: 0 N2-nx3, 1 N3-nx2 - int comp_prim_sol; // primal solution (v) - int comp_dual_sol_eq; // dual solution equality constr (pi) - int comp_dual_sol_ineq; // dual solution inequality constr (lam t) - int square_root_alg; // square root algorithm (faster but requires RSQ>0) - hpipm_size_t memsize; - }; - - - -struct s_cond_qp_ws - { - struct blasfeo_smat *Gamma; - struct blasfeo_smat *GammaQ; - struct blasfeo_smat *L; - struct blasfeo_smat *Lx; - struct blasfeo_smat *AL; - struct blasfeo_svec *Gammab; - struct blasfeo_svec *l; - struct blasfeo_svec *tmp_nbgM; - struct blasfeo_svec *tmp_nuxM; - int bs; // block size - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_cond_qp_arg_memsize(); -// -void s_cond_qp_arg_create(struct s_cond_qp_arg *cond_arg, void *mem); -// -void s_cond_qp_arg_set_default(struct s_cond_qp_arg *cond_arg); -// condensing algorithm: 0 N2-nx3, 1 N3-nx2 -void s_cond_qp_arg_set_cond_alg(int cond_alg, struct s_cond_qp_arg *cond_arg); -// set riccati-like algorithm: 0 classical, 1 square-root -void s_cond_qp_arg_set_ric_alg(int ric_alg, struct s_cond_qp_arg *cond_arg); -// condense last stage: 0 last stage disregarded, 1 last stage condensed too -void s_cond_qp_arg_set_cond_last_stage(int cond_last_stage, struct s_cond_qp_arg *cond_arg); -// -void s_cond_qp_arg_set_comp_prim_sol(int value, struct s_cond_qp_arg *cond_arg); -// -void s_cond_qp_arg_set_comp_dual_sol_eq(int value, struct s_cond_qp_arg *cond_arg); -// -void s_cond_qp_arg_set_comp_dual_sol_ineq(int value, struct s_cond_qp_arg *cond_arg); - -// -void s_cond_qp_compute_dim(struct s_ocp_qp_dim *ocp_dim, struct s_dense_qp_dim *dense_dim); -// -hpipm_size_t s_cond_qp_ws_memsize(struct s_ocp_qp_dim *ocp_dim, struct s_cond_qp_arg *cond_arg); -// -void s_cond_qp_ws_create(struct s_ocp_qp_dim *ocp_dim, struct s_cond_qp_arg *cond_arg, struct s_cond_qp_ws *cond_ws, void *mem); -// -void s_cond_qp_cond(struct s_ocp_qp *ocp_qp, struct s_dense_qp *dense_qp, struct s_cond_qp_arg *cond_arg, struct s_cond_qp_ws *cond_ws); -// -void s_cond_qp_cond_lhs(struct s_ocp_qp *ocp_qp, struct s_dense_qp *dense_qp, struct s_cond_qp_arg *cond_arg, struct s_cond_qp_ws *cond_ws); -// -void s_cond_qp_cond_rhs(struct s_ocp_qp *ocp_qp, struct s_dense_qp *dense_qp, struct s_cond_qp_arg *cond_arg, struct s_cond_qp_ws *cond_ws); -// -void s_cond_qp_expand_sol(struct s_ocp_qp *ocp_qp, struct s_dense_qp_sol *dense_qp_sol, struct s_ocp_qp_sol *ocp_qp_sol, struct s_cond_qp_arg *cond_arg, struct s_cond_qp_ws *cond_ws); -// TODO remove -void s_cond_qp_expand_primal_sol(struct s_ocp_qp *ocp_qp, struct s_dense_qp_sol *dense_qp_sol, struct s_ocp_qp_sol *ocp_qp_sol, struct s_cond_qp_arg *cond_arg, struct s_cond_qp_ws *cond_ws); - -// -void s_cond_qp_update(int *idxc, struct s_ocp_qp *ocp_qp, struct s_dense_qp *dense_qp, struct s_cond_qp_arg *cond_arg, struct s_cond_qp_ws *cond_ws); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_S_COND_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_s_cond_aux.h b/third_party/acados/include/hpipm/include/hpipm_s_cond_aux.h deleted file mode 100644 index 003472a..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_cond_aux.h +++ /dev/null @@ -1,92 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_S_COND_AUX_H_ -#define HPIPM_S_COND_AUX_H_ - - - -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -// -void s_cond_BAbt(struct s_ocp_qp *ocp_qp, struct blasfeo_smat *BAbt2, struct blasfeo_svec *b2, struct s_cond_qp_arg *cond_arg, struct s_cond_qp_ws *cond_ws); -// -void s_cond_BAt(struct s_ocp_qp *ocp_qp, struct blasfeo_smat *BAbt2, struct s_cond_qp_arg *cond_arg, struct s_cond_qp_ws *cond_ws); -// -void s_cond_b(struct s_ocp_qp *ocp_qp, struct blasfeo_svec *b2, struct s_cond_qp_arg *cond_arg, struct s_cond_qp_ws *cond_ws); -// -void s_cond_RSQrq(struct s_ocp_qp *ocp_qp, struct blasfeo_smat *RSQrq2, struct blasfeo_svec *rq2, struct s_cond_qp_arg *cond_arg, struct s_cond_qp_ws *cond_ws); -// -void s_cond_RSQ(struct s_ocp_qp *ocp_qp, struct blasfeo_smat *RSQrq2, struct s_cond_qp_arg *cond_arg, struct s_cond_qp_ws *cond_ws); -// -void s_cond_rq(struct s_ocp_qp *ocp_qp, struct blasfeo_svec *rq2, struct s_cond_qp_arg *cond_arg, struct s_cond_qp_ws *cond_ws); -// -void s_cond_DCtd(struct s_ocp_qp *ocp_qp, int *idxb2, struct blasfeo_smat *DCt2, struct blasfeo_svec *d2, struct blasfeo_svec *d_mask2, int *idxs_rev2, struct blasfeo_svec *Z2, struct blasfeo_svec *z2, struct s_cond_qp_arg *cond_arg, struct s_cond_qp_ws *cond_ws); -// -void s_cond_DCt(struct s_ocp_qp *ocp_qp, int *idxb2, struct blasfeo_smat *DCt2, int *idxs_rev2, struct blasfeo_svec *Z2, struct s_cond_qp_arg *cond_arg, struct s_cond_qp_ws *cond_ws); -// -void s_cond_d(struct s_ocp_qp *ocp_qp, struct blasfeo_svec *d2, struct blasfeo_svec *d_mask2, struct blasfeo_svec *z2, struct s_cond_qp_arg *cond_arg, struct s_cond_qp_ws *cond_ws); -// -void s_expand_sol(struct s_ocp_qp *ocp_qp, struct s_dense_qp_sol *dense_qp_sol, struct s_ocp_qp_sol *ocp_qp_sol, struct s_cond_qp_arg *cond_arg, struct s_cond_qp_ws *cond_ws); -// -void s_expand_primal_sol(struct s_ocp_qp *ocp_qp, struct s_dense_qp_sol *dense_qp_sol, struct s_ocp_qp_sol *ocp_qp_sol, struct s_cond_qp_arg *cond_arg, struct s_cond_qp_ws *cond_ws); - -// -void s_update_cond_BAbt(int *idxc, struct s_ocp_qp *ocp_qp, struct blasfeo_smat *BAbt2, struct blasfeo_svec *b2, struct s_cond_qp_arg *cond_arg, struct s_cond_qp_ws *cond_ws); -// -void s_update_cond_RSQrq_N2nx3(int *idxc, struct s_ocp_qp *ocp_qp, struct blasfeo_smat *RSQrq2, struct blasfeo_svec *rq2, struct s_cond_qp_arg *cond_arg, struct s_cond_qp_ws *cond_ws); -// -void s_update_cond_DCtd(int *idxc, struct s_ocp_qp *ocp_qp, int *idxb2, struct blasfeo_smat *DCt2, struct blasfeo_svec *d2, int *idxs2, struct blasfeo_svec *Z2, struct blasfeo_svec *z2, struct s_cond_qp_arg *cond_arg, struct s_cond_qp_ws *cond_ws); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_S_COND_AUX_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_s_cond_qcqp.h b/third_party/acados/include/hpipm/include/hpipm_s_cond_qcqp.h deleted file mode 100644 index c36678a..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_cond_qcqp.h +++ /dev/null @@ -1,130 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_S_COND_QCQP_H_ -#define HPIPM_S_COND_QCQP_H_ - - - -#include -#include - -#include "hpipm_s_dense_qcqp.h" -#include "hpipm_s_dense_qcqp_sol.h" -#include "hpipm_s_ocp_qcqp.h" -#include "hpipm_s_ocp_qcqp_dim.h" -#include "hpipm_s_ocp_qcqp_sol.h" - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_cond_qcqp_arg - { - struct s_cond_qp_arg *qp_arg; - int cond_last_stage; // condense last stage -// int cond_variant; // TODO - int comp_prim_sol; // primal solution (v) - int comp_dual_sol_eq; // dual solution equality constr (pi) - int comp_dual_sol_ineq; // dual solution equality constr (lam t) - int square_root_alg; // square root algorithm (faster but requires RSQ>0) - hpipm_size_t memsize; - }; - - - -struct s_cond_qcqp_ws - { - struct s_cond_qp_ws *qp_ws; - struct blasfeo_smat *hess_array; // TODO remove - struct blasfeo_smat *zero_hess; // TODO remove - struct blasfeo_svec *zero_grad; // TODO remove - struct blasfeo_svec *grad_array; // TODO remove - struct blasfeo_svec *tmp_nvc; - struct blasfeo_svec *tmp_nuxM; - struct blasfeo_smat *GammaQ; - struct blasfeo_smat *tmp_DCt; - struct blasfeo_smat *tmp_nuM_nxM; -// struct blasfeo_svec *d_qp; -// struct blasfeo_svec *d_mask_qp; - hpipm_size_t memsize; - }; - - -// -hpipm_size_t s_cond_qcqp_arg_memsize(); -// -void s_cond_qcqp_arg_create(struct s_cond_qcqp_arg *cond_arg, void *mem); -// -void s_cond_qcqp_arg_set_default(struct s_cond_qcqp_arg *cond_arg); -// set riccati-like algorithm: 0 classical, 1 square-root -void s_cond_qcqp_arg_set_ric_alg(int ric_alg, struct s_cond_qcqp_arg *cond_arg); -// condense last stage: 0 last stage disregarded, 1 last stage condensed too -void s_cond_qcqp_arg_set_cond_last_stage(int cond_last_stage, struct s_cond_qcqp_arg *cond_arg); - -// -void s_cond_qcqp_compute_dim(struct s_ocp_qcqp_dim *ocp_dim, struct s_dense_qcqp_dim *dense_dim); -// -hpipm_size_t s_cond_qcqp_ws_memsize(struct s_ocp_qcqp_dim *ocp_dim, struct s_cond_qcqp_arg *cond_arg); -// -void s_cond_qcqp_ws_create(struct s_ocp_qcqp_dim *ocp_dim, struct s_cond_qcqp_arg *cond_arg, struct s_cond_qcqp_ws *cond_ws, void *mem); -// -void s_cond_qcqp_qc(struct s_ocp_qcqp *ocp_qp, struct blasfeo_smat *Hq2, int *Hq_nzero2, struct blasfeo_smat *Ct2, struct blasfeo_svec *d2, struct s_cond_qcqp_arg *cond_arg, struct s_cond_qcqp_ws *cond_ws); -// -void s_cond_qcqp_qc_lhs(struct s_ocp_qcqp *ocp_qp, struct blasfeo_smat *Hq2, int *Hq_nzero2, struct blasfeo_smat *Ct2, struct s_cond_qcqp_arg *cond_arg, struct s_cond_qcqp_ws *cond_ws); -// -void s_cond_qcqp_qc_rhs(struct s_ocp_qcqp *ocp_qp, struct blasfeo_svec *d2, struct s_cond_qcqp_arg *cond_arg, struct s_cond_qcqp_ws *cond_ws); -// -void s_cond_qcqp_cond(struct s_ocp_qcqp *ocp_qp, struct s_dense_qcqp *dense_qp, struct s_cond_qcqp_arg *cond_arg, struct s_cond_qcqp_ws *cond_ws); -// -void s_cond_qcqp_cond_rhs(struct s_ocp_qcqp *ocp_qp, struct s_dense_qcqp *dense_qp, struct s_cond_qcqp_arg *cond_arg, struct s_cond_qcqp_ws *cond_ws); -// -void s_cond_qcqp_cond_lhs(struct s_ocp_qcqp *ocp_qp, struct s_dense_qcqp *dense_qp, struct s_cond_qcqp_arg *cond_arg, struct s_cond_qcqp_ws *cond_ws); -// -void s_cond_qcqp_expand_sol(struct s_ocp_qcqp *ocp_qp, struct s_dense_qcqp_sol *dense_qp_sol, struct s_ocp_qcqp_sol *ocp_qp_sol, struct s_cond_qcqp_arg *cond_arg, struct s_cond_qcqp_ws *cond_ws); - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_S_COND_QCQP_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_core_qp_ipm.h b/third_party/acados/include/hpipm/include/hpipm_s_core_qp_ipm.h deleted file mode 100644 index 480392c..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_core_qp_ipm.h +++ /dev/null @@ -1,101 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_CORE_QP_IPM_ -#define HPIPM_S_CORE_QP_IPM_ - -#include "hpipm_common.h" - -#ifdef __cplusplus -extern "C" { -#endif - -struct s_core_qp_ipm_workspace - { - float *v; // primal variables - float *pi; // equality constraints multipliers - float *lam; // inequality constraints multipliers - float *t; // inequality constraints slacks - float *t_inv; // inverse of t - float *v_bkp; // backup of primal variables - float *pi_bkp; // backup of equality constraints multipliers - float *lam_bkp; // backup of inequality constraints multipliers - float *t_bkp; // backup of inequality constraints slacks - float *dv; // step in v - float *dpi; // step in pi - float *dlam; // step in lam - float *dt; // step in t - float *res_g; // q-residuals - float *res_b; // b-residuals - float *res_d; // d-residuals - float *res_m; // m-residuals - float *res_m_bkp; // m-residuals - float *Gamma; // Hessian update - float *gamma; // gradient update - float alpha_prim; // step length - float alpha_dual; // step length - float alpha; // step length - float sigma; // centering XXX - float mu; // duality measuere - float mu_aff; // affine duality measuere - float nc_inv; // 1.0/nc, where nc is the total number of constraints - float nc_mask_inv; // 1.0/nc_mask - float lam_min; // min value in lam vector - float t_min; // min value in t vector - float t_min_inv; // inverse of min value in t vector - float tau_min; // min value of barrier parameter - int nv; // number of primal variables - int ne; // number of equality constraints - int nc; // (twice the) number of (two-sided) inequality constraints - int nc_mask; // total number of ineq constr after masking - int split_step; // use different step for primal and dual variables - int t_lam_min; // clip t and lam also in solution, or only in Gamma computation - hpipm_size_t memsize; // memory size (in bytes) of workspace - }; - - - -// -hpipm_size_t s_memsize_core_qp_ipm(int nv, int ne, int nc); -// -void s_create_core_qp_ipm(int nv, int ne, int nc, struct s_core_qp_ipm_workspace *workspace, void *mem); -// -void s_core_qp_ipm(struct s_core_qp_ipm_workspace *workspace); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // HPIPM_S_CORE_QP_IPM_ diff --git a/third_party/acados/include/hpipm/include/hpipm_s_core_qp_ipm_aux.h b/third_party/acados/include/hpipm/include/hpipm_s_core_qp_ipm_aux.h deleted file mode 100644 index 1ac3d7e..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_core_qp_ipm_aux.h +++ /dev/null @@ -1,68 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_CORE_QP_IPM_AUX_ -#define HPIPM_S_CORE_QP_IPM_AUX_ - -#ifdef __cplusplus -extern "C" { -#endif - -// -void s_compute_Gamma_gamma_qp(float *res_d, float *res_m, struct s_core_qp_ipm_workspace *rws); -// -void s_compute_gamma_qp(float *res_d, float *res_m, struct s_core_qp_ipm_workspace *rws); -// -void s_compute_lam_t_qp(float *res_d, float *res_m, float *dlam, float *dt, struct s_core_qp_ipm_workspace *rws); -// -void s_compute_alpha_qp(struct s_core_qp_ipm_workspace *rws); -// -void s_update_var_qp(struct s_core_qp_ipm_workspace *rws); -// -void s_compute_mu_aff_qp(struct s_core_qp_ipm_workspace *rws); -// -void s_backup_res_m(struct s_core_qp_ipm_workspace *rws); -// -void s_compute_centering_correction_qp(struct s_core_qp_ipm_workspace *rws); -// -void s_compute_centering_qp(struct s_core_qp_ipm_workspace *rws); -// -void s_compute_tau_min_qp(struct s_core_qp_ipm_workspace *rws); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // HPIPM_S_CORE_QP_IPM_AUX_ diff --git a/third_party/acados/include/hpipm/include/hpipm_s_dense_qcqp.h b/third_party/acados/include/hpipm/include/hpipm_s_dense_qcqp.h deleted file mode 100644 index d03c065..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_dense_qcqp.h +++ /dev/null @@ -1,200 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_S_DENSE_QCQP_H_ -#define HPIPM_S_DENSE_QCQP_H_ - - - -#include -#include - -#include "hpipm_s_dense_qcqp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_dense_qcqp - { - struct s_dense_qcqp_dim *dim; - struct blasfeo_smat *Hv; // hessian of cost & vector work space - struct blasfeo_smat *A; // equality constraint matrix - struct blasfeo_smat *Ct; // inequality constraints matrix - struct blasfeo_smat *Hq; // hessians of quadratic constraints - struct blasfeo_svec *gz; // gradient of cost & gradient of slacks - struct blasfeo_svec *b; // equality constraint vector - struct blasfeo_svec *d; // inequality constraints vector - struct blasfeo_svec *d_mask; // inequality constraints mask vector - struct blasfeo_svec *m; // rhs of complementarity condition - struct blasfeo_svec *Z; // (diagonal) hessian of slacks - int *idxb; // indices of box constrained variables within [u; x] - int *idxs_rev; // index of soft constraints (reverse storage) - int *Hq_nzero; // for each int, the last 3 bits ...abc, {a,b,c}=0 => {R,S,Q}=0 - hpipm_size_t memsize; // memory size in bytes - }; - - - -// -hpipm_size_t s_dense_qcqp_memsize(struct s_dense_qcqp_dim *dim); -// -void s_dense_qcqp_create(struct s_dense_qcqp_dim *dim, struct s_dense_qcqp *qp, void *memory); - -// -void s_dense_qcqp_set(char *field, void *value, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_H(float *H, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_g(float *g, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_A(float *A, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_b(float *b, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_idxb(int *idxb, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_lb(float *lb, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_lb_mask(float *lb, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_ub(float *ub, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_ub_mask(float *ub, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_C(float *C, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_lg(float *lg, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_lg_mask(float *lg, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_ug(float *ug, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_ug_mask(float *ug, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_Hq(float *Hq, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_gq(float *gq, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_uq(float *uq, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_uq_mask(float *uq, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_idxs(int *idxs, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_idxs_rev(int *idxs_rev, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_Zl(float *Zl, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_Zu(float *Zu, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_zl(float *zl, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_zu(float *zu, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_ls(float *ls, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_ls_mask(float *ls, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_us(float *us, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_set_us_mask(float *us, struct s_dense_qcqp *qp); - -// getters (COLMAJ) - -void s_dense_qcqp_get_H(struct s_dense_qcqp *qp, float *H); -// -void s_dense_qcqp_get_g(struct s_dense_qcqp *qp, float *g); -// -void s_dense_qcqp_get_A(struct s_dense_qcqp *qp, float *A); -// -void s_dense_qcqp_get_b(struct s_dense_qcqp *qp, float *b); -// -void s_dense_qcqp_get_idxb(struct s_dense_qcqp *qp, int *idxb); -// -void s_dense_qcqp_get_lb(struct s_dense_qcqp *qp, float *lb); -// -void s_dense_qcqp_get_lb_mask(struct s_dense_qcqp *qp, float *lb); -// -void s_dense_qcqp_get_ub(struct s_dense_qcqp *qp, float *ub); -// -void s_dense_qcqp_get_ub_mask(struct s_dense_qcqp *qp, float *ub); -// -void s_dense_qcqp_get_C(struct s_dense_qcqp *qp, float *C); -// -void s_dense_qcqp_get_lg(struct s_dense_qcqp *qp, float *lg); -// -void s_dense_qcqp_get_lg_mask(struct s_dense_qcqp *qp, float *lg); -// -void s_dense_qcqp_get_ug(struct s_dense_qcqp *qp, float *ug); -// -void s_dense_qcqp_get_ug_mask(struct s_dense_qcqp *qp, float *ug); -// -void s_dense_qcqp_get_idxs(struct s_dense_qcqp *qp, int *idxs); -// -void s_dense_qcqp_get_idxs_rev(struct s_dense_qcqp *qp, int *idxs_rev); -// -void s_dense_qcqp_get_Zl(struct s_dense_qcqp *qp, float *Zl); -// -void s_dense_qcqp_get_Zu(struct s_dense_qcqp *qp, float *Zu); -// -void s_dense_qcqp_get_zl(struct s_dense_qcqp *qp, float *zl); -// -void s_dense_qcqp_get_zu(struct s_dense_qcqp *qp, float *zu); -// -void s_dense_qcqp_get_ls(struct s_dense_qcqp *qp, float *ls); -// -void s_dense_qcqp_get_ls_mask(struct s_dense_qcqp *qp, float *ls); -// -void s_dense_qcqp_get_us(struct s_dense_qcqp *qp, float *us); -// -void s_dense_qcqp_get_us_mask(struct s_dense_qcqp *qp, float *us); - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_S_DENSE_QCQP_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_dense_qcqp_dim.h b/third_party/acados/include/hpipm/include/hpipm_s_dense_qcqp_dim.h deleted file mode 100644 index 04908c2..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_dense_qcqp_dim.h +++ /dev/null @@ -1,99 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_DENSE_QCQP_DIM_H_ -#define HPIPM_S_DENSE_QCQP_DIM_H_ - -#include "hpipm_common.h" - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_dense_qcqp_dim - { - struct s_dense_qp_dim *qp_dim; // dim of qp approximation - int nv; // number of variables - int ne; // number of equality constraints - int nb; // number of box constraints - int ng; // number of general constraints - int nq; // number of quadratic constraints - int nsb; // number of softened box constraints - int nsg; // number of softened general constraints - int nsq; // number of softened quadratic constraints - int ns; // number of softened constraints (nsb+nsg+nsq) TODO number of slacks - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_dense_qcqp_dim_memsize(); -// -void s_dense_qcqp_dim_create(struct s_dense_qcqp_dim *dim, void *memory); -// -void s_dense_qcqp_dim_set(char *fiels_name, int value, struct s_dense_qcqp_dim *dim); -// -void s_dense_qcqp_dim_set_nv(int value, struct s_dense_qcqp_dim *dim); -// -void s_dense_qcqp_dim_set_ne(int value, struct s_dense_qcqp_dim *dim); -// -void s_dense_qcqp_dim_set_nb(int value, struct s_dense_qcqp_dim *dim); -// -void s_dense_qcqp_dim_set_ng(int value, struct s_dense_qcqp_dim *dim); -// -void s_dense_qcqp_dim_set_nq(int value, struct s_dense_qcqp_dim *dim); -// -void s_dense_qcqp_dim_set_nsb(int value, struct s_dense_qcqp_dim *dim); -// -void s_dense_qcqp_dim_set_nsg(int value, struct s_dense_qcqp_dim *dim); -// -void s_dense_qcqp_dim_set_nsq(int value, struct s_dense_qcqp_dim *dim); -// -void s_dense_qcqp_dim_set_ns(int value, struct s_dense_qcqp_dim *dim); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_S_DENSE_QCQP_DIM_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_dense_qcqp_ipm.h b/third_party/acados/include/hpipm/include/hpipm_s_dense_qcqp_ipm.h deleted file mode 100644 index 8f85768..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_dense_qcqp_ipm.h +++ /dev/null @@ -1,204 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_S_DENSE_QCQP_IPM_H_ -#define HPIPM_S_DENSE_QCQP_IPM_H_ - - - -#include -#include - -#include -#include -#include -#include -#include - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_dense_qcqp_ipm_arg - { - struct s_dense_qp_ipm_arg *qp_arg; - float mu0; // initial value for duality measure - float alpha_min; // exit cond on step length - float res_g_max; // exit cond on inf norm of residuals - float res_b_max; // exit cond on inf norm of residuals - float res_d_max; // exit cond on inf norm of residuals - float res_m_max; // exit cond on inf norm of residuals - float reg_prim; // reg of primal hessian - float reg_dual; // reg of dual hessian - float lam_min; // min value in lam vector - float t_min; // min value in t vector - int iter_max; // exit cond in iter number - int stat_max; // iterations saved in stat - int pred_corr; // Mehrotra's predictor-corrector IPM algirthm - int cond_pred_corr; // conditional Mehrotra's predictor-corrector - int scale; // scale hessian - int itref_pred_max; // max number of iterative refinement steps for predictor step - int itref_corr_max; // max number of iterative refinement steps for corrector step - int warm_start; // 0 no warm start, 1 warm start primal sol, 2 warm start primal and dual sol - int lq_fact; // 0 syrk+potrf, 1 mix, 2 lq - int abs_form; // absolute IPM formulation - int comp_res_exit; // compute residuals on exit (only for abs_form==1) - int comp_res_pred; // compute residuals of prediction - int split_step; // use different step for primal and dual variables - int t_lam_min; // clip t and lam: 0 no, 1 in Gamma computation, 2 in solution - int mode; - hpipm_size_t memsize; - }; - - - -struct s_dense_qcqp_ipm_ws - { -// float qp_res[4]; // infinity norm of residuals - struct s_dense_qp_ipm_ws *qp_ws; - struct s_dense_qp *qp; - struct s_dense_qp_sol *qp_sol; - struct s_dense_qcqp_res_ws *qcqp_res_ws; - struct s_dense_qcqp_res *qcqp_res; - struct blasfeo_svec *tmp_nv; -// float *stat; // convergence statistics -// void *lq_work0; -// void *lq_work1; - int iter; // iteration number -// int stat_max; // iterations saved in stat -// int stat_m; // numer of recorded stat per ipm iter -// int scale; -// int use_hess_fact; - int status; - hpipm_size_t memsize; // memory size (in bytes) of workspace - }; - - - -// -hpipm_size_t s_dense_qcqp_ipm_arg_memsize(struct s_dense_qcqp_dim *dim); -// -void s_dense_qcqp_ipm_arg_create(struct s_dense_qcqp_dim *dim, struct s_dense_qcqp_ipm_arg *arg, void *mem); -// -void s_dense_qcqp_ipm_arg_set_default(enum hpipm_mode mode, struct s_dense_qcqp_ipm_arg *arg); -// -void s_dense_qcqp_ipm_arg_set(char *field, void *value, struct s_dense_qcqp_ipm_arg *arg); -// -void s_dense_qcqp_ipm_arg_set_iter_max(int *iter_max, struct s_dense_qcqp_ipm_arg *arg); -// -void s_dense_qcqp_ipm_arg_set_alpha_min(float *alpha_min, struct s_dense_qcqp_ipm_arg *arg); -// -void s_dense_qcqp_ipm_arg_set_mu0(float *mu0, struct s_dense_qcqp_ipm_arg *arg); -// -void s_dense_qcqp_ipm_arg_set_tol_stat(float *tol_stat, struct s_dense_qcqp_ipm_arg *arg); -// -void s_dense_qcqp_ipm_arg_set_tol_eq(float *tol_eq, struct s_dense_qcqp_ipm_arg *arg); -// -void s_dense_qcqp_ipm_arg_set_tol_ineq(float *tol_ineq, struct s_dense_qcqp_ipm_arg *arg); -// -void s_dense_qcqp_ipm_arg_set_tol_comp(float *tol_comp, struct s_dense_qcqp_ipm_arg *arg); -// -void s_dense_qcqp_ipm_arg_set_reg_prim(float *reg, struct s_dense_qcqp_ipm_arg *arg); -// -void s_dense_qcqp_ipm_arg_set_reg_dual(float *reg, struct s_dense_qcqp_ipm_arg *arg); -// -void s_dense_qcqp_ipm_arg_set_warm_start(int *warm_start, struct s_dense_qcqp_ipm_arg *arg); -// -void s_dense_qcqp_ipm_arg_set_pred_corr(int *pred_corr, struct s_dense_qcqp_ipm_arg *arg); -// -void s_dense_qcqp_ipm_arg_set_cond_pred_corr(int *cond_pred_corr, struct s_dense_qcqp_ipm_arg *arg); -// -void s_dense_qcqp_ipm_arg_set_comp_res_pred(int *comp_res_pred, struct s_dense_qcqp_ipm_arg *arg); -// -void s_dense_qcqp_ipm_arg_set_comp_res_exit(int *comp_res_exit, struct s_dense_qcqp_ipm_arg *arg); -// -void s_dense_qcqp_ipm_arg_set_lam_min(float *value, struct s_dense_qcqp_ipm_arg *arg); -// -void s_dense_qcqp_ipm_arg_set_t_min(float *value, struct s_dense_qcqp_ipm_arg *arg); -// -void s_dense_qcqp_ipm_arg_set_split_step(int *value, struct s_dense_qcqp_ipm_arg *arg); -// -void s_dense_qcqp_ipm_arg_set_t_lam_min(int *value, struct s_dense_qcqp_ipm_arg *arg); - -// -hpipm_size_t s_dense_qcqp_ipm_ws_memsize(struct s_dense_qcqp_dim *qp_dim, struct s_dense_qcqp_ipm_arg *arg); -// -void s_dense_qcqp_ipm_ws_create(struct s_dense_qcqp_dim *qp_dim, struct s_dense_qcqp_ipm_arg *arg, struct s_dense_qcqp_ipm_ws *ws, void *mem); -// -void s_dense_qcqp_ipm_get(char *field, struct s_dense_qcqp_ipm_ws *ws, void *value); -// -void s_dense_qcqp_ipm_get_status(struct s_dense_qcqp_ipm_ws *ws, int *status); -// -void s_dense_qcqp_ipm_get_iter(struct s_dense_qcqp_ipm_ws *ws, int *iter); -// -void s_dense_qcqp_ipm_get_max_res_stat(struct s_dense_qcqp_ipm_ws *ws, float *res_stat); -// -void s_dense_qcqp_ipm_get_max_res_eq(struct s_dense_qcqp_ipm_ws *ws, float *res_eq); -// -void s_dense_qcqp_ipm_get_max_res_ineq(struct s_dense_qcqp_ipm_ws *ws, float *res_ineq); -// -void s_dense_qcqp_ipm_get_max_res_comp(struct s_dense_qcqp_ipm_ws *ws, float *res_comp); -// -void s_dense_qcqp_ipm_get_stat(struct s_dense_qcqp_ipm_ws *ws, float **stat); -// -void s_dense_qcqp_ipm_get_stat_m(struct s_dense_qcqp_ipm_ws *ws, int *stat_m); -#if 0 -// -void s_dense_qcqp_init_var(struct s_dense_qcqp *qp, struct s_dense_qcqp_sol *qp_sol, struct s_dense_qcqp_ipm_arg *arg, struct s_dense_qcqp_ipm_ws *ws); -#endif -// -void s_dense_qcqp_ipm_solve(struct s_dense_qcqp *qp, struct s_dense_qcqp_sol *qp_sol, struct s_dense_qcqp_ipm_arg *arg, struct s_dense_qcqp_ipm_ws *ws); -#if 0 -// -void s_dense_qcqp_ipm_predict(struct s_dense_qcqp *qp, struct s_dense_qcqp_sol *qp_sol, struct s_dense_qcqp_ipm_arg *arg, struct s_dense_qcqp_ipm_ws *ws); -// -void s_dense_qcqp_ipm_sens(struct s_dense_qcqp *qp, struct s_dense_qcqp_sol *qp_sol, struct s_dense_qcqp_ipm_arg *arg, struct s_dense_qcqp_ipm_ws *ws); -#endif - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_S_DENSE_QCQP_IPM_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_dense_qcqp_res.h b/third_party/acados/include/hpipm/include/hpipm_s_dense_qcqp_res.h deleted file mode 100644 index 779658c..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_dense_qcqp_res.h +++ /dev/null @@ -1,108 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_DENSE_QCQP_RES_H_ -#define HPIPM_S_DENSE_QCQP_RES_H_ - - - -#include -#include - -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_dense_qcqp_res - { - struct s_dense_qcqp_dim *dim; - struct blasfeo_svec *res_g; // q-residuals - struct blasfeo_svec *res_b; // b-residuals - struct blasfeo_svec *res_d; // d-residuals - struct blasfeo_svec *res_m; // m-residuals - float res_max[4]; // infinity norm of residuals - float res_mu; // mu-residual - hpipm_size_t memsize; - }; - - - -struct s_dense_qcqp_res_ws - { - struct blasfeo_svec *tmp_nv; // work space of size nv - struct blasfeo_svec *tmp_nbgq; // work space of size nbM+ngM+nqM - struct blasfeo_svec *tmp_ns; // work space of size nsM - struct blasfeo_svec *q_fun; // value for evaluation of quadr constr - struct blasfeo_svec *q_adj; // value for adjoint of quadr constr - int use_q_fun; // reuse cached value for evaluation of quadr constr - int use_q_adj; // reuse cached value for adjoint of quadr constr - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_dense_qcqp_res_memsize(struct s_dense_qcqp_dim *dim); -// -void s_dense_qcqp_res_create(struct s_dense_qcqp_dim *dim, struct s_dense_qcqp_res *res, void *mem); -// -hpipm_size_t s_dense_qcqp_res_ws_memsize(struct s_dense_qcqp_dim *dim); -// -void s_dense_qcqp_res_ws_create(struct s_dense_qcqp_dim *dim, struct s_dense_qcqp_res_ws *workspace, void *mem); -// -void s_dense_qcqp_res_compute(struct s_dense_qcqp *qp, struct s_dense_qcqp_sol *qp_sol, struct s_dense_qcqp_res *res, struct s_dense_qcqp_res_ws *ws); -// -void s_dense_qcqp_res_compute_inf_norm(struct s_dense_qcqp_res *res); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - -#endif // HPIPM_S_DENSE_QCQP_RES_H_ - - - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_dense_qcqp_sol.h b/third_party/acados/include/hpipm/include/hpipm_s_dense_qcqp_sol.h deleted file mode 100644 index 197a690..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_dense_qcqp_sol.h +++ /dev/null @@ -1,86 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_S_DENSE_QCQP_SOL_H_ -#define HPIPM_S_DENSE_QCQP_SOL_H_ - - - -#include -#include - -#include "hpipm_s_dense_qcqp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_dense_qcqp_sol - { - struct s_dense_qcqp_dim *dim; - struct blasfeo_svec *v; - struct blasfeo_svec *pi; - struct blasfeo_svec *lam; - struct blasfeo_svec *t; - void *misc; - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_dense_qcqp_sol_memsize(struct s_dense_qcqp_dim *dim); -// -void s_dense_qcqp_sol_create(struct s_dense_qcqp_dim *dim, struct s_dense_qcqp_sol *qp_sol, void *memory); -// -void s_dense_qcqp_sol_get_v(struct s_dense_qcqp_sol *qp_sol, float *v); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_S_DENSE_QCQP_SOL_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_dense_qcqp_utils.h b/third_party/acados/include/hpipm/include/hpipm_s_dense_qcqp_utils.h deleted file mode 100644 index 4f5aae2..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_dense_qcqp_utils.h +++ /dev/null @@ -1,83 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_DENSE_QCQP_UTILS_H_ -#define HPIPM_S_DENSE_QCQP_UTILS_H_ - - - -#include -#include - -#include "hpipm_s_dense_qcqp_dim.h" -#include "hpipm_s_dense_qcqp.h" -#include "hpipm_s_dense_qcqp_sol.h" -//#include "hpipm_s_dense_qcqp_ipm.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -// -void s_dense_qcqp_dim_print(struct s_dense_qcqp_dim *qp_dim); -// -//void s_dense_qcqp_dim_codegen(char *file_name, char *mode, struct s_dense_qcqp_dim *qp_dim); -// -void s_dense_qcqp_print(struct s_dense_qcqp_dim *qp_dim, struct s_dense_qcqp *qp); -// -//void s_dense_qcqp_codegen(char *file_name, char *mode, struct s_dense_qcqp_dim *qp_dim, struct s_dense_qcqp *qp); -// -void s_dense_qcqp_sol_print(struct s_dense_qcqp_dim *qp_dim, struct s_dense_qcqp_sol *dense_qcqp_sol); -// -//void s_dense_qcqp_ipm_arg_codegen(char *file_name, char *mode, struct s_dense_qcqp_dim *qp_dim, struct s_dense_qcqp_ipm_arg *arg); -// -void s_dense_qcqp_res_print(struct s_dense_qcqp_dim *qp_dim, struct s_dense_qcqp_res *dense_qcqp_res); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_S_DENSE_QCQP_UTILS_H_ - - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_dense_qp.h b/third_party/acados/include/hpipm/include/hpipm_s_dense_qp.h deleted file mode 100644 index 3c2517f..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_dense_qp.h +++ /dev/null @@ -1,207 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_S_DENSE_QP_H_ -#define HPIPM_S_DENSE_QP_H_ - - - -#include -#include - -#include "hpipm_s_dense_qp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_dense_qp - { - struct s_dense_qp_dim *dim; - struct blasfeo_smat *Hv; // hessian & gradient - struct blasfeo_smat *A; // dynamics matrix - struct blasfeo_smat *Ct; // constraints matrix - struct blasfeo_svec *gz; // gradient & gradient of slacks - struct blasfeo_svec *b; // dynamics vector - struct blasfeo_svec *d; // constraints vector - struct blasfeo_svec *d_mask; // inequality constraints mask vector - struct blasfeo_svec *m; // rhs of complementarity condition - struct blasfeo_svec *Z; // (diagonal) hessian of slacks - int *idxb; // indices of box constrained variables within [u; x] - int *idxs_rev; // index of soft constraints (reverse storage) - hpipm_size_t memsize; // memory size in bytes - }; - - - -// -hpipm_size_t s_dense_qp_memsize(struct s_dense_qp_dim *dim); -// -void s_dense_qp_create(struct s_dense_qp_dim *dim, struct s_dense_qp *qp, void *memory); - -// setters - colmaj -// -void s_dense_qp_set_all(float *H, float *g, float *A, float *b, int *idxb, float *d_lb, float *d_ub, float *C, float *d_lg, float *d_ug, float *Zl, float *Zu, float *zl, float *zu, int *idxs, float *d_ls, float *d_us, struct s_dense_qp *qp); -// -void s_dense_qp_get_all(struct s_dense_qp *qp, float *H, float *g, float *A, float *b, int *idxb, float *d_lb, float *d_ub, float *C, float *d_lg, float *d_ug, float *Zl, float *Zu, float *zl, float *zu, int *idxs, float *d_ls, float *d_us); -// -void s_dense_qp_set(char *field, void *value, struct s_dense_qp *qp); -// -void s_dense_qp_set_H(float *H, struct s_dense_qp *qp); -// -void s_dense_qp_set_g(float *g, struct s_dense_qp *qp); -// -void s_dense_qp_set_A(float *A, struct s_dense_qp *qp); -// -void s_dense_qp_set_b(float *b, struct s_dense_qp *qp); -// -void s_dense_qp_set_idxb(int *idxb, struct s_dense_qp *qp); -// -void s_dense_qp_set_Jb(float *Jb, struct s_dense_qp *qp); -// -void s_dense_qp_set_lb(float *lb, struct s_dense_qp *qp); -// -void s_dense_qp_set_lb_mask(float *lb, struct s_dense_qp *qp); -// -void s_dense_qp_set_ub(float *ub, struct s_dense_qp *qp); -// -void s_dense_qp_set_ub_mask(float *ub, struct s_dense_qp *qp); -// -void s_dense_qp_set_C(float *C, struct s_dense_qp *qp); -// -void s_dense_qp_set_lg(float *lg, struct s_dense_qp *qp); -// -void s_dense_qp_set_lg_mask(float *lg, struct s_dense_qp *qp); -// -void s_dense_qp_set_ug(float *ug, struct s_dense_qp *qp); -// -void s_dense_qp_set_ug_mask(float *ug, struct s_dense_qp *qp); -// -void s_dense_qp_set_idxs(int *idxs, struct s_dense_qp *qp); -// -void s_dense_qp_set_idxs_rev(int *idxs_rev, struct s_dense_qp *qp); -// -void s_dense_qp_set_Jsb(float *Jsb, struct s_dense_qp *qp); -// -void s_dense_qp_set_Jsg(float *Jsg, struct s_dense_qp *qp); -// -void s_dense_qp_set_Zl(float *Zl, struct s_dense_qp *qp); -// -void s_dense_qp_set_Zu(float *Zu, struct s_dense_qp *qp); -// -void s_dense_qp_set_zl(float *zl, struct s_dense_qp *qp); -// -void s_dense_qp_set_zu(float *zu, struct s_dense_qp *qp); -// -void s_dense_qp_set_ls(float *ls, struct s_dense_qp *qp); -// -void s_dense_qp_set_ls_mask(float *ls, struct s_dense_qp *qp); -// -void s_dense_qp_set_us(float *us, struct s_dense_qp *qp); -// -void s_dense_qp_set_us_mask(float *us, struct s_dense_qp *qp); - -// getters - colmaj -// -void s_dense_qp_get_H(struct s_dense_qp *qp, float *H); -// -void s_dense_qp_get_g(struct s_dense_qp *qp, float *g); -// -void s_dense_qp_get_A(struct s_dense_qp *qp, float *A); -// -void s_dense_qp_get_b(struct s_dense_qp *qp, float *b); -// -void s_dense_qp_get_idxb(struct s_dense_qp *qp, int *idxb); -// -void s_dense_qp_get_lb(struct s_dense_qp *qp, float *lb); -// -void s_dense_qp_get_lb_mask(struct s_dense_qp *qp, float *lb); -// -void s_dense_qp_get_ub(struct s_dense_qp *qp, float *ub); -// -void s_dense_qp_get_ub_mask(struct s_dense_qp *qp, float *ub); -// -void s_dense_qp_get_C(struct s_dense_qp *qp, float *C); -// -void s_dense_qp_get_lg(struct s_dense_qp *qp, float *lg); -// -void s_dense_qp_get_lg_mask(struct s_dense_qp *qp, float *lg); -// -void s_dense_qp_get_ug(struct s_dense_qp *qp, float *ug); -// -void s_dense_qp_get_ug_mask(struct s_dense_qp *qp, float *ug); -// -void s_dense_qp_get_idxs(struct s_dense_qp *qp, int *idxs); -// -void s_dense_qp_get_idxs_rev(struct s_dense_qp *qp, int *idxs_rev); -// -void s_dense_qp_get_Zl(struct s_dense_qp *qp, float *Zl); -// -void s_dense_qp_get_Zu(struct s_dense_qp *qp, float *Zu); -// -void s_dense_qp_get_zl(struct s_dense_qp *qp, float *zl); -// -void s_dense_qp_get_zu(struct s_dense_qp *qp, float *zu); -// -void s_dense_qp_get_ls(struct s_dense_qp *qp, float *ls); -// -void s_dense_qp_get_ls_mask(struct s_dense_qp *qp, float *ls); -// -void s_dense_qp_get_us(struct s_dense_qp *qp, float *us); -// -void s_dense_qp_get_us_mask(struct s_dense_qp *qp, float *us); - -// setters - rowmaj -// -void s_dense_qp_set_all_rowmaj(float *H, float *g, float *A, float *b, int *idxb, float *d_lb, float *d_ub, float *C, float *d_lg, float *d_ug, float *Zl, float *Zu, float *zl, float *zu, int *idxs, float *d_ls, float *d_us, struct s_dense_qp *qp); - -// getters - rowmaj -// -void s_dense_qp_get_all_rowmaj(struct s_dense_qp *qp, float *H, float *g, float *A, float *b, int *idxb, float *d_lb, float *d_ub, float *C, float *d_lg, float *d_ug, float *Zl, float *Zu, float *zl, float *zu, int *idxs, float *d_ls, float *d_us); - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_S_DENSE_QP_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_s_dense_qp_dim.h b/third_party/acados/include/hpipm/include/hpipm_s_dense_qp_dim.h deleted file mode 100644 index b979d24..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_dense_qp_dim.h +++ /dev/null @@ -1,94 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_DENSE_QP_DIM_H_ -#define HPIPM_S_DENSE_QP_DIM_H_ - -#include "hpipm_common.h" - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_dense_qp_dim - { - int nv; // number of variables - int ne; // number of equality constraints - int nb; // number of box constraints - int ng; // number of general constraints - int nsb; // number of softened box constraints - int nsg; // number of softened general constraints - int ns; // number of softened constraints (nsb+nsg) - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_dense_qp_dim_memsize(); -// -void s_dense_qp_dim_create(struct s_dense_qp_dim *qp_dim, void *memory); -// -void s_dense_qp_dim_set_all(int nv, int ne, int nb, int ng, int nsb, int nsg, struct s_dense_qp_dim *dim); -// -void s_dense_qp_dim_set(char *fiels_name, int value, struct s_dense_qp_dim *dim); -// -void s_dense_qp_dim_set_nv(int value, struct s_dense_qp_dim *dim); -// -void s_dense_qp_dim_set_ne(int value, struct s_dense_qp_dim *dim); -// -void s_dense_qp_dim_set_nb(int value, struct s_dense_qp_dim *dim); -// -void s_dense_qp_dim_set_ng(int value, struct s_dense_qp_dim *dim); -// -void s_dense_qp_dim_set_nsb(int value, struct s_dense_qp_dim *dim); -// -void s_dense_qp_dim_set_nsg(int value, struct s_dense_qp_dim *dim); -// -void s_dense_qp_dim_set_ns(int value, struct s_dense_qp_dim *dim); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_S_DENSE_QP_DIM_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_dense_qp_ipm.h b/third_party/acados/include/hpipm/include/hpipm_s_dense_qp_ipm.h deleted file mode 100644 index f2d56d4..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_dense_qp_ipm.h +++ /dev/null @@ -1,260 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_S_DENSE_QP_IPM_H_ -#define HPIPM_S_DENSE_QP_IPM_H_ - - - -#include -#include - -#include -#include -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_dense_qp_ipm_arg - { - float mu0; // initial value for duality measure - float alpha_min; // exit cond on step length - float res_g_max; // exit cond on inf norm of residuals - float res_b_max; // exit cond on inf norm of residuals - float res_d_max; // exit cond on inf norm of residuals - float res_m_max; // exit cond on inf norm of residuals - float reg_prim; // reg of primal hessian - float reg_dual; // reg of dual hessian - float lam_min; // min value in lam vector - float t_min; // min value in t vector - float tau_min; // min value of barrier parameter - int iter_max; // exit cond in iter number - int stat_max; // iterations saved in stat - int pred_corr; // Mehrotra's predictor-corrector IPM algirthm - int cond_pred_corr; // conditional Mehrotra's predictor-corrector - int scale; // scale hessian - int itref_pred_max; // max number of iterative refinement steps for predictor step - int itref_corr_max; // max number of iterative refinement steps for corrector step - int warm_start; // 0 no warm start, 1 warm start primal sol, 2 warm start primal and dual sol - int lq_fact; // 0 syrk+potrf, 1 mix, 2 lq - int abs_form; // absolute IPM formulation - int comp_res_exit; // compute residuals on exit (only for abs_form==1) - int comp_res_pred; // compute residuals of prediction - int kkt_fact_alg; // 0 null-space, 1 schur-complement - int remove_lin_dep_eq; // 0 do not, 1 do check and remove linearly dependent equality constraints - int compute_obj; // compute obj on exit - int split_step; // use different steps for primal and dual variables - int t_lam_min; // clip t and lam: 0 no, 1 in Gamma computation, 2 in solution - int mode; - hpipm_size_t memsize; - }; - - - -struct s_dense_qp_ipm_ws - { - struct s_core_qp_ipm_workspace *core_workspace; - struct s_dense_qp_res_ws *res_ws; - struct s_dense_qp_sol *sol_step; - struct s_dense_qp_sol *sol_itref; - struct s_dense_qp *qp_step; - struct s_dense_qp *qp_itref; - struct s_dense_qp_res *res; - struct s_dense_qp_res *res_itref; - struct s_dense_qp_res *res_step; - struct blasfeo_svec *Gamma; // - struct blasfeo_svec *gamma; // - struct blasfeo_svec *Zs_inv; // - struct blasfeo_smat *Lv; // - struct blasfeo_smat *AL; // - struct blasfeo_smat *Le; // - struct blasfeo_smat *Ctx; // - struct blasfeo_svec *lv; // - struct blasfeo_svec *sv; // scale for Lv - struct blasfeo_svec *se; // scale for Le - struct blasfeo_svec *tmp_nbg; // work space of size nb+ng - struct blasfeo_svec *tmp_ns; // work space of size ns - struct blasfeo_smat *lq0; - struct blasfeo_smat *lq1; - struct blasfeo_svec *tmp_m; - struct blasfeo_smat *A_LQ; - struct blasfeo_smat *A_Q; - struct blasfeo_smat *Zt; - struct blasfeo_smat *ZtH; - struct blasfeo_smat *ZtHZ; - struct blasfeo_svec *xy; - struct blasfeo_svec *Yxy; - struct blasfeo_svec *xz; - struct blasfeo_svec *tmp_nv; - struct blasfeo_svec *tmp_2ns; - struct blasfeo_svec *tmp_nv2ns; - struct blasfeo_smat *A_li; // A of linearly independent equality constraints - struct blasfeo_svec *b_li; // b of linearly independent equality constraints - struct blasfeo_smat *A_bkp; // pointer to backup A - struct blasfeo_svec *b_bkp; // pointer to backup b - struct blasfeo_smat *Ab_LU; - float *stat; // convergence statistics - int *ipiv_v; - int *ipiv_e; - int *ipiv_e1; - void *lq_work0; - void *lq_work1; - void *lq_work_null; - void *orglq_work_null; - int iter; // iteration number - int stat_max; // iterations saved in stat - int stat_m; // numer of recorded stat per ipm iter - int scale; - int use_hess_fact; - int use_A_fact; - int status; - int lq_fact; // cache from arg - int mask_constr; // use constr mask - int ne_li; // number of linearly independent equality constraints - int ne_bkp; // ne backup - hpipm_size_t memsize; // memory size (in bytes) of workspace - }; - - - -// -hpipm_size_t s_dense_qp_ipm_arg_memsize(struct s_dense_qp_dim *qp_dim); -// -void s_dense_qp_ipm_arg_create(struct s_dense_qp_dim *qp_dim, struct s_dense_qp_ipm_arg *arg, void *mem); -// -void s_dense_qp_ipm_arg_set_default(enum hpipm_mode mode, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set(char *field, void *value, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set_iter_max(int *iter_max, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set_alpha_min(float *alpha_min, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set_mu0(float *mu0, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set_tol_stat(float *tol_stat, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set_tol_eq(float *tol_eq, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set_tol_ineq(float *tol_ineq, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set_tol_comp(float *tol_comp, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set_reg_prim(float *reg, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set_reg_dual(float *reg, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set_warm_start(int *warm_start, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set_pred_corr(int *pred_corr, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set_cond_pred_corr(int *cond_pred_corr, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set_comp_res_pred(int *comp_res_pred, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set_comp_res_exit(int *comp_res_exit, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set_lam_min(float *value, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set_t_min(float *value, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set_tau_min(float *value, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set_kkt_fact_alg(int *value, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set_remove_lin_dep_eq(int *value, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set_compute_obj(int *value, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set_split_step(int *value, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_arg_set_t_lam_min(int *value, struct s_dense_qp_ipm_arg *arg); - -// -hpipm_size_t s_dense_qp_ipm_ws_memsize(struct s_dense_qp_dim *qp_dim, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_ipm_ws_create(struct s_dense_qp_dim *qp_dim, struct s_dense_qp_ipm_arg *arg, struct s_dense_qp_ipm_ws *ws, void *mem); -// -void s_dense_qp_ipm_get(char *field, struct s_dense_qp_ipm_ws *ws, void *value); -// -void s_dense_qp_ipm_get_status(struct s_dense_qp_ipm_ws *ws, int *status); -// -void s_dense_qp_ipm_get_iter(struct s_dense_qp_ipm_ws *ws, int *iter); -// -void s_dense_qp_ipm_get_max_res_stat(struct s_dense_qp_ipm_ws *ws, float *res_stat); -// -void s_dense_qp_ipm_get_max_res_eq(struct s_dense_qp_ipm_ws *ws, float *res_eq); -// -void s_dense_qp_ipm_get_max_res_ineq(struct s_dense_qp_ipm_ws *ws, float *res_ineq); -// -void s_dense_qp_ipm_get_max_res_comp(struct s_dense_qp_ipm_ws *ws, float *res_comp); -// -void s_dense_qp_ipm_get_stat(struct s_dense_qp_ipm_ws *ws, float **stat); -// -void s_dense_qp_ipm_get_stat_m(struct s_dense_qp_ipm_ws *ws, int *stat_m); -// -void s_dense_qp_init_var(struct s_dense_qp *qp, struct s_dense_qp_sol *qp_sol, struct s_dense_qp_ipm_arg *arg, struct s_dense_qp_ipm_ws *ws); -// -void s_dense_qp_ipm_abs_step(int kk, struct s_dense_qp *qp, struct s_dense_qp_sol *qp_sol, struct s_dense_qp_ipm_arg *arg, struct s_dense_qp_ipm_ws *ws); -// -void s_dense_qp_ipm_delta_step(int kk, struct s_dense_qp *qp, struct s_dense_qp_sol *qp_sol, struct s_dense_qp_ipm_arg *arg, struct s_dense_qp_ipm_ws *ws); -// -void s_dense_qp_ipm_solve(struct s_dense_qp *qp, struct s_dense_qp_sol *qp_sol, struct s_dense_qp_ipm_arg *arg, struct s_dense_qp_ipm_ws *ws); -// -void s_dense_qp_ipm_predict(struct s_dense_qp *qp, struct s_dense_qp_sol *qp_sol, struct s_dense_qp_ipm_arg *arg, struct s_dense_qp_ipm_ws *ws); -// -void s_dense_qp_ipm_sens(struct s_dense_qp *qp, struct s_dense_qp_sol *qp_sol, struct s_dense_qp_ipm_arg *arg, struct s_dense_qp_ipm_ws *ws); -// -void s_dense_qp_compute_step_length(struct s_dense_qp *qp, struct s_dense_qp_sol *qp_sol, struct s_dense_qp_ipm_arg *arg, struct s_dense_qp_ipm_ws *ws); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_S_DENSE_QP_IPM_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_s_dense_qp_kkt.h b/third_party/acados/include/hpipm/include/hpipm_s_dense_qp_kkt.h deleted file mode 100644 index 260dc0a..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_dense_qp_kkt.h +++ /dev/null @@ -1,72 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_S_DENSE_QP_KKT_H_ -#define HPIPM_S_DENSE_QP_KKT_H_ - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -// -void s_fact_solve_kkt_unconstr_dense_qp(struct s_dense_qp *qp, struct s_dense_qp_sol *qp_sol, struct s_dense_qp_ipm_arg *arg, struct s_dense_qp_ipm_ws *ws); -// -void s_fact_solve_kkt_step_dense_qp(struct s_dense_qp *qp, struct s_dense_qp_sol *qp_sol, struct s_dense_qp_ipm_arg *arg, struct s_dense_qp_ipm_ws *ws); -// -void s_fact_lq_solve_kkt_step_dense_qp(struct s_dense_qp *qp, struct s_dense_qp_sol *qp_sol, struct s_dense_qp_ipm_arg *arg, struct s_dense_qp_ipm_ws *ws); -// -void s_solve_kkt_step_dense_qp(struct s_dense_qp *qp, struct s_dense_qp_sol *qp_sol, struct s_dense_qp_ipm_arg *arg, struct s_dense_qp_ipm_ws *ws); -// -void s_dense_qp_remove_lin_dep_eq(struct s_dense_qp *qp, struct s_dense_qp_ipm_arg *arg, struct s_dense_qp_ipm_ws *ws); -// -void s_dense_qp_restore_lin_dep_eq(struct s_dense_qp *qp, struct s_dense_qp_ipm_arg *arg, struct s_dense_qp_ipm_ws *ws); -// -void s_dense_qp_compute_obj(struct s_dense_qp *qp, struct s_dense_qp_sol *qp_sol, struct s_dense_qp_ipm_arg *arg, struct s_dense_qp_ipm_ws *ws); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_S_DENSE_QP_KKT_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_s_dense_qp_res.h b/third_party/acados/include/hpipm/include/hpipm_s_dense_qp_res.h deleted file mode 100644 index 06b609c..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_dense_qp_res.h +++ /dev/null @@ -1,106 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_DENSE_QP_RES_H_ -#define HPIPM_S_DENSE_QP_RES_H_ - - - -#include -#include - -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_dense_qp_res - { - struct s_dense_qp_dim *dim; - struct blasfeo_svec *res_g; // q-residuals - struct blasfeo_svec *res_b; // b-residuals - struct blasfeo_svec *res_d; // d-residuals - struct blasfeo_svec *res_m; // m-residuals - float res_max[4]; // max of residuals - float res_mu; // mu-residual - hpipm_size_t memsize; - }; - - - -struct s_dense_qp_res_ws - { - struct blasfeo_svec *tmp_nbg; // work space of size nbM+ngM - struct blasfeo_svec *tmp_ns; // work space of size nsM - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_dense_qp_res_memsize(struct s_dense_qp_dim *dim); -// -void s_dense_qp_res_create(struct s_dense_qp_dim *dim, struct s_dense_qp_res *res, void *mem); -// -hpipm_size_t s_dense_qp_res_ws_memsize(struct s_dense_qp_dim *dim); -// -void s_dense_qp_res_ws_create(struct s_dense_qp_dim *dim, struct s_dense_qp_res_ws *workspace, void *mem); -// -void s_dense_qp_res_compute(struct s_dense_qp *qp, struct s_dense_qp_sol *qp_sol, struct s_dense_qp_res *res, struct s_dense_qp_res_ws *ws); -// -void s_dense_qp_res_compute_lin(struct s_dense_qp *qp, struct s_dense_qp_sol *qp_sol, struct s_dense_qp_sol *qp_step, struct s_dense_qp_res *res, struct s_dense_qp_res_ws *ws); -// -void s_dense_qp_res_compute_inf_norm(struct s_dense_qp_res *res); -// -void s_dense_qp_res_get_all(struct s_dense_qp_res *res, float *res_g, float *res_ls, float *res_us, float *res_b, float *res_d_lb, float *res_d_ub, float *res_d_lg, float *res_d_ug, float *res_d_ls, float *res_d_us, float *res_m_lb, float *res_m_ub, float *res_m_lg, float *res_m_ug, float *res_m_ls, float *res_m_us); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - -#endif // HPIPM_D_DENSE_QP_RES_H_ - - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_dense_qp_sol.h b/third_party/acados/include/hpipm/include/hpipm_s_dense_qp_sol.h deleted file mode 100644 index 1f40076..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_dense_qp_sol.h +++ /dev/null @@ -1,94 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_S_DENSE_QP_SOL_H_ -#define HPIPM_S_DENSE_QP_SOL_H_ - - - -#include -#include - -#include "hpipm_s_dense_qp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_dense_qp_sol - { - struct s_dense_qp_dim *dim; - struct blasfeo_svec *v; - struct blasfeo_svec *pi; - struct blasfeo_svec *lam; - struct blasfeo_svec *t; - void *misc; - float obj; - int valid_obj; - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_dense_qp_sol_memsize(struct s_dense_qp_dim *dim); -// -void s_dense_qp_sol_create(struct s_dense_qp_dim *dim, struct s_dense_qp_sol *qp_sol, void *memory); -// -void s_dense_qp_sol_get_all(struct s_dense_qp_sol *qp_sol, float *v, float *ls, float *us, float *pi, float *lam_lb, float *lam_ub, float *lam_lg, float *lam_ug, float *lam_ls, float *lam_us); -// -void s_dense_qp_sol_get(char *field, struct s_dense_qp_sol *sol, void *value); -// -void s_dense_qp_sol_get_v(struct s_dense_qp_sol *sol, float *v); -// -void s_dense_qp_sol_get_valid_obj(struct s_dense_qp_sol *sol, int *valid_obj); -// -void s_dense_qp_sol_get_obj(struct s_dense_qp_sol *sol, float *obj); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_S_DENSE_QP_SOL_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_s_dense_qp_utils.h b/third_party/acados/include/hpipm/include/hpipm_s_dense_qp_utils.h deleted file mode 100644 index 3dd9325..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_dense_qp_utils.h +++ /dev/null @@ -1,84 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_DENSE_QP_UTILS_H_ -#define HPIPM_S_DENSE_QP_UTILS_H_ - - - -#include -#include - -#include "hpipm_s_dense_qp_dim.h" -#include "hpipm_s_dense_qp.h" -#include "hpipm_s_dense_qp_sol.h" -#include "hpipm_s_dense_qp_ipm.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -// -void s_dense_qp_dim_print(struct s_dense_qp_dim *qp_dim); -// -//void s_dense_qp_dim_codegen(char *file_name, char *mode, struct s_dense_qp_dim *qp_dim); -// -void s_dense_qp_print(struct s_dense_qp_dim *qp_dim, struct s_dense_qp *qp); -// -//void s_dense_qp_codegen(char *file_name, char *mode, struct s_dense_qp_dim *qp_dim, struct s_dense_qp *qp); -// -void s_dense_qp_sol_print(struct s_dense_qp_dim *qp_dim, struct s_dense_qp_sol *dense_qp_sol); -// -//void s_dense_qp_ipm_arg_codegen(char *file_name, char *mode, struct s_dense_qp_dim *qp_dim, struct s_dense_qp_ipm_arg *arg); -// -void s_dense_qp_res_print(struct s_dense_qp_dim *qp_dim, struct s_dense_qp_res *dense_qp_res); -// -void s_dense_qp_arg_print(struct s_dense_qp_dim *qp_dim, struct s_dense_qp_ipm_arg *qp_ipm_arg); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_S_DENSE_QP_UTILS_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qcqp.h b/third_party/acados/include/hpipm/include/hpipm_s_ocp_qcqp.h deleted file mode 100644 index b90b2ac..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qcqp.h +++ /dev/null @@ -1,303 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_OCP_QCQP_H_ -#define HPIPM_S_OCP_QCQP_H_ - - - -#include -#include - -#include "hpipm_s_ocp_qcqp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_ocp_qcqp - { - struct s_ocp_qcqp_dim *dim; - struct blasfeo_smat *BAbt; // dynamics matrix & vector work space - struct blasfeo_smat *RSQrq; // hessian of cost & vector work space - struct blasfeo_smat *DCt; // inequality constraints matrix - struct blasfeo_smat **Hq; // hessians of quadratic constraints - struct blasfeo_svec *b; // dynamics vector - struct blasfeo_svec *rqz; // gradient of cost & gradient of slacks - struct blasfeo_svec *d; // inequality constraints vector - struct blasfeo_svec *d_mask; // inequality constraints mask vector - struct blasfeo_svec *m; // rhs of complementarity condition - struct blasfeo_svec *Z; // (diagonal) hessian of slacks - int **idxb; // indices of box constrained variables within [u; x] - int **idxs_rev; // index of soft constraints (reverse storage) - int **Hq_nzero; // for each int, the last 3 bits ...abc, {a,b,c}=0 => {R,S,Q}=0 - hpipm_size_t memsize; // memory size in bytes - }; - - - -// -hpipm_size_t s_ocp_qcqp_strsize(); -// -hpipm_size_t s_ocp_qcqp_memsize(struct s_ocp_qcqp_dim *dim); -// -void s_ocp_qcqp_create(struct s_ocp_qcqp_dim *dim, struct s_ocp_qcqp *qp, void *memory); -// -void s_ocp_qcqp_copy_all(struct s_ocp_qcqp *qp_orig, struct s_ocp_qcqp *qp_dest); - -// setters -// -void s_ocp_qcqp_set_all_zero(struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_rhs_zero(struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set(char *fiels_name, int stage, void *value, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_el(char *fiels_name, int stage, int index, void *value, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_A(int stage, float *mat, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_B(int stage, float *mat, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_b(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_Q(int stage, float *mat, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_S(int stage, float *mat, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_R(int stage, float *mat, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_q(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_r(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_lb(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_lb_mask(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_ub(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_ub_mask(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_lbx(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_lbx_mask(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_el_lbx(int stage, int index, float *elem, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_ubx(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_ubx_mask(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_el_ubx(int stage, int index, float *elem, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_lbu(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_lbu_mask(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_ubu(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_ubu_mask(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_idxb(int stage, int *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_idxbx(int stage, int *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_Jbx(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_idxbu(int stage, int *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_Jbu(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_C(int stage, float *mat, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_D(int stage, float *mat, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_lg(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_lg_mask(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_ug(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_ug_mask(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_Qq(int stage, float *mat, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_Sq(int stage, float *mat, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_Rq(int stage, float *mat, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_qq(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_rq(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_uq(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_uq_mask(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_Zl(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_Zu(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_zl(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_zu(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_lls(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_lls_mask(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_lus(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_lus_mask(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_idxs(int stage, int *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_idxs_rev(int stage, int *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_Jsbu(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_Jsbx(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_Jsg(int stage, float *vec, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_set_Jsq(int stage, float *vec, struct s_ocp_qcqp *qp); - -// getters -// -void s_ocp_qcqp_get(char *field, int stage, struct s_ocp_qcqp *qp, void *value); -// -void s_ocp_qcqp_get_A(int stage, struct s_ocp_qcqp *qp, float *mat); -// -void s_ocp_qcqp_get_B(int stage, struct s_ocp_qcqp *qp, float *mat); -// -void s_ocp_qcqp_get_b(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_Q(int stage, struct s_ocp_qcqp *qp, float *mat); -// -void s_ocp_qcqp_get_S(int stage, struct s_ocp_qcqp *qp, float *mat); -// -void s_ocp_qcqp_get_R(int stage, struct s_ocp_qcqp *qp, float *mat); -// -void s_ocp_qcqp_get_q(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_r(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_ub(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_ub_mask(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_lb(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_lb_mask(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_lbx(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_lbx_mask(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_ubx(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_ubx_mask(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_lbu(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_lbu_mask(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_ubu(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_ubu_mask(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_idxb(int stage, struct s_ocp_qcqp *qp, int *vec); -// -//void s_ocp_qcqp_get_idxbx(int stage, struct s_ocp_qcqp *qp, int *vec); -// -//void s_ocp_qcqp_get_Jbx(int stage, struct s_ocp_qcqp *qp, float *vec); -// -//void s_ocp_qcqp_get_idxbu(int stage, struct s_ocp_qcqp *qp, int *vec); -// -//void s_ocp_qcqp_get_Jbu(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_C(int stage, struct s_ocp_qcqp *qp, float *mat); -// -void s_ocp_qcqp_get_D(int stage, struct s_ocp_qcqp *qp, float *mat); -// -void s_ocp_qcqp_get_lg(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_lg_mask(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_ug(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_ug_mask(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_Zl(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_Zu(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_zl(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_zu(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_lls(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_lls_mask(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_lus(int stage, struct s_ocp_qcqp *qp, float *vec); -// -void s_ocp_qcqp_get_lus_mask(int stage, struct s_ocp_qcqp *qp, float *vec); -// XXX only valid if there is one slack per softed constraint !!! -void s_ocp_qcqp_get_idxs(int stage, struct s_ocp_qcqp *qp, int *vec); -// -void s_ocp_qcqp_get_idxs_rev(int stage, struct s_ocp_qcqp *qp, int *vec); -// -//void s_ocp_qcqp_get_Jsbu(int stage, struct s_ocp_qcqp *qp, float *vec); -// -//void s_ocp_qcqp_get_Jsbx(int stage, struct s_ocp_qcqp *qp, float *vec); -// -//void s_ocp_qcqp_get_Jsg(int stage, struct s_ocp_qcqp *qp, float *vec); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_S_OCP_QCQP_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qcqp_dim.h b/third_party/acados/include/hpipm/include/hpipm_s_ocp_qcqp_dim.h deleted file mode 100644 index c09903f..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qcqp_dim.h +++ /dev/null @@ -1,119 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_OCP_QCQP_DIM_H_ -#define HPIPM_S_OCP_QCQP_DIM_H_ - -#include "hpipm_common.h" - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_ocp_qcqp_dim - { - struct s_ocp_qp_dim *qp_dim; // dim of qp approximation - int *nx; // number of states - int *nu; // number of inputs - int *nb; // number of box constraints - int *nbx; // number of (two-sided) state box constraints - int *nbu; // number of (two-sided) input box constraints - int *ng; // number of (two-sided) general constraints - int *nq; // number of (upper) quadratic constraints - int *ns; // number of soft constraints - int *nsbx; // number of (two-sided) soft state box constraints - int *nsbu; // number of (two-sided) soft input box constraints - int *nsg; // number of (two-sided) soft general constraints - int *nsq; // number of (upper) soft quadratic constraints - int N; // horizon length - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_ocp_qcqp_dim_strsize(); -// -hpipm_size_t s_ocp_qcqp_dim_memsize(int N); -// -void s_ocp_qcqp_dim_create(int N, struct s_ocp_qcqp_dim *qp_dim, void *memory); -// -void s_ocp_qcqp_dim_copy_all(struct s_ocp_qcqp_dim *dim_orig, struct s_ocp_qcqp_dim *dim_dest); -// -void s_ocp_qcqp_dim_set(char *field, int stage, int value, struct s_ocp_qcqp_dim *dim); -// -void s_ocp_qcqp_dim_set_nx(int stage, int value, struct s_ocp_qcqp_dim *dim); -// -void s_ocp_qcqp_dim_set_nu(int stage, int value, struct s_ocp_qcqp_dim *dim); -// -void s_ocp_qcqp_dim_set_nbx(int stage, int value, struct s_ocp_qcqp_dim *dim); -// -void s_ocp_qcqp_dim_set_nbu(int stage, int value, struct s_ocp_qcqp_dim *dim); -// -void s_ocp_qcqp_dim_set_ng(int stage, int value, struct s_ocp_qcqp_dim *dim); -// -void s_ocp_qcqp_dim_set_nq(int stage, int value, struct s_ocp_qcqp_dim *dim); -// -void s_ocp_qcqp_dim_set_ns(int stage, int value, struct s_ocp_qcqp_dim *dim); -// -void s_ocp_qcqp_dim_set_nsbx(int stage, int value, struct s_ocp_qcqp_dim *dim); -// -void s_ocp_qcqp_dim_set_nsbu(int stage, int value, struct s_ocp_qcqp_dim *dim); -// -void s_ocp_qcqp_dim_set_nsg(int stage, int value, struct s_ocp_qcqp_dim *dim); -// -void s_ocp_qcqp_dim_set_nsq(int stage, int value, struct s_ocp_qcqp_dim *dim); -// -void s_ocp_qcqp_dim_get(struct s_ocp_qcqp_dim *dim, char *field, int stage, int *value); -// -void s_ocp_qcqp_dim_get_N(struct s_ocp_qcqp_dim *dim, int *value); -// -void s_ocp_qcqp_dim_get_nx(struct s_ocp_qcqp_dim *dim, int stage, int *value); -// -void s_ocp_qcqp_dim_get_nu(struct s_ocp_qcqp_dim *dim, int stage, int *value); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_S_OCP_QCQP_DIM_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qcqp_ipm.h b/third_party/acados/include/hpipm/include/hpipm_s_ocp_qcqp_ipm.h deleted file mode 100644 index c14fc1c..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qcqp_ipm.h +++ /dev/null @@ -1,191 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_OCP_QCQP_IPM_H_ -#define HPIPM_S_OCP_QCQP_IPM_H_ - - - -#include -#include - -#include -#include -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_ocp_qcqp_ipm_arg - { - struct s_ocp_qp_ipm_arg *qp_arg; - float mu0; // initial value for complementarity slackness - float alpha_min; // exit cond on step length - float res_g_max; // exit cond on inf norm of residuals - float res_b_max; // exit cond on inf norm of residuals - float res_d_max; // exit cond on inf norm of residuals - float res_m_max; // exit cond on inf norm of residuals - float reg_prim; // reg of primal hessian - float lam_min; // min value in lam vector - float t_min; // min value in t vector - int iter_max; // exit cond in iter number - int stat_max; // iterations saved in stat - int pred_corr; // use Mehrotra's predictor-corrector IPM algirthm - int cond_pred_corr; // conditional Mehrotra's predictor-corrector - int itref_pred_max; // max number of iterative refinement steps for predictor step - int itref_corr_max; // max number of iterative refinement steps for corrector step - int warm_start; // 0 no warm start, 1 warm start primal sol, 2 warm start primal and dual sol - int square_root_alg; // 0 classical Riccati, 1 square-root Riccati - int lq_fact; // 0 syrk+potrf, 1 mix, 2 lq (for square_root_alg==1) - int abs_form; // absolute IPM formulation - int comp_dual_sol_eq; // dual solution of equality constraints (only for abs_form==1) - int comp_res_exit; // compute residuals on exit (only for abs_form==1 and comp_dual_sol_eq==1) - int comp_res_pred; // compute residuals of prediction - int split_step; // use different step for primal and dual variables - int t_lam_min; // clip t and lam: 0 no, 1 in Gamma computation, 2 in solution - int mode; - hpipm_size_t memsize; - }; - - - -struct s_ocp_qcqp_ipm_ws - { - struct s_ocp_qp_ipm_ws *qp_ws; - struct s_ocp_qp *qp; - struct s_ocp_qp_sol *qp_sol; - struct s_ocp_qcqp_res_ws *qcqp_res_ws; - struct s_ocp_qcqp_res *qcqp_res; - struct blasfeo_svec *tmp_nuxM; - int iter; // iteration number - int status; - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_ocp_qcqp_ipm_arg_strsize(); -// -hpipm_size_t s_ocp_qcqp_ipm_arg_memsize(struct s_ocp_qcqp_dim *ocp_dim); -// -void s_ocp_qcqp_ipm_arg_create(struct s_ocp_qcqp_dim *ocp_dim, struct s_ocp_qcqp_ipm_arg *arg, void *mem); -// -void s_ocp_qcqp_ipm_arg_set_default(enum hpipm_mode mode, struct s_ocp_qcqp_ipm_arg *arg); -// -void s_ocp_qcqp_ipm_arg_set(char *field, void *value, struct s_ocp_qcqp_ipm_arg *arg); -// set maximum number of iterations -void s_ocp_qcqp_ipm_arg_set_iter_max(int *value, struct s_ocp_qcqp_ipm_arg *arg); -// set minimum step lenght -void s_ocp_qcqp_ipm_arg_set_alpha_min(float *value, struct s_ocp_qcqp_ipm_arg *arg); -// set initial value of barrier parameter -void s_ocp_qcqp_ipm_arg_set_mu0(float *value, struct s_ocp_qcqp_ipm_arg *arg); -// set exit tolerance on stationarity condition -void s_ocp_qcqp_ipm_arg_set_tol_stat(float *value, struct s_ocp_qcqp_ipm_arg *arg); -// set exit tolerance on equality constr -void s_ocp_qcqp_ipm_arg_set_tol_eq(float *value, struct s_ocp_qcqp_ipm_arg *arg); -// set exit tolerance on inequality constr -void s_ocp_qcqp_ipm_arg_set_tol_ineq(float *value, struct s_ocp_qcqp_ipm_arg *arg); -// set exit tolerance on complementarity condition -void s_ocp_qcqp_ipm_arg_set_tol_comp(float *value, struct s_ocp_qcqp_ipm_arg *arg); -// set regularization of primal variables -void s_ocp_qcqp_ipm_arg_set_reg_prim(float *value, struct s_ocp_qcqp_ipm_arg *arg); -// set warm start: 0 no warm start, 1 primal var -void s_ocp_qcqp_ipm_arg_set_warm_start(int *value, struct s_ocp_qcqp_ipm_arg *arg); -// Mehrotra's predictor-corrector IPM algorithm: 0 no predictor-corrector, 1 use predictor-corrector -void s_ocp_qcqp_ipm_arg_set_pred_corr(int *value, struct s_ocp_qcqp_ipm_arg *arg); -// conditional predictor-corrector: 0 no conditinal predictor-corrector, 1 conditional predictor-corrector -void s_ocp_qcqp_ipm_arg_set_cond_pred_corr(int *value, struct s_ocp_qcqp_ipm_arg *arg); -// set riccati algorithm: 0 classic, 1 square-root -void s_ocp_qcqp_ipm_arg_set_ric_alg(int *value, struct s_ocp_qcqp_ipm_arg *arg); -// compute residuals after solution -void s_ocp_qcqp_ipm_arg_set_comp_res_exit(int *value, struct s_ocp_qcqp_ipm_arg *arg); -// compute residuals of prediction -void s_ocp_qcqp_ipm_arg_set_comp_res_pred(int *value, struct s_ocp_qcqp_ipm_arg *arg); -// min value of lam in the solution -void s_ocp_qcqp_ipm_arg_set_lam_min(float *value, struct s_ocp_qcqp_ipm_arg *arg); -// min value of t in the solution -void s_ocp_qcqp_ipm_arg_set_t_min(float *value, struct s_ocp_qcqp_ipm_arg *arg); -// use different step for primal and dual variables -void s_ocp_qcqp_ipm_arg_set_split_step(int *value, struct s_ocp_qcqp_ipm_arg *arg); -// clip t and lam: 0 no, 1 in Gamma computation, 2 in solution -void s_ocp_qcqp_ipm_arg_set_t_lam_min(int *value, struct s_ocp_qcqp_ipm_arg *arg); - -// -hpipm_size_t s_ocp_qcqp_ipm_ws_strsize(); -// -hpipm_size_t s_ocp_qcqp_ipm_ws_memsize(struct s_ocp_qcqp_dim *ocp_dim, struct s_ocp_qcqp_ipm_arg *arg); -// -void s_ocp_qcqp_ipm_ws_create(struct s_ocp_qcqp_dim *ocp_dim, struct s_ocp_qcqp_ipm_arg *arg, struct s_ocp_qcqp_ipm_ws *ws, void *mem); -// -void s_ocp_qcqp_ipm_get(char *field, struct s_ocp_qcqp_ipm_ws *ws, void *value); -// -void s_ocp_qcqp_ipm_get_status(struct s_ocp_qcqp_ipm_ws *ws, int *status); -// -void s_ocp_qcqp_ipm_get_iter(struct s_ocp_qcqp_ipm_ws *ws, int *iter); -// -void s_ocp_qcqp_ipm_get_max_res_stat(struct s_ocp_qcqp_ipm_ws *ws, float *res_stat); -// -void s_ocp_qcqp_ipm_get_max_res_eq(struct s_ocp_qcqp_ipm_ws *ws, float *res_eq); -// -void s_ocp_qcqp_ipm_get_max_res_ineq(struct s_ocp_qcqp_ipm_ws *ws, float *res_ineq); -// -void s_ocp_qcqp_ipm_get_max_res_comp(struct s_ocp_qcqp_ipm_ws *ws, float *res_comp); -// -void s_ocp_qcqp_ipm_get_stat(struct s_ocp_qcqp_ipm_ws *ws, float **stat); -// -void s_ocp_qcqp_ipm_get_stat_m(struct s_ocp_qcqp_ipm_ws *ws, int *stat_m); -// -void s_ocp_qcqp_init_var(struct s_ocp_qcqp *qp, struct s_ocp_qcqp_sol *qp_sol, struct s_ocp_qcqp_ipm_arg *arg, struct s_ocp_qcqp_ipm_ws *ws); -// -void s_ocp_qcqp_ipm_solve(struct s_ocp_qcqp *qp, struct s_ocp_qcqp_sol *qp_sol, struct s_ocp_qcqp_ipm_arg *arg, struct s_ocp_qcqp_ipm_ws *ws); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - -#endif // HPIPM_S_OCP_QCQP_IPM_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qcqp_res.h b/third_party/acados/include/hpipm/include/hpipm_s_ocp_qcqp_res.h deleted file mode 100644 index 1ceeec9..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qcqp_res.h +++ /dev/null @@ -1,115 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_OCP_QCQP_RES_H_ -#define HPIPM_S_OCP_QCQP_RES_H_ - - - -#include -#include - -#include -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_ocp_qcqp_res - { - struct s_ocp_qcqp_dim *dim; - struct blasfeo_svec *res_g; // q-residuals - struct blasfeo_svec *res_b; // b-residuals - struct blasfeo_svec *res_d; // d-residuals - struct blasfeo_svec *res_m; // m-residuals - float res_max[4]; // max of residuals - float res_mu; // mu-residual - hpipm_size_t memsize; - }; - - - -struct s_ocp_qcqp_res_ws - { - struct blasfeo_svec *tmp_nuxM; // work space of size nuM+nxM - struct blasfeo_svec *tmp_nbgqM; // work space of size nbM+ngM+nqM - struct blasfeo_svec *tmp_nsM; // work space of size nsM - struct blasfeo_svec *q_fun; // value for evaluation of quadr constr - struct blasfeo_svec *q_adj; // value for adjoint of quadr constr - int use_q_fun; // reuse cached value for evaluation of quadr constr - int use_q_adj; // reuse cached value for adjoint of quadr constr - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_ocp_qcqp_res_memsize(struct s_ocp_qcqp_dim *ocp_dim); -// -void s_ocp_qcqp_res_create(struct s_ocp_qcqp_dim *ocp_dim, struct s_ocp_qcqp_res *res, void *mem); -// -hpipm_size_t s_ocp_qcqp_res_ws_memsize(struct s_ocp_qcqp_dim *ocp_dim); -// -void s_ocp_qcqp_res_ws_create(struct s_ocp_qcqp_dim *ocp_dim, struct s_ocp_qcqp_res_ws *workspace, void *mem); -// -void s_ocp_qcqp_res_compute(struct s_ocp_qcqp *qp, struct s_ocp_qcqp_sol *qp_sol, struct s_ocp_qcqp_res *res, struct s_ocp_qcqp_res_ws *ws); -// -void s_ocp_qcqp_res_compute_inf_norm(struct s_ocp_qcqp_res *res); -// -void s_ocp_qcqp_res_get_max_res_stat(struct s_ocp_qcqp_res *res, float *value); -// -void s_ocp_qcqp_res_get_max_res_eq(struct s_ocp_qcqp_res *res, float *value); -// -void s_ocp_qcqp_res_get_max_res_ineq(struct s_ocp_qcqp_res *res, float *value); -// -void s_ocp_qcqp_res_get_max_res_comp(struct s_ocp_qcqp_res *res, float *value); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - -#endif // HPIPM_S_OCP_QCQP_RES_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qcqp_sol.h b/third_party/acados/include/hpipm/include/hpipm_s_ocp_qcqp_sol.h deleted file mode 100644 index 3d58022..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qcqp_sol.h +++ /dev/null @@ -1,115 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_OCP_QCQP_SOL_H_ -#define HPIPM_S_OCP_QCQP_SOL_H_ - - - -#include -#include - -#include "hpipm_s_ocp_qcqp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_ocp_qcqp_sol - { - struct s_ocp_qcqp_dim *dim; - struct blasfeo_svec *ux; - struct blasfeo_svec *pi; - struct blasfeo_svec *lam; - struct blasfeo_svec *t; - hpipm_size_t memsize; // memory size in bytes - }; - - - -// -hpipm_size_t s_ocp_qcqp_sol_strsize(); -// -hpipm_size_t s_ocp_qcqp_sol_memsize(struct s_ocp_qcqp_dim *dim); -// -void s_ocp_qcqp_sol_create(struct s_ocp_qcqp_dim *dim, struct s_ocp_qcqp_sol *qp_sol, void *memory); -// -void s_ocp_qcqp_sol_copy_all(struct s_ocp_qcqp_sol *qp_sol_orig, struct s_ocp_qcqp_sol *qp_sol_dest); -// -void s_ocp_qcqp_sol_get(char *field, int stage, struct s_ocp_qcqp_sol *qp_sol, float *vec); -// -void s_ocp_qcqp_sol_get_u(int stage, struct s_ocp_qcqp_sol *qp_sol, float *vec); -// -void s_ocp_qcqp_sol_get_x(int stage, struct s_ocp_qcqp_sol *qp_sol, float *vec); -// -void s_ocp_qcqp_sol_get_sl(int stage, struct s_ocp_qcqp_sol *qp_sol, float *vec); -// -void s_ocp_qcqp_sol_get_su(int stage, struct s_ocp_qcqp_sol *qp_sol, float *vec); -// -void s_ocp_qcqp_sol_get_pi(int stage, struct s_ocp_qcqp_sol *qp_sol, float *vec); -// -void s_ocp_qcqp_sol_get_lam_lb(int stage, struct s_ocp_qcqp_sol *qp_sol, float *vec); -// -void s_ocp_qcqp_sol_get_lam_ub(int stage, struct s_ocp_qcqp_sol *qp_sol, float *vec); -// -void s_ocp_qcqp_sol_get_lam_lg(int stage, struct s_ocp_qcqp_sol *qp_sol, float *vec); -// -void s_ocp_qcqp_sol_get_lam_ug(int stage, struct s_ocp_qcqp_sol *qp_sol, float *vec); -// -void s_ocp_qcqp_sol_set(char *field, int stage, float *vec, struct s_ocp_qcqp_sol *qp_sol); -// -void s_ocp_qcqp_sol_set_u(int stage, float *vec, struct s_ocp_qcqp_sol *qp_sol); -// -void s_ocp_qcqp_sol_set_x(int stage, float *vec, struct s_ocp_qcqp_sol *qp_sol); -// -void s_ocp_qcqp_sol_set_sl(int stage, float *vec, struct s_ocp_qcqp_sol *qp_sol); -// -void s_ocp_qcqp_sol_set_su(int stage, float *vec, struct s_ocp_qcqp_sol *qp_sol); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_S_OCP_QCQP_SOL_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qcqp_utils.h b/third_party/acados/include/hpipm/include/hpipm_s_ocp_qcqp_utils.h deleted file mode 100644 index d64e3aa..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qcqp_utils.h +++ /dev/null @@ -1,82 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_OCP_QCQP_UTILS_H_ -#define HPIPM_S_OCP_QCQP_UTILS_H_ - - - -#include -#include - -#include "hpipm_s_ocp_qcqp_dim.h" -#include "hpipm_s_ocp_qp.h" -#include "hpipm_s_ocp_qcqp_sol.h" -#include "hpipm_s_ocp_qcqp_ipm.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -// -void s_ocp_qcqp_dim_print(struct s_ocp_qcqp_dim *qcqp_dim); -// -void s_ocp_qcqp_dim_codegen(char *file_name, char *mode, struct s_ocp_qcqp_dim *qcqp_dim); -// -void s_ocp_qcqp_print(struct s_ocp_qcqp_dim *qcqp_dim, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_codegen(char *file_name, char *mode, struct s_ocp_qcqp_dim *qcqp_dim, struct s_ocp_qcqp *qp); -// -void s_ocp_qcqp_sol_print(struct s_ocp_qcqp_dim *qcqp_dim, struct s_ocp_qcqp_sol *ocp_qcqp_sol); -// -void s_ocp_qcqp_ipm_arg_codegen(char *file_name, char *mode, struct s_ocp_qcqp_dim *qcqp_dim, struct s_ocp_qcqp_ipm_arg *arg); -// -void s_ocp_qcqp_res_print(struct s_ocp_qcqp_dim *qcqp_dim, struct s_ocp_qcqp_res *ocp_qcqp_res); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_S_OCP_QCQP_UTILS_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp.h b/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp.h deleted file mode 100644 index b49191f..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp.h +++ /dev/null @@ -1,306 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_OCP_QP_H_ -#define HPIPM_S_OCP_QP_H_ - - - -#include -#include - -#include "hpipm_s_ocp_qp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_ocp_qp - { - struct s_ocp_qp_dim *dim; - struct blasfeo_smat *BAbt; // dynamics matrix & vector work space - struct blasfeo_smat *RSQrq; // hessian of cost & vector work space - struct blasfeo_smat *DCt; // inequality constraints matrix - struct blasfeo_svec *b; // dynamics vector - struct blasfeo_svec *rqz; // gradient of cost & gradient of slacks - struct blasfeo_svec *d; // inequality constraints vector - struct blasfeo_svec *d_mask; // inequality constraints mask vector - struct blasfeo_svec *m; // rhs of complementarity condition - struct blasfeo_svec *Z; // (diagonal) hessian of slacks - int **idxb; // indices of box constrained variables within [u; x] - int **idxs_rev; // index of soft constraints (reverse storage) - int **idxe; // indices of constraints within [bu, bx, g] that are equalities, subset of [0, ..., nbu+nbx+ng-1] - int *diag_H_flag; // flag the fact that Hessian is diagonal - hpipm_size_t memsize; // memory size in bytes - }; - - - -// -hpipm_size_t s_ocp_qp_strsize(); -// -hpipm_size_t s_ocp_qp_memsize(struct s_ocp_qp_dim *dim); -// -void s_ocp_qp_create(struct s_ocp_qp_dim *dim, struct s_ocp_qp *qp, void *memory); -// -void s_ocp_qp_copy_all(struct s_ocp_qp *qp_orig, struct s_ocp_qp *qp_dest); - -// setters -// -void s_ocp_qp_set_all_zero(struct s_ocp_qp *qp); -// -void s_ocp_qp_set_rhs_zero(struct s_ocp_qp *qp); -// -void s_ocp_qp_set_all(float **A, float **B, float **b, float **Q, float **S, float **R, float **q, float **r, int **idxbx, float **lbx, float **ubx, int **idxbu, float **lbu, float **ubu, float **C, float **D, float **lg, float **ug, float **Zl, float **Zu, float **zl, float **zu, int **idxs, float **ls, float **us, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_all_rowmaj(float **A, float **B, float **b, float **Q, float **S, float **R, float **q, float **r, int **idxbx, float **lbx, float **ubx, int **idxbu, float **lbu, float **ubu, float **C, float **D, float **lg, float **ug, float **Zl, float **Zu, float **zl, float **zu, int **idxs, float **ls, float **us, struct s_ocp_qp *qp); -// -void s_ocp_qp_set(char *fiels_name, int stage, void *value, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_el(char *fiels_name, int stage, int index, void *value, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_A(int stage, float *mat, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_B(int stage, float *mat, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_b(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_Q(int stage, float *mat, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_S(int stage, float *mat, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_R(int stage, float *mat, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_q(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_r(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_lb(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_lb_mask(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_ub(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_ub_mask(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_lbx(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_lbx_mask(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_el_lbx(int stage, int index, float *elem, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_ubx(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_ubx_mask(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_el_ubx(int stage, int index, float *elem, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_lbu(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_lbu_mask(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_ubu(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_ubu_mask(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_idxb(int stage, int *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_idxbx(int stage, int *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_Jbx(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_idxbu(int stage, int *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_Jbu(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_C(int stage, float *mat, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_D(int stage, float *mat, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_lg(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_lg_mask(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_ug(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_ug_mask(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_Zl(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_Zu(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_zl(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_zu(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_lls(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_lls_mask(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_lus(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_lus_mask(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_idxs(int stage, int *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_idxs_rev(int stage, int *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_Jsbu(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_Jsbx(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_Jsg(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_idxe(int stage, int *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_idxbxe(int stage, int *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_idxbue(int stage, int *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_idxge(int stage, int *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_Jbxe(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_Jbue(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_Jge(int stage, float *vec, struct s_ocp_qp *qp); -// -void s_ocp_qp_set_diag_H_flag(int stage, int *value, struct s_ocp_qp *qp); - -// getters -// -void s_ocp_qp_get(char *field, int stage, struct s_ocp_qp *qp, void *value); -// -void s_ocp_qp_get_A(int stage, struct s_ocp_qp *qp, float *mat); -// -void s_ocp_qp_get_B(int stage, struct s_ocp_qp *qp, float *mat); -// -void s_ocp_qp_get_b(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_Q(int stage, struct s_ocp_qp *qp, float *mat); -// -void s_ocp_qp_get_S(int stage, struct s_ocp_qp *qp, float *mat); -// -void s_ocp_qp_get_R(int stage, struct s_ocp_qp *qp, float *mat); -// -void s_ocp_qp_get_q(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_r(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_ub(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_ub_mask(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_lb(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_lb_mask(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_lbx(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_lbx_mask(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_ubx(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_ubx_mask(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_lbu(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_lbu_mask(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_ubu(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_ubu_mask(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_idxb(int stage, struct s_ocp_qp *qp, int *vec); -// -//void s_ocp_qp_get_idxbx(int stage, struct s_ocp_qp *qp, int *vec); -// -//void s_ocp_qp_get_Jbx(int stage, struct s_ocp_qp *qp, float *vec); -// -//void s_ocp_qp_get_idxbu(int stage, struct s_ocp_qp *qp, int *vec); -// -//void s_ocp_qp_get_Jbu(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_C(int stage, struct s_ocp_qp *qp, float *mat); -// -void s_ocp_qp_get_D(int stage, struct s_ocp_qp *qp, float *mat); -// -void s_ocp_qp_get_lg(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_lg_mask(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_ug(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_ug_mask(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_Zl(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_Zu(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_zl(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_zu(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_lls(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_lls_mask(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_lus(int stage, struct s_ocp_qp *qp, float *vec); -// -void s_ocp_qp_get_lus_mask(int stage, struct s_ocp_qp *qp, float *vec); -// XXX only valid if there is one slack per softed constraint !!! -void s_ocp_qp_get_idxs(int stage, struct s_ocp_qp *qp, int *vec); -// -void s_ocp_qp_get_idxs_rev(int stage, struct s_ocp_qp *qp, int *vec); -// -//void s_ocp_qp_get_Jsbu(int stage, struct s_ocp_qp *qp, float *vec); -// -//void s_ocp_qp_get_Jsbx(int stage, struct s_ocp_qp *qp, float *vec); -// -//void s_ocp_qp_get_Jsg(int stage, struct s_ocp_qp *qp, float *vec); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_S_OCP_QP_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp_dim.h b/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp_dim.h deleted file mode 100644 index bce8024..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp_dim.h +++ /dev/null @@ -1,141 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_OCP_QP_DIM_H_ -#define HPIPM_S_OCP_QP_DIM_H_ - -#include "hpipm_common.h" - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_ocp_qp_dim - { - int *nx; // number of states - int *nu; // number of inputs - int *nb; // number of box constraints - int *nbx; // number of state box constraints - int *nbu; // number of input box constraints - int *ng; // number of general constraints - int *ns; // number of soft constraints - int *nsbx; // number of soft state box constraints - int *nsbu; // number of soft input box constraints - int *nsg; // number of soft general constraints - int *nbxe; // number of state box constraints which are equality - int *nbue; // number of input box constraints which are equality - int *nge; // number of general constraints which are equality - int N; // horizon length - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_ocp_qp_dim_strsize(); -// -hpipm_size_t s_ocp_qp_dim_memsize(int N); -// -void s_ocp_qp_dim_create(int N, struct s_ocp_qp_dim *qp_dim, void *memory); -// -void s_ocp_qp_dim_copy_all(struct s_ocp_qp_dim *dim_orig, struct s_ocp_qp_dim *dim_dest); -// -void s_ocp_qp_dim_set_all(int *nx, int *nu, int *nbx, int *nbu, int *ng, int *nsbx, int *nsbu, int *nsg, struct s_ocp_qp_dim *dim); -// -void s_ocp_qp_dim_set(char *field, int stage, int value, struct s_ocp_qp_dim *dim); -// -void s_ocp_qp_dim_set_nx(int stage, int value, struct s_ocp_qp_dim *dim); -// -void s_ocp_qp_dim_set_nu(int stage, int value, struct s_ocp_qp_dim *dim); -// -void s_ocp_qp_dim_set_nbx(int stage, int value, struct s_ocp_qp_dim *dim); -// -void s_ocp_qp_dim_set_nbu(int stage, int value, struct s_ocp_qp_dim *dim); -// -void s_ocp_qp_dim_set_ng(int stage, int value, struct s_ocp_qp_dim *dim); -// -void s_ocp_qp_dim_set_ns(int stage, int value, struct s_ocp_qp_dim *dim); -// -void s_ocp_qp_dim_set_nsbx(int stage, int value, struct s_ocp_qp_dim *dim); -// -void s_ocp_qp_dim_set_nsbu(int stage, int value, struct s_ocp_qp_dim *dim); -// -void s_ocp_qp_dim_set_nsg(int stage, int value, struct s_ocp_qp_dim *dim); -// -void s_ocp_qp_dim_set_nbxe(int stage, int value, struct s_ocp_qp_dim *dim); -// -void s_ocp_qp_dim_set_nbue(int stage, int value, struct s_ocp_qp_dim *dim); -// -void s_ocp_qp_dim_set_nge(int stage, int value, struct s_ocp_qp_dim *dim); -// -void s_ocp_qp_dim_get(struct s_ocp_qp_dim *dim, char *field, int stage, int *value); -// -void s_ocp_qp_dim_get_N(struct s_ocp_qp_dim *dim, int *value); -// -void s_ocp_qp_dim_get_nx(struct s_ocp_qp_dim *dim, int stage, int *value); -// -void s_ocp_qp_dim_get_nu(struct s_ocp_qp_dim *dim, int stage, int *value); -// -void s_ocp_qp_dim_get_nbx(struct s_ocp_qp_dim *dim, int stage, int *value); -// -void s_ocp_qp_dim_get_nbu(struct s_ocp_qp_dim *dim, int stage, int *value); -// -void s_ocp_qp_dim_get_ng(struct s_ocp_qp_dim *dim, int stage, int *value); -// -void s_ocp_qp_dim_get_ns(struct s_ocp_qp_dim *dim, int stage, int *value); -// -void s_ocp_qp_dim_get_nsbx(struct s_ocp_qp_dim *dim, int stage, int *value); -// -void s_ocp_qp_dim_get_nsbu(struct s_ocp_qp_dim *dim, int stage, int *value); -// -void s_ocp_qp_dim_get_nsg(struct s_ocp_qp_dim *dim, int stage, int *value); -// -void s_ocp_qp_dim_get_nbxe(struct s_ocp_qp_dim *dim, int stage, int *value); -// -void s_ocp_qp_dim_get_nbue(struct s_ocp_qp_dim *dim, int stage, int *value); -// -void s_ocp_qp_dim_get_nge(struct s_ocp_qp_dim *dim, int stage, int *value); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_S_OCP_QP_DIM_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp_ipm.h b/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp_ipm.h deleted file mode 100644 index 11f3c47..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp_ipm.h +++ /dev/null @@ -1,250 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_OCP_QP_IPM_H_ -#define HPIPM_S_OCP_QP_IPM_H_ - - - -#include -#include - -#include -#include -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_ocp_qp_ipm_arg - { - float mu0; // initial value for complementarity slackness - float alpha_min; // exit cond on step length - float res_g_max; // exit cond on inf norm of residuals - float res_b_max; // exit cond on inf norm of residuals - float res_d_max; // exit cond on inf norm of residuals - float res_m_max; // exit cond on inf norm of residuals - float reg_prim; // reg of primal hessian - float lam_min; // min value in lam vector - float t_min; // min value in t vector - float tau_min; // min value of barrier parameter - int iter_max; // exit cond in iter number - int stat_max; // iterations saved in stat - int pred_corr; // use Mehrotra's predictor-corrector IPM algirthm - int cond_pred_corr; // conditional Mehrotra's predictor-corrector - int itref_pred_max; // max number of iterative refinement steps for predictor step - int itref_corr_max; // max number of iterative refinement steps for corrector step - int warm_start; // 0 no warm start, 1 warm start primal sol, 2 warm start primal and dual sol - int square_root_alg; // 0 classical Riccati, 1 square-root Riccati - int lq_fact; // 0 syrk+potrf, 1 mix, 2 lq (for square_root_alg==1) - int abs_form; // absolute IPM formulation - int comp_dual_sol_eq; // dual solution of equality constraints (only for abs_form==1) - int comp_res_exit; // compute residuals on exit (only for abs_form==1 and comp_dual_sol_eq==1) - int comp_res_pred; // compute residuals of prediction - int split_step; // use different steps for primal and dual variables - int var_init_scheme; // variables initialization scheme - int t_lam_min; // clip t and lam: 0 no, 1 in Gamma computation, 2 in solution - int mode; - hpipm_size_t memsize; - }; - - - -struct s_ocp_qp_ipm_ws - { - struct s_core_qp_ipm_workspace *core_workspace; - struct s_ocp_qp_res_ws *res_workspace; - struct s_ocp_qp_dim *dim; // cache dim - struct s_ocp_qp_sol *sol_step; - struct s_ocp_qp_sol *sol_itref; - struct s_ocp_qp *qp_step; - struct s_ocp_qp *qp_itref; - struct s_ocp_qp_res *res; - struct s_ocp_qp_res *res_itref; - struct blasfeo_svec *Gamma; // hessian update - struct blasfeo_svec *gamma; // hessian update - struct blasfeo_svec *tmp_nuxM; // work space of size nxM - struct blasfeo_svec *tmp_nbgM; // work space of size nbM+ngM - struct blasfeo_svec *tmp_nsM; // work space of size nsM - struct blasfeo_svec *Pb; // Pb - struct blasfeo_svec *Zs_inv; - struct blasfeo_svec *tmp_m; - struct blasfeo_svec *l; // cache linear part for _get_ric_xxx - struct blasfeo_smat *L; - struct blasfeo_smat *Ls; - struct blasfeo_smat *P; - struct blasfeo_smat *Lh; - struct blasfeo_smat *AL; - struct blasfeo_smat *lq0; - struct blasfeo_smat *tmp_nxM_nxM; - float *stat; // convergence statistics - int *use_hess_fact; - void *lq_work0; - float qp_res[4]; // infinity norm of residuals - int iter; // iteration number - int stat_max; // iterations saved in stat - int stat_m; // number of recorded stat per IPM iter - int use_Pb; - int status; // solver status - int square_root_alg; // cache from arg - int lq_fact; // cache from arg - int mask_constr; // use constr mask - int valid_ric_vec; // meaningful riccati vectors - int valid_ric_p; // form of riccati p: 0 p*inv(L), 1 p - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_ocp_qp_ipm_arg_strsize(); -// -hpipm_size_t s_ocp_qp_ipm_arg_memsize(struct s_ocp_qp_dim *ocp_dim); -// -void s_ocp_qp_ipm_arg_create(struct s_ocp_qp_dim *ocp_dim, struct s_ocp_qp_ipm_arg *arg, void *mem); -// -void s_ocp_qp_ipm_arg_set_default(enum hpipm_mode mode, struct s_ocp_qp_ipm_arg *arg); -// -void s_ocp_qp_ipm_arg_set(char *field, void *value, struct s_ocp_qp_ipm_arg *arg); -// set maximum number of iterations -void s_ocp_qp_ipm_arg_set_iter_max(int *iter_max, struct s_ocp_qp_ipm_arg *arg); -// set minimum step lenght -void s_ocp_qp_ipm_arg_set_alpha_min(float *alpha_min, struct s_ocp_qp_ipm_arg *arg); -// set initial value of barrier parameter -void s_ocp_qp_ipm_arg_set_mu0(float *mu0, struct s_ocp_qp_ipm_arg *arg); -// set exit tolerance on stationarity condition -void s_ocp_qp_ipm_arg_set_tol_stat(float *tol_stat, struct s_ocp_qp_ipm_arg *arg); -// set exit tolerance on equality constr -void s_ocp_qp_ipm_arg_set_tol_eq(float *tol_eq, struct s_ocp_qp_ipm_arg *arg); -// set exit tolerance on inequality constr -void s_ocp_qp_ipm_arg_set_tol_ineq(float *tol_ineq, struct s_ocp_qp_ipm_arg *arg); -// set exit tolerance on complementarity condition -void s_ocp_qp_ipm_arg_set_tol_comp(float *tol_comp, struct s_ocp_qp_ipm_arg *arg); -// set regularization of primal variables -void s_ocp_qp_ipm_arg_set_reg_prim(float *tol_comp, struct s_ocp_qp_ipm_arg *arg); -// set warm start: 0 no warm start, 1 primal var -void s_ocp_qp_ipm_arg_set_warm_start(int *warm_start, struct s_ocp_qp_ipm_arg *arg); -// Mehrotra's predictor-corrector IPM algorithm: 0 no predictor-corrector, 1 use predictor-corrector -void s_ocp_qp_ipm_arg_set_pred_corr(int *pred_corr, struct s_ocp_qp_ipm_arg *arg); -// conditional predictor-corrector: 0 no conditinal predictor-corrector, 1 conditional predictor-corrector -void s_ocp_qp_ipm_arg_set_cond_pred_corr(int *value, struct s_ocp_qp_ipm_arg *arg); -// set riccati algorithm: 0 classic, 1 square-root -void s_ocp_qp_ipm_arg_set_ric_alg(int *alg, struct s_ocp_qp_ipm_arg *arg); -// dual solution of equality constraints (only for abs_form==1) -void s_ocp_qp_ipm_arg_set_comp_dual_sol_eq(int *value, struct s_ocp_qp_ipm_arg *arg); -// compute residuals after solution -void s_ocp_qp_ipm_arg_set_comp_res_exit(int *value, struct s_ocp_qp_ipm_arg *arg); -// compute residuals of prediction -void s_ocp_qp_ipm_arg_set_comp_res_pred(int *alg, struct s_ocp_qp_ipm_arg *arg); -// min value of lam in the solution -void s_ocp_qp_ipm_arg_set_lam_min(float *value, struct s_ocp_qp_ipm_arg *arg); -// min value of t in the solution -void s_ocp_qp_ipm_arg_set_t_min(float *value, struct s_ocp_qp_ipm_arg *arg); -// min value of tau in the solution -void s_ocp_qp_ipm_arg_set_tau_min(float *value, struct s_ocp_qp_ipm_arg *arg); -// set split step: 0 same step, 1 different step for primal and dual variables -void s_ocp_qp_ipm_arg_set_split_step(int *value, struct s_ocp_qp_ipm_arg *arg); -// variables initialization scheme -void s_ocp_qp_ipm_arg_set_var_init_scheme(int *value, struct s_ocp_qp_ipm_arg *arg); -// clip t and lam: 0 no, 1 in Gamma computation, 2 in solution -void s_ocp_qp_ipm_arg_set_t_lam_min(int *value, struct s_ocp_qp_ipm_arg *arg); - -// -hpipm_size_t s_ocp_qp_ipm_ws_strsize(); -// -hpipm_size_t s_ocp_qp_ipm_ws_memsize(struct s_ocp_qp_dim *ocp_dim, struct s_ocp_qp_ipm_arg *arg); -// -void s_ocp_qp_ipm_ws_create(struct s_ocp_qp_dim *ocp_dim, struct s_ocp_qp_ipm_arg *arg, struct s_ocp_qp_ipm_ws *ws, void *mem); -// -void s_ocp_qp_ipm_get(char *field, struct s_ocp_qp_ipm_ws *ws, void *value); -// -void s_ocp_qp_ipm_get_status(struct s_ocp_qp_ipm_ws *ws, int *status); -// -void s_ocp_qp_ipm_get_iter(struct s_ocp_qp_ipm_ws *ws, int *iter); -// -void s_ocp_qp_ipm_get_max_res_stat(struct s_ocp_qp_ipm_ws *ws, float *res_stat); -// -void s_ocp_qp_ipm_get_max_res_eq(struct s_ocp_qp_ipm_ws *ws, float *res_eq); -// -void s_ocp_qp_ipm_get_max_res_ineq(struct s_ocp_qp_ipm_ws *ws, float *res_ineq); -// -void s_ocp_qp_ipm_get_max_res_comp(struct s_ocp_qp_ipm_ws *ws, float *res_comp); -// -void s_ocp_qp_ipm_get_stat(struct s_ocp_qp_ipm_ws *ws, float **stat); -// -void s_ocp_qp_ipm_get_stat_m(struct s_ocp_qp_ipm_ws *ws, int *stat_m); -// -void s_ocp_qp_ipm_get_ric_Lr(struct s_ocp_qp *qp, struct s_ocp_qp_ipm_arg *arg, struct s_ocp_qp_ipm_ws *ws, int stage, float *Lr); -// -void s_ocp_qp_ipm_get_ric_Ls(struct s_ocp_qp *qp, struct s_ocp_qp_ipm_arg *arg, struct s_ocp_qp_ipm_ws *ws, int stage, float *Ls); -// -void s_ocp_qp_ipm_get_ric_P(struct s_ocp_qp *qp, struct s_ocp_qp_ipm_arg *arg, struct s_ocp_qp_ipm_ws *ws, int stage, float *P); -// -void s_ocp_qp_ipm_get_ric_lr(struct s_ocp_qp *qp, struct s_ocp_qp_ipm_arg *arg, struct s_ocp_qp_ipm_ws *ws, int stage, float *lr); -// -void s_ocp_qp_ipm_get_ric_p(struct s_ocp_qp *qp, struct s_ocp_qp_ipm_arg *arg, struct s_ocp_qp_ipm_ws *ws, int stage, float *p); -// feedback control gain in the form u = K x + k -void s_ocp_qp_ipm_get_ric_K(struct s_ocp_qp *qp, struct s_ocp_qp_ipm_arg *arg, struct s_ocp_qp_ipm_ws *ws, int stage, float *K); -// feedback control gain in the form u = K x + k -void s_ocp_qp_ipm_get_ric_k(struct s_ocp_qp *qp, struct s_ocp_qp_ipm_arg *arg, struct s_ocp_qp_ipm_ws *ws, int stage, float *k); -// -void s_ocp_qp_init_var(struct s_ocp_qp *qp, struct s_ocp_qp_sol *qp_sol, struct s_ocp_qp_ipm_arg *arg, struct s_ocp_qp_ipm_ws *ws); -// -void s_ocp_qp_ipm_abs_step(int kk, struct s_ocp_qp *qp, struct s_ocp_qp_sol *qp_sol, struct s_ocp_qp_ipm_arg *arg, struct s_ocp_qp_ipm_ws *ws); -// -void s_ocp_qp_ipm_delta_step(int kk, struct s_ocp_qp *qp, struct s_ocp_qp_sol *qp_sol, struct s_ocp_qp_ipm_arg *arg, struct s_ocp_qp_ipm_ws *ws); -// -void s_ocp_qp_ipm_solve(struct s_ocp_qp *qp, struct s_ocp_qp_sol *qp_sol, struct s_ocp_qp_ipm_arg *arg, struct s_ocp_qp_ipm_ws *ws); -// -void s_ocp_qp_ipm_predict(struct s_ocp_qp *qp, struct s_ocp_qp_sol *qp_sol, struct s_ocp_qp_ipm_arg *arg, struct s_ocp_qp_ipm_ws *ws); -// -void s_ocp_qp_ipm_sens(struct s_ocp_qp *qp, struct s_ocp_qp_sol *qp_sol, struct s_ocp_qp_ipm_arg *arg, struct s_ocp_qp_ipm_ws *ws); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_S_OCP_QP_IPM_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp_kkt.h b/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp_kkt.h deleted file mode 100644 index 3eb1f4a..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp_kkt.h +++ /dev/null @@ -1,66 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - -#ifndef HPIPM_S_OCP_QP_KKT_H_ -#define HPIPM_S_OCP_QP_KKT_H_ - -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - -// -void s_ocp_qp_fact_solve_kkt_unconstr(struct s_ocp_qp *qp, struct s_ocp_qp_sol *qp_sol, struct s_ocp_qp_ipm_arg *arg, struct s_ocp_qp_ipm_ws *ws); -// -void s_ocp_qp_fact_solve_kkt_step(struct s_ocp_qp *qp, struct s_ocp_qp_sol *qp_sol, struct s_ocp_qp_ipm_arg *arg, struct s_ocp_qp_ipm_ws *ws); -// -void s_ocp_qp_fact_lq_solve_kkt_step(struct s_ocp_qp *qp, struct s_ocp_qp_sol *qp_sol, struct s_ocp_qp_ipm_arg *arg, struct s_ocp_qp_ipm_ws *ws); -// -void s_ocp_qp_solve_kkt_step(struct s_ocp_qp *qp, struct s_ocp_qp_sol *qp_sol, struct s_ocp_qp_ipm_arg *arg, struct s_ocp_qp_ipm_ws *ws); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - -#endif // HPIPM_S_OCP_QP_KKT_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp_red.h b/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp_red.h deleted file mode 100644 index 5a7b3b0..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp_red.h +++ /dev/null @@ -1,118 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_OCP_QP_RED_H_ -#define HPIPM_S_OCP_QP_RED_H_ - - - -#include -#include - -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_ocp_qp_reduce_eq_dof_arg - { - float lam_min; - float t_min; - int alias_unchanged; // do not keep copy unchanged stage - int comp_prim_sol; // primal solution (v) - int comp_dual_sol_eq; // dual solution equality constr (pi) - int comp_dual_sol_ineq; // dual solution inequality constr (lam t) - hpipm_size_t memsize; // memory size in bytes - }; - - - -struct s_ocp_qp_reduce_eq_dof_ws - { - struct blasfeo_svec *tmp_nuxM; - struct blasfeo_svec *tmp_nbgM; - int *e_imask_ux; - int *e_imask_d; - hpipm_size_t memsize; // memory size in bytes - }; - - - -// -void s_ocp_qp_dim_reduce_eq_dof(struct s_ocp_qp_dim *dim, struct s_ocp_qp_dim *dim_red); -// -hpipm_size_t s_ocp_qp_reduce_eq_dof_arg_memsize(); -// -void s_ocp_qp_reduce_eq_dof_arg_create(struct s_ocp_qp_reduce_eq_dof_arg *arg, void *mem); -// -void s_ocp_qp_reduce_eq_dof_arg_set_default(struct s_ocp_qp_reduce_eq_dof_arg *arg); -// -void s_ocp_qp_reduce_eq_dof_arg_set_alias_unchanged(struct s_ocp_qp_reduce_eq_dof_arg *arg, int value); -// -void s_ocp_qp_reduce_eq_dof_arg_set_comp_prim_sol(struct s_ocp_qp_reduce_eq_dof_arg *arg, int value); -// -void s_ocp_qp_reduce_eq_dof_arg_set_comp_dual_sol_eq(struct s_ocp_qp_reduce_eq_dof_arg *arg, int value); -// -void s_ocp_qp_reduce_eq_dof_arg_set_comp_dual_sol_ineq(struct s_ocp_qp_reduce_eq_dof_arg *arg, int value); -// -hpipm_size_t s_ocp_qp_reduce_eq_dof_ws_memsize(struct s_ocp_qp_dim *dim); -// -void s_ocp_qp_reduce_eq_dof_ws_create(struct s_ocp_qp_dim *dim, struct s_ocp_qp_reduce_eq_dof_ws *work, void *mem); -// -void s_ocp_qp_reduce_eq_dof(struct s_ocp_qp *qp, struct s_ocp_qp *qp_red, struct s_ocp_qp_reduce_eq_dof_arg *arg, struct s_ocp_qp_reduce_eq_dof_ws *work); -// -void s_ocp_qp_reduce_eq_dof_lhs(struct s_ocp_qp *qp, struct s_ocp_qp *qp_red, struct s_ocp_qp_reduce_eq_dof_arg *arg, struct s_ocp_qp_reduce_eq_dof_ws *work); -// -void s_ocp_qp_reduce_eq_dof_rhs(struct s_ocp_qp *qp, struct s_ocp_qp *qp_red, struct s_ocp_qp_reduce_eq_dof_arg *arg, struct s_ocp_qp_reduce_eq_dof_ws *work); -// -void s_ocp_qp_restore_eq_dof(struct s_ocp_qp *qp, struct s_ocp_qp_sol *qp_sol_red, struct s_ocp_qp_sol *qp_sol, struct s_ocp_qp_reduce_eq_dof_arg *arg, struct s_ocp_qp_reduce_eq_dof_ws *work); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_S_OCP_QP_RED_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp_res.h b/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp_res.h deleted file mode 100644 index 821585d..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp_res.h +++ /dev/null @@ -1,114 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_OCP_QP_RES_H_ -#define HPIPM_S_OCP_QP_RES_H_ - - - -#include -#include - -#include -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_ocp_qp_res - { - struct s_ocp_qp_dim *dim; - struct blasfeo_svec *res_g; // q-residuals - struct blasfeo_svec *res_b; // b-residuals - struct blasfeo_svec *res_d; // d-residuals - struct blasfeo_svec *res_m; // m-residuals - float res_max[4]; // max of residuals - float res_mu; // mu-residual - hpipm_size_t memsize; - }; - - - -struct s_ocp_qp_res_ws - { - struct blasfeo_svec *tmp_nbgM; // work space of size nbM+ngM - struct blasfeo_svec *tmp_nsM; // work space of size nsM - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_ocp_qp_res_memsize(struct s_ocp_qp_dim *ocp_dim); -// -void s_ocp_qp_res_create(struct s_ocp_qp_dim *ocp_dim, struct s_ocp_qp_res *res, void *mem); -// -hpipm_size_t s_ocp_qp_res_ws_memsize(struct s_ocp_qp_dim *ocp_dim); -// -void s_ocp_qp_res_ws_create(struct s_ocp_qp_dim *ocp_dim, struct s_ocp_qp_res_ws *workspace, void *mem); -// -void s_ocp_qp_res_compute(struct s_ocp_qp *qp, struct s_ocp_qp_sol *qp_sol, struct s_ocp_qp_res *res, struct s_ocp_qp_res_ws *ws); -// -void s_ocp_qp_res_compute_lin(struct s_ocp_qp *qp, struct s_ocp_qp_sol *qp_sol, struct s_ocp_qp_sol *qp_step, struct s_ocp_qp_res *res, struct s_ocp_qp_res_ws *ws); -// -void s_ocp_qp_res_compute_inf_norm(struct s_ocp_qp_res *res); -// -void s_ocp_qp_res_get_all(struct s_ocp_qp_res *res, float **res_r, float **res_q, float **res_ls, float **res_us, float **res_b, float **res_d_lb, float **res_d_ub, float **res_d_lg, float **res_d_ug, float **res_d_ls, float **res_d_us, float **res_m_lb, float **res_m_ub, float **res_m_lg, float **res_m_ug, float **res_m_ls, float **res_m_us); -// -void s_ocp_qp_res_get_max_res_stat(struct s_ocp_qp_res *res, float *value); -// -void s_ocp_qp_res_get_max_res_eq(struct s_ocp_qp_res *res, float *value); -// -void s_ocp_qp_res_get_max_res_ineq(struct s_ocp_qp_res *res, float *value); -// -void s_ocp_qp_res_get_max_res_comp(struct s_ocp_qp_res *res, float *value); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - -#endif // HPIPM_S_OCP_QP_RES_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp_sol.h b/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp_sol.h deleted file mode 100644 index 94dfa0d..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp_sol.h +++ /dev/null @@ -1,128 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_OCP_QP_SOL_H_ -#define HPIPM_S_OCP_QP_SOL_H_ - - - -#include -#include - -#include "hpipm_s_ocp_qp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_ocp_qp_sol - { - struct s_ocp_qp_dim *dim; - struct blasfeo_svec *ux; - struct blasfeo_svec *pi; - struct blasfeo_svec *lam; - struct blasfeo_svec *t; - void *misc; - hpipm_size_t memsize; // memory size in bytes - }; - - - -// -hpipm_size_t s_ocp_qp_sol_strsize(); -// -hpipm_size_t s_ocp_qp_sol_memsize(struct s_ocp_qp_dim *dim); -// -void s_ocp_qp_sol_create(struct s_ocp_qp_dim *dim, struct s_ocp_qp_sol *qp_sol, void *memory); -// -void s_ocp_qp_sol_copy_all(struct s_ocp_qp_sol *qp_sol_orig, struct s_ocp_qp_sol *qp_sol_dest); -// -void s_qp_sol_get_all(struct s_ocp_qp_sol *qp_sol, float **u, float **x, float **ls, float **us, float **pi, float **lam_lb, float **lam_ub, float **lam_lg, float **lam_ug, float **lam_ls, float **lam_us); -// -void s_qp_sol_get_all_rowmaj(struct s_ocp_qp_sol *qp_sol, float **u, float **x, float **ls, float **us, float **pi, float **lam_lb, float **lam_ub, float **lam_lg, float **lam_ug, float **lam_ls, float **lam_us); -// -void s_ocp_qp_sol_set_all(float **u, float **x, float **ls, float **us, float **pi, float **lam_lb, float **lam_ub, float **lam_lg, float **lam_ug, float **lam_ls, float **lam_us, struct s_ocp_qp_sol *qp_sol); -// -void s_ocp_qp_sol_get(char *field, int stage, struct s_ocp_qp_sol *qp_sol, float *vec); -// -void s_ocp_qp_sol_get_u(int stage, struct s_ocp_qp_sol *qp_sol, float *vec); -// -void s_ocp_qp_sol_get_x(int stage, struct s_ocp_qp_sol *qp_sol, float *vec); -// -void s_ocp_qp_sol_get_sl(int stage, struct s_ocp_qp_sol *qp_sol, float *vec); -// -void s_ocp_qp_sol_get_su(int stage, struct s_ocp_qp_sol *qp_sol, float *vec); -// -void s_ocp_qp_sol_get_pi(int stage, struct s_ocp_qp_sol *qp_sol, float *vec); -// -void s_ocp_qp_sol_get_lam_lb(int stage, struct s_ocp_qp_sol *qp_sol, float *vec); -// -void s_ocp_qp_sol_get_lam_lbu(int stage, struct s_ocp_qp_sol *qp_sol, float *vec); -// -void s_ocp_qp_sol_get_lam_lbx(int stage, struct s_ocp_qp_sol *qp_sol, float *vec); -// -void s_ocp_qp_sol_get_lam_ub(int stage, struct s_ocp_qp_sol *qp_sol, float *vec); -// -void s_ocp_qp_sol_get_lam_ubu(int stage, struct s_ocp_qp_sol *qp_sol, float *vec); -// -void s_ocp_qp_sol_get_lam_ubx(int stage, struct s_ocp_qp_sol *qp_sol, float *vec); -// -void s_ocp_qp_sol_get_lam_lg(int stage, struct s_ocp_qp_sol *qp_sol, float *vec); -// -void s_ocp_qp_sol_get_lam_ug(int stage, struct s_ocp_qp_sol *qp_sol, float *vec); -// -void s_ocp_qp_sol_set(char *field, int stage, float *vec, struct s_ocp_qp_sol *qp_sol); -// -void s_ocp_qp_sol_set_u(int stage, float *vec, struct s_ocp_qp_sol *qp_sol); -// -void s_ocp_qp_sol_set_x(int stage, float *vec, struct s_ocp_qp_sol *qp_sol); -// -void s_ocp_qp_sol_set_sl(int stage, float *vec, struct s_ocp_qp_sol *qp_sol); -// -void s_ocp_qp_sol_set_su(int stage, float *vec, struct s_ocp_qp_sol *qp_sol); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_S_OCP_QP_SOL_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp_utils.h b/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp_utils.h deleted file mode 100644 index a4f832a..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_ocp_qp_utils.h +++ /dev/null @@ -1,83 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_OCP_QP_UTILS_H_ -#define HPIPM_S_OCP_QP_UTILS_H_ - - - -#include -#include - -#include "hpipm_s_ocp_qp_dim.h" -#include "hpipm_s_ocp_qp.h" -#include "hpipm_s_ocp_qp_sol.h" -#include "hpipm_s_ocp_qp_ipm.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -// -void s_ocp_qp_dim_print(struct s_ocp_qp_dim *qp_dim); -// -void s_ocp_qp_dim_codegen(char *file_name, char *mode, struct s_ocp_qp_dim *qp_dim); -// -void s_ocp_qp_print(struct s_ocp_qp_dim *qp_dim, struct s_ocp_qp *qp); -// -void s_ocp_qp_codegen(char *file_name, char *mode, struct s_ocp_qp_dim *qp_dim, struct s_ocp_qp *qp); -// -void s_ocp_qp_sol_print(struct s_ocp_qp_dim *qp_dim, struct s_ocp_qp_sol *ocp_qp_sol); -// -void s_ocp_qp_ipm_arg_print(struct s_ocp_qp_dim *qp_dim, struct s_ocp_qp_ipm_arg *arg); -// -void s_ocp_qp_ipm_arg_codegen(char *file_name, char *mode, struct s_ocp_qp_dim *qp_dim, struct s_ocp_qp_ipm_arg *arg); -// -void s_ocp_qp_res_print(struct s_ocp_qp_dim *qp_dim, struct s_ocp_qp_res *ocp_qp_res); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_D_OCP_QP_UTILS_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_part_cond.h b/third_party/acados/include/hpipm/include/hpipm_s_part_cond.h deleted file mode 100644 index e40511e..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_part_cond.h +++ /dev/null @@ -1,115 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_S_PART_COND_H_ -#define HPIPM_S_PART_COND_H_ - - - -#include -#include - -#include "hpipm_s_cond.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_part_cond_qp_arg - { - struct s_cond_qp_arg *cond_arg; - int N2; - hpipm_size_t memsize; - }; - - - -struct s_part_cond_qp_ws - { - struct s_cond_qp_ws *cond_workspace; - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_part_cond_qp_arg_memsize(int N2); -// -void s_part_cond_qp_arg_create(int N2, struct s_part_cond_qp_arg *cond_arg, void *mem); -// -void s_part_cond_qp_arg_set_default(struct s_part_cond_qp_arg *cond_arg); -// set riccati-like algorithm: 0 classical, 1 squre-root -void s_part_cond_qp_arg_set_ric_alg(int ric_alg, struct s_part_cond_qp_arg *cond_arg); -// -void s_part_cond_qp_arg_set_comp_prim_sol(int value, struct s_part_cond_qp_arg *cond_arg); -// -void s_part_cond_qp_arg_set_comp_dual_sol_eq(int value, struct s_part_cond_qp_arg *cond_arg); -// -void s_part_cond_qp_arg_set_comp_dual_sol_ineq(int value, struct s_part_cond_qp_arg *cond_arg); - -// -void s_part_cond_qp_compute_block_size(int N, int N2, int *block_size); -// -void s_part_cond_qp_compute_dim(struct s_ocp_qp_dim *ocp_dim, int *block_size, struct s_ocp_qp_dim *part_dense_dim); -// -hpipm_size_t s_part_cond_qp_ws_memsize(struct s_ocp_qp_dim *ocp_dim, int *block_size, struct s_ocp_qp_dim *part_dense_dim, struct s_part_cond_qp_arg *cond_arg); -// -void s_part_cond_qp_ws_create(struct s_ocp_qp_dim *ocp_dim, int *block_size, struct s_ocp_qp_dim *part_dense_dim, struct s_part_cond_qp_arg *cond_arg, struct s_part_cond_qp_ws *cond_ws, void *mem); -// -void s_part_cond_qp_cond(struct s_ocp_qp *ocp_qp, struct s_ocp_qp *part_dense_qp, struct s_part_cond_qp_arg *cond_arg, struct s_part_cond_qp_ws *cond_ws); -// -void s_part_cond_qp_cond_lhs(struct s_ocp_qp *ocp_qp, struct s_ocp_qp *part_dense_qp, struct s_part_cond_qp_arg *cond_arg, struct s_part_cond_qp_ws *cond_ws); -// -void s_part_cond_qp_cond_rhs(struct s_ocp_qp *ocp_qp, struct s_ocp_qp *part_dense_qp, struct s_part_cond_qp_arg *cond_arg, struct s_part_cond_qp_ws *cond_ws); -// -void s_part_cond_qp_expand_sol(struct s_ocp_qp *ocp_qp, struct s_ocp_qp *part_dense_qp, struct s_ocp_qp_sol *part_dense_qp_sol, struct s_ocp_qp_sol *ocp_qp_sol, struct s_part_cond_qp_arg *cond_arg, struct s_part_cond_qp_ws *cond_ws); - -// -void s_part_cond_qp_update(int *idxc, struct s_ocp_qp *ocp_qp, struct s_ocp_qp *part_dense_qp, struct s_part_cond_qp_arg *cond_arg, struct s_part_cond_qp_ws *cond_ws); - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_S_PART_COND_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_s_part_cond_qcqp.h b/third_party/acados/include/hpipm/include/hpipm_s_part_cond_qcqp.h deleted file mode 100644 index 311f700..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_part_cond_qcqp.h +++ /dev/null @@ -1,107 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_S_PART_COND_QCQP_H_ -#define HPIPM_S_PART_COND_QCQP_H_ - - - -#include -#include - -#include "hpipm_s_cond_qcqp.h" - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_part_cond_qcqp_arg - { - struct s_cond_qcqp_arg *cond_arg; - int N2; - hpipm_size_t memsize; - }; - - - -struct s_part_cond_qcqp_ws - { - struct s_cond_qcqp_ws *cond_ws; - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_part_cond_qcqp_arg_memsize(int N2); -// -void s_part_cond_qcqp_arg_create(int N2, struct s_part_cond_qcqp_arg *cond_arg, void *mem); -// -void s_part_cond_qcqp_arg_set_default(struct s_part_cond_qcqp_arg *cond_arg); -// set riccati-like algorithm: 0 classical, 1 squre-root -void s_part_cond_qcqp_arg_set_ric_alg(int ric_alg, struct s_part_cond_qcqp_arg *cond_arg); - -// -void s_part_cond_qcqp_compute_block_size(int N, int N2, int *block_size); -// -void s_part_cond_qcqp_compute_dim(struct s_ocp_qcqp_dim *ocp_dim, int *block_size, struct s_ocp_qcqp_dim *part_dense_dim); -// -hpipm_size_t s_part_cond_qcqp_ws_memsize(struct s_ocp_qcqp_dim *ocp_dim, int *block_size, struct s_ocp_qcqp_dim *part_dense_dim, struct s_part_cond_qcqp_arg *cond_arg); -// -void s_part_cond_qcqp_ws_create(struct s_ocp_qcqp_dim *ocp_dim, int *block_size, struct s_ocp_qcqp_dim *part_dense_dim, struct s_part_cond_qcqp_arg *cond_arg, struct s_part_cond_qcqp_ws *cond_ws, void *mem); -// -void s_part_cond_qcqp_cond(struct s_ocp_qcqp *ocp_qp, struct s_ocp_qcqp *part_dense_qp, struct s_part_cond_qcqp_arg *cond_arg, struct s_part_cond_qcqp_ws *cond_ws); -// -void s_part_cond_qcqp_cond_lhs(struct s_ocp_qcqp *ocp_qp, struct s_ocp_qcqp *part_dense_qp, struct s_part_cond_qcqp_arg *cond_arg, struct s_part_cond_qcqp_ws *cond_ws); -// -void s_part_cond_qcqp_cond_rhs(struct s_ocp_qcqp *ocp_qp, struct s_ocp_qcqp *part_dense_qp, struct s_part_cond_qcqp_arg *cond_arg, struct s_part_cond_qcqp_ws *cond_ws); -// -void s_part_cond_qcqp_expand_sol(struct s_ocp_qcqp *ocp_qp, struct s_ocp_qcqp *part_dense_qp, struct s_ocp_qcqp_sol *part_dense_qp_sol, struct s_ocp_qcqp_sol *ocp_qp_sol, struct s_part_cond_qcqp_arg *cond_arg, struct s_part_cond_qcqp_ws *cond_ws); - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_D_PART_COND_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_sim_erk.h b/third_party/acados/include/hpipm/include/hpipm_s_sim_erk.h deleted file mode 100644 index 1a05ad1..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_sim_erk.h +++ /dev/null @@ -1,121 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_SIM_ERK_H_ -#define HPIPM_S_SIM_ERK_H_ - -#ifdef __cplusplus -extern "C" { -#endif - -struct s_sim_erk_arg - { - struct s_sim_rk_data *rk_data; // integrator data - float h; // step size - int steps; // number of steps -// int for_sens; // compute adjoint sensitivities -// int adj_sens; // compute adjoint sensitivities - hpipm_size_t memsize; - }; - - - -struct s_sim_erk_ws - { - void (*ode)(int t, float *x, float *p, void *ode_args, float *xdot); // function pointer to ode - void (*vde_for)(int t, float *x, float *p, void *ode_args, float *xdot); // function pointer to forward vde - void (*vde_adj)(int t, float *adj_in, void *ode_args, float *adj_out); // function pointer to adjoint vde - void *ode_args; // pointer to ode args - struct s_sim_erk_arg *erk_arg; // erk arg - float *K; // internal variables - float *x_for; // states and forward sensitivities - float *x_traj; // states at all steps - float *l; // adjoint sensitivities - float *p; // parameter - float *x_tmp; // temporary states and forward sensitivities - float *adj_in; - float *adj_tmp; - int nx; // number of states - int np; // number of parameters - int nf; // number of forward sensitivities - int na; // number of adjoint sensitivities - int nf_max; // max number of forward sensitivities - int na_max; // max number of adjoint sensitivities - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_sim_erk_arg_memsize(); -// -void s_sim_erk_arg_create(struct s_sim_erk_arg *erk_arg, void *mem); -// -void s_sim_erk_arg_set_all(struct s_sim_rk_data *rk_data, float h, int steps, struct s_sim_erk_arg *erk_arg); - -// -hpipm_size_t s_sim_erk_ws_memsize(struct s_sim_erk_arg *erk_arg, int nx, int np, int nf_max, int na_max); -// -void s_sim_erk_ws_create(struct s_sim_erk_arg *erk_arg, int nx, int np, int nf_max, int na_max, struct s_sim_erk_ws *work, void *memory); -// -void s_sim_erk_ws_set_all(int nf, int na, float *x, float *fs, float *bs, float *p, void (*ode)(int t, float *x, float *p, void *ode_args, float *xdot), void (*vde_for)(int t, float *x, float *p, void *ode_args, float *xdot), void (*vde_adj)(int t, float *adj_in, void *ode_args, float *adj_out), void *ode_args, struct s_sim_erk_ws *work); -// number of directions for forward sensitivities -void s_sim_erk_ws_set_nf(int *nf, struct s_sim_erk_ws *work); -// parameters (e.g. inputs) -void s_sim_erk_ws_set_p(float *p, struct s_sim_erk_ws *work); -// state -void s_sim_erk_ws_set_x(float *x, struct s_sim_erk_ws *work); -// forward sensitivities -void s_sim_erk_ws_set_fs(float *fs, struct s_sim_erk_ws *work); -// ode funtion -void s_sim_erk_ws_set_ode(void (*ode)(int t, float *x, float *p, void *ode_args, float *xdot), struct s_sim_erk_ws *work); -// forward vde function -void s_sim_erk_ws_set_vde_for(void (*ode)(int t, float *x, float *p, void *ode_args, float *xdot), struct s_sim_erk_ws *work); -// ode_args, passed straight to the ode/vde_for/vde_adj functions -void s_sim_erk_ws_set_ode_args(void *ode_args, struct s_sim_erk_ws *work); -// state -void s_sim_erk_ws_get_x(struct s_sim_erk_ws *work, float *x); -// forward sensitivities -void s_sim_erk_ws_get_fs(struct s_sim_erk_ws *work, float *fs); -// -void s_sim_erk_solve(struct s_sim_erk_arg *arg, struct s_sim_erk_ws *work); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // HPIPM_D_SIM_ERK_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_sim_rk.h b/third_party/acados/include/hpipm/include/hpipm_s_sim_rk.h deleted file mode 100644 index 53acd71..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_sim_rk.h +++ /dev/null @@ -1,72 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_SIM_RK_H_ -#define HPIPM_S_SIM_RK_H_ - -#include "hpipm_common.h" - -#ifdef __cplusplus -extern "C" { -#endif - -struct s_sim_rk_data - { - float *A_rk; // A in butcher tableau - float *B_rk; // b in butcher tableau - float *C_rk; // c in butcher tableau - int expl; // erk vs irk - int ns; // number of stages - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_sim_rk_data_memsize(int ns); -// -void s_sim_rk_data_create(int ns, struct s_sim_rk_data *rk_data, void *memory); -// -void s_sim_rk_data_init_default(char *field, struct s_sim_rk_data *rk_data); -// -void s_sim_rk_data_set_all(int expl, float *A_rk, float *B_rk, float *C_rk, struct s_sim_rk_data *rk_data); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // HPIPM_S_SIM_RK_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qcqp.h b/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qcqp.h deleted file mode 100644 index 450e992..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qcqp.h +++ /dev/null @@ -1,213 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_TREE_OCP_QCQP_H_ -#define HPIPM_S_TREE_OCP_QCQP_H_ - - - -#include -#include - -#include "hpipm_s_tree_ocp_qcqp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_tree_ocp_qcqp - { - struct s_tree_ocp_qcqp_dim *dim; - struct blasfeo_smat *BAbt; // Nn-1 - struct blasfeo_smat *RSQrq; // Nn - struct blasfeo_smat *DCt; // Nn - struct blasfeo_smat **Hq; // Nn - struct blasfeo_svec *b; // Nn-1 - struct blasfeo_svec *rqz; // Nn - struct blasfeo_svec *d; // Nn - struct blasfeo_svec *d_mask; // Nn - struct blasfeo_svec *m; // Nn - struct blasfeo_svec *Z; // Nn - int **idxb; // indices of box constrained variables within [u; x] // Nn - int **idxs_rev; // index of soft constraints - hpipm_size_t memsize; // memory size in bytes - }; - - - -// -hpipm_size_t s_tree_ocp_qcqp_memsize(struct s_tree_ocp_qcqp_dim *dim); -// -void s_tree_ocp_qcqp_create(struct s_tree_ocp_qcqp_dim *dim, struct s_tree_ocp_qcqp *qp, void *memory); -// -void s_tree_ocp_qcqp_set_all(float **A, float **B, float **b, float **Q, float **S, float **R, float **q, float **r, int **idxb, float **d_lb, float **d_ub, float **C, float **D, float **d_lg, float **d_ug, float **Zl, float **Zu, float **zl, float **zu, int **idxs, float **d_ls, float **d_us, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set(char *field_name, int node_edge, void *value, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_A(int edge, float *mat, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_B(int edge, float *mat, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_b(int edge, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_Q(int node, float *mat, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_S(int node, float *mat, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_R(int node, float *mat, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_q(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_r(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_lb(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_lb_mask(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_ub(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_ub_mask(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_lbx(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_lbx_mask(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_ubx(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_ubx_mask(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_lbu(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_lbu_mask(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_ubu(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_ubu_mask(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_idxb(int node, int *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_idxbx(int node, int *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_Jbx(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_idxbu(int node, int *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_Jbu(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_C(int node, float *mat, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_D(int node, float *mat, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_lg(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_lg_mask(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_ug(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_ug_mask(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_Qq(int node, float *mat, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_Sq(int node, float *mat, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_Rq(int node, float *mat, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_qq(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_rq(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_uq(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_uq_mask(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_Zl(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_Zu(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_zl(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_zu(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_lls(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_lls_mask(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_lus(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_lus_mask(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_idxs(int node, int *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_idxs_rev(int node, int *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_Jsbu(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_Jsbx(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_Jsg(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_set_Jsq(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -//void s_tree_ocp_qcqp_set_idxe(int node, int *vec, struct s_tree_ocp_qcqp *qp); -// -//void s_tree_ocp_qcqp_set_idxbxe(int node, int *vec, struct s_tree_ocp_qcqp *qp); -// -//void s_tree_ocp_qcqp_set_idxbue(int node, int *vec, struct s_tree_ocp_qcqp *qp); -// -//void s_tree_ocp_qcqp_set_idxge(int node, int *vec, struct s_tree_ocp_qcqp *qp); -// -//void s_tree_ocp_qcqp_set_Jbxe(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -//void s_tree_ocp_qcqp_set_Jbue(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -//void s_tree_ocp_qcqp_set_Jge(int node, float *vec, struct s_tree_ocp_qcqp *qp); -// -//void s_tree_ocp_qcqp_set_diag_H_flag(int node, int *value, struct s_tree_ocp_qcqp *qp); - - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_S_TREE_OCP_QCQP_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qcqp_dim.h b/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qcqp_dim.h deleted file mode 100644 index 7a49d51..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qcqp_dim.h +++ /dev/null @@ -1,118 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_TREE_OCP_QCQP_DIM_H_ -#define HPIPM_S_TREE_OCP_QCQP_DIM_H_ - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_tree_ocp_qcqp_dim - { - struct s_tree_ocp_qp_dim *qp_dim; // dim of qp approximation - struct tree *ttree; // tree describing node conndection - int *nx; // number of states // Nn - int *nu; // number of inputs // Nn - int *nb; // number of box constraints // Nn - int *nbx; // number of state box constraints // Nn - int *nbu; // number of input box constraints // Nn - int *ng; // number of general constraints // Nn - int *nq; // number of (upper) quadratic constraints - int *ns; // number of soft constraints // Nn - int *nsbx; // number of soft state box constraints - int *nsbu; // number of soft input box constraints - int *nsg; // number of soft general constraints - int *nsq; // number of (upper) soft quadratic constraints - int Nn; // number of nodes - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_tree_ocp_qcqp_dim_strsize(); -// -hpipm_size_t s_tree_ocp_qcqp_dim_memsize(int Nn); -// -void s_tree_ocp_qcqp_dim_create(int Nn, struct s_tree_ocp_qcqp_dim *qp_dim, void *memory); -// -void s_tree_ocp_qcqp_dim_set_tree(struct tree *ttree, struct s_tree_ocp_qcqp_dim *dim); -// -void s_tree_ocp_qcqp_dim_set(char *field, int stage, int value, struct s_tree_ocp_qcqp_dim *dim); -// -void s_tree_ocp_qcqp_dim_set_nx(int stage, int value, struct s_tree_ocp_qcqp_dim *dim); -// -void s_tree_ocp_qcqp_dim_set_nu(int stage, int value, struct s_tree_ocp_qcqp_dim *dim); -// -void s_tree_ocp_qcqp_dim_set_nbx(int stage, int value, struct s_tree_ocp_qcqp_dim *dim); -// -void s_tree_ocp_qcqp_dim_set_nbu(int stage, int value, struct s_tree_ocp_qcqp_dim *dim); -// -void s_tree_ocp_qcqp_dim_set_ng(int stage, int value, struct s_tree_ocp_qcqp_dim *dim); -// -void s_tree_ocp_qcqp_dim_set_nq(int stage, int value, struct s_tree_ocp_qcqp_dim *dim); -// -void s_tree_ocp_qcqp_dim_set_ns(int stage, int value, struct s_tree_ocp_qcqp_dim *dim); -// -void s_tree_ocp_qcqp_dim_set_nsbx(int stage, int value, struct s_tree_ocp_qcqp_dim *dim); -// -void s_tree_ocp_qcqp_dim_set_nsbu(int stage, int value, struct s_tree_ocp_qcqp_dim *dim); -// -void s_tree_ocp_qcqp_dim_set_nsg(int stage, int value, struct s_tree_ocp_qcqp_dim *dim); -// -void s_tree_ocp_qcqp_dim_set_nsq(int stage, int value, struct s_tree_ocp_qcqp_dim *dim); -// -//void s_tree_ocp_qcqp_dim_set_nbxe(int stage, int value, struct s_tree_ocp_qcqp_dim *dim); -// -//void s_tree_ocp_qcqp_dim_set_nbue(int stage, int value, struct s_tree_ocp_qcqp_dim *dim); -// -//void s_tree_ocp_qcqp_dim_set_nge(int stage, int value, struct s_tree_ocp_qcqp_dim *dim); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_S_TREE_OCP_QCQP_DIM_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qcqp_ipm.h b/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qcqp_ipm.h deleted file mode 100644 index 69d6591..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qcqp_ipm.h +++ /dev/null @@ -1,192 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_TREE_OCP_QCQP_IPM_H_ -#define HPIPM_S_TREE_OCP_QCQP_IPM_H_ - - - -#include -#include - -#include -#include -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_tree_ocp_qcqp_ipm_arg - { - struct s_tree_ocp_qp_ipm_arg *qp_arg; - float mu0; // initial value for complementarity slackness - float alpha_min; // exit cond on step length - float res_g_max; // exit cond on inf norm of residuals - float res_b_max; // exit cond on inf norm of residuals - float res_d_max; // exit cond on inf norm of residuals - float res_m_max; // exit cond on inf norm of residuals - float reg_prim; // reg of primal hessian - float lam_min; // min value in lam vector - float t_min; // min value in t vector - int iter_max; // exit cond in iter number - int stat_max; // iterations saved in stat - int pred_corr; // use Mehrotra's predictor-corrector IPM algirthm - int cond_pred_corr; // conditional Mehrotra's predictor-corrector - int itref_pred_max; // max number of iterative refinement steps for predictor step - int itref_corr_max; // max number of iterative refinement steps for corrector step - int warm_start; // 0 no warm start, 1 warm start primal sol, 2 warm start primal and dual sol -// int square_root_alg; // 0 classical Riccati, 1 square-root Riccati - int lq_fact; // 0 syrk+potrf, 1 mix, 2 lq (for square_root_alg==1) - int abs_form; // absolute IPM formulation - int comp_dual_sol_eq; // dual solution of equality constraints (only for abs_form==1) - int comp_res_exit; // compute residuals on exit (only for abs_form==1 and comp_dual_sol_eq==1) -// int comp_res_pred; // compute residuals of prediction - int split_step; // use different step for primal and dual variables - int t_lam_min; // clip t and lam: 0 no, 1 in Gamma computation, 2 in solution - int mode; - hpipm_size_t memsize; - }; - - - -struct s_tree_ocp_qcqp_ipm_ws - { - struct s_tree_ocp_qp_ipm_ws *qp_ws; - struct s_tree_ocp_qp *qp; - struct s_tree_ocp_qp_sol *qp_sol; - struct s_tree_ocp_qcqp_res_ws *qcqp_res_ws; - struct s_tree_ocp_qcqp_res *qcqp_res; - struct blasfeo_svec *tmp_nuxM; - int iter; // iteration number - int status; - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_tree_ocp_qcqp_ipm_arg_strsize(); -// -hpipm_size_t s_tree_ocp_qcqp_ipm_arg_memsize(struct s_tree_ocp_qcqp_dim *ocp_dim); -// -void s_tree_ocp_qcqp_ipm_arg_create(struct s_tree_ocp_qcqp_dim *ocp_dim, struct s_tree_ocp_qcqp_ipm_arg *arg, void *mem); -// -void s_tree_ocp_qcqp_ipm_arg_set_default(enum hpipm_mode mode, struct s_tree_ocp_qcqp_ipm_arg *arg); -// -void s_tree_ocp_qcqp_ipm_arg_set(char *field, void *value, struct s_tree_ocp_qcqp_ipm_arg *arg); -// set maximum number of iterations -void s_tree_ocp_qcqp_ipm_arg_set_iter_max(int *value, struct s_tree_ocp_qcqp_ipm_arg *arg); -// set minimum step lenght -void s_tree_ocp_qcqp_ipm_arg_set_alpha_min(float *value, struct s_tree_ocp_qcqp_ipm_arg *arg); -// set initial value of barrier parameter -void s_tree_ocp_qcqp_ipm_arg_set_mu0(float *value, struct s_tree_ocp_qcqp_ipm_arg *arg); -// set exit tolerance on stationarity condition -void s_tree_ocp_qcqp_ipm_arg_set_tol_stat(float *value, struct s_tree_ocp_qcqp_ipm_arg *arg); -// set exit tolerance on equality constr -void s_tree_ocp_qcqp_ipm_arg_set_tol_eq(float *value, struct s_tree_ocp_qcqp_ipm_arg *arg); -// set exit tolerance on inequality constr -void s_tree_ocp_qcqp_ipm_arg_set_tol_ineq(float *value, struct s_tree_ocp_qcqp_ipm_arg *arg); -// set exit tolerance on complementarity condition -void s_tree_ocp_qcqp_ipm_arg_set_tol_comp(float *value, struct s_tree_ocp_qcqp_ipm_arg *arg); -// set regularization of primal variables -void s_tree_ocp_qcqp_ipm_arg_set_reg_prim(float *value, struct s_tree_ocp_qcqp_ipm_arg *arg); -// set warm start: 0 no warm start, 1 primal var -void s_tree_ocp_qcqp_ipm_arg_set_warm_start(int *value, struct s_tree_ocp_qcqp_ipm_arg *arg); -// Mehrotra's predictor-corrector IPM algorithm: 0 no predictor-corrector, 1 use predictor-corrector -void s_tree_ocp_qcqp_ipm_arg_set_pred_corr(int *value, struct s_tree_ocp_qcqp_ipm_arg *arg); -// conditional predictor-corrector: 0 no conditinal predictor-corrector, 1 conditional predictor-corrector -void s_tree_ocp_qcqp_ipm_arg_set_cond_pred_corr(int *value, struct s_tree_ocp_qcqp_ipm_arg *arg); -// set riccati algorithm: 0 classic, 1 square-root -//void s_tree_ocp_qcqp_ipm_arg_set_ric_alg(int *value, struct s_tree_ocp_qcqp_ipm_arg *arg); -// compute residuals after solution -void s_tree_ocp_qcqp_ipm_arg_set_comp_res_exit(int *value, struct s_tree_ocp_qcqp_ipm_arg *arg); -// compute residuals of prediction -//void s_tree_ocp_qcqp_ipm_arg_set_comp_res_pred(int *value, struct s_tree_ocp_qcqp_ipm_arg *arg); -// min value of lam in the solution -void s_tree_ocp_qcqp_ipm_arg_set_lam_min(float *value, struct s_tree_ocp_qcqp_ipm_arg *arg); -// min value of t in the solution -void s_tree_ocp_qcqp_ipm_arg_set_t_min(float *value, struct s_tree_ocp_qcqp_ipm_arg *arg); -// use different step for primal and dual variables -void s_tree_ocp_qcqp_ipm_arg_set_split_step(int *value, struct s_tree_ocp_qcqp_ipm_arg *arg); -// clip t and lam: 0 no, 1 in Gamma computation, 2 in solution -void s_tree_ocp_qcqp_ipm_arg_set_t_lam_min(int *value, struct s_tree_ocp_qcqp_ipm_arg *arg); - -// -hpipm_size_t s_tree_ocp_qcqp_ipm_ws_strsize(); -// -hpipm_size_t s_tree_ocp_qcqp_ipm_ws_memsize(struct s_tree_ocp_qcqp_dim *ocp_dim, struct s_tree_ocp_qcqp_ipm_arg *arg); -// -void s_tree_ocp_qcqp_ipm_ws_create(struct s_tree_ocp_qcqp_dim *ocp_dim, struct s_tree_ocp_qcqp_ipm_arg *arg, struct s_tree_ocp_qcqp_ipm_ws *ws, void *mem); -// -void s_tree_ocp_qcqp_ipm_get(char *field, struct s_tree_ocp_qcqp_ipm_ws *ws, void *value); -// -void s_tree_ocp_qcqp_ipm_get_status(struct s_tree_ocp_qcqp_ipm_ws *ws, int *status); -// -void s_tree_ocp_qcqp_ipm_get_iter(struct s_tree_ocp_qcqp_ipm_ws *ws, int *iter); -// -void s_tree_ocp_qcqp_ipm_get_max_res_stat(struct s_tree_ocp_qcqp_ipm_ws *ws, float *res_stat); -// -void s_tree_ocp_qcqp_ipm_get_max_res_eq(struct s_tree_ocp_qcqp_ipm_ws *ws, float *res_eq); -// -void s_tree_ocp_qcqp_ipm_get_max_res_ineq(struct s_tree_ocp_qcqp_ipm_ws *ws, float *res_ineq); -// -void s_tree_ocp_qcqp_ipm_get_max_res_comp(struct s_tree_ocp_qcqp_ipm_ws *ws, float *res_comp); -// -void s_tree_ocp_qcqp_ipm_get_stat(struct s_tree_ocp_qcqp_ipm_ws *ws, float **stat); -// -void s_tree_ocp_qcqp_ipm_get_stat_m(struct s_tree_ocp_qcqp_ipm_ws *ws, int *stat_m); -// -void s_tree_ocp_qcqp_init_var(struct s_tree_ocp_qcqp *qp, struct s_tree_ocp_qcqp_sol *qp_sol, struct s_tree_ocp_qcqp_ipm_arg *arg, struct s_tree_ocp_qcqp_ipm_ws *ws); -// -void s_tree_ocp_qcqp_ipm_solve(struct s_tree_ocp_qcqp *qp, struct s_tree_ocp_qcqp_sol *qp_sol, struct s_tree_ocp_qcqp_ipm_arg *arg, struct s_tree_ocp_qcqp_ipm_ws *ws); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - -#endif // HPIPM_S_TREE_OCP_QCQP_IPM_H_ - - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qcqp_res.h b/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qcqp_res.h deleted file mode 100644 index d0d84a6..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qcqp_res.h +++ /dev/null @@ -1,109 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_TREE_OCP_QCQP_RES_H_ -#define HPIPM_S_TREE_OCP_QCQP_RES_H_ - - - -#include -#include - -#include -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_tree_ocp_qcqp_res - { - struct s_tree_ocp_qcqp_dim *dim; - struct blasfeo_svec *res_g; // q-residuals - struct blasfeo_svec *res_b; // b-residuals - struct blasfeo_svec *res_d; // d-residuals - struct blasfeo_svec *res_m; // m-residuals - float res_max[4]; // max of residuals - float res_mu; // mu-residual - hpipm_size_t memsize; - }; - - - -struct s_tree_ocp_qcqp_res_ws - { - struct blasfeo_svec *tmp_nuxM; // work space of size nuM+nxM - struct blasfeo_svec *tmp_nbgqM; // work space of size nbM+ngM+nqM - struct blasfeo_svec *tmp_nsM; // work space of size nsM - struct blasfeo_svec *q_fun; // value for evaluation of quadr constr - struct blasfeo_svec *q_adj; // value for adjoint of quadr constr - int use_q_fun; // reuse cached value for evaluation of quadr constr - int use_q_adj; // reuse cached value for adjoint of quadr constr - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_tree_ocp_qcqp_res_memsize(struct s_tree_ocp_qcqp_dim *ocp_dim); -// -void s_tree_ocp_qcqp_res_create(struct s_tree_ocp_qcqp_dim *ocp_dim, struct s_tree_ocp_qcqp_res *res, void *mem); -// -hpipm_size_t s_tree_ocp_qcqp_res_ws_memsize(struct s_tree_ocp_qcqp_dim *ocp_dim); -// -void s_tree_ocp_qcqp_res_ws_create(struct s_tree_ocp_qcqp_dim *ocp_dim, struct s_tree_ocp_qcqp_res_ws *ws, void *mem); -// -void s_tree_ocp_qcqp_res_compute(struct s_tree_ocp_qcqp *qp, struct s_tree_ocp_qcqp_sol *qp_sol, struct s_tree_ocp_qcqp_res *res, struct s_tree_ocp_qcqp_res_ws *ws); -// -void s_tree_ocp_qcqp_res_compute_inf_norm(struct s_tree_ocp_qcqp_res *res); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - -#endif // HPIPM_S_TREE_OCP_QCQP_RES_H_ - - - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qcqp_sol.h b/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qcqp_sol.h deleted file mode 100644 index 47f038c..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qcqp_sol.h +++ /dev/null @@ -1,97 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_TREE_OCP_QCQP_SOL_H_ -#define HPIPM_S_TREE_OCP_QCQP_SOL_H_ - - - -#include -#include - -#include "hpipm_s_tree_ocp_qcqp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - -struct s_tree_ocp_qcqp_sol - { - struct s_tree_ocp_qcqp_dim *dim; - struct blasfeo_svec *ux; - struct blasfeo_svec *pi; - struct blasfeo_svec *lam; - struct blasfeo_svec *t; - void *misc; - hpipm_size_t memsize; // memory size in bytes - }; - - - -// -hpipm_size_t s_tree_ocp_qcqp_sol_memsize(struct s_tree_ocp_qcqp_dim *dim); -// -void s_tree_ocp_qcqp_sol_create(struct s_tree_ocp_qcqp_dim *dim, struct s_tree_ocp_qcqp_sol *qp_sol, void *memory); -// -void s_tree_ocp_qcqp_sol_get_u(int node, struct s_tree_ocp_qcqp_sol *qp_sol, float *vec); -// -void s_tree_ocp_qcqp_sol_get_x(int node, struct s_tree_ocp_qcqp_sol *qp_sol, float *vec); -// -void s_tree_ocp_qcqp_sol_get_sl(int node, struct s_tree_ocp_qcqp_sol *qp_sol, float *vec); -// -void s_tree_ocp_qcqp_sol_get_su(int node, struct s_tree_ocp_qcqp_sol *qp_sol, float *vec); -// -void s_tree_ocp_qcqp_sol_get_pi(int edge, struct s_tree_ocp_qcqp_sol *qp_sol, float *vec); -// -void s_tree_ocp_qcqp_sol_get_lam_lb(int node, struct s_tree_ocp_qcqp_sol *qp_sol, float *vec); -// -void s_tree_ocp_qcqp_sol_get_lam_ub(int node, struct s_tree_ocp_qcqp_sol *qp_sol, float *vec); -// -void s_tree_ocp_qcqp_sol_get_lam_lg(int node, struct s_tree_ocp_qcqp_sol *qp_sol, float *vec); -// -void s_tree_ocp_qcqp_sol_get_lam_ug(int node, struct s_tree_ocp_qcqp_sol *qp_sol, float *vec); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_S_TREE_OCP_QCQP_SOL_H_ - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qcqp_utils.h b/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qcqp_utils.h deleted file mode 100644 index 79528de..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qcqp_utils.h +++ /dev/null @@ -1,85 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_TREE_OCP_QCQP_UTILS_H_ -#define HPIPM_S_TREE_OCP_QCQP_UTILS_H_ - - - -#include -#include - -#include "hpipm_s_tree_ocp_qcqp_dim.h" -#include "hpipm_s_tree_ocp_qcqp.h" -#include "hpipm_s_tree_ocp_qcqp_sol.h" -#include "hpipm_s_tree_ocp_qcqp_ipm.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -// -void s_tree_ocp_qcqp_dim_print(struct s_tree_ocp_qcqp_dim *qp_dim); -// -//void s_tree_ocp_qcqp_dim_codegen(char *file_name, char *mode, struct s_tree_ocp_qcqp_dim *qp_dim); -// -void s_tree_ocp_qcqp_print(struct s_tree_ocp_qcqp_dim *qp_dim, struct s_tree_ocp_qcqp *qp); -// -//void s_tree_ocp_qcqp_codegen(char *file_name, char *mode, struct s_tree_ocp_qcqp_dim *qp_dim, struct s_tree_ocp_qcqp *qp); -// -void s_tree_ocp_qcqp_sol_print(struct s_tree_ocp_qcqp_dim *qp_dim, struct s_tree_ocp_qcqp_sol *ocp_qcqp_sol); -// -void s_tree_ocp_qcqp_ipm_arg_print(struct s_tree_ocp_qcqp_dim *qp_dim, struct s_tree_ocp_qcqp_ipm_arg *arg); -// -//void s_tree_ocp_qcqp_ipm_arg_codegen(char *file_name, char *mode, struct s_tree_ocp_qcqp_dim *qp_dim, struct s_tree_ocp_qcqp_ipm_arg *arg); -// -void s_tree_ocp_qcqp_res_print(struct s_tree_ocp_qcqp_dim *qp_dim, struct s_tree_ocp_qcqp_res *ocp_qcqp_res); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_S_TREE_OCP_QCQP_UTILS_H_ - - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qp.h b/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qp.h deleted file mode 100644 index 722b930..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qp.h +++ /dev/null @@ -1,196 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_TREE_OCP_QP_H_ -#define HPIPM_S_TREE_OCP_QP_H_ - - - -#include -#include - -#include "hpipm_s_tree_ocp_qp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_tree_ocp_qp - { - struct s_tree_ocp_qp_dim *dim; - struct blasfeo_smat *BAbt; // Nn-1 - struct blasfeo_smat *RSQrq; // Nn - struct blasfeo_smat *DCt; // Nn - struct blasfeo_svec *b; // Nn-1 - struct blasfeo_svec *rqz; // Nn - struct blasfeo_svec *d; // Nn - struct blasfeo_svec *d_mask; // Nn - struct blasfeo_svec *m; // Nn - struct blasfeo_svec *Z; // Nn - int **idxb; // indices of box constrained variables within [u; x] // Nn -// int **idxs; // index of soft constraints - int **idxs_rev; // index of soft constraints - hpipm_size_t memsize; // memory size in bytes - }; - - - -// -hpipm_size_t s_tree_ocp_qp_memsize(struct s_tree_ocp_qp_dim *dim); -// -void s_tree_ocp_qp_create(struct s_tree_ocp_qp_dim *dim, struct s_tree_ocp_qp *qp, void *memory); -// -void s_tree_ocp_qp_set_all(float **A, float **B, float **b, float **Q, float **S, float **R, float **q, float **r, int **idxb, float **d_lb, float **d_ub, float **C, float **D, float **d_lg, float **d_ug, float **Zl, float **Zu, float **zl, float **zu, int **idxs, float **d_ls, float **d_us, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set(char *field_name, int node_edge, void *value, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_A(int edge, float *mat, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_B(int edge, float *mat, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_b(int edge, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_Q(int node, float *mat, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_S(int node, float *mat, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_R(int node, float *mat, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_q(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_r(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_lb(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_lb_mask(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_ub(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_ub_mask(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_lbx(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_lbx_mask(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_ubx(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_ubx_mask(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_lbu(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_lbu_mask(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_ubu(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_ubu_mask(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_idxb(int node, int *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_idxbx(int node, int *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_Jbx(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_idxbu(int node, int *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_Jbu(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_C(int node, float *mat, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_D(int node, float *mat, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_lg(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_lg_mask(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_ug(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_ug_mask(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_Zl(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_Zu(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_zl(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_zu(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_lls(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_lls_mask(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_lus(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_lus_mask(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_idxs(int node, int *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_idxs_rev(int node, int *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_Jsbu(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_Jsbx(int node, float *vec, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_set_Jsg(int node, float *vec, struct s_tree_ocp_qp *qp); -// -//void s_tree_ocp_qp_set_idxe(int node, int *vec, struct s_tree_ocp_qp *qp); -// -//void s_tree_ocp_qp_set_idxbxe(int node, int *vec, struct s_tree_ocp_qp *qp); -// -//void s_tree_ocp_qp_set_idxbue(int node, int *vec, struct s_tree_ocp_qp *qp); -// -//void s_tree_ocp_qp_set_idxge(int node, int *vec, struct s_tree_ocp_qp *qp); -// -//void s_tree_ocp_qp_set_Jbxe(int node, float *vec, struct s_tree_ocp_qp *qp); -// -//void s_tree_ocp_qp_set_Jbue(int node, float *vec, struct s_tree_ocp_qp *qp); -// -//void s_tree_ocp_qp_set_Jge(int node, float *vec, struct s_tree_ocp_qp *qp); -// -//void s_tree_ocp_qp_set_diag_H_flag(int node, int *value, struct s_tree_ocp_qp *qp); - - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_S_TREE_OCP_QP_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qp_dim.h b/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qp_dim.h deleted file mode 100644 index 90df571..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qp_dim.h +++ /dev/null @@ -1,111 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_TREE_OCP_QP_DIM_H_ -#define HPIPM_S_TREE_OCP_QP_DIM_H_ - -#include "hpipm_common.h" - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_tree_ocp_qp_dim - { - struct tree *ttree; // tree describing node conndection - int *nx; // number of states // Nn - int *nu; // number of inputs // Nn - int *nb; // number of box constraints // Nn - int *nbx; // number of state box constraints // Nn - int *nbu; // number of input box constraints // Nn - int *ng; // number of general constraints // Nn - int *ns; // number of soft constraints // Nn - int *nsbx; // number of soft state box constraints - int *nsbu; // number of soft input box constraints - int *nsg; // number of soft general constraints - int Nn; // number of nodes - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_tree_ocp_qp_dim_strsize(); -// -hpipm_size_t s_tree_ocp_qp_dim_memsize(int Nn); -// -void s_tree_ocp_qp_dim_create(int Nn, struct s_tree_ocp_qp_dim *qp_dim, void *memory); -// -void s_tree_ocp_qp_dim_set_all(struct tree *ttree, int *nx, int *nu, int *nbx, int *nbu, int *ng, int *nsbx, int *nsbu, int *nsg, struct s_tree_ocp_qp_dim *dim); -// -void s_tree_ocp_qp_dim_set_tree(struct tree *ttree, struct s_tree_ocp_qp_dim *dim); -// -void s_tree_ocp_qp_dim_set(char *field, int stage, int value, struct s_tree_ocp_qp_dim *dim); -// -void s_tree_ocp_qp_dim_set_nx(int stage, int value, struct s_tree_ocp_qp_dim *dim); -// -void s_tree_ocp_qp_dim_set_nu(int stage, int value, struct s_tree_ocp_qp_dim *dim); -// -void s_tree_ocp_qp_dim_set_nbx(int stage, int value, struct s_tree_ocp_qp_dim *dim); -// -void s_tree_ocp_qp_dim_set_nbu(int stage, int value, struct s_tree_ocp_qp_dim *dim); -// -void s_tree_ocp_qp_dim_set_ng(int stage, int value, struct s_tree_ocp_qp_dim *dim); -// -void s_tree_ocp_qp_dim_set_ns(int stage, int value, struct s_tree_ocp_qp_dim *dim); -// -void s_tree_ocp_qp_dim_set_nsbx(int stage, int value, struct s_tree_ocp_qp_dim *dim); -// -void s_tree_ocp_qp_dim_set_nsbu(int stage, int value, struct s_tree_ocp_qp_dim *dim); -// -void s_tree_ocp_qp_dim_set_nsg(int stage, int value, struct s_tree_ocp_qp_dim *dim); -// -void s_tree_ocp_qp_dim_set_nbxe(int stage, int value, struct s_tree_ocp_qp_dim *dim); -// -void s_tree_ocp_qp_dim_set_nbue(int stage, int value, struct s_tree_ocp_qp_dim *dim); -// -void s_tree_ocp_qp_dim_set_nge(int stage, int value, struct s_tree_ocp_qp_dim *dim); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_S_TREE_OCP_QP_DIM_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qp_ipm.h b/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qp_ipm.h deleted file mode 100644 index f8c26d3..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qp_ipm.h +++ /dev/null @@ -1,208 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - - -#ifndef HPIPM_S_TREE_OCP_QP_IPM_H_ -#define HPIPM_S_TREE_OCP_QP_IPM_H_ - - - -#include -#include - -#include -#include -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_tree_ocp_qp_ipm_arg - { - float mu0; // initial value for duality measure - float alpha_min; // exit cond on step length - float res_g_max; // exit cond on inf norm of residuals - float res_b_max; // exit cond on inf norm of residuals - float res_d_max; // exit cond on inf norm of residuals - float res_m_max; // exit cond on inf norm of residuals - float reg_prim; // reg of primal hessian - float lam_min; // min value in lam vector - float t_min; // min value in t vector - float tau_min; // min value of barrier parameter - int iter_max; // exit cond in iter number - int stat_max; // iterations saved in stat - int stat_m; // number of recorded stat per IPM iter - int pred_corr; // use Mehrotra's predictor-corrector IPM algirthm - int cond_pred_corr; // conditional Mehrotra's predictor-corrector - int itref_pred_max; // max number of iterative refinement steps for predictor step - int itref_corr_max; // max number of iterative refinement steps for corrector step - int warm_start; // 0 no warm start, 1 warm start primal sol, 2 warm start primal and dual sol - int lq_fact; // 0 syrk+potrf, 1 mix, 2 lq - int abs_form; // absolute IPM formulation - int comp_dual_sol_eq; // dual solution (only for abs_form==1) - int comp_res_exit; // compute residuals on exit (only for abs_form==1 and comp_dual_sol==1) - int split_step; // use different steps for primal and dual variables - int t_lam_min; // clip t and lam: 0 no, 1 in Gamma computation, 2 in solution - int mode; - hpipm_size_t memsize; - }; - - - -struct s_tree_ocp_qp_ipm_ws - { - struct s_core_qp_ipm_workspace *core_workspace; - struct s_tree_ocp_qp_res_ws *res_workspace; - struct s_tree_ocp_qp_sol *sol_step; - struct s_tree_ocp_qp_sol *sol_itref; - struct s_tree_ocp_qp *qp_step; - struct s_tree_ocp_qp *qp_itref; - struct s_tree_ocp_qp_res *res_itref; - struct s_tree_ocp_qp_res *res; - struct blasfeo_svec *Gamma; // hessian update - struct blasfeo_svec *gamma; // hessian update - struct blasfeo_svec *tmp_nxM; // work space of size nxM - struct blasfeo_svec *tmp_nbgM; // work space of size nbgM - struct blasfeo_svec *tmp_nsM; // work space of size nsM - struct blasfeo_svec *Pb; // Pb - struct blasfeo_svec *Zs_inv; - struct blasfeo_smat *L; - struct blasfeo_smat *Lh; - struct blasfeo_smat *AL; - struct blasfeo_smat *lq0; - struct blasfeo_svec *tmp_m; - float *stat; // convergence statistics - int *use_hess_fact; - void *lq_work0; - float qp_res[4]; // infinity norm of residuals - int iter; // iteration number - int stat_max; // iterations saved in stat - int stat_m; // number of recorded stat per IPM iter - int use_Pb; - int status; // solver status - int lq_fact; // cache from arg - int mask_constr; // use constr mask - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_tree_ocp_qp_ipm_arg_memsize(struct s_tree_ocp_qp_dim *dim); -// -void s_tree_ocp_qp_ipm_arg_create(struct s_tree_ocp_qp_dim *dim, struct s_tree_ocp_qp_ipm_arg *arg, void *mem); -// -void s_tree_ocp_qp_ipm_arg_set_default(enum hpipm_mode mode, struct s_tree_ocp_qp_ipm_arg *arg); -// -void s_tree_ocp_qp_ipm_arg_set_iter_max(int *iter_max, struct s_tree_ocp_qp_ipm_arg *arg); -// -void s_tree_ocp_qp_ipm_arg_set_alpha_min(float *alpha_min, struct s_tree_ocp_qp_ipm_arg *arg); -// -void s_tree_ocp_qp_ipm_arg_set_mu0(float *mu0, struct s_tree_ocp_qp_ipm_arg *arg); -// -void s_tree_ocp_qp_ipm_arg_set_tol_stat(float *tol_stat, struct s_tree_ocp_qp_ipm_arg *arg); -// -void s_tree_ocp_qp_ipm_arg_set_tol_eq(float *tol_eq, struct s_tree_ocp_qp_ipm_arg *arg); -// -void s_tree_ocp_qp_ipm_arg_set_tol_ineq(float *tol_ineq, struct s_tree_ocp_qp_ipm_arg *arg); -// -void s_tree_ocp_qp_ipm_arg_set_tol_comp(float *tol_comp, struct s_tree_ocp_qp_ipm_arg *arg); -// -void s_tree_ocp_qp_ipm_arg_set_reg_prim(float *reg, struct s_tree_ocp_qp_ipm_arg *arg); -// -void s_tree_ocp_qp_ipm_arg_set_warm_start(int *warm_start, struct s_tree_ocp_qp_ipm_arg *arg); -// -void s_tree_ocp_qp_ipm_arg_set_pred_corr(int *pred_corr, struct s_tree_ocp_qp_ipm_arg *arg); -// -void s_tree_ocp_qp_ipm_arg_set_cond_pred_corr(int *value, struct s_tree_ocp_qp_ipm_arg *arg); -// -void s_tree_ocp_qp_ipm_arg_set_comp_dual_sol_eq(int *value, struct s_tree_ocp_qp_ipm_arg *arg); -// -void s_tree_ocp_qp_ipm_arg_set_comp_res_exit(int *value, struct s_tree_ocp_qp_ipm_arg *arg); -// -void s_tree_ocp_qp_ipm_arg_set_lam_min(float *value, struct s_tree_ocp_qp_ipm_arg *arg); -// -void s_tree_ocp_qp_ipm_arg_set_t_min(float *value, struct s_tree_ocp_qp_ipm_arg *arg); -// -void s_tree_ocp_qp_ipm_arg_set_tau_min(float *value, struct s_tree_ocp_qp_ipm_arg *arg); -// -void s_tree_ocp_qp_ipm_arg_set_split_step(int *value, struct s_tree_ocp_qp_ipm_arg *arg); -// -void s_tree_ocp_qp_ipm_arg_set_t_lam_min(int *value, struct s_tree_ocp_qp_ipm_arg *arg); - -// -hpipm_size_t s_tree_ocp_qp_ipm_ws_memsize(struct s_tree_ocp_qp_dim *dim, struct s_tree_ocp_qp_ipm_arg *arg); -// -void s_tree_ocp_qp_ipm_ws_create(struct s_tree_ocp_qp_dim *dim, struct s_tree_ocp_qp_ipm_arg *arg, struct s_tree_ocp_qp_ipm_ws *ws, void *mem); -// -void s_tree_ocp_qp_ipm_get_status(struct s_tree_ocp_qp_ipm_ws *ws, int *status); -// -void s_tree_ocp_qp_ipm_get_iter(struct s_tree_ocp_qp_ipm_ws *ws, int *iter); -// -void s_tree_ocp_qp_ipm_get_max_res_stat(struct s_tree_ocp_qp_ipm_ws *ws, float *res_stat); -// -void s_tree_ocp_qp_ipm_get_max_res_eq(struct s_tree_ocp_qp_ipm_ws *ws, float *res_eq); -// -void s_tree_ocp_qp_ipm_get_max_res_ineq(struct s_tree_ocp_qp_ipm_ws *ws, float *res_ineq); -// -void s_tree_ocp_qp_ipm_get_max_res_comp(struct s_tree_ocp_qp_ipm_ws *ws, float *res_comp); -// -void s_tree_ocp_qp_ipm_get_stat(struct s_tree_ocp_qp_ipm_ws *ws, float **stat); -// -void s_tree_ocp_qp_ipm_get_stat_m(struct s_tree_ocp_qp_ipm_ws *ws, int *stat_m); -// -void s_tree_ocp_qp_init_var(struct s_tree_ocp_qp *qp, struct s_tree_ocp_qp_sol *qp_sol, struct s_tree_ocp_qp_ipm_arg *arg, struct s_tree_ocp_qp_ipm_ws *ws); -// -void s_tree_ocp_qp_ipm_abs_step(int kk, struct s_tree_ocp_qp *qp, struct s_tree_ocp_qp_sol *qp_sol, struct s_tree_ocp_qp_ipm_arg *arg, struct s_tree_ocp_qp_ipm_ws *ws); -// -void s_tree_ocp_qp_ipm_delta_step(int kk, struct s_tree_ocp_qp *qp, struct s_tree_ocp_qp_sol *qp_sol, struct s_tree_ocp_qp_ipm_arg *arg, struct s_tree_ocp_qp_ipm_ws *ws); -// -void s_tree_ocp_qp_ipm_solve(struct s_tree_ocp_qp *qp, struct s_tree_ocp_qp_sol *qp_sol, struct s_tree_ocp_qp_ipm_arg *arg, struct s_tree_ocp_qp_ipm_ws *ws); - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_S_TREE_OCP_QP_IPM_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qp_kkt.h b/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qp_kkt.h deleted file mode 100644 index bcf7354..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qp_kkt.h +++ /dev/null @@ -1,54 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - -#ifdef __cplusplus -extern "C" { -#endif - -// -void s_tree_ocp_qp_fact_solve_kkt_unconstr(struct s_tree_ocp_qp *qp, struct s_tree_ocp_qp_sol *qp_sol, struct s_tree_ocp_qp_ipm_arg *arg, struct s_tree_ocp_qp_ipm_ws *ws); -// -void s_tree_ocp_qp_fact_solve_kkt_step(struct s_tree_ocp_qp *qp, struct s_tree_ocp_qp_sol *qp_sol, struct s_tree_ocp_qp_ipm_arg *arg, struct s_tree_ocp_qp_ipm_ws *ws); -// -void s_tree_ocp_qp_fact_lq_solve_kkt_step(struct s_tree_ocp_qp *qp, struct s_tree_ocp_qp_sol *qp_sol, struct s_tree_ocp_qp_ipm_arg *arg, struct s_tree_ocp_qp_ipm_ws *ws); -// -void s_tree_ocp_qp_solve_kkt_step(struct s_tree_ocp_qp *qp, struct s_tree_ocp_qp_sol *qp_sol, struct s_tree_ocp_qp_ipm_arg *arg, struct s_tree_ocp_qp_ipm_ws *ws); - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qp_res.h b/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qp_res.h deleted file mode 100644 index 5c67972..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qp_res.h +++ /dev/null @@ -1,107 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_TREE_OCP_QP_RES_H_ -#define HPIPM_S_TREE_OCP_QP_RES_H_ - - - -#include -#include - -#include -#include -#include -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct s_tree_ocp_qp_res - { - struct s_tree_ocp_qp_dim *dim; - struct blasfeo_svec *res_g; // q-residuals - struct blasfeo_svec *res_b; // b-residuals - struct blasfeo_svec *res_d; // d-residuals - struct blasfeo_svec *res_m; // m-residuals - float res_max[4]; // max of residuals - float res_mu; // mu-residual - hpipm_size_t memsize; - }; - - - -struct s_tree_ocp_qp_res_ws - { - struct blasfeo_svec *tmp_nbgM; // work space of size nbM+ngM - struct blasfeo_svec *tmp_nsM; // work space of size nsM - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t s_tree_ocp_qp_res_memsize(struct s_tree_ocp_qp_dim *ocp_dim); -// -void s_tree_ocp_qp_res_create(struct s_tree_ocp_qp_dim *ocp_dim, struct s_tree_ocp_qp_res *res, void *mem); -// -hpipm_size_t s_tree_ocp_qp_res_ws_memsize(struct s_tree_ocp_qp_dim *ocp_dim); -// -void s_tree_ocp_qp_res_ws_create(struct s_tree_ocp_qp_dim *ocp_dim, struct s_tree_ocp_qp_res_ws *ws, void *mem); -// -void s_tree_ocp_qp_res_get_all(struct s_tree_ocp_qp_res *res, float **res_r, float **res_q, float **res_ls, float **res_us, float **res_b, float **res_d_lb, float **res_d_ub, float **res_d_lg, float **res_d_ug, float **res_d_ls, float **res_d_us, float **res_m_lb, float **res_m_ub, float **res_m_lg, float **res_m_ug, float **res_m_ls, float **res_m_us); -// -void s_tree_ocp_qp_res_compute(struct s_tree_ocp_qp *qp, struct s_tree_ocp_qp_sol *qp_sol, struct s_tree_ocp_qp_res *res, struct s_tree_ocp_qp_res_ws *ws); -// -void s_tree_ocp_qp_res_compute_lin(struct s_tree_ocp_qp *qp, struct s_tree_ocp_qp_sol *qp_sol, struct s_tree_ocp_qp_sol *qp_step, struct s_tree_ocp_qp_res *res, struct s_tree_ocp_qp_res_ws *ws); -// -void s_tree_ocp_qp_res_compute_inf_norm(struct s_tree_ocp_qp_res *res); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - -#endif // HPIPM_S_TREE_OCP_QP_RES_H_ - - - diff --git a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qp_sol.h b/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qp_sol.h deleted file mode 100644 index 71e8876..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qp_sol.h +++ /dev/null @@ -1,98 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_TREE_OCP_QP_SOL_H_ -#define HPIPM_S_TREE_OCP_QP_SOL_H_ - - - -#include -#include - -#include "hpipm_s_tree_ocp_qp_dim.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - -struct s_tree_ocp_qp_sol - { - struct s_tree_ocp_qp_dim *dim; - struct blasfeo_svec *ux; - struct blasfeo_svec *pi; - struct blasfeo_svec *lam; - struct blasfeo_svec *t; - void *misc; - hpipm_size_t memsize; // memory size in bytes - }; - - - -// -hpipm_size_t s_tree_ocp_qp_sol_memsize(struct s_tree_ocp_qp_dim *dim); -// -void s_tree_ocp_qp_sol_create(struct s_tree_ocp_qp_dim *dim, struct s_tree_ocp_qp_sol *qp_sol, void *memory); -// -void s_tree_ocp_qp_sol_get_all(struct s_tree_ocp_qp *qp, struct s_tree_ocp_qp_sol *qp_sol, float **u, float **x, float **ls, float **us, float **pi, float **lam_lb, float **lam_ub, float **lam_lg, float **lam_ug, float **lam_ls, float **lam_us); -// -void s_tree_ocp_qp_sol_get_u(int node, struct s_tree_ocp_qp_sol *qp_sol, float *vec); -// -void s_tree_ocp_qp_sol_get_x(int node, struct s_tree_ocp_qp_sol *qp_sol, float *vec); -// -void s_tree_ocp_qp_sol_get_sl(int node, struct s_tree_ocp_qp_sol *qp_sol, float *vec); -// -void s_tree_ocp_qp_sol_get_su(int node, struct s_tree_ocp_qp_sol *qp_sol, float *vec); -// -void s_tree_ocp_qp_sol_get_pi(int edge, struct s_tree_ocp_qp_sol *qp_sol, float *vec); -// -void s_tree_ocp_qp_sol_get_lam_lb(int node, struct s_tree_ocp_qp_sol *qp_sol, float *vec); -// -void s_tree_ocp_qp_sol_get_lam_ub(int node, struct s_tree_ocp_qp_sol *qp_sol, float *vec); -// -void s_tree_ocp_qp_sol_get_lam_lg(int node, struct s_tree_ocp_qp_sol *qp_sol, float *vec); -// -void s_tree_ocp_qp_sol_get_lam_ug(int node, struct s_tree_ocp_qp_sol *qp_sol, float *vec); - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - - - -#endif // HPIPM_S_TREE_OCP_QP_SOL_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qp_utils.h b/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qp_utils.h deleted file mode 100644 index ec17475..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_s_tree_ocp_qp_utils.h +++ /dev/null @@ -1,84 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_S_TREE_OCP_QP_UTILS_H_ -#define HPIPM_S_TREE_OCP_QP_UTILS_H_ - - - -#include -#include - -#include "hpipm_s_tree_ocp_qp_dim.h" -#include "hpipm_s_tree_ocp_qp.h" -#include "hpipm_s_tree_ocp_qp_sol.h" -#include "hpipm_s_tree_ocp_qp_ipm.h" - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -// -void s_tree_ocp_qp_dim_print(struct s_tree_ocp_qp_dim *qp_dim); -// -//void s_tree_ocp_qp_dim_codegen(char *file_name, char *mode, struct s_tree_ocp_qp_dim *qp_dim); -// -void s_tree_ocp_qp_print(struct s_tree_ocp_qp_dim *qp_dim, struct s_tree_ocp_qp *qp); -// -//void s_tree_ocp_qp_codegen(char *file_name, char *mode, struct s_tree_ocp_qp_dim *qp_dim, struct s_tree_ocp_qp *qp); -// -void s_tree_ocp_qp_sol_print(struct s_tree_ocp_qp_dim *qp_dim, struct s_tree_ocp_qp_sol *ocp_qp_sol); -// -void s_tree_ocp_qp_ipm_arg_print(struct s_tree_ocp_qp_dim *qp_dim, struct s_tree_ocp_qp_ipm_arg *arg); -// -//void s_tree_ocp_qp_ipm_arg_codegen(char *file_name, char *mode, struct s_tree_ocp_qp_dim *qp_dim, struct s_tree_ocp_qp_ipm_arg *arg); -// -void s_tree_ocp_qp_res_print(struct s_tree_ocp_qp_dim *qp_dim, struct s_tree_ocp_qp_res *ocp_qp_res); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - - -#endif // HPIPM_S_TREE_OCP_QP_UTILS_H_ - - diff --git a/third_party/acados/include/hpipm/include/hpipm_scenario_tree.h b/third_party/acados/include/hpipm/include/hpipm_scenario_tree.h deleted file mode 100644 index a3c77a6..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_scenario_tree.h +++ /dev/null @@ -1,70 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_SCENARIO_TREE_H_ -#define HPIPM_SCENARIO_TREE_H_ - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct sctree - { - struct node *root; // pointer to root - int *kids; // pointer to array of kids - int Nn; // numer of nodes - int md; // number of realizations - int Nr; // robust horizion - int Nh; // control horizion - hpipm_size_t memsize; - }; - - - -// -hpipm_size_t sctree_memsize(int md, int Nr, int Nh); -// -void sctree_create(int md, int Nr, int Nh, struct sctree *st, void *memory); -// -void sctree_cast_to_tree(struct sctree *st, struct tree *tt); - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // HPIPM_SCENARIO_TREE_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_timing.h b/third_party/acados/include/hpipm/include/hpipm_timing.h deleted file mode 100644 index bd0f2db..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_timing.h +++ /dev/null @@ -1,67 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - -#ifndef HPIPM_TIMING_H_ -#define HPIPM_TIMING_H_ - - - -#include - - - -#ifdef __cplusplus -extern "C" { -#endif - - - -typedef blasfeo_timer hpipm_timer; - - - -// -void hpipm_tic(hpipm_timer *t); -// -double hpipm_toc(hpipm_timer *t); - - - -#ifdef __cplusplus -} // #extern "C" -#endif - - -#endif // HPIPM_TIMING_H_ diff --git a/third_party/acados/include/hpipm/include/hpipm_tree.h b/third_party/acados/include/hpipm/include/hpipm_tree.h deleted file mode 100644 index f9d69ec..0000000 --- a/third_party/acados/include/hpipm/include/hpipm_tree.h +++ /dev/null @@ -1,76 +0,0 @@ -/************************************************************************************************** -* * -* This file is part of HPIPM. * -* * -* HPIPM -- High-Performance Interior Point Method. * -* Copyright (C) 2019 by Gianluca Frison. * -* Developed at IMTEK (University of Freiburg) under the supervision of Moritz Diehl. * -* All rights reserved. * -* * -* The 2-Clause BSD License * -* * -* Redistribution and use in source and binary forms, with or without * -* modification, are permitted provided that the following conditions are met: * -* * -* 1. Redistributions of source code must retain the above copyright notice, this * -* list of conditions and the following disclaimer. * -* 2. Redistributions in binary form must reproduce the above copyright notice, * -* this list of conditions and the following disclaimer in the documentation * -* and/or other materials provided with the distribution. * -* * -* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND * -* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED * -* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE * -* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR * -* ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES * -* (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; * -* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND * -* ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT * -* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS * -* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. * -* * -* Author: Gianluca Frison, gianluca.frison (at) imtek.uni-freiburg.de * -* * -**************************************************************************************************/ - - -#ifndef HPIPM_TREE_H_ -#define HPIPM_TREE_H_ - -#include "hpipm_common.h" - -#ifdef __cplusplus -extern "C" { -#endif - - - -struct node - { - int *kids; // 64 bits - int idx; // 32 bits - int dad; // 32 bits - int nkids; // 32 bits - int stage; // 32 bits - int real; // 32 bits - int idxkid; // 32 bits // XXX needed ??? - // total 256 bits - }; - - - -struct tree - { - struct node *root; // pointer to root - int *kids; // pointer to array of kids - int Nn; // numer of nodes - hpipm_size_t memsize; - }; - - - -#ifdef __cplusplus -} /* extern "C" */ -#endif - -#endif // HPIPM_TREE_H_ diff --git a/third_party/acados/include/qpOASES_e/Bounds.h b/third_party/acados/include/qpOASES_e/Bounds.h deleted file mode 100644 index 4e41c1d..0000000 --- a/third_party/acados/include/qpOASES_e/Bounds.h +++ /dev/null @@ -1,543 +0,0 @@ -/* - * This file is part of qpOASES. - * - * qpOASES -- An Implementation of the Online Active Set Strategy. - * Copyright (C) 2007-2015 by Hans Joachim Ferreau, Andreas Potschka, - * Christian Kirches et al. All rights reserved. - * - * qpOASES is free software; you can redistribute it and/or - * modify it under the terms of the GNU Lesser General Public - * License as published by the Free Software Foundation; either - * version 2.1 of the License, or (at your option) any later version. - * - * qpOASES is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public - * License along with qpOASES; if not, write to the Free Software - * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - * - */ - - -/** - * \file include/qpOASES_e/Bounds.h - * \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches - * \version 3.1embedded - * \date 2007-2015 - * - * Declaration of the Bounds class designed to manage working sets of - * bounds within a QProblem. - */ - - -#ifndef QPOASES_BOUNDS_H -#define QPOASES_BOUNDS_H - - -#include - - -BEGIN_NAMESPACE_QPOASES - - -/** - * \brief Manages working sets of bounds (= box constraints). - * - * This class manages working sets of bounds (= box constraints) - * by storing index sets and other status information. - * - * \author Hans Joachim Ferreau - * \version 3.1embedded - * \date 2007-2015 - */ -typedef struct -{ - Indexlist *freee; /**< Index list of free variables. */ - Indexlist *fixed; /**< Index list of fixed variables. */ - - Indexlist *shiftedFreee; /**< Memory for shifting free variables. */ - Indexlist *shiftedFixed; /**< Memory for shifting fixed variables. */ - - Indexlist *rotatedFreee; /**< Memory for rotating free variables. */ - Indexlist *rotatedFixed; /**< Memory for rotating fixed variables. */ - - SubjectToType *type; /**< Type of bounds. */ - SubjectToStatus *status; /**< Status of bounds. */ - - SubjectToType *typeTmp; /**< Temp memory for type of bounds. */ - SubjectToStatus *statusTmp; /**< Temp memory for status of bounds. */ - - BooleanType noLower; /**< This flag indicates if there is no lower bound on any variable. */ - BooleanType noUpper; /**< This flag indicates if there is no upper bound on any variable. */ - - int n; /**< Total number of bounds. */ -} Bounds; - -int Bounds_calculateMemorySize( int n); - -char *Bounds_assignMemory(int n, Bounds **mem, void *raw_memory); - -Bounds *Bounds_createMemory( int n ); - -/** Constructor which takes the number of bounds. */ -void BoundsCON( Bounds* _THIS, - int _n /**< Number of bounds. */ - ); - -/** Copies all members from given rhs object. - * \return SUCCESSFUL_RETURN */ -void BoundsCPY( Bounds* FROM, - Bounds* TO - ); - - -/** Initialises object with given number of bounds. - * \return SUCCESSFUL_RETURN \n - RET_INVALID_ARGUMENTS */ -returnValue Bounds_init( Bounds* _THIS, - int _n /**< Number of bounds. */ - ); - - -/** Initially adds number of a new (i.e. not yet in the list) bound to - * given index set. - * \return SUCCESSFUL_RETURN \n - RET_SETUP_BOUND_FAILED \n - RET_INDEX_OUT_OF_BOUNDS \n - RET_INVALID_ARGUMENTS */ -returnValue Bounds_setupBound( Bounds* _THIS, - int number, /**< Number of new bound. */ - SubjectToStatus _status /**< Status of new bound. */ - ); - -/** Initially adds all numbers of new (i.e. not yet in the list) bounds to - * to the index set of free bounds; the order depends on the SujectToType - * of each index. - * \return SUCCESSFUL_RETURN \n - RET_SETUP_BOUND_FAILED */ -returnValue Bounds_setupAllFree( Bounds* _THIS - ); - -/** Initially adds all numbers of new (i.e. not yet in the list) bounds to - * to the index set of fixed bounds (on their lower bounds); - * the order depends on the SujectToType of each index. - * \return SUCCESSFUL_RETURN \n - RET_SETUP_BOUND_FAILED */ -returnValue Bounds_setupAllLower( Bounds* _THIS - ); - -/** Initially adds all numbers of new (i.e. not yet in the list) bounds to - * to the index set of fixed bounds (on their upper bounds); - * the order depends on the SujectToType of each index. - * \return SUCCESSFUL_RETURN \n - RET_SETUP_BOUND_FAILED */ -returnValue Bounds_setupAllUpper( Bounds* _THIS - ); - - -/** Moves index of a bound from index list of fixed to that of free bounds. - * \return SUCCESSFUL_RETURN \n - RET_MOVING_BOUND_FAILED \n - RET_INDEX_OUT_OF_BOUNDS */ -returnValue Bounds_moveFixedToFree( Bounds* _THIS, - int number /**< Number of bound to be freed. */ - ); - -/** Moves index of a bound from index list of free to that of fixed bounds. - * \return SUCCESSFUL_RETURN \n - RET_MOVING_BOUND_FAILED \n - RET_INDEX_OUT_OF_BOUNDS */ -returnValue Bounds_moveFreeToFixed( Bounds* _THIS, - int number, /**< Number of bound to be fixed. */ - SubjectToStatus _status /**< Status of bound to be fixed. */ - ); - -/** Flip fixed bound. - * \return SUCCESSFUL_RETURN \n - RET_MOVING_BOUND_FAILED \n - RET_INDEX_OUT_OF_BOUNDS */ -returnValue Bounds_flipFixed( Bounds* _THIS, - int number - ); - -/** Swaps the indices of two free bounds within the index set. - * \return SUCCESSFUL_RETURN \n - RET_SWAPINDEX_FAILED */ -returnValue Bounds_swapFree( Bounds* _THIS, - int number1, /**< Number of first bound. */ - int number2 /**< Number of second bound. */ - ); - - -/** Returns number of variables. - * \return Number of variables. */ -static inline int Bounds_getNV( Bounds* _THIS - ); - -/** Returns number of implicitly fixed variables. - * \return Number of implicitly fixed variables. */ -static inline int Bounds_getNFV( Bounds* _THIS - ); - -/** Returns number of bounded (but possibly free) variables. - * \return Number of bounded (but possibly free) variables. */ -static inline int Bounds_getNBV( Bounds* _THIS - ); - -/** Returns number of unbounded variables. - * \return Number of unbounded variables. */ -static inline int Bounds_getNUV( Bounds* _THIS - ); - -/** Returns number of free variables. - * \return Number of free variables. */ -static inline int Bounds_getNFR( Bounds* _THIS - ); - -/** Returns number of fixed variables. - * \return Number of fixed variables. */ -static inline int Bounds_getNFX( Bounds* _THIS - ); - - -/** Returns a pointer to free variables index list. - * \return Pointer to free variables index list. */ -static inline Indexlist* Bounds_getFree( Bounds* _THIS - ); - -/** Returns a pointer to fixed variables index list. - * \return Pointer to fixed variables index list. */ -static inline Indexlist* Bounds_getFixed( Bounds* _THIS - ); - - -/** Returns number of bounds with given SubjectTo type. - * \return Number of bounds with given type. */ -static inline int Bounds_getNumberOfType( Bounds* _THIS, - SubjectToType _type /**< Type of bound. */ - ); - - -/** Returns type of bound. - * \return Type of bound \n - RET_INDEX_OUT_OF_BOUNDS */ -static inline SubjectToType Bounds_getType( Bounds* _THIS, - int i /**< Number of bound. */ - ); - -/** Returns status of bound. - * \return Status of bound \n - ST_UNDEFINED */ -static inline SubjectToStatus Bounds_getStatus( Bounds* _THIS, - int i /**< Number of bound. */ - ); - - -/** Sets type of bound. - * \return SUCCESSFUL_RETURN \n - RET_INDEX_OUT_OF_BOUNDS */ -static inline returnValue Bounds_setType( Bounds* _THIS, - int i, /**< Number of bound. */ - SubjectToType value /**< Type of bound. */ - ); - -/** Sets status of bound. - * \return SUCCESSFUL_RETURN \n - RET_INDEX_OUT_OF_BOUNDS */ -static inline returnValue Bounds_setStatus( Bounds* _THIS, - int i, /**< Number of bound. */ - SubjectToStatus value /**< Status of bound. */ - ); - - -/** Sets status of lower bounds. */ -static inline void Bounds_setNoLower( Bounds* _THIS, - BooleanType _status /**< Status of lower bounds. */ - ); - -/** Sets status of upper bounds. */ -static inline void Bounds_setNoUpper( Bounds* _THIS, - BooleanType _status /**< Status of upper bounds. */ - ); - - -/** Returns status of lower bounds. - * \return BT_TRUE if there is no lower bound on any variable. */ -static inline BooleanType Bounds_hasNoLower( Bounds* _THIS - ); - -/** Returns status of upper bounds. - * \return BT_TRUE if there is no upper bound on any variable. */ -static inline BooleanType Bounds_hasNoUpper( Bounds* _THIS - ); - - -/** Shifts forward type and status of all bounds by a given - * offset. This offset has to lie within the range [0,n/2] and has to - * be an integer divisor of the total number of bounds n. - * Type and status of the first \ bounds is thrown away, - * type and status of the last \ bounds is doubled, - * e.g. for offset = 2: \n - * shift( {b1,b2,b3,b4,b5,b6} ) = {b3,b4,b5,b6,b5,b6} - * \return SUCCESSFUL_RETURN \n - RET_INDEX_OUT_OF_BOUNDS \n - RET_INVALID_ARGUMENTS \n - RET_SHIFTING_FAILED */ -returnValue Bounds_shift( Bounds* _THIS, - int offset /**< Shift offset within the range [0,n/2] and integer divisor of n. */ - ); - -/** Rotates forward type and status of all bounds by a given - * offset. This offset has to lie within the range [0,n]. - * Example for offset = 2: \n - * rotate( {b1,b2,b3,b4,b5,b6} ) = {b3,b4,b5,b6,b1,b2} - * \return SUCCESSFUL_RETURN \n - RET_INDEX_OUT_OF_BOUNDS \n - RET_ROTATING_FAILED */ -returnValue Bounds_rotate( Bounds* _THIS, - int offset /**< Rotation offset within the range [0,n]. */ - ); - - -/** Prints information on bounds object - * (in particular, lists of free and fixed bounds. - * \return SUCCESSFUL_RETURN \n - RET_INDEXLIST_CORRUPTED */ -returnValue Bounds_print( Bounds* _THIS - ); - - -/** Initially adds all numbers of new (i.e. not yet in the list) bounds to - * to the index set corresponding to the desired status; - * the order depends on the SujectToType of each index. - * \return SUCCESSFUL_RETURN \n - RET_SETUP_BOUND_FAILED */ -returnValue Bounds_setupAll( Bounds* _THIS, - SubjectToStatus _status /**< Desired initial status for all bounds. */ - ); - - -/** Adds the index of a new bound to index set. - * \return SUCCESSFUL_RETURN \n - RET_ADDINDEX_FAILED \n - RET_INVALID_ARGUMENTS */ -returnValue Bounds_addIndex( Bounds* _THIS, - Indexlist* const indexlist, /**< Index list to which the new index shall be added. */ - int newnumber, /**< Number of new bound. */ - SubjectToStatus newstatus /**< Status of new bound. */ - ); - -/** Removes the index of a bound from index set. - * \return SUCCESSFUL_RETURN \n - RET_REMOVEINDEX_FAILED \n - RET_INVALID_ARGUMENTS */ -returnValue Bounds_removeIndex( Bounds* _THIS, - Indexlist* const indexlist, /**< Index list from which the new index shall be removed. */ - int removenumber /**< Number of bound to be removed. */ - ); - -/** Swaps the indices of two constraints or bounds within the index set. - * \return SUCCESSFUL_RETURN \n - RET_SWAPINDEX_FAILED \n - RET_INVALID_ARGUMENTS */ -returnValue Bounds_swapIndex( Bounds* _THIS, - Indexlist* const indexlist, /**< Index list in which the indices shold be swapped. */ - int number1, /**< Number of first bound. */ - int number2 /**< Number of second bound. */ - ); - - - -/* - * g e t N u m b e r O f T y p e - */ -static inline int Bounds_getNumberOfType( Bounds* _THIS, SubjectToType _type ) -{ - int i; - int numberOfType = 0; - - if ( _THIS->type != 0 ) - { - for( i=0; i<_THIS->n; ++i ) - if ( _THIS->type[i] == _type ) - ++numberOfType; - } - - return numberOfType; -} - - -/* - * g e t T y p e - */ -static inline SubjectToType Bounds_getType( Bounds* _THIS, int i ) -{ - if ( ( i >= 0 ) && ( i < _THIS->n ) ) - return _THIS->type[i]; - - return ST_UNKNOWN; -} - - -/* - * g e t S t a t u s - */ -static inline SubjectToStatus Bounds_getStatus( Bounds* _THIS, int i ) -{ - if ( ( i >= 0 ) && ( i < _THIS->n ) ) - return _THIS->status[i]; - - return ST_UNDEFINED; -} - - -/* - * s e t T y p e - */ -static inline returnValue Bounds_setType( Bounds* _THIS, int i, SubjectToType value ) -{ - if ( ( i >= 0 ) && ( i < _THIS->n ) ) - { - _THIS->type[i] = value; - return SUCCESSFUL_RETURN; - } - else - return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); -} - - -/* - * s e t S t a t u s - */ -static inline returnValue Bounds_setStatus( Bounds* _THIS, int i, SubjectToStatus value ) -{ - if ( ( i >= 0 ) && ( i < _THIS->n ) ) - { - _THIS->status[i] = value; - return SUCCESSFUL_RETURN; - } - else - return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); -} - - -/* - * s e t N o L o w e r - */ -static inline void Bounds_setNoLower( Bounds* _THIS, BooleanType _status ) -{ - _THIS->noLower = _status; -} - - -/* - * s e t N o U p p e r - */ -static inline void Bounds_setNoUpper( Bounds* _THIS, BooleanType _status ) -{ - _THIS->noUpper = _status; -} - - -/* - * h a s N o L o w e r - */ -static inline BooleanType Bounds_hasNoLower( Bounds* _THIS ) -{ - return _THIS->noLower; -} - - -/* - * h a s N o U p p p e r - */ -static inline BooleanType Bounds_hasNoUpper( Bounds* _THIS ) -{ - return _THIS->noUpper; -} - - - -/* - * g e t N V - */ -static inline int Bounds_getNV( Bounds* _THIS ) -{ - return _THIS->n; -} - - -/* - * g e t N F V - */ -static inline int Bounds_getNFV( Bounds* _THIS ) -{ - return Bounds_getNumberOfType( _THIS,ST_EQUALITY ); -} - - -/* - * g e t N B V - */ -static inline int Bounds_getNBV( Bounds* _THIS ) -{ - return Bounds_getNumberOfType( _THIS,ST_BOUNDED ); -} - - -/* - * g e t N U V - */ -static inline int Bounds_getNUV( Bounds* _THIS ) -{ - return Bounds_getNumberOfType( _THIS,ST_UNBOUNDED ); -} - - -/* - * g e t N F R - */ -static inline int Bounds_getNFR( Bounds* _THIS ) -{ - return Indexlist_getLength( _THIS->freee ); -} - - -/* - * g e t N F X - */ -static inline int Bounds_getNFX( Bounds* _THIS ) -{ - return Indexlist_getLength( _THIS->fixed ); -} - - -/* - * g e t F r e e - */ -static inline Indexlist* Bounds_getFree( Bounds* _THIS ) -{ - return _THIS->freee; -} - - -/* - * g e t F i x e d - */ -static inline Indexlist* Bounds_getFixed( Bounds* _THIS ) -{ - return _THIS->fixed; -} - - -END_NAMESPACE_QPOASES - -#endif /* QPOASES_BOUNDS_H */ - - -/* - * end of file - */ diff --git a/third_party/acados/include/qpOASES_e/Constants.h b/third_party/acados/include/qpOASES_e/Constants.h deleted file mode 100644 index 13c777d..0000000 --- a/third_party/acados/include/qpOASES_e/Constants.h +++ /dev/null @@ -1,134 +0,0 @@ -/* - * This file is part of qpOASES. - * - * qpOASES -- An Implementation of the Online Active Set Strategy. - * Copyright (C) 2007-2015 by Hans Joachim Ferreau, Andreas Potschka, - * Christian Kirches et al. All rights reserved. - * - * qpOASES is free software; you can redistribute it and/or - * modify it under the terms of the GNU Lesser General Public - * License as published by the Free Software Foundation; either - * version 2.1 of the License, or (at your option) any later version. - * - * qpOASES is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public - * License along with qpOASES; if not, write to the Free Software - * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - * - */ - - -/** - * \file include/qpOASES_e/Constants.h - * \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches - * \version 3.1embedded - * \date 2007-2015 - * - * Definition of all global constants. - */ - - -#ifndef QPOASES_CONSTANTS_H -#define QPOASES_CONSTANTS_H - - -#include - -#ifdef __CODE_GENERATION__ - - #define CONVERTTOSTRINGAUX(x) #x - #define CONVERTTOSTRING(x) CONVERTTOSTRINGAUX(x) - - #ifndef QPOASES_CUSTOM_INTERFACE - #include "acado_qpoases3_interface.h" - #else - #include CONVERTTOSTRING(QPOASES_CUSTOM_INTERFACE) - #endif - -#endif - - -BEGIN_NAMESPACE_QPOASES - - -#ifndef __EXTERNAL_DIMENSIONS__ - - /*#define QPOASES_NVMAX 50 - #define QPOASES_NCMAX 100*/ - #define QPOASES_NVMAX 287 - #define QPOASES_NCMAX 709 - -#endif /* __EXTERNAL_DIMENSIONS__ */ - - -/** Maximum number of variables within a QP formulation. - * Note: this value has to be positive! */ -#define NVMAX QPOASES_NVMAX - -/** Maximum number of constraints within a QP formulation. - * Note: this value has to be positive! */ -#define NCMAX QPOASES_NCMAX - -#if ( QPOASES_NVMAX > QPOASES_NCMAX ) -#define NVCMAX QPOASES_NVMAX -#else -#define NVCMAX QPOASES_NCMAX -#endif - -#if ( QPOASES_NVMAX > QPOASES_NCMAX ) -#define NVCMIN QPOASES_NCMAX -#else -#define NVCMIN QPOASES_NVMAX -#endif - - -/** Maximum number of QPs in a sequence solved by means of the OQP interface. - * Note: this value has to be positive! */ -#define NQPMAX 1000 - - -/** Numerical value of machine precision (min eps, s.t. 1+eps > 1). - * Note: this value has to be positive! */ -#ifndef __CODE_GENERATION__ - - #ifdef __USE_SINGLE_PRECISION__ - static const real_t QPOASES_EPS = 1.193e-07; - #else - static const real_t QPOASES_EPS = 2.221e-16; - #endif /* __USE_SINGLE_PRECISION__ */ - -#endif /* __CODE_GENERATION__ */ - - -/** Numerical value of zero (for situations in which it would be - * unreasonable to compare with 0.0). - * Note: this value has to be positive! */ -static const real_t QPOASES_ZERO = 1.0e-25; - -/** Numerical value of infinity (e.g. for non-existing bounds). - * Note: this value has to be positive! */ -static const real_t QPOASES_INFTY = 1.0e20; - -/** Tolerance to used for isEqual, isZero etc. - * Note: this value has to be positive! */ -static const real_t QPOASES_TOL = 1.0e-25; - - -/** Maximum number of characters within a string. - * Note: this value should be at least 41! */ -#define QPOASES_MAX_STRING_LENGTH 160 - - -END_NAMESPACE_QPOASES - - -#endif /* QPOASES_CONSTANTS_H */ - - -/* - * end of file - */ diff --git a/third_party/acados/include/qpOASES_e/ConstraintProduct.h b/third_party/acados/include/qpOASES_e/ConstraintProduct.h deleted file mode 100644 index eb5400c..0000000 --- a/third_party/acados/include/qpOASES_e/ConstraintProduct.h +++ /dev/null @@ -1,62 +0,0 @@ -/* - * This file is part of qpOASES. - * - * qpOASES -- An Implementation of the Online Active Set Strategy. - * Copyright (C) 2007-2015 by Hans Joachim Ferreau, Andreas Potschka, - * Christian Kirches et al. All rights reserved. - * - * qpOASES is free software; you can redistribute it and/or - * modify it under the terms of the GNU Lesser General Public - * License as published by the Free Software Foundation; either - * version 2.1 of the License, or (at your option) any later version. - * - * qpOASES is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public - * License along with qpOASES; if not, write to the Free Software - * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - * - */ - - -/** - * \file include/qpOASES_e/ConstraintProduct.h - * \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches (thanks to D. Kwame Minde Kufoalor) - * \version 3.1embedded - * \date 2009-2015 - * - * Declaration of the ConstraintProduct interface which allows to specify a - * user-defined function for evaluating the constraint product at the - * current iterate to speed-up QP solution in case of a specially structured - * constraint matrix. - */ - - - -#ifndef QPOASES_CONSTRAINT_PRODUCT_H -#define QPOASES_CONSTRAINT_PRODUCT_H - - -BEGIN_NAMESPACE_QPOASES - - -/** - * \brief Interface for specifying user-defined evaluations of constraint products. - * - * An interface which allows to specify a user-defined function for evaluating the - * constraint product at the current iterate to speed-up QP solution in case - * of a specially structured constraint matrix. - * - * \author Hans Joachim Ferreau (thanks to Kwame Minde Kufoalor) - * \version 3.1embedded - * \date 2009-2015 - */ -typedef int(*ConstraintProduct)( int, const real_t* const, real_t* const ); - - -END_NAMESPACE_QPOASES - -#endif /* QPOASES_CONSTRAINT_PRODUCT_H */ diff --git a/third_party/acados/include/qpOASES_e/Constraints.h b/third_party/acados/include/qpOASES_e/Constraints.h deleted file mode 100644 index 8aca10d..0000000 --- a/third_party/acados/include/qpOASES_e/Constraints.h +++ /dev/null @@ -1,535 +0,0 @@ -/* - * This file is part of qpOASES. - * - * qpOASES -- An Implementation of the Online Active Set Strategy. - * Copyright (C) 2007-2015 by Hans Joachim Ferreau, Andreas Potschka, - * Christian Kirches et al. All rights reserved. - * - * qpOASES is free software; you can redistribute it and/or - * modify it under the terms of the GNU Lesser General Public - * License as published by the Free Software Foundation; either - * version 2.1 of the License, or (at your option) any later version. - * - * qpOASES is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public - * License along with qpOASES; if not, write to the Free Software - * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - * - */ - - -/** - * \file include/qpOASES_e/Constraints.h - * \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches - * \version 3.1embedded - * \date 2007-2015 - * - * Declaration of the Constraints class designed to manage working sets of - * constraints within a QProblem. - */ - - -#ifndef QPOASES_CONSTRAINTS_H -#define QPOASES_CONSTRAINTS_H - - -#include - - -BEGIN_NAMESPACE_QPOASES - - -/** - * \brief Manages working sets of constraints. - * - * This class manages working sets of constraints by storing - * index sets and other status information. - * - * \author Hans Joachim Ferreau - * \version 3.1embedded - * \date 2007-2015 - */ -typedef struct -{ - Indexlist *active; /**< Index list of active constraints. */ - Indexlist *inactive; /**< Index list of inactive constraints. */ - - Indexlist *shiftedActive; /**< Memory for shifting active constraints. */ - Indexlist *shiftedInactive; /**< Memory for shifting inactive constraints. */ - - Indexlist *rotatedActive; /**< Memory for rotating active constraints. */ - Indexlist *rotatedInactive; /**< Memory for rotating inactive constraints. */ - - SubjectToType *type; /**< Type of constraints. */ - SubjectToStatus *status; /**< Status of constraints. */ - - SubjectToType *typeTmp; /**< Temp memory for type of constraints. */ - SubjectToStatus *statusTmp; /**< Temp memory for status of constraints. */ - - BooleanType noLower; /**< This flag indicates if there is no lower bound on any variable. */ - BooleanType noUpper; /**< This flag indicates if there is no upper bound on any variable. */ - - int n; /**< Total number of constraints. */ -} Constraints; - -int Constraints_calculateMemorySize( int n); - -char *Constraints_assignMemory(int n, Constraints **mem, void *raw_memory); - -Constraints *Constraints_createMemory( int n ); - -/** Constructor which takes the number of constraints. */ -void ConstraintsCON( Constraints* _THIS, - int _n /**< Number of constraints. */ - ); - -/** Copies all members from given rhs object. - * \return SUCCESSFUL_RETURN */ -void ConstraintsCPY( Constraints* FROM, - Constraints* TO - ); - - -/** Initialises object with given number of constraints. - * \return SUCCESSFUL_RETURN \n - RET_INVALID_ARGUMENTS */ -returnValue Constraints_init( Constraints* _THIS, - int _n /**< Number of constraints. */ - ); - - -/** Initially adds number of a new (i.e. not yet in the list) constraint to - * a given index set. - * \return SUCCESSFUL_RETURN \n - RET_SETUP_CONSTRAINT_FAILED \n - RET_INDEX_OUT_OF_BOUNDS \n - RET_INVALID_ARGUMENTS */ -returnValue Constraints_setupConstraint( Constraints* _THIS, - int number, /**< Number of new constraint. */ - SubjectToStatus _status /**< Status of new constraint. */ - ); - -/** Initially adds all enabled numbers of new (i.e. not yet in the list) constraints to - * to the index set of inactive constraints; the order depends on the SujectToType - * of each index. Only disabled constraints are added to index set of disabled constraints! - * \return SUCCESSFUL_RETURN \n - RET_SETUP_CONSTRAINT_FAILED */ -returnValue Constraints_setupAllInactive( Constraints* _THIS - ); - -/** Initially adds all enabled numbers of new (i.e. not yet in the list) constraints to - * to the index set of active constraints (on their lower bounds); the order depends on the SujectToType - * of each index. Only disabled constraints are added to index set of disabled constraints! - * \return SUCCESSFUL_RETURN \n - RET_SETUP_CONSTRAINT_FAILED */ -returnValue Constraints_setupAllLower( Constraints* _THIS - ); - -/** Initially adds all enabled numbers of new (i.e. not yet in the list) constraints to - * to the index set of active constraints (on their upper bounds); the order depends on the SujectToType - * of each index. Only disabled constraints are added to index set of disabled constraints! - * \return SUCCESSFUL_RETURN \n - RET_SETUP_CONSTRAINT_FAILED */ -returnValue Constraints_setupAllUpper( Constraints* _THIS - ); - - -/** Moves index of a constraint from index list of active to that of inactive constraints. - * \return SUCCESSFUL_RETURN \n - RET_MOVING_CONSTRAINT_FAILED */ -returnValue Constraints_moveActiveToInactive( Constraints* _THIS, - int number /**< Number of constraint to become inactive. */ - ); - -/** Moves index of a constraint from index list of inactive to that of active constraints. - * \return SUCCESSFUL_RETURN \n - RET_MOVING_CONSTRAINT_FAILED */ -returnValue Constraints_moveInactiveToActive( Constraints* _THIS, - int number, /**< Number of constraint to become active. */ - SubjectToStatus _status /**< Status of constraint to become active. */ - ); - -/** Flip fixed constraint. - * \return SUCCESSFUL_RETURN \n - RET_MOVING_CONSTRAINT_FAILED \n - RET_INDEX_OUT_OF_BOUNDS */ -returnValue Constraints_flipFixed( Constraints* _THIS, - int number - ); - - -/** Returns the number of constraints. - * \return Number of constraints. */ -static inline int Constraints_getNC( Constraints* _THIS - ); - -/** Returns the number of implicit equality constraints. - * \return Number of implicit equality constraints. */ -static inline int Constraints_getNEC( Constraints* _THIS - ); - -/** Returns the number of "real" inequality constraints. - * \return Number of "real" inequality constraints. */ -static inline int Constraints_getNIC( Constraints* _THIS - ); - -/** Returns the number of unbounded constraints (i.e. without any bounds). - * \return Number of unbounded constraints (i.e. without any bounds). */ -static inline int Constraints_getNUC( Constraints* _THIS - ); - -/** Returns the number of active constraints. - * \return Number of active constraints. */ -static inline int Constraints_getNAC( Constraints* _THIS - ); - -/** Returns the number of inactive constraints. - * \return Number of inactive constraints. */ -static inline int Constraints_getNIAC( Constraints* _THIS - ); - - -/** Returns a pointer to active constraints index list. - * \return Pointer to active constraints index list. */ -static inline Indexlist* Constraints_getActive( Constraints* _THIS - ); - -/** Returns a pointer to inactive constraints index list. - * \return Pointer to inactive constraints index list. */ -static inline Indexlist* Constraints_getInactive( Constraints* _THIS - ); - - -/** Returns number of constraints with given SubjectTo type. - * \return Number of constraints with given type. */ -static inline int Constraints_getNumberOfType( Constraints* _THIS, - SubjectToType _type /**< Type of constraints' bound. */ - ); - - -/** Returns type of constraints' bound. - * \return Type of constraints' bound \n - RET_INDEX_OUT_OF_BOUNDS */ -static inline SubjectToType Constraints_getType( Constraints* _THIS, - int i /**< Number of constraints' bound. */ - ); - -/** Returns status of constraints' bound. - * \return Status of constraints' bound \n - ST_UNDEFINED */ -static inline SubjectToStatus Constraints_getStatus( Constraints* _THIS, - int i /**< Number of constraints' bound. */ - ); - - -/** Sets type of constraints' bound. - * \return SUCCESSFUL_RETURN \n - RET_INDEX_OUT_OF_BOUNDS */ -static inline returnValue Constraints_setType( Constraints* _THIS, - int i, /**< Number of constraints' bound. */ - SubjectToType value /**< Type of constraints' bound. */ - ); - -/** Sets status of constraints' bound. - * \return SUCCESSFUL_RETURN \n - RET_INDEX_OUT_OF_BOUNDS */ -static inline returnValue Constraints_setStatus( Constraints* _THIS, - int i, /**< Number of constraints' bound. */ - SubjectToStatus value /**< Status of constraints' bound. */ - ); - - -/** Sets status of lower constraints' bounds. */ -static inline void Constraints_setNoLower( Constraints* _THIS, - BooleanType _status /**< Status of lower constraints' bounds. */ - ); - -/** Sets status of upper constraints' bounds. */ -static inline void Constraints_setNoUpper( Constraints* _THIS, - BooleanType _status /**< Status of upper constraints' bounds. */ - ); - - -/** Returns status of lower constraints' bounds. - * \return BT_TRUE if there is no lower constraints' bound on any variable. */ -static inline BooleanType Constraints_hasNoLower( Constraints* _THIS - ); - -/** Returns status of upper bounds. - * \return BT_TRUE if there is no upper constraints' bound on any variable. */ -static inline BooleanType Constraints_hasNoUpper( Constraints* _THIS - ); - - -/** Shifts forward type and status of all constraints by a given - * offset. This offset has to lie within the range [0,n/2] and has to - * be an integer divisor of the total number of constraints n. - * Type and status of the first \ constraints is thrown away, - * type and status of the last \ constraints is doubled, - * e.g. for offset = 2: \n - * shift( {c/b1,c/b2,c/b3,c/b4,c/b5,c/b6} ) = {c/b3,c/b4,c/b5,c/b6,c/b5,c/b6} - * \return SUCCESSFUL_RETURN \n - RET_INDEX_OUT_OF_BOUNDS \n - RET_INVALID_ARGUMENTS \n - RET_SHIFTING_FAILED */ -returnValue Constraints_shift( Constraints* _THIS, - int offset /**< Shift offset within the range [0,n/2] and integer divisor of n. */ - ); - -/** Rotates forward type and status of all constraints by a given - * offset. This offset has to lie within the range [0,n]. - * Example for offset = 2: \n - * rotate( {c1,c2,c3,c4,c5,c6} ) = {c3,c4,c5,c6,c1,c2} - * \return SUCCESSFUL_RETURN \n - RET_INDEX_OUT_OF_BOUNDS \n - RET_ROTATING_FAILED */ -returnValue Constraints_rotate( Constraints* _THIS, - int offset /**< Rotation offset within the range [0,n]. */ - ); - - -/** Prints information on constraints object - * (in particular, lists of inactive and active constraints. - * \return SUCCESSFUL_RETURN \n - RET_INDEXLIST_CORRUPTED */ -returnValue Constraints_print( Constraints* _THIS - ); - - -/** Initially adds all numbers of new (i.e. not yet in the list) bounds to - * to the index set corresponding to the desired status; - * the order depends on the SujectToType of each index. - * \return SUCCESSFUL_RETURN \n - RET_SETUP_CONSTRAINT_FAILED */ -returnValue Constraints_setupAll( Constraints* _THIS, - SubjectToStatus _status /**< Desired initial status for all bounds. */ - ); - - -/** Adds the index of a new constraint to index set. - * \return SUCCESSFUL_RETURN \n - RET_ADDINDEX_FAILED \n - RET_INVALID_ARGUMENTS */ -returnValue Constraints_addIndex( Constraints* _THIS, - Indexlist* const indexlist, /**< Index list to which the new index shall be added. */ - int newnumber, /**< Number of new constraint. */ - SubjectToStatus newstatus /**< Status of new constraint. */ - ); - -/** Removes the index of a constraint from index set. - * \return SUCCESSFUL_RETURN \n - RET_REMOVEINDEX_FAILED \n - RET_INVALID_ARGUMENTS */ -returnValue Constraints_removeIndex( Constraints* _THIS, - Indexlist* const indexlist, /**< Index list from which the new index shall be removed. */ - int removenumber /**< Number of constraint to be removed. */ - ); - -/** Swaps the indices of two constraints or bounds within the index set. - * \return SUCCESSFUL_RETURN \n - RET_SWAPINDEX_FAILED \n - RET_INVALID_ARGUMENTS */ -returnValue Constraints_swapIndex( Constraints* _THIS, - Indexlist* const indexlist, /**< Index list in which the indices shold be swapped. */ - int number1, /**< Number of first constraint. */ - int number2 /**< Number of second constraint. */ - ); - - - -/* - * g e t N u m b e r O f T y p e - */ -static inline int Constraints_getNumberOfType( Constraints* _THIS, SubjectToType _type ) -{ - int i; - int numberOfType = 0; - - if ( _THIS->type != 0 ) - { - for( i=0; i<_THIS->n; ++i ) - if ( _THIS->type[i] == _type ) - ++numberOfType; - } - - return numberOfType; -} - - -/* - * g e t T y p e - */ -static inline SubjectToType Constraints_getType( Constraints* _THIS, int i ) -{ - if ( ( i >= 0 ) && ( i < _THIS->n ) ) - return _THIS->type[i]; - - return ST_UNKNOWN; -} - - -/* - * g e t S t a t u s - */ -static inline SubjectToStatus Constraints_getStatus( Constraints* _THIS, int i ) -{ - if ( ( i >= 0 ) && ( i < _THIS->n ) ) - return _THIS->status[i]; - - return ST_UNDEFINED; -} - - -/* - * s e t T y p e - */ -static inline returnValue Constraints_setType( Constraints* _THIS, int i, SubjectToType value ) -{ - if ( ( i >= 0 ) && ( i < _THIS->n ) ) - { - _THIS->type[i] = value; - return SUCCESSFUL_RETURN; - } - else - return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); -} - - -/* - * s e t S t a t u s - */ -static inline returnValue Constraints_setStatus( Constraints* _THIS, int i, SubjectToStatus value ) -{ - if ( ( i >= 0 ) && ( i < _THIS->n ) ) - { - _THIS->status[i] = value; - return SUCCESSFUL_RETURN; - } - else - return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); -} - - -/* - * s e t N o L o w e r - */ -static inline void Constraints_setNoLower( Constraints* _THIS, BooleanType _status ) -{ - _THIS->noLower = _status; -} - - -/* - * s e t N o U p p e r - */ -static inline void Constraints_setNoUpper( Constraints* _THIS, BooleanType _status ) -{ - _THIS->noUpper = _status; -} - - -/* - * h a s N o L o w e r - */ -static inline BooleanType Constraints_hasNoLower( Constraints* _THIS ) -{ - return _THIS->noLower; -} - - -/* - * h a s N o U p p p e r - */ -static inline BooleanType Constraints_hasNoUpper( Constraints* _THIS ) -{ - return _THIS->noUpper; -} - - - -/* - * g e t N C - */ -static inline int Constraints_getNC( Constraints* _THIS ) -{ - return _THIS->n; -} - - -/* - * g e t N E C - */ -static inline int Constraints_getNEC( Constraints* _THIS ) -{ - return Constraints_getNumberOfType( _THIS,ST_EQUALITY ); -} - - -/* - * g e t N I C - */ -static inline int Constraints_getNIC( Constraints* _THIS ) -{ - return Constraints_getNumberOfType( _THIS,ST_BOUNDED ); -} - - -/* - * g e t N U C - */ -static inline int Constraints_getNUC( Constraints* _THIS ) -{ - return Constraints_getNumberOfType( _THIS,ST_UNBOUNDED ); -} - - -/* - * g e t N A C - */ -static inline int Constraints_getNAC( Constraints* _THIS ) -{ - return Indexlist_getLength( _THIS->active ); -} - - -/* - * g e t N I A C - */ -static inline int Constraints_getNIAC( Constraints* _THIS ) -{ - return Indexlist_getLength( _THIS->inactive ); -} - - - -/* - * g e t A c t i v e - */ -static inline Indexlist* Constraints_getActive( Constraints* _THIS ) -{ - return _THIS->active; -} - - -/* - * g e t I n a c t i v e - */ -static inline Indexlist* Constraints_getInactive( Constraints* _THIS ) -{ - return _THIS->inactive; -} - - -END_NAMESPACE_QPOASES - - -#endif /* QPOASES_CONSTRAINTS_H */ - - -/* - * end of file - */ diff --git a/third_party/acados/include/qpOASES_e/Flipper.h b/third_party/acados/include/qpOASES_e/Flipper.h deleted file mode 100644 index 63526a3..0000000 --- a/third_party/acados/include/qpOASES_e/Flipper.h +++ /dev/null @@ -1,129 +0,0 @@ -/* - * This file is part of qpOASES. - * - * qpOASES -- An Implementation of the Online Active Set Strategy. - * Copyright (C) 2007-2015 by Hans Joachim Ferreau, Andreas Potschka, - * Christian Kirches et al. All rights reserved. - * - * qpOASES is free software; you can redistribute it and/or - * modify it under the terms of the GNU Lesser General Public - * License as published by the Free Software Foundation; either - * version 2.1 of the License, or (at your option) any later version. - * - * qpOASES is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public - * License along with qpOASES; if not, write to the Free Software - * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - * - */ - - -/** - * \file include/qpOASES_e/Flipper.h - * \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches - * \version 3.1embedded - * \date 2007-2015 - * - * Declaration of the Options class designed to manage user-specified - * options for solving a QProblem. - */ - - -#ifndef QPOASES_FLIPPER_H -#define QPOASES_FLIPPER_H - - -#include -#include - - -BEGIN_NAMESPACE_QPOASES - - -/** - * \brief Auxiliary class for storing a copy of the current matrix factorisations. - * - * This auxiliary class stores a copy of the current matrix factorisations. It - * is used by the classe QProblemB and QProblem in case flipping bounds are enabled. - * - * \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches - * \version 3.1embedded - * \date 2007-2015 - */ -typedef struct -{ - Bounds *bounds; /**< Data structure for problem's bounds. */ - Constraints *constraints; /**< Data structure for problem's constraints. */ - - real_t *R; /**< Cholesky factor of H (i.e. H = R^T*R). */ - real_t *Q; /**< Orthonormal quadratic matrix, A = [0 T]*Q'. */ - real_t *T; /**< Reverse triangular matrix, A = [0 T]*Q'. */ - - unsigned int nV; /**< Number of variables. */ - unsigned int nC; /**< Number of constraints. */ -} Flipper; - -int Flipper_calculateMemorySize( unsigned int nV, unsigned int nC ); - -char *Flipper_assignMemory( unsigned int nV, unsigned int nC, Flipper **mem, void *raw_memory ); - -Flipper *Flipper_createMemory( unsigned int nV, unsigned int nC ); - -/** Constructor which takes the number of bounds and constraints. */ -void FlipperCON( Flipper* _THIS, - unsigned int _nV, /**< Number of bounds. */ - unsigned int _nC /**< Number of constraints. */ - ); - -/** Copy constructor (deep copy). */ -void FlipperCPY( Flipper* FROM, - Flipper* TO - ); - -/** Initialises object with given number of bounds and constraints. - * \return SUCCESSFUL_RETURN \n - RET_INVALID_ARGUMENTS */ -returnValue Flipper_init( Flipper* _THIS, - unsigned int _nV, /**< Number of bounds. */ - unsigned int _nC /**< Number of constraints. */ - ); - - -/** Copies current values to non-null arguments (assumed to be allocated with consistent size). - * \return SUCCESSFUL_RETURN */ -returnValue Flipper_get( Flipper* _THIS, - Bounds* const _bounds, /**< Pointer to new bounds. */ - real_t* const R, /**< New matrix R. */ - Constraints* const _constraints, /**< Pointer to new constraints. */ - real_t* const _Q, /**< New matrix Q. */ - real_t* const _T /**< New matrix T. */ - ); - -/** Assigns new values to non-null arguments. - * \return SUCCESSFUL_RETURN */ -returnValue Flipper_set( Flipper* _THIS, - const Bounds* const _bounds, /**< Pointer to new bounds. */ - const real_t* const _R, /**< New matrix R. */ - const Constraints* const _constraints, /**< Pointer to new constraints. */ - const real_t* const _Q, /**< New matrix Q. */ - const real_t* const _T /**< New matrix T. */ - ); - -/** Returns dimension of matrix T. - * \return Dimension of matrix T. */ -unsigned int Flipper_getDimT( Flipper* _THIS ); - - -END_NAMESPACE_QPOASES - - -#endif /* QPOASES_FLIPPER_H */ - - -/* - * end of file - */ diff --git a/third_party/acados/include/qpOASES_e/Indexlist.h b/third_party/acados/include/qpOASES_e/Indexlist.h deleted file mode 100644 index 02d259d..0000000 --- a/third_party/acados/include/qpOASES_e/Indexlist.h +++ /dev/null @@ -1,221 +0,0 @@ -/* - * This file is part of qpOASES. - * - * qpOASES -- An Implementation of the Online Active Set Strategy. - * Copyright (C) 2007-2015 by Hans Joachim Ferreau, Andreas Potschka, - * Christian Kirches et al. All rights reserved. - * - * qpOASES is free software; you can redistribute it and/or - * modify it under the terms of the GNU Lesser General Public - * License as published by the Free Software Foundation; either - * version 2.1 of the License, or (at your option) any later version. - * - * qpOASES is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public - * License along with qpOASES; if not, write to the Free Software - * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - * - */ - - -/** - * \file include/qpOASES_e/Indexlist.h - * \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches - * \version 3.1embedded - * \date 2007-2015 - * - * Declaration of the Indexlist class designed to manage index lists of - * constraints and bounds within a SubjectTo object. - */ - - -#ifndef QPOASES_INDEXLIST_H -#define QPOASES_INDEXLIST_H - - -#include - - -BEGIN_NAMESPACE_QPOASES - - -/** - * \brief Stores and manages index lists. - * - * This class manages index lists of active/inactive bounds/constraints. - * - * \author Hans Joachim Ferreau - * \version 3.1embedded - * \date 2007-2015 - */ -typedef struct -{ - int *number; /**< Array to store numbers of constraints or bounds. */ - int *iSort; /**< Index list to sort vector \a number */ - - int length; /**< Length of index list. */ - int first; /**< Physical index of first element. */ - int last; /**< Physical index of last element. */ - int lastusedindex; /**< Physical index of last entry in index list. */ - int physicallength; /**< Physical length of index list. */ -} Indexlist; - -int Indexlist_calculateMemorySize( int n); - -char *Indexlist_assignMemory(int n, Indexlist **mem, void *raw_memory); - -Indexlist *Indexlist_createMemory( int n ); - -/** Constructor which takes the desired physical length of the index list. */ -void IndexlistCON( Indexlist* _THIS, - int n /**< Physical length of index list. */ - ); - -/** Copies all members from given rhs object. - * \return SUCCESSFUL_RETURN */ -void IndexlistCPY( Indexlist* FROM, - Indexlist* TO - ); - -/** Initialises index list of desired physical length. - * \return SUCCESSFUL_RETURN \n - RET_INVALID_ARGUMENTS */ -returnValue Indexlist_init( Indexlist* _THIS, - int n /**< Physical length of index list. */ - ); - -/** Creates an array of all numbers within the index set in correct order. - * \return SUCCESSFUL_RETURN \n - RET_INDEXLIST_CORRUPTED */ -returnValue Indexlist_getNumberArray( Indexlist* _THIS, - int** const numberarray /**< Output: Array of numbers (NULL on error). */ - ); - -/** Creates an array of all numbers within the index set in correct order. - * \return SUCCESSFUL_RETURN \n - RET_INDEXLIST_CORRUPTED */ -returnValue Indexlist_getISortArray( Indexlist* _THIS, - int** const iSortArray /**< Output: iSort Array. */ - ); - - -/** Determines the index within the index list at which a given number is stored. - * \return >= 0: Index of given number. \n - -1: Number not found. */ -int Indexlist_getIndex( Indexlist* _THIS, - int givennumber /**< Number whose index shall be determined. */ - ); - -/** Returns the number stored at a given physical index. - * \return >= 0: Number stored at given physical index. \n - -RET_INDEXLIST_OUTOFBOUNDS */ -static inline int Indexlist_getNumber( Indexlist* _THIS, - int physicalindex /**< Physical index of the number to be returned. */ - ); - - -/** Returns the current length of the index list. - * \return Current length of the index list. */ -static inline int Indexlist_getLength( Indexlist* _THIS - ); - -/** Returns last number within the index list. - * \return Last number within the index list. */ -static inline int Indexlist_getLastNumber( Indexlist* _THIS - ); - - -/** Adds number to index list. - * \return SUCCESSFUL_RETURN \n - RET_INDEXLIST_MUST_BE_REORDERD \n - RET_INDEXLIST_EXCEEDS_MAX_LENGTH */ -returnValue Indexlist_addNumber( Indexlist* _THIS, - int addnumber /**< Number to be added. */ - ); - -/** Removes number from index list. - * \return SUCCESSFUL_RETURN */ -returnValue Indexlist_removeNumber( Indexlist* _THIS, - int removenumber /**< Number to be removed. */ - ); - -/** Swaps two numbers within index list. - * \return SUCCESSFUL_RETURN */ -returnValue Indexlist_swapNumbers( Indexlist* _THIS, - int number1, /**< First number for swapping. */ - int number2 /**< Second number for swapping. */ - ); - -/** Determines if a given number is contained in the index set. - * \return BT_TRUE iff number is contain in the index set */ -static inline BooleanType Indexlist_isMember( Indexlist* _THIS, - int _number /**< Number to be tested for membership. */ - ); - - -/** Find first index j between -1 and length in sorted list of indices - * iSort such that numbers[iSort[j]] <= i < numbers[iSort[j+1]]. Uses - * bisection. - * \return j. */ -int Indexlist_findInsert( Indexlist* _THIS, - int i - ); - - - -/* - * g e t N u m b e r - */ -static inline int Indexlist_getNumber( Indexlist* _THIS, int physicalindex ) -{ - /* consistency check */ - if ( ( physicalindex < 0 ) || ( physicalindex > _THIS->length ) ) - return -RET_INDEXLIST_OUTOFBOUNDS; - - return _THIS->number[physicalindex]; -} - - -/* - * g e t L e n g t h - */ -static inline int Indexlist_getLength( Indexlist* _THIS ) -{ - return _THIS->length; -} - - -/* - * g e t L a s t N u m b e r - */ -static inline int Indexlist_getLastNumber( Indexlist* _THIS ) -{ - return _THIS->number[_THIS->length-1]; -} - - -/* - * g e t L a s t N u m b e r - */ -static inline BooleanType Indexlist_isMember( Indexlist* _THIS, int _number ) -{ - if ( Indexlist_getIndex( _THIS,_number ) >= 0 ) - return BT_TRUE; - else - return BT_FALSE; -} - - -END_NAMESPACE_QPOASES - - -#endif /* QPOASES_INDEXLIST_H */ - - -/* - * end of file - */ diff --git a/third_party/acados/include/qpOASES_e/Matrices.h b/third_party/acados/include/qpOASES_e/Matrices.h deleted file mode 100644 index e2a46b3..0000000 --- a/third_party/acados/include/qpOASES_e/Matrices.h +++ /dev/null @@ -1,287 +0,0 @@ -/* - * This file is part of qpOASES. - * - * qpOASES -- An Implementation of the Online Active Set Strategy. - * Copyright (C) 2007-2015 by Hans Joachim Ferreau, Andreas Potschka, - * Christian Kirches et al. All rights reserved. - * - * qpOASES is free software; you can redistribute it and/or - * modify it under the terms of the GNU Lesser General Public - * License as published by the Free Software Foundation; either - * version 2.1 of the License, or (at your option) any later version. - * - * qpOASES is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public - * License along with qpOASES; if not, write to the Free Software - * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - * - */ - - -/** - * \file include/qpOASES_e/Matrices.h - * \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches - * \version 3.1embedded - * \date 2009-2015 - * - * Various matrix classes: Abstract base matrix class, dense and sparse matrices, - * including symmetry exploiting specializations. - */ - - - -#ifndef QPOASES_MATRICES_H -#define QPOASES_MATRICES_H - -#ifdef __USE_SINGLE_PRECISION__ - - // single precision - #define GEMM sgemm_ - #define GEMV sgemv_ -// #define SYR ssyr_ -// #define SYR2 ssyr2_ - #define POTRF spotrf_ - -#else - - // double precision - #define GEMM dgemm_ - #define GEMV dgemv_ -// #define SYR dsyr_ -// #define SYR2 dsyr2_ - #define POTRF dpotrf_ - -#endif /* __USE_SINGLE_PRECISION__ */ - - -#ifdef EXTERNAL_BLAS - // double precision - void dgemm_(char *ta, char *tb, int *m, int *n, int *k, double *alpha, double *A, int *lda, double *B, int ldb, double *beta, double *C, int *ldc); - void dgemv_(char *ta, int *m, int *n, double *alpha, double *A, int *lda, double *x, int *incx, double *beta, double *y, int *incy); - void dpotrf_(char *uplo, int *m, double *A, int *lda, int *info); - // single precision - void sgemm_(char *ta, char *tb, int *m, int *n, int *k, float *alpha, float *A, int *lda, float *B, int ldb, float *beta, float *C, int *ldc); - void sgemv_(char *ta, int *m, int *n, float *alpha, float *A, int *lda, float *x, int *incx, float *beta, float *y, int *incy); - void spotrf_(char *uplo, int *m, float *A, int *lda, int *info); -#else - /** Performs one of the matrix-matrix operation in double precision. */ - void dgemm_ ( const char*, const char*, const unsigned long*, const unsigned long*, const unsigned long*, - const double*, const double*, const unsigned long*, const double*, const unsigned long*, - const double*, double*, const unsigned long* ); - /** Performs one of the matrix-matrix operation in single precision. */ - void sgemm_ ( const char*, const char*, const unsigned long*, const unsigned long*, const unsigned long*, - const float*, const float*, const unsigned long*, const float*, const unsigned long*, - const float*, float*, const unsigned long* ); - - /** Calculates the Cholesky factorization of a real symmetric positive definite matrix in double precision. */ - void dpotrf_ ( const char *, const unsigned long *, double *, const unsigned long *, long * ); - /** Calculates the Cholesky factorization of a real symmetric positive definite matrix in single precision. */ - void spotrf_ ( const char *, const unsigned long *, float *, const unsigned long *, long * ); - -#endif - - /** Performs a symmetric rank 1 operation in double precision. */ -// void dsyr_ ( const char *, const unsigned long *, const double *, const double *, -// const unsigned long *, double *, const unsigned long *); - /** Performs a symmetric rank 1 operation in single precision. */ -// void ssyr_ ( const char *, const unsigned long *, const float *, const float *, -// const unsigned long *, float *, const unsigned long *); - - /** Performs a symmetric rank 2 operation in double precision. */ -// void dsyr2_ ( const char *, const unsigned long *, const double *, const double *, -// const unsigned long *, const double *, const unsigned long *, double *, const unsigned long *); - /** Performs a symmetric rank 2 operation in single precision. */ -// void ssyr2_ ( const char *, const unsigned long *, const float *, const float *, -// const unsigned long *, const float *, const unsigned long *, float *, const unsigned long *); - - -#include - - -BEGIN_NAMESPACE_QPOASES - - -/** - * \brief Interfaces matrix-vector operations tailored to general dense matrices. - * - * Dense matrix class (row major format). - * - * \author Andreas Potschka, Christian Kirches, Hans Joachim Ferreau - * \version 3.1embedded - * \date 2011-2015 - */ -typedef struct -{ - real_t *val; /**< Vector of entries. */ - int nRows; /**< Number of rows. */ - int nCols; /**< Number of columns. */ - int leaDim; /**< Leading dimension. */ -} DenseMatrix; - -int DenseMatrix_calculateMemorySize( int m, int n ); - -char *DenseMatrix_assignMemory( int m, int n, DenseMatrix **mem, void *raw_memory ); - -DenseMatrix *DenseMatrix_createMemory( int m, int n ); - -/** Constructor from vector of values. - * Caution: Data pointer must be valid throughout lifetime - */ -void DenseMatrixCON( DenseMatrix* _THIS, - int m, /**< Number of rows. */ - int n, /**< Number of columns. */ - int lD, /**< Leading dimension. */ - real_t *v /**< Values. */ - ); - -void DenseMatrixCPY( DenseMatrix* FROM, - DenseMatrix* TO - ); - - -/** Frees all internal memory. */ -void DenseMatrix_free( DenseMatrix* _THIS ); - -/** Constructor from vector of values. - * Caution: Data pointer must be valid throughout lifetime - */ -returnValue DenseMatrix_init( DenseMatrix* _THIS, - int m, /**< Number of rows. */ - int n, /**< Number of columns. */ - int lD, /**< Leading dimension. */ - real_t *v /**< Values. */ - ); - - -/** Returns i-th diagonal entry. - * \return i-th diagonal entry */ -real_t DenseMatrix_diag( DenseMatrix* _THIS, - int i /**< Index. */ - ); - -/** Checks whether matrix is square and diagonal. - * \return BT_TRUE iff matrix is square and diagonal; \n - * BT_FALSE otherwise. */ -BooleanType DenseMatrix_isDiag( DenseMatrix* _THIS ); - -/** Get the N-norm of the matrix - * \return N-norm of the matrix - */ -real_t DenseMatrix_getNorm( DenseMatrix* _THIS, - int type /**< Norm type, 1: one-norm, 2: Euclidean norm. */ - ); - -/** Get the N-norm of a row - * \return N-norm of row \a rNum - */ -real_t DenseMatrix_getRowNorm( DenseMatrix* _THIS, - int rNum, /**< Row number. */ - int type /**< Norm type, 1: one-norm, 2: Euclidean norm. */ - ); - -/** Retrieve indexed entries of matrix row multiplied by alpha. - * \return SUCCESSFUL_RETURN */ -returnValue DenseMatrix_getRow( DenseMatrix* _THIS, - int rNum, /**< Row number. */ - const Indexlist* const icols, /**< Index list specifying columns. */ - real_t alpha, /**< Scalar factor. */ - real_t *row /**< Output row vector. */ - ); - -/** Retrieve indexed entries of matrix column multiplied by alpha. - * \return SUCCESSFUL_RETURN */ - returnValue DenseMatrix_getCol( DenseMatrix* _THIS, - int cNum, /**< Column number. */ - const Indexlist* const irows, /**< Index list specifying rows. */ - real_t alpha, /**< Scalar factor. */ - real_t *col /**< Output column vector. */ - ); - -/** Evaluate Y=alpha*A*X + beta*Y. - * \return SUCCESSFUL_RETURN. */ -returnValue DenseMatrix_times( DenseMatrix* _THIS, - int xN, /**< Number of vectors to multiply. */ - real_t alpha, /**< Scalar factor for matrix vector product. */ - const real_t *x, /**< Input vector to be multiplied. */ - int xLD, /**< Leading dimension of input x. */ - real_t beta, /**< Scalar factor for y. */ - real_t *y, /**< Output vector of results. */ - int yLD /**< Leading dimension of output y. */ - ); - -/** Evaluate Y=alpha*A'*X + beta*Y. - * \return SUCCESSFUL_RETURN. */ -returnValue DenseMatrix_transTimes( DenseMatrix* _THIS, - int xN, /**< Number of vectors to multiply. */ - real_t alpha, /**< Scalar factor for matrix vector product. */ - const real_t *x, /**< Input vector to be multiplied. */ - int xLD, /**< Leading dimension of input x. */ - real_t beta, /**< Scalar factor for y. */ - real_t *y, /**< Output vector of results. */ - int yLD /**< Leading dimension of output y. */ - ); - -/** Evaluate matrix vector product with submatrix given by Indexlist. - * \return SUCCESSFUL_RETURN */ - returnValue DenseMatrix_subTimes( DenseMatrix* _THIS, - const Indexlist* const irows, /**< Index list specifying rows. */ - const Indexlist* const icols, /**< Index list specifying columns. */ - int xN, /**< Number of vectors to multiply. */ - real_t alpha, /**< Scalar factor for matrix vector product. */ - const real_t *x, /**< Input vector to be multiplied. */ - int xLD, /**< Leading dimension of input x. */ - real_t beta, /**< Scalar factor for y. */ - real_t *y, /**< Output vector of results. */ - int yLD, /**< Leading dimension of output y. */ - BooleanType yCompr /**< Compressed storage for y. */ - ); - -/** Evaluate matrix transpose vector product. - * \return SUCCESSFUL_RETURN */ -returnValue DenseMatrix_subTransTimes( DenseMatrix* _THIS, - const Indexlist* const irows, /**< Index list specifying rows. */ - const Indexlist* const icols, /**< Index list specifying columns. */ - int xN, /**< Number of vectors to multiply. */ - real_t alpha, /**< Scalar factor for matrix vector product. */ - const real_t *x, /**< Input vector to be multiplied. */ - int xLD, /**< Leading dimension of input x. */ - real_t beta, /**< Scalar factor for y. */ - real_t *y, /**< Output vector of results. */ - int yLD /**< Leading dimension of output y. */ - ); - -/** Adds given offset to diagonal of matrix. - * \return SUCCESSFUL_RETURN \n - RET_NO_DIAGONAL_AVAILABLE */ -returnValue DenseMatrix_addToDiag( DenseMatrix* _THIS, - real_t alpha /**< Diagonal offset. */ - ); - -/** Prints matrix to screen. - * \return SUCCESSFUL_RETURN */ -returnValue DenseMatrix_print( DenseMatrix* _THIS - ); - -static inline real_t* DenseMatrix_getVal( DenseMatrix* _THIS ) { return _THIS->val; } - -/** Compute bilinear form y = x'*H*x using submatrix given by index list. - * \return SUCCESSFUL_RETURN */ -returnValue DenseMatrix_bilinear( DenseMatrix* _THIS, - const Indexlist* const icols, /**< Index list specifying columns of x. */ - int xN, /**< Number of vectors to multiply. */ - const real_t *x, /**< Input vector to be multiplied (uncompressed). */ - int xLD, /**< Leading dimension of input x. */ - real_t *y, /**< Output vector of results (compressed). */ - int yLD /**< Leading dimension of output y. */ - ); - - - -END_NAMESPACE_QPOASES - - -#endif /* QPOASES_MATRICES_H */ diff --git a/third_party/acados/include/qpOASES_e/MessageHandling.h b/third_party/acados/include/qpOASES_e/MessageHandling.h deleted file mode 100644 index fe55249..0000000 --- a/third_party/acados/include/qpOASES_e/MessageHandling.h +++ /dev/null @@ -1,544 +0,0 @@ -/* - * This file is part of qpOASES. - * - * qpOASES -- An Implementation of the Online Active Set Strategy. - * Copyright (C) 2007-2015 by Hans Joachim Ferreau, Andreas Potschka, - * Christian Kirches et al. All rights reserved. - * - * qpOASES is free software; you can redistribute it and/or - * modify it under the terms of the GNU Lesser General Public - * License as published by the Free Software Foundation; either - * version 2.1 of the License, or (at your option) any later version. - * - * qpOASES is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public - * License along with qpOASES; if not, write to the Free Software - * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - * - */ - - -/** - * \file include/qpOASES_e/MessageHandling.h - * \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches (thanks to Leonard Wirsching) - * \version 3.1embedded - * \date 2007-2015 - * - * Declaration of the MessageHandling class including global return values. - */ - - -#ifndef QPOASES_MESSAGEHANDLING_H -#define QPOASES_MESSAGEHANDLING_H - - -#include -#include -#include -#include - -#include - - -BEGIN_NAMESPACE_QPOASES - - -/** Default file to display messages. */ -#define stdFile stderr - - -/** - * \brief Defines all symbols for global return values. - * - * The enumeration returnValueType defines all symbols for global return values. - * Important: All return values are assumed to be nonnegative! - * - * \author Hans Joachim Ferreau - */ -typedef enum -{ -TERMINAL_LIST_ELEMENT = -1, /**< Terminal list element, internal usage only! */ -/* miscellaneous */ -SUCCESSFUL_RETURN = 0, /**< Successful return. */ -RET_DIV_BY_ZERO, /**< Division by zero. */ -RET_INDEX_OUT_OF_BOUNDS, /**< Index out of bounds. */ -RET_INVALID_ARGUMENTS, /**< At least one of the arguments is invalid. */ -RET_ERROR_UNDEFINED, /**< Error number undefined. */ -RET_WARNING_UNDEFINED, /**< Warning number undefined. */ -RET_INFO_UNDEFINED, /**< Info number undefined. */ -RET_EWI_UNDEFINED, /**< Error/warning/info number undefined. */ -RET_AVAILABLE_WITH_LINUX_ONLY, /**< This function is available under Linux only. */ -RET_UNKNOWN_BUG, /**< The error occurred is not yet known. */ -RET_PRINTLEVEL_CHANGED, /**< Print level changed. (10) */ -RET_NOT_YET_IMPLEMENTED, /**< Requested function is not yet implemented in this version of qpOASES. */ -/* Indexlist */ -RET_INDEXLIST_MUST_BE_REORDERD, /**< Index list has to be reordered. */ -RET_INDEXLIST_EXCEEDS_MAX_LENGTH, /**< Index list exceeds its maximal physical length. */ -RET_INDEXLIST_CORRUPTED, /**< Index list corrupted. */ -RET_INDEXLIST_OUTOFBOUNDS, /**< Physical index is out of bounds. */ -RET_INDEXLIST_ADD_FAILED, /**< Adding indices from another index set failed. */ -RET_INDEXLIST_INTERSECT_FAILED, /**< Intersection with another index set failed. */ -/* SubjectTo / Bounds / Constraints */ -RET_INDEX_ALREADY_OF_DESIRED_STATUS, /**< Index is already of desired status. (18) */ -RET_ADDINDEX_FAILED, /**< Adding index to index set failed. */ -RET_REMOVEINDEX_FAILED, /**< Removing index from index set failed. (20) */ -RET_SWAPINDEX_FAILED, /**< Cannot swap between different indexsets. */ -RET_NOTHING_TO_DO, /**< Nothing to do. */ -RET_SETUP_BOUND_FAILED, /**< Setting up bound index failed. */ -RET_SETUP_CONSTRAINT_FAILED, /**< Setting up constraint index failed. */ -RET_MOVING_BOUND_FAILED, /**< Moving bound between index sets failed. */ -RET_MOVING_CONSTRAINT_FAILED, /**< Moving constraint between index sets failed. */ -RET_SHIFTING_FAILED, /**< Shifting of bounds/constraints failed. */ -RET_ROTATING_FAILED, /**< Rotating of bounds/constraints failed. */ -/* QProblem */ -RET_QPOBJECT_NOT_SETUP, /**< The QP object has not been setup correctly, use another constructor. */ -RET_QP_ALREADY_INITIALISED, /**< QProblem has already been initialised. (30) */ -RET_NO_INIT_WITH_STANDARD_SOLVER, /**< Initialisation via extern QP solver is not yet implemented. */ -RET_RESET_FAILED, /**< Reset failed. */ -RET_INIT_FAILED, /**< Initialisation failed. */ -RET_INIT_FAILED_TQ, /**< Initialisation failed due to TQ factorisation. */ -RET_INIT_FAILED_CHOLESKY, /**< Initialisation failed due to Cholesky decomposition. */ -RET_INIT_FAILED_HOTSTART, /**< Initialisation failed! QP could not be solved! */ -RET_INIT_FAILED_INFEASIBILITY, /**< Initial QP could not be solved due to infeasibility! */ -RET_INIT_FAILED_UNBOUNDEDNESS, /**< Initial QP could not be solved due to unboundedness! */ -RET_INIT_FAILED_REGULARISATION, /**< Initialisation failed as Hessian matrix could not be regularised. */ -RET_INIT_SUCCESSFUL, /**< Initialisation done. (40) */ -RET_OBTAINING_WORKINGSET_FAILED, /**< Failed to obtain working set for auxiliary QP. */ -RET_SETUP_WORKINGSET_FAILED, /**< Failed to setup working set for auxiliary QP. */ -RET_SETUP_AUXILIARYQP_FAILED, /**< Failed to setup auxiliary QP for initialised homotopy. */ -RET_NO_CHOLESKY_WITH_INITIAL_GUESS, /**< Externally computed Cholesky factor cannot be combined with an initial guess. */ -RET_NO_EXTERN_SOLVER, /**< No extern QP solver available. */ -RET_QP_UNBOUNDED, /**< QP is unbounded. */ -RET_QP_INFEASIBLE, /**< QP is infeasible. */ -RET_QP_NOT_SOLVED, /**< Problems occurred while solving QP with standard solver. */ -RET_QP_SOLVED, /**< QP successfully solved. */ -RET_UNABLE_TO_SOLVE_QP, /**< Problems occurred while solving QP. (50) */ -RET_INITIALISATION_STARTED, /**< Starting problem initialisation... */ -RET_HOTSTART_FAILED, /**< Unable to perform homotopy due to internal error. */ -RET_HOTSTART_FAILED_TO_INIT, /**< Unable to initialise problem. */ -RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED, /**< Unable to perform homotopy as previous QP is not solved. */ -RET_ITERATION_STARTED, /**< Iteration... */ -RET_SHIFT_DETERMINATION_FAILED, /**< Determination of shift of the QP data failed. */ -RET_STEPDIRECTION_DETERMINATION_FAILED, /**< Determination of step direction failed. */ -RET_STEPLENGTH_DETERMINATION_FAILED, /**< Determination of step direction failed. */ -RET_OPTIMAL_SOLUTION_FOUND, /**< Optimal solution of neighbouring QP found. */ -RET_HOMOTOPY_STEP_FAILED, /**< Unable to perform homotopy step. (60) */ -RET_HOTSTART_STOPPED_INFEASIBILITY, /**< Premature homotopy termination because QP is infeasible. */ -RET_HOTSTART_STOPPED_UNBOUNDEDNESS, /**< Premature homotopy termination because QP is unbounded. */ -RET_WORKINGSET_UPDATE_FAILED, /**< Unable to update working sets according to initial guesses. */ -RET_MAX_NWSR_REACHED, /**< Maximum number of working set recalculations performed. */ -RET_CONSTRAINTS_NOT_SPECIFIED, /**< Problem does comprise constraints! You also have to specify new constraints' bounds. */ -RET_INVALID_FACTORISATION_FLAG, /**< Invalid factorisation flag. */ -RET_UNABLE_TO_SAVE_QPDATA, /**< Unable to save QP data. */ -RET_STEPDIRECTION_FAILED_TQ, /**< Abnormal termination due to TQ factorisation. */ -RET_STEPDIRECTION_FAILED_CHOLESKY, /**< Abnormal termination due to Cholesky factorisation. */ -RET_CYCLING_DETECTED, /**< Cycling detected. (70) */ -RET_CYCLING_NOT_RESOLVED, /**< Cycling cannot be resolved, QP probably infeasible. */ -RET_CYCLING_RESOLVED, /**< Cycling probably resolved. */ -RET_STEPSIZE, /**< For displaying performed stepsize. */ -RET_STEPSIZE_NONPOSITIVE, /**< For displaying non-positive stepsize. */ -RET_SETUPSUBJECTTOTYPE_FAILED, /**< Setup of SubjectToTypes failed. */ -RET_ADDCONSTRAINT_FAILED, /**< Addition of constraint to working set failed. */ -RET_ADDCONSTRAINT_FAILED_INFEASIBILITY, /**< Addition of constraint to working set failed (due to QP infeasibility). */ -RET_ADDBOUND_FAILED, /**< Addition of bound to working set failed. */ -RET_ADDBOUND_FAILED_INFEASIBILITY, /**< Addition of bound to working set failed (due to QP infeasibility). */ -RET_REMOVECONSTRAINT_FAILED, /**< Removal of constraint from working set failed. (80) */ -RET_REMOVEBOUND_FAILED, /**< Removal of bound from working set failed. */ -RET_REMOVE_FROM_ACTIVESET, /**< Removing from active set... */ -RET_ADD_TO_ACTIVESET, /**< Adding to active set... */ -RET_REMOVE_FROM_ACTIVESET_FAILED, /**< Removing from active set failed. */ -RET_ADD_TO_ACTIVESET_FAILED, /**< Adding to active set failed. */ -RET_CONSTRAINT_ALREADY_ACTIVE, /**< Constraint is already active. */ -RET_ALL_CONSTRAINTS_ACTIVE, /**< All constraints are active, no further constraint can be added. */ -RET_LINEARLY_DEPENDENT, /**< New bound/constraint is linearly dependent. */ -RET_LINEARLY_INDEPENDENT, /**< New bound/constraint is linearly independent. */ -RET_LI_RESOLVED, /**< Linear independence of active constraint matrix successfully resolved. (90) */ -RET_ENSURELI_FAILED, /**< Failed to ensure linear independence of active constraint matrix. */ -RET_ENSURELI_FAILED_TQ, /**< Abnormal termination due to TQ factorisation. */ -RET_ENSURELI_FAILED_NOINDEX, /**< QP is infeasible. */ -RET_ENSURELI_FAILED_CYCLING, /**< QP is infeasible. */ -RET_BOUND_ALREADY_ACTIVE, /**< Bound is already active. */ -RET_ALL_BOUNDS_ACTIVE, /**< All bounds are active, no further bound can be added. */ -RET_CONSTRAINT_NOT_ACTIVE, /**< Constraint is not active. */ -RET_BOUND_NOT_ACTIVE, /**< Bound is not active. */ -RET_HESSIAN_NOT_SPD, /**< Projected Hessian matrix not positive definite. */ -RET_HESSIAN_INDEFINITE, /**< Hessian matrix is indefinite. (100) */ -RET_MATRIX_SHIFT_FAILED, /**< Unable to update matrices or to transform vectors. */ -RET_MATRIX_FACTORISATION_FAILED, /**< Unable to calculate new matrix factorisations. */ -RET_PRINT_ITERATION_FAILED, /**< Unable to print information on current iteration. */ -RET_NO_GLOBAL_MESSAGE_OUTPUTFILE, /**< No global message output file initialised. */ -RET_DISABLECONSTRAINTS_FAILED, /**< Unable to disbable constraints. */ -RET_ENABLECONSTRAINTS_FAILED, /**< Unable to enbable constraints. */ -RET_ALREADY_ENABLED, /**< Bound or constraint is already enabled. */ -RET_ALREADY_DISABLED, /**< Bound or constraint is already disabled. */ -RET_NO_HESSIAN_SPECIFIED, /**< No Hessian matrix has been specified. */ -RET_USING_REGULARISATION, /**< Using regularisation as Hessian matrix is not positive definite. (110) */ -RET_EPS_MUST_BE_POSITVE, /**< Eps for regularisation must be sufficiently positive. */ -RET_REGSTEPS_MUST_BE_POSITVE, /**< Maximum number of regularisation steps must be non-negative. */ -RET_HESSIAN_ALREADY_REGULARISED, /**< Hessian has been already regularised. */ -RET_CANNOT_REGULARISE_IDENTITY, /**< Identity Hessian matrix cannot be regularised. */ -RET_CANNOT_REGULARISE_SPARSE, /**< Sparse matrix cannot be regularised as diagonal entry is missing. */ -RET_NO_REGSTEP_NWSR, /**< No additional regularisation step could be performed due to limits. */ -RET_FEWER_REGSTEPS_NWSR, /**< Fewer additional regularisation steps have been performed due to limits. */ -RET_CHOLESKY_OF_ZERO_HESSIAN, /**< Cholesky decomposition of (unregularised) zero Hessian matrix. */ -RET_ZERO_HESSIAN_ASSUMED, /**< Zero Hessian matrix assumed as null pointer passed without specifying hessianType. */ -RET_CONSTRAINTS_ARE_NOT_SCALED, /**< (no longer in use) (120) */ -RET_INITIAL_BOUNDS_STATUS_NYI, /**< (no longer in use) */ -RET_ERROR_IN_CONSTRAINTPRODUCT, /**< Error in user-defined constraint product function. */ -RET_FIX_BOUNDS_FOR_LP, /**< All initial bounds must be fixed when solving an (unregularised) LP. */ -RET_USE_REGULARISATION_FOR_LP, /**< Set options.enableRegularisation=BT_TRUE for solving LPs. */ -/* SQProblem */ -RET_UPDATEMATRICES_FAILED, /**< Unable to update QP matrices. */ -RET_UPDATEMATRICES_FAILED_AS_QP_NOT_SOLVED, /**< Unable to update matrices as previous QP is not solved. */ -/* Utils */ -RET_UNABLE_TO_OPEN_FILE, /**< Unable to open file. */ -RET_UNABLE_TO_WRITE_FILE, /**< Unable to write into file. */ -RET_UNABLE_TO_READ_FILE, /**< Unable to read from file. */ -RET_FILEDATA_INCONSISTENT, /**< File contains inconsistent data. (130) */ -/* Options */ -RET_OPTIONS_ADJUSTED, /**< Options needed to be adjusted for consistency reasons. */ -/* SolutionAnalysis */ -RET_UNABLE_TO_ANALYSE_QPROBLEM, /**< Unable to analyse (S)QProblem(B) object. */ -/* Benchmark */ -RET_NWSR_SET_TO_ONE, /**< Maximum number of working set changes was set to 1. */ -RET_UNABLE_TO_READ_BENCHMARK, /**< Unable to read benchmark data. */ -RET_BENCHMARK_ABORTED, /**< Benchmark aborted. */ -RET_INITIAL_QP_SOLVED, /**< Initial QP solved. */ -RET_QP_SOLUTION_STARTED, /**< Solving QP... */ -RET_BENCHMARK_SUCCESSFUL, /**< Benchmark terminated successfully. */ -/* Sparse matrices */ -RET_NO_DIAGONAL_AVAILABLE, /**< Sparse matrix does not have entries on full diagonal. */ -RET_DIAGONAL_NOT_INITIALISED, /**< Diagonal data of sparse matrix has not been initialised. (140) */ -/* Dropping of infeasible constraints */ -RET_ENSURELI_DROPPED, /**< Linear independence resolved by dropping blocking constraint. */ -/* Simple exitflags */ -RET_SIMPLE_STATUS_P1, /**< QP problem could not be solved within given number of iterations. */ -RET_SIMPLE_STATUS_P0, /**< QP problem solved. */ -RET_SIMPLE_STATUS_M1, /**< QP problem could not be solved due to an internal error. */ -RET_SIMPLE_STATUS_M2, /**< QP problem is infeasible (and thus could not be solved). */ -RET_SIMPLE_STATUS_M3 /**< QP problem is unbounded (and thus could not be solved). (146) */ -} returnValue; - - -/** - * \brief Data structure for entries in global message list. - * - * Data structure for entries in global message list. - * - * \author Hans Joachim Ferreau - * \version 3.1embedded - * \date 2007-2015 - */ -typedef struct -{ - returnValue key; /**< Global return value. */ - const char* data; /**< Corresponding message. */ - VisibilityStatus globalVisibilityStatus; /**< Determines if message can be printed. - * If this value is set to VS_HIDDEN, no message is printed! */ -} ReturnValueList; - - - -/** - * \brief Handles all kind of error messages, warnings and other information. - * - * This class handles all kinds of messages (errors, warnings, infos) initiated - * by qpOASES modules and stores the corresponding global preferences. - * - * \author Hans Joachim Ferreau (thanks to Leonard Wirsching) - * \version 3.1embedded - * \date 2007-2015 - */ -typedef struct -{ - VisibilityStatus errorVisibility; /**< Error messages visible? */ - VisibilityStatus warningVisibility; /**< Warning messages visible? */ - VisibilityStatus infoVisibility; /**< Info messages visible? */ - - FILE* outputFile; /**< Output file for messages. */ - - int errorCount; /**< Counts number of errors (for nicer output only). */ -} MessageHandling; - - - -/** Constructor which takes the desired output file and desired visibility states. */ -void MessageHandlingCON( MessageHandling* _THIS, - FILE* _outputFile, /**< Output file. */ - VisibilityStatus _errorVisibility, /**< Visibility status for error messages. */ - VisibilityStatus _warningVisibility,/**< Visibility status for warning messages. */ - VisibilityStatus _infoVisibility /**< Visibility status for info messages. */ - ); - -void MessageHandlingCPY( MessageHandling* FROM, - MessageHandling* TO - ); - - -/** Prints an error message(a simplified macro THROWERROR is also provided). \n - * Errors are definied as abnormal events which cause an immediate termination of the current (sub) function. - * Errors of a sub function should be commented by the calling function by means of a warning message - * (if this error does not cause an error of the calling function, either)! - * \return Error number returned by sub function call - */ -returnValue MessageHandling_throwError( MessageHandling* _THIS, - returnValue Enumber, /**< Error number returned by sub function call. */ - const char* additionaltext, /**< Additional error text (0, if none). */ - const char* functionname, /**< Name of function which caused the error. */ - const char* filename, /**< Name of file which caused the error. */ - const unsigned long linenumber, /**< Number of line which caused the error.incompatible binary file */ - VisibilityStatus localVisibilityStatus /**< Determines (locally) if error message can be printed to stderr. - * If GLOBAL visibility status of the message is set to VS_HIDDEN, - * no message is printed, anyway! */ - ); - -/** Prints a warning message (a simplified macro THROWWARNING is also provided). - * Warnings are definied as abnormal events which does NOT cause an immediate termination of the current (sub) function. - * \return Warning number returned by sub function call - */ -returnValue MessageHandling_throwWarning( MessageHandling* _THIS, - returnValue Wnumber, /**< Warning number returned by sub function call. */ - const char* additionaltext, /**< Additional warning text (0, if none). */ - const char* functionname, /**< Name of function which caused the warning. */ - const char* filename, /**< Name of file which caused the warning. */ - const unsigned long linenumber, /**< Number of line which caused the warning. */ - VisibilityStatus localVisibilityStatus /**< Determines (locally) if warning message can be printed to stderr. - * If GLOBAL visibility status of the message is set to VS_HIDDEN, - * no message is printed, anyway! */ - ); - -/** Prints a info message (a simplified macro THROWINFO is also provided). - * \return Info number returned by sub function call - */ -returnValue MessageHandling_throwInfo( MessageHandling* _THIS, - returnValue Inumber, /**< Info number returned by sub function call. */ - const char* additionaltext, /**< Additional warning text (0, if none). */ - const char* functionname, /**< Name of function which submitted the info. */ - const char* filename, /**< Name of file which submitted the info. */ - const unsigned long linenumber, /**< Number of line which submitted the info. */ - VisibilityStatus localVisibilityStatus /**< Determines (locally) if info message can be printed to stderr. - * If GLOBAL visibility status of the message is set to VS_HIDDEN, - * no message is printed, anyway! */ - ); - - -/** Resets all preferences to default values. - * \return SUCCESSFUL_RETURN */ -returnValue MessageHandling_reset( MessageHandling* _THIS ); - - -/** Prints a complete list of all messages to output file. - * \return SUCCESSFUL_RETURN */ -returnValue MessageHandling_listAllMessages( MessageHandling* _THIS ); - - -/** Returns visibility status for error messages. - * \return Visibility status for error messages. */ -static inline VisibilityStatus MessageHandling_getErrorVisibilityStatus( MessageHandling* _THIS ); - -/** Returns visibility status for warning messages. - * \return Visibility status for warning messages. */ -static inline VisibilityStatus MessageHandling_getWarningVisibilityStatus( MessageHandling* _THIS ); - -/** Returns visibility status for info messages. - * \return Visibility status for info messages. */ -static inline VisibilityStatus MessageHandling_getInfoVisibilityStatus( MessageHandling* _THIS ); - -/** Returns pointer to output file. - * \return Pointer to output file. */ -static inline FILE* MessageHandling_getOutputFile( MessageHandling* _THIS ); - -/** Returns error count value. - * \return Error count value. */ -static inline int MessageHandling_getErrorCount( MessageHandling* _THIS ); - - -/** Changes visibility status for error messages. */ -static inline void MessageHandling_setErrorVisibilityStatus( MessageHandling* _THIS, - VisibilityStatus _errorVisibility /**< New visibility status for error messages. */ - ); - -/** Changes visibility status for warning messages. */ -static inline void MessageHandling_setWarningVisibilityStatus( MessageHandling* _THIS, - VisibilityStatus _warningVisibility /**< New visibility status for warning messages. */ - ); - -/** Changes visibility status for info messages. */ -static inline void MessageHandling_setInfoVisibilityStatus( MessageHandling* _THIS, - VisibilityStatus _infoVisibility /**< New visibility status for info messages. */ - ); - -/** Changes output file for messages. */ -static inline void MessageHandling_setOutputFile( MessageHandling* _THIS, - FILE* _outputFile /**< New output file for messages. */ - ); - -/** Changes error count. - * \return SUCCESSFUL_RETURN \n - * RET_INVALID_ARGUMENT */ -static inline returnValue MessageHandling_setErrorCount( MessageHandling* _THIS, - int _errorCount /**< New error count value. */ - ); - -/** Provides message text corresponding to given \a returnValue. - * \return String containing message text. */ -const char* MessageHandling_getErrorCodeMessage( MessageHandling* _THIS, - const returnValue _returnValue - ); - - -returnValue MessageHandling_throwMessage( MessageHandling* _THIS, - returnValue RETnumber, /**< Error/warning/info number returned by sub function call. */ - const char* additionaltext, /**< Additional warning text (0, if none). */ - const char* functionname, /**< Name of function which caused the error/warning/info. */ - const char* filename, /**< Name of file which caused the error/warning/info. */ - const unsigned long linenumber, /**< Number of line which caused the error/warning/info. */ - VisibilityStatus localVisibilityStatus, /**< Determines (locally) if info message can be printed to stderr. - * If GLOBAL visibility status of the message is set to VS_HIDDEN, - * no message is printed, anyway! */ - const char* RETstring /**< Leading string of error/warning/info message. */ - ); - - -#ifndef __FILE__ - /** Ensures that __FILE__ macro is defined. */ - #define __FILE__ 0 -#endif - -#ifndef __LINE__ - /** Ensures that __LINE__ macro is defined. */ - #define __LINE__ 0 -#endif - -/** Define __FUNC__ macro providing current function for debugging. */ -/*#define __FUNC__ 0*/ -#define __FUNC__ ("(no function name provided)") -/*#define __FUNC__ __func__*/ -/*#define __FUNC__ __FUNCTION__*/ - - -/** Short version of throwError with default values, only returnValue is needed */ -#define THROWERROR(retval) ( MessageHandling_throwError( qpOASES_getGlobalMessageHandler(),(retval),0,__FUNC__,__FILE__,__LINE__,VS_VISIBLE) ) - -/** Short version of throwWarning with default values, only returnValue is needed */ -#define THROWWARNING(retval) ( MessageHandling_throwWarning( qpOASES_getGlobalMessageHandler(),(retval),0,__FUNC__,__FILE__,__LINE__,VS_VISIBLE) ) - -/** Short version of throwInfo with default values, only returnValue is needed */ -#define THROWINFO(retval) ( MessageHandling_throwInfo( qpOASES_getGlobalMessageHandler(),(retval),0,__FUNC__,__FILE__,__LINE__,VS_VISIBLE) ) - - -/** Returns a pointer to global message handler. - * \return Pointer to global message handler. - */ -MessageHandling* qpOASES_getGlobalMessageHandler( ); - - -/* - * g e t E r r o r V i s i b i l i t y S t a t u s - */ -static inline VisibilityStatus MessageHandling_getErrorVisibilityStatus( MessageHandling* _THIS ) -{ - return _THIS->errorVisibility; -} - - -/* - * g e t W a r n i n g V i s i b i l i t y S t a t u s - */ -static inline VisibilityStatus MessageHandling_getWarningVisibilityStatus( MessageHandling* _THIS ) -{ - return _THIS->warningVisibility; -} - - -/* - * g e t I n f o V i s i b i l i t y S t a t u s - */ -static inline VisibilityStatus MessageHandling_getInfoVisibilityStatus( MessageHandling* _THIS ) -{ - return _THIS->infoVisibility; -} - - -/* - * g e t O u t p u t F i l e - */ -static inline FILE* MessageHandling_getOutputFile( MessageHandling* _THIS ) -{ - return _THIS->outputFile; -} - - -/* - * g e t E r r o r C o u n t - */ -static inline int MessageHandling_getErrorCount( MessageHandling* _THIS ) -{ - return _THIS->errorCount; -} - - -/* - * s e t E r r o r V i s i b i l i t y S t a t u s - */ -static inline void MessageHandling_setErrorVisibilityStatus( MessageHandling* _THIS, VisibilityStatus _errorVisibility ) -{ - _THIS->errorVisibility = _errorVisibility; -} - - -/* - * s e t W a r n i n g V i s i b i l i t y S t a t u s - */ -static inline void MessageHandling_setWarningVisibilityStatus( MessageHandling* _THIS, VisibilityStatus _warningVisibility ) -{ - _THIS->warningVisibility = _warningVisibility; -} - - -/* - * s e t I n f o V i s i b i l i t y S t a t u s - */ -static inline void MessageHandling_setInfoVisibilityStatus( MessageHandling* _THIS, VisibilityStatus _infoVisibility ) -{ - _THIS->infoVisibility = _infoVisibility; -} - - -/* - * s e t O u t p u t F i l e - */ -static inline void MessageHandling_setOutputFile( MessageHandling* _THIS, FILE* _outputFile ) -{ - _THIS->outputFile = _outputFile; -} - - -/* - * s e t E r r o r C o u n t - */ -static inline returnValue MessageHandling_setErrorCount( MessageHandling* _THIS, int _errorCount ) -{ - if ( _errorCount >= 0 ) - { - _THIS->errorCount = _errorCount; - return SUCCESSFUL_RETURN; - } - else - return RET_INVALID_ARGUMENTS; -} - - -END_NAMESPACE_QPOASES - - -#endif /* QPOASES_MESSAGEHANDLING_H */ - - -/* - * end of file - */ diff --git a/third_party/acados/include/qpOASES_e/Options.h b/third_party/acados/include/qpOASES_e/Options.h deleted file mode 100644 index ca8086d..0000000 --- a/third_party/acados/include/qpOASES_e/Options.h +++ /dev/null @@ -1,153 +0,0 @@ -/* - * This file is part of qpOASES. - * - * qpOASES -- An Implementation of the Online Active Set Strategy. - * Copyright (C) 2007-2015 by Hans Joachim Ferreau, Andreas Potschka, - * Christian Kirches et al. All rights reserved. - * - * qpOASES is free software; you can redistribute it and/or - * modify it under the terms of the GNU Lesser General Public - * License as published by the Free Software Foundation; either - * version 2.1 of the License, or (at your option) any later version. - * - * qpOASES is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public - * License along with qpOASES; if not, write to the Free Software - * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - * - */ - - -/** - * \file include/qpOASES_e/Options.h - * \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches - * \version 3.1embedded - * \date 2007-2015 - * - * Declaration of the Options class designed to manage user-specified - * options for solving a QProblem. - */ - - -#ifndef QPOASES_OPTIONS_H -#define QPOASES_OPTIONS_H - - -#include - - -BEGIN_NAMESPACE_QPOASES - - -/** - * \brief Manages all user-specified options for solving QPs. - * - * This class manages all user-specified options used for solving - * quadratic programs. - * - * \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches - * \version 3.1embedded - * \date 2007-2015 - */ -typedef struct -{ - PrintLevel printLevel; /**< Print level. */ - - BooleanType enableRamping; /**< Specifies whether ramping shall be enabled or not. */ - BooleanType enableFarBounds; /**< Specifies whether far bounds shall be used or not. */ - BooleanType enableFlippingBounds; /**< Specifies whether flipping bounds shall be used or not. */ - BooleanType enableRegularisation; /**< Specifies whether Hessian matrix shall be regularised in case semi-definiteness is detected. */ - BooleanType enableFullLITests; /**< Specifies whether condition-hardened LI test shall be used or not. */ - BooleanType enableNZCTests; /**< Specifies whether nonzero curvature tests shall be used. */ - int enableDriftCorrection; /**< Specifies the frequency of drift corrections (0 = off). */ - int enableCholeskyRefactorisation; /**< Specifies the frequency of full refactorisation of proj. Hessian (otherwise updates). */ - BooleanType enableEqualities; /**< Specifies whether equalities shall be always treated as active constraints. */ - - real_t terminationTolerance; /**< Termination tolerance. */ - real_t boundTolerance; /**< Lower/upper (constraints') bound tolerance (an inequality constraint whose lower and upper bounds differ by less is regarded to be an equality constraint). */ - real_t boundRelaxation; /**< Offset for relaxing (constraints') bounds at beginning of an initial homotopy. It is also as initial value for far bounds. */ - real_t epsNum; /**< Numerator tolerance for ratio tests. */ - real_t epsDen; /**< Denominator tolerance for ratio tests. */ - real_t maxPrimalJump; /**< Maximum allowed jump in primal variables in nonzero curvature tests. */ - real_t maxDualJump; /**< Maximum allowed jump in dual variables in linear independence tests. */ - - real_t initialRamping; /**< Start value for Ramping Strategy. */ - real_t finalRamping; /**< Final value for Ramping Strategy. */ - real_t initialFarBounds; /**< Initial size of Far Bounds. */ - real_t growFarBounds; /**< Factor to grow Far Bounds. */ - SubjectToStatus initialStatusBounds; /**< Initial status of bounds at first iteration. */ - real_t epsFlipping; /**< Tolerance of squared Cholesky diagonal factor which triggers flipping bound. */ - int numRegularisationSteps; /**< Maximum number of successive regularisation steps. */ - real_t epsRegularisation; /**< Scaling factor of identity matrix used for Hessian regularisation. */ - int numRefinementSteps; /**< Maximum number of iterative refinement steps. */ - real_t epsIterRef; /**< Early termination tolerance for iterative refinement. */ - real_t epsLITests; /**< Tolerance for linear independence tests. */ - real_t epsNZCTests; /**< Tolerance for nonzero curvature tests. */ - - BooleanType enableDropInfeasibles; /**< ... */ - int dropBoundPriority; /**< ... */ - int dropEqConPriority; /**< ... */ - int dropIneqConPriority; /**< ... */ -} Options; - - -void OptionsCON( Options* _THIS - ); - -/** Copies all members from given rhs object. - * \return SUCCESSFUL_RETURN */ -void OptionsCPY( Options* FROM, - Options* TO - ); - - -/** Sets all options to default values. - * \return SUCCESSFUL_RETURN */ -returnValue Options_setToDefault( Options* _THIS - ); - -/** Sets all options to values resulting in maximum reliabilty. - * \return SUCCESSFUL_RETURN */ -returnValue Options_setToReliable( Options* _THIS - ); - -/** Sets all options to values resulting in minimum solution time. - * \return SUCCESSFUL_RETURN */ -returnValue Options_setToMPC( Options* _THIS - ); - -/** Same as setToMPC( ), for ensuring backwards compatibility. - * \return SUCCESSFUL_RETURN */ -returnValue Options_setToFast( Options* _THIS - ); - - -/** Ensures that all options have consistent values by automatically - * adjusting inconsistent ones. - * Note: This routine cannot (and does not try to) ensure that values - * are set to reasonable values that make the QP solution work! - * \return SUCCESSFUL_RETURN \n - * RET_OPTIONS_ADJUSTED */ -returnValue Options_ensureConsistency( Options* _THIS - ); - - -/** Prints values of all options. - * \return SUCCESSFUL_RETURN */ -returnValue Options_print( Options* _THIS - ); - - -END_NAMESPACE_QPOASES - - -#endif /* QPOASES_OPTIONS_H */ - - -/* - * end of file - */ diff --git a/third_party/acados/include/qpOASES_e/QProblem.h b/third_party/acados/include/qpOASES_e/QProblem.h deleted file mode 100644 index 91a4a6f..0000000 --- a/third_party/acados/include/qpOASES_e/QProblem.h +++ /dev/null @@ -1,2369 +0,0 @@ -/* - * This file is part of qpOASES. - * - * qpOASES -- An Implementation of the Online Active Set Strategy. - * Copyright (C) 2007-2015 by Hans Joachim Ferreau, Andreas Potschka, - * Christian Kirches et al. All rights reserved. - * - * qpOASES is free software; you can redistribute it and/or - * modify it under the terms of the GNU Lesser General Public - * License as published by the Free Software Foundation; either - * version 2.1 of the License, or (at your option) any later version. - * - * qpOASES is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public - * License along with qpOASES; if not, write to the Free Software - * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - * - */ - - -/** - * \file include/qpOASES_e/QProblem.h - * \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches - * \version 3.1embedded - * \date 2007-2015 - * - * Declaration of the QProblem class which is able to use the newly - * developed online active set strategy for parametric quadratic programming. - */ - - - -#ifndef QPOASES_QPROBLEM_H -#define QPOASES_QPROBLEM_H - - -#include -#include -#include -#include -#include -#include - - -BEGIN_NAMESPACE_QPOASES - -typedef struct { - Bounds *auxiliaryBounds; - Constraints *auxiliaryConstraints; - - real_t *ub_new_far; - real_t *lb_new_far; - real_t *ubA_new_far; - real_t *lbA_new_far; - - real_t *g_new; - real_t *lb_new; - real_t *ub_new; - real_t *lbA_new; - real_t *ubA_new; - - real_t *g_new2; - real_t *lb_new2; - real_t *ub_new2; - real_t *lbA_new2; - real_t *ubA_new2; - - real_t *delta_xFX5; - real_t *delta_xFR5; - real_t *delta_yAC5; - real_t *delta_yFX5; - - real_t *Hx; - - real_t *_H; - - real_t *g_original; - real_t *lb_original; - real_t *ub_original; - real_t *lbA_original; - real_t *ubA_original; - - real_t *delta_xFR; - real_t *delta_xFX; - real_t *delta_yAC; - real_t *delta_yFX; - real_t *delta_g; - real_t *delta_lb; - real_t *delta_ub; - real_t *delta_lbA; - real_t *delta_ubA; - - real_t *gMod; - - real_t *aFR; - real_t *wZ; - - real_t *delta_g2; - real_t *delta_xFX2; - real_t *delta_xFR2; - real_t *delta_yAC2; - real_t *delta_yFX2; - real_t *nul; - real_t *Arow; - - real_t *xiC; - real_t *xiC_TMP; - real_t *xiB; - real_t *Arow2; - real_t *num; - - real_t *w; - real_t *tmp; - - real_t *delta_g3; - real_t *delta_xFX3; - real_t *delta_xFR3; - real_t *delta_yAC3; - real_t *delta_yFX3; - real_t *nul2; - - real_t *xiC2; - real_t *xiC_TMP2; - real_t *xiB2; - real_t *num2; - - real_t *Hz; - real_t *z; - real_t *ZHz; - real_t *r; - - real_t *tmp2; - real_t *Hz2; - real_t *z2; - real_t *r2; - real_t *rhs; - - real_t *delta_xFX4; - real_t *delta_xFR4; - real_t *delta_yAC4; - real_t *delta_yFX4; - real_t *nul3; - real_t *ek; - real_t *x_W; - real_t *As; - real_t *Ax_W; - - real_t *num3; - real_t *den; - real_t *delta_Ax_l; - real_t *delta_Ax_u; - real_t *delta_Ax; - real_t *delta_x; - - real_t *_A; - - real_t *grad; - real_t *AX; -} QProblem_ws; - -int QProblem_ws_calculateMemorySize( unsigned int nV, unsigned int nC ); - -char *QProblem_ws_assignMemory( unsigned int nV, unsigned int nC, QProblem_ws **mem, void *raw_memory ); - -QProblem_ws *QProblem_ws_createMemory( unsigned int nV, unsigned int nC ); - -/** - * \brief Implements the online active set strategy for QPs with general constraints. - * - * A class for setting up and solving quadratic programs. The main feature is - * the possibily to use the newly developed online active set strategy for - * parametric quadratic programming. - * - * \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches - * \version 3.1embedded - * \date 2007-2015 - */ -typedef struct -{ - QProblem_ws *ws; /**< Workspace */ - Bounds *bounds; /**< Data structure for problem's bounds. */ - Constraints *constraints; /**< Data structure for problem's constraints. */ - Flipper *flipper; /**< Struct for making a temporary copy of the matrix factorisations. */ - - DenseMatrix* H; /**< Hessian matrix pointer. */ - DenseMatrix* A; /**< Constraint matrix pointer. */ - - Options options; /**< Struct containing all user-defined options for solving QPs. */ - TabularOutput tabularOutput; /**< Struct storing information for tabular output (printLevel == PL_TABULAR). */ - - real_t *g; /**< Gradient. */ - - real_t *lb; /**< Lower bound vector (on variables). */ - real_t *ub; /**< Upper bound vector (on variables). */ - real_t *lbA; /**< Lower constraints' bound vector. */ - real_t *ubA; /**< Upper constraints' bound vector. */ - - real_t *R; /**< Cholesky factor of H (i.e. H = R^T*R). */ - - real_t *T; /**< Reverse triangular matrix, A = [0 T]*Q'. */ - real_t *Q; /**< Orthonormal quadratic matrix, A = [0 T]*Q'. */ - - real_t *Ax; /**< Stores the current A*x \n - * (for increased efficiency only). */ - real_t *Ax_l; /**< Stores the current distance to lower constraints' bounds A*x-lbA \n - * (for increased efficiency only). */ - real_t *Ax_u; /**< Stores the current distance to lower constraints' bounds ubA-A*x \n - * (for increased efficiency only). */ - - real_t *x; /**< Primal solution vector. */ - real_t *y; /**< Dual solution vector. */ - - real_t *delta_xFR_TMP; /**< Temporary for determineStepDirection */ - real_t *tempA; /**< Temporary for determineStepDirection. */ - real_t *tempB; /**< Temporary for determineStepDirection. */ - real_t *ZFR_delta_xFRz; /**< Temporary for determineStepDirection. */ - real_t *delta_xFRy; /**< Temporary for determineStepDirection. */ - real_t *delta_xFRz; /**< Temporary for determineStepDirection. */ - real_t *delta_yAC_TMP; /**< Temporary for determineStepDirection. */ - - ConstraintProduct constraintProduct; /**< Pointer to user-defined constraint product function. */ - - real_t tau; /**< Last homotopy step length. */ - real_t regVal; /**< Holds the offset used to regularise Hessian matrix (zero by default). */ - - real_t ramp0; /**< Start value for Ramping Strategy. */ - real_t ramp1; /**< Final value for Ramping Strategy. */ - - QProblemStatus status; /**< Current status of the solution process. */ - HessianType hessianType; /**< Type of Hessian matrix. */ - - BooleanType haveCholesky; /**< Flag indicating whether Cholesky decomposition has already been setup. */ - BooleanType infeasible; /**< QP infeasible? */ - BooleanType unbounded; /**< QP unbounded? */ - - int rampOffset; /**< Offset index for Ramping. */ - unsigned int count; /**< Counts the number of hotstart function calls (internal usage only!). */ - - int sizeT; /**< Matrix T is stored in a (sizeT x sizeT) array. */ -} QProblem; - -int QProblem_calculateMemorySize( unsigned int nV, unsigned int nC ); - -char *QProblem_assignMemory( unsigned int nV, unsigned int nC, QProblem **mem, void *raw_memory ); - -QProblem *QProblem_createMemory( unsigned int nV, unsigned int nC ); - - -/** Constructor which takes the QP dimension and Hessian type - * information. If the Hessian is the zero (i.e. HST_ZERO) or the - * identity matrix (i.e. HST_IDENTITY), respectively, no memory - * is allocated for it and a NULL pointer can be passed for it - * to the init() functions. */ -void QProblemCON( QProblem* _THIS, - int _nV, /**< Number of variables. */ - int _nC, /**< Number of constraints. */ - HessianType _hessianType /**< Type of Hessian matrix. */ - ); - -/** Copies all members from given rhs object. - * \return SUCCESSFUL_RETURN */ -void QProblemCPY( QProblem* FROM, - QProblem* TO - ); - - -/** Clears all data structures of QProblem except for QP data. - * \return SUCCESSFUL_RETURN \n - RET_RESET_FAILED */ -returnValue QProblem_reset( QProblem* _THIS ); - - -/** Initialises a QP problem with given QP data and tries to solve it - * using at most nWSR iterations. - * - * Note: This function internally calls solveInitialQP for initialisation! - * - * \return SUCCESSFUL_RETURN \n - RET_INIT_FAILED \n - RET_INIT_FAILED_CHOLESKY \n - RET_INIT_FAILED_TQ \n - RET_INIT_FAILED_HOTSTART \n - RET_INIT_FAILED_INFEASIBILITY \n - RET_INIT_FAILED_UNBOUNDEDNESS \n - RET_MAX_NWSR_REACHED \n - RET_INVALID_ARGUMENTS */ -returnValue QProblem_initM( QProblem* _THIS, - DenseMatrix *_H, /**< Hessian matrix. */ - const real_t* const _g, /**< Gradient vector. */ - DenseMatrix *_A, /**< Constraint matrix. */ - const real_t* const _lb, /**< Lower bound vector (on variables). \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* const _ub, /**< Upper bound vector (on variables). \n - If no upper bounds exist, a NULL pointer can be passed. */ - const real_t* const _lbA, /**< Lower constraints' bound vector. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - const real_t* const _ubA, /**< Upper constraints' bound vector. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations when using initial homotopy. - Output: Number of performed working set recalculations. */ - real_t* const cputime /**< Input: Maximum CPU time allowed for QP initialisation. \n - Output: CPU time spent for QP initialisation (if pointer passed). */ - ); - - -/** Initialises a QP problem with given QP data and tries to solve it - * using at most nWSR iterations. - * - * Note: This function internally calls solveInitialQP for initialisation! - * - * \return SUCCESSFUL_RETURN \n - RET_INIT_FAILED \n - RET_INIT_FAILED_CHOLESKY \n - RET_INIT_FAILED_TQ \n - RET_INIT_FAILED_HOTSTART \n - RET_INIT_FAILED_INFEASIBILITY \n - RET_INIT_FAILED_UNBOUNDEDNESS \n - RET_MAX_NWSR_REACHED \n - RET_INVALID_ARGUMENTS */ -returnValue QProblem_init( QProblem* _THIS, - real_t* const _H, /**< Hessian matrix. \n - If Hessian matrix is trivial, a NULL pointer can be passed. */ - const real_t* const _g, /**< Gradient vector. */ - real_t* const _A, /**< Constraint matrix. */ - const real_t* const _lb, /**< Lower bound vector (on variables). \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* const _ub, /**< Upper bound vector (on variables). \n - If no upper bounds exist, a NULL pointer can be passed. */ - const real_t* const _lbA, /**< Lower constraints' bound vector. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - const real_t* const _ubA, /**< Upper constraints' bound vector. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations when using initial homotopy. - Output: Number of performed working set recalculations. */ - real_t* const cputime /**< Input: Maximum CPU time allowed for QP initialisation. \n - Output: CPU time spent for QP initialisation (if pointer passed). */ - ); - -/** Initialises a QP problem with given QP data to be read from files and tries to solve it - * using at most nWSR iterations. - * - * Note: This function internally calls solveInitialQP for initialisation! - * - * \return SUCCESSFUL_RETURN \n - RET_INIT_FAILED \n - RET_INIT_FAILED_CHOLESKY \n - RET_INIT_FAILED_TQ \n - RET_INIT_FAILED_HOTSTART \n - RET_INIT_FAILED_INFEASIBILITY \n - RET_INIT_FAILED_UNBOUNDEDNESS \n - RET_MAX_NWSR_REACHED \n - RET_UNABLE_TO_READ_FILE */ -returnValue QProblem_initF( QProblem* _THIS, - const char* const H_file, /**< Name of file where Hessian matrix is stored. \n - If Hessian matrix is trivial, a NULL pointer can be passed. */ - const char* const g_file, /**< Name of file where gradient vector is stored. */ - const char* const A_file, /**< Name of file where constraint matrix is stored. */ - const char* const lb_file, /**< Name of file where lower bound vector. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const char* const ub_file, /**< Name of file where upper bound vector. \n - If no upper bounds exist, a NULL pointer can be passed. */ - const char* const lbA_file, /**< Name of file where lower constraints' bound vector. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - const char* const ubA_file, /**< Name of file where upper constraints' bound vector. \n - If no upper constraints' bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations when using initial homotopy. - Output: Number of performed working set recalculations. */ - real_t* const cputime /**< Input: Maximum CPU time allowed for QP initialisation. \n - Output: CPU time spent for QP initialisation (if pointer passed). */ - ); - -/** Initialises a QP problem with given QP data and tries to solve it - * using at most nWSR iterations. Depending on the parameter constellation it: \n - * 1. 0, 0, 0 : starts with xOpt = 0, yOpt = 0 and gB/gC empty (or all implicit equality bounds), \n - * 2. xOpt, 0, 0 : starts with xOpt, yOpt = 0 and obtain gB/gC by "clipping", \n - * 3. 0, yOpt, 0 : starts with xOpt = 0, yOpt and obtain gB/gC from yOpt != 0, \n - * 4. 0, 0, gB/gC: starts with xOpt = 0, yOpt = 0 and gB/gC, \n - * 5. xOpt, yOpt, 0 : starts with xOpt, yOpt and obtain gB/gC from yOpt != 0, \n - * 6. xOpt, 0, gB/gC: starts with xOpt, yOpt = 0 and gB/gC, \n - * 7. xOpt, yOpt, gB/gC: starts with xOpt, yOpt and gB/gC (assume them to be consistent!) - * - * Note: This function internally calls solveInitialQP for initialisation! - * - * \return SUCCESSFUL_RETURN \n - RET_INIT_FAILED \n - RET_INIT_FAILED_CHOLESKY \n - RET_INIT_FAILED_TQ \n - RET_INIT_FAILED_HOTSTART \n - RET_INIT_FAILED_INFEASIBILITY \n - RET_INIT_FAILED_UNBOUNDEDNESS \n - RET_MAX_NWSR_REACHED \n - RET_INVALID_ARGUMENTS */ -returnValue QProblem_initMW( QProblem* _THIS, - DenseMatrix *_H, /**< Hessian matrix. \n - If Hessian matrix is trivial, a NULL pointer can be passed. */ - const real_t* const _g, /**< Gradient vector. */ - DenseMatrix *_A, /**< Constraint matrix. */ - const real_t* const _lb, /**< Lower bound vector (on variables). \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* const _ub, /**< Upper bound vector (on variables). \n - If no upper bounds exist, a NULL pointer can be passed. */ - const real_t* const _lbA, /**< Lower constraints' bound vector. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - const real_t* const _ubA, /**< Upper constraints' bound vector. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations when using initial homotopy. - * Output: Number of performed working set recalculations. */ - real_t* const cputime, /**< Input: Maximum CPU time allowed for QP initialisation. \n - Output: CPU time spent for QP initialisation. */ - const real_t* const xOpt, /**< Optimal primal solution vector. \n - (If a null pointer is passed, the old primal solution is kept!) */ - const real_t* const yOpt, /**< Optimal dual solution vector. \n - (If a null pointer is passed, the old dual solution is kept!) */ - Bounds* const guessedBounds, /**< Optimal working set of bounds for solution (xOpt,yOpt). */ - Constraints* const guessedConstraints, /**< Optimal working set of constraints for solution (xOpt,yOpt). */ - const real_t* const _R /**< Pre-computed (upper triangular) Cholesky factor of Hessian matrix. - The Cholesky factor must be stored in a real_t array of size nV*nV - in row-major format. Note: Only used if xOpt/yOpt and gB are NULL! \n - (If a null pointer is passed, Cholesky decomposition is computed internally!) */ - ); - -/** Initialises a QP problem with given QP data and tries to solve it - * using at most nWSR iterations. Depending on the parameter constellation it: \n - * 1. 0, 0, 0 : starts with xOpt = 0, yOpt = 0 and gB/gC empty (or all implicit equality bounds), \n - * 2. xOpt, 0, 0 : starts with xOpt, yOpt = 0 and obtain gB/gC by "clipping", \n - * 3. 0, yOpt, 0 : starts with xOpt = 0, yOpt and obtain gB/gC from yOpt != 0, \n - * 4. 0, 0, gB/gC: starts with xOpt = 0, yOpt = 0 and gB/gC, \n - * 5. xOpt, yOpt, 0 : starts with xOpt, yOpt and obtain gB/gC from yOpt != 0, \n - * 6. xOpt, 0, gB/gC: starts with xOpt, yOpt = 0 and gB/gC, \n - * 7. xOpt, yOpt, gB/gC: starts with xOpt, yOpt and gB/gC (assume them to be consistent!) - * - * Note: This function internally calls solveInitialQP for initialisation! - * - * \return SUCCESSFUL_RETURN \n - RET_INIT_FAILED \n - RET_INIT_FAILED_CHOLESKY \n - RET_INIT_FAILED_TQ \n - RET_INIT_FAILED_HOTSTART \n - RET_INIT_FAILED_INFEASIBILITY \n - RET_INIT_FAILED_UNBOUNDEDNESS \n - RET_MAX_NWSR_REACHED \n - RET_INVALID_ARGUMENTS */ -returnValue QProblem_initW( QProblem* _THIS, - real_t* const _H, /**< Hessian matrix. \n - If Hessian matrix is trivial, a NULL pointer can be passed. */ - const real_t* const _g, /**< Gradient vector. */ - real_t* const _A, /**< Constraint matrix. */ - const real_t* const _lb, /**< Lower bound vector (on variables). \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* const _ub, /**< Upper bound vector (on variables). \n - If no upper bounds exist, a NULL pointer can be passed. */ - const real_t* const _lbA, /**< Lower constraints' bound vector. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - const real_t* const _ubA, /**< Upper constraints' bound vector. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations when using initial homotopy. - * Output: Number of performed working set recalculations. */ - real_t* const cputime, /**< Input: Maximum CPU time allowed for QP initialisation. \n - Output: CPU time spent for QP initialisation. */ - const real_t* const xOpt, /**< Optimal primal solution vector. \n - (If a null pointer is passed, the old primal solution is kept!) */ - const real_t* const yOpt, /**< Optimal dual solution vector. \n - (If a null pointer is passed, the old dual solution is kept!) */ - Bounds* const guessedBounds, /**< Optimal working set of bounds for solution (xOpt,yOpt). */ - Constraints* const guessedConstraints, /**< Optimal working set of constraints for solution (xOpt,yOpt). */ - const real_t* const _R /**< Pre-computed (upper triangular) Cholesky factor of Hessian matrix. - The Cholesky factor must be stored in a real_t array of size nV*nV - in row-major format. Note: Only used if xOpt/yOpt and gB are NULL! \n - (If a null pointer is passed, Cholesky decomposition is computed internally!) */ - ); - -/** Initialises a QP problem with given QP data to be ream from files and tries to solve it - * using at most nWSR iterations. Depending on the parameter constellation it: \n - * 1. 0, 0, 0 : starts with xOpt = 0, yOpt = 0 and gB/gC empty (or all implicit equality bounds), \n - * 2. xOpt, 0, 0 : starts with xOpt, yOpt = 0 and obtain gB/gC by "clipping", \n - * 3. 0, yOpt, 0 : starts with xOpt = 0, yOpt and obtain gB/gC from yOpt != 0, \n - * 4. 0, 0, gB/gC: starts with xOpt = 0, yOpt = 0 and gB/gC, \n - * 5. xOpt, yOpt, 0 : starts with xOpt, yOpt and obtain gB/gC from yOpt != 0, \n - * 6. xOpt, 0, gB/gC: starts with xOpt, yOpt = 0 and gB/gC, \n - * 7. xOpt, yOpt, gB/gC: starts with xOpt, yOpt and gB/gC (assume them to be consistent!) - * - * Note: This function internally calls solveInitialQP for initialisation! - * - * \return SUCCESSFUL_RETURN \n - RET_INIT_FAILED \n - RET_INIT_FAILED_CHOLESKY \n - RET_INIT_FAILED_TQ \n - RET_INIT_FAILED_HOTSTART \n - RET_INIT_FAILED_INFEASIBILITY \n - RET_INIT_FAILED_UNBOUNDEDNESS \n - RET_MAX_NWSR_REACHED \n - RET_UNABLE_TO_READ_FILE */ -returnValue QProblem_initFW( QProblem* _THIS, - const char* const H_file, /**< Name of file where Hessian matrix is stored. \n - If Hessian matrix is trivial, a NULL pointer can be passed. */ - const char* const g_file, /**< Name of file where gradient vector is stored. */ - const char* const A_file, /**< Name of file where constraint matrix is stored. */ - const char* const lb_file, /**< Name of file where lower bound vector. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const char* const ub_file, /**< Name of file where upper bound vector. \n - If no upper bounds exist, a NULL pointer can be passed. */ - const char* const lbA_file, /**< Name of file where lower constraints' bound vector. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - const char* const ubA_file, /**< Name of file where upper constraints' bound vector. \n - If no upper constraints' bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations when using initial homotopy. - Output: Number of performed working set recalculations. */ - real_t* const cputime, /**< Input: Maximum CPU time allowed for QP initialisation. \n - Output: CPU time spent for QP initialisation. */ - const real_t* const xOpt, /**< Optimal primal solution vector. \n - (If a null pointer is passed, the old primal solution is kept!) */ - const real_t* const yOpt, /**< Optimal dual solution vector. \n - (If a null pointer is passed, the old dual solution is kept!) */ - Bounds* const guessedBounds, /**< Optimal working set of bounds for solution (xOpt,yOpt). */ - Constraints* const guessedConstraints, /**< Optimal working set of constraints for solution (xOpt,yOpt). */ - const char* const R_file /**< Pre-computed (upper triangular) Cholesky factor of Hessian matrix. - The Cholesky factor must be stored in a real_t array of size nV*nV - in row-major format. Note: Only used if xOpt/yOpt and gB are NULL! \n - (If a null pointer is passed, Cholesky decomposition is computed internally!) */ - ); - -/** Solves an initialised QP sequence using the online active set strategy. - * QP solution is started from previous solution. - * - * Note: This function internally calls solveQP/solveRegularisedQP - * for solving an initialised QP! - * - * \return SUCCESSFUL_RETURN \n - RET_MAX_NWSR_REACHED \n - RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED \n - RET_HOTSTART_FAILED \n - RET_SHIFT_DETERMINATION_FAILED \n - RET_STEPDIRECTION_DETERMINATION_FAILED \n - RET_STEPLENGTH_DETERMINATION_FAILED \n - RET_HOMOTOPY_STEP_FAILED \n - RET_HOTSTART_STOPPED_INFEASIBILITY \n - RET_HOTSTART_STOPPED_UNBOUNDEDNESS */ -returnValue QProblem_hotstart( QProblem* _THIS, - const real_t* const g_new, /**< Gradient of neighbouring QP to be solved. */ - const real_t* const lb_new, /**< Lower bounds of neighbouring QP to be solved. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* const ub_new, /**< Upper bounds of neighbouring QP to be solved. \n - If no upper bounds exist, a NULL pointer can be passed. */ - const real_t* const lbA_new, /**< Lower constraints' bounds of neighbouring QP to be solved. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - const real_t* const ubA_new, /**< Upper constraints' bounds of neighbouring QP to be solved. \n - If no upper constraints' bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations; \n - Output: Number of performed working set recalculations. */ - real_t* const cputime /**< Input: Maximum CPU time allowed for QP solution. \n - Output: CPU time spent for QP solution (or to perform nWSR iterations). */ - ); - -/** Solves an initialised QP sequence using the online active set strategy, - * where QP data is read from files. QP solution is started from previous solution. - * - * Note: This function internally calls solveQP/solveRegularisedQP - * for solving an initialised QP! - * - * \return SUCCESSFUL_RETURN \n - RET_MAX_NWSR_REACHED \n - RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED \n - RET_HOTSTART_FAILED \n - RET_SHIFT_DETERMINATION_FAILED \n - RET_STEPDIRECTION_DETERMINATION_FAILED \n - RET_STEPLENGTH_DETERMINATION_FAILED \n - RET_HOMOTOPY_STEP_FAILED \n - RET_HOTSTART_STOPPED_INFEASIBILITY \n - RET_HOTSTART_STOPPED_UNBOUNDEDNESS \n - RET_UNABLE_TO_READ_FILE \n - RET_INVALID_ARGUMENTS */ -returnValue QProblem_hotstartF( QProblem* _THIS, - const char* const g_file, /**< Name of file where gradient, of neighbouring QP to be solved, is stored. */ - const char* const lb_file, /**< Name of file where lower bounds, of neighbouring QP to be solved, is stored. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const char* const ub_file, /**< Name of file where upper bounds, of neighbouring QP to be solved, is stored. \n - If no upper bounds exist, a NULL pointer can be passed. */ - const char* const lbA_file, /**< Name of file where lower constraints' bounds, of neighbouring QP to be solved, is stored. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - const char* const ubA_file, /**< Name of file where upper constraints' bounds, of neighbouring QP to be solved, is stored. \n - If no upper constraints' bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations; \n - Output: Number of performed working set recalculations. */ - real_t* const cputime /**< Input: Maximum CPU time allowed for QP solution. \n - Output: CPU time spent for QP solution (or to perform nWSR iterations). */ - ); - -/** Solves an initialised QP sequence using the online active set strategy. - * By default, QP solution is started from previous solution. If a guess - * for the working set is provided, an initialised homotopy is performed. - * - * Note: This function internally calls solveQP/solveRegularisedQP - * for solving an initialised QP! - * - * \return SUCCESSFUL_RETURN \n - RET_MAX_NWSR_REACHED \n - RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED \n - RET_HOTSTART_FAILED \n - RET_SHIFT_DETERMINATION_FAILED \n - RET_STEPDIRECTION_DETERMINATION_FAILED \n - RET_STEPLENGTH_DETERMINATION_FAILED \n - RET_HOMOTOPY_STEP_FAILED \n - RET_HOTSTART_STOPPED_INFEASIBILITY \n - RET_HOTSTART_STOPPED_UNBOUNDEDNESS \n - RET_SETUP_AUXILIARYQP_FAILED */ -returnValue QProblem_hotstartW( QProblem* _THIS, - const real_t* const g_new, /**< Gradient of neighbouring QP to be solved. */ - const real_t* const lb_new, /**< Lower bounds of neighbouring QP to be solved. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* const ub_new, /**< Upper bounds of neighbouring QP to be solved. \n - If no upper bounds exist, a NULL pointer can be passed. */ - const real_t* const lbA_new, /**< Lower constraints' bounds of neighbouring QP to be solved. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - const real_t* const ubA_new, /**< Upper constraints' bounds of neighbouring QP to be solved. \n - If no upper constraints' bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations; \n - Output: Number of performed working set recalculations. */ - real_t* const cputime, /**< Input: Maximum CPU time allowed for QP solution. \n - Output: CPU time spent for QP solution (or to perform nWSR iterations). */ - Bounds* const guessedBounds, /**< Optimal working set of bounds for solution (xOpt,yOpt). \n - (If a null pointer is passed, the previous working set of bounds is kept!) */ - Constraints* const guessedConstraints /**< Optimal working set of constraints for solution (xOpt,yOpt). \n - (If a null pointer is passed, the previous working set of constraints is kept!) */ - ); - -/** Solves an initialised QP sequence using the online active set strategy, - * where QP data is read from files. - * By default, QP solution is started from previous solution. If a guess - * for the working set is provided, an initialised homotopy is performed. - * - * Note: This function internally calls solveQP/solveRegularisedQP - * for solving an initialised QP! - * - * \return SUCCESSFUL_RETURN \n - RET_MAX_NWSR_REACHED \n - RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED \n - RET_HOTSTART_FAILED \n - RET_SHIFT_DETERMINATION_FAILED \n - RET_STEPDIRECTION_DETERMINATION_FAILED \n - RET_STEPLENGTH_DETERMINATION_FAILED \n - RET_HOMOTOPY_STEP_FAILED \n - RET_HOTSTART_STOPPED_INFEASIBILITY \n - RET_HOTSTART_STOPPED_UNBOUNDEDNESS \n - RET_SETUP_AUXILIARYQP_FAILED \n - RET_UNABLE_TO_READ_FILE \n - RET_INVALID_ARGUMENTS */ -returnValue QProblem_hotstartFW( QProblem* _THIS, - const char* const g_file, /**< Name of file where gradient, of neighbouring QP to be solved, is stored. */ - const char* const lb_file, /**< Name of file where lower bounds, of neighbouring QP to be solved, is stored. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const char* const ub_file, /**< Name of file where upper bounds, of neighbouring QP to be solved, is stored. \n - If no upper bounds exist, a NULL pointer can be passed. */ - const char* const lbA_file, /**< Name of file where lower constraints' bounds, of neighbouring QP to be solved, is stored. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - const char* const ubA_file, /**< Name of file where upper constraints' bounds, of neighbouring QP to be solved, is stored. \n - If no upper constraints' bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations; \n - Output: Number of performed working set recalculations. */ - real_t* const cputime, /**< Input: Maximum CPU time allowed for QP solution. \n - Output: CPU time spent for QP solution (or to perform nWSR iterations). */ - Bounds* const guessedBounds, /**< Optimal working set of bounds for solution (xOpt,yOpt). \n - (If a null pointer is passed, the previous working set of bounds is kept!) */ - Constraints* const guessedConstraints /**< Optimal working set of constraints for solution (xOpt,yOpt). \n - (If a null pointer is passed, the previous working set of constraints is kept!) */ - ); - - -/** Solves using the current working set - * \return SUCCESSFUL_RETURN \n - * RET_STEPDIRECTION_FAILED_TQ \n - * RET_STEPDIRECTION_FAILED_CHOLESKY \n - * RET_INVALID_ARGUMENTS */ -returnValue QProblem_solveCurrentEQP ( QProblem* _THIS, - const int n_rhs, /**< Number of consecutive right hand sides */ - const real_t* g_in, /**< Gradient of neighbouring QP to be solved. */ - const real_t* lb_in, /**< Lower bounds of neighbouring QP to be solved. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* ub_in, /**< Upper bounds of neighbouring QP to be solved. \n - If no upper bounds exist, a NULL pointer can be passed. */ - const real_t* lbA_in, /**< Lower constraints' bounds of neighbouring QP to be solved. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - const real_t* ubA_in, /**< Upper constraints' bounds of neighbouring QP to be solved. \n */ - real_t* x_out, /**< Output: Primal solution */ - real_t* y_out /**< Output: Dual solution */ - ); - - - -/** Returns current constraints object of the QP (deep copy). - * \return SUCCESSFUL_RETURN \n - RET_QPOBJECT_NOT_SETUP */ -static inline returnValue QProblem_getConstraints( QProblem* _THIS, - Constraints* _constraints /** Output: Constraints object. */ - ); - - -/** Returns the number of constraints. - * \return Number of constraints. */ -static inline int QProblem_getNC( QProblem* _THIS ); - -/** Returns the number of (implicitly defined) equality constraints. - * \return Number of (implicitly defined) equality constraints. */ -static inline int QProblem_getNEC( QProblem* _THIS ); - -/** Returns the number of active constraints. - * \return Number of active constraints. */ -static inline int QProblem_getNAC( QProblem* _THIS ); - -/** Returns the number of inactive constraints. - * \return Number of inactive constraints. */ -static inline int QProblem_getNIAC( QProblem* _THIS ); - -/** Returns the dimension of null space. - * \return Dimension of null space. */ -int QProblem_getNZ( QProblem* _THIS ); - - -/** Returns the dual solution vector (deep copy). - * \return SUCCESSFUL_RETURN \n - RET_QP_NOT_SOLVED */ -returnValue QProblem_getDualSolution( QProblem* _THIS, - real_t* const yOpt /**< Output: Dual solution vector (if QP has been solved). */ - ); - - -/** Defines user-defined routine for calculating the constraint product A*x - * \return SUCCESSFUL_RETURN \n */ -returnValue QProblem_setConstraintProduct( QProblem* _THIS, - ConstraintProduct _constraintProduct - ); - - -/** Prints concise list of properties of the current QP. - * \return SUCCESSFUL_RETURN \n */ -returnValue QProblem_printProperties( QProblem* _THIS ); - - - -/** Writes a vector with the state of the working set -* \return SUCCESSFUL_RETURN */ -returnValue QProblem_getWorkingSet( QProblem* _THIS, - real_t* workingSet /** Output: array containing state of the working set. */ - ); - -/** Writes a vector with the state of the working set of bounds - * \return SUCCESSFUL_RETURN \n - * RET_INVALID_ARGUMENTS */ -returnValue QProblem_getWorkingSetBounds( QProblem* _THIS, - real_t* workingSetB /** Output: array containing state of the working set of bounds. */ - ); - -/** Writes a vector with the state of the working set of constraints - * \return SUCCESSFUL_RETURN \n - * RET_INVALID_ARGUMENTS */ -returnValue QProblem_getWorkingSetConstraints( QProblem* _THIS, - real_t* workingSetC /** Output: array containing state of the working set of constraints. */ - ); - - -/** Returns current bounds object of the QP (deep copy). - * \return SUCCESSFUL_RETURN \n - RET_QPOBJECT_NOT_SETUP */ -static inline returnValue QProblem_getBounds( QProblem* _THIS, - Bounds* _bounds /** Output: Bounds object. */ - ); - - -/** Returns the number of variables. - * \return Number of variables. */ -static inline int QProblem_getNV( QProblem* _THIS ); - -/** Returns the number of free variables. - * \return Number of free variables. */ -static inline int QProblem_getNFR( QProblem* _THIS ); - -/** Returns the number of fixed variables. - * \return Number of fixed variables. */ -static inline int QProblem_getNFX( QProblem* _THIS ); - -/** Returns the number of implicitly fixed variables. - * \return Number of implicitly fixed variables. */ -static inline int QProblem_getNFV( QProblem* _THIS ); - - -/** Returns the optimal objective function value. - * \return finite value: Optimal objective function value (QP was solved) \n - +infinity: QP was not yet solved */ -real_t QProblem_getObjVal( QProblem* _THIS ); - -/** Returns the objective function value at an arbitrary point x. - * \return Objective function value at point x */ -real_t QProblem_getObjValX( QProblem* _THIS, - const real_t* const _x /**< Point at which the objective function shall be evaluated. */ - ); - -/** Returns the primal solution vector. - * \return SUCCESSFUL_RETURN \n - RET_QP_NOT_SOLVED */ -returnValue QProblem_getPrimalSolution( QProblem* _THIS, - real_t* const xOpt /**< Output: Primal solution vector (if QP has been solved). */ - ); - - -/** Returns status of the solution process. - * \return Status of solution process. */ -static inline QProblemStatus QProblem_getStatus( QProblem* _THIS ); - - -/** Returns if the QProblem object is initialised. - * \return BT_TRUE: QProblem initialised \n - BT_FALSE: QProblem not initialised */ -static inline BooleanType QProblem_isInitialised( QProblem* _THIS ); - -/** Returns if the QP has been solved. - * \return BT_TRUE: QProblem solved \n - BT_FALSE: QProblem not solved */ -static inline BooleanType QProblem_isSolved( QProblem* _THIS ); - -/** Returns if the QP is infeasible. - * \return BT_TRUE: QP infeasible \n - BT_FALSE: QP feasible (or not known to be infeasible!) */ -static inline BooleanType QProblem_isInfeasible( QProblem* _THIS ); - -/** Returns if the QP is unbounded. - * \return BT_TRUE: QP unbounded \n - BT_FALSE: QP unbounded (or not known to be unbounded!) */ -static inline BooleanType QProblem_isUnbounded( QProblem* _THIS ); - - -/** Returns Hessian type flag (type is not determined due to _THIS call!). - * \return Hessian type. */ -static inline HessianType QProblem_getHessianType( QProblem* _THIS ); - -/** Changes the print level. - * \return SUCCESSFUL_RETURN */ -static inline returnValue QProblem_setHessianType( QProblem* _THIS, - HessianType _hessianType /**< New Hessian type. */ - ); - -/** Returns if the QP has been internally regularised. - * \return BT_TRUE: Hessian is internally regularised for QP solution \n - BT_FALSE: No internal Hessian regularisation is used for QP solution */ -static inline BooleanType QProblem_usingRegularisation( QProblem* _THIS ); - -/** Returns current options struct. - * \return Current options struct. */ -static inline Options QProblem_getOptions( QProblem* _THIS ); - -/** Overrides current options with given ones. - * \return SUCCESSFUL_RETURN */ -static inline returnValue QProblem_setOptions( QProblem* _THIS, - Options _options /**< New options. */ - ); - -/** Returns the print level. - * \return Print level. */ -static inline PrintLevel QProblem_getPrintLevel( QProblem* _THIS ); - -/** Changes the print level. - * \return SUCCESSFUL_RETURN */ -returnValue QProblem_setPrintLevel( QProblem* _THIS, - PrintLevel _printlevel /**< New print level. */ - ); - - -/** Returns the current number of QP problems solved. - * \return Number of QP problems solved. */ -static inline unsigned int QProblem_getCount( QProblem* _THIS ); - -/** Resets QP problem counter (to zero). - * \return SUCCESSFUL_RETURN. */ -static inline returnValue QProblem_resetCounter( QProblem* _THIS ); - - -/** Prints a list of all options and their current values. - * \return SUCCESSFUL_RETURN \n */ -returnValue QProblem_printOptions( QProblem* _THIS ); - - -/** Solves a QProblem whose QP data is assumed to be stored in the member variables. - * A guess for its primal/dual optimal solution vectors and the corresponding - * working sets of bounds and constraints can be provided. - * Note: This function is internally called by all init functions! - * \return SUCCESSFUL_RETURN \n - RET_INIT_FAILED \n - RET_INIT_FAILED_CHOLESKY \n - RET_INIT_FAILED_TQ \n - RET_INIT_FAILED_HOTSTART \n - RET_INIT_FAILED_INFEASIBILITY \n - RET_INIT_FAILED_UNBOUNDEDNESS \n - RET_MAX_NWSR_REACHED */ -returnValue QProblem_solveInitialQP( QProblem* _THIS, - const real_t* const xOpt, /**< Optimal primal solution vector.*/ - const real_t* const yOpt, /**< Optimal dual solution vector. */ - Bounds* const guessedBounds, /**< Optimal working set of bounds for solution (xOpt,yOpt). */ - Constraints* const guessedConstraints, /**< Optimal working set of constraints for solution (xOpt,yOpt). */ - const real_t* const _R, /**< Pre-computed (upper triangular) Cholesky factor of Hessian matrix. */ - int* nWSR, /**< Input: Maximum number of working set recalculations; \n - * Output: Number of performed working set recalculations. */ - real_t* const cputime /**< Input: Maximum CPU time allowed for QP solution. \n - * Output: CPU time spent for QP solution (or to perform nWSR iterations). */ - ); - -/** Solves QProblem using online active set strategy. - * Note: This function is internally called by all hotstart functions! - * \return SUCCESSFUL_RETURN \n - RET_MAX_NWSR_REACHED \n - RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED \n - RET_HOTSTART_FAILED \n - RET_SHIFT_DETERMINATION_FAILED \n - RET_STEPDIRECTION_DETERMINATION_FAILED \n - RET_STEPLENGTH_DETERMINATION_FAILED \n - RET_HOMOTOPY_STEP_FAILED \n - RET_HOTSTART_STOPPED_INFEASIBILITY \n - RET_HOTSTART_STOPPED_UNBOUNDEDNESS */ -returnValue QProblem_solveQP( QProblem* _THIS, - const real_t* const g_new, /**< Gradient of neighbouring QP to be solved. */ - const real_t* const lb_new, /**< Lower bounds of neighbouring QP to be solved. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* const ub_new, /**< Upper bounds of neighbouring QP to be solved. \n - If no upper bounds exist, a NULL pointer can be passed. */ - const real_t* const lbA_new, /**< Lower constraints' bounds of neighbouring QP to be solved. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - const real_t* const ubA_new, /**< Upper constraints' bounds of neighbouring QP to be solved. \n - If no upper constraints' bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations; \n - Output: Number of performed working set recalculations. */ - real_t* const cputime, /**< Input: Maximum CPU time allowed for QP solution. \n - Output: CPU time spent for QP solution (or to perform nWSR iterations). */ - int nWSRperformed, /**< Number of working set recalculations already performed to solve - this QP within previous solveQP() calls. This number is - always zero, except for successive calls from solveRegularisedQP() - or when using the far bound strategy. */ - BooleanType isFirstCall /**< Indicating whether this is the first call for current QP. */ - ); - - -/** Solves QProblem using online active set strategy. - * Note: This function is internally called by all hotstart functions! - * \return SUCCESSFUL_RETURN \n - RET_MAX_NWSR_REACHED \n - RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED \n - RET_HOTSTART_FAILED \n - RET_SHIFT_DETERMINATION_FAILED \n - RET_STEPDIRECTION_DETERMINATION_FAILED \n - RET_STEPLENGTH_DETERMINATION_FAILED \n - RET_HOMOTOPY_STEP_FAILED \n - RET_HOTSTART_STOPPED_INFEASIBILITY \n - RET_HOTSTART_STOPPED_UNBOUNDEDNESS */ -returnValue QProblem_solveRegularisedQP( QProblem* _THIS, - const real_t* const g_new, /**< Gradient of neighbouring QP to be solved. */ - const real_t* const lb_new, /**< Lower bounds of neighbouring QP to be solved. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* const ub_new, /**< Upper bounds of neighbouring QP to be solved. \n - If no upper bounds exist, a NULL pointer can be passed. */ - const real_t* const lbA_new, /**< Lower constraints' bounds of neighbouring QP to be solved. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - const real_t* const ubA_new, /**< Upper constraints' bounds of neighbouring QP to be solved. \n - If no upper constraints' bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations; \n - Output: Number of performed working set recalculations. */ - real_t* const cputime, /**< Input: Maximum CPU time allowed for QP solution. \n - Output: CPU time spent for QP solution (or to perform nWSR iterations). */ - int nWSRperformed, /**< Number of working set recalculations already performed to solve - this QP within previous solveRegularisedQP() calls. This number is - always zero, except for successive calls when using the far bound strategy. */ - BooleanType isFirstCall /**< Indicating whether this is the first call for current QP. */ - ); - - -/** Determines type of existing constraints and bounds (i.e. implicitly fixed, unbounded etc.). - * \return SUCCESSFUL_RETURN \n - RET_SETUPSUBJECTTOTYPE_FAILED */ -returnValue QProblem_setupSubjectToType( QProblem* _THIS ); - -/** Determines type of new constraints and bounds (i.e. implicitly fixed, unbounded etc.). - * \return SUCCESSFUL_RETURN \n - RET_SETUPSUBJECTTOTYPE_FAILED */ -returnValue QProblem_setupSubjectToTypeNew( QProblem* _THIS, - const real_t* const lb_new, /**< New lower bounds. */ - const real_t* const ub_new, /**< New upper bounds. */ - const real_t* const lbA_new, /**< New lower constraints' bounds. */ - const real_t* const ubA_new /**< New upper constraints' bounds. */ - ); - -/** Computes the Cholesky decomposition of the projected Hessian (i.e. R^T*R = Z^T*H*Z). - * Note: If Hessian turns out not to be positive definite, the Hessian type - * is set to HST_SEMIDEF accordingly. - * \return SUCCESSFUL_RETURN \n - * RET_HESSIAN_NOT_SPD \n - * RET_INDEXLIST_CORRUPTED */ -returnValue QProblem_computeProjectedCholesky( QProblem* _THIS ); - -/** Computes initial Cholesky decomposition of the projected Hessian making - * use of the function setupCholeskyDecomposition() or setupCholeskyDecompositionProjected(). - * \return SUCCESSFUL_RETURN \n - * RET_HESSIAN_NOT_SPD \n - * RET_INDEXLIST_CORRUPTED */ -returnValue QProblem_setupInitialCholesky( QProblem* _THIS ); - -/** Initialises TQ factorisation of A (i.e. A*Q = [0 T]) if NO constraint is active. - * \return SUCCESSFUL_RETURN \n - RET_INDEXLIST_CORRUPTED */ -returnValue QProblem_setupTQfactorisation( QProblem* _THIS ); - - -/** Obtains the desired working set for the auxiliary initial QP in - * accordance with the user specifications - * (assumes that member AX has already been initialised!) - * \return SUCCESSFUL_RETURN \n - RET_OBTAINING_WORKINGSET_FAILED \n - RET_INVALID_ARGUMENTS */ -returnValue QProblem_obtainAuxiliaryWorkingSet( QProblem* _THIS, - const real_t* const xOpt, /**< Optimal primal solution vector. - * If a NULL pointer is passed, all entries are assumed to be zero. */ - const real_t* const yOpt, /**< Optimal dual solution vector. - * If a NULL pointer is passed, all entries are assumed to be zero. */ - Bounds* const guessedBounds, /**< Guessed working set of bounds for solution (xOpt,yOpt). */ - Constraints* const guessedConstraints, /**< Guessed working set for solution (xOpt,yOpt). */ - Bounds* auxiliaryBounds, /**< Input: Allocated bound object. \n - * Ouput: Working set of constraints for auxiliary QP. */ - Constraints* auxiliaryConstraints /**< Input: Allocated bound object. \n - * Ouput: Working set for auxiliary QP. */ - ); - -/** Sets up bound and constraints data structures according to auxiliaryBounds/Constraints. - * (If the working set shall be setup afresh, make sure that - * bounds and constraints data structure have been resetted - * and the TQ factorisation has been initialised!) - * \return SUCCESSFUL_RETURN \n - RET_SETUP_WORKINGSET_FAILED \n - RET_INVALID_ARGUMENTS \n - RET_UNKNOWN_BUG */ -returnValue QProblem_setupAuxiliaryWorkingSet( QProblem* _THIS, - Bounds* const auxiliaryBounds, /**< Working set of bounds for auxiliary QP. */ - Constraints* const auxiliaryConstraints, /**< Working set of constraints for auxiliary QP. */ - BooleanType setupAfresh /**< Flag indicating if given working set shall be - * setup afresh or by updating the current one. */ - ); - -/** Sets up the optimal primal/dual solution of the auxiliary initial QP. - * \return SUCCESSFUL_RETURN */ -returnValue QProblem_setupAuxiliaryQPsolution( QProblem* _THIS, - const real_t* const xOpt, /**< Optimal primal solution vector. - * If a NULL pointer is passed, all entries are set to zero. */ - const real_t* const yOpt /**< Optimal dual solution vector. - * If a NULL pointer is passed, all entries are set to zero. */ - ); - -/** Sets up gradient of the auxiliary initial QP for given - * optimal primal/dual solution and given initial working set - * (assumes that members X, Y and BOUNDS, CONSTRAINTS have already been initialised!). - * \return SUCCESSFUL_RETURN */ -returnValue QProblem_setupAuxiliaryQPgradient( QProblem* _THIS ); - -/** Sets up (constraints') bounds of the auxiliary initial QP for given - * optimal primal/dual solution and given initial working set - * (assumes that members X, Y and BOUNDS, CONSTRAINTS have already been initialised!). - * \return SUCCESSFUL_RETURN \n - RET_UNKNOWN_BUG */ -returnValue QProblem_setupAuxiliaryQPbounds( QProblem* _THIS, - Bounds* const auxiliaryBounds, /**< Working set of bounds for auxiliary QP. */ - Constraints* const auxiliaryConstraints, /**< Working set of constraints for auxiliary QP. */ - BooleanType useRelaxation /**< Flag indicating if inactive (constraints') bounds shall be relaxed. */ - ); - - -/** Adds a constraint to active set. - * \return SUCCESSFUL_RETURN \n - RET_ADDCONSTRAINT_FAILED \n - RET_ADDCONSTRAINT_FAILED_INFEASIBILITY \n - RET_ENSURELI_FAILED */ -returnValue QProblem_addConstraint( QProblem* _THIS, - int number, /**< Number of constraint to be added to active set. */ - SubjectToStatus C_status, /**< Status of new active constraint. */ - BooleanType updateCholesky, /**< Flag indicating if Cholesky decomposition shall be updated. */ - BooleanType ensureLI /**< Ensure linear independence by exchange rules by default. */ - ); - -/** Checks if new active constraint to be added is linearly dependent from - * from row of the active constraints matrix. - * \return RET_LINEARLY_DEPENDENT \n - RET_LINEARLY_INDEPENDENT \n - RET_INDEXLIST_CORRUPTED */ -returnValue QProblem_addConstraint_checkLI( QProblem* _THIS, - int number /**< Number of constraint to be added to active set. */ - ); - -/** Ensures linear independence of constraint matrix when a new constraint is added. - * To _THIS end a bound or constraint is removed simultaneously if necessary. - * \return SUCCESSFUL_RETURN \n - RET_LI_RESOLVED \n - RET_ENSURELI_FAILED \n - RET_ENSURELI_FAILED_TQ \n - RET_ENSURELI_FAILED_NOINDEX \n - RET_REMOVE_FROM_ACTIVESET */ -returnValue QProblem_addConstraint_ensureLI( QProblem* _THIS, - int number, /**< Number of constraint to be added to active set. */ - SubjectToStatus C_status /**< Status of new active bound. */ - ); - -/** Adds a bound to active set. - * \return SUCCESSFUL_RETURN \n - RET_ADDBOUND_FAILED \n - RET_ADDBOUND_FAILED_INFEASIBILITY \n - RET_ENSURELI_FAILED */ -returnValue QProblem_addBound( QProblem* _THIS, - int number, /**< Number of bound to be added to active set. */ - SubjectToStatus B_status, /**< Status of new active bound. */ - BooleanType updateCholesky, /**< Flag indicating if Cholesky decomposition shall be updated. */ - BooleanType ensureLI /**< Ensure linear independence by exchange rules by default. */ - ); - -/** Checks if new active bound to be added is linearly dependent from - * from row of the active constraints matrix. - * \return RET_LINEARLY_DEPENDENT \n - RET_LINEARLY_INDEPENDENT */ -returnValue QProblem_addBound_checkLI( QProblem* _THIS, - int number /**< Number of bound to be added to active set. */ - ); - -/** Ensures linear independence of constraint matrix when a new bound is added. - * To _THIS end a bound or constraint is removed simultaneously if necessary. - * \return SUCCESSFUL_RETURN \n - RET_LI_RESOLVED \n - RET_ENSURELI_FAILED \n - RET_ENSURELI_FAILED_TQ \n - RET_ENSURELI_FAILED_NOINDEX \n - RET_REMOVE_FROM_ACTIVESET */ -returnValue QProblem_addBound_ensureLI( QProblem* _THIS, - int number, /**< Number of bound to be added to active set. */ - SubjectToStatus B_status /**< Status of new active bound. */ - ); - -/** Removes a constraint from active set. - * \return SUCCESSFUL_RETURN \n - RET_CONSTRAINT_NOT_ACTIVE \n - RET_REMOVECONSTRAINT_FAILED \n - RET_HESSIAN_NOT_SPD */ -returnValue QProblem_removeConstraint( QProblem* _THIS, - int number, /**< Number of constraint to be removed from active set. */ - BooleanType updateCholesky, /**< Flag indicating if Cholesky decomposition shall be updated. */ - BooleanType allowFlipping, /**< Flag indicating if flipping bounds are allowed. */ - BooleanType ensureNZC /**< Flag indicating if non-zero curvature is ensured by exchange rules. */ - ); - -/** Removes a bounds from active set. - * \return SUCCESSFUL_RETURN \n - RET_BOUND_NOT_ACTIVE \n - RET_HESSIAN_NOT_SPD \n - RET_REMOVEBOUND_FAILED */ -returnValue QProblem_removeBound( QProblem* _THIS, - int number, /**< Number of bound to be removed from active set. */ - BooleanType updateCholesky, /**< Flag indicating if Cholesky decomposition shall be updated. */ - BooleanType allowFlipping, /**< Flag indicating if flipping bounds are allowed. */ - BooleanType ensureNZC /**< Flag indicating if non-zero curvature is ensured by exchange rules. */ - ); - - -/** Performs robustified ratio test yield the maximum possible step length - * along the homotopy path. - * \return SUCCESSFUL_RETURN */ -returnValue QProblem_performPlainRatioTest( QProblem* _THIS, - int nIdx, /**< Number of ratios to be checked. */ - const int* const idxList, /**< Array containing the indices of all ratios to be checked. */ - const real_t* const num, /**< Array containing all numerators for performing the ratio test. */ - const real_t* const den, /**< Array containing all denominators for performing the ratio test. */ - real_t epsNum, /**< Numerator tolerance. */ - real_t epsDen, /**< Denominator tolerance. */ - real_t* t, /**< Output: Maximum possible step length along the homotopy path. */ - int* BC_idx /**< Output: Index of blocking constraint. */ - ); - - -/** Ensure non-zero curvature by primal jump. - * \return SUCCESSFUL_RETURN \n - * RET_HOTSTART_STOPPED_UNBOUNDEDNESS */ -returnValue QProblem_ensureNonzeroCurvature( QProblem* _THIS, - BooleanType removeBoundNotConstraint, /**< SubjectTo to be removed is a bound. */ - int remIdx, /**< Index of bound/constraint to be removed. */ - BooleanType* exchangeHappened, /**< Output: Exchange was necessary to ensure. */ - BooleanType* addBoundNotConstraint, /**< SubjectTo to be added is a bound. */ - int* addIdx, /**< Index of bound/constraint to be added. */ - SubjectToStatus* addStatus /**< Status of bound/constraint to be added. */ - ); - - -/** Solves the system Ta = b or T^Ta = b where T is a reverse upper triangular matrix. - * \return SUCCESSFUL_RETURN \n - RET_DIV_BY_ZERO */ -returnValue QProblem_backsolveT( QProblem* _THIS, - const real_t* const b, /**< Right hand side vector. */ - BooleanType transposed, /**< Indicates if the transposed system shall be solved. */ - real_t* const a /**< Output: Solution vector */ - ); - - -/** Determines step direction of the shift of the QP data. - * \return SUCCESSFUL_RETURN */ -returnValue QProblem_determineDataShift( QProblem* _THIS, - const real_t* const g_new, /**< New gradient vector. */ - const real_t* const lbA_new, /**< New lower constraints' bounds. */ - const real_t* const ubA_new, /**< New upper constraints' bounds. */ - const real_t* const lb_new, /**< New lower bounds. */ - const real_t* const ub_new, /**< New upper bounds. */ - real_t* const delta_g, /**< Output: Step direction of gradient vector. */ - real_t* const delta_lbA, /**< Output: Step direction of lower constraints' bounds. */ - real_t* const delta_ubA, /**< Output: Step direction of upper constraints' bounds. */ - real_t* const delta_lb, /**< Output: Step direction of lower bounds. */ - real_t* const delta_ub, /**< Output: Step direction of upper bounds. */ - BooleanType* Delta_bC_isZero, /**< Output: Indicates if active constraints' bounds are to be shifted. */ - BooleanType* Delta_bB_isZero /**< Output: Indicates if active bounds are to be shifted. */ - ); - -/** Determines step direction of the homotopy path. - * \return SUCCESSFUL_RETURN \n - RET_STEPDIRECTION_FAILED_TQ \n - RET_STEPDIRECTION_FAILED_CHOLESKY */ -returnValue QProblem_determineStepDirection( QProblem* _THIS, - const real_t* const delta_g, /**< Step direction of gradient vector. */ - const real_t* const delta_lbA, /**< Step direction of lower constraints' bounds. */ - const real_t* const delta_ubA, /**< Step direction of upper constraints' bounds. */ - const real_t* const delta_lb, /**< Step direction of lower bounds. */ - const real_t* const delta_ub, /**< Step direction of upper bounds. */ - BooleanType Delta_bC_isZero, /**< Indicates if active constraints' bounds are to be shifted. */ - BooleanType Delta_bB_isZero, /**< Indicates if active bounds are to be shifted. */ - real_t* const delta_xFX, /**< Output: Primal homotopy step direction of fixed variables. */ - real_t* const delta_xFR, /**< Output: Primal homotopy step direction of free variables. */ - real_t* const delta_yAC, /**< Output: Dual homotopy step direction of active constraints' multiplier. */ - real_t* const delta_yFX /**< Output: Dual homotopy step direction of fixed variables' multiplier. */ - ); - -/** Determines the maximum possible step length along the homotopy path - * and performs _THIS step (without changing working set). - * \return SUCCESSFUL_RETURN \n - * RET_ERROR_IN_CONSTRAINTPRODUCT \n - * RET_QP_INFEASIBLE */ -returnValue QProblem_performStep( QProblem* _THIS, - const real_t* const delta_g, /**< Step direction of gradient. */ - const real_t* const delta_lbA, /**< Step direction of lower constraints' bounds. */ - const real_t* const delta_ubA, /**< Step direction of upper constraints' bounds. */ - const real_t* const delta_lb, /**< Step direction of lower bounds. */ - const real_t* const delta_ub, /**< Step direction of upper bounds. */ - const real_t* const delta_xFX, /**< Primal homotopy step direction of fixed variables. */ - const real_t* const delta_xFR, /**< Primal homotopy step direction of free variables. */ - const real_t* const delta_yAC, /**< Dual homotopy step direction of active constraints' multiplier. */ - const real_t* const delta_yFX, /**< Dual homotopy step direction of fixed variables' multiplier. */ - int* BC_idx, /**< Output: Index of blocking constraint. */ - SubjectToStatus* BC_status, /**< Output: Status of blocking constraint. */ - BooleanType* BC_isBound /**< Output: Indicates if blocking constraint is a bound. */ - ); - -/** Updates the active set. - * \return SUCCESSFUL_RETURN \n - RET_REMOVE_FROM_ACTIVESET_FAILED \n - RET_ADD_TO_ACTIVESET_FAILED */ -returnValue QProblem_changeActiveSet( QProblem* _THIS, - int BC_idx, /**< Index of blocking constraint. */ - SubjectToStatus BC_status, /**< Status of blocking constraint. */ - BooleanType BC_isBound /**< Indicates if blocking constraint is a bound. */ - ); - - -/** Compute relative length of homotopy in data space for termination - * criterion. - * \return Relative length in data space. */ -real_t QProblem_getRelativeHomotopyLength( QProblem* _THIS, - const real_t* const g_new, /**< Final gradient. */ - const real_t* const lb_new, /**< Final lower variable bounds. */ - const real_t* const ub_new, /**< Final upper variable bounds. */ - const real_t* const lbA_new, /**< Final lower constraint bounds. */ - const real_t* const ubA_new /**< Final upper constraint bounds. */ - ); - - -/** Ramping Strategy to avoid ties. Modifies homotopy start without - * changing current active set. - * \return SUCCESSFUL_RETURN */ -returnValue QProblem_performRamping( QProblem* _THIS ); - - -/** ... */ -returnValue QProblem_updateFarBounds( QProblem* _THIS, - real_t curFarBound, /**< ... */ - int nRamp, /**< ... */ - const real_t* const lb_new, /**< ... */ - real_t* const lb_new_far, /**< ... */ - const real_t* const ub_new, /**< ... */ - real_t* const ub_new_far, /**< ... */ - const real_t* const lbA_new, /**< ... */ - real_t* const lbA_new_far, /**< ... */ - const real_t* const ubA_new, /**< ... */ - real_t* const ubA_new_far /**< ... */ - ); - -/** ... */ -returnValue QProblemBCPY_updateFarBounds( QProblem* _THIS, - real_t curFarBound, /**< ... */ - int nRamp, /**< ... */ - const real_t* const lb_new, /**< ... */ - real_t* const lb_new_far, /**< ... */ - const real_t* const ub_new, /**< ... */ - real_t* const ub_new_far /**< ... */ - ); - - - -/** Performs robustified ratio test yield the maximum possible step length - * along the homotopy path. - * \return SUCCESSFUL_RETURN */ -returnValue QProblem_performRatioTestC( QProblem* _THIS, - int nIdx, /**< Number of ratios to be checked. */ - const int* const idxList, /**< Array containing the indices of all ratios to be checked. */ - Constraints* const subjectTo, /**< Constraint object corresponding to ratios to be checked. */ - const real_t* const num, /**< Array containing all numerators for performing the ratio test. */ - const real_t* const den, /**< Array containing all denominators for performing the ratio test. */ - real_t epsNum, /**< Numerator tolerance. */ - real_t epsDen, /**< Denominator tolerance. */ - real_t* t, /**< Output: Maximum possible step length along the homotopy path. */ - int* BC_idx /**< Output: Index of blocking constraint. */ - ); - - -/** Drift correction at end of each active set iteration - * \return SUCCESSFUL_RETURN */ -returnValue QProblem_performDriftCorrection( QProblem* _THIS ); - - -/** Updates QP vectors, working sets and internal data structures in order to - start from an optimal solution corresponding to initial guesses of the working - set for bounds and constraints. - * \return SUCCESSFUL_RETURN \n - * RET_SETUP_AUXILIARYQP_FAILED \n - RET_INVALID_ARGUMENTS */ -returnValue QProblem_setupAuxiliaryQP( QProblem* _THIS, - Bounds* const guessedBounds, /**< Initial guess for working set of bounds. */ - Constraints* const guessedConstraints /**< Initial guess for working set of constraints. */ - ); - -/** Determines if it is more efficient to refactorise the matrices when - * hotstarting or not (i.e. better to update the existing factorisations). - * \return BT_TRUE iff matrices shall be refactorised afresh - */ -BooleanType QProblem_shallRefactorise( QProblem* _THIS, - Bounds* const guessedBounds, /**< Guessed new working set of bounds. */ - Constraints* const guessedConstraints /**< Guessed new working set of constraints. */ - ); - -/** Setups internal QP data. - * \return SUCCESSFUL_RETURN \n - RET_INVALID_ARGUMENTS \n - RET_UNKNONW_BUG */ -returnValue QProblem_setupQPdataM( QProblem* _THIS, - DenseMatrix *_H, /**< Hessian matrix. \n - If Hessian matrix is trivial,a NULL pointer can be passed. */ - const real_t* const _g, /**< Gradient vector. */ - DenseMatrix *_A, /**< Constraint matrix. */ - const real_t* const _lb, /**< Lower bound vector (on variables). \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* const _ub, /**< Upper bound vector (on variables). \n - If no upper bounds exist, a NULL pointer can be passed. */ - const real_t* const _lbA, /**< Lower constraints' bound vector. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - const real_t* const _ubA /**< Upper constraints' bound vector. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - ); - - -/** Sets up dense internal QP data. If the current Hessian is trivial - * (i.e. HST_ZERO or HST_IDENTITY) but a non-trivial one is given, - * memory for Hessian is allocated and it is set to the given one. - * \return SUCCESSFUL_RETURN \n - RET_INVALID_ARGUMENTS \n - RET_UNKNONW_BUG */ -returnValue QProblem_setupQPdata( QProblem* _THIS, - real_t* const _H, /**< Hessian matrix. \n - If Hessian matrix is trivial,a NULL pointer can be passed. */ - const real_t* const _g, /**< Gradient vector. */ - real_t* const _A, /**< Constraint matrix. */ - const real_t* const _lb, /**< Lower bound vector (on variables). \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* const _ub, /**< Upper bound vector (on variables). \n - If no upper bounds exist, a NULL pointer can be passed. */ - const real_t* const _lbA, /**< Lower constraints' bound vector. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - const real_t* const _ubA /**< Upper constraints' bound vector. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - ); - -/** Sets up internal QP data by loading it from files. If the current Hessian - * is trivial (i.e. HST_ZERO or HST_IDENTITY) but a non-trivial one is given, - * memory for Hessian is allocated and it is set to the given one. - * \return SUCCESSFUL_RETURN \n - RET_UNABLE_TO_OPEN_FILE \n - RET_UNABLE_TO_READ_FILE \n - RET_INVALID_ARGUMENTS \n - RET_UNKNONW_BUG */ -returnValue QProblem_setupQPdataFromFile( QProblem* _THIS, - const char* const H_file, /**< Name of file where Hessian matrix, of neighbouring QP to be solved, is stored. \n - If Hessian matrix is trivial,a NULL pointer can be passed. */ - const char* const g_file, /**< Name of file where gradient, of neighbouring QP to be solved, is stored. */ - const char* const A_file, /**< Name of file where constraint matrix, of neighbouring QP to be solved, is stored. */ - const char* const lb_file, /**< Name of file where lower bounds, of neighbouring QP to be solved, is stored. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const char* const ub_file, /**< Name of file where upper bounds, of neighbouring QP to be solved, is stored. \n - If no upper bounds exist, a NULL pointer can be passed. */ - const char* const lbA_file, /**< Name of file where lower constraints' bounds, of neighbouring QP to be solved, is stored. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - const char* const ubA_file /**< Name of file where upper constraints' bounds, of neighbouring QP to be solved, is stored. \n - If no upper constraints' bounds exist, a NULL pointer can be passed. */ - ); - -/** Loads new QP vectors from files (internal members are not affected!). - * \return SUCCESSFUL_RETURN \n - RET_UNABLE_TO_OPEN_FILE \n - RET_UNABLE_TO_READ_FILE \n - RET_INVALID_ARGUMENTS */ -returnValue QProblem_loadQPvectorsFromFile( QProblem* _THIS, - const char* const g_file, /**< Name of file where gradient, of neighbouring QP to be solved, is stored. */ - const char* const lb_file, /**< Name of file where lower bounds, of neighbouring QP to be solved, is stored. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const char* const ub_file, /**< Name of file where upper bounds, of neighbouring QP to be solved, is stored. \n - If no upper bounds exist, a NULL pointer can be passed. */ - const char* const lbA_file, /**< Name of file where lower constraints' bounds, of neighbouring QP to be solved, is stored. \n - If no lower constraints' bounds exist, a NULL pointer can be passed. */ - const char* const ubA_file, /**< Name of file where upper constraints' bounds, of neighbouring QP to be solved, is stored. \n - If no upper constraints' bounds exist, a NULL pointer can be passed. */ - real_t* const g_new, /**< Output: Gradient of neighbouring QP to be solved. */ - real_t* const lb_new, /**< Output: Lower bounds of neighbouring QP to be solved */ - real_t* const ub_new, /**< Output: Upper bounds of neighbouring QP to be solved */ - real_t* const lbA_new, /**< Output: Lower constraints' bounds of neighbouring QP to be solved */ - real_t* const ubA_new /**< Output: Upper constraints' bounds of neighbouring QP to be solved */ - ); - - -/** Prints concise information on the current iteration. - * \return SUCCESSFUL_RETURN \n */ -returnValue QProblem_printIteration( QProblem* _THIS, - int iter, /**< Number of current iteration. */ - int BC_idx, /**< Index of blocking constraint. */ - SubjectToStatus BC_status, /**< Status of blocking constraint. */ - BooleanType BC_isBound, /**< Indicates if blocking constraint is a bound. */ - real_t homotopyLength, /**< Current homotopy distance. */ - BooleanType isFirstCall /**< Indicating whether this is the first call for current QP. */ - ); - - -/** Sets constraint matrix of the QP. \n - Note: Also internal vector Ax is recomputed! - * \return SUCCESSFUL_RETURN \n - * RET_INVALID_ARGUMENTS */ -static inline returnValue QProblem_setAM( QProblem* _THIS, - DenseMatrix *A_new /**< New constraint matrix. */ - ); - -/** Sets dense constraint matrix of the QP. \n - Note: Also internal vector Ax is recomputed! - * \return SUCCESSFUL_RETURN \n - * RET_INVALID_ARGUMENTS */ -static inline returnValue QProblem_setA( QProblem* _THIS, - real_t* const A_new /**< New dense constraint matrix (with correct dimension!). */ - ); - - -/** Sets constraints' lower bound vector of the QP. - * \return SUCCESSFUL_RETURN \n - * RET_QPOBJECT_NOT_SETUP */ -static inline returnValue QProblem_setLBA( QProblem* _THIS, - const real_t* const lbA_new /**< New constraints' lower bound vector (with correct dimension!). */ - ); - -/** Changes single entry of lower constraints' bound vector of the QP. - * \return SUCCESSFUL_RETURN \n - * RET_QPOBJECT_NOT_SETUP \n - * RET_INDEX_OUT_OF_BOUNDS */ -static inline returnValue QProblem_setLBAn( QProblem* _THIS, - int number, /**< Number of entry to be changed. */ - real_t value /**< New value for entry of lower constraints' bound vector (with correct dimension!). */ - ); - -/** Sets constraints' upper bound vector of the QP. - * \return SUCCESSFUL_RETURN \n - * RET_QPOBJECT_NOT_SETUP */ -static inline returnValue QProblem_setUBA( QProblem* _THIS, - const real_t* const ubA_new /**< New constraints' upper bound vector (with correct dimension!). */ - ); - -/** Changes single entry of upper constraints' bound vector of the QP. - * \return SUCCESSFUL_RETURN \n - * RET_QPOBJECT_NOT_SETUP \n - * RET_INDEX_OUT_OF_BOUNDS */ -static inline returnValue QProblem_setUBAn( QProblem* _THIS, - int number, /**< Number of entry to be changed. */ - real_t value /**< New value for entry of upper constraints' bound vector (with correct dimension!). */ - ); - - -/** Decides if lower bounds are smaller than upper bounds - * - * \return SUCCESSFUL_RETURN \n - * RET_QP_INFEASIBLE */ -returnValue QProblem_areBoundsConsistent( QProblem* _THIS, - const real_t* const lb, /**< Vector of lower bounds*/ - const real_t* const ub, /**< Vector of upper bounds*/ - const real_t* const lbA, /**< Vector of lower constraints*/ - const real_t* const ubA /**< Vector of upper constraints*/ - ); - - -/** Drops the blocking bound/constraint that led to infeasibility, or finds another - * bound/constraint to drop according to drop priorities. - * \return SUCCESSFUL_RETURN \n - */ -returnValue QProblem_dropInfeasibles ( QProblem* _THIS, - int BC_number, /**< Number of the bound or constraint to be added */ - SubjectToStatus BC_status, /**< New status of the bound or constraint to be added */ - BooleanType BC_isBound, /**< Whether a bound or a constraint is to be added */ - real_t *xiB, - real_t *xiC - ); - - -/** If Hessian type has been set by the user, nothing is done. - * Otherwise the Hessian type is set to HST_IDENTITY, HST_ZERO, or - * HST_POSDEF (default), respectively. - * \return SUCCESSFUL_RETURN \n - RET_HESSIAN_INDEFINITE */ -returnValue QProblem_determineHessianType( QProblem* _THIS ); - -/** Computes the Cholesky decomposition of the (simply projected) Hessian - * (i.e. R^T*R = Z^T*H*Z). It only works in the case where Z is a simple - * projection matrix! - * Note: If Hessian turns out not to be positive definite, the Hessian type - * is set to HST_SEMIDEF accordingly. - * \return SUCCESSFUL_RETURN \n - * RET_HESSIAN_NOT_SPD \n - * RET_INDEXLIST_CORRUPTED */ -returnValue QProblemBCPY_computeCholesky( QProblem* _THIS ); - -/** Obtains the desired working set for the auxiliary initial QP in - * accordance with the user specifications - * \return SUCCESSFUL_RETURN \n - RET_OBTAINING_WORKINGSET_FAILED \n - RET_INVALID_ARGUMENTS */ -returnValue QProblemBCPY_obtainAuxiliaryWorkingSet( QProblem* _THIS, - const real_t* const xOpt, /**< Optimal primal solution vector. - * If a NULL pointer is passed, all entries are assumed to be zero. */ - const real_t* const yOpt, /**< Optimal dual solution vector. - * If a NULL pointer is passed, all entries are assumed to be zero. */ - Bounds* const guessedBounds, /**< Guessed working set for solution (xOpt,yOpt). */ - Bounds* auxiliaryBounds /**< Input: Allocated bound object. \n - * Output: Working set for auxiliary QP. */ - ); - - -/** Solves the system Ra = b or R^Ta = b where R is an upper triangular matrix. - * \return SUCCESSFUL_RETURN \n - RET_DIV_BY_ZERO */ -returnValue QProblem_backsolveR( QProblem* _THIS, - const real_t* const b, /**< Right hand side vector. */ - BooleanType transposed, /**< Indicates if the transposed system shall be solved. */ - real_t* const a /**< Output: Solution vector */ - ); - -/** Solves the system Ra = b or R^Ta = b where R is an upper triangular matrix. \n - * Special variant for the case that _THIS function is called from within "removeBound()". - * \return SUCCESSFUL_RETURN \n - RET_DIV_BY_ZERO */ -returnValue QProblem_backsolveRrem( QProblem* _THIS, - const real_t* const b, /**< Right hand side vector. */ - BooleanType transposed, /**< Indicates if the transposed system shall be solved. */ - BooleanType removingBound, /**< Indicates if function is called from "removeBound()". */ - real_t* const a /**< Output: Solution vector */ - ); - - -/** Determines step direction of the shift of the QP data. - * \return SUCCESSFUL_RETURN */ -returnValue QProblemBCPY_determineDataShift( QProblem* _THIS, - const real_t* const g_new, /**< New gradient vector. */ - const real_t* const lb_new, /**< New lower bounds. */ - const real_t* const ub_new, /**< New upper bounds. */ - real_t* const delta_g, /**< Output: Step direction of gradient vector. */ - real_t* const delta_lb, /**< Output: Step direction of lower bounds. */ - real_t* const delta_ub, /**< Output: Step direction of upper bounds. */ - BooleanType* Delta_bB_isZero /**< Output: Indicates if active bounds are to be shifted. */ - ); - - -/** Sets up internal QP data. - * \return SUCCESSFUL_RETURN \n - RET_INVALID_ARGUMENTS */ -returnValue QProblemBCPY_setupQPdataM( QProblem* _THIS, - DenseMatrix *_H, /**< Hessian matrix.*/ - const real_t* const _g, /**< Gradient vector. */ - const real_t* const _lb, /**< Lower bounds (on variables). \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* const _ub /**< Upper bounds (on variables). \n - If no upper bounds exist, a NULL pointer can be passed. */ - ); - -/** Sets up internal QP data. If the current Hessian is trivial - * (i.e. HST_ZERO or HST_IDENTITY) but a non-trivial one is given, - * memory for Hessian is allocated and it is set to the given one. - * \return SUCCESSFUL_RETURN \n - RET_INVALID_ARGUMENTS \n - RET_NO_HESSIAN_SPECIFIED */ -returnValue QProblemBCPY_setupQPdata( QProblem* _THIS, - real_t* const _H, /**< Hessian matrix. \n - If Hessian matrix is trivial,a NULL pointer can be passed. */ - const real_t* const _g, /**< Gradient vector. */ - const real_t* const _lb, /**< Lower bounds (on variables). \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* const _ub /**< Upper bounds (on variables). \n - If no upper bounds exist, a NULL pointer can be passed. */ - ); - -/** Sets up internal QP data by loading it from files. If the current Hessian - * is trivial (i.e. HST_ZERO or HST_IDENTITY) but a non-trivial one is given, - * memory for Hessian is allocated and it is set to the given one. - * \return SUCCESSFUL_RETURN \n - RET_UNABLE_TO_OPEN_FILE \n - RET_UNABLE_TO_READ_FILE \n - RET_INVALID_ARGUMENTS \n - RET_NO_HESSIAN_SPECIFIED */ -returnValue QProblemBCPY_setupQPdataFromFile( QProblem* _THIS, - const char* const H_file, /**< Name of file where Hessian matrix, of neighbouring QP to be solved, is stored. \n - If Hessian matrix is trivial,a NULL pointer can be passed. */ - const char* const g_file, /**< Name of file where gradient, of neighbouring QP to be solved, is stored. */ - const char* const lb_file, /**< Name of file where lower bounds, of neighbouring QP to be solved, is stored. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const char* const ub_file /**< Name of file where upper bounds, of neighbouring QP to be solved, is stored. \n - If no upper bounds exist, a NULL pointer can be passed. */ - ); - -/** Loads new QP vectors from files (internal members are not affected!). - * \return SUCCESSFUL_RETURN \n - RET_UNABLE_TO_OPEN_FILE \n - RET_UNABLE_TO_READ_FILE \n - RET_INVALID_ARGUMENTS */ -returnValue QProblemBCPY_loadQPvectorsFromFile( QProblem* _THIS, - const char* const g_file, /**< Name of file where gradient, of neighbouring QP to be solved, is stored. */ - const char* const lb_file, /**< Name of file where lower bounds, of neighbouring QP to be solved, is stored. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const char* const ub_file, /**< Name of file where upper bounds, of neighbouring QP to be solved, is stored. \n - If no upper bounds exist, a NULL pointer can be passed. */ - real_t* const g_new, /**< Output: Gradient of neighbouring QP to be solved. */ - real_t* const lb_new, /**< Output: Lower bounds of neighbouring QP to be solved */ - real_t* const ub_new /**< Output: Upper bounds of neighbouring QP to be solved */ - ); - - -/** Sets internal infeasibility flag and throws given error in case the far bound - * strategy is not enabled (as QP might actually not be infeasible in _THIS case). - * \return RET_HOTSTART_STOPPED_INFEASIBILITY \n - RET_ENSURELI_FAILED_CYCLING \n - RET_ENSURELI_FAILED_NOINDEX */ -returnValue QProblem_setInfeasibilityFlag( QProblem* _THIS, - returnValue returnvalue, /**< Returnvalue to be tunneled. */ - BooleanType doThrowError /**< Flag forcing to throw an error. */ - ); - - -/** Determines if next QP iteration can be performed within given CPU time limit. - * \return BT_TRUE: CPU time limit is exceeded, stop QP solution. \n - BT_FALSE: Sufficient CPU time for next QP iteration. */ -BooleanType QProblem_isCPUtimeLimitExceeded( QProblem* _THIS, - const real_t* const cputime, /**< Maximum CPU time allowed for QP solution. */ - real_t starttime, /**< Start time of current QP solution. */ - int nWSR /**< Number of working set recalculations performed so far. */ - ); - - -/** Regularise Hessian matrix by adding a scaled identity matrix to it. - * \return SUCCESSFUL_RETURN \n - RET_HESSIAN_ALREADY_REGULARISED */ -returnValue QProblem_regulariseHessian( QProblem* _THIS ); - - -/** Sets Hessian matrix of the QP. - * \return SUCCESSFUL_RETURN */ -static inline returnValue QProblem_setHM( QProblem* _THIS, - DenseMatrix* H_new /**< New Hessian matrix. */ - ); - -/** Sets dense Hessian matrix of the QP. - * If a null pointer is passed and - * a) hessianType is HST_IDENTITY, nothing is done, - * b) hessianType is not HST_IDENTITY, Hessian matrix is set to zero. - * \return SUCCESSFUL_RETURN */ -static inline returnValue QProblem_setH( QProblem* _THIS, - real_t* const H_new /**< New dense Hessian matrix (with correct dimension!). */ - ); - -/** Changes gradient vector of the QP. - * \return SUCCESSFUL_RETURN \n - * RET_INVALID_ARGUMENTS */ -static inline returnValue QProblem_setG( QProblem* _THIS, - const real_t* const g_new /**< New gradient vector (with correct dimension!). */ - ); - -/** Changes lower bound vector of the QP. - * \return SUCCESSFUL_RETURN \n - * RET_INVALID_ARGUMENTS */ -static inline returnValue QProblem_setLB( QProblem* _THIS, - const real_t* const lb_new /**< New lower bound vector (with correct dimension!). */ - ); - -/** Changes single entry of lower bound vector of the QP. - * \return SUCCESSFUL_RETURN \n - RET_INDEX_OUT_OF_BOUNDS */ -static inline returnValue QProblem_setLBn( QProblem* _THIS, - int number, /**< Number of entry to be changed. */ - real_t value /**< New value for entry of lower bound vector. */ - ); - -/** Changes upper bound vector of the QP. - * \return SUCCESSFUL_RETURN \n - * RET_INVALID_ARGUMENTS */ -static inline returnValue QProblem_setUB( QProblem* _THIS, - const real_t* const ub_new /**< New upper bound vector (with correct dimension!). */ - ); - -/** Changes single entry of upper bound vector of the QP. - * \return SUCCESSFUL_RETURN \n - RET_INDEX_OUT_OF_BOUNDS */ -static inline returnValue QProblem_setUBn( QProblem* _THIS, - int number, /**< Number of entry to be changed. */ - real_t value /**< New value for entry of upper bound vector. */ - ); - - - -/** Compute relative length of homotopy in data space for termination - * criterion. - * \return Relative length in data space. */ -real_t QProblemBCPY_getRelativeHomotopyLength( QProblem* _THIS, - const real_t* const g_new, /**< Final gradient. */ - const real_t* const lb_new, /**< Final lower variable bounds. */ - const real_t* const ub_new /**< Final upper variable bounds. */ - ); - - - -/** Performs robustified ratio test yield the maximum possible step length - * along the homotopy path. - * \return SUCCESSFUL_RETURN */ -returnValue QProblem_performRatioTestB( QProblem* _THIS, - int nIdx, /**< Number of ratios to be checked. */ - const int* const idxList, /**< Array containing the indices of all ratios to be checked. */ - Bounds* const subjectTo, /**< Bound object corresponding to ratios to be checked. */ - const real_t* const num, /**< Array containing all numerators for performing the ratio test. */ - const real_t* const den, /**< Array containing all denominators for performing the ratio test. */ - real_t epsNum, /**< Numerator tolerance. */ - real_t epsDen, /**< Denominator tolerance. */ - real_t* t, /**< Output: Maximum possible step length along the homotopy path. */ - int* BC_idx /**< Output: Index of blocking constraint. */ - ); - -/** Checks whether given ratio is blocking, i.e. limits the maximum step length - * along the homotopy path to a value lower than given one. - * \return SUCCESSFUL_RETURN */ -static inline BooleanType QProblem_isBlocking( QProblem* _THIS, - real_t num, /**< Numerator for performing the ratio test. */ - real_t den, /**< Denominator for performing the ratio test. */ - real_t epsNum, /**< Numerator tolerance. */ - real_t epsDen, /**< Denominator tolerance. */ - real_t* t /**< Input: Current maximum step length along the homotopy path, - * Output: Updated maximum possible step length along the homotopy path. */ - ); - - -/** ... - * \return SUCCESSFUL_RETURN \n - RET_UNABLE_TO_OPEN_FILE */ -returnValue QProblem_writeQpDataIntoMatFile( QProblem* _THIS, - const char* const filename /**< Mat file name. */ - ); - -/** ... -* \return SUCCESSFUL_RETURN \n - RET_UNABLE_TO_OPEN_FILE */ -returnValue QProblem_writeQpWorkspaceIntoMatFile( QProblem* _THIS, - const char* const filename /**< Mat file name. */ - ); - - -/* - * g e t B o u n d s - */ -static inline returnValue QProblem_getBounds( QProblem* _THIS, Bounds* _bounds ) -{ - int nV = QProblem_getNV( _THIS ); - - if ( nV == 0 ) - return THROWERROR( RET_QPOBJECT_NOT_SETUP ); - - _bounds = _THIS->bounds; - - return SUCCESSFUL_RETURN; -} - - -/* - * g e t N V - */ -static inline int QProblem_getNV( QProblem* _THIS ) -{ - return Bounds_getNV( _THIS->bounds ); -} - - -/* - * g e t N F R - */ -static inline int QProblem_getNFR( QProblem* _THIS ) -{ - return Bounds_getNFR( _THIS->bounds ); -} - - -/* - * g e t N F X - */ -static inline int QProblem_getNFX( QProblem* _THIS ) -{ - return Bounds_getNFX( _THIS->bounds ); -} - - -/* - * g e t N F V - */ -static inline int QProblem_getNFV( QProblem* _THIS ) -{ - return Bounds_getNFV( _THIS->bounds ); -} - - -/* - * g e t S t a t u s - */ -static inline QProblemStatus QProblem_getStatus( QProblem* _THIS ) -{ - return _THIS->status; -} - - -/* - * i s I n i t i a l i s e d - */ -static inline BooleanType QProblem_isInitialised( QProblem* _THIS ) -{ - if ( _THIS->status == QPS_NOTINITIALISED ) - return BT_FALSE; - else - return BT_TRUE; -} - - -/* - * i s S o l v e d - */ -static inline BooleanType QProblem_isSolved( QProblem* _THIS ) -{ - if ( _THIS->status == QPS_SOLVED ) - return BT_TRUE; - else - return BT_FALSE; -} - - -/* - * i s I n f e a s i b l e - */ -static inline BooleanType QProblem_isInfeasible( QProblem* _THIS ) -{ - return _THIS->infeasible; -} - - -/* - * i s U n b o u n d e d - */ -static inline BooleanType QProblem_isUnbounded( QProblem* _THIS ) -{ - return _THIS->unbounded; -} - - -/* - * g e t H e s s i a n T y p e - */ -static inline HessianType QProblem_getHessianType( QProblem* _THIS ) -{ - return _THIS->hessianType; -} - - -/* - * s e t H e s s i a n T y p e - */ -static inline returnValue QProblem_setHessianType( QProblem* _THIS, HessianType _hessianType ) -{ - _THIS->hessianType = _hessianType; - return SUCCESSFUL_RETURN; -} - - -/* - * u s i n g R e g u l a r i s a t i o n - */ -static inline BooleanType QProblem_usingRegularisation( QProblem* _THIS ) -{ - if ( _THIS->regVal > QPOASES_ZERO ) - return BT_TRUE; - else - return BT_FALSE; -} - - -/* - * g e t O p t i o n s - */ -static inline Options QProblem_getOptions( QProblem* _THIS ) -{ - return _THIS->options; -} - - -/* - * s e t O p t i o n s - */ -static inline returnValue QProblem_setOptions( QProblem* _THIS, - Options _options - ) -{ - OptionsCPY( &_options,&(_THIS->options) ); - Options_ensureConsistency( &(_THIS->options) ); - - QProblem_setPrintLevel( _THIS,_THIS->options.printLevel ); - - return SUCCESSFUL_RETURN; -} - - -/* - * g e t P r i n t L e v e l - */ -static inline PrintLevel QProblem_getPrintLevel( QProblem* _THIS ) -{ - return _THIS->options.printLevel; -} - - -/* - * g e t C o u n t - */ -static inline unsigned int QProblem_getCount( QProblem* _THIS ) -{ - return _THIS->count; -} - - -/* - * r e s e t C o u n t e r - */ -static inline returnValue QProblem_resetCounter( QProblem* _THIS ) -{ - _THIS->count = 0; - return SUCCESSFUL_RETURN; -} - - - -/***************************************************************************** - * P R O T E C T E D * - *****************************************************************************/ - - -/* - * s e t H - */ -static inline returnValue QProblem_setHM( QProblem* _THIS, DenseMatrix* H_new ) -{ - if ( H_new == 0 ) - return QProblem_setH( _THIS,(real_t*)0 ); - else - return QProblem_setH( _THIS,DenseMatrix_getVal(H_new) ); -} - - -/* - * s e t H - */ -static inline returnValue QProblem_setH( QProblem* _THIS, real_t* const H_new ) -{ - /* if null pointer is passed, Hessian is set to zero matrix - * (or stays identity matrix) */ - if ( H_new == 0 ) - { - if ( _THIS->hessianType == HST_IDENTITY ) - return SUCCESSFUL_RETURN; - - _THIS->hessianType = HST_ZERO; - - _THIS->H = 0; - } - else - { - DenseMatrixCON( _THIS->H,QProblem_getNV( _THIS ),QProblem_getNV( _THIS ),QProblem_getNV( _THIS ),H_new ); - } - - return SUCCESSFUL_RETURN; -} - - -/* - * s e t G - */ -static inline returnValue QProblem_setG( QProblem* _THIS, const real_t* const g_new ) -{ - unsigned int nV = (unsigned int)QProblem_getNV( _THIS ); - - if ( nV == 0 ) - return THROWERROR( RET_QPOBJECT_NOT_SETUP ); - - if ( g_new == 0 ) - return THROWERROR( RET_INVALID_ARGUMENTS ); - - memcpy( _THIS->g,g_new,nV*sizeof(real_t) ); - - return SUCCESSFUL_RETURN; -} - - -/* - * s e t L B - */ -static inline returnValue QProblem_setLB( QProblem* _THIS, const real_t* const lb_new ) -{ - unsigned int i; - unsigned int nV = (unsigned int)QProblem_getNV( _THIS ); - - if ( nV == 0 ) - return THROWERROR( RET_QPOBJECT_NOT_SETUP ); - - if ( lb_new != 0 ) - { - memcpy( _THIS->lb,lb_new,nV*sizeof(real_t) ); - } - else - { - /* if no lower bounds are specified, set them to -infinity */ - for( i=0; ilb[i] = -QPOASES_INFTY; - } - - return SUCCESSFUL_RETURN; -} - - -/* - * s e t L B - */ -static inline returnValue QProblem_setLBn( QProblem* _THIS, int number, real_t value ) -{ - int nV = QProblem_getNV( _THIS ); - - if ( nV == 0 ) - return THROWERROR( RET_QPOBJECT_NOT_SETUP ); - - if ( ( number >= 0 ) && ( number < nV ) ) - { - _THIS->lb[number] = value; - return SUCCESSFUL_RETURN; - } - else - { - return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); - } -} - - -/* - * s e t U B - */ -static inline returnValue QProblem_setUB( QProblem* _THIS, const real_t* const ub_new ) -{ - unsigned int i; - unsigned int nV = (unsigned int)QProblem_getNV( _THIS ); - - if ( nV == 0 ) - return THROWERROR( RET_QPOBJECT_NOT_SETUP ); - - if ( ub_new != 0 ) - { - memcpy( _THIS->ub,ub_new,nV*sizeof(real_t) ); - } - else - { - /* if no upper bounds are specified, set them to infinity */ - for( i=0; iub[i] = QPOASES_INFTY; - } - - return SUCCESSFUL_RETURN; -} - - -/* - * s e t U B - */ -static inline returnValue QProblem_setUBn( QProblem* _THIS, int number, real_t value ) -{ - int nV = QProblem_getNV( _THIS ); - - if ( nV == 0 ) - return THROWERROR( RET_QPOBJECT_NOT_SETUP ); - - if ( ( number >= 0 ) && ( number < nV ) ) - { - _THIS->ub[number] = value; - - return SUCCESSFUL_RETURN; - } - else - { - return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); - } -} - - - -/* - * i s B l o c k i n g - */ -static inline BooleanType QProblem_isBlocking( QProblem* _THIS, - real_t num, - real_t den, - real_t epsNum, - real_t epsDen, - real_t* t - ) -{ - if ( ( den >= epsDen ) && ( num >= epsNum ) ) - { - if ( num < (*t)*den ) - return BT_TRUE; - } - - return BT_FALSE; -} - - - -/* - * g e t C o n s t r a i n t s - */ -static inline returnValue QProblem_getConstraints( QProblem* _THIS, Constraints* _constraints ) -{ - int nV = QProblem_getNV( _THIS ); - - if ( nV == 0 ) - return THROWERROR( RET_QPOBJECT_NOT_SETUP ); - - ConstraintsCPY( _THIS->constraints,_constraints ); - - return SUCCESSFUL_RETURN; -} - - - -/* - * g e t N C - */ -static inline int QProblem_getNC( QProblem* _THIS ) -{ - return Constraints_getNC( _THIS->constraints ); -} - - -/* - * g e t N E C - */ -static inline int QProblem_getNEC( QProblem* _THIS ) -{ - return Constraints_getNEC( _THIS->constraints ); -} - - -/* - * g e t N A C - */ -static inline int QProblem_getNAC( QProblem* _THIS ) -{ - return Constraints_getNAC( _THIS->constraints ); -} - - -/* - * g e t N I A C - */ -static inline int QProblem_getNIAC( QProblem* _THIS ) -{ - return Constraints_getNIAC( _THIS->constraints ); -} - - - -/***************************************************************************** - * P R O T E C T E D * - *****************************************************************************/ - - -/* - * s e t A - */ -static inline returnValue QProblem_setAM( QProblem* _THIS, DenseMatrix *A_new ) -{ - if ( A_new == 0 ) - return QProblem_setA( _THIS,(real_t*)0 ); - else - return QProblem_setA( _THIS,DenseMatrix_getVal(A_new) ); -} - - -/* - * s e t A - */ -static inline returnValue QProblem_setA( QProblem* _THIS, real_t* const A_new ) -{ - int j; - int nV = QProblem_getNV( _THIS ); - int nC = QProblem_getNC( _THIS ); - - if ( nV == 0 ) - return THROWERROR( RET_QPOBJECT_NOT_SETUP ); - - if ( A_new == 0 ) - return THROWERROR( RET_INVALID_ARGUMENTS ); - - DenseMatrixCON( _THIS->A,QProblem_getNC( _THIS ),QProblem_getNV( _THIS ),QProblem_getNV( _THIS ),A_new ); - - DenseMatrix_times( _THIS->A,1, 1.0, _THIS->x, nV, 0.0, _THIS->Ax, nC); - - for( j=0; jAx_u[j] = _THIS->ubA[j] - _THIS->Ax[j]; - _THIS->Ax_l[j] = _THIS->Ax[j] - _THIS->lbA[j]; - - /* (ckirches) disable constraints with empty rows */ - if ( qpOASES_isZero( DenseMatrix_getRowNorm( _THIS->A,j,2 ),QPOASES_ZERO ) == BT_TRUE ) - Constraints_setType( _THIS->constraints,j,ST_DISABLED ); - } - - return SUCCESSFUL_RETURN; -} - - -/* - * s e t L B A - */ -static inline returnValue QProblem_setLBA( QProblem* _THIS, const real_t* const lbA_new ) -{ - unsigned int i; - unsigned int nV = (unsigned int)QProblem_getNV( _THIS ); - unsigned int nC = (unsigned int)QProblem_getNC( _THIS ); - - if ( nV == 0 ) - return THROWERROR( RET_QPOBJECT_NOT_SETUP ); - - if ( lbA_new != 0 ) - { - memcpy( _THIS->lbA,lbA_new,nC*sizeof(real_t) ); - } - else - { - /* if no lower constraints' bounds are specified, set them to -infinity */ - for( i=0; ilbA[i] = -QPOASES_INFTY; - } - - return SUCCESSFUL_RETURN; -} - - -/* - * s e t L B A - */ -static inline returnValue QProblem_setLBAn( QProblem* _THIS, int number, real_t value ) -{ - int nV = QProblem_getNV( _THIS ); - int nC = QProblem_getNC( _THIS ); - - if ( nV == 0 ) - return THROWERROR( RET_QPOBJECT_NOT_SETUP ); - - if ( ( number >= 0 ) && ( number < nC ) ) - { - _THIS->lbA[number] = value; - return SUCCESSFUL_RETURN; - } - else - return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); -} - - -/* - * s e t U B A - */ -static inline returnValue QProblem_setUBA( QProblem* _THIS, const real_t* const ubA_new ) -{ - unsigned int i; - unsigned int nV = (unsigned int)QProblem_getNV( _THIS ); - unsigned int nC = (unsigned int)QProblem_getNC( _THIS ); - - if ( nV == 0 ) - return THROWERROR( RET_QPOBJECT_NOT_SETUP ); - - if ( ubA_new != 0 ) - { - memcpy( _THIS->ubA,ubA_new,nC*sizeof(real_t) ); - } - else - { - /* if no upper constraints' bounds are specified, set them to infinity */ - for( i=0; iubA[i] = QPOASES_INFTY; - } - - return SUCCESSFUL_RETURN; -} - - -/* - * s e t U B A - */ -static inline returnValue QProblem_setUBAn( QProblem* _THIS, int number, real_t value ) -{ - int nV = QProblem_getNV( _THIS ); - int nC = QProblem_getNC( _THIS ); - - if ( nV == 0 ) - return THROWERROR( RET_QPOBJECT_NOT_SETUP ); - - if ( ( number >= 0 ) && ( number < nC ) ) - { - _THIS->ubA[number] = value; - return SUCCESSFUL_RETURN; - } - else - return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); -} - - -END_NAMESPACE_QPOASES - - -#endif /* QPOASES_QPROBLEM_H */ - - -/* - * end of file - */ diff --git a/third_party/acados/include/qpOASES_e/QProblemB.h b/third_party/acados/include/qpOASES_e/QProblemB.h deleted file mode 100644 index ee5157d..0000000 --- a/third_party/acados/include/qpOASES_e/QProblemB.h +++ /dev/null @@ -1,1641 +0,0 @@ -/* - * This file is part of qpOASES. - * - * qpOASES -- An Implementation of the Online Active Set Strategy. - * Copyright (C) 2007-2015 by Hans Joachim Ferreau, Andreas Potschka, - * Christian Kirches et al. All rights reserved. - * - * qpOASES is free software; you can redistribute it and/or - * modify it under the terms of the GNU Lesser General Public - * License as published by the Free Software Foundation; either - * version 2.1 of the License, or (at your option) any later version. - * - * qpOASES is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public - * License along with qpOASES; if not, write to the Free Software - * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - * - */ - - -/** - * \file include/qpOASES_e/QProblemB.h - * \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches - * \version 3.1embedded - * \date 2007-2015 - * - * Declaration of the QProblemB class which is able to use the newly - * developed online active set strategy for parametric quadratic programming - * for problems with (simple) bounds only. - */ - - - -#ifndef QPOASES_QPROBLEMB_H -#define QPOASES_QPROBLEMB_H - - -#include -#include -#include -#include - - -BEGIN_NAMESPACE_QPOASES - -typedef struct { - Bounds *emptyBounds; - Bounds *auxiliaryBounds; - - real_t *ub_new_far; - real_t *lb_new_far; - - real_t *g_new; - real_t *lb_new; - real_t *ub_new; - - real_t *g_new2; - real_t *lb_new2; - real_t *ub_new2; - - real_t *Hx; - - real_t *_H; - - real_t *g_original; - real_t *lb_original; - real_t *ub_original; - - real_t *delta_xFR; - real_t *delta_xFX; - real_t *delta_yFX; - real_t *delta_g; - real_t *delta_lb; - real_t *delta_ub; - - real_t *gMod; - - real_t *num; - real_t *den; - - real_t *rhs; - real_t *r; -} QProblemB_ws; - -int QProblemB_ws_calculateMemorySize( unsigned int nV ); - -char *QProblemB_ws_assignMemory( unsigned int nV, QProblemB_ws **mem, void *raw_memory ); - -QProblemB_ws *QProblemB_ws_createMemory( unsigned int nV ); - - -/** - * \brief Implements the online active set strategy for box-constrained QPs. - * - * Class for setting up and solving quadratic programs with bounds (= box constraints) only. - * The main feature is the possibility to use the newly developed online active set strategy - * for parametric quadratic programming. - * - * \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches - * \version 3.1embedded - * \date 2007-2015 - */ -typedef struct -{ - QProblemB_ws *ws; - Bounds *bounds; /**< Data structure for problem's bounds. */ - Flipper *flipper; /**< Struct for making a temporary copy of the matrix factorisations. */ - - DenseMatrix* H; /**< Hessian matrix pointer. */ - - Options options; /**< Struct containing all user-defined options for solving QPs. */ - TabularOutput tabularOutput; /**< Struct storing information for tabular output (printLevel == PL_TABULAR). */ - - real_t *g; /**< Gradient. */ - real_t *lb; /**< Lower bound vector (on variables). */ - real_t *ub; /**< Upper bound vector (on variables). */ - - real_t *R; /**< Cholesky factor of H (i.e. H = R^T*R). */ - - real_t *x; /**< Primal solution vector. */ - real_t *y; /**< Dual solution vector. */ - - real_t *delta_xFR_TMP; /**< Temporary for determineStepDirection */ - - real_t tau; /**< Last homotopy step length. */ - real_t regVal; /**< Holds the offset used to regularise Hessian matrix (zero by default). */ - - real_t ramp0; /**< Start value for Ramping Strategy. */ - real_t ramp1; /**< Final value for Ramping Strategy. */ - - QProblemStatus status; /**< Current status of the solution process. */ - HessianType hessianType; /**< Type of Hessian matrix. */ - - BooleanType haveCholesky; /**< Flag indicating whether Cholesky decomposition has already been setup. */ - BooleanType infeasible; /**< QP infeasible? */ - BooleanType unbounded; /**< QP unbounded? */ - - int rampOffset; /**< Offset index for Ramping. */ - unsigned int count; /**< Counts the number of hotstart function calls (internal usage only!). */ -} QProblemB; - -int QProblemB_calculateMemorySize( unsigned int nV ); - -char *QProblemB_assignMemory( unsigned int nV, QProblemB **mem, void *raw_memory ); - -QProblemB *QProblemB_createMemory( unsigned int nV ); - - -/** Constructor which takes the QP dimension and Hessian type - * information. If the Hessian is the zero (i.e. HST_ZERO) or the - * identity matrix (i.e. HST_IDENTITY), respectively, no memory - * is allocated for it and a NULL pointer can be passed for it - * to the init() functions. */ -void QProblemBCON( QProblemB* _THIS, - int _nV, /**< Number of variables. */ - HessianType _hessianType /**< Type of Hessian matrix. */ - ); - -void QProblemBCPY( QProblemB* FROM, - QProblemB* TO - ); - - -/** Clears all data structures of QProblemB except for QP data. - * \return SUCCESSFUL_RETURN \n - RET_RESET_FAILED */ -returnValue QProblemB_reset( QProblemB* _THIS ); - - -/** Initialises a simply bounded QP problem with given QP data and tries to solve it - * using at most nWSR iterations. - * - * Note: This function internally calls solveInitialQP for initialisation! - * - * \return SUCCESSFUL_RETURN \n - RET_INIT_FAILED \n - RET_INIT_FAILED_CHOLESKY \n - RET_INIT_FAILED_HOTSTART \n - RET_INIT_FAILED_INFEASIBILITY \n - RET_INIT_FAILED_UNBOUNDEDNESS \n - RET_MAX_NWSR_REACHED \n - RET_INVALID_ARGUMENTS */ -returnValue QProblemB_initM( QProblemB* _THIS, - DenseMatrix *_H, /**< Hessian matrix. */ - const real_t* const _g, /**< Gradient vector. */ - const real_t* const _lb, /**< Lower bounds (on variables). \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* const _ub, /**< Upper bounds (on variables). \n - If no upper bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations when using initial homotopy. \n - Output: Number of performed working set recalculations. */ - real_t* const cputime /**< Input: Maximum CPU time allowed for QP initialisation. \n - Output: CPU time spent for QP initialisation (if pointer passed). */ - ); - -/** Initialises a simply bounded QP problem with given QP data and tries to solve it - * using at most nWSR iterations. - * - * Note: This function internally calls solveInitialQP for initialisation! - * - * \return SUCCESSFUL_RETURN \n - RET_INIT_FAILED \n - RET_INIT_FAILED_CHOLESKY \n - RET_INIT_FAILED_HOTSTART \n - RET_INIT_FAILED_INFEASIBILITY \n - RET_INIT_FAILED_UNBOUNDEDNESS \n - RET_MAX_NWSR_REACHED \n - RET_INVALID_ARGUMENTS */ -returnValue QProblemB_init( QProblemB* _THIS, - real_t* const _H, /**< Hessian matrix. \n - If Hessian matrix is trivial, a NULL pointer can be passed. */ - const real_t* const _g, /**< Gradient vector. */ - const real_t* const _lb, /**< Lower bounds (on variables). \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* const _ub, /**< Upper bounds (on variables). \n - If no upper bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations when using initial homotopy. \n - Output: Number of performed working set recalculations. */ - real_t* const cputime /**< Input: Maximum CPU time allowed for QP initialisation. \n - Output: CPU time spent for QP initialisation (if pointer passed). */ - ); - -/** Initialises a simply bounded QP problem with given QP data to be read from files and solves it - * using at most nWSR iterations. - * - * Note: This function internally calls solveInitialQP for initialisation! - * - * \return SUCCESSFUL_RETURN \n - RET_INIT_FAILED \n - RET_INIT_FAILED_CHOLESKY \n - RET_INIT_FAILED_HOTSTART \n - RET_INIT_FAILED_INFEASIBILITY \n - RET_INIT_FAILED_UNBOUNDEDNESS \n - RET_MAX_NWSR_REACHED \n - RET_UNABLE_TO_READ_FILE */ -returnValue QProblemB_initF( QProblemB* _THIS, - const char* const H_file, /**< Name of file where Hessian matrix is stored. \n - If Hessian matrix is trivial, a NULL pointer can be passed. */ - const char* const g_file, /**< Name of file where gradient vector is stored. */ - const char* const lb_file, /**< Name of file where lower bound vector. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const char* const ub_file, /**< Name of file where upper bound vector. \n - If no upper bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations when using initial homotopy. \n - Output: Number of performed working set recalculations. */ - real_t* const cputime /**< Input: Maximum CPU time allowed for QP initialisation. \n - Output: CPU time spent for QP initialisation (if pointer passed). */ - ); - -/** Initialises a simply bounded QP problem with given QP data and tries to solve it - * using at most nWSR iterations. Depending on the parameter constellation it: \n - * 1. 0, 0, 0 : starts with xOpt = 0, yOpt = 0 and gB empty (or all implicit equality bounds), \n - * 2. xOpt, 0, 0 : starts with xOpt, yOpt = 0 and obtain gB by "clipping", \n - * 3. 0, yOpt, 0 : starts with xOpt = 0, yOpt and obtain gB from yOpt != 0, \n - * 4. 0, 0, gB: starts with xOpt = 0, yOpt = 0 and gB, \n - * 5. xOpt, yOpt, 0 : starts with xOpt, yOpt and obtain gB from yOpt != 0, \n - * 6. xOpt, 0, gB: starts with xOpt, yOpt = 0 and gB, \n - * 7. xOpt, yOpt, gB: starts with xOpt, yOpt and gB (assume them to be consistent!) - * - * Note: This function internally calls solveInitialQP for initialisation! - * - * \return SUCCESSFUL_RETURN \n - RET_INIT_FAILED \n - RET_INIT_FAILED_CHOLESKY \n - RET_INIT_FAILED_HOTSTART \n - RET_INIT_FAILED_INFEASIBILITY \n - RET_INIT_FAILED_UNBOUNDEDNESS \n - RET_MAX_NWSR_REACHED \n - RET_INVALID_ARGUMENTS */ -returnValue QProblemB_initMW( QProblemB* _THIS, - DenseMatrix *_H, /**< Hessian matrix. */ - const real_t* const _g, /**< Gradient vector. */ - const real_t* const _lb, /**< Lower bounds (on variables). \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* const _ub, /**< Upper bounds (on variables). \n - If no upper bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations when using initial homotopy. \n - Output: Number of performed working set recalculations. */ - real_t* const cputime, /**< Input: Maximum CPU time allowed for QP initialisation. \n - Output: CPU time spent for QP initialisation. */ - const real_t* const xOpt, /**< Optimal primal solution vector. A NULL pointer can be passed. \n - (If a null pointer is passed, the old primal solution is kept!) */ - const real_t* const yOpt, /**< Optimal dual solution vector. A NULL pointer can be passed. \n - (If a null pointer is passed, the old dual solution is kept!) */ - Bounds* const guessedBounds, /**< Optimal working set of bounds for solution (xOpt,yOpt). \n - (If a null pointer is passed, all bounds are assumed inactive!) */ - const real_t* const _R /**< Pre-computed (upper triangular) Cholesky factor of Hessian matrix. - The Cholesky factor must be stored in a real_t array of size nV*nV - in row-major format. Note: Only used if xOpt/yOpt and gB are NULL! \n - (If a null pointer is passed, Cholesky decomposition is computed internally!) */ - ); - -/** Initialises a simply bounded QP problem with given QP data and tries to solve it - * using at most nWSR iterations. Depending on the parameter constellation it: \n - * 1. 0, 0, 0 : starts with xOpt = 0, yOpt = 0 and gB empty (or all implicit equality bounds), \n - * 2. xOpt, 0, 0 : starts with xOpt, yOpt = 0 and obtain gB by "clipping", \n - * 3. 0, yOpt, 0 : starts with xOpt = 0, yOpt and obtain gB from yOpt != 0, \n - * 4. 0, 0, gB: starts with xOpt = 0, yOpt = 0 and gB, \n - * 5. xOpt, yOpt, 0 : starts with xOpt, yOpt and obtain gB from yOpt != 0, \n - * 6. xOpt, 0, gB: starts with xOpt, yOpt = 0 and gB, \n - * 7. xOpt, yOpt, gB: starts with xOpt, yOpt and gB (assume them to be consistent!) - * - * Note: This function internally calls solveInitialQP for initialisation! - * - * \return SUCCESSFUL_RETURN \n - RET_INIT_FAILED \n - RET_INIT_FAILED_CHOLESKY \n - RET_INIT_FAILED_HOTSTART \n - RET_INIT_FAILED_INFEASIBILITY \n - RET_INIT_FAILED_UNBOUNDEDNESS \n - RET_MAX_NWSR_REACHED \n - RET_INVALID_ARGUMENTS */ -returnValue QProblemB_initW( QProblemB* _THIS, - real_t* const _H, /**< Hessian matrix. \n - If Hessian matrix is trivial, a NULL pointer can be passed. */ - const real_t* const _g, /**< Gradient vector. */ - const real_t* const _lb, /**< Lower bounds (on variables). \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* const _ub, /**< Upper bounds (on variables). \n - If no upper bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations when using initial homotopy. \n - Output: Number of performed working set recalculations. */ - real_t* const cputime, /**< Input: Maximum CPU time allowed for QP initialisation. \n - Output: CPU time spent for QP initialisation. */ - const real_t* const xOpt, /**< Optimal primal solution vector. A NULL pointer can be passed. \n - (If a null pointer is passed, the old primal solution is kept!) */ - const real_t* const yOpt, /**< Optimal dual solution vector. A NULL pointer can be passed. \n - (If a null pointer is passed, the old dual solution is kept!) */ - Bounds* const guessedBounds, /**< Optimal working set of bounds for solution (xOpt,yOpt). \n - (If a null pointer is passed, all bounds are assumed inactive!) */ - const real_t* const _R /**< Pre-computed (upper triangular) Cholesky factor of Hessian matrix. - The Cholesky factor must be stored in a real_t array of size nV*nV - in row-major format. Note: Only used if xOpt/yOpt and gB are NULL! \n - (If a null pointer is passed, Cholesky decomposition is computed internally!) */ - ); - -/** Initialises a simply bounded QP problem with given QP data to be read from files and solves it - * using at most nWSR iterations. Depending on the parameter constellation it: \n - * 1. 0, 0, 0 : starts with xOpt = 0, yOpt = 0 and gB empty (or all implicit equality bounds), \n - * 2. xOpt, 0, 0 : starts with xOpt, yOpt = 0 and obtain gB by "clipping", \n - * 3. 0, yOpt, 0 : starts with xOpt = 0, yOpt and obtain gB from yOpt != 0, \n - * 4. 0, 0, gB: starts with xOpt = 0, yOpt = 0 and gB, \n - * 5. xOpt, yOpt, 0 : starts with xOpt, yOpt and obtain gB from yOpt != 0, \n - * 6. xOpt, 0, gB: starts with xOpt, yOpt = 0 and gB, \n - * 7. xOpt, yOpt, gB: starts with xOpt, yOpt and gB (assume them to be consistent!) - * - * Note: This function internally calls solveInitialQP for initialisation! - * - * \return SUCCESSFUL_RETURN \n - RET_INIT_FAILED \n - RET_INIT_FAILED_CHOLESKY \n - RET_INIT_FAILED_HOTSTART \n - RET_INIT_FAILED_INFEASIBILITY \n - RET_INIT_FAILED_UNBOUNDEDNESS \n - RET_MAX_NWSR_REACHED \n - RET_UNABLE_TO_READ_FILE */ -returnValue QProblemB_initFW( QProblemB* _THIS, - const char* const H_file, /**< Name of file where Hessian matrix is stored. \n - If Hessian matrix is trivial, a NULL pointer can be passed. */ - const char* const g_file, /**< Name of file where gradient vector is stored. */ - const char* const lb_file, /**< Name of file where lower bound vector. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const char* const ub_file, /**< Name of file where upper bound vector. \n - If no upper bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations when using initial homotopy. \n - Output: Number of performed working set recalculations. */ - real_t* const cputime, /**< Input: Maximum CPU time allowed for QP initialisation. \n - Output: CPU time spent for QP initialisation. */ - const real_t* const xOpt, /**< Optimal primal solution vector. A NULL pointer can be passed. \n - (If a null pointer is passed, the old primal solution is kept!) */ - const real_t* const yOpt, /**< Optimal dual solution vector. A NULL pointer can be passed. \n - (If a null pointer is passed, the old dual solution is kept!) */ - Bounds* const guessedBounds, /**< Optimal working set of bounds for solution (xOpt,yOpt). \n - (If a null pointer is passed, all bounds are assumed inactive!) */ - const char* const R_file /**< Name of the file where a pre-computed (upper triangular) Cholesky factor - of the Hessian matrix is stored. \n - (If a null pointer is passed, Cholesky decomposition is computed internally!) */ - ); - - -/** Solves an initialised QP sequence using the online active set strategy. - * By default, QP solution is started from previous solution. - * - * Note: This function internally calls solveQP/solveRegularisedQP - * for solving an initialised QP! - * - * \return SUCCESSFUL_RETURN \n - RET_MAX_NWSR_REACHED \n - RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED \n - RET_HOTSTART_FAILED \n - RET_SHIFT_DETERMINATION_FAILED \n - RET_STEPDIRECTION_DETERMINATION_FAILED \n - RET_STEPLENGTH_DETERMINATION_FAILED \n - RET_HOMOTOPY_STEP_FAILED \n - RET_HOTSTART_STOPPED_INFEASIBILITY \n - RET_HOTSTART_STOPPED_UNBOUNDEDNESS */ -returnValue QProblemB_hotstart( QProblemB* _THIS, - const real_t* const g_new, /**< Gradient of neighbouring QP to be solved. */ - const real_t* const lb_new, /**< Lower bounds of neighbouring QP to be solved. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* const ub_new, /**< Upper bounds of neighbouring QP to be solved. \n - If no upper bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations; \n - Output: Number of performed working set recalculations. */ - real_t* const cputime /**< Input: Maximum CPU time allowed for QP solution. \n - Output: CPU time spent for QP solution (or to perform nWSR iterations). */ - ); - -/** Solves an initialised QP sequence using the online active set strategy, - * where QP data is read from files. QP solution is started from previous solution. - * - * Note: This function internally calls solveQP/solveRegularisedQP - * for solving an initialised QP! - * - * \return SUCCESSFUL_RETURN \n - RET_MAX_NWSR_REACHED \n - RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED \n - RET_HOTSTART_FAILED \n - RET_SHIFT_DETERMINATION_FAILED \n - RET_STEPDIRECTION_DETERMINATION_FAILED \n - RET_STEPLENGTH_DETERMINATION_FAILED \n - RET_HOMOTOPY_STEP_FAILED \n - RET_HOTSTART_STOPPED_INFEASIBILITY \n - RET_HOTSTART_STOPPED_UNBOUNDEDNESS \n - RET_UNABLE_TO_READ_FILE \n - RET_INVALID_ARGUMENTS */ -returnValue QProblemB_hotstartF( QProblemB* _THIS, - const char* const g_file, /**< Name of file where gradient, of neighbouring QP to be solved, is stored. */ - const char* const lb_file, /**< Name of file where lower bounds, of neighbouring QP to be solved, is stored. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const char* const ub_file, /**< Name of file where upper bounds, of neighbouring QP to be solved, is stored. \n - If no upper bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations; \n - Output: Number of performed working set recalculations. */ - real_t* const cputime /**< Input: Maximum CPU time allowed for QP solution. \n - Output: CPU time spent for QP solution (or to perform nWSR iterations). */ - ); - -/** Solves an initialised QP sequence using the online active set strategy. - * By default, QP solution is started from previous solution. If a guess - * for the working set is provided, an initialised homotopy is performed. - * - * Note: This function internally calls solveQP/solveRegularisedQP - * for solving an initialised QP! - * - * \return SUCCESSFUL_RETURN \n - RET_MAX_NWSR_REACHED \n - RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED \n - RET_HOTSTART_FAILED \n - RET_SHIFT_DETERMINATION_FAILED \n - RET_STEPDIRECTION_DETERMINATION_FAILED \n - RET_STEPLENGTH_DETERMINATION_FAILED \n - RET_HOMOTOPY_STEP_FAILED \n - RET_HOTSTART_STOPPED_INFEASIBILITY \n - RET_HOTSTART_STOPPED_UNBOUNDEDNESS \n - RET_SETUP_AUXILIARYQP_FAILED */ -returnValue QProblemB_hotstartW( QProblemB* _THIS, - const real_t* const g_new, /**< Gradient of neighbouring QP to be solved. */ - const real_t* const lb_new, /**< Lower bounds of neighbouring QP to be solved. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* const ub_new, /**< Upper bounds of neighbouring QP to be solved. \n - If no upper bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations; \n - Output: Number of performed working set recalculations. */ - real_t* const cputime, /**< Input: Maximum CPU time allowed for QP solution. \n - Output: CPU time spent for QP solution (or to perform nWSR iterations). */ - Bounds* const guessedBounds /**< Optimal working set of bounds for solution (xOpt,yOpt). \n - (If a null pointer is passed, the previous working set is kept!) */ - ); - -/** Solves an initialised QP sequence using the online active set strategy, - * where QP data is read from files. - * By default, QP solution is started from previous solution. If a guess - * for the working set is provided, an initialised homotopy is performed. - * - * Note: This function internally calls solveQP/solveRegularisedQP - * for solving an initialised QP! - * - * \return SUCCESSFUL_RETURN \n - RET_MAX_NWSR_REACHED \n - RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED \n - RET_HOTSTART_FAILED \n - RET_SHIFT_DETERMINATION_FAILED \n - RET_STEPDIRECTION_DETERMINATION_FAILED \n - RET_STEPLENGTH_DETERMINATION_FAILED \n - RET_HOMOTOPY_STEP_FAILED \n - RET_HOTSTART_STOPPED_INFEASIBILITY \n - RET_HOTSTART_STOPPED_UNBOUNDEDNESS \n - RET_UNABLE_TO_READ_FILE \n - RET_INVALID_ARGUMENTS \n - RET_SETUP_AUXILIARYQP_FAILED */ -returnValue QProblemB_hotstartFW( QProblemB* _THIS, - const char* const g_file, /**< Name of file where gradient, of neighbouring QP to be solved, is stored. */ - const char* const lb_file, /**< Name of file where lower bounds, of neighbouring QP to be solved, is stored. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const char* const ub_file, /**< Name of file where upper bounds, of neighbouring QP to be solved, is stored. \n - If no upper bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations; \n - Output: Number of performed working set recalculations. */ - real_t* const cputime, /**< Input: Maximum CPU time allowed for QP solution. \n - Output: CPU time spent for QP solution (or to perform nWSR iterations). */ - Bounds* const guessedBounds /**< Optimal working set of bounds for solution (xOpt,yOpt). \n - (If a null pointer is passed, the previous working set is kept!) */ - ); - - -/** Writes a vector with the state of the working set - * \return SUCCESSFUL_RETURN \n - * RET_INVALID_ARGUMENTS */ -returnValue QProblemB_getWorkingSet( QProblemB* _THIS, - real_t* workingSet /** Output: array containing state of the working set. */ - ); - -/** Writes a vector with the state of the working set of bounds - * \return SUCCESSFUL_RETURN \n - * RET_INVALID_ARGUMENTS */ -returnValue QProblemB_getWorkingSetBounds( QProblemB* _THIS, - real_t* workingSetB /** Output: array containing state of the working set of bounds. */ - ); - -/** Writes a vector with the state of the working set of constraints - * \return SUCCESSFUL_RETURN \n - * RET_INVALID_ARGUMENTS */ -returnValue QProblemB_getWorkingSetConstraints( QProblemB* _THIS, - real_t* workingSetC /** Output: array containing state of the working set of constraints. */ - ); - - -/** Returns current bounds object of the QP (deep copy). - * \return SUCCESSFUL_RETURN \n - RET_QPOBJECT_NOT_SETUP */ -static inline returnValue QProblemB_getBounds( QProblemB* _THIS, - Bounds* _bounds /** Output: Bounds object. */ - ); - - -/** Returns the number of variables. - * \return Number of variables. */ -static inline int QProblemB_getNV( QProblemB* _THIS ); - -/** Returns the number of free variables. - * \return Number of free variables. */ -static inline int QProblemB_getNFR( QProblemB* _THIS ); - -/** Returns the number of fixed variables. - * \return Number of fixed variables. */ -static inline int QProblemB_getNFX( QProblemB* _THIS ); - -/** Returns the number of implicitly fixed variables. - * \return Number of implicitly fixed variables. */ -static inline int QProblemB_getNFV( QProblemB* _THIS ); - -/** Returns the dimension of null space. - * \return Dimension of null space. */ -int QProblemB_getNZ( QProblemB* _THIS ); - - -/** Returns the optimal objective function value. - * \return finite value: Optimal objective function value (QP was solved) \n - +infinity: QP was not yet solved */ -real_t QProblemB_getObjVal( QProblemB* _THIS ); - -/** Returns the objective function value at an arbitrary point x. - * \return Objective function value at point x */ -real_t QProblemB_getObjValX( QProblemB* _THIS, - const real_t* const _x /**< Point at which the objective function shall be evaluated. */ - ); - -/** Returns the primal solution vector. - * \return SUCCESSFUL_RETURN \n - RET_QP_NOT_SOLVED */ -returnValue QProblemB_getPrimalSolution( QProblemB* _THIS, - real_t* const xOpt /**< Output: Primal solution vector (if QP has been solved). */ - ); - -/** Returns the dual solution vector. - * \return SUCCESSFUL_RETURN \n - RET_QP_NOT_SOLVED */ -returnValue QProblemB_getDualSolution( QProblemB* _THIS, - real_t* const yOpt /**< Output: Dual solution vector (if QP has been solved). */ - ); - - -/** Returns status of the solution process. - * \return Status of solution process. */ -static inline QProblemStatus QProblemB_getStatus( QProblemB* _THIS ); - - -/** Returns if the QProblem object is initialised. - * \return BT_TRUE: QProblemB initialised \n - BT_FALSE: QProblemB not initialised */ -static inline BooleanType QProblemB_isInitialised( QProblemB* _THIS ); - -/** Returns if the QP has been solved. - * \return BT_TRUE: QProblemB solved \n - BT_FALSE: QProblemB not solved */ -static inline BooleanType QProblemB_isSolved( QProblemB* _THIS ); - -/** Returns if the QP is infeasible. - * \return BT_TRUE: QP infeasible \n - BT_FALSE: QP feasible (or not known to be infeasible!) */ -static inline BooleanType QProblemB_isInfeasible( QProblemB* _THIS ); - -/** Returns if the QP is unbounded. - * \return BT_TRUE: QP unbounded \n - BT_FALSE: QP unbounded (or not known to be unbounded!) */ -static inline BooleanType QProblemB_isUnbounded( QProblemB* _THIS ); - - -/** Returns Hessian type flag (type is not determined due to _THIS call!). - * \return Hessian type. */ -static inline HessianType QProblemB_getHessianType( QProblemB* _THIS ); - -/** Changes the print level. - * \return SUCCESSFUL_RETURN */ -static inline returnValue QProblemB_setHessianType( QProblemB* _THIS, - HessianType _hessianType /**< New Hessian type. */ - ); - -/** Returns if the QP has been internally regularised. - * \return BT_TRUE: Hessian is internally regularised for QP solution \n - BT_FALSE: No internal Hessian regularisation is used for QP solution */ -static inline BooleanType QProblemB_usingRegularisation( QProblemB* _THIS ); - -/** Returns current options struct. - * \return Current options struct. */ -static inline Options QProblemB_getOptions( QProblemB* _THIS ); - -/** Overrides current options with given ones. - * \return SUCCESSFUL_RETURN */ -static inline returnValue QProblemB_setOptions( QProblemB* _THIS, - Options _options /**< New options. */ - ); - -/** Returns the print level. - * \return Print level. */ -static inline PrintLevel QProblemB_getPrintLevel( QProblemB* _THIS ); - -/** Changes the print level. - * \return SUCCESSFUL_RETURN */ -returnValue QProblemB_setPrintLevel( QProblemB* _THIS, - PrintLevel _printlevel /**< New print level. */ - ); - -/** Returns the current number of QP problems solved. - * \return Number of QP problems solved. */ -static inline unsigned int QProblemB_getCount( QProblemB* _THIS ); - -/** Resets QP problem counter (to zero). - * \return SUCCESSFUL_RETURN. */ -static inline returnValue QProblemB_resetCounter( QProblemB* _THIS ); - - -/** Prints concise list of properties of the current QP. - * \return SUCCESSFUL_RETURN \n */ -returnValue QProblemB_printProperties( QProblemB* _THIS ); - -/** Prints a list of all options and their current values. - * \return SUCCESSFUL_RETURN \n */ -returnValue QProblemB_printOptions( QProblemB* _THIS ); - - -/** If Hessian type has been set by the user, nothing is done. - * Otherwise the Hessian type is set to HST_IDENTITY, HST_ZERO, or - * HST_POSDEF (default), respectively. - * \return SUCCESSFUL_RETURN \n - RET_HESSIAN_INDEFINITE */ -returnValue QProblemB_determineHessianType( QProblemB* _THIS ); - -/** Determines type of existing constraints and bounds (i.e. implicitly fixed, unbounded etc.). - * \return SUCCESSFUL_RETURN \n - RET_SETUPSUBJECTTOTYPE_FAILED */ -returnValue QProblemB_setupSubjectToType( QProblemB* _THIS ); - -/** Determines type of new constraints and bounds (i.e. implicitly fixed, unbounded etc.). - * \return SUCCESSFUL_RETURN \n - RET_SETUPSUBJECTTOTYPE_FAILED */ -returnValue QProblemB_setupSubjectToTypeNew( QProblemB* _THIS, - const real_t* const lb_new, /**< New lower bounds. */ - const real_t* const ub_new /**< New upper bounds. */ - ); - -/** Computes the Cholesky decomposition of the (simply projected) Hessian - * (i.e. R^T*R = Z^T*H*Z). It only works in the case where Z is a simple - * projection matrix! - * Note: If Hessian turns out not to be positive definite, the Hessian type - * is set to HST_SEMIDEF accordingly. - * \return SUCCESSFUL_RETURN \n - * RET_HESSIAN_NOT_SPD \n - * RET_INDEXLIST_CORRUPTED */ -returnValue QProblemB_computeCholesky( QProblemB* _THIS ); - -/** Computes initial Cholesky decomposition of the projected Hessian making - * use of the function setupCholeskyDecomposition() or setupCholeskyDecompositionProjected(). - * \return SUCCESSFUL_RETURN \n - * RET_HESSIAN_NOT_SPD \n - * RET_INDEXLIST_CORRUPTED */ -returnValue QProblemB_setupInitialCholesky( QProblemB* _THIS ); - - -/** Obtains the desired working set for the auxiliary initial QP in - * accordance with the user specifications - * \return SUCCESSFUL_RETURN \n - RET_OBTAINING_WORKINGSET_FAILED \n - RET_INVALID_ARGUMENTS */ -returnValue QProblemB_obtainAuxiliaryWorkingSet( QProblemB* _THIS, - const real_t* const xOpt, /**< Optimal primal solution vector. - * If a NULL pointer is passed, all entries are assumed to be zero. */ - const real_t* const yOpt, /**< Optimal dual solution vector. - * If a NULL pointer is passed, all entries are assumed to be zero. */ - Bounds* const guessedBounds, /**< Guessed working set for solution (xOpt,yOpt). */ - Bounds* auxiliaryBounds /**< Input: Allocated bound object. \n - * Ouput: Working set for auxiliary QP. */ - ); - -/** Decides if lower bounds are smaller than upper bounds - * - * \return SUCCESSFUL_RETURN \n - * RET_QP_INFEASIBLE */ -returnValue QProblemB_areBoundsConsistent( QProblemB* _THIS, - const real_t* const lb, /**< Vector of lower bounds*/ - const real_t* const ub /**< Vector of upper bounds*/ - ); - -/** Solves the system Ra = b or R^Ta = b where R is an upper triangular matrix. - * \return SUCCESSFUL_RETURN \n - RET_DIV_BY_ZERO */ -returnValue QProblemB_backsolveR( QProblemB* _THIS, - const real_t* const b, /**< Right hand side vector. */ - BooleanType transposed, /**< Indicates if the transposed system shall be solved. */ - real_t* const a /**< Output: Solution vector */ - ); - -/** Solves the system Ra = b or R^Ta = b where R is an upper triangular matrix. \n - * Special variant for the case that _THIS function is called from within "removeBound()". - * \return SUCCESSFUL_RETURN \n - RET_DIV_BY_ZERO */ -returnValue QProblemB_backsolveRrem( QProblemB* _THIS, - const real_t* const b, /**< Right hand side vector. */ - BooleanType transposed, /**< Indicates if the transposed system shall be solved. */ - BooleanType removingBound, /**< Indicates if function is called from "removeBound()". */ - real_t* const a /**< Output: Solution vector */ - ); - - -/** Determines step direction of the shift of the QP data. - * \return SUCCESSFUL_RETURN */ -returnValue QProblemB_determineDataShift( QProblemB* _THIS, - const real_t* const g_new, /**< New gradient vector. */ - const real_t* const lb_new, /**< New lower bounds. */ - const real_t* const ub_new, /**< New upper bounds. */ - real_t* const delta_g, /**< Output: Step direction of gradient vector. */ - real_t* const delta_lb, /**< Output: Step direction of lower bounds. */ - real_t* const delta_ub, /**< Output: Step direction of upper bounds. */ - BooleanType* Delta_bB_isZero/**< Output: Indicates if active bounds are to be shifted. */ - ); - - -/** Sets up internal QP data. - * \return SUCCESSFUL_RETURN \n - RET_INVALID_ARGUMENTS */ -returnValue QProblemB_setupQPdataM( QProblemB* _THIS, - DenseMatrix *_H, /**< Hessian matrix.*/ - const real_t* const _g, /**< Gradient vector. */ - const real_t* const _lb, /**< Lower bounds (on variables). \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* const _ub /**< Upper bounds (on variables). \n - If no upper bounds exist, a NULL pointer can be passed. */ - ); - -/** Sets up internal QP data. If the current Hessian is trivial - * (i.e. HST_ZERO or HST_IDENTITY) but a non-trivial one is given, - * memory for Hessian is allocated and it is set to the given one. - * \return SUCCESSFUL_RETURN \n - RET_INVALID_ARGUMENTS \n - RET_NO_HESSIAN_SPECIFIED */ -returnValue QProblemB_setupQPdata( QProblemB* _THIS, - real_t* const _H, /**< Hessian matrix. \n - If Hessian matrix is trivial,a NULL pointer can be passed. */ - const real_t* const _g, /**< Gradient vector. */ - const real_t* const _lb, /**< Lower bounds (on variables). \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* const _ub /**< Upper bounds (on variables). \n - If no upper bounds exist, a NULL pointer can be passed. */ - ); - -/** Sets up internal QP data by loading it from files. If the current Hessian - * is trivial (i.e. HST_ZERO or HST_IDENTITY) but a non-trivial one is given, - * memory for Hessian is allocated and it is set to the given one. - * \return SUCCESSFUL_RETURN \n - RET_UNABLE_TO_OPEN_FILE \n - RET_UNABLE_TO_READ_FILE \n - RET_INVALID_ARGUMENTS \n - RET_NO_HESSIAN_SPECIFIED */ -returnValue QProblemB_setupQPdataFromFile( QProblemB* _THIS, - const char* const H_file, /**< Name of file where Hessian matrix, of neighbouring QP to be solved, is stored. \n - If Hessian matrix is trivial,a NULL pointer can be passed. */ - const char* const g_file, /**< Name of file where gradient, of neighbouring QP to be solved, is stored. */ - const char* const lb_file, /**< Name of file where lower bounds, of neighbouring QP to be solved, is stored. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const char* const ub_file /**< Name of file where upper bounds, of neighbouring QP to be solved, is stored. \n - If no upper bounds exist, a NULL pointer can be passed. */ - ); - -/** Loads new QP vectors from files (internal members are not affected!). - * \return SUCCESSFUL_RETURN \n - RET_UNABLE_TO_OPEN_FILE \n - RET_UNABLE_TO_READ_FILE \n - RET_INVALID_ARGUMENTS */ -returnValue QProblemB_loadQPvectorsFromFile( QProblemB* _THIS, - const char* const g_file, /**< Name of file where gradient, of neighbouring QP to be solved, is stored. */ - const char* const lb_file, /**< Name of file where lower bounds, of neighbouring QP to be solved, is stored. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const char* const ub_file, /**< Name of file where upper bounds, of neighbouring QP to be solved, is stored. \n - If no upper bounds exist, a NULL pointer can be passed. */ - real_t* const g_new, /**< Output: Gradient of neighbouring QP to be solved. */ - real_t* const lb_new, /**< Output: Lower bounds of neighbouring QP to be solved */ - real_t* const ub_new /**< Output: Upper bounds of neighbouring QP to be solved */ - ); - - -/** Sets internal infeasibility flag and throws given error in case the far bound - * strategy is not enabled (as QP might actually not be infeasible in _THIS case). - * \return RET_HOTSTART_STOPPED_INFEASIBILITY \n - RET_ENSURELI_FAILED_CYCLING \n - RET_ENSURELI_FAILED_NOINDEX */ -returnValue QProblemB_setInfeasibilityFlag( QProblemB* _THIS, - returnValue returnvalue, /**< Returnvalue to be tunneled. */ - BooleanType doThrowError /**< Flag forcing to throw an error. */ - ); - - -/** Determines if next QP iteration can be performed within given CPU time limit. - * \return BT_TRUE: CPU time limit is exceeded, stop QP solution. \n - BT_FALSE: Sufficient CPU time for next QP iteration. */ -BooleanType QProblemB_isCPUtimeLimitExceeded( QProblemB* _THIS, - const real_t* const cputime, /**< Maximum CPU time allowed for QP solution. */ - real_t starttime, /**< Start time of current QP solution. */ - int nWSR /**< Number of working set recalculations performed so far. */ - ); - - -/** Regularise Hessian matrix by adding a scaled identity matrix to it. - * \return SUCCESSFUL_RETURN \n - RET_HESSIAN_ALREADY_REGULARISED */ -returnValue QProblemB_regulariseHessian( QProblemB* _THIS ); - - -/** Sets Hessian matrix of the QP. - * \return SUCCESSFUL_RETURN */ -static inline returnValue QProblemB_setHM( QProblemB* _THIS, - DenseMatrix* H_new /**< New Hessian matrix. */ - ); - -/** Sets dense Hessian matrix of the QP. - * If a null pointer is passed and - * a) hessianType is HST_IDENTITY, nothing is done, - * b) hessianType is not HST_IDENTITY, Hessian matrix is set to zero. - * \return SUCCESSFUL_RETURN */ -static inline returnValue QProblemB_setH( QProblemB* _THIS, - real_t* const H_new /**< New dense Hessian matrix (with correct dimension!). */ - ); - -/** Changes gradient vector of the QP. - * \return SUCCESSFUL_RETURN \n - * RET_INVALID_ARGUMENTS */ -static inline returnValue QProblemB_setG( QProblemB* _THIS, - const real_t* const g_new /**< New gradient vector (with correct dimension!). */ - ); - -/** Changes lower bound vector of the QP. - * \return SUCCESSFUL_RETURN \n - * RET_QPOBJECT_NOT_SETUP */ -static inline returnValue QProblemB_setLB( QProblemB* _THIS, - const real_t* const lb_new /**< New lower bound vector (with correct dimension!). */ - ); - -/** Changes single entry of lower bound vector of the QP. - * \return SUCCESSFUL_RETURN \n - * RET_QPOBJECT_NOT_SETUP \n - * RET_INDEX_OUT_OF_BOUNDS */ -static inline returnValue QProblemB_setLBn( QProblemB* _THIS, - int number, /**< Number of entry to be changed. */ - real_t value /**< New value for entry of lower bound vector. */ - ); - -/** Changes upper bound vector of the QP. - * \return SUCCESSFUL_RETURN \n - * RET_QPOBJECT_NOT_SETUP */ -static inline returnValue QProblemB_setUB( QProblemB* _THIS, - const real_t* const ub_new /**< New upper bound vector (with correct dimension!). */ - ); - -/** Changes single entry of upper bound vector of the QP. - * \return SUCCESSFUL_RETURN \n - * RET_QPOBJECT_NOT_SETUP \n - * RET_INDEX_OUT_OF_BOUNDS */ -static inline returnValue QProblemB_setUBn( QProblemB* _THIS, - int number, /**< Number of entry to be changed. */ - real_t value /**< New value for entry of upper bound vector. */ - ); - - -/** Computes parameters for the Givens matrix G for which [x,y]*G = [z,0] - * \return SUCCESSFUL_RETURN */ -static inline void QProblemB_computeGivens( real_t xold, /**< Matrix entry to be normalised. */ - real_t yold, /**< Matrix entry to be annihilated. */ - real_t* xnew, /**< Output: Normalised matrix entry. */ - real_t* ynew, /**< Output: Annihilated matrix entry. */ - real_t* c, /**< Output: Cosine entry of Givens matrix. */ - real_t* s /**< Output: Sine entry of Givens matrix. */ - ); - -/** Applies Givens matrix determined by c and s (cf. computeGivens). - * \return SUCCESSFUL_RETURN */ -static inline void QProblemB_applyGivens( real_t c, /**< Cosine entry of Givens matrix. */ - real_t s, /**< Sine entry of Givens matrix. */ - real_t nu, /**< Further factor: s/(1+c). */ - real_t xold, /**< Matrix entry to be transformed corresponding to - * the normalised entry of the original matrix. */ - real_t yold, /**< Matrix entry to be transformed corresponding to - * the annihilated entry of the original matrix. */ - real_t* xnew, /**< Output: Transformed matrix entry corresponding to - * the normalised entry of the original matrix. */ - real_t* ynew /**< Output: Transformed matrix entry corresponding to - * the annihilated entry of the original matrix. */ - ); - - - -/** Compute relative length of homotopy in data space for termination - * criterion. - * \return Relative length in data space. */ -real_t QProblemB_getRelativeHomotopyLength( QProblemB* _THIS, - const real_t* const g_new, /**< Final gradient. */ - const real_t* const lb_new, /**< Final lower variable bounds. */ - const real_t* const ub_new /**< Final upper variable bounds. */ - ); - -/** Ramping Strategy to avoid ties. Modifies homotopy start without - * changing current active set. - * \return SUCCESSFUL_RETURN */ -returnValue QProblemB_performRamping( QProblemB* _THIS ); - - -/** ... */ -returnValue QProblemB_updateFarBounds( QProblemB* _THIS, - real_t curFarBound, /**< ... */ - int nRamp, /**< ... */ - const real_t* const lb_new, /**< ... */ - real_t* const lb_new_far, /**< ... */ - const real_t* const ub_new, /**< ... */ - real_t* const ub_new_far /**< ... */ - ); - - - -/** Performs robustified ratio test yield the maximum possible step length - * along the homotopy path. - * \return SUCCESSFUL_RETURN */ -returnValue QProblemB_performRatioTestB( QProblemB* _THIS, - int nIdx, /**< Number of ratios to be checked. */ - const int* const idxList, /**< Array containing the indices of all ratios to be checked. */ - Bounds* const subjectTo, /**< Bound object corresponding to ratios to be checked. */ - const real_t* const num, /**< Array containing all numerators for performing the ratio test. */ - const real_t* const den, /**< Array containing all denominators for performing the ratio test. */ - real_t epsNum, /**< Numerator tolerance. */ - real_t epsDen, /**< Denominator tolerance. */ - real_t* t, /**< Output: Maximum possible step length along the homotopy path. */ - int* BC_idx /**< Output: Index of blocking constraint. */ - ); - -/** Checks whether given ratio is blocking, i.e. limits the maximum step length - * along the homotopy path to a value lower than given one. - * \return SUCCESSFUL_RETURN */ -static inline BooleanType QProblemB_isBlocking( QProblemB* _THIS, - real_t num, /**< Numerator for performing the ratio test. */ - real_t den, /**< Denominator for performing the ratio test. */ - real_t epsNum, /**< Numerator tolerance. */ - real_t epsDen, /**< Denominator tolerance. */ - real_t* t /**< Input: Current maximum step length along the homotopy path, - * Output: Updated maximum possible step length along the homotopy path. */ - ); - - -/** Solves a QProblemB whose QP data is assumed to be stored in the member variables. - * A guess for its primal/dual optimal solution vectors and the corresponding - * optimal working set can be provided. - * Note: This function is internally called by all init functions! - * \return SUCCESSFUL_RETURN \n - RET_INIT_FAILED \n - RET_INIT_FAILED_CHOLESKY \n - RET_INIT_FAILED_HOTSTART \n - RET_INIT_FAILED_INFEASIBILITY \n - RET_INIT_FAILED_UNBOUNDEDNESS \n - RET_MAX_NWSR_REACHED */ -returnValue QProblemB_solveInitialQP( QProblemB* _THIS, - const real_t* const xOpt, /**< Optimal primal solution vector.*/ - const real_t* const yOpt, /**< Optimal dual solution vector. */ - Bounds* const guessedBounds, /**< Optimal working set of bounds for solution (xOpt,yOpt). */ - const real_t* const _R, /**< Pre-computed (upper triangular) Cholesky factor of Hessian matrix. */ - int* nWSR, /**< Input: Maximum number of working set recalculations; \n - * Output: Number of performed working set recalculations. */ - real_t* const cputime /**< Input: Maximum CPU time allowed for QP solution. \n - * Output: CPU time spent for QP solution (or to perform nWSR iterations). */ - ); - -/** Solves an initialised QProblemB using online active set strategy. - * Note: This function is internally called by all hotstart functions! - * \return SUCCESSFUL_RETURN \n - RET_MAX_NWSR_REACHED \n - RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED \n - RET_HOTSTART_FAILED \n - RET_SHIFT_DETERMINATION_FAILED \n - RET_STEPDIRECTION_DETERMINATION_FAILED \n - RET_STEPLENGTH_DETERMINATION_FAILED \n - RET_HOMOTOPY_STEP_FAILED \n - RET_HOTSTART_STOPPED_INFEASIBILITY \n - RET_HOTSTART_STOPPED_UNBOUNDEDNESS */ -returnValue QProblemB_solveQP( QProblemB* _THIS, - const real_t* const g_new, /**< Gradient of neighbouring QP to be solved. */ - const real_t* const lb_new, /**< Lower bounds of neighbouring QP to be solved. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* const ub_new, /**< Upper bounds of neighbouring QP to be solved. \n - If no upper bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations; \n - Output: Number of performed working set recalculations. */ - real_t* const cputime, /**< Input: Maximum CPU time allowed for QP solution. \n - Output: CPU time spent for QP solution (or to perform nWSR iterations). */ - int nWSRperformed, /**< Number of working set recalculations already performed to solve - this QP within previous solveQP() calls. This number is - always zero, except for successive calls from solveRegularisedQP() - or when using the far bound strategy. */ - BooleanType isFirstCall /**< Indicating whether this is the first call for current QP. */ - ); - - -/** Solves an initialised QProblemB using online active set strategy. - * Note: This function is internally called by all hotstart functions! - * \return SUCCESSFUL_RETURN \n - RET_MAX_NWSR_REACHED \n - RET_HOTSTART_FAILED_AS_QP_NOT_INITIALISED \n - RET_HOTSTART_FAILED \n - RET_SHIFT_DETERMINATION_FAILED \n - RET_STEPDIRECTION_DETERMINATION_FAILED \n - RET_STEPLENGTH_DETERMINATION_FAILED \n - RET_HOMOTOPY_STEP_FAILED \n - RET_HOTSTART_STOPPED_INFEASIBILITY \n - RET_HOTSTART_STOPPED_UNBOUNDEDNESS */ -returnValue QProblemB_solveRegularisedQP( QProblemB* _THIS, - const real_t* const g_new, /**< Gradient of neighbouring QP to be solved. */ - const real_t* const lb_new, /**< Lower bounds of neighbouring QP to be solved. \n - If no lower bounds exist, a NULL pointer can be passed. */ - const real_t* const ub_new, /**< Upper bounds of neighbouring QP to be solved. \n - If no upper bounds exist, a NULL pointer can be passed. */ - int* nWSR, /**< Input: Maximum number of working set recalculations; \n - Output: Number of performed working set recalculations. */ - real_t* const cputime, /**< Input: Maximum CPU time allowed for QP solution. \n - Output: CPU time spent for QP solution (or to perform nWSR iterations). */ - int nWSRperformed, /**< Number of working set recalculations already performed to solve - this QP within previous solveRegularisedQP() calls. This number is - always zero, except for successive calls when using the far bound strategy. */ - BooleanType isFirstCall /**< Indicating whether this is the first call for current QP. */ - ); - - -/** Sets up bound data structure according to auxiliaryBounds. - * (If the working set shall be setup afresh, make sure that - * bounds data structure has been resetted!) - * \return SUCCESSFUL_RETURN \n - RET_SETUP_WORKINGSET_FAILED \n - RET_INVALID_ARGUMENTS \n - RET_UNKNOWN_BUG */ -returnValue QProblemB_setupAuxiliaryWorkingSet( QProblemB* _THIS, - Bounds* const auxiliaryBounds, /**< Working set for auxiliary QP. */ - BooleanType setupAfresh /**< Flag indicating if given working set shall be - * setup afresh or by updating the current one. */ - ); - -/** Sets up the optimal primal/dual solution of the auxiliary initial QP. - * \return SUCCESSFUL_RETURN */ -returnValue QProblemB_setupAuxiliaryQPsolution( QProblemB* _THIS, - const real_t* const xOpt, /**< Optimal primal solution vector. - * If a NULL pointer is passed, all entries are set to zero. */ - const real_t* const yOpt /**< Optimal dual solution vector. - * If a NULL pointer is passed, all entries are set to zero. */ - ); - -/** Sets up gradient of the auxiliary initial QP for given - * optimal primal/dual solution and given initial working set - * (assumes that members X, Y and BOUNDS have already been (ialised!). - * \return SUCCESSFUL_RETURN */ -returnValue QProblemB_setupAuxiliaryQPgradient( QProblemB* _THIS ); - -/** Sets up bounds of the auxiliary initial QP for given - * optimal primal/dual solution and given initial working set - * (assumes that members X, Y and BOUNDS have already been initialised!). - * \return SUCCESSFUL_RETURN \n - RET_UNKNOWN_BUG */ -returnValue QProblemB_setupAuxiliaryQPbounds( QProblemB* _THIS, - BooleanType useRelaxation /**< Flag indicating if inactive bounds shall be relaxed. */ - ); - - -/** Updates QP vectors, working sets and internal data structures in order to - start from an optimal solution corresponding to initial guesses of the working - set for bounds - * \return SUCCESSFUL_RETURN \n - * RET_SETUP_AUXILIARYQP_FAILED */ -returnValue QProblemB_setupAuxiliaryQP( QProblemB* _THIS, - Bounds* const guessedBounds /**< Initial guess for working set of bounds. */ - ); - -/** Determines step direction of the homotopy path. - * \return SUCCESSFUL_RETURN \n - RET_STEPDIRECTION_FAILED_CHOLESKY */ -returnValue QProblemB_determineStepDirection( QProblemB* _THIS, - const real_t* const delta_g, /**< Step direction of gradient vector. */ - const real_t* const delta_lb, /**< Step direction of lower bounds. */ - const real_t* const delta_ub, /**< Step direction of upper bounds. */ - BooleanType Delta_bB_isZero, /**< Indicates if active bounds are to be shifted. */ - real_t* const delta_xFX, /**< Output: Primal homotopy step direction of fixed variables. */ - real_t* const delta_xFR, /**< Output: Primal homotopy step direction of free variables. */ - real_t* const delta_yFX /**< Output: Dual homotopy step direction of fixed variables' multiplier. */ - ); - -/** Determines the maximum possible step length along the homotopy path - * and performs _THIS step (without changing working set). - * \return SUCCESSFUL_RETURN \n - * RET_QP_INFEASIBLE \n - */ -returnValue QProblemB_performStep( QProblemB* _THIS, - const real_t* const delta_g, /**< Step direction of gradient. */ - const real_t* const delta_lb, /**< Step direction of lower bounds. */ - const real_t* const delta_ub, /**< Step direction of upper bounds. */ - const real_t* const delta_xFX, /**< Primal homotopy step direction of fixed variables. */ - const real_t* const delta_xFR, /**< Primal homotopy step direction of free variables. */ - const real_t* const delta_yFX, /**< Dual homotopy step direction of fixed variables' multiplier. */ - int* BC_idx, /**< Output: Index of blocking constraint. */ - SubjectToStatus* BC_status /**< Output: Status of blocking constraint. */ - ); - -/** Updates active set. - * \return SUCCESSFUL_RETURN \n - RET_REMOVE_FROM_ACTIVESET_FAILED \n - RET_ADD_TO_ACTIVESET_FAILED */ -returnValue QProblemB_changeActiveSet( QProblemB* _THIS, - int BC_idx, /**< Index of blocking constraint. */ - SubjectToStatus BC_status /**< Status of blocking constraint. */ - ); - -/** Drift correction at end of each active set iteration - * \return SUCCESSFUL_RETURN */ -returnValue QProblemB_performDriftCorrection( QProblemB* _THIS ); - -/** Determines if it is more efficient to refactorise the matrices when - * hotstarting or not (i.e. better to update the existing factorisations). - * \return BT_TRUE iff matrices shall be refactorised afresh - */ -BooleanType QProblemB_shallRefactorise( QProblemB* _THIS, - Bounds* const guessedBounds /**< Guessed new working set. */ - ); - - -/** Adds a bound to active set (specialised version for the case where no constraints exist). - * \return SUCCESSFUL_RETURN \n - RET_ADDBOUND_FAILED */ -returnValue QProblemB_addBound( QProblemB* _THIS, - int number, /**< Number of bound to be added to active set. */ - SubjectToStatus B_status, /**< Status of new active bound. */ - BooleanType updateCholesky /**< Flag indicating if Cholesky decomposition shall be updated. */ - ); - -/** Removes a bounds from active set (specialised version for the case where no constraints exist). - * \return SUCCESSFUL_RETURN \n - RET_HESSIAN_NOT_SPD \n - RET_REMOVEBOUND_FAILED */ -returnValue QProblemB_removeBound( QProblemB* _THIS, - int number, /**< Number of bound to be removed from active set. */ - BooleanType updateCholesky /**< Flag indicating if Cholesky decomposition shall be updated. */ - ); - - -/** Prints concise information on the current iteration. - * \return SUCCESSFUL_RETURN \n */ -returnValue QProblemB_printIteration( QProblemB* _THIS, - int iter, /**< Number of current iteration. */ - int BC_idx, /**< Index of blocking bound. */ - SubjectToStatus BC_status, /**< Status of blocking bound. */ - real_t homotopyLength, /**< Current homotopy distance. */ - BooleanType isFirstCall /**< Indicating whether this is the first call for current QP. */ - ); - - - -/* - * g e t B o u n d s - */ -static inline returnValue QProblemB_getBounds( QProblemB* _THIS, Bounds* _bounds ) -{ - int nV = QProblemB_getNV( _THIS ); - - if ( nV == 0 ) - return THROWERROR( RET_QPOBJECT_NOT_SETUP ); - - _bounds = _THIS->bounds; - - return SUCCESSFUL_RETURN; -} - - -/* - * g e t N V - */ -static inline int QProblemB_getNV( QProblemB* _THIS ) -{ - return Bounds_getNV( _THIS->bounds ); -} - - -/* - * g e t N F R - */ -static inline int QProblemB_getNFR( QProblemB* _THIS ) -{ - return Bounds_getNFR( _THIS->bounds ); -} - - -/* - * g e t N F X - */ -static inline int QProblemB_getNFX( QProblemB* _THIS ) -{ - return Bounds_getNFX( _THIS->bounds ); -} - - -/* - * g e t N F V - */ -static inline int QProblemB_getNFV( QProblemB* _THIS ) -{ - return Bounds_getNFV( _THIS->bounds ); -} - - -/* - * g e t S t a t u s - */ -static inline QProblemStatus QProblemB_getStatus( QProblemB* _THIS ) -{ - return _THIS->status; -} - - -/* - * i s I n i t i a l i s e d - */ -static inline BooleanType QProblemB_isInitialised( QProblemB* _THIS ) -{ - if ( _THIS->status == QPS_NOTINITIALISED ) - return BT_FALSE; - else - return BT_TRUE; -} - - -/* - * i s S o l v e d - */ -static inline BooleanType QProblemB_isSolved( QProblemB* _THIS ) -{ - if ( _THIS->status == QPS_SOLVED ) - return BT_TRUE; - else - return BT_FALSE; -} - - -/* - * i s I n f e a s i b l e - */ -static inline BooleanType QProblemB_isInfeasible( QProblemB* _THIS ) -{ - return _THIS->infeasible; -} - - -/* - * i s U n b o u n d e d - */ -static inline BooleanType QProblemB_isUnbounded( QProblemB* _THIS ) -{ - return _THIS->unbounded; -} - - -/* - * g e t H e s s i a n T y p e - */ -static inline HessianType QProblemB_getHessianType( QProblemB* _THIS ) -{ - return _THIS->hessianType; -} - - -/* - * s e t H e s s i a n T y p e - */ -static inline returnValue QProblemB_setHessianType( QProblemB* _THIS, HessianType _hessianType ) -{ - _THIS->hessianType = _hessianType; - return SUCCESSFUL_RETURN; -} - - -/* - * u s i n g R e g u l a r i s a t i o n - */ -static inline BooleanType QProblemB_usingRegularisation( QProblemB* _THIS ) -{ - if ( _THIS->regVal > QPOASES_ZERO ) - return BT_TRUE; - else - return BT_FALSE; -} - - -/* - * g e t O p t i o n s - */ -static inline Options QProblemB_getOptions( QProblemB* _THIS ) -{ - return _THIS->options; -} - - -/* - * s e t O p t i o n s - */ -static inline returnValue QProblemB_setOptions( QProblemB* _THIS, - Options _options - ) -{ - OptionsCPY( &_options,&(_THIS->options) ); - Options_ensureConsistency( &(_THIS->options) ); - - QProblemB_setPrintLevel( _THIS,_THIS->options.printLevel ); - - return SUCCESSFUL_RETURN; -} - - -/* - * g e t P r i n t L e v e l - */ -static inline PrintLevel QProblemB_getPrintLevel( QProblemB* _THIS ) -{ - return _THIS->options.printLevel; -} - - - -/* - * g e t C o u n t - */ -static inline unsigned int QProblemB_getCount( QProblemB* _THIS ) -{ - return _THIS->count; -} - - -/* - * r e s e t C o u n t e r - */ -static inline returnValue QProblemB_resetCounter( QProblemB* _THIS ) -{ - _THIS->count = 0; - return SUCCESSFUL_RETURN; -} - - - -/***************************************************************************** - * P R O T E C T E D * - *****************************************************************************/ - - -/* - * s e t H - */ -static inline returnValue QProblemB_setHM( QProblemB* _THIS, DenseMatrix* H_new ) -{ - if ( H_new == 0 ) - return QProblemB_setH( _THIS,(real_t*)0 ); - else - return QProblemB_setH( _THIS,DenseMatrix_getVal(H_new) ); -} - - -/* - * s e t H - */ -static inline returnValue QProblemB_setH( QProblemB* _THIS, real_t* const H_new ) -{ - /* if null pointer is passed, Hessian is set to zero matrix - * (or stays identity matrix) */ - if ( H_new == 0 ) - { - if ( _THIS->hessianType == HST_IDENTITY ) - return SUCCESSFUL_RETURN; - - _THIS->hessianType = HST_ZERO; - - _THIS->H = 0; - } - else - { - DenseMatrixCON( _THIS->H,QProblemB_getNV( _THIS ),QProblemB_getNV( _THIS ),QProblemB_getNV( _THIS ),H_new ); - } - - return SUCCESSFUL_RETURN; -} - - -/* - * s e t G - */ -static inline returnValue QProblemB_setG( QProblemB* _THIS, const real_t* const g_new ) -{ - unsigned int nV = (unsigned int)QProblemB_getNV( _THIS ); - - if ( nV == 0 ) - return THROWERROR( RET_QPOBJECT_NOT_SETUP ); - - if ( g_new == 0 ) - return THROWERROR( RET_INVALID_ARGUMENTS ); - - memcpy( _THIS->g,g_new,nV*sizeof(real_t) ); - - return SUCCESSFUL_RETURN; -} - - -/* - * s e t L B - */ -static inline returnValue QProblemB_setLB( QProblemB* _THIS, const real_t* const lb_new ) -{ - unsigned int i; - unsigned int nV = (unsigned int)QProblemB_getNV( _THIS ); - - if ( nV == 0 ) - return THROWERROR( RET_QPOBJECT_NOT_SETUP ); - - if ( lb_new != 0 ) - { - memcpy( _THIS->lb,lb_new,nV*sizeof(real_t) ); - } - else - { - /* if no lower bounds are specified, set them to -infinity */ - for( i=0; ilb[i] = -QPOASES_INFTY; - } - - return SUCCESSFUL_RETURN; -} - - -/* - * s e t L B - */ -static inline returnValue QProblemB_setLBn( QProblemB* _THIS, int number, real_t value ) -{ - int nV = QProblemB_getNV( _THIS ); - - if ( nV == 0 ) - return THROWERROR( RET_QPOBJECT_NOT_SETUP ); - - if ( ( number >= 0 ) && ( number < nV ) ) - { - _THIS->lb[number] = value; - return SUCCESSFUL_RETURN; - } - else - { - return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); - } -} - - -/* - * s e t U B - */ -static inline returnValue QProblemB_setUB( QProblemB* _THIS, const real_t* const ub_new ) -{ - unsigned int i; - unsigned int nV = (unsigned int)QProblemB_getNV( _THIS ); - - if ( nV == 0 ) - return THROWERROR( RET_QPOBJECT_NOT_SETUP ); - - if ( ub_new != 0 ) - { - memcpy( _THIS->ub,ub_new,nV*sizeof(real_t) ); - } - else - { - /* if no upper bounds are specified, set them to infinity */ - for( i=0; iub[i] = QPOASES_INFTY; - } - - return SUCCESSFUL_RETURN; -} - - -/* - * s e t U B - */ -static inline returnValue QProblemB_setUBn( QProblemB* _THIS, int number, real_t value ) -{ - int nV = QProblemB_getNV( _THIS ); - - if ( nV == 0 ) - return THROWERROR( RET_QPOBJECT_NOT_SETUP ); - - if ( ( number >= 0 ) && ( number < nV ) ) - { - _THIS->ub[number] = value; - - return SUCCESSFUL_RETURN; - } - else - { - return THROWERROR( RET_INDEX_OUT_OF_BOUNDS ); - } -} - - -/* - * c o m p u t e G i v e n s - */ -static inline void QProblemB_computeGivens( real_t xold, real_t yold, - real_t* xnew, real_t* ynew, real_t* c, real_t* s - ) -{ - real_t t, mu; - - if ( fabs( yold ) <= QPOASES_ZERO ) - { - *c = 1.0; - *s = 0.0; - - *xnew = xold; - *ynew = yold; - } - else - { - mu = fabs( xold ); - if ( fabs( yold ) > mu ) - mu = fabs( yold ); - - t = mu * sqrt( (xold/mu)*(xold/mu) + (yold/mu)*(yold/mu) ); - - if ( xold < 0.0 ) - t = -t; - - *c = xold/t; - *s = yold/t; - *xnew = t; - *ynew = 0.0; - } - - return; -} - - -/* - * a p p l y G i v e n s - */ -static inline void QProblemB_applyGivens( real_t c, real_t s, real_t nu, real_t xold, real_t yold, - real_t* xnew, real_t* ynew - ) -{ - #ifdef __USE_THREE_MULTS_GIVENS__ - - /* Givens plane rotation requiring only three multiplications, - * cf. Hammarling, S.: A note on modifications to the givens plane rotation. - * J. Inst. Maths Applics, 13:215-218, 1974. */ - *xnew = xold*c + yold*s; - *ynew = (*xnew+xold)*nu - yold; - - #else - - /* Usual Givens plane rotation requiring four multiplications. */ - *xnew = c*xold + s*yold; - *ynew = -s*xold + c*yold; - - #endif - - return; -} - - -/* - * i s B l o c k i n g - */ -static inline BooleanType QProblemB_isBlocking( QProblemB* _THIS, - real_t num, - real_t den, - real_t epsNum, - real_t epsDen, - real_t* t - ) -{ - if ( ( den >= epsDen ) && ( num >= epsNum ) ) - { - if ( num < (*t)*den ) - return BT_TRUE; - } - - return BT_FALSE; -} - - -END_NAMESPACE_QPOASES - - -#endif /* QPOASES_QPROBLEMB_H */ - - -/* - * end of file - */ diff --git a/third_party/acados/include/qpOASES_e/Types.h b/third_party/acados/include/qpOASES_e/Types.h deleted file mode 100644 index fc042ae..0000000 --- a/third_party/acados/include/qpOASES_e/Types.h +++ /dev/null @@ -1,310 +0,0 @@ -/* - * This file is part of qpOASES. - * - * qpOASES -- An Implementation of the Online Active Set Strategy. - * Copyright (C) 2007-2015 by Hans Joachim Ferreau, Andreas Potschka, - * Christian Kirches et al. All rights reserved. - * - * qpOASES is free software; you can redistribute it and/or - * modify it under the terms of the GNU Lesser General Public - * License as published by the Free Software Foundation; either - * version 2.1 of the License, or (at your option) any later version. - * - * qpOASES is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public - * License along with qpOASES; if not, write to the Free Software - * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - * - */ - - -/** - * \file include/qpOASES_e/Types.h - * \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches - * \version 3.1embedded - * \date 2007-2015 - * - * Declaration of all non-built-in types (except for classes). - */ - - -#ifndef QPOASES_TYPES_H -#define QPOASES_TYPES_H - -#ifdef USE_ACADOS_TYPES -#include "acados/utils/types.h" -#endif - -/* If your compiler does not support the snprintf() function, - * uncomment the following line and try to compile again. */ -/* #define __NO_SNPRINTF__ */ - - -/* Uncomment the following line for setting the __DSPACE__ flag. */ -/* #define __DSPACE__ */ - -/* Uncomment the following line for setting the __XPCTARGET__ flag. */ -/* #define __XPCTARGET__ */ - - -/* Uncomment the following line for setting the __NO_FMATH__ flag. */ -/* #define __NO_FMATH__ */ - -/* Uncomment the following line to enable debug information. */ -/* #define __DEBUG__ */ - -/* Uncomment the following line to enable suppress any kind of console output. */ -/* #define __SUPPRESSANYOUTPUT__ */ - - -/** Forces to always include all implicitly fixed bounds and all equality constraints - * into the initial working set when setting up an auxiliary QP. */ -#define __ALWAYS_INITIALISE_WITH_ALL_EQUALITIES__ - -/* Uncomment the following line to activate the use of an alternative Givens - * plane rotation requiring only three multiplications. */ -/* #define __USE_THREE_MULTS_GIVENS__ */ - -/* Uncomment the following line to activate the use of single precision arithmetic. */ -/* #define __USE_SINGLE_PRECISION__ */ - -/* The inline keyword is skipped by default as it is not part of the C90 standard. - * However, by uncommenting the following line, use of the inline keyword can be enforced. */ -/* #define __USE_INLINE__ */ - - -/* Work-around for Borland BCC 5.5 compiler. */ -#ifdef __BORLANDC__ -#if __BORLANDC__ < 0x0561 - #define __STDC__ 1 -#endif -#endif - - -/* Work-around for Microsoft compilers. */ -#ifdef _MSC_VER - #define __NO_SNPRINTF__ - #pragma warning( disable : 4061 4100 4250 4514 4996 ) -#endif - - -/* Apply pre-processor settings when using qpOASES within auto-generated code. */ -#ifdef __CODE_GENERATION__ - #define __NO_COPYRIGHT__ - #define __EXTERNAL_DIMENSIONS__ -#endif /* __CODE_GENERATION__ */ - - -/* Avoid using static variables declaration within functions. */ -#ifdef __NO_STATIC__ - #define myStatic -#else - #define myStatic static -#endif /* __NO_STATIC__ */ - - -/* Skip inline keyword if not specified otherwise. */ -#ifndef __USE_INLINE__ - #define inline -#endif - - -/* Avoid any printing on embedded platforms. */ -#if defined(__DSPACE__) || defined(__XPCTARGET__) - #define __SUPPRESSANYOUTPUT__ - #define __NO_SNPRINTF__ -#endif - - -#ifdef __NO_SNPRINTF__ - #if (!defined(_MSC_VER)) || defined(__DSPACE__) || defined(__XPCTARGET__) - /* If snprintf is not available, provide an empty implementation... */ - int snprintf( char* s, size_t n, const char* format, ... ); - #else - /* ... or substitute snprintf by _snprintf for Microsoft compilers. */ - #define snprintf _snprintf - #endif -#endif /* __NO_SNPRINTF__ */ - - -/** Macro for switching on/off the beginning of the qpOASES namespace definition. */ -#define BEGIN_NAMESPACE_QPOASES - -/** Macro for switching on/off the end of the qpOASES namespace definition. */ -#define END_NAMESPACE_QPOASES - -/** Macro for switching on/off the use of the qpOASES namespace. */ -#define USING_NAMESPACE_QPOASES - -/** Macro for switching on/off references to the qpOASES namespace. */ -#define REFER_NAMESPACE_QPOASES /*::*/ - - -/** Macro for accessing the Cholesky factor R. */ -#define RR( I,J ) _THIS->R[(I)+nV*(J)] - -/** Macro for accessing the orthonormal matrix Q of the QT factorisation. */ -#define QQ( I,J ) _THIS->Q[(I)+nV*(J)] - -/** Macro for accessing the triangular matrix T of the QT factorisation. */ -#define TT( I,J ) _THIS->T[(I)*nVC_min+(J)] - - - -BEGIN_NAMESPACE_QPOASES - - -/** Defines real_t for facilitating switching between double and float. */ - -#ifndef USE_ACADOS_TYPES -#ifndef __CODE_GENERATION__ - - #ifdef __USE_SINGLE_PRECISION__ - typedef float real_t; - #else - typedef double real_t; - #endif /* __USE_SINGLE_PRECISION__ */ - -#endif /* __CODE_GENERATION__ */ -#endif /* USE_ACADOS_TYPES */ - -/** Summarises all possible logical values. */ -typedef enum -{ - BT_FALSE = 0, /**< Logical value for "false". */ - BT_TRUE /**< Logical value for "true". */ -} BooleanType; - - -/** Summarises all possible print levels. Print levels are used to describe - * the desired amount of output during runtime of qpOASES. */ -typedef enum -{ - PL_DEBUG_ITER = -2, /**< Full tabular debugging output. */ - PL_TABULAR, /**< Tabular output. */ - PL_NONE, /**< No output. */ - PL_LOW, /**< Print error messages only. */ - PL_MEDIUM, /**< Print error and warning messages as well as concise info messages. */ - PL_HIGH /**< Print all messages with full details. */ -} PrintLevel; - - -/** Defines visibility status of a message. */ -typedef enum -{ - VS_HIDDEN, /**< Message not visible. */ - VS_VISIBLE /**< Message visible. */ -} VisibilityStatus; - - -/** Summarises all possible states of the (S)QProblem(B) object during the -solution process of a QP sequence. */ -typedef enum -{ - QPS_NOTINITIALISED, /**< QProblem object is freshly instantiated or reset. */ - QPS_PREPARINGAUXILIARYQP, /**< An auxiliary problem is currently setup, either at the very beginning - * via an initial homotopy or after changing the QP matrices. */ - QPS_AUXILIARYQPSOLVED, /**< An auxilary problem was solved, either at the very beginning - * via an initial homotopy or after changing the QP matrices. */ - QPS_PERFORMINGHOMOTOPY, /**< A homotopy according to the main idea of the online active - * set strategy is performed. */ - QPS_HOMOTOPYQPSOLVED, /**< An intermediate QP along the homotopy path was solved. */ - QPS_SOLVED /**< The solution of the actual QP was found. */ -} QProblemStatus; - - -/** Summarises all possible types of the QP's Hessian matrix. */ -typedef enum -{ - HST_ZERO, /**< Hessian is zero matrix (i.e. LP formulation). */ - HST_IDENTITY, /**< Hessian is identity matrix. */ - HST_POSDEF, /**< Hessian is (strictly) positive definite. */ - HST_POSDEF_NULLSPACE, /**< Hessian is positive definite on null space of active bounds/constraints. */ - HST_SEMIDEF, /**< Hessian is positive semi-definite. */ - HST_INDEF, /**< Hessian is indefinite. */ - HST_UNKNOWN /**< Hessian type is unknown. */ -} HessianType; - - -/** Summarises all possible types of bounds and constraints. */ -typedef enum -{ - ST_UNBOUNDED, /**< Bound/constraint is unbounded. */ - ST_BOUNDED, /**< Bound/constraint is bounded but not fixed. */ - ST_EQUALITY, /**< Bound/constraint is fixed (implicit equality bound/constraint). */ - ST_DISABLED, /**< Bound/constraint is disabled (i.e. ignored when solving QP). */ - ST_UNKNOWN /**< Type of bound/constraint unknown. */ -} SubjectToType; - - -/** Summarises all possible states of bounds and constraints. */ -typedef enum -{ - ST_LOWER = -1, /**< Bound/constraint is at its lower bound. */ - ST_INACTIVE, /**< Bound/constraint is inactive. */ - ST_UPPER, /**< Bound/constraint is at its upper bound. */ - ST_INFEASIBLE_LOWER, /**< (to be documented) */ - ST_INFEASIBLE_UPPER, /**< (to be documented) */ - ST_UNDEFINED /**< Status of bound/constraint undefined. */ -} SubjectToStatus; - - -/** - * \brief Stores internal information for tabular (debugging) output. - * - * Struct storing internal information for tabular (debugging) output - * when using the (S)QProblem(B) objects. - * - * \author Hans Joachim Ferreau - * \version 3.1embedded - * \date 2013-2015 - */ -typedef struct -{ - int idxAddB; /**< Index of bound that has been added to working set. */ - int idxRemB; /**< Index of bound that has been removed from working set. */ - int idxAddC; /**< Index of constraint that has been added to working set. */ - int idxRemC; /**< Index of constraint that has been removed from working set. */ - int excAddB; /**< Flag indicating whether a bound has been added to working set to keep a regular projected Hessian. */ - int excRemB; /**< Flag indicating whether a bound has been removed from working set to keep a regular projected Hessian. */ - int excAddC; /**< Flag indicating whether a constraint has been added to working set to keep a regular projected Hessian. */ - int excRemC; /**< Flag indicating whether a constraint has been removed from working set to keep a regular projected Hessian. */ -} TabularOutput; - -/** - * \brief Struct containing the variable header for mat file. - * - * Struct storing the header of a variable to be stored in - * Matlab's binary format (using the outdated Level 4 variant - * for simplictiy). - * - * Note, this code snippet has been inspired from the document - * "Matlab(R) MAT-file Format, R2013b" by MathWorks - * - * \author Hans Joachim Ferreau - * \version 3.1embedded - * \date 2013-2015 - */ -typedef struct -{ - long numericFormat; /**< Flag indicating numerical format. */ - long nRows; /**< Number of rows. */ - long nCols; /**< Number of rows. */ - long imaginaryPart; /**< (to be documented) */ - long nCharName; /**< Number of character in name. */ -} MatMatrixHeader; - - -END_NAMESPACE_QPOASES - - -#endif /* QPOASES_TYPES_H */ - - -/* - * end of file - */ diff --git a/third_party/acados/include/qpOASES_e/UnitTesting.h b/third_party/acados/include/qpOASES_e/UnitTesting.h deleted file mode 100644 index dbff201..0000000 --- a/third_party/acados/include/qpOASES_e/UnitTesting.h +++ /dev/null @@ -1,79 +0,0 @@ -/* - * This file is part of qpOASES. - * - * qpOASES -- An Implementation of the Online Active Set Strategy. - * Copyright (C) 2007-2015 by Hans Joachim Ferreau, Andreas Potschka, - * Christian Kirches et al. All rights reserved. - * - * qpOASES is free software; you can redistribute it and/or - * modify it under the terms of the GNU Lesser General Public - * License as published by the Free Software Foundation; either - * version 2.1 of the License, or (at your option) any later version. - * - * qpOASES is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public - * License along with qpOASES; if not, write to the Free Software - * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - * - */ - - -/** - * \file include/qpOASES_e/UnitTesting.h - * \author Hans Joachim Ferreau - * \version 3.1embedded - * \date 2014-2015 - * - * Definition of auxiliary functions/macros for unit testing. - */ - - -#ifndef QPOASES_UNIT_TESTING_H -#define QPOASES_UNIT_TESTING_H - - -#ifndef TEST_TOL_FACTOR -#define TEST_TOL_FACTOR 1 -#endif - - -/** Return value for tests that passed. */ -#define TEST_PASSED 0 - -/** Return value for tests that failed. */ -#define TEST_FAILED 1 - -/** Return value for tests that could not run due to missing external data. */ -#define TEST_DATA_NOT_FOUND 99 - - -/** Macro verifying that two numerical values are equal in order to pass unit test. */ -#define QPOASES_TEST_FOR_EQUAL( x,y ) if ( REFER_NAMESPACE_QPOASES isEqual( (x),(y) ) == BT_FALSE ) { return TEST_FAILED; } - -/** Macro verifying that two numerical values are close to each other in order to pass unit test. */ -#define QPOASES_TEST_FOR_NEAR( x,y ) if ( REFER_NAMESPACE_QPOASES getAbs((x)-(y)) / REFER_NAMESPACE_QPOASES getMax( 1.0,REFER_NAMESPACE_QPOASES getAbs(x) ) >= 1e-10 ) { return TEST_FAILED; } - -/** Macro verifying that first quantity is lower or equal than second one in order to pass unit test. */ -#define QPOASES_TEST_FOR_TOL( x,tol ) if ( (x) > (tol)*(TEST_TOL_FACTOR) ) { return TEST_FAILED; } - -/** Macro verifying that a logical expression holds in order to pass unit test. */ -#define QPOASES_TEST_FOR_TRUE( x ) if ( (x) == 0 ) { return TEST_FAILED; } - - - -BEGIN_NAMESPACE_QPOASES - - -END_NAMESPACE_QPOASES - - -#endif /* QPOASES_UNIT_TESTING_H */ - - -/* - * end of file - */ diff --git a/third_party/acados/include/qpOASES_e/Utils.h b/third_party/acados/include/qpOASES_e/Utils.h deleted file mode 100644 index 75e45a5..0000000 --- a/third_party/acados/include/qpOASES_e/Utils.h +++ /dev/null @@ -1,500 +0,0 @@ -/* - * This file is part of qpOASES. - * - * qpOASES -- An Implementation of the Online Active Set Strategy. - * Copyright (C) 2007-2015 by Hans Joachim Ferreau, Andreas Potschka, - * Christian Kirches et al. All rights reserved. - * - * qpOASES is free software; you can redistribute it and/or - * modify it under the terms of the GNU Lesser General Public - * License as published by the Free Software Foundation; either - * version 2.1 of the License, or (at your option) any later version. - * - * qpOASES is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public - * License along with qpOASES; if not, write to the Free Software - * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - * - */ - - -/** - * \file include/qpOASES_e/Utils.h - * \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches - * \version 3.1embedded - * \date 2007-2015 - * - * Declaration of some utilities for working with the different QProblem classes. - */ - - -#ifndef QPOASES_UTILS_H -#define QPOASES_UTILS_H - -#include - - -BEGIN_NAMESPACE_QPOASES - - -/** Prints a vector. - * \return SUCCESSFUL_RETURN */ -returnValue qpOASES_printV( const real_t* const v, /**< Vector to be printed. */ - int n /**< Length of vector. */ - ); - -/** Prints a permuted vector. - * \return SUCCESSFUL_RETURN */ -returnValue qpOASES_printPV( const real_t* const v, /**< Vector to be printed. */ - int n, /**< Length of vector. */ - const int* const V_idx /**< Pemutation vector. */ - ); - -/** Prints a named vector. - * \return SUCCESSFUL_RETURN */ -returnValue qpOASES_printNV( const real_t* const v, /**< Vector to be printed. */ - int n, /**< Length of vector. */ - const char* name /** Name of vector. */ - ); - -/** Prints a matrix. - * \return SUCCESSFUL_RETURN */ -returnValue qpOASES_printM( const real_t* const M, /**< Matrix to be printed. */ - int nrow, /**< Row number of matrix. */ - int ncol /**< Column number of matrix. */ - ); - -/** Prints a permuted matrix. - * \return SUCCESSFUL_RETURN */ -returnValue qpOASES_printPM( const real_t* const M, /**< Matrix to be printed. */ - int nrow, /**< Row number of matrix. */ - int ncol , /**< Column number of matrix. */ - const int* const ROW_idx, /**< Row pemutation vector. */ - const int* const COL_idx /**< Column pemutation vector. */ - ); - -/** Prints a named matrix. - * \return SUCCESSFUL_RETURN */ -returnValue qpOASES_printNM( const real_t* const M, /**< Matrix to be printed. */ - int nrow, /**< Row number of matrix. */ - int ncol, /**< Column number of matrix. */ - const char* name /** Name of matrix. */ - ); - -/** Prints an index array. - * \return SUCCESSFUL_RETURN */ -returnValue qpOASES_printI( const int* const _index, /**< Index array to be printed. */ - int n /**< Length of index array. */ - ); - -/** Prints a named index array. - * \return SUCCESSFUL_RETURN */ -returnValue qpOASES_printNI( const int* const _index, /**< Index array to be printed. */ - int n, /**< Length of index array. */ - const char* name /**< Name of index array. */ - ); - - -/** Prints a string to desired output target (useful also for MATLAB output!). - * \return SUCCESSFUL_RETURN */ -returnValue qpOASES_myPrintf( const char* s /**< String to be written. */ - ); - - -/** Prints qpOASES copyright notice. - * \return SUCCESSFUL_RETURN */ -returnValue qpOASES_printCopyrightNotice( ); - - -/** Reads a real_t matrix from file. - * \return SUCCESSFUL_RETURN \n - RET_UNABLE_TO_OPEN_FILE \n - RET_UNABLE_TO_READ_FILE */ -returnValue qpOASES_readFromFileM( real_t* data, /**< Matrix to be read from file. */ - int nrow, /**< Row number of matrix. */ - int ncol, /**< Column number of matrix. */ - const char* datafilename /**< Data file name. */ - ); - -/** Reads a real_t vector from file. - * \return SUCCESSFUL_RETURN \n - RET_UNABLE_TO_OPEN_FILE \n - RET_UNABLE_TO_READ_FILE */ -returnValue qpOASES_readFromFileV( real_t* data, /**< Vector to be read from file. */ - int n, /**< Length of vector. */ - const char* datafilename /**< Data file name. */ - ); - -/** Reads an integer (column) vector from file. - * \return SUCCESSFUL_RETURN \n - RET_UNABLE_TO_OPEN_FILE \n - RET_UNABLE_TO_READ_FILE */ -returnValue qpOASES_readFromFileI( int* data, /**< Vector to be read from file. */ - int n, /**< Length of vector. */ - const char* datafilename /**< Data file name. */ - ); - - -/** Writes a real_t matrix into a file. - * \return SUCCESSFUL_RETURN \n - RET_UNABLE_TO_OPEN_FILE */ -returnValue qpOASES_writeIntoFileM( const real_t* const data, /**< Matrix to be written into file. */ - int nrow, /**< Row number of matrix. */ - int ncol, /**< Column number of matrix. */ - const char* datafilename, /**< Data file name. */ - BooleanType append /**< Indicates if data shall be appended if the file already exists (otherwise it is overwritten). */ - ); - -/** Writes a real_t vector into a file. - * \return SUCCESSFUL_RETURN \n - RET_UNABLE_TO_OPEN_FILE */ -returnValue qpOASES_writeIntoFileV( const real_t* const data, /**< Vector to be written into file. */ - int n, /**< Length of vector. */ - const char* datafilename, /**< Data file name. */ - BooleanType append /**< Indicates if data shall be appended if the file already exists (otherwise it is overwritten). */ - ); - -/** Writes an integer (column) vector into a file. - * \return SUCCESSFUL_RETURN \n - RET_UNABLE_TO_OPEN_FILE */ -returnValue qpOASES_writeIntoFileI( const int* const integer, /**< Integer vector to be written into file. */ - int n, /**< Length of vector. */ - const char* datafilename, /**< Data file name. */ - BooleanType append /**< Indicates if integer shall be appended if the file already exists (otherwise it is overwritten). */ - ); - -/** Writes a real_t matrix/vector into a Matlab binary file. - * \return SUCCESSFUL_RETURN \n - RET_INVALID_ARGUMENTS - RET_UNABLE_TO_WRITE_FILE */ -returnValue qpOASES_writeIntoMatFile( FILE* const matFile, /**< Pointer to Matlab binary file. */ - const real_t* const data, /**< Data to be written into file. */ - int nRows, /**< Row number of matrix. */ - int nCols, /**< Column number of matrix. */ - const char* name /**< Matlab name of matrix/vector to be stored. */ - ); - -/** Writes in integer matrix/vector into a Matlab binary file. - * \return SUCCESSFUL_RETURN \n - RET_INVALID_ARGUMENTS - RET_UNABLE_TO_WRITE_FILE */ -returnValue qpOASES_writeIntoMatFileI( FILE* const matFile, /**< Pointer to Matlab binary file. */ - const int* const data, /**< Data to be written into file. */ - int nRows, /**< Row number of matrix. */ - int nCols, /**< Column number of matrix. */ - const char* name /**< Matlab name of matrix/vector to be stored. */ - ); - - -/** Returns the current system time. - * \return current system time */ -real_t qpOASES_getCPUtime( ); - - -/** Returns the N-norm of a vector. - * \return >= 0.0: successful */ -real_t qpOASES_getNorm( const real_t* const v, /**< Vector. */ - int n, /**< Vector's dimension. */ - int type /**< Norm type, 1: one-norm, 2: Euclidean norm. */ - ); - -/** Tests whether two real-valued arguments are (numerically) equal. - * \return BT_TRUE: arguments differ not more than TOL \n - BT_FALSE: arguments differ more than TOL */ -static inline BooleanType qpOASES_isEqual( real_t x, /**< First real number. */ - real_t y, /**< Second real number. */ - real_t TOL /**< Tolerance for comparison. */ - ); - - -/** Tests whether a real-valued argument is (numerically) zero. - * \return BT_TRUE: argument differs from 0.0 not more than TOL \n - BT_FALSE: argument differs from 0.0 more than TOL */ -static inline BooleanType qpOASES_isZero( real_t x, /**< Real number. */ - real_t TOL /**< Tolerance for comparison. */ - ); - - -/** Returns sign of a real-valued argument. - * \return 1.0: argument is non-negative \n - -1.0: argument is negative */ -static inline real_t qpOASES_getSign( real_t arg /**< real-valued argument whose sign is to be determined. */ - ); - - -/** Returns maximum of two integers. - * \return Maximum of two integers */ -static inline int qpOASES_getMaxI( int x, /**< First integer. */ - int y /**< Second integer. */ - ); - - -/** Returns minimum of two integers. - * \return Minimum of two integers */ -static inline int qpOASES_getMinI( int x, /**< First integer. */ - int y /**< Second integer. */ - ); - - -/** Returns maximum of two reals. - * \return Maximum of two reals */ -static inline real_t qpOASES_getMax( real_t x, /**< First real number. */ - real_t y /**< Second real number. */ - ); - - -/** Returns minimum of two reals. - * \return Minimum of two reals */ -static inline real_t qpOASES_getMin( real_t x, /**< First real number. */ - real_t y /**< Second real number. */ - ); - - -/** Returns the absolute value of a real_t-valued argument. - * \return Absolute value of a real_t-valued argument */ -static inline real_t qpOASES_getAbs( real_t x /**< real_t-valued argument. */ - ); - -/** Returns the square-root of a real number. - * \return Square-root of a real number */ -static inline real_t qpOASES_getSqrt( real_t x /**< Non-negative real number. */ - ); - - -/** Computes the maximum violation of the KKT optimality conditions - * of given iterate for given QP data. */ -returnValue qpOASES_getKktViolation( int nV, /**< Number of variables. */ - int nC, /**< Number of constraints. */ - const real_t* const H, /**< Hessian matrix (may be NULL if Hessian is zero or identity matrix). */ - const real_t* const g, /**< Gradient vector. */ - const real_t* const A, /**< Constraint matrix. */ - const real_t* const lb, /**< Lower bound vector (on variables). */ - const real_t* const ub, /**< Upper bound vector (on variables). */ - const real_t* const lbA, /**< Lower constraints' bound vector. */ - const real_t* const ubA, /**< Upper constraints' bound vector. */ - const real_t* const x, /**< Primal trial vector. */ - const real_t* const y, /**< Dual trial vector. */ - real_t* const _stat, /**< Output: maximum value of stationarity condition residual. */ - real_t* const feas, /**< Output: maximum value of primal feasibility violation. */ - real_t* const cmpl /**< Output: maximum value of complementarity residual. */ - ); - -/** Computes the maximum violation of the KKT optimality conditions - * of given iterate for given QP data. */ -returnValue qpOASES_getKktViolationSB( int nV, /**< Number of variables. */ - const real_t* const H, /**< Hessian matrix (may be NULL if Hessian is zero or identity matrix). */ - const real_t* const g, /**< Gradient vector. */ - const real_t* const lb, /**< Lower bound vector (on variables). */ - const real_t* const ub, /**< Upper bound vector (on variables). */ - const real_t* const x, /**< Primal trial vector. */ - const real_t* const y, /**< Dual trial vector. */ - real_t* const _stat, /**< Output: maximum value of stationarity condition residual. */ - real_t* const feas, /**< Output: maximum value of primal feasibility violation. */ - real_t* const cmpl /**< Output: maximum value of complementarity residual. */ - ); - - -/** Writes a value of BooleanType into a string. - * \return SUCCESSFUL_RETURN */ -returnValue qpOASES_convertBooleanTypeToString( BooleanType value, /**< Value to be written. */ - char* const string /**< Input: String of sufficient size, \n - Output: String containing value. */ - ); - -/** Writes a value of SubjectToStatus into a string. - * \return SUCCESSFUL_RETURN */ -returnValue qpOASES_convertSubjectToStatusToString( SubjectToStatus value, /**< Value to be written. */ - char* const string /**< Input: String of sufficient size, \n - Output: String containing value. */ - ); - -/** Writes a value of PrintLevel into a string. - * \return SUCCESSFUL_RETURN */ -returnValue qpOASES_convertPrintLevelToString( PrintLevel value, /**< Value to be written. */ - char* const string /**< Input: String of sufficient size, \n - Output: String containing value. */ - ); - - -/** Converts a returnValue from an QProblem(B) object into a more - * simple status flag. - * - * \return 0: QP problem solved - * 1: QP could not be solved within given number of iterations - * -1: QP could not be solved due to an internal error - * -2: QP is infeasible (and thus could not be solved) - * -3: QP is unbounded (and thus could not be solved) - */ -int qpOASES_getSimpleStatus( returnValue returnvalue, /**< ReturnValue to be analysed. */ - BooleanType doPrintStatus /**< Flag indicating whether simple status shall be printed to screen. */ - ); - -/** Normalises QP constraints. - * \return SUCCESSFUL_RETURN \n - * RET_INVALID_ARGUMENTS */ -returnValue qpOASES_normaliseConstraints( int nV, /**< Number of variables. */ - int nC, /**< Number of constraints. */ - real_t* A, /**< Input: Constraint matrix, \n - Output: Normalised constraint matrix. */ - real_t* lbA, /**< Input: Constraints' lower bound vector, \n - Output: Normalised constraints' lower bound vector. */ - real_t* ubA, /**< Input: Constraints' upper bound vector, \n - Output: Normalised constraints' upper bound vector. */ - int type /**< Norm type, 1: one-norm, 2: Euclidean norm. */ - ); - - -#ifdef __DEBUG__ -/** Writes matrix with given dimension into specified file. */ -void gdb_printmat( const char *fname, /**< File name. */ - real_t *M, /**< Matrix to be written. */ - int n, /**< Number of rows. */ - int m, /**< Number of columns. */ - int ldim /**< Leading dimension. */ - ); -#endif /* __DEBUG__ */ - - -#if defined(__DSPACE__) || defined(__XPCTARGET__) -void __cxa_pure_virtual( void ); -#endif /* __DSPACE__ || __XPCTARGET__*/ - - - -/* - * i s E q u a l - */ -static inline BooleanType qpOASES_isEqual( real_t x, - real_t y, - real_t TOL - ) -{ - if ( qpOASES_getAbs(x-y) <= TOL ) - return BT_TRUE; - else - return BT_FALSE; -} - - -/* - * i s Z e r o - */ -static inline BooleanType qpOASES_isZero( real_t x, - real_t TOL - ) -{ - if ( qpOASES_getAbs(x) <= TOL ) - return BT_TRUE; - else - return BT_FALSE; -} - - -/* - * g e t S i g n - */ -static inline real_t qpOASES_getSign( real_t arg - ) -{ - if ( arg >= 0.0 ) - return 1.0; - else - return -1.0; -} - - - -/* - * g e t M a x - */ -static inline int qpOASES_getMaxI( int x, - int y - ) -{ - return (yx) ? x : y; -} - - -/* - * g e t M a x - */ -static inline real_t qpOASES_getMax( real_t x, - real_t y - ) -{ - #ifdef __NO_FMATH__ - return (yx) ? x : y; - #else - return (y>x) ? x : y; - /*return fmin(x,y); seems to be slower */ - #endif -} - - -/* - * g e t A b s - */ -static inline real_t qpOASES_getAbs( real_t x - ) -{ - #ifdef __NO_FMATH__ - return (x>=0.0) ? x : -x; - #else - return fabs(x); - #endif -} - -/* - * g e t S q r t - */ -static inline real_t qpOASES_getSqrt( real_t x - ) -{ - #ifdef __NO_FMATH__ - return sqrt(x); /* put your custom sqrt-replacement here */ - #else - return sqrt(x); - #endif -} - - -END_NAMESPACE_QPOASES - - -#endif /* QPOASES_UTILS_H */ - - -/* - * end of file - */ diff --git a/third_party/acados/include/qpOASES_e/extras/OQPinterface.h b/third_party/acados/include/qpOASES_e/extras/OQPinterface.h deleted file mode 100644 index da59ea9..0000000 --- a/third_party/acados/include/qpOASES_e/extras/OQPinterface.h +++ /dev/null @@ -1,227 +0,0 @@ -/* - * This file is part of qpOASES. - * - * qpOASES -- An Implementation of the Online Active Set Strategy. - * Copyright (C) 2007-2015 by Hans Joachim Ferreau, Andreas Potschka, - * Christian Kirches et al. All rights reserved. - * - * qpOASES is free software; you can redistribute it and/or - * modify it under the terms of the GNU Lesser General Public - * License as published by the Free Software Foundation; either - * version 2.1 of the License, or (at your option) any later version. - * - * qpOASES is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public - * License along with qpOASES; if not, write to the Free Software - * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - * - */ - - -/** - * \file include/qpOASES_e/extras/OQPinterface.h - * \author Hans Joachim Ferreau, Andreas Potschka, Christian Kirches - * \version 3.1embedded - * \date 2007-2015 - * - * Declaration of an interface comprising several utility functions - * for solving test problems from the Online QP Benchmark Collection - * (This collection is no longer maintained, see - * http://www.qpOASES.org/onlineQP for a backup). - */ - - -#ifndef QPOASES_OQPINTERFACE_H -#define QPOASES_OQPINTERFACE_H - - -#include -#include - -#include -#include - - -BEGIN_NAMESPACE_QPOASES - -typedef struct { - QProblem *qp; - - DenseMatrix *H; - DenseMatrix *A; - - real_t *x; - real_t *y; -} OQPbenchmark_ws; - -int OQPbenchmark_ws_calculateMemorySize( unsigned int nV, unsigned int nC ); - -char *OQPbenchmark_ws_assignMemory( unsigned int nV, unsigned int nC, OQPbenchmark_ws **mem, void *raw_memory ); - -OQPbenchmark_ws *OQPbenchmark_ws_createMemory( unsigned int nV, unsigned int nC ); - -typedef struct { - QProblemB *qp; - - DenseMatrix *H; - - real_t *x; - real_t *y; -} OQPbenchmarkB_ws; - -int OQPbenchmarkB_ws_calculateMemorySize( unsigned int nV ); - -char *OQPbenchmarkB_ws_assignMemory( unsigned int nV, OQPbenchmarkB_ws **mem, void *raw_memory ); - -OQPbenchmarkB_ws *OQPbenchmarkB_ws_createMemory( unsigned int nV ); - -typedef struct { - OQPbenchmark_ws *qp_ws; - OQPbenchmarkB_ws *qpB_ws; - - real_t *H; - real_t *g; - real_t *A; - real_t *lb; - real_t *ub; - real_t *lbA; - real_t *ubA; -} OQPinterface_ws; - -int OQPinterface_ws_calculateMemorySize( unsigned int nV, unsigned int nC, unsigned int nQP ); - -char *OQPinterface_ws_assignMemory( unsigned int nV, unsigned int nC, unsigned int nQP, OQPinterface_ws **mem, void *raw_memory ); - -OQPinterface_ws *OQPinterface_ws_createMemory( unsigned int nV, unsigned int nC, unsigned int nQP ); - -/** Reads dimensions of an Online QP Benchmark problem from file. - * \return SUCCESSFUL_RETURN \n - RET_UNABLE_TO_READ_FILE \n - RET_FILEDATA_INCONSISTENT */ -returnValue readOQPdimensions( const char* path, /**< Full path of the data files (without trailing slash!). */ - int* nQP, /**< Output: Number of QPs. */ - int* nV, /**< Output: Number of variables. */ - int* nC, /**< Output: Number of constraints. */ - int* nEC /**< Output: Number of equality constraints. */ - ); - -/** Reads data of an Online QP Benchmark problem from file. - * This function allocates the required memory for all data; after successfully calling it, - * you have to free this memory yourself! - * \return SUCCESSFUL_RETURN \n - RET_INVALID_ARGUMENTS \n - RET_UNABLE_TO_READ_FILE \n - RET_FILEDATA_INCONSISTENT */ -returnValue readOQPdata( const char* path, /**< Full path of the data files (without trailing slash!). */ - int* nQP, /**< Output: Number of QPs. */ - int* nV, /**< Output: Number of variables. */ - int* nC, /**< Output: Number of constraints. */ - int* nEC, /**< Output: Number of equality constraints. */ - real_t* H, /**< Output: Hessian matrix. */ - real_t* g, /**< Output: Sequence of gradient vectors. */ - real_t* A, /**< Output: Constraint matrix. */ - real_t* lb, /**< Output: Sequence of lower bound vectors (on variables). */ - real_t* ub, /**< Output: Sequence of upper bound vectors (on variables). */ - real_t* lbA, /**< Output: Sequence of lower constraints' bound vectors. */ - real_t* ubA, /**< Output: Sequence of upper constraints' bound vectors. */ - real_t* xOpt, /**< Output: Sequence of primal solution vectors - * (not read if a null pointer is passed). */ - real_t* yOpt, /**< Output: Sequence of dual solution vectors - * (not read if a null pointer is passed). */ - real_t* objOpt /**< Output: Sequence of optimal objective function values - * (not read if a null pointer is passed). */ - ); - - -/** Solves an Online QP Benchmark problem as specified by the arguments. - * The maximum deviations from the given optimal solution as well as the - * maximum CPU time to solve each QP are determined. - * \return SUCCESSFUL_RETURN \n - RET_BENCHMARK_ABORTED */ -returnValue solveOQPbenchmark( int nQP, /**< Number of QPs. */ - int nV, /**< Number of variables. */ - int nC, /**< Number of constraints. */ - int nEC, /**< Number of equality constraints. */ - real_t* _H, /**< Hessian matrix. */ - const real_t* const g, /**< Sequence of gradient vectors. */ - real_t* _A, /**< Constraint matrix. */ - const real_t* const lb, /**< Sequence of lower bound vectors (on variables). */ - const real_t* const ub, /**< Sequence of upper bound vectors (on variables). */ - const real_t* const lbA, /**< Sequence of lower constraints' bound vectors. */ - const real_t* const ubA, /**< Sequence of upper constraints' bound vectors. */ - BooleanType isSparse, /**< Shall convert matrices to sparse format before solution? */ - BooleanType useHotstarts, /**< Shall QP solution be hotstarted? */ - const Options* options, /**< QP solver options to be used while solving benchmark problems. */ - int maxAllowedNWSR, /**< Maximum number of working set recalculations to be performed. */ - real_t* maxNWSR, /**< Output: Maximum number of performed working set recalculations. */ - real_t* avgNWSR, /**< Output: Average number of performed working set recalculations. */ - real_t* maxCPUtime, /**< Output: Maximum CPU time required for solving each QP. */ - real_t* avgCPUtime, /**< Output: Average CPU time required for solving each QP. */ - real_t* maxStationarity, /**< Output: Maximum residual of stationarity condition. */ - real_t* maxFeasibility, /**< Output: Maximum residual of primal feasibility condition. */ - real_t* maxComplementarity, /**< Output: Maximum residual of complementarity condition. */ - OQPbenchmark_ws *work /**< Workspace. */ - ); - -/** Solves an Online QP Benchmark problem (without constraints) as specified - * by the arguments. The maximum deviations from the given optimal solution - * as well as the maximum CPU time to solve each QP are determined. - * \return SUCCESSFUL_RETURN \n - RET_BENCHMARK_ABORTED */ -returnValue solveOQPbenchmarkB( int nQP, /**< Number of QPs. */ - int nV, /**< Number of variables. */ - real_t* _H, /**< Hessian matrix. */ - const real_t* const g, /**< Sequence of gradient vectors. */ - const real_t* const lb, /**< Sequence of lower bound vectors (on variables). */ - const real_t* const ub, /**< Sequence of upper bound vectors (on variables). */ - BooleanType isSparse, /**< Shall convert matrices to sparse format before solution? */ - BooleanType useHotstarts, /**< Shall QP solution be hotstarted? */ - const Options* options, /**< QP solver options to be used while solving benchmark problems. */ - int maxAllowedNWSR, /**< Maximum number of working set recalculations to be performed. */ - real_t* maxNWSR, /**< Output: Maximum number of performed working set recalculations. */ - real_t* avgNWSR, /**< Output: Average number of performed working set recalculations. */ - real_t* maxCPUtime, /**< Output: Maximum CPU time required for solving each QP. */ - real_t* avgCPUtime, /**< Output: Average CPU time required for solving each QP. */ - real_t* maxStationarity, /**< Output: Maximum residual of stationarity condition. */ - real_t* maxFeasibility, /**< Output: Maximum residual of primal feasibility condition. */ - real_t* maxComplementarity, /**< Output: Maximum residual of complementarity condition. */ - OQPbenchmarkB_ws *work /**< Workspace. */ - ); - - -/** Runs an Online QP Benchmark problem and determines the maximum - * violation of the KKT optimality conditions as well as the - * maximum and average number of iterations and CPU time to solve - * each QP. - * - * \return SUCCESSFUL_RETURN \n - RET_UNABLE_TO_READ_BENCHMARK \n - RET_BENCHMARK_ABORTED */ -returnValue runOQPbenchmark( const char* path, /**< Full path of the benchmark files (without trailing slash!). */ - BooleanType isSparse, /**< Shall convert matrices to sparse format before solution? */ - BooleanType useHotstarts, /**< Shall QP solution be hotstarted? */ - const Options* options, /**< QP solver options to be used while solving benchmark problems. */ - int maxAllowedNWSR, /**< Maximum number of working set recalculations to be performed. */ - real_t* maxNWSR, /**< Output: Maximum number of performed working set recalculations. */ - real_t* avgNWSR, /**< Output: Average number of performed working set recalculations. */ - real_t* maxCPUtime, /**< Output: Maximum CPU time required for solving each QP. */ - real_t* avgCPUtime, /**< Output: Average CPU time required for solving each QP. */ - real_t* maxStationarity, /**< Output: Maximum residual of stationarity condition. */ - real_t* maxFeasibility, /**< Output: Maximum residual of primal feasibility condition. */ - real_t* maxComplementarity, /**< Output: Maximum residual of complementarity condition. */ - OQPinterface_ws* work /**< Workspace. */ - ); - -END_NAMESPACE_QPOASES - - -#endif /* QPOASES_OQPINTERFACE_H */ - - -/* - * end of file - */ diff --git a/third_party/acados/larch64/lib/libqpOASES_e.so b/third_party/acados/larch64/lib/libqpOASES_e.so index 1404862..19e7a69 120000 Binary files a/third_party/acados/larch64/lib/libqpOASES_e.so and b/third_party/acados/larch64/lib/libqpOASES_e.so differ diff --git a/third_party/acados/x86_64/lib/libacados.so b/third_party/acados/x86_64/lib/libacados.so deleted file mode 100644 index ae5fc36..0000000 Binary files a/third_party/acados/x86_64/lib/libacados.so and /dev/null differ diff --git a/third_party/acados/x86_64/lib/libblasfeo.so b/third_party/acados/x86_64/lib/libblasfeo.so deleted file mode 100644 index 676ff67..0000000 Binary files a/third_party/acados/x86_64/lib/libblasfeo.so and /dev/null differ diff --git a/third_party/acados/x86_64/lib/libhpipm.so b/third_party/acados/x86_64/lib/libhpipm.so deleted file mode 100644 index 8d026b1..0000000 Binary files a/third_party/acados/x86_64/lib/libhpipm.so and /dev/null differ diff --git a/third_party/acados/x86_64/lib/libqpOASES_e.so b/third_party/acados/x86_64/lib/libqpOASES_e.so deleted file mode 120000 index 1404862..0000000 --- a/third_party/acados/x86_64/lib/libqpOASES_e.so +++ /dev/null @@ -1 +0,0 @@ -libqpOASES_e.so.3.1 \ No newline at end of file diff --git a/third_party/acados/x86_64/lib/libqpOASES_e.so.3.1 b/third_party/acados/x86_64/lib/libqpOASES_e.so.3.1 deleted file mode 100644 index c0c8b66..0000000 Binary files a/third_party/acados/x86_64/lib/libqpOASES_e.so.3.1 and /dev/null differ diff --git a/third_party/acados/x86_64/t_renderer b/third_party/acados/x86_64/t_renderer old mode 100755 new mode 100644 diff --git a/third_party/kaitai/custom_decoder.h b/third_party/kaitai/custom_decoder.h deleted file mode 100644 index 6da7f5f..0000000 --- a/third_party/kaitai/custom_decoder.h +++ /dev/null @@ -1,16 +0,0 @@ -#ifndef KAITAI_CUSTOM_DECODER_H -#define KAITAI_CUSTOM_DECODER_H - -#include - -namespace kaitai { - -class custom_decoder { -public: - virtual ~custom_decoder() {}; - virtual std::string decode(std::string src) = 0; -}; - -} - -#endif diff --git a/third_party/kaitai/exceptions.h b/third_party/kaitai/exceptions.h deleted file mode 100644 index 5c09c46..0000000 --- a/third_party/kaitai/exceptions.h +++ /dev/null @@ -1,189 +0,0 @@ -#ifndef KAITAI_EXCEPTIONS_H -#define KAITAI_EXCEPTIONS_H - -#include - -#include -#include - -// We need to use "noexcept" in virtual destructor of our exceptions -// subclasses. Different compilers have different ideas on how to -// achieve that: C++98 compilers prefer `throw()`, C++11 and later -// use `noexcept`. We define KS_NOEXCEPT macro for that. - -#if __cplusplus >= 201103L || (defined(_MSC_VER) && _MSC_VER >= 1900) -#define KS_NOEXCEPT noexcept -#else -#define KS_NOEXCEPT throw() -#endif - -namespace kaitai { - -/** - * Common ancestor for all error originating from Kaitai Struct usage. - * Stores KSY source path, pointing to an element supposedly guilty of - * an error. - */ -class kstruct_error: public std::runtime_error { -public: - kstruct_error(const std::string what, const std::string src_path): - std::runtime_error(src_path + ": " + what), - m_src_path(src_path) - { - } - - virtual ~kstruct_error() KS_NOEXCEPT {}; - -protected: - const std::string m_src_path; -}; - -/** - * Error that occurs when default endianness should be decided with - * a switch, but nothing matches (although using endianness expression - * implies that there should be some positive result). - */ -class undecided_endianness_error: public kstruct_error { -public: - undecided_endianness_error(const std::string src_path): - kstruct_error("unable to decide on endianness for a type", src_path) - { - } - - virtual ~undecided_endianness_error() KS_NOEXCEPT {}; -}; - -/** - * Common ancestor for all validation failures. Stores pointer to - * KaitaiStream IO object which was involved in an error. - */ -class validation_failed_error: public kstruct_error { -public: - validation_failed_error(const std::string what, kstream* io, const std::string src_path): - kstruct_error("at pos " + kstream::to_string(static_cast(io->pos())) + ": validation failed: " + what, src_path), - m_io(io) - { - } - -// "at pos #{io.pos}: validation failed: #{msg}" - - virtual ~validation_failed_error() KS_NOEXCEPT {}; - -protected: - kstream* m_io; -}; - -/** - * Signals validation failure: we required "actual" value to be equal to - * "expected", but it turned out that it's not. - */ -template -class validation_not_equal_error: public validation_failed_error { -public: - validation_not_equal_error(const T& expected, const T& actual, kstream* io, const std::string src_path): - validation_failed_error("not equal", io, src_path), - m_expected(expected), - m_actual(actual) - { - } - - // "not equal, expected #{expected.inspect}, but got #{actual.inspect}" - - virtual ~validation_not_equal_error() KS_NOEXCEPT {}; - -protected: - const T& m_expected; - const T& m_actual; -}; - -/** - * Signals validation failure: we required "actual" value to be greater - * than or equal to "min", but it turned out that it's not. - */ -template -class validation_less_than_error: public validation_failed_error { -public: - validation_less_than_error(const T& min, const T& actual, kstream* io, const std::string src_path): - validation_failed_error("not in range", io, src_path), - m_min(min), - m_actual(actual) - { - } - - // "not in range, min #{min.inspect}, but got #{actual.inspect}" - - virtual ~validation_less_than_error() KS_NOEXCEPT {}; - -protected: - const T& m_min; - const T& m_actual; -}; - -/** - * Signals validation failure: we required "actual" value to be less - * than or equal to "max", but it turned out that it's not. - */ -template -class validation_greater_than_error: public validation_failed_error { -public: - validation_greater_than_error(const T& max, const T& actual, kstream* io, const std::string src_path): - validation_failed_error("not in range", io, src_path), - m_max(max), - m_actual(actual) - { - } - - // "not in range, max #{max.inspect}, but got #{actual.inspect}" - - virtual ~validation_greater_than_error() KS_NOEXCEPT {}; - -protected: - const T& m_max; - const T& m_actual; -}; - -/** - * Signals validation failure: we required "actual" value to be from - * the list, but it turned out that it's not. - */ -template -class validation_not_any_of_error: public validation_failed_error { -public: - validation_not_any_of_error(const T& actual, kstream* io, const std::string src_path): - validation_failed_error("not any of the list", io, src_path), - m_actual(actual) - { - } - - // "not any of the list, got #{actual.inspect}" - - virtual ~validation_not_any_of_error() KS_NOEXCEPT {}; - -protected: - const T& m_actual; -}; - -/** - * Signals validation failure: we required "actual" value to match - * the expression, but it turned out that it doesn't. - */ -template -class validation_expr_error: public validation_failed_error { -public: - validation_expr_error(const T& actual, kstream* io, const std::string src_path): - validation_failed_error("not matching the expression", io, src_path), - m_actual(actual) - { - } - - // "not matching the expression, got #{actual.inspect}" - - virtual ~validation_expr_error() KS_NOEXCEPT {}; - -protected: - const T& m_actual; -}; - -} - -#endif diff --git a/third_party/kaitai/kaitaistream.h b/third_party/kaitai/kaitaistream.h deleted file mode 100644 index e7f4c6c..0000000 --- a/third_party/kaitai/kaitaistream.h +++ /dev/null @@ -1,268 +0,0 @@ -#ifndef KAITAI_STREAM_H -#define KAITAI_STREAM_H - -// Kaitai Struct runtime API version: x.y.z = 'xxxyyyzzz' decimal -#define KAITAI_STRUCT_VERSION 9000L - -#include -#include -#include -#include - -namespace kaitai { - -/** - * Kaitai Stream class (kaitai::kstream) is an implementation of - * Kaitai Struct stream API - * for C++/STL. It's implemented as a wrapper over generic STL std::istream. - * - * It provides a wide variety of simple methods to read (parse) binary - * representations of primitive types, such as integer and floating - * point numbers, byte arrays and strings, and also provides stream - * positioning / navigation methods with unified cross-language and - * cross-toolkit semantics. - * - * Typically, end users won't access Kaitai Stream class manually, but would - * describe a binary structure format using .ksy language and then would use - * Kaitai Struct compiler to generate source code in desired target language. - * That code, in turn, would use this class and API to do the actual parsing - * job. - */ -class kstream { -public: - /** - * Constructs new Kaitai Stream object, wrapping a given std::istream. - * \param io istream object to use for this Kaitai Stream - */ - kstream(std::istream* io); - - /** - * Constructs new Kaitai Stream object, wrapping a given in-memory data - * buffer. - * \param data data buffer to use for this Kaitai Stream - */ - kstream(std::string& data); - - void close(); - - /** @name Stream positioning */ - //@{ - /** - * Check if stream pointer is at the end of stream. Note that the semantics - * are different from traditional STL semantics: one does *not* need to do a - * read (which will fail) after the actual end of the stream to trigger EOF - * flag, which can be accessed after that read. It is sufficient to just be - * at the end of the stream for this method to return true. - * \return "true" if we are located at the end of the stream. - */ - bool is_eof() const; - - /** - * Set stream pointer to designated position. - * \param pos new position (offset in bytes from the beginning of the stream) - */ - void seek(uint64_t pos); - - /** - * Get current position of a stream pointer. - * \return pointer position, number of bytes from the beginning of the stream - */ - uint64_t pos(); - - /** - * Get total size of the stream in bytes. - * \return size of the stream in bytes - */ - uint64_t size(); - //@} - - /** @name Integer numbers */ - //@{ - - // ------------------------------------------------------------------------ - // Signed - // ------------------------------------------------------------------------ - - int8_t read_s1(); - - // ........................................................................ - // Big-endian - // ........................................................................ - - int16_t read_s2be(); - int32_t read_s4be(); - int64_t read_s8be(); - - // ........................................................................ - // Little-endian - // ........................................................................ - - int16_t read_s2le(); - int32_t read_s4le(); - int64_t read_s8le(); - - // ------------------------------------------------------------------------ - // Unsigned - // ------------------------------------------------------------------------ - - uint8_t read_u1(); - - // ........................................................................ - // Big-endian - // ........................................................................ - - uint16_t read_u2be(); - uint32_t read_u4be(); - uint64_t read_u8be(); - - // ........................................................................ - // Little-endian - // ........................................................................ - - uint16_t read_u2le(); - uint32_t read_u4le(); - uint64_t read_u8le(); - - //@} - - /** @name Floating point numbers */ - //@{ - - // ........................................................................ - // Big-endian - // ........................................................................ - - float read_f4be(); - double read_f8be(); - - // ........................................................................ - // Little-endian - // ........................................................................ - - float read_f4le(); - double read_f8le(); - - //@} - - /** @name Unaligned bit values */ - //@{ - - void align_to_byte(); - uint64_t read_bits_int_be(int n); - uint64_t read_bits_int(int n); - uint64_t read_bits_int_le(int n); - - //@} - - /** @name Byte arrays */ - //@{ - - std::string read_bytes(std::streamsize len); - std::string read_bytes_full(); - std::string read_bytes_term(char term, bool include, bool consume, bool eos_error); - std::string ensure_fixed_contents(std::string expected); - - static std::string bytes_strip_right(std::string src, char pad_byte); - static std::string bytes_terminate(std::string src, char term, bool include); - static std::string bytes_to_str(std::string src, std::string src_enc); - - //@} - - /** @name Byte array processing */ - //@{ - - /** - * Performs a XOR processing with given data, XORing every byte of input with a single - * given value. - * @param data data to process - * @param key value to XOR with - * @return processed data - */ - static std::string process_xor_one(std::string data, uint8_t key); - - /** - * Performs a XOR processing with given data, XORing every byte of input with a key - * array, repeating key array many times, if necessary (i.e. if data array is longer - * than key array). - * @param data data to process - * @param key array of bytes to XOR with - * @return processed data - */ - static std::string process_xor_many(std::string data, std::string key); - - /** - * Performs a circular left rotation shift for a given buffer by a given amount of bits, - * using groups of 1 bytes each time. Right circular rotation should be performed - * using this procedure with corrected amount. - * @param data source data to process - * @param amount number of bits to shift by - * @return copy of source array with requested shift applied - */ - static std::string process_rotate_left(std::string data, int amount); - -#ifdef KS_ZLIB - /** - * Performs an unpacking ("inflation") of zlib-compressed data with usual zlib headers. - * @param data data to unpack - * @return unpacked data - * @throws IOException - */ - static std::string process_zlib(std::string data); -#endif - - //@} - - /** - * Performs modulo operation between two integers: dividend `a` - * and divisor `b`. Divisor `b` is expected to be positive. The - * result is always 0 <= x <= b - 1. - */ - static int mod(int a, int b); - - /** - * Converts given integer `val` to a decimal string representation. - * Should be used in place of std::to_string() (which is available only - * since C++11) in older C++ implementations. - */ - static std::string to_string(int val); - - /** - * Reverses given string `val`, so that the first character becomes the - * last and the last one becomes the first. This should be used to avoid - * the need of local variables at the caller. - */ - static std::string reverse(std::string val); - - /** - * Finds the minimal byte in a byte array, treating bytes as - * unsigned values. - * @param val byte array to scan - * @return minimal byte in byte array as integer - */ - static uint8_t byte_array_min(const std::string val); - - /** - * Finds the maximal byte in a byte array, treating bytes as - * unsigned values. - * @param val byte array to scan - * @return maximal byte in byte array as integer - */ - static uint8_t byte_array_max(const std::string val); - -private: - std::istream* m_io; - std::istringstream m_io_str; - int m_bits_left; - uint64_t m_bits; - - void init(); - void exceptions_enable() const; - - static uint64_t get_mask_ones(int n); - - static const int ZLIB_BUF_SIZE = 128 * 1024; -}; - -} - -#endif diff --git a/third_party/kaitai/kaitaistruct.h b/third_party/kaitai/kaitaistruct.h deleted file mode 100644 index 8172ede..0000000 --- a/third_party/kaitai/kaitaistruct.h +++ /dev/null @@ -1,20 +0,0 @@ -#ifndef KAITAI_STRUCT_H -#define KAITAI_STRUCT_H - -#include - -namespace kaitai { - -class kstruct { -public: - kstruct(kstream *_io) { m__io = _io; } - virtual ~kstruct() {} -protected: - kstream *m__io; -public: - kstream *_io() { return m__io; } -}; - -} - -#endif diff --git a/third_party/libyuv/include/libyuv.h b/third_party/libyuv/include/libyuv.h deleted file mode 100644 index aeffd5e..0000000 --- a/third_party/libyuv/include/libyuv.h +++ /dev/null @@ -1,32 +0,0 @@ -/* - * Copyright 2011 The LibYuv Project Authors. All rights reserved. - * - * Use of this source code is governed by a BSD-style license - * that can be found in the LICENSE file in the root of the source - * tree. An additional intellectual property rights grant can be found - * in the file PATENTS. All contributing project authors may - * be found in the AUTHORS file in the root of the source tree. - */ - -#ifndef INCLUDE_LIBYUV_H_ -#define INCLUDE_LIBYUV_H_ - -#include "libyuv/basic_types.h" -#include "libyuv/compare.h" -#include "libyuv/convert.h" -#include "libyuv/convert_argb.h" -#include "libyuv/convert_from.h" -#include "libyuv/convert_from_argb.h" -#include "libyuv/cpu_id.h" -#include "libyuv/mjpeg_decoder.h" -#include "libyuv/planar_functions.h" -#include "libyuv/rotate.h" -#include "libyuv/rotate_argb.h" -#include "libyuv/row.h" -#include "libyuv/scale.h" -#include "libyuv/scale_argb.h" -#include "libyuv/scale_row.h" -#include "libyuv/version.h" -#include "libyuv/video_common.h" - -#endif // INCLUDE_LIBYUV_H_ diff --git a/third_party/libyuv/include/libyuv/basic_types.h b/third_party/libyuv/include/libyuv/basic_types.h deleted file mode 100644 index 5b760ee..0000000 --- a/third_party/libyuv/include/libyuv/basic_types.h +++ /dev/null @@ -1,118 +0,0 @@ -/* - * Copyright 2011 The LibYuv Project Authors. All rights reserved. - * - * Use of this source code is governed by a BSD-style license - * that can be found in the LICENSE file in the root of the source - * tree. An additional intellectual property rights grant can be found - * in the file PATENTS. All contributing project authors may - * be found in the AUTHORS file in the root of the source tree. - */ - -#ifndef INCLUDE_LIBYUV_BASIC_TYPES_H_ -#define INCLUDE_LIBYUV_BASIC_TYPES_H_ - -#include // for NULL, size_t - -#if defined(_MSC_VER) && (_MSC_VER < 1600) -#include // for uintptr_t on x86 -#else -#include // for uintptr_t -#endif - -#ifndef GG_LONGLONG -#ifndef INT_TYPES_DEFINED -#define INT_TYPES_DEFINED -#ifdef COMPILER_MSVC -typedef unsigned __int64 uint64; -typedef __int64 int64; -#ifndef INT64_C -#define INT64_C(x) x ## I64 -#endif -#ifndef UINT64_C -#define UINT64_C(x) x ## UI64 -#endif -#define INT64_F "I64" -#else // COMPILER_MSVC -#if defined(__LP64__) && !defined(__OpenBSD__) && !defined(__APPLE__) -typedef unsigned long uint64; // NOLINT -typedef long int64; // NOLINT -#ifndef INT64_C -#define INT64_C(x) x ## L -#endif -#ifndef UINT64_C -#define UINT64_C(x) x ## UL -#endif -#define INT64_F "l" -#else // defined(__LP64__) && !defined(__OpenBSD__) && !defined(__APPLE__) -typedef unsigned long long uint64; // NOLINT -typedef long long int64; // NOLINT -#ifndef INT64_C -#define INT64_C(x) x ## LL -#endif -#ifndef UINT64_C -#define UINT64_C(x) x ## ULL -#endif -#define INT64_F "ll" -#endif // __LP64__ -#endif // COMPILER_MSVC -typedef unsigned int uint32; -typedef int int32; -typedef unsigned short uint16; // NOLINT -typedef short int16; // NOLINT -typedef unsigned char uint8; -typedef signed char int8; -#endif // INT_TYPES_DEFINED -#endif // GG_LONGLONG - -// Detect compiler is for x86 or x64. -#if defined(__x86_64__) || defined(_M_X64) || \ - defined(__i386__) || defined(_M_IX86) -#define CPU_X86 1 -#endif -// Detect compiler is for ARM. -#if defined(__arm__) || defined(_M_ARM) -#define CPU_ARM 1 -#endif - -#ifndef ALIGNP -#ifdef __cplusplus -#define ALIGNP(p, t) \ - (reinterpret_cast(((reinterpret_cast(p) + \ - ((t) - 1)) & ~((t) - 1)))) -#else -#define ALIGNP(p, t) \ - ((uint8*)((((uintptr_t)(p) + ((t) - 1)) & ~((t) - 1)))) /* NOLINT */ -#endif -#endif - -#if !defined(LIBYUV_API) -#if defined(_WIN32) || defined(__CYGWIN__) -#if defined(LIBYUV_BUILDING_SHARED_LIBRARY) -#define LIBYUV_API __declspec(dllexport) -#elif defined(LIBYUV_USING_SHARED_LIBRARY) -#define LIBYUV_API __declspec(dllimport) -#else -#define LIBYUV_API -#endif // LIBYUV_BUILDING_SHARED_LIBRARY -#elif defined(__GNUC__) && (__GNUC__ >= 4) && !defined(__APPLE__) && \ - (defined(LIBYUV_BUILDING_SHARED_LIBRARY) || \ - defined(LIBYUV_USING_SHARED_LIBRARY)) -#define LIBYUV_API __attribute__ ((visibility ("default"))) -#else -#define LIBYUV_API -#endif // __GNUC__ -#endif // LIBYUV_API - -#define LIBYUV_BOOL int -#define LIBYUV_FALSE 0 -#define LIBYUV_TRUE 1 - -// Visual C x86 or GCC little endian. -#if defined(__x86_64__) || defined(_M_X64) || \ - defined(__i386__) || defined(_M_IX86) || \ - defined(__arm__) || defined(_M_ARM) || \ - (defined(__BYTE_ORDER__) && __BYTE_ORDER__ == __ORDER_LITTLE_ENDIAN__) -#define LIBYUV_LITTLE_ENDIAN -#endif - -#endif // INCLUDE_LIBYUV_BASIC_TYPES_H_ diff --git a/third_party/libyuv/include/libyuv/compare.h b/third_party/libyuv/include/libyuv/compare.h deleted file mode 100644 index 550712d..0000000 --- a/third_party/libyuv/include/libyuv/compare.h +++ /dev/null @@ -1,78 +0,0 @@ -/* - * Copyright 2011 The LibYuv Project Authors. All rights reserved. - * - * Use of this source code is governed by a BSD-style license - * that can be found in the LICENSE file in the root of the source - * tree. An additional intellectual property rights grant can be found - * in the file PATENTS. All contributing project authors may - * be found in the AUTHORS file in the root of the source tree. - */ - -#ifndef INCLUDE_LIBYUV_COMPARE_H_ -#define INCLUDE_LIBYUV_COMPARE_H_ - -#include "libyuv/basic_types.h" - -#ifdef __cplusplus -namespace libyuv { -extern "C" { -#endif - -// Compute a hash for specified memory. Seed of 5381 recommended. -LIBYUV_API -uint32 HashDjb2(const uint8* src, uint64 count, uint32 seed); - -// Scan an opaque argb image and return fourcc based on alpha offset. -// Returns FOURCC_ARGB, FOURCC_BGRA, or 0 if unknown. -LIBYUV_API -uint32 ARGBDetect(const uint8* argb, int stride_argb, int width, int height); - -// Sum Square Error - used to compute Mean Square Error or PSNR. -LIBYUV_API -uint64 ComputeSumSquareError(const uint8* src_a, - const uint8* src_b, int count); - -LIBYUV_API -uint64 ComputeSumSquareErrorPlane(const uint8* src_a, int stride_a, - const uint8* src_b, int stride_b, - int width, int height); - -static const int kMaxPsnr = 128; - -LIBYUV_API -double SumSquareErrorToPsnr(uint64 sse, uint64 count); - -LIBYUV_API -double CalcFramePsnr(const uint8* src_a, int stride_a, - const uint8* src_b, int stride_b, - int width, int height); - -LIBYUV_API -double I420Psnr(const uint8* src_y_a, int stride_y_a, - const uint8* src_u_a, int stride_u_a, - const uint8* src_v_a, int stride_v_a, - const uint8* src_y_b, int stride_y_b, - const uint8* src_u_b, int stride_u_b, - const uint8* src_v_b, int stride_v_b, - int width, int height); - -LIBYUV_API -double CalcFrameSsim(const uint8* src_a, int stride_a, - const uint8* src_b, int stride_b, - int width, int height); - -LIBYUV_API -double I420Ssim(const uint8* src_y_a, int stride_y_a, - const uint8* src_u_a, int stride_u_a, - const uint8* src_v_a, int stride_v_a, - const uint8* src_y_b, int stride_y_b, - const uint8* src_u_b, int stride_u_b, - const uint8* src_v_b, int stride_v_b, - int width, int height); - -#ifdef __cplusplus -} // extern "C" -} // namespace libyuv -#endif - -#endif // INCLUDE_LIBYUV_COMPARE_H_ diff --git a/third_party/libyuv/include/libyuv/compare_row.h b/third_party/libyuv/include/libyuv/compare_row.h deleted file mode 100644 index 781cad3..0000000 --- a/third_party/libyuv/include/libyuv/compare_row.h +++ /dev/null @@ -1,84 +0,0 @@ -/* - * Copyright 2013 The LibYuv Project Authors. All rights reserved. - * - * Use of this source code is governed by a BSD-style license - * that can be found in the LICENSE file in the root of the source - * tree. An additional intellectual property rights grant can be found - * in the file PATENTS. All contributing project authors may - * be found in the AUTHORS file in the root of the source tree. - */ - -#ifndef INCLUDE_LIBYUV_COMPARE_ROW_H_ -#define INCLUDE_LIBYUV_COMPARE_ROW_H_ - -#include "libyuv/basic_types.h" - -#ifdef __cplusplus -namespace libyuv { -extern "C" { -#endif - -#if defined(__pnacl__) || defined(__CLR_VER) || \ - (defined(__i386__) && !defined(__SSE2__)) -#define LIBYUV_DISABLE_X86 -#endif -// MemorySanitizer does not support assembly code yet. http://crbug.com/344505 -#if defined(__has_feature) -#if __has_feature(memory_sanitizer) -#define LIBYUV_DISABLE_X86 -#endif -#endif - -// Visual C 2012 required for AVX2. -#if defined(_M_IX86) && !defined(__clang__) && \ - defined(_MSC_VER) && _MSC_VER >= 1700 -#define VISUALC_HAS_AVX2 1 -#endif // VisualStudio >= 2012 - -// clang >= 3.4.0 required for AVX2. -#if defined(__clang__) && (defined(__x86_64__) || defined(__i386__)) -#if (__clang_major__ > 3) || (__clang_major__ == 3 && (__clang_minor__ >= 4)) -#define CLANG_HAS_AVX2 1 -#endif // clang >= 3.4 -#endif // __clang__ - -#if !defined(LIBYUV_DISABLE_X86) && \ - defined(_M_IX86) && (defined(VISUALC_HAS_AVX2) || defined(CLANG_HAS_AVX2)) -#define HAS_HASHDJB2_AVX2 -#endif - -// The following are available for Visual C and GCC: -#if !defined(LIBYUV_DISABLE_X86) && \ - (defined(__x86_64__) || (defined(__i386__) || defined(_M_IX86))) -#define HAS_HASHDJB2_SSE41 -#define HAS_SUMSQUAREERROR_SSE2 -#endif - -// The following are available for Visual C and clangcl 32 bit: -#if !defined(LIBYUV_DISABLE_X86) && defined(_M_IX86) && \ - (defined(VISUALC_HAS_AVX2) || defined(CLANG_HAS_AVX2)) -#define HAS_HASHDJB2_AVX2 -#define HAS_SUMSQUAREERROR_AVX2 -#endif - -// The following are available for Neon: -#if !defined(LIBYUV_DISABLE_NEON) && \ - (defined(__ARM_NEON__) || defined(LIBYUV_NEON) || defined(__aarch64__)) -#define HAS_SUMSQUAREERROR_NEON -#endif - -uint32 SumSquareError_C(const uint8* src_a, const uint8* src_b, int count); -uint32 SumSquareError_SSE2(const uint8* src_a, const uint8* src_b, int count); -uint32 SumSquareError_AVX2(const uint8* src_a, const uint8* src_b, int count); -uint32 SumSquareError_NEON(const uint8* src_a, const uint8* src_b, int count); - -uint32 HashDjb2_C(const uint8* src, int count, uint32 seed); -uint32 HashDjb2_SSE41(const uint8* src, int count, uint32 seed); -uint32 HashDjb2_AVX2(const uint8* src, int count, uint32 seed); - -#ifdef __cplusplus -} // extern "C" -} // namespace libyuv -#endif - -#endif // INCLUDE_LIBYUV_COMPARE_ROW_H_ diff --git a/third_party/libyuv/include/libyuv/convert.h b/third_party/libyuv/include/libyuv/convert.h deleted file mode 100644 index d444858..0000000 --- a/third_party/libyuv/include/libyuv/convert.h +++ /dev/null @@ -1,259 +0,0 @@ -/* - * Copyright 2011 The LibYuv Project Authors. All rights reserved. - * - * Use of this source code is governed by a BSD-style license - * that can be found in the LICENSE file in the root of the source - * tree. An additional intellectual property rights grant can be found - * in the file PATENTS. All contributing project authors may - * be found in the AUTHORS file in the root of the source tree. - */ - -#ifndef INCLUDE_LIBYUV_CONVERT_H_ -#define INCLUDE_LIBYUV_CONVERT_H_ - -#include "libyuv/basic_types.h" - -#include "libyuv/rotate.h" // For enum RotationMode. - -// TODO(fbarchard): fix WebRTC source to include following libyuv headers: -#include "libyuv/convert_argb.h" // For WebRTC I420ToARGB. b/620 -#include "libyuv/convert_from.h" // For WebRTC ConvertFromI420. b/620 -#include "libyuv/planar_functions.h" // For WebRTC I420Rect, CopyPlane. b/618 - -#ifdef __cplusplus -namespace libyuv { -extern "C" { -#endif - -// Convert I444 to I420. -LIBYUV_API -int I444ToI420(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_y, int dst_stride_y, - uint8* dst_u, int dst_stride_u, - uint8* dst_v, int dst_stride_v, - int width, int height); - -// Convert I422 to I420. -LIBYUV_API -int I422ToI420(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_y, int dst_stride_y, - uint8* dst_u, int dst_stride_u, - uint8* dst_v, int dst_stride_v, - int width, int height); - -// Convert I411 to I420. -LIBYUV_API -int I411ToI420(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_y, int dst_stride_y, - uint8* dst_u, int dst_stride_u, - uint8* dst_v, int dst_stride_v, - int width, int height); - -// Copy I420 to I420. -#define I420ToI420 I420Copy -LIBYUV_API -int I420Copy(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_y, int dst_stride_y, - uint8* dst_u, int dst_stride_u, - uint8* dst_v, int dst_stride_v, - int width, int height); - -// Convert I400 (grey) to I420. -LIBYUV_API -int I400ToI420(const uint8* src_y, int src_stride_y, - uint8* dst_y, int dst_stride_y, - uint8* dst_u, int dst_stride_u, - uint8* dst_v, int dst_stride_v, - int width, int height); - -#define J400ToJ420 I400ToI420 - -// Convert NV12 to I420. -LIBYUV_API -int NV12ToI420(const uint8* src_y, int src_stride_y, - const uint8* src_uv, int src_stride_uv, - uint8* dst_y, int dst_stride_y, - uint8* dst_u, int dst_stride_u, - uint8* dst_v, int dst_stride_v, - int width, int height); - -// Convert NV21 to I420. -LIBYUV_API -int NV21ToI420(const uint8* src_y, int src_stride_y, - const uint8* src_vu, int src_stride_vu, - uint8* dst_y, int dst_stride_y, - uint8* dst_u, int dst_stride_u, - uint8* dst_v, int dst_stride_v, - int width, int height); - -// Convert YUY2 to I420. -LIBYUV_API -int YUY2ToI420(const uint8* src_yuy2, int src_stride_yuy2, - uint8* dst_y, int dst_stride_y, - uint8* dst_u, int dst_stride_u, - uint8* dst_v, int dst_stride_v, - int width, int height); - -// Convert UYVY to I420. -LIBYUV_API -int UYVYToI420(const uint8* src_uyvy, int src_stride_uyvy, - uint8* dst_y, int dst_stride_y, - uint8* dst_u, int dst_stride_u, - uint8* dst_v, int dst_stride_v, - int width, int height); - -// Convert M420 to I420. -LIBYUV_API -int M420ToI420(const uint8* src_m420, int src_stride_m420, - uint8* dst_y, int dst_stride_y, - uint8* dst_u, int dst_stride_u, - uint8* dst_v, int dst_stride_v, - int width, int height); - -// Convert Android420 to I420. -LIBYUV_API -int Android420ToI420(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - int pixel_stride_uv, - uint8* dst_y, int dst_stride_y, - uint8* dst_u, int dst_stride_u, - uint8* dst_v, int dst_stride_v, - int width, int height); - -// ARGB little endian (bgra in memory) to I420. -LIBYUV_API -int ARGBToI420(const uint8* src_frame, int src_stride_frame, - uint8* dst_y, int dst_stride_y, - uint8* dst_u, int dst_stride_u, - uint8* dst_v, int dst_stride_v, - int width, int height); - -// BGRA little endian (argb in memory) to I420. -LIBYUV_API -int BGRAToI420(const uint8* src_frame, int src_stride_frame, - uint8* dst_y, int dst_stride_y, - uint8* dst_u, int dst_stride_u, - uint8* dst_v, int dst_stride_v, - int width, int height); - -// ABGR little endian (rgba in memory) to I420. -LIBYUV_API -int ABGRToI420(const uint8* src_frame, int src_stride_frame, - uint8* dst_y, int dst_stride_y, - uint8* dst_u, int dst_stride_u, - uint8* dst_v, int dst_stride_v, - int width, int height); - -// RGBA little endian (abgr in memory) to I420. -LIBYUV_API -int RGBAToI420(const uint8* src_frame, int src_stride_frame, - uint8* dst_y, int dst_stride_y, - uint8* dst_u, int dst_stride_u, - uint8* dst_v, int dst_stride_v, - int width, int height); - -// RGB little endian (bgr in memory) to I420. -LIBYUV_API -int RGB24ToI420(const uint8* src_frame, int src_stride_frame, - uint8* dst_y, int dst_stride_y, - uint8* dst_u, int dst_stride_u, - uint8* dst_v, int dst_stride_v, - int width, int height); - -// RGB big endian (rgb in memory) to I420. -LIBYUV_API -int RAWToI420(const uint8* src_frame, int src_stride_frame, - uint8* dst_y, int dst_stride_y, - uint8* dst_u, int dst_stride_u, - uint8* dst_v, int dst_stride_v, - int width, int height); - -// RGB16 (RGBP fourcc) little endian to I420. -LIBYUV_API -int RGB565ToI420(const uint8* src_frame, int src_stride_frame, - uint8* dst_y, int dst_stride_y, - uint8* dst_u, int dst_stride_u, - uint8* dst_v, int dst_stride_v, - int width, int height); - -// RGB15 (RGBO fourcc) little endian to I420. -LIBYUV_API -int ARGB1555ToI420(const uint8* src_frame, int src_stride_frame, - uint8* dst_y, int dst_stride_y, - uint8* dst_u, int dst_stride_u, - uint8* dst_v, int dst_stride_v, - int width, int height); - -// RGB12 (R444 fourcc) little endian to I420. -LIBYUV_API -int ARGB4444ToI420(const uint8* src_frame, int src_stride_frame, - uint8* dst_y, int dst_stride_y, - uint8* dst_u, int dst_stride_u, - uint8* dst_v, int dst_stride_v, - int width, int height); - -#ifdef HAVE_JPEG -// src_width/height provided by capture. -// dst_width/height for clipping determine final size. -LIBYUV_API -int MJPGToI420(const uint8* sample, size_t sample_size, - uint8* dst_y, int dst_stride_y, - uint8* dst_u, int dst_stride_u, - uint8* dst_v, int dst_stride_v, - int src_width, int src_height, - int dst_width, int dst_height); - -// Query size of MJPG in pixels. -LIBYUV_API -int MJPGSize(const uint8* sample, size_t sample_size, - int* width, int* height); -#endif - -// Convert camera sample to I420 with cropping, rotation and vertical flip. -// "src_size" is needed to parse MJPG. -// "dst_stride_y" number of bytes in a row of the dst_y plane. -// Normally this would be the same as dst_width, with recommended alignment -// to 16 bytes for better efficiency. -// If rotation of 90 or 270 is used, stride is affected. The caller should -// allocate the I420 buffer according to rotation. -// "dst_stride_u" number of bytes in a row of the dst_u plane. -// Normally this would be the same as (dst_width + 1) / 2, with -// recommended alignment to 16 bytes for better efficiency. -// If rotation of 90 or 270 is used, stride is affected. -// "crop_x" and "crop_y" are starting position for cropping. -// To center, crop_x = (src_width - dst_width) / 2 -// crop_y = (src_height - dst_height) / 2 -// "src_width" / "src_height" is size of src_frame in pixels. -// "src_height" can be negative indicating a vertically flipped image source. -// "crop_width" / "crop_height" is the size to crop the src to. -// Must be less than or equal to src_width/src_height -// Cropping parameters are pre-rotation. -// "rotation" can be 0, 90, 180 or 270. -// "format" is a fourcc. ie 'I420', 'YUY2' -// Returns 0 for successful; -1 for invalid parameter. Non-zero for failure. -LIBYUV_API -int ConvertToI420(const uint8* src_frame, size_t src_size, - uint8* dst_y, int dst_stride_y, - uint8* dst_u, int dst_stride_u, - uint8* dst_v, int dst_stride_v, - int crop_x, int crop_y, - int src_width, int src_height, - int crop_width, int crop_height, - enum RotationMode rotation, - uint32 format); - -#ifdef __cplusplus -} // extern "C" -} // namespace libyuv -#endif - -#endif // INCLUDE_LIBYUV_CONVERT_H_ diff --git a/third_party/libyuv/include/libyuv/convert_argb.h b/third_party/libyuv/include/libyuv/convert_argb.h deleted file mode 100644 index dc03ac8..0000000 --- a/third_party/libyuv/include/libyuv/convert_argb.h +++ /dev/null @@ -1,319 +0,0 @@ -/* - * Copyright 2012 The LibYuv Project Authors. All rights reserved. - * - * Use of this source code is governed by a BSD-style license - * that can be found in the LICENSE file in the root of the source - * tree. An additional intellectual property rights grant can be found - * in the file PATENTS. All contributing project authors may - * be found in the AUTHORS file in the root of the source tree. - */ - -#ifndef INCLUDE_LIBYUV_CONVERT_ARGB_H_ -#define INCLUDE_LIBYUV_CONVERT_ARGB_H_ - -#include "libyuv/basic_types.h" - -#include "libyuv/rotate.h" // For enum RotationMode. - -// TODO(fbarchard): This set of functions should exactly match convert.h -// TODO(fbarchard): Add tests. Create random content of right size and convert -// with C vs Opt and or to I420 and compare. -// TODO(fbarchard): Some of these functions lack parameter setting. - -#ifdef __cplusplus -namespace libyuv { -extern "C" { -#endif - -// Alias. -#define ARGBToARGB ARGBCopy - -// Copy ARGB to ARGB. -LIBYUV_API -int ARGBCopy(const uint8* src_argb, int src_stride_argb, - uint8* dst_argb, int dst_stride_argb, - int width, int height); - -// Convert I420 to ARGB. -LIBYUV_API -int I420ToARGB(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_argb, int dst_stride_argb, - int width, int height); - -// Duplicate prototype for function in convert_from.h for remoting. -LIBYUV_API -int I420ToABGR(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_argb, int dst_stride_argb, - int width, int height); - -// Convert I422 to ARGB. -LIBYUV_API -int I422ToARGB(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_argb, int dst_stride_argb, - int width, int height); - -// Convert I444 to ARGB. -LIBYUV_API -int I444ToARGB(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_argb, int dst_stride_argb, - int width, int height); - -// Convert J444 to ARGB. -LIBYUV_API -int J444ToARGB(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_argb, int dst_stride_argb, - int width, int height); - -// Convert I444 to ABGR. -LIBYUV_API -int I444ToABGR(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_abgr, int dst_stride_abgr, - int width, int height); - -// Convert I411 to ARGB. -LIBYUV_API -int I411ToARGB(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_argb, int dst_stride_argb, - int width, int height); - -// Convert I420 with Alpha to preattenuated ARGB. -LIBYUV_API -int I420AlphaToARGB(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - const uint8* src_a, int src_stride_a, - uint8* dst_argb, int dst_stride_argb, - int width, int height, int attenuate); - -// Convert I420 with Alpha to preattenuated ABGR. -LIBYUV_API -int I420AlphaToABGR(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - const uint8* src_a, int src_stride_a, - uint8* dst_abgr, int dst_stride_abgr, - int width, int height, int attenuate); - -// Convert I400 (grey) to ARGB. Reverse of ARGBToI400. -LIBYUV_API -int I400ToARGB(const uint8* src_y, int src_stride_y, - uint8* dst_argb, int dst_stride_argb, - int width, int height); - -// Convert J400 (jpeg grey) to ARGB. -LIBYUV_API -int J400ToARGB(const uint8* src_y, int src_stride_y, - uint8* dst_argb, int dst_stride_argb, - int width, int height); - -// Alias. -#define YToARGB I400ToARGB - -// Convert NV12 to ARGB. -LIBYUV_API -int NV12ToARGB(const uint8* src_y, int src_stride_y, - const uint8* src_uv, int src_stride_uv, - uint8* dst_argb, int dst_stride_argb, - int width, int height); - -// Convert NV21 to ARGB. -LIBYUV_API -int NV21ToARGB(const uint8* src_y, int src_stride_y, - const uint8* src_vu, int src_stride_vu, - uint8* dst_argb, int dst_stride_argb, - int width, int height); - -// Convert M420 to ARGB. -LIBYUV_API -int M420ToARGB(const uint8* src_m420, int src_stride_m420, - uint8* dst_argb, int dst_stride_argb, - int width, int height); - -// Convert YUY2 to ARGB. -LIBYUV_API -int YUY2ToARGB(const uint8* src_yuy2, int src_stride_yuy2, - uint8* dst_argb, int dst_stride_argb, - int width, int height); - -// Convert UYVY to ARGB. -LIBYUV_API -int UYVYToARGB(const uint8* src_uyvy, int src_stride_uyvy, - uint8* dst_argb, int dst_stride_argb, - int width, int height); - -// Convert J420 to ARGB. -LIBYUV_API -int J420ToARGB(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_argb, int dst_stride_argb, - int width, int height); - -// Convert J422 to ARGB. -LIBYUV_API -int J422ToARGB(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_argb, int dst_stride_argb, - int width, int height); - -// Convert J420 to ABGR. -LIBYUV_API -int J420ToABGR(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_abgr, int dst_stride_abgr, - int width, int height); - -// Convert J422 to ABGR. -LIBYUV_API -int J422ToABGR(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_abgr, int dst_stride_abgr, - int width, int height); - -// Convert H420 to ARGB. -LIBYUV_API -int H420ToARGB(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_argb, int dst_stride_argb, - int width, int height); - -// Convert H422 to ARGB. -LIBYUV_API -int H422ToARGB(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_argb, int dst_stride_argb, - int width, int height); - -// Convert H420 to ABGR. -LIBYUV_API -int H420ToABGR(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_abgr, int dst_stride_abgr, - int width, int height); - -// Convert H422 to ABGR. -LIBYUV_API -int H422ToABGR(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_abgr, int dst_stride_abgr, - int width, int height); - -// BGRA little endian (argb in memory) to ARGB. -LIBYUV_API -int BGRAToARGB(const uint8* src_frame, int src_stride_frame, - uint8* dst_argb, int dst_stride_argb, - int width, int height); - -// ABGR little endian (rgba in memory) to ARGB. -LIBYUV_API -int ABGRToARGB(const uint8* src_frame, int src_stride_frame, - uint8* dst_argb, int dst_stride_argb, - int width, int height); - -// RGBA little endian (abgr in memory) to ARGB. -LIBYUV_API -int RGBAToARGB(const uint8* src_frame, int src_stride_frame, - uint8* dst_argb, int dst_stride_argb, - int width, int height); - -// Deprecated function name. -#define BG24ToARGB RGB24ToARGB - -// RGB little endian (bgr in memory) to ARGB. -LIBYUV_API -int RGB24ToARGB(const uint8* src_frame, int src_stride_frame, - uint8* dst_argb, int dst_stride_argb, - int width, int height); - -// RGB big endian (rgb in memory) to ARGB. -LIBYUV_API -int RAWToARGB(const uint8* src_frame, int src_stride_frame, - uint8* dst_argb, int dst_stride_argb, - int width, int height); - -// RGB16 (RGBP fourcc) little endian to ARGB. -LIBYUV_API -int RGB565ToARGB(const uint8* src_frame, int src_stride_frame, - uint8* dst_argb, int dst_stride_argb, - int width, int height); - -// RGB15 (RGBO fourcc) little endian to ARGB. -LIBYUV_API -int ARGB1555ToARGB(const uint8* src_frame, int src_stride_frame, - uint8* dst_argb, int dst_stride_argb, - int width, int height); - -// RGB12 (R444 fourcc) little endian to ARGB. -LIBYUV_API -int ARGB4444ToARGB(const uint8* src_frame, int src_stride_frame, - uint8* dst_argb, int dst_stride_argb, - int width, int height); - -#ifdef HAVE_JPEG -// src_width/height provided by capture -// dst_width/height for clipping determine final size. -LIBYUV_API -int MJPGToARGB(const uint8* sample, size_t sample_size, - uint8* dst_argb, int dst_stride_argb, - int src_width, int src_height, - int dst_width, int dst_height); -#endif - -// Convert camera sample to ARGB with cropping, rotation and vertical flip. -// "src_size" is needed to parse MJPG. -// "dst_stride_argb" number of bytes in a row of the dst_argb plane. -// Normally this would be the same as dst_width, with recommended alignment -// to 16 bytes for better efficiency. -// If rotation of 90 or 270 is used, stride is affected. The caller should -// allocate the I420 buffer according to rotation. -// "dst_stride_u" number of bytes in a row of the dst_u plane. -// Normally this would be the same as (dst_width + 1) / 2, with -// recommended alignment to 16 bytes for better efficiency. -// If rotation of 90 or 270 is used, stride is affected. -// "crop_x" and "crop_y" are starting position for cropping. -// To center, crop_x = (src_width - dst_width) / 2 -// crop_y = (src_height - dst_height) / 2 -// "src_width" / "src_height" is size of src_frame in pixels. -// "src_height" can be negative indicating a vertically flipped image source. -// "crop_width" / "crop_height" is the size to crop the src to. -// Must be less than or equal to src_width/src_height -// Cropping parameters are pre-rotation. -// "rotation" can be 0, 90, 180 or 270. -// "format" is a fourcc. ie 'I420', 'YUY2' -// Returns 0 for successful; -1 for invalid parameter. Non-zero for failure. -LIBYUV_API -int ConvertToARGB(const uint8* src_frame, size_t src_size, - uint8* dst_argb, int dst_stride_argb, - int crop_x, int crop_y, - int src_width, int src_height, - int crop_width, int crop_height, - enum RotationMode rotation, - uint32 format); - -#ifdef __cplusplus -} // extern "C" -} // namespace libyuv -#endif - -#endif // INCLUDE_LIBYUV_CONVERT_ARGB_H_ diff --git a/third_party/libyuv/include/libyuv/convert_from.h b/third_party/libyuv/include/libyuv/convert_from.h deleted file mode 100644 index 59c4047..0000000 --- a/third_party/libyuv/include/libyuv/convert_from.h +++ /dev/null @@ -1,179 +0,0 @@ -/* - * Copyright 2011 The LibYuv Project Authors. All rights reserved. - * - * Use of this source code is governed by a BSD-style license - * that can be found in the LICENSE file in the root of the source - * tree. An additional intellectual property rights grant can be found - * in the file PATENTS. All contributing project authors may - * be found in the AUTHORS file in the root of the source tree. - */ - -#ifndef INCLUDE_LIBYUV_CONVERT_FROM_H_ -#define INCLUDE_LIBYUV_CONVERT_FROM_H_ - -#include "libyuv/basic_types.h" -#include "libyuv/rotate.h" - -#ifdef __cplusplus -namespace libyuv { -extern "C" { -#endif - -// See Also convert.h for conversions from formats to I420. - -// I420Copy in convert to I420ToI420. - -LIBYUV_API -int I420ToI422(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_y, int dst_stride_y, - uint8* dst_u, int dst_stride_u, - uint8* dst_v, int dst_stride_v, - int width, int height); - -LIBYUV_API -int I420ToI444(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_y, int dst_stride_y, - uint8* dst_u, int dst_stride_u, - uint8* dst_v, int dst_stride_v, - int width, int height); - -LIBYUV_API -int I420ToI411(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_y, int dst_stride_y, - uint8* dst_u, int dst_stride_u, - uint8* dst_v, int dst_stride_v, - int width, int height); - -// Copy to I400. Source can be I420, I422, I444, I400, NV12 or NV21. -LIBYUV_API -int I400Copy(const uint8* src_y, int src_stride_y, - uint8* dst_y, int dst_stride_y, - int width, int height); - -LIBYUV_API -int I420ToNV12(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_y, int dst_stride_y, - uint8* dst_uv, int dst_stride_uv, - int width, int height); - -LIBYUV_API -int I420ToNV21(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_y, int dst_stride_y, - uint8* dst_vu, int dst_stride_vu, - int width, int height); - -LIBYUV_API -int I420ToYUY2(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_frame, int dst_stride_frame, - int width, int height); - -LIBYUV_API -int I420ToUYVY(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_frame, int dst_stride_frame, - int width, int height); - -LIBYUV_API -int I420ToARGB(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_argb, int dst_stride_argb, - int width, int height); - -LIBYUV_API -int I420ToBGRA(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_argb, int dst_stride_argb, - int width, int height); - -LIBYUV_API -int I420ToABGR(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_argb, int dst_stride_argb, - int width, int height); - -LIBYUV_API -int I420ToRGBA(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_rgba, int dst_stride_rgba, - int width, int height); - -LIBYUV_API -int I420ToRGB24(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_frame, int dst_stride_frame, - int width, int height); - -LIBYUV_API -int I420ToRAW(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_frame, int dst_stride_frame, - int width, int height); - -LIBYUV_API -int I420ToRGB565(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_frame, int dst_stride_frame, - int width, int height); - -// Convert I420 To RGB565 with 4x4 dither matrix (16 bytes). -// Values in dither matrix from 0 to 7 recommended. -// The order of the dither matrix is first byte is upper left. - -LIBYUV_API -int I420ToRGB565Dither(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_frame, int dst_stride_frame, - const uint8* dither4x4, int width, int height); - -LIBYUV_API -int I420ToARGB1555(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_frame, int dst_stride_frame, - int width, int height); - -LIBYUV_API -int I420ToARGB4444(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_frame, int dst_stride_frame, - int width, int height); - -// Convert I420 to specified format. -// "dst_sample_stride" is bytes in a row for the destination. Pass 0 if the -// buffer has contiguous rows. Can be negative. A multiple of 16 is optimal. -LIBYUV_API -int ConvertFromI420(const uint8* y, int y_stride, - const uint8* u, int u_stride, - const uint8* v, int v_stride, - uint8* dst_sample, int dst_sample_stride, - int width, int height, - uint32 format); - -#ifdef __cplusplus -} // extern "C" -} // namespace libyuv -#endif - -#endif // INCLUDE_LIBYUV_CONVERT_FROM_H_ diff --git a/third_party/libyuv/include/libyuv/convert_from_argb.h b/third_party/libyuv/include/libyuv/convert_from_argb.h deleted file mode 100644 index 8d7f02f..0000000 --- a/third_party/libyuv/include/libyuv/convert_from_argb.h +++ /dev/null @@ -1,190 +0,0 @@ -/* - * Copyright 2012 The LibYuv Project Authors. All rights reserved. - * - * Use of this source code is governed by a BSD-style license - * that can be found in the LICENSE file in the root of the source - * tree. An additional intellectual property rights grant can be found - * in the file PATENTS. All contributing project authors may - * be found in the AUTHORS file in the root of the source tree. - */ - -#ifndef INCLUDE_LIBYUV_CONVERT_FROM_ARGB_H_ -#define INCLUDE_LIBYUV_CONVERT_FROM_ARGB_H_ - -#include "libyuv/basic_types.h" - -#ifdef __cplusplus -namespace libyuv { -extern "C" { -#endif - -// Copy ARGB to ARGB. -#define ARGBToARGB ARGBCopy -LIBYUV_API -int ARGBCopy(const uint8* src_argb, int src_stride_argb, - uint8* dst_argb, int dst_stride_argb, - int width, int height); - -// Convert ARGB To BGRA. -LIBYUV_API -int ARGBToBGRA(const uint8* src_argb, int src_stride_argb, - uint8* dst_bgra, int dst_stride_bgra, - int width, int height); - -// Convert ARGB To ABGR. -LIBYUV_API -int ARGBToABGR(const uint8* src_argb, int src_stride_argb, - uint8* dst_abgr, int dst_stride_abgr, - int width, int height); - -// Convert ARGB To RGBA. -LIBYUV_API -int ARGBToRGBA(const uint8* src_argb, int src_stride_argb, - uint8* dst_rgba, int dst_stride_rgba, - int width, int height); - -// Convert ARGB To RGB24. -LIBYUV_API -int ARGBToRGB24(const uint8* src_argb, int src_stride_argb, - uint8* dst_rgb24, int dst_stride_rgb24, - int width, int height); - -// Convert ARGB To RAW. -LIBYUV_API -int ARGBToRAW(const uint8* src_argb, int src_stride_argb, - uint8* dst_rgb, int dst_stride_rgb, - int width, int height); - -// Convert ARGB To RGB565. -LIBYUV_API -int ARGBToRGB565(const uint8* src_argb, int src_stride_argb, - uint8* dst_rgb565, int dst_stride_rgb565, - int width, int height); - -// Convert ARGB To RGB565 with 4x4 dither matrix (16 bytes). -// Values in dither matrix from 0 to 7 recommended. -// The order of the dither matrix is first byte is upper left. -// TODO(fbarchard): Consider pointer to 2d array for dither4x4. -// const uint8(*dither)[4][4]; -LIBYUV_API -int ARGBToRGB565Dither(const uint8* src_argb, int src_stride_argb, - uint8* dst_rgb565, int dst_stride_rgb565, - const uint8* dither4x4, int width, int height); - -// Convert ARGB To ARGB1555. -LIBYUV_API -int ARGBToARGB1555(const uint8* src_argb, int src_stride_argb, - uint8* dst_argb1555, int dst_stride_argb1555, - int width, int height); - -// Convert ARGB To ARGB4444. -LIBYUV_API -int ARGBToARGB4444(const uint8* src_argb, int src_stride_argb, - uint8* dst_argb4444, int dst_stride_argb4444, - int width, int height); - -// Convert ARGB To I444. -LIBYUV_API -int ARGBToI444(const uint8* src_argb, int src_stride_argb, - uint8* dst_y, int dst_stride_y, - uint8* dst_u, int dst_stride_u, - uint8* dst_v, int dst_stride_v, - int width, int height); - -// Convert ARGB To I422. -LIBYUV_API -int ARGBToI422(const uint8* src_argb, int src_stride_argb, - uint8* dst_y, int dst_stride_y, - uint8* dst_u, int dst_stride_u, - uint8* dst_v, int dst_stride_v, - int width, int height); - -// Convert ARGB To I420. (also in convert.h) -LIBYUV_API -int ARGBToI420(const uint8* src_argb, int src_stride_argb, - uint8* dst_y, int dst_stride_y, - uint8* dst_u, int dst_stride_u, - uint8* dst_v, int dst_stride_v, - int width, int height); - -// Convert ARGB to J420. (JPeg full range I420). -LIBYUV_API -int ARGBToJ420(const uint8* src_argb, int src_stride_argb, - uint8* dst_yj, int dst_stride_yj, - uint8* dst_u, int dst_stride_u, - uint8* dst_v, int dst_stride_v, - int width, int height); - -// Convert ARGB to J422. -LIBYUV_API -int ARGBToJ422(const uint8* src_argb, int src_stride_argb, - uint8* dst_yj, int dst_stride_yj, - uint8* dst_u, int dst_stride_u, - uint8* dst_v, int dst_stride_v, - int width, int height); - -// Convert ARGB To I411. -LIBYUV_API -int ARGBToI411(const uint8* src_argb, int src_stride_argb, - uint8* dst_y, int dst_stride_y, - uint8* dst_u, int dst_stride_u, - uint8* dst_v, int dst_stride_v, - int width, int height); - -// Convert ARGB to J400. (JPeg full range). -LIBYUV_API -int ARGBToJ400(const uint8* src_argb, int src_stride_argb, - uint8* dst_yj, int dst_stride_yj, - int width, int height); - -// Convert ARGB to I400. -LIBYUV_API -int ARGBToI400(const uint8* src_argb, int src_stride_argb, - uint8* dst_y, int dst_stride_y, - int width, int height); - -// Convert ARGB to G. (Reverse of J400toARGB, which replicates G back to ARGB) -LIBYUV_API -int ARGBToG(const uint8* src_argb, int src_stride_argb, - uint8* dst_g, int dst_stride_g, - int width, int height); - -// Convert ARGB To NV12. -LIBYUV_API -int ARGBToNV12(const uint8* src_argb, int src_stride_argb, - uint8* dst_y, int dst_stride_y, - uint8* dst_uv, int dst_stride_uv, - int width, int height); - -// Convert ARGB To NV21. -LIBYUV_API -int ARGBToNV21(const uint8* src_argb, int src_stride_argb, - uint8* dst_y, int dst_stride_y, - uint8* dst_vu, int dst_stride_vu, - int width, int height); - -// Convert ARGB To NV21. -LIBYUV_API -int ARGBToNV21(const uint8* src_argb, int src_stride_argb, - uint8* dst_y, int dst_stride_y, - uint8* dst_vu, int dst_stride_vu, - int width, int height); - -// Convert ARGB To YUY2. -LIBYUV_API -int ARGBToYUY2(const uint8* src_argb, int src_stride_argb, - uint8* dst_yuy2, int dst_stride_yuy2, - int width, int height); - -// Convert ARGB To UYVY. -LIBYUV_API -int ARGBToUYVY(const uint8* src_argb, int src_stride_argb, - uint8* dst_uyvy, int dst_stride_uyvy, - int width, int height); - -#ifdef __cplusplus -} // extern "C" -} // namespace libyuv -#endif - -#endif // INCLUDE_LIBYUV_CONVERT_FROM_ARGB_H_ diff --git a/third_party/libyuv/include/libyuv/cpu_id.h b/third_party/libyuv/include/libyuv/cpu_id.h deleted file mode 100644 index 7c6c9ae..0000000 --- a/third_party/libyuv/include/libyuv/cpu_id.h +++ /dev/null @@ -1,81 +0,0 @@ -/* - * Copyright 2011 The LibYuv Project Authors. All rights reserved. - * - * Use of this source code is governed by a BSD-style license - * that can be found in the LICENSE file in the root of the source - * tree. An additional intellectual property rights grant can be found - * in the file PATENTS. All contributing project authors may - * be found in the AUTHORS file in the root of the source tree. - */ - -#ifndef INCLUDE_LIBYUV_CPU_ID_H_ -#define INCLUDE_LIBYUV_CPU_ID_H_ - -#include "libyuv/basic_types.h" - -#ifdef __cplusplus -namespace libyuv { -extern "C" { -#endif - -// Internal flag to indicate cpuid requires initialization. -static const int kCpuInitialized = 0x1; - -// These flags are only valid on ARM processors. -static const int kCpuHasARM = 0x2; -static const int kCpuHasNEON = 0x4; -// 0x8 reserved for future ARM flag. - -// These flags are only valid on x86 processors. -static const int kCpuHasX86 = 0x10; -static const int kCpuHasSSE2 = 0x20; -static const int kCpuHasSSSE3 = 0x40; -static const int kCpuHasSSE41 = 0x80; -static const int kCpuHasSSE42 = 0x100; -static const int kCpuHasAVX = 0x200; -static const int kCpuHasAVX2 = 0x400; -static const int kCpuHasERMS = 0x800; -static const int kCpuHasFMA3 = 0x1000; -static const int kCpuHasAVX3 = 0x2000; -// 0x2000, 0x4000, 0x8000 reserved for future X86 flags. - -// These flags are only valid on MIPS processors. -static const int kCpuHasMIPS = 0x10000; -static const int kCpuHasDSPR2 = 0x20000; -static const int kCpuHasMSA = 0x40000; - -// Internal function used to auto-init. -LIBYUV_API -int InitCpuFlags(void); - -// Internal function for parsing /proc/cpuinfo. -LIBYUV_API -int ArmCpuCaps(const char* cpuinfo_name); - -// Detect CPU has SSE2 etc. -// Test_flag parameter should be one of kCpuHas constants above. -// returns non-zero if instruction set is detected -static __inline int TestCpuFlag(int test_flag) { - LIBYUV_API extern int cpu_info_; - return (!cpu_info_ ? InitCpuFlags() : cpu_info_) & test_flag; -} - -// For testing, allow CPU flags to be disabled. -// ie MaskCpuFlags(~kCpuHasSSSE3) to disable SSSE3. -// MaskCpuFlags(-1) to enable all cpu specific optimizations. -// MaskCpuFlags(1) to disable all cpu specific optimizations. -LIBYUV_API -void MaskCpuFlags(int enable_flags); - -// Low level cpuid for X86. Returns zeros on other CPUs. -// eax is the info type that you want. -// ecx is typically the cpu number, and should normally be zero. -LIBYUV_API -void CpuId(uint32 eax, uint32 ecx, uint32* cpu_info); - -#ifdef __cplusplus -} // extern "C" -} // namespace libyuv -#endif - -#endif // INCLUDE_LIBYUV_CPU_ID_H_ diff --git a/third_party/libyuv/include/libyuv/macros_msa.h b/third_party/libyuv/include/libyuv/macros_msa.h deleted file mode 100644 index 92ed21c..0000000 --- a/third_party/libyuv/include/libyuv/macros_msa.h +++ /dev/null @@ -1,76 +0,0 @@ -/* - * Copyright 2016 The LibYuv Project Authors. All rights reserved. - * - * Use of this source code is governed by a BSD-style license - * that can be found in the LICENSE file in the root of the source - * tree. An additional intellectual property rights grant can be found - * in the file PATENTS. All contributing project authors may - * be found in the AUTHORS file in the root of the source tree. - */ - -#ifndef INCLUDE_LIBYUV_MACROS_MSA_H_ -#define INCLUDE_LIBYUV_MACROS_MSA_H_ - -#if !defined(LIBYUV_DISABLE_MSA) && defined(__mips_msa) -#include -#include - -#define LD_B(RTYPE, psrc) *((RTYPE*)(psrc)) /* NOLINT */ -#define LD_UB(...) LD_B(v16u8, __VA_ARGS__) - -#define ST_B(RTYPE, in, pdst) *((RTYPE*)(pdst)) = (in) /* NOLINT */ -#define ST_UB(...) ST_B(v16u8, __VA_ARGS__) - -/* Description : Load two vectors with 16 'byte' sized elements - Arguments : Inputs - psrc, stride - Outputs - out0, out1 - Return Type - as per RTYPE - Details : Load 16 byte elements in 'out0' from (psrc) - Load 16 byte elements in 'out1' from (psrc + stride) -*/ -#define LD_B2(RTYPE, psrc, stride, out0, out1) { \ - out0 = LD_B(RTYPE, (psrc)); \ - out1 = LD_B(RTYPE, (psrc) + stride); \ -} -#define LD_UB2(...) LD_B2(v16u8, __VA_ARGS__) - -#define LD_B4(RTYPE, psrc, stride, out0, out1, out2, out3) { \ - LD_B2(RTYPE, (psrc), stride, out0, out1); \ - LD_B2(RTYPE, (psrc) + 2 * stride , stride, out2, out3); \ -} -#define LD_UB4(...) LD_B4(v16u8, __VA_ARGS__) - -/* Description : Store two vectors with stride each having 16 'byte' sized - elements - Arguments : Inputs - in0, in1, pdst, stride - Details : Store 16 byte elements from 'in0' to (pdst) - Store 16 byte elements from 'in1' to (pdst + stride) -*/ -#define ST_B2(RTYPE, in0, in1, pdst, stride) { \ - ST_B(RTYPE, in0, (pdst)); \ - ST_B(RTYPE, in1, (pdst) + stride); \ -} -#define ST_UB2(...) ST_B2(v16u8, __VA_ARGS__) -# -#define ST_B4(RTYPE, in0, in1, in2, in3, pdst, stride) { \ - ST_B2(RTYPE, in0, in1, (pdst), stride); \ - ST_B2(RTYPE, in2, in3, (pdst) + 2 * stride, stride); \ -} -#define ST_UB4(...) ST_B4(v16u8, __VA_ARGS__) -# -/* Description : Shuffle byte vector elements as per mask vector - Arguments : Inputs - in0, in1, in2, in3, mask0, mask1 - Outputs - out0, out1 - Return Type - as per RTYPE - Details : Byte elements from 'in0' & 'in1' are copied selectively to - 'out0' as per control vector 'mask0' -*/ -#define VSHF_B2(RTYPE, in0, in1, in2, in3, mask0, mask1, out0, out1) { \ - out0 = (RTYPE) __msa_vshf_b((v16i8) mask0, (v16i8) in1, (v16i8) in0); \ - out1 = (RTYPE) __msa_vshf_b((v16i8) mask1, (v16i8) in3, (v16i8) in2); \ -} -#define VSHF_B2_UB(...) VSHF_B2(v16u8, __VA_ARGS__) - -#endif /* !defined(LIBYUV_DISABLE_MSA) && defined(__mips_msa) */ - -#endif // INCLUDE_LIBYUV_MACROS_MSA_H_ diff --git a/third_party/libyuv/include/libyuv/mjpeg_decoder.h b/third_party/libyuv/include/libyuv/mjpeg_decoder.h deleted file mode 100644 index 4975bae..0000000 --- a/third_party/libyuv/include/libyuv/mjpeg_decoder.h +++ /dev/null @@ -1,192 +0,0 @@ -/* - * Copyright 2012 The LibYuv Project Authors. All rights reserved. - * - * Use of this source code is governed by a BSD-style license - * that can be found in the LICENSE file in the root of the source - * tree. An additional intellectual property rights grant can be found - * in the file PATENTS. All contributing project authors may - * be found in the AUTHORS file in the root of the source tree. - */ - -#ifndef INCLUDE_LIBYUV_MJPEG_DECODER_H_ -#define INCLUDE_LIBYUV_MJPEG_DECODER_H_ - -#include "libyuv/basic_types.h" - -#ifdef __cplusplus -// NOTE: For a simplified public API use convert.h MJPGToI420(). - -struct jpeg_common_struct; -struct jpeg_decompress_struct; -struct jpeg_source_mgr; - -namespace libyuv { - -#ifdef __cplusplus -extern "C" { -#endif - -LIBYUV_BOOL ValidateJpeg(const uint8* sample, size_t sample_size); - -#ifdef __cplusplus -} // extern "C" -#endif - -static const uint32 kUnknownDataSize = 0xFFFFFFFF; - -enum JpegSubsamplingType { - kJpegYuv420, - kJpegYuv422, - kJpegYuv411, - kJpegYuv444, - kJpegYuv400, - kJpegUnknown -}; - -struct Buffer { - const uint8* data; - int len; -}; - -struct BufferVector { - Buffer* buffers; - int len; - int pos; -}; - -struct SetJmpErrorMgr; - -// MJPEG ("Motion JPEG") is a pseudo-standard video codec where the frames are -// simply independent JPEG images with a fixed huffman table (which is omitted). -// It is rarely used in video transmission, but is common as a camera capture -// format, especially in Logitech devices. This class implements a decoder for -// MJPEG frames. -// -// See http://tools.ietf.org/html/rfc2435 -class LIBYUV_API MJpegDecoder { - public: - typedef void (*CallbackFunction)(void* opaque, - const uint8* const* data, - const int* strides, - int rows); - - static const int kColorSpaceUnknown; - static const int kColorSpaceGrayscale; - static const int kColorSpaceRgb; - static const int kColorSpaceYCbCr; - static const int kColorSpaceCMYK; - static const int kColorSpaceYCCK; - - MJpegDecoder(); - ~MJpegDecoder(); - - // Loads a new frame, reads its headers, and determines the uncompressed - // image format. - // Returns LIBYUV_TRUE if image looks valid and format is supported. - // If return value is LIBYUV_TRUE, then the values for all the following - // getters are populated. - // src_len is the size of the compressed mjpeg frame in bytes. - LIBYUV_BOOL LoadFrame(const uint8* src, size_t src_len); - - // Returns width of the last loaded frame in pixels. - int GetWidth(); - - // Returns height of the last loaded frame in pixels. - int GetHeight(); - - // Returns format of the last loaded frame. The return value is one of the - // kColorSpace* constants. - int GetColorSpace(); - - // Number of color components in the color space. - int GetNumComponents(); - - // Sample factors of the n-th component. - int GetHorizSampFactor(int component); - - int GetVertSampFactor(int component); - - int GetHorizSubSampFactor(int component); - - int GetVertSubSampFactor(int component); - - // Public for testability. - int GetImageScanlinesPerImcuRow(); - - // Public for testability. - int GetComponentScanlinesPerImcuRow(int component); - - // Width of a component in bytes. - int GetComponentWidth(int component); - - // Height of a component. - int GetComponentHeight(int component); - - // Width of a component in bytes with padding for DCTSIZE. Public for testing. - int GetComponentStride(int component); - - // Size of a component in bytes. - int GetComponentSize(int component); - - // Call this after LoadFrame() if you decide you don't want to decode it - // after all. - LIBYUV_BOOL UnloadFrame(); - - // Decodes the entire image into a one-buffer-per-color-component format. - // dst_width must match exactly. dst_height must be <= to image height; if - // less, the image is cropped. "planes" must have size equal to at least - // GetNumComponents() and they must point to non-overlapping buffers of size - // at least GetComponentSize(i). The pointers in planes are incremented - // to point to after the end of the written data. - // TODO(fbarchard): Add dst_x, dst_y to allow specific rect to be decoded. - LIBYUV_BOOL DecodeToBuffers(uint8** planes, int dst_width, int dst_height); - - // Decodes the entire image and passes the data via repeated calls to a - // callback function. Each call will get the data for a whole number of - // image scanlines. - // TODO(fbarchard): Add dst_x, dst_y to allow specific rect to be decoded. - LIBYUV_BOOL DecodeToCallback(CallbackFunction fn, void* opaque, - int dst_width, int dst_height); - - // The helper function which recognizes the jpeg sub-sampling type. - static JpegSubsamplingType JpegSubsamplingTypeHelper( - int* subsample_x, int* subsample_y, int number_of_components); - - private: - void AllocOutputBuffers(int num_outbufs); - void DestroyOutputBuffers(); - - LIBYUV_BOOL StartDecode(); - LIBYUV_BOOL FinishDecode(); - - void SetScanlinePointers(uint8** data); - LIBYUV_BOOL DecodeImcuRow(); - - int GetComponentScanlinePadding(int component); - - // A buffer holding the input data for a frame. - Buffer buf_; - BufferVector buf_vec_; - - jpeg_decompress_struct* decompress_struct_; - jpeg_source_mgr* source_mgr_; - SetJmpErrorMgr* error_mgr_; - - // LIBYUV_TRUE iff at least one component has scanline padding. (i.e., - // GetComponentScanlinePadding() != 0.) - LIBYUV_BOOL has_scanline_padding_; - - // Temporaries used to point to scanline outputs. - int num_outbufs_; // Outermost size of all arrays below. - uint8*** scanlines_; - int* scanlines_sizes_; - // Temporary buffer used for decoding when we can't decode directly to the - // output buffers. Large enough for just one iMCU row. - uint8** databuf_; - int* databuf_strides_; -}; - -} // namespace libyuv - -#endif // __cplusplus -#endif // INCLUDE_LIBYUV_MJPEG_DECODER_H_ diff --git a/third_party/libyuv/include/libyuv/planar_functions.h b/third_party/libyuv/include/libyuv/planar_functions.h deleted file mode 100644 index 1b57b29..0000000 --- a/third_party/libyuv/include/libyuv/planar_functions.h +++ /dev/null @@ -1,529 +0,0 @@ -/* - * Copyright 2011 The LibYuv Project Authors. All rights reserved. - * - * Use of this source code is governed by a BSD-style license - * that can be found in the LICENSE file in the root of the source - * tree. An additional intellectual property rights grant can be found - * in the file PATENTS. All contributing project authors may - * be found in the AUTHORS file in the root of the source tree. - */ - -#ifndef INCLUDE_LIBYUV_PLANAR_FUNCTIONS_H_ -#define INCLUDE_LIBYUV_PLANAR_FUNCTIONS_H_ - -#include "libyuv/basic_types.h" - -// TODO(fbarchard): Remove the following headers includes. -#include "libyuv/convert.h" -#include "libyuv/convert_argb.h" - -#ifdef __cplusplus -namespace libyuv { -extern "C" { -#endif - -// Copy a plane of data. -LIBYUV_API -void CopyPlane(const uint8* src_y, int src_stride_y, - uint8* dst_y, int dst_stride_y, - int width, int height); - -LIBYUV_API -void CopyPlane_16(const uint16* src_y, int src_stride_y, - uint16* dst_y, int dst_stride_y, - int width, int height); - -// Set a plane of data to a 32 bit value. -LIBYUV_API -void SetPlane(uint8* dst_y, int dst_stride_y, - int width, int height, - uint32 value); - -// Split interleaved UV plane into separate U and V planes. -LIBYUV_API -void SplitUVPlane(const uint8* src_uv, int src_stride_uv, - uint8* dst_u, int dst_stride_u, - uint8* dst_v, int dst_stride_v, - int width, int height); - -// Merge separate U and V planes into one interleaved UV plane. -LIBYUV_API -void MergeUVPlane(const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_uv, int dst_stride_uv, - int width, int height); - -// Copy I400. Supports inverting. -LIBYUV_API -int I400ToI400(const uint8* src_y, int src_stride_y, - uint8* dst_y, int dst_stride_y, - int width, int height); - -#define J400ToJ400 I400ToI400 - -// Copy I422 to I422. -#define I422ToI422 I422Copy -LIBYUV_API -int I422Copy(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_y, int dst_stride_y, - uint8* dst_u, int dst_stride_u, - uint8* dst_v, int dst_stride_v, - int width, int height); - -// Copy I444 to I444. -#define I444ToI444 I444Copy -LIBYUV_API -int I444Copy(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_y, int dst_stride_y, - uint8* dst_u, int dst_stride_u, - uint8* dst_v, int dst_stride_v, - int width, int height); - -// Convert YUY2 to I422. -LIBYUV_API -int YUY2ToI422(const uint8* src_yuy2, int src_stride_yuy2, - uint8* dst_y, int dst_stride_y, - uint8* dst_u, int dst_stride_u, - uint8* dst_v, int dst_stride_v, - int width, int height); - -// Convert UYVY to I422. -LIBYUV_API -int UYVYToI422(const uint8* src_uyvy, int src_stride_uyvy, - uint8* dst_y, int dst_stride_y, - uint8* dst_u, int dst_stride_u, - uint8* dst_v, int dst_stride_v, - int width, int height); - -LIBYUV_API -int YUY2ToNV12(const uint8* src_yuy2, int src_stride_yuy2, - uint8* dst_y, int dst_stride_y, - uint8* dst_uv, int dst_stride_uv, - int width, int height); - -LIBYUV_API -int UYVYToNV12(const uint8* src_uyvy, int src_stride_uyvy, - uint8* dst_y, int dst_stride_y, - uint8* dst_uv, int dst_stride_uv, - int width, int height); - -// Convert I420 to I400. (calls CopyPlane ignoring u/v). -LIBYUV_API -int I420ToI400(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_y, int dst_stride_y, - int width, int height); - -// Alias -#define J420ToJ400 I420ToI400 -#define I420ToI420Mirror I420Mirror - -// I420 mirror. -LIBYUV_API -int I420Mirror(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_y, int dst_stride_y, - uint8* dst_u, int dst_stride_u, - uint8* dst_v, int dst_stride_v, - int width, int height); - -// Alias -#define I400ToI400Mirror I400Mirror - -// I400 mirror. A single plane is mirrored horizontally. -// Pass negative height to achieve 180 degree rotation. -LIBYUV_API -int I400Mirror(const uint8* src_y, int src_stride_y, - uint8* dst_y, int dst_stride_y, - int width, int height); - -// Alias -#define ARGBToARGBMirror ARGBMirror - -// ARGB mirror. -LIBYUV_API -int ARGBMirror(const uint8* src_argb, int src_stride_argb, - uint8* dst_argb, int dst_stride_argb, - int width, int height); - -// Convert NV12 to RGB565. -LIBYUV_API -int NV12ToRGB565(const uint8* src_y, int src_stride_y, - const uint8* src_uv, int src_stride_uv, - uint8* dst_rgb565, int dst_stride_rgb565, - int width, int height); - -// I422ToARGB is in convert_argb.h -// Convert I422 to BGRA. -LIBYUV_API -int I422ToBGRA(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_bgra, int dst_stride_bgra, - int width, int height); - -// Convert I422 to ABGR. -LIBYUV_API -int I422ToABGR(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_abgr, int dst_stride_abgr, - int width, int height); - -// Convert I422 to RGBA. -LIBYUV_API -int I422ToRGBA(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_rgba, int dst_stride_rgba, - int width, int height); - -// Alias -#define RGB24ToRAW RAWToRGB24 - -LIBYUV_API -int RAWToRGB24(const uint8* src_raw, int src_stride_raw, - uint8* dst_rgb24, int dst_stride_rgb24, - int width, int height); - -// Draw a rectangle into I420. -LIBYUV_API -int I420Rect(uint8* dst_y, int dst_stride_y, - uint8* dst_u, int dst_stride_u, - uint8* dst_v, int dst_stride_v, - int x, int y, int width, int height, - int value_y, int value_u, int value_v); - -// Draw a rectangle into ARGB. -LIBYUV_API -int ARGBRect(uint8* dst_argb, int dst_stride_argb, - int x, int y, int width, int height, uint32 value); - -// Convert ARGB to gray scale ARGB. -LIBYUV_API -int ARGBGrayTo(const uint8* src_argb, int src_stride_argb, - uint8* dst_argb, int dst_stride_argb, - int width, int height); - -// Make a rectangle of ARGB gray scale. -LIBYUV_API -int ARGBGray(uint8* dst_argb, int dst_stride_argb, - int x, int y, int width, int height); - -// Make a rectangle of ARGB Sepia tone. -LIBYUV_API -int ARGBSepia(uint8* dst_argb, int dst_stride_argb, - int x, int y, int width, int height); - -// Apply a matrix rotation to each ARGB pixel. -// matrix_argb is 4 signed ARGB values. -128 to 127 representing -2 to 2. -// The first 4 coefficients apply to B, G, R, A and produce B of the output. -// The next 4 coefficients apply to B, G, R, A and produce G of the output. -// The next 4 coefficients apply to B, G, R, A and produce R of the output. -// The last 4 coefficients apply to B, G, R, A and produce A of the output. -LIBYUV_API -int ARGBColorMatrix(const uint8* src_argb, int src_stride_argb, - uint8* dst_argb, int dst_stride_argb, - const int8* matrix_argb, - int width, int height); - -// Deprecated. Use ARGBColorMatrix instead. -// Apply a matrix rotation to each ARGB pixel. -// matrix_argb is 3 signed ARGB values. -128 to 127 representing -1 to 1. -// The first 4 coefficients apply to B, G, R, A and produce B of the output. -// The next 4 coefficients apply to B, G, R, A and produce G of the output. -// The last 4 coefficients apply to B, G, R, A and produce R of the output. -LIBYUV_API -int RGBColorMatrix(uint8* dst_argb, int dst_stride_argb, - const int8* matrix_rgb, - int x, int y, int width, int height); - -// Apply a color table each ARGB pixel. -// Table contains 256 ARGB values. -LIBYUV_API -int ARGBColorTable(uint8* dst_argb, int dst_stride_argb, - const uint8* table_argb, - int x, int y, int width, int height); - -// Apply a color table each ARGB pixel but preserve destination alpha. -// Table contains 256 ARGB values. -LIBYUV_API -int RGBColorTable(uint8* dst_argb, int dst_stride_argb, - const uint8* table_argb, - int x, int y, int width, int height); - -// Apply a luma/color table each ARGB pixel but preserve destination alpha. -// Table contains 32768 values indexed by [Y][C] where 7 it 7 bit luma from -// RGB (YJ style) and C is an 8 bit color component (R, G or B). -LIBYUV_API -int ARGBLumaColorTable(const uint8* src_argb, int src_stride_argb, - uint8* dst_argb, int dst_stride_argb, - const uint8* luma_rgb_table, - int width, int height); - -// Apply a 3 term polynomial to ARGB values. -// poly points to a 4x4 matrix. The first row is constants. The 2nd row is -// coefficients for b, g, r and a. The 3rd row is coefficients for b squared, -// g squared, r squared and a squared. The 4rd row is coefficients for b to -// the 3, g to the 3, r to the 3 and a to the 3. The values are summed and -// result clamped to 0 to 255. -// A polynomial approximation can be dirived using software such as 'R'. - -LIBYUV_API -int ARGBPolynomial(const uint8* src_argb, int src_stride_argb, - uint8* dst_argb, int dst_stride_argb, - const float* poly, - int width, int height); - -// Convert plane of 16 bit shorts to half floats. -// Source values are multiplied by scale before storing as half float. -LIBYUV_API -int HalfFloatPlane(const uint16* src_y, int src_stride_y, - uint16* dst_y, int dst_stride_y, - float scale, - int width, int height); - -// Quantize a rectangle of ARGB. Alpha unaffected. -// scale is a 16 bit fractional fixed point scaler between 0 and 65535. -// interval_size should be a value between 1 and 255. -// interval_offset should be a value between 0 and 255. -LIBYUV_API -int ARGBQuantize(uint8* dst_argb, int dst_stride_argb, - int scale, int interval_size, int interval_offset, - int x, int y, int width, int height); - -// Copy ARGB to ARGB. -LIBYUV_API -int ARGBCopy(const uint8* src_argb, int src_stride_argb, - uint8* dst_argb, int dst_stride_argb, - int width, int height); - -// Copy Alpha channel of ARGB to alpha of ARGB. -LIBYUV_API -int ARGBCopyAlpha(const uint8* src_argb, int src_stride_argb, - uint8* dst_argb, int dst_stride_argb, - int width, int height); - -// Extract the alpha channel from ARGB. -LIBYUV_API -int ARGBExtractAlpha(const uint8* src_argb, int src_stride_argb, - uint8* dst_a, int dst_stride_a, - int width, int height); - -// Copy Y channel to Alpha of ARGB. -LIBYUV_API -int ARGBCopyYToAlpha(const uint8* src_y, int src_stride_y, - uint8* dst_argb, int dst_stride_argb, - int width, int height); - -typedef void (*ARGBBlendRow)(const uint8* src_argb0, const uint8* src_argb1, - uint8* dst_argb, int width); - -// Get function to Alpha Blend ARGB pixels and store to destination. -LIBYUV_API -ARGBBlendRow GetARGBBlend(); - -// Alpha Blend ARGB images and store to destination. -// Source is pre-multiplied by alpha using ARGBAttenuate. -// Alpha of destination is set to 255. -LIBYUV_API -int ARGBBlend(const uint8* src_argb0, int src_stride_argb0, - const uint8* src_argb1, int src_stride_argb1, - uint8* dst_argb, int dst_stride_argb, - int width, int height); - -// Alpha Blend plane and store to destination. -// Source is not pre-multiplied by alpha. -LIBYUV_API -int BlendPlane(const uint8* src_y0, int src_stride_y0, - const uint8* src_y1, int src_stride_y1, - const uint8* alpha, int alpha_stride, - uint8* dst_y, int dst_stride_y, - int width, int height); - -// Alpha Blend YUV images and store to destination. -// Source is not pre-multiplied by alpha. -// Alpha is full width x height and subsampled to half size to apply to UV. -LIBYUV_API -int I420Blend(const uint8* src_y0, int src_stride_y0, - const uint8* src_u0, int src_stride_u0, - const uint8* src_v0, int src_stride_v0, - const uint8* src_y1, int src_stride_y1, - const uint8* src_u1, int src_stride_u1, - const uint8* src_v1, int src_stride_v1, - const uint8* alpha, int alpha_stride, - uint8* dst_y, int dst_stride_y, - uint8* dst_u, int dst_stride_u, - uint8* dst_v, int dst_stride_v, - int width, int height); - -// Multiply ARGB image by ARGB image. Shifted down by 8. Saturates to 255. -LIBYUV_API -int ARGBMultiply(const uint8* src_argb0, int src_stride_argb0, - const uint8* src_argb1, int src_stride_argb1, - uint8* dst_argb, int dst_stride_argb, - int width, int height); - -// Add ARGB image with ARGB image. Saturates to 255. -LIBYUV_API -int ARGBAdd(const uint8* src_argb0, int src_stride_argb0, - const uint8* src_argb1, int src_stride_argb1, - uint8* dst_argb, int dst_stride_argb, - int width, int height); - -// Subtract ARGB image (argb1) from ARGB image (argb0). Saturates to 0. -LIBYUV_API -int ARGBSubtract(const uint8* src_argb0, int src_stride_argb0, - const uint8* src_argb1, int src_stride_argb1, - uint8* dst_argb, int dst_stride_argb, - int width, int height); - -// Convert I422 to YUY2. -LIBYUV_API -int I422ToYUY2(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_frame, int dst_stride_frame, - int width, int height); - -// Convert I422 to UYVY. -LIBYUV_API -int I422ToUYVY(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_frame, int dst_stride_frame, - int width, int height); - -// Convert unattentuated ARGB to preattenuated ARGB. -LIBYUV_API -int ARGBAttenuate(const uint8* src_argb, int src_stride_argb, - uint8* dst_argb, int dst_stride_argb, - int width, int height); - -// Convert preattentuated ARGB to unattenuated ARGB. -LIBYUV_API -int ARGBUnattenuate(const uint8* src_argb, int src_stride_argb, - uint8* dst_argb, int dst_stride_argb, - int width, int height); - -// Internal function - do not call directly. -// Computes table of cumulative sum for image where the value is the sum -// of all values above and to the left of the entry. Used by ARGBBlur. -LIBYUV_API -int ARGBComputeCumulativeSum(const uint8* src_argb, int src_stride_argb, - int32* dst_cumsum, int dst_stride32_cumsum, - int width, int height); - -// Blur ARGB image. -// dst_cumsum table of width * (height + 1) * 16 bytes aligned to -// 16 byte boundary. -// dst_stride32_cumsum is number of ints in a row (width * 4). -// radius is number of pixels around the center. e.g. 1 = 3x3. 2=5x5. -// Blur is optimized for radius of 5 (11x11) or less. -LIBYUV_API -int ARGBBlur(const uint8* src_argb, int src_stride_argb, - uint8* dst_argb, int dst_stride_argb, - int32* dst_cumsum, int dst_stride32_cumsum, - int width, int height, int radius); - -// Multiply ARGB image by ARGB value. -LIBYUV_API -int ARGBShade(const uint8* src_argb, int src_stride_argb, - uint8* dst_argb, int dst_stride_argb, - int width, int height, uint32 value); - -// Interpolate between two images using specified amount of interpolation -// (0 to 255) and store to destination. -// 'interpolation' is specified as 8 bit fraction where 0 means 100% src0 -// and 255 means 1% src0 and 99% src1. -LIBYUV_API -int InterpolatePlane(const uint8* src0, int src_stride0, - const uint8* src1, int src_stride1, - uint8* dst, int dst_stride, - int width, int height, int interpolation); - -// Interpolate between two ARGB images using specified amount of interpolation -// Internally calls InterpolatePlane with width * 4 (bpp). -LIBYUV_API -int ARGBInterpolate(const uint8* src_argb0, int src_stride_argb0, - const uint8* src_argb1, int src_stride_argb1, - uint8* dst_argb, int dst_stride_argb, - int width, int height, int interpolation); - -// Interpolate between two YUV images using specified amount of interpolation -// Internally calls InterpolatePlane on each plane where the U and V planes -// are half width and half height. -LIBYUV_API -int I420Interpolate(const uint8* src0_y, int src0_stride_y, - const uint8* src0_u, int src0_stride_u, - const uint8* src0_v, int src0_stride_v, - const uint8* src1_y, int src1_stride_y, - const uint8* src1_u, int src1_stride_u, - const uint8* src1_v, int src1_stride_v, - uint8* dst_y, int dst_stride_y, - uint8* dst_u, int dst_stride_u, - uint8* dst_v, int dst_stride_v, - int width, int height, int interpolation); - -#if defined(__pnacl__) || defined(__CLR_VER) || \ - (defined(__i386__) && !defined(__SSE2__)) -#define LIBYUV_DISABLE_X86 -#endif -// MemorySanitizer does not support assembly code yet. http://crbug.com/344505 -#if defined(__has_feature) -#if __has_feature(memory_sanitizer) -#define LIBYUV_DISABLE_X86 -#endif -#endif -// The following are available on all x86 platforms: -#if !defined(LIBYUV_DISABLE_X86) && \ - (defined(_M_IX86) || defined(__x86_64__) || defined(__i386__)) -#define HAS_ARGBAFFINEROW_SSE2 -#endif - -// Row function for copying pixels from a source with a slope to a row -// of destination. Useful for scaling, rotation, mirror, texture mapping. -LIBYUV_API -void ARGBAffineRow_C(const uint8* src_argb, int src_argb_stride, - uint8* dst_argb, const float* uv_dudv, int width); -LIBYUV_API -void ARGBAffineRow_SSE2(const uint8* src_argb, int src_argb_stride, - uint8* dst_argb, const float* uv_dudv, int width); - -// Shuffle ARGB channel order. e.g. BGRA to ARGB. -// shuffler is 16 bytes and must be aligned. -LIBYUV_API -int ARGBShuffle(const uint8* src_bgra, int src_stride_bgra, - uint8* dst_argb, int dst_stride_argb, - const uint8* shuffler, int width, int height); - -// Sobel ARGB effect with planar output. -LIBYUV_API -int ARGBSobelToPlane(const uint8* src_argb, int src_stride_argb, - uint8* dst_y, int dst_stride_y, - int width, int height); - -// Sobel ARGB effect. -LIBYUV_API -int ARGBSobel(const uint8* src_argb, int src_stride_argb, - uint8* dst_argb, int dst_stride_argb, - int width, int height); - -// Sobel ARGB effect w/ Sobel X, Sobel, Sobel Y in ARGB. -LIBYUV_API -int ARGBSobelXY(const uint8* src_argb, int src_stride_argb, - uint8* dst_argb, int dst_stride_argb, - int width, int height); - -#ifdef __cplusplus -} // extern "C" -} // namespace libyuv -#endif - -#endif // INCLUDE_LIBYUV_PLANAR_FUNCTIONS_H_ diff --git a/third_party/libyuv/include/libyuv/rotate.h b/third_party/libyuv/include/libyuv/rotate.h deleted file mode 100644 index 8a2da9a..0000000 --- a/third_party/libyuv/include/libyuv/rotate.h +++ /dev/null @@ -1,117 +0,0 @@ -/* - * Copyright 2011 The LibYuv Project Authors. All rights reserved. - * - * Use of this source code is governed by a BSD-style license - * that can be found in the LICENSE file in the root of the source - * tree. An additional intellectual property rights grant can be found - * in the file PATENTS. All contributing project authors may - * be found in the AUTHORS file in the root of the source tree. - */ - -#ifndef INCLUDE_LIBYUV_ROTATE_H_ -#define INCLUDE_LIBYUV_ROTATE_H_ - -#include "libyuv/basic_types.h" - -#ifdef __cplusplus -namespace libyuv { -extern "C" { -#endif - -// Supported rotation. -typedef enum RotationMode { - kRotate0 = 0, // No rotation. - kRotate90 = 90, // Rotate 90 degrees clockwise. - kRotate180 = 180, // Rotate 180 degrees. - kRotate270 = 270, // Rotate 270 degrees clockwise. - - // Deprecated. - kRotateNone = 0, - kRotateClockwise = 90, - kRotateCounterClockwise = 270, -} RotationModeEnum; - -// Rotate I420 frame. -LIBYUV_API -int I420Rotate(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint8* dst_y, int dst_stride_y, - uint8* dst_u, int dst_stride_u, - uint8* dst_v, int dst_stride_v, - int src_width, int src_height, enum RotationMode mode); - -// Rotate NV12 input and store in I420. -LIBYUV_API -int NV12ToI420Rotate(const uint8* src_y, int src_stride_y, - const uint8* src_uv, int src_stride_uv, - uint8* dst_y, int dst_stride_y, - uint8* dst_u, int dst_stride_u, - uint8* dst_v, int dst_stride_v, - int src_width, int src_height, enum RotationMode mode); - -// Rotate a plane by 0, 90, 180, or 270. -LIBYUV_API -int RotatePlane(const uint8* src, int src_stride, - uint8* dst, int dst_stride, - int src_width, int src_height, enum RotationMode mode); - -// Rotate planes by 90, 180, 270. Deprecated. -LIBYUV_API -void RotatePlane90(const uint8* src, int src_stride, - uint8* dst, int dst_stride, - int width, int height); - -LIBYUV_API -void RotatePlane180(const uint8* src, int src_stride, - uint8* dst, int dst_stride, - int width, int height); - -LIBYUV_API -void RotatePlane270(const uint8* src, int src_stride, - uint8* dst, int dst_stride, - int width, int height); - -LIBYUV_API -void RotateUV90(const uint8* src, int src_stride, - uint8* dst_a, int dst_stride_a, - uint8* dst_b, int dst_stride_b, - int width, int height); - -// Rotations for when U and V are interleaved. -// These functions take one input pointer and -// split the data into two buffers while -// rotating them. Deprecated. -LIBYUV_API -void RotateUV180(const uint8* src, int src_stride, - uint8* dst_a, int dst_stride_a, - uint8* dst_b, int dst_stride_b, - int width, int height); - -LIBYUV_API -void RotateUV270(const uint8* src, int src_stride, - uint8* dst_a, int dst_stride_a, - uint8* dst_b, int dst_stride_b, - int width, int height); - -// The 90 and 270 functions are based on transposes. -// Doing a transpose with reversing the read/write -// order will result in a rotation by +- 90 degrees. -// Deprecated. -LIBYUV_API -void TransposePlane(const uint8* src, int src_stride, - uint8* dst, int dst_stride, - int width, int height); - -LIBYUV_API -void TransposeUV(const uint8* src, int src_stride, - uint8* dst_a, int dst_stride_a, - uint8* dst_b, int dst_stride_b, - int width, int height); - -#ifdef __cplusplus -} // extern "C" -} // namespace libyuv -#endif - -#endif // INCLUDE_LIBYUV_ROTATE_H_ diff --git a/third_party/libyuv/include/libyuv/rotate_argb.h b/third_party/libyuv/include/libyuv/rotate_argb.h deleted file mode 100644 index 21fe7e1..0000000 --- a/third_party/libyuv/include/libyuv/rotate_argb.h +++ /dev/null @@ -1,33 +0,0 @@ -/* - * Copyright 2012 The LibYuv Project Authors. All rights reserved. - * - * Use of this source code is governed by a BSD-style license - * that can be found in the LICENSE file in the root of the source - * tree. An additional intellectual property rights grant can be found - * in the file PATENTS. All contributing project authors may - * be found in the AUTHORS file in the root of the source tree. - */ - -#ifndef INCLUDE_LIBYUV_ROTATE_ARGB_H_ -#define INCLUDE_LIBYUV_ROTATE_ARGB_H_ - -#include "libyuv/basic_types.h" -#include "libyuv/rotate.h" // For RotationMode. - -#ifdef __cplusplus -namespace libyuv { -extern "C" { -#endif - -// Rotate ARGB frame -LIBYUV_API -int ARGBRotate(const uint8* src_argb, int src_stride_argb, - uint8* dst_argb, int dst_stride_argb, - int src_width, int src_height, enum RotationMode mode); - -#ifdef __cplusplus -} // extern "C" -} // namespace libyuv -#endif - -#endif // INCLUDE_LIBYUV_ROTATE_ARGB_H_ diff --git a/third_party/libyuv/include/libyuv/rotate_row.h b/third_party/libyuv/include/libyuv/rotate_row.h deleted file mode 100644 index 6abd201..0000000 --- a/third_party/libyuv/include/libyuv/rotate_row.h +++ /dev/null @@ -1,121 +0,0 @@ -/* - * Copyright 2013 The LibYuv Project Authors. All rights reserved. - * - * Use of this source code is governed by a BSD-style license - * that can be found in the LICENSE file in the root of the source - * tree. An additional intellectual property rights grant can be found - * in the file PATENTS. All contributing project authors may - * be found in the AUTHORS file in the root of the source tree. - */ - -#ifndef INCLUDE_LIBYUV_ROTATE_ROW_H_ -#define INCLUDE_LIBYUV_ROTATE_ROW_H_ - -#include "libyuv/basic_types.h" - -#ifdef __cplusplus -namespace libyuv { -extern "C" { -#endif - -#if defined(__pnacl__) || defined(__CLR_VER) || \ - (defined(__i386__) && !defined(__SSE2__)) -#define LIBYUV_DISABLE_X86 -#endif -// MemorySanitizer does not support assembly code yet. http://crbug.com/344505 -#if defined(__has_feature) -#if __has_feature(memory_sanitizer) -#define LIBYUV_DISABLE_X86 -#endif -#endif -// The following are available for Visual C and clangcl 32 bit: -#if !defined(LIBYUV_DISABLE_X86) && defined(_M_IX86) -#define HAS_TRANSPOSEWX8_SSSE3 -#define HAS_TRANSPOSEUVWX8_SSE2 -#endif - -// The following are available for GCC 32 or 64 bit but not NaCL for 64 bit: -#if !defined(LIBYUV_DISABLE_X86) && \ - (defined(__i386__) || (defined(__x86_64__) && !defined(__native_client__))) -#define HAS_TRANSPOSEWX8_SSSE3 -#endif - -// The following are available for 64 bit GCC but not NaCL: -#if !defined(LIBYUV_DISABLE_X86) && !defined(__native_client__) && \ - defined(__x86_64__) -#define HAS_TRANSPOSEWX8_FAST_SSSE3 -#define HAS_TRANSPOSEUVWX8_SSE2 -#endif - -#if !defined(LIBYUV_DISABLE_NEON) && !defined(__native_client__) && \ - (defined(__ARM_NEON__) || defined(LIBYUV_NEON) || defined(__aarch64__)) -#define HAS_TRANSPOSEWX8_NEON -#define HAS_TRANSPOSEUVWX8_NEON -#endif - -#if !defined(LIBYUV_DISABLE_MIPS) && !defined(__native_client__) && \ - defined(__mips__) && \ - defined(__mips_dsp) && (__mips_dsp_rev >= 2) -#define HAS_TRANSPOSEWX8_DSPR2 -#define HAS_TRANSPOSEUVWX8_DSPR2 -#endif // defined(__mips__) - -void TransposeWxH_C(const uint8* src, int src_stride, - uint8* dst, int dst_stride, int width, int height); - -void TransposeWx8_C(const uint8* src, int src_stride, - uint8* dst, int dst_stride, int width); -void TransposeWx8_NEON(const uint8* src, int src_stride, - uint8* dst, int dst_stride, int width); -void TransposeWx8_SSSE3(const uint8* src, int src_stride, - uint8* dst, int dst_stride, int width); -void TransposeWx8_Fast_SSSE3(const uint8* src, int src_stride, - uint8* dst, int dst_stride, int width); -void TransposeWx8_DSPR2(const uint8* src, int src_stride, - uint8* dst, int dst_stride, int width); -void TransposeWx8_Fast_DSPR2(const uint8* src, int src_stride, - uint8* dst, int dst_stride, int width); - -void TransposeWx8_Any_NEON(const uint8* src, int src_stride, - uint8* dst, int dst_stride, int width); -void TransposeWx8_Any_SSSE3(const uint8* src, int src_stride, - uint8* dst, int dst_stride, int width); -void TransposeWx8_Fast_Any_SSSE3(const uint8* src, int src_stride, - uint8* dst, int dst_stride, int width); -void TransposeWx8_Any_DSPR2(const uint8* src, int src_stride, - uint8* dst, int dst_stride, int width); - -void TransposeUVWxH_C(const uint8* src, int src_stride, - uint8* dst_a, int dst_stride_a, - uint8* dst_b, int dst_stride_b, - int width, int height); - -void TransposeUVWx8_C(const uint8* src, int src_stride, - uint8* dst_a, int dst_stride_a, - uint8* dst_b, int dst_stride_b, int width); -void TransposeUVWx8_SSE2(const uint8* src, int src_stride, - uint8* dst_a, int dst_stride_a, - uint8* dst_b, int dst_stride_b, int width); -void TransposeUVWx8_NEON(const uint8* src, int src_stride, - uint8* dst_a, int dst_stride_a, - uint8* dst_b, int dst_stride_b, int width); -void TransposeUVWx8_DSPR2(const uint8* src, int src_stride, - uint8* dst_a, int dst_stride_a, - uint8* dst_b, int dst_stride_b, int width); - -void TransposeUVWx8_Any_SSE2(const uint8* src, int src_stride, - uint8* dst_a, int dst_stride_a, - uint8* dst_b, int dst_stride_b, int width); -void TransposeUVWx8_Any_NEON(const uint8* src, int src_stride, - uint8* dst_a, int dst_stride_a, - uint8* dst_b, int dst_stride_b, int width); -void TransposeUVWx8_Any_DSPR2(const uint8* src, int src_stride, - uint8* dst_a, int dst_stride_a, - uint8* dst_b, int dst_stride_b, int width); - -#ifdef __cplusplus -} // extern "C" -} // namespace libyuv -#endif - -#endif // INCLUDE_LIBYUV_ROTATE_ROW_H_ diff --git a/third_party/libyuv/include/libyuv/row.h b/third_party/libyuv/include/libyuv/row.h deleted file mode 100644 index b810221..0000000 --- a/third_party/libyuv/include/libyuv/row.h +++ /dev/null @@ -1,1963 +0,0 @@ -/* - * Copyright 2011 The LibYuv Project Authors. All rights reserved. - * - * Use of this source code is governed by a BSD-style license - * that can be found in the LICENSE file in the root of the source - * tree. An additional intellectual property rights grant can be found - * in the file PATENTS. All contributing project authors may - * be found in the AUTHORS file in the root of the source tree. - */ - -#ifndef INCLUDE_LIBYUV_ROW_H_ -#define INCLUDE_LIBYUV_ROW_H_ - -#include // For malloc. - -#include "libyuv/basic_types.h" - -#ifdef __cplusplus -namespace libyuv { -extern "C" { -#endif - -#define IS_ALIGNED(p, a) (!((uintptr_t)(p) & ((a) - 1))) - -#define align_buffer_64(var, size) \ - uint8* var##_mem = (uint8*)(malloc((size) + 63)); /* NOLINT */ \ - uint8* var = (uint8*)(((intptr_t)(var##_mem) + 63) & ~63) /* NOLINT */ - -#define free_aligned_buffer_64(var) \ - free(var##_mem); \ - var = 0 - -#if defined(__pnacl__) || defined(__CLR_VER) || \ - (defined(__i386__) && !defined(__SSE2__)) -#define LIBYUV_DISABLE_X86 -#endif -// MemorySanitizer does not support assembly code yet. http://crbug.com/344505 -#if defined(__has_feature) -#if __has_feature(memory_sanitizer) -#define LIBYUV_DISABLE_X86 -#endif -#endif -// True if compiling for SSSE3 as a requirement. -#if defined(__SSSE3__) || (defined(_M_IX86_FP) && (_M_IX86_FP >= 3)) -#define LIBYUV_SSSE3_ONLY -#endif - -#if defined(__native_client__) -#define LIBYUV_DISABLE_NEON -#endif -// clang >= 3.5.0 required for Arm64. -#if defined(__clang__) && defined(__aarch64__) && !defined(LIBYUV_DISABLE_NEON) -#if (__clang_major__ < 3) || (__clang_major__ == 3 && (__clang_minor__ < 5)) -#define LIBYUV_DISABLE_NEON -#endif // clang >= 3.5 -#endif // __clang__ - -// GCC >= 4.7.0 required for AVX2. -#if defined(__GNUC__) && (defined(__x86_64__) || defined(__i386__)) -#if (__GNUC__ > 4) || (__GNUC__ == 4 && (__GNUC_MINOR__ >= 7)) -#define GCC_HAS_AVX2 1 -#endif // GNUC >= 4.7 -#endif // __GNUC__ - -// clang >= 3.4.0 required for AVX2. -#if defined(__clang__) && (defined(__x86_64__) || defined(__i386__)) -#if (__clang_major__ > 3) || (__clang_major__ == 3 && (__clang_minor__ >= 4)) -#define CLANG_HAS_AVX2 1 -#endif // clang >= 3.4 -#endif // __clang__ - -// Visual C 2012 required for AVX2. -#if defined(_M_IX86) && !defined(__clang__) && \ - defined(_MSC_VER) && _MSC_VER >= 1700 -#define VISUALC_HAS_AVX2 1 -#endif // VisualStudio >= 2012 - -// The following are available on all x86 platforms: -#if !defined(LIBYUV_DISABLE_X86) && \ - (defined(_M_IX86) || defined(__x86_64__) || defined(__i386__)) -// Conversions: -#define HAS_ABGRTOUVROW_SSSE3 -#define HAS_ABGRTOYROW_SSSE3 -#define HAS_ARGB1555TOARGBROW_SSE2 -#define HAS_ARGB4444TOARGBROW_SSE2 -#define HAS_ARGBSETROW_X86 -#define HAS_ARGBSHUFFLEROW_SSE2 -#define HAS_ARGBSHUFFLEROW_SSSE3 -#define HAS_ARGBTOARGB1555ROW_SSE2 -#define HAS_ARGBTOARGB4444ROW_SSE2 -#define HAS_ARGBTORAWROW_SSSE3 -#define HAS_ARGBTORGB24ROW_SSSE3 -#define HAS_ARGBTORGB565DITHERROW_SSE2 -#define HAS_ARGBTORGB565ROW_SSE2 -#define HAS_ARGBTOUV444ROW_SSSE3 -#define HAS_ARGBTOUVJROW_SSSE3 -#define HAS_ARGBTOUVROW_SSSE3 -#define HAS_ARGBTOYJROW_SSSE3 -#define HAS_ARGBTOYROW_SSSE3 -#define HAS_ARGBEXTRACTALPHAROW_SSE2 -#define HAS_BGRATOUVROW_SSSE3 -#define HAS_BGRATOYROW_SSSE3 -#define HAS_COPYROW_ERMS -#define HAS_COPYROW_SSE2 -#define HAS_H422TOARGBROW_SSSE3 -#define HAS_I400TOARGBROW_SSE2 -#define HAS_I422TOARGB1555ROW_SSSE3 -#define HAS_I422TOARGB4444ROW_SSSE3 -#define HAS_I422TOARGBROW_SSSE3 -#define HAS_I422TORGB24ROW_SSSE3 -#define HAS_I422TORGB565ROW_SSSE3 -#define HAS_I422TORGBAROW_SSSE3 -#define HAS_I422TOUYVYROW_SSE2 -#define HAS_I422TOYUY2ROW_SSE2 -#define HAS_I444TOARGBROW_SSSE3 -#define HAS_J400TOARGBROW_SSE2 -#define HAS_J422TOARGBROW_SSSE3 -#define HAS_MERGEUVROW_SSE2 -#define HAS_MIRRORROW_SSSE3 -#define HAS_MIRRORUVROW_SSSE3 -#define HAS_NV12TOARGBROW_SSSE3 -#define HAS_NV12TORGB565ROW_SSSE3 -#define HAS_NV21TOARGBROW_SSSE3 -#define HAS_RAWTOARGBROW_SSSE3 -#define HAS_RAWTORGB24ROW_SSSE3 -#define HAS_RAWTOYROW_SSSE3 -#define HAS_RGB24TOARGBROW_SSSE3 -#define HAS_RGB24TOYROW_SSSE3 -#define HAS_RGB565TOARGBROW_SSE2 -#define HAS_RGBATOUVROW_SSSE3 -#define HAS_RGBATOYROW_SSSE3 -#define HAS_SETROW_ERMS -#define HAS_SETROW_X86 -#define HAS_SPLITUVROW_SSE2 -#define HAS_UYVYTOARGBROW_SSSE3 -#define HAS_UYVYTOUV422ROW_SSE2 -#define HAS_UYVYTOUVROW_SSE2 -#define HAS_UYVYTOYROW_SSE2 -#define HAS_YUY2TOARGBROW_SSSE3 -#define HAS_YUY2TOUV422ROW_SSE2 -#define HAS_YUY2TOUVROW_SSE2 -#define HAS_YUY2TOYROW_SSE2 - -// Effects: -#define HAS_ARGBADDROW_SSE2 -#define HAS_ARGBAFFINEROW_SSE2 -#define HAS_ARGBATTENUATEROW_SSSE3 -#define HAS_ARGBBLENDROW_SSSE3 -#define HAS_ARGBCOLORMATRIXROW_SSSE3 -#define HAS_ARGBCOLORTABLEROW_X86 -#define HAS_ARGBCOPYALPHAROW_SSE2 -#define HAS_ARGBCOPYYTOALPHAROW_SSE2 -#define HAS_ARGBGRAYROW_SSSE3 -#define HAS_ARGBLUMACOLORTABLEROW_SSSE3 -#define HAS_ARGBMIRRORROW_SSE2 -#define HAS_ARGBMULTIPLYROW_SSE2 -#define HAS_ARGBPOLYNOMIALROW_SSE2 -#define HAS_ARGBQUANTIZEROW_SSE2 -#define HAS_ARGBSEPIAROW_SSSE3 -#define HAS_ARGBSHADEROW_SSE2 -#define HAS_ARGBSUBTRACTROW_SSE2 -#define HAS_ARGBUNATTENUATEROW_SSE2 -#define HAS_BLENDPLANEROW_SSSE3 -#define HAS_COMPUTECUMULATIVESUMROW_SSE2 -#define HAS_CUMULATIVESUMTOAVERAGEROW_SSE2 -#define HAS_INTERPOLATEROW_SSSE3 -#define HAS_RGBCOLORTABLEROW_X86 -#define HAS_SOBELROW_SSE2 -#define HAS_SOBELTOPLANEROW_SSE2 -#define HAS_SOBELXROW_SSE2 -#define HAS_SOBELXYROW_SSE2 -#define HAS_SOBELYROW_SSE2 - -// The following functions fail on gcc/clang 32 bit with fpic and framepointer. -// caveat: clangcl uses row_win.cc which works. -#if defined(NDEBUG) || !(defined(_DEBUG) && defined(__i386__)) || \ - !defined(__i386__) || defined(_MSC_VER) -// TODO(fbarchard): fix build error on x86 debug -// https://code.google.com/p/libyuv/issues/detail?id=524 -#define HAS_I411TOARGBROW_SSSE3 -// TODO(fbarchard): fix build error on android_full_debug=1 -// https://code.google.com/p/libyuv/issues/detail?id=517 -#define HAS_I422ALPHATOARGBROW_SSSE3 -#endif -#endif - -// The following are available on all x86 platforms, but -// require VS2012, clang 3.4 or gcc 4.7. -// The code supports NaCL but requires a new compiler and validator. -#if !defined(LIBYUV_DISABLE_X86) && (defined(VISUALC_HAS_AVX2) || \ - defined(CLANG_HAS_AVX2) || defined(GCC_HAS_AVX2)) -#define HAS_ARGBCOPYALPHAROW_AVX2 -#define HAS_ARGBCOPYYTOALPHAROW_AVX2 -#define HAS_ARGBMIRRORROW_AVX2 -#define HAS_ARGBPOLYNOMIALROW_AVX2 -#define HAS_ARGBSHUFFLEROW_AVX2 -#define HAS_ARGBTORGB565DITHERROW_AVX2 -#define HAS_ARGBTOUVJROW_AVX2 -#define HAS_ARGBTOUVROW_AVX2 -#define HAS_ARGBTOYJROW_AVX2 -#define HAS_ARGBTOYROW_AVX2 -#define HAS_COPYROW_AVX -#define HAS_H422TOARGBROW_AVX2 -#define HAS_I400TOARGBROW_AVX2 -#if !(defined(_DEBUG) && defined(__i386__)) -// TODO(fbarchard): fix build error on android_full_debug=1 -// https://code.google.com/p/libyuv/issues/detail?id=517 -#define HAS_I422ALPHATOARGBROW_AVX2 -#endif -#define HAS_I411TOARGBROW_AVX2 -#define HAS_I422TOARGB1555ROW_AVX2 -#define HAS_I422TOARGB4444ROW_AVX2 -#define HAS_I422TOARGBROW_AVX2 -#define HAS_I422TORGB24ROW_AVX2 -#define HAS_I422TORGB565ROW_AVX2 -#define HAS_I422TORGBAROW_AVX2 -#define HAS_I444TOARGBROW_AVX2 -#define HAS_INTERPOLATEROW_AVX2 -#define HAS_J422TOARGBROW_AVX2 -#define HAS_MERGEUVROW_AVX2 -#define HAS_MIRRORROW_AVX2 -#define HAS_NV12TOARGBROW_AVX2 -#define HAS_NV12TORGB565ROW_AVX2 -#define HAS_NV21TOARGBROW_AVX2 -#define HAS_SPLITUVROW_AVX2 -#define HAS_UYVYTOARGBROW_AVX2 -#define HAS_UYVYTOUV422ROW_AVX2 -#define HAS_UYVYTOUVROW_AVX2 -#define HAS_UYVYTOYROW_AVX2 -#define HAS_YUY2TOARGBROW_AVX2 -#define HAS_YUY2TOUV422ROW_AVX2 -#define HAS_YUY2TOUVROW_AVX2 -#define HAS_YUY2TOYROW_AVX2 -#define HAS_HALFFLOATROW_AVX2 - -// Effects: -#define HAS_ARGBADDROW_AVX2 -#define HAS_ARGBATTENUATEROW_AVX2 -#define HAS_ARGBMULTIPLYROW_AVX2 -#define HAS_ARGBSUBTRACTROW_AVX2 -#define HAS_ARGBUNATTENUATEROW_AVX2 -#define HAS_BLENDPLANEROW_AVX2 -#endif - -// The following are available for AVX2 Visual C and clangcl 32 bit: -// TODO(fbarchard): Port to gcc. -#if !defined(LIBYUV_DISABLE_X86) && defined(_M_IX86) && \ - (defined(VISUALC_HAS_AVX2) || defined(CLANG_HAS_AVX2)) -#define HAS_ARGB1555TOARGBROW_AVX2 -#define HAS_ARGB4444TOARGBROW_AVX2 -#define HAS_ARGBTOARGB1555ROW_AVX2 -#define HAS_ARGBTOARGB4444ROW_AVX2 -#define HAS_ARGBTORGB565ROW_AVX2 -#define HAS_J400TOARGBROW_AVX2 -#define HAS_RGB565TOARGBROW_AVX2 -#endif - -// The following are also available on x64 Visual C. -#if !defined(LIBYUV_DISABLE_X86) && defined(_MSC_VER) && defined(_M_X64) && \ - (!defined(__clang__) || defined(__SSSE3__)) -#define HAS_I422ALPHATOARGBROW_SSSE3 -#define HAS_I422TOARGBROW_SSSE3 -#endif - -// The following are available on gcc x86 platforms: -// TODO(fbarchard): Port to Visual C. -#if !defined(LIBYUV_DISABLE_X86) && \ - (defined(__x86_64__) || (defined(__i386__) && !defined(_MSC_VER))) -#define HAS_HALFFLOATROW_SSE2 -#endif - -// The following are available on Neon platforms: -#if !defined(LIBYUV_DISABLE_NEON) && \ - (defined(__aarch64__) || defined(__ARM_NEON__) || defined(LIBYUV_NEON)) -#define HAS_ABGRTOUVROW_NEON -#define HAS_ABGRTOYROW_NEON -#define HAS_ARGB1555TOARGBROW_NEON -#define HAS_ARGB1555TOUVROW_NEON -#define HAS_ARGB1555TOYROW_NEON -#define HAS_ARGB4444TOARGBROW_NEON -#define HAS_ARGB4444TOUVROW_NEON -#define HAS_ARGB4444TOYROW_NEON -#define HAS_ARGBSETROW_NEON -#define HAS_ARGBTOARGB1555ROW_NEON -#define HAS_ARGBTOARGB4444ROW_NEON -#define HAS_ARGBTORAWROW_NEON -#define HAS_ARGBTORGB24ROW_NEON -#define HAS_ARGBTORGB565DITHERROW_NEON -#define HAS_ARGBTORGB565ROW_NEON -#define HAS_ARGBTOUV411ROW_NEON -#define HAS_ARGBTOUV444ROW_NEON -#define HAS_ARGBTOUVJROW_NEON -#define HAS_ARGBTOUVROW_NEON -#define HAS_ARGBTOYJROW_NEON -#define HAS_ARGBTOYROW_NEON -#define HAS_ARGBEXTRACTALPHAROW_NEON -#define HAS_BGRATOUVROW_NEON -#define HAS_BGRATOYROW_NEON -#define HAS_COPYROW_NEON -#define HAS_I400TOARGBROW_NEON -#define HAS_I411TOARGBROW_NEON -#define HAS_I422ALPHATOARGBROW_NEON -#define HAS_I422TOARGB1555ROW_NEON -#define HAS_I422TOARGB4444ROW_NEON -#define HAS_I422TOARGBROW_NEON -#define HAS_I422TORGB24ROW_NEON -#define HAS_I422TORGB565ROW_NEON -#define HAS_I422TORGBAROW_NEON -#define HAS_I422TOUYVYROW_NEON -#define HAS_I422TOYUY2ROW_NEON -#define HAS_I444TOARGBROW_NEON -#define HAS_J400TOARGBROW_NEON -#define HAS_MERGEUVROW_NEON -#define HAS_MIRRORROW_NEON -#define HAS_MIRRORUVROW_NEON -#define HAS_NV12TOARGBROW_NEON -#define HAS_NV12TORGB565ROW_NEON -#define HAS_NV21TOARGBROW_NEON -#define HAS_RAWTOARGBROW_NEON -#define HAS_RAWTORGB24ROW_NEON -#define HAS_RAWTOUVROW_NEON -#define HAS_RAWTOYROW_NEON -#define HAS_RGB24TOARGBROW_NEON -#define HAS_RGB24TOUVROW_NEON -#define HAS_RGB24TOYROW_NEON -#define HAS_RGB565TOARGBROW_NEON -#define HAS_RGB565TOUVROW_NEON -#define HAS_RGB565TOYROW_NEON -#define HAS_RGBATOUVROW_NEON -#define HAS_RGBATOYROW_NEON -#define HAS_SETROW_NEON -#define HAS_SPLITUVROW_NEON -#define HAS_UYVYTOARGBROW_NEON -#define HAS_UYVYTOUV422ROW_NEON -#define HAS_UYVYTOUVROW_NEON -#define HAS_UYVYTOYROW_NEON -#define HAS_YUY2TOARGBROW_NEON -#define HAS_YUY2TOUV422ROW_NEON -#define HAS_YUY2TOUVROW_NEON -#define HAS_YUY2TOYROW_NEON - -// Effects: -#define HAS_ARGBADDROW_NEON -#define HAS_ARGBATTENUATEROW_NEON -#define HAS_ARGBBLENDROW_NEON -#define HAS_ARGBCOLORMATRIXROW_NEON -#define HAS_ARGBGRAYROW_NEON -#define HAS_ARGBMIRRORROW_NEON -#define HAS_ARGBMULTIPLYROW_NEON -#define HAS_ARGBQUANTIZEROW_NEON -#define HAS_ARGBSEPIAROW_NEON -#define HAS_ARGBSHADEROW_NEON -#define HAS_ARGBSHUFFLEROW_NEON -#define HAS_ARGBSUBTRACTROW_NEON -#define HAS_INTERPOLATEROW_NEON -#define HAS_SOBELROW_NEON -#define HAS_SOBELTOPLANEROW_NEON -#define HAS_SOBELXROW_NEON -#define HAS_SOBELXYROW_NEON -#define HAS_SOBELYROW_NEON -#endif - -// The following are available on Mips platforms: -#if !defined(LIBYUV_DISABLE_MIPS) && defined(__mips__) && \ - (_MIPS_SIM == _MIPS_SIM_ABI32) && (__mips_isa_rev < 6) -#define HAS_COPYROW_MIPS -#if defined(__mips_dsp) && (__mips_dsp_rev >= 2) -#define HAS_I422TOARGBROW_DSPR2 -#define HAS_INTERPOLATEROW_DSPR2 -#define HAS_MIRRORROW_DSPR2 -#define HAS_MIRRORUVROW_DSPR2 -#define HAS_SPLITUVROW_DSPR2 -#endif -#endif - -#if !defined(LIBYUV_DISABLE_MSA) && defined(__mips_msa) -#define HAS_MIRRORROW_MSA -#define HAS_ARGBMIRRORROW_MSA -#endif - -#if defined(_MSC_VER) && !defined(__CLR_VER) && !defined(__clang__) -#if defined(VISUALC_HAS_AVX2) -#define SIMD_ALIGNED(var) __declspec(align(32)) var -#else -#define SIMD_ALIGNED(var) __declspec(align(16)) var -#endif -typedef __declspec(align(16)) int16 vec16[8]; -typedef __declspec(align(16)) int32 vec32[4]; -typedef __declspec(align(16)) int8 vec8[16]; -typedef __declspec(align(16)) uint16 uvec16[8]; -typedef __declspec(align(16)) uint32 uvec32[4]; -typedef __declspec(align(16)) uint8 uvec8[16]; -typedef __declspec(align(32)) int16 lvec16[16]; -typedef __declspec(align(32)) int32 lvec32[8]; -typedef __declspec(align(32)) int8 lvec8[32]; -typedef __declspec(align(32)) uint16 ulvec16[16]; -typedef __declspec(align(32)) uint32 ulvec32[8]; -typedef __declspec(align(32)) uint8 ulvec8[32]; -#elif !defined(__pnacl__) && (defined(__GNUC__) || defined(__clang__)) -// Caveat GCC 4.2 to 4.7 have a known issue using vectors with const. -#if defined(CLANG_HAS_AVX2) || defined(GCC_HAS_AVX2) -#define SIMD_ALIGNED(var) var __attribute__((aligned(32))) -#else -#define SIMD_ALIGNED(var) var __attribute__((aligned(16))) -#endif -typedef int16 __attribute__((vector_size(16))) vec16; -typedef int32 __attribute__((vector_size(16))) vec32; -typedef int8 __attribute__((vector_size(16))) vec8; -typedef uint16 __attribute__((vector_size(16))) uvec16; -typedef uint32 __attribute__((vector_size(16))) uvec32; -typedef uint8 __attribute__((vector_size(16))) uvec8; -typedef int16 __attribute__((vector_size(32))) lvec16; -typedef int32 __attribute__((vector_size(32))) lvec32; -typedef int8 __attribute__((vector_size(32))) lvec8; -typedef uint16 __attribute__((vector_size(32))) ulvec16; -typedef uint32 __attribute__((vector_size(32))) ulvec32; -typedef uint8 __attribute__((vector_size(32))) ulvec8; -#else -#define SIMD_ALIGNED(var) var -typedef int16 vec16[8]; -typedef int32 vec32[4]; -typedef int8 vec8[16]; -typedef uint16 uvec16[8]; -typedef uint32 uvec32[4]; -typedef uint8 uvec8[16]; -typedef int16 lvec16[16]; -typedef int32 lvec32[8]; -typedef int8 lvec8[32]; -typedef uint16 ulvec16[16]; -typedef uint32 ulvec32[8]; -typedef uint8 ulvec8[32]; -#endif - -#if defined(__aarch64__) -// This struct is for Arm64 color conversion. -struct YuvConstants { - uvec16 kUVToRB; - uvec16 kUVToRB2; - uvec16 kUVToG; - uvec16 kUVToG2; - vec16 kUVBiasBGR; - vec32 kYToRgb; -}; -#elif defined(__arm__) -// This struct is for ArmV7 color conversion. -struct YuvConstants { - uvec8 kUVToRB; - uvec8 kUVToG; - vec16 kUVBiasBGR; - vec32 kYToRgb; -}; -#else -// This struct is for Intel color conversion. -struct YuvConstants { - int8 kUVToB[32]; - int8 kUVToG[32]; - int8 kUVToR[32]; - int16 kUVBiasB[16]; - int16 kUVBiasG[16]; - int16 kUVBiasR[16]; - int16 kYToRgb[16]; -}; - -// Offsets into YuvConstants structure -#define KUVTOB 0 -#define KUVTOG 32 -#define KUVTOR 64 -#define KUVBIASB 96 -#define KUVBIASG 128 -#define KUVBIASR 160 -#define KYTORGB 192 -#endif - -// Conversion matrix for YUV to RGB -extern const struct YuvConstants SIMD_ALIGNED(kYuvI601Constants); // BT.601 -extern const struct YuvConstants SIMD_ALIGNED(kYuvJPEGConstants); // JPeg -extern const struct YuvConstants SIMD_ALIGNED(kYuvH709Constants); // BT.709 - -// Conversion matrix for YVU to BGR -extern const struct YuvConstants SIMD_ALIGNED(kYvuI601Constants); // BT.601 -extern const struct YuvConstants SIMD_ALIGNED(kYvuJPEGConstants); // JPeg -extern const struct YuvConstants SIMD_ALIGNED(kYvuH709Constants); // BT.709 - -#if defined(__APPLE__) || defined(__x86_64__) || defined(__llvm__) -#define OMITFP -#else -#define OMITFP __attribute__((optimize("omit-frame-pointer"))) -#endif - -// NaCL macros for GCC x86 and x64. -#if defined(__native_client__) -#define LABELALIGN ".p2align 5\n" -#else -#define LABELALIGN -#endif -#if defined(__native_client__) && defined(__x86_64__) -// r14 is used for MEMOP macros. -#define NACL_R14 "r14", -#define BUNDLELOCK ".bundle_lock\n" -#define BUNDLEUNLOCK ".bundle_unlock\n" -#define MEMACCESS(base) "%%nacl:(%%r15,%q" #base ")" -#define MEMACCESS2(offset, base) "%%nacl:" #offset "(%%r15,%q" #base ")" -#define MEMLEA(offset, base) #offset "(%q" #base ")" -#define MEMLEA3(offset, index, scale) \ - #offset "(,%q" #index "," #scale ")" -#define MEMLEA4(offset, base, index, scale) \ - #offset "(%q" #base ",%q" #index "," #scale ")" -#define MEMMOVESTRING(s, d) "%%nacl:(%q" #s "),%%nacl:(%q" #d "), %%r15" -#define MEMSTORESTRING(reg, d) "%%" #reg ",%%nacl:(%q" #d "), %%r15" -#define MEMOPREG(opcode, offset, base, index, scale, reg) \ - BUNDLELOCK \ - "lea " #offset "(%q" #base ",%q" #index "," #scale "),%%r14d\n" \ - #opcode " (%%r15,%%r14),%%" #reg "\n" \ - BUNDLEUNLOCK -#define MEMOPMEM(opcode, reg, offset, base, index, scale) \ - BUNDLELOCK \ - "lea " #offset "(%q" #base ",%q" #index "," #scale "),%%r14d\n" \ - #opcode " %%" #reg ",(%%r15,%%r14)\n" \ - BUNDLEUNLOCK -#define MEMOPARG(opcode, offset, base, index, scale, arg) \ - BUNDLELOCK \ - "lea " #offset "(%q" #base ",%q" #index "," #scale "),%%r14d\n" \ - #opcode " (%%r15,%%r14),%" #arg "\n" \ - BUNDLEUNLOCK -#define VMEMOPREG(opcode, offset, base, index, scale, reg1, reg2) \ - BUNDLELOCK \ - "lea " #offset "(%q" #base ",%q" #index "," #scale "),%%r14d\n" \ - #opcode " (%%r15,%%r14),%%" #reg1 ",%%" #reg2 "\n" \ - BUNDLEUNLOCK -#define VEXTOPMEM(op, sel, reg, offset, base, index, scale) \ - BUNDLELOCK \ - "lea " #offset "(%q" #base ",%q" #index "," #scale "),%%r14d\n" \ - #op " $" #sel ",%%" #reg ",(%%r15,%%r14)\n" \ - BUNDLEUNLOCK -#else // defined(__native_client__) && defined(__x86_64__) -#define NACL_R14 -#define BUNDLEALIGN -#define MEMACCESS(base) "(%" #base ")" -#define MEMACCESS2(offset, base) #offset "(%" #base ")" -#define MEMLEA(offset, base) #offset "(%" #base ")" -#define MEMLEA3(offset, index, scale) \ - #offset "(,%" #index "," #scale ")" -#define MEMLEA4(offset, base, index, scale) \ - #offset "(%" #base ",%" #index "," #scale ")" -#define MEMMOVESTRING(s, d) -#define MEMSTORESTRING(reg, d) -#define MEMOPREG(opcode, offset, base, index, scale, reg) \ - #opcode " " #offset "(%" #base ",%" #index "," #scale "),%%" #reg "\n" -#define MEMOPMEM(opcode, reg, offset, base, index, scale) \ - #opcode " %%" #reg ","#offset "(%" #base ",%" #index "," #scale ")\n" -#define MEMOPARG(opcode, offset, base, index, scale, arg) \ - #opcode " " #offset "(%" #base ",%" #index "," #scale "),%" #arg "\n" -#define VMEMOPREG(opcode, offset, base, index, scale, reg1, reg2) \ - #opcode " " #offset "(%" #base ",%" #index "," #scale "),%%" #reg1 ",%%" \ - #reg2 "\n" -#define VEXTOPMEM(op, sel, reg, offset, base, index, scale) \ - #op " $" #sel ",%%" #reg ","#offset "(%" #base ",%" #index "," #scale ")\n" -#endif // defined(__native_client__) && defined(__x86_64__) - -#if defined(__arm__) || defined(__aarch64__) -#undef MEMACCESS -#if defined(__native_client__) -#define MEMACCESS(base) ".p2align 3\nbic %" #base ", #0xc0000000\n" -#else -#define MEMACCESS(base) -#endif -#endif - -void I444ToARGBRow_NEON(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I422ToARGBRow_NEON(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I422AlphaToARGBRow_NEON(const uint8* y_buf, - const uint8* u_buf, - const uint8* v_buf, - const uint8* a_buf, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I422ToARGBRow_NEON(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I411ToARGBRow_NEON(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I422ToRGBARow_NEON(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_rgba, - const struct YuvConstants* yuvconstants, - int width); -void I422ToRGB24Row_NEON(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_rgb24, - const struct YuvConstants* yuvconstants, - int width); -void I422ToRGB565Row_NEON(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_rgb565, - const struct YuvConstants* yuvconstants, - int width); -void I422ToARGB1555Row_NEON(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb1555, - const struct YuvConstants* yuvconstants, - int width); -void I422ToARGB4444Row_NEON(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb4444, - const struct YuvConstants* yuvconstants, - int width); -void NV12ToARGBRow_NEON(const uint8* src_y, - const uint8* src_uv, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void NV12ToRGB565Row_NEON(const uint8* src_y, - const uint8* src_uv, - uint8* dst_rgb565, - const struct YuvConstants* yuvconstants, - int width); -void NV21ToARGBRow_NEON(const uint8* src_y, - const uint8* src_vu, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void YUY2ToARGBRow_NEON(const uint8* src_yuy2, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void UYVYToARGBRow_NEON(const uint8* src_uyvy, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); - -void ARGBToYRow_AVX2(const uint8* src_argb, uint8* dst_y, int width); -void ARGBToYRow_Any_AVX2(const uint8* src_argb, uint8* dst_y, int width); -void ARGBToYRow_SSSE3(const uint8* src_argb, uint8* dst_y, int width); -void ARGBToYJRow_AVX2(const uint8* src_argb, uint8* dst_y, int width); -void ARGBToYJRow_Any_AVX2(const uint8* src_argb, uint8* dst_y, int width); -void ARGBToYJRow_SSSE3(const uint8* src_argb, uint8* dst_y, int width); -void BGRAToYRow_SSSE3(const uint8* src_bgra, uint8* dst_y, int width); -void ABGRToYRow_SSSE3(const uint8* src_abgr, uint8* dst_y, int width); -void RGBAToYRow_SSSE3(const uint8* src_rgba, uint8* dst_y, int width); -void RGB24ToYRow_SSSE3(const uint8* src_rgb24, uint8* dst_y, int width); -void RAWToYRow_SSSE3(const uint8* src_raw, uint8* dst_y, int width); -void ARGBToYRow_NEON(const uint8* src_argb, uint8* dst_y, int width); -void ARGBToYJRow_NEON(const uint8* src_argb, uint8* dst_y, int width); -void ARGBToUV444Row_NEON(const uint8* src_argb, uint8* dst_u, uint8* dst_v, - int width); -void ARGBToUV411Row_NEON(const uint8* src_argb, uint8* dst_u, uint8* dst_v, - int width); -void ARGBToUVRow_NEON(const uint8* src_argb, int src_stride_argb, - uint8* dst_u, uint8* dst_v, int width); -void ARGBToUVJRow_NEON(const uint8* src_argb, int src_stride_argb, - uint8* dst_u, uint8* dst_v, int width); -void BGRAToUVRow_NEON(const uint8* src_bgra, int src_stride_bgra, - uint8* dst_u, uint8* dst_v, int width); -void ABGRToUVRow_NEON(const uint8* src_abgr, int src_stride_abgr, - uint8* dst_u, uint8* dst_v, int width); -void RGBAToUVRow_NEON(const uint8* src_rgba, int src_stride_rgba, - uint8* dst_u, uint8* dst_v, int width); -void RGB24ToUVRow_NEON(const uint8* src_rgb24, int src_stride_rgb24, - uint8* dst_u, uint8* dst_v, int width); -void RAWToUVRow_NEON(const uint8* src_raw, int src_stride_raw, - uint8* dst_u, uint8* dst_v, int width); -void RGB565ToUVRow_NEON(const uint8* src_rgb565, int src_stride_rgb565, - uint8* dst_u, uint8* dst_v, int width); -void ARGB1555ToUVRow_NEON(const uint8* src_argb1555, int src_stride_argb1555, - uint8* dst_u, uint8* dst_v, int width); -void ARGB4444ToUVRow_NEON(const uint8* src_argb4444, int src_stride_argb4444, - uint8* dst_u, uint8* dst_v, int width); -void BGRAToYRow_NEON(const uint8* src_bgra, uint8* dst_y, int width); -void ABGRToYRow_NEON(const uint8* src_abgr, uint8* dst_y, int width); -void RGBAToYRow_NEON(const uint8* src_rgba, uint8* dst_y, int width); -void RGB24ToYRow_NEON(const uint8* src_rgb24, uint8* dst_y, int width); -void RAWToYRow_NEON(const uint8* src_raw, uint8* dst_y, int width); -void RGB565ToYRow_NEON(const uint8* src_rgb565, uint8* dst_y, int width); -void ARGB1555ToYRow_NEON(const uint8* src_argb1555, uint8* dst_y, int width); -void ARGB4444ToYRow_NEON(const uint8* src_argb4444, uint8* dst_y, int width); -void ARGBToYRow_C(const uint8* src_argb, uint8* dst_y, int width); -void ARGBToYJRow_C(const uint8* src_argb, uint8* dst_y, int width); -void BGRAToYRow_C(const uint8* src_bgra, uint8* dst_y, int width); -void ABGRToYRow_C(const uint8* src_abgr, uint8* dst_y, int width); -void RGBAToYRow_C(const uint8* src_rgba, uint8* dst_y, int width); -void RGB24ToYRow_C(const uint8* src_rgb24, uint8* dst_y, int width); -void RAWToYRow_C(const uint8* src_raw, uint8* dst_y, int width); -void RGB565ToYRow_C(const uint8* src_rgb565, uint8* dst_y, int width); -void ARGB1555ToYRow_C(const uint8* src_argb1555, uint8* dst_y, int width); -void ARGB4444ToYRow_C(const uint8* src_argb4444, uint8* dst_y, int width); -void ARGBToYRow_Any_SSSE3(const uint8* src_argb, uint8* dst_y, int width); -void ARGBToYJRow_Any_SSSE3(const uint8* src_argb, uint8* dst_y, int width); -void BGRAToYRow_Any_SSSE3(const uint8* src_bgra, uint8* dst_y, int width); -void ABGRToYRow_Any_SSSE3(const uint8* src_abgr, uint8* dst_y, int width); -void RGBAToYRow_Any_SSSE3(const uint8* src_rgba, uint8* dst_y, int width); -void RGB24ToYRow_Any_SSSE3(const uint8* src_rgb24, uint8* dst_y, int width); -void RAWToYRow_Any_SSSE3(const uint8* src_raw, uint8* dst_y, int width); -void ARGBToYRow_Any_NEON(const uint8* src_argb, uint8* dst_y, int width); -void ARGBToYJRow_Any_NEON(const uint8* src_argb, uint8* dst_y, int width); -void BGRAToYRow_Any_NEON(const uint8* src_bgra, uint8* dst_y, int width); -void ABGRToYRow_Any_NEON(const uint8* src_abgr, uint8* dst_y, int width); -void RGBAToYRow_Any_NEON(const uint8* src_rgba, uint8* dst_y, int width); -void RGB24ToYRow_Any_NEON(const uint8* src_rgb24, uint8* dst_y, int width); -void RAWToYRow_Any_NEON(const uint8* src_raw, uint8* dst_y, int width); -void RGB565ToYRow_Any_NEON(const uint8* src_rgb565, uint8* dst_y, int width); -void ARGB1555ToYRow_Any_NEON(const uint8* src_argb1555, uint8* dst_y, - int width); -void ARGB4444ToYRow_Any_NEON(const uint8* src_argb4444, uint8* dst_y, - int width); - -void ARGBToUVRow_AVX2(const uint8* src_argb, int src_stride_argb, - uint8* dst_u, uint8* dst_v, int width); -void ARGBToUVJRow_AVX2(const uint8* src_argb, int src_stride_argb, - uint8* dst_u, uint8* dst_v, int width); -void ARGBToUVRow_SSSE3(const uint8* src_argb, int src_stride_argb, - uint8* dst_u, uint8* dst_v, int width); -void ARGBToUVJRow_SSSE3(const uint8* src_argb, int src_stride_argb, - uint8* dst_u, uint8* dst_v, int width); -void BGRAToUVRow_SSSE3(const uint8* src_bgra, int src_stride_bgra, - uint8* dst_u, uint8* dst_v, int width); -void ABGRToUVRow_SSSE3(const uint8* src_abgr, int src_stride_abgr, - uint8* dst_u, uint8* dst_v, int width); -void RGBAToUVRow_SSSE3(const uint8* src_rgba, int src_stride_rgba, - uint8* dst_u, uint8* dst_v, int width); -void ARGBToUVRow_Any_AVX2(const uint8* src_argb, int src_stride_argb, - uint8* dst_u, uint8* dst_v, int width); -void ARGBToUVJRow_Any_AVX2(const uint8* src_argb, int src_stride_argb, - uint8* dst_u, uint8* dst_v, int width); -void ARGBToUVRow_Any_SSSE3(const uint8* src_argb, int src_stride_argb, - uint8* dst_u, uint8* dst_v, int width); -void ARGBToUVJRow_Any_SSSE3(const uint8* src_argb, int src_stride_argb, - uint8* dst_u, uint8* dst_v, int width); -void BGRAToUVRow_Any_SSSE3(const uint8* src_bgra, int src_stride_bgra, - uint8* dst_u, uint8* dst_v, int width); -void ABGRToUVRow_Any_SSSE3(const uint8* src_abgr, int src_stride_abgr, - uint8* dst_u, uint8* dst_v, int width); -void RGBAToUVRow_Any_SSSE3(const uint8* src_rgba, int src_stride_rgba, - uint8* dst_u, uint8* dst_v, int width); -void ARGBToUV444Row_Any_NEON(const uint8* src_argb, uint8* dst_u, uint8* dst_v, - int width); -void ARGBToUV411Row_Any_NEON(const uint8* src_argb, uint8* dst_u, uint8* dst_v, - int width); -void ARGBToUVRow_Any_NEON(const uint8* src_argb, int src_stride_argb, - uint8* dst_u, uint8* dst_v, int width); -void ARGBToUVJRow_Any_NEON(const uint8* src_argb, int src_stride_argb, - uint8* dst_u, uint8* dst_v, int width); -void BGRAToUVRow_Any_NEON(const uint8* src_bgra, int src_stride_bgra, - uint8* dst_u, uint8* dst_v, int width); -void ABGRToUVRow_Any_NEON(const uint8* src_abgr, int src_stride_abgr, - uint8* dst_u, uint8* dst_v, int width); -void RGBAToUVRow_Any_NEON(const uint8* src_rgba, int src_stride_rgba, - uint8* dst_u, uint8* dst_v, int width); -void RGB24ToUVRow_Any_NEON(const uint8* src_rgb24, int src_stride_rgb24, - uint8* dst_u, uint8* dst_v, int width); -void RAWToUVRow_Any_NEON(const uint8* src_raw, int src_stride_raw, - uint8* dst_u, uint8* dst_v, int width); -void RGB565ToUVRow_Any_NEON(const uint8* src_rgb565, int src_stride_rgb565, - uint8* dst_u, uint8* dst_v, int width); -void ARGB1555ToUVRow_Any_NEON(const uint8* src_argb1555, - int src_stride_argb1555, - uint8* dst_u, uint8* dst_v, int width); -void ARGB4444ToUVRow_Any_NEON(const uint8* src_argb4444, - int src_stride_argb4444, - uint8* dst_u, uint8* dst_v, int width); -void ARGBToUVRow_C(const uint8* src_argb, int src_stride_argb, - uint8* dst_u, uint8* dst_v, int width); -void ARGBToUVJRow_C(const uint8* src_argb, int src_stride_argb, - uint8* dst_u, uint8* dst_v, int width); -void BGRAToUVRow_C(const uint8* src_bgra, int src_stride_bgra, - uint8* dst_u, uint8* dst_v, int width); -void ABGRToUVRow_C(const uint8* src_abgr, int src_stride_abgr, - uint8* dst_u, uint8* dst_v, int width); -void RGBAToUVRow_C(const uint8* src_rgba, int src_stride_rgba, - uint8* dst_u, uint8* dst_v, int width); -void RGB24ToUVRow_C(const uint8* src_rgb24, int src_stride_rgb24, - uint8* dst_u, uint8* dst_v, int width); -void RAWToUVRow_C(const uint8* src_raw, int src_stride_raw, - uint8* dst_u, uint8* dst_v, int width); -void RGB565ToUVRow_C(const uint8* src_rgb565, int src_stride_rgb565, - uint8* dst_u, uint8* dst_v, int width); -void ARGB1555ToUVRow_C(const uint8* src_argb1555, int src_stride_argb1555, - uint8* dst_u, uint8* dst_v, int width); -void ARGB4444ToUVRow_C(const uint8* src_argb4444, int src_stride_argb4444, - uint8* dst_u, uint8* dst_v, int width); - -void ARGBToUV444Row_SSSE3(const uint8* src_argb, - uint8* dst_u, uint8* dst_v, int width); -void ARGBToUV444Row_Any_SSSE3(const uint8* src_argb, - uint8* dst_u, uint8* dst_v, int width); - -void ARGBToUV444Row_C(const uint8* src_argb, - uint8* dst_u, uint8* dst_v, int width); -void ARGBToUV411Row_C(const uint8* src_argb, - uint8* dst_u, uint8* dst_v, int width); - -void MirrorRow_AVX2(const uint8* src, uint8* dst, int width); -void MirrorRow_SSSE3(const uint8* src, uint8* dst, int width); -void MirrorRow_NEON(const uint8* src, uint8* dst, int width); -void MirrorRow_DSPR2(const uint8* src, uint8* dst, int width); -void MirrorRow_MSA(const uint8* src, uint8* dst, int width); -void MirrorRow_C(const uint8* src, uint8* dst, int width); -void MirrorRow_Any_AVX2(const uint8* src, uint8* dst, int width); -void MirrorRow_Any_SSSE3(const uint8* src, uint8* dst, int width); -void MirrorRow_Any_SSE2(const uint8* src, uint8* dst, int width); -void MirrorRow_Any_NEON(const uint8* src, uint8* dst, int width); -void MirrorRow_Any_MSA(const uint8* src, uint8* dst, int width); - -void MirrorUVRow_SSSE3(const uint8* src_uv, uint8* dst_u, uint8* dst_v, - int width); -void MirrorUVRow_NEON(const uint8* src_uv, uint8* dst_u, uint8* dst_v, - int width); -void MirrorUVRow_DSPR2(const uint8* src_uv, uint8* dst_u, uint8* dst_v, - int width); -void MirrorUVRow_C(const uint8* src_uv, uint8* dst_u, uint8* dst_v, int width); - -void ARGBMirrorRow_AVX2(const uint8* src, uint8* dst, int width); -void ARGBMirrorRow_SSE2(const uint8* src, uint8* dst, int width); -void ARGBMirrorRow_NEON(const uint8* src, uint8* dst, int width); -void ARGBMirrorRow_MSA(const uint8* src, uint8* dst, int width); -void ARGBMirrorRow_C(const uint8* src, uint8* dst, int width); -void ARGBMirrorRow_Any_AVX2(const uint8* src, uint8* dst, int width); -void ARGBMirrorRow_Any_SSE2(const uint8* src, uint8* dst, int width); -void ARGBMirrorRow_Any_NEON(const uint8* src, uint8* dst, int width); -void ARGBMirrorRow_Any_MSA(const uint8* src, uint8* dst, int width); - -void SplitUVRow_C(const uint8* src_uv, uint8* dst_u, uint8* dst_v, int width); -void SplitUVRow_SSE2(const uint8* src_uv, uint8* dst_u, uint8* dst_v, - int width); -void SplitUVRow_AVX2(const uint8* src_uv, uint8* dst_u, uint8* dst_v, - int width); -void SplitUVRow_NEON(const uint8* src_uv, uint8* dst_u, uint8* dst_v, - int width); -void SplitUVRow_DSPR2(const uint8* src_uv, uint8* dst_u, uint8* dst_v, - int width); -void SplitUVRow_Any_SSE2(const uint8* src_uv, uint8* dst_u, uint8* dst_v, - int width); -void SplitUVRow_Any_AVX2(const uint8* src_uv, uint8* dst_u, uint8* dst_v, - int width); -void SplitUVRow_Any_NEON(const uint8* src_uv, uint8* dst_u, uint8* dst_v, - int width); -void SplitUVRow_Any_DSPR2(const uint8* src_uv, uint8* dst_u, uint8* dst_v, - int width); - -void MergeUVRow_C(const uint8* src_u, const uint8* src_v, uint8* dst_uv, - int width); -void MergeUVRow_SSE2(const uint8* src_u, const uint8* src_v, uint8* dst_uv, - int width); -void MergeUVRow_AVX2(const uint8* src_u, const uint8* src_v, uint8* dst_uv, - int width); -void MergeUVRow_NEON(const uint8* src_u, const uint8* src_v, uint8* dst_uv, - int width); -void MergeUVRow_Any_SSE2(const uint8* src_u, const uint8* src_v, uint8* dst_uv, - int width); -void MergeUVRow_Any_AVX2(const uint8* src_u, const uint8* src_v, uint8* dst_uv, - int width); -void MergeUVRow_Any_NEON(const uint8* src_u, const uint8* src_v, uint8* dst_uv, - int width); - -void CopyRow_SSE2(const uint8* src, uint8* dst, int count); -void CopyRow_AVX(const uint8* src, uint8* dst, int count); -void CopyRow_ERMS(const uint8* src, uint8* dst, int count); -void CopyRow_NEON(const uint8* src, uint8* dst, int count); -void CopyRow_MIPS(const uint8* src, uint8* dst, int count); -void CopyRow_C(const uint8* src, uint8* dst, int count); -void CopyRow_Any_SSE2(const uint8* src, uint8* dst, int count); -void CopyRow_Any_AVX(const uint8* src, uint8* dst, int count); -void CopyRow_Any_NEON(const uint8* src, uint8* dst, int count); - -void CopyRow_16_C(const uint16* src, uint16* dst, int count); - -void ARGBCopyAlphaRow_C(const uint8* src_argb, uint8* dst_argb, int width); -void ARGBCopyAlphaRow_SSE2(const uint8* src_argb, uint8* dst_argb, int width); -void ARGBCopyAlphaRow_AVX2(const uint8* src_argb, uint8* dst_argb, int width); -void ARGBCopyAlphaRow_Any_SSE2(const uint8* src_argb, uint8* dst_argb, - int width); -void ARGBCopyAlphaRow_Any_AVX2(const uint8* src_argb, uint8* dst_argb, - int width); - -void ARGBExtractAlphaRow_C(const uint8* src_argb, uint8* dst_a, int width); -void ARGBExtractAlphaRow_SSE2(const uint8* src_argb, uint8* dst_a, int width); -void ARGBExtractAlphaRow_NEON(const uint8* src_argb, uint8* dst_a, int width); -void ARGBExtractAlphaRow_Any_SSE2(const uint8* src_argb, uint8* dst_a, - int width); -void ARGBExtractAlphaRow_Any_NEON(const uint8* src_argb, uint8* dst_a, - int width); - -void ARGBCopyYToAlphaRow_C(const uint8* src_y, uint8* dst_argb, int width); -void ARGBCopyYToAlphaRow_SSE2(const uint8* src_y, uint8* dst_argb, int width); -void ARGBCopyYToAlphaRow_AVX2(const uint8* src_y, uint8* dst_argb, int width); -void ARGBCopyYToAlphaRow_Any_SSE2(const uint8* src_y, uint8* dst_argb, - int width); -void ARGBCopyYToAlphaRow_Any_AVX2(const uint8* src_y, uint8* dst_argb, - int width); - -void SetRow_C(uint8* dst, uint8 v8, int count); -void SetRow_X86(uint8* dst, uint8 v8, int count); -void SetRow_ERMS(uint8* dst, uint8 v8, int count); -void SetRow_NEON(uint8* dst, uint8 v8, int count); -void SetRow_Any_X86(uint8* dst, uint8 v8, int count); -void SetRow_Any_NEON(uint8* dst, uint8 v8, int count); - -void ARGBSetRow_C(uint8* dst_argb, uint32 v32, int count); -void ARGBSetRow_X86(uint8* dst_argb, uint32 v32, int count); -void ARGBSetRow_NEON(uint8* dst_argb, uint32 v32, int count); -void ARGBSetRow_Any_NEON(uint8* dst_argb, uint32 v32, int count); - -// ARGBShufflers for BGRAToARGB etc. -void ARGBShuffleRow_C(const uint8* src_argb, uint8* dst_argb, - const uint8* shuffler, int width); -void ARGBShuffleRow_SSE2(const uint8* src_argb, uint8* dst_argb, - const uint8* shuffler, int width); -void ARGBShuffleRow_SSSE3(const uint8* src_argb, uint8* dst_argb, - const uint8* shuffler, int width); -void ARGBShuffleRow_AVX2(const uint8* src_argb, uint8* dst_argb, - const uint8* shuffler, int width); -void ARGBShuffleRow_NEON(const uint8* src_argb, uint8* dst_argb, - const uint8* shuffler, int width); -void ARGBShuffleRow_Any_SSE2(const uint8* src_argb, uint8* dst_argb, - const uint8* shuffler, int width); -void ARGBShuffleRow_Any_SSSE3(const uint8* src_argb, uint8* dst_argb, - const uint8* shuffler, int width); -void ARGBShuffleRow_Any_AVX2(const uint8* src_argb, uint8* dst_argb, - const uint8* shuffler, int width); -void ARGBShuffleRow_Any_NEON(const uint8* src_argb, uint8* dst_argb, - const uint8* shuffler, int width); - -void RGB24ToARGBRow_SSSE3(const uint8* src_rgb24, uint8* dst_argb, int width); -void RAWToARGBRow_SSSE3(const uint8* src_raw, uint8* dst_argb, int width); -void RAWToRGB24Row_SSSE3(const uint8* src_raw, uint8* dst_rgb24, int width); -void RGB565ToARGBRow_SSE2(const uint8* src_rgb565, uint8* dst_argb, int width); -void ARGB1555ToARGBRow_SSE2(const uint8* src_argb1555, uint8* dst_argb, - int width); -void ARGB4444ToARGBRow_SSE2(const uint8* src_argb4444, uint8* dst_argb, - int width); -void RGB565ToARGBRow_AVX2(const uint8* src_rgb565, uint8* dst_argb, int width); -void ARGB1555ToARGBRow_AVX2(const uint8* src_argb1555, uint8* dst_argb, - int width); -void ARGB4444ToARGBRow_AVX2(const uint8* src_argb4444, uint8* dst_argb, - int width); - -void RGB24ToARGBRow_NEON(const uint8* src_rgb24, uint8* dst_argb, int width); -void RAWToARGBRow_NEON(const uint8* src_raw, uint8* dst_argb, int width); -void RAWToRGB24Row_NEON(const uint8* src_raw, uint8* dst_rgb24, int width); -void RGB565ToARGBRow_NEON(const uint8* src_rgb565, uint8* dst_argb, int width); -void ARGB1555ToARGBRow_NEON(const uint8* src_argb1555, uint8* dst_argb, - int width); -void ARGB4444ToARGBRow_NEON(const uint8* src_argb4444, uint8* dst_argb, - int width); -void RGB24ToARGBRow_C(const uint8* src_rgb24, uint8* dst_argb, int width); -void RAWToARGBRow_C(const uint8* src_raw, uint8* dst_argb, int width); -void RAWToRGB24Row_C(const uint8* src_raw, uint8* dst_rgb24, int width); -void RGB565ToARGBRow_C(const uint8* src_rgb, uint8* dst_argb, int width); -void ARGB1555ToARGBRow_C(const uint8* src_argb, uint8* dst_argb, int width); -void ARGB4444ToARGBRow_C(const uint8* src_argb, uint8* dst_argb, int width); -void RGB24ToARGBRow_Any_SSSE3(const uint8* src_rgb24, uint8* dst_argb, - int width); -void RAWToARGBRow_Any_SSSE3(const uint8* src_raw, uint8* dst_argb, int width); -void RAWToRGB24Row_Any_SSSE3(const uint8* src_raw, uint8* dst_rgb24, int width); - -void RGB565ToARGBRow_Any_SSE2(const uint8* src_rgb565, uint8* dst_argb, - int width); -void ARGB1555ToARGBRow_Any_SSE2(const uint8* src_argb1555, uint8* dst_argb, - int width); -void ARGB4444ToARGBRow_Any_SSE2(const uint8* src_argb4444, uint8* dst_argb, - int width); -void RGB565ToARGBRow_Any_AVX2(const uint8* src_rgb565, uint8* dst_argb, - int width); -void ARGB1555ToARGBRow_Any_AVX2(const uint8* src_argb1555, uint8* dst_argb, - int width); -void ARGB4444ToARGBRow_Any_AVX2(const uint8* src_argb4444, uint8* dst_argb, - int width); - -void RGB24ToARGBRow_Any_NEON(const uint8* src_rgb24, uint8* dst_argb, - int width); -void RAWToARGBRow_Any_NEON(const uint8* src_raw, uint8* dst_argb, int width); -void RAWToRGB24Row_Any_NEON(const uint8* src_raw, uint8* dst_rgb24, int width); -void RGB565ToARGBRow_Any_NEON(const uint8* src_rgb565, uint8* dst_argb, - int width); -void ARGB1555ToARGBRow_Any_NEON(const uint8* src_argb1555, uint8* dst_argb, - int width); -void ARGB4444ToARGBRow_Any_NEON(const uint8* src_argb4444, uint8* dst_argb, - int width); - -void ARGBToRGB24Row_SSSE3(const uint8* src_argb, uint8* dst_rgb, int width); -void ARGBToRAWRow_SSSE3(const uint8* src_argb, uint8* dst_rgb, int width); -void ARGBToRGB565Row_SSE2(const uint8* src_argb, uint8* dst_rgb, int width); -void ARGBToARGB1555Row_SSE2(const uint8* src_argb, uint8* dst_rgb, int width); -void ARGBToARGB4444Row_SSE2(const uint8* src_argb, uint8* dst_rgb, int width); - -void ARGBToRGB565DitherRow_C(const uint8* src_argb, uint8* dst_rgb, - const uint32 dither4, int width); -void ARGBToRGB565DitherRow_SSE2(const uint8* src_argb, uint8* dst_rgb, - const uint32 dither4, int width); -void ARGBToRGB565DitherRow_AVX2(const uint8* src_argb, uint8* dst_rgb, - const uint32 dither4, int width); - -void ARGBToRGB565Row_AVX2(const uint8* src_argb, uint8* dst_rgb, int width); -void ARGBToARGB1555Row_AVX2(const uint8* src_argb, uint8* dst_rgb, int width); -void ARGBToARGB4444Row_AVX2(const uint8* src_argb, uint8* dst_rgb, int width); - -void ARGBToRGB24Row_NEON(const uint8* src_argb, uint8* dst_rgb, int width); -void ARGBToRAWRow_NEON(const uint8* src_argb, uint8* dst_rgb, int width); -void ARGBToRGB565Row_NEON(const uint8* src_argb, uint8* dst_rgb, int width); -void ARGBToARGB1555Row_NEON(const uint8* src_argb, uint8* dst_rgb, int width); -void ARGBToARGB4444Row_NEON(const uint8* src_argb, uint8* dst_rgb, int width); -void ARGBToRGB565DitherRow_NEON(const uint8* src_argb, uint8* dst_rgb, - const uint32 dither4, int width); - -void ARGBToRGBARow_C(const uint8* src_argb, uint8* dst_rgb, int width); -void ARGBToRGB24Row_C(const uint8* src_argb, uint8* dst_rgb, int width); -void ARGBToRAWRow_C(const uint8* src_argb, uint8* dst_rgb, int width); -void ARGBToRGB565Row_C(const uint8* src_argb, uint8* dst_rgb, int width); -void ARGBToARGB1555Row_C(const uint8* src_argb, uint8* dst_rgb, int width); -void ARGBToARGB4444Row_C(const uint8* src_argb, uint8* dst_rgb, int width); - -void J400ToARGBRow_SSE2(const uint8* src_y, uint8* dst_argb, int width); -void J400ToARGBRow_AVX2(const uint8* src_y, uint8* dst_argb, int width); -void J400ToARGBRow_NEON(const uint8* src_y, uint8* dst_argb, int width); -void J400ToARGBRow_C(const uint8* src_y, uint8* dst_argb, int width); -void J400ToARGBRow_Any_SSE2(const uint8* src_y, uint8* dst_argb, int width); -void J400ToARGBRow_Any_AVX2(const uint8* src_y, uint8* dst_argb, int width); -void J400ToARGBRow_Any_NEON(const uint8* src_y, uint8* dst_argb, int width); - -void I444ToARGBRow_C(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I422ToARGBRow_C(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I422ToARGBRow_C(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I422AlphaToARGBRow_C(const uint8* y_buf, - const uint8* u_buf, - const uint8* v_buf, - const uint8* a_buf, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I411ToARGBRow_C(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void NV12ToARGBRow_C(const uint8* src_y, - const uint8* src_uv, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void NV12ToRGB565Row_C(const uint8* src_y, - const uint8* src_uv, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void NV21ToARGBRow_C(const uint8* src_y, - const uint8* src_uv, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void YUY2ToARGBRow_C(const uint8* src_yuy2, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void UYVYToARGBRow_C(const uint8* src_uyvy, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I422ToRGBARow_C(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_rgba, - const struct YuvConstants* yuvconstants, - int width); -void I422ToRGB24Row_C(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_rgb24, - const struct YuvConstants* yuvconstants, - int width); -void I422ToARGB4444Row_C(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb4444, - const struct YuvConstants* yuvconstants, - int width); -void I422ToARGB1555Row_C(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb4444, - const struct YuvConstants* yuvconstants, - int width); -void I422ToRGB565Row_C(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_rgb565, - const struct YuvConstants* yuvconstants, - int width); -void I422ToARGBRow_AVX2(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I422ToARGBRow_AVX2(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I422ToRGBARow_AVX2(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I444ToARGBRow_SSSE3(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I444ToARGBRow_AVX2(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I444ToARGBRow_SSSE3(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I444ToARGBRow_AVX2(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I422ToARGBRow_SSSE3(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I422AlphaToARGBRow_SSSE3(const uint8* y_buf, - const uint8* u_buf, - const uint8* v_buf, - const uint8* a_buf, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I422AlphaToARGBRow_AVX2(const uint8* y_buf, - const uint8* u_buf, - const uint8* v_buf, - const uint8* a_buf, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I422ToARGBRow_SSSE3(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I411ToARGBRow_SSSE3(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I411ToARGBRow_AVX2(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void NV12ToARGBRow_SSSE3(const uint8* src_y, - const uint8* src_uv, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void NV12ToARGBRow_AVX2(const uint8* src_y, - const uint8* src_uv, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void NV12ToRGB565Row_SSSE3(const uint8* src_y, - const uint8* src_uv, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void NV12ToRGB565Row_AVX2(const uint8* src_y, - const uint8* src_uv, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void NV21ToARGBRow_SSSE3(const uint8* src_y, - const uint8* src_uv, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void NV21ToARGBRow_AVX2(const uint8* src_y, - const uint8* src_uv, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void YUY2ToARGBRow_SSSE3(const uint8* src_yuy2, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void UYVYToARGBRow_SSSE3(const uint8* src_uyvy, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void YUY2ToARGBRow_AVX2(const uint8* src_yuy2, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void UYVYToARGBRow_AVX2(const uint8* src_uyvy, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I422ToRGBARow_SSSE3(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_rgba, - const struct YuvConstants* yuvconstants, - int width); -void I422ToARGB4444Row_SSSE3(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I422ToARGB4444Row_AVX2(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I422ToARGB1555Row_SSSE3(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I422ToARGB1555Row_AVX2(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I422ToRGB565Row_SSSE3(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I422ToRGB565Row_AVX2(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I422ToRGB24Row_SSSE3(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_rgb24, - const struct YuvConstants* yuvconstants, - int width); -void I422ToRGB24Row_AVX2(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_rgb24, - const struct YuvConstants* yuvconstants, - int width); -void I422ToARGBRow_Any_AVX2(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I422ToRGBARow_Any_AVX2(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I444ToARGBRow_Any_SSSE3(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I444ToARGBRow_Any_AVX2(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I422ToARGBRow_Any_SSSE3(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I422AlphaToARGBRow_Any_SSSE3(const uint8* y_buf, - const uint8* u_buf, - const uint8* v_buf, - const uint8* a_buf, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I422AlphaToARGBRow_Any_AVX2(const uint8* y_buf, - const uint8* u_buf, - const uint8* v_buf, - const uint8* a_buf, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I411ToARGBRow_Any_SSSE3(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I411ToARGBRow_Any_AVX2(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void NV12ToARGBRow_Any_SSSE3(const uint8* src_y, - const uint8* src_uv, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void NV12ToARGBRow_Any_AVX2(const uint8* src_y, - const uint8* src_uv, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void NV21ToARGBRow_Any_SSSE3(const uint8* src_y, - const uint8* src_vu, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void NV21ToARGBRow_Any_AVX2(const uint8* src_y, - const uint8* src_vu, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void NV12ToRGB565Row_Any_SSSE3(const uint8* src_y, - const uint8* src_uv, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void NV12ToRGB565Row_Any_AVX2(const uint8* src_y, - const uint8* src_uv, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void YUY2ToARGBRow_Any_SSSE3(const uint8* src_yuy2, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void UYVYToARGBRow_Any_SSSE3(const uint8* src_uyvy, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void YUY2ToARGBRow_Any_AVX2(const uint8* src_yuy2, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void UYVYToARGBRow_Any_AVX2(const uint8* src_uyvy, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I422ToRGBARow_Any_SSSE3(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_rgba, - const struct YuvConstants* yuvconstants, - int width); -void I422ToARGB4444Row_Any_SSSE3(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_rgba, - const struct YuvConstants* yuvconstants, - int width); -void I422ToARGB4444Row_Any_AVX2(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_rgba, - const struct YuvConstants* yuvconstants, - int width); -void I422ToARGB1555Row_Any_SSSE3(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_rgba, - const struct YuvConstants* yuvconstants, - int width); -void I422ToARGB1555Row_Any_AVX2(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_rgba, - const struct YuvConstants* yuvconstants, - int width); -void I422ToRGB565Row_Any_SSSE3(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_rgba, - const struct YuvConstants* yuvconstants, - int width); -void I422ToRGB565Row_Any_AVX2(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_rgba, - const struct YuvConstants* yuvconstants, - int width); -void I422ToRGB24Row_Any_SSSE3(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I422ToRGB24Row_Any_AVX2(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); - -void I400ToARGBRow_C(const uint8* src_y, uint8* dst_argb, int width); -void I400ToARGBRow_SSE2(const uint8* src_y, uint8* dst_argb, int width); -void I400ToARGBRow_AVX2(const uint8* src_y, uint8* dst_argb, int width); -void I400ToARGBRow_NEON(const uint8* src_y, uint8* dst_argb, int width); -void I400ToARGBRow_Any_SSE2(const uint8* src_y, uint8* dst_argb, int width); -void I400ToARGBRow_Any_AVX2(const uint8* src_y, uint8* dst_argb, int width); -void I400ToARGBRow_Any_NEON(const uint8* src_y, uint8* dst_argb, int width); - -// ARGB preattenuated alpha blend. -void ARGBBlendRow_SSSE3(const uint8* src_argb, const uint8* src_argb1, - uint8* dst_argb, int width); -void ARGBBlendRow_NEON(const uint8* src_argb, const uint8* src_argb1, - uint8* dst_argb, int width); -void ARGBBlendRow_C(const uint8* src_argb, const uint8* src_argb1, - uint8* dst_argb, int width); - -// Unattenuated planar alpha blend. -void BlendPlaneRow_SSSE3(const uint8* src0, const uint8* src1, - const uint8* alpha, uint8* dst, int width); -void BlendPlaneRow_Any_SSSE3(const uint8* src0, const uint8* src1, - const uint8* alpha, uint8* dst, int width); -void BlendPlaneRow_AVX2(const uint8* src0, const uint8* src1, - const uint8* alpha, uint8* dst, int width); -void BlendPlaneRow_Any_AVX2(const uint8* src0, const uint8* src1, - const uint8* alpha, uint8* dst, int width); -void BlendPlaneRow_C(const uint8* src0, const uint8* src1, - const uint8* alpha, uint8* dst, int width); - -// ARGB multiply images. Same API as Blend, but these require -// pointer and width alignment for SSE2. -void ARGBMultiplyRow_C(const uint8* src_argb, const uint8* src_argb1, - uint8* dst_argb, int width); -void ARGBMultiplyRow_SSE2(const uint8* src_argb, const uint8* src_argb1, - uint8* dst_argb, int width); -void ARGBMultiplyRow_Any_SSE2(const uint8* src_argb, const uint8* src_argb1, - uint8* dst_argb, int width); -void ARGBMultiplyRow_AVX2(const uint8* src_argb, const uint8* src_argb1, - uint8* dst_argb, int width); -void ARGBMultiplyRow_Any_AVX2(const uint8* src_argb, const uint8* src_argb1, - uint8* dst_argb, int width); -void ARGBMultiplyRow_NEON(const uint8* src_argb, const uint8* src_argb1, - uint8* dst_argb, int width); -void ARGBMultiplyRow_Any_NEON(const uint8* src_argb, const uint8* src_argb1, - uint8* dst_argb, int width); - -// ARGB add images. -void ARGBAddRow_C(const uint8* src_argb, const uint8* src_argb1, - uint8* dst_argb, int width); -void ARGBAddRow_SSE2(const uint8* src_argb, const uint8* src_argb1, - uint8* dst_argb, int width); -void ARGBAddRow_Any_SSE2(const uint8* src_argb, const uint8* src_argb1, - uint8* dst_argb, int width); -void ARGBAddRow_AVX2(const uint8* src_argb, const uint8* src_argb1, - uint8* dst_argb, int width); -void ARGBAddRow_Any_AVX2(const uint8* src_argb, const uint8* src_argb1, - uint8* dst_argb, int width); -void ARGBAddRow_NEON(const uint8* src_argb, const uint8* src_argb1, - uint8* dst_argb, int width); -void ARGBAddRow_Any_NEON(const uint8* src_argb, const uint8* src_argb1, - uint8* dst_argb, int width); - -// ARGB subtract images. Same API as Blend, but these require -// pointer and width alignment for SSE2. -void ARGBSubtractRow_C(const uint8* src_argb, const uint8* src_argb1, - uint8* dst_argb, int width); -void ARGBSubtractRow_SSE2(const uint8* src_argb, const uint8* src_argb1, - uint8* dst_argb, int width); -void ARGBSubtractRow_Any_SSE2(const uint8* src_argb, const uint8* src_argb1, - uint8* dst_argb, int width); -void ARGBSubtractRow_AVX2(const uint8* src_argb, const uint8* src_argb1, - uint8* dst_argb, int width); -void ARGBSubtractRow_Any_AVX2(const uint8* src_argb, const uint8* src_argb1, - uint8* dst_argb, int width); -void ARGBSubtractRow_NEON(const uint8* src_argb, const uint8* src_argb1, - uint8* dst_argb, int width); -void ARGBSubtractRow_Any_NEON(const uint8* src_argb, const uint8* src_argb1, - uint8* dst_argb, int width); - -void ARGBToRGB24Row_Any_SSSE3(const uint8* src_argb, uint8* dst_rgb, int width); -void ARGBToRAWRow_Any_SSSE3(const uint8* src_argb, uint8* dst_rgb, int width); -void ARGBToRGB565Row_Any_SSE2(const uint8* src_argb, uint8* dst_rgb, int width); -void ARGBToARGB1555Row_Any_SSE2(const uint8* src_argb, uint8* dst_rgb, - int width); -void ARGBToARGB4444Row_Any_SSE2(const uint8* src_argb, uint8* dst_rgb, - int width); - -void ARGBToRGB565DitherRow_Any_SSE2(const uint8* src_argb, uint8* dst_rgb, - const uint32 dither4, int width); -void ARGBToRGB565DitherRow_Any_AVX2(const uint8* src_argb, uint8* dst_rgb, - const uint32 dither4, int width); - -void ARGBToRGB565Row_Any_AVX2(const uint8* src_argb, uint8* dst_rgb, int width); -void ARGBToARGB1555Row_Any_AVX2(const uint8* src_argb, uint8* dst_rgb, - int width); -void ARGBToARGB4444Row_Any_AVX2(const uint8* src_argb, uint8* dst_rgb, - int width); - -void ARGBToRGB24Row_Any_NEON(const uint8* src_argb, uint8* dst_rgb, int width); -void ARGBToRAWRow_Any_NEON(const uint8* src_argb, uint8* dst_rgb, int width); -void ARGBToRGB565Row_Any_NEON(const uint8* src_argb, uint8* dst_rgb, int width); -void ARGBToARGB1555Row_Any_NEON(const uint8* src_argb, uint8* dst_rgb, - int width); -void ARGBToARGB4444Row_Any_NEON(const uint8* src_argb, uint8* dst_rgb, - int width); -void ARGBToRGB565DitherRow_Any_NEON(const uint8* src_argb, uint8* dst_rgb, - const uint32 dither4, int width); - -void I444ToARGBRow_Any_NEON(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I422ToARGBRow_Any_NEON(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I422AlphaToARGBRow_Any_NEON(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - const uint8* src_a, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I411ToARGBRow_Any_NEON(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I422ToRGBARow_Any_NEON(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I422ToRGB24Row_Any_NEON(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I422ToARGB4444Row_Any_NEON(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I422ToARGB1555Row_Any_NEON(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I422ToRGB565Row_Any_NEON(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void NV12ToARGBRow_Any_NEON(const uint8* src_y, - const uint8* src_uv, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void NV21ToARGBRow_Any_NEON(const uint8* src_y, - const uint8* src_vu, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void NV12ToRGB565Row_Any_NEON(const uint8* src_y, - const uint8* src_uv, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void YUY2ToARGBRow_Any_NEON(const uint8* src_yuy2, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void UYVYToARGBRow_Any_NEON(const uint8* src_uyvy, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I422ToARGBRow_DSPR2(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); -void I422ToARGBRow_DSPR2(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_argb, - const struct YuvConstants* yuvconstants, - int width); - -void YUY2ToYRow_AVX2(const uint8* src_yuy2, uint8* dst_y, int width); -void YUY2ToUVRow_AVX2(const uint8* src_yuy2, int stride_yuy2, - uint8* dst_u, uint8* dst_v, int width); -void YUY2ToUV422Row_AVX2(const uint8* src_yuy2, - uint8* dst_u, uint8* dst_v, int width); -void YUY2ToYRow_SSE2(const uint8* src_yuy2, uint8* dst_y, int width); -void YUY2ToUVRow_SSE2(const uint8* src_yuy2, int stride_yuy2, - uint8* dst_u, uint8* dst_v, int width); -void YUY2ToUV422Row_SSE2(const uint8* src_yuy2, - uint8* dst_u, uint8* dst_v, int width); -void YUY2ToYRow_NEON(const uint8* src_yuy2, uint8* dst_y, int width); -void YUY2ToUVRow_NEON(const uint8* src_yuy2, int stride_yuy2, - uint8* dst_u, uint8* dst_v, int width); -void YUY2ToUV422Row_NEON(const uint8* src_yuy2, - uint8* dst_u, uint8* dst_v, int width); -void YUY2ToYRow_C(const uint8* src_yuy2, uint8* dst_y, int width); -void YUY2ToUVRow_C(const uint8* src_yuy2, int stride_yuy2, - uint8* dst_u, uint8* dst_v, int width); -void YUY2ToUV422Row_C(const uint8* src_yuy2, - uint8* dst_u, uint8* dst_v, int width); -void YUY2ToYRow_Any_AVX2(const uint8* src_yuy2, uint8* dst_y, int width); -void YUY2ToUVRow_Any_AVX2(const uint8* src_yuy2, int stride_yuy2, - uint8* dst_u, uint8* dst_v, int width); -void YUY2ToUV422Row_Any_AVX2(const uint8* src_yuy2, - uint8* dst_u, uint8* dst_v, int width); -void YUY2ToYRow_Any_SSE2(const uint8* src_yuy2, uint8* dst_y, int width); -void YUY2ToUVRow_Any_SSE2(const uint8* src_yuy2, int stride_yuy2, - uint8* dst_u, uint8* dst_v, int width); -void YUY2ToUV422Row_Any_SSE2(const uint8* src_yuy2, - uint8* dst_u, uint8* dst_v, int width); -void YUY2ToYRow_Any_NEON(const uint8* src_yuy2, uint8* dst_y, int width); -void YUY2ToUVRow_Any_NEON(const uint8* src_yuy2, int stride_yuy2, - uint8* dst_u, uint8* dst_v, int width); -void YUY2ToUV422Row_Any_NEON(const uint8* src_yuy2, - uint8* dst_u, uint8* dst_v, int width); -void UYVYToYRow_AVX2(const uint8* src_uyvy, uint8* dst_y, int width); -void UYVYToUVRow_AVX2(const uint8* src_uyvy, int stride_uyvy, - uint8* dst_u, uint8* dst_v, int width); -void UYVYToUV422Row_AVX2(const uint8* src_uyvy, - uint8* dst_u, uint8* dst_v, int width); -void UYVYToYRow_SSE2(const uint8* src_uyvy, uint8* dst_y, int width); -void UYVYToUVRow_SSE2(const uint8* src_uyvy, int stride_uyvy, - uint8* dst_u, uint8* dst_v, int width); -void UYVYToUV422Row_SSE2(const uint8* src_uyvy, - uint8* dst_u, uint8* dst_v, int width); -void UYVYToYRow_AVX2(const uint8* src_uyvy, uint8* dst_y, int width); -void UYVYToUVRow_AVX2(const uint8* src_uyvy, int stride_uyvy, - uint8* dst_u, uint8* dst_v, int width); -void UYVYToUV422Row_AVX2(const uint8* src_uyvy, - uint8* dst_u, uint8* dst_v, int width); -void UYVYToYRow_NEON(const uint8* src_uyvy, uint8* dst_y, int width); -void UYVYToUVRow_NEON(const uint8* src_uyvy, int stride_uyvy, - uint8* dst_u, uint8* dst_v, int width); -void UYVYToUV422Row_NEON(const uint8* src_uyvy, - uint8* dst_u, uint8* dst_v, int width); - -void UYVYToYRow_C(const uint8* src_uyvy, uint8* dst_y, int width); -void UYVYToUVRow_C(const uint8* src_uyvy, int stride_uyvy, - uint8* dst_u, uint8* dst_v, int width); -void UYVYToUV422Row_C(const uint8* src_uyvy, - uint8* dst_u, uint8* dst_v, int width); -void UYVYToYRow_Any_AVX2(const uint8* src_uyvy, uint8* dst_y, int width); -void UYVYToUVRow_Any_AVX2(const uint8* src_uyvy, int stride_uyvy, - uint8* dst_u, uint8* dst_v, int width); -void UYVYToUV422Row_Any_AVX2(const uint8* src_uyvy, - uint8* dst_u, uint8* dst_v, int width); -void UYVYToYRow_Any_SSE2(const uint8* src_uyvy, uint8* dst_y, int width); -void UYVYToUVRow_Any_SSE2(const uint8* src_uyvy, int stride_uyvy, - uint8* dst_u, uint8* dst_v, int width); -void UYVYToUV422Row_Any_SSE2(const uint8* src_uyvy, - uint8* dst_u, uint8* dst_v, int width); -void UYVYToYRow_Any_NEON(const uint8* src_uyvy, uint8* dst_y, int width); -void UYVYToUVRow_Any_NEON(const uint8* src_uyvy, int stride_uyvy, - uint8* dst_u, uint8* dst_v, int width); -void UYVYToUV422Row_Any_NEON(const uint8* src_uyvy, - uint8* dst_u, uint8* dst_v, int width); - -void I422ToYUY2Row_C(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_yuy2, int width); -void I422ToUYVYRow_C(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_uyvy, int width); -void I422ToYUY2Row_SSE2(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_yuy2, int width); -void I422ToUYVYRow_SSE2(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_uyvy, int width); -void I422ToYUY2Row_Any_SSE2(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_yuy2, int width); -void I422ToUYVYRow_Any_SSE2(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_uyvy, int width); -void I422ToYUY2Row_NEON(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_yuy2, int width); -void I422ToUYVYRow_NEON(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_uyvy, int width); -void I422ToYUY2Row_Any_NEON(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_yuy2, int width); -void I422ToUYVYRow_Any_NEON(const uint8* src_y, - const uint8* src_u, - const uint8* src_v, - uint8* dst_uyvy, int width); - -// Effects related row functions. -void ARGBAttenuateRow_C(const uint8* src_argb, uint8* dst_argb, int width); -void ARGBAttenuateRow_SSSE3(const uint8* src_argb, uint8* dst_argb, int width); -void ARGBAttenuateRow_AVX2(const uint8* src_argb, uint8* dst_argb, int width); -void ARGBAttenuateRow_NEON(const uint8* src_argb, uint8* dst_argb, int width); -void ARGBAttenuateRow_Any_SSE2(const uint8* src_argb, uint8* dst_argb, - int width); -void ARGBAttenuateRow_Any_SSSE3(const uint8* src_argb, uint8* dst_argb, - int width); -void ARGBAttenuateRow_Any_AVX2(const uint8* src_argb, uint8* dst_argb, - int width); -void ARGBAttenuateRow_Any_NEON(const uint8* src_argb, uint8* dst_argb, - int width); - -// Inverse table for unattenuate, shared by C and SSE2. -extern const uint32 fixed_invtbl8[256]; -void ARGBUnattenuateRow_C(const uint8* src_argb, uint8* dst_argb, int width); -void ARGBUnattenuateRow_SSE2(const uint8* src_argb, uint8* dst_argb, int width); -void ARGBUnattenuateRow_AVX2(const uint8* src_argb, uint8* dst_argb, int width); -void ARGBUnattenuateRow_Any_SSE2(const uint8* src_argb, uint8* dst_argb, - int width); -void ARGBUnattenuateRow_Any_AVX2(const uint8* src_argb, uint8* dst_argb, - int width); - -void ARGBGrayRow_C(const uint8* src_argb, uint8* dst_argb, int width); -void ARGBGrayRow_SSSE3(const uint8* src_argb, uint8* dst_argb, int width); -void ARGBGrayRow_NEON(const uint8* src_argb, uint8* dst_argb, int width); - -void ARGBSepiaRow_C(uint8* dst_argb, int width); -void ARGBSepiaRow_SSSE3(uint8* dst_argb, int width); -void ARGBSepiaRow_NEON(uint8* dst_argb, int width); - -void ARGBColorMatrixRow_C(const uint8* src_argb, uint8* dst_argb, - const int8* matrix_argb, int width); -void ARGBColorMatrixRow_SSSE3(const uint8* src_argb, uint8* dst_argb, - const int8* matrix_argb, int width); -void ARGBColorMatrixRow_NEON(const uint8* src_argb, uint8* dst_argb, - const int8* matrix_argb, int width); - -void ARGBColorTableRow_C(uint8* dst_argb, const uint8* table_argb, int width); -void ARGBColorTableRow_X86(uint8* dst_argb, const uint8* table_argb, int width); - -void RGBColorTableRow_C(uint8* dst_argb, const uint8* table_argb, int width); -void RGBColorTableRow_X86(uint8* dst_argb, const uint8* table_argb, int width); - -void ARGBQuantizeRow_C(uint8* dst_argb, int scale, int interval_size, - int interval_offset, int width); -void ARGBQuantizeRow_SSE2(uint8* dst_argb, int scale, int interval_size, - int interval_offset, int width); -void ARGBQuantizeRow_NEON(uint8* dst_argb, int scale, int interval_size, - int interval_offset, int width); - -void ARGBShadeRow_C(const uint8* src_argb, uint8* dst_argb, int width, - uint32 value); -void ARGBShadeRow_SSE2(const uint8* src_argb, uint8* dst_argb, int width, - uint32 value); -void ARGBShadeRow_NEON(const uint8* src_argb, uint8* dst_argb, int width, - uint32 value); - -// Used for blur. -void CumulativeSumToAverageRow_SSE2(const int32* topleft, const int32* botleft, - int width, int area, uint8* dst, int count); -void ComputeCumulativeSumRow_SSE2(const uint8* row, int32* cumsum, - const int32* previous_cumsum, int width); - -void CumulativeSumToAverageRow_C(const int32* topleft, const int32* botleft, - int width, int area, uint8* dst, int count); -void ComputeCumulativeSumRow_C(const uint8* row, int32* cumsum, - const int32* previous_cumsum, int width); - -LIBYUV_API -void ARGBAffineRow_C(const uint8* src_argb, int src_argb_stride, - uint8* dst_argb, const float* uv_dudv, int width); -LIBYUV_API -void ARGBAffineRow_SSE2(const uint8* src_argb, int src_argb_stride, - uint8* dst_argb, const float* uv_dudv, int width); - -// Used for I420Scale, ARGBScale, and ARGBInterpolate. -void InterpolateRow_C(uint8* dst_ptr, const uint8* src_ptr, - ptrdiff_t src_stride_ptr, - int width, int source_y_fraction); -void InterpolateRow_SSSE3(uint8* dst_ptr, const uint8* src_ptr, - ptrdiff_t src_stride_ptr, int width, - int source_y_fraction); -void InterpolateRow_AVX2(uint8* dst_ptr, const uint8* src_ptr, - ptrdiff_t src_stride_ptr, int width, - int source_y_fraction); -void InterpolateRow_NEON(uint8* dst_ptr, const uint8* src_ptr, - ptrdiff_t src_stride_ptr, int width, - int source_y_fraction); -void InterpolateRow_DSPR2(uint8* dst_ptr, const uint8* src_ptr, - ptrdiff_t src_stride_ptr, int width, - int source_y_fraction); -void InterpolateRow_Any_NEON(uint8* dst_ptr, const uint8* src_ptr, - ptrdiff_t src_stride_ptr, int width, - int source_y_fraction); -void InterpolateRow_Any_SSSE3(uint8* dst_ptr, const uint8* src_ptr, - ptrdiff_t src_stride_ptr, int width, - int source_y_fraction); -void InterpolateRow_Any_AVX2(uint8* dst_ptr, const uint8* src_ptr, - ptrdiff_t src_stride_ptr, int width, - int source_y_fraction); -void InterpolateRow_Any_DSPR2(uint8* dst_ptr, const uint8* src_ptr, - ptrdiff_t src_stride_ptr, int width, - int source_y_fraction); - -void InterpolateRow_16_C(uint16* dst_ptr, const uint16* src_ptr, - ptrdiff_t src_stride_ptr, - int width, int source_y_fraction); - -// Sobel images. -void SobelXRow_C(const uint8* src_y0, const uint8* src_y1, const uint8* src_y2, - uint8* dst_sobelx, int width); -void SobelXRow_SSE2(const uint8* src_y0, const uint8* src_y1, - const uint8* src_y2, uint8* dst_sobelx, int width); -void SobelXRow_NEON(const uint8* src_y0, const uint8* src_y1, - const uint8* src_y2, uint8* dst_sobelx, int width); -void SobelYRow_C(const uint8* src_y0, const uint8* src_y1, - uint8* dst_sobely, int width); -void SobelYRow_SSE2(const uint8* src_y0, const uint8* src_y1, - uint8* dst_sobely, int width); -void SobelYRow_NEON(const uint8* src_y0, const uint8* src_y1, - uint8* dst_sobely, int width); -void SobelRow_C(const uint8* src_sobelx, const uint8* src_sobely, - uint8* dst_argb, int width); -void SobelRow_SSE2(const uint8* src_sobelx, const uint8* src_sobely, - uint8* dst_argb, int width); -void SobelRow_NEON(const uint8* src_sobelx, const uint8* src_sobely, - uint8* dst_argb, int width); -void SobelToPlaneRow_C(const uint8* src_sobelx, const uint8* src_sobely, - uint8* dst_y, int width); -void SobelToPlaneRow_SSE2(const uint8* src_sobelx, const uint8* src_sobely, - uint8* dst_y, int width); -void SobelToPlaneRow_NEON(const uint8* src_sobelx, const uint8* src_sobely, - uint8* dst_y, int width); -void SobelXYRow_C(const uint8* src_sobelx, const uint8* src_sobely, - uint8* dst_argb, int width); -void SobelXYRow_SSE2(const uint8* src_sobelx, const uint8* src_sobely, - uint8* dst_argb, int width); -void SobelXYRow_NEON(const uint8* src_sobelx, const uint8* src_sobely, - uint8* dst_argb, int width); -void SobelRow_Any_SSE2(const uint8* src_sobelx, const uint8* src_sobely, - uint8* dst_argb, int width); -void SobelRow_Any_NEON(const uint8* src_sobelx, const uint8* src_sobely, - uint8* dst_argb, int width); -void SobelToPlaneRow_Any_SSE2(const uint8* src_sobelx, const uint8* src_sobely, - uint8* dst_y, int width); -void SobelToPlaneRow_Any_NEON(const uint8* src_sobelx, const uint8* src_sobely, - uint8* dst_y, int width); -void SobelXYRow_Any_SSE2(const uint8* src_sobelx, const uint8* src_sobely, - uint8* dst_argb, int width); -void SobelXYRow_Any_NEON(const uint8* src_sobelx, const uint8* src_sobely, - uint8* dst_argb, int width); - -void ARGBPolynomialRow_C(const uint8* src_argb, - uint8* dst_argb, const float* poly, - int width); -void ARGBPolynomialRow_SSE2(const uint8* src_argb, - uint8* dst_argb, const float* poly, - int width); -void ARGBPolynomialRow_AVX2(const uint8* src_argb, - uint8* dst_argb, const float* poly, - int width); - -// Scale and convert to half float. -void HalfFloatRow_C(const uint16* src, uint16* dst, float scale, int width); -void HalfFloatRow_AVX2(const uint16* src, uint16* dst, float scale, int width); -void HalfFloatRow_Any_AVX2(const uint16* src, uint16* dst, float scale, - int width); -void HalfFloatRow_SSE2(const uint16* src, uint16* dst, float scale, int width); -void HalfFloatRow_Any_SSE2(const uint16* src, uint16* dst, float scale, - int width); - -void ARGBLumaColorTableRow_C(const uint8* src_argb, uint8* dst_argb, int width, - const uint8* luma, uint32 lumacoeff); -void ARGBLumaColorTableRow_SSSE3(const uint8* src_argb, uint8* dst_argb, - int width, - const uint8* luma, uint32 lumacoeff); - -#ifdef __cplusplus -} // extern "C" -} // namespace libyuv -#endif - -#endif // INCLUDE_LIBYUV_ROW_H_ diff --git a/third_party/libyuv/include/libyuv/scale.h b/third_party/libyuv/include/libyuv/scale.h deleted file mode 100644 index ae14694..0000000 --- a/third_party/libyuv/include/libyuv/scale.h +++ /dev/null @@ -1,103 +0,0 @@ -/* - * Copyright 2011 The LibYuv Project Authors. All rights reserved. - * - * Use of this source code is governed by a BSD-style license - * that can be found in the LICENSE file in the root of the source - * tree. An additional intellectual property rights grant can be found - * in the file PATENTS. All contributing project authors may - * be found in the AUTHORS file in the root of the source tree. - */ - -#ifndef INCLUDE_LIBYUV_SCALE_H_ -#define INCLUDE_LIBYUV_SCALE_H_ - -#include "libyuv/basic_types.h" - -#ifdef __cplusplus -namespace libyuv { -extern "C" { -#endif - -// Supported filtering. -typedef enum FilterMode { - kFilterNone = 0, // Point sample; Fastest. - kFilterLinear = 1, // Filter horizontally only. - kFilterBilinear = 2, // Faster than box, but lower quality scaling down. - kFilterBox = 3 // Highest quality. -} FilterModeEnum; - -// Scale a YUV plane. -LIBYUV_API -void ScalePlane(const uint8* src, int src_stride, - int src_width, int src_height, - uint8* dst, int dst_stride, - int dst_width, int dst_height, - enum FilterMode filtering); - -LIBYUV_API -void ScalePlane_16(const uint16* src, int src_stride, - int src_width, int src_height, - uint16* dst, int dst_stride, - int dst_width, int dst_height, - enum FilterMode filtering); - -// Scales a YUV 4:2:0 image from the src width and height to the -// dst width and height. -// If filtering is kFilterNone, a simple nearest-neighbor algorithm is -// used. This produces basic (blocky) quality at the fastest speed. -// If filtering is kFilterBilinear, interpolation is used to produce a better -// quality image, at the expense of speed. -// If filtering is kFilterBox, averaging is used to produce ever better -// quality image, at further expense of speed. -// Returns 0 if successful. - -LIBYUV_API -int I420Scale(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - int src_width, int src_height, - uint8* dst_y, int dst_stride_y, - uint8* dst_u, int dst_stride_u, - uint8* dst_v, int dst_stride_v, - int dst_width, int dst_height, - enum FilterMode filtering); - -LIBYUV_API -int I420Scale_16(const uint16* src_y, int src_stride_y, - const uint16* src_u, int src_stride_u, - const uint16* src_v, int src_stride_v, - int src_width, int src_height, - uint16* dst_y, int dst_stride_y, - uint16* dst_u, int dst_stride_u, - uint16* dst_v, int dst_stride_v, - int dst_width, int dst_height, - enum FilterMode filtering); - -#ifdef __cplusplus -// Legacy API. Deprecated. -LIBYUV_API -int Scale(const uint8* src_y, const uint8* src_u, const uint8* src_v, - int src_stride_y, int src_stride_u, int src_stride_v, - int src_width, int src_height, - uint8* dst_y, uint8* dst_u, uint8* dst_v, - int dst_stride_y, int dst_stride_u, int dst_stride_v, - int dst_width, int dst_height, - LIBYUV_BOOL interpolate); - -// Legacy API. Deprecated. -LIBYUV_API -int ScaleOffset(const uint8* src_i420, int src_width, int src_height, - uint8* dst_i420, int dst_width, int dst_height, int dst_yoffset, - LIBYUV_BOOL interpolate); - -// For testing, allow disabling of specialized scalers. -LIBYUV_API -void SetUseReferenceImpl(LIBYUV_BOOL use); -#endif // __cplusplus - -#ifdef __cplusplus -} // extern "C" -} // namespace libyuv -#endif - -#endif // INCLUDE_LIBYUV_SCALE_H_ diff --git a/third_party/libyuv/include/libyuv/scale_argb.h b/third_party/libyuv/include/libyuv/scale_argb.h deleted file mode 100644 index 35cd191..0000000 --- a/third_party/libyuv/include/libyuv/scale_argb.h +++ /dev/null @@ -1,56 +0,0 @@ -/* - * Copyright 2012 The LibYuv Project Authors. All rights reserved. - * - * Use of this source code is governed by a BSD-style license - * that can be found in the LICENSE file in the root of the source - * tree. An additional intellectual property rights grant can be found - * in the file PATENTS. All contributing project authors may - * be found in the AUTHORS file in the root of the source tree. - */ - -#ifndef INCLUDE_LIBYUV_SCALE_ARGB_H_ -#define INCLUDE_LIBYUV_SCALE_ARGB_H_ - -#include "libyuv/basic_types.h" -#include "libyuv/scale.h" // For FilterMode - -#ifdef __cplusplus -namespace libyuv { -extern "C" { -#endif - -LIBYUV_API -int ARGBScale(const uint8* src_argb, int src_stride_argb, - int src_width, int src_height, - uint8* dst_argb, int dst_stride_argb, - int dst_width, int dst_height, - enum FilterMode filtering); - -// Clipped scale takes destination rectangle coordinates for clip values. -LIBYUV_API -int ARGBScaleClip(const uint8* src_argb, int src_stride_argb, - int src_width, int src_height, - uint8* dst_argb, int dst_stride_argb, - int dst_width, int dst_height, - int clip_x, int clip_y, int clip_width, int clip_height, - enum FilterMode filtering); - -// Scale with YUV conversion to ARGB and clipping. -LIBYUV_API -int YUVToARGBScaleClip(const uint8* src_y, int src_stride_y, - const uint8* src_u, int src_stride_u, - const uint8* src_v, int src_stride_v, - uint32 src_fourcc, - int src_width, int src_height, - uint8* dst_argb, int dst_stride_argb, - uint32 dst_fourcc, - int dst_width, int dst_height, - int clip_x, int clip_y, int clip_width, int clip_height, - enum FilterMode filtering); - -#ifdef __cplusplus -} // extern "C" -} // namespace libyuv -#endif - -#endif // INCLUDE_LIBYUV_SCALE_ARGB_H_ diff --git a/third_party/libyuv/include/libyuv/scale_row.h b/third_party/libyuv/include/libyuv/scale_row.h deleted file mode 100644 index 791fbf7..0000000 --- a/third_party/libyuv/include/libyuv/scale_row.h +++ /dev/null @@ -1,503 +0,0 @@ -/* - * Copyright 2013 The LibYuv Project Authors. All rights reserved. - * - * Use of this source code is governed by a BSD-style license - * that can be found in the LICENSE file in the root of the source - * tree. An additional intellectual property rights grant can be found - * in the file PATENTS. All contributing project authors may - * be found in the AUTHORS file in the root of the source tree. - */ - -#ifndef INCLUDE_LIBYUV_SCALE_ROW_H_ -#define INCLUDE_LIBYUV_SCALE_ROW_H_ - -#include "libyuv/basic_types.h" -#include "libyuv/scale.h" - -#ifdef __cplusplus -namespace libyuv { -extern "C" { -#endif - -#if defined(__pnacl__) || defined(__CLR_VER) || \ - (defined(__i386__) && !defined(__SSE2__)) -#define LIBYUV_DISABLE_X86 -#endif -// MemorySanitizer does not support assembly code yet. http://crbug.com/344505 -#if defined(__has_feature) -#if __has_feature(memory_sanitizer) -#define LIBYUV_DISABLE_X86 -#endif -#endif - -// GCC >= 4.7.0 required for AVX2. -#if defined(__GNUC__) && (defined(__x86_64__) || defined(__i386__)) -#if (__GNUC__ > 4) || (__GNUC__ == 4 && (__GNUC_MINOR__ >= 7)) -#define GCC_HAS_AVX2 1 -#endif // GNUC >= 4.7 -#endif // __GNUC__ - -// clang >= 3.4.0 required for AVX2. -#if defined(__clang__) && (defined(__x86_64__) || defined(__i386__)) -#if (__clang_major__ > 3) || (__clang_major__ == 3 && (__clang_minor__ >= 4)) -#define CLANG_HAS_AVX2 1 -#endif // clang >= 3.4 -#endif // __clang__ - -// Visual C 2012 required for AVX2. -#if defined(_M_IX86) && !defined(__clang__) && \ - defined(_MSC_VER) && _MSC_VER >= 1700 -#define VISUALC_HAS_AVX2 1 -#endif // VisualStudio >= 2012 - -// The following are available on all x86 platforms: -#if !defined(LIBYUV_DISABLE_X86) && \ - (defined(_M_IX86) || defined(__x86_64__) || defined(__i386__)) -#define HAS_FIXEDDIV1_X86 -#define HAS_FIXEDDIV_X86 -#define HAS_SCALEARGBCOLS_SSE2 -#define HAS_SCALEARGBCOLSUP2_SSE2 -#define HAS_SCALEARGBFILTERCOLS_SSSE3 -#define HAS_SCALEARGBROWDOWN2_SSE2 -#define HAS_SCALEARGBROWDOWNEVEN_SSE2 -#define HAS_SCALECOLSUP2_SSE2 -#define HAS_SCALEFILTERCOLS_SSSE3 -#define HAS_SCALEROWDOWN2_SSSE3 -#define HAS_SCALEROWDOWN34_SSSE3 -#define HAS_SCALEROWDOWN38_SSSE3 -#define HAS_SCALEROWDOWN4_SSSE3 -#define HAS_SCALEADDROW_SSE2 -#endif - -// The following are available on all x86 platforms, but -// require VS2012, clang 3.4 or gcc 4.7. -// The code supports NaCL but requires a new compiler and validator. -#if !defined(LIBYUV_DISABLE_X86) && (defined(VISUALC_HAS_AVX2) || \ - defined(CLANG_HAS_AVX2) || defined(GCC_HAS_AVX2)) -#define HAS_SCALEADDROW_AVX2 -#define HAS_SCALEROWDOWN2_AVX2 -#define HAS_SCALEROWDOWN4_AVX2 -#endif - -// The following are available on Neon platforms: -#if !defined(LIBYUV_DISABLE_NEON) && !defined(__native_client__) && \ - (defined(__ARM_NEON__) || defined(LIBYUV_NEON) || defined(__aarch64__)) -#define HAS_SCALEARGBCOLS_NEON -#define HAS_SCALEARGBROWDOWN2_NEON -#define HAS_SCALEARGBROWDOWNEVEN_NEON -#define HAS_SCALEFILTERCOLS_NEON -#define HAS_SCALEROWDOWN2_NEON -#define HAS_SCALEROWDOWN34_NEON -#define HAS_SCALEROWDOWN38_NEON -#define HAS_SCALEROWDOWN4_NEON -#define HAS_SCALEARGBFILTERCOLS_NEON -#endif - -// The following are available on Mips platforms: -#if !defined(LIBYUV_DISABLE_MIPS) && !defined(__native_client__) && \ - defined(__mips__) && defined(__mips_dsp) && (__mips_dsp_rev >= 2) -#define HAS_SCALEROWDOWN2_DSPR2 -#define HAS_SCALEROWDOWN4_DSPR2 -#define HAS_SCALEROWDOWN34_DSPR2 -#define HAS_SCALEROWDOWN38_DSPR2 -#endif - -// Scale ARGB vertically with bilinear interpolation. -void ScalePlaneVertical(int src_height, - int dst_width, int dst_height, - int src_stride, int dst_stride, - const uint8* src_argb, uint8* dst_argb, - int x, int y, int dy, - int bpp, enum FilterMode filtering); - -void ScalePlaneVertical_16(int src_height, - int dst_width, int dst_height, - int src_stride, int dst_stride, - const uint16* src_argb, uint16* dst_argb, - int x, int y, int dy, - int wpp, enum FilterMode filtering); - -// Simplify the filtering based on scale factors. -enum FilterMode ScaleFilterReduce(int src_width, int src_height, - int dst_width, int dst_height, - enum FilterMode filtering); - -// Divide num by div and return as 16.16 fixed point result. -int FixedDiv_C(int num, int div); -int FixedDiv_X86(int num, int div); -// Divide num - 1 by div - 1 and return as 16.16 fixed point result. -int FixedDiv1_C(int num, int div); -int FixedDiv1_X86(int num, int div); -#ifdef HAS_FIXEDDIV_X86 -#define FixedDiv FixedDiv_X86 -#define FixedDiv1 FixedDiv1_X86 -#else -#define FixedDiv FixedDiv_C -#define FixedDiv1 FixedDiv1_C -#endif - -// Compute slope values for stepping. -void ScaleSlope(int src_width, int src_height, - int dst_width, int dst_height, - enum FilterMode filtering, - int* x, int* y, int* dx, int* dy); - -void ScaleRowDown2_C(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst, int dst_width); -void ScaleRowDown2_16_C(const uint16* src_ptr, ptrdiff_t src_stride, - uint16* dst, int dst_width); -void ScaleRowDown2Linear_C(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst, int dst_width); -void ScaleRowDown2Linear_16_C(const uint16* src_ptr, ptrdiff_t src_stride, - uint16* dst, int dst_width); -void ScaleRowDown2Box_C(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst, int dst_width); -void ScaleRowDown2Box_Odd_C(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst, int dst_width); -void ScaleRowDown2Box_16_C(const uint16* src_ptr, ptrdiff_t src_stride, - uint16* dst, int dst_width); -void ScaleRowDown4_C(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst, int dst_width); -void ScaleRowDown4_16_C(const uint16* src_ptr, ptrdiff_t src_stride, - uint16* dst, int dst_width); -void ScaleRowDown4Box_C(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst, int dst_width); -void ScaleRowDown4Box_16_C(const uint16* src_ptr, ptrdiff_t src_stride, - uint16* dst, int dst_width); -void ScaleRowDown34_C(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst, int dst_width); -void ScaleRowDown34_16_C(const uint16* src_ptr, ptrdiff_t src_stride, - uint16* dst, int dst_width); -void ScaleRowDown34_0_Box_C(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* d, int dst_width); -void ScaleRowDown34_0_Box_16_C(const uint16* src_ptr, ptrdiff_t src_stride, - uint16* d, int dst_width); -void ScaleRowDown34_1_Box_C(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* d, int dst_width); -void ScaleRowDown34_1_Box_16_C(const uint16* src_ptr, ptrdiff_t src_stride, - uint16* d, int dst_width); -void ScaleCols_C(uint8* dst_ptr, const uint8* src_ptr, - int dst_width, int x, int dx); -void ScaleCols_16_C(uint16* dst_ptr, const uint16* src_ptr, - int dst_width, int x, int dx); -void ScaleColsUp2_C(uint8* dst_ptr, const uint8* src_ptr, - int dst_width, int, int); -void ScaleColsUp2_16_C(uint16* dst_ptr, const uint16* src_ptr, - int dst_width, int, int); -void ScaleFilterCols_C(uint8* dst_ptr, const uint8* src_ptr, - int dst_width, int x, int dx); -void ScaleFilterCols_16_C(uint16* dst_ptr, const uint16* src_ptr, - int dst_width, int x, int dx); -void ScaleFilterCols64_C(uint8* dst_ptr, const uint8* src_ptr, - int dst_width, int x, int dx); -void ScaleFilterCols64_16_C(uint16* dst_ptr, const uint16* src_ptr, - int dst_width, int x, int dx); -void ScaleRowDown38_C(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst, int dst_width); -void ScaleRowDown38_16_C(const uint16* src_ptr, ptrdiff_t src_stride, - uint16* dst, int dst_width); -void ScaleRowDown38_3_Box_C(const uint8* src_ptr, - ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -void ScaleRowDown38_3_Box_16_C(const uint16* src_ptr, - ptrdiff_t src_stride, - uint16* dst_ptr, int dst_width); -void ScaleRowDown38_2_Box_C(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -void ScaleRowDown38_2_Box_16_C(const uint16* src_ptr, ptrdiff_t src_stride, - uint16* dst_ptr, int dst_width); -void ScaleAddRow_C(const uint8* src_ptr, uint16* dst_ptr, int src_width); -void ScaleAddRow_16_C(const uint16* src_ptr, uint32* dst_ptr, int src_width); -void ScaleARGBRowDown2_C(const uint8* src_argb, - ptrdiff_t src_stride, - uint8* dst_argb, int dst_width); -void ScaleARGBRowDown2Linear_C(const uint8* src_argb, - ptrdiff_t src_stride, - uint8* dst_argb, int dst_width); -void ScaleARGBRowDown2Box_C(const uint8* src_argb, ptrdiff_t src_stride, - uint8* dst_argb, int dst_width); -void ScaleARGBRowDownEven_C(const uint8* src_argb, ptrdiff_t src_stride, - int src_stepx, - uint8* dst_argb, int dst_width); -void ScaleARGBRowDownEvenBox_C(const uint8* src_argb, - ptrdiff_t src_stride, - int src_stepx, - uint8* dst_argb, int dst_width); -void ScaleARGBCols_C(uint8* dst_argb, const uint8* src_argb, - int dst_width, int x, int dx); -void ScaleARGBCols64_C(uint8* dst_argb, const uint8* src_argb, - int dst_width, int x, int dx); -void ScaleARGBColsUp2_C(uint8* dst_argb, const uint8* src_argb, - int dst_width, int, int); -void ScaleARGBFilterCols_C(uint8* dst_argb, const uint8* src_argb, - int dst_width, int x, int dx); -void ScaleARGBFilterCols64_C(uint8* dst_argb, const uint8* src_argb, - int dst_width, int x, int dx); - -// Specialized scalers for x86. -void ScaleRowDown2_SSSE3(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -void ScaleRowDown2Linear_SSSE3(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -void ScaleRowDown2Box_SSSE3(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -void ScaleRowDown2_AVX2(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -void ScaleRowDown2Linear_AVX2(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -void ScaleRowDown2Box_AVX2(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -void ScaleRowDown4_SSSE3(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -void ScaleRowDown4Box_SSSE3(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -void ScaleRowDown4_AVX2(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -void ScaleRowDown4Box_AVX2(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); - -void ScaleRowDown34_SSSE3(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -void ScaleRowDown34_1_Box_SSSE3(const uint8* src_ptr, - ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -void ScaleRowDown34_0_Box_SSSE3(const uint8* src_ptr, - ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -void ScaleRowDown38_SSSE3(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -void ScaleRowDown38_3_Box_SSSE3(const uint8* src_ptr, - ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -void ScaleRowDown38_2_Box_SSSE3(const uint8* src_ptr, - ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -void ScaleRowDown2_Any_SSSE3(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -void ScaleRowDown2Linear_Any_SSSE3(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -void ScaleRowDown2Box_Any_SSSE3(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -void ScaleRowDown2Box_Odd_SSSE3(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -void ScaleRowDown2_Any_AVX2(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -void ScaleRowDown2Linear_Any_AVX2(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -void ScaleRowDown2Box_Any_AVX2(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -void ScaleRowDown2Box_Odd_AVX2(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -void ScaleRowDown4_Any_SSSE3(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -void ScaleRowDown4Box_Any_SSSE3(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -void ScaleRowDown4_Any_AVX2(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -void ScaleRowDown4Box_Any_AVX2(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); - -void ScaleRowDown34_Any_SSSE3(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -void ScaleRowDown34_1_Box_Any_SSSE3(const uint8* src_ptr, - ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -void ScaleRowDown34_0_Box_Any_SSSE3(const uint8* src_ptr, - ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -void ScaleRowDown38_Any_SSSE3(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -void ScaleRowDown38_3_Box_Any_SSSE3(const uint8* src_ptr, - ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -void ScaleRowDown38_2_Box_Any_SSSE3(const uint8* src_ptr, - ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); - -void ScaleAddRow_SSE2(const uint8* src_ptr, uint16* dst_ptr, int src_width); -void ScaleAddRow_AVX2(const uint8* src_ptr, uint16* dst_ptr, int src_width); -void ScaleAddRow_Any_SSE2(const uint8* src_ptr, uint16* dst_ptr, int src_width); -void ScaleAddRow_Any_AVX2(const uint8* src_ptr, uint16* dst_ptr, int src_width); - -void ScaleFilterCols_SSSE3(uint8* dst_ptr, const uint8* src_ptr, - int dst_width, int x, int dx); -void ScaleColsUp2_SSE2(uint8* dst_ptr, const uint8* src_ptr, - int dst_width, int x, int dx); - - -// ARGB Column functions -void ScaleARGBCols_SSE2(uint8* dst_argb, const uint8* src_argb, - int dst_width, int x, int dx); -void ScaleARGBFilterCols_SSSE3(uint8* dst_argb, const uint8* src_argb, - int dst_width, int x, int dx); -void ScaleARGBColsUp2_SSE2(uint8* dst_argb, const uint8* src_argb, - int dst_width, int x, int dx); -void ScaleARGBFilterCols_NEON(uint8* dst_argb, const uint8* src_argb, - int dst_width, int x, int dx); -void ScaleARGBCols_NEON(uint8* dst_argb, const uint8* src_argb, - int dst_width, int x, int dx); -void ScaleARGBFilterCols_Any_NEON(uint8* dst_argb, const uint8* src_argb, - int dst_width, int x, int dx); -void ScaleARGBCols_Any_NEON(uint8* dst_argb, const uint8* src_argb, - int dst_width, int x, int dx); - -// ARGB Row functions -void ScaleARGBRowDown2_SSE2(const uint8* src_argb, ptrdiff_t src_stride, - uint8* dst_argb, int dst_width); -void ScaleARGBRowDown2Linear_SSE2(const uint8* src_argb, ptrdiff_t src_stride, - uint8* dst_argb, int dst_width); -void ScaleARGBRowDown2Box_SSE2(const uint8* src_argb, ptrdiff_t src_stride, - uint8* dst_argb, int dst_width); -void ScaleARGBRowDown2_NEON(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst, int dst_width); -void ScaleARGBRowDown2Linear_NEON(const uint8* src_argb, ptrdiff_t src_stride, - uint8* dst_argb, int dst_width); -void ScaleARGBRowDown2Box_NEON(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst, int dst_width); -void ScaleARGBRowDown2_Any_SSE2(const uint8* src_argb, ptrdiff_t src_stride, - uint8* dst_argb, int dst_width); -void ScaleARGBRowDown2Linear_Any_SSE2(const uint8* src_argb, - ptrdiff_t src_stride, - uint8* dst_argb, int dst_width); -void ScaleARGBRowDown2Box_Any_SSE2(const uint8* src_argb, ptrdiff_t src_stride, - uint8* dst_argb, int dst_width); -void ScaleARGBRowDown2_Any_NEON(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst, int dst_width); -void ScaleARGBRowDown2Linear_Any_NEON(const uint8* src_argb, - ptrdiff_t src_stride, - uint8* dst_argb, int dst_width); -void ScaleARGBRowDown2Box_Any_NEON(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst, int dst_width); - -void ScaleARGBRowDownEven_SSE2(const uint8* src_argb, ptrdiff_t src_stride, - int src_stepx, uint8* dst_argb, int dst_width); -void ScaleARGBRowDownEvenBox_SSE2(const uint8* src_argb, ptrdiff_t src_stride, - int src_stepx, - uint8* dst_argb, int dst_width); -void ScaleARGBRowDownEven_NEON(const uint8* src_argb, ptrdiff_t src_stride, - int src_stepx, - uint8* dst_argb, int dst_width); -void ScaleARGBRowDownEvenBox_NEON(const uint8* src_argb, ptrdiff_t src_stride, - int src_stepx, - uint8* dst_argb, int dst_width); -void ScaleARGBRowDownEven_Any_SSE2(const uint8* src_argb, ptrdiff_t src_stride, - int src_stepx, - uint8* dst_argb, int dst_width); -void ScaleARGBRowDownEvenBox_Any_SSE2(const uint8* src_argb, - ptrdiff_t src_stride, - int src_stepx, - uint8* dst_argb, int dst_width); -void ScaleARGBRowDownEven_Any_NEON(const uint8* src_argb, ptrdiff_t src_stride, - int src_stepx, - uint8* dst_argb, int dst_width); -void ScaleARGBRowDownEvenBox_Any_NEON(const uint8* src_argb, - ptrdiff_t src_stride, - int src_stepx, - uint8* dst_argb, int dst_width); - -// ScaleRowDown2Box also used by planar functions -// NEON downscalers with interpolation. - -// Note - not static due to reuse in convert for 444 to 420. -void ScaleRowDown2_NEON(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst, int dst_width); -void ScaleRowDown2Linear_NEON(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst, int dst_width); -void ScaleRowDown2Box_NEON(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst, int dst_width); - -void ScaleRowDown4_NEON(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -void ScaleRowDown4Box_NEON(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); - -// Down scale from 4 to 3 pixels. Use the neon multilane read/write -// to load up the every 4th pixel into a 4 different registers. -// Point samples 32 pixels to 24 pixels. -void ScaleRowDown34_NEON(const uint8* src_ptr, - ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -void ScaleRowDown34_0_Box_NEON(const uint8* src_ptr, - ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -void ScaleRowDown34_1_Box_NEON(const uint8* src_ptr, - ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); - -// 32 -> 12 -void ScaleRowDown38_NEON(const uint8* src_ptr, - ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -// 32x3 -> 12x1 -void ScaleRowDown38_3_Box_NEON(const uint8* src_ptr, - ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -// 32x2 -> 12x1 -void ScaleRowDown38_2_Box_NEON(const uint8* src_ptr, - ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); - -void ScaleRowDown2_Any_NEON(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst, int dst_width); -void ScaleRowDown2Linear_Any_NEON(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst, int dst_width); -void ScaleRowDown2Box_Any_NEON(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst, int dst_width); -void ScaleRowDown2Box_Odd_NEON(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst, int dst_width); -void ScaleRowDown4_Any_NEON(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -void ScaleRowDown4Box_Any_NEON(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -void ScaleRowDown34_Any_NEON(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -void ScaleRowDown34_0_Box_Any_NEON(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -void ScaleRowDown34_1_Box_Any_NEON(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -// 32 -> 12 -void ScaleRowDown38_Any_NEON(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -// 32x3 -> 12x1 -void ScaleRowDown38_3_Box_Any_NEON(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -// 32x2 -> 12x1 -void ScaleRowDown38_2_Box_Any_NEON(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); - -void ScaleAddRow_NEON(const uint8* src_ptr, uint16* dst_ptr, int src_width); -void ScaleAddRow_Any_NEON(const uint8* src_ptr, uint16* dst_ptr, int src_width); - -void ScaleFilterCols_NEON(uint8* dst_ptr, const uint8* src_ptr, - int dst_width, int x, int dx); - -void ScaleFilterCols_Any_NEON(uint8* dst_ptr, const uint8* src_ptr, - int dst_width, int x, int dx); - -void ScaleRowDown2_DSPR2(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst, int dst_width); -void ScaleRowDown2Box_DSPR2(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst, int dst_width); -void ScaleRowDown4_DSPR2(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst, int dst_width); -void ScaleRowDown4Box_DSPR2(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst, int dst_width); -void ScaleRowDown34_DSPR2(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst, int dst_width); -void ScaleRowDown34_0_Box_DSPR2(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* d, int dst_width); -void ScaleRowDown34_1_Box_DSPR2(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* d, int dst_width); -void ScaleRowDown38_DSPR2(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst, int dst_width); -void ScaleRowDown38_2_Box_DSPR2(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); -void ScaleRowDown38_3_Box_DSPR2(const uint8* src_ptr, ptrdiff_t src_stride, - uint8* dst_ptr, int dst_width); - -#ifdef __cplusplus -} // extern "C" -} // namespace libyuv -#endif - -#endif // INCLUDE_LIBYUV_SCALE_ROW_H_ diff --git a/third_party/libyuv/include/libyuv/version.h b/third_party/libyuv/include/libyuv/version.h deleted file mode 100644 index 3a8f633..0000000 --- a/third_party/libyuv/include/libyuv/version.h +++ /dev/null @@ -1,16 +0,0 @@ -/* - * Copyright 2012 The LibYuv Project Authors. All rights reserved. - * - * Use of this source code is governed by a BSD-style license - * that can be found in the LICENSE file in the root of the source - * tree. An additional intellectual property rights grant can be found - * in the file PATENTS. All contributing project authors may - * be found in the AUTHORS file in the root of the source tree. - */ - -#ifndef INCLUDE_LIBYUV_VERSION_H_ -#define INCLUDE_LIBYUV_VERSION_H_ - -#define LIBYUV_VERSION 1622 - -#endif // INCLUDE_LIBYUV_VERSION_H_ diff --git a/third_party/libyuv/include/libyuv/video_common.h b/third_party/libyuv/include/libyuv/video_common.h deleted file mode 100644 index cb42542..0000000 --- a/third_party/libyuv/include/libyuv/video_common.h +++ /dev/null @@ -1,184 +0,0 @@ -/* - * Copyright 2011 The LibYuv Project Authors. All rights reserved. - * - * Use of this source code is governed by a BSD-style license - * that can be found in the LICENSE file in the root of the source - * tree. An additional intellectual property rights grant can be found - * in the file PATENTS. All contributing project authors may - * be found in the AUTHORS file in the root of the source tree. - */ - -// Common definitions for video, including fourcc and VideoFormat. - -#ifndef INCLUDE_LIBYUV_VIDEO_COMMON_H_ -#define INCLUDE_LIBYUV_VIDEO_COMMON_H_ - -#include "libyuv/basic_types.h" - -#ifdef __cplusplus -namespace libyuv { -extern "C" { -#endif - -////////////////////////////////////////////////////////////////////////////// -// Definition of FourCC codes -////////////////////////////////////////////////////////////////////////////// - -// Convert four characters to a FourCC code. -// Needs to be a macro otherwise the OS X compiler complains when the kFormat* -// constants are used in a switch. -#ifdef __cplusplus -#define FOURCC(a, b, c, d) ( \ - (static_cast(a)) | (static_cast(b) << 8) | \ - (static_cast(c) << 16) | (static_cast(d) << 24)) -#else -#define FOURCC(a, b, c, d) ( \ - ((uint32)(a)) | ((uint32)(b) << 8) | /* NOLINT */ \ - ((uint32)(c) << 16) | ((uint32)(d) << 24)) /* NOLINT */ -#endif - -// Some pages discussing FourCC codes: -// http://www.fourcc.org/yuv.php -// http://v4l2spec.bytesex.org/spec/book1.htm -// http://developer.apple.com/quicktime/icefloe/dispatch020.html -// http://msdn.microsoft.com/library/windows/desktop/dd206750.aspx#nv12 -// http://people.xiph.org/~xiphmont/containers/nut/nut4cc.txt - -// FourCC codes grouped according to implementation efficiency. -// Primary formats should convert in 1 efficient step. -// Secondary formats are converted in 2 steps. -// Auxilliary formats call primary converters. -enum FourCC { - // 9 Primary YUV formats: 5 planar, 2 biplanar, 2 packed. - FOURCC_I420 = FOURCC('I', '4', '2', '0'), - FOURCC_I422 = FOURCC('I', '4', '2', '2'), - FOURCC_I444 = FOURCC('I', '4', '4', '4'), - FOURCC_I411 = FOURCC('I', '4', '1', '1'), - FOURCC_I400 = FOURCC('I', '4', '0', '0'), - FOURCC_NV21 = FOURCC('N', 'V', '2', '1'), - FOURCC_NV12 = FOURCC('N', 'V', '1', '2'), - FOURCC_YUY2 = FOURCC('Y', 'U', 'Y', '2'), - FOURCC_UYVY = FOURCC('U', 'Y', 'V', 'Y'), - - // 2 Secondary YUV formats: row biplanar. - FOURCC_M420 = FOURCC('M', '4', '2', '0'), - FOURCC_Q420 = FOURCC('Q', '4', '2', '0'), // deprecated. - - // 9 Primary RGB formats: 4 32 bpp, 2 24 bpp, 3 16 bpp. - FOURCC_ARGB = FOURCC('A', 'R', 'G', 'B'), - FOURCC_BGRA = FOURCC('B', 'G', 'R', 'A'), - FOURCC_ABGR = FOURCC('A', 'B', 'G', 'R'), - FOURCC_24BG = FOURCC('2', '4', 'B', 'G'), - FOURCC_RAW = FOURCC('r', 'a', 'w', ' '), - FOURCC_RGBA = FOURCC('R', 'G', 'B', 'A'), - FOURCC_RGBP = FOURCC('R', 'G', 'B', 'P'), // rgb565 LE. - FOURCC_RGBO = FOURCC('R', 'G', 'B', 'O'), // argb1555 LE. - FOURCC_R444 = FOURCC('R', '4', '4', '4'), // argb4444 LE. - - // 4 Secondary RGB formats: 4 Bayer Patterns. deprecated. - FOURCC_RGGB = FOURCC('R', 'G', 'G', 'B'), - FOURCC_BGGR = FOURCC('B', 'G', 'G', 'R'), - FOURCC_GRBG = FOURCC('G', 'R', 'B', 'G'), - FOURCC_GBRG = FOURCC('G', 'B', 'R', 'G'), - - // 1 Primary Compressed YUV format. - FOURCC_MJPG = FOURCC('M', 'J', 'P', 'G'), - - // 5 Auxiliary YUV variations: 3 with U and V planes are swapped, 1 Alias. - FOURCC_YV12 = FOURCC('Y', 'V', '1', '2'), - FOURCC_YV16 = FOURCC('Y', 'V', '1', '6'), - FOURCC_YV24 = FOURCC('Y', 'V', '2', '4'), - FOURCC_YU12 = FOURCC('Y', 'U', '1', '2'), // Linux version of I420. - FOURCC_J420 = FOURCC('J', '4', '2', '0'), - FOURCC_J400 = FOURCC('J', '4', '0', '0'), // unofficial fourcc - FOURCC_H420 = FOURCC('H', '4', '2', '0'), // unofficial fourcc - - // 14 Auxiliary aliases. CanonicalFourCC() maps these to canonical fourcc. - FOURCC_IYUV = FOURCC('I', 'Y', 'U', 'V'), // Alias for I420. - FOURCC_YU16 = FOURCC('Y', 'U', '1', '6'), // Alias for I422. - FOURCC_YU24 = FOURCC('Y', 'U', '2', '4'), // Alias for I444. - FOURCC_YUYV = FOURCC('Y', 'U', 'Y', 'V'), // Alias for YUY2. - FOURCC_YUVS = FOURCC('y', 'u', 'v', 's'), // Alias for YUY2 on Mac. - FOURCC_HDYC = FOURCC('H', 'D', 'Y', 'C'), // Alias for UYVY. - FOURCC_2VUY = FOURCC('2', 'v', 'u', 'y'), // Alias for UYVY on Mac. - FOURCC_JPEG = FOURCC('J', 'P', 'E', 'G'), // Alias for MJPG. - FOURCC_DMB1 = FOURCC('d', 'm', 'b', '1'), // Alias for MJPG on Mac. - FOURCC_BA81 = FOURCC('B', 'A', '8', '1'), // Alias for BGGR. - FOURCC_RGB3 = FOURCC('R', 'G', 'B', '3'), // Alias for RAW. - FOURCC_BGR3 = FOURCC('B', 'G', 'R', '3'), // Alias for 24BG. - FOURCC_CM32 = FOURCC(0, 0, 0, 32), // Alias for BGRA kCMPixelFormat_32ARGB - FOURCC_CM24 = FOURCC(0, 0, 0, 24), // Alias for RAW kCMPixelFormat_24RGB - FOURCC_L555 = FOURCC('L', '5', '5', '5'), // Alias for RGBO. - FOURCC_L565 = FOURCC('L', '5', '6', '5'), // Alias for RGBP. - FOURCC_5551 = FOURCC('5', '5', '5', '1'), // Alias for RGBO. - - // 1 Auxiliary compressed YUV format set aside for capturer. - FOURCC_H264 = FOURCC('H', '2', '6', '4'), - - // Match any fourcc. - FOURCC_ANY = -1, -}; - -enum FourCCBpp { - // Canonical fourcc codes used in our code. - FOURCC_BPP_I420 = 12, - FOURCC_BPP_I422 = 16, - FOURCC_BPP_I444 = 24, - FOURCC_BPP_I411 = 12, - FOURCC_BPP_I400 = 8, - FOURCC_BPP_NV21 = 12, - FOURCC_BPP_NV12 = 12, - FOURCC_BPP_YUY2 = 16, - FOURCC_BPP_UYVY = 16, - FOURCC_BPP_M420 = 12, - FOURCC_BPP_Q420 = 12, - FOURCC_BPP_ARGB = 32, - FOURCC_BPP_BGRA = 32, - FOURCC_BPP_ABGR = 32, - FOURCC_BPP_RGBA = 32, - FOURCC_BPP_24BG = 24, - FOURCC_BPP_RAW = 24, - FOURCC_BPP_RGBP = 16, - FOURCC_BPP_RGBO = 16, - FOURCC_BPP_R444 = 16, - FOURCC_BPP_RGGB = 8, - FOURCC_BPP_BGGR = 8, - FOURCC_BPP_GRBG = 8, - FOURCC_BPP_GBRG = 8, - FOURCC_BPP_YV12 = 12, - FOURCC_BPP_YV16 = 16, - FOURCC_BPP_YV24 = 24, - FOURCC_BPP_YU12 = 12, - FOURCC_BPP_J420 = 12, - FOURCC_BPP_J400 = 8, - FOURCC_BPP_H420 = 12, - FOURCC_BPP_MJPG = 0, // 0 means unknown. - FOURCC_BPP_H264 = 0, - FOURCC_BPP_IYUV = 12, - FOURCC_BPP_YU16 = 16, - FOURCC_BPP_YU24 = 24, - FOURCC_BPP_YUYV = 16, - FOURCC_BPP_YUVS = 16, - FOURCC_BPP_HDYC = 16, - FOURCC_BPP_2VUY = 16, - FOURCC_BPP_JPEG = 1, - FOURCC_BPP_DMB1 = 1, - FOURCC_BPP_BA81 = 8, - FOURCC_BPP_RGB3 = 24, - FOURCC_BPP_BGR3 = 24, - FOURCC_BPP_CM32 = 32, - FOURCC_BPP_CM24 = 24, - - // Match any fourcc. - FOURCC_BPP_ANY = 0, // 0 means unknown. -}; - -// Converts fourcc aliases into canonical ones. -LIBYUV_API uint32 CanonicalFourCC(uint32 fourcc); - -#ifdef __cplusplus -} // extern "C" -} // namespace libyuv -#endif - -#endif // INCLUDE_LIBYUV_VIDEO_COMMON_H_ diff --git a/third_party/libyuv/larch64/lib/libyuv.a b/third_party/libyuv/larch64/lib/libyuv.a deleted file mode 100644 index fdbcda2..0000000 Binary files a/third_party/libyuv/larch64/lib/libyuv.a and /dev/null differ diff --git a/third_party/libyuv/x86_64/include b/third_party/libyuv/x86_64/include deleted file mode 120000 index f5030fe..0000000 --- a/third_party/libyuv/x86_64/include +++ /dev/null @@ -1 +0,0 @@ -../include \ No newline at end of file diff --git a/third_party/libyuv/x86_64/lib/libyuv.a b/third_party/libyuv/x86_64/lib/libyuv.a deleted file mode 100644 index ef786b1..0000000 Binary files a/third_party/libyuv/x86_64/lib/libyuv.a and /dev/null differ diff --git a/third_party/linux/include/linux/ion.h b/third_party/linux/include/linux/ion.h deleted file mode 100644 index 7b5b031..0000000 --- a/third_party/linux/include/linux/ion.h +++ /dev/null @@ -1,78 +0,0 @@ -/**************************************************************************** - **************************************************************************** - *** - *** This header was automatically generated from a Linux kernel header - *** of the same name, to make information necessary for userspace to - *** call into the kernel available to libc. It contains only constants, - *** structures, and macros generated from the original header, and thus, - *** contains no copyrightable information. - *** - *** To edit the content of this header, modify the corresponding - *** source file (e.g. under external/kernel-headers/original/) then - *** run bionic/libc/kernel/tools/update_all.py - *** - *** Any manual change here will be lost the next time this script will - *** be run. You've been warned! - *** - **************************************************************************** - ****************************************************************************/ -#ifndef _UAPI_LINUX_ION_H -#define _UAPI_LINUX_ION_H -#include -#include -typedef int ion_user_handle_t; -enum ion_heap_type { - ION_HEAP_TYPE_SYSTEM, - ION_HEAP_TYPE_SYSTEM_CONTIG, - ION_HEAP_TYPE_CARVEOUT, - ION_HEAP_TYPE_CHUNK, - ION_HEAP_TYPE_DMA, - ION_HEAP_TYPE_CUSTOM, -}; -#define ION_NUM_HEAP_IDS (sizeof(unsigned int) * 8) -#define ION_FLAG_CACHED 1 -#define ION_FLAG_CACHED_NEEDS_SYNC 2 -struct ion_allocation_data { - size_t len; - size_t align; - unsigned int heap_id_mask; - unsigned int flags; - ion_user_handle_t handle; -}; -struct ion_fd_data { - ion_user_handle_t handle; - int fd; -}; -struct ion_handle_data { - ion_user_handle_t handle; -}; -struct ion_custom_data { - unsigned int cmd; - unsigned long arg; -}; -#define MAX_HEAP_NAME 32 -struct ion_heap_data { - char name[MAX_HEAP_NAME]; - __u32 type; - __u32 heap_id; - __u32 reserved0; - __u32 reserved1; - __u32 reserved2; -}; -struct ion_heap_query { - __u32 cnt; - __u32 reserved0; - __u64 heaps; - __u32 reserved1; - __u32 reserved2; -}; -#define ION_IOC_MAGIC 'I' -#define ION_IOC_ALLOC _IOWR(ION_IOC_MAGIC, 0, struct ion_allocation_data) -#define ION_IOC_FREE _IOWR(ION_IOC_MAGIC, 1, struct ion_handle_data) -#define ION_IOC_MAP _IOWR(ION_IOC_MAGIC, 2, struct ion_fd_data) -#define ION_IOC_SHARE _IOWR(ION_IOC_MAGIC, 4, struct ion_fd_data) -#define ION_IOC_IMPORT _IOWR(ION_IOC_MAGIC, 5, struct ion_fd_data) -#define ION_IOC_SYNC _IOWR(ION_IOC_MAGIC, 7, struct ion_fd_data) -#define ION_IOC_CUSTOM _IOWR(ION_IOC_MAGIC, 6, struct ion_custom_data) -#define ION_IOC_HEAP_QUERY _IOWR(ION_IOC_MAGIC, 8, struct ion_heap_query) -#endif diff --git a/third_party/linux/include/media/cam_cpas.h b/third_party/linux/include/media/cam_cpas.h deleted file mode 100644 index c5cbac8..0000000 --- a/third_party/linux/include/media/cam_cpas.h +++ /dev/null @@ -1,25 +0,0 @@ -#ifndef __UAPI_CAM_CPAS_H__ -#define __UAPI_CAM_CPAS_H__ - -#include "cam_defs.h" - -#define CAM_FAMILY_CAMERA_SS 1 -#define CAM_FAMILY_CPAS_SS 2 - -/** - * struct cam_cpas_query_cap - CPAS query device capability payload - * - * @camera_family : Camera family type - * @reserved : Reserved field for alignment - * @camera_version : Camera platform version - * @cpas_version : Camera CPAS version within camera platform - * - */ -struct cam_cpas_query_cap { - uint32_t camera_family; - uint32_t reserved; - struct cam_hw_version camera_version; - struct cam_hw_version cpas_version; -}; - -#endif /* __UAPI_CAM_CPAS_H__ */ diff --git a/third_party/linux/include/media/cam_defs.h b/third_party/linux/include/media/cam_defs.h deleted file mode 100644 index e006463..0000000 --- a/third_party/linux/include/media/cam_defs.h +++ /dev/null @@ -1,477 +0,0 @@ -#ifndef __UAPI_CAM_DEFS_H__ -#define __UAPI_CAM_DEFS_H__ - -#include -#include -#include - - -/* camera op codes */ -#define CAM_COMMON_OPCODE_BASE 0x100 -#define CAM_QUERY_CAP (CAM_COMMON_OPCODE_BASE + 0x1) -#define CAM_ACQUIRE_DEV (CAM_COMMON_OPCODE_BASE + 0x2) -#define CAM_START_DEV (CAM_COMMON_OPCODE_BASE + 0x3) -#define CAM_STOP_DEV (CAM_COMMON_OPCODE_BASE + 0x4) -#define CAM_CONFIG_DEV (CAM_COMMON_OPCODE_BASE + 0x5) -#define CAM_RELEASE_DEV (CAM_COMMON_OPCODE_BASE + 0x6) -#define CAM_SD_SHUTDOWN (CAM_COMMON_OPCODE_BASE + 0x7) -#define CAM_FLUSH_REQ (CAM_COMMON_OPCODE_BASE + 0x8) -#define CAM_COMMON_OPCODE_MAX (CAM_COMMON_OPCODE_BASE + 0x9) - -#define CAM_EXT_OPCODE_BASE 0x200 -#define CAM_CONFIG_DEV_EXTERNAL (CAM_EXT_OPCODE_BASE + 0x1) - -/* camera handle type */ -#define CAM_HANDLE_USER_POINTER 1 -#define CAM_HANDLE_MEM_HANDLE 2 - -/* Generic Blob CmdBuffer header properties */ -#define CAM_GENERIC_BLOB_CMDBUFFER_SIZE_MASK 0xFFFFFF00 -#define CAM_GENERIC_BLOB_CMDBUFFER_SIZE_SHIFT 8 -#define CAM_GENERIC_BLOB_CMDBUFFER_TYPE_MASK 0xFF -#define CAM_GENERIC_BLOB_CMDBUFFER_TYPE_SHIFT 0 - -/* Command Buffer Types */ -#define CAM_CMD_BUF_DMI 0x1 -#define CAM_CMD_BUF_DMI16 0x2 -#define CAM_CMD_BUF_DMI32 0x3 -#define CAM_CMD_BUF_DMI64 0x4 -#define CAM_CMD_BUF_DIRECT 0x5 -#define CAM_CMD_BUF_INDIRECT 0x6 -#define CAM_CMD_BUF_I2C 0x7 -#define CAM_CMD_BUF_FW 0x8 -#define CAM_CMD_BUF_GENERIC 0x9 -#define CAM_CMD_BUF_LEGACY 0xA - -/** - * enum flush_type_t - Identifies the various flush types - * - * @CAM_FLUSH_TYPE_REQ: Flush specific request - * @CAM_FLUSH_TYPE_ALL: Flush all requests belonging to a context - * @CAM_FLUSH_TYPE_MAX: Max enum to validate flush type - * - */ -enum flush_type_t { - CAM_FLUSH_TYPE_REQ, - CAM_FLUSH_TYPE_ALL, - CAM_FLUSH_TYPE_MAX -}; - -/** - * struct cam_control - Structure used by ioctl control for camera - * - * @op_code: This is the op code for camera control - * @size: Control command size - * @handle_type: User pointer or shared memory handle - * @reserved: Reserved field for 64 bit alignment - * @handle: Control command payload - */ -struct cam_control { - uint32_t op_code; - uint32_t size; - uint32_t handle_type; - uint32_t reserved; - uint64_t handle; -}; - -/* camera IOCTL */ -#define VIDIOC_CAM_CONTROL \ - _IOWR('V', BASE_VIDIOC_PRIVATE, struct cam_control) - -/** - * struct cam_hw_version - Structure for HW version of camera devices - * - * @major : Hardware version major - * @minor : Hardware version minor - * @incr : Hardware version increment - * @reserved : Reserved for 64 bit aligngment - */ -struct cam_hw_version { - uint32_t major; - uint32_t minor; - uint32_t incr; - uint32_t reserved; -}; - -/** - * struct cam_iommu_handle - Structure for IOMMU handles of camera hw devices - * - * @non_secure: Device Non Secure IOMMU handle - * @secure: Device Secure IOMMU handle - * - */ -struct cam_iommu_handle { - int32_t non_secure; - int32_t secure; -}; - -/* camera secure mode */ -#define CAM_SECURE_MODE_NON_SECURE 0 -#define CAM_SECURE_MODE_SECURE 1 - -/* Camera Format Type */ -#define CAM_FORMAT_BASE 0 -#define CAM_FORMAT_MIPI_RAW_6 1 -#define CAM_FORMAT_MIPI_RAW_8 2 -#define CAM_FORMAT_MIPI_RAW_10 3 -#define CAM_FORMAT_MIPI_RAW_12 4 -#define CAM_FORMAT_MIPI_RAW_14 5 -#define CAM_FORMAT_MIPI_RAW_16 6 -#define CAM_FORMAT_MIPI_RAW_20 7 -#define CAM_FORMAT_QTI_RAW_8 8 -#define CAM_FORMAT_QTI_RAW_10 9 -#define CAM_FORMAT_QTI_RAW_12 10 -#define CAM_FORMAT_QTI_RAW_14 11 -#define CAM_FORMAT_PLAIN8 12 -#define CAM_FORMAT_PLAIN16_8 13 -#define CAM_FORMAT_PLAIN16_10 14 -#define CAM_FORMAT_PLAIN16_12 15 -#define CAM_FORMAT_PLAIN16_14 16 -#define CAM_FORMAT_PLAIN16_16 17 -#define CAM_FORMAT_PLAIN32_20 18 -#define CAM_FORMAT_PLAIN64 19 -#define CAM_FORMAT_PLAIN128 20 -#define CAM_FORMAT_ARGB 21 -#define CAM_FORMAT_ARGB_10 22 -#define CAM_FORMAT_ARGB_12 23 -#define CAM_FORMAT_ARGB_14 24 -#define CAM_FORMAT_DPCM_10_6_10 25 -#define CAM_FORMAT_DPCM_10_8_10 26 -#define CAM_FORMAT_DPCM_12_6_12 27 -#define CAM_FORMAT_DPCM_12_8_12 28 -#define CAM_FORMAT_DPCM_14_8_14 29 -#define CAM_FORMAT_DPCM_14_10_14 30 -#define CAM_FORMAT_NV21 31 -#define CAM_FORMAT_NV12 32 -#define CAM_FORMAT_TP10 33 -#define CAM_FORMAT_YUV422 34 -#define CAM_FORMAT_PD8 35 -#define CAM_FORMAT_PD10 36 -#define CAM_FORMAT_UBWC_NV12 37 -#define CAM_FORMAT_UBWC_NV12_4R 38 -#define CAM_FORMAT_UBWC_TP10 39 -#define CAM_FORMAT_UBWC_P010 40 -#define CAM_FORMAT_PLAIN8_SWAP 41 -#define CAM_FORMAT_PLAIN8_10 42 -#define CAM_FORMAT_PLAIN8_10_SWAP 43 -#define CAM_FORMAT_YV12 44 -#define CAM_FORMAT_Y_ONLY 45 -#define CAM_FORMAT_MAX 46 - -/* camera rotaion */ -#define CAM_ROTATE_CW_0_DEGREE 0 -#define CAM_ROTATE_CW_90_DEGREE 1 -#define CAM_RORATE_CW_180_DEGREE 2 -#define CAM_ROTATE_CW_270_DEGREE 3 - -/* camera Color Space */ -#define CAM_COLOR_SPACE_BASE 0 -#define CAM_COLOR_SPACE_BT601_FULL 1 -#define CAM_COLOR_SPACE_BT601625 2 -#define CAM_COLOR_SPACE_BT601525 3 -#define CAM_COLOR_SPACE_BT709 4 -#define CAM_COLOR_SPACE_DEPTH 5 -#define CAM_COLOR_SPACE_MAX 6 - -/* camera buffer direction */ -#define CAM_BUF_INPUT 1 -#define CAM_BUF_OUTPUT 2 -#define CAM_BUF_IN_OUT 3 - -/* camera packet device Type */ -#define CAM_PACKET_DEV_BASE 0 -#define CAM_PACKET_DEV_IMG_SENSOR 1 -#define CAM_PACKET_DEV_ACTUATOR 2 -#define CAM_PACKET_DEV_COMPANION 3 -#define CAM_PACKET_DEV_EEPOM 4 -#define CAM_PACKET_DEV_CSIPHY 5 -#define CAM_PACKET_DEV_OIS 6 -#define CAM_PACKET_DEV_FLASH 7 -#define CAM_PACKET_DEV_FD 8 -#define CAM_PACKET_DEV_JPEG_ENC 9 -#define CAM_PACKET_DEV_JPEG_DEC 10 -#define CAM_PACKET_DEV_VFE 11 -#define CAM_PACKET_DEV_CPP 12 -#define CAM_PACKET_DEV_CSID 13 -#define CAM_PACKET_DEV_ISPIF 14 -#define CAM_PACKET_DEV_IFE 15 -#define CAM_PACKET_DEV_ICP 16 -#define CAM_PACKET_DEV_LRME 17 -#define CAM_PACKET_DEV_MAX 18 - - -/* constants */ -#define CAM_PACKET_MAX_PLANES 3 - -/** - * struct cam_plane_cfg - Plane configuration info - * - * @width: Plane width in pixels - * @height: Plane height in lines - * @plane_stride: Plane stride in pixel - * @slice_height: Slice height in line (not used by ISP) - * @meta_stride: UBWC metadata stride - * @meta_size: UBWC metadata plane size - * @meta_offset: UBWC metadata offset - * @packer_config: UBWC packer config - * @mode_config: UBWC mode config - * @tile_config: UBWC tile config - * @h_init: UBWC horizontal initial coordinate in pixels - * @v_init: UBWC vertical initial coordinate in lines - * - */ -struct cam_plane_cfg { - uint32_t width; - uint32_t height; - uint32_t plane_stride; - uint32_t slice_height; - uint32_t meta_stride; - uint32_t meta_size; - uint32_t meta_offset; - uint32_t packer_config; - uint32_t mode_config; - uint32_t tile_config; - uint32_t h_init; - uint32_t v_init; -}; - -/** - * struct cam_cmd_buf_desc - Command buffer descriptor - * - * @mem_handle: Command buffer handle - * @offset: Command start offset - * @size: Size of the command buffer in bytes - * @length: Used memory in command buffer in bytes - * @type: Type of the command buffer - * @meta_data: Data type for private command buffer - * Between UMD and KMD - * - */ -struct cam_cmd_buf_desc { - int32_t mem_handle; - uint32_t offset; - uint32_t size; - uint32_t length; - uint32_t type; - uint32_t meta_data; -}; - -/** - * struct cam_buf_io_cfg - Buffer io configuration for buffers - * - * @mem_handle: Mem_handle array for the buffers. - * @offsets: Offsets for each planes in the buffer - * @planes: Per plane information - * @width: Main plane width in pixel - * @height: Main plane height in lines - * @format: Format of the buffer - * @color_space: Color space for the buffer - * @color_pattern: Color pattern in the buffer - * @bpp: Bit per pixel - * @rotation: Rotation information for the buffer - * @resource_type: Resource type associated with the buffer - * @fence: Fence handle - * @early_fence: Fence handle for early signal - * @aux_cmd_buf: An auxiliary command buffer that may be - * used for programming the IO - * @direction: Direction of the config - * @batch_size: Batch size in HFR mode - * @subsample_pattern: Subsample pattern. Used in HFR mode. It - * should be consistent with batchSize and - * CAMIF programming. - * @subsample_period: Subsample period. Used in HFR mode. It - * should be consistent with batchSize and - * CAMIF programming. - * @framedrop_pattern: Framedrop pattern - * @framedrop_period: Framedrop period - * @flag: Flags for extra information - * @direction: Buffer direction: input or output - * @padding: Padding for the structure - * - */ -struct cam_buf_io_cfg { - int32_t mem_handle[CAM_PACKET_MAX_PLANES]; - uint32_t offsets[CAM_PACKET_MAX_PLANES]; - struct cam_plane_cfg planes[CAM_PACKET_MAX_PLANES]; - uint32_t format; - uint32_t color_space; - uint32_t color_pattern; - uint32_t bpp; - uint32_t rotation; - uint32_t resource_type; - int32_t fence; - int32_t early_fence; - struct cam_cmd_buf_desc aux_cmd_buf; - uint32_t direction; - uint32_t batch_size; - uint32_t subsample_pattern; - uint32_t subsample_period; - uint32_t framedrop_pattern; - uint32_t framedrop_period; - uint32_t flag; - uint32_t padding; -}; - -/** - * struct cam_packet_header - Camera packet header - * - * @op_code: Camera packet opcode - * @size: Size of the camera packet in bytes - * @request_id: Request id for this camera packet - * @flags: Flags for the camera packet - * @padding: Padding - * - */ -struct cam_packet_header { - uint32_t op_code; - uint32_t size; - uint64_t request_id; - uint32_t flags; - uint32_t padding; -}; - -/** - * struct cam_patch_desc - Patch structure - * - * @dst_buf_hdl: Memory handle for the dest buffer - * @dst_offset: Offset byte in the dest buffer - * @src_buf_hdl: Memory handle for the source buffer - * @src_offset: Offset byte in the source buffer - * - */ -struct cam_patch_desc { - int32_t dst_buf_hdl; - uint32_t dst_offset; - int32_t src_buf_hdl; - uint32_t src_offset; -}; - -/** - * struct cam_packet - Camera packet structure - * - * @header: Camera packet header - * @cmd_buf_offset: Command buffer start offset - * @num_cmd_buf: Number of the command buffer in the packet - * @io_config_offset: Buffer io configuration start offset - * @num_io_configs: Number of the buffer io configurations - * @patch_offset: Patch offset for the patch structure - * @num_patches: Number of the patch structure - * @kmd_cmd_buf_index: Command buffer index which contains extra - * space for the KMD buffer - * @kmd_cmd_buf_offset: Offset from the beginning of the command - * buffer for KMD usage. - * @payload: Camera packet payload - * - */ -struct cam_packet { - struct cam_packet_header header; - uint32_t cmd_buf_offset; - uint32_t num_cmd_buf; - uint32_t io_configs_offset; - uint32_t num_io_configs; - uint32_t patch_offset; - uint32_t num_patches; - uint32_t kmd_cmd_buf_index; - uint32_t kmd_cmd_buf_offset; - uint64_t payload[1]; - -}; - -/** - * struct cam_release_dev_cmd - Control payload for release devices - * - * @session_handle: Session handle for the release - * @dev_handle: Device handle for the release - */ -struct cam_release_dev_cmd { - int32_t session_handle; - int32_t dev_handle; -}; - -/** - * struct cam_start_stop_dev_cmd - Control payload for start/stop device - * - * @session_handle: Session handle for the start/stop command - * @dev_handle: Device handle for the start/stop command - * - */ -struct cam_start_stop_dev_cmd { - int32_t session_handle; - int32_t dev_handle; -}; - -/** - * struct cam_config_dev_cmd - Command payload for configure device - * - * @session_handle: Session handle for the command - * @dev_handle: Device handle for the command - * @offset: Offset byte in the packet handle. - * @packet_handle: Packet memory handle for the actual packet: - * struct cam_packet. - * - */ -struct cam_config_dev_cmd { - int32_t session_handle; - int32_t dev_handle; - uint64_t offset; - uint64_t packet_handle; -}; - -/** - * struct cam_query_cap_cmd - Payload for query device capability - * - * @size: Handle size - * @handle_type: User pointer or shared memory handle - * @caps_handle: Device specific query command payload - * - */ -struct cam_query_cap_cmd { - uint32_t size; - uint32_t handle_type; - uint64_t caps_handle; -}; - -/** - * struct cam_acquire_dev_cmd - Control payload for acquire devices - * - * @session_handle: Session handle for the acquire command - * @dev_handle: Device handle to be returned - * @handle_type: Resource handle type: - * 1 = user pointer, 2 = mem handle - * @num_resources: Number of the resources to be acquired - * @resources_hdl: Resource handle that refers to the actual - * resource array. Each item in this - * array is device specific resource structure - * - */ -struct cam_acquire_dev_cmd { - int32_t session_handle; - int32_t dev_handle; - uint32_t handle_type; - uint32_t num_resources; - uint64_t resource_hdl; -}; - -/** - * struct cam_flush_dev_cmd - Control payload for flush devices - * - * @version: Version - * @session_handle: Session handle for the acquire command - * @dev_handle: Device handle to be returned - * @flush_type: Flush type: - * 0 = flush specific request - * 1 = flush all - * @reserved: Reserved for 64 bit aligngment - * @req_id: Request id that needs to cancel - * - */ -struct cam_flush_dev_cmd { - uint64_t version; - int32_t session_handle; - int32_t dev_handle; - uint32_t flush_type; - uint32_t reserved; - int64_t req_id; -}; - -#endif /* __UAPI_CAM_DEFS_H__ */ diff --git a/third_party/linux/include/media/cam_fd.h b/third_party/linux/include/media/cam_fd.h deleted file mode 100644 index 8feb6e4..0000000 --- a/third_party/linux/include/media/cam_fd.h +++ /dev/null @@ -1,127 +0,0 @@ -#ifndef __UAPI_CAM_FD_H__ -#define __UAPI_CAM_FD_H__ - -#include "cam_defs.h" - -#define CAM_FD_MAX_FACES 35 -#define CAM_FD_RAW_RESULT_ENTRIES 512 - -/* FD Op Codes */ -#define CAM_PACKET_OPCODES_FD_FRAME_UPDATE 0x0 - -/* FD Command Buffer identifiers */ -#define CAM_FD_CMD_BUFFER_ID_GENERIC 0x0 -#define CAM_FD_CMD_BUFFER_ID_CDM 0x1 -#define CAM_FD_CMD_BUFFER_ID_MAX 0x2 - -/* FD Blob types */ -#define CAM_FD_BLOB_TYPE_SOC_CLOCK_BW_REQUEST 0x0 -#define CAM_FD_BLOB_TYPE_RAW_RESULTS_REQUIRED 0x1 - -/* FD Resource IDs */ -#define CAM_FD_INPUT_PORT_ID_IMAGE 0x0 -#define CAM_FD_INPUT_PORT_ID_MAX 0x1 - -#define CAM_FD_OUTPUT_PORT_ID_RESULTS 0x0 -#define CAM_FD_OUTPUT_PORT_ID_RAW_RESULTS 0x1 -#define CAM_FD_OUTPUT_PORT_ID_WORK_BUFFER 0x2 -#define CAM_FD_OUTPUT_PORT_ID_MAX 0x3 - -/** - * struct cam_fd_soc_clock_bw_request - SOC clock, bandwidth request info - * - * @clock_rate : Clock rate required while processing frame - * @bandwidth : Bandwidth required while processing frame - * @reserved : Reserved for future use - */ -struct cam_fd_soc_clock_bw_request { - uint64_t clock_rate; - uint64_t bandwidth; - uint64_t reserved[4]; -}; - -/** - * struct cam_fd_face - Face properties - * - * @prop1 : Property 1 of face - * @prop2 : Property 2 of face - * @prop3 : Property 3 of face - * @prop4 : Property 4 of face - * - * Do not change this layout, this is inline with how HW writes - * these values directly when the buffer is programmed to HW - */ -struct cam_fd_face { - uint32_t prop1; - uint32_t prop2; - uint32_t prop3; - uint32_t prop4; -}; - -/** - * struct cam_fd_results - FD results layout - * - * @faces : Array of faces with face properties - * @face_count : Number of faces detected - * @reserved : Reserved for alignment - * - * Do not change this layout, this is inline with how HW writes - * these values directly when the buffer is programmed to HW - */ -struct cam_fd_results { - struct cam_fd_face faces[CAM_FD_MAX_FACES]; - uint32_t face_count; - uint32_t reserved[3]; -}; - -/** - * struct cam_fd_hw_caps - Face properties - * - * @core_version : FD core version - * @wrapper_version : FD wrapper version - * @raw_results_available : Whether raw results are available on this HW - * @supported_modes : Modes supported by this HW. - * @reserved : Reserved for future use - */ -struct cam_fd_hw_caps { - struct cam_hw_version core_version; - struct cam_hw_version wrapper_version; - uint32_t raw_results_available; - uint32_t supported_modes; - uint64_t reserved; -}; - -/** - * struct cam_fd_query_cap_cmd - FD Query capabilities information - * - * @device_iommu : FD IOMMU handles - * @cdm_iommu : CDM iommu handles - * @hw_caps : FD HW capabilities - * @reserved : Reserved for alignment - */ -struct cam_fd_query_cap_cmd { - struct cam_iommu_handle device_iommu; - struct cam_iommu_handle cdm_iommu; - struct cam_fd_hw_caps hw_caps; - uint64_t reserved; -}; - -/** - * struct cam_fd_acquire_dev_info - FD acquire device information - * - * @clk_bw_request : SOC clock, bandwidth request - * @priority : Priority for this acquire - * @mode : Mode in which to run FD HW. - * @get_raw_results : Whether this acquire needs face raw results - * while frame processing - * @reserved : Reserved field for 64 bit alignment - */ -struct cam_fd_acquire_dev_info { - struct cam_fd_soc_clock_bw_request clk_bw_request; - uint32_t priority; - uint32_t mode; - uint32_t get_raw_results; - uint32_t reserved[13]; -}; - -#endif /* __UAPI_CAM_FD_H__ */ diff --git a/third_party/linux/include/media/cam_icp.h b/third_party/linux/include/media/cam_icp.h deleted file mode 100644 index 680d05b..0000000 --- a/third_party/linux/include/media/cam_icp.h +++ /dev/null @@ -1,179 +0,0 @@ -#ifndef __UAPI_CAM_ICP_H__ -#define __UAPI_CAM_ICP_H__ - -#include "cam_defs.h" - -/* icp, ipe, bps, cdm(ipe/bps) are used in querycap */ -#define CAM_ICP_DEV_TYPE_A5 1 -#define CAM_ICP_DEV_TYPE_IPE 2 -#define CAM_ICP_DEV_TYPE_BPS 3 -#define CAM_ICP_DEV_TYPE_IPE_CDM 4 -#define CAM_ICP_DEV_TYPE_BPS_CDM 5 -#define CAM_ICP_DEV_TYPE_MAX 5 - -/* definitions needed for icp aquire device */ -#define CAM_ICP_RES_TYPE_BPS 1 -#define CAM_ICP_RES_TYPE_IPE_RT 2 -#define CAM_ICP_RES_TYPE_IPE 3 -#define CAM_ICP_RES_TYPE_MAX 4 - -/* packet opcode types */ -#define CAM_ICP_OPCODE_IPE_UPDATE 0 -#define CAM_ICP_OPCODE_BPS_UPDATE 1 - -/* IPE input port resource type */ -#define CAM_ICP_IPE_INPUT_IMAGE_FULL 0x0 -#define CAM_ICP_IPE_INPUT_IMAGE_DS4 0x1 -#define CAM_ICP_IPE_INPUT_IMAGE_DS16 0x2 -#define CAM_ICP_IPE_INPUT_IMAGE_DS64 0x3 -#define CAM_ICP_IPE_INPUT_IMAGE_FULL_REF 0x4 -#define CAM_ICP_IPE_INPUT_IMAGE_DS4_REF 0x5 -#define CAM_ICP_IPE_INPUT_IMAGE_DS16_REF 0x6 -#define CAM_ICP_IPE_INPUT_IMAGE_DS64_REF 0x7 - -/* IPE output port resource type */ -#define CAM_ICP_IPE_OUTPUT_IMAGE_DISPLAY 0x8 -#define CAM_ICP_IPE_OUTPUT_IMAGE_VIDEO 0x9 -#define CAM_ICP_IPE_OUTPUT_IMAGE_FULL_REF 0xA -#define CAM_ICP_IPE_OUTPUT_IMAGE_DS4_REF 0xB -#define CAM_ICP_IPE_OUTPUT_IMAGE_DS16_REF 0xC -#define CAM_ICP_IPE_OUTPUT_IMAGE_DS64_REF 0xD - -#define CAM_ICP_IPE_IMAGE_MAX 0xE - -/* BPS input port resource type */ -#define CAM_ICP_BPS_INPUT_IMAGE 0x0 - -/* BPS output port resource type */ -#define CAM_ICP_BPS_OUTPUT_IMAGE_FULL 0x1 -#define CAM_ICP_BPS_OUTPUT_IMAGE_DS4 0x2 -#define CAM_ICP_BPS_OUTPUT_IMAGE_DS16 0x3 -#define CAM_ICP_BPS_OUTPUT_IMAGE_DS64 0x4 -#define CAM_ICP_BPS_OUTPUT_IMAGE_STATS_BG 0x5 -#define CAM_ICP_BPS_OUTPUT_IMAGE_STATS_BHIST 0x6 -#define CAM_ICP_BPS_OUTPUT_IMAGE_REG1 0x7 -#define CAM_ICP_BPS_OUTPUT_IMAGE_REG2 0x8 - -#define CAM_ICP_BPS_IO_IMAGES_MAX 0x9 - -/* Command meta types */ -#define CAM_ICP_CMD_META_GENERIC_BLOB 0x1 - -/* Generic blob types */ -#define CAM_ICP_CMD_GENERIC_BLOB_CLK 0x1 -#define CAM_ICP_CMD_GENERIC_BLOB_CFG_IO 0x2 - -/** - * struct cam_icp_clk_bw_request - * - * @budget_ns: Time required to process frame - * @frame_cycles: Frame cycles needed to process the frame - * @rt_flag: Flag to indicate real time stream - * @uncompressed_bw: Bandwidth required to process frame - * @compressed_bw: Compressed bandwidth to process frame - */ -struct cam_icp_clk_bw_request { - uint64_t budget_ns; - uint32_t frame_cycles; - uint32_t rt_flag; - uint64_t uncompressed_bw; - uint64_t compressed_bw; -}; - -/** - * struct cam_icp_dev_ver - Device information for particular hw type - * - * This is used to get device version info of - * ICP, IPE, BPS and CDM related IPE and BPS from firmware - * and use this info in CAM_QUERY_CAP IOCTL - * - * @dev_type: hardware type for the cap info(icp, ipe, bps, cdm(ipe/bps)) - * @reserved: reserved field - * @hw_ver: major, minor and incr values of a device version - */ -struct cam_icp_dev_ver { - uint32_t dev_type; - uint32_t reserved; - struct cam_hw_version hw_ver; -}; - -/** - * struct cam_icp_ver - ICP version info - * - * This strcuture is used for fw and api version - * this is used to get firmware version and api version from firmware - * and use this info in CAM_QUERY_CAP IOCTL - * - * @major: FW version major - * @minor: FW version minor - * @revision: FW version increment - */ -struct cam_icp_ver { - uint32_t major; - uint32_t minor; - uint32_t revision; - uint32_t reserved; -}; - -/** - * struct cam_icp_query_cap_cmd - ICP query device capability payload - * - * @dev_iommu_handle: icp iommu handles for secure/non secure modes - * @cdm_iommu_handle: iommu handles for secure/non secure modes - * @fw_version: firmware version info - * @api_version: api version info - * @num_ipe: number of ipes - * @num_bps: number of bps - * @dev_ver: returned device capability array - */ -struct cam_icp_query_cap_cmd { - struct cam_iommu_handle dev_iommu_handle; - struct cam_iommu_handle cdm_iommu_handle; - struct cam_icp_ver fw_version; - struct cam_icp_ver api_version; - uint32_t num_ipe; - uint32_t num_bps; - struct cam_icp_dev_ver dev_ver[CAM_ICP_DEV_TYPE_MAX]; -}; - -/** - * struct cam_icp_res_info - ICP output resource info - * - * @format: format of the resource - * @width: width in pixels - * @height: height in lines - * @fps: fps - */ -struct cam_icp_res_info { - uint32_t format; - uint32_t width; - uint32_t height; - uint32_t fps; -}; - -/** - * struct cam_icp_acquire_dev_info - An ICP device info - * - * @scratch_mem_size: Output param - size of scratch memory - * @dev_type: device type (IPE_RT/IPE_NON_RT/BPS) - * @io_config_cmd_size: size of IO config command - * @io_config_cmd_handle: IO config command for each acquire - * @secure_mode: camera mode (secure/non secure) - * @chain_info: chaining info of FW device handles - * @in_res: resource info used for clock and bandwidth calculation - * @num_out_res: number of output resources - * @out_res: output resource - */ -struct cam_icp_acquire_dev_info { - uint32_t scratch_mem_size; - uint32_t dev_type; - uint32_t io_config_cmd_size; - int32_t io_config_cmd_handle; - uint32_t secure_mode; - int32_t chain_info; - struct cam_icp_res_info in_res; - uint32_t num_out_res; - struct cam_icp_res_info out_res[1]; -} __attribute__((__packed__)); - -#endif /* __UAPI_CAM_ICP_H__ */ diff --git a/third_party/linux/include/media/cam_isp.h b/third_party/linux/include/media/cam_isp.h deleted file mode 100644 index 266840d..0000000 --- a/third_party/linux/include/media/cam_isp.h +++ /dev/null @@ -1,379 +0,0 @@ -#ifndef __UAPI_CAM_ISP_H__ -#define __UAPI_CAM_ISP_H__ - -#include "cam_defs.h" -#include "cam_isp_vfe.h" -#include "cam_isp_ife.h" - - -/* ISP driver name */ -#define CAM_ISP_DEV_NAME "cam-isp" - -/* HW type */ -#define CAM_ISP_HW_BASE 0 -#define CAM_ISP_HW_CSID 1 -#define CAM_ISP_HW_VFE 2 -#define CAM_ISP_HW_IFE 3 -#define CAM_ISP_HW_ISPIF 4 -#define CAM_ISP_HW_MAX 5 - -/* Color Pattern */ -#define CAM_ISP_PATTERN_BAYER_RGRGRG 0 -#define CAM_ISP_PATTERN_BAYER_GRGRGR 1 -#define CAM_ISP_PATTERN_BAYER_BGBGBG 2 -#define CAM_ISP_PATTERN_BAYER_GBGBGB 3 -#define CAM_ISP_PATTERN_YUV_YCBYCR 4 -#define CAM_ISP_PATTERN_YUV_YCRYCB 5 -#define CAM_ISP_PATTERN_YUV_CBYCRY 6 -#define CAM_ISP_PATTERN_YUV_CRYCBY 7 -#define CAM_ISP_PATTERN_MAX 8 - -/* Usage Type */ -#define CAM_ISP_RES_USAGE_SINGLE 0 -#define CAM_ISP_RES_USAGE_DUAL 1 -#define CAM_ISP_RES_USAGE_MAX 2 - -/* Resource ID */ -#define CAM_ISP_RES_ID_PORT 0 -#define CAM_ISP_RES_ID_CLK 1 -#define CAM_ISP_RES_ID_MAX 2 - -/* Resource Type - Type of resource for the resource id - * defined in cam_isp_vfe.h, cam_isp_ife.h - */ - -/* Lane Type in input resource for Port */ -#define CAM_ISP_LANE_TYPE_DPHY 0 -#define CAM_ISP_LANE_TYPE_CPHY 1 -#define CAM_ISP_LANE_TYPE_MAX 2 - -/* ISP Resurce Composite Group ID */ -#define CAM_ISP_RES_COMP_GROUP_NONE 0 -#define CAM_ISP_RES_COMP_GROUP_ID_0 1 -#define CAM_ISP_RES_COMP_GROUP_ID_1 2 -#define CAM_ISP_RES_COMP_GROUP_ID_2 3 -#define CAM_ISP_RES_COMP_GROUP_ID_3 4 -#define CAM_ISP_RES_COMP_GROUP_ID_4 5 -#define CAM_ISP_RES_COMP_GROUP_ID_5 6 -#define CAM_ISP_RES_COMP_GROUP_ID_MAX 6 - -/* ISP packet opcode for ISP */ -#define CAM_ISP_PACKET_OP_BASE 0 -#define CAM_ISP_PACKET_INIT_DEV 1 -#define CAM_ISP_PACKET_UPDATE_DEV 2 -#define CAM_ISP_PACKET_OP_MAX 3 - -/* ISP packet meta_data type for command buffer */ -#define CAM_ISP_PACKET_META_BASE 0 -#define CAM_ISP_PACKET_META_LEFT 1 -#define CAM_ISP_PACKET_META_RIGHT 2 -#define CAM_ISP_PACKET_META_COMMON 3 -#define CAM_ISP_PACKET_META_DMI_LEFT 4 -#define CAM_ISP_PACKET_META_DMI_RIGHT 5 -#define CAM_ISP_PACKET_META_DMI_COMMON 6 -#define CAM_ISP_PACKET_META_CLOCK 7 -#define CAM_ISP_PACKET_META_CSID 8 -#define CAM_ISP_PACKET_META_DUAL_CONFIG 9 -#define CAM_ISP_PACKET_META_GENERIC_BLOB_LEFT 10 -#define CAM_ISP_PACKET_META_GENERIC_BLOB_RIGHT 11 -#define CAM_ISP_PACKET_META_GENERIC_BLOB_COMMON 12 - -/* DSP mode */ -#define CAM_ISP_DSP_MODE_NONE 0 -#define CAM_ISP_DSP_MODE_ONE_WAY 1 -#define CAM_ISP_DSP_MODE_ROUND 2 - -/* ISP Generic Cmd Buffer Blob types */ -#define CAM_ISP_GENERIC_BLOB_TYPE_HFR_CONFIG 0 -#define CAM_ISP_GENERIC_BLOB_TYPE_CLOCK_CONFIG 1 -#define CAM_ISP_GENERIC_BLOB_TYPE_BW_CONFIG 2 - -/* Query devices */ -/** - * struct cam_isp_dev_cap_info - A cap info for particular hw type - * - * @hw_type: Hardware type for the cap info - * @reserved: reserved field for alignment - * @hw_version: Hardware version - * - */ -struct cam_isp_dev_cap_info { - uint32_t hw_type; - uint32_t reserved; - struct cam_hw_version hw_version; -}; - -/** - * struct cam_isp_query_cap_cmd - ISP query device capability payload - * - * @device_iommu: returned iommu handles for device - * @cdm_iommu: returned iommu handles for cdm - * @num_dev: returned number of device capabilities - * @reserved: reserved field for alignment - * @dev_caps: returned device capability array - * - */ -struct cam_isp_query_cap_cmd { - struct cam_iommu_handle device_iommu; - struct cam_iommu_handle cdm_iommu; - int32_t num_dev; - uint32_t reserved; - struct cam_isp_dev_cap_info dev_caps[CAM_ISP_HW_MAX]; -}; - -/* Acquire Device */ -/** - * struct cam_isp_out_port_info - An output port resource info - * - * @res_type: output resource type defined in file - * cam_isp_vfe.h or cam_isp_ife.h - * @format: output format of the resource - * @wdith: output width in pixels - * @height: output height in lines - * @comp_grp_id: composite group id for the resource. - * @split_point: split point in pixels for the dual VFE. - * @secure_mode: flag to tell if output should be run in secure - * mode or not. See cam_defs.h for definition - * @reserved: reserved field for alignment - * - */ -struct cam_isp_out_port_info { - uint32_t res_type; - uint32_t format; - uint32_t width; - uint32_t height; - uint32_t comp_grp_id; - uint32_t split_point; - uint32_t secure_mode; - uint32_t reserved; -}; - -/** - * struct cam_isp_in_port_info - An input port resource info - * - * @res_type: input resource type define in file - * cam_isp_vfe.h or cam_isp_ife.h - * @lane_type: lane type: c-phy or d-phy. - * @lane_num: active lane number - * @lane_cfg: lane configurations: 4 bits per lane - * @vc: input virtual channel number - * @dt: input data type number - * @format: input format - * @test_pattern: test pattern for the testgen - * @usage_type: whether dual vfe is required - * @left_start: left input start offset in pixels - * @left_stop: left input stop offset in pixels - * @left_width: left input width in pixels - * @right_start: right input start offset in pixels. - * Only for Dual VFE - * @right_stop: right input stop offset in pixels. - * Only for Dual VFE - * @right_width: right input width in pixels. - * Only for dual VFE - * @line_start: top of the line number - * @line_stop: bottome of the line number - * @height: input height in lines - * @pixel_clk; sensor output clock - * @batch_size: batch size for HFR mode - * @dsp_mode: DSP stream mode (Defines as CAM_ISP_DSP_MODE_*) - * @hbi_cnt: HBI count for the camif input - * @reserved: Reserved field for alignment - * @num_out_res: number of the output resource associated - * @data: payload that contains the output resources - * - */ -struct cam_isp_in_port_info { - uint32_t res_type; - uint32_t lane_type; - uint32_t lane_num; - uint32_t lane_cfg; - uint32_t vc; - uint32_t dt; - uint32_t format; - uint32_t test_pattern; - uint32_t usage_type; - uint32_t left_start; - uint32_t left_stop; - uint32_t left_width; - uint32_t right_start; - uint32_t right_stop; - uint32_t right_width; - uint32_t line_start; - uint32_t line_stop; - uint32_t height; - uint32_t pixel_clk; - uint32_t batch_size; - uint32_t dsp_mode; - uint32_t hbi_cnt; - uint32_t custom_csid; - uint32_t reserved; - uint32_t num_out_res; - struct cam_isp_out_port_info data[1]; -}; - -/** - * struct cam_isp_resource - A resource bundle - * - * @resoruce_id: resource id for the resource bundle - * @length: length of the while resource blob - * @handle_type: type of the resource handle - * @reserved: reserved field for alignment - * @res_hdl: resource handle that points to the - * resource array; - * - */ -struct cam_isp_resource { - uint32_t resource_id; - uint32_t length; - uint32_t handle_type; - uint32_t reserved; - uint64_t res_hdl; -}; - -/** - * struct cam_isp_port_hfr_config - HFR configuration for this port - * - * @resource_type: Resource type - * @subsample_pattern: Subsample pattern. Used in HFR mode. It - * should be consistent with batchSize and - * CAMIF programming. - * @subsample_period: Subsample period. Used in HFR mode. It - * should be consistent with batchSize and - * CAMIF programming. - * @framedrop_pattern: Framedrop pattern - * @framedrop_period: Framedrop period - * @reserved: Reserved for alignment - */ -struct cam_isp_port_hfr_config { - uint32_t resource_type; - uint32_t subsample_pattern; - uint32_t subsample_period; - uint32_t framedrop_pattern; - uint32_t framedrop_period; - uint32_t reserved; -} __attribute__((packed)); - -/** - * struct cam_isp_resource_hfr_config - Resource HFR configuration - * - * @num_ports: Number of ports - * @reserved: Reserved for alignment - * @port_hfr_config: HFR configuration for each IO port - */ -struct cam_isp_resource_hfr_config { - uint32_t num_ports; - uint32_t reserved; - struct cam_isp_port_hfr_config port_hfr_config[1]; -} __attribute__((packed)); - -/** - * struct cam_isp_dual_split_params - dual isp spilt parameters - * - * @split_point: Split point information x, where (0 < x < width) - * left ISP's input ends at x + righ padding and - * Right ISP's input starts at x - left padding - * @right_padding: Padding added past the split point for left - * ISP's input - * @left_padding: Padding added before split point for right - * ISP's input - * @reserved: Reserved filed for alignment - * - */ -struct cam_isp_dual_split_params { - uint32_t split_point; - uint32_t right_padding; - uint32_t left_padding; - uint32_t reserved; -}; - -/** - * struct cam_isp_dual_stripe_config - stripe config per bus client - * - * @offset: Start horizontal offset relative to - * output buffer - * In UBWC mode, this value indicates the H_INIT - * value in pixel - * @width: Width of the stripe in bytes - * @tileconfig Ubwc meta tile config. Contain the partial - * tile info - * @port_id: port id of ISP output - * - */ -struct cam_isp_dual_stripe_config { - uint32_t offset; - uint32_t width; - uint32_t tileconfig; - uint32_t port_id; -}; - -/** - * struct cam_isp_dual_config - dual isp configuration - * - * @num_ports Number of isp output ports - * @reserved Reserved field for alignment - * @split_params: Inpput split parameters - * @stripes: Stripe information - * - */ -struct cam_isp_dual_config { - uint32_t num_ports; - uint32_t reserved; - struct cam_isp_dual_split_params split_params; - struct cam_isp_dual_stripe_config stripes[1]; -} __attribute__((packed)); - -/** - * struct cam_isp_clock_config - Clock configuration - * - * @usage_type: Usage type (Single/Dual) - * @num_rdi: Number of RDI votes - * @left_pix_hz: Pixel Clock for Left ISP - * @right_pix_hz: Pixel Clock for Right ISP, valid only if Dual - * @rdi_hz: RDI Clock. ISP clock will be max of RDI and - * PIX clocks. For a particular context which ISP - * HW the RDI is allocated to is not known to UMD. - * Hence pass the clock and let KMD decide. - */ -struct cam_isp_clock_config { - uint32_t usage_type; - uint32_t num_rdi; - uint64_t left_pix_hz; - uint64_t right_pix_hz; - uint64_t rdi_hz[1]; -} __attribute__((packed)); - -/** - * struct cam_isp_bw_vote - Bandwidth vote information - * - * @resource_id: Resource ID - * @reserved: Reserved field for alignment - * @cam_bw_bps: Bandwidth vote for CAMNOC - * @ext_bw_bps: Bandwidth vote for path-to-DDR after CAMNOC - */ - -struct cam_isp_bw_vote { - uint32_t resource_id; - uint32_t reserved; - uint64_t cam_bw_bps; - uint64_t ext_bw_bps; -} __attribute__((packed)); - -/** - * struct cam_isp_bw_config - Bandwidth configuration - * - * @usage_type: Usage type (Single/Dual) - * @num_rdi: Number of RDI votes - * @left_pix_vote: Bandwidth vote for left ISP - * @right_pix_vote: Bandwidth vote for right ISP - * @rdi_vote: RDI bandwidth requirements - */ - -struct cam_isp_bw_config { - uint32_t usage_type; - uint32_t num_rdi; - struct cam_isp_bw_vote left_pix_vote; - struct cam_isp_bw_vote right_pix_vote; - struct cam_isp_bw_vote rdi_vote[1]; -} __attribute__((packed)); - -#endif /* __UAPI_CAM_ISP_H__ */ diff --git a/third_party/linux/include/media/cam_isp_ife.h b/third_party/linux/include/media/cam_isp_ife.h deleted file mode 100644 index f5e7281..0000000 --- a/third_party/linux/include/media/cam_isp_ife.h +++ /dev/null @@ -1,39 +0,0 @@ -#ifndef __UAPI_CAM_ISP_IFE_H__ -#define __UAPI_CAM_ISP_IFE_H__ - -/* IFE output port resource type (global unique)*/ -#define CAM_ISP_IFE_OUT_RES_BASE 0x3000 - -#define CAM_ISP_IFE_OUT_RES_FULL (CAM_ISP_IFE_OUT_RES_BASE + 0) -#define CAM_ISP_IFE_OUT_RES_DS4 (CAM_ISP_IFE_OUT_RES_BASE + 1) -#define CAM_ISP_IFE_OUT_RES_DS16 (CAM_ISP_IFE_OUT_RES_BASE + 2) -#define CAM_ISP_IFE_OUT_RES_RAW_DUMP (CAM_ISP_IFE_OUT_RES_BASE + 3) -#define CAM_ISP_IFE_OUT_RES_FD (CAM_ISP_IFE_OUT_RES_BASE + 4) -#define CAM_ISP_IFE_OUT_RES_PDAF (CAM_ISP_IFE_OUT_RES_BASE + 5) -#define CAM_ISP_IFE_OUT_RES_RDI_0 (CAM_ISP_IFE_OUT_RES_BASE + 6) -#define CAM_ISP_IFE_OUT_RES_RDI_1 (CAM_ISP_IFE_OUT_RES_BASE + 7) -#define CAM_ISP_IFE_OUT_RES_RDI_2 (CAM_ISP_IFE_OUT_RES_BASE + 8) -#define CAM_ISP_IFE_OUT_RES_RDI_3 (CAM_ISP_IFE_OUT_RES_BASE + 9) -#define CAM_ISP_IFE_OUT_RES_STATS_HDR_BE (CAM_ISP_IFE_OUT_RES_BASE + 10) -#define CAM_ISP_IFE_OUT_RES_STATS_HDR_BHIST (CAM_ISP_IFE_OUT_RES_BASE + 11) -#define CAM_ISP_IFE_OUT_RES_STATS_TL_BG (CAM_ISP_IFE_OUT_RES_BASE + 12) -#define CAM_ISP_IFE_OUT_RES_STATS_BF (CAM_ISP_IFE_OUT_RES_BASE + 13) -#define CAM_ISP_IFE_OUT_RES_STATS_AWB_BG (CAM_ISP_IFE_OUT_RES_BASE + 14) -#define CAM_ISP_IFE_OUT_RES_STATS_BHIST (CAM_ISP_IFE_OUT_RES_BASE + 15) -#define CAM_ISP_IFE_OUT_RES_STATS_RS (CAM_ISP_IFE_OUT_RES_BASE + 16) -#define CAM_ISP_IFE_OUT_RES_STATS_CS (CAM_ISP_IFE_OUT_RES_BASE + 17) -#define CAM_ISP_IFE_OUT_RES_STATS_IHIST (CAM_ISP_IFE_OUT_RES_BASE + 18) -#define CAM_ISP_IFE_OUT_RES_MAX (CAM_ISP_IFE_OUT_RES_BASE + 19) - - -/* IFE input port resource type (global unique) */ -#define CAM_ISP_IFE_IN_RES_BASE 0x4000 - -#define CAM_ISP_IFE_IN_RES_TPG (CAM_ISP_IFE_IN_RES_BASE + 0) -#define CAM_ISP_IFE_IN_RES_PHY_0 (CAM_ISP_IFE_IN_RES_BASE + 1) -#define CAM_ISP_IFE_IN_RES_PHY_1 (CAM_ISP_IFE_IN_RES_BASE + 2) -#define CAM_ISP_IFE_IN_RES_PHY_2 (CAM_ISP_IFE_IN_RES_BASE + 3) -#define CAM_ISP_IFE_IN_RES_PHY_3 (CAM_ISP_IFE_IN_RES_BASE + 4) -#define CAM_ISP_IFE_IN_RES_MAX (CAM_ISP_IFE_IN_RES_BASE + 5) - -#endif /* __UAPI_CAM_ISP_IFE_H__ */ diff --git a/third_party/linux/include/media/cam_isp_vfe.h b/third_party/linux/include/media/cam_isp_vfe.h deleted file mode 100644 index e48db2f..0000000 --- a/third_party/linux/include/media/cam_isp_vfe.h +++ /dev/null @@ -1,44 +0,0 @@ -#ifndef __UAPI_CAM_ISP_VFE_H__ -#define __UAPI_CAM_ISP_VFE_H__ - -/* VFE output port resource type (global unique) */ -#define CAM_ISP_VFE_OUT_RES_BASE 0x1000 - -#define CAM_ISP_VFE_OUT_RES_ENC (CAM_ISP_VFE_OUT_RES_BASE + 0) -#define CAM_ISP_VFE_OUT_RES_VIEW (CAM_ISP_VFE_OUT_RES_BASE + 1) -#define CAM_ISP_VFE_OUT_RES_VID (CAM_ISP_VFE_OUT_RES_BASE + 2) -#define CAM_ISP_VFE_OUT_RES_RDI_0 (CAM_ISP_VFE_OUT_RES_BASE + 3) -#define CAM_ISP_VFE_OUT_RES_RDI_1 (CAM_ISP_VFE_OUT_RES_BASE + 4) -#define CAM_ISP_VFE_OUT_RES_RDI_2 (CAM_ISP_VFE_OUT_RES_BASE + 5) -#define CAM_ISP_VFE_OUT_RES_RDI_3 (CAM_ISP_VFE_OUT_RES_BASE + 6) -#define CAM_ISP_VFE_OUT_RES_STATS_AEC (CAM_ISP_VFE_OUT_RES_BASE + 7) -#define CAM_ISP_VFE_OUT_RES_STATS_AF (CAM_ISP_VFE_OUT_RES_BASE + 8) -#define CAM_ISP_VFE_OUT_RES_STATS_AWB (CAM_ISP_VFE_OUT_RES_BASE + 9) -#define CAM_ISP_VFE_OUT_RES_STATS_RS (CAM_ISP_VFE_OUT_RES_BASE + 10) -#define CAM_ISP_VFE_OUT_RES_STATS_CS (CAM_ISP_VFE_OUT_RES_BASE + 11) -#define CAM_ISP_VFE_OUT_RES_STATS_IHIST (CAM_ISP_VFE_OUT_RES_BASE + 12) -#define CAM_ISP_VFE_OUT_RES_STATS_SKIN (CAM_ISP_VFE_OUT_RES_BASE + 13) -#define CAM_ISP_VFE_OUT_RES_STATS_BG (CAM_ISP_VFE_OUT_RES_BASE + 14) -#define CAM_ISP_VFE_OUT_RES_STATS_BF (CAM_ISP_VFE_OUT_RES_BASE + 15) -#define CAM_ISP_VFE_OUT_RES_STATS_BE (CAM_ISP_VFE_OUT_RES_BASE + 16) -#define CAM_ISP_VFE_OUT_RES_STATS_BHIST (CAM_ISP_VFE_OUT_RES_BASE + 17) -#define CAM_ISP_VFE_OUT_RES_STATS_BF_SCALE (CAM_ISP_VFE_OUT_RES_BASE + 18) -#define CAM_ISP_VFE_OUT_RES_STATS_HDR_BE (CAM_ISP_VFE_OUT_RES_BASE + 19) -#define CAM_ISP_VFE_OUT_RES_STATS_HDR_BHIST (CAM_ISP_VFE_OUT_RES_BASE + 20) -#define CAM_ISP_VFE_OUT_RES_STATS_AEC_BG (CAM_ISP_VFE_OUT_RES_BASE + 21) -#define CAM_ISP_VFE_OUT_RES_CAMIF_RAW (CAM_ISP_VFE_OUT_RES_BASE + 22) -#define CAM_ISP_VFE_OUT_RES_IDEAL_RAW (CAM_ISP_VFE_OUT_RES_BASE + 23) -#define CAM_ISP_VFE_OUT_RES_MAX (CAM_ISP_VFE_OUT_RES_BASE + 24) - -/* VFE input port_ resource type (global unique) */ -#define CAM_ISP_VFE_IN_RES_BASE 0x2000 - -#define CAM_ISP_VFE_IN_RES_TPG (CAM_ISP_VFE_IN_RES_BASE + 0) -#define CAM_ISP_VFE_IN_RES_PHY_0 (CAM_ISP_VFE_IN_RES_BASE + 1) -#define CAM_ISP_VFE_IN_RES_PHY_1 (CAM_ISP_VFE_IN_RES_BASE + 2) -#define CAM_ISP_VFE_IN_RES_PHY_2 (CAM_ISP_VFE_IN_RES_BASE + 3) -#define CAM_ISP_VFE_IN_RES_PHY_3 (CAM_ISP_VFE_IN_RES_BASE + 4) -#define CAM_ISP_VFE_IN_RES_FE (CAM_ISP_VFE_IN_RES_BASE + 5) -#define CAM_ISP_VFE_IN_RES_MAX (CAM_ISP_VFE_IN_RES_BASE + 6) - -#endif /* __UAPI_CAM_ISP_VFE_H__ */ diff --git a/third_party/linux/include/media/cam_jpeg.h b/third_party/linux/include/media/cam_jpeg.h deleted file mode 100644 index f3082f3..0000000 --- a/third_party/linux/include/media/cam_jpeg.h +++ /dev/null @@ -1,117 +0,0 @@ -#ifndef __UAPI_CAM_JPEG_H__ -#define __UAPI_CAM_JPEG_H__ - -#include "cam_defs.h" - -/* enc, dma, cdm(enc/dma) are used in querycap */ -#define CAM_JPEG_DEV_TYPE_ENC 0 -#define CAM_JPEG_DEV_TYPE_DMA 1 -#define CAM_JPEG_DEV_TYPE_MAX 2 - -#define CAM_JPEG_NUM_DEV_PER_RES_MAX 1 - -/* definitions needed for jpeg aquire device */ -#define CAM_JPEG_RES_TYPE_ENC 0 -#define CAM_JPEG_RES_TYPE_DMA 1 -#define CAM_JPEG_RES_TYPE_MAX 2 - -/* packet opcode types */ -#define CAM_JPEG_OPCODE_ENC_UPDATE 0 -#define CAM_JPEG_OPCODE_DMA_UPDATE 1 - -/* ENC input port resource type */ -#define CAM_JPEG_ENC_INPUT_IMAGE 0x0 - -/* ENC output port resource type */ -#define CAM_JPEG_ENC_OUTPUT_IMAGE 0x1 - -#define CAM_JPEG_ENC_IO_IMAGES_MAX 0x2 - -/* DMA input port resource type */ -#define CAM_JPEG_DMA_INPUT_IMAGE 0x0 - -/* DMA output port resource type */ -#define CAM_JPEG_DMA_OUTPUT_IMAGE 0x1 - -#define CAM_JPEG_DMA_IO_IMAGES_MAX 0x2 - -#define CAM_JPEG_IMAGE_MAX 0x2 - -/** - * struct cam_jpeg_dev_ver - Device information for particular hw type - * - * This is used to get device version info of JPEG ENC, JPEG DMA - * from hardware and use this info in CAM_QUERY_CAP IOCTL - * - * @size : Size of struct passed - * @dev_type: Hardware type for the cap info(jpeg enc, jpeg dma) - * @hw_ver: Major, minor and incr values of a device version - */ -struct cam_jpeg_dev_ver { - uint32_t size; - uint32_t dev_type; - struct cam_hw_version hw_ver; -}; - -/** - * struct cam_jpeg_query_cap_cmd - JPEG query device capability payload - * - * @dev_iommu_handle: Jpeg iommu handles for secure/non secure - * modes - * @cdm_iommu_handle: Iommu handles for secure/non secure modes - * @num_enc: Number of encoder - * @num_dma: Number of dma - * @dev_ver: Returned device capability array - */ -struct cam_jpeg_query_cap_cmd { - struct cam_iommu_handle dev_iommu_handle; - struct cam_iommu_handle cdm_iommu_handle; - uint32_t num_enc; - uint32_t num_dma; - struct cam_jpeg_dev_ver dev_ver[CAM_JPEG_DEV_TYPE_MAX]; -}; - -/** - * struct cam_jpeg_res_info - JPEG output resource info - * - * @format: Format of the resource - * @width: Width in pixels - * @height: Height in lines - * @fps: Fps - */ -struct cam_jpeg_res_info { - uint32_t format; - uint32_t width; - uint32_t height; - uint32_t fps; -}; - -/** - * struct cam_jpeg_acquire_dev_info - An JPEG device info - * - * @dev_type: Device type (ENC/DMA) - * @reserved: Reserved Bytes - * @in_res: In resource info - * @in_res: Iut resource info - */ -struct cam_jpeg_acquire_dev_info { - uint32_t dev_type; - uint32_t reserved; - struct cam_jpeg_res_info in_res; - struct cam_jpeg_res_info out_res; -}; - -/** - * struct cam_jpeg_config_inout_param_info - JPEG Config time - * input output params - * - * @clk_index: Input Param- clock selection index.(-1 default) - * @output_size: Output Param - jpeg encode/dma output size in - * bytes - */ -struct cam_jpeg_config_inout_param_info { - int32_t clk_index; - int32_t output_size; -}; - -#endif /* __UAPI_CAM_JPEG_H__ */ diff --git a/third_party/linux/include/media/cam_lrme.h b/third_party/linux/include/media/cam_lrme.h deleted file mode 100644 index 97d9578..0000000 --- a/third_party/linux/include/media/cam_lrme.h +++ /dev/null @@ -1,65 +0,0 @@ -#ifndef __UAPI_CAM_LRME_H__ -#define __UAPI_CAM_LRME_H__ - -#include "cam_defs.h" - -/* LRME Resource Types */ - -enum CAM_LRME_IO_TYPE { - CAM_LRME_IO_TYPE_TAR, - CAM_LRME_IO_TYPE_REF, - CAM_LRME_IO_TYPE_RES, - CAM_LRME_IO_TYPE_DS2, -}; - -#define CAM_LRME_INPUT_PORT_TYPE_TAR (1 << 0) -#define CAM_LRME_INPUT_PORT_TYPE_REF (1 << 1) - -#define CAM_LRME_OUTPUT_PORT_TYPE_DS2 (1 << 0) -#define CAM_LRME_OUTPUT_PORT_TYPE_RES (1 << 1) - -#define CAM_LRME_DEV_MAX 1 - - -struct cam_lrme_hw_version { - uint32_t gen; - uint32_t rev; - uint32_t step; -}; - -struct cam_lrme_dev_cap { - struct cam_lrme_hw_version clc_hw_version; - struct cam_lrme_hw_version bus_rd_hw_version; - struct cam_lrme_hw_version bus_wr_hw_version; - struct cam_lrme_hw_version top_hw_version; - struct cam_lrme_hw_version top_titan_version; -}; - -/** - * struct cam_lrme_query_cap_cmd - LRME query device capability payload - * - * @dev_iommu_handle: LRME iommu handles for secure/non secure - * modes - * @cdm_iommu_handle: Iommu handles for secure/non secure modes - * @num_devices: number of hardware devices - * @dev_caps: Returned device capability array - */ -struct cam_lrme_query_cap_cmd { - struct cam_iommu_handle device_iommu; - struct cam_iommu_handle cdm_iommu; - uint32_t num_devices; - struct cam_lrme_dev_cap dev_caps[CAM_LRME_DEV_MAX]; -}; - -struct cam_lrme_soc_info { - uint64_t clock_rate; - uint64_t bandwidth; - uint64_t reserved[4]; -}; - -struct cam_lrme_acquire_args { - struct cam_lrme_soc_info lrme_soc_info; -}; - -#endif /* __UAPI_CAM_LRME_H__ */ - diff --git a/third_party/linux/include/media/cam_req_mgr.h b/third_party/linux/include/media/cam_req_mgr.h deleted file mode 100644 index ae65649..0000000 --- a/third_party/linux/include/media/cam_req_mgr.h +++ /dev/null @@ -1,436 +0,0 @@ -#ifndef __UAPI_LINUX_CAM_REQ_MGR_H -#define __UAPI_LINUX_CAM_REQ_MGR_H - -#include -#include -#include -#include -#include - -#define CAM_REQ_MGR_VNODE_NAME "cam-req-mgr-devnode" - -#define CAM_DEVICE_TYPE_BASE (MEDIA_ENT_F_OLD_BASE) -#define CAM_VNODE_DEVICE_TYPE (CAM_DEVICE_TYPE_BASE) -#define CAM_SENSOR_DEVICE_TYPE (CAM_DEVICE_TYPE_BASE + 1) -#define CAM_IFE_DEVICE_TYPE (CAM_DEVICE_TYPE_BASE + 2) -#define CAM_ICP_DEVICE_TYPE (CAM_DEVICE_TYPE_BASE + 3) -#define CAM_LRME_DEVICE_TYPE (CAM_DEVICE_TYPE_BASE + 4) -#define CAM_JPEG_DEVICE_TYPE (CAM_DEVICE_TYPE_BASE + 5) -#define CAM_FD_DEVICE_TYPE (CAM_DEVICE_TYPE_BASE + 6) -#define CAM_CPAS_DEVICE_TYPE (CAM_DEVICE_TYPE_BASE + 7) -#define CAM_CSIPHY_DEVICE_TYPE (CAM_DEVICE_TYPE_BASE + 8) -#define CAM_ACTUATOR_DEVICE_TYPE (CAM_DEVICE_TYPE_BASE + 9) -#define CAM_CCI_DEVICE_TYPE (CAM_DEVICE_TYPE_BASE + 10) -#define CAM_FLASH_DEVICE_TYPE (CAM_DEVICE_TYPE_BASE + 11) -#define CAM_EEPROM_DEVICE_TYPE (CAM_DEVICE_TYPE_BASE + 12) -#define CAM_OIS_DEVICE_TYPE (CAM_DEVICE_TYPE_BASE + 13) - -/* cam_req_mgr hdl info */ -#define CAM_REQ_MGR_HDL_IDX_POS 8 -#define CAM_REQ_MGR_HDL_IDX_MASK ((1 << CAM_REQ_MGR_HDL_IDX_POS) - 1) -#define CAM_REQ_MGR_GET_HDL_IDX(hdl) (hdl & CAM_REQ_MGR_HDL_IDX_MASK) - -/** - * Max handles supported by cam_req_mgr - * It includes both session and device handles - */ -#define CAM_REQ_MGR_MAX_HANDLES 64 -#define MAX_LINKS_PER_SESSION 2 - -/* V4L event type which user space will subscribe to */ -#define V4L_EVENT_CAM_REQ_MGR_EVENT (V4L2_EVENT_PRIVATE_START + 0) - -/* Specific event ids to get notified in user space */ -#define V4L_EVENT_CAM_REQ_MGR_SOF 0 -#define V4L_EVENT_CAM_REQ_MGR_ERROR 1 -#define V4L_EVENT_CAM_REQ_MGR_SOF_BOOT_TS 2 - -/* SOF Event status */ -#define CAM_REQ_MGR_SOF_EVENT_SUCCESS 0 -#define CAM_REQ_MGR_SOF_EVENT_ERROR 1 - -/* Link control operations */ -#define CAM_REQ_MGR_LINK_ACTIVATE 0 -#define CAM_REQ_MGR_LINK_DEACTIVATE 1 - -/** - * Request Manager : flush_type - * @CAM_REQ_MGR_FLUSH_TYPE_ALL: Req mgr will remove all the pending - * requests from input/processing queue. - * @CAM_REQ_MGR_FLUSH_TYPE_CANCEL_REQ: Req mgr will remove only particular - * request id from input/processing queue. - * @CAM_REQ_MGR_FLUSH_TYPE_MAX: Max number of the flush type - * @opcode: CAM_REQ_MGR_FLUSH_REQ - */ -#define CAM_REQ_MGR_FLUSH_TYPE_ALL 0 -#define CAM_REQ_MGR_FLUSH_TYPE_CANCEL_REQ 1 -#define CAM_REQ_MGR_FLUSH_TYPE_MAX 2 - -/** - * Request Manager : Sync Mode type - * @CAM_REQ_MGR_SYNC_MODE_NO_SYNC: Req mgr will apply non-sync mode for this - * request. - * @CAM_REQ_MGR_SYNC_MODE_SYNC: Req mgr will apply sync mode for this request. - */ -#define CAM_REQ_MGR_SYNC_MODE_NO_SYNC 0 -#define CAM_REQ_MGR_SYNC_MODE_SYNC 1 - -/** - * struct cam_req_mgr_event_data - * @session_hdl: session handle - * @link_hdl: link handle - * @frame_id: frame id - * @reserved: reserved for 64 bit aligngment - * @req_id: request id - * @tv_sec: timestamp in seconds - * @tv_usec: timestamp in micro seconds - */ -struct cam_req_mgr_event_data { - int32_t session_hdl; - int32_t link_hdl; - int32_t frame_id; - int32_t reserved; - int64_t req_id; - uint64_t tv_sec; - uint64_t tv_usec; -}; - -/** - * struct cam_req_mgr_session_info - * @session_hdl: In/Output param - session_handle - * @opcode1: CAM_REQ_MGR_CREATE_SESSION - * @opcode2: CAM_REQ_MGR_DESTROY_SESSION - */ -struct cam_req_mgr_session_info { - int32_t session_hdl; - int32_t reserved; -}; - -/** - * struct cam_req_mgr_link_info - * @session_hdl: Input param - Identifier for CSL session - * @num_devices: Input Param - Num of devices to be linked - * @dev_hdls: Input param - List of device handles to be linked - * @link_hdl: Output Param -Identifier for link - * @opcode: CAM_REQ_MGR_LINK - */ -struct cam_req_mgr_link_info { - int32_t session_hdl; - uint32_t num_devices; - int32_t dev_hdls[CAM_REQ_MGR_MAX_HANDLES]; - int32_t link_hdl; -}; - -/** - * struct cam_req_mgr_unlink_info - * @session_hdl: input param - session handle - * @link_hdl: input param - link handle - * @opcode: CAM_REQ_MGR_UNLINK - */ -struct cam_req_mgr_unlink_info { - int32_t session_hdl; - int32_t link_hdl; -}; - -/** - * struct cam_req_mgr_flush_info - * @brief: User can tell drivers to flush a particular request id or - * flush all requests from its pending processing queue. Flush is a - * blocking call and driver shall ensure all requests are flushed - * before returning. - * @session_hdl: Input param - Identifier for CSL session - * @link_hdl: Input Param -Identifier for link - * @flush_type: User can cancel a particular req id or can flush - * all requests in queue - * @reserved: reserved for 64 bit aligngment - * @req_id: field is valid only if flush type is cancel request - * for flush all this field value is not considered. - * @opcode: CAM_REQ_MGR_FLUSH_REQ - */ -struct cam_req_mgr_flush_info { - int32_t session_hdl; - int32_t link_hdl; - uint32_t flush_type; - uint32_t reserved; - int64_t req_id; -}; - -/** struct cam_req_mgr_sched_info - * @session_hdl: Input param - Identifier for CSL session - * @link_hdl: Input Param -Identifier for link - * inluding itself. - * @bubble_enable: Input Param - Cam req mgr will do bubble recovery if this - * flag is set. - * @sync_mode: Type of Sync mode for this request - * @req_id: Input Param - Request Id from which all requests will be flushed - */ -struct cam_req_mgr_sched_request { - int32_t session_hdl; - int32_t link_hdl; - int32_t bubble_enable; - int32_t sync_mode; - int64_t req_id; -}; - -/** - * struct cam_req_mgr_sync_mode - * @session_hdl: Input param - Identifier for CSL session - * @sync_mode: Input Param - Type of sync mode - * @num_links: Input Param - Num of links in sync mode (Valid only - * when sync_mode is one of SYNC enabled modes) - * @link_hdls: Input Param - Array of link handles to be in sync mode - * (Valid only when sync_mode is one of SYNC - * enabled modes) - * @master_link_hdl: Input Param - To dictate which link's SOF drives system - * (Valid only when sync_mode is one of SYNC - * enabled modes) - * - * @opcode: CAM_REQ_MGR_SYNC_MODE - */ -struct cam_req_mgr_sync_mode { - int32_t session_hdl; - int32_t sync_mode; - int32_t num_links; - int32_t link_hdls[MAX_LINKS_PER_SESSION]; - int32_t master_link_hdl; - int32_t reserved; -}; - -/** - * struct cam_req_mgr_link_control - * @ops: Link operations: activate/deactive - * @session_hdl: Input param - Identifier for CSL session - * @num_links: Input Param - Num of links - * @reserved: reserved field - * @link_hdls: Input Param - Links to be activated/deactivated - * - * @opcode: CAM_REQ_MGR_LINK_CONTROL - */ -struct cam_req_mgr_link_control { - int32_t ops; - int32_t session_hdl; - int32_t num_links; - int32_t reserved; - int32_t link_hdls[MAX_LINKS_PER_SESSION]; -}; - -/** - * cam_req_mgr specific opcode ids - */ -#define CAM_REQ_MGR_CREATE_DEV_NODES (CAM_COMMON_OPCODE_MAX + 1) -#define CAM_REQ_MGR_CREATE_SESSION (CAM_COMMON_OPCODE_MAX + 2) -#define CAM_REQ_MGR_DESTROY_SESSION (CAM_COMMON_OPCODE_MAX + 3) -#define CAM_REQ_MGR_LINK (CAM_COMMON_OPCODE_MAX + 4) -#define CAM_REQ_MGR_UNLINK (CAM_COMMON_OPCODE_MAX + 5) -#define CAM_REQ_MGR_SCHED_REQ (CAM_COMMON_OPCODE_MAX + 6) -#define CAM_REQ_MGR_FLUSH_REQ (CAM_COMMON_OPCODE_MAX + 7) -#define CAM_REQ_MGR_SYNC_MODE (CAM_COMMON_OPCODE_MAX + 8) -#define CAM_REQ_MGR_ALLOC_BUF (CAM_COMMON_OPCODE_MAX + 9) -#define CAM_REQ_MGR_MAP_BUF (CAM_COMMON_OPCODE_MAX + 10) -#define CAM_REQ_MGR_RELEASE_BUF (CAM_COMMON_OPCODE_MAX + 11) -#define CAM_REQ_MGR_CACHE_OPS (CAM_COMMON_OPCODE_MAX + 12) -#define CAM_REQ_MGR_LINK_CONTROL (CAM_COMMON_OPCODE_MAX + 13) -/* end of cam_req_mgr opcodes */ - -#define CAM_MEM_FLAG_HW_READ_WRITE (1<<0) -#define CAM_MEM_FLAG_HW_READ_ONLY (1<<1) -#define CAM_MEM_FLAG_HW_WRITE_ONLY (1<<2) -#define CAM_MEM_FLAG_KMD_ACCESS (1<<3) -#define CAM_MEM_FLAG_UMD_ACCESS (1<<4) -#define CAM_MEM_FLAG_PROTECTED_MODE (1<<5) -#define CAM_MEM_FLAG_CMD_BUF_TYPE (1<<6) -#define CAM_MEM_FLAG_PIXEL_BUF_TYPE (1<<7) -#define CAM_MEM_FLAG_STATS_BUF_TYPE (1<<8) -#define CAM_MEM_FLAG_PACKET_BUF_TYPE (1<<9) -#define CAM_MEM_FLAG_CACHE (1<<10) -#define CAM_MEM_FLAG_HW_SHARED_ACCESS (1<<11) - -#define CAM_MEM_MMU_MAX_HANDLE 16 - -/* Maximum allowed buffers in existence */ -#define CAM_MEM_BUFQ_MAX 1024 - -#define CAM_MEM_MGR_SECURE_BIT_POS 15 -#define CAM_MEM_MGR_HDL_IDX_SIZE 15 -#define CAM_MEM_MGR_HDL_FD_SIZE 16 -#define CAM_MEM_MGR_HDL_IDX_END_POS 16 -#define CAM_MEM_MGR_HDL_FD_END_POS 32 - -#define CAM_MEM_MGR_HDL_IDX_MASK ((1 << CAM_MEM_MGR_HDL_IDX_SIZE) - 1) - -#define GET_MEM_HANDLE(idx, fd) \ - ((idx & CAM_MEM_MGR_HDL_IDX_MASK) | \ - (fd << (CAM_MEM_MGR_HDL_FD_END_POS - CAM_MEM_MGR_HDL_FD_SIZE))) \ - -#define GET_FD_FROM_HANDLE(hdl) \ - (hdl >> (CAM_MEM_MGR_HDL_FD_END_POS - CAM_MEM_MGR_HDL_FD_SIZE)) \ - -#define CAM_MEM_MGR_GET_HDL_IDX(hdl) (hdl & CAM_MEM_MGR_HDL_IDX_MASK) - -#define CAM_MEM_MGR_SET_SECURE_HDL(hdl, flag) \ - ((flag) ? (hdl |= (1 << CAM_MEM_MGR_SECURE_BIT_POS)) : \ - ((hdl) &= ~(1 << CAM_MEM_MGR_SECURE_BIT_POS))) - -#define CAM_MEM_MGR_IS_SECURE_HDL(hdl) \ - (((hdl) & \ - (1<> CAM_MEM_MGR_SECURE_BIT_POS) - -/** - * memory allocation type - */ -#define CAM_MEM_DMA_NONE 0 -#define CAM_MEM_DMA_BIDIRECTIONAL 1 -#define CAM_MEM_DMA_TO_DEVICE 2 -#define CAM_MEM_DMA_FROM_DEVICE 3 - - -/** - * memory cache operation - */ -#define CAM_MEM_CLEAN_CACHE 1 -#define CAM_MEM_INV_CACHE 2 -#define CAM_MEM_CLEAN_INV_CACHE 3 - - -/** - * struct cam_mem_alloc_out_params - * @buf_handle: buffer handle - * @fd: output buffer file descriptor - * @vaddr: virtual address pointer - */ -struct cam_mem_alloc_out_params { - uint32_t buf_handle; - int32_t fd; - uint64_t vaddr; -}; - -/** - * struct cam_mem_map_out_params - * @buf_handle: buffer handle - * @reserved: reserved for future - * @vaddr: virtual address pointer - */ -struct cam_mem_map_out_params { - uint32_t buf_handle; - uint32_t reserved; - uint64_t vaddr; -}; - -/** - * struct cam_mem_mgr_alloc_cmd - * @len: size of buffer to allocate - * @align: alignment of the buffer - * @mmu_hdls: array of mmu handles - * @num_hdl: number of handles - * @flags: flags of the buffer - * @out: out params - */ -/* CAM_REQ_MGR_ALLOC_BUF */ -struct cam_mem_mgr_alloc_cmd { - uint64_t len; - uint64_t align; - int32_t mmu_hdls[CAM_MEM_MMU_MAX_HANDLE]; - uint32_t num_hdl; - uint32_t flags; - struct cam_mem_alloc_out_params out; -}; - -/** - * struct cam_mem_mgr_map_cmd - * @mmu_hdls: array of mmu handles - * @num_hdl: number of handles - * @flags: flags of the buffer - * @fd: output buffer file descriptor - * @reserved: reserved field - * @out: out params - */ - -/* CAM_REQ_MGR_MAP_BUF */ -struct cam_mem_mgr_map_cmd { - int32_t mmu_hdls[CAM_MEM_MMU_MAX_HANDLE]; - uint32_t num_hdl; - uint32_t flags; - int32_t fd; - uint32_t reserved; - struct cam_mem_map_out_params out; -}; - -/** - * struct cam_mem_mgr_map_cmd - * @buf_handle: buffer handle - * @reserved: reserved field - */ -/* CAM_REQ_MGR_RELEASE_BUF */ -struct cam_mem_mgr_release_cmd { - int32_t buf_handle; - uint32_t reserved; -}; - -/** - * struct cam_mem_mgr_map_cmd - * @buf_handle: buffer handle - * @ops: cache operations - */ -/* CAM_REQ_MGR_CACHE_OPS */ -struct cam_mem_cache_ops_cmd { - int32_t buf_handle; - uint32_t mem_cache_ops; -}; - -/** - * Request Manager : error message type - * @CAM_REQ_MGR_ERROR_TYPE_DEVICE: Device error message, fatal to session - * @CAM_REQ_MGR_ERROR_TYPE_REQUEST: Error on a single request, not fatal - * @CAM_REQ_MGR_ERROR_TYPE_BUFFER: Buffer was not filled, not fatal - */ -#define CAM_REQ_MGR_ERROR_TYPE_DEVICE 0 -#define CAM_REQ_MGR_ERROR_TYPE_REQUEST 1 -#define CAM_REQ_MGR_ERROR_TYPE_BUFFER 2 - -/** - * struct cam_req_mgr_error_msg - * @error_type: type of error - * @request_id: request id of frame - * @device_hdl: device handle - * @linke_hdl: link_hdl - * @resource_size: size of the resource - */ -struct cam_req_mgr_error_msg { - uint32_t error_type; - uint32_t request_id; - int32_t device_hdl; - int32_t link_hdl; - uint64_t resource_size; -}; - -/** - * struct cam_req_mgr_frame_msg - * @request_id: request id of the frame - * @frame_id: frame id of the frame - * @timestamp: timestamp of the frame - * @link_hdl: link handle associated with this message - * @sof_status: sof status success or fail - */ -struct cam_req_mgr_frame_msg { - uint64_t request_id; - uint64_t frame_id; - uint64_t timestamp; - int32_t link_hdl; - uint32_t sof_status; -}; - -/** - * struct cam_req_mgr_message - * @session_hdl: session to which the frame belongs to - * @reserved: reserved field - * @u: union which can either be error or frame message - */ -struct cam_req_mgr_message { - int32_t session_hdl; - int32_t reserved; - union { - struct cam_req_mgr_error_msg err_msg; - struct cam_req_mgr_frame_msg frame_msg; - } u; -}; -#endif /* __UAPI_LINUX_CAM_REQ_MGR_H */ diff --git a/third_party/linux/include/media/cam_sensor.h b/third_party/linux/include/media/cam_sensor.h deleted file mode 100644 index f5af604..0000000 --- a/third_party/linux/include/media/cam_sensor.h +++ /dev/null @@ -1,477 +0,0 @@ -#ifndef __UAPI_CAM_SENSOR_H__ -#define __UAPI_CAM_SENSOR_H__ - -#include -#include -#include - -#define CAM_SENSOR_PROBE_CMD (CAM_COMMON_OPCODE_MAX + 1) -#define CAM_FLASH_MAX_LED_TRIGGERS 3 -#define MAX_OIS_NAME_SIZE 32 -#define CAM_CSIPHY_SECURE_MODE_ENABLED 1 -/** - * struct cam_sensor_query_cap - capabilities info for sensor - * - * @slot_info : Indicates about the slotId or cell Index - * @secure_camera : Camera is in secure/Non-secure mode - * @pos_pitch : Sensor position pitch - * @pos_roll : Sensor position roll - * @pos_yaw : Sensor position yaw - * @actuator_slot_id : Actuator slot id which connected to sensor - * @eeprom_slot_id : EEPROM slot id which connected to sensor - * @ois_slot_id : OIS slot id which connected to sensor - * @flash_slot_id : Flash slot id which connected to sensor - * @csiphy_slot_id : CSIphy slot id which connected to sensor - * - */ -struct cam_sensor_query_cap { - uint32_t slot_info; - uint32_t secure_camera; - uint32_t pos_pitch; - uint32_t pos_roll; - uint32_t pos_yaw; - uint32_t actuator_slot_id; - uint32_t eeprom_slot_id; - uint32_t ois_slot_id; - uint32_t flash_slot_id; - uint32_t csiphy_slot_id; -} __attribute__((packed)); - -/** - * struct cam_csiphy_query_cap - capabilities info for csiphy - * - * @slot_info : Indicates about the slotId or cell Index - * @version : CSIphy version - * @clk lane : Of the 5 lanes, informs lane configured - * as clock lane - * @reserved - */ -struct cam_csiphy_query_cap { - uint32_t slot_info; - uint32_t version; - uint32_t clk_lane; - uint32_t reserved; -} __attribute__((packed)); - -/** - * struct cam_actuator_query_cap - capabilities info for actuator - * - * @slot_info : Indicates about the slotId or cell Index - * @reserved - */ -struct cam_actuator_query_cap { - uint32_t slot_info; - uint32_t reserved; -} __attribute__((packed)); - -/** - * struct cam_eeprom_query_cap_t - capabilities info for eeprom - * - * @slot_info : Indicates about the slotId or cell Index - * @eeprom_kernel_probe : Indicates about the kernel or userspace probe - */ -struct cam_eeprom_query_cap_t { - uint32_t slot_info; - uint16_t eeprom_kernel_probe; - uint16_t reserved; -} __attribute__((packed)); - -/** - * struct cam_ois_query_cap_t - capabilities info for ois - * - * @slot_info : Indicates about the slotId or cell Index - */ -struct cam_ois_query_cap_t { - uint32_t slot_info; - uint16_t reserved; -} __attribute__((packed)); - -/** - * struct cam_cmd_i2c_info - Contains slave I2C related info - * - * @slave_addr : Slave address - * @i2c_freq_mode : 4 bits are used for I2c freq mode - * @cmd_type : Explains type of command - */ -struct cam_cmd_i2c_info { - uint16_t slave_addr; - uint8_t i2c_freq_mode; - uint8_t cmd_type; -} __attribute__((packed)); - -/** - * struct cam_ois_opcode - Contains OIS opcode - * - * @prog : OIS FW prog register address - * @coeff : OIS FW coeff register address - * @pheripheral : OIS pheripheral - * @memory : OIS memory - */ -struct cam_ois_opcode { - uint32_t prog; - uint32_t coeff; - uint32_t pheripheral; - uint32_t memory; -} __attribute__((packed)); - -/** - * struct cam_cmd_ois_info - Contains OIS slave info - * - * @slave_addr : OIS i2c slave address - * @i2c_freq_mode : i2c frequency mode - * @cmd_type : Explains type of command - * @ois_fw_flag : indicates if fw is present or not - * @is_ois_calib : indicates the calibration data is available - * @ois_name : OIS name - * @opcode : opcode - */ -struct cam_cmd_ois_info { - uint16_t slave_addr; - uint8_t i2c_freq_mode; - uint8_t cmd_type; - uint8_t ois_fw_flag; - uint8_t is_ois_calib; - char ois_name[MAX_OIS_NAME_SIZE]; - struct cam_ois_opcode opcode; -} __attribute__((packed)); - -/** - * struct cam_cmd_probe - Contains sensor slave info - * - * @data_type : Slave register data type - * @addr_type : Slave register address type - * @op_code : Don't Care - * @cmd_type : Explains type of command - * @reg_addr : Slave register address - * @expected_data : Data expected at slave register address - * @data_mask : Data mask if only few bits are valid - * @camera_id : Indicates the slot to which camera - * needs to be probed - * @reserved - */ -struct cam_cmd_probe { - uint8_t data_type; - uint8_t addr_type; - uint8_t op_code; - uint8_t cmd_type; - uint32_t reg_addr; - uint32_t expected_data; - uint32_t data_mask; - uint16_t camera_id; - uint16_t reserved; -} __attribute__((packed)); - -/** - * struct cam_power_settings - Contains sensor power setting info - * - * @power_seq_type : Type of power sequence - * @reserved - * @config_val_low : Lower 32 bit value configuration value - * @config_val_high : Higher 32 bit value configuration value - * - */ -struct cam_power_settings { - uint16_t power_seq_type; - uint16_t reserved; - uint32_t config_val_low; - uint32_t config_val_high; -} __attribute__((packed)); - -/** - * struct cam_cmd_power - Explains about the power settings - * - * @count : Number of power settings follows - * @reserved - * @cmd_type : Explains type of command - * @power_settings : Contains power setting info - */ -struct cam_cmd_power { - uint16_t count; - uint8_t reserved; - uint8_t cmd_type; - struct cam_power_settings power_settings[1]; -} __attribute__((packed)); - -/** - * struct i2c_rdwr_header - header of READ/WRITE I2C command - * - * @ count : Number of registers / data / reg-data pairs - * @ op_code : Operation code - * @ cmd_type : Command buffer type - * @ data_type : I2C data type - * @ addr_type : I2C address type - * @ reserved - */ -struct i2c_rdwr_header { - uint16_t count; - uint8_t op_code; - uint8_t cmd_type; - uint8_t data_type; - uint8_t addr_type; - uint16_t reserved; -} __attribute__((packed)); - -/** - * struct i2c_random_wr_payload - payload for I2C random write - * - * @ reg_addr : Register address - * @ reg_data : Register data - * - */ -struct i2c_random_wr_payload { - uint32_t reg_addr; - uint32_t reg_data; -} __attribute__((packed)); - -/** - * struct cam_cmd_i2c_random_wr - I2C random write command - * @ header : header of READ/WRITE I2C command - * @ random_wr_payload : payload for I2C random write - */ -struct cam_cmd_i2c_random_wr { - struct i2c_rdwr_header header; - struct i2c_random_wr_payload random_wr_payload[1]; -} __attribute__((packed)); - -/** - * struct cam_cmd_read - I2C read command - * @ reg_data : Register data - * @ reserved - */ -struct cam_cmd_read { - uint32_t reg_data; - uint32_t reserved; -} __attribute__((packed)); - -/** - * struct cam_cmd_i2c_continuous_wr - I2C continuous write command - * @ header : header of READ/WRITE I2C command - * @ reg_addr : Register address - * @ data_read : I2C read command - */ -struct cam_cmd_i2c_continuous_wr { - struct i2c_rdwr_header header; - uint32_t reg_addr; - struct cam_cmd_read data_read[1]; -} __attribute__((packed)); - -/** - * struct cam_cmd_i2c_random_rd - I2C random read command - * @ header : header of READ/WRITE I2C command - * @ data_read : I2C read command - */ -struct cam_cmd_i2c_random_rd { - struct i2c_rdwr_header header; - struct cam_cmd_read data_read[1]; -} __attribute__((packed)); - -/** - * struct cam_cmd_i2c_continuous_rd - I2C continuous continuous read command - * @ header : header of READ/WRITE I2C command - * @ reg_addr : Register address - * - */ -struct cam_cmd_i2c_continuous_rd { - struct i2c_rdwr_header header; - uint32_t reg_addr; -} __attribute__((packed)); - -/** - * struct cam_cmd_conditional_wait - Conditional wait command - * @data_type : Data type - * @addr_type : Address type - * @op_code : Opcode - * @cmd_type : Explains type of command - * @timeout : Timeout for retries - * @reserved - * @reg_addr : Register Address - * @reg_data : Register data - * @data_mask : Data mask if only few bits are valid - * @camera_id : Indicates the slot to which camera - * needs to be probed - * - */ -struct cam_cmd_conditional_wait { - uint8_t data_type; - uint8_t addr_type; - uint8_t op_code; - uint8_t cmd_type; - uint16_t timeout; - uint16_t reserved; - uint32_t reg_addr; - uint32_t reg_data; - uint32_t data_mask; -} __attribute__((packed)); - -/** - * struct cam_cmd_unconditional_wait - Un-conditional wait command - * @delay : Delay - * @op_code : Opcode - * @cmd_type : Explains type of command - */ -struct cam_cmd_unconditional_wait { - int16_t delay; - uint8_t op_code; - uint8_t cmd_type; -} __attribute__((packed)); - -/** - * cam_csiphy_info: Provides cmdbuffer structre - * @lane_mask : Lane mask details - * @lane_assign : Lane sensor will be using - * @csiphy_3phase : Total number of lanes - * @combo_mode : Info regarding combo_mode is enable / disable - * @lane_cnt : Total number of lanes - * @secure_mode : Secure mode flag to enable / disable - * @3phase : Details whether 3Phase / 2Phase operation - * @settle_time : Settling time in ms - * @data_rate : Data rate - * - */ -struct cam_csiphy_info { - uint16_t lane_mask; - uint16_t lane_assign; - uint8_t csiphy_3phase; - uint8_t combo_mode; - uint8_t lane_cnt; - uint8_t secure_mode; - uint64_t settle_time; - uint64_t data_rate; -} __attribute__((packed)); - -/** - * cam_csiphy_acquire_dev_info : Information needed for - * csiphy at the time of acquire - * @combo_mode : Indicates the device mode of operation - * @reserved - * - */ -struct cam_csiphy_acquire_dev_info { - uint32_t combo_mode; - uint32_t reserved; -} __attribute__((packed)); - -/** - * cam_sensor_acquire_dev : Updates sensor acuire cmd - * @device_handle : Updates device handle - * @session_handle : Session handle for acquiring device - * @handle_type : Resource handle type - * @reserved - * @info_handle : Handle to additional info - * needed for sensor sub modules - * - */ -struct cam_sensor_acquire_dev { - uint32_t session_handle; - uint32_t device_handle; - uint32_t handle_type; - uint32_t reserved; - uint64_t info_handle; -} __attribute__((packed)); - -/** - * cam_sensor_streamon_dev : StreamOn command for the sensor - * @session_handle : Session handle for acquiring device - * @device_handle : Updates device handle - * @handle_type : Resource handle type - * @reserved - * @info_handle : Information Needed at the time of streamOn - * - */ -struct cam_sensor_streamon_dev { - uint32_t session_handle; - uint32_t device_handle; - uint32_t handle_type; - uint32_t reserved; - uint64_t info_handle; -} __attribute__((packed)); - -/** - * struct cam_flash_init : Init command for the flash - * @flash_type : flash hw type - * @reserved - * @cmd_type : command buffer type - */ -struct cam_flash_init { - uint8_t flash_type; - uint16_t reserved; - uint8_t cmd_type; -} __attribute__((packed)); - -/** - * struct cam_flash_set_rer : RedEyeReduction command buffer - * - * @count : Number of flash leds - * @opcode : Command buffer opcode - * CAM_FLASH_FIRE_RER - * @cmd_type : command buffer operation type - * @num_iteration : Number of led turn on/off sequence - * @reserved - * @led_on_delay_ms : flash led turn on time in ms - * @led_off_delay_ms : flash led turn off time in ms - * @led_current_ma : flash led current in ma - * - */ -struct cam_flash_set_rer { - uint16_t count; - uint8_t opcode; - uint8_t cmd_type; - uint16_t num_iteration; - uint16_t reserved; - uint32_t led_on_delay_ms; - uint32_t led_off_delay_ms; - uint32_t led_current_ma[CAM_FLASH_MAX_LED_TRIGGERS]; -} __attribute__((packed)); - -/** - * struct cam_flash_set_on_off : led turn on/off command buffer - * - * @count : Number of Flash leds - * @opcode : command buffer opcodes - * CAM_FLASH_FIRE_LOW - * CAM_FLASH_FIRE_HIGH - * CAM_FLASH_OFF - * @cmd_type : command buffer operation type - * @led_current_ma : flash led current in ma - * - */ -struct cam_flash_set_on_off { - uint16_t count; - uint8_t opcode; - uint8_t cmd_type; - uint32_t led_current_ma[CAM_FLASH_MAX_LED_TRIGGERS]; -} __attribute__((packed)); - -/** - * struct cam_flash_query_curr : query current command buffer - * - * @reserved - * @opcode : command buffer opcode - * @cmd_type : command buffer operation type - * @query_current_ma : battery current in ma - * - */ -struct cam_flash_query_curr { - uint16_t reserved; - uint8_t opcode; - uint8_t cmd_type; - uint32_t query_current_ma; -} __attribute__ ((packed)); - -/** - * struct cam_flash_query_cap : capabilities info for flash - * - * @slot_info : Indicates about the slotId or cell Index - * @max_current_flash : max supported current for flash - * @max_duration_flash : max flash turn on duration - * @max_current_torch : max supported current for torch - * - */ -struct cam_flash_query_cap_info { - uint32_t slot_info; - uint32_t max_current_flash[CAM_FLASH_MAX_LED_TRIGGERS]; - uint32_t max_duration_flash[CAM_FLASH_MAX_LED_TRIGGERS]; - uint32_t max_current_torch[CAM_FLASH_MAX_LED_TRIGGERS]; -} __attribute__ ((packed)); - -#endif diff --git a/third_party/linux/include/media/cam_sensor_cmn_header.h b/third_party/linux/include/media/cam_sensor_cmn_header.h deleted file mode 100644 index 24617b3..0000000 --- a/third_party/linux/include/media/cam_sensor_cmn_header.h +++ /dev/null @@ -1,391 +0,0 @@ -/* Copyright (c) 2017-2018, The Linux Foundation. All rights reserved. - * - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License version 2 and - * only version 2 as published by the Free Software Foundation. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - */ - -#ifndef _CAM_SENSOR_CMN_HEADER_ -#define _CAM_SENSOR_CMN_HEADER_ - -#include -#include -#include - -#define MAX_REGULATOR 5 -#define MAX_POWER_CONFIG 12 - -#define MAX_PER_FRAME_ARRAY 32 -#define BATCH_SIZE_MAX 16 - -#define CAM_SENSOR_NAME "cam-sensor" -#define CAM_ACTUATOR_NAME "cam-actuator" -#define CAM_CSIPHY_NAME "cam-csiphy" -#define CAM_FLASH_NAME "cam-flash" -#define CAM_EEPROM_NAME "cam-eeprom" -#define CAM_OIS_NAME "cam-ois" - -#define MAX_SYSTEM_PIPELINE_DELAY 2 - -#define CAM_PKT_NOP_OPCODE 127 - -enum camera_sensor_cmd_type { - CAMERA_SENSOR_CMD_TYPE_INVALID, - CAMERA_SENSOR_CMD_TYPE_PROBE, - CAMERA_SENSOR_CMD_TYPE_PWR_UP, - CAMERA_SENSOR_CMD_TYPE_PWR_DOWN, - CAMERA_SENSOR_CMD_TYPE_I2C_INFO, - CAMERA_SENSOR_CMD_TYPE_I2C_RNDM_WR, - CAMERA_SENSOR_CMD_TYPE_I2C_RNDM_RD, - CAMERA_SENSOR_CMD_TYPE_I2C_CONT_WR, - CAMERA_SENSOR_CMD_TYPE_I2C_CONT_RD, - CAMERA_SENSOR_CMD_TYPE_WAIT, - CAMERA_SENSOR_FLASH_CMD_TYPE_INIT_INFO, - CAMERA_SENSOR_FLASH_CMD_TYPE_FIRE, - CAMERA_SENSOR_FLASH_CMD_TYPE_RER, - CAMERA_SENSOR_FLASH_CMD_TYPE_QUERYCURR, - CAMERA_SENSOR_FLASH_CMD_TYPE_WIDGET, - CAMERA_SENSOR_CMD_TYPE_RD_DATA, - CAMERA_SENSOR_FLASH_CMD_TYPE_INIT_FIRE, - CAMERA_SENSOR_CMD_TYPE_MAX, -}; - -enum camera_sensor_i2c_op_code { - CAMERA_SENSOR_I2C_OP_INVALID, - CAMERA_SENSOR_I2C_OP_RNDM_WR, - CAMERA_SENSOR_I2C_OP_RNDM_WR_VERF, - CAMERA_SENSOR_I2C_OP_CONT_WR_BRST, - CAMERA_SENSOR_I2C_OP_CONT_WR_BRST_VERF, - CAMERA_SENSOR_I2C_OP_CONT_WR_SEQN, - CAMERA_SENSOR_I2C_OP_CONT_WR_SEQN_VERF, - CAMERA_SENSOR_I2C_OP_MAX, -}; - -enum camera_sensor_wait_op_code { - CAMERA_SENSOR_WAIT_OP_INVALID, - CAMERA_SENSOR_WAIT_OP_COND, - CAMERA_SENSOR_WAIT_OP_HW_UCND, - CAMERA_SENSOR_WAIT_OP_SW_UCND, - CAMERA_SENSOR_WAIT_OP_MAX, -}; - -enum camera_flash_opcode { - CAMERA_SENSOR_FLASH_OP_INVALID, - CAMERA_SENSOR_FLASH_OP_OFF, - CAMERA_SENSOR_FLASH_OP_FIRELOW, - CAMERA_SENSOR_FLASH_OP_FIREHIGH, - CAMERA_SENSOR_FLASH_OP_MAX, -}; - -enum camera_sensor_i2c_type { - CAMERA_SENSOR_I2C_TYPE_INVALID, - CAMERA_SENSOR_I2C_TYPE_BYTE, - CAMERA_SENSOR_I2C_TYPE_WORD, - CAMERA_SENSOR_I2C_TYPE_3B, - CAMERA_SENSOR_I2C_TYPE_DWORD, - CAMERA_SENSOR_I2C_TYPE_MAX, -}; - -enum i2c_freq_mode { - I2C_STANDARD_MODE, - I2C_FAST_MODE, - I2C_CUSTOM_MODE, - I2C_FAST_PLUS_MODE, - I2C_MAX_MODES, -}; - -enum position_roll { - ROLL_0 = 0, - ROLL_90 = 90, - ROLL_180 = 180, - ROLL_270 = 270, - ROLL_INVALID = 360, -}; - -enum position_yaw { - FRONT_CAMERA_YAW = 0, - REAR_CAMERA_YAW = 180, - INVALID_YAW = 360, -}; - -enum position_pitch { - LEVEL_PITCH = 0, - INVALID_PITCH = 360, -}; - -enum sensor_sub_module { - SUB_MODULE_SENSOR, - SUB_MODULE_ACTUATOR, - SUB_MODULE_EEPROM, - SUB_MODULE_LED_FLASH, - SUB_MODULE_CSID, - SUB_MODULE_CSIPHY, - SUB_MODULE_OIS, - SUB_MODULE_EXT, - SUB_MODULE_MAX, -}; - -enum msm_camera_power_seq_type { - SENSOR_MCLK, - SENSOR_VANA, - SENSOR_VDIG, - SENSOR_VIO, - SENSOR_VAF, - SENSOR_VAF_PWDM, - SENSOR_CUSTOM_REG1, - SENSOR_CUSTOM_REG2, - SENSOR_RESET, - SENSOR_STANDBY, - SENSOR_CUSTOM_GPIO1, - SENSOR_CUSTOM_GPIO2, - SENSOR_SEQ_TYPE_MAX, -}; - -enum cam_sensor_packet_opcodes { - CAM_SENSOR_PACKET_OPCODE_SENSOR_STREAMON, - CAM_SENSOR_PACKET_OPCODE_SENSOR_UPDATE, - CAM_SENSOR_PACKET_OPCODE_SENSOR_INITIAL_CONFIG, - CAM_SENSOR_PACKET_OPCODE_SENSOR_PROBE, - CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG, - CAM_SENSOR_PACKET_OPCODE_SENSOR_STREAMOFF, - CAM_SENSOR_PACKET_OPCODE_SENSOR_NOP = 127 -}; - -enum cam_actuator_packet_opcodes { - CAM_ACTUATOR_PACKET_OPCODE_INIT, - CAM_ACTUATOR_PACKET_AUTO_MOVE_LENS, - CAM_ACTUATOR_PACKET_MANUAL_MOVE_LENS -}; - -enum cam_eeprom_packet_opcodes { - CAM_EEPROM_PACKET_OPCODE_INIT -}; - -enum cam_ois_packet_opcodes { - CAM_OIS_PACKET_OPCODE_INIT, - CAM_OIS_PACKET_OPCODE_OIS_CONTROL -}; - -enum msm_bus_perf_setting { - S_INIT, - S_PREVIEW, - S_VIDEO, - S_CAPTURE, - S_ZSL, - S_STEREO_VIDEO, - S_STEREO_CAPTURE, - S_DEFAULT, - S_LIVESHOT, - S_DUAL, - S_EXIT -}; - -enum msm_camera_device_type_t { - MSM_CAMERA_I2C_DEVICE, - MSM_CAMERA_PLATFORM_DEVICE, - MSM_CAMERA_SPI_DEVICE, -}; - -enum cam_flash_device_type { - CAMERA_FLASH_DEVICE_TYPE_PMIC = 0, - CAMERA_FLASH_DEVICE_TYPE_I2C, - CAMERA_FLASH_DEVICE_TYPE_GPIO, -}; - -enum cci_i2c_master_t { - MASTER_0, - MASTER_1, - MASTER_MAX, -}; - -enum camera_vreg_type { - VREG_TYPE_DEFAULT, - VREG_TYPE_CUSTOM, -}; - -enum cam_sensor_i2c_cmd_type { - CAM_SENSOR_I2C_WRITE_RANDOM, - CAM_SENSOR_I2C_WRITE_BURST, - CAM_SENSOR_I2C_WRITE_SEQ, - CAM_SENSOR_I2C_READ, - CAM_SENSOR_I2C_POLL -}; - -struct common_header { - uint16_t first_word; - uint8_t third_byte; - uint8_t cmd_type; -}; - -struct camera_vreg_t { - const char *reg_name; - int min_voltage; - int max_voltage; - int op_mode; - uint32_t delay; - const char *custom_vreg_name; - enum camera_vreg_type type; -}; - -struct msm_camera_gpio_num_info { - uint16_t gpio_num[SENSOR_SEQ_TYPE_MAX]; - uint8_t valid[SENSOR_SEQ_TYPE_MAX]; -}; - -struct msm_cam_clk_info { - const char *clk_name; - long clk_rate; - uint32_t delay; -}; - -struct msm_pinctrl_info { - struct pinctrl *pinctrl; - struct pinctrl_state *gpio_state_active; - struct pinctrl_state *gpio_state_suspend; - bool use_pinctrl; -}; - -struct cam_sensor_i2c_reg_array { - uint32_t reg_addr; - uint32_t reg_data; - uint32_t delay; - uint32_t data_mask; -}; - -struct cam_sensor_i2c_reg_setting { - struct cam_sensor_i2c_reg_array *reg_setting; - unsigned short size; - enum camera_sensor_i2c_type addr_type; - enum camera_sensor_i2c_type data_type; - unsigned short delay; -}; - -/*struct i2c_settings_list { - struct cam_sensor_i2c_reg_setting i2c_settings; - enum cam_sensor_i2c_cmd_type op_code; - struct list_head list; -}; - -struct i2c_settings_array { - struct list_head list_head; - int32_t is_settings_valid; - int64_t request_id; -}; - -struct i2c_data_settings { - struct i2c_settings_array init_settings; - struct i2c_settings_array config_settings; - struct i2c_settings_array streamon_settings; - struct i2c_settings_array streamoff_settings; - struct i2c_settings_array *per_frame; -};*/ - -struct cam_sensor_power_ctrl_t { - struct device *dev; - struct cam_sensor_power_setting *power_setting; - uint16_t power_setting_size; - struct cam_sensor_power_setting *power_down_setting; - uint16_t power_down_setting_size; - struct msm_camera_gpio_num_info *gpio_num_info; - struct msm_pinctrl_info pinctrl_info; - uint8_t cam_pinctrl_status; -}; - -struct cam_camera_slave_info { - uint16_t sensor_slave_addr; - uint16_t sensor_id_reg_addr; - uint16_t sensor_id; - uint16_t sensor_id_mask; -}; - -struct msm_sensor_init_params { - int modes_supported; - unsigned int sensor_mount_angle; -}; - -enum msm_sensor_camera_id_t { - CAMERA_0, - CAMERA_1, - CAMERA_2, - CAMERA_3, - CAMERA_4, - CAMERA_5, - CAMERA_6, - MAX_CAMERAS, -}; - -struct msm_sensor_id_info_t { - unsigned short sensor_id_reg_addr; - unsigned short sensor_id; - unsigned short sensor_id_mask; -}; - -enum msm_sensor_output_format_t { - MSM_SENSOR_BAYER, - MSM_SENSOR_YCBCR, - MSM_SENSOR_META, -}; - -struct cam_sensor_power_setting { - enum msm_camera_power_seq_type seq_type; - unsigned short seq_val; - long config_val; - unsigned short delay; - void *data[10]; -}; - -struct cam_sensor_board_info { - struct cam_camera_slave_info slave_info; - int32_t sensor_mount_angle; - int32_t secure_mode; - int modes_supported; - int32_t pos_roll; - int32_t pos_yaw; - int32_t pos_pitch; - int32_t subdev_id[SUB_MODULE_MAX]; - int32_t subdev_intf[SUB_MODULE_MAX]; - const char *misc_regulator; - struct cam_sensor_power_ctrl_t power_info; -}; - -enum msm_camera_vreg_name_t { - CAM_VDIG, - CAM_VIO, - CAM_VANA, - CAM_VAF, - CAM_V_CUSTOM1, - CAM_V_CUSTOM2, - CAM_VREG_MAX, -}; - -struct msm_camera_gpio_conf { - void *cam_gpiomux_conf_tbl; - uint8_t cam_gpiomux_conf_tbl_size; - struct gpio *cam_gpio_common_tbl; - uint8_t cam_gpio_common_tbl_size; - struct gpio *cam_gpio_req_tbl; - uint8_t cam_gpio_req_tbl_size; - uint32_t gpio_no_mux; - uint32_t *camera_off_table; - uint8_t camera_off_table_size; - uint32_t *camera_on_table; - uint8_t camera_on_table_size; - struct msm_camera_gpio_num_info *gpio_num_info; -}; - -/*for tof camera Begin*/ -enum EEPROM_DATA_OP_T{ - EEPROM_DEFAULT_DATA = 0, - EEPROM_INIT_DATA, - EEPROM_CONFIG_DATA, - EEPROM_STREAMON_DATA, - EEPROM_STREAMOFF_DATA, - EEPROM_OTHER_DATA, -}; -/*for tof camera End*/ -#endif /* _CAM_SENSOR_CMN_HEADER_ */ diff --git a/third_party/linux/include/media/cam_sync.h b/third_party/linux/include/media/cam_sync.h deleted file mode 100644 index 4a8781f..0000000 --- a/third_party/linux/include/media/cam_sync.h +++ /dev/null @@ -1,134 +0,0 @@ -#ifndef __UAPI_CAM_SYNC_H__ -#define __UAPI_CAM_SYNC_H__ - -#include -#include -#include -#include - -#define CAM_SYNC_DEVICE_NAME "cam_sync_device" - -/* V4L event which user space will subscribe to */ -#define CAM_SYNC_V4L_EVENT (V4L2_EVENT_PRIVATE_START + 0) - -/* Specific event ids to get notified in user space */ -#define CAM_SYNC_V4L_EVENT_ID_CB_TRIG 0 - -/* Size of opaque payload sent to kernel for safekeeping until signal time */ -#define CAM_SYNC_USER_PAYLOAD_SIZE 2 - -/* Device type for sync device needed for device discovery */ -#define CAM_SYNC_DEVICE_TYPE (MEDIA_ENT_F_OLD_BASE) - -#define CAM_SYNC_GET_PAYLOAD_PTR(ev, type) \ - (type *)((char *)ev.u.data + sizeof(struct cam_sync_ev_header)) - -#define CAM_SYNC_GET_HEADER_PTR(ev) \ - ((struct cam_sync_ev_header *)ev.u.data) - -#define CAM_SYNC_STATE_INVALID 0 -#define CAM_SYNC_STATE_ACTIVE 1 -#define CAM_SYNC_STATE_SIGNALED_SUCCESS 2 -#define CAM_SYNC_STATE_SIGNALED_ERROR 3 - -/** - * struct cam_sync_ev_header - Event header for sync event notification - * - * @sync_obj: Sync object - * @status: Status of the object - */ -struct cam_sync_ev_header { - int32_t sync_obj; - int32_t status; -}; - -/** - * struct cam_sync_info - Sync object creation information - * - * @name: Optional string representation of the sync object - * @sync_obj: Sync object returned after creation in kernel - */ -struct cam_sync_info { - char name[64]; - int32_t sync_obj; -}; - -/** - * struct cam_sync_signal - Sync object signaling struct - * - * @sync_obj: Sync object to be signaled - * @sync_state: State of the sync object to which it should be signaled - */ -struct cam_sync_signal { - int32_t sync_obj; - uint32_t sync_state; -}; - -/** - * struct cam_sync_merge - Merge information for sync objects - * - * @sync_objs: Pointer to sync objects - * @num_objs: Number of objects in the array - * @merged: Merged sync object - */ -struct cam_sync_merge { - __u64 sync_objs; - uint32_t num_objs; - int32_t merged; -}; - -/** - * struct cam_sync_userpayload_info - Payload info from user space - * - * @sync_obj: Sync object for which payload has to be registered for - * @reserved: Reserved - * @payload: Pointer to user payload - */ -struct cam_sync_userpayload_info { - int32_t sync_obj; - uint32_t reserved; - __u64 payload[CAM_SYNC_USER_PAYLOAD_SIZE]; -}; - -/** - * struct cam_sync_wait - Sync object wait information - * - * @sync_obj: Sync object to wait on - * @reserved: Reserved - * @timeout_ms: Timeout in milliseconds - */ -struct cam_sync_wait { - int32_t sync_obj; - uint32_t reserved; - uint64_t timeout_ms; -}; - -/** - * struct cam_private_ioctl_arg - Sync driver ioctl argument - * - * @id: IOCTL command id - * @size: Size of command payload - * @result: Result of command execution - * @reserved: Reserved - * @ioctl_ptr: Pointer to user data - */ -struct cam_private_ioctl_arg { - __u32 id; - __u32 size; - __u32 result; - __u32 reserved; - __u64 ioctl_ptr; -}; - -#define CAM_PRIVATE_IOCTL_CMD \ - _IOWR('V', BASE_VIDIOC_PRIVATE, struct cam_private_ioctl_arg) - -#define CAM_SYNC_CREATE 0 -#define CAM_SYNC_DESTROY 1 -#define CAM_SYNC_SIGNAL 2 -#define CAM_SYNC_MERGE 3 -#define CAM_SYNC_REGISTER_PAYLOAD 4 -#define CAM_SYNC_DEREGISTER_PAYLOAD 5 -#define CAM_SYNC_WAIT 6 - -#endif /* __UAPI_CAM_SYNC_H__ */ diff --git a/third_party/linux/include/msm_cam_sensor.h b/third_party/linux/include/msm_cam_sensor.h deleted file mode 100644 index c75d1fd..0000000 --- a/third_party/linux/include/msm_cam_sensor.h +++ /dev/null @@ -1,829 +0,0 @@ -#ifndef __LINUX_MSM_CAM_SENSOR_H -#define __LINUX_MSM_CAM_SENSOR_H - -#ifdef MSM_CAMERA_BIONIC -#include -#endif - -//#include -#include "msm_camsensor_sdk.h" - -#include -#include -#ifdef CONFIG_COMPAT -#include -#endif - -#define I2C_SEQ_REG_SETTING_MAX 5 - -#define MSM_SENSOR_MCLK_8HZ 8000000 -#define MSM_SENSOR_MCLK_16HZ 16000000 -#define MSM_SENSOR_MCLK_24HZ 24000000 - -#define MAX_SENSOR_NAME 32 -#define MAX_ACTUATOR_AF_TOTAL_STEPS 1024 - -#define MAX_OIS_MOD_NAME_SIZE 32 -#define MAX_OIS_NAME_SIZE 32 -#define MAX_OIS_REG_SETTINGS 800 - -#define MOVE_NEAR 0 -#define MOVE_FAR 1 - -#define MSM_ACTUATOR_MOVE_SIGNED_FAR -1 -#define MSM_ACTUATOR_MOVE_SIGNED_NEAR 1 - -#define MAX_ACTUATOR_REGION 5 - -#define MAX_EEPROM_NAME 32 - -#define MAX_AF_ITERATIONS 3 -#define MAX_NUMBER_OF_STEPS 47 -#define MAX_REGULATOR 5 - -#define MSM_V4L2_PIX_FMT_META v4l2_fourcc('M', 'E', 'T', 'A') /* META */ -#define MSM_V4L2_PIX_FMT_SBGGR14 v4l2_fourcc('B', 'G', '1', '4') - /* 14 BGBG.. GRGR.. */ -#define MSM_V4L2_PIX_FMT_SGBRG14 v4l2_fourcc('G', 'B', '1', '4') - /* 14 GBGB.. RGRG.. */ -#define MSM_V4L2_PIX_FMT_SGRBG14 v4l2_fourcc('B', 'A', '1', '4') - /* 14 GRGR.. BGBG.. */ -#define MSM_V4L2_PIX_FMT_SRGGB14 v4l2_fourcc('R', 'G', '1', '4') - /* 14 RGRG.. GBGB.. */ - -enum flash_type { - LED_FLASH = 1, - STROBE_FLASH, - GPIO_FLASH -}; - -enum msm_sensor_resolution_t { - MSM_SENSOR_RES_FULL, - MSM_SENSOR_RES_QTR, - MSM_SENSOR_RES_2, - MSM_SENSOR_RES_3, - MSM_SENSOR_RES_4, - MSM_SENSOR_RES_5, - MSM_SENSOR_RES_6, - MSM_SENSOR_RES_7, - MSM_SENSOR_INVALID_RES, -}; - -enum msm_camera_stream_type_t { - MSM_CAMERA_STREAM_PREVIEW, - MSM_CAMERA_STREAM_SNAPSHOT, - MSM_CAMERA_STREAM_VIDEO, - MSM_CAMERA_STREAM_INVALID, -}; - -enum sensor_sub_module_t { - SUB_MODULE_SENSOR, - SUB_MODULE_CHROMATIX, - SUB_MODULE_ACTUATOR, - SUB_MODULE_EEPROM, - SUB_MODULE_LED_FLASH, - SUB_MODULE_STROBE_FLASH, - SUB_MODULE_CSID, - SUB_MODULE_CSID_3D, - SUB_MODULE_CSIPHY, - SUB_MODULE_CSIPHY_3D, - SUB_MODULE_OIS, - SUB_MODULE_EXT, - SUB_MODULE_MAX, -}; - -enum { - MSM_CAMERA_EFFECT_MODE_OFF, - MSM_CAMERA_EFFECT_MODE_MONO, - MSM_CAMERA_EFFECT_MODE_NEGATIVE, - MSM_CAMERA_EFFECT_MODE_SOLARIZE, - MSM_CAMERA_EFFECT_MODE_SEPIA, - MSM_CAMERA_EFFECT_MODE_POSTERIZE, - MSM_CAMERA_EFFECT_MODE_WHITEBOARD, - MSM_CAMERA_EFFECT_MODE_BLACKBOARD, - MSM_CAMERA_EFFECT_MODE_AQUA, - MSM_CAMERA_EFFECT_MODE_EMBOSS, - MSM_CAMERA_EFFECT_MODE_SKETCH, - MSM_CAMERA_EFFECT_MODE_NEON, - MSM_CAMERA_EFFECT_MODE_MAX -}; - -enum { - MSM_CAMERA_WB_MODE_AUTO, - MSM_CAMERA_WB_MODE_CUSTOM, - MSM_CAMERA_WB_MODE_INCANDESCENT, - MSM_CAMERA_WB_MODE_FLUORESCENT, - MSM_CAMERA_WB_MODE_WARM_FLUORESCENT, - MSM_CAMERA_WB_MODE_DAYLIGHT, - MSM_CAMERA_WB_MODE_CLOUDY_DAYLIGHT, - MSM_CAMERA_WB_MODE_TWILIGHT, - MSM_CAMERA_WB_MODE_SHADE, - MSM_CAMERA_WB_MODE_OFF, - MSM_CAMERA_WB_MODE_MAX -}; - -enum { - MSM_CAMERA_SCENE_MODE_OFF, - MSM_CAMERA_SCENE_MODE_AUTO, - MSM_CAMERA_SCENE_MODE_LANDSCAPE, - MSM_CAMERA_SCENE_MODE_SNOW, - MSM_CAMERA_SCENE_MODE_BEACH, - MSM_CAMERA_SCENE_MODE_SUNSET, - MSM_CAMERA_SCENE_MODE_NIGHT, - MSM_CAMERA_SCENE_MODE_PORTRAIT, - MSM_CAMERA_SCENE_MODE_BACKLIGHT, - MSM_CAMERA_SCENE_MODE_SPORTS, - MSM_CAMERA_SCENE_MODE_ANTISHAKE, - MSM_CAMERA_SCENE_MODE_FLOWERS, - MSM_CAMERA_SCENE_MODE_CANDLELIGHT, - MSM_CAMERA_SCENE_MODE_FIREWORKS, - MSM_CAMERA_SCENE_MODE_PARTY, - MSM_CAMERA_SCENE_MODE_NIGHT_PORTRAIT, - MSM_CAMERA_SCENE_MODE_THEATRE, - MSM_CAMERA_SCENE_MODE_ACTION, - MSM_CAMERA_SCENE_MODE_AR, - MSM_CAMERA_SCENE_MODE_FACE_PRIORITY, - MSM_CAMERA_SCENE_MODE_BARCODE, - MSM_CAMERA_SCENE_MODE_HDR, - MSM_CAMERA_SCENE_MODE_MAX -}; - -enum csid_cfg_type_t { - CSID_INIT, - CSID_CFG, - CSID_TESTMODE_CFG, - CSID_RELEASE, -}; - -enum csiphy_cfg_type_t { - CSIPHY_INIT, - CSIPHY_CFG, - CSIPHY_RELEASE, -}; - -enum camera_vreg_type { - VREG_TYPE_DEFAULT, - VREG_TYPE_CUSTOM, -}; - -enum sensor_af_t { - SENSOR_AF_FOCUSSED, - SENSOR_AF_NOT_FOCUSSED, -}; - -enum cci_i2c_master_t { - MASTER_0, - MASTER_1, - MASTER_MAX, -}; - -struct msm_camera_i2c_array_write_config { - struct msm_camera_i2c_reg_setting conf_array; - uint16_t slave_addr; -}; - -struct msm_camera_i2c_read_config { - uint16_t slave_addr; - uint16_t reg_addr; - enum msm_camera_i2c_reg_addr_type addr_type; - enum msm_camera_i2c_data_type data_type; - uint16_t data; -}; - -struct msm_camera_csi2_params { - struct msm_camera_csid_params csid_params; - struct msm_camera_csiphy_params csiphy_params; - uint8_t csi_clk_scale_enable; -}; - -struct msm_camera_csi_lane_params { - uint16_t csi_lane_assign; - uint16_t csi_lane_mask; -}; - -struct csi_lane_params_t { - uint16_t csi_lane_assign; - uint8_t csi_lane_mask; - uint8_t csi_if; - int8_t csid_core[2]; - uint8_t csi_phy_sel; -}; - -struct msm_sensor_info_t { - char sensor_name[MAX_SENSOR_NAME]; - uint32_t session_id; - int32_t subdev_id[SUB_MODULE_MAX]; - int32_t subdev_intf[SUB_MODULE_MAX]; - uint8_t is_mount_angle_valid; - uint32_t sensor_mount_angle; - int modes_supported; - enum camb_position_t position; -}; - -struct camera_vreg_t { - const char *reg_name; - int min_voltage; - int max_voltage; - int op_mode; - uint32_t delay; - const char *custom_vreg_name; - enum camera_vreg_type type; -}; - -struct sensorb_cfg_data { - int cfgtype; - union { - struct msm_sensor_info_t sensor_info; - struct msm_sensor_init_params sensor_init_params; - void *setting; - struct msm_sensor_i2c_sync_params sensor_i2c_sync_params; - } cfg; -}; - -struct csid_cfg_data { - enum csid_cfg_type_t cfgtype; - union { - uint32_t csid_version; - struct msm_camera_csid_params *csid_params; - struct msm_camera_csid_testmode_parms *csid_testmode_params; - } cfg; -}; - -struct csiphy_cfg_data { - enum csiphy_cfg_type_t cfgtype; - union { - struct msm_camera_csiphy_params *csiphy_params; - struct msm_camera_csi_lane_params *csi_lane_params; - } cfg; -}; - -enum eeprom_cfg_type_t { - CFG_EEPROM_GET_INFO, - CFG_EEPROM_GET_CAL_DATA, - CFG_EEPROM_READ_CAL_DATA, - CFG_EEPROM_WRITE_DATA, - CFG_EEPROM_GET_MM_INFO, - CFG_EEPROM_INIT, -}; - -struct eeprom_get_t { - uint32_t num_bytes; -}; - -struct eeprom_read_t { - uint8_t *dbuffer; - uint32_t num_bytes; -}; - -struct eeprom_write_t { - uint8_t *dbuffer; - uint32_t num_bytes; -}; - -struct eeprom_get_cmm_t { - uint32_t cmm_support; - uint32_t cmm_compression; - uint32_t cmm_size; -}; - -struct msm_eeprom_info_t { - struct msm_sensor_power_setting_array *power_setting_array; - enum i2c_freq_mode_t i2c_freq_mode; - struct msm_eeprom_memory_map_array *mem_map_array; -}; - -struct msm_eeprom_cfg_data { - enum eeprom_cfg_type_t cfgtype; - uint8_t is_supported; - union { - char eeprom_name[MAX_SENSOR_NAME]; - struct eeprom_get_t get_data; - struct eeprom_read_t read_data; - struct eeprom_write_t write_data; - struct eeprom_get_cmm_t get_cmm_data; - struct msm_eeprom_info_t eeprom_info; - } cfg; -}; - -#ifdef CONFIG_COMPAT -struct msm_sensor_power_setting32 { - enum msm_sensor_power_seq_type_t seq_type; - uint16_t seq_val; - compat_uint_t config_val; - uint16_t delay; - compat_uptr_t data[10]; -}; - -struct msm_sensor_power_setting_array32 { - struct msm_sensor_power_setting32 power_setting_a[MAX_POWER_CONFIG]; - compat_uptr_t power_setting; - uint16_t size; - struct msm_sensor_power_setting32 - power_down_setting_a[MAX_POWER_CONFIG]; - compat_uptr_t power_down_setting; - uint16_t size_down; -}; - -struct msm_camera_sensor_slave_info32 { - char sensor_name[32]; - char eeprom_name[32]; - char actuator_name[32]; - char ois_name[32]; - char flash_name[32]; - enum msm_sensor_camera_id_t camera_id; - uint16_t slave_addr; - enum i2c_freq_mode_t i2c_freq_mode; - enum msm_camera_i2c_reg_addr_type addr_type; - struct msm_sensor_id_info_t sensor_id_info; - struct msm_sensor_power_setting_array32 power_setting_array; - uint8_t is_init_params_valid; - struct msm_sensor_init_params sensor_init_params; - enum msm_sensor_output_format_t output_format; -}; - -struct msm_camera_csid_lut_params32 { - uint8_t num_cid; - struct msm_camera_csid_vc_cfg vc_cfg_a[MAX_CID]; - compat_uptr_t vc_cfg[MAX_CID]; -}; - -struct msm_camera_csid_params32 { - uint8_t lane_cnt; - uint16_t lane_assign; - uint8_t phy_sel; - uint32_t csi_clk; - struct msm_camera_csid_lut_params32 lut_params; - uint8_t csi_3p_sel; -}; - -struct msm_camera_csi2_params32 { - struct msm_camera_csid_params32 csid_params; - struct msm_camera_csiphy_params csiphy_params; - uint8_t csi_clk_scale_enable; -}; - -struct csid_cfg_data32 { - enum csid_cfg_type_t cfgtype; - union { - uint32_t csid_version; - compat_uptr_t csid_params; - compat_uptr_t csid_testmode_params; - } cfg; -}; - -struct eeprom_read_t32 { - compat_uptr_t dbuffer; - uint32_t num_bytes; -}; - -struct eeprom_write_t32 { - compat_uptr_t dbuffer; - uint32_t num_bytes; -}; - -struct msm_eeprom_info_t32 { - compat_uptr_t power_setting_array; - enum i2c_freq_mode_t i2c_freq_mode; - compat_uptr_t mem_map_array; -}; - -struct msm_eeprom_cfg_data32 { - enum eeprom_cfg_type_t cfgtype; - uint8_t is_supported; - union { - char eeprom_name[MAX_SENSOR_NAME]; - struct eeprom_get_t get_data; - struct eeprom_read_t32 read_data; - struct eeprom_write_t32 write_data; - struct msm_eeprom_info_t32 eeprom_info; - } cfg; -}; - -struct msm_camera_i2c_seq_reg_setting32 { - compat_uptr_t reg_setting; - uint16_t size; - enum msm_camera_i2c_reg_addr_type addr_type; - uint16_t delay; -}; -#endif - -enum msm_sensor_cfg_type_t { - CFG_SET_SLAVE_INFO, - CFG_SLAVE_READ_I2C, - CFG_WRITE_I2C_ARRAY, - CFG_SLAVE_WRITE_I2C_ARRAY, - CFG_WRITE_I2C_SEQ_ARRAY, - CFG_POWER_UP, - CFG_POWER_DOWN, - CFG_SET_STOP_STREAM_SETTING, - CFG_GET_SENSOR_INFO, - CFG_GET_SENSOR_INIT_PARAMS, - CFG_SET_INIT_SETTING, - CFG_SET_RESOLUTION, - CFG_SET_STOP_STREAM, - CFG_SET_START_STREAM, - CFG_SET_SATURATION, - CFG_SET_CONTRAST, - CFG_SET_SHARPNESS, - CFG_SET_ISO, - CFG_SET_EXPOSURE_COMPENSATION, - CFG_SET_ANTIBANDING, - CFG_SET_BESTSHOT_MODE, - CFG_SET_EFFECT, - CFG_SET_WHITE_BALANCE, - CFG_SET_AUTOFOCUS, - CFG_CANCEL_AUTOFOCUS, - CFG_SET_STREAM_TYPE, - CFG_SET_I2C_SYNC_PARAM, - CFG_WRITE_I2C_ARRAY_ASYNC, - CFG_WRITE_I2C_ARRAY_SYNC, - CFG_WRITE_I2C_ARRAY_SYNC_BLOCK, -}; - -enum msm_actuator_cfg_type_t { - CFG_GET_ACTUATOR_INFO, - CFG_SET_ACTUATOR_INFO, - CFG_SET_DEFAULT_FOCUS, - CFG_MOVE_FOCUS, - CFG_SET_POSITION, - CFG_ACTUATOR_POWERDOWN, - CFG_ACTUATOR_POWERUP, - CFG_ACTUATOR_INIT, -}; - -enum msm_ois_cfg_type_t { - CFG_OIS_INIT, - CFG_OIS_POWERDOWN, - CFG_OIS_POWERUP, - CFG_OIS_CONTROL, - CFG_OIS_I2C_WRITE_SEQ_TABLE, -}; - -enum msm_ois_i2c_operation { - MSM_OIS_WRITE = 0, - MSM_OIS_POLL, -}; - -struct reg_settings_ois_t { - uint16_t reg_addr; - enum msm_camera_i2c_reg_addr_type addr_type; - uint32_t reg_data; - enum msm_camera_i2c_data_type data_type; - enum msm_ois_i2c_operation i2c_operation; - uint32_t delay; -#define OIS_REG_DATA_SEQ_MAX 128 - unsigned char reg_data_seq[OIS_REG_DATA_SEQ_MAX]; - uint32_t reg_data_seq_size; -}; - -struct msm_ois_params_t { - uint16_t data_size; - uint16_t setting_size; - uint32_t i2c_addr; - enum i2c_freq_mode_t i2c_freq_mode; - enum msm_camera_i2c_reg_addr_type i2c_addr_type; - enum msm_camera_i2c_data_type i2c_data_type; - struct reg_settings_ois_t *settings; -}; - -struct msm_ois_set_info_t { - struct msm_ois_params_t ois_params; -}; - -struct msm_actuator_move_params_t { - int8_t dir; - int8_t sign_dir; - int16_t dest_step_pos; - int32_t num_steps; - uint16_t curr_lens_pos; - struct damping_params_t *ringing_params; -}; - -struct msm_actuator_tuning_params_t { - int16_t initial_code; - uint16_t pwd_step; - uint16_t region_size; - uint32_t total_steps; - struct region_params_t *region_params; -}; - -struct park_lens_data_t { - uint32_t damping_step; - uint32_t damping_delay; - uint32_t hw_params; - uint32_t max_step; -}; - -struct msm_actuator_params_t { - enum actuator_type act_type; - uint8_t reg_tbl_size; - uint16_t data_size; - uint16_t init_setting_size; - uint32_t i2c_addr; - enum i2c_freq_mode_t i2c_freq_mode; - enum msm_actuator_addr_type i2c_addr_type; - enum msm_actuator_data_type i2c_data_type; - struct msm_actuator_reg_params_t *reg_tbl_params; - struct reg_settings_t *init_settings; - struct park_lens_data_t park_lens; -}; - -struct msm_actuator_set_info_t { - struct msm_actuator_params_t actuator_params; - struct msm_actuator_tuning_params_t af_tuning_params; -}; - -struct msm_actuator_get_info_t { - uint32_t focal_length_num; - uint32_t focal_length_den; - uint32_t f_number_num; - uint32_t f_number_den; - uint32_t f_pix_num; - uint32_t f_pix_den; - uint32_t total_f_dist_num; - uint32_t total_f_dist_den; - uint32_t hor_view_angle_num; - uint32_t hor_view_angle_den; - uint32_t ver_view_angle_num; - uint32_t ver_view_angle_den; -}; - -enum af_camera_name { - ACTUATOR_MAIN_CAM_0, - ACTUATOR_MAIN_CAM_1, - ACTUATOR_MAIN_CAM_2, - ACTUATOR_MAIN_CAM_3, - ACTUATOR_MAIN_CAM_4, - ACTUATOR_MAIN_CAM_5, - ACTUATOR_WEB_CAM_0, - ACTUATOR_WEB_CAM_1, - ACTUATOR_WEB_CAM_2, -}; - -struct msm_ois_cfg_data { - int cfgtype; - union { - struct msm_ois_set_info_t set_info; - struct msm_camera_i2c_seq_reg_setting *settings; - } cfg; -}; - -struct msm_actuator_set_position_t { - uint16_t number_of_steps; - uint32_t hw_params; - uint16_t pos[MAX_NUMBER_OF_STEPS]; - uint16_t delay[MAX_NUMBER_OF_STEPS]; -}; - -struct msm_actuator_cfg_data { - int cfgtype; - uint8_t is_af_supported; - union { - struct msm_actuator_move_params_t move; - struct msm_actuator_set_info_t set_info; - struct msm_actuator_get_info_t get_info; - struct msm_actuator_set_position_t setpos; - enum af_camera_name cam_name; - } cfg; -}; - -enum msm_camera_led_config_t { - MSM_CAMERA_LED_OFF, - MSM_CAMERA_LED_LOW, - MSM_CAMERA_LED_HIGH, - MSM_CAMERA_LED_INIT, - MSM_CAMERA_LED_RELEASE, -}; - -struct msm_camera_led_cfg_t { - enum msm_camera_led_config_t cfgtype; - int32_t torch_current[MAX_LED_TRIGGERS]; - int32_t flash_current[MAX_LED_TRIGGERS]; - int32_t flash_duration[MAX_LED_TRIGGERS]; -}; - -struct msm_flash_init_info_t { - enum msm_flash_driver_type flash_driver_type; - uint32_t slave_addr; - enum i2c_freq_mode_t i2c_freq_mode; - struct msm_sensor_power_setting_array *power_setting_array; - struct msm_camera_i2c_reg_setting_array *settings; -}; - -struct msm_flash_cfg_data_t { - enum msm_flash_cfg_type_t cfg_type; - int32_t flash_current[MAX_LED_TRIGGERS]; - int32_t flash_duration[MAX_LED_TRIGGERS]; - union { - struct msm_flash_init_info_t *flash_init_info; - struct msm_camera_i2c_reg_setting_array *settings; - } cfg; -}; - -/* sensor init structures and enums */ -enum msm_sensor_init_cfg_type_t { - CFG_SINIT_PROBE, - CFG_SINIT_PROBE_DONE, - CFG_SINIT_PROBE_WAIT_DONE, -}; - -struct sensor_init_cfg_data { - enum msm_sensor_init_cfg_type_t cfgtype; - struct msm_sensor_info_t probed_info; - char entity_name[MAX_SENSOR_NAME]; - union { - void *setting; - } cfg; -}; - -#define VIDIOC_MSM_SENSOR_CFG \ - _IOWR('V', BASE_VIDIOC_PRIVATE + 1, struct sensorb_cfg_data) - -#define VIDIOC_MSM_SENSOR_RELEASE \ - _IO('V', BASE_VIDIOC_PRIVATE + 2) - -#define VIDIOC_MSM_SENSOR_GET_SUBDEV_ID \ - _IOWR('V', BASE_VIDIOC_PRIVATE + 3, uint32_t) - -#define VIDIOC_MSM_CSIPHY_IO_CFG \ - _IOWR('V', BASE_VIDIOC_PRIVATE + 4, struct csiphy_cfg_data) - -#define VIDIOC_MSM_CSID_IO_CFG \ - _IOWR('V', BASE_VIDIOC_PRIVATE + 5, struct csid_cfg_data) - -#define VIDIOC_MSM_ACTUATOR_CFG \ - _IOWR('V', BASE_VIDIOC_PRIVATE + 6, struct msm_actuator_cfg_data) - -#define VIDIOC_MSM_FLASH_LED_DATA_CFG \ - _IOWR('V', BASE_VIDIOC_PRIVATE + 7, struct msm_camera_led_cfg_t) - -#define VIDIOC_MSM_EEPROM_CFG \ - _IOWR('V', BASE_VIDIOC_PRIVATE + 8, struct msm_eeprom_cfg_data) - -#define VIDIOC_MSM_SENSOR_GET_AF_STATUS \ - _IOWR('V', BASE_VIDIOC_PRIVATE + 9, uint32_t) - -#define VIDIOC_MSM_SENSOR_INIT_CFG \ - _IOWR('V', BASE_VIDIOC_PRIVATE + 10, struct sensor_init_cfg_data) - -#define VIDIOC_MSM_OIS_CFG \ - _IOWR('V', BASE_VIDIOC_PRIVATE + 11, struct msm_ois_cfg_data) - -#define VIDIOC_MSM_FLASH_CFG \ - _IOWR('V', BASE_VIDIOC_PRIVATE + 13, struct msm_flash_cfg_data_t) - -#ifdef CONFIG_COMPAT -struct msm_camera_i2c_reg_setting32 { - compat_uptr_t reg_setting; - uint16_t size; - enum msm_camera_i2c_reg_addr_type addr_type; - enum msm_camera_i2c_data_type data_type; - uint16_t delay; -}; - -struct msm_camera_i2c_array_write_config32 { - struct msm_camera_i2c_reg_setting32 conf_array; - uint16_t slave_addr; -}; - -struct msm_actuator_tuning_params_t32 { - int16_t initial_code; - uint16_t pwd_step; - uint16_t region_size; - uint32_t total_steps; - compat_uptr_t region_params; -}; - -struct msm_actuator_params_t32 { - enum actuator_type act_type; - uint8_t reg_tbl_size; - uint16_t data_size; - uint16_t init_setting_size; - uint32_t i2c_addr; - enum i2c_freq_mode_t i2c_freq_mode; - enum msm_actuator_addr_type i2c_addr_type; - enum msm_actuator_data_type i2c_data_type; - compat_uptr_t reg_tbl_params; - compat_uptr_t init_settings; - struct park_lens_data_t park_lens; -}; - -struct msm_actuator_set_info_t32 { - struct msm_actuator_params_t32 actuator_params; - struct msm_actuator_tuning_params_t32 af_tuning_params; -}; - -struct sensor_init_cfg_data32 { - enum msm_sensor_init_cfg_type_t cfgtype; - struct msm_sensor_info_t probed_info; - char entity_name[MAX_SENSOR_NAME]; - union { - compat_uptr_t setting; - } cfg; -}; - -struct msm_actuator_move_params_t32 { - int8_t dir; - int8_t sign_dir; - int16_t dest_step_pos; - int32_t num_steps; - uint16_t curr_lens_pos; - compat_uptr_t ringing_params; -}; - -struct msm_actuator_cfg_data32 { - int cfgtype; - uint8_t is_af_supported; - union { - struct msm_actuator_move_params_t32 move; - struct msm_actuator_set_info_t32 set_info; - struct msm_actuator_get_info_t get_info; - struct msm_actuator_set_position_t setpos; - enum af_camera_name cam_name; - } cfg; -}; - -struct csiphy_cfg_data32 { - enum csiphy_cfg_type_t cfgtype; - union { - compat_uptr_t csiphy_params; - compat_uptr_t csi_lane_params; - } cfg; -}; - -struct sensorb_cfg_data32 { - int cfgtype; - union { - struct msm_sensor_info_t sensor_info; - struct msm_sensor_init_params sensor_init_params; - compat_uptr_t setting; - struct msm_sensor_i2c_sync_params sensor_i2c_sync_params; - } cfg; -}; - -struct msm_ois_params_t32 { - uint16_t data_size; - uint16_t setting_size; - uint32_t i2c_addr; - enum i2c_freq_mode_t i2c_freq_mode; - enum msm_camera_i2c_reg_addr_type i2c_addr_type; - enum msm_camera_i2c_data_type i2c_data_type; - compat_uptr_t settings; -}; - -struct msm_ois_set_info_t32 { - struct msm_ois_params_t32 ois_params; -}; - -struct msm_ois_cfg_data32 { - int cfgtype; - union { - struct msm_ois_set_info_t32 set_info; - compat_uptr_t settings; - } cfg; -}; - -struct msm_flash_init_info_t32 { - enum msm_flash_driver_type flash_driver_type; - uint32_t slave_addr; - enum i2c_freq_mode_t i2c_freq_mode; - compat_uptr_t power_setting_array; - compat_uptr_t settings; -}; - -struct msm_flash_cfg_data_t32 { - enum msm_flash_cfg_type_t cfg_type; - int32_t flash_current[MAX_LED_TRIGGERS]; - int32_t flash_duration[MAX_LED_TRIGGERS]; - union { - compat_uptr_t flash_init_info; - compat_uptr_t settings; - } cfg; -}; - -#define VIDIOC_MSM_ACTUATOR_CFG32 \ - _IOWR('V', BASE_VIDIOC_PRIVATE + 6, struct msm_actuator_cfg_data32) - -#define VIDIOC_MSM_SENSOR_INIT_CFG32 \ - _IOWR('V', BASE_VIDIOC_PRIVATE + 10, struct sensor_init_cfg_data32) - -#define VIDIOC_MSM_CSIPHY_IO_CFG32 \ - _IOWR('V', BASE_VIDIOC_PRIVATE + 4, struct csiphy_cfg_data32) - -#define VIDIOC_MSM_SENSOR_CFG32 \ - _IOWR('V', BASE_VIDIOC_PRIVATE + 1, struct sensorb_cfg_data32) - -#define VIDIOC_MSM_EEPROM_CFG32 \ - _IOWR('V', BASE_VIDIOC_PRIVATE + 8, struct msm_eeprom_cfg_data32) - -#define VIDIOC_MSM_OIS_CFG32 \ - _IOWR('V', BASE_VIDIOC_PRIVATE + 11, struct msm_ois_cfg_data32) - -#define VIDIOC_MSM_CSID_IO_CFG32 \ - _IOWR('V', BASE_VIDIOC_PRIVATE + 5, struct csid_cfg_data32) - -#define VIDIOC_MSM_FLASH_CFG32 \ - _IOWR('V', BASE_VIDIOC_PRIVATE + 13, struct msm_flash_cfg_data_t32) -#endif - -#endif /* __LINUX_MSM_CAM_SENSOR_H */ diff --git a/third_party/linux/include/msm_camsensor_sdk.h b/third_party/linux/include/msm_camsensor_sdk.h deleted file mode 100644 index 62a4da2..0000000 --- a/third_party/linux/include/msm_camsensor_sdk.h +++ /dev/null @@ -1,386 +0,0 @@ -#ifndef __LINUX_MSM_CAMSENSOR_SDK_H -#define __LINUX_MSM_CAMSENSOR_SDK_H - -#define KVERSION 0x1 - -#define MAX_POWER_CONFIG 12 -#define GPIO_OUT_LOW (0 << 1) -#define GPIO_OUT_HIGH (1 << 1) -#define CSI_EMBED_DATA 0x12 -#define CSI_RESERVED_DATA_0 0x13 -#define CSI_YUV422_8 0x1E -#define CSI_RAW8 0x2A -#define CSI_RAW10 0x2B -#define CSI_RAW12 0x2C -#define CSI_DECODE_6BIT 0 -#define CSI_DECODE_8BIT 1 -#define CSI_DECODE_10BIT 2 -#define CSI_DECODE_12BIT 3 -#define CSI_DECODE_DPCM_10_8_10 5 -#define MAX_CID 16 -#define I2C_SEQ_REG_DATA_MAX 1024 -#define I2C_REG_DATA_MAX (8*1024) - -#define MSM_V4L2_PIX_FMT_META v4l2_fourcc('M', 'E', 'T', 'A') /* META */ -#define MSM_V4L2_PIX_FMT_SBGGR14 v4l2_fourcc('B', 'G', '1', '4') - /* 14 BGBG.. GRGR.. */ -#define MSM_V4L2_PIX_FMT_SGBRG14 v4l2_fourcc('G', 'B', '1', '4') - /* 14 GBGB.. RGRG.. */ -#define MSM_V4L2_PIX_FMT_SGRBG14 v4l2_fourcc('B', 'A', '1', '4') - /* 14 GRGR.. BGBG.. */ -#define MSM_V4L2_PIX_FMT_SRGGB14 v4l2_fourcc('R', 'G', '1', '4') - /* 14 RGRG.. GBGB.. */ - -#define MAX_ACTUATOR_REG_TBL_SIZE 8 -#define MAX_ACTUATOR_REGION 5 -#define NUM_ACTUATOR_DIR 2 -#define MAX_ACTUATOR_SCENARIO 8 -#define MAX_ACT_MOD_NAME_SIZE 32 -#define MAX_ACT_NAME_SIZE 32 -#define MAX_ACTUATOR_INIT_SET 120 -#define MAX_I2C_REG_SET 12 - -#define MAX_LED_TRIGGERS 3 - -#define MSM_EEPROM_MEMORY_MAP_MAX_SIZE 80 -#define MSM_EEPROM_MAX_MEM_MAP_CNT 8 - -enum msm_sensor_camera_id_t { - CAMERA_0, - CAMERA_1, - CAMERA_2, - CAMERA_3, - MAX_CAMERAS, -}; - -enum i2c_freq_mode_t { - I2C_STANDARD_MODE, - I2C_FAST_MODE, - I2C_CUSTOM_MODE, - I2C_FAST_PLUS_MODE, - I2C_MAX_MODES, -}; - -enum camb_position_t { - BACK_CAMERA_B, - FRONT_CAMERA_B, - AUX_CAMERA_B = 0x100, - INVALID_CAMERA_B, -}; - -enum msm_sensor_power_seq_type_t { - SENSOR_CLK, - SENSOR_GPIO, - SENSOR_VREG, - SENSOR_I2C_MUX, - SENSOR_I2C, -}; - -enum msm_camera_i2c_reg_addr_type { - MSM_CAMERA_I2C_BYTE_ADDR = 1, - MSM_CAMERA_I2C_WORD_ADDR, - MSM_CAMERA_I2C_3B_ADDR, - MSM_CAMERA_I2C_ADDR_TYPE_MAX, -}; - -enum msm_camera_i2c_data_type { - MSM_CAMERA_I2C_BYTE_DATA = 1, - MSM_CAMERA_I2C_WORD_DATA, - MSM_CAMERA_I2C_DWORD_DATA, - MSM_CAMERA_I2C_SET_BYTE_MASK, - MSM_CAMERA_I2C_UNSET_BYTE_MASK, - MSM_CAMERA_I2C_SET_WORD_MASK, - MSM_CAMERA_I2C_UNSET_WORD_MASK, - MSM_CAMERA_I2C_SET_BYTE_WRITE_MASK_DATA, - MSM_CAMERA_I2C_SEQ_DATA, - MSM_CAMERA_I2C_DATA_TYPE_MAX, -}; - -enum msm_sensor_power_seq_gpio_t { - SENSOR_GPIO_RESET, - SENSOR_GPIO_STANDBY, - SENSOR_GPIO_AF_PWDM, - SENSOR_GPIO_VIO, - SENSOR_GPIO_VANA, - SENSOR_GPIO_VDIG, - SENSOR_GPIO_VAF, - SENSOR_GPIO_FL_EN, - SENSOR_GPIO_FL_NOW, - SENSOR_GPIO_FL_RESET, - SENSOR_GPIO_CUSTOM1, - SENSOR_GPIO_CUSTOM2, - SENSOR_GPIO_MAX, -}; - -enum msm_camera_vreg_name_t { - CAM_VDIG, - CAM_VIO, - CAM_VANA, - CAM_VAF, - CAM_V_CUSTOM1, - CAM_V_CUSTOM2, - CAM_VREG_MAX, -}; - -enum msm_sensor_clk_type_t { - SENSOR_CAM_MCLK, - SENSOR_CAM_CLK, - SENSOR_CAM_CLK_MAX, -}; - -enum camerab_mode_t { - CAMERA_MODE_2D_B = (1<<0), - CAMERA_MODE_3D_B = (1<<1), - CAMERA_MODE_INVALID = (1<<2), -}; - -enum msm_actuator_data_type { - MSM_ACTUATOR_BYTE_DATA = 1, - MSM_ACTUATOR_WORD_DATA, -}; - -enum msm_actuator_addr_type { - MSM_ACTUATOR_BYTE_ADDR = 1, - MSM_ACTUATOR_WORD_ADDR, -}; - -enum msm_actuator_write_type { - MSM_ACTUATOR_WRITE_HW_DAMP, - MSM_ACTUATOR_WRITE_DAC, - MSM_ACTUATOR_WRITE, - MSM_ACTUATOR_WRITE_DIR_REG, - MSM_ACTUATOR_POLL, - MSM_ACTUATOR_READ_WRITE, -}; - -enum msm_actuator_i2c_operation { - MSM_ACT_WRITE = 0, - MSM_ACT_POLL, -}; - -enum actuator_type { - ACTUATOR_VCM, - ACTUATOR_PIEZO, - ACTUATOR_HVCM, - ACTUATOR_BIVCM, -}; - -enum msm_flash_driver_type { - FLASH_DRIVER_PMIC, - FLASH_DRIVER_I2C, - FLASH_DRIVER_GPIO, - FLASH_DRIVER_DEFAULT -}; - -enum msm_flash_cfg_type_t { - CFG_FLASH_INIT, - CFG_FLASH_RELEASE, - CFG_FLASH_OFF, - CFG_FLASH_LOW, - CFG_FLASH_HIGH, -}; - -enum msm_sensor_output_format_t { - MSM_SENSOR_BAYER, - MSM_SENSOR_YCBCR, - MSM_SENSOR_META, -}; - -struct msm_sensor_power_setting { - enum msm_sensor_power_seq_type_t seq_type; - unsigned short seq_val; - long config_val; - unsigned short delay; - void *data[10]; -}; - -struct msm_sensor_power_setting_array { - struct msm_sensor_power_setting power_setting_a[MAX_POWER_CONFIG]; - struct msm_sensor_power_setting *power_setting; - unsigned short size; - struct msm_sensor_power_setting power_down_setting_a[MAX_POWER_CONFIG]; - struct msm_sensor_power_setting *power_down_setting; - unsigned short size_down; -}; - -enum msm_camera_i2c_operation { - MSM_CAM_WRITE = 0, - MSM_CAM_POLL, - MSM_CAM_READ, -}; - -struct msm_sensor_i2c_sync_params { - unsigned int cid; - int csid; - unsigned short line; - unsigned short delay; -}; - -struct msm_camera_reg_settings_t { - uint16_t reg_addr; - enum msm_camera_i2c_reg_addr_type addr_type; - uint16_t reg_data; - enum msm_camera_i2c_data_type data_type; - enum msm_camera_i2c_operation i2c_operation; - uint16_t delay; -}; - -struct msm_eeprom_mem_map_t { - int slave_addr; - struct msm_camera_reg_settings_t - mem_settings[MSM_EEPROM_MEMORY_MAP_MAX_SIZE]; - int memory_map_size; -}; - -struct msm_eeprom_memory_map_array { - struct msm_eeprom_mem_map_t memory_map[MSM_EEPROM_MAX_MEM_MAP_CNT]; - uint32_t msm_size_of_max_mappings; -}; - -struct msm_sensor_init_params { - /* mask of modes supported: 2D, 3D */ - int modes_supported; - /* sensor position: front, back */ - enum camb_position_t position; - /* sensor mount angle */ - unsigned int sensor_mount_angle; -}; - -struct msm_sensor_id_info_t { - unsigned short sensor_id_reg_addr; - unsigned short sensor_id; - unsigned short sensor_id_mask; - // added in LeEco - unsigned char module_id; - unsigned char vcm_id; -}; - -struct msm_camera_sensor_slave_info { - char sensor_name[32]; - char eeprom_name[32]; - char actuator_name[32]; - char ois_name[32]; - char flash_name[32]; - enum msm_sensor_camera_id_t camera_id; - unsigned short slave_addr; - enum i2c_freq_mode_t i2c_freq_mode; - enum msm_camera_i2c_reg_addr_type addr_type; - struct msm_sensor_id_info_t sensor_id_info; - struct msm_sensor_power_setting_array power_setting_array; - unsigned char is_init_params_valid; - struct msm_sensor_init_params sensor_init_params; - enum msm_sensor_output_format_t output_format; -}; - -struct msm_camera_i2c_reg_array { - unsigned short reg_addr; - unsigned short reg_data; - unsigned int delay; -}; - -struct msm_camera_i2c_reg_setting { - struct msm_camera_i2c_reg_array *reg_setting; - unsigned short size; - enum msm_camera_i2c_reg_addr_type addr_type; - enum msm_camera_i2c_data_type data_type; - unsigned short delay; -}; - -struct msm_camera_csid_vc_cfg { - unsigned char cid; - unsigned char dt; - unsigned char decode_format; -}; - -struct msm_camera_csid_lut_params { - unsigned char num_cid; - struct msm_camera_csid_vc_cfg vc_cfg_a[MAX_CID]; - struct msm_camera_csid_vc_cfg *vc_cfg[MAX_CID]; -}; - -struct msm_camera_csid_params { - unsigned char lane_cnt; - unsigned short lane_assign; - unsigned char phy_sel; - unsigned int csi_clk; - struct msm_camera_csid_lut_params lut_params; - unsigned char csi_3p_sel; -}; - -struct msm_camera_csid_testmode_parms { - unsigned int num_bytes_per_line; - unsigned int num_lines; - unsigned int h_blanking_count; - unsigned int v_blanking_count; - unsigned int payload_mode; -}; - -struct msm_camera_csiphy_params { - unsigned char lane_cnt; - unsigned char settle_cnt; - unsigned short lane_mask; - unsigned char combo_mode; - unsigned char csid_core; - unsigned int csiphy_clk; - unsigned char csi_3phase; -}; - -struct msm_camera_i2c_seq_reg_array { - unsigned short reg_addr; - unsigned char reg_data[I2C_SEQ_REG_DATA_MAX]; - unsigned short reg_data_size; -}; - -struct msm_camera_i2c_seq_reg_setting { - struct msm_camera_i2c_seq_reg_array *reg_setting; - unsigned short size; - enum msm_camera_i2c_reg_addr_type addr_type; - unsigned short delay; -}; - -struct msm_actuator_reg_params_t { - enum msm_actuator_write_type reg_write_type; - unsigned int hw_mask; - unsigned short reg_addr; - unsigned short hw_shift; - unsigned short data_shift; - unsigned short data_type; - unsigned short addr_type; - unsigned short reg_data; - unsigned short delay; -}; - - -struct damping_params_t { - unsigned int damping_step; - unsigned int damping_delay; - unsigned int hw_params; -}; - -struct region_params_t { - /* [0] = ForwardDirection Macro boundary - [1] = ReverseDirection Inf boundary - */ - unsigned short step_bound[2]; - unsigned short code_per_step; - /* qvalue for converting float type numbers to integer format */ - unsigned int qvalue; -}; - -struct reg_settings_t { - unsigned short reg_addr; - enum msm_actuator_addr_type addr_type; - unsigned short reg_data; - enum msm_actuator_data_type data_type; - enum msm_actuator_i2c_operation i2c_operation; - unsigned int delay; -}; - -struct msm_camera_i2c_reg_setting_array { - struct msm_camera_i2c_reg_array reg_setting_a[MAX_I2C_REG_SET]; - unsigned short size; - enum msm_camera_i2c_reg_addr_type addr_type; - enum msm_camera_i2c_data_type data_type; - unsigned short delay; -}; -#endif /* __LINUX_MSM_CAM_SENSOR_H */ diff --git a/third_party/linux/include/msm_ion.h b/third_party/linux/include/msm_ion.h deleted file mode 100644 index d5caed5..0000000 --- a/third_party/linux/include/msm_ion.h +++ /dev/null @@ -1,211 +0,0 @@ -#ifndef _UAPI_MSM_ION_H -#define _UAPI_MSM_ION_H - -#include - -enum msm_ion_heap_types { - ION_HEAP_TYPE_MSM_START = ION_HEAP_TYPE_CUSTOM + 1, - ION_HEAP_TYPE_SECURE_DMA = ION_HEAP_TYPE_MSM_START, - ION_HEAP_TYPE_SYSTEM_SECURE, - ION_HEAP_TYPE_HYP_CMA, - /* - * if you add a heap type here you should also add it to - * heap_types_info[] in msm_ion.c - */ -}; - -/** - * These are the only ids that should be used for Ion heap ids. - * The ids listed are the order in which allocation will be attempted - * if specified. Don't swap the order of heap ids unless you know what - * you are doing! - * Id's are spaced by purpose to allow new Id's to be inserted in-between (for - * possible fallbacks) - */ - -enum ion_heap_ids { - INVALID_HEAP_ID = -1, - ION_CP_MM_HEAP_ID = 8, - ION_SECURE_HEAP_ID = 9, - ION_SECURE_DISPLAY_HEAP_ID = 10, - ION_CP_MFC_HEAP_ID = 12, - ION_CP_WB_HEAP_ID = 16, /* 8660 only */ - ION_CAMERA_HEAP_ID = 20, /* 8660 only */ - ION_SYSTEM_CONTIG_HEAP_ID = 21, - ION_ADSP_HEAP_ID = 22, - ION_PIL1_HEAP_ID = 23, /* Currently used for other PIL images */ - ION_SF_HEAP_ID = 24, - ION_SYSTEM_HEAP_ID = 25, - ION_PIL2_HEAP_ID = 26, /* Currently used for modem firmware images */ - ION_QSECOM_HEAP_ID = 27, - ION_AUDIO_HEAP_ID = 28, - - ION_MM_FIRMWARE_HEAP_ID = 29, - - ION_HEAP_ID_RESERVED = 31 /** Bit reserved for ION_FLAG_SECURE flag */ -}; - -/* - * The IOMMU heap is deprecated! Here are some aliases for backwards - * compatibility: - */ -#define ION_IOMMU_HEAP_ID ION_SYSTEM_HEAP_ID -#define ION_HEAP_TYPE_IOMMU ION_HEAP_TYPE_SYSTEM - -enum ion_fixed_position { - NOT_FIXED, - FIXED_LOW, - FIXED_MIDDLE, - FIXED_HIGH, -}; - -enum cp_mem_usage { - VIDEO_BITSTREAM = 0x1, - VIDEO_PIXEL = 0x2, - VIDEO_NONPIXEL = 0x3, - DISPLAY_SECURE_CP_USAGE = 0x4, - CAMERA_SECURE_CP_USAGE = 0x5, - MAX_USAGE = 0x6, - UNKNOWN = 0x7FFFFFFF, -}; - -/** - * Flags to be used when allocating from the secure heap for - * content protection - */ -#define ION_FLAG_CP_TOUCH (1 << 17) -#define ION_FLAG_CP_BITSTREAM (1 << 18) -#define ION_FLAG_CP_PIXEL (1 << 19) -#define ION_FLAG_CP_NON_PIXEL (1 << 20) -#define ION_FLAG_CP_CAMERA (1 << 21) -#define ION_FLAG_CP_HLOS (1 << 22) -#define ION_FLAG_CP_HLOS_FREE (1 << 23) -#define ION_FLAG_CP_SEC_DISPLAY (1 << 25) -#define ION_FLAG_CP_APP (1 << 26) - -/** - * Flag to allow non continguous allocation of memory from secure - * heap - */ -#define ION_FLAG_ALLOW_NON_CONTIG (1 << 24) - -/** - * Flag to use when allocating to indicate that a heap is secure. - */ -#define ION_FLAG_SECURE (1 << ION_HEAP_ID_RESERVED) - -/** - * Flag for clients to force contiguous memort allocation - * - * Use of this flag is carefully monitored! - */ -#define ION_FLAG_FORCE_CONTIGUOUS (1 << 30) - -/* - * Used in conjunction with heap which pool memory to force an allocation - * to come from the page allocator directly instead of from the pool allocation - */ -#define ION_FLAG_POOL_FORCE_ALLOC (1 << 16) - - -#define ION_FLAG_POOL_PREFETCH (1 << 27) - -/** -* Deprecated! Please use the corresponding ION_FLAG_* -*/ -#define ION_SECURE ION_FLAG_SECURE -#define ION_FORCE_CONTIGUOUS ION_FLAG_FORCE_CONTIGUOUS - -/** - * Macro should be used with ion_heap_ids defined above. - */ -#define ION_HEAP(bit) (1 << (bit)) - -#define ION_ADSP_HEAP_NAME "adsp" -#define ION_SYSTEM_HEAP_NAME "system" -#define ION_VMALLOC_HEAP_NAME ION_SYSTEM_HEAP_NAME -#define ION_KMALLOC_HEAP_NAME "kmalloc" -#define ION_AUDIO_HEAP_NAME "audio" -#define ION_SF_HEAP_NAME "sf" -#define ION_MM_HEAP_NAME "mm" -#define ION_CAMERA_HEAP_NAME "camera_preview" -#define ION_IOMMU_HEAP_NAME "iommu" -#define ION_MFC_HEAP_NAME "mfc" -#define ION_WB_HEAP_NAME "wb" -#define ION_MM_FIRMWARE_HEAP_NAME "mm_fw" -#define ION_PIL1_HEAP_NAME "pil_1" -#define ION_PIL2_HEAP_NAME "pil_2" -#define ION_QSECOM_HEAP_NAME "qsecom" -#define ION_SECURE_HEAP_NAME "secure_heap" -#define ION_SECURE_DISPLAY_HEAP_NAME "secure_display" - -#define ION_SET_CACHED(__cache) (__cache | ION_FLAG_CACHED) -#define ION_SET_UNCACHED(__cache) (__cache & ~ION_FLAG_CACHED) - -#define ION_IS_CACHED(__flags) ((__flags) & ION_FLAG_CACHED) - -/* struct ion_flush_data - data passed to ion for flushing caches - * - * @handle: handle with data to flush - * @fd: fd to flush - * @vaddr: userspace virtual address mapped with mmap - * @offset: offset into the handle to flush - * @length: length of handle to flush - * - * Performs cache operations on the handle. If p is the start address - * of the handle, p + offset through p + offset + length will have - * the cache operations performed - */ -struct ion_flush_data { - ion_user_handle_t handle; - int fd; - void *vaddr; - unsigned int offset; - unsigned int length; -}; - -struct ion_prefetch_regions { - unsigned int vmid; - size_t *sizes; - unsigned int nr_sizes; -}; - -struct ion_prefetch_data { - int heap_id; - unsigned long len; - /* Is unsigned long bad? 32bit compiler vs 64 bit compiler*/ - struct ion_prefetch_regions *regions; - unsigned int nr_regions; -}; - -#define ION_IOC_MSM_MAGIC 'M' - -/** - * DOC: ION_IOC_CLEAN_CACHES - clean the caches - * - * Clean the caches of the handle specified. - */ -#define ION_IOC_CLEAN_CACHES _IOWR(ION_IOC_MSM_MAGIC, 0, \ - struct ion_flush_data) -/** - * DOC: ION_IOC_INV_CACHES - invalidate the caches - * - * Invalidate the caches of the handle specified. - */ -#define ION_IOC_INV_CACHES _IOWR(ION_IOC_MSM_MAGIC, 1, \ - struct ion_flush_data) -/** - * DOC: ION_IOC_CLEAN_INV_CACHES - clean and invalidate the caches - * - * Clean and invalidate the caches of the handle specified. - */ -#define ION_IOC_CLEAN_INV_CACHES _IOWR(ION_IOC_MSM_MAGIC, 2, \ - struct ion_flush_data) - -#define ION_IOC_PREFETCH _IOWR(ION_IOC_MSM_MAGIC, 3, \ - struct ion_prefetch_data) - -#define ION_IOC_DRAIN _IOWR(ION_IOC_MSM_MAGIC, 4, \ - struct ion_prefetch_data) - -#endif diff --git a/third_party/linux/include/msm_kgsl.h b/third_party/linux/include/msm_kgsl.h deleted file mode 100644 index 93582eb..0000000 --- a/third_party/linux/include/msm_kgsl.h +++ /dev/null @@ -1,1449 +0,0 @@ -#ifndef _UAPI_MSM_KGSL_H -#define _UAPI_MSM_KGSL_H - -#include -#include - -/* - * The KGSL version has proven not to be very useful in userspace if features - * are cherry picked into other trees out of order so it is frozen as of 3.14. - * It is left here for backwards compatabilty and as a reminder that - * software releases are never linear. Also, I like pie. - */ - -#define KGSL_VERSION_MAJOR 3 -#define KGSL_VERSION_MINOR 14 - -/* - * We have traditionally mixed context and issueibcmds / command batch flags - * together into a big flag stew. This worked fine until we started adding a - * lot more command batch flags and we started running out of bits. Turns out - * we have a bit of room in the context type / priority mask that we could use - * for command batches, but that means we need to split out the flags into two - * coherent sets. - * - * If any future definitions are for both context and cmdbatch add both defines - * and link the cmdbatch to the context define as we do below. Otherwise feel - * free to add exclusive bits to either set. - */ - -/* --- context flags --- */ -#define KGSL_CONTEXT_SAVE_GMEM 0x00000001 -#define KGSL_CONTEXT_NO_GMEM_ALLOC 0x00000002 -/* This is a cmdbatch exclusive flag - use the CMDBATCH equivalent instead */ -#define KGSL_CONTEXT_SUBMIT_IB_LIST 0x00000004 -#define KGSL_CONTEXT_CTX_SWITCH 0x00000008 -#define KGSL_CONTEXT_PREAMBLE 0x00000010 -#define KGSL_CONTEXT_TRASH_STATE 0x00000020 -#define KGSL_CONTEXT_PER_CONTEXT_TS 0x00000040 -#define KGSL_CONTEXT_USER_GENERATED_TS 0x00000080 -/* This is a cmdbatch exclusive flag - use the CMDBATCH equivalent instead */ -#define KGSL_CONTEXT_END_OF_FRAME 0x00000100 -#define KGSL_CONTEXT_NO_FAULT_TOLERANCE 0x00000200 -/* This is a cmdbatch exclusive flag - use the CMDBATCH equivalent instead */ -#define KGSL_CONTEXT_SYNC 0x00000400 -#define KGSL_CONTEXT_PWR_CONSTRAINT 0x00000800 - -#define KGSL_CONTEXT_PRIORITY_MASK 0x0000F000 -#define KGSL_CONTEXT_PRIORITY_SHIFT 12 -#define KGSL_CONTEXT_PRIORITY_UNDEF 0 - -#define KGSL_CONTEXT_IFH_NOP 0x00010000 -#define KGSL_CONTEXT_SECURE 0x00020000 - -#define KGSL_CONTEXT_PREEMPT_STYLE_MASK 0x0E000000 -#define KGSL_CONTEXT_PREEMPT_STYLE_SHIFT 25 -#define KGSL_CONTEXT_PREEMPT_STYLE_DEFAULT 0x0 -#define KGSL_CONTEXT_PREEMPT_STYLE_RINGBUFFER 0x1 -#define KGSL_CONTEXT_PREEMPT_STYLE_FINEGRAIN 0x2 - -#define KGSL_CONTEXT_TYPE_MASK 0x01F00000 -#define KGSL_CONTEXT_TYPE_SHIFT 20 -#define KGSL_CONTEXT_TYPE_ANY 0 -#define KGSL_CONTEXT_TYPE_GL 1 -#define KGSL_CONTEXT_TYPE_CL 2 -#define KGSL_CONTEXT_TYPE_C2D 3 -#define KGSL_CONTEXT_TYPE_RS 4 -#define KGSL_CONTEXT_TYPE_UNKNOWN 0x1E - -#define KGSL_CONTEXT_INVALID 0xffffffff - -/* - * --- command batch flags --- - * The bits that are linked to a KGSL_CONTEXT equivalent are either legacy - * definitions or bits that are valid for both contexts and cmdbatches. To be - * safe the other 8 bits that are still available in the context field should be - * omitted here in case we need to share - the other bits are available for - * cmdbatch only flags as needed - */ -#define KGSL_CMDBATCH_MEMLIST 0x00000001 -#define KGSL_CMDBATCH_MARKER 0x00000002 -#define KGSL_CMDBATCH_SUBMIT_IB_LIST KGSL_CONTEXT_SUBMIT_IB_LIST /* 0x004 */ -#define KGSL_CMDBATCH_CTX_SWITCH KGSL_CONTEXT_CTX_SWITCH /* 0x008 */ -#define KGSL_CMDBATCH_PROFILING 0x00000010 -#define KGSL_CMDBATCH_PROFILING_KTIME 0x00000020 -#define KGSL_CMDBATCH_END_OF_FRAME KGSL_CONTEXT_END_OF_FRAME /* 0x100 */ -#define KGSL_CMDBATCH_SYNC KGSL_CONTEXT_SYNC /* 0x400 */ -#define KGSL_CMDBATCH_PWR_CONSTRAINT KGSL_CONTEXT_PWR_CONSTRAINT /* 0x800 */ - -/* - * Reserve bits [16:19] and bits [28:31] for possible bits shared between - * contexts and command batches. Update this comment as new flags are added. - */ - -/* - * gpu_command_object flags - these flags communicate the type of command or - * memory object being submitted for a GPU command - */ - -/* Flags for GPU command objects */ -#define KGSL_CMDLIST_IB 0x00000001U -#define KGSL_CMDLIST_CTXTSWITCH_PREAMBLE 0x00000002U -#define KGSL_CMDLIST_IB_PREAMBLE 0x00000004U - -/* Flags for GPU command memory objects */ -#define KGSL_OBJLIST_MEMOBJ 0x00000008U -#define KGSL_OBJLIST_PROFILE 0x00000010U - -/* Flags for GPU command sync points */ -#define KGSL_CMD_SYNCPOINT_TYPE_TIMESTAMP 0 -#define KGSL_CMD_SYNCPOINT_TYPE_FENCE 1 - -/* --- Memory allocation flags --- */ - -/* General allocation hints */ -#define KGSL_MEMFLAGS_SECURE 0x00000008ULL -#define KGSL_MEMFLAGS_GPUREADONLY 0x01000000U -#define KGSL_MEMFLAGS_GPUWRITEONLY 0x02000000U -#define KGSL_MEMFLAGS_FORCE_32BIT 0x100000000ULL - -/* Memory caching hints */ -#define KGSL_CACHEMODE_MASK 0x0C000000U -#define KGSL_CACHEMODE_SHIFT 26 - -#define KGSL_CACHEMODE_WRITECOMBINE 0 -#define KGSL_CACHEMODE_UNCACHED 1 -#define KGSL_CACHEMODE_WRITETHROUGH 2 -#define KGSL_CACHEMODE_WRITEBACK 3 - -#define KGSL_MEMFLAGS_USE_CPU_MAP 0x10000000ULL - -/* Memory types for which allocations are made */ -#define KGSL_MEMTYPE_MASK 0x0000FF00 -#define KGSL_MEMTYPE_SHIFT 8 - -#define KGSL_MEMTYPE_OBJECTANY 0 -#define KGSL_MEMTYPE_FRAMEBUFFER 1 -#define KGSL_MEMTYPE_RENDERBUFFER 2 -#define KGSL_MEMTYPE_ARRAYBUFFER 3 -#define KGSL_MEMTYPE_ELEMENTARRAYBUFFER 4 -#define KGSL_MEMTYPE_VERTEXARRAYBUFFER 5 -#define KGSL_MEMTYPE_TEXTURE 6 -#define KGSL_MEMTYPE_SURFACE 7 -#define KGSL_MEMTYPE_EGL_SURFACE 8 -#define KGSL_MEMTYPE_GL 9 -#define KGSL_MEMTYPE_CL 10 -#define KGSL_MEMTYPE_CL_BUFFER_MAP 11 -#define KGSL_MEMTYPE_CL_BUFFER_NOMAP 12 -#define KGSL_MEMTYPE_CL_IMAGE_MAP 13 -#define KGSL_MEMTYPE_CL_IMAGE_NOMAP 14 -#define KGSL_MEMTYPE_CL_KERNEL_STACK 15 -#define KGSL_MEMTYPE_COMMAND 16 -#define KGSL_MEMTYPE_2D 17 -#define KGSL_MEMTYPE_EGL_IMAGE 18 -#define KGSL_MEMTYPE_EGL_SHADOW 19 -#define KGSL_MEMTYPE_MULTISAMPLE 20 -#define KGSL_MEMTYPE_KERNEL 255 - -/* - * Alignment hint, passed as the power of 2 exponent. - * i.e 4k (2^12) would be 12, 64k (2^16)would be 16. - */ -#define KGSL_MEMALIGN_MASK 0x00FF0000 -#define KGSL_MEMALIGN_SHIFT 16 - -enum kgsl_user_mem_type { - KGSL_USER_MEM_TYPE_PMEM = 0x00000000, - KGSL_USER_MEM_TYPE_ASHMEM = 0x00000001, - KGSL_USER_MEM_TYPE_ADDR = 0x00000002, - KGSL_USER_MEM_TYPE_ION = 0x00000003, - /* - * ION type is retained for backwards compatibilty but Ion buffers are - * dma-bufs so try to use that naming if we can - */ - KGSL_USER_MEM_TYPE_DMABUF = 0x00000003, - KGSL_USER_MEM_TYPE_MAX = 0x00000007, -}; -#define KGSL_MEMFLAGS_USERMEM_MASK 0x000000e0 -#define KGSL_MEMFLAGS_USERMEM_SHIFT 5 - -/* - * Unfortunately, enum kgsl_user_mem_type starts at 0 which does not - * leave a good value for allocated memory. In the flags we use - * 0 to indicate allocated memory and thus need to add 1 to the enum - * values. - */ -#define KGSL_USERMEM_FLAG(x) (((x) + 1) << KGSL_MEMFLAGS_USERMEM_SHIFT) - -#define KGSL_MEMFLAGS_NOT_USERMEM 0 -#define KGSL_MEMFLAGS_USERMEM_PMEM KGSL_USERMEM_FLAG(KGSL_USER_MEM_TYPE_PMEM) -#define KGSL_MEMFLAGS_USERMEM_ASHMEM \ - KGSL_USERMEM_FLAG(KGSL_USER_MEM_TYPE_ASHMEM) -#define KGSL_MEMFLAGS_USERMEM_ADDR KGSL_USERMEM_FLAG(KGSL_USER_MEM_TYPE_ADDR) -#define KGSL_MEMFLAGS_USERMEM_ION KGSL_USERMEM_FLAG(KGSL_USER_MEM_TYPE_ION) - -/* --- generic KGSL flag values --- */ - -#define KGSL_FLAGS_NORMALMODE 0x00000000 -#define KGSL_FLAGS_SAFEMODE 0x00000001 -#define KGSL_FLAGS_INITIALIZED0 0x00000002 -#define KGSL_FLAGS_INITIALIZED 0x00000004 -#define KGSL_FLAGS_STARTED 0x00000008 -#define KGSL_FLAGS_ACTIVE 0x00000010 -#define KGSL_FLAGS_RESERVED0 0x00000020 -#define KGSL_FLAGS_RESERVED1 0x00000040 -#define KGSL_FLAGS_RESERVED2 0x00000080 -#define KGSL_FLAGS_SOFT_RESET 0x00000100 -#define KGSL_FLAGS_PER_CONTEXT_TIMESTAMPS 0x00000200 - -/* Server Side Sync Timeout in milliseconds */ -#define KGSL_SYNCOBJ_SERVER_TIMEOUT 2000 - -/* - * Reset status values for context - */ -enum kgsl_ctx_reset_stat { - KGSL_CTX_STAT_NO_ERROR = 0x00000000, - KGSL_CTX_STAT_GUILTY_CONTEXT_RESET_EXT = 0x00000001, - KGSL_CTX_STAT_INNOCENT_CONTEXT_RESET_EXT = 0x00000002, - KGSL_CTX_STAT_UNKNOWN_CONTEXT_RESET_EXT = 0x00000003 -}; - -#define KGSL_CONVERT_TO_MBPS(val) \ - (val*1000*1000U) - -/* device id */ -enum kgsl_deviceid { - KGSL_DEVICE_3D0 = 0x00000000, - KGSL_DEVICE_MAX -}; - -struct kgsl_devinfo { - - unsigned int device_id; - /* chip revision id - * coreid:8 majorrev:8 minorrev:8 patch:8 - */ - unsigned int chip_id; - unsigned int mmu_enabled; - unsigned long gmem_gpubaseaddr; - /* - * This field contains the adreno revision - * number 200, 205, 220, etc... - */ - unsigned int gpu_id; - size_t gmem_sizebytes; -}; - -/* - * struct kgsl_devmemstore - this structure defines the region of memory - * that can be mmap()ed from this driver. The timestamp fields are volatile - * because they are written by the GPU - * @soptimestamp: Start of pipeline timestamp written by GPU before the - * commands in concern are processed - * @sbz: Unused, kept for 8 byte alignment - * @eoptimestamp: End of pipeline timestamp written by GPU after the - * commands in concern are processed - * @sbz2: Unused, kept for 8 byte alignment - * @preempted: Indicates if the context was preempted - * @sbz3: Unused, kept for 8 byte alignment - * @ref_wait_ts: Timestamp on which to generate interrupt, unused now. - * @sbz4: Unused, kept for 8 byte alignment - * @current_context: The current context the GPU is working on - * @sbz5: Unused, kept for 8 byte alignment - */ -struct kgsl_devmemstore { - volatile unsigned int soptimestamp; - unsigned int sbz; - volatile unsigned int eoptimestamp; - unsigned int sbz2; - volatile unsigned int preempted; - unsigned int sbz3; - volatile unsigned int ref_wait_ts; - unsigned int sbz4; - unsigned int current_context; - unsigned int sbz5; -}; - -#define KGSL_MEMSTORE_OFFSET(ctxt_id, field) \ - ((ctxt_id)*sizeof(struct kgsl_devmemstore) + \ - offsetof(struct kgsl_devmemstore, field)) - -/* timestamp id*/ -enum kgsl_timestamp_type { - KGSL_TIMESTAMP_CONSUMED = 0x00000001, /* start-of-pipeline timestamp */ - KGSL_TIMESTAMP_RETIRED = 0x00000002, /* end-of-pipeline timestamp*/ - KGSL_TIMESTAMP_QUEUED = 0x00000003, -}; - -/* property types - used with kgsl_device_getproperty */ -#define KGSL_PROP_DEVICE_INFO 0x1 -#define KGSL_PROP_DEVICE_SHADOW 0x2 -#define KGSL_PROP_DEVICE_POWER 0x3 -#define KGSL_PROP_SHMEM 0x4 -#define KGSL_PROP_SHMEM_APERTURES 0x5 -#define KGSL_PROP_MMU_ENABLE 0x6 -#define KGSL_PROP_INTERRUPT_WAITS 0x7 -#define KGSL_PROP_VERSION 0x8 -#define KGSL_PROP_GPU_RESET_STAT 0x9 -#define KGSL_PROP_PWRCTRL 0xE -#define KGSL_PROP_PWR_CONSTRAINT 0x12 -#define KGSL_PROP_UCHE_GMEM_VADDR 0x13 -#define KGSL_PROP_SP_GENERIC_MEM 0x14 -#define KGSL_PROP_UCODE_VERSION 0x15 -#define KGSL_PROP_GPMU_VERSION 0x16 -#define KGSL_PROP_DEVICE_BITNESS 0x18 - -struct kgsl_shadowprop { - unsigned long gpuaddr; - size_t size; - unsigned int flags; /* contains KGSL_FLAGS_ values */ -}; - -struct kgsl_version { - unsigned int drv_major; - unsigned int drv_minor; - unsigned int dev_major; - unsigned int dev_minor; -}; - -struct kgsl_sp_generic_mem { - uint64_t local; - uint64_t pvt; -}; - -struct kgsl_ucode_version { - unsigned int pfp; - unsigned int pm4; -}; - -struct kgsl_gpmu_version { - unsigned int major; - unsigned int minor; - unsigned int features; -}; - -/* Performance counter groups */ - -#define KGSL_PERFCOUNTER_GROUP_CP 0x0 -#define KGSL_PERFCOUNTER_GROUP_RBBM 0x1 -#define KGSL_PERFCOUNTER_GROUP_PC 0x2 -#define KGSL_PERFCOUNTER_GROUP_VFD 0x3 -#define KGSL_PERFCOUNTER_GROUP_HLSQ 0x4 -#define KGSL_PERFCOUNTER_GROUP_VPC 0x5 -#define KGSL_PERFCOUNTER_GROUP_TSE 0x6 -#define KGSL_PERFCOUNTER_GROUP_RAS 0x7 -#define KGSL_PERFCOUNTER_GROUP_UCHE 0x8 -#define KGSL_PERFCOUNTER_GROUP_TP 0x9 -#define KGSL_PERFCOUNTER_GROUP_SP 0xA -#define KGSL_PERFCOUNTER_GROUP_RB 0xB -#define KGSL_PERFCOUNTER_GROUP_PWR 0xC -#define KGSL_PERFCOUNTER_GROUP_VBIF 0xD -#define KGSL_PERFCOUNTER_GROUP_VBIF_PWR 0xE -#define KGSL_PERFCOUNTER_GROUP_MH 0xF -#define KGSL_PERFCOUNTER_GROUP_PA_SU 0x10 -#define KGSL_PERFCOUNTER_GROUP_SQ 0x11 -#define KGSL_PERFCOUNTER_GROUP_SX 0x12 -#define KGSL_PERFCOUNTER_GROUP_TCF 0x13 -#define KGSL_PERFCOUNTER_GROUP_TCM 0x14 -#define KGSL_PERFCOUNTER_GROUP_TCR 0x15 -#define KGSL_PERFCOUNTER_GROUP_L2 0x16 -#define KGSL_PERFCOUNTER_GROUP_VSC 0x17 -#define KGSL_PERFCOUNTER_GROUP_CCU 0x18 -#define KGSL_PERFCOUNTER_GROUP_LRZ 0x19 -#define KGSL_PERFCOUNTER_GROUP_CMP 0x1A -#define KGSL_PERFCOUNTER_GROUP_ALWAYSON 0x1B -#define KGSL_PERFCOUNTER_GROUP_SP_PWR 0x1C -#define KGSL_PERFCOUNTER_GROUP_TP_PWR 0x1D -#define KGSL_PERFCOUNTER_GROUP_RB_PWR 0x1E -#define KGSL_PERFCOUNTER_GROUP_CCU_PWR 0x1F -#define KGSL_PERFCOUNTER_GROUP_UCHE_PWR 0x20 -#define KGSL_PERFCOUNTER_GROUP_CP_PWR 0x21 -#define KGSL_PERFCOUNTER_GROUP_GPMU_PWR 0x22 -#define KGSL_PERFCOUNTER_GROUP_ALWAYSON_PWR 0x23 -#define KGSL_PERFCOUNTER_GROUP_MAX 0x24 - -#define KGSL_PERFCOUNTER_NOT_USED 0xFFFFFFFF -#define KGSL_PERFCOUNTER_BROKEN 0xFFFFFFFE - -/* structure holds list of ibs */ -struct kgsl_ibdesc { - unsigned long gpuaddr; - unsigned long __pad; - size_t sizedwords; - unsigned int ctrl; -}; - -/** - * struct kgsl_cmdbatch_profiling_buffer - * @wall_clock_s: Ringbuffer submission time (seconds). - * If KGSL_CMDBATCH_PROFILING_KTIME is set, time is provided - * in kernel clocks, otherwise wall clock time is used. - * @wall_clock_ns: Ringbuffer submission time (nanoseconds). - * If KGSL_CMDBATCH_PROFILING_KTIME is set time is provided - * in kernel clocks, otherwise wall clock time is used. - * @gpu_ticks_queued: GPU ticks at ringbuffer submission - * @gpu_ticks_submitted: GPU ticks when starting cmdbatch execution - * @gpu_ticks_retired: GPU ticks when finishing cmdbatch execution - * - * This structure defines the profiling buffer used to measure cmdbatch - * execution time - */ -struct kgsl_cmdbatch_profiling_buffer { - uint64_t wall_clock_s; - uint64_t wall_clock_ns; - uint64_t gpu_ticks_queued; - uint64_t gpu_ticks_submitted; - uint64_t gpu_ticks_retired; -}; - -/* ioctls */ -#define KGSL_IOC_TYPE 0x09 - -/* get misc info about the GPU - type should be a value from enum kgsl_property_type - value points to a structure that varies based on type - sizebytes is sizeof() that structure - for KGSL_PROP_DEVICE_INFO, use struct kgsl_devinfo - this structure contaings hardware versioning info. - for KGSL_PROP_DEVICE_SHADOW, use struct kgsl_shadowprop - this is used to find mmap() offset and sizes for mapping - struct kgsl_memstore into userspace. -*/ -struct kgsl_device_getproperty { - unsigned int type; - void __user *value; - size_t sizebytes; -}; - -#define IOCTL_KGSL_DEVICE_GETPROPERTY \ - _IOWR(KGSL_IOC_TYPE, 0x2, struct kgsl_device_getproperty) - -/* IOCTL_KGSL_DEVICE_READ (0x3) - removed 03/2012 - */ - -/* block until the GPU has executed past a given timestamp - * timeout is in milliseconds. - */ -struct kgsl_device_waittimestamp { - unsigned int timestamp; - unsigned int timeout; -}; - -#define IOCTL_KGSL_DEVICE_WAITTIMESTAMP \ - _IOW(KGSL_IOC_TYPE, 0x6, struct kgsl_device_waittimestamp) - -struct kgsl_device_waittimestamp_ctxtid { - unsigned int context_id; - unsigned int timestamp; - unsigned int timeout; -}; - -#define IOCTL_KGSL_DEVICE_WAITTIMESTAMP_CTXTID \ - _IOW(KGSL_IOC_TYPE, 0x7, struct kgsl_device_waittimestamp_ctxtid) - -/* DEPRECATED: issue indirect commands to the GPU. - * drawctxt_id must have been created with IOCTL_KGSL_DRAWCTXT_CREATE - * ibaddr and sizedwords must specify a subset of a buffer created - * with IOCTL_KGSL_SHAREDMEM_FROM_PMEM - * flags may be a mask of KGSL_CONTEXT_ values - * timestamp is a returned counter value which can be passed to - * other ioctls to determine when the commands have been executed by - * the GPU. - * - * This fucntion is deprecated - consider using IOCTL_KGSL_SUBMIT_COMMANDS - * instead - */ -struct kgsl_ringbuffer_issueibcmds { - unsigned int drawctxt_id; - unsigned long ibdesc_addr; - unsigned int numibs; - unsigned int timestamp; /*output param */ - unsigned int flags; -}; - -#define IOCTL_KGSL_RINGBUFFER_ISSUEIBCMDS \ - _IOWR(KGSL_IOC_TYPE, 0x10, struct kgsl_ringbuffer_issueibcmds) - -/* read the most recently executed timestamp value - * type should be a value from enum kgsl_timestamp_type - */ -struct kgsl_cmdstream_readtimestamp { - unsigned int type; - unsigned int timestamp; /*output param */ -}; - -#define IOCTL_KGSL_CMDSTREAM_READTIMESTAMP_OLD \ - _IOR(KGSL_IOC_TYPE, 0x11, struct kgsl_cmdstream_readtimestamp) - -#define IOCTL_KGSL_CMDSTREAM_READTIMESTAMP \ - _IOWR(KGSL_IOC_TYPE, 0x11, struct kgsl_cmdstream_readtimestamp) - -/* free memory when the GPU reaches a given timestamp. - * gpuaddr specify a memory region created by a - * IOCTL_KGSL_SHAREDMEM_FROM_PMEM call - * type should be a value from enum kgsl_timestamp_type - */ -struct kgsl_cmdstream_freememontimestamp { - unsigned long gpuaddr; - unsigned int type; - unsigned int timestamp; -}; - -#define IOCTL_KGSL_CMDSTREAM_FREEMEMONTIMESTAMP \ - _IOW(KGSL_IOC_TYPE, 0x12, struct kgsl_cmdstream_freememontimestamp) - -/* Previous versions of this header had incorrectly defined - IOCTL_KGSL_CMDSTREAM_FREEMEMONTIMESTAMP as a read-only ioctl instead - of a write only ioctl. To ensure binary compatability, the following - #define will be used to intercept the incorrect ioctl -*/ - -#define IOCTL_KGSL_CMDSTREAM_FREEMEMONTIMESTAMP_OLD \ - _IOR(KGSL_IOC_TYPE, 0x12, struct kgsl_cmdstream_freememontimestamp) - -/* create a draw context, which is used to preserve GPU state. - * The flags field may contain a mask KGSL_CONTEXT_* values - */ -struct kgsl_drawctxt_create { - unsigned int flags; - unsigned int drawctxt_id; /*output param */ -}; - -#define IOCTL_KGSL_DRAWCTXT_CREATE \ - _IOWR(KGSL_IOC_TYPE, 0x13, struct kgsl_drawctxt_create) - -/* destroy a draw context */ -struct kgsl_drawctxt_destroy { - unsigned int drawctxt_id; -}; - -#define IOCTL_KGSL_DRAWCTXT_DESTROY \ - _IOW(KGSL_IOC_TYPE, 0x14, struct kgsl_drawctxt_destroy) - -/* add a block of pmem, fb, ashmem or user allocated address - * into the GPU address space */ -struct kgsl_map_user_mem { - int fd; - unsigned long gpuaddr; /*output param */ - size_t len; - size_t offset; - unsigned long hostptr; /*input param */ - enum kgsl_user_mem_type memtype; - unsigned int flags; -}; - -#define IOCTL_KGSL_MAP_USER_MEM \ - _IOWR(KGSL_IOC_TYPE, 0x15, struct kgsl_map_user_mem) - -struct kgsl_cmdstream_readtimestamp_ctxtid { - unsigned int context_id; - unsigned int type; - unsigned int timestamp; /*output param */ -}; - -#define IOCTL_KGSL_CMDSTREAM_READTIMESTAMP_CTXTID \ - _IOWR(KGSL_IOC_TYPE, 0x16, struct kgsl_cmdstream_readtimestamp_ctxtid) - -struct kgsl_cmdstream_freememontimestamp_ctxtid { - unsigned int context_id; - unsigned long gpuaddr; - unsigned int type; - unsigned int timestamp; -}; - -#define IOCTL_KGSL_CMDSTREAM_FREEMEMONTIMESTAMP_CTXTID \ - _IOW(KGSL_IOC_TYPE, 0x17, \ - struct kgsl_cmdstream_freememontimestamp_ctxtid) - -/* add a block of pmem or fb into the GPU address space */ -struct kgsl_sharedmem_from_pmem { - int pmem_fd; - unsigned long gpuaddr; /*output param */ - unsigned int len; - unsigned int offset; -}; - -#define IOCTL_KGSL_SHAREDMEM_FROM_PMEM \ - _IOWR(KGSL_IOC_TYPE, 0x20, struct kgsl_sharedmem_from_pmem) - -/* remove memory from the GPU's address space */ -struct kgsl_sharedmem_free { - unsigned long gpuaddr; -}; - -#define IOCTL_KGSL_SHAREDMEM_FREE \ - _IOW(KGSL_IOC_TYPE, 0x21, struct kgsl_sharedmem_free) - -struct kgsl_cff_user_event { - unsigned char cff_opcode; - unsigned int op1; - unsigned int op2; - unsigned int op3; - unsigned int op4; - unsigned int op5; - unsigned int __pad[2]; -}; - -#define IOCTL_KGSL_CFF_USER_EVENT \ - _IOW(KGSL_IOC_TYPE, 0x31, struct kgsl_cff_user_event) - -struct kgsl_gmem_desc { - unsigned int x; - unsigned int y; - unsigned int width; - unsigned int height; - unsigned int pitch; -}; - -struct kgsl_buffer_desc { - void *hostptr; - unsigned long gpuaddr; - int size; - unsigned int format; - unsigned int pitch; - unsigned int enabled; -}; - -struct kgsl_bind_gmem_shadow { - unsigned int drawctxt_id; - struct kgsl_gmem_desc gmem_desc; - unsigned int shadow_x; - unsigned int shadow_y; - struct kgsl_buffer_desc shadow_buffer; - unsigned int buffer_id; -}; - -#define IOCTL_KGSL_DRAWCTXT_BIND_GMEM_SHADOW \ - _IOW(KGSL_IOC_TYPE, 0x22, struct kgsl_bind_gmem_shadow) - -/* add a block of memory into the GPU address space */ - -/* - * IOCTL_KGSL_SHAREDMEM_FROM_VMALLOC deprecated 09/2012 - * use IOCTL_KGSL_GPUMEM_ALLOC instead - */ - -struct kgsl_sharedmem_from_vmalloc { - unsigned long gpuaddr; /*output param */ - unsigned int hostptr; - unsigned int flags; -}; - -#define IOCTL_KGSL_SHAREDMEM_FROM_VMALLOC \ - _IOWR(KGSL_IOC_TYPE, 0x23, struct kgsl_sharedmem_from_vmalloc) - -/* - * This is being deprecated in favor of IOCTL_KGSL_GPUMEM_CACHE_SYNC which - * supports both directions (flush and invalidate). This code will still - * work, but by definition it will do a flush of the cache which might not be - * what you want to have happen on a buffer following a GPU operation. It is - * safer to go with IOCTL_KGSL_GPUMEM_CACHE_SYNC - */ - -#define IOCTL_KGSL_SHAREDMEM_FLUSH_CACHE \ - _IOW(KGSL_IOC_TYPE, 0x24, struct kgsl_sharedmem_free) - -struct kgsl_drawctxt_set_bin_base_offset { - unsigned int drawctxt_id; - unsigned int offset; -}; - -#define IOCTL_KGSL_DRAWCTXT_SET_BIN_BASE_OFFSET \ - _IOW(KGSL_IOC_TYPE, 0x25, struct kgsl_drawctxt_set_bin_base_offset) - -enum kgsl_cmdwindow_type { - KGSL_CMDWINDOW_MIN = 0x00000000, - KGSL_CMDWINDOW_2D = 0x00000000, - KGSL_CMDWINDOW_3D = 0x00000001, /* legacy */ - KGSL_CMDWINDOW_MMU = 0x00000002, - KGSL_CMDWINDOW_ARBITER = 0x000000FF, - KGSL_CMDWINDOW_MAX = 0x000000FF, -}; - -/* write to the command window */ -struct kgsl_cmdwindow_write { - enum kgsl_cmdwindow_type target; - unsigned int addr; - unsigned int data; -}; - -#define IOCTL_KGSL_CMDWINDOW_WRITE \ - _IOW(KGSL_IOC_TYPE, 0x2e, struct kgsl_cmdwindow_write) - -struct kgsl_gpumem_alloc { - unsigned long gpuaddr; /* output param */ - size_t size; - unsigned int flags; -}; - -#define IOCTL_KGSL_GPUMEM_ALLOC \ - _IOWR(KGSL_IOC_TYPE, 0x2f, struct kgsl_gpumem_alloc) - -struct kgsl_cff_syncmem { - unsigned long gpuaddr; - size_t len; - unsigned int __pad[2]; /* For future binary compatibility */ -}; - -#define IOCTL_KGSL_CFF_SYNCMEM \ - _IOW(KGSL_IOC_TYPE, 0x30, struct kgsl_cff_syncmem) - -/* - * A timestamp event allows the user space to register an action following an - * expired timestamp. Note IOCTL_KGSL_TIMESTAMP_EVENT has been redefined to - * _IOWR to support fences which need to return a fd for the priv parameter. - */ - -struct kgsl_timestamp_event { - int type; /* Type of event (see list below) */ - unsigned int timestamp; /* Timestamp to trigger event on */ - unsigned int context_id; /* Context for the timestamp */ - void __user *priv; /* Pointer to the event specific blob */ - size_t len; /* Size of the event specific blob */ -}; - -#define IOCTL_KGSL_TIMESTAMP_EVENT_OLD \ - _IOW(KGSL_IOC_TYPE, 0x31, struct kgsl_timestamp_event) - -/* A genlock timestamp event releases an existing lock on timestamp expire */ - -#define KGSL_TIMESTAMP_EVENT_GENLOCK 1 - -struct kgsl_timestamp_event_genlock { - int handle; /* Handle of the genlock lock to release */ -}; - -/* A fence timestamp event releases an existing lock on timestamp expire */ - -#define KGSL_TIMESTAMP_EVENT_FENCE 2 - -struct kgsl_timestamp_event_fence { - int fence_fd; /* Fence to signal */ -}; - -/* - * Set a property within the kernel. Uses the same structure as - * IOCTL_KGSL_GETPROPERTY - */ - -#define IOCTL_KGSL_SETPROPERTY \ - _IOW(KGSL_IOC_TYPE, 0x32, struct kgsl_device_getproperty) - -#define IOCTL_KGSL_TIMESTAMP_EVENT \ - _IOWR(KGSL_IOC_TYPE, 0x33, struct kgsl_timestamp_event) - -/** - * struct kgsl_gpumem_alloc_id - argument to IOCTL_KGSL_GPUMEM_ALLOC_ID - * @id: returned id value for this allocation. - * @flags: mask of KGSL_MEM* values requested and actual flags on return. - * @size: requested size of the allocation and actual size on return. - * @mmapsize: returned size to pass to mmap() which may be larger than 'size' - * @gpuaddr: returned GPU address for the allocation - * - * Allocate memory for access by the GPU. The flags and size fields are echoed - * back by the kernel, so that the caller can know if the request was - * adjusted. - * - * Supported flags: - * KGSL_MEMFLAGS_GPUREADONLY: the GPU will be unable to write to the buffer - * KGSL_MEMTYPE*: usage hint for debugging aid - * KGSL_MEMALIGN*: alignment hint, may be ignored or adjusted by the kernel. - * KGSL_MEMFLAGS_USE_CPU_MAP: If set on call and return, the returned GPU - * address will be 0. Calling mmap() will set the GPU address. - */ -struct kgsl_gpumem_alloc_id { - unsigned int id; - unsigned int flags; - size_t size; - size_t mmapsize; - unsigned long gpuaddr; -/* private: reserved for future use*/ - unsigned long __pad[2]; -}; - -#define IOCTL_KGSL_GPUMEM_ALLOC_ID \ - _IOWR(KGSL_IOC_TYPE, 0x34, struct kgsl_gpumem_alloc_id) - -/** - * struct kgsl_gpumem_free_id - argument to IOCTL_KGSL_GPUMEM_FREE_ID - * @id: GPU allocation id to free - * - * Free an allocation by id, in case a GPU address has not been assigned or - * is unknown. Freeing an allocation by id with this ioctl or by GPU address - * with IOCTL_KGSL_SHAREDMEM_FREE are equivalent. - */ -struct kgsl_gpumem_free_id { - unsigned int id; -/* private: reserved for future use*/ - unsigned int __pad; -}; - -#define IOCTL_KGSL_GPUMEM_FREE_ID \ - _IOWR(KGSL_IOC_TYPE, 0x35, struct kgsl_gpumem_free_id) - -/** - * struct kgsl_gpumem_get_info - argument to IOCTL_KGSL_GPUMEM_GET_INFO - * @gpuaddr: GPU address to query. Also set on return. - * @id: GPU allocation id to query. Also set on return. - * @flags: returned mask of KGSL_MEM* values. - * @size: returned size of the allocation. - * @mmapsize: returned size to pass mmap(), which may be larger than 'size' - * @useraddr: returned address of the userspace mapping for this buffer - * - * This ioctl allows querying of all user visible attributes of an existing - * allocation, by either the GPU address or the id returned by a previous - * call to IOCTL_KGSL_GPUMEM_ALLOC_ID. Legacy allocation ioctls may not - * return all attributes so this ioctl can be used to look them up if needed. - * - */ -struct kgsl_gpumem_get_info { - unsigned long gpuaddr; - unsigned int id; - unsigned int flags; - size_t size; - size_t mmapsize; - unsigned long useraddr; -/* private: reserved for future use*/ - unsigned long __pad[4]; -}; - -#define IOCTL_KGSL_GPUMEM_GET_INFO\ - _IOWR(KGSL_IOC_TYPE, 0x36, struct kgsl_gpumem_get_info) - -/** - * struct kgsl_gpumem_sync_cache - argument to IOCTL_KGSL_GPUMEM_SYNC_CACHE - * @gpuaddr: GPU address of the buffer to sync. - * @id: id of the buffer to sync. Either gpuaddr or id is sufficient. - * @op: a mask of KGSL_GPUMEM_CACHE_* values - * @offset: offset into the buffer - * @length: number of bytes starting from offset to perform - * the cache operation on - * - * Sync the L2 cache for memory headed to and from the GPU - this replaces - * KGSL_SHAREDMEM_FLUSH_CACHE since it can handle cache management for both - * directions - * - */ -struct kgsl_gpumem_sync_cache { - unsigned long gpuaddr; - unsigned int id; - unsigned int op; - size_t offset; - size_t length; -}; - -#define KGSL_GPUMEM_CACHE_CLEAN (1 << 0) -#define KGSL_GPUMEM_CACHE_TO_GPU KGSL_GPUMEM_CACHE_CLEAN - -#define KGSL_GPUMEM_CACHE_INV (1 << 1) -#define KGSL_GPUMEM_CACHE_FROM_GPU KGSL_GPUMEM_CACHE_INV - -#define KGSL_GPUMEM_CACHE_FLUSH \ - (KGSL_GPUMEM_CACHE_CLEAN | KGSL_GPUMEM_CACHE_INV) - -/* Flag to ensure backwards compatibility of kgsl_gpumem_sync_cache struct */ -#define KGSL_GPUMEM_CACHE_RANGE (1 << 31U) - -#define IOCTL_KGSL_GPUMEM_SYNC_CACHE \ - _IOW(KGSL_IOC_TYPE, 0x37, struct kgsl_gpumem_sync_cache) - -/** - * struct kgsl_perfcounter_get - argument to IOCTL_KGSL_PERFCOUNTER_GET - * @groupid: Performance counter group ID - * @countable: Countable to select within the group - * @offset: Return offset of the reserved LO counter - * @offset_hi: Return offset of the reserved HI counter - * - * Get an available performance counter from a specified groupid. The offset - * of the performance counter will be returned after successfully assigning - * the countable to the counter for the specified group. An error will be - * returned and an offset of 0 if the groupid is invalid or there are no - * more counters left. After successfully getting a perfcounter, the user - * must call kgsl_perfcounter_put(groupid, contable) when finished with - * the perfcounter to clear up perfcounter resources. - * - */ -struct kgsl_perfcounter_get { - unsigned int groupid; - unsigned int countable; - unsigned int offset; - unsigned int offset_hi; -/* private: reserved for future use */ - unsigned int __pad; /* For future binary compatibility */ -}; - -#define IOCTL_KGSL_PERFCOUNTER_GET \ - _IOWR(KGSL_IOC_TYPE, 0x38, struct kgsl_perfcounter_get) - -/** - * struct kgsl_perfcounter_put - argument to IOCTL_KGSL_PERFCOUNTER_PUT - * @groupid: Performance counter group ID - * @countable: Countable to release within the group - * - * Put an allocated performance counter to allow others to have access to the - * resource that was previously taken. This is only to be called after - * successfully getting a performance counter from kgsl_perfcounter_get(). - * - */ -struct kgsl_perfcounter_put { - unsigned int groupid; - unsigned int countable; -/* private: reserved for future use */ - unsigned int __pad[2]; /* For future binary compatibility */ -}; - -#define IOCTL_KGSL_PERFCOUNTER_PUT \ - _IOW(KGSL_IOC_TYPE, 0x39, struct kgsl_perfcounter_put) - -/** - * struct kgsl_perfcounter_query - argument to IOCTL_KGSL_PERFCOUNTER_QUERY - * @groupid: Performance counter group ID - * @countable: Return active countables array - * @size: Size of active countables array - * @max_counters: Return total number counters for the group ID - * - * Query the available performance counters given a groupid. The array - * *countables is used to return the current active countables in counters. - * The size of the array is passed in so the kernel will only write at most - * size or counter->size for the group id. The total number of available - * counters for the group ID is returned in max_counters. - * If the array or size passed in are invalid, then only the maximum number - * of counters will be returned, no data will be written to *countables. - * If the groupid is invalid an error code will be returned. - * - */ -struct kgsl_perfcounter_query { - unsigned int groupid; - /* Array to return the current countable for up to size counters */ - unsigned int __user *countables; - unsigned int count; - unsigned int max_counters; -/* private: reserved for future use */ - unsigned int __pad[2]; /* For future binary compatibility */ -}; - -#define IOCTL_KGSL_PERFCOUNTER_QUERY \ - _IOWR(KGSL_IOC_TYPE, 0x3A, struct kgsl_perfcounter_query) - -/** - * struct kgsl_perfcounter_query - argument to IOCTL_KGSL_PERFCOUNTER_QUERY - * @groupid: Performance counter group IDs - * @countable: Performance counter countable IDs - * @value: Return performance counter reads - * @size: Size of all arrays (groupid/countable pair and return value) - * - * Read in the current value of a performance counter given by the groupid - * and countable. - * - */ - -struct kgsl_perfcounter_read_group { - unsigned int groupid; - unsigned int countable; - unsigned long long value; -}; - -struct kgsl_perfcounter_read { - struct kgsl_perfcounter_read_group __user *reads; - unsigned int count; -/* private: reserved for future use */ - unsigned int __pad[2]; /* For future binary compatibility */ -}; - -#define IOCTL_KGSL_PERFCOUNTER_READ \ - _IOWR(KGSL_IOC_TYPE, 0x3B, struct kgsl_perfcounter_read) -/* - * struct kgsl_gpumem_sync_cache_bulk - argument to - * IOCTL_KGSL_GPUMEM_SYNC_CACHE_BULK - * @id_list: list of GPU buffer ids of the buffers to sync - * @count: number of GPU buffer ids in id_list - * @op: a mask of KGSL_GPUMEM_CACHE_* values - * - * Sync the cache for memory headed to and from the GPU. Certain - * optimizations can be made on the cache operation based on the total - * size of the working set of memory to be managed. - */ -struct kgsl_gpumem_sync_cache_bulk { - unsigned int __user *id_list; - unsigned int count; - unsigned int op; -/* private: reserved for future use */ - unsigned int __pad[2]; /* For future binary compatibility */ -}; - -#define IOCTL_KGSL_GPUMEM_SYNC_CACHE_BULK \ - _IOWR(KGSL_IOC_TYPE, 0x3C, struct kgsl_gpumem_sync_cache_bulk) - -/* - * struct kgsl_cmd_syncpoint_timestamp - * @context_id: ID of a KGSL context - * @timestamp: GPU timestamp - * - * This structure defines a syncpoint comprising a context/timestamp pair. A - * list of these may be passed by IOCTL_KGSL_SUBMIT_COMMANDS to define - * dependencies that must be met before the command can be submitted to the - * hardware - */ -struct kgsl_cmd_syncpoint_timestamp { - unsigned int context_id; - unsigned int timestamp; -}; - -struct kgsl_cmd_syncpoint_fence { - int fd; -}; - -/** - * struct kgsl_cmd_syncpoint - Define a sync point for a command batch - * @type: type of sync point defined here - * @priv: Pointer to the type specific buffer - * @size: Size of the type specific buffer - * - * This structure contains pointers defining a specific command sync point. - * The pointer and size should point to a type appropriate structure. - */ -struct kgsl_cmd_syncpoint { - int type; - void __user *priv; - size_t size; -}; - -/* Flag to indicate that the cmdlist may contain memlists */ -#define KGSL_IBDESC_MEMLIST 0x1 - -/* Flag to point out the cmdbatch profiling buffer in the memlist */ -#define KGSL_IBDESC_PROFILING_BUFFER 0x2 - -/** - * struct kgsl_submit_commands - Argument to IOCTL_KGSL_SUBMIT_COMMANDS - * @context_id: KGSL context ID that owns the commands - * @flags: - * @cmdlist: User pointer to a list of kgsl_ibdesc structures - * @numcmds: Number of commands listed in cmdlist - * @synclist: User pointer to a list of kgsl_cmd_syncpoint structures - * @numsyncs: Number of sync points listed in synclist - * @timestamp: On entry the a user defined timestamp, on exist the timestamp - * assigned to the command batch - * - * This structure specifies a command to send to the GPU hardware. This is - * similar to kgsl_issueibcmds expect that it doesn't support the legacy way to - * submit IB lists and it adds sync points to block the IB until the - * dependencies are satisified. This entry point is the new and preferred way - * to submit commands to the GPU. The memory list can be used to specify all - * memory that is referrenced in the current set of commands. - */ - -struct kgsl_submit_commands { - unsigned int context_id; - unsigned int flags; - struct kgsl_ibdesc __user *cmdlist; - unsigned int numcmds; - struct kgsl_cmd_syncpoint __user *synclist; - unsigned int numsyncs; - unsigned int timestamp; -/* private: reserved for future use */ - unsigned int __pad[4]; -}; - -#define IOCTL_KGSL_SUBMIT_COMMANDS \ - _IOWR(KGSL_IOC_TYPE, 0x3D, struct kgsl_submit_commands) - -/** - * struct kgsl_device_constraint - device constraint argument - * @context_id: KGSL context ID - * @type: type of constraint i.e pwrlevel/none - * @data: constraint data - * @size: size of the constraint data - */ -struct kgsl_device_constraint { - unsigned int type; - unsigned int context_id; - void __user *data; - size_t size; -}; - -/* Constraint Type*/ -#define KGSL_CONSTRAINT_NONE 0 -#define KGSL_CONSTRAINT_PWRLEVEL 1 - -/* PWRLEVEL constraint level*/ -/* set to min frequency */ -#define KGSL_CONSTRAINT_PWR_MIN 0 -/* set to max frequency */ -#define KGSL_CONSTRAINT_PWR_MAX 1 - -struct kgsl_device_constraint_pwrlevel { - unsigned int level; -}; - -/** - * struct kgsl_syncsource_create - Argument to IOCTL_KGSL_SYNCSOURCE_CREATE - * @id: returned id for the syncsource that was created. - * - * This ioctl creates a userspace sync timeline. - */ - -struct kgsl_syncsource_create { - unsigned int id; -/* private: reserved for future use */ - unsigned int __pad[3]; -}; - -#define IOCTL_KGSL_SYNCSOURCE_CREATE \ - _IOWR(KGSL_IOC_TYPE, 0x40, struct kgsl_syncsource_create) - -/** - * struct kgsl_syncsource_destroy - Argument to IOCTL_KGSL_SYNCSOURCE_DESTROY - * @id: syncsource id to destroy - * - * This ioctl creates a userspace sync timeline. - */ - -struct kgsl_syncsource_destroy { - unsigned int id; -/* private: reserved for future use */ - unsigned int __pad[3]; -}; - -#define IOCTL_KGSL_SYNCSOURCE_DESTROY \ - _IOWR(KGSL_IOC_TYPE, 0x41, struct kgsl_syncsource_destroy) - -/** - * struct kgsl_syncsource_create_fence - Argument to - * IOCTL_KGSL_SYNCSOURCE_CREATE_FENCE - * @id: syncsource id - * @fence_fd: returned sync_fence fd - * - * Create a fence that may be signaled by userspace by calling - * IOCTL_KGSL_SYNCSOURCE_SIGNAL_FENCE. There are no order dependencies between - * these fences. - */ -struct kgsl_syncsource_create_fence { - unsigned int id; - int fence_fd; -/* private: reserved for future use */ - unsigned int __pad[4]; -}; - -/** - * struct kgsl_syncsource_signal_fence - Argument to - * IOCTL_KGSL_SYNCSOURCE_SIGNAL_FENCE - * @id: syncsource id - * @fence_fd: sync_fence fd to signal - * - * Signal a fence that was created by a IOCTL_KGSL_SYNCSOURCE_CREATE_FENCE - * call using the same syncsource id. This allows a fence to be shared - * to other processes but only signaled by the process owning the fd - * used to create the fence. - */ -#define IOCTL_KGSL_SYNCSOURCE_CREATE_FENCE \ - _IOWR(KGSL_IOC_TYPE, 0x42, struct kgsl_syncsource_create_fence) - -struct kgsl_syncsource_signal_fence { - unsigned int id; - int fence_fd; -/* private: reserved for future use */ - unsigned int __pad[4]; -}; - -#define IOCTL_KGSL_SYNCSOURCE_SIGNAL_FENCE \ - _IOWR(KGSL_IOC_TYPE, 0x43, struct kgsl_syncsource_signal_fence) - -/** - * struct kgsl_cff_sync_gpuobj - Argument to IOCTL_KGSL_CFF_SYNC_GPUOBJ - * @offset: Offset into the GPU object to sync - * @length: Number of bytes to sync - * @id: ID of the GPU object to sync - */ -struct kgsl_cff_sync_gpuobj { - uint64_t offset; - uint64_t length; - unsigned int id; -}; - -#define IOCTL_KGSL_CFF_SYNC_GPUOBJ \ - _IOW(KGSL_IOC_TYPE, 0x44, struct kgsl_cff_sync_gpuobj) - -/** - * struct kgsl_gpuobj_alloc - Argument to IOCTL_KGSL_GPUOBJ_ALLOC - * @size: Size in bytes of the object to allocate - * @flags: mask of KGSL_MEMFLAG_* bits - * @va_len: Size in bytes of the virtual region to allocate - * @mmapsize: Returns the mmap() size of the object - * @id: Returns the GPU object ID of the new object - * @metadata_len: Length of the metdata to copy from the user - * @metadata: Pointer to the user specified metadata to store for the object - */ -struct kgsl_gpuobj_alloc { - uint64_t size; - uint64_t flags; - uint64_t va_len; - uint64_t mmapsize; - unsigned int id; - unsigned int metadata_len; - uint64_t metadata; -}; - -/* Let the user know that this header supports the gpuobj metadata */ -#define KGSL_GPUOBJ_ALLOC_METADATA_MAX 64 - -#define IOCTL_KGSL_GPUOBJ_ALLOC \ - _IOWR(KGSL_IOC_TYPE, 0x45, struct kgsl_gpuobj_alloc) - -/** - * struct kgsl_gpuobj_free - Argument to IOCTL_KGLS_GPUOBJ_FREE - * @flags: Mask of: KGSL_GUPOBJ_FREE_ON_EVENT - * @priv: Pointer to the private object if KGSL_GPUOBJ_FREE_ON_EVENT is - * specified - * @id: ID of the GPU object to free - * @type: If KGSL_GPUOBJ_FREE_ON_EVENT is specified, the type of asynchronous - * event to free on - * @len: Length of the data passed in priv - */ -struct kgsl_gpuobj_free { - uint64_t flags; - uint64_t __user priv; - unsigned int id; - unsigned int type; - unsigned int len; -}; - -#define KGSL_GPUOBJ_FREE_ON_EVENT 1 - -#define KGSL_GPU_EVENT_TIMESTAMP 1 -#define KGSL_GPU_EVENT_FENCE 2 - -/** - * struct kgsl_gpu_event_timestamp - Specifies a timestamp event to free a GPU - * object on - * @context_id: ID of the timestamp event to wait for - * @timestamp: Timestamp of the timestamp event to wait for - */ -struct kgsl_gpu_event_timestamp { - unsigned int context_id; - unsigned int timestamp; -}; - -/** - * struct kgsl_gpu_event_fence - Specifies a fence ID to to free a GPU object on - * @fd: File descriptor for the fence - */ -struct kgsl_gpu_event_fence { - int fd; -}; - -#define IOCTL_KGSL_GPUOBJ_FREE \ - _IOW(KGSL_IOC_TYPE, 0x46, struct kgsl_gpuobj_free) - -/** - * struct kgsl_gpuobj_info - argument to IOCTL_KGSL_GPUOBJ_INFO - * @gpuaddr: GPU address of the object - * @flags: Current flags for the object - * @size: Size of the object - * @va_len: VA size of the object - * @va_addr: Virtual address of the object (if it is mapped) - * id - GPU object ID of the object to query - */ -struct kgsl_gpuobj_info { - uint64_t gpuaddr; - uint64_t flags; - uint64_t size; - uint64_t va_len; - uint64_t va_addr; - unsigned int id; -}; - -#define IOCTL_KGSL_GPUOBJ_INFO \ - _IOWR(KGSL_IOC_TYPE, 0x47, struct kgsl_gpuobj_info) - -/** - * struct kgsl_gpuobj_import - argument to IOCTL_KGSL_GPUOBJ_IMPORT - * @priv: Pointer to the private data for the import type - * @priv_len: Length of the private data - * @flags: Mask of KGSL_MEMFLAG_ flags - * @type: Type of the import (KGSL_USER_MEM_TYPE_*) - * @id: Returns the ID of the new GPU object - */ -struct kgsl_gpuobj_import { - uint64_t __user priv; - uint64_t priv_len; - uint64_t flags; - unsigned int type; - unsigned int id; -}; - -/** - * struct kgsl_gpuobj_import_dma_buf - import a dmabuf object - * @fd: File descriptor for the dma-buf object - */ -struct kgsl_gpuobj_import_dma_buf { - int fd; -}; - -/** - * struct kgsl_gpuobj_import_useraddr - import an object based on a useraddr - * @virtaddr: Virtual address of the object to import - */ -struct kgsl_gpuobj_import_useraddr { - uint64_t virtaddr; -}; - -#define IOCTL_KGSL_GPUOBJ_IMPORT \ - _IOWR(KGSL_IOC_TYPE, 0x48, struct kgsl_gpuobj_import) - -/** - * struct kgsl_gpuobj_sync_obj - Individual GPU object to sync - * @offset: Offset within the GPU object to sync - * @length: Number of bytes to sync - * @id: ID of the GPU object to sync - * @op: Cache operation to execute - */ - -struct kgsl_gpuobj_sync_obj { - uint64_t offset; - uint64_t length; - unsigned int id; - unsigned int op; -}; - -/** - * struct kgsl_gpuobj_sync - Argument for IOCTL_KGSL_GPUOBJ_SYNC - * @objs: Pointer to an array of kgsl_gpuobj_sync_obj structs - * @obj_len: Size of each item in the array - * @count: Number of items in the array - */ - -struct kgsl_gpuobj_sync { - uint64_t __user objs; - unsigned int obj_len; - unsigned int count; -}; - -#define IOCTL_KGSL_GPUOBJ_SYNC \ - _IOW(KGSL_IOC_TYPE, 0x49, struct kgsl_gpuobj_sync) - -/** - * struct kgsl_command_object - GPU command object - * @offset: GPU address offset of the object - * @gpuaddr: GPU address of the object - * @size: Size of the object - * @flags: Current flags for the object - * @id - GPU command object ID - */ -struct kgsl_command_object { - uint64_t offset; - uint64_t gpuaddr; - uint64_t size; - unsigned int flags; - unsigned int id; -}; - -/** - * struct kgsl_command_syncpoint - GPU syncpoint object - * @priv: Pointer to the type specific buffer - * @size: Size of the type specific buffer - * @type: type of sync point defined here - */ -struct kgsl_command_syncpoint { - uint64_t __user priv; - uint64_t size; - unsigned int type; -}; - -/** - * struct kgsl_command_object - Argument for IOCTL_KGSL_GPU_COMMAND - * @flags: Current flags for the object - * @cmdlist: List of kgsl_command_objects for submission - * @cmd_size: Size of kgsl_command_objects structure - * @numcmds: Number of kgsl_command_objects in command list - * @objlist: List of kgsl_command_objects for tracking - * @obj_size: Size of kgsl_command_objects structure - * @numobjs: Number of kgsl_command_objects in object list - * @synclist: List of kgsl_command_syncpoints - * @sync_size: Size of kgsl_command_syncpoint structure - * @numsyncs: Number of kgsl_command_syncpoints in syncpoint list - * @context_id: Context ID submittin ghte kgsl_gpu_command - * @timestamp: Timestamp for the submitted commands - */ -struct kgsl_gpu_command { - uint64_t flags; - uint64_t __user cmdlist; - unsigned int cmdsize; - unsigned int numcmds; - uint64_t __user objlist; - unsigned int objsize; - unsigned int numobjs; - uint64_t __user synclist; - unsigned int syncsize; - unsigned int numsyncs; - unsigned int context_id; - unsigned int timestamp; -}; - -#define IOCTL_KGSL_GPU_COMMAND \ - _IOWR(KGSL_IOC_TYPE, 0x4A, struct kgsl_gpu_command) - -/** - * struct kgsl_preemption_counters_query - argument to - * IOCTL_KGSL_PREEMPTIONCOUNTER_QUERY - * @counters: Return preemption counters array - * @size_user: Size allocated by userspace - * @size_priority_level: Size of preemption counters for each - * priority level - * @max_priority_level: Return max number of priority levels - * - * Query the available preemption counters. The array counters - * is used to return preemption counters. The size of the array - * is passed in so the kernel will only write at most size_user - * or max available preemption counters. The total number of - * preemption counters is returned in max_priority_level. If the - * array or size passed in are invalid, then an error is - * returned back. - */ -struct kgsl_preemption_counters_query { - uint64_t __user counters; - unsigned int size_user; - unsigned int size_priority_level; - unsigned int max_priority_level; -}; - -#define IOCTL_KGSL_PREEMPTIONCOUNTER_QUERY \ - _IOWR(KGSL_IOC_TYPE, 0x4B, struct kgsl_preemption_counters_query) - -/** - * struct kgsl_gpuobj_set_info - argument for IOCTL_KGSL_GPUOBJ_SET_INFO - * @flags: Flags to indicate which paramaters to change - * @metadata: If KGSL_GPUOBJ_SET_INFO_METADATA is set, a pointer to the new - * metadata - * @id: GPU memory object ID to change - * @metadata_len: If KGSL_GPUOBJ_SET_INFO_METADATA is set, the length of the - * new metadata string - * @type: If KGSL_GPUOBJ_SET_INFO_TYPE is set, the new type of the memory object - */ - -#define KGSL_GPUOBJ_SET_INFO_METADATA (1 << 0) -#define KGSL_GPUOBJ_SET_INFO_TYPE (1 << 1) - -struct kgsl_gpuobj_set_info { - uint64_t flags; - uint64_t metadata; - unsigned int id; - unsigned int metadata_len; - unsigned int type; -}; - -#define IOCTL_KGSL_GPUOBJ_SET_INFO \ - _IOW(KGSL_IOC_TYPE, 0x4C, struct kgsl_gpuobj_set_info) - -#endif /* _UAPI_MSM_KGSL_H */ diff --git a/third_party/linux/include/msm_media_info.h b/third_party/linux/include/msm_media_info.h deleted file mode 100644 index 39dceb2..0000000 --- a/third_party/linux/include/msm_media_info.h +++ /dev/null @@ -1,819 +0,0 @@ -#ifndef __MEDIA_INFO_H__ -#define __MEDIA_INFO_H__ - -#ifndef MSM_MEDIA_ALIGN -#define MSM_MEDIA_ALIGN(__sz, __align) (((__sz) + (__align-1)) & (~(__align-1))) -#endif - -#ifndef MSM_MEDIA_ROUNDUP -#define MSM_MEDIA_ROUNDUP(__sz, __r) (((__sz) + ((__r) - 1)) / (__r)) -#endif - -#ifndef MSM_MEDIA_MAX -#define MSM_MEDIA_MAX(__a, __b) ((__a) > (__b)?(__a):(__b)) -#endif - -enum color_fmts { - /* Venus NV12: - * YUV 4:2:0 image with a plane of 8 bit Y samples followed - * by an interleaved U/V plane containing 8 bit 2x2 subsampled - * colour difference samples. - * - * <-------- Y/UV_Stride --------> - * <------- Width -------> - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . ^ ^ - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . Height | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | Y_Scanlines - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . V | - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . V - * U V U V U V U V U V U V . . . . ^ - * U V U V U V U V U V U V . . . . | - * U V U V U V U V U V U V . . . . | - * U V U V U V U V U V U V . . . . UV_Scanlines - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . V - * . . . . . . . . . . . . . . . . --> Buffer size alignment - * - * Y_Stride : Width aligned to 128 - * UV_Stride : Width aligned to 128 - * Y_Scanlines: Height aligned to 32 - * UV_Scanlines: Height/2 aligned to 16 - * Extradata: Arbitrary (software-imposed) padding - * Total size = align((Y_Stride * Y_Scanlines - * + UV_Stride * UV_Scanlines - * + max(Extradata, Y_Stride * 8), 4096) - */ - COLOR_FMT_NV12, - - /* Venus NV21: - * YUV 4:2:0 image with a plane of 8 bit Y samples followed - * by an interleaved V/U plane containing 8 bit 2x2 subsampled - * colour difference samples. - * - * <-------- Y/UV_Stride --------> - * <------- Width -------> - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . ^ ^ - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . Height | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | Y_Scanlines - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . V | - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . V - * V U V U V U V U V U V U . . . . ^ - * V U V U V U V U V U V U . . . . | - * V U V U V U V U V U V U . . . . | - * V U V U V U V U V U V U . . . . UV_Scanlines - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . V - * . . . . . . . . . . . . . . . . --> Padding & Buffer size alignment - * - * Y_Stride : Width aligned to 128 - * UV_Stride : Width aligned to 128 - * Y_Scanlines: Height aligned to 32 - * UV_Scanlines: Height/2 aligned to 16 - * Extradata: Arbitrary (software-imposed) padding - * Total size = align((Y_Stride * Y_Scanlines - * + UV_Stride * UV_Scanlines - * + max(Extradata, Y_Stride * 8), 4096) - */ - COLOR_FMT_NV21, - /* Venus NV12_MVTB: - * Two YUV 4:2:0 images/views one after the other - * in a top-bottom layout, same as NV12 - * with a plane of 8 bit Y samples followed - * by an interleaved U/V plane containing 8 bit 2x2 subsampled - * colour difference samples. - * - * - * <-------- Y/UV_Stride --------> - * <------- Width -------> - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . ^ ^ ^ - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | | | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . Height | | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | Y_Scanlines | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | | | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | | | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | | | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . V | | - * . . . . . . . . . . . . . . . . | View_1 - * . . . . . . . . . . . . . . . . | | - * . . . . . . . . . . . . . . . . | | - * . . . . . . . . . . . . . . . . V | - * U V U V U V U V U V U V . . . . ^ | - * U V U V U V U V U V U V . . . . | | - * U V U V U V U V U V U V . . . . | | - * U V U V U V U V U V U V . . . . UV_Scanlines | - * . . . . . . . . . . . . . . . . | | - * . . . . . . . . . . . . . . . . V V - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . ^ ^ ^ - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | | | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . Height | | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | Y_Scanlines | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | | | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | | | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . | | | - * Y Y Y Y Y Y Y Y Y Y Y Y . . . . V | | - * . . . . . . . . . . . . . . . . | View_2 - * . . . . . . . . . . . . . . . . | | - * . . . . . . . . . . . . . . . . | | - * . . . . . . . . . . . . . . . . V | - * U V U V U V U V U V U V . . . . ^ | - * U V U V U V U V U V U V . . . . | | - * U V U V U V U V U V U V . . . . | | - * U V U V U V U V U V U V . . . . UV_Scanlines | - * . . . . . . . . . . . . . . . . | | - * . . . . . . . . . . . . . . . . V V - * . . . . . . . . . . . . . . . . --> Buffer size alignment - * - * Y_Stride : Width aligned to 128 - * UV_Stride : Width aligned to 128 - * Y_Scanlines: Height aligned to 32 - * UV_Scanlines: Height/2 aligned to 16 - * View_1 begin at: 0 (zero) - * View_2 begin at: Y_Stride * Y_Scanlines + UV_Stride * UV_Scanlines - * Extradata: Arbitrary (software-imposed) padding - * Total size = align((2*(Y_Stride * Y_Scanlines) - * + 2*(UV_Stride * UV_Scanlines) + Extradata), 4096) - */ - COLOR_FMT_NV12_MVTB, - /* Venus NV12 UBWC: - * Compressed Macro-tile format for NV12. - * Contains 4 planes in the following order - - * (A) Y_Meta_Plane - * (B) Y_UBWC_Plane - * (C) UV_Meta_Plane - * (D) UV_UBWC_Plane - * - * Y_Meta_Plane consists of meta information to decode compressed - * tile data in Y_UBWC_Plane. - * Y_UBWC_Plane consists of Y data in compressed macro-tile format. - * UBWC decoder block will use the Y_Meta_Plane data together with - * Y_UBWC_Plane data to produce loss-less uncompressed 8 bit Y samples. - * - * UV_Meta_Plane consists of meta information to decode compressed - * tile data in UV_UBWC_Plane. - * UV_UBWC_Plane consists of UV data in compressed macro-tile format. - * UBWC decoder block will use UV_Meta_Plane data together with - * UV_UBWC_Plane data to produce loss-less uncompressed 8 bit 2x2 - * subsampled color difference samples. - * - * Each tile in Y_UBWC_Plane/UV_UBWC_Plane is independently decodable - * and randomly accessible. There is no dependency between tiles. - * - * <----- Y_Meta_Stride ----> - * <-------- Width ------> - * M M M M M M M M M M M M . . ^ ^ - * M M M M M M M M M M M M . . | | - * M M M M M M M M M M M M . . Height | - * M M M M M M M M M M M M . . | Meta_Y_Scanlines - * M M M M M M M M M M M M . . | | - * M M M M M M M M M M M M . . | | - * M M M M M M M M M M M M . . | | - * M M M M M M M M M M M M . . V | - * . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . -------> Buffer size aligned to 4k - * . . . . . . . . . . . . . . V - * <--Compressed tile Y Stride---> - * <------- Width -------> - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . ^ ^ - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . | | - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . Height | - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . | Macro_tile_Y_Scanlines - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . | | - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . | | - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . | | - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . V | - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . -------> Buffer size aligned to 4k - * . . . . . . . . . . . . . . . . V - * <----- UV_Meta_Stride ----> - * M M M M M M M M M M M M . . ^ - * M M M M M M M M M M M M . . | - * M M M M M M M M M M M M . . | - * M M M M M M M M M M M M . . M_UV_Scanlines - * . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . V - * . . . . . . . . . . . . . . -------> Buffer size aligned to 4k - * <--Compressed tile UV Stride---> - * U* V* U* V* U* V* U* V* . . . . ^ - * U* V* U* V* U* V* U* V* . . . . | - * U* V* U* V* U* V* U* V* . . . . | - * U* V* U* V* U* V* U* V* . . . . UV_Scanlines - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . V - * . . . . . . . . . . . . . . . . -------> Buffer size aligned to 4k - * - * Y_Stride = align(Width, 128) - * UV_Stride = align(Width, 128) - * Y_Scanlines = align(Height, 32) - * UV_Scanlines = align(Height/2, 16) - * Y_UBWC_Plane_size = align(Y_Stride * Y_Scanlines, 4096) - * UV_UBWC_Plane_size = align(UV_Stride * UV_Scanlines, 4096) - * Y_Meta_Stride = align(roundup(Width, Y_TileWidth), 64) - * Y_Meta_Scanlines = align(roundup(Height, Y_TileHeight), 16) - * Y_Meta_Plane_size = align(Y_Meta_Stride * Y_Meta_Scanlines, 4096) - * UV_Meta_Stride = align(roundup(Width, UV_TileWidth), 64) - * UV_Meta_Scanlines = align(roundup(Height, UV_TileHeight), 16) - * UV_Meta_Plane_size = align(UV_Meta_Stride * UV_Meta_Scanlines, 4096) - * Extradata = 8k - * - * Total size = align( Y_UBWC_Plane_size + UV_UBWC_Plane_size + - * Y_Meta_Plane_size + UV_Meta_Plane_size - * + max(Extradata, Y_Stride * 48), 4096) - */ - COLOR_FMT_NV12_UBWC, - /* Venus NV12 10-bit UBWC: - * Compressed Macro-tile format for NV12. - * Contains 4 planes in the following order - - * (A) Y_Meta_Plane - * (B) Y_UBWC_Plane - * (C) UV_Meta_Plane - * (D) UV_UBWC_Plane - * - * Y_Meta_Plane consists of meta information to decode compressed - * tile data in Y_UBWC_Plane. - * Y_UBWC_Plane consists of Y data in compressed macro-tile format. - * UBWC decoder block will use the Y_Meta_Plane data together with - * Y_UBWC_Plane data to produce loss-less uncompressed 10 bit Y samples. - * - * UV_Meta_Plane consists of meta information to decode compressed - * tile data in UV_UBWC_Plane. - * UV_UBWC_Plane consists of UV data in compressed macro-tile format. - * UBWC decoder block will use UV_Meta_Plane data together with - * UV_UBWC_Plane data to produce loss-less uncompressed 10 bit 2x2 - * subsampled color difference samples. - * - * Each tile in Y_UBWC_Plane/UV_UBWC_Plane is independently decodable - * and randomly accessible. There is no dependency between tiles. - * - * <----- Y_Meta_Stride -----> - * <-------- Width ------> - * M M M M M M M M M M M M . . ^ ^ - * M M M M M M M M M M M M . . | | - * M M M M M M M M M M M M . . Height | - * M M M M M M M M M M M M . . | Meta_Y_Scanlines - * M M M M M M M M M M M M . . | | - * M M M M M M M M M M M M . . | | - * M M M M M M M M M M M M . . | | - * M M M M M M M M M M M M . . V | - * . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . -------> Buffer size aligned to 4k - * . . . . . . . . . . . . . . V - * <--Compressed tile Y Stride---> - * <------- Width -------> - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . ^ ^ - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . | | - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . Height | - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . | Macro_tile_Y_Scanlines - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . | | - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . | | - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . | | - * Y* Y* Y* Y* Y* Y* Y* Y* . . . . V | - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . -------> Buffer size aligned to 4k - * . . . . . . . . . . . . . . . . V - * <----- UV_Meta_Stride ----> - * M M M M M M M M M M M M . . ^ - * M M M M M M M M M M M M . . | - * M M M M M M M M M M M M . . | - * M M M M M M M M M M M M . . M_UV_Scanlines - * . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . V - * . . . . . . . . . . . . . . -------> Buffer size aligned to 4k - * <--Compressed tile UV Stride---> - * U* V* U* V* U* V* U* V* . . . . ^ - * U* V* U* V* U* V* U* V* . . . . | - * U* V* U* V* U* V* U* V* . . . . | - * U* V* U* V* U* V* U* V* . . . . UV_Scanlines - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . V - * . . . . . . . . . . . . . . . . -------> Buffer size aligned to 4k - * - * - * Y_Stride = align(Width * 4/3, 128) - * UV_Stride = align(Width * 4/3, 128) - * Y_Scanlines = align(Height, 32) - * UV_Scanlines = align(Height/2, 16) - * Y_UBWC_Plane_Size = align(Y_Stride * Y_Scanlines, 4096) - * UV_UBWC_Plane_Size = align(UV_Stride * UV_Scanlines, 4096) - * Y_Meta_Stride = align(roundup(Width, Y_TileWidth), 64) - * Y_Meta_Scanlines = align(roundup(Height, Y_TileHeight), 16) - * Y_Meta_Plane_size = align(Y_Meta_Stride * Y_Meta_Scanlines, 4096) - * UV_Meta_Stride = align(roundup(Width, UV_TileWidth), 64) - * UV_Meta_Scanlines = align(roundup(Height, UV_TileHeight), 16) - * UV_Meta_Plane_size = align(UV_Meta_Stride * UV_Meta_Scanlines, 4096) - * Extradata = 8k - * - * Total size = align(Y_UBWC_Plane_size + UV_UBWC_Plane_size + - * Y_Meta_Plane_size + UV_Meta_Plane_size - * + max(Extradata, Y_Stride * 48), 4096) - */ - COLOR_FMT_NV12_BPP10_UBWC, - /* Venus RGBA8888 format: - * Contains 1 plane in the following order - - * (A) RGBA plane - * - * <-------- RGB_Stride --------> - * <------- Width -------> - * R R R R R R R R R R R R . . . . ^ ^ - * R R R R R R R R R R R R . . . . | | - * R R R R R R R R R R R R . . . . Height | - * R R R R R R R R R R R R . . . . | RGB_Scanlines - * R R R R R R R R R R R R . . . . | | - * R R R R R R R R R R R R . . . . | | - * R R R R R R R R R R R R . . . . | | - * R R R R R R R R R R R R . . . . V | - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . V - * - * RGB_Stride = align(Width * 4, 128) - * RGB_Scanlines = align(Height, 32) - * RGB_Plane_size = align(RGB_Stride * RGB_Scanlines, 4096) - * Extradata = 8k - * - * Total size = align(RGB_Plane_size + Extradata, 4096) - */ - COLOR_FMT_RGBA8888, - /* Venus RGBA8888 UBWC format: - * Contains 2 planes in the following order - - * (A) Meta plane - * (B) RGBA plane - * - * <--- RGB_Meta_Stride ----> - * <-------- Width ------> - * M M M M M M M M M M M M . . ^ ^ - * M M M M M M M M M M M M . . | | - * M M M M M M M M M M M M . . Height | - * M M M M M M M M M M M M . . | Meta_RGB_Scanlines - * M M M M M M M M M M M M . . | | - * M M M M M M M M M M M M . . | | - * M M M M M M M M M M M M . . | | - * M M M M M M M M M M M M . . V | - * . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . -------> Buffer size aligned to 4k - * . . . . . . . . . . . . . . V - * <-------- RGB_Stride --------> - * <------- Width -------> - * R R R R R R R R R R R R . . . . ^ ^ - * R R R R R R R R R R R R . . . . | | - * R R R R R R R R R R R R . . . . Height | - * R R R R R R R R R R R R . . . . | RGB_Scanlines - * R R R R R R R R R R R R . . . . | | - * R R R R R R R R R R R R . . . . | | - * R R R R R R R R R R R R . . . . | | - * R R R R R R R R R R R R . . . . V | - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . | - * . . . . . . . . . . . . . . . . -------> Buffer size aligned to 4k - * . . . . . . . . . . . . . . . . V - * - * RGB_Stride = align(Width * 4, 128) - * RGB_Scanlines = align(Height, 32) - * RGB_Plane_size = align(RGB_Stride * RGB_Scanlines, 4096) - * RGB_Meta_Stride = align(roundup(Width, RGB_TileWidth), 64) - * RGB_Meta_Scanline = align(roundup(Height, RGB_TileHeight), 16) - * RGB_Meta_Plane_size = align(RGB_Meta_Stride * - * RGB_Meta_Scanlines, 4096) - * Extradata = 8k - * - * Total size = align(RGB_Meta_Plane_size + RGB_Plane_size + - * Extradata, 4096) - */ - COLOR_FMT_RGBA8888_UBWC, -}; - -static inline unsigned int VENUS_EXTRADATA_SIZE(int width, int height) -{ - (void)height; - (void)width; - - /* - * In the future, calculate the size based on the w/h but just - * hardcode it for now since 16K satisfies all current usecases. - */ - return 16 * 1024; -} - -static inline unsigned int VENUS_Y_STRIDE(int color_fmt, int width) -{ - unsigned int alignment, stride = 0; - if (!width) - goto invalid_input; - - switch (color_fmt) { - case COLOR_FMT_NV21: - case COLOR_FMT_NV12: - case COLOR_FMT_NV12_MVTB: - case COLOR_FMT_NV12_UBWC: - alignment = 128; - stride = MSM_MEDIA_ALIGN(width, alignment); - break; - case COLOR_FMT_NV12_BPP10_UBWC: - alignment = 256; - stride = MSM_MEDIA_ALIGN(width, 192); - stride = MSM_MEDIA_ALIGN(stride * 4/3, alignment); - break; - default: - break; - } -invalid_input: - return stride; -} - -static inline unsigned int VENUS_UV_STRIDE(int color_fmt, int width) -{ - unsigned int alignment, stride = 0; - if (!width) - goto invalid_input; - - switch (color_fmt) { - case COLOR_FMT_NV21: - case COLOR_FMT_NV12: - case COLOR_FMT_NV12_MVTB: - case COLOR_FMT_NV12_UBWC: - alignment = 128; - stride = MSM_MEDIA_ALIGN(width, alignment); - break; - case COLOR_FMT_NV12_BPP10_UBWC: - alignment = 256; - stride = MSM_MEDIA_ALIGN(width, 192); - stride = MSM_MEDIA_ALIGN(stride * 4/3, alignment); - break; - default: - break; - } -invalid_input: - return stride; -} - -static inline unsigned int VENUS_Y_SCANLINES(int color_fmt, int height) -{ - unsigned int alignment, sclines = 0; - if (!height) - goto invalid_input; - - switch (color_fmt) { - case COLOR_FMT_NV21: - case COLOR_FMT_NV12: - case COLOR_FMT_NV12_MVTB: - case COLOR_FMT_NV12_UBWC: - alignment = 32; - break; - case COLOR_FMT_NV12_BPP10_UBWC: - alignment = 16; - break; - default: - return 0; - } - sclines = MSM_MEDIA_ALIGN(height, alignment); -invalid_input: - return sclines; -} - -static inline unsigned int VENUS_UV_SCANLINES(int color_fmt, int height) -{ - unsigned int alignment, sclines = 0; - if (!height) - goto invalid_input; - - switch (color_fmt) { - case COLOR_FMT_NV21: - case COLOR_FMT_NV12: - case COLOR_FMT_NV12_MVTB: - case COLOR_FMT_NV12_BPP10_UBWC: - alignment = 16; - break; - case COLOR_FMT_NV12_UBWC: - alignment = 32; - break; - default: - goto invalid_input; - } - - sclines = MSM_MEDIA_ALIGN(height / 2, alignment); - -invalid_input: - return sclines; -} - -static inline unsigned int VENUS_Y_META_STRIDE(int color_fmt, int width) -{ - int y_tile_width = 0, y_meta_stride = 0; - - if (!width) - goto invalid_input; - - switch (color_fmt) { - case COLOR_FMT_NV12_UBWC: - y_tile_width = 32; - break; - case COLOR_FMT_NV12_BPP10_UBWC: - y_tile_width = 48; - break; - default: - goto invalid_input; - } - - y_meta_stride = MSM_MEDIA_ROUNDUP(width, y_tile_width); - y_meta_stride = MSM_MEDIA_ALIGN(y_meta_stride, 64); - -invalid_input: - return y_meta_stride; -} - -static inline unsigned int VENUS_Y_META_SCANLINES(int color_fmt, int height) -{ - int y_tile_height = 0, y_meta_scanlines = 0; - - if (!height) - goto invalid_input; - - switch (color_fmt) { - case COLOR_FMT_NV12_UBWC: - y_tile_height = 8; - break; - case COLOR_FMT_NV12_BPP10_UBWC: - y_tile_height = 4; - break; - default: - goto invalid_input; - } - - y_meta_scanlines = MSM_MEDIA_ROUNDUP(height, y_tile_height); - y_meta_scanlines = MSM_MEDIA_ALIGN(y_meta_scanlines, 16); - -invalid_input: - return y_meta_scanlines; -} - -static inline unsigned int VENUS_UV_META_STRIDE(int color_fmt, int width) -{ - int uv_tile_width = 0, uv_meta_stride = 0; - - if (!width) - goto invalid_input; - - switch (color_fmt) { - case COLOR_FMT_NV12_UBWC: - uv_tile_width = 16; - break; - case COLOR_FMT_NV12_BPP10_UBWC: - uv_tile_width = 24; - break; - default: - goto invalid_input; - } - - uv_meta_stride = MSM_MEDIA_ROUNDUP(width / 2, uv_tile_width); - uv_meta_stride = MSM_MEDIA_ALIGN(uv_meta_stride, 64); - -invalid_input: - return uv_meta_stride; -} - -static inline unsigned int VENUS_UV_META_SCANLINES(int color_fmt, int height) -{ - int uv_tile_height = 0, uv_meta_scanlines = 0; - - if (!height) - goto invalid_input; - - switch (color_fmt) { - case COLOR_FMT_NV12_UBWC: - uv_tile_height = 8; - break; - case COLOR_FMT_NV12_BPP10_UBWC: - uv_tile_height = 4; - break; - default: - goto invalid_input; - } - - uv_meta_scanlines = MSM_MEDIA_ROUNDUP(height / 2, uv_tile_height); - uv_meta_scanlines = MSM_MEDIA_ALIGN(uv_meta_scanlines, 16); - -invalid_input: - return uv_meta_scanlines; -} - -static inline unsigned int VENUS_RGB_STRIDE(int color_fmt, int width) -{ - unsigned int alignment = 0, stride = 0; - if (!width) - goto invalid_input; - - switch (color_fmt) { - case COLOR_FMT_RGBA8888: - alignment = 128; - break; - case COLOR_FMT_RGBA8888_UBWC: - alignment = 256; - break; - default: - goto invalid_input; - } - - stride = MSM_MEDIA_ALIGN(width * 4, alignment); - -invalid_input: - return stride; -} - -static inline unsigned int VENUS_RGB_SCANLINES(int color_fmt, int height) -{ - unsigned int alignment = 0, scanlines = 0; - - if (!height) - goto invalid_input; - - switch (color_fmt) { - case COLOR_FMT_RGBA8888: - alignment = 32; - break; - case COLOR_FMT_RGBA8888_UBWC: - alignment = 16; - break; - default: - goto invalid_input; - } - - scanlines = MSM_MEDIA_ALIGN(height, alignment); - -invalid_input: - return scanlines; -} - -static inline unsigned int VENUS_RGB_META_STRIDE(int color_fmt, int width) -{ - int rgb_tile_width = 0, rgb_meta_stride = 0; - - if (!width) - goto invalid_input; - - switch (color_fmt) { - case COLOR_FMT_RGBA8888_UBWC: - rgb_tile_width = 16; - break; - default: - goto invalid_input; - } - - rgb_meta_stride = MSM_MEDIA_ROUNDUP(width, rgb_tile_width); - rgb_meta_stride = MSM_MEDIA_ALIGN(rgb_meta_stride, 64); - -invalid_input: - return rgb_meta_stride; -} - -static inline unsigned int VENUS_RGB_META_SCANLINES(int color_fmt, int height) -{ - int rgb_tile_height = 0, rgb_meta_scanlines = 0; - - if (!height) - goto invalid_input; - - switch (color_fmt) { - case COLOR_FMT_RGBA8888_UBWC: - rgb_tile_height = 4; - break; - default: - goto invalid_input; - } - - rgb_meta_scanlines = MSM_MEDIA_ROUNDUP(height, rgb_tile_height); - rgb_meta_scanlines = MSM_MEDIA_ALIGN(rgb_meta_scanlines, 16); - -invalid_input: - return rgb_meta_scanlines; -} - -static inline unsigned int VENUS_BUFFER_SIZE( - int color_fmt, int width, int height) -{ - const unsigned int extra_size = VENUS_EXTRADATA_SIZE(width, height); - unsigned int uv_alignment = 0, size = 0; - unsigned int y_plane, uv_plane, y_stride, - uv_stride, y_sclines, uv_sclines; - unsigned int y_ubwc_plane = 0, uv_ubwc_plane = 0; - unsigned int y_meta_stride = 0, y_meta_scanlines = 0; - unsigned int uv_meta_stride = 0, uv_meta_scanlines = 0; - unsigned int y_meta_plane = 0, uv_meta_plane = 0; - unsigned int rgb_stride = 0, rgb_scanlines = 0; - unsigned int rgb_plane = 0, rgb_ubwc_plane = 0, rgb_meta_plane = 0; - unsigned int rgb_meta_stride = 0, rgb_meta_scanlines = 0; - - if (!width || !height) - goto invalid_input; - - y_stride = VENUS_Y_STRIDE(color_fmt, width); - uv_stride = VENUS_UV_STRIDE(color_fmt, width); - y_sclines = VENUS_Y_SCANLINES(color_fmt, height); - uv_sclines = VENUS_UV_SCANLINES(color_fmt, height); - rgb_stride = VENUS_RGB_STRIDE(color_fmt, width); - rgb_scanlines = VENUS_RGB_SCANLINES(color_fmt, height); - - switch (color_fmt) { - case COLOR_FMT_NV21: - case COLOR_FMT_NV12: - uv_alignment = 4096; - y_plane = y_stride * y_sclines; - uv_plane = uv_stride * uv_sclines + uv_alignment; - size = y_plane + uv_plane + - MSM_MEDIA_MAX(extra_size, 8 * y_stride); - size = MSM_MEDIA_ALIGN(size, 4096); - break; - case COLOR_FMT_NV12_MVTB: - uv_alignment = 4096; - y_plane = y_stride * y_sclines; - uv_plane = uv_stride * uv_sclines + uv_alignment; - size = y_plane + uv_plane; - size = 2 * size + extra_size; - size = MSM_MEDIA_ALIGN(size, 4096); - break; - case COLOR_FMT_NV12_UBWC: - case COLOR_FMT_NV12_BPP10_UBWC: - y_ubwc_plane = MSM_MEDIA_ALIGN(y_stride * y_sclines, 4096); - uv_ubwc_plane = MSM_MEDIA_ALIGN(uv_stride * uv_sclines, 4096); - y_meta_stride = VENUS_Y_META_STRIDE(color_fmt, width); - y_meta_scanlines = VENUS_Y_META_SCANLINES(color_fmt, height); - y_meta_plane = MSM_MEDIA_ALIGN( - y_meta_stride * y_meta_scanlines, 4096); - uv_meta_stride = VENUS_UV_META_STRIDE(color_fmt, width); - uv_meta_scanlines = VENUS_UV_META_SCANLINES(color_fmt, height); - uv_meta_plane = MSM_MEDIA_ALIGN(uv_meta_stride * - uv_meta_scanlines, 4096); - - size = y_ubwc_plane + uv_ubwc_plane + y_meta_plane + - uv_meta_plane + - MSM_MEDIA_MAX(extra_size + 8192, 48 * y_stride); - size = MSM_MEDIA_ALIGN(size, 4096); - break; - case COLOR_FMT_RGBA8888: - rgb_plane = MSM_MEDIA_ALIGN(rgb_stride * rgb_scanlines, 4096); - size = rgb_plane; - size = MSM_MEDIA_ALIGN(size, 4096); - break; - case COLOR_FMT_RGBA8888_UBWC: - rgb_ubwc_plane = MSM_MEDIA_ALIGN(rgb_stride * rgb_scanlines, - 4096); - rgb_meta_stride = VENUS_RGB_META_STRIDE(color_fmt, width); - rgb_meta_scanlines = VENUS_RGB_META_SCANLINES(color_fmt, - height); - rgb_meta_plane = MSM_MEDIA_ALIGN(rgb_meta_stride * - rgb_meta_scanlines, 4096); - size = rgb_ubwc_plane + rgb_meta_plane; - size = MSM_MEDIA_ALIGN(size, 4096); - break; - default: - break; - } -invalid_input: - return size; -} - -static inline unsigned int VENUS_VIEW2_OFFSET( - int color_fmt, int width, int height) -{ - unsigned int offset = 0; - unsigned int y_plane, uv_plane, y_stride, - uv_stride, y_sclines, uv_sclines; - if (!width || !height) - goto invalid_input; - - y_stride = VENUS_Y_STRIDE(color_fmt, width); - uv_stride = VENUS_UV_STRIDE(color_fmt, width); - y_sclines = VENUS_Y_SCANLINES(color_fmt, height); - uv_sclines = VENUS_UV_SCANLINES(color_fmt, height); - switch (color_fmt) { - case COLOR_FMT_NV12_MVTB: - y_plane = y_stride * y_sclines; - uv_plane = uv_stride * uv_sclines; - offset = y_plane + uv_plane; - break; - default: - break; - } -invalid_input: - return offset; -} - -#endif diff --git a/third_party/linux/include/msmb_camera.h b/third_party/linux/include/msmb_camera.h deleted file mode 100644 index f4c4b3e..0000000 --- a/third_party/linux/include/msmb_camera.h +++ /dev/null @@ -1,220 +0,0 @@ -#ifndef __LINUX_MSMB_CAMERA_H -#define __LINUX_MSMB_CAMERA_H - -#include -#include -#include - -#define MSM_CAM_LOGSYNC_FILE_NAME "logsync" -#define MSM_CAM_LOGSYNC_FILE_BASEDIR "camera" - -#define MSM_CAM_V4L2_IOCTL_NOTIFY \ - _IOW('V', BASE_VIDIOC_PRIVATE + 30, struct msm_v4l2_event_data) - -#define MSM_CAM_V4L2_IOCTL_NOTIFY_META \ - _IOW('V', BASE_VIDIOC_PRIVATE + 31, struct msm_v4l2_event_data) - -#define MSM_CAM_V4L2_IOCTL_CMD_ACK \ - _IOW('V', BASE_VIDIOC_PRIVATE + 32, struct msm_v4l2_event_data) - -#define MSM_CAM_V4L2_IOCTL_NOTIFY_ERROR \ - _IOW('V', BASE_VIDIOC_PRIVATE + 33, struct msm_v4l2_event_data) - -#define MSM_CAM_V4L2_IOCTL_NOTIFY_DEBUG \ - _IOW('V', BASE_VIDIOC_PRIVATE + 34, struct msm_v4l2_event_data) - -#ifdef CONFIG_COMPAT -#define MSM_CAM_V4L2_IOCTL_NOTIFY32 \ - _IOW('V', BASE_VIDIOC_PRIVATE + 30, struct v4l2_event32) - -#define MSM_CAM_V4L2_IOCTL_NOTIFY_META32 \ - _IOW('V', BASE_VIDIOC_PRIVATE + 31, struct v4l2_event32) - -#define MSM_CAM_V4L2_IOCTL_CMD_ACK32 \ - _IOW('V', BASE_VIDIOC_PRIVATE + 32, struct v4l2_event32) - -#define MSM_CAM_V4L2_IOCTL_NOTIFY_ERROR32 \ - _IOW('V', BASE_VIDIOC_PRIVATE + 33, struct v4l2_event32) - -#define MSM_CAM_V4L2_IOCTL_NOTIFY_DEBUG32 \ - _IOW('V', BASE_VIDIOC_PRIVATE + 34, struct v4l2_event32) - -#endif - -#define QCAMERA_DEVICE_GROUP_ID 1 -#define QCAMERA_VNODE_GROUP_ID 2 -#define MSM_CAMERA_NAME "msm_camera" -#define MSM_CONFIGURATION_NAME "msm_config" - -#define MSM_CAMERA_SUBDEV_CSIPHY 0 -#define MSM_CAMERA_SUBDEV_CSID 1 -#define MSM_CAMERA_SUBDEV_ISPIF 2 -#define MSM_CAMERA_SUBDEV_VFE 3 -#define MSM_CAMERA_SUBDEV_AXI 4 -#define MSM_CAMERA_SUBDEV_VPE 5 -#define MSM_CAMERA_SUBDEV_SENSOR 6 -#define MSM_CAMERA_SUBDEV_ACTUATOR 7 -#define MSM_CAMERA_SUBDEV_EEPROM 8 -#define MSM_CAMERA_SUBDEV_CPP 9 -#define MSM_CAMERA_SUBDEV_CCI 10 -#define MSM_CAMERA_SUBDEV_LED_FLASH 11 -#define MSM_CAMERA_SUBDEV_STROBE_FLASH 12 -#define MSM_CAMERA_SUBDEV_BUF_MNGR 13 -#define MSM_CAMERA_SUBDEV_SENSOR_INIT 14 -#define MSM_CAMERA_SUBDEV_OIS 15 -#define MSM_CAMERA_SUBDEV_FLASH 16 -#define MSM_CAMERA_SUBDEV_EXT 17 - -#define MSM_MAX_CAMERA_SENSORS 5 - -/* The below macro is defined to put an upper limit on maximum - * number of buffer requested per stream. In case of extremely - * large value for number of buffer due to data structure corruption - * we return error to avoid integer overflow. Group processing - * can have max of 9 groups of 8 bufs each. This value may be - * configured in future*/ -#define MSM_CAMERA_MAX_STREAM_BUF 72 - -/* Max batch size of processing */ -#define MSM_CAMERA_MAX_USER_BUFF_CNT 16 - -/* featur base */ -#define MSM_CAMERA_FEATURE_BASE 0x00010000 -#define MSM_CAMERA_FEATURE_SHUTDOWN (MSM_CAMERA_FEATURE_BASE + 1) - -#define MSM_CAMERA_STATUS_BASE 0x00020000 -#define MSM_CAMERA_STATUS_FAIL (MSM_CAMERA_STATUS_BASE + 1) -#define MSM_CAMERA_STATUS_SUCCESS (MSM_CAMERA_STATUS_BASE + 2) - -/* event type */ -#define MSM_CAMERA_V4L2_EVENT_TYPE (V4L2_EVENT_PRIVATE_START + 0x00002000) - -/* event id */ -#define MSM_CAMERA_EVENT_MIN 0 -#define MSM_CAMERA_NEW_SESSION (MSM_CAMERA_EVENT_MIN + 1) -#define MSM_CAMERA_DEL_SESSION (MSM_CAMERA_EVENT_MIN + 2) -#define MSM_CAMERA_SET_PARM (MSM_CAMERA_EVENT_MIN + 3) -#define MSM_CAMERA_GET_PARM (MSM_CAMERA_EVENT_MIN + 4) -#define MSM_CAMERA_MAPPING_CFG (MSM_CAMERA_EVENT_MIN + 5) -#define MSM_CAMERA_MAPPING_SES (MSM_CAMERA_EVENT_MIN + 6) -#define MSM_CAMERA_MSM_NOTIFY (MSM_CAMERA_EVENT_MIN + 7) -#define MSM_CAMERA_EVENT_MAX (MSM_CAMERA_EVENT_MIN + 8) - -/* data.command */ -#define MSM_CAMERA_PRIV_S_CROP (V4L2_CID_PRIVATE_BASE + 1) -#define MSM_CAMERA_PRIV_G_CROP (V4L2_CID_PRIVATE_BASE + 2) -#define MSM_CAMERA_PRIV_G_FMT (V4L2_CID_PRIVATE_BASE + 3) -#define MSM_CAMERA_PRIV_S_FMT (V4L2_CID_PRIVATE_BASE + 4) -#define MSM_CAMERA_PRIV_TRY_FMT (V4L2_CID_PRIVATE_BASE + 5) -#define MSM_CAMERA_PRIV_METADATA (V4L2_CID_PRIVATE_BASE + 6) -#define MSM_CAMERA_PRIV_QUERY_CAP (V4L2_CID_PRIVATE_BASE + 7) -#define MSM_CAMERA_PRIV_STREAM_ON (V4L2_CID_PRIVATE_BASE + 8) -#define MSM_CAMERA_PRIV_STREAM_OFF (V4L2_CID_PRIVATE_BASE + 9) -#define MSM_CAMERA_PRIV_NEW_STREAM (V4L2_CID_PRIVATE_BASE + 10) -#define MSM_CAMERA_PRIV_DEL_STREAM (V4L2_CID_PRIVATE_BASE + 11) -#define MSM_CAMERA_PRIV_SHUTDOWN (V4L2_CID_PRIVATE_BASE + 12) -#define MSM_CAMERA_PRIV_STREAM_INFO_SYNC \ - (V4L2_CID_PRIVATE_BASE + 13) -#define MSM_CAMERA_PRIV_G_SESSION_ID (V4L2_CID_PRIVATE_BASE + 14) -#define MSM_CAMERA_PRIV_CMD_MAX 20 - -/* data.status - success */ -#define MSM_CAMERA_CMD_SUCESS 0x00000001 -#define MSM_CAMERA_BUF_MAP_SUCESS 0x00000002 - -/* data.status - error */ -#define MSM_CAMERA_ERR_EVT_BASE 0x00010000 -#define MSM_CAMERA_ERR_CMD_FAIL (MSM_CAMERA_ERR_EVT_BASE + 1) -#define MSM_CAMERA_ERR_MAPPING (MSM_CAMERA_ERR_EVT_BASE + 2) -#define MSM_CAMERA_ERR_DEVICE_BUSY (MSM_CAMERA_ERR_EVT_BASE + 3) - -/* The msm_v4l2_event_data structure should match the - * v4l2_event.u.data field. - * should not exceed 16 elements */ -struct msm_v4l2_event_data { - /*word 0*/ - unsigned int command; - /*word 1*/ - unsigned int status; - /*word 2*/ - unsigned int session_id; - /*word 3*/ - unsigned int stream_id; - /*word 4*/ - unsigned int map_op; - /*word 5*/ - unsigned int map_buf_idx; - /*word 6*/ - unsigned int notify; - /*word 7*/ - unsigned int arg_value; - /*word 8*/ - unsigned int ret_value; - /*word 9*/ - unsigned int v4l2_event_type; - /*word 10*/ - unsigned int v4l2_event_id; - /*word 11*/ - unsigned int handle; - /*word 12*/ - unsigned int nop6; - /*word 13*/ - unsigned int nop7; - /*word 14*/ - unsigned int nop8; - /*word 15*/ - unsigned int nop9; -}; - -/* map to v4l2_format.fmt.raw_data */ -struct msm_v4l2_format_data { - enum v4l2_buf_type type; - unsigned int width; - unsigned int height; - unsigned int pixelformat; /* FOURCC */ - unsigned char num_planes; - unsigned int plane_sizes[VIDEO_MAX_PLANES]; -}; - -/* MSM Four-character-code (FOURCC) */ -#define msm_v4l2_fourcc(a, b, c, d)\ - ((__u32)(a) | ((__u32)(b) << 8) | ((__u32)(c) << 16) |\ - ((__u32)(d) << 24)) - -/* Composite stats */ -#define MSM_V4L2_PIX_FMT_STATS_COMB v4l2_fourcc('S', 'T', 'C', 'M') -/* AEC stats */ -#define MSM_V4L2_PIX_FMT_STATS_AE v4l2_fourcc('S', 'T', 'A', 'E') -/* AF stats */ -#define MSM_V4L2_PIX_FMT_STATS_AF v4l2_fourcc('S', 'T', 'A', 'F') -/* AWB stats */ -#define MSM_V4L2_PIX_FMT_STATS_AWB v4l2_fourcc('S', 'T', 'W', 'B') -/* IHIST stats */ -#define MSM_V4L2_PIX_FMT_STATS_IHST v4l2_fourcc('I', 'H', 'S', 'T') -/* Column count stats */ -#define MSM_V4L2_PIX_FMT_STATS_CS v4l2_fourcc('S', 'T', 'C', 'S') -/* Row count stats */ -#define MSM_V4L2_PIX_FMT_STATS_RS v4l2_fourcc('S', 'T', 'R', 'S') -/* Bayer Grid stats */ -#define MSM_V4L2_PIX_FMT_STATS_BG v4l2_fourcc('S', 'T', 'B', 'G') -/* Bayer focus stats */ -#define MSM_V4L2_PIX_FMT_STATS_BF v4l2_fourcc('S', 'T', 'B', 'F') -/* Bayer hist stats */ -#define MSM_V4L2_PIX_FMT_STATS_BHST v4l2_fourcc('B', 'H', 'S', 'T') - -enum smmu_attach_mode { - NON_SECURE_MODE = 0x01, - SECURE_MODE = 0x02, - MAX_PROTECTION_MODE = 0x03, -}; - -struct msm_camera_smmu_attach_type { - enum smmu_attach_mode attach; -}; - -struct msm_camera_user_buf_cont_t { - unsigned int buf_cnt; - unsigned int buf_idx[MSM_CAMERA_MAX_USER_BUFF_CNT]; -}; - -#endif /* __LINUX_MSMB_CAMERA_H */ diff --git a/third_party/linux/include/msmb_isp.h b/third_party/linux/include/msmb_isp.h deleted file mode 100644 index 35589e0..0000000 --- a/third_party/linux/include/msmb_isp.h +++ /dev/null @@ -1,880 +0,0 @@ -#ifndef __MSMB_ISP__ -#define __MSMB_ISP__ - -#include - -#define MAX_PLANES_PER_STREAM 3 -#define MAX_NUM_STREAM 7 - -#define ISP_VERSION_47 47 -#define ISP_VERSION_46 46 -#define ISP_VERSION_44 44 -#define ISP_VERSION_40 40 -#define ISP_VERSION_32 32 -#define ISP_NATIVE_BUF_BIT (0x10000 << 0) -#define ISP0_BIT (0x10000 << 1) -#define ISP1_BIT (0x10000 << 2) -#define ISP_META_CHANNEL_BIT (0x10000 << 3) -#define ISP_SCRATCH_BUF_BIT (0x10000 << 4) -#define ISP_OFFLINE_STATS_BIT (0x10000 << 5) -#define ISP_STATS_STREAM_BIT 0x80000000 - -struct msm_vfe_cfg_cmd_list; - -enum ISP_START_PIXEL_PATTERN { - ISP_BAYER_RGRGRG, - ISP_BAYER_GRGRGR, - ISP_BAYER_BGBGBG, - ISP_BAYER_GBGBGB, - ISP_YUV_YCbYCr, - ISP_YUV_YCrYCb, - ISP_YUV_CbYCrY, - ISP_YUV_CrYCbY, - ISP_PIX_PATTERN_MAX -}; - -enum msm_vfe_plane_fmt { - Y_PLANE, - CB_PLANE, - CR_PLANE, - CRCB_PLANE, - CBCR_PLANE, - VFE_PLANE_FMT_MAX -}; - -enum msm_vfe_input_src { - VFE_PIX_0, - VFE_RAW_0, - VFE_RAW_1, - VFE_RAW_2, - VFE_SRC_MAX, -}; - -enum msm_vfe_axi_stream_src { - PIX_ENCODER, - PIX_VIEWFINDER, - PIX_VIDEO, - CAMIF_RAW, - IDEAL_RAW, - RDI_INTF_0, - RDI_INTF_1, - RDI_INTF_2, - VFE_AXI_SRC_MAX -}; - -enum msm_vfe_frame_skip_pattern { - NO_SKIP, - EVERY_2FRAME, - EVERY_3FRAME, - EVERY_4FRAME, - EVERY_5FRAME, - EVERY_6FRAME, - EVERY_7FRAME, - EVERY_8FRAME, - EVERY_16FRAME, - EVERY_32FRAME, - SKIP_ALL, - SKIP_RANGE, - MAX_SKIP, -}; - -/* - * Define an unused period. When this period is set it means that the stream is - * stopped(i.e the pattern is 0). We don't track the current pattern, just the - * period defines what the pattern is, if period is this then pattern is 0 else - * pattern is 1 - */ -#define MSM_VFE_STREAM_STOP_PERIOD 15 - -enum msm_isp_stats_type { - MSM_ISP_STATS_AEC, /* legacy based AEC */ - MSM_ISP_STATS_AF, /* legacy based AF */ - MSM_ISP_STATS_AWB, /* legacy based AWB */ - MSM_ISP_STATS_RS, /* legacy based RS */ - MSM_ISP_STATS_CS, /* legacy based CS */ - MSM_ISP_STATS_IHIST, /* legacy based HIST */ - MSM_ISP_STATS_SKIN, /* legacy based SKIN */ - MSM_ISP_STATS_BG, /* Bayer Grids */ - MSM_ISP_STATS_BF, /* Bayer Focus */ - MSM_ISP_STATS_BE, /* Bayer Exposure*/ - MSM_ISP_STATS_BHIST, /* Bayer Hist */ - MSM_ISP_STATS_BF_SCALE, /* Bayer Focus scale */ - MSM_ISP_STATS_HDR_BE, /* HDR Bayer Exposure */ - MSM_ISP_STATS_HDR_BHIST, /* HDR Bayer Hist */ - MSM_ISP_STATS_AEC_BG, /* AEC BG */ - MSM_ISP_STATS_MAX /* MAX */ -}; - -/* - * @stats_type_mask: Stats type mask (enum msm_isp_stats_type). - * @stream_src_mask: Stream src mask (enum msm_vfe_axi_stream_src) - * @skip_mode: skip pattern, if skip mode is range only then min/max is used - * @min_frame_id: minimum frame id (valid only if skip_mode = RANGE) - * @max_frame_id: maximum frame id (valid only if skip_mode = RANGE) -*/ -struct msm_isp_sw_framskip { - uint32_t stats_type_mask; - uint32_t stream_src_mask; - enum msm_vfe_frame_skip_pattern skip_mode; - uint32_t min_frame_id; - uint32_t max_frame_id; -}; - -enum msm_vfe_testgen_color_pattern { - COLOR_BAR_8_COLOR, - UNICOLOR_WHITE, - UNICOLOR_YELLOW, - UNICOLOR_CYAN, - UNICOLOR_GREEN, - UNICOLOR_MAGENTA, - UNICOLOR_RED, - UNICOLOR_BLUE, - UNICOLOR_BLACK, - MAX_COLOR, -}; - -enum msm_vfe_camif_input { - CAMIF_DISABLED, - CAMIF_PAD_REG_INPUT, - CAMIF_MIDDI_INPUT, - CAMIF_MIPI_INPUT, -}; - -struct msm_vfe_fetch_engine_cfg { - uint32_t input_format; - uint32_t buf_width; - uint32_t buf_height; - uint32_t fetch_width; - uint32_t fetch_height; - uint32_t x_offset; - uint32_t y_offset; - uint32_t buf_stride; -}; - -enum msm_vfe_camif_output_format { - CAMIF_QCOM_RAW, - CAMIF_MIPI_RAW, - CAMIF_PLAIN_8, - CAMIF_PLAIN_16, - CAMIF_MAX_FORMAT, -}; - -/* - * Camif output general configuration - */ -struct msm_vfe_camif_subsample_cfg { - uint32_t irq_subsample_period; - uint32_t irq_subsample_pattern; - uint32_t sof_counter_step; - uint32_t pixel_skip; - uint32_t line_skip; - uint32_t first_line; - uint32_t last_line; - uint32_t first_pixel; - uint32_t last_pixel; - enum msm_vfe_camif_output_format output_format; -}; - -/* - * Camif frame and window configuration - */ -struct msm_vfe_camif_cfg { - uint32_t lines_per_frame; - uint32_t pixels_per_line; - uint32_t first_pixel; - uint32_t last_pixel; - uint32_t first_line; - uint32_t last_line; - uint32_t epoch_line0; - uint32_t epoch_line1; - uint32_t is_split; - enum msm_vfe_camif_input camif_input; - struct msm_vfe_camif_subsample_cfg subsample_cfg; -}; - -struct msm_vfe_testgen_cfg { - uint32_t lines_per_frame; - uint32_t pixels_per_line; - uint32_t v_blank; - uint32_t h_blank; - enum ISP_START_PIXEL_PATTERN pixel_bayer_pattern; - uint32_t rotate_period; - enum msm_vfe_testgen_color_pattern color_bar_pattern; - uint32_t burst_num_frame; -}; - -enum msm_vfe_inputmux { - CAMIF, - TESTGEN, - EXTERNAL_READ, -}; - -enum msm_vfe_stats_composite_group { - STATS_COMPOSITE_GRP_NONE, - STATS_COMPOSITE_GRP_1, - STATS_COMPOSITE_GRP_2, - STATS_COMPOSITE_GRP_MAX, -}; - -enum msm_vfe_hvx_streaming_cmd { - HVX_DISABLE, - HVX_ONE_WAY, - HVX_ROUND_TRIP -}; - -struct msm_vfe_pix_cfg { - struct msm_vfe_camif_cfg camif_cfg; - struct msm_vfe_testgen_cfg testgen_cfg; - struct msm_vfe_fetch_engine_cfg fetch_engine_cfg; - enum msm_vfe_inputmux input_mux; - enum ISP_START_PIXEL_PATTERN pixel_pattern; - uint32_t input_format; - enum msm_vfe_hvx_streaming_cmd hvx_cmd; - uint32_t is_split; -}; - -struct msm_vfe_rdi_cfg { - uint8_t cid; - uint8_t frame_based; -}; - -struct msm_vfe_input_cfg { - union { - struct msm_vfe_pix_cfg pix_cfg; - struct msm_vfe_rdi_cfg rdi_cfg; - } d; - enum msm_vfe_input_src input_src; - uint32_t input_pix_clk; -}; - -struct msm_vfe_fetch_eng_start { - uint32_t session_id; - uint32_t stream_id; - uint32_t buf_idx; - uint8_t offline_mode; - uint32_t fd; - uint32_t buf_addr; - uint32_t frame_id; -}; - -struct msm_vfe_axi_plane_cfg { - uint32_t output_width; /*Include padding*/ - uint32_t output_height; - uint32_t output_stride; - uint32_t output_scan_lines; - uint32_t output_plane_format; /*Y/Cb/Cr/CbCr*/ - uint32_t plane_addr_offset; - uint8_t csid_src; /*RDI 0-2*/ - uint8_t rdi_cid;/*CID 1-16*/ -}; - -enum msm_stream_memory_input_t { - MEMORY_INPUT_DISABLED, - MEMORY_INPUT_ENABLED -}; - -struct msm_vfe_axi_stream_request_cmd { - uint32_t session_id; - uint32_t stream_id; - uint32_t vt_enable; - uint32_t output_format;/*Planar/RAW/Misc*/ - enum msm_vfe_axi_stream_src stream_src; /*CAMIF/IDEAL/RDIs*/ - struct msm_vfe_axi_plane_cfg plane_cfg[MAX_PLANES_PER_STREAM]; - - uint32_t burst_count; - uint32_t hfr_mode; - uint8_t frame_base; - - uint32_t init_frame_drop; /*MAX 31 Frames*/ - enum msm_vfe_frame_skip_pattern frame_skip_pattern; - uint8_t buf_divert; /* if TRUE no vb2 buf done. */ - /*Return values*/ - uint32_t axi_stream_handle; - uint32_t controllable_output; - uint32_t burst_len; - /* Flag indicating memory input stream */ - enum msm_stream_memory_input_t memory_input; -}; - -struct msm_vfe_axi_stream_release_cmd { - uint32_t stream_handle; -}; - -enum msm_vfe_axi_stream_cmd { - STOP_STREAM, - START_STREAM, - STOP_IMMEDIATELY, -}; - -struct msm_vfe_axi_stream_cfg_cmd { - uint8_t num_streams; - uint32_t stream_handle[VFE_AXI_SRC_MAX]; - enum msm_vfe_axi_stream_cmd cmd; - uint8_t sync_frame_id_src; -}; - -enum msm_vfe_axi_stream_update_type { - ENABLE_STREAM_BUF_DIVERT, - DISABLE_STREAM_BUF_DIVERT, - UPDATE_STREAM_FRAMEDROP_PATTERN, - UPDATE_STREAM_STATS_FRAMEDROP_PATTERN, - UPDATE_STREAM_AXI_CONFIG, - UPDATE_STREAM_REQUEST_FRAMES, - UPDATE_STREAM_ADD_BUFQ, - UPDATE_STREAM_REMOVE_BUFQ, - UPDATE_STREAM_SW_FRAME_DROP, -}; - -enum msm_vfe_iommu_type { - IOMMU_ATTACH, - IOMMU_DETACH, -}; - -enum msm_vfe_buff_queue_id { - VFE_BUF_QUEUE_DEFAULT, - VFE_BUF_QUEUE_SHARED, - VFE_BUF_QUEUE_MAX, -}; - -struct msm_vfe_axi_stream_cfg_update_info { - uint32_t stream_handle; - uint32_t output_format; - uint32_t user_stream_id; - uint32_t frame_id; - enum msm_vfe_frame_skip_pattern skip_pattern; - struct msm_vfe_axi_plane_cfg plane_cfg[MAX_PLANES_PER_STREAM]; - struct msm_isp_sw_framskip sw_skip_info; -}; - -struct msm_vfe_axi_halt_cmd { - uint32_t stop_camif; - uint32_t overflow_detected; - uint32_t blocking_halt; -}; - -struct msm_vfe_axi_reset_cmd { - uint32_t blocking; - uint32_t frame_id; -}; - -struct msm_vfe_axi_restart_cmd { - uint32_t enable_camif; -}; - -struct msm_vfe_axi_stream_update_cmd { - uint32_t num_streams; - enum msm_vfe_axi_stream_update_type update_type; - struct msm_vfe_axi_stream_cfg_update_info - update_info[MSM_ISP_STATS_MAX]; -}; - -struct msm_vfe_smmu_attach_cmd { - uint32_t security_mode; - uint32_t iommu_attach_mode; -}; - -struct msm_vfe_stats_stream_request_cmd { - uint32_t session_id; - uint32_t stream_id; - enum msm_isp_stats_type stats_type; - uint32_t composite_flag; - uint32_t framedrop_pattern; - uint32_t init_frame_drop; /*MAX 31 Frames*/ - uint32_t irq_subsample_pattern; - uint32_t buffer_offset; - uint32_t stream_handle; -}; - -struct msm_vfe_stats_stream_release_cmd { - uint32_t stream_handle; -}; -struct msm_vfe_stats_stream_cfg_cmd { - uint8_t num_streams; - uint32_t stream_handle[MSM_ISP_STATS_MAX]; - uint8_t enable; - uint32_t stats_burst_len; -}; - -enum msm_vfe_reg_cfg_type { - VFE_WRITE, - VFE_WRITE_MB, - VFE_READ, - VFE_CFG_MASK, - VFE_WRITE_DMI_16BIT, - VFE_WRITE_DMI_32BIT, - VFE_WRITE_DMI_64BIT, - VFE_READ_DMI_16BIT, - VFE_READ_DMI_32BIT, - VFE_READ_DMI_64BIT, - GET_MAX_CLK_RATE, - GET_CLK_RATES, - GET_ISP_ID, - VFE_HW_UPDATE_LOCK, - VFE_HW_UPDATE_UNLOCK, - SET_WM_UB_SIZE, - SET_UB_POLICY, -}; - -struct msm_vfe_cfg_cmd2 { - uint16_t num_cfg; - uint16_t cmd_len; - void __user *cfg_data; - void __user *cfg_cmd; -}; - -struct msm_vfe_cfg_cmd_list { - struct msm_vfe_cfg_cmd2 cfg_cmd; - struct msm_vfe_cfg_cmd_list *next; - uint32_t next_size; -}; - -struct msm_vfe_reg_rw_info { - uint32_t reg_offset; - uint32_t cmd_data_offset; - uint32_t len; -}; - -struct msm_vfe_reg_mask_info { - uint32_t reg_offset; - uint32_t mask; - uint32_t val; -}; - -struct msm_vfe_reg_dmi_info { - uint32_t hi_tbl_offset; /*Optional*/ - uint32_t lo_tbl_offset; /*Required*/ - uint32_t len; -}; - -struct msm_vfe_reg_cfg_cmd { - union { - struct msm_vfe_reg_rw_info rw_info; - struct msm_vfe_reg_mask_info mask_info; - struct msm_vfe_reg_dmi_info dmi_info; - } u; - - enum msm_vfe_reg_cfg_type cmd_type; -}; - -enum vfe_sd_type { - VFE_SD_0 = 0, - VFE_SD_1, - VFE_SD_COMMON, - VFE_SD_MAX, -}; - -/* When you change the value below, check for the sof event_data size. - * V4l2 limits payload to 64 bytes */ -#define MS_NUM_SLAVE_MAX 1 - -/* Usecases when 2 HW need to be related or synced */ -enum msm_vfe_dual_hw_type { - DUAL_NONE = 0, - DUAL_HW_VFE_SPLIT = 1, - DUAL_HW_MASTER_SLAVE = 2, -}; - -/* Type for 2 INTF when used in Master-Slave mode */ -enum msm_vfe_dual_hw_ms_type { - MS_TYPE_NONE, - MS_TYPE_MASTER, - MS_TYPE_SLAVE, -}; - -struct msm_isp_set_dual_hw_ms_cmd { - uint8_t num_src; - /* Each session can be only one type but multiple intf if YUV cam */ - enum msm_vfe_dual_hw_ms_type dual_hw_ms_type; - /* Primary intf is mostly associated with preview. - * This primary intf SOF frame_id and timestamp is tracked - * and used to calculate delta */ - enum msm_vfe_input_src primary_intf; - /* input_src array indicates other input INTF that may be Master/Slave. - * For these additional intf, frame_id and timestamp are not saved. - * However, if these are slaves then they will still get their - * frame_id from Master */ - enum msm_vfe_input_src input_src[VFE_SRC_MAX]; - uint32_t sof_delta_threshold; /* In milliseconds. Sent for Master */ -}; - -enum msm_isp_buf_type { - ISP_PRIVATE_BUF, - ISP_SHARE_BUF, - MAX_ISP_BUF_TYPE, -}; - -struct msm_isp_unmap_buf_req { - uint32_t fd; -}; - -struct msm_isp_buf_request { - uint32_t session_id; - uint32_t stream_id; - uint8_t num_buf; - uint32_t handle; - enum msm_isp_buf_type buf_type; -}; - -struct msm_isp_qbuf_plane { - uint32_t addr; - uint32_t offset; - uint32_t length; -}; - -struct msm_isp_qbuf_buffer { - struct msm_isp_qbuf_plane planes[MAX_PLANES_PER_STREAM]; - uint32_t num_planes; -}; - -struct msm_isp_qbuf_info { - uint32_t handle; - int32_t buf_idx; - /*Only used for prepare buffer*/ - struct msm_isp_qbuf_buffer buffer; - /*Only used for diverted buffer*/ - uint32_t dirty_buf; -}; - -struct msm_isp_clk_rates { - uint32_t svs_rate; - uint32_t nominal_rate; - uint32_t high_rate; -}; - -struct msm_vfe_axi_src_state { - enum msm_vfe_input_src input_src; - uint32_t src_active; - uint32_t src_frame_id; -}; - -enum msm_isp_event_mask_index { - ISP_EVENT_MASK_INDEX_STATS_NOTIFY = 0, - ISP_EVENT_MASK_INDEX_ERROR = 1, - ISP_EVENT_MASK_INDEX_IOMMU_P_FAULT = 2, - ISP_EVENT_MASK_INDEX_STREAM_UPDATE_DONE = 3, - ISP_EVENT_MASK_INDEX_REG_UPDATE = 4, - ISP_EVENT_MASK_INDEX_SOF = 5, - ISP_EVENT_MASK_INDEX_BUF_DIVERT = 6, - ISP_EVENT_MASK_INDEX_COMP_STATS_NOTIFY = 7, - ISP_EVENT_MASK_INDEX_MASK_FE_READ_DONE = 8, - ISP_EVENT_MASK_INDEX_BUF_DONE = 9, - ISP_EVENT_MASK_INDEX_REG_UPDATE_MISSING = 10, - ISP_EVENT_MASK_INDEX_PING_PONG_MISMATCH = 11, - ISP_EVENT_MASK_INDEX_BUF_FATAL_ERROR = 12, -}; - - -#define ISP_EVENT_SUBS_MASK_NONE 0 - -#define ISP_EVENT_SUBS_MASK_STATS_NOTIFY \ - (1 << ISP_EVENT_MASK_INDEX_STATS_NOTIFY) - -#define ISP_EVENT_SUBS_MASK_ERROR \ - (1 << ISP_EVENT_MASK_INDEX_ERROR) - -#define ISP_EVENT_SUBS_MASK_IOMMU_P_FAULT \ - (1 << ISP_EVENT_MASK_INDEX_IOMMU_P_FAULT) - -#define ISP_EVENT_SUBS_MASK_STREAM_UPDATE_DONE \ - (1 << ISP_EVENT_MASK_INDEX_STREAM_UPDATE_DONE) - -#define ISP_EVENT_SUBS_MASK_REG_UPDATE \ - (1 << ISP_EVENT_MASK_INDEX_REG_UPDATE) - -#define ISP_EVENT_SUBS_MASK_SOF \ - (1 << ISP_EVENT_MASK_INDEX_SOF) - -#define ISP_EVENT_SUBS_MASK_BUF_DIVERT \ - (1 << ISP_EVENT_MASK_INDEX_BUF_DIVERT) - -#define ISP_EVENT_SUBS_MASK_COMP_STATS_NOTIFY \ - (1 << ISP_EVENT_MASK_INDEX_COMP_STATS_NOTIFY) - -#define ISP_EVENT_SUBS_MASK_FE_READ_DONE \ - (1 << ISP_EVENT_MASK_INDEX_MASK_FE_READ_DONE) - -#define ISP_EVENT_SUBS_MASK_BUF_DONE \ - (1 << ISP_EVENT_MASK_INDEX_BUF_DONE) - -#define ISP_EVENT_SUBS_MASK_REG_UPDATE_MISSING \ - (1 << ISP_EVENT_MASK_INDEX_REG_UPDATE_MISSING) - -#define ISP_EVENT_SUBS_MASK_PING_PONG_MISMATCH \ - (1 << ISP_EVENT_MASK_INDEX_PING_PONG_MISMATCH) - -#define ISP_EVENT_SUBS_MASK_BUF_FATAL_ERROR \ - (1 << ISP_EVENT_MASK_INDEX_BUF_FATAL_ERROR) - -enum msm_isp_event_idx { - ISP_REG_UPDATE = 0, - ISP_EPOCH_0 = 1, - ISP_EPOCH_1 = 2, - ISP_START_ACK = 3, - ISP_STOP_ACK = 4, - ISP_IRQ_VIOLATION = 5, - ISP_STATS_OVERFLOW = 6, - ISP_BUF_DONE = 7, - ISP_FE_RD_DONE = 8, - ISP_IOMMU_P_FAULT = 9, - ISP_ERROR = 10, - ISP_HW_FATAL_ERROR = 11, - ISP_PING_PONG_MISMATCH = 12, - ISP_REG_UPDATE_MISSING = 13, - ISP_BUF_FATAL_ERROR = 14, - ISP_EVENT_MAX = 15 -}; - -#define ISP_EVENT_OFFSET 8 -#define ISP_EVENT_BASE (V4L2_EVENT_PRIVATE_START) -#define ISP_BUF_EVENT_BASE (ISP_EVENT_BASE + (1 << ISP_EVENT_OFFSET)) -#define ISP_STATS_EVENT_BASE (ISP_EVENT_BASE + (2 << ISP_EVENT_OFFSET)) -#define ISP_CAMIF_EVENT_BASE (ISP_EVENT_BASE + (3 << ISP_EVENT_OFFSET)) -#define ISP_STREAM_EVENT_BASE (ISP_EVENT_BASE + (4 << ISP_EVENT_OFFSET)) -#define ISP_EVENT_REG_UPDATE (ISP_EVENT_BASE + ISP_REG_UPDATE) -#define ISP_EVENT_EPOCH_0 (ISP_EVENT_BASE + ISP_EPOCH_0) -#define ISP_EVENT_EPOCH_1 (ISP_EVENT_BASE + ISP_EPOCH_1) -#define ISP_EVENT_START_ACK (ISP_EVENT_BASE + ISP_START_ACK) -#define ISP_EVENT_STOP_ACK (ISP_EVENT_BASE + ISP_STOP_ACK) -#define ISP_EVENT_IRQ_VIOLATION (ISP_EVENT_BASE + ISP_IRQ_VIOLATION) -#define ISP_EVENT_STATS_OVERFLOW (ISP_EVENT_BASE + ISP_STATS_OVERFLOW) -#define ISP_EVENT_ERROR (ISP_EVENT_BASE + ISP_ERROR) -#define ISP_EVENT_SOF (ISP_CAMIF_EVENT_BASE) -#define ISP_EVENT_EOF (ISP_CAMIF_EVENT_BASE + 1) -#define ISP_EVENT_BUF_DONE (ISP_EVENT_BASE + ISP_BUF_DONE) -#define ISP_EVENT_BUF_DIVERT (ISP_BUF_EVENT_BASE) -#define ISP_EVENT_STATS_NOTIFY (ISP_STATS_EVENT_BASE) -#define ISP_EVENT_COMP_STATS_NOTIFY (ISP_EVENT_STATS_NOTIFY + MSM_ISP_STATS_MAX) -#define ISP_EVENT_FE_READ_DONE (ISP_EVENT_BASE + ISP_FE_RD_DONE) -#define ISP_EVENT_IOMMU_P_FAULT (ISP_EVENT_BASE + ISP_IOMMU_P_FAULT) -#define ISP_EVENT_HW_FATAL_ERROR (ISP_EVENT_BASE + ISP_HW_FATAL_ERROR) -#define ISP_EVENT_PING_PONG_MISMATCH (ISP_EVENT_BASE + ISP_PING_PONG_MISMATCH) -#define ISP_EVENT_REG_UPDATE_MISSING (ISP_EVENT_BASE + ISP_REG_UPDATE_MISSING) -#define ISP_EVENT_BUF_FATAL_ERROR (ISP_EVENT_BASE + ISP_BUF_FATAL_ERROR) -#define ISP_EVENT_STREAM_UPDATE_DONE (ISP_STREAM_EVENT_BASE) - -/* The msm_v4l2_event_data structure should match the - * v4l2_event.u.data field. - * should not exceed 64 bytes */ - -struct msm_isp_buf_event { - uint32_t session_id; - uint32_t stream_id; - uint32_t handle; - uint32_t output_format; - int8_t buf_idx; -}; -struct msm_isp_fetch_eng_event { - uint32_t session_id; - uint32_t stream_id; - uint32_t handle; - uint32_t fd; - int8_t buf_idx; - int8_t offline_mode; -}; -struct msm_isp_stats_event { - uint32_t stats_mask; /* 4 bytes */ - uint8_t stats_buf_idxs[MSM_ISP_STATS_MAX]; /* 11 bytes */ -}; - -struct msm_isp_stream_ack { - uint32_t session_id; - uint32_t stream_id; - uint32_t handle; -}; - -enum msm_vfe_error_type { - ISP_ERROR_NONE, - ISP_ERROR_CAMIF, - ISP_ERROR_BUS_OVERFLOW, - ISP_ERROR_RETURN_EMPTY_BUFFER, - ISP_ERROR_FRAME_ID_MISMATCH, - ISP_ERROR_MAX, -}; - -struct msm_isp_error_info { - enum msm_vfe_error_type err_type; - uint32_t session_id; - uint32_t stream_id; - uint32_t stream_id_mask; -}; - -/* This structure reports delta between master and slave */ -struct msm_isp_ms_delta_info { - uint8_t num_delta_info; - uint32_t delta[MS_NUM_SLAVE_MAX]; -}; - -/* This is sent in EPOCH irq */ -struct msm_isp_output_info { - uint8_t regs_not_updated; - /* mask with bufq_handle for regs not updated or return empty */ - uint16_t output_err_mask; - /* mask with stream_idx for get_buf failed */ - uint8_t stream_framedrop_mask; - /* mask with stats stream_idx for get_buf failed */ - uint16_t stats_framedrop_mask; - /* delta between master and slave */ -}; - -/* This structure is piggybacked with SOF event */ -struct msm_isp_sof_info { - uint8_t regs_not_updated; - /* mask with AXI_SRC for regs not updated */ - uint16_t reg_update_fail_mask; - /* mask with bufq_handle for get_buf failed */ - uint32_t stream_get_buf_fail_mask; - /* mask with stats stream_idx for get_buf failed */ - uint16_t stats_get_buf_fail_mask; - /* delta between master and slave */ - struct msm_isp_ms_delta_info ms_delta_info; -}; - -struct msm_isp_event_data { - /*Wall clock except for buffer divert events - *which use monotonic clock - */ - struct timeval timestamp; - /* Monotonic timestamp since bootup */ - struct timeval mono_timestamp; - uint32_t frame_id; - union { - /* Sent for Stats_Done event */ - struct msm_isp_stats_event stats; - /* Sent for Buf_Divert event */ - struct msm_isp_buf_event buf_done; - /* Sent for offline fetch done event */ - struct msm_isp_fetch_eng_event fetch_done; - /* Sent for Error_Event */ - struct msm_isp_error_info error_info; - /* - * This struct needs to be removed once - * userspace switches to sof_info - */ - struct msm_isp_output_info output_info; - /* Sent for SOF event */ - struct msm_isp_sof_info sof_info; - } u; /* union can have max 52 bytes */ -}; - -#ifdef CONFIG_COMPAT -struct msm_isp_event_data32 { - struct compat_timeval timestamp; - struct compat_timeval mono_timestamp; - uint32_t frame_id; - union { - struct msm_isp_stats_event stats; - struct msm_isp_buf_event buf_done; - struct msm_isp_fetch_eng_event fetch_done; - struct msm_isp_error_info error_info; - struct msm_isp_output_info output_info; - struct msm_isp_sof_info sof_info; - } u; -}; -#endif - -#define V4L2_PIX_FMT_QBGGR8 v4l2_fourcc('Q', 'B', 'G', '8') -#define V4L2_PIX_FMT_QGBRG8 v4l2_fourcc('Q', 'G', 'B', '8') -#define V4L2_PIX_FMT_QGRBG8 v4l2_fourcc('Q', 'G', 'R', '8') -#define V4L2_PIX_FMT_QRGGB8 v4l2_fourcc('Q', 'R', 'G', '8') -#define V4L2_PIX_FMT_QBGGR10 v4l2_fourcc('Q', 'B', 'G', '0') -#define V4L2_PIX_FMT_QGBRG10 v4l2_fourcc('Q', 'G', 'B', '0') -#define V4L2_PIX_FMT_QGRBG10 v4l2_fourcc('Q', 'G', 'R', '0') -#define V4L2_PIX_FMT_QRGGB10 v4l2_fourcc('Q', 'R', 'G', '0') -#define V4L2_PIX_FMT_QBGGR12 v4l2_fourcc('Q', 'B', 'G', '2') -#define V4L2_PIX_FMT_QGBRG12 v4l2_fourcc('Q', 'G', 'B', '2') -#define V4L2_PIX_FMT_QGRBG12 v4l2_fourcc('Q', 'G', 'R', '2') -#define V4L2_PIX_FMT_QRGGB12 v4l2_fourcc('Q', 'R', 'G', '2') -#define V4L2_PIX_FMT_QBGGR14 v4l2_fourcc('Q', 'B', 'G', '4') -#define V4L2_PIX_FMT_QGBRG14 v4l2_fourcc('Q', 'G', 'B', '4') -#define V4L2_PIX_FMT_QGRBG14 v4l2_fourcc('Q', 'G', 'R', '4') -#define V4L2_PIX_FMT_QRGGB14 v4l2_fourcc('Q', 'R', 'G', '4') -#define V4L2_PIX_FMT_P16BGGR10 v4l2_fourcc('P', 'B', 'G', '0') -#define V4L2_PIX_FMT_P16GBRG10 v4l2_fourcc('P', 'G', 'B', '0') -#define V4L2_PIX_FMT_P16GRBG10 v4l2_fourcc('P', 'G', 'R', '0') -#define V4L2_PIX_FMT_P16RGGB10 v4l2_fourcc('P', 'R', 'G', '0') -#define V4L2_PIX_FMT_NV14 v4l2_fourcc('N', 'V', '1', '4') -#define V4L2_PIX_FMT_NV41 v4l2_fourcc('N', 'V', '4', '1') -#define V4L2_PIX_FMT_META v4l2_fourcc('Q', 'M', 'E', 'T') -#define V4L2_PIX_FMT_SBGGR14 v4l2_fourcc('B', 'G', '1', '4') /* 14 BGBG.GRGR.*/ -#define V4L2_PIX_FMT_SGBRG14 v4l2_fourcc('G', 'B', '1', '4') /* 14 GBGB.RGRG.*/ -#define V4L2_PIX_FMT_SGRBG14 v4l2_fourcc('B', 'A', '1', '4') /* 14 GRGR.BGBG.*/ -#define V4L2_PIX_FMT_SRGGB14 v4l2_fourcc('R', 'G', '1', '4') /* 14 RGRG.GBGB.*/ - -#define VIDIOC_MSM_VFE_REG_CFG \ - _IOWR('V', BASE_VIDIOC_PRIVATE, struct msm_vfe_cfg_cmd2) - -#define VIDIOC_MSM_ISP_REQUEST_BUF \ - _IOWR('V', BASE_VIDIOC_PRIVATE+1, struct msm_isp_buf_request) - -#define VIDIOC_MSM_ISP_ENQUEUE_BUF \ - _IOWR('V', BASE_VIDIOC_PRIVATE+2, struct msm_isp_qbuf_info) - -#define VIDIOC_MSM_ISP_RELEASE_BUF \ - _IOWR('V', BASE_VIDIOC_PRIVATE+3, struct msm_isp_buf_request) - -#define VIDIOC_MSM_ISP_REQUEST_STREAM \ - _IOWR('V', BASE_VIDIOC_PRIVATE+4, struct msm_vfe_axi_stream_request_cmd) - -#define VIDIOC_MSM_ISP_CFG_STREAM \ - _IOWR('V', BASE_VIDIOC_PRIVATE+5, struct msm_vfe_axi_stream_cfg_cmd) - -#define VIDIOC_MSM_ISP_RELEASE_STREAM \ - _IOWR('V', BASE_VIDIOC_PRIVATE+6, struct msm_vfe_axi_stream_release_cmd) - -#define VIDIOC_MSM_ISP_INPUT_CFG \ - _IOWR('V', BASE_VIDIOC_PRIVATE+7, struct msm_vfe_input_cfg) - -#define VIDIOC_MSM_ISP_SET_SRC_STATE \ - _IOWR('V', BASE_VIDIOC_PRIVATE+8, struct msm_vfe_axi_src_state) - -#define VIDIOC_MSM_ISP_REQUEST_STATS_STREAM \ - _IOWR('V', BASE_VIDIOC_PRIVATE+9, \ - struct msm_vfe_stats_stream_request_cmd) - -#define VIDIOC_MSM_ISP_CFG_STATS_STREAM \ - _IOWR('V', BASE_VIDIOC_PRIVATE+10, struct msm_vfe_stats_stream_cfg_cmd) - -#define VIDIOC_MSM_ISP_RELEASE_STATS_STREAM \ - _IOWR('V', BASE_VIDIOC_PRIVATE+11, \ - struct msm_vfe_stats_stream_release_cmd) - -#define VIDIOC_MSM_ISP_REG_UPDATE_CMD \ - _IOWR('V', BASE_VIDIOC_PRIVATE+12, enum msm_vfe_input_src) - -#define VIDIOC_MSM_ISP_UPDATE_STREAM \ - _IOWR('V', BASE_VIDIOC_PRIVATE+13, struct msm_vfe_axi_stream_update_cmd) - -#define VIDIOC_MSM_VFE_REG_LIST_CFG \ - _IOWR('V', BASE_VIDIOC_PRIVATE+14, struct msm_vfe_cfg_cmd_list) - -#define VIDIOC_MSM_ISP_SMMU_ATTACH \ - _IOWR('V', BASE_VIDIOC_PRIVATE+15, struct msm_vfe_smmu_attach_cmd) - -#define VIDIOC_MSM_ISP_UPDATE_STATS_STREAM \ - _IOWR('V', BASE_VIDIOC_PRIVATE+16, struct msm_vfe_axi_stream_update_cmd) - -#define VIDIOC_MSM_ISP_AXI_HALT \ - _IOWR('V', BASE_VIDIOC_PRIVATE+17, struct msm_vfe_axi_halt_cmd) - -#define VIDIOC_MSM_ISP_AXI_RESET \ - _IOWR('V', BASE_VIDIOC_PRIVATE+18, struct msm_vfe_axi_reset_cmd) - -#define VIDIOC_MSM_ISP_AXI_RESTART \ - _IOWR('V', BASE_VIDIOC_PRIVATE+19, struct msm_vfe_axi_restart_cmd) - -#define VIDIOC_MSM_ISP_FETCH_ENG_START \ - _IOWR('V', BASE_VIDIOC_PRIVATE+20, struct msm_vfe_fetch_eng_start) - -#define VIDIOC_MSM_ISP_DEQUEUE_BUF \ - _IOWR('V', BASE_VIDIOC_PRIVATE+21, struct msm_isp_qbuf_info) - -#define VIDIOC_MSM_ISP_SET_DUAL_HW_MASTER_SLAVE \ - _IOWR('V', BASE_VIDIOC_PRIVATE+22, struct msm_isp_set_dual_hw_ms_cmd) - -#define VIDIOC_MSM_ISP_MAP_BUF_START_FE \ - _IOWR('V', BASE_VIDIOC_PRIVATE+23, struct msm_vfe_fetch_eng_start) - -#define VIDIOC_MSM_ISP_UNMAP_BUF \ - _IOWR('V', BASE_VIDIOC_PRIVATE+24, struct msm_isp_unmap_buf_req) - -#endif /* __MSMB_ISP__ */ diff --git a/third_party/linux/include/msmb_ispif.h b/third_party/linux/include/msmb_ispif.h deleted file mode 100644 index 2564c33..0000000 --- a/third_party/linux/include/msmb_ispif.h +++ /dev/null @@ -1,125 +0,0 @@ -#ifndef MSM_CAM_ISPIF_H -#define MSM_CAM_ISPIF_H - -#define CSID_VERSION_V20 0x02000011 -#define CSID_VERSION_V22 0x02001000 -#define CSID_VERSION_V30 0x30000000 -#define CSID_VERSION_V3 0x30000000 - -enum msm_ispif_vfe_intf { - VFE0, - VFE1, - VFE_MAX -}; -#define VFE0_MASK (1 << VFE0) -#define VFE1_MASK (1 << VFE1) - -enum msm_ispif_intftype { - PIX0, - RDI0, - PIX1, - RDI1, - RDI2, - INTF_MAX -}; -#define MAX_PARAM_ENTRIES (INTF_MAX * 2) -#define MAX_CID_CH 8 - -#define PIX0_MASK (1 << PIX0) -#define PIX1_MASK (1 << PIX1) -#define RDI0_MASK (1 << RDI0) -#define RDI1_MASK (1 << RDI1) -#define RDI2_MASK (1 << RDI2) - - -enum msm_ispif_vc { - VC0, - VC1, - VC2, - VC3, - VC_MAX -}; - -enum msm_ispif_cid { - CID0, - CID1, - CID2, - CID3, - CID4, - CID5, - CID6, - CID7, - CID8, - CID9, - CID10, - CID11, - CID12, - CID13, - CID14, - CID15, - CID_MAX -}; - -enum msm_ispif_csid { - CSID0, - CSID1, - CSID2, - CSID3, - CSID_MAX -}; - -struct msm_ispif_params_entry { - enum msm_ispif_vfe_intf vfe_intf; - enum msm_ispif_intftype intftype; - int num_cids; - enum msm_ispif_cid cids[3]; - enum msm_ispif_csid csid; - int crop_enable; - uint16_t crop_start_pixel; - uint16_t crop_end_pixel; -}; - -struct msm_ispif_param_data { - uint32_t num; - struct msm_ispif_params_entry entries[MAX_PARAM_ENTRIES]; -}; - -struct msm_isp_info { - uint32_t max_resolution; - uint32_t id; - uint32_t ver; -}; - -struct msm_ispif_vfe_info { - int num_vfe; - struct msm_isp_info info[VFE_MAX]; -}; - -enum ispif_cfg_type_t { - ISPIF_CLK_ENABLE, - ISPIF_CLK_DISABLE, - ISPIF_INIT, - ISPIF_CFG, - ISPIF_START_FRAME_BOUNDARY, - ISPIF_RESTART_FRAME_BOUNDARY, - ISPIF_STOP_FRAME_BOUNDARY, - ISPIF_STOP_IMMEDIATELY, - ISPIF_RELEASE, - ISPIF_ENABLE_REG_DUMP, - ISPIF_SET_VFE_INFO, -}; - -struct ispif_cfg_data { - enum ispif_cfg_type_t cfg_type; - union { - int reg_dump; /* ISPIF_ENABLE_REG_DUMP */ - uint32_t csid_version; /* ISPIF_INIT */ - struct msm_ispif_vfe_info vfe_info; /* ISPIF_SET_VFE_INFO */ - struct msm_ispif_param_data params; /* CFG, START, STOP */ - }; -}; - -#define VIDIOC_MSM_ISPIF_CFG \ - _IOWR('V', BASE_VIDIOC_PRIVATE, struct ispif_cfg_data) - -#endif /* MSM_CAM_ISPIF_H */ diff --git a/third_party/linux/include/v4l2-controls.h b/third_party/linux/include/v4l2-controls.h deleted file mode 100644 index d14cd8f..0000000 --- a/third_party/linux/include/v4l2-controls.h +++ /dev/null @@ -1,1696 +0,0 @@ -/* - * Video for Linux Two controls header file - * - * Copyright (C) 1999-2012 the contributors - * - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 2 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * Alternatively you can redistribute this file under the terms of the - * BSD license as stated below: - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. The names of its contributors may not be used to endorse or promote - * products derived from this software without specific prior written - * permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR - * A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT - * OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, - * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED - * TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR - * PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF - * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING - * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS - * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - * - * The contents of this header was split off from videodev2.h. All control - * definitions should be added to this header, which is included by - * videodev2.h. - */ - -#ifndef __LINUX_V4L2_CONTROLS_H -#define __LINUX_V4L2_CONTROLS_H - -/* Control classes */ -#define V4L2_CTRL_CLASS_USER 0x00980000 /* Old-style 'user' controls */ -#define V4L2_CTRL_CLASS_MPEG 0x00990000 /* MPEG-compression controls */ -#define V4L2_CTRL_CLASS_CAMERA 0x009a0000 /* Camera class controls */ -#define V4L2_CTRL_CLASS_FM_TX 0x009b0000 /* FM Modulator controls */ -#define V4L2_CTRL_CLASS_FLASH 0x009c0000 /* Camera flash controls */ -#define V4L2_CTRL_CLASS_JPEG 0x009d0000 /* JPEG-compression controls */ -#define V4L2_CTRL_CLASS_IMAGE_SOURCE 0x009e0000 /* Image source controls */ -#define V4L2_CTRL_CLASS_IMAGE_PROC 0x009f0000 /* Image processing controls */ -#define V4L2_CTRL_CLASS_DV 0x00a00000 /* Digital Video controls */ -#define V4L2_CTRL_CLASS_FM_RX 0x00a10000 /* FM Receiver controls */ -#define V4L2_CTRL_CLASS_RF_TUNER 0x00a20000 /* RF tuner controls */ -#define V4L2_CTRL_CLASS_DETECT 0x00a30000 /* Detection controls */ - -/* User-class control IDs */ - -#define V4L2_CID_BASE (V4L2_CTRL_CLASS_USER | 0x900) -#define V4L2_CID_USER_BASE V4L2_CID_BASE -#define V4L2_CID_USER_CLASS (V4L2_CTRL_CLASS_USER | 1) -#define V4L2_CID_BRIGHTNESS (V4L2_CID_BASE+0) -#define V4L2_CID_CONTRAST (V4L2_CID_BASE+1) -#define V4L2_CID_SATURATION (V4L2_CID_BASE+2) -#define V4L2_CID_HUE (V4L2_CID_BASE+3) -#define V4L2_CID_AUDIO_VOLUME (V4L2_CID_BASE+5) -#define V4L2_CID_AUDIO_BALANCE (V4L2_CID_BASE+6) -#define V4L2_CID_AUDIO_BASS (V4L2_CID_BASE+7) -#define V4L2_CID_AUDIO_TREBLE (V4L2_CID_BASE+8) -#define V4L2_CID_AUDIO_MUTE (V4L2_CID_BASE+9) -#define V4L2_CID_AUDIO_LOUDNESS (V4L2_CID_BASE+10) -#define V4L2_CID_BLACK_LEVEL (V4L2_CID_BASE+11) /* Deprecated */ -#define V4L2_CID_AUTO_WHITE_BALANCE (V4L2_CID_BASE+12) -#define V4L2_CID_DO_WHITE_BALANCE (V4L2_CID_BASE+13) -#define V4L2_CID_RED_BALANCE (V4L2_CID_BASE+14) -#define V4L2_CID_BLUE_BALANCE (V4L2_CID_BASE+15) -#define V4L2_CID_GAMMA (V4L2_CID_BASE+16) -#define V4L2_CID_WHITENESS (V4L2_CID_GAMMA) /* Deprecated */ -#define V4L2_CID_EXPOSURE (V4L2_CID_BASE+17) -#define V4L2_CID_AUTOGAIN (V4L2_CID_BASE+18) -#define V4L2_CID_GAIN (V4L2_CID_BASE+19) -#define V4L2_CID_HFLIP (V4L2_CID_BASE+20) -#define V4L2_CID_VFLIP (V4L2_CID_BASE+21) - -#define V4L2_CID_POWER_LINE_FREQUENCY (V4L2_CID_BASE+24) -enum v4l2_power_line_frequency { - V4L2_CID_POWER_LINE_FREQUENCY_DISABLED = 0, - V4L2_CID_POWER_LINE_FREQUENCY_50HZ = 1, - V4L2_CID_POWER_LINE_FREQUENCY_60HZ = 2, - V4L2_CID_POWER_LINE_FREQUENCY_AUTO = 3, -}; -#define V4L2_CID_HUE_AUTO (V4L2_CID_BASE+25) -#define V4L2_CID_WHITE_BALANCE_TEMPERATURE (V4L2_CID_BASE+26) -#define V4L2_CID_SHARPNESS (V4L2_CID_BASE+27) -#define V4L2_CID_BACKLIGHT_COMPENSATION (V4L2_CID_BASE+28) -#define V4L2_CID_CHROMA_AGC (V4L2_CID_BASE+29) -#define V4L2_CID_COLOR_KILLER (V4L2_CID_BASE+30) -#define V4L2_CID_COLORFX (V4L2_CID_BASE+31) -enum v4l2_colorfx { - V4L2_COLORFX_NONE = 0, - V4L2_COLORFX_BW = 1, - V4L2_COLORFX_SEPIA = 2, - V4L2_COLORFX_NEGATIVE = 3, - V4L2_COLORFX_EMBOSS = 4, - V4L2_COLORFX_SKETCH = 5, - V4L2_COLORFX_SKY_BLUE = 6, - V4L2_COLORFX_GRASS_GREEN = 7, - V4L2_COLORFX_SKIN_WHITEN = 8, - V4L2_COLORFX_VIVID = 9, - V4L2_COLORFX_AQUA = 10, - V4L2_COLORFX_ART_FREEZE = 11, - V4L2_COLORFX_SILHOUETTE = 12, - V4L2_COLORFX_SOLARIZATION = 13, - V4L2_COLORFX_ANTIQUE = 14, - V4L2_COLORFX_SET_CBCR = 15, -}; -#define V4L2_CID_AUTOBRIGHTNESS (V4L2_CID_BASE+32) -#define V4L2_CID_BAND_STOP_FILTER (V4L2_CID_BASE+33) - -#define V4L2_CID_ROTATE (V4L2_CID_BASE+34) -#define V4L2_CID_BG_COLOR (V4L2_CID_BASE+35) - -#define V4L2_CID_CHROMA_GAIN (V4L2_CID_BASE+36) - -#define V4L2_CID_ILLUMINATORS_1 (V4L2_CID_BASE+37) -#define V4L2_CID_ILLUMINATORS_2 (V4L2_CID_BASE+38) - -#define V4L2_CID_MIN_BUFFERS_FOR_CAPTURE (V4L2_CID_BASE+39) -#define V4L2_CID_MIN_BUFFERS_FOR_OUTPUT (V4L2_CID_BASE+40) - -#define V4L2_CID_ALPHA_COMPONENT (V4L2_CID_BASE+41) -#define V4L2_CID_COLORFX_CBCR (V4L2_CID_BASE+42) - -/* last CID + 1 */ -#define V4L2_CID_LASTP1 (V4L2_CID_BASE+43) - -/* USER-class private control IDs */ - -/* The base for the meye driver controls. See linux/meye.h for the list - * of controls. We reserve 16 controls for this driver. */ -#define V4L2_CID_USER_MEYE_BASE (V4L2_CID_USER_BASE + 0x1000) - -/* The base for the bttv driver controls. - * We reserve 32 controls for this driver. */ -#define V4L2_CID_USER_BTTV_BASE (V4L2_CID_USER_BASE + 0x1010) - - -/* The base for the s2255 driver controls. - * We reserve 16 controls for this driver. */ -#define V4L2_CID_USER_S2255_BASE (V4L2_CID_USER_BASE + 0x1030) - -/* - * The base for the si476x driver controls. See include/media/drv-intf/si476x.h - * for the list of controls. Total of 16 controls is reserved for this driver - */ -#define V4L2_CID_USER_SI476X_BASE (V4L2_CID_USER_BASE + 0x1040) - -/* The base for the TI VPE driver controls. Total of 16 controls is reserved for - * this driver */ -#define V4L2_CID_USER_TI_VPE_BASE (V4L2_CID_USER_BASE + 0x1050) - -/* The base for the saa7134 driver controls. - * We reserve 16 controls for this driver. */ -#define V4L2_CID_USER_SAA7134_BASE (V4L2_CID_USER_BASE + 0x1060) - -/* The base for the adv7180 driver controls. - * We reserve 16 controls for this driver. */ -#define V4L2_CID_USER_ADV7180_BASE (V4L2_CID_USER_BASE + 0x1070) - -/* The base for the tc358743 driver controls. - * We reserve 16 controls for this driver. */ -#define V4L2_CID_USER_TC358743_BASE (V4L2_CID_USER_BASE + 0x1080) - -/* MPEG-class control IDs */ -/* The MPEG controls are applicable to all codec controls - * and the 'MPEG' part of the define is historical */ - -#define V4L2_CID_MPEG_BASE (V4L2_CTRL_CLASS_MPEG | 0x900) -#define V4L2_CID_MPEG_CLASS (V4L2_CTRL_CLASS_MPEG | 1) - -/* MPEG streams, specific to multiplexed streams */ -#define V4L2_CID_MPEG_STREAM_TYPE (V4L2_CID_MPEG_BASE+0) -enum v4l2_mpeg_stream_type { - V4L2_MPEG_STREAM_TYPE_MPEG2_PS = 0, /* MPEG-2 program stream */ - V4L2_MPEG_STREAM_TYPE_MPEG2_TS = 1, /* MPEG-2 transport stream */ - V4L2_MPEG_STREAM_TYPE_MPEG1_SS = 2, /* MPEG-1 system stream */ - V4L2_MPEG_STREAM_TYPE_MPEG2_DVD = 3, /* MPEG-2 DVD-compatible stream */ - V4L2_MPEG_STREAM_TYPE_MPEG1_VCD = 4, /* MPEG-1 VCD-compatible stream */ - V4L2_MPEG_STREAM_TYPE_MPEG2_SVCD = 5, /* MPEG-2 SVCD-compatible stream */ -}; -#define V4L2_CID_MPEG_STREAM_PID_PMT (V4L2_CID_MPEG_BASE+1) -#define V4L2_CID_MPEG_STREAM_PID_AUDIO (V4L2_CID_MPEG_BASE+2) -#define V4L2_CID_MPEG_STREAM_PID_VIDEO (V4L2_CID_MPEG_BASE+3) -#define V4L2_CID_MPEG_STREAM_PID_PCR (V4L2_CID_MPEG_BASE+4) -#define V4L2_CID_MPEG_STREAM_PES_ID_AUDIO (V4L2_CID_MPEG_BASE+5) -#define V4L2_CID_MPEG_STREAM_PES_ID_VIDEO (V4L2_CID_MPEG_BASE+6) -#define V4L2_CID_MPEG_STREAM_VBI_FMT (V4L2_CID_MPEG_BASE+7) -enum v4l2_mpeg_stream_vbi_fmt { - V4L2_MPEG_STREAM_VBI_FMT_NONE = 0, /* No VBI in the MPEG stream */ - V4L2_MPEG_STREAM_VBI_FMT_IVTV = 1, /* VBI in private packets, IVTV format */ -}; - -/* MPEG audio controls specific to multiplexed streams */ -#define V4L2_CID_MPEG_AUDIO_SAMPLING_FREQ (V4L2_CID_MPEG_BASE+100) -enum v4l2_mpeg_audio_sampling_freq { - V4L2_MPEG_AUDIO_SAMPLING_FREQ_44100 = 0, - V4L2_MPEG_AUDIO_SAMPLING_FREQ_48000 = 1, - V4L2_MPEG_AUDIO_SAMPLING_FREQ_32000 = 2, -}; -#define V4L2_CID_MPEG_AUDIO_ENCODING (V4L2_CID_MPEG_BASE+101) -enum v4l2_mpeg_audio_encoding { - V4L2_MPEG_AUDIO_ENCODING_LAYER_1 = 0, - V4L2_MPEG_AUDIO_ENCODING_LAYER_2 = 1, - V4L2_MPEG_AUDIO_ENCODING_LAYER_3 = 2, - V4L2_MPEG_AUDIO_ENCODING_AAC = 3, - V4L2_MPEG_AUDIO_ENCODING_AC3 = 4, -}; -#define V4L2_CID_MPEG_AUDIO_L1_BITRATE (V4L2_CID_MPEG_BASE+102) -enum v4l2_mpeg_audio_l1_bitrate { - V4L2_MPEG_AUDIO_L1_BITRATE_32K = 0, - V4L2_MPEG_AUDIO_L1_BITRATE_64K = 1, - V4L2_MPEG_AUDIO_L1_BITRATE_96K = 2, - V4L2_MPEG_AUDIO_L1_BITRATE_128K = 3, - V4L2_MPEG_AUDIO_L1_BITRATE_160K = 4, - V4L2_MPEG_AUDIO_L1_BITRATE_192K = 5, - V4L2_MPEG_AUDIO_L1_BITRATE_224K = 6, - V4L2_MPEG_AUDIO_L1_BITRATE_256K = 7, - V4L2_MPEG_AUDIO_L1_BITRATE_288K = 8, - V4L2_MPEG_AUDIO_L1_BITRATE_320K = 9, - V4L2_MPEG_AUDIO_L1_BITRATE_352K = 10, - V4L2_MPEG_AUDIO_L1_BITRATE_384K = 11, - V4L2_MPEG_AUDIO_L1_BITRATE_416K = 12, - V4L2_MPEG_AUDIO_L1_BITRATE_448K = 13, -}; -#define V4L2_CID_MPEG_AUDIO_L2_BITRATE (V4L2_CID_MPEG_BASE+103) -enum v4l2_mpeg_audio_l2_bitrate { - V4L2_MPEG_AUDIO_L2_BITRATE_32K = 0, - V4L2_MPEG_AUDIO_L2_BITRATE_48K = 1, - V4L2_MPEG_AUDIO_L2_BITRATE_56K = 2, - V4L2_MPEG_AUDIO_L2_BITRATE_64K = 3, - V4L2_MPEG_AUDIO_L2_BITRATE_80K = 4, - V4L2_MPEG_AUDIO_L2_BITRATE_96K = 5, - V4L2_MPEG_AUDIO_L2_BITRATE_112K = 6, - V4L2_MPEG_AUDIO_L2_BITRATE_128K = 7, - V4L2_MPEG_AUDIO_L2_BITRATE_160K = 8, - V4L2_MPEG_AUDIO_L2_BITRATE_192K = 9, - V4L2_MPEG_AUDIO_L2_BITRATE_224K = 10, - V4L2_MPEG_AUDIO_L2_BITRATE_256K = 11, - V4L2_MPEG_AUDIO_L2_BITRATE_320K = 12, - V4L2_MPEG_AUDIO_L2_BITRATE_384K = 13, -}; -#define V4L2_CID_MPEG_AUDIO_L3_BITRATE (V4L2_CID_MPEG_BASE+104) -enum v4l2_mpeg_audio_l3_bitrate { - V4L2_MPEG_AUDIO_L3_BITRATE_32K = 0, - V4L2_MPEG_AUDIO_L3_BITRATE_40K = 1, - V4L2_MPEG_AUDIO_L3_BITRATE_48K = 2, - V4L2_MPEG_AUDIO_L3_BITRATE_56K = 3, - V4L2_MPEG_AUDIO_L3_BITRATE_64K = 4, - V4L2_MPEG_AUDIO_L3_BITRATE_80K = 5, - V4L2_MPEG_AUDIO_L3_BITRATE_96K = 6, - V4L2_MPEG_AUDIO_L3_BITRATE_112K = 7, - V4L2_MPEG_AUDIO_L3_BITRATE_128K = 8, - V4L2_MPEG_AUDIO_L3_BITRATE_160K = 9, - V4L2_MPEG_AUDIO_L3_BITRATE_192K = 10, - V4L2_MPEG_AUDIO_L3_BITRATE_224K = 11, - V4L2_MPEG_AUDIO_L3_BITRATE_256K = 12, - V4L2_MPEG_AUDIO_L3_BITRATE_320K = 13, -}; -#define V4L2_CID_MPEG_AUDIO_MODE (V4L2_CID_MPEG_BASE+105) -enum v4l2_mpeg_audio_mode { - V4L2_MPEG_AUDIO_MODE_STEREO = 0, - V4L2_MPEG_AUDIO_MODE_JOINT_STEREO = 1, - V4L2_MPEG_AUDIO_MODE_DUAL = 2, - V4L2_MPEG_AUDIO_MODE_MONO = 3, -}; -#define V4L2_CID_MPEG_AUDIO_MODE_EXTENSION (V4L2_CID_MPEG_BASE+106) -enum v4l2_mpeg_audio_mode_extension { - V4L2_MPEG_AUDIO_MODE_EXTENSION_BOUND_4 = 0, - V4L2_MPEG_AUDIO_MODE_EXTENSION_BOUND_8 = 1, - V4L2_MPEG_AUDIO_MODE_EXTENSION_BOUND_12 = 2, - V4L2_MPEG_AUDIO_MODE_EXTENSION_BOUND_16 = 3, -}; -#define V4L2_CID_MPEG_AUDIO_EMPHASIS (V4L2_CID_MPEG_BASE+107) -enum v4l2_mpeg_audio_emphasis { - V4L2_MPEG_AUDIO_EMPHASIS_NONE = 0, - V4L2_MPEG_AUDIO_EMPHASIS_50_DIV_15_uS = 1, - V4L2_MPEG_AUDIO_EMPHASIS_CCITT_J17 = 2, -}; -#define V4L2_CID_MPEG_AUDIO_CRC (V4L2_CID_MPEG_BASE+108) -enum v4l2_mpeg_audio_crc { - V4L2_MPEG_AUDIO_CRC_NONE = 0, - V4L2_MPEG_AUDIO_CRC_CRC16 = 1, -}; -#define V4L2_CID_MPEG_AUDIO_MUTE (V4L2_CID_MPEG_BASE+109) -#define V4L2_CID_MPEG_AUDIO_AAC_BITRATE (V4L2_CID_MPEG_BASE+110) -#define V4L2_CID_MPEG_AUDIO_AC3_BITRATE (V4L2_CID_MPEG_BASE+111) -enum v4l2_mpeg_audio_ac3_bitrate { - V4L2_MPEG_AUDIO_AC3_BITRATE_32K = 0, - V4L2_MPEG_AUDIO_AC3_BITRATE_40K = 1, - V4L2_MPEG_AUDIO_AC3_BITRATE_48K = 2, - V4L2_MPEG_AUDIO_AC3_BITRATE_56K = 3, - V4L2_MPEG_AUDIO_AC3_BITRATE_64K = 4, - V4L2_MPEG_AUDIO_AC3_BITRATE_80K = 5, - V4L2_MPEG_AUDIO_AC3_BITRATE_96K = 6, - V4L2_MPEG_AUDIO_AC3_BITRATE_112K = 7, - V4L2_MPEG_AUDIO_AC3_BITRATE_128K = 8, - V4L2_MPEG_AUDIO_AC3_BITRATE_160K = 9, - V4L2_MPEG_AUDIO_AC3_BITRATE_192K = 10, - V4L2_MPEG_AUDIO_AC3_BITRATE_224K = 11, - V4L2_MPEG_AUDIO_AC3_BITRATE_256K = 12, - V4L2_MPEG_AUDIO_AC3_BITRATE_320K = 13, - V4L2_MPEG_AUDIO_AC3_BITRATE_384K = 14, - V4L2_MPEG_AUDIO_AC3_BITRATE_448K = 15, - V4L2_MPEG_AUDIO_AC3_BITRATE_512K = 16, - V4L2_MPEG_AUDIO_AC3_BITRATE_576K = 17, - V4L2_MPEG_AUDIO_AC3_BITRATE_640K = 18, -}; -#define V4L2_CID_MPEG_AUDIO_DEC_PLAYBACK (V4L2_CID_MPEG_BASE+112) -enum v4l2_mpeg_audio_dec_playback { - V4L2_MPEG_AUDIO_DEC_PLAYBACK_AUTO = 0, - V4L2_MPEG_AUDIO_DEC_PLAYBACK_STEREO = 1, - V4L2_MPEG_AUDIO_DEC_PLAYBACK_LEFT = 2, - V4L2_MPEG_AUDIO_DEC_PLAYBACK_RIGHT = 3, - V4L2_MPEG_AUDIO_DEC_PLAYBACK_MONO = 4, - V4L2_MPEG_AUDIO_DEC_PLAYBACK_SWAPPED_STEREO = 5, -}; -#define V4L2_CID_MPEG_AUDIO_DEC_MULTILINGUAL_PLAYBACK (V4L2_CID_MPEG_BASE+113) - -/* MPEG video controls specific to multiplexed streams */ -#define V4L2_CID_MPEG_VIDEO_ENCODING (V4L2_CID_MPEG_BASE+200) -enum v4l2_mpeg_video_encoding { - V4L2_MPEG_VIDEO_ENCODING_MPEG_1 = 0, - V4L2_MPEG_VIDEO_ENCODING_MPEG_2 = 1, - V4L2_MPEG_VIDEO_ENCODING_MPEG_4_AVC = 2, -}; -#define V4L2_CID_MPEG_VIDEO_ASPECT (V4L2_CID_MPEG_BASE+201) -enum v4l2_mpeg_video_aspect { - V4L2_MPEG_VIDEO_ASPECT_1x1 = 0, - V4L2_MPEG_VIDEO_ASPECT_4x3 = 1, - V4L2_MPEG_VIDEO_ASPECT_16x9 = 2, - V4L2_MPEG_VIDEO_ASPECT_221x100 = 3, -}; -#define V4L2_CID_MPEG_VIDEO_B_FRAMES (V4L2_CID_MPEG_BASE+202) -#define V4L2_CID_MPEG_VIDEO_GOP_SIZE (V4L2_CID_MPEG_BASE+203) -#define V4L2_CID_MPEG_VIDEO_GOP_CLOSURE (V4L2_CID_MPEG_BASE+204) -#define V4L2_CID_MPEG_VIDEO_PULLDOWN (V4L2_CID_MPEG_BASE+205) -#define V4L2_CID_MPEG_VIDEO_BITRATE_MODE (V4L2_CID_MPEG_BASE+206) -enum v4l2_mpeg_video_bitrate_mode { - V4L2_MPEG_VIDEO_BITRATE_MODE_VBR = 0, - V4L2_MPEG_VIDEO_BITRATE_MODE_CBR = 1, -}; -#define V4L2_CID_MPEG_VIDEO_BITRATE (V4L2_CID_MPEG_BASE+207) -#define V4L2_CID_MPEG_VIDEO_BITRATE_PEAK (V4L2_CID_MPEG_BASE+208) -#define V4L2_CID_MPEG_VIDEO_TEMPORAL_DECIMATION (V4L2_CID_MPEG_BASE+209) -#define V4L2_CID_MPEG_VIDEO_MUTE (V4L2_CID_MPEG_BASE+210) -#define V4L2_CID_MPEG_VIDEO_MUTE_YUV (V4L2_CID_MPEG_BASE+211) -#define V4L2_CID_MPEG_VIDEO_DECODER_SLICE_INTERFACE (V4L2_CID_MPEG_BASE+212) -#define V4L2_CID_MPEG_VIDEO_DECODER_MPEG4_DEBLOCK_FILTER (V4L2_CID_MPEG_BASE+213) -#define V4L2_CID_MPEG_VIDEO_CYCLIC_INTRA_REFRESH_MB (V4L2_CID_MPEG_BASE+214) -#define V4L2_CID_MPEG_VIDEO_FRAME_RC_ENABLE (V4L2_CID_MPEG_BASE+215) -#define V4L2_CID_MPEG_VIDEO_HEADER_MODE (V4L2_CID_MPEG_BASE+216) -enum v4l2_mpeg_video_header_mode { - V4L2_MPEG_VIDEO_HEADER_MODE_SEPARATE = 0, - V4L2_MPEG_VIDEO_HEADER_MODE_JOINED_WITH_1ST_FRAME = 1, - V4L2_MPEG_VIDEO_HEADER_MODE_JOINED_WITH_I_FRAME = 2, -}; -#define V4L2_CID_MPEG_VIDEO_MAX_REF_PIC (V4L2_CID_MPEG_BASE+217) -#define V4L2_CID_MPEG_VIDEO_MB_RC_ENABLE (V4L2_CID_MPEG_BASE+218) -#define V4L2_CID_MPEG_VIDEO_MULTI_SLICE_MAX_BYTES (V4L2_CID_MPEG_BASE+219) -#define V4L2_CID_MPEG_VIDEO_MULTI_SLICE_MAX_MB (V4L2_CID_MPEG_BASE+220) -#define V4L2_CID_MPEG_VIDEO_MULTI_SLICE_MODE (V4L2_CID_MPEG_BASE+221) -enum v4l2_mpeg_video_multi_slice_mode { - V4L2_MPEG_VIDEO_MULTI_SLICE_MODE_SINGLE = 0, - V4L2_MPEG_VIDEO_MULTI_SICE_MODE_MAX_MB = 1, - V4L2_MPEG_VIDEO_MULTI_SICE_MODE_MAX_BYTES = 2, - V4L2_MPEG_VIDEO_MULTI_SLICE_GOB = 3, -}; -#define V4L2_CID_MPEG_VIDEO_VBV_SIZE (V4L2_CID_MPEG_BASE+222) -#define V4L2_CID_MPEG_VIDEO_DEC_PTS (V4L2_CID_MPEG_BASE+223) -#define V4L2_CID_MPEG_VIDEO_DEC_FRAME (V4L2_CID_MPEG_BASE+224) -#define V4L2_CID_MPEG_VIDEO_VBV_DELAY (V4L2_CID_MPEG_BASE+225) -#define V4L2_CID_MPEG_VIDEO_REPEAT_SEQ_HEADER (V4L2_CID_MPEG_BASE+226) -#define V4L2_CID_MPEG_VIDEO_MV_H_SEARCH_RANGE (V4L2_CID_MPEG_BASE+227) -#define V4L2_CID_MPEG_VIDEO_MV_V_SEARCH_RANGE (V4L2_CID_MPEG_BASE+228) -#define V4L2_CID_MPEG_VIDEO_FORCE_KEY_FRAME (V4L2_CID_MPEG_BASE+229) - -#define V4L2_CID_MPEG_VIDEO_H263_I_FRAME_QP (V4L2_CID_MPEG_BASE+300) -#define V4L2_CID_MPEG_VIDEO_H263_P_FRAME_QP (V4L2_CID_MPEG_BASE+301) -#define V4L2_CID_MPEG_VIDEO_H263_B_FRAME_QP (V4L2_CID_MPEG_BASE+302) -#define V4L2_CID_MPEG_VIDEO_H263_MIN_QP (V4L2_CID_MPEG_BASE+303) -#define V4L2_CID_MPEG_VIDEO_H263_MAX_QP (V4L2_CID_MPEG_BASE+304) -#define V4L2_CID_MPEG_VIDEO_H264_I_FRAME_QP (V4L2_CID_MPEG_BASE+350) -#define V4L2_CID_MPEG_VIDEO_H264_P_FRAME_QP (V4L2_CID_MPEG_BASE+351) -#define V4L2_CID_MPEG_VIDEO_H264_B_FRAME_QP (V4L2_CID_MPEG_BASE+352) -#define V4L2_CID_MPEG_VIDEO_H264_MIN_QP (V4L2_CID_MPEG_BASE+353) -#define V4L2_CID_MPEG_VIDEO_H264_MAX_QP (V4L2_CID_MPEG_BASE+354) -#define V4L2_CID_MPEG_VIDEO_H264_8X8_TRANSFORM (V4L2_CID_MPEG_BASE+355) -#define V4L2_CID_MPEG_VIDEO_H264_CPB_SIZE (V4L2_CID_MPEG_BASE+356) -#define V4L2_CID_MPEG_VIDEO_H264_ENTROPY_MODE (V4L2_CID_MPEG_BASE+357) -enum v4l2_mpeg_video_h264_entropy_mode { - V4L2_MPEG_VIDEO_H264_ENTROPY_MODE_CAVLC = 0, - V4L2_MPEG_VIDEO_H264_ENTROPY_MODE_CABAC = 1, -}; -#define V4L2_CID_MPEG_VIDEO_H264_I_PERIOD (V4L2_CID_MPEG_BASE+358) -#define V4L2_CID_MPEG_VIDEO_H264_LEVEL (V4L2_CID_MPEG_BASE+359) -enum v4l2_mpeg_video_h264_level { - V4L2_MPEG_VIDEO_H264_LEVEL_1_0 = 0, - V4L2_MPEG_VIDEO_H264_LEVEL_1B = 1, - V4L2_MPEG_VIDEO_H264_LEVEL_1_1 = 2, - V4L2_MPEG_VIDEO_H264_LEVEL_1_2 = 3, - V4L2_MPEG_VIDEO_H264_LEVEL_1_3 = 4, - V4L2_MPEG_VIDEO_H264_LEVEL_2_0 = 5, - V4L2_MPEG_VIDEO_H264_LEVEL_2_1 = 6, - V4L2_MPEG_VIDEO_H264_LEVEL_2_2 = 7, - V4L2_MPEG_VIDEO_H264_LEVEL_3_0 = 8, - V4L2_MPEG_VIDEO_H264_LEVEL_3_1 = 9, - V4L2_MPEG_VIDEO_H264_LEVEL_3_2 = 10, - V4L2_MPEG_VIDEO_H264_LEVEL_4_0 = 11, - V4L2_MPEG_VIDEO_H264_LEVEL_4_1 = 12, - V4L2_MPEG_VIDEO_H264_LEVEL_4_2 = 13, - V4L2_MPEG_VIDEO_H264_LEVEL_5_0 = 14, - V4L2_MPEG_VIDEO_H264_LEVEL_5_1 = 15, - V4L2_MPEG_VIDEO_H264_LEVEL_5_2 = 16, -#define V4L2_MPEG_VIDEO_H264_LEVEL_UNKNOWN \ - V4L2_MPEG_VIDEO_H264_LEVEL_UNKNOWN - V4L2_MPEG_VIDEO_H264_LEVEL_UNKNOWN = 17, -}; -#define V4L2_CID_MPEG_VIDEO_H264_LOOP_FILTER_ALPHA (V4L2_CID_MPEG_BASE+360) -#define V4L2_CID_MPEG_VIDEO_H264_LOOP_FILTER_BETA (V4L2_CID_MPEG_BASE+361) -#define V4L2_CID_MPEG_VIDEO_H264_LOOP_FILTER_MODE (V4L2_CID_MPEG_BASE+362) -enum v4l2_mpeg_video_h264_loop_filter_mode { - V4L2_MPEG_VIDEO_H264_LOOP_FILTER_MODE_ENABLED = 0, - V4L2_MPEG_VIDEO_H264_LOOP_FILTER_MODE_DISABLED = 1, - V4L2_MPEG_VIDEO_H264_LOOP_FILTER_MODE_DISABLED_AT_SLICE_BOUNDARY = 2, -}; -#define V4L2_CID_MPEG_VIDEO_H264_PROFILE (V4L2_CID_MPEG_BASE+363) -enum v4l2_mpeg_video_h264_profile { - V4L2_MPEG_VIDEO_H264_PROFILE_BASELINE = 0, - V4L2_MPEG_VIDEO_H264_PROFILE_CONSTRAINED_BASELINE = 1, - V4L2_MPEG_VIDEO_H264_PROFILE_MAIN = 2, - V4L2_MPEG_VIDEO_H264_PROFILE_EXTENDED = 3, - V4L2_MPEG_VIDEO_H264_PROFILE_HIGH = 4, - V4L2_MPEG_VIDEO_H264_PROFILE_HIGH_10 = 5, - V4L2_MPEG_VIDEO_H264_PROFILE_HIGH_422 = 6, - V4L2_MPEG_VIDEO_H264_PROFILE_HIGH_444_PREDICTIVE = 7, - V4L2_MPEG_VIDEO_H264_PROFILE_HIGH_10_INTRA = 8, - V4L2_MPEG_VIDEO_H264_PROFILE_HIGH_422_INTRA = 9, - V4L2_MPEG_VIDEO_H264_PROFILE_HIGH_444_INTRA = 10, - V4L2_MPEG_VIDEO_H264_PROFILE_CAVLC_444_INTRA = 11, - V4L2_MPEG_VIDEO_H264_PROFILE_SCALABLE_BASELINE = 12, - V4L2_MPEG_VIDEO_H264_PROFILE_SCALABLE_HIGH = 13, - V4L2_MPEG_VIDEO_H264_PROFILE_SCALABLE_HIGH_INTRA = 14, - V4L2_MPEG_VIDEO_H264_PROFILE_STEREO_HIGH = 15, - V4L2_MPEG_VIDEO_H264_PROFILE_MULTIVIEW_HIGH = 16, - V4L2_MPEG_VIDEO_H264_PROFILE_CONSTRAINED_HIGH = 17, -}; -#define V4L2_CID_MPEG_VIDEO_H264_VUI_EXT_SAR_HEIGHT (V4L2_CID_MPEG_BASE+364) -#define V4L2_CID_MPEG_VIDEO_H264_VUI_EXT_SAR_WIDTH (V4L2_CID_MPEG_BASE+365) -#define V4L2_CID_MPEG_VIDEO_H264_VUI_SAR_ENABLE (V4L2_CID_MPEG_BASE+366) -#define V4L2_CID_MPEG_VIDEO_H264_VUI_SAR_IDC (V4L2_CID_MPEG_BASE+367) -enum v4l2_mpeg_video_h264_vui_sar_idc { - V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_UNSPECIFIED = 0, - V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_1x1 = 1, - V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_12x11 = 2, - V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_10x11 = 3, - V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_16x11 = 4, - V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_40x33 = 5, - V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_24x11 = 6, - V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_20x11 = 7, - V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_32x11 = 8, - V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_80x33 = 9, - V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_18x11 = 10, - V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_15x11 = 11, - V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_64x33 = 12, - V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_160x99 = 13, - V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_4x3 = 14, - V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_3x2 = 15, - V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_2x1 = 16, - V4L2_MPEG_VIDEO_H264_VUI_SAR_IDC_EXTENDED = 17, -}; -#define V4L2_CID_MPEG_VIDEO_H264_SEI_FRAME_PACKING (V4L2_CID_MPEG_BASE+368) -#define V4L2_CID_MPEG_VIDEO_H264_SEI_FP_CURRENT_FRAME_0 (V4L2_CID_MPEG_BASE+369) -#define V4L2_CID_MPEG_VIDEO_H264_SEI_FP_ARRANGEMENT_TYPE (V4L2_CID_MPEG_BASE+370) -enum v4l2_mpeg_video_h264_sei_fp_arrangement_type { - V4L2_MPEG_VIDEO_H264_SEI_FP_ARRANGEMENT_TYPE_CHECKERBOARD = 0, - V4L2_MPEG_VIDEO_H264_SEI_FP_ARRANGEMENT_TYPE_COLUMN = 1, - V4L2_MPEG_VIDEO_H264_SEI_FP_ARRANGEMENT_TYPE_ROW = 2, - V4L2_MPEG_VIDEO_H264_SEI_FP_ARRANGEMENT_TYPE_SIDE_BY_SIDE = 3, - V4L2_MPEG_VIDEO_H264_SEI_FP_ARRANGEMENT_TYPE_TOP_BOTTOM = 4, - V4L2_MPEG_VIDEO_H264_SEI_FP_ARRANGEMENT_TYPE_TEMPORAL = 5, -}; -#define V4L2_CID_MPEG_VIDEO_H264_FMO (V4L2_CID_MPEG_BASE+371) -#define V4L2_CID_MPEG_VIDEO_H264_FMO_MAP_TYPE (V4L2_CID_MPEG_BASE+372) -enum v4l2_mpeg_video_h264_fmo_map_type { - V4L2_MPEG_VIDEO_H264_FMO_MAP_TYPE_INTERLEAVED_SLICES = 0, - V4L2_MPEG_VIDEO_H264_FMO_MAP_TYPE_SCATTERED_SLICES = 1, - V4L2_MPEG_VIDEO_H264_FMO_MAP_TYPE_FOREGROUND_WITH_LEFT_OVER = 2, - V4L2_MPEG_VIDEO_H264_FMO_MAP_TYPE_BOX_OUT = 3, - V4L2_MPEG_VIDEO_H264_FMO_MAP_TYPE_RASTER_SCAN = 4, - V4L2_MPEG_VIDEO_H264_FMO_MAP_TYPE_WIPE_SCAN = 5, - V4L2_MPEG_VIDEO_H264_FMO_MAP_TYPE_EXPLICIT = 6, -}; -#define V4L2_CID_MPEG_VIDEO_H264_FMO_SLICE_GROUP (V4L2_CID_MPEG_BASE+373) -#define V4L2_CID_MPEG_VIDEO_H264_FMO_CHANGE_DIRECTION (V4L2_CID_MPEG_BASE+374) -enum v4l2_mpeg_video_h264_fmo_change_dir { - V4L2_MPEG_VIDEO_H264_FMO_CHANGE_DIR_RIGHT = 0, - V4L2_MPEG_VIDEO_H264_FMO_CHANGE_DIR_LEFT = 1, -}; -#define V4L2_CID_MPEG_VIDEO_H264_FMO_CHANGE_RATE (V4L2_CID_MPEG_BASE+375) -#define V4L2_CID_MPEG_VIDEO_H264_FMO_RUN_LENGTH (V4L2_CID_MPEG_BASE+376) -#define V4L2_CID_MPEG_VIDEO_H264_ASO (V4L2_CID_MPEG_BASE+377) -#define V4L2_CID_MPEG_VIDEO_H264_ASO_SLICE_ORDER (V4L2_CID_MPEG_BASE+378) -#define V4L2_CID_MPEG_VIDEO_H264_HIERARCHICAL_CODING (V4L2_CID_MPEG_BASE+379) -#define V4L2_CID_MPEG_VIDEO_H264_HIERARCHICAL_CODING_TYPE (V4L2_CID_MPEG_BASE+380) -enum v4l2_mpeg_video_h264_hierarchical_coding_type { - V4L2_MPEG_VIDEO_H264_HIERARCHICAL_CODING_B = 0, - V4L2_MPEG_VIDEO_H264_HIERARCHICAL_CODING_P = 1, -}; -#define V4L2_CID_MPEG_VIDEO_H264_HIERARCHICAL_CODING_LAYER (V4L2_CID_MPEG_BASE+381) -#define V4L2_CID_MPEG_VIDEO_H264_HIERARCHICAL_CODING_LAYER_QP (V4L2_CID_MPEG_BASE+382) -#define V4L2_CID_MPEG_VIDEO_MPEG4_I_FRAME_QP (V4L2_CID_MPEG_BASE+400) -#define V4L2_CID_MPEG_VIDEO_MPEG4_P_FRAME_QP (V4L2_CID_MPEG_BASE+401) -#define V4L2_CID_MPEG_VIDEO_MPEG4_B_FRAME_QP (V4L2_CID_MPEG_BASE+402) -#define V4L2_CID_MPEG_VIDEO_MPEG4_MIN_QP (V4L2_CID_MPEG_BASE+403) -#define V4L2_CID_MPEG_VIDEO_MPEG4_MAX_QP (V4L2_CID_MPEG_BASE+404) -#define V4L2_CID_MPEG_VIDEO_MPEG4_LEVEL (V4L2_CID_MPEG_BASE+405) -enum v4l2_mpeg_video_mpeg4_level { - V4L2_MPEG_VIDEO_MPEG4_LEVEL_0 = 0, - V4L2_MPEG_VIDEO_MPEG4_LEVEL_0B = 1, - V4L2_MPEG_VIDEO_MPEG4_LEVEL_1 = 2, - V4L2_MPEG_VIDEO_MPEG4_LEVEL_2 = 3, - V4L2_MPEG_VIDEO_MPEG4_LEVEL_3 = 4, - V4L2_MPEG_VIDEO_MPEG4_LEVEL_3B = 5, - V4L2_MPEG_VIDEO_MPEG4_LEVEL_4 = 6, - V4L2_MPEG_VIDEO_MPEG4_LEVEL_5 = 7, -}; -#define V4L2_CID_MPEG_VIDEO_MPEG4_PROFILE (V4L2_CID_MPEG_BASE+406) -enum v4l2_mpeg_video_mpeg4_profile { - V4L2_MPEG_VIDEO_MPEG4_PROFILE_SIMPLE = 0, - V4L2_MPEG_VIDEO_MPEG4_PROFILE_ADVANCED_SIMPLE = 1, - V4L2_MPEG_VIDEO_MPEG4_PROFILE_CORE = 2, - V4L2_MPEG_VIDEO_MPEG4_PROFILE_SIMPLE_SCALABLE = 3, - V4L2_MPEG_VIDEO_MPEG4_PROFILE_ADVANCED_CODING_EFFICIENCY = 4, -}; -#define V4L2_CID_MPEG_VIDEO_MPEG4_QPEL (V4L2_CID_MPEG_BASE+407) - -/* Control IDs for VP8 streams - * Although VP8 is not part of MPEG we add these controls to the MPEG class - * as that class is already handling other video compression standards - */ -#define V4L2_CID_MPEG_VIDEO_VPX_NUM_PARTITIONS (V4L2_CID_MPEG_BASE+500) -enum v4l2_vp8_num_partitions { - V4L2_CID_MPEG_VIDEO_VPX_1_PARTITION = 0, - V4L2_CID_MPEG_VIDEO_VPX_2_PARTITIONS = 1, - V4L2_CID_MPEG_VIDEO_VPX_4_PARTITIONS = 2, - V4L2_CID_MPEG_VIDEO_VPX_8_PARTITIONS = 3, -}; -#define V4L2_CID_MPEG_VIDEO_VPX_IMD_DISABLE_4X4 (V4L2_CID_MPEG_BASE+501) -#define V4L2_CID_MPEG_VIDEO_VPX_NUM_REF_FRAMES (V4L2_CID_MPEG_BASE+502) -enum v4l2_vp8_num_ref_frames { - V4L2_CID_MPEG_VIDEO_VPX_1_REF_FRAME = 0, - V4L2_CID_MPEG_VIDEO_VPX_2_REF_FRAME = 1, - V4L2_CID_MPEG_VIDEO_VPX_3_REF_FRAME = 2, -}; -#define V4L2_CID_MPEG_VIDEO_VPX_FILTER_LEVEL (V4L2_CID_MPEG_BASE+503) -#define V4L2_CID_MPEG_VIDEO_VPX_FILTER_SHARPNESS (V4L2_CID_MPEG_BASE+504) -#define V4L2_CID_MPEG_VIDEO_VPX_GOLDEN_FRAME_REF_PERIOD (V4L2_CID_MPEG_BASE+505) -#define V4L2_CID_MPEG_VIDEO_VPX_GOLDEN_FRAME_SEL (V4L2_CID_MPEG_BASE+506) -enum v4l2_vp8_golden_frame_sel { - V4L2_CID_MPEG_VIDEO_VPX_GOLDEN_FRAME_USE_PREV = 0, - V4L2_CID_MPEG_VIDEO_VPX_GOLDEN_FRAME_USE_REF_PERIOD = 1, -}; -#define V4L2_CID_MPEG_VIDEO_VPX_MIN_QP (V4L2_CID_MPEG_BASE+507) -#define V4L2_CID_MPEG_VIDEO_VPX_MAX_QP (V4L2_CID_MPEG_BASE+508) -#define V4L2_CID_MPEG_VIDEO_VPX_I_FRAME_QP (V4L2_CID_MPEG_BASE+509) -#define V4L2_CID_MPEG_VIDEO_VPX_P_FRAME_QP (V4L2_CID_MPEG_BASE+510) -#define V4L2_CID_MPEG_VIDEO_VPX_PROFILE (V4L2_CID_MPEG_BASE+511) - -/* MPEG-class control IDs specific to the CX2341x driver as defined by V4L2 */ -#define V4L2_CID_MPEG_CX2341X_BASE (V4L2_CTRL_CLASS_MPEG | 0x1000) -#define V4L2_CID_MPEG_CX2341X_VIDEO_SPATIAL_FILTER_MODE (V4L2_CID_MPEG_CX2341X_BASE+0) -enum v4l2_mpeg_cx2341x_video_spatial_filter_mode { - V4L2_MPEG_CX2341X_VIDEO_SPATIAL_FILTER_MODE_MANUAL = 0, - V4L2_MPEG_CX2341X_VIDEO_SPATIAL_FILTER_MODE_AUTO = 1, -}; -#define V4L2_CID_MPEG_CX2341X_VIDEO_SPATIAL_FILTER (V4L2_CID_MPEG_CX2341X_BASE+1) -#define V4L2_CID_MPEG_CX2341X_VIDEO_LUMA_SPATIAL_FILTER_TYPE (V4L2_CID_MPEG_CX2341X_BASE+2) -enum v4l2_mpeg_cx2341x_video_luma_spatial_filter_type { - V4L2_MPEG_CX2341X_VIDEO_LUMA_SPATIAL_FILTER_TYPE_OFF = 0, - V4L2_MPEG_CX2341X_VIDEO_LUMA_SPATIAL_FILTER_TYPE_1D_HOR = 1, - V4L2_MPEG_CX2341X_VIDEO_LUMA_SPATIAL_FILTER_TYPE_1D_VERT = 2, - V4L2_MPEG_CX2341X_VIDEO_LUMA_SPATIAL_FILTER_TYPE_2D_HV_SEPARABLE = 3, - V4L2_MPEG_CX2341X_VIDEO_LUMA_SPATIAL_FILTER_TYPE_2D_SYM_NON_SEPARABLE = 4, -}; -#define V4L2_CID_MPEG_CX2341X_VIDEO_CHROMA_SPATIAL_FILTER_TYPE (V4L2_CID_MPEG_CX2341X_BASE+3) -enum v4l2_mpeg_cx2341x_video_chroma_spatial_filter_type { - V4L2_MPEG_CX2341X_VIDEO_CHROMA_SPATIAL_FILTER_TYPE_OFF = 0, - V4L2_MPEG_CX2341X_VIDEO_CHROMA_SPATIAL_FILTER_TYPE_1D_HOR = 1, -}; -#define V4L2_CID_MPEG_CX2341X_VIDEO_TEMPORAL_FILTER_MODE (V4L2_CID_MPEG_CX2341X_BASE+4) -enum v4l2_mpeg_cx2341x_video_temporal_filter_mode { - V4L2_MPEG_CX2341X_VIDEO_TEMPORAL_FILTER_MODE_MANUAL = 0, - V4L2_MPEG_CX2341X_VIDEO_TEMPORAL_FILTER_MODE_AUTO = 1, -}; -#define V4L2_CID_MPEG_CX2341X_VIDEO_TEMPORAL_FILTER (V4L2_CID_MPEG_CX2341X_BASE+5) -#define V4L2_CID_MPEG_CX2341X_VIDEO_MEDIAN_FILTER_TYPE (V4L2_CID_MPEG_CX2341X_BASE+6) -enum v4l2_mpeg_cx2341x_video_median_filter_type { - V4L2_MPEG_CX2341X_VIDEO_MEDIAN_FILTER_TYPE_OFF = 0, - V4L2_MPEG_CX2341X_VIDEO_MEDIAN_FILTER_TYPE_HOR = 1, - V4L2_MPEG_CX2341X_VIDEO_MEDIAN_FILTER_TYPE_VERT = 2, - V4L2_MPEG_CX2341X_VIDEO_MEDIAN_FILTER_TYPE_HOR_VERT = 3, - V4L2_MPEG_CX2341X_VIDEO_MEDIAN_FILTER_TYPE_DIAG = 4, -}; -#define V4L2_CID_MPEG_CX2341X_VIDEO_LUMA_MEDIAN_FILTER_BOTTOM (V4L2_CID_MPEG_CX2341X_BASE+7) -#define V4L2_CID_MPEG_CX2341X_VIDEO_LUMA_MEDIAN_FILTER_TOP (V4L2_CID_MPEG_CX2341X_BASE+8) -#define V4L2_CID_MPEG_CX2341X_VIDEO_CHROMA_MEDIAN_FILTER_BOTTOM (V4L2_CID_MPEG_CX2341X_BASE+9) -#define V4L2_CID_MPEG_CX2341X_VIDEO_CHROMA_MEDIAN_FILTER_TOP (V4L2_CID_MPEG_CX2341X_BASE+10) -#define V4L2_CID_MPEG_CX2341X_STREAM_INSERT_NAV_PACKETS (V4L2_CID_MPEG_CX2341X_BASE+11) - -/* MPEG-class control IDs specific to the Samsung MFC 5.1 driver as defined by V4L2 */ -#define V4L2_CID_MPEG_MFC51_BASE (V4L2_CTRL_CLASS_MPEG | 0x1100) - -#define V4L2_CID_MPEG_MFC51_VIDEO_DECODER_H264_DISPLAY_DELAY (V4L2_CID_MPEG_MFC51_BASE+0) -#define V4L2_CID_MPEG_MFC51_VIDEO_DECODER_H264_DISPLAY_DELAY_ENABLE (V4L2_CID_MPEG_MFC51_BASE+1) -#define V4L2_CID_MPEG_MFC51_VIDEO_FRAME_SKIP_MODE (V4L2_CID_MPEG_MFC51_BASE+2) -enum v4l2_mpeg_mfc51_video_frame_skip_mode { - V4L2_MPEG_MFC51_VIDEO_FRAME_SKIP_MODE_DISABLED = 0, - V4L2_MPEG_MFC51_VIDEO_FRAME_SKIP_MODE_LEVEL_LIMIT = 1, - V4L2_MPEG_MFC51_VIDEO_FRAME_SKIP_MODE_BUF_LIMIT = 2, -}; -#define V4L2_CID_MPEG_MFC51_VIDEO_FORCE_FRAME_TYPE (V4L2_CID_MPEG_MFC51_BASE+3) -enum v4l2_mpeg_mfc51_video_force_frame_type { - V4L2_MPEG_MFC51_VIDEO_FORCE_FRAME_TYPE_DISABLED = 0, - V4L2_MPEG_MFC51_VIDEO_FORCE_FRAME_TYPE_I_FRAME = 1, - V4L2_MPEG_MFC51_VIDEO_FORCE_FRAME_TYPE_NOT_CODED = 2, -}; -#define V4L2_CID_MPEG_MFC51_VIDEO_PADDING (V4L2_CID_MPEG_MFC51_BASE+4) -#define V4L2_CID_MPEG_MFC51_VIDEO_PADDING_YUV (V4L2_CID_MPEG_MFC51_BASE+5) -#define V4L2_CID_MPEG_MFC51_VIDEO_RC_FIXED_TARGET_BIT (V4L2_CID_MPEG_MFC51_BASE+6) -#define V4L2_CID_MPEG_MFC51_VIDEO_RC_REACTION_COEFF (V4L2_CID_MPEG_MFC51_BASE+7) -#define V4L2_CID_MPEG_MFC51_VIDEO_H264_ADAPTIVE_RC_ACTIVITY (V4L2_CID_MPEG_MFC51_BASE+50) -#define V4L2_CID_MPEG_MFC51_VIDEO_H264_ADAPTIVE_RC_DARK (V4L2_CID_MPEG_MFC51_BASE+51) -#define V4L2_CID_MPEG_MFC51_VIDEO_H264_ADAPTIVE_RC_SMOOTH (V4L2_CID_MPEG_MFC51_BASE+52) -#define V4L2_CID_MPEG_MFC51_VIDEO_H264_ADAPTIVE_RC_STATIC (V4L2_CID_MPEG_MFC51_BASE+53) -#define V4L2_CID_MPEG_MFC51_VIDEO_H264_NUM_REF_PIC_FOR_P (V4L2_CID_MPEG_MFC51_BASE+54) - -/* MPEG-class control IDs specific to the msm_vidc driver */ -#define V4L2_CID_MPEG_MSM_VIDC_BASE (V4L2_CTRL_CLASS_MPEG | 0x2000) - -#define V4L2_CID_MPEG_VIDC_VIDEO_PICTYPE_DEC_MODE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE+0) -enum v4l2_mpeg_vidc_video_pictype_dec_mode { - V4L2_MPEG_VIDC_VIDEO_PICTYPE_DECODE_OFF = 0, - V4L2_MPEG_VIDC_VIDEO_PICTYPE_DECODE_ON = 1, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_KEEP_ASPECT_RATIO \ - (V4L2_CID_MPEG_MSM_VIDC_BASE+1) - -#define V4L2_CID_MPEG_VIDC_VIDEO_STREAM_FORMAT (V4L2_CID_MPEG_MSM_VIDC_BASE+2) -enum v4l2_mpeg_vidc_video_stream_format { - V4L2_MPEG_VIDC_VIDEO_NAL_FORMAT_STARTCODES = 0, - V4L2_MPEG_VIDC_VIDEO_NAL_FORMAT_ONE_NAL_PER_BUFFER = 1, - V4L2_MPEG_VIDC_VIDEO_NAL_FORMAT_ONE_BYTE_LENGTH = 2, - V4L2_MPEG_VIDC_VIDEO_NAL_FORMAT_TWO_BYTE_LENGTH = 3, - V4L2_MPEG_VIDC_VIDEO_NAL_FORMAT_FOUR_BYTE_LENGTH = 4, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_OUTPUT_ORDER (V4L2_CID_MPEG_MSM_VIDC_BASE+3) -enum v4l2_mpeg_vidc_video_output_order { - V4L2_MPEG_VIDC_VIDEO_OUTPUT_ORDER_DISPLAY = 0, - V4L2_MPEG_VIDC_VIDEO_OUTPUT_ORDER_DECODE = 1, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_FRAME_RATE (V4L2_CID_MPEG_MSM_VIDC_BASE+4) -#define V4L2_CID_MPEG_VIDC_VIDEO_IDR_PERIOD (V4L2_CID_MPEG_MSM_VIDC_BASE+5) -#define V4L2_CID_MPEG_VIDC_VIDEO_NUM_P_FRAMES (V4L2_CID_MPEG_MSM_VIDC_BASE+6) -#define V4L2_CID_MPEG_VIDC_VIDEO_NUM_B_FRAMES (V4L2_CID_MPEG_MSM_VIDC_BASE+7) -#define V4L2_CID_MPEG_VIDC_VIDEO_REQUEST_IFRAME (V4L2_CID_MPEG_MSM_VIDC_BASE+8) - -#define V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL (V4L2_CID_MPEG_MSM_VIDC_BASE+9) -enum v4l2_mpeg_vidc_video_rate_control { - V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_OFF = 0, - V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_VBR_VFR = 1, - V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_VBR_CFR = 2, - V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_CBR_VFR = 3, - V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_CBR_CFR = 4, - V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_MBR_CFR = 5, - V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_MBR_VFR = 6, - V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_CQ = 7, -}; -#define V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_MBR_CFR \ - V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_MBR_CFR -#define V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_MBR_VFR \ - V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_MBR_VFR - -#define V4L2_CID_MPEG_VIDC_VIDEO_ROTATION (V4L2_CID_MPEG_MSM_VIDC_BASE+10) -enum v4l2_mpeg_vidc_video_rotation { - V4L2_CID_MPEG_VIDC_VIDEO_ROTATION_NONE = 0, - V4L2_CID_MPEG_VIDC_VIDEO_ROTATION_90 = 1, - V4L2_CID_MPEG_VIDC_VIDEO_ROTATION_180 = 2, - V4L2_CID_MPEG_VIDC_VIDEO_ROTATION_270 = 3, -}; -#define V4L2_CID_MPEG_VIDC_VIDEO_H264_CABAC_MODEL \ - (V4L2_CID_MPEG_MSM_VIDC_BASE+11) -enum v4l2_mpeg_vidc_h264_cabac_model { - V4L2_CID_MPEG_VIDC_VIDEO_H264_CABAC_MODEL_0 = 0, - V4L2_CID_MPEG_VIDC_VIDEO_H264_CABAC_MODEL_1 = 1, - V4L2_CID_MPEG_VIDC_VIDEO_H264_CABAC_MODEL_2 = 2, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_INTRA_REFRESH_MODE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE+12) -enum v4l2_mpeg_vidc_video_intra_refresh_mode { - V4L2_CID_MPEG_VIDC_VIDEO_INTRA_REFRESH_NONE = 0, - V4L2_CID_MPEG_VIDC_VIDEO_INTRA_REFRESH_CYCLIC = 1, - V4L2_CID_MPEG_VIDC_VIDEO_INTRA_REFRESH_RANDOM = 2, - V4L2_CID_MPEG_VIDC_VIDEO_INTRA_REFRESH_ADAPTIVE = 3, - V4L2_CID_MPEG_VIDC_VIDEO_INTRA_REFRESH_CYCLIC_ADAPTIVE = 4, -}; -#define V4L2_CID_MPEG_VIDC_VIDEO_IR_MBS (V4L2_CID_MPEG_MSM_VIDC_BASE+13) - -#define V4L2_CID_MPEG_VIDC_VIDEO_AU_DELIMITER \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 14) -enum v4l2_mpeg_vidc_video_au_delimiter { - V4L2_MPEG_VIDC_VIDEO_AU_DELIMITER_DISABLED = 0, - V4L2_MPEG_VIDC_VIDEO_AU_DELIMITER_ENABLED = 1 -}; -#define V4L2_CID_MPEG_VIDC_VIDEO_SYNC_FRAME_DECODE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 15) -enum v4l2_mpeg_vidc_video_sync_frame_decode { - V4L2_MPEG_VIDC_VIDEO_SYNC_FRAME_DECODE_DISABLE = 0, - V4L2_MPEG_VIDC_VIDEO_SYNC_FRAME_DECODE_ENABLE = 1 -}; -#define V4L2_CID_MPEG_VIDC_VIDEO_SECURE (V4L2_CID_MPEG_MSM_VIDC_BASE+16) -#define V4L2_CID_MPEG_VIDC_VIDEO_EXTRADATA \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 17) -enum v4l2_mpeg_vidc_extradata { - V4L2_MPEG_VIDC_EXTRADATA_NONE = 0, - V4L2_MPEG_VIDC_EXTRADATA_MB_QUANTIZATION = 1, - V4L2_MPEG_VIDC_EXTRADATA_INTERLACE_VIDEO = 2, - V4L2_MPEG_VIDC_EXTRADATA_VC1_FRAMEDISP = 3, - V4L2_MPEG_VIDC_EXTRADATA_VC1_SEQDISP = 4, - V4L2_MPEG_VIDC_EXTRADATA_TIMESTAMP = 5, - V4L2_MPEG_VIDC_EXTRADATA_S3D_FRAME_PACKING = 6, - V4L2_MPEG_VIDC_EXTRADATA_FRAME_RATE = 7, - V4L2_MPEG_VIDC_EXTRADATA_PANSCAN_WINDOW = 8, - V4L2_MPEG_VIDC_EXTRADATA_RECOVERY_POINT_SEI = 9, - V4L2_MPEG_VIDC_EXTRADATA_MULTISLICE_INFO = 10, - V4L2_MPEG_VIDC_EXTRADATA_NUM_CONCEALED_MB = 11, - V4L2_MPEG_VIDC_EXTRADATA_METADATA_FILLER = 12, - V4L2_MPEG_VIDC_EXTRADATA_INPUT_CROP = 13, - V4L2_MPEG_VIDC_EXTRADATA_DIGITAL_ZOOM = 14, - V4L2_MPEG_VIDC_EXTRADATA_ASPECT_RATIO = 15, - V4L2_MPEG_VIDC_EXTRADATA_MPEG2_SEQDISP = 16, - V4L2_MPEG_VIDC_EXTRADATA_STREAM_USERDATA = 17, - V4L2_MPEG_VIDC_EXTRADATA_FRAME_QP = 18, - V4L2_MPEG_VIDC_EXTRADATA_FRAME_BITS_INFO = 19, - V4L2_MPEG_VIDC_EXTRADATA_LTR = 20, - V4L2_MPEG_VIDC_EXTRADATA_METADATA_MBI = 21, - V4L2_MPEG_VIDC_EXTRADATA_VQZIP_SEI = 22, - V4L2_MPEG_VIDC_EXTRADATA_YUV_STATS = 23, - V4L2_MPEG_VIDC_EXTRADATA_ROI_QP = 24, -#define V4L2_MPEG_VIDC_EXTRADATA_OUTPUT_CROP \ - V4L2_MPEG_VIDC_EXTRADATA_OUTPUT_CROP - V4L2_MPEG_VIDC_EXTRADATA_OUTPUT_CROP = 25, -#define V4L2_MPEG_VIDC_EXTRADATA_DISPLAY_COLOUR_SEI \ - V4L2_MPEG_VIDC_EXTRADATA_DISPLAY_COLOUR_SEI - V4L2_MPEG_VIDC_EXTRADATA_DISPLAY_COLOUR_SEI = 26, -#define V4L2_MPEG_VIDC_EXTRADATA_CONTENT_LIGHT_LEVEL_SEI \ - V4L2_MPEG_VIDC_EXTRADATA_CONTENT_LIGHT_LEVEL_SEI - V4L2_MPEG_VIDC_EXTRADATA_CONTENT_LIGHT_LEVEL_SEI = 27, -#define V4L2_MPEG_VIDC_EXTRADATA_PQ_INFO \ - V4L2_MPEG_VIDC_EXTRADATA_PQ_INFO - V4L2_MPEG_VIDC_EXTRADATA_PQ_INFO = 28, -#define V4L2_MPEG_VIDC_EXTRADATA_VUI_DISPLAY \ - V4L2_MPEG_VIDC_EXTRADATA_VUI_DISPLAY - V4L2_MPEG_VIDC_EXTRADATA_VUI_DISPLAY = 29, -#define V4L2_MPEG_VIDC_EXTRADATA_VPX_COLORSPACE \ - V4L2_MPEG_VIDC_EXTRADATA_VPX_COLORSPACE - V4L2_MPEG_VIDC_EXTRADATA_VPX_COLORSPACE = 30, -#define V4L2_MPEG_VIDC_EXTRADATA_UBWC_CR_STATS_INFO \ - V4L2_MPEG_VIDC_EXTRADATA_UBWC_CR_STATS_INFO - V4L2_MPEG_VIDC_EXTRADATA_UBWC_CR_STATS_INFO = 31, -#define V4L2_MPEG_VIDC_EXTRADATA_ENC_FRAME_QP \ - V4L2_MPEG_VIDC_EXTRADATA_ENC_FRAME_QP - V4L2_MPEG_VIDC_EXTRADATA_ENC_FRAME_QP = 32, -}; - -#define V4L2_CID_MPEG_VIDEO_MULTI_SLICE_DELIVERY_MODE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 18) - -#define V4L2_CID_MPEG_VIDC_VIDEO_VUI_TIMING_INFO \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 19) -enum v4l2_mpeg_vidc_video_vui_timing_info { - V4L2_MPEG_VIDC_VIDEO_VUI_TIMING_INFO_DISABLED = 0, - V4L2_MPEG_VIDC_VIDEO_VUI_TIMING_INFO_ENABLED = 1 -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_VP8_PROFILE_LEVEL \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 20) -enum v4l2_mpeg_vidc_video_vp8_profile_level { - V4L2_MPEG_VIDC_VIDEO_VP8_UNUSED, - V4L2_MPEG_VIDC_VIDEO_VP8_VERSION_0, - V4L2_MPEG_VIDC_VIDEO_VP8_VERSION_1, - V4L2_MPEG_VIDC_VIDEO_VP8_VERSION_2, - V4L2_MPEG_VIDC_VIDEO_VP8_VERSION_3, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_PRESERVE_TEXT_QUALITY \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 21) -enum v4l2_mpeg_vidc_video_preserve_text_quality { - V4L2_MPEG_VIDC_VIDEO_PRESERVE_TEXT_QUALITY_DISABLED = 0, - V4L2_MPEG_VIDC_VIDEO_PRESERVE_TEXT_QUALITY_ENABLED = 1 -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_STREAM_OUTPUT_MODE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 22) -enum v4l2_mpeg_vidc_video_decoder_multi_stream { - V4L2_CID_MPEG_VIDC_VIDEO_STREAM_OUTPUT_PRIMARY = 0, - V4L2_CID_MPEG_VIDC_VIDEO_STREAM_OUTPUT_SECONDARY = 1, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_MPEG2_LEVEL (V4L2_CID_MPEG_MSM_VIDC_BASE+23) -enum v4l2_mpeg_vidc_video_mpeg2_level { - V4L2_MPEG_VIDC_VIDEO_MPEG2_LEVEL_0 = 0, - V4L2_MPEG_VIDC_VIDEO_MPEG2_LEVEL_1 = 1, - V4L2_MPEG_VIDC_VIDEO_MPEG2_LEVEL_2 = 2, - V4L2_MPEG_VIDC_VIDEO_MPEG2_LEVEL_3 = 3, -}; -#define V4L2_CID_MPEG_VIDC_VIDEO_MPEG2_PROFILE (V4L2_CID_MPEG_MSM_VIDC_BASE+24) -enum v4l2_mpeg_vidc_video_mpeg2_profile { - V4L2_MPEG_VIDC_VIDEO_MPEG2_PROFILE_SIMPLE = 0, - V4L2_MPEG_VIDC_VIDEO_MPEG2_PROFILE_MAIN = 1, - V4L2_MPEG_VIDC_VIDEO_MPEG2_PROFILE_422 = 2, - V4L2_MPEG_VIDC_VIDEO_MPEG2_PROFILE_SNR_SCALABLE = 3, - V4L2_MPEG_VIDC_VIDEO_MPEG2_PROFILE_SPATIAL_SCALABLE = 4, - V4L2_MPEG_VIDC_VIDEO_MPEG2_PROFILE_HIGH = 5, -}; - -enum v4l2_mpeg_vidc_video_mvc_layout { - V4L2_MPEG_VIDC_VIDEO_MVC_SEQUENTIAL = 0, - V4L2_MPEG_VIDC_VIDEO_MVC_TOP_BOTTOM = 1 -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_CONCEAL_COLOR \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 25) - -#define V4L2_CID_MPEG_VIDC_VIDEO_LTRMODE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 26) - -enum v4l2_mpeg_vidc_video_ltrmode { - V4L2_MPEG_VIDC_VIDEO_LTR_MODE_DISABLE = 0, - V4L2_MPEG_VIDC_VIDEO_LTR_MODE_MANUAL = 1, - V4L2_MPEG_VIDC_VIDEO_LTR_MODE_PERIODIC = 2 -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_LTRCOUNT \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 27) - -#define V4L2_CID_MPEG_VIDC_VIDEO_USELTRFRAME \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 28) - -#define V4L2_CID_MPEG_VIDC_VIDEO_MARKLTRFRAME \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 29) - -#define V4L2_CID_MPEG_VIDC_VIDEO_HIER_P_NUM_LAYERS \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 30) - -#define V4L2_CID_MPEG_VIDC_VIDEO_ALLOC_MODE_OUTPUT \ - (V4L2_CID_MPEG_MSM_VIDC_BASE+31) -enum v4l2_mpeg_vidc_video_alloc_mode_type { - V4L2_MPEG_VIDC_VIDEO_STATIC = 0, - V4L2_MPEG_VIDC_VIDEO_RING = 1, - V4L2_MPEG_VIDC_VIDEO_DYNAMIC = 2, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_IFRAME_X_RANGE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 32) - -#define V4L2_CID_MPEG_VIDC_VIDEO_PFRAME_X_RANGE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 33) - -#define V4L2_CID_MPEG_VIDC_VIDEO_BFRAME_X_RANGE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 34) - -#define V4L2_CID_MPEG_VIDC_VIDEO_IFRAME_Y_RANGE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 35) - -#define V4L2_CID_MPEG_VIDC_VIDEO_PFRAME_Y_RANGE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 36) - -#define V4L2_CID_MPEG_VIDC_VIDEO_BFRAME_Y_RANGE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 37) - -#define V4L2_CID_MPEG_VIDC_VIDEO_VPX_ERROR_RESILIENCE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 38) - -#define V4L2_CID_MPEG_VIDC_VIDEO_BUFFER_SIZE_LIMIT \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 39) - -enum vl42_mpeg_vidc_video_vpx_error_resilience { - V4L2_MPEG_VIDC_VIDEO_VPX_ERROR_RESILIENCE_DISABLED = 0, - V4L2_MPEG_VIDC_VIDEO_VPX_ERROR_RESILIENCE_ENABLED = 1, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_HEVC_PROFILE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 40) -enum v4l2_mpeg_video_hevc_profile { - V4L2_MPEG_VIDC_VIDEO_HEVC_PROFILE_MAIN = 0, - V4L2_MPEG_VIDC_VIDEO_HEVC_PROFILE_MAIN10 = 1, - V4L2_MPEG_VIDC_VIDEO_HEVC_PROFILE_MAIN_STILL_PIC = 2, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_HEVC_TIER_LEVEL \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 41) -enum v4l2_mpeg_video_hevc_level { - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_1 = 0, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_1 = 1, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_2 = 2, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_2 = 3, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_2_1 = 4, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_2_1 = 5, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_3 = 6, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_3 = 7, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_3_1 = 8, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_3_1 = 9, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_4 = 10, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_4 = 11, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_4_1 = 12, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_4_1 = 13, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_5 = 14, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_5 = 15, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_5_1 = 16, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_5_1 = 17, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_5_2 = 18, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_5_2 = 19, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_6 = 20, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_6 = 21, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_6_1 = 22, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_6_1 = 23, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_MAIN_TIER_LEVEL_6_2 = 24, - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_HIGH_TIER_LEVEL_6_2 = 25, -#define V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_UNKNOWN \ - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_UNKNOWN - V4L2_MPEG_VIDC_VIDEO_HEVC_LEVEL_UNKNOWN = 26, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_HIER_B_NUM_LAYERS \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 42) - -#define V4L2_CID_MPEG_VIDC_VIDEO_HYBRID_HIERP_MODE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 43) - -#define V4L2_CID_MPEG_VIDC_VIDEO_DPB_COLOR_FORMAT \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 44) - -enum v4l2_mpeg_vidc_video_dpb_color_format { - V4L2_MPEG_VIDC_VIDEO_DPB_COLOR_FMT_NONE = 0, - V4L2_MPEG_VIDC_VIDEO_DPB_COLOR_FMT_UBWC = 1, - V4L2_MPEG_VIDC_VIDEO_DPB_COLOR_FMT_TP10_UBWC = 2 -}; - -#define V4L2_CID_VIDC_QBUF_MODE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 45) -enum v4l2_vidc_qbuf_mode { - V4L2_VIDC_QBUF_STANDARD = 0, - V4L2_VIDC_QBUF_BATCHED = 1, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_MAX_HIERP_LAYERS \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 46) - -#define V4L2_CID_MPEG_VIDC_VIDEO_BASELAYER_ID \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 47) - -#define V4L2_CID_MPEG_VIDC_VENC_PARAM_SAR_WIDTH \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 48) - -#define V4L2_CID_MPEG_VIDC_VENC_PARAM_SAR_HEIGHT \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 49) - -#define V4L2_CID_MPEG_VIDC_VIDEO_VQZIP_SEI \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 50) - -enum v4l2_mpeg_vidc_video_vqzip_sei_enable { - V4L2_CID_MPEG_VIDC_VIDEO_VQZIP_SEI_DISABLE = 0, - V4L2_CID_MPEG_VIDC_VIDEO_VQZIP_SEI_ENABLE = 1 -}; - -#define V4L2_CID_MPEG_VIDC_VENC_PARAM_LAYER_BITRATE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 51) - -#define V4L2_CID_MPEG_VIDC_VIDEO_PRIORITY \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 52) - -enum v4l2_mpeg_vidc_video_priority { - V4L2_MPEG_VIDC_VIDEO_PRIORITY_REALTIME_ENABLE = 0, - V4L2_MPEG_VIDC_VIDEO_PRIORITY_REALTIME_DISABLE = 1, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_OPERATING_RATE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 53) - -#define V4L2_CID_MPEG_VIDC_VIDEO_VENC_BITRATE_TYPE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 54) - -enum v4l2_mpeg_vidc_video_venc_bitrate_type_enable { - V4L2_CID_MPEG_VIDC_VIDEO_VENC_BITRATE_DISABLE = 0, - V4L2_CID_MPEG_VIDC_VIDEO_VENC_BITRATE_ENABLE = 1 -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_VPE_CSC \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 55) - -enum v4l2_cid_mpeg_vidc_video_vpe_csc_type_enable { - V4L2_CID_MPEG_VIDC_VIDEO_VPE_CSC_DISABLE = 0, - V4L2_CID_MPEG_VIDC_VIDEO_VPE_CSC_ENABLE = 1 -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_LOWLATENCY_MODE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 56) - -enum v4l2_mpeg_vidc_video_lowlatency_mode { - V4L2_CID_MPEG_VIDC_VIDEO_LOWLATENCY_DISABLE = 0, - V4L2_CID_MPEG_VIDC_VIDEO_LOWLATENCY_ENABLE = 1, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_BLUR_WIDTH \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 57) - -#define V4L2_CID_MPEG_VIDC_VIDEO_BLUR_HEIGHT \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 58) - -#define V4L2_CID_MPEG_VIDC_VIDEO_H264_TRANSFORM_8x8 \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 59) -enum v4l2_mpeg_vidc_video_h264_transform_8x8 { - V4L2_MPEG_VIDC_VIDEO_H264_TRANSFORM_8x8_DISABLE = 0, - V4L2_MPEG_VIDC_VIDEO_H264_TRANSFORM_8x8_ENABLE = 1, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_COLOR_SPACE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 60) - -#define V4L2_CID_MPEG_VIDC_VIDEO_FULL_RANGE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 61) - -enum v4l2_cid_mpeg_vidc_video_full_range { - V4L2_CID_MPEG_VIDC_VIDEO_FULL_RANGE_DISABLE = 0, - V4L2_CID_MPEG_VIDC_VIDEO_FULL_RANGE_ENABLE = 1, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_TRANSFER_CHARS \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 62) - -#define V4L2_CID_MPEG_VIDC_VIDEO_MATRIX_COEFFS \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 63) - -#define V4L2_CID_MPEG_VIDC_VIDEO_IFRAME_SIZE_TYPE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 64) - -#define V4L2_CID_MPEG_VIDC_VIDEO_LAYER_ID \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 65) - -#define V4L2_CID_MPEG_VIDC_VIDEO_VP9_PROFILE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 66) -enum v4l2_mpeg_vidc_video_vp9_profile { - V4L2_MPEG_VIDC_VIDEO_VP9_PROFILE_UNUSED = 0, - V4L2_MPEG_VIDC_VIDEO_VP9_PROFILE_P0 = 1, - V4L2_MPEG_VIDC_VIDEO_VP9_PROFILE_P2_10 = 2, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_VP9_LEVEL \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 67) -enum v4l2_mpeg_vidc_video_vp9_level { - V4L2_MPEG_VIDC_VIDEO_VP9_LEVEL_UNUSED = 0, - V4L2_MPEG_VIDC_VIDEO_VP9_LEVEL_1 = 1, - V4L2_MPEG_VIDC_VIDEO_VP9_LEVEL_11 = 2, - V4L2_MPEG_VIDC_VIDEO_VP9_LEVEL_2 = 3, - V4L2_MPEG_VIDC_VIDEO_VP9_LEVEL_21 = 4, - V4L2_MPEG_VIDC_VIDEO_VP9_LEVEL_3 = 5, - V4L2_MPEG_VIDC_VIDEO_VP9_LEVEL_31 = 6, - V4L2_MPEG_VIDC_VIDEO_VP9_LEVEL_4 = 7, - V4L2_MPEG_VIDC_VIDEO_VP9_LEVEL_41 = 8, - V4L2_MPEG_VIDC_VIDEO_VP9_LEVEL_5 = 9, - V4L2_MPEG_VIDC_VIDEO_VP9_LEVEL_51 = 10, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_MB_ERROR_MAP_REPORTING \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 68) -#define V4L2_CID_MPEG_VIDC_VIDEO_CONTINUE_DATA_TRANSFER \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 69) - -#define V4L2_CID_MPEG_VIDC_VIDEO_ALLOC_MODE_INPUT \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 70) - -#define V4L2_CID_MPEG_VIDC_VIDEO_FRAME_ASSEMBLY \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 71) -enum v4l2_mpeg_vidc_video_assembly { - V4L2_MPEG_VIDC_FRAME_ASSEMBLY_DISABLE = 0, - V4L2_MPEG_VIDC_FRAME_ASSEMBLY_ENABLE = 1, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_H263_PROFILE\ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 72) -enum v4l2_mpeg_vidc_video_h263_profile { - V4L2_MPEG_VIDC_VIDEO_H263_PROFILE_BASELINE = 0, - V4L2_MPEG_VIDC_VIDEO_H263_PROFILE_H320CODING = 1, - V4L2_MPEG_VIDC_VIDEO_H263_PROFILE_BACKWARDCOMPATIBLE = 2, - V4L2_MPEG_VIDC_VIDEO_H263_PROFILE_ISWV2 = 3, - V4L2_MPEG_VIDC_VIDEO_H263_PROFILE_ISWV3 = 4, - V4L2_MPEG_VIDC_VIDEO_H263_PROFILE_HIGHCOMPRESSION = 5, - V4L2_MPEG_VIDC_VIDEO_H263_PROFILE_INTERNET = 6, - V4L2_MPEG_VIDC_VIDEO_H263_PROFILE_INTERLACE = 7, - V4L2_MPEG_VIDC_VIDEO_H263_PROFILE_HIGHLATENCY = 8, -}; - -#define V4L2_CID_MPEG_VIDEO_MIN_QP_PACKED \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 97) -#define V4L2_CID_MPEG_VIDEO_MAX_QP_PACKED \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 98) -#define V4L2_CID_MPEG_VIDC_VIDEO_I_FRAME_QP \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 99) -#define V4L2_CID_MPEG_VIDC_VIDEO_P_FRAME_QP \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 100) -#define V4L2_CID_MPEG_VIDC_VIDEO_B_FRAME_QP \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 101) -#define V4L2_CID_MPEG_VIDC_VIDEO_I_FRAME_QP_MIN \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 102) -#define V4L2_CID_MPEG_VIDC_VIDEO_P_FRAME_QP_MIN \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 103) -#define V4L2_CID_MPEG_VIDC_VIDEO_B_FRAME_QP_MIN \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 104) -#define V4L2_CID_MPEG_VIDC_VIDEO_I_FRAME_QP_MAX \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 105) -#define V4L2_CID_MPEG_VIDC_VIDEO_P_FRAME_QP_MAX \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 106) -#define V4L2_CID_MPEG_VIDC_VIDEO_B_FRAME_QP_MAX \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 107) -#define V4L2_CID_MPEG_VIDC_VIDEO_QP_MASK \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 108) - -enum v4l2_mpeg_vidc_video_venc_iframesize_type { - V4L2_CID_MPEG_VIDC_VIDEO_IFRAME_SIZE_DEFAULT, - V4L2_CID_MPEG_VIDC_VIDEO_IFRAME_SIZE_MEDIUM, - V4L2_CID_MPEG_VIDC_VIDEO_IFRAME_SIZE_HUGE, - V4L2_CID_MPEG_VIDC_VIDEO_IFRAME_SIZE_UNLIMITED, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_CONCEAL_COLOR_8BIT \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 109) -#define V4L2_CID_MPEG_VIDC_VIDEO_CONCEAL_COLOR_10BIT \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 110) - -#define V4L2_CID_MPEG_VIDC_VIDEO_TME_PROFILE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 111) - -enum v4l2_mpeg_vidc_video_tme_profile { - V4L2_MPEG_VIDC_VIDEO_TME_PROFILE_0 = 0, - V4L2_MPEG_VIDC_VIDEO_TME_PROFILE_1 = 1, - V4L2_MPEG_VIDC_VIDEO_TME_PROFILE_2 = 2, - V4L2_MPEG_VIDC_VIDEO_TME_PROFILE_3 = 3, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_TME_LEVEL \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 112) - -enum v4l2_mpeg_vidc_video_tme_level { - V4L2_MPEG_VIDC_VIDEO_TME_LEVEL_INTEGER = 0, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_TME_PAYLOAD_VERSION \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 113) - -#define V4L2_CID_MPEG_VIDC_VIDEO_VPE_CSC_CUSTOM_MATRIX \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 114) - -#define V4L2_CID_MPEG_VIDC_VIDEO_FLIP (V4L2_CID_MPEG_MSM_VIDC_BASE + 115) -enum v4l2_mpeg_vidc_video_flip { - V4L2_CID_MPEG_VIDC_VIDEO_FLIP_NONE = 0, - V4L2_CID_MPEG_VIDC_VIDEO_FLIP_HORI = 1, - V4L2_CID_MPEG_VIDC_VIDEO_FLIP_VERT = 2, - V4L2_CID_MPEG_VIDC_VIDEO_FLIP_BOTH = 3, -}; - -/* HDR SEI INFO related control IDs and definitions*/ -#define V4L2_MPEG_VIDC_VENC_HDR_INFO_ENABLED 1 -#define V4L2_MPEG_VIDC_VENC_HDR_INFO_DISABLED 0 - -#define V4L2_CID_MPEG_VIDC_VENC_HDR_INFO \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 116) -#define V4L2_CID_MPEG_VIDC_VENC_RGB_PRIMARY_00 \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 117) -#define V4L2_CID_MPEG_VIDC_VENC_RGB_PRIMARY_01 \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 118) -#define V4L2_CID_MPEG_VIDC_VENC_RGB_PRIMARY_10 \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 119) -#define V4L2_CID_MPEG_VIDC_VENC_RGB_PRIMARY_11 \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 120) -#define V4L2_CID_MPEG_VIDC_VENC_RGB_PRIMARY_20 \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 121) -#define V4L2_CID_MPEG_VIDC_VENC_RGB_PRIMARY_21 \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 122) -#define V4L2_CID_MPEG_VIDC_VENC_WHITEPOINT_X \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 123) -#define V4L2_CID_MPEG_VIDC_VENC_WHITEPOINT_Y \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 124) -#define V4L2_CID_MPEG_VIDC_VENC_MAX_DISP_LUM \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 125) -#define V4L2_CID_MPEG_VIDC_VENC_MIN_DISP_LUM \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 126) -#define V4L2_CID_MPEG_VIDC_VENC_MAX_CLL \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 127) -#define V4L2_CID_MPEG_VIDC_VENC_MAX_FLL \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 128) - -#define V4L2_CID_MPEG_VIDC_SET_PERF_LEVEL \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 129) -enum v4l2_mpeg_vidc_perf_level { - V4L2_CID_MPEG_VIDC_PERF_LEVEL_NOMINAL = 0, - V4L2_CID_MPEG_VIDC_PERF_LEVEL_PERFORMANCE = 1, - V4L2_CID_MPEG_VIDC_PERF_LEVEL_TURBO = 2, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_AIR_MBS (V4L2_CID_MPEG_MSM_VIDC_BASE + 130) -#define V4L2_CID_MPEG_VIDC_VIDEO_AIR_REF (V4L2_CID_MPEG_MSM_VIDC_BASE + 131) -#define V4L2_CID_MPEG_VIDC_VIDEO_CIR_MBS (V4L2_CID_MPEG_MSM_VIDC_BASE + 132) - -#define V4L2_CID_MPEG_VIDC_VIDEO_H264_VUI_TIMING_INFO \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 135) - -#define V4L2_CID_MPEG_VIDEO_MULTI_SLICE_GOB \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 136) - -#define V4L2_CID_MPEG_VIDC_VIDEO_H264_VUI_BITSTREAM_RESTRICT \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 137) -enum v4l2_mpeg_vidc_video_h264_vui_bitstream_restrict { - V4L2_MPEG_VIDC_VIDEO_H264_VUI_BITSTREAM_RESTRICT_DISABLED = 0, - V4L2_MPEG_VIDC_VIDEO_H264_VUI_BITSTREAM_RESTRICT_ENABLED = 1 -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_DEINTERLACE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 138) -enum v4l2_mpeg_vidc_video_deinterlace { - V4L2_CID_MPEG_VIDC_VIDEO_DEINTERLACE_DISABLED = 0, - V4L2_CID_MPEG_VIDC_VIDEO_DEINTERLACE_ENABLED = 1 -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_MPEG4_TIME_RESOLUTION \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 139) - -#define V4L2_CID_MPEG_VIDC_VIDEO_REQUEST_SEQ_HEADER \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 140) - -#define V4L2_CID_MPEG_VIDC_VIDEO_RATE_CONTROL_TIMESTAMP_MODE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 141) -enum v4l2_mpeg_vidc_video_rate_control_timestamp_mode { - V4L2_MPEG_VIDC_VIDEO_RATE_CONTROL_TIMESTAMP_MODE_HONOR = 0, - V4L2_MPEG_VIDC_VIDEO_RATE_CONTROL_TIMESTAMP_MODE_IGNORE = 1, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_ENABLE_INITIAL_QP \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 142) -enum vl42_mpeg_vidc_video_enable_initial_qp { - V4L2_CID_MPEG_VIDC_VIDEO_ENABLE_INITIAL_QP_IFRAME = 0x1, - V4L2_CID_MPEG_VIDC_VIDEO_ENABLE_INITIAL_QP_PFRAME = 0x2, - V4L2_CID_MPEG_VIDC_VIDEO_ENABLE_INITIAL_QP_BFRAME = 0x4, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_INITIAL_I_FRAME_QP \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 143) - -#define V4L2_CID_MPEG_VIDC_VIDEO_INITIAL_P_FRAME_QP \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 144) - -#define V4L2_CID_MPEG_VIDC_VIDEO_INITIAL_B_FRAME_QP \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 145) - -#define V4L2_CID_MPEG_VIDC_VIDEO_H264_NAL_SVC \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 146) - -#define V4L2_CID_MPEG_VIDC_VIDEO_PERF_MODE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 147) -enum v4l2_mpeg_vidc_video_perf_mode { - V4L2_MPEG_VIDC_VIDEO_PERF_MAX_QUALITY = 1, - V4L2_MPEG_VIDC_VIDEO_PERF_POWER_SAVE = 2 -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_MBI_STATISTICS_MODE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 148) - -#define V4L2_CID_MPEG_VIDC_VIDEO_CONFIG_QP \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 149) - -#define V4L2_CID_MPEG_VIDC_VIDEO_H264_PIC_ORDER_CNT \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 150) - -#define V4L2_CID_MPEG_VIDC_VIDEO_SCS_THRESHOLD \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 151) - -#define V4L2_CID_MPEG_VIDC_VIDEO_MVC_BUFFER_LAYOUT \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 152) - - -#define V4L2_CID_MPEG_VIDC_VIDEO_SECURE_SCALING_THRESHOLD \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 153) - -#define V4L2_CID_MPEG_VIDC_VIDEO_NON_SECURE_OUTPUT2 \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 154) - -#define V4L2_CID_MPEG_VIDC_VIDEO_VP8_MIN_QP (V4L2_CID_MPEG_MSM_VIDC_BASE + 155) -#define V4L2_CID_MPEG_VIDC_VIDEO_VP8_MAX_QP (V4L2_CID_MPEG_MSM_VIDC_BASE + 156) - -#define V4L2_CID_MPEG_VIDC_VIDEO_H263_LEVEL (V4L2_CID_MPEG_MSM_VIDC_BASE + 157) -enum v4l2_mpeg_vidc_video_h263_level { - V4L2_MPEG_VIDC_VIDEO_H263_LEVEL_1_0 = 0, - V4L2_MPEG_VIDC_VIDEO_H263_LEVEL_2_0 = 1, - V4L2_MPEG_VIDC_VIDEO_H263_LEVEL_3_0 = 2, - V4L2_MPEG_VIDC_VIDEO_H263_LEVEL_4_0 = 3, - V4L2_MPEG_VIDC_VIDEO_H263_LEVEL_4_5 = 4, - V4L2_MPEG_VIDC_VIDEO_H263_LEVEL_5_0 = 5, - V4L2_MPEG_VIDC_VIDEO_H263_LEVEL_6_0 = 6, - V4L2_MPEG_VIDC_VIDEO_H263_LEVEL_7_0 = 7, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_POST_LOOP_DEBLOCKER_MODE \ - (V4L2_CID_MPEG_MSM_VIDC_BASE + 158) - - -#define V4L2_CID_MPEG_VIDC_VIDEO_DIVX_FORMAT (V4L2_CID_MPEG_MSM_VIDC_BASE+159) - -enum v4l2_mpeg_vidc_video_divx_format_type { - V4L2_MPEG_VIDC_VIDEO_DIVX_FORMAT_4 = 0, - V4L2_MPEG_VIDC_VIDEO_DIVX_FORMAT_5 = 1, - V4L2_MPEG_VIDC_VIDEO_DIVX_FORMAT_6 = 2, -}; - -#define V4L2_CID_MPEG_VIDC_VIDEO_FRAME_QUALITY \ - (V4L2_CID_MPEG_MSM_VIDC_BASE+160) - -#define V4L2_CID_MPEG_VIDC_IMG_GRID_DIMENSION \ - (V4L2_CID_MPEG_MSM_VIDC_BASE+161) - -enum v4l2_mpeg_vidc_video_mbi_statistics_mode { - V4L2_CID_MPEG_VIDC_VIDEO_MBI_MODE_DEFAULT = 0, - V4L2_CID_MPEG_VIDC_VIDEO_MBI_MODE_1 = 1, - V4L2_CID_MPEG_VIDC_VIDEO_MBI_MODE_2 = 2, - V4L2_CID_MPEG_VIDC_VIDEO_MBI_MODE_3 = 3, -}; - -enum vl42_mpeg_vidc_video_h264_svc_nal { - V4L2_CID_MPEG_VIDC_VIDEO_H264_NAL_SVC_DISABLED = 0, - V4L2_CID_MPEG_VIDC_VIDEO_H264_NAL_SVC_ENABLED = 1, -}; - -enum v4l2_mpeg_vidc_video_h264_vui_timing_info { - V4L2_MPEG_VIDC_VIDEO_H264_VUI_TIMING_INFO_DISABLED = 0, - V4L2_MPEG_VIDC_VIDEO_H264_VUI_TIMING_INFO_ENABLED = 1 -}; - -/* Camera class control IDs */ - -#define V4L2_CID_CAMERA_CLASS_BASE (V4L2_CTRL_CLASS_CAMERA | 0x900) -#define V4L2_CID_CAMERA_CLASS (V4L2_CTRL_CLASS_CAMERA | 1) - -#define V4L2_CID_EXPOSURE_AUTO (V4L2_CID_CAMERA_CLASS_BASE+1) -enum v4l2_exposure_auto_type { - V4L2_EXPOSURE_AUTO = 0, - V4L2_EXPOSURE_MANUAL = 1, - V4L2_EXPOSURE_SHUTTER_PRIORITY = 2, - V4L2_EXPOSURE_APERTURE_PRIORITY = 3 -}; -#define V4L2_CID_EXPOSURE_ABSOLUTE (V4L2_CID_CAMERA_CLASS_BASE+2) -#define V4L2_CID_EXPOSURE_AUTO_PRIORITY (V4L2_CID_CAMERA_CLASS_BASE+3) - -#define V4L2_CID_PAN_RELATIVE (V4L2_CID_CAMERA_CLASS_BASE+4) -#define V4L2_CID_TILT_RELATIVE (V4L2_CID_CAMERA_CLASS_BASE+5) -#define V4L2_CID_PAN_RESET (V4L2_CID_CAMERA_CLASS_BASE+6) -#define V4L2_CID_TILT_RESET (V4L2_CID_CAMERA_CLASS_BASE+7) - -#define V4L2_CID_PAN_ABSOLUTE (V4L2_CID_CAMERA_CLASS_BASE+8) -#define V4L2_CID_TILT_ABSOLUTE (V4L2_CID_CAMERA_CLASS_BASE+9) - -#define V4L2_CID_FOCUS_ABSOLUTE (V4L2_CID_CAMERA_CLASS_BASE+10) -#define V4L2_CID_FOCUS_RELATIVE (V4L2_CID_CAMERA_CLASS_BASE+11) -#define V4L2_CID_FOCUS_AUTO (V4L2_CID_CAMERA_CLASS_BASE+12) - -#define V4L2_CID_ZOOM_ABSOLUTE (V4L2_CID_CAMERA_CLASS_BASE+13) -#define V4L2_CID_ZOOM_RELATIVE (V4L2_CID_CAMERA_CLASS_BASE+14) -#define V4L2_CID_ZOOM_CONTINUOUS (V4L2_CID_CAMERA_CLASS_BASE+15) - -#define V4L2_CID_PRIVACY (V4L2_CID_CAMERA_CLASS_BASE+16) - -#define V4L2_CID_IRIS_ABSOLUTE (V4L2_CID_CAMERA_CLASS_BASE+17) -#define V4L2_CID_IRIS_RELATIVE (V4L2_CID_CAMERA_CLASS_BASE+18) - -#define V4L2_CID_AUTO_EXPOSURE_BIAS (V4L2_CID_CAMERA_CLASS_BASE+19) - -#define V4L2_CID_AUTO_N_PRESET_WHITE_BALANCE (V4L2_CID_CAMERA_CLASS_BASE+20) -enum v4l2_auto_n_preset_white_balance { - V4L2_WHITE_BALANCE_MANUAL = 0, - V4L2_WHITE_BALANCE_AUTO = 1, - V4L2_WHITE_BALANCE_INCANDESCENT = 2, - V4L2_WHITE_BALANCE_FLUORESCENT = 3, - V4L2_WHITE_BALANCE_FLUORESCENT_H = 4, - V4L2_WHITE_BALANCE_HORIZON = 5, - V4L2_WHITE_BALANCE_DAYLIGHT = 6, - V4L2_WHITE_BALANCE_FLASH = 7, - V4L2_WHITE_BALANCE_CLOUDY = 8, - V4L2_WHITE_BALANCE_SHADE = 9, -}; - -#define V4L2_CID_WIDE_DYNAMIC_RANGE (V4L2_CID_CAMERA_CLASS_BASE+21) -#define V4L2_CID_IMAGE_STABILIZATION (V4L2_CID_CAMERA_CLASS_BASE+22) - -#define V4L2_CID_ISO_SENSITIVITY (V4L2_CID_CAMERA_CLASS_BASE+23) -#define V4L2_CID_ISO_SENSITIVITY_AUTO (V4L2_CID_CAMERA_CLASS_BASE+24) -enum v4l2_iso_sensitivity_auto_type { - V4L2_ISO_SENSITIVITY_MANUAL = 0, - V4L2_ISO_SENSITIVITY_AUTO = 1, -}; - -#define V4L2_CID_EXPOSURE_METERING (V4L2_CID_CAMERA_CLASS_BASE+25) -enum v4l2_exposure_metering { - V4L2_EXPOSURE_METERING_AVERAGE = 0, - V4L2_EXPOSURE_METERING_CENTER_WEIGHTED = 1, - V4L2_EXPOSURE_METERING_SPOT = 2, - V4L2_EXPOSURE_METERING_MATRIX = 3, -}; - -#define V4L2_CID_SCENE_MODE (V4L2_CID_CAMERA_CLASS_BASE+26) -enum v4l2_scene_mode { - V4L2_SCENE_MODE_NONE = 0, - V4L2_SCENE_MODE_BACKLIGHT = 1, - V4L2_SCENE_MODE_BEACH_SNOW = 2, - V4L2_SCENE_MODE_CANDLE_LIGHT = 3, - V4L2_SCENE_MODE_DAWN_DUSK = 4, - V4L2_SCENE_MODE_FALL_COLORS = 5, - V4L2_SCENE_MODE_FIREWORKS = 6, - V4L2_SCENE_MODE_LANDSCAPE = 7, - V4L2_SCENE_MODE_NIGHT = 8, - V4L2_SCENE_MODE_PARTY_INDOOR = 9, - V4L2_SCENE_MODE_PORTRAIT = 10, - V4L2_SCENE_MODE_SPORTS = 11, - V4L2_SCENE_MODE_SUNSET = 12, - V4L2_SCENE_MODE_TEXT = 13, -}; - -#define V4L2_CID_3A_LOCK (V4L2_CID_CAMERA_CLASS_BASE+27) -#define V4L2_LOCK_EXPOSURE (1 << 0) -#define V4L2_LOCK_WHITE_BALANCE (1 << 1) -#define V4L2_LOCK_FOCUS (1 << 2) - -#define V4L2_CID_AUTO_FOCUS_START (V4L2_CID_CAMERA_CLASS_BASE+28) -#define V4L2_CID_AUTO_FOCUS_STOP (V4L2_CID_CAMERA_CLASS_BASE+29) -#define V4L2_CID_AUTO_FOCUS_STATUS (V4L2_CID_CAMERA_CLASS_BASE+30) -#define V4L2_AUTO_FOCUS_STATUS_IDLE (0 << 0) -#define V4L2_AUTO_FOCUS_STATUS_BUSY (1 << 0) -#define V4L2_AUTO_FOCUS_STATUS_REACHED (1 << 1) -#define V4L2_AUTO_FOCUS_STATUS_FAILED (1 << 2) - -#define V4L2_CID_AUTO_FOCUS_RANGE (V4L2_CID_CAMERA_CLASS_BASE+31) -enum v4l2_auto_focus_range { - V4L2_AUTO_FOCUS_RANGE_AUTO = 0, - V4L2_AUTO_FOCUS_RANGE_NORMAL = 1, - V4L2_AUTO_FOCUS_RANGE_MACRO = 2, - V4L2_AUTO_FOCUS_RANGE_INFINITY = 3, -}; - -#define V4L2_CID_PAN_SPEED (V4L2_CID_CAMERA_CLASS_BASE+32) -#define V4L2_CID_TILT_SPEED (V4L2_CID_CAMERA_CLASS_BASE+33) - -/* FM Modulator class control IDs */ - -#define V4L2_CID_FM_TX_CLASS_BASE (V4L2_CTRL_CLASS_FM_TX | 0x900) -#define V4L2_CID_FM_TX_CLASS (V4L2_CTRL_CLASS_FM_TX | 1) - -#define V4L2_CID_RDS_TX_DEVIATION (V4L2_CID_FM_TX_CLASS_BASE + 1) -#define V4L2_CID_RDS_TX_PI (V4L2_CID_FM_TX_CLASS_BASE + 2) -#define V4L2_CID_RDS_TX_PTY (V4L2_CID_FM_TX_CLASS_BASE + 3) -#define V4L2_CID_RDS_TX_PS_NAME (V4L2_CID_FM_TX_CLASS_BASE + 5) -#define V4L2_CID_RDS_TX_RADIO_TEXT (V4L2_CID_FM_TX_CLASS_BASE + 6) -#define V4L2_CID_RDS_TX_MONO_STEREO (V4L2_CID_FM_TX_CLASS_BASE + 7) -#define V4L2_CID_RDS_TX_ARTIFICIAL_HEAD (V4L2_CID_FM_TX_CLASS_BASE + 8) -#define V4L2_CID_RDS_TX_COMPRESSED (V4L2_CID_FM_TX_CLASS_BASE + 9) -#define V4L2_CID_RDS_TX_DYNAMIC_PTY (V4L2_CID_FM_TX_CLASS_BASE + 10) -#define V4L2_CID_RDS_TX_TRAFFIC_ANNOUNCEMENT (V4L2_CID_FM_TX_CLASS_BASE + 11) -#define V4L2_CID_RDS_TX_TRAFFIC_PROGRAM (V4L2_CID_FM_TX_CLASS_BASE + 12) -#define V4L2_CID_RDS_TX_MUSIC_SPEECH (V4L2_CID_FM_TX_CLASS_BASE + 13) -#define V4L2_CID_RDS_TX_ALT_FREQS_ENABLE (V4L2_CID_FM_TX_CLASS_BASE + 14) -#define V4L2_CID_RDS_TX_ALT_FREQS (V4L2_CID_FM_TX_CLASS_BASE + 15) - -#define V4L2_CID_AUDIO_LIMITER_ENABLED (V4L2_CID_FM_TX_CLASS_BASE + 64) -#define V4L2_CID_AUDIO_LIMITER_RELEASE_TIME (V4L2_CID_FM_TX_CLASS_BASE + 65) -#define V4L2_CID_AUDIO_LIMITER_DEVIATION (V4L2_CID_FM_TX_CLASS_BASE + 66) - -#define V4L2_CID_AUDIO_COMPRESSION_ENABLED (V4L2_CID_FM_TX_CLASS_BASE + 80) -#define V4L2_CID_AUDIO_COMPRESSION_GAIN (V4L2_CID_FM_TX_CLASS_BASE + 81) -#define V4L2_CID_AUDIO_COMPRESSION_THRESHOLD (V4L2_CID_FM_TX_CLASS_BASE + 82) -#define V4L2_CID_AUDIO_COMPRESSION_ATTACK_TIME (V4L2_CID_FM_TX_CLASS_BASE + 83) -#define V4L2_CID_AUDIO_COMPRESSION_RELEASE_TIME (V4L2_CID_FM_TX_CLASS_BASE + 84) - -#define V4L2_CID_PILOT_TONE_ENABLED (V4L2_CID_FM_TX_CLASS_BASE + 96) -#define V4L2_CID_PILOT_TONE_DEVIATION (V4L2_CID_FM_TX_CLASS_BASE + 97) -#define V4L2_CID_PILOT_TONE_FREQUENCY (V4L2_CID_FM_TX_CLASS_BASE + 98) - -#define V4L2_CID_TUNE_PREEMPHASIS (V4L2_CID_FM_TX_CLASS_BASE + 112) -enum v4l2_preemphasis { - V4L2_PREEMPHASIS_DISABLED = 0, - V4L2_PREEMPHASIS_50_uS = 1, - V4L2_PREEMPHASIS_75_uS = 2, -}; -#define V4L2_CID_TUNE_POWER_LEVEL (V4L2_CID_FM_TX_CLASS_BASE + 113) -#define V4L2_CID_TUNE_ANTENNA_CAPACITOR (V4L2_CID_FM_TX_CLASS_BASE + 114) - - -/* Flash and privacy (indicator) light controls */ - -#define V4L2_CID_FLASH_CLASS_BASE (V4L2_CTRL_CLASS_FLASH | 0x900) -#define V4L2_CID_FLASH_CLASS (V4L2_CTRL_CLASS_FLASH | 1) - -#define V4L2_CID_FLASH_LED_MODE (V4L2_CID_FLASH_CLASS_BASE + 1) -enum v4l2_flash_led_mode { - V4L2_FLASH_LED_MODE_NONE, - V4L2_FLASH_LED_MODE_FLASH, - V4L2_FLASH_LED_MODE_TORCH, -}; - -#define V4L2_CID_FLASH_STROBE_SOURCE (V4L2_CID_FLASH_CLASS_BASE + 2) -enum v4l2_flash_strobe_source { - V4L2_FLASH_STROBE_SOURCE_SOFTWARE, - V4L2_FLASH_STROBE_SOURCE_EXTERNAL, -}; - -#define V4L2_CID_FLASH_STROBE (V4L2_CID_FLASH_CLASS_BASE + 3) -#define V4L2_CID_FLASH_STROBE_STOP (V4L2_CID_FLASH_CLASS_BASE + 4) -#define V4L2_CID_FLASH_STROBE_STATUS (V4L2_CID_FLASH_CLASS_BASE + 5) - -#define V4L2_CID_FLASH_TIMEOUT (V4L2_CID_FLASH_CLASS_BASE + 6) -#define V4L2_CID_FLASH_INTENSITY (V4L2_CID_FLASH_CLASS_BASE + 7) -#define V4L2_CID_FLASH_TORCH_INTENSITY (V4L2_CID_FLASH_CLASS_BASE + 8) -#define V4L2_CID_FLASH_INDICATOR_INTENSITY (V4L2_CID_FLASH_CLASS_BASE + 9) - -#define V4L2_CID_FLASH_FAULT (V4L2_CID_FLASH_CLASS_BASE + 10) -#define V4L2_FLASH_FAULT_OVER_VOLTAGE (1 << 0) -#define V4L2_FLASH_FAULT_TIMEOUT (1 << 1) -#define V4L2_FLASH_FAULT_OVER_TEMPERATURE (1 << 2) -#define V4L2_FLASH_FAULT_SHORT_CIRCUIT (1 << 3) -#define V4L2_FLASH_FAULT_OVER_CURRENT (1 << 4) -#define V4L2_FLASH_FAULT_INDICATOR (1 << 5) -#define V4L2_FLASH_FAULT_UNDER_VOLTAGE (1 << 6) -#define V4L2_FLASH_FAULT_INPUT_VOLTAGE (1 << 7) -#define V4L2_FLASH_FAULT_LED_OVER_TEMPERATURE (1 << 8) - -#define V4L2_CID_FLASH_CHARGE (V4L2_CID_FLASH_CLASS_BASE + 11) -#define V4L2_CID_FLASH_READY (V4L2_CID_FLASH_CLASS_BASE + 12) - - -/* JPEG-class control IDs */ - -#define V4L2_CID_JPEG_CLASS_BASE (V4L2_CTRL_CLASS_JPEG | 0x900) -#define V4L2_CID_JPEG_CLASS (V4L2_CTRL_CLASS_JPEG | 1) - -#define V4L2_CID_JPEG_CHROMA_SUBSAMPLING (V4L2_CID_JPEG_CLASS_BASE + 1) -enum v4l2_jpeg_chroma_subsampling { - V4L2_JPEG_CHROMA_SUBSAMPLING_444 = 0, - V4L2_JPEG_CHROMA_SUBSAMPLING_422 = 1, - V4L2_JPEG_CHROMA_SUBSAMPLING_420 = 2, - V4L2_JPEG_CHROMA_SUBSAMPLING_411 = 3, - V4L2_JPEG_CHROMA_SUBSAMPLING_410 = 4, - V4L2_JPEG_CHROMA_SUBSAMPLING_GRAY = 5, -}; -#define V4L2_CID_JPEG_RESTART_INTERVAL (V4L2_CID_JPEG_CLASS_BASE + 2) -#define V4L2_CID_JPEG_COMPRESSION_QUALITY (V4L2_CID_JPEG_CLASS_BASE + 3) - -#define V4L2_CID_JPEG_ACTIVE_MARKER (V4L2_CID_JPEG_CLASS_BASE + 4) -#define V4L2_JPEG_ACTIVE_MARKER_APP0 (1 << 0) -#define V4L2_JPEG_ACTIVE_MARKER_APP1 (1 << 1) -#define V4L2_JPEG_ACTIVE_MARKER_COM (1 << 16) -#define V4L2_JPEG_ACTIVE_MARKER_DQT (1 << 17) -#define V4L2_JPEG_ACTIVE_MARKER_DHT (1 << 18) - - -/* Image source controls */ -#define V4L2_CID_IMAGE_SOURCE_CLASS_BASE (V4L2_CTRL_CLASS_IMAGE_SOURCE | 0x900) -#define V4L2_CID_IMAGE_SOURCE_CLASS (V4L2_CTRL_CLASS_IMAGE_SOURCE | 1) - -#define V4L2_CID_VBLANK (V4L2_CID_IMAGE_SOURCE_CLASS_BASE + 1) -#define V4L2_CID_HBLANK (V4L2_CID_IMAGE_SOURCE_CLASS_BASE + 2) -#define V4L2_CID_ANALOGUE_GAIN (V4L2_CID_IMAGE_SOURCE_CLASS_BASE + 3) -#define V4L2_CID_TEST_PATTERN_RED (V4L2_CID_IMAGE_SOURCE_CLASS_BASE + 4) -#define V4L2_CID_TEST_PATTERN_GREENR (V4L2_CID_IMAGE_SOURCE_CLASS_BASE + 5) -#define V4L2_CID_TEST_PATTERN_BLUE (V4L2_CID_IMAGE_SOURCE_CLASS_BASE + 6) -#define V4L2_CID_TEST_PATTERN_GREENB (V4L2_CID_IMAGE_SOURCE_CLASS_BASE + 7) - - -/* Image processing controls */ - -#define V4L2_CID_IMAGE_PROC_CLASS_BASE (V4L2_CTRL_CLASS_IMAGE_PROC | 0x900) -#define V4L2_CID_IMAGE_PROC_CLASS (V4L2_CTRL_CLASS_IMAGE_PROC | 1) - -#define V4L2_CID_LINK_FREQ (V4L2_CID_IMAGE_PROC_CLASS_BASE + 1) -#define V4L2_CID_PIXEL_RATE (V4L2_CID_IMAGE_PROC_CLASS_BASE + 2) -#define V4L2_CID_TEST_PATTERN (V4L2_CID_IMAGE_PROC_CLASS_BASE + 3) - - -/* DV-class control IDs defined by V4L2 */ -#define V4L2_CID_DV_CLASS_BASE (V4L2_CTRL_CLASS_DV | 0x900) -#define V4L2_CID_DV_CLASS (V4L2_CTRL_CLASS_DV | 1) - -#define V4L2_CID_DV_TX_HOTPLUG (V4L2_CID_DV_CLASS_BASE + 1) -#define V4L2_CID_DV_TX_RXSENSE (V4L2_CID_DV_CLASS_BASE + 2) -#define V4L2_CID_DV_TX_EDID_PRESENT (V4L2_CID_DV_CLASS_BASE + 3) -#define V4L2_CID_DV_TX_MODE (V4L2_CID_DV_CLASS_BASE + 4) -enum v4l2_dv_tx_mode { - V4L2_DV_TX_MODE_DVI_D = 0, - V4L2_DV_TX_MODE_HDMI = 1, -}; -#define V4L2_CID_DV_TX_RGB_RANGE (V4L2_CID_DV_CLASS_BASE + 5) -enum v4l2_dv_rgb_range { - V4L2_DV_RGB_RANGE_AUTO = 0, - V4L2_DV_RGB_RANGE_LIMITED = 1, - V4L2_DV_RGB_RANGE_FULL = 2, -}; - -#define V4L2_CID_DV_TX_IT_CONTENT_TYPE (V4L2_CID_DV_CLASS_BASE + 6) -enum v4l2_dv_it_content_type { - V4L2_DV_IT_CONTENT_TYPE_GRAPHICS = 0, - V4L2_DV_IT_CONTENT_TYPE_PHOTO = 1, - V4L2_DV_IT_CONTENT_TYPE_CINEMA = 2, - V4L2_DV_IT_CONTENT_TYPE_GAME = 3, - V4L2_DV_IT_CONTENT_TYPE_NO_ITC = 4, -}; - -#define V4L2_CID_DV_RX_POWER_PRESENT (V4L2_CID_DV_CLASS_BASE + 100) -#define V4L2_CID_DV_RX_RGB_RANGE (V4L2_CID_DV_CLASS_BASE + 101) -#define V4L2_CID_DV_RX_IT_CONTENT_TYPE (V4L2_CID_DV_CLASS_BASE + 102) - -#define V4L2_CID_FM_RX_CLASS_BASE (V4L2_CTRL_CLASS_FM_RX | 0x900) -#define V4L2_CID_FM_RX_CLASS (V4L2_CTRL_CLASS_FM_RX | 1) - -#define V4L2_CID_TUNE_DEEMPHASIS (V4L2_CID_FM_RX_CLASS_BASE + 1) -enum v4l2_deemphasis { - V4L2_DEEMPHASIS_DISABLED = V4L2_PREEMPHASIS_DISABLED, - V4L2_DEEMPHASIS_50_uS = V4L2_PREEMPHASIS_50_uS, - V4L2_DEEMPHASIS_75_uS = V4L2_PREEMPHASIS_75_uS, -}; - -#define V4L2_CID_RDS_RECEPTION (V4L2_CID_FM_RX_CLASS_BASE + 2) -#define V4L2_CID_RDS_RX_PTY (V4L2_CID_FM_RX_CLASS_BASE + 3) -#define V4L2_CID_RDS_RX_PS_NAME (V4L2_CID_FM_RX_CLASS_BASE + 4) -#define V4L2_CID_RDS_RX_RADIO_TEXT (V4L2_CID_FM_RX_CLASS_BASE + 5) -#define V4L2_CID_RDS_RX_TRAFFIC_ANNOUNCEMENT (V4L2_CID_FM_RX_CLASS_BASE + 6) -#define V4L2_CID_RDS_RX_TRAFFIC_PROGRAM (V4L2_CID_FM_RX_CLASS_BASE + 7) -#define V4L2_CID_RDS_RX_MUSIC_SPEECH (V4L2_CID_FM_RX_CLASS_BASE + 8) - -#define V4L2_CID_RF_TUNER_CLASS_BASE (V4L2_CTRL_CLASS_RF_TUNER | 0x900) -#define V4L2_CID_RF_TUNER_CLASS (V4L2_CTRL_CLASS_RF_TUNER | 1) - -#define V4L2_CID_RF_TUNER_BANDWIDTH_AUTO (V4L2_CID_RF_TUNER_CLASS_BASE + 11) -#define V4L2_CID_RF_TUNER_BANDWIDTH (V4L2_CID_RF_TUNER_CLASS_BASE + 12) -#define V4L2_CID_RF_TUNER_RF_GAIN (V4L2_CID_RF_TUNER_CLASS_BASE + 32) -#define V4L2_CID_RF_TUNER_LNA_GAIN_AUTO (V4L2_CID_RF_TUNER_CLASS_BASE + 41) -#define V4L2_CID_RF_TUNER_LNA_GAIN (V4L2_CID_RF_TUNER_CLASS_BASE + 42) -#define V4L2_CID_RF_TUNER_MIXER_GAIN_AUTO (V4L2_CID_RF_TUNER_CLASS_BASE + 51) -#define V4L2_CID_RF_TUNER_MIXER_GAIN (V4L2_CID_RF_TUNER_CLASS_BASE + 52) -#define V4L2_CID_RF_TUNER_IF_GAIN_AUTO (V4L2_CID_RF_TUNER_CLASS_BASE + 61) -#define V4L2_CID_RF_TUNER_IF_GAIN (V4L2_CID_RF_TUNER_CLASS_BASE + 62) -#define V4L2_CID_RF_TUNER_PLL_LOCK (V4L2_CID_RF_TUNER_CLASS_BASE + 91) - - -/* Detection-class control IDs defined by V4L2 */ -#define V4L2_CID_DETECT_CLASS_BASE (V4L2_CTRL_CLASS_DETECT | 0x900) -#define V4L2_CID_DETECT_CLASS (V4L2_CTRL_CLASS_DETECT | 1) - -#define V4L2_CID_DETECT_MD_MODE (V4L2_CID_DETECT_CLASS_BASE + 1) -enum v4l2_detect_md_mode { - V4L2_DETECT_MD_MODE_DISABLED = 0, - V4L2_DETECT_MD_MODE_GLOBAL = 1, - V4L2_DETECT_MD_MODE_THRESHOLD_GRID = 2, - V4L2_DETECT_MD_MODE_REGION_GRID = 3, -}; -#define V4L2_CID_DETECT_MD_GLOBAL_THRESHOLD (V4L2_CID_DETECT_CLASS_BASE + 2) -#define V4L2_CID_DETECT_MD_THRESHOLD_GRID (V4L2_CID_DETECT_CLASS_BASE + 3) -#define V4L2_CID_DETECT_MD_REGION_GRID (V4L2_CID_DETECT_CLASS_BASE + 4) - -#endif diff --git a/third_party/maplibre-native-qt/aarch64~HEAD b/third_party/maplibre-native-qt/aarch64~HEAD new file mode 100644 index 0000000..062c65e --- /dev/null +++ b/third_party/maplibre-native-qt/aarch64~HEAD @@ -0,0 +1 @@ +larch64/ \ No newline at end of file diff --git a/third_party/maplibre-native-qt/x86_64/lib/libQMapLibre.so b/third_party/maplibre-native-qt/x86_64/lib/libQMapLibre.so index 9d440fa..a586872 120000 Binary files a/third_party/maplibre-native-qt/x86_64/lib/libQMapLibre.so and b/third_party/maplibre-native-qt/x86_64/lib/libQMapLibre.so differ diff --git a/third_party/opencl/include/CL/cl.h b/third_party/opencl/include/CL/cl.h deleted file mode 100644 index 0086319..0000000 --- a/third_party/opencl/include/CL/cl.h +++ /dev/null @@ -1,1452 +0,0 @@ -/******************************************************************************* - * Copyright (c) 2008-2015 The Khronos Group Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining a - * copy of this software and/or associated documentation files (the - * "Materials"), to deal in the Materials without restriction, including - * without limitation the rights to use, copy, modify, merge, publish, - * distribute, sublicense, and/or sell copies of the Materials, and to - * permit persons to whom the Materials are furnished to do so, subject to - * the following conditions: - * - * The above copyright notice and this permission notice shall be included - * in all copies or substantial portions of the Materials. - * - * MODIFICATIONS TO THIS FILE MAY MEAN IT NO LONGER ACCURATELY REFLECTS - * KHRONOS STANDARDS. THE UNMODIFIED, NORMATIVE VERSIONS OF KHRONOS - * SPECIFICATIONS AND HEADER INFORMATION ARE LOCATED AT - * https://www.khronos.org/registry/ - * - * THE MATERIALS ARE PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, - * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. - * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY - * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, - * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE - * MATERIALS OR THE USE OR OTHER DEALINGS IN THE MATERIALS. - ******************************************************************************/ - -#ifndef __OPENCL_CL_H -#define __OPENCL_CL_H - -#ifdef __APPLE__ -#include -#else -#include -#endif - -#ifdef __cplusplus -extern "C" { -#endif - -/******************************************************************************/ - -typedef struct _cl_platform_id * cl_platform_id; -typedef struct _cl_device_id * cl_device_id; -typedef struct _cl_context * cl_context; -typedef struct _cl_command_queue * cl_command_queue; -typedef struct _cl_mem * cl_mem; -typedef struct _cl_program * cl_program; -typedef struct _cl_kernel * cl_kernel; -typedef struct _cl_event * cl_event; -typedef struct _cl_sampler * cl_sampler; - -typedef cl_uint cl_bool; /* WARNING! Unlike cl_ types in cl_platform.h, cl_bool is not guaranteed to be the same size as the bool in kernels. */ -typedef cl_ulong cl_bitfield; -typedef cl_bitfield cl_device_type; -typedef cl_uint cl_platform_info; -typedef cl_uint cl_device_info; -typedef cl_bitfield cl_device_fp_config; -typedef cl_uint cl_device_mem_cache_type; -typedef cl_uint cl_device_local_mem_type; -typedef cl_bitfield cl_device_exec_capabilities; -typedef cl_bitfield cl_device_svm_capabilities; -typedef cl_bitfield cl_command_queue_properties; -typedef intptr_t cl_device_partition_property; -typedef cl_bitfield cl_device_affinity_domain; - -typedef intptr_t cl_context_properties; -typedef cl_uint cl_context_info; -typedef cl_bitfield cl_queue_properties; -typedef cl_uint cl_command_queue_info; -typedef cl_uint cl_channel_order; -typedef cl_uint cl_channel_type; -typedef cl_bitfield cl_mem_flags; -typedef cl_bitfield cl_svm_mem_flags; -typedef cl_uint cl_mem_object_type; -typedef cl_uint cl_mem_info; -typedef cl_bitfield cl_mem_migration_flags; -typedef cl_uint cl_image_info; -typedef cl_uint cl_buffer_create_type; -typedef cl_uint cl_addressing_mode; -typedef cl_uint cl_filter_mode; -typedef cl_uint cl_sampler_info; -typedef cl_bitfield cl_map_flags; -typedef intptr_t cl_pipe_properties; -typedef cl_uint cl_pipe_info; -typedef cl_uint cl_program_info; -typedef cl_uint cl_program_build_info; -typedef cl_uint cl_program_binary_type; -typedef cl_int cl_build_status; -typedef cl_uint cl_kernel_info; -typedef cl_uint cl_kernel_arg_info; -typedef cl_uint cl_kernel_arg_address_qualifier; -typedef cl_uint cl_kernel_arg_access_qualifier; -typedef cl_bitfield cl_kernel_arg_type_qualifier; -typedef cl_uint cl_kernel_work_group_info; -typedef cl_uint cl_kernel_sub_group_info; -typedef cl_uint cl_event_info; -typedef cl_uint cl_command_type; -typedef cl_uint cl_profiling_info; -typedef cl_bitfield cl_sampler_properties; -typedef cl_uint cl_kernel_exec_info; - -typedef struct _cl_image_format { - cl_channel_order image_channel_order; - cl_channel_type image_channel_data_type; -} cl_image_format; - -typedef struct _cl_image_desc { - cl_mem_object_type image_type; - size_t image_width; - size_t image_height; - size_t image_depth; - size_t image_array_size; - size_t image_row_pitch; - size_t image_slice_pitch; - cl_uint num_mip_levels; - cl_uint num_samples; -#ifdef __GNUC__ - __extension__ /* Prevents warnings about anonymous union in -pedantic builds */ -#endif - union { - cl_mem buffer; - cl_mem mem_object; - }; -} cl_image_desc; - -typedef struct _cl_buffer_region { - size_t origin; - size_t size; -} cl_buffer_region; - - -/******************************************************************************/ - -/* Error Codes */ -#define CL_SUCCESS 0 -#define CL_DEVICE_NOT_FOUND -1 -#define CL_DEVICE_NOT_AVAILABLE -2 -#define CL_COMPILER_NOT_AVAILABLE -3 -#define CL_MEM_OBJECT_ALLOCATION_FAILURE -4 -#define CL_OUT_OF_RESOURCES -5 -#define CL_OUT_OF_HOST_MEMORY -6 -#define CL_PROFILING_INFO_NOT_AVAILABLE -7 -#define CL_MEM_COPY_OVERLAP -8 -#define CL_IMAGE_FORMAT_MISMATCH -9 -#define CL_IMAGE_FORMAT_NOT_SUPPORTED -10 -#define CL_BUILD_PROGRAM_FAILURE -11 -#define CL_MAP_FAILURE -12 -#define CL_MISALIGNED_SUB_BUFFER_OFFSET -13 -#define CL_EXEC_STATUS_ERROR_FOR_EVENTS_IN_WAIT_LIST -14 -#define CL_COMPILE_PROGRAM_FAILURE -15 -#define CL_LINKER_NOT_AVAILABLE -16 -#define CL_LINK_PROGRAM_FAILURE -17 -#define CL_DEVICE_PARTITION_FAILED -18 -#define CL_KERNEL_ARG_INFO_NOT_AVAILABLE -19 - -#define CL_INVALID_VALUE -30 -#define CL_INVALID_DEVICE_TYPE -31 -#define CL_INVALID_PLATFORM -32 -#define CL_INVALID_DEVICE -33 -#define CL_INVALID_CONTEXT -34 -#define CL_INVALID_QUEUE_PROPERTIES -35 -#define CL_INVALID_COMMAND_QUEUE -36 -#define CL_INVALID_HOST_PTR -37 -#define CL_INVALID_MEM_OBJECT -38 -#define CL_INVALID_IMAGE_FORMAT_DESCRIPTOR -39 -#define CL_INVALID_IMAGE_SIZE -40 -#define CL_INVALID_SAMPLER -41 -#define CL_INVALID_BINARY -42 -#define CL_INVALID_BUILD_OPTIONS -43 -#define CL_INVALID_PROGRAM -44 -#define CL_INVALID_PROGRAM_EXECUTABLE -45 -#define CL_INVALID_KERNEL_NAME -46 -#define CL_INVALID_KERNEL_DEFINITION -47 -#define CL_INVALID_KERNEL -48 -#define CL_INVALID_ARG_INDEX -49 -#define CL_INVALID_ARG_VALUE -50 -#define CL_INVALID_ARG_SIZE -51 -#define CL_INVALID_KERNEL_ARGS -52 -#define CL_INVALID_WORK_DIMENSION -53 -#define CL_INVALID_WORK_GROUP_SIZE -54 -#define CL_INVALID_WORK_ITEM_SIZE -55 -#define CL_INVALID_GLOBAL_OFFSET -56 -#define CL_INVALID_EVENT_WAIT_LIST -57 -#define CL_INVALID_EVENT -58 -#define CL_INVALID_OPERATION -59 -#define CL_INVALID_GL_OBJECT -60 -#define CL_INVALID_BUFFER_SIZE -61 -#define CL_INVALID_MIP_LEVEL -62 -#define CL_INVALID_GLOBAL_WORK_SIZE -63 -#define CL_INVALID_PROPERTY -64 -#define CL_INVALID_IMAGE_DESCRIPTOR -65 -#define CL_INVALID_COMPILER_OPTIONS -66 -#define CL_INVALID_LINKER_OPTIONS -67 -#define CL_INVALID_DEVICE_PARTITION_COUNT -68 -#define CL_INVALID_PIPE_SIZE -69 -#define CL_INVALID_DEVICE_QUEUE -70 - -/* OpenCL Version */ -#define CL_VERSION_1_0 1 -#define CL_VERSION_1_1 1 -#define CL_VERSION_1_2 1 -#define CL_VERSION_2_0 1 -#define CL_VERSION_2_1 1 - -/* cl_bool */ -#define CL_FALSE 0 -#define CL_TRUE 1 -#define CL_BLOCKING CL_TRUE -#define CL_NON_BLOCKING CL_FALSE - -/* cl_platform_info */ -#define CL_PLATFORM_PROFILE 0x0900 -#define CL_PLATFORM_VERSION 0x0901 -#define CL_PLATFORM_NAME 0x0902 -#define CL_PLATFORM_VENDOR 0x0903 -#define CL_PLATFORM_EXTENSIONS 0x0904 -#define CL_PLATFORM_HOST_TIMER_RESOLUTION 0x0905 - -/* cl_device_type - bitfield */ -#define CL_DEVICE_TYPE_DEFAULT (1 << 0) -#define CL_DEVICE_TYPE_CPU (1 << 1) -#define CL_DEVICE_TYPE_GPU (1 << 2) -#define CL_DEVICE_TYPE_ACCELERATOR (1 << 3) -#define CL_DEVICE_TYPE_CUSTOM (1 << 4) -#define CL_DEVICE_TYPE_ALL 0xFFFFFFFF - -/* cl_device_info */ -#define CL_DEVICE_TYPE 0x1000 -#define CL_DEVICE_VENDOR_ID 0x1001 -#define CL_DEVICE_MAX_COMPUTE_UNITS 0x1002 -#define CL_DEVICE_MAX_WORK_ITEM_DIMENSIONS 0x1003 -#define CL_DEVICE_MAX_WORK_GROUP_SIZE 0x1004 -#define CL_DEVICE_MAX_WORK_ITEM_SIZES 0x1005 -#define CL_DEVICE_PREFERRED_VECTOR_WIDTH_CHAR 0x1006 -#define CL_DEVICE_PREFERRED_VECTOR_WIDTH_SHORT 0x1007 -#define CL_DEVICE_PREFERRED_VECTOR_WIDTH_INT 0x1008 -#define CL_DEVICE_PREFERRED_VECTOR_WIDTH_LONG 0x1009 -#define CL_DEVICE_PREFERRED_VECTOR_WIDTH_FLOAT 0x100A -#define CL_DEVICE_PREFERRED_VECTOR_WIDTH_DOUBLE 0x100B -#define CL_DEVICE_MAX_CLOCK_FREQUENCY 0x100C -#define CL_DEVICE_ADDRESS_BITS 0x100D -#define CL_DEVICE_MAX_READ_IMAGE_ARGS 0x100E -#define CL_DEVICE_MAX_WRITE_IMAGE_ARGS 0x100F -#define CL_DEVICE_MAX_MEM_ALLOC_SIZE 0x1010 -#define CL_DEVICE_IMAGE2D_MAX_WIDTH 0x1011 -#define CL_DEVICE_IMAGE2D_MAX_HEIGHT 0x1012 -#define CL_DEVICE_IMAGE3D_MAX_WIDTH 0x1013 -#define CL_DEVICE_IMAGE3D_MAX_HEIGHT 0x1014 -#define CL_DEVICE_IMAGE3D_MAX_DEPTH 0x1015 -#define CL_DEVICE_IMAGE_SUPPORT 0x1016 -#define CL_DEVICE_MAX_PARAMETER_SIZE 0x1017 -#define CL_DEVICE_MAX_SAMPLERS 0x1018 -#define CL_DEVICE_MEM_BASE_ADDR_ALIGN 0x1019 -#define CL_DEVICE_MIN_DATA_TYPE_ALIGN_SIZE 0x101A -#define CL_DEVICE_SINGLE_FP_CONFIG 0x101B -#define CL_DEVICE_GLOBAL_MEM_CACHE_TYPE 0x101C -#define CL_DEVICE_GLOBAL_MEM_CACHELINE_SIZE 0x101D -#define CL_DEVICE_GLOBAL_MEM_CACHE_SIZE 0x101E -#define CL_DEVICE_GLOBAL_MEM_SIZE 0x101F -#define CL_DEVICE_MAX_CONSTANT_BUFFER_SIZE 0x1020 -#define CL_DEVICE_MAX_CONSTANT_ARGS 0x1021 -#define CL_DEVICE_LOCAL_MEM_TYPE 0x1022 -#define CL_DEVICE_LOCAL_MEM_SIZE 0x1023 -#define CL_DEVICE_ERROR_CORRECTION_SUPPORT 0x1024 -#define CL_DEVICE_PROFILING_TIMER_RESOLUTION 0x1025 -#define CL_DEVICE_ENDIAN_LITTLE 0x1026 -#define CL_DEVICE_AVAILABLE 0x1027 -#define CL_DEVICE_COMPILER_AVAILABLE 0x1028 -#define CL_DEVICE_EXECUTION_CAPABILITIES 0x1029 -#define CL_DEVICE_QUEUE_PROPERTIES 0x102A /* deprecated */ -#define CL_DEVICE_QUEUE_ON_HOST_PROPERTIES 0x102A -#define CL_DEVICE_NAME 0x102B -#define CL_DEVICE_VENDOR 0x102C -#define CL_DRIVER_VERSION 0x102D -#define CL_DEVICE_PROFILE 0x102E -#define CL_DEVICE_VERSION 0x102F -#define CL_DEVICE_EXTENSIONS 0x1030 -#define CL_DEVICE_PLATFORM 0x1031 -#define CL_DEVICE_DOUBLE_FP_CONFIG 0x1032 -/* 0x1033 reserved for CL_DEVICE_HALF_FP_CONFIG */ -#define CL_DEVICE_PREFERRED_VECTOR_WIDTH_HALF 0x1034 -#define CL_DEVICE_HOST_UNIFIED_MEMORY 0x1035 /* deprecated */ -#define CL_DEVICE_NATIVE_VECTOR_WIDTH_CHAR 0x1036 -#define CL_DEVICE_NATIVE_VECTOR_WIDTH_SHORT 0x1037 -#define CL_DEVICE_NATIVE_VECTOR_WIDTH_INT 0x1038 -#define CL_DEVICE_NATIVE_VECTOR_WIDTH_LONG 0x1039 -#define CL_DEVICE_NATIVE_VECTOR_WIDTH_FLOAT 0x103A -#define CL_DEVICE_NATIVE_VECTOR_WIDTH_DOUBLE 0x103B -#define CL_DEVICE_NATIVE_VECTOR_WIDTH_HALF 0x103C -#define CL_DEVICE_OPENCL_C_VERSION 0x103D -#define CL_DEVICE_LINKER_AVAILABLE 0x103E -#define CL_DEVICE_BUILT_IN_KERNELS 0x103F -#define CL_DEVICE_IMAGE_MAX_BUFFER_SIZE 0x1040 -#define CL_DEVICE_IMAGE_MAX_ARRAY_SIZE 0x1041 -#define CL_DEVICE_PARENT_DEVICE 0x1042 -#define CL_DEVICE_PARTITION_MAX_SUB_DEVICES 0x1043 -#define CL_DEVICE_PARTITION_PROPERTIES 0x1044 -#define CL_DEVICE_PARTITION_AFFINITY_DOMAIN 0x1045 -#define CL_DEVICE_PARTITION_TYPE 0x1046 -#define CL_DEVICE_REFERENCE_COUNT 0x1047 -#define CL_DEVICE_PREFERRED_INTEROP_USER_SYNC 0x1048 -#define CL_DEVICE_PRINTF_BUFFER_SIZE 0x1049 -#define CL_DEVICE_IMAGE_PITCH_ALIGNMENT 0x104A -#define CL_DEVICE_IMAGE_BASE_ADDRESS_ALIGNMENT 0x104B -#define CL_DEVICE_MAX_READ_WRITE_IMAGE_ARGS 0x104C -#define CL_DEVICE_MAX_GLOBAL_VARIABLE_SIZE 0x104D -#define CL_DEVICE_QUEUE_ON_DEVICE_PROPERTIES 0x104E -#define CL_DEVICE_QUEUE_ON_DEVICE_PREFERRED_SIZE 0x104F -#define CL_DEVICE_QUEUE_ON_DEVICE_MAX_SIZE 0x1050 -#define CL_DEVICE_MAX_ON_DEVICE_QUEUES 0x1051 -#define CL_DEVICE_MAX_ON_DEVICE_EVENTS 0x1052 -#define CL_DEVICE_SVM_CAPABILITIES 0x1053 -#define CL_DEVICE_GLOBAL_VARIABLE_PREFERRED_TOTAL_SIZE 0x1054 -#define CL_DEVICE_MAX_PIPE_ARGS 0x1055 -#define CL_DEVICE_PIPE_MAX_ACTIVE_RESERVATIONS 0x1056 -#define CL_DEVICE_PIPE_MAX_PACKET_SIZE 0x1057 -#define CL_DEVICE_PREFERRED_PLATFORM_ATOMIC_ALIGNMENT 0x1058 -#define CL_DEVICE_PREFERRED_GLOBAL_ATOMIC_ALIGNMENT 0x1059 -#define CL_DEVICE_PREFERRED_LOCAL_ATOMIC_ALIGNMENT 0x105A -#define CL_DEVICE_IL_VERSION 0x105B -#define CL_DEVICE_MAX_NUM_SUB_GROUPS 0x105C -#define CL_DEVICE_SUB_GROUP_INDEPENDENT_FORWARD_PROGRESS 0x105D - -/* cl_device_fp_config - bitfield */ -#define CL_FP_DENORM (1 << 0) -#define CL_FP_INF_NAN (1 << 1) -#define CL_FP_ROUND_TO_NEAREST (1 << 2) -#define CL_FP_ROUND_TO_ZERO (1 << 3) -#define CL_FP_ROUND_TO_INF (1 << 4) -#define CL_FP_FMA (1 << 5) -#define CL_FP_SOFT_FLOAT (1 << 6) -#define CL_FP_CORRECTLY_ROUNDED_DIVIDE_SQRT (1 << 7) - -/* cl_device_mem_cache_type */ -#define CL_NONE 0x0 -#define CL_READ_ONLY_CACHE 0x1 -#define CL_READ_WRITE_CACHE 0x2 - -/* cl_device_local_mem_type */ -#define CL_LOCAL 0x1 -#define CL_GLOBAL 0x2 - -/* cl_device_exec_capabilities - bitfield */ -#define CL_EXEC_KERNEL (1 << 0) -#define CL_EXEC_NATIVE_KERNEL (1 << 1) - -/* cl_command_queue_properties - bitfield */ -#define CL_QUEUE_OUT_OF_ORDER_EXEC_MODE_ENABLE (1 << 0) -#define CL_QUEUE_PROFILING_ENABLE (1 << 1) -#define CL_QUEUE_ON_DEVICE (1 << 2) -#define CL_QUEUE_ON_DEVICE_DEFAULT (1 << 3) - -/* cl_context_info */ -#define CL_CONTEXT_REFERENCE_COUNT 0x1080 -#define CL_CONTEXT_DEVICES 0x1081 -#define CL_CONTEXT_PROPERTIES 0x1082 -#define CL_CONTEXT_NUM_DEVICES 0x1083 - -/* cl_context_properties */ -#define CL_CONTEXT_PLATFORM 0x1084 -#define CL_CONTEXT_INTEROP_USER_SYNC 0x1085 - -/* cl_device_partition_property */ -#define CL_DEVICE_PARTITION_EQUALLY 0x1086 -#define CL_DEVICE_PARTITION_BY_COUNTS 0x1087 -#define CL_DEVICE_PARTITION_BY_COUNTS_LIST_END 0x0 -#define CL_DEVICE_PARTITION_BY_AFFINITY_DOMAIN 0x1088 - -/* cl_device_affinity_domain */ -#define CL_DEVICE_AFFINITY_DOMAIN_NUMA (1 << 0) -#define CL_DEVICE_AFFINITY_DOMAIN_L4_CACHE (1 << 1) -#define CL_DEVICE_AFFINITY_DOMAIN_L3_CACHE (1 << 2) -#define CL_DEVICE_AFFINITY_DOMAIN_L2_CACHE (1 << 3) -#define CL_DEVICE_AFFINITY_DOMAIN_L1_CACHE (1 << 4) -#define CL_DEVICE_AFFINITY_DOMAIN_NEXT_PARTITIONABLE (1 << 5) - -/* cl_device_svm_capabilities */ -#define CL_DEVICE_SVM_COARSE_GRAIN_BUFFER (1 << 0) -#define CL_DEVICE_SVM_FINE_GRAIN_BUFFER (1 << 1) -#define CL_DEVICE_SVM_FINE_GRAIN_SYSTEM (1 << 2) -#define CL_DEVICE_SVM_ATOMICS (1 << 3) - -/* cl_command_queue_info */ -#define CL_QUEUE_CONTEXT 0x1090 -#define CL_QUEUE_DEVICE 0x1091 -#define CL_QUEUE_REFERENCE_COUNT 0x1092 -#define CL_QUEUE_PROPERTIES 0x1093 -#define CL_QUEUE_SIZE 0x1094 -#define CL_QUEUE_DEVICE_DEFAULT 0x1095 - -/* cl_mem_flags and cl_svm_mem_flags - bitfield */ -#define CL_MEM_READ_WRITE (1 << 0) -#define CL_MEM_WRITE_ONLY (1 << 1) -#define CL_MEM_READ_ONLY (1 << 2) -#define CL_MEM_USE_HOST_PTR (1 << 3) -#define CL_MEM_ALLOC_HOST_PTR (1 << 4) -#define CL_MEM_COPY_HOST_PTR (1 << 5) -/* reserved (1 << 6) */ -#define CL_MEM_HOST_WRITE_ONLY (1 << 7) -#define CL_MEM_HOST_READ_ONLY (1 << 8) -#define CL_MEM_HOST_NO_ACCESS (1 << 9) -#define CL_MEM_SVM_FINE_GRAIN_BUFFER (1 << 10) /* used by cl_svm_mem_flags only */ -#define CL_MEM_SVM_ATOMICS (1 << 11) /* used by cl_svm_mem_flags only */ -#define CL_MEM_KERNEL_READ_AND_WRITE (1 << 12) - -/* cl_mem_migration_flags - bitfield */ -#define CL_MIGRATE_MEM_OBJECT_HOST (1 << 0) -#define CL_MIGRATE_MEM_OBJECT_CONTENT_UNDEFINED (1 << 1) - -/* cl_channel_order */ -#define CL_R 0x10B0 -#define CL_A 0x10B1 -#define CL_RG 0x10B2 -#define CL_RA 0x10B3 -#define CL_RGB 0x10B4 -#define CL_RGBA 0x10B5 -#define CL_BGRA 0x10B6 -#define CL_ARGB 0x10B7 -#define CL_INTENSITY 0x10B8 -#define CL_LUMINANCE 0x10B9 -#define CL_Rx 0x10BA -#define CL_RGx 0x10BB -#define CL_RGBx 0x10BC -#define CL_DEPTH 0x10BD -#define CL_DEPTH_STENCIL 0x10BE -#define CL_sRGB 0x10BF -#define CL_sRGBx 0x10C0 -#define CL_sRGBA 0x10C1 -#define CL_sBGRA 0x10C2 -#define CL_ABGR 0x10C3 - -/* cl_channel_type */ -#define CL_SNORM_INT8 0x10D0 -#define CL_SNORM_INT16 0x10D1 -#define CL_UNORM_INT8 0x10D2 -#define CL_UNORM_INT16 0x10D3 -#define CL_UNORM_SHORT_565 0x10D4 -#define CL_UNORM_SHORT_555 0x10D5 -#define CL_UNORM_INT_101010 0x10D6 -#define CL_SIGNED_INT8 0x10D7 -#define CL_SIGNED_INT16 0x10D8 -#define CL_SIGNED_INT32 0x10D9 -#define CL_UNSIGNED_INT8 0x10DA -#define CL_UNSIGNED_INT16 0x10DB -#define CL_UNSIGNED_INT32 0x10DC -#define CL_HALF_FLOAT 0x10DD -#define CL_FLOAT 0x10DE -#define CL_UNORM_INT24 0x10DF -#define CL_UNORM_INT_101010_2 0x10E0 - -/* cl_mem_object_type */ -#define CL_MEM_OBJECT_BUFFER 0x10F0 -#define CL_MEM_OBJECT_IMAGE2D 0x10F1 -#define CL_MEM_OBJECT_IMAGE3D 0x10F2 -#define CL_MEM_OBJECT_IMAGE2D_ARRAY 0x10F3 -#define CL_MEM_OBJECT_IMAGE1D 0x10F4 -#define CL_MEM_OBJECT_IMAGE1D_ARRAY 0x10F5 -#define CL_MEM_OBJECT_IMAGE1D_BUFFER 0x10F6 -#define CL_MEM_OBJECT_PIPE 0x10F7 - -/* cl_mem_info */ -#define CL_MEM_TYPE 0x1100 -#define CL_MEM_FLAGS 0x1101 -#define CL_MEM_SIZE 0x1102 -#define CL_MEM_HOST_PTR 0x1103 -#define CL_MEM_MAP_COUNT 0x1104 -#define CL_MEM_REFERENCE_COUNT 0x1105 -#define CL_MEM_CONTEXT 0x1106 -#define CL_MEM_ASSOCIATED_MEMOBJECT 0x1107 -#define CL_MEM_OFFSET 0x1108 -#define CL_MEM_USES_SVM_POINTER 0x1109 - -/* cl_image_info */ -#define CL_IMAGE_FORMAT 0x1110 -#define CL_IMAGE_ELEMENT_SIZE 0x1111 -#define CL_IMAGE_ROW_PITCH 0x1112 -#define CL_IMAGE_SLICE_PITCH 0x1113 -#define CL_IMAGE_WIDTH 0x1114 -#define CL_IMAGE_HEIGHT 0x1115 -#define CL_IMAGE_DEPTH 0x1116 -#define CL_IMAGE_ARRAY_SIZE 0x1117 -#define CL_IMAGE_BUFFER 0x1118 -#define CL_IMAGE_NUM_MIP_LEVELS 0x1119 -#define CL_IMAGE_NUM_SAMPLES 0x111A - -/* cl_pipe_info */ -#define CL_PIPE_PACKET_SIZE 0x1120 -#define CL_PIPE_MAX_PACKETS 0x1121 - -/* cl_addressing_mode */ -#define CL_ADDRESS_NONE 0x1130 -#define CL_ADDRESS_CLAMP_TO_EDGE 0x1131 -#define CL_ADDRESS_CLAMP 0x1132 -#define CL_ADDRESS_REPEAT 0x1133 -#define CL_ADDRESS_MIRRORED_REPEAT 0x1134 - -/* cl_filter_mode */ -#define CL_FILTER_NEAREST 0x1140 -#define CL_FILTER_LINEAR 0x1141 - -/* cl_sampler_info */ -#define CL_SAMPLER_REFERENCE_COUNT 0x1150 -#define CL_SAMPLER_CONTEXT 0x1151 -#define CL_SAMPLER_NORMALIZED_COORDS 0x1152 -#define CL_SAMPLER_ADDRESSING_MODE 0x1153 -#define CL_SAMPLER_FILTER_MODE 0x1154 -#define CL_SAMPLER_MIP_FILTER_MODE 0x1155 -#define CL_SAMPLER_LOD_MIN 0x1156 -#define CL_SAMPLER_LOD_MAX 0x1157 - -/* cl_map_flags - bitfield */ -#define CL_MAP_READ (1 << 0) -#define CL_MAP_WRITE (1 << 1) -#define CL_MAP_WRITE_INVALIDATE_REGION (1 << 2) - -/* cl_program_info */ -#define CL_PROGRAM_REFERENCE_COUNT 0x1160 -#define CL_PROGRAM_CONTEXT 0x1161 -#define CL_PROGRAM_NUM_DEVICES 0x1162 -#define CL_PROGRAM_DEVICES 0x1163 -#define CL_PROGRAM_SOURCE 0x1164 -#define CL_PROGRAM_BINARY_SIZES 0x1165 -#define CL_PROGRAM_BINARIES 0x1166 -#define CL_PROGRAM_NUM_KERNELS 0x1167 -#define CL_PROGRAM_KERNEL_NAMES 0x1168 -#define CL_PROGRAM_IL 0x1169 - -/* cl_program_build_info */ -#define CL_PROGRAM_BUILD_STATUS 0x1181 -#define CL_PROGRAM_BUILD_OPTIONS 0x1182 -#define CL_PROGRAM_BUILD_LOG 0x1183 -#define CL_PROGRAM_BINARY_TYPE 0x1184 -#define CL_PROGRAM_BUILD_GLOBAL_VARIABLE_TOTAL_SIZE 0x1185 - -/* cl_program_binary_type */ -#define CL_PROGRAM_BINARY_TYPE_NONE 0x0 -#define CL_PROGRAM_BINARY_TYPE_COMPILED_OBJECT 0x1 -#define CL_PROGRAM_BINARY_TYPE_LIBRARY 0x2 -#define CL_PROGRAM_BINARY_TYPE_EXECUTABLE 0x4 - -/* cl_build_status */ -#define CL_BUILD_SUCCESS 0 -#define CL_BUILD_NONE -1 -#define CL_BUILD_ERROR -2 -#define CL_BUILD_IN_PROGRESS -3 - -/* cl_kernel_info */ -#define CL_KERNEL_FUNCTION_NAME 0x1190 -#define CL_KERNEL_NUM_ARGS 0x1191 -#define CL_KERNEL_REFERENCE_COUNT 0x1192 -#define CL_KERNEL_CONTEXT 0x1193 -#define CL_KERNEL_PROGRAM 0x1194 -#define CL_KERNEL_ATTRIBUTES 0x1195 -#define CL_KERNEL_MAX_NUM_SUB_GROUPS 0x11B9 -#define CL_KERNEL_COMPILE_NUM_SUB_GROUPS 0x11BA - -/* cl_kernel_arg_info */ -#define CL_KERNEL_ARG_ADDRESS_QUALIFIER 0x1196 -#define CL_KERNEL_ARG_ACCESS_QUALIFIER 0x1197 -#define CL_KERNEL_ARG_TYPE_NAME 0x1198 -#define CL_KERNEL_ARG_TYPE_QUALIFIER 0x1199 -#define CL_KERNEL_ARG_NAME 0x119A - -/* cl_kernel_arg_address_qualifier */ -#define CL_KERNEL_ARG_ADDRESS_GLOBAL 0x119B -#define CL_KERNEL_ARG_ADDRESS_LOCAL 0x119C -#define CL_KERNEL_ARG_ADDRESS_CONSTANT 0x119D -#define CL_KERNEL_ARG_ADDRESS_PRIVATE 0x119E - -/* cl_kernel_arg_access_qualifier */ -#define CL_KERNEL_ARG_ACCESS_READ_ONLY 0x11A0 -#define CL_KERNEL_ARG_ACCESS_WRITE_ONLY 0x11A1 -#define CL_KERNEL_ARG_ACCESS_READ_WRITE 0x11A2 -#define CL_KERNEL_ARG_ACCESS_NONE 0x11A3 - -/* cl_kernel_arg_type_qualifer */ -#define CL_KERNEL_ARG_TYPE_NONE 0 -#define CL_KERNEL_ARG_TYPE_CONST (1 << 0) -#define CL_KERNEL_ARG_TYPE_RESTRICT (1 << 1) -#define CL_KERNEL_ARG_TYPE_VOLATILE (1 << 2) -#define CL_KERNEL_ARG_TYPE_PIPE (1 << 3) - -/* cl_kernel_work_group_info */ -#define CL_KERNEL_WORK_GROUP_SIZE 0x11B0 -#define CL_KERNEL_COMPILE_WORK_GROUP_SIZE 0x11B1 -#define CL_KERNEL_LOCAL_MEM_SIZE 0x11B2 -#define CL_KERNEL_PREFERRED_WORK_GROUP_SIZE_MULTIPLE 0x11B3 -#define CL_KERNEL_PRIVATE_MEM_SIZE 0x11B4 -#define CL_KERNEL_GLOBAL_WORK_SIZE 0x11B5 - -/* cl_kernel_sub_group_info */ -#define CL_KERNEL_MAX_SUB_GROUP_SIZE_FOR_NDRANGE 0x2033 -#define CL_KERNEL_SUB_GROUP_COUNT_FOR_NDRANGE 0x2034 -#define CL_KERNEL_LOCAL_SIZE_FOR_SUB_GROUP_COUNT 0x11B8 - -/* cl_kernel_exec_info */ -#define CL_KERNEL_EXEC_INFO_SVM_PTRS 0x11B6 -#define CL_KERNEL_EXEC_INFO_SVM_FINE_GRAIN_SYSTEM 0x11B7 - -/* cl_event_info */ -#define CL_EVENT_COMMAND_QUEUE 0x11D0 -#define CL_EVENT_COMMAND_TYPE 0x11D1 -#define CL_EVENT_REFERENCE_COUNT 0x11D2 -#define CL_EVENT_COMMAND_EXECUTION_STATUS 0x11D3 -#define CL_EVENT_CONTEXT 0x11D4 - -/* cl_command_type */ -#define CL_COMMAND_NDRANGE_KERNEL 0x11F0 -#define CL_COMMAND_TASK 0x11F1 -#define CL_COMMAND_NATIVE_KERNEL 0x11F2 -#define CL_COMMAND_READ_BUFFER 0x11F3 -#define CL_COMMAND_WRITE_BUFFER 0x11F4 -#define CL_COMMAND_COPY_BUFFER 0x11F5 -#define CL_COMMAND_READ_IMAGE 0x11F6 -#define CL_COMMAND_WRITE_IMAGE 0x11F7 -#define CL_COMMAND_COPY_IMAGE 0x11F8 -#define CL_COMMAND_COPY_IMAGE_TO_BUFFER 0x11F9 -#define CL_COMMAND_COPY_BUFFER_TO_IMAGE 0x11FA -#define CL_COMMAND_MAP_BUFFER 0x11FB -#define CL_COMMAND_MAP_IMAGE 0x11FC -#define CL_COMMAND_UNMAP_MEM_OBJECT 0x11FD -#define CL_COMMAND_MARKER 0x11FE -#define CL_COMMAND_ACQUIRE_GL_OBJECTS 0x11FF -#define CL_COMMAND_RELEASE_GL_OBJECTS 0x1200 -#define CL_COMMAND_READ_BUFFER_RECT 0x1201 -#define CL_COMMAND_WRITE_BUFFER_RECT 0x1202 -#define CL_COMMAND_COPY_BUFFER_RECT 0x1203 -#define CL_COMMAND_USER 0x1204 -#define CL_COMMAND_BARRIER 0x1205 -#define CL_COMMAND_MIGRATE_MEM_OBJECTS 0x1206 -#define CL_COMMAND_FILL_BUFFER 0x1207 -#define CL_COMMAND_FILL_IMAGE 0x1208 -#define CL_COMMAND_SVM_FREE 0x1209 -#define CL_COMMAND_SVM_MEMCPY 0x120A -#define CL_COMMAND_SVM_MEMFILL 0x120B -#define CL_COMMAND_SVM_MAP 0x120C -#define CL_COMMAND_SVM_UNMAP 0x120D - -/* command execution status */ -#define CL_COMPLETE 0x0 -#define CL_RUNNING 0x1 -#define CL_SUBMITTED 0x2 -#define CL_QUEUED 0x3 - -/* cl_buffer_create_type */ -#define CL_BUFFER_CREATE_TYPE_REGION 0x1220 - -/* cl_profiling_info */ -#define CL_PROFILING_COMMAND_QUEUED 0x1280 -#define CL_PROFILING_COMMAND_SUBMIT 0x1281 -#define CL_PROFILING_COMMAND_START 0x1282 -#define CL_PROFILING_COMMAND_END 0x1283 -#define CL_PROFILING_COMMAND_COMPLETE 0x1284 - -/********************************************************************************************************/ - -/* Platform API */ -extern CL_API_ENTRY cl_int CL_API_CALL -clGetPlatformIDs(cl_uint /* num_entries */, - cl_platform_id * /* platforms */, - cl_uint * /* num_platforms */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clGetPlatformInfo(cl_platform_id /* platform */, - cl_platform_info /* param_name */, - size_t /* param_value_size */, - void * /* param_value */, - size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; - -/* Device APIs */ -extern CL_API_ENTRY cl_int CL_API_CALL -clGetDeviceIDs(cl_platform_id /* platform */, - cl_device_type /* device_type */, - cl_uint /* num_entries */, - cl_device_id * /* devices */, - cl_uint * /* num_devices */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clGetDeviceInfo(cl_device_id /* device */, - cl_device_info /* param_name */, - size_t /* param_value_size */, - void * /* param_value */, - size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clCreateSubDevices(cl_device_id /* in_device */, - const cl_device_partition_property * /* properties */, - cl_uint /* num_devices */, - cl_device_id * /* out_devices */, - cl_uint * /* num_devices_ret */) CL_API_SUFFIX__VERSION_1_2; - -extern CL_API_ENTRY cl_int CL_API_CALL -clRetainDevice(cl_device_id /* device */) CL_API_SUFFIX__VERSION_1_2; - -extern CL_API_ENTRY cl_int CL_API_CALL -clReleaseDevice(cl_device_id /* device */) CL_API_SUFFIX__VERSION_1_2; - -extern CL_API_ENTRY cl_int CL_API_CALL -clSetDefaultDeviceCommandQueue(cl_context /* context */, - cl_device_id /* device */, - cl_command_queue /* command_queue */) CL_API_SUFFIX__VERSION_2_1; - -extern CL_API_ENTRY cl_int CL_API_CALL -clGetDeviceAndHostTimer(cl_device_id /* device */, - cl_ulong* /* device_timestamp */, - cl_ulong* /* host_timestamp */) CL_API_SUFFIX__VERSION_2_1; - -extern CL_API_ENTRY cl_int CL_API_CALL -clGetHostTimer(cl_device_id /* device */, - cl_ulong * /* host_timestamp */) CL_API_SUFFIX__VERSION_2_1; - - -/* Context APIs */ -extern CL_API_ENTRY cl_context CL_API_CALL -clCreateContext(const cl_context_properties * /* properties */, - cl_uint /* num_devices */, - const cl_device_id * /* devices */, - void (CL_CALLBACK * /* pfn_notify */)(const char *, const void *, size_t, void *), - void * /* user_data */, - cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_context CL_API_CALL -clCreateContextFromType(const cl_context_properties * /* properties */, - cl_device_type /* device_type */, - void (CL_CALLBACK * /* pfn_notify*/ )(const char *, const void *, size_t, void *), - void * /* user_data */, - cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clRetainContext(cl_context /* context */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clReleaseContext(cl_context /* context */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clGetContextInfo(cl_context /* context */, - cl_context_info /* param_name */, - size_t /* param_value_size */, - void * /* param_value */, - size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; - -/* Command Queue APIs */ -extern CL_API_ENTRY cl_command_queue CL_API_CALL -clCreateCommandQueueWithProperties(cl_context /* context */, - cl_device_id /* device */, - const cl_queue_properties * /* properties */, - cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_2_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clRetainCommandQueue(cl_command_queue /* command_queue */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clReleaseCommandQueue(cl_command_queue /* command_queue */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clGetCommandQueueInfo(cl_command_queue /* command_queue */, - cl_command_queue_info /* param_name */, - size_t /* param_value_size */, - void * /* param_value */, - size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; - -/* Memory Object APIs */ -extern CL_API_ENTRY cl_mem CL_API_CALL -clCreateBuffer(cl_context /* context */, - cl_mem_flags /* flags */, - size_t /* size */, - void * /* host_ptr */, - cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_mem CL_API_CALL -clCreateSubBuffer(cl_mem /* buffer */, - cl_mem_flags /* flags */, - cl_buffer_create_type /* buffer_create_type */, - const void * /* buffer_create_info */, - cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_1; - -extern CL_API_ENTRY cl_mem CL_API_CALL -clCreateImage(cl_context /* context */, - cl_mem_flags /* flags */, - const cl_image_format * /* image_format */, - const cl_image_desc * /* image_desc */, - void * /* host_ptr */, - cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_2; - -extern CL_API_ENTRY cl_mem CL_API_CALL -clCreatePipe(cl_context /* context */, - cl_mem_flags /* flags */, - cl_uint /* pipe_packet_size */, - cl_uint /* pipe_max_packets */, - const cl_pipe_properties * /* properties */, - cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_2_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clRetainMemObject(cl_mem /* memobj */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clReleaseMemObject(cl_mem /* memobj */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clGetSupportedImageFormats(cl_context /* context */, - cl_mem_flags /* flags */, - cl_mem_object_type /* image_type */, - cl_uint /* num_entries */, - cl_image_format * /* image_formats */, - cl_uint * /* num_image_formats */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clGetMemObjectInfo(cl_mem /* memobj */, - cl_mem_info /* param_name */, - size_t /* param_value_size */, - void * /* param_value */, - size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clGetImageInfo(cl_mem /* image */, - cl_image_info /* param_name */, - size_t /* param_value_size */, - void * /* param_value */, - size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clGetPipeInfo(cl_mem /* pipe */, - cl_pipe_info /* param_name */, - size_t /* param_value_size */, - void * /* param_value */, - size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_2_0; - - -extern CL_API_ENTRY cl_int CL_API_CALL -clSetMemObjectDestructorCallback(cl_mem /* memobj */, - void (CL_CALLBACK * /*pfn_notify*/)( cl_mem /* memobj */, void* /*user_data*/), - void * /*user_data */ ) CL_API_SUFFIX__VERSION_1_1; - -/* SVM Allocation APIs */ -extern CL_API_ENTRY void * CL_API_CALL -clSVMAlloc(cl_context /* context */, - cl_svm_mem_flags /* flags */, - size_t /* size */, - cl_uint /* alignment */) CL_API_SUFFIX__VERSION_2_0; - -extern CL_API_ENTRY void CL_API_CALL -clSVMFree(cl_context /* context */, - void * /* svm_pointer */) CL_API_SUFFIX__VERSION_2_0; - -/* Sampler APIs */ -extern CL_API_ENTRY cl_sampler CL_API_CALL -clCreateSamplerWithProperties(cl_context /* context */, - const cl_sampler_properties * /* normalized_coords */, - cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_2_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clRetainSampler(cl_sampler /* sampler */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clReleaseSampler(cl_sampler /* sampler */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clGetSamplerInfo(cl_sampler /* sampler */, - cl_sampler_info /* param_name */, - size_t /* param_value_size */, - void * /* param_value */, - size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; - -/* Program Object APIs */ -extern CL_API_ENTRY cl_program CL_API_CALL -clCreateProgramWithSource(cl_context /* context */, - cl_uint /* count */, - const char ** /* strings */, - const size_t * /* lengths */, - cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_program CL_API_CALL -clCreateProgramWithBinary(cl_context /* context */, - cl_uint /* num_devices */, - const cl_device_id * /* device_list */, - const size_t * /* lengths */, - const unsigned char ** /* binaries */, - cl_int * /* binary_status */, - cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_program CL_API_CALL -clCreateProgramWithBuiltInKernels(cl_context /* context */, - cl_uint /* num_devices */, - const cl_device_id * /* device_list */, - const char * /* kernel_names */, - cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_2; - -extern CL_API_ENTRY cl_program CL_API_CALL -clCreateProgramWithIL(cl_context /* context */, - const void* /* il */, - size_t /* length */, - cl_int* /* errcode_ret */) CL_API_SUFFIX__VERSION_2_1; - - -extern CL_API_ENTRY cl_int CL_API_CALL -clRetainProgram(cl_program /* program */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clReleaseProgram(cl_program /* program */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clBuildProgram(cl_program /* program */, - cl_uint /* num_devices */, - const cl_device_id * /* device_list */, - const char * /* options */, - void (CL_CALLBACK * /* pfn_notify */)(cl_program /* program */, void * /* user_data */), - void * /* user_data */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clCompileProgram(cl_program /* program */, - cl_uint /* num_devices */, - const cl_device_id * /* device_list */, - const char * /* options */, - cl_uint /* num_input_headers */, - const cl_program * /* input_headers */, - const char ** /* header_include_names */, - void (CL_CALLBACK * /* pfn_notify */)(cl_program /* program */, void * /* user_data */), - void * /* user_data */) CL_API_SUFFIX__VERSION_1_2; - -extern CL_API_ENTRY cl_program CL_API_CALL -clLinkProgram(cl_context /* context */, - cl_uint /* num_devices */, - const cl_device_id * /* device_list */, - const char * /* options */, - cl_uint /* num_input_programs */, - const cl_program * /* input_programs */, - void (CL_CALLBACK * /* pfn_notify */)(cl_program /* program */, void * /* user_data */), - void * /* user_data */, - cl_int * /* errcode_ret */ ) CL_API_SUFFIX__VERSION_1_2; - - -extern CL_API_ENTRY cl_int CL_API_CALL -clUnloadPlatformCompiler(cl_platform_id /* platform */) CL_API_SUFFIX__VERSION_1_2; - -extern CL_API_ENTRY cl_int CL_API_CALL -clGetProgramInfo(cl_program /* program */, - cl_program_info /* param_name */, - size_t /* param_value_size */, - void * /* param_value */, - size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clGetProgramBuildInfo(cl_program /* program */, - cl_device_id /* device */, - cl_program_build_info /* param_name */, - size_t /* param_value_size */, - void * /* param_value */, - size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; - -/* Kernel Object APIs */ -extern CL_API_ENTRY cl_kernel CL_API_CALL -clCreateKernel(cl_program /* program */, - const char * /* kernel_name */, - cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clCreateKernelsInProgram(cl_program /* program */, - cl_uint /* num_kernels */, - cl_kernel * /* kernels */, - cl_uint * /* num_kernels_ret */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_kernel CL_API_CALL -clCloneKernel(cl_kernel /* source_kernel */, - cl_int* /* errcode_ret */) CL_API_SUFFIX__VERSION_2_1; - -extern CL_API_ENTRY cl_int CL_API_CALL -clRetainKernel(cl_kernel /* kernel */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clReleaseKernel(cl_kernel /* kernel */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clSetKernelArg(cl_kernel /* kernel */, - cl_uint /* arg_index */, - size_t /* arg_size */, - const void * /* arg_value */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clSetKernelArgSVMPointer(cl_kernel /* kernel */, - cl_uint /* arg_index */, - const void * /* arg_value */) CL_API_SUFFIX__VERSION_2_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clSetKernelExecInfo(cl_kernel /* kernel */, - cl_kernel_exec_info /* param_name */, - size_t /* param_value_size */, - const void * /* param_value */) CL_API_SUFFIX__VERSION_2_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clGetKernelInfo(cl_kernel /* kernel */, - cl_kernel_info /* param_name */, - size_t /* param_value_size */, - void * /* param_value */, - size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clGetKernelArgInfo(cl_kernel /* kernel */, - cl_uint /* arg_indx */, - cl_kernel_arg_info /* param_name */, - size_t /* param_value_size */, - void * /* param_value */, - size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_2; - -extern CL_API_ENTRY cl_int CL_API_CALL -clGetKernelWorkGroupInfo(cl_kernel /* kernel */, - cl_device_id /* device */, - cl_kernel_work_group_info /* param_name */, - size_t /* param_value_size */, - void * /* param_value */, - size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clGetKernelSubGroupInfo(cl_kernel /* kernel */, - cl_device_id /* device */, - cl_kernel_sub_group_info /* param_name */, - size_t /* input_value_size */, - const void* /*input_value */, - size_t /* param_value_size */, - void* /* param_value */, - size_t* /* param_value_size_ret */ ) CL_API_SUFFIX__VERSION_2_1; - - -/* Event Object APIs */ -extern CL_API_ENTRY cl_int CL_API_CALL -clWaitForEvents(cl_uint /* num_events */, - const cl_event * /* event_list */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clGetEventInfo(cl_event /* event */, - cl_event_info /* param_name */, - size_t /* param_value_size */, - void * /* param_value */, - size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_event CL_API_CALL -clCreateUserEvent(cl_context /* context */, - cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_1; - -extern CL_API_ENTRY cl_int CL_API_CALL -clRetainEvent(cl_event /* event */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clReleaseEvent(cl_event /* event */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clSetUserEventStatus(cl_event /* event */, - cl_int /* execution_status */) CL_API_SUFFIX__VERSION_1_1; - -extern CL_API_ENTRY cl_int CL_API_CALL -clSetEventCallback( cl_event /* event */, - cl_int /* command_exec_callback_type */, - void (CL_CALLBACK * /* pfn_notify */)(cl_event, cl_int, void *), - void * /* user_data */) CL_API_SUFFIX__VERSION_1_1; - -/* Profiling APIs */ -extern CL_API_ENTRY cl_int CL_API_CALL -clGetEventProfilingInfo(cl_event /* event */, - cl_profiling_info /* param_name */, - size_t /* param_value_size */, - void * /* param_value */, - size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; - -/* Flush and Finish APIs */ -extern CL_API_ENTRY cl_int CL_API_CALL -clFlush(cl_command_queue /* command_queue */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clFinish(cl_command_queue /* command_queue */) CL_API_SUFFIX__VERSION_1_0; - -/* Enqueued Commands APIs */ -extern CL_API_ENTRY cl_int CL_API_CALL -clEnqueueReadBuffer(cl_command_queue /* command_queue */, - cl_mem /* buffer */, - cl_bool /* blocking_read */, - size_t /* offset */, - size_t /* size */, - void * /* ptr */, - cl_uint /* num_events_in_wait_list */, - const cl_event * /* event_wait_list */, - cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clEnqueueReadBufferRect(cl_command_queue /* command_queue */, - cl_mem /* buffer */, - cl_bool /* blocking_read */, - const size_t * /* buffer_offset */, - const size_t * /* host_offset */, - const size_t * /* region */, - size_t /* buffer_row_pitch */, - size_t /* buffer_slice_pitch */, - size_t /* host_row_pitch */, - size_t /* host_slice_pitch */, - void * /* ptr */, - cl_uint /* num_events_in_wait_list */, - const cl_event * /* event_wait_list */, - cl_event * /* event */) CL_API_SUFFIX__VERSION_1_1; - -extern CL_API_ENTRY cl_int CL_API_CALL -clEnqueueWriteBuffer(cl_command_queue /* command_queue */, - cl_mem /* buffer */, - cl_bool /* blocking_write */, - size_t /* offset */, - size_t /* size */, - const void * /* ptr */, - cl_uint /* num_events_in_wait_list */, - const cl_event * /* event_wait_list */, - cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clEnqueueWriteBufferRect(cl_command_queue /* command_queue */, - cl_mem /* buffer */, - cl_bool /* blocking_write */, - const size_t * /* buffer_offset */, - const size_t * /* host_offset */, - const size_t * /* region */, - size_t /* buffer_row_pitch */, - size_t /* buffer_slice_pitch */, - size_t /* host_row_pitch */, - size_t /* host_slice_pitch */, - const void * /* ptr */, - cl_uint /* num_events_in_wait_list */, - const cl_event * /* event_wait_list */, - cl_event * /* event */) CL_API_SUFFIX__VERSION_1_1; - -extern CL_API_ENTRY cl_int CL_API_CALL -clEnqueueFillBuffer(cl_command_queue /* command_queue */, - cl_mem /* buffer */, - const void * /* pattern */, - size_t /* pattern_size */, - size_t /* offset */, - size_t /* size */, - cl_uint /* num_events_in_wait_list */, - const cl_event * /* event_wait_list */, - cl_event * /* event */) CL_API_SUFFIX__VERSION_1_2; - -extern CL_API_ENTRY cl_int CL_API_CALL -clEnqueueCopyBuffer(cl_command_queue /* command_queue */, - cl_mem /* src_buffer */, - cl_mem /* dst_buffer */, - size_t /* src_offset */, - size_t /* dst_offset */, - size_t /* size */, - cl_uint /* num_events_in_wait_list */, - const cl_event * /* event_wait_list */, - cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clEnqueueCopyBufferRect(cl_command_queue /* command_queue */, - cl_mem /* src_buffer */, - cl_mem /* dst_buffer */, - const size_t * /* src_origin */, - const size_t * /* dst_origin */, - const size_t * /* region */, - size_t /* src_row_pitch */, - size_t /* src_slice_pitch */, - size_t /* dst_row_pitch */, - size_t /* dst_slice_pitch */, - cl_uint /* num_events_in_wait_list */, - const cl_event * /* event_wait_list */, - cl_event * /* event */) CL_API_SUFFIX__VERSION_1_1; - -extern CL_API_ENTRY cl_int CL_API_CALL -clEnqueueReadImage(cl_command_queue /* command_queue */, - cl_mem /* image */, - cl_bool /* blocking_read */, - const size_t * /* origin[3] */, - const size_t * /* region[3] */, - size_t /* row_pitch */, - size_t /* slice_pitch */, - void * /* ptr */, - cl_uint /* num_events_in_wait_list */, - const cl_event * /* event_wait_list */, - cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clEnqueueWriteImage(cl_command_queue /* command_queue */, - cl_mem /* image */, - cl_bool /* blocking_write */, - const size_t * /* origin[3] */, - const size_t * /* region[3] */, - size_t /* input_row_pitch */, - size_t /* input_slice_pitch */, - const void * /* ptr */, - cl_uint /* num_events_in_wait_list */, - const cl_event * /* event_wait_list */, - cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clEnqueueFillImage(cl_command_queue /* command_queue */, - cl_mem /* image */, - const void * /* fill_color */, - const size_t * /* origin[3] */, - const size_t * /* region[3] */, - cl_uint /* num_events_in_wait_list */, - const cl_event * /* event_wait_list */, - cl_event * /* event */) CL_API_SUFFIX__VERSION_1_2; - -extern CL_API_ENTRY cl_int CL_API_CALL -clEnqueueCopyImage(cl_command_queue /* command_queue */, - cl_mem /* src_image */, - cl_mem /* dst_image */, - const size_t * /* src_origin[3] */, - const size_t * /* dst_origin[3] */, - const size_t * /* region[3] */, - cl_uint /* num_events_in_wait_list */, - const cl_event * /* event_wait_list */, - cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clEnqueueCopyImageToBuffer(cl_command_queue /* command_queue */, - cl_mem /* src_image */, - cl_mem /* dst_buffer */, - const size_t * /* src_origin[3] */, - const size_t * /* region[3] */, - size_t /* dst_offset */, - cl_uint /* num_events_in_wait_list */, - const cl_event * /* event_wait_list */, - cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clEnqueueCopyBufferToImage(cl_command_queue /* command_queue */, - cl_mem /* src_buffer */, - cl_mem /* dst_image */, - size_t /* src_offset */, - const size_t * /* dst_origin[3] */, - const size_t * /* region[3] */, - cl_uint /* num_events_in_wait_list */, - const cl_event * /* event_wait_list */, - cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY void * CL_API_CALL -clEnqueueMapBuffer(cl_command_queue /* command_queue */, - cl_mem /* buffer */, - cl_bool /* blocking_map */, - cl_map_flags /* map_flags */, - size_t /* offset */, - size_t /* size */, - cl_uint /* num_events_in_wait_list */, - const cl_event * /* event_wait_list */, - cl_event * /* event */, - cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY void * CL_API_CALL -clEnqueueMapImage(cl_command_queue /* command_queue */, - cl_mem /* image */, - cl_bool /* blocking_map */, - cl_map_flags /* map_flags */, - const size_t * /* origin[3] */, - const size_t * /* region[3] */, - size_t * /* image_row_pitch */, - size_t * /* image_slice_pitch */, - cl_uint /* num_events_in_wait_list */, - const cl_event * /* event_wait_list */, - cl_event * /* event */, - cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clEnqueueUnmapMemObject(cl_command_queue /* command_queue */, - cl_mem /* memobj */, - void * /* mapped_ptr */, - cl_uint /* num_events_in_wait_list */, - const cl_event * /* event_wait_list */, - cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clEnqueueMigrateMemObjects(cl_command_queue /* command_queue */, - cl_uint /* num_mem_objects */, - const cl_mem * /* mem_objects */, - cl_mem_migration_flags /* flags */, - cl_uint /* num_events_in_wait_list */, - const cl_event * /* event_wait_list */, - cl_event * /* event */) CL_API_SUFFIX__VERSION_1_2; - -extern CL_API_ENTRY cl_int CL_API_CALL -clEnqueueNDRangeKernel(cl_command_queue /* command_queue */, - cl_kernel /* kernel */, - cl_uint /* work_dim */, - const size_t * /* global_work_offset */, - const size_t * /* global_work_size */, - const size_t * /* local_work_size */, - cl_uint /* num_events_in_wait_list */, - const cl_event * /* event_wait_list */, - cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clEnqueueNativeKernel(cl_command_queue /* command_queue */, - void (CL_CALLBACK * /*user_func*/)(void *), - void * /* args */, - size_t /* cb_args */, - cl_uint /* num_mem_objects */, - const cl_mem * /* mem_list */, - const void ** /* args_mem_loc */, - cl_uint /* num_events_in_wait_list */, - const cl_event * /* event_wait_list */, - cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clEnqueueMarkerWithWaitList(cl_command_queue /* command_queue */, - cl_uint /* num_events_in_wait_list */, - const cl_event * /* event_wait_list */, - cl_event * /* event */) CL_API_SUFFIX__VERSION_1_2; - -extern CL_API_ENTRY cl_int CL_API_CALL -clEnqueueBarrierWithWaitList(cl_command_queue /* command_queue */, - cl_uint /* num_events_in_wait_list */, - const cl_event * /* event_wait_list */, - cl_event * /* event */) CL_API_SUFFIX__VERSION_1_2; - -extern CL_API_ENTRY cl_int CL_API_CALL -clEnqueueSVMFree(cl_command_queue /* command_queue */, - cl_uint /* num_svm_pointers */, - void *[] /* svm_pointers[] */, - void (CL_CALLBACK * /*pfn_free_func*/)(cl_command_queue /* queue */, - cl_uint /* num_svm_pointers */, - void *[] /* svm_pointers[] */, - void * /* user_data */), - void * /* user_data */, - cl_uint /* num_events_in_wait_list */, - const cl_event * /* event_wait_list */, - cl_event * /* event */) CL_API_SUFFIX__VERSION_2_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clEnqueueSVMMemcpy(cl_command_queue /* command_queue */, - cl_bool /* blocking_copy */, - void * /* dst_ptr */, - const void * /* src_ptr */, - size_t /* size */, - cl_uint /* num_events_in_wait_list */, - const cl_event * /* event_wait_list */, - cl_event * /* event */) CL_API_SUFFIX__VERSION_2_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clEnqueueSVMMemFill(cl_command_queue /* command_queue */, - void * /* svm_ptr */, - const void * /* pattern */, - size_t /* pattern_size */, - size_t /* size */, - cl_uint /* num_events_in_wait_list */, - const cl_event * /* event_wait_list */, - cl_event * /* event */) CL_API_SUFFIX__VERSION_2_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clEnqueueSVMMap(cl_command_queue /* command_queue */, - cl_bool /* blocking_map */, - cl_map_flags /* flags */, - void * /* svm_ptr */, - size_t /* size */, - cl_uint /* num_events_in_wait_list */, - const cl_event * /* event_wait_list */, - cl_event * /* event */) CL_API_SUFFIX__VERSION_2_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clEnqueueSVMUnmap(cl_command_queue /* command_queue */, - void * /* svm_ptr */, - cl_uint /* num_events_in_wait_list */, - const cl_event * /* event_wait_list */, - cl_event * /* event */) CL_API_SUFFIX__VERSION_2_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clEnqueueSVMMigrateMem(cl_command_queue /* command_queue */, - cl_uint /* num_svm_pointers */, - const void ** /* svm_pointers */, - const size_t * /* sizes */, - cl_mem_migration_flags /* flags */, - cl_uint /* num_events_in_wait_list */, - const cl_event * /* event_wait_list */, - cl_event * /* event */) CL_API_SUFFIX__VERSION_2_1; - - -/* Extension function access - * - * Returns the extension function address for the given function name, - * or NULL if a valid function can not be found. The client must - * check to make sure the address is not NULL, before using or - * calling the returned function address. - */ -extern CL_API_ENTRY void * CL_API_CALL -clGetExtensionFunctionAddressForPlatform(cl_platform_id /* platform */, - const char * /* func_name */) CL_API_SUFFIX__VERSION_1_2; - - -/* Deprecated OpenCL 1.1 APIs */ -extern CL_API_ENTRY CL_EXT_PREFIX__VERSION_1_1_DEPRECATED cl_mem CL_API_CALL -clCreateImage2D(cl_context /* context */, - cl_mem_flags /* flags */, - const cl_image_format * /* image_format */, - size_t /* image_width */, - size_t /* image_height */, - size_t /* image_row_pitch */, - void * /* host_ptr */, - cl_int * /* errcode_ret */) CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED; - -extern CL_API_ENTRY CL_EXT_PREFIX__VERSION_1_1_DEPRECATED cl_mem CL_API_CALL -clCreateImage3D(cl_context /* context */, - cl_mem_flags /* flags */, - const cl_image_format * /* image_format */, - size_t /* image_width */, - size_t /* image_height */, - size_t /* image_depth */, - size_t /* image_row_pitch */, - size_t /* image_slice_pitch */, - void * /* host_ptr */, - cl_int * /* errcode_ret */) CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED; - -extern CL_API_ENTRY CL_EXT_PREFIX__VERSION_1_1_DEPRECATED cl_int CL_API_CALL -clEnqueueMarker(cl_command_queue /* command_queue */, - cl_event * /* event */) CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED; - -extern CL_API_ENTRY CL_EXT_PREFIX__VERSION_1_1_DEPRECATED cl_int CL_API_CALL -clEnqueueWaitForEvents(cl_command_queue /* command_queue */, - cl_uint /* num_events */, - const cl_event * /* event_list */) CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED; - -extern CL_API_ENTRY CL_EXT_PREFIX__VERSION_1_1_DEPRECATED cl_int CL_API_CALL -clEnqueueBarrier(cl_command_queue /* command_queue */) CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED; - -extern CL_API_ENTRY CL_EXT_PREFIX__VERSION_1_1_DEPRECATED cl_int CL_API_CALL -clUnloadCompiler(void) CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED; - -extern CL_API_ENTRY CL_EXT_PREFIX__VERSION_1_1_DEPRECATED void * CL_API_CALL -clGetExtensionFunctionAddress(const char * /* func_name */) CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED; - -/* Deprecated OpenCL 2.0 APIs */ -extern CL_API_ENTRY CL_EXT_PREFIX__VERSION_1_2_DEPRECATED cl_command_queue CL_API_CALL -clCreateCommandQueue(cl_context /* context */, - cl_device_id /* device */, - cl_command_queue_properties /* properties */, - cl_int * /* errcode_ret */) CL_EXT_SUFFIX__VERSION_1_2_DEPRECATED; - - -extern CL_API_ENTRY CL_EXT_PREFIX__VERSION_1_2_DEPRECATED cl_sampler CL_API_CALL -clCreateSampler(cl_context /* context */, - cl_bool /* normalized_coords */, - cl_addressing_mode /* addressing_mode */, - cl_filter_mode /* filter_mode */, - cl_int * /* errcode_ret */) CL_EXT_SUFFIX__VERSION_1_2_DEPRECATED; - -extern CL_API_ENTRY CL_EXT_PREFIX__VERSION_1_2_DEPRECATED cl_int CL_API_CALL -clEnqueueTask(cl_command_queue /* command_queue */, - cl_kernel /* kernel */, - cl_uint /* num_events_in_wait_list */, - const cl_event * /* event_wait_list */, - cl_event * /* event */) CL_EXT_SUFFIX__VERSION_1_2_DEPRECATED; - -#ifdef __cplusplus -} -#endif - -#endif /* __OPENCL_CL_H */ - diff --git a/third_party/opencl/include/CL/cl_d3d10.h b/third_party/opencl/include/CL/cl_d3d10.h deleted file mode 100644 index d5960a4..0000000 --- a/third_party/opencl/include/CL/cl_d3d10.h +++ /dev/null @@ -1,131 +0,0 @@ -/********************************************************************************** - * Copyright (c) 2008-2015 The Khronos Group Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining a - * copy of this software and/or associated documentation files (the - * "Materials"), to deal in the Materials without restriction, including - * without limitation the rights to use, copy, modify, merge, publish, - * distribute, sublicense, and/or sell copies of the Materials, and to - * permit persons to whom the Materials are furnished to do so, subject to - * the following conditions: - * - * The above copyright notice and this permission notice shall be included - * in all copies or substantial portions of the Materials. - * - * MODIFICATIONS TO THIS FILE MAY MEAN IT NO LONGER ACCURATELY REFLECTS - * KHRONOS STANDARDS. THE UNMODIFIED, NORMATIVE VERSIONS OF KHRONOS - * SPECIFICATIONS AND HEADER INFORMATION ARE LOCATED AT - * https://www.khronos.org/registry/ - * - * THE MATERIALS ARE PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, - * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. - * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY - * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, - * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE - * MATERIALS OR THE USE OR OTHER DEALINGS IN THE MATERIALS. - **********************************************************************************/ - -/* $Revision: 11708 $ on $Date: 2010-06-13 23:36:24 -0700 (Sun, 13 Jun 2010) $ */ - -#ifndef __OPENCL_CL_D3D10_H -#define __OPENCL_CL_D3D10_H - -#include -#include -#include - -#ifdef __cplusplus -extern "C" { -#endif - -/****************************************************************************** - * cl_khr_d3d10_sharing */ -#define cl_khr_d3d10_sharing 1 - -typedef cl_uint cl_d3d10_device_source_khr; -typedef cl_uint cl_d3d10_device_set_khr; - -/******************************************************************************/ - -/* Error Codes */ -#define CL_INVALID_D3D10_DEVICE_KHR -1002 -#define CL_INVALID_D3D10_RESOURCE_KHR -1003 -#define CL_D3D10_RESOURCE_ALREADY_ACQUIRED_KHR -1004 -#define CL_D3D10_RESOURCE_NOT_ACQUIRED_KHR -1005 - -/* cl_d3d10_device_source_nv */ -#define CL_D3D10_DEVICE_KHR 0x4010 -#define CL_D3D10_DXGI_ADAPTER_KHR 0x4011 - -/* cl_d3d10_device_set_nv */ -#define CL_PREFERRED_DEVICES_FOR_D3D10_KHR 0x4012 -#define CL_ALL_DEVICES_FOR_D3D10_KHR 0x4013 - -/* cl_context_info */ -#define CL_CONTEXT_D3D10_DEVICE_KHR 0x4014 -#define CL_CONTEXT_D3D10_PREFER_SHARED_RESOURCES_KHR 0x402C - -/* cl_mem_info */ -#define CL_MEM_D3D10_RESOURCE_KHR 0x4015 - -/* cl_image_info */ -#define CL_IMAGE_D3D10_SUBRESOURCE_KHR 0x4016 - -/* cl_command_type */ -#define CL_COMMAND_ACQUIRE_D3D10_OBJECTS_KHR 0x4017 -#define CL_COMMAND_RELEASE_D3D10_OBJECTS_KHR 0x4018 - -/******************************************************************************/ - -typedef CL_API_ENTRY cl_int (CL_API_CALL *clGetDeviceIDsFromD3D10KHR_fn)( - cl_platform_id platform, - cl_d3d10_device_source_khr d3d_device_source, - void * d3d_object, - cl_d3d10_device_set_khr d3d_device_set, - cl_uint num_entries, - cl_device_id * devices, - cl_uint * num_devices) CL_API_SUFFIX__VERSION_1_0; - -typedef CL_API_ENTRY cl_mem (CL_API_CALL *clCreateFromD3D10BufferKHR_fn)( - cl_context context, - cl_mem_flags flags, - ID3D10Buffer * resource, - cl_int * errcode_ret) CL_API_SUFFIX__VERSION_1_0; - -typedef CL_API_ENTRY cl_mem (CL_API_CALL *clCreateFromD3D10Texture2DKHR_fn)( - cl_context context, - cl_mem_flags flags, - ID3D10Texture2D * resource, - UINT subresource, - cl_int * errcode_ret) CL_API_SUFFIX__VERSION_1_0; - -typedef CL_API_ENTRY cl_mem (CL_API_CALL *clCreateFromD3D10Texture3DKHR_fn)( - cl_context context, - cl_mem_flags flags, - ID3D10Texture3D * resource, - UINT subresource, - cl_int * errcode_ret) CL_API_SUFFIX__VERSION_1_0; - -typedef CL_API_ENTRY cl_int (CL_API_CALL *clEnqueueAcquireD3D10ObjectsKHR_fn)( - cl_command_queue command_queue, - cl_uint num_objects, - const cl_mem * mem_objects, - cl_uint num_events_in_wait_list, - const cl_event * event_wait_list, - cl_event * event) CL_API_SUFFIX__VERSION_1_0; - -typedef CL_API_ENTRY cl_int (CL_API_CALL *clEnqueueReleaseD3D10ObjectsKHR_fn)( - cl_command_queue command_queue, - cl_uint num_objects, - const cl_mem * mem_objects, - cl_uint num_events_in_wait_list, - const cl_event * event_wait_list, - cl_event * event) CL_API_SUFFIX__VERSION_1_0; - -#ifdef __cplusplus -} -#endif - -#endif /* __OPENCL_CL_D3D10_H */ - diff --git a/third_party/opencl/include/CL/cl_d3d11.h b/third_party/opencl/include/CL/cl_d3d11.h deleted file mode 100644 index 39f9072..0000000 --- a/third_party/opencl/include/CL/cl_d3d11.h +++ /dev/null @@ -1,131 +0,0 @@ -/********************************************************************************** - * Copyright (c) 2008-2015 The Khronos Group Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining a - * copy of this software and/or associated documentation files (the - * "Materials"), to deal in the Materials without restriction, including - * without limitation the rights to use, copy, modify, merge, publish, - * distribute, sublicense, and/or sell copies of the Materials, and to - * permit persons to whom the Materials are furnished to do so, subject to - * the following conditions: - * - * The above copyright notice and this permission notice shall be included - * in all copies or substantial portions of the Materials. - * - * MODIFICATIONS TO THIS FILE MAY MEAN IT NO LONGER ACCURATELY REFLECTS - * KHRONOS STANDARDS. THE UNMODIFIED, NORMATIVE VERSIONS OF KHRONOS - * SPECIFICATIONS AND HEADER INFORMATION ARE LOCATED AT - * https://www.khronos.org/registry/ - * - * THE MATERIALS ARE PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, - * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. - * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY - * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, - * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE - * MATERIALS OR THE USE OR OTHER DEALINGS IN THE MATERIALS. - **********************************************************************************/ - -/* $Revision: 11708 $ on $Date: 2010-06-13 23:36:24 -0700 (Sun, 13 Jun 2010) $ */ - -#ifndef __OPENCL_CL_D3D11_H -#define __OPENCL_CL_D3D11_H - -#include -#include -#include - -#ifdef __cplusplus -extern "C" { -#endif - -/****************************************************************************** - * cl_khr_d3d11_sharing */ -#define cl_khr_d3d11_sharing 1 - -typedef cl_uint cl_d3d11_device_source_khr; -typedef cl_uint cl_d3d11_device_set_khr; - -/******************************************************************************/ - -/* Error Codes */ -#define CL_INVALID_D3D11_DEVICE_KHR -1006 -#define CL_INVALID_D3D11_RESOURCE_KHR -1007 -#define CL_D3D11_RESOURCE_ALREADY_ACQUIRED_KHR -1008 -#define CL_D3D11_RESOURCE_NOT_ACQUIRED_KHR -1009 - -/* cl_d3d11_device_source */ -#define CL_D3D11_DEVICE_KHR 0x4019 -#define CL_D3D11_DXGI_ADAPTER_KHR 0x401A - -/* cl_d3d11_device_set */ -#define CL_PREFERRED_DEVICES_FOR_D3D11_KHR 0x401B -#define CL_ALL_DEVICES_FOR_D3D11_KHR 0x401C - -/* cl_context_info */ -#define CL_CONTEXT_D3D11_DEVICE_KHR 0x401D -#define CL_CONTEXT_D3D11_PREFER_SHARED_RESOURCES_KHR 0x402D - -/* cl_mem_info */ -#define CL_MEM_D3D11_RESOURCE_KHR 0x401E - -/* cl_image_info */ -#define CL_IMAGE_D3D11_SUBRESOURCE_KHR 0x401F - -/* cl_command_type */ -#define CL_COMMAND_ACQUIRE_D3D11_OBJECTS_KHR 0x4020 -#define CL_COMMAND_RELEASE_D3D11_OBJECTS_KHR 0x4021 - -/******************************************************************************/ - -typedef CL_API_ENTRY cl_int (CL_API_CALL *clGetDeviceIDsFromD3D11KHR_fn)( - cl_platform_id platform, - cl_d3d11_device_source_khr d3d_device_source, - void * d3d_object, - cl_d3d11_device_set_khr d3d_device_set, - cl_uint num_entries, - cl_device_id * devices, - cl_uint * num_devices) CL_API_SUFFIX__VERSION_1_2; - -typedef CL_API_ENTRY cl_mem (CL_API_CALL *clCreateFromD3D11BufferKHR_fn)( - cl_context context, - cl_mem_flags flags, - ID3D11Buffer * resource, - cl_int * errcode_ret) CL_API_SUFFIX__VERSION_1_2; - -typedef CL_API_ENTRY cl_mem (CL_API_CALL *clCreateFromD3D11Texture2DKHR_fn)( - cl_context context, - cl_mem_flags flags, - ID3D11Texture2D * resource, - UINT subresource, - cl_int * errcode_ret) CL_API_SUFFIX__VERSION_1_2; - -typedef CL_API_ENTRY cl_mem (CL_API_CALL *clCreateFromD3D11Texture3DKHR_fn)( - cl_context context, - cl_mem_flags flags, - ID3D11Texture3D * resource, - UINT subresource, - cl_int * errcode_ret) CL_API_SUFFIX__VERSION_1_2; - -typedef CL_API_ENTRY cl_int (CL_API_CALL *clEnqueueAcquireD3D11ObjectsKHR_fn)( - cl_command_queue command_queue, - cl_uint num_objects, - const cl_mem * mem_objects, - cl_uint num_events_in_wait_list, - const cl_event * event_wait_list, - cl_event * event) CL_API_SUFFIX__VERSION_1_2; - -typedef CL_API_ENTRY cl_int (CL_API_CALL *clEnqueueReleaseD3D11ObjectsKHR_fn)( - cl_command_queue command_queue, - cl_uint num_objects, - const cl_mem * mem_objects, - cl_uint num_events_in_wait_list, - const cl_event * event_wait_list, - cl_event * event) CL_API_SUFFIX__VERSION_1_2; - -#ifdef __cplusplus -} -#endif - -#endif /* __OPENCL_CL_D3D11_H */ - diff --git a/third_party/opencl/include/CL/cl_dx9_media_sharing.h b/third_party/opencl/include/CL/cl_dx9_media_sharing.h deleted file mode 100644 index 2729e8b..0000000 --- a/third_party/opencl/include/CL/cl_dx9_media_sharing.h +++ /dev/null @@ -1,132 +0,0 @@ -/********************************************************************************** - * Copyright (c) 2008-2015 The Khronos Group Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining a - * copy of this software and/or associated documentation files (the - * "Materials"), to deal in the Materials without restriction, including - * without limitation the rights to use, copy, modify, merge, publish, - * distribute, sublicense, and/or sell copies of the Materials, and to - * permit persons to whom the Materials are furnished to do so, subject to - * the following conditions: - * - * The above copyright notice and this permission notice shall be included - * in all copies or substantial portions of the Materials. - * - * MODIFICATIONS TO THIS FILE MAY MEAN IT NO LONGER ACCURATELY REFLECTS - * KHRONOS STANDARDS. THE UNMODIFIED, NORMATIVE VERSIONS OF KHRONOS - * SPECIFICATIONS AND HEADER INFORMATION ARE LOCATED AT - * https://www.khronos.org/registry/ - * - * THE MATERIALS ARE PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, - * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. - * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY - * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, - * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE - * MATERIALS OR THE USE OR OTHER DEALINGS IN THE MATERIALS. - **********************************************************************************/ - -/* $Revision: 11708 $ on $Date: 2010-06-13 23:36:24 -0700 (Sun, 13 Jun 2010) $ */ - -#ifndef __OPENCL_CL_DX9_MEDIA_SHARING_H -#define __OPENCL_CL_DX9_MEDIA_SHARING_H - -#include -#include - -#ifdef __cplusplus -extern "C" { -#endif - -/******************************************************************************/ -/* cl_khr_dx9_media_sharing */ -#define cl_khr_dx9_media_sharing 1 - -typedef cl_uint cl_dx9_media_adapter_type_khr; -typedef cl_uint cl_dx9_media_adapter_set_khr; - -#if defined(_WIN32) -#include -typedef struct _cl_dx9_surface_info_khr -{ - IDirect3DSurface9 *resource; - HANDLE shared_handle; -} cl_dx9_surface_info_khr; -#endif - - -/******************************************************************************/ - -/* Error Codes */ -#define CL_INVALID_DX9_MEDIA_ADAPTER_KHR -1010 -#define CL_INVALID_DX9_MEDIA_SURFACE_KHR -1011 -#define CL_DX9_MEDIA_SURFACE_ALREADY_ACQUIRED_KHR -1012 -#define CL_DX9_MEDIA_SURFACE_NOT_ACQUIRED_KHR -1013 - -/* cl_media_adapter_type_khr */ -#define CL_ADAPTER_D3D9_KHR 0x2020 -#define CL_ADAPTER_D3D9EX_KHR 0x2021 -#define CL_ADAPTER_DXVA_KHR 0x2022 - -/* cl_media_adapter_set_khr */ -#define CL_PREFERRED_DEVICES_FOR_DX9_MEDIA_ADAPTER_KHR 0x2023 -#define CL_ALL_DEVICES_FOR_DX9_MEDIA_ADAPTER_KHR 0x2024 - -/* cl_context_info */ -#define CL_CONTEXT_ADAPTER_D3D9_KHR 0x2025 -#define CL_CONTEXT_ADAPTER_D3D9EX_KHR 0x2026 -#define CL_CONTEXT_ADAPTER_DXVA_KHR 0x2027 - -/* cl_mem_info */ -#define CL_MEM_DX9_MEDIA_ADAPTER_TYPE_KHR 0x2028 -#define CL_MEM_DX9_MEDIA_SURFACE_INFO_KHR 0x2029 - -/* cl_image_info */ -#define CL_IMAGE_DX9_MEDIA_PLANE_KHR 0x202A - -/* cl_command_type */ -#define CL_COMMAND_ACQUIRE_DX9_MEDIA_SURFACES_KHR 0x202B -#define CL_COMMAND_RELEASE_DX9_MEDIA_SURFACES_KHR 0x202C - -/******************************************************************************/ - -typedef CL_API_ENTRY cl_int (CL_API_CALL *clGetDeviceIDsFromDX9MediaAdapterKHR_fn)( - cl_platform_id platform, - cl_uint num_media_adapters, - cl_dx9_media_adapter_type_khr * media_adapter_type, - void * media_adapters, - cl_dx9_media_adapter_set_khr media_adapter_set, - cl_uint num_entries, - cl_device_id * devices, - cl_uint * num_devices) CL_API_SUFFIX__VERSION_1_2; - -typedef CL_API_ENTRY cl_mem (CL_API_CALL *clCreateFromDX9MediaSurfaceKHR_fn)( - cl_context context, - cl_mem_flags flags, - cl_dx9_media_adapter_type_khr adapter_type, - void * surface_info, - cl_uint plane, - cl_int * errcode_ret) CL_API_SUFFIX__VERSION_1_2; - -typedef CL_API_ENTRY cl_int (CL_API_CALL *clEnqueueAcquireDX9MediaSurfacesKHR_fn)( - cl_command_queue command_queue, - cl_uint num_objects, - const cl_mem * mem_objects, - cl_uint num_events_in_wait_list, - const cl_event * event_wait_list, - cl_event * event) CL_API_SUFFIX__VERSION_1_2; - -typedef CL_API_ENTRY cl_int (CL_API_CALL *clEnqueueReleaseDX9MediaSurfacesKHR_fn)( - cl_command_queue command_queue, - cl_uint num_objects, - const cl_mem * mem_objects, - cl_uint num_events_in_wait_list, - const cl_event * event_wait_list, - cl_event * event) CL_API_SUFFIX__VERSION_1_2; - -#ifdef __cplusplus -} -#endif - -#endif /* __OPENCL_CL_DX9_MEDIA_SHARING_H */ - diff --git a/third_party/opencl/include/CL/cl_egl.h b/third_party/opencl/include/CL/cl_egl.h deleted file mode 100644 index a765bd5..0000000 --- a/third_party/opencl/include/CL/cl_egl.h +++ /dev/null @@ -1,136 +0,0 @@ -/******************************************************************************* - * Copyright (c) 2008-2015 The Khronos Group Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining a - * copy of this software and/or associated documentation files (the - * "Materials"), to deal in the Materials without restriction, including - * without limitation the rights to use, copy, modify, merge, publish, - * distribute, sublicense, and/or sell copies of the Materials, and to - * permit persons to whom the Materials are furnished to do so, subject to - * the following conditions: - * - * The above copyright notice and this permission notice shall be included - * in all copies or substantial portions of the Materials. - * - * MODIFICATIONS TO THIS FILE MAY MEAN IT NO LONGER ACCURATELY REFLECTS - * KHRONOS STANDARDS. THE UNMODIFIED, NORMATIVE VERSIONS OF KHRONOS - * SPECIFICATIONS AND HEADER INFORMATION ARE LOCATED AT - * https://www.khronos.org/registry/ - * - * THE MATERIALS ARE PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, - * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. - * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY - * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, - * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE - * MATERIALS OR THE USE OR OTHER DEALINGS IN THE MATERIALS. - ******************************************************************************/ - -#ifndef __OPENCL_CL_EGL_H -#define __OPENCL_CL_EGL_H - -#ifdef __APPLE__ - -#else -#include -#endif - -#ifdef __cplusplus -extern "C" { -#endif - - -/* Command type for events created with clEnqueueAcquireEGLObjectsKHR */ -#define CL_COMMAND_EGL_FENCE_SYNC_OBJECT_KHR 0x202F -#define CL_COMMAND_ACQUIRE_EGL_OBJECTS_KHR 0x202D -#define CL_COMMAND_RELEASE_EGL_OBJECTS_KHR 0x202E - -/* Error type for clCreateFromEGLImageKHR */ -#define CL_INVALID_EGL_OBJECT_KHR -1093 -#define CL_EGL_RESOURCE_NOT_ACQUIRED_KHR -1092 - -/* CLeglImageKHR is an opaque handle to an EGLImage */ -typedef void* CLeglImageKHR; - -/* CLeglDisplayKHR is an opaque handle to an EGLDisplay */ -typedef void* CLeglDisplayKHR; - -/* CLeglSyncKHR is an opaque handle to an EGLSync object */ -typedef void* CLeglSyncKHR; - -/* properties passed to clCreateFromEGLImageKHR */ -typedef intptr_t cl_egl_image_properties_khr; - - -#define cl_khr_egl_image 1 - -extern CL_API_ENTRY cl_mem CL_API_CALL -clCreateFromEGLImageKHR(cl_context /* context */, - CLeglDisplayKHR /* egldisplay */, - CLeglImageKHR /* eglimage */, - cl_mem_flags /* flags */, - const cl_egl_image_properties_khr * /* properties */, - cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_0; - -typedef CL_API_ENTRY cl_mem (CL_API_CALL *clCreateFromEGLImageKHR_fn)( - cl_context context, - CLeglDisplayKHR egldisplay, - CLeglImageKHR eglimage, - cl_mem_flags flags, - const cl_egl_image_properties_khr * properties, - cl_int * errcode_ret); - - -extern CL_API_ENTRY cl_int CL_API_CALL -clEnqueueAcquireEGLObjectsKHR(cl_command_queue /* command_queue */, - cl_uint /* num_objects */, - const cl_mem * /* mem_objects */, - cl_uint /* num_events_in_wait_list */, - const cl_event * /* event_wait_list */, - cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; - -typedef CL_API_ENTRY cl_int (CL_API_CALL *clEnqueueAcquireEGLObjectsKHR_fn)( - cl_command_queue command_queue, - cl_uint num_objects, - const cl_mem * mem_objects, - cl_uint num_events_in_wait_list, - const cl_event * event_wait_list, - cl_event * event); - - -extern CL_API_ENTRY cl_int CL_API_CALL -clEnqueueReleaseEGLObjectsKHR(cl_command_queue /* command_queue */, - cl_uint /* num_objects */, - const cl_mem * /* mem_objects */, - cl_uint /* num_events_in_wait_list */, - const cl_event * /* event_wait_list */, - cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; - -typedef CL_API_ENTRY cl_int (CL_API_CALL *clEnqueueReleaseEGLObjectsKHR_fn)( - cl_command_queue command_queue, - cl_uint num_objects, - const cl_mem * mem_objects, - cl_uint num_events_in_wait_list, - const cl_event * event_wait_list, - cl_event * event); - - -#define cl_khr_egl_event 1 - -extern CL_API_ENTRY cl_event CL_API_CALL -clCreateEventFromEGLSyncKHR(cl_context /* context */, - CLeglSyncKHR /* sync */, - CLeglDisplayKHR /* display */, - cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_0; - -typedef CL_API_ENTRY cl_event (CL_API_CALL *clCreateEventFromEGLSyncKHR_fn)( - cl_context context, - CLeglSyncKHR sync, - CLeglDisplayKHR display, - cl_int * errcode_ret); - -#ifdef __cplusplus -} -#endif - -#endif /* __OPENCL_CL_EGL_H */ diff --git a/third_party/opencl/include/CL/cl_ext.h b/third_party/opencl/include/CL/cl_ext.h deleted file mode 100644 index 7941583..0000000 --- a/third_party/opencl/include/CL/cl_ext.h +++ /dev/null @@ -1,391 +0,0 @@ -/******************************************************************************* - * Copyright (c) 2008-2015 The Khronos Group Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining a - * copy of this software and/or associated documentation files (the - * "Materials"), to deal in the Materials without restriction, including - * without limitation the rights to use, copy, modify, merge, publish, - * distribute, sublicense, and/or sell copies of the Materials, and to - * permit persons to whom the Materials are furnished to do so, subject to - * the following conditions: - * - * The above copyright notice and this permission notice shall be included - * in all copies or substantial portions of the Materials. - * - * MODIFICATIONS TO THIS FILE MAY MEAN IT NO LONGER ACCURATELY REFLECTS - * KHRONOS STANDARDS. THE UNMODIFIED, NORMATIVE VERSIONS OF KHRONOS - * SPECIFICATIONS AND HEADER INFORMATION ARE LOCATED AT - * https://www.khronos.org/registry/ - * - * THE MATERIALS ARE PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, - * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. - * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY - * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, - * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE - * MATERIALS OR THE USE OR OTHER DEALINGS IN THE MATERIALS. - ******************************************************************************/ - -/* $Revision: 11928 $ on $Date: 2010-07-13 09:04:56 -0700 (Tue, 13 Jul 2010) $ */ - -/* cl_ext.h contains OpenCL extensions which don't have external */ -/* (OpenGL, D3D) dependencies. */ - -#ifndef __CL_EXT_H -#define __CL_EXT_H - -#ifdef __cplusplus -extern "C" { -#endif - -#ifdef __APPLE__ - #include - #include -#else - #include -#endif - -/* cl_khr_fp16 extension - no extension #define since it has no functions */ -#define CL_DEVICE_HALF_FP_CONFIG 0x1033 - -/* Memory object destruction - * - * Apple extension for use to manage externally allocated buffers used with cl_mem objects with CL_MEM_USE_HOST_PTR - * - * Registers a user callback function that will be called when the memory object is deleted and its resources - * freed. Each call to clSetMemObjectCallbackFn registers the specified user callback function on a callback - * stack associated with memobj. The registered user callback functions are called in the reverse order in - * which they were registered. The user callback functions are called and then the memory object is deleted - * and its resources freed. This provides a mechanism for the application (and libraries) using memobj to be - * notified when the memory referenced by host_ptr, specified when the memory object is created and used as - * the storage bits for the memory object, can be reused or freed. - * - * The application may not call CL api's with the cl_mem object passed to the pfn_notify. - * - * Please check for the "cl_APPLE_SetMemObjectDestructor" extension using clGetDeviceInfo(CL_DEVICE_EXTENSIONS) - * before using. - */ -#define cl_APPLE_SetMemObjectDestructor 1 -cl_int CL_API_ENTRY clSetMemObjectDestructorAPPLE( cl_mem /* memobj */, - void (* /*pfn_notify*/)( cl_mem /* memobj */, void* /*user_data*/), - void * /*user_data */ ) CL_EXT_SUFFIX__VERSION_1_0; - - -/* Context Logging Functions - * - * The next three convenience functions are intended to be used as the pfn_notify parameter to clCreateContext(). - * Please check for the "cl_APPLE_ContextLoggingFunctions" extension using clGetDeviceInfo(CL_DEVICE_EXTENSIONS) - * before using. - * - * clLogMessagesToSystemLog fowards on all log messages to the Apple System Logger - */ -#define cl_APPLE_ContextLoggingFunctions 1 -extern void CL_API_ENTRY clLogMessagesToSystemLogAPPLE( const char * /* errstr */, - const void * /* private_info */, - size_t /* cb */, - void * /* user_data */ ) CL_EXT_SUFFIX__VERSION_1_0; - -/* clLogMessagesToStdout sends all log messages to the file descriptor stdout */ -extern void CL_API_ENTRY clLogMessagesToStdoutAPPLE( const char * /* errstr */, - const void * /* private_info */, - size_t /* cb */, - void * /* user_data */ ) CL_EXT_SUFFIX__VERSION_1_0; - -/* clLogMessagesToStderr sends all log messages to the file descriptor stderr */ -extern void CL_API_ENTRY clLogMessagesToStderrAPPLE( const char * /* errstr */, - const void * /* private_info */, - size_t /* cb */, - void * /* user_data */ ) CL_EXT_SUFFIX__VERSION_1_0; - - -/************************ -* cl_khr_icd extension * -************************/ -#define cl_khr_icd 1 - -/* cl_platform_info */ -#define CL_PLATFORM_ICD_SUFFIX_KHR 0x0920 - -/* Additional Error Codes */ -#define CL_PLATFORM_NOT_FOUND_KHR -1001 - -extern CL_API_ENTRY cl_int CL_API_CALL -clIcdGetPlatformIDsKHR(cl_uint /* num_entries */, - cl_platform_id * /* platforms */, - cl_uint * /* num_platforms */); - -typedef CL_API_ENTRY cl_int (CL_API_CALL *clIcdGetPlatformIDsKHR_fn)( - cl_uint /* num_entries */, - cl_platform_id * /* platforms */, - cl_uint * /* num_platforms */); - - -/* Extension: cl_khr_image2D_buffer - * - * This extension allows a 2D image to be created from a cl_mem buffer without a copy. - * The type associated with a 2D image created from a buffer in an OpenCL program is image2d_t. - * Both the sampler and sampler-less read_image built-in functions are supported for 2D images - * and 2D images created from a buffer. Similarly, the write_image built-ins are also supported - * for 2D images created from a buffer. - * - * When the 2D image from buffer is created, the client must specify the width, - * height, image format (i.e. channel order and channel data type) and optionally the row pitch - * - * The pitch specified must be a multiple of CL_DEVICE_IMAGE_PITCH_ALIGNMENT pixels. - * The base address of the buffer must be aligned to CL_DEVICE_IMAGE_BASE_ADDRESS_ALIGNMENT pixels. - */ - -/************************************* - * cl_khr_initalize_memory extension * - *************************************/ - -#define CL_CONTEXT_MEMORY_INITIALIZE_KHR 0x2030 - - -/************************************** - * cl_khr_terminate_context extension * - **************************************/ - -#define CL_DEVICE_TERMINATE_CAPABILITY_KHR 0x2031 -#define CL_CONTEXT_TERMINATE_KHR 0x2032 - -#define cl_khr_terminate_context 1 -extern CL_API_ENTRY cl_int CL_API_CALL clTerminateContextKHR(cl_context /* context */) CL_EXT_SUFFIX__VERSION_1_2; - -typedef CL_API_ENTRY cl_int (CL_API_CALL *clTerminateContextKHR_fn)(cl_context /* context */) CL_EXT_SUFFIX__VERSION_1_2; - - -/* - * Extension: cl_khr_spir - * - * This extension adds support to create an OpenCL program object from a - * Standard Portable Intermediate Representation (SPIR) instance - */ - -#define CL_DEVICE_SPIR_VERSIONS 0x40E0 -#define CL_PROGRAM_BINARY_TYPE_INTERMEDIATE 0x40E1 - - -/****************************************** -* cl_nv_device_attribute_query extension * -******************************************/ -/* cl_nv_device_attribute_query extension - no extension #define since it has no functions */ -#define CL_DEVICE_COMPUTE_CAPABILITY_MAJOR_NV 0x4000 -#define CL_DEVICE_COMPUTE_CAPABILITY_MINOR_NV 0x4001 -#define CL_DEVICE_REGISTERS_PER_BLOCK_NV 0x4002 -#define CL_DEVICE_WARP_SIZE_NV 0x4003 -#define CL_DEVICE_GPU_OVERLAP_NV 0x4004 -#define CL_DEVICE_KERNEL_EXEC_TIMEOUT_NV 0x4005 -#define CL_DEVICE_INTEGRATED_MEMORY_NV 0x4006 - -/********************************* -* cl_amd_device_attribute_query * -*********************************/ -#define CL_DEVICE_PROFILING_TIMER_OFFSET_AMD 0x4036 - -/********************************* -* cl_arm_printf extension -*********************************/ -#define CL_PRINTF_CALLBACK_ARM 0x40B0 -#define CL_PRINTF_BUFFERSIZE_ARM 0x40B1 - -#ifdef CL_VERSION_1_1 - /*********************************** - * cl_ext_device_fission extension * - ***********************************/ - #define cl_ext_device_fission 1 - - extern CL_API_ENTRY cl_int CL_API_CALL - clReleaseDeviceEXT( cl_device_id /*device*/ ) CL_EXT_SUFFIX__VERSION_1_1; - - typedef CL_API_ENTRY cl_int - (CL_API_CALL *clReleaseDeviceEXT_fn)( cl_device_id /*device*/ ) CL_EXT_SUFFIX__VERSION_1_1; - - extern CL_API_ENTRY cl_int CL_API_CALL - clRetainDeviceEXT( cl_device_id /*device*/ ) CL_EXT_SUFFIX__VERSION_1_1; - - typedef CL_API_ENTRY cl_int - (CL_API_CALL *clRetainDeviceEXT_fn)( cl_device_id /*device*/ ) CL_EXT_SUFFIX__VERSION_1_1; - - typedef cl_ulong cl_device_partition_property_ext; - extern CL_API_ENTRY cl_int CL_API_CALL - clCreateSubDevicesEXT( cl_device_id /*in_device*/, - const cl_device_partition_property_ext * /* properties */, - cl_uint /*num_entries*/, - cl_device_id * /*out_devices*/, - cl_uint * /*num_devices*/ ) CL_EXT_SUFFIX__VERSION_1_1; - - typedef CL_API_ENTRY cl_int - ( CL_API_CALL * clCreateSubDevicesEXT_fn)( cl_device_id /*in_device*/, - const cl_device_partition_property_ext * /* properties */, - cl_uint /*num_entries*/, - cl_device_id * /*out_devices*/, - cl_uint * /*num_devices*/ ) CL_EXT_SUFFIX__VERSION_1_1; - - /* cl_device_partition_property_ext */ - #define CL_DEVICE_PARTITION_EQUALLY_EXT 0x4050 - #define CL_DEVICE_PARTITION_BY_COUNTS_EXT 0x4051 - #define CL_DEVICE_PARTITION_BY_NAMES_EXT 0x4052 - #define CL_DEVICE_PARTITION_BY_AFFINITY_DOMAIN_EXT 0x4053 - - /* clDeviceGetInfo selectors */ - #define CL_DEVICE_PARENT_DEVICE_EXT 0x4054 - #define CL_DEVICE_PARTITION_TYPES_EXT 0x4055 - #define CL_DEVICE_AFFINITY_DOMAINS_EXT 0x4056 - #define CL_DEVICE_REFERENCE_COUNT_EXT 0x4057 - #define CL_DEVICE_PARTITION_STYLE_EXT 0x4058 - - /* error codes */ - #define CL_DEVICE_PARTITION_FAILED_EXT -1057 - #define CL_INVALID_PARTITION_COUNT_EXT -1058 - #define CL_INVALID_PARTITION_NAME_EXT -1059 - - /* CL_AFFINITY_DOMAINs */ - #define CL_AFFINITY_DOMAIN_L1_CACHE_EXT 0x1 - #define CL_AFFINITY_DOMAIN_L2_CACHE_EXT 0x2 - #define CL_AFFINITY_DOMAIN_L3_CACHE_EXT 0x3 - #define CL_AFFINITY_DOMAIN_L4_CACHE_EXT 0x4 - #define CL_AFFINITY_DOMAIN_NUMA_EXT 0x10 - #define CL_AFFINITY_DOMAIN_NEXT_FISSIONABLE_EXT 0x100 - - /* cl_device_partition_property_ext list terminators */ - #define CL_PROPERTIES_LIST_END_EXT ((cl_device_partition_property_ext) 0) - #define CL_PARTITION_BY_COUNTS_LIST_END_EXT ((cl_device_partition_property_ext) 0) - #define CL_PARTITION_BY_NAMES_LIST_END_EXT ((cl_device_partition_property_ext) 0 - 1) - -/********************************* -* cl_qcom_ext_host_ptr extension -*********************************/ - -#define CL_MEM_EXT_HOST_PTR_QCOM (1 << 29) - -#define CL_DEVICE_EXT_MEM_PADDING_IN_BYTES_QCOM 0x40A0 -#define CL_DEVICE_PAGE_SIZE_QCOM 0x40A1 -#define CL_IMAGE_ROW_ALIGNMENT_QCOM 0x40A2 -#define CL_IMAGE_SLICE_ALIGNMENT_QCOM 0x40A3 -#define CL_MEM_HOST_UNCACHED_QCOM 0x40A4 -#define CL_MEM_HOST_WRITEBACK_QCOM 0x40A5 -#define CL_MEM_HOST_WRITETHROUGH_QCOM 0x40A6 -#define CL_MEM_HOST_WRITE_COMBINING_QCOM 0x40A7 - -typedef cl_uint cl_image_pitch_info_qcom; - -extern CL_API_ENTRY cl_int CL_API_CALL -clGetDeviceImageInfoQCOM(cl_device_id device, - size_t image_width, - size_t image_height, - const cl_image_format *image_format, - cl_image_pitch_info_qcom param_name, - size_t param_value_size, - void *param_value, - size_t *param_value_size_ret); - -typedef struct _cl_mem_ext_host_ptr -{ - /* Type of external memory allocation. */ - /* Legal values will be defined in layered extensions. */ - cl_uint allocation_type; - - /* Host cache policy for this external memory allocation. */ - cl_uint host_cache_policy; - -} cl_mem_ext_host_ptr; - -/********************************* -* cl_qcom_ion_host_ptr extension -*********************************/ - -#define CL_MEM_ION_HOST_PTR_QCOM 0x40A8 - -typedef struct _cl_mem_ion_host_ptr -{ - /* Type of external memory allocation. */ - /* Must be CL_MEM_ION_HOST_PTR_QCOM for ION allocations. */ - cl_mem_ext_host_ptr ext_host_ptr; - - /* ION file descriptor */ - int ion_filedesc; - - /* Host pointer to the ION allocated memory */ - void* ion_hostptr; - -} cl_mem_ion_host_ptr; - -#endif /* CL_VERSION_1_1 */ - - -#ifdef CL_VERSION_2_0 -/********************************* -* cl_khr_sub_groups extension -*********************************/ -#define cl_khr_sub_groups 1 - -typedef cl_uint cl_kernel_sub_group_info_khr; - -/* cl_khr_sub_group_info */ -#define CL_KERNEL_MAX_SUB_GROUP_SIZE_FOR_NDRANGE_KHR 0x2033 -#define CL_KERNEL_SUB_GROUP_COUNT_FOR_NDRANGE_KHR 0x2034 - -extern CL_API_ENTRY cl_int CL_API_CALL -clGetKernelSubGroupInfoKHR(cl_kernel /* in_kernel */, - cl_device_id /*in_device*/, - cl_kernel_sub_group_info_khr /* param_name */, - size_t /*input_value_size*/, - const void * /*input_value*/, - size_t /*param_value_size*/, - void* /*param_value*/, - size_t* /*param_value_size_ret*/ ) CL_EXT_SUFFIX__VERSION_2_0_DEPRECATED; - -typedef CL_API_ENTRY cl_int - ( CL_API_CALL * clGetKernelSubGroupInfoKHR_fn)(cl_kernel /* in_kernel */, - cl_device_id /*in_device*/, - cl_kernel_sub_group_info_khr /* param_name */, - size_t /*input_value_size*/, - const void * /*input_value*/, - size_t /*param_value_size*/, - void* /*param_value*/, - size_t* /*param_value_size_ret*/ ) CL_EXT_SUFFIX__VERSION_2_0_DEPRECATED; -#endif /* CL_VERSION_2_0 */ - -#ifdef CL_VERSION_2_1 -/********************************* -* cl_khr_priority_hints extension -*********************************/ -#define cl_khr_priority_hints 1 - -typedef cl_uint cl_queue_priority_khr; - -/* cl_command_queue_properties */ -#define CL_QUEUE_PRIORITY_KHR 0x1096 - -/* cl_queue_priority_khr */ -#define CL_QUEUE_PRIORITY_HIGH_KHR (1<<0) -#define CL_QUEUE_PRIORITY_MED_KHR (1<<1) -#define CL_QUEUE_PRIORITY_LOW_KHR (1<<2) - -#endif /* CL_VERSION_2_1 */ - -#ifdef CL_VERSION_2_1 -/********************************* -* cl_khr_throttle_hints extension -*********************************/ -#define cl_khr_throttle_hints 1 - -typedef cl_uint cl_queue_throttle_khr; - -/* cl_command_queue_properties */ -#define CL_QUEUE_THROTTLE_KHR 0x1097 - -/* cl_queue_throttle_khr */ -#define CL_QUEUE_THROTTLE_HIGH_KHR (1<<0) -#define CL_QUEUE_THROTTLE_MED_KHR (1<<1) -#define CL_QUEUE_THROTTLE_LOW_KHR (1<<2) - -#endif /* CL_VERSION_2_1 */ - -#ifdef __cplusplus -} -#endif - - -#endif /* __CL_EXT_H */ diff --git a/third_party/opencl/include/CL/cl_ext_qcom.h b/third_party/opencl/include/CL/cl_ext_qcom.h deleted file mode 100644 index 6328a1c..0000000 --- a/third_party/opencl/include/CL/cl_ext_qcom.h +++ /dev/null @@ -1,255 +0,0 @@ -/* Copyright (c) 2009-2017 Qualcomm Technologies, Inc. All Rights Reserved. - * Qualcomm Technologies Proprietary and Confidential. - */ - -#ifndef __OPENCL_CL_EXT_QCOM_H -#define __OPENCL_CL_EXT_QCOM_H - -// Needed by cl_khr_egl_event extension -#include -#include -#include - -#ifdef __cplusplus -extern "C" { -#endif - - -/************************************ - * cl_qcom_create_buffer_from_image * - ************************************/ - -#define CL_BUFFER_FROM_IMAGE_ROW_PITCH_QCOM 0x40C0 -#define CL_BUFFER_FROM_IMAGE_SLICE_PITCH_QCOM 0x40C1 - -extern CL_API_ENTRY cl_mem CL_API_CALL -clCreateBufferFromImageQCOM(cl_mem image, - cl_mem_flags flags, - cl_int *errcode_ret); - - -/************************************ - * cl_qcom_limited_printf extension * - ************************************/ - -/* Builtin printf function buffer size in bytes. */ -#define CL_DEVICE_PRINTF_BUFFER_SIZE_QCOM 0x1049 - - -/************************************* - * cl_qcom_extended_images extension * - *************************************/ - -#define CL_CONTEXT_ENABLE_EXTENDED_IMAGES_QCOM 0x40AA -#define CL_DEVICE_EXTENDED_IMAGE2D_MAX_WIDTH_QCOM 0x40AB -#define CL_DEVICE_EXTENDED_IMAGE2D_MAX_HEIGHT_QCOM 0x40AC -#define CL_DEVICE_EXTENDED_IMAGE3D_MAX_WIDTH_QCOM 0x40AD -#define CL_DEVICE_EXTENDED_IMAGE3D_MAX_HEIGHT_QCOM 0x40AE -#define CL_DEVICE_EXTENDED_IMAGE3D_MAX_DEPTH_QCOM 0x40AF - -/************************************* - * cl_qcom_perf_hint extension * - *************************************/ - -typedef cl_uint cl_perf_hint; - -#define CL_CONTEXT_PERF_HINT_QCOM 0x40C2 - -/*cl_perf_hint*/ -#define CL_PERF_HINT_HIGH_QCOM 0x40C3 -#define CL_PERF_HINT_NORMAL_QCOM 0x40C4 -#define CL_PERF_HINT_LOW_QCOM 0x40C5 - -extern CL_API_ENTRY cl_int CL_API_CALL -clSetPerfHintQCOM(cl_context context, - cl_perf_hint perf_hint); - -// This extension is published at Khronos, so its definitions are made in cl_ext.h. -// This duplication is for backward compatibility. - -#ifndef CL_MEM_ANDROID_NATIVE_BUFFER_HOST_PTR_QCOM - -/********************************* -* cl_qcom_android_native_buffer_host_ptr extension -*********************************/ - -#define CL_MEM_ANDROID_NATIVE_BUFFER_HOST_PTR_QCOM 0x40C6 - - -typedef struct _cl_mem_android_native_buffer_host_ptr -{ - // Type of external memory allocation. - // Must be CL_MEM_ANDROID_NATIVE_BUFFER_HOST_PTR_QCOM for Android native buffers. - cl_mem_ext_host_ptr ext_host_ptr; - - // Virtual pointer to the android native buffer - void* anb_ptr; - -} cl_mem_android_native_buffer_host_ptr; - -#endif //#ifndef CL_MEM_ANDROID_NATIVE_BUFFER_HOST_PTR_QCOM - -/*********************************** -* cl_img_egl_image extension * -************************************/ -typedef void* CLeglImageIMG; -typedef void* CLeglDisplayIMG; - -extern CL_API_ENTRY cl_mem CL_API_CALL -clCreateFromEGLImageIMG(cl_context context, - cl_mem_flags flags, - CLeglImageIMG image, - CLeglDisplayIMG display, - cl_int *errcode_ret); - - -/********************************* -* cl_qcom_other_image extension -*********************************/ - -// Extended flag for creating/querying QCOM non-standard images -#define CL_MEM_OTHER_IMAGE_QCOM (1<<25) - -// cl_channel_type -#define CL_QCOM_UNORM_MIPI10 0x4159 -#define CL_QCOM_UNORM_MIPI12 0x415A -#define CL_QCOM_UNSIGNED_MIPI10 0x415B -#define CL_QCOM_UNSIGNED_MIPI12 0x415C -#define CL_QCOM_UNORM_INT10 0x415D -#define CL_QCOM_UNORM_INT12 0x415E -#define CL_QCOM_UNSIGNED_INT16 0x415F - -// cl_channel_order -// Dedicate 0x4130-0x415F range for QCOM extended image formats -// 0x4130 - 0x4132 range is assigned to pixel-oriented compressed format -#define CL_QCOM_BAYER 0x414E - -#define CL_QCOM_NV12 0x4133 -#define CL_QCOM_NV12_Y 0x4134 -#define CL_QCOM_NV12_UV 0x4135 - -#define CL_QCOM_TILED_NV12 0x4136 -#define CL_QCOM_TILED_NV12_Y 0x4137 -#define CL_QCOM_TILED_NV12_UV 0x4138 - -#define CL_QCOM_P010 0x413C -#define CL_QCOM_P010_Y 0x413D -#define CL_QCOM_P010_UV 0x413E - -#define CL_QCOM_TILED_P010 0x413F -#define CL_QCOM_TILED_P010_Y 0x4140 -#define CL_QCOM_TILED_P010_UV 0x4141 - - -#define CL_QCOM_TP10 0x4145 -#define CL_QCOM_TP10_Y 0x4146 -#define CL_QCOM_TP10_UV 0x4147 - -#define CL_QCOM_TILED_TP10 0x4148 -#define CL_QCOM_TILED_TP10_Y 0x4149 -#define CL_QCOM_TILED_TP10_UV 0x414A - -/********************************* -* cl_qcom_compressed_image extension -*********************************/ - -// Extended flag for creating/querying QCOM non-planar compressed images -#define CL_MEM_COMPRESSED_IMAGE_QCOM (1<<27) - -// Extended image format -// cl_channel_order -#define CL_QCOM_COMPRESSED_RGBA 0x4130 -#define CL_QCOM_COMPRESSED_RGBx 0x4131 - -#define CL_QCOM_COMPRESSED_NV12_Y 0x413A -#define CL_QCOM_COMPRESSED_NV12_UV 0x413B - -#define CL_QCOM_COMPRESSED_P010 0x4142 -#define CL_QCOM_COMPRESSED_P010_Y 0x4143 -#define CL_QCOM_COMPRESSED_P010_UV 0x4144 - -#define CL_QCOM_COMPRESSED_TP10 0x414B -#define CL_QCOM_COMPRESSED_TP10_Y 0x414C -#define CL_QCOM_COMPRESSED_TP10_UV 0x414D - -#define CL_QCOM_COMPRESSED_NV12_4R 0x414F -#define CL_QCOM_COMPRESSED_NV12_4R_Y 0x4150 -#define CL_QCOM_COMPRESSED_NV12_4R_UV 0x4151 -/********************************* -* cl_qcom_compressed_yuv_image_read extension -*********************************/ - -// Extended flag for creating/querying QCOM compressed images -#define CL_MEM_COMPRESSED_YUV_IMAGE_QCOM (1<<28) - -// Extended image format -#define CL_QCOM_COMPRESSED_NV12 0x10C4 - -// Extended flag for setting ION buffer allocation type -#define CL_MEM_ION_HOST_PTR_COMPRESSED_YUV_QCOM 0x40CD -#define CL_MEM_ION_HOST_PTR_PROTECTED_COMPRESSED_YUV_QCOM 0x40CE - -/********************************* -* cl_qcom_accelerated_image_ops -*********************************/ -#define CL_MEM_OBJECT_WEIGHT_IMAGE_QCOM 0x4110 -#define CL_DEVICE_HOF_MAX_NUM_PHASES_QCOM 0x4111 -#define CL_DEVICE_HOF_MAX_FILTER_SIZE_X_QCOM 0x4112 -#define CL_DEVICE_HOF_MAX_FILTER_SIZE_Y_QCOM 0x4113 -#define CL_DEVICE_BLOCK_MATCHING_MAX_REGION_SIZE_X_QCOM 0x4114 -#define CL_DEVICE_BLOCK_MATCHING_MAX_REGION_SIZE_Y_QCOM 0x4115 - -//Extended flag for specifying weight image type -#define CL_WEIGHT_IMAGE_SEPARABLE_QCOM (1<<0) - -// Box Filter -typedef struct _cl_box_filter_size_qcom -{ - // Width of box filter on X direction. - float box_filter_width; - - // Height of box filter on Y direction. - float box_filter_height; -} cl_box_filter_size_qcom; - -// HOF Weight Image Desc -typedef struct _cl_weight_desc_qcom -{ - /** Coordinate of the "center" point of the weight image, - based on the weight image's top-left corner as the origin. */ - size_t center_coord_x; - size_t center_coord_y; - cl_bitfield flags; -} cl_weight_desc_qcom; - -typedef struct _cl_weight_image_desc_qcom -{ - cl_image_desc image_desc; - cl_weight_desc_qcom weight_desc; -} cl_weight_image_desc_qcom; - -/************************************* - * cl_qcom_protected_context extension * - *************************************/ - -#define CL_CONTEXT_PROTECTED_QCOM 0x40C7 -#define CL_MEM_ION_HOST_PTR_PROTECTED_QCOM 0x40C8 - -/************************************* - * cl_qcom_priority_hint extension * - *************************************/ -#define CL_PRIORITY_HINT_NONE_QCOM 0 -typedef cl_uint cl_priority_hint; - -#define CL_CONTEXT_PRIORITY_HINT_QCOM 0x40C9 - -/*cl_priority_hint*/ -#define CL_PRIORITY_HINT_HIGH_QCOM 0x40CA -#define CL_PRIORITY_HINT_NORMAL_QCOM 0x40CB -#define CL_PRIORITY_HINT_LOW_QCOM 0x40CC - -#ifdef __cplusplus -} -#endif - -#endif /* __OPENCL_CL_EXT_QCOM_H */ diff --git a/third_party/opencl/include/CL/cl_gl.h b/third_party/opencl/include/CL/cl_gl.h deleted file mode 100644 index 945daa8..0000000 --- a/third_party/opencl/include/CL/cl_gl.h +++ /dev/null @@ -1,167 +0,0 @@ -/********************************************************************************** - * Copyright (c) 2008-2015 The Khronos Group Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining a - * copy of this software and/or associated documentation files (the - * "Materials"), to deal in the Materials without restriction, including - * without limitation the rights to use, copy, modify, merge, publish, - * distribute, sublicense, and/or sell copies of the Materials, and to - * permit persons to whom the Materials are furnished to do so, subject to - * the following conditions: - * - * The above copyright notice and this permission notice shall be included - * in all copies or substantial portions of the Materials. - * - * MODIFICATIONS TO THIS FILE MAY MEAN IT NO LONGER ACCURATELY REFLECTS - * KHRONOS STANDARDS. THE UNMODIFIED, NORMATIVE VERSIONS OF KHRONOS - * SPECIFICATIONS AND HEADER INFORMATION ARE LOCATED AT - * https://www.khronos.org/registry/ - * - * THE MATERIALS ARE PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, - * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. - * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY - * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, - * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE - * MATERIALS OR THE USE OR OTHER DEALINGS IN THE MATERIALS. - **********************************************************************************/ - -#ifndef __OPENCL_CL_GL_H -#define __OPENCL_CL_GL_H - -#ifdef __APPLE__ -#include -#else -#include -#endif - -#ifdef __cplusplus -extern "C" { -#endif - -typedef cl_uint cl_gl_object_type; -typedef cl_uint cl_gl_texture_info; -typedef cl_uint cl_gl_platform_info; -typedef struct __GLsync *cl_GLsync; - -/* cl_gl_object_type = 0x2000 - 0x200F enum values are currently taken */ -#define CL_GL_OBJECT_BUFFER 0x2000 -#define CL_GL_OBJECT_TEXTURE2D 0x2001 -#define CL_GL_OBJECT_TEXTURE3D 0x2002 -#define CL_GL_OBJECT_RENDERBUFFER 0x2003 -#define CL_GL_OBJECT_TEXTURE2D_ARRAY 0x200E -#define CL_GL_OBJECT_TEXTURE1D 0x200F -#define CL_GL_OBJECT_TEXTURE1D_ARRAY 0x2010 -#define CL_GL_OBJECT_TEXTURE_BUFFER 0x2011 - -/* cl_gl_texture_info */ -#define CL_GL_TEXTURE_TARGET 0x2004 -#define CL_GL_MIPMAP_LEVEL 0x2005 -#define CL_GL_NUM_SAMPLES 0x2012 - - -extern CL_API_ENTRY cl_mem CL_API_CALL -clCreateFromGLBuffer(cl_context /* context */, - cl_mem_flags /* flags */, - cl_GLuint /* bufobj */, - int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_mem CL_API_CALL -clCreateFromGLTexture(cl_context /* context */, - cl_mem_flags /* flags */, - cl_GLenum /* target */, - cl_GLint /* miplevel */, - cl_GLuint /* texture */, - cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_2; - -extern CL_API_ENTRY cl_mem CL_API_CALL -clCreateFromGLRenderbuffer(cl_context /* context */, - cl_mem_flags /* flags */, - cl_GLuint /* renderbuffer */, - cl_int * /* errcode_ret */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clGetGLObjectInfo(cl_mem /* memobj */, - cl_gl_object_type * /* gl_object_type */, - cl_GLuint * /* gl_object_name */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clGetGLTextureInfo(cl_mem /* memobj */, - cl_gl_texture_info /* param_name */, - size_t /* param_value_size */, - void * /* param_value */, - size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clEnqueueAcquireGLObjects(cl_command_queue /* command_queue */, - cl_uint /* num_objects */, - const cl_mem * /* mem_objects */, - cl_uint /* num_events_in_wait_list */, - const cl_event * /* event_wait_list */, - cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; - -extern CL_API_ENTRY cl_int CL_API_CALL -clEnqueueReleaseGLObjects(cl_command_queue /* command_queue */, - cl_uint /* num_objects */, - const cl_mem * /* mem_objects */, - cl_uint /* num_events_in_wait_list */, - const cl_event * /* event_wait_list */, - cl_event * /* event */) CL_API_SUFFIX__VERSION_1_0; - - -/* Deprecated OpenCL 1.1 APIs */ -extern CL_API_ENTRY CL_EXT_PREFIX__VERSION_1_1_DEPRECATED cl_mem CL_API_CALL -clCreateFromGLTexture2D(cl_context /* context */, - cl_mem_flags /* flags */, - cl_GLenum /* target */, - cl_GLint /* miplevel */, - cl_GLuint /* texture */, - cl_int * /* errcode_ret */) CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED; - -extern CL_API_ENTRY CL_EXT_PREFIX__VERSION_1_1_DEPRECATED cl_mem CL_API_CALL -clCreateFromGLTexture3D(cl_context /* context */, - cl_mem_flags /* flags */, - cl_GLenum /* target */, - cl_GLint /* miplevel */, - cl_GLuint /* texture */, - cl_int * /* errcode_ret */) CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED; - -/* cl_khr_gl_sharing extension */ - -#define cl_khr_gl_sharing 1 - -typedef cl_uint cl_gl_context_info; - -/* Additional Error Codes */ -#define CL_INVALID_GL_SHAREGROUP_REFERENCE_KHR -1000 - -/* cl_gl_context_info */ -#define CL_CURRENT_DEVICE_FOR_GL_CONTEXT_KHR 0x2006 -#define CL_DEVICES_FOR_GL_CONTEXT_KHR 0x2007 - -/* Additional cl_context_properties */ -#define CL_GL_CONTEXT_KHR 0x2008 -#define CL_EGL_DISPLAY_KHR 0x2009 -#define CL_GLX_DISPLAY_KHR 0x200A -#define CL_WGL_HDC_KHR 0x200B -#define CL_CGL_SHAREGROUP_KHR 0x200C - -extern CL_API_ENTRY cl_int CL_API_CALL -clGetGLContextInfoKHR(const cl_context_properties * /* properties */, - cl_gl_context_info /* param_name */, - size_t /* param_value_size */, - void * /* param_value */, - size_t * /* param_value_size_ret */) CL_API_SUFFIX__VERSION_1_0; - -typedef CL_API_ENTRY cl_int (CL_API_CALL *clGetGLContextInfoKHR_fn)( - const cl_context_properties * properties, - cl_gl_context_info param_name, - size_t param_value_size, - void * param_value, - size_t * param_value_size_ret); - -#ifdef __cplusplus -} -#endif - -#endif /* __OPENCL_CL_GL_H */ diff --git a/third_party/opencl/include/CL/cl_gl_ext.h b/third_party/opencl/include/CL/cl_gl_ext.h deleted file mode 100644 index e3c14c6..0000000 --- a/third_party/opencl/include/CL/cl_gl_ext.h +++ /dev/null @@ -1,74 +0,0 @@ -/********************************************************************************** - * Copyright (c) 2008-2015 The Khronos Group Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining a - * copy of this software and/or associated documentation files (the - * "Materials"), to deal in the Materials without restriction, including - * without limitation the rights to use, copy, modify, merge, publish, - * distribute, sublicense, and/or sell copies of the Materials, and to - * permit persons to whom the Materials are furnished to do so, subject to - * the following conditions: - * - * The above copyright notice and this permission notice shall be included - * in all copies or substantial portions of the Materials. - * - * MODIFICATIONS TO THIS FILE MAY MEAN IT NO LONGER ACCURATELY REFLECTS - * KHRONOS STANDARDS. THE UNMODIFIED, NORMATIVE VERSIONS OF KHRONOS - * SPECIFICATIONS AND HEADER INFORMATION ARE LOCATED AT - * https://www.khronos.org/registry/ - * - * THE MATERIALS ARE PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, - * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. - * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY - * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, - * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE - * MATERIALS OR THE USE OR OTHER DEALINGS IN THE MATERIALS. - **********************************************************************************/ - -/* $Revision: 11708 $ on $Date: 2010-06-13 23:36:24 -0700 (Sun, 13 Jun 2010) $ */ - -/* cl_gl_ext.h contains vendor (non-KHR) OpenCL extensions which have */ -/* OpenGL dependencies. */ - -#ifndef __OPENCL_CL_GL_EXT_H -#define __OPENCL_CL_GL_EXT_H - -#ifdef __cplusplus -extern "C" { -#endif - -#ifdef __APPLE__ - #include -#else - #include -#endif - -/* - * For each extension, follow this template - * cl_VEN_extname extension */ -/* #define cl_VEN_extname 1 - * ... define new types, if any - * ... define new tokens, if any - * ... define new APIs, if any - * - * If you need GLtypes here, mirror them with a cl_GLtype, rather than including a GL header - * This allows us to avoid having to decide whether to include GL headers or GLES here. - */ - -/* - * cl_khr_gl_event extension - * See section 9.9 in the OpenCL 1.1 spec for more information - */ -#define CL_COMMAND_GL_FENCE_SYNC_OBJECT_KHR 0x200D - -extern CL_API_ENTRY cl_event CL_API_CALL -clCreateEventFromGLsyncKHR(cl_context /* context */, - cl_GLsync /* cl_GLsync */, - cl_int * /* errcode_ret */) CL_EXT_SUFFIX__VERSION_1_1; - -#ifdef __cplusplus -} -#endif - -#endif /* __OPENCL_CL_GL_EXT_H */ diff --git a/third_party/opencl/include/CL/cl_platform.h b/third_party/opencl/include/CL/cl_platform.h deleted file mode 100644 index 4e334a2..0000000 --- a/third_party/opencl/include/CL/cl_platform.h +++ /dev/null @@ -1,1333 +0,0 @@ -/********************************************************************************** - * Copyright (c) 2008-2015 The Khronos Group Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining a - * copy of this software and/or associated documentation files (the - * "Materials"), to deal in the Materials without restriction, including - * without limitation the rights to use, copy, modify, merge, publish, - * distribute, sublicense, and/or sell copies of the Materials, and to - * permit persons to whom the Materials are furnished to do so, subject to - * the following conditions: - * - * The above copyright notice and this permission notice shall be included - * in all copies or substantial portions of the Materials. - * - * MODIFICATIONS TO THIS FILE MAY MEAN IT NO LONGER ACCURATELY REFLECTS - * KHRONOS STANDARDS. THE UNMODIFIED, NORMATIVE VERSIONS OF KHRONOS - * SPECIFICATIONS AND HEADER INFORMATION ARE LOCATED AT - * https://www.khronos.org/registry/ - * - * THE MATERIALS ARE PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, - * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. - * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY - * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, - * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE - * MATERIALS OR THE USE OR OTHER DEALINGS IN THE MATERIALS. - **********************************************************************************/ - -/* $Revision: 11803 $ on $Date: 2010-06-25 10:02:12 -0700 (Fri, 25 Jun 2010) $ */ - -#ifndef __CL_PLATFORM_H -#define __CL_PLATFORM_H - -#ifdef __APPLE__ - /* Contains #defines for AVAILABLE_MAC_OS_X_VERSION_10_6_AND_LATER below */ - #include -#endif - -#ifdef __cplusplus -extern "C" { -#endif - -#if defined(_WIN32) - #define CL_API_ENTRY - #define CL_API_CALL __stdcall - #define CL_CALLBACK __stdcall -#else - #define CL_API_ENTRY - #define CL_API_CALL - #define CL_CALLBACK -#endif - -/* - * Deprecation flags refer to the last version of the header in which the - * feature was not deprecated. - * - * E.g. VERSION_1_1_DEPRECATED means the feature is present in 1.1 without - * deprecation but is deprecated in versions later than 1.1. - */ - -#ifdef __APPLE__ - #define CL_EXTENSION_WEAK_LINK __attribute__((weak_import)) - #define CL_API_SUFFIX__VERSION_1_0 AVAILABLE_MAC_OS_X_VERSION_10_6_AND_LATER - #define CL_EXT_SUFFIX__VERSION_1_0 CL_EXTENSION_WEAK_LINK AVAILABLE_MAC_OS_X_VERSION_10_6_AND_LATER - #define CL_API_SUFFIX__VERSION_1_1 AVAILABLE_MAC_OS_X_VERSION_10_7_AND_LATER - #define GCL_API_SUFFIX__VERSION_1_1 AVAILABLE_MAC_OS_X_VERSION_10_7_AND_LATER - #define CL_EXT_SUFFIX__VERSION_1_1 CL_EXTENSION_WEAK_LINK AVAILABLE_MAC_OS_X_VERSION_10_7_AND_LATER - #define CL_EXT_SUFFIX__VERSION_1_0_DEPRECATED CL_EXTENSION_WEAK_LINK AVAILABLE_MAC_OS_X_VERSION_10_6_AND_LATER_BUT_DEPRECATED_IN_MAC_OS_X_VERSION_10_7 - - #ifdef AVAILABLE_MAC_OS_X_VERSION_10_8_AND_LATER - #define CL_API_SUFFIX__VERSION_1_2 AVAILABLE_MAC_OS_X_VERSION_10_8_AND_LATER - #define GCL_API_SUFFIX__VERSION_1_2 AVAILABLE_MAC_OS_X_VERSION_10_8_AND_LATER - #define CL_EXT_SUFFIX__VERSION_1_2 CL_EXTENSION_WEAK_LINK AVAILABLE_MAC_OS_X_VERSION_10_8_AND_LATER - #define CL_EXT_PREFIX__VERSION_1_1_DEPRECATED - #define CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED CL_EXTENSION_WEAK_LINK AVAILABLE_MAC_OS_X_VERSION_10_7_AND_LATER_BUT_DEPRECATED_IN_MAC_OS_X_VERSION_10_8 - #else - #warning This path should never happen outside of internal operating system development. AvailabilityMacros do not function correctly here! - #define CL_API_SUFFIX__VERSION_1_2 AVAILABLE_MAC_OS_X_VERSION_10_7_AND_LATER - #define GCL_API_SUFFIX__VERSION_1_2 AVAILABLE_MAC_OS_X_VERSION_10_7_AND_LATER - #define CL_EXT_SUFFIX__VERSION_1_2 CL_EXTENSION_WEAK_LINK AVAILABLE_MAC_OS_X_VERSION_10_7_AND_LATER - #define CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED CL_EXTENSION_WEAK_LINK AVAILABLE_MAC_OS_X_VERSION_10_7_AND_LATER - #endif -#else - #define CL_EXTENSION_WEAK_LINK - #define CL_API_SUFFIX__VERSION_1_0 - #define CL_EXT_SUFFIX__VERSION_1_0 - #define CL_API_SUFFIX__VERSION_1_1 - #define CL_EXT_SUFFIX__VERSION_1_1 - #define CL_API_SUFFIX__VERSION_1_2 - #define CL_EXT_SUFFIX__VERSION_1_2 - #define CL_API_SUFFIX__VERSION_2_0 - #define CL_EXT_SUFFIX__VERSION_2_0 - #define CL_API_SUFFIX__VERSION_2_1 - #define CL_EXT_SUFFIX__VERSION_2_1 - - #ifdef __GNUC__ - #ifdef CL_USE_DEPRECATED_OPENCL_1_0_APIS - #define CL_EXT_SUFFIX__VERSION_1_0_DEPRECATED - #define CL_EXT_PREFIX__VERSION_1_0_DEPRECATED - #else - #define CL_EXT_SUFFIX__VERSION_1_0_DEPRECATED __attribute__((deprecated)) - #define CL_EXT_PREFIX__VERSION_1_0_DEPRECATED - #endif - - #ifdef CL_USE_DEPRECATED_OPENCL_1_1_APIS - #define CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED - #define CL_EXT_PREFIX__VERSION_1_1_DEPRECATED - #else - #define CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED __attribute__((deprecated)) - #define CL_EXT_PREFIX__VERSION_1_1_DEPRECATED - #endif - - #ifdef CL_USE_DEPRECATED_OPENCL_1_2_APIS - #define CL_EXT_SUFFIX__VERSION_1_2_DEPRECATED - #define CL_EXT_PREFIX__VERSION_1_2_DEPRECATED - #else - #define CL_EXT_SUFFIX__VERSION_1_2_DEPRECATED __attribute__((deprecated)) - #define CL_EXT_PREFIX__VERSION_1_2_DEPRECATED - #endif - - #ifdef CL_USE_DEPRECATED_OPENCL_2_0_APIS - #define CL_EXT_SUFFIX__VERSION_2_0_DEPRECATED - #define CL_EXT_PREFIX__VERSION_2_0_DEPRECATED - #else - #define CL_EXT_SUFFIX__VERSION_2_0_DEPRECATED __attribute__((deprecated)) - #define CL_EXT_PREFIX__VERSION_2_0_DEPRECATED - #endif - #elif _WIN32 - #ifdef CL_USE_DEPRECATED_OPENCL_1_0_APIS - #define CL_EXT_SUFFIX__VERSION_1_0_DEPRECATED - #define CL_EXT_PREFIX__VERSION_1_0_DEPRECATED - #else - #define CL_EXT_SUFFIX__VERSION_1_0_DEPRECATED - #define CL_EXT_PREFIX__VERSION_1_0_DEPRECATED __declspec(deprecated) - #endif - - #ifdef CL_USE_DEPRECATED_OPENCL_1_1_APIS - #define CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED - #define CL_EXT_PREFIX__VERSION_1_1_DEPRECATED - #else - #define CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED - #define CL_EXT_PREFIX__VERSION_1_1_DEPRECATED __declspec(deprecated) - #endif - - #ifdef CL_USE_DEPRECATED_OPENCL_1_2_APIS - #define CL_EXT_SUFFIX__VERSION_1_2_DEPRECATED - #define CL_EXT_PREFIX__VERSION_1_2_DEPRECATED - #else - #define CL_EXT_SUFFIX__VERSION_1_2_DEPRECATED - #define CL_EXT_PREFIX__VERSION_1_2_DEPRECATED __declspec(deprecated) - #endif - - #ifdef CL_USE_DEPRECATED_OPENCL_2_0_APIS - #define CL_EXT_SUFFIX__VERSION_2_0_DEPRECATED - #define CL_EXT_PREFIX__VERSION_2_0_DEPRECATED - #else - #define CL_EXT_SUFFIX__VERSION_2_0_DEPRECATED - #define CL_EXT_PREFIX__VERSION_2_0_DEPRECATED __declspec(deprecated) - #endif - #else - #define CL_EXT_SUFFIX__VERSION_1_0_DEPRECATED - #define CL_EXT_PREFIX__VERSION_1_0_DEPRECATED - - #define CL_EXT_SUFFIX__VERSION_1_1_DEPRECATED - #define CL_EXT_PREFIX__VERSION_1_1_DEPRECATED - - #define CL_EXT_SUFFIX__VERSION_1_2_DEPRECATED - #define CL_EXT_PREFIX__VERSION_1_2_DEPRECATED - - #define CL_EXT_SUFFIX__VERSION_2_0_DEPRECATED - #define CL_EXT_PREFIX__VERSION_2_0_DEPRECATED - #endif -#endif - -#if (defined (_WIN32) && defined(_MSC_VER)) - -/* scalar types */ -typedef signed __int8 cl_char; -typedef unsigned __int8 cl_uchar; -typedef signed __int16 cl_short; -typedef unsigned __int16 cl_ushort; -typedef signed __int32 cl_int; -typedef unsigned __int32 cl_uint; -typedef signed __int64 cl_long; -typedef unsigned __int64 cl_ulong; - -typedef unsigned __int16 cl_half; -typedef float cl_float; -typedef double cl_double; - -/* Macro names and corresponding values defined by OpenCL */ -#define CL_CHAR_BIT 8 -#define CL_SCHAR_MAX 127 -#define CL_SCHAR_MIN (-127-1) -#define CL_CHAR_MAX CL_SCHAR_MAX -#define CL_CHAR_MIN CL_SCHAR_MIN -#define CL_UCHAR_MAX 255 -#define CL_SHRT_MAX 32767 -#define CL_SHRT_MIN (-32767-1) -#define CL_USHRT_MAX 65535 -#define CL_INT_MAX 2147483647 -#define CL_INT_MIN (-2147483647-1) -#define CL_UINT_MAX 0xffffffffU -#define CL_LONG_MAX ((cl_long) 0x7FFFFFFFFFFFFFFFLL) -#define CL_LONG_MIN ((cl_long) -0x7FFFFFFFFFFFFFFFLL - 1LL) -#define CL_ULONG_MAX ((cl_ulong) 0xFFFFFFFFFFFFFFFFULL) - -#define CL_FLT_DIG 6 -#define CL_FLT_MANT_DIG 24 -#define CL_FLT_MAX_10_EXP +38 -#define CL_FLT_MAX_EXP +128 -#define CL_FLT_MIN_10_EXP -37 -#define CL_FLT_MIN_EXP -125 -#define CL_FLT_RADIX 2 -#define CL_FLT_MAX 340282346638528859811704183484516925440.0f -#define CL_FLT_MIN 1.175494350822287507969e-38f -#define CL_FLT_EPSILON 0x1.0p-23f - -#define CL_DBL_DIG 15 -#define CL_DBL_MANT_DIG 53 -#define CL_DBL_MAX_10_EXP +308 -#define CL_DBL_MAX_EXP +1024 -#define CL_DBL_MIN_10_EXP -307 -#define CL_DBL_MIN_EXP -1021 -#define CL_DBL_RADIX 2 -#define CL_DBL_MAX 179769313486231570814527423731704356798070567525844996598917476803157260780028538760589558632766878171540458953514382464234321326889464182768467546703537516986049910576551282076245490090389328944075868508455133942304583236903222948165808559332123348274797826204144723168738177180919299881250404026184124858368.0 -#define CL_DBL_MIN 2.225073858507201383090e-308 -#define CL_DBL_EPSILON 2.220446049250313080847e-16 - -#define CL_M_E 2.718281828459045090796 -#define CL_M_LOG2E 1.442695040888963387005 -#define CL_M_LOG10E 0.434294481903251816668 -#define CL_M_LN2 0.693147180559945286227 -#define CL_M_LN10 2.302585092994045901094 -#define CL_M_PI 3.141592653589793115998 -#define CL_M_PI_2 1.570796326794896557999 -#define CL_M_PI_4 0.785398163397448278999 -#define CL_M_1_PI 0.318309886183790691216 -#define CL_M_2_PI 0.636619772367581382433 -#define CL_M_2_SQRTPI 1.128379167095512558561 -#define CL_M_SQRT2 1.414213562373095145475 -#define CL_M_SQRT1_2 0.707106781186547572737 - -#define CL_M_E_F 2.71828174591064f -#define CL_M_LOG2E_F 1.44269502162933f -#define CL_M_LOG10E_F 0.43429449200630f -#define CL_M_LN2_F 0.69314718246460f -#define CL_M_LN10_F 2.30258512496948f -#define CL_M_PI_F 3.14159274101257f -#define CL_M_PI_2_F 1.57079637050629f -#define CL_M_PI_4_F 0.78539818525314f -#define CL_M_1_PI_F 0.31830987334251f -#define CL_M_2_PI_F 0.63661974668503f -#define CL_M_2_SQRTPI_F 1.12837922573090f -#define CL_M_SQRT2_F 1.41421353816986f -#define CL_M_SQRT1_2_F 0.70710676908493f - -#define CL_NAN (CL_INFINITY - CL_INFINITY) -#define CL_HUGE_VALF ((cl_float) 1e50) -#define CL_HUGE_VAL ((cl_double) 1e500) -#define CL_MAXFLOAT CL_FLT_MAX -#define CL_INFINITY CL_HUGE_VALF - -#else - -#include - -/* scalar types */ -typedef int8_t cl_char; -typedef uint8_t cl_uchar; -typedef int16_t cl_short __attribute__((aligned(2))); -typedef uint16_t cl_ushort __attribute__((aligned(2))); -typedef int32_t cl_int __attribute__((aligned(4))); -typedef uint32_t cl_uint __attribute__((aligned(4))); -typedef int64_t cl_long __attribute__((aligned(8))); -typedef uint64_t cl_ulong __attribute__((aligned(8))); - -typedef uint16_t cl_half __attribute__((aligned(2))); -typedef float cl_float __attribute__((aligned(4))); -typedef double cl_double __attribute__((aligned(8))); - -/* Macro names and corresponding values defined by OpenCL */ -#define CL_CHAR_BIT 8 -#define CL_SCHAR_MAX 127 -#define CL_SCHAR_MIN (-127-1) -#define CL_CHAR_MAX CL_SCHAR_MAX -#define CL_CHAR_MIN CL_SCHAR_MIN -#define CL_UCHAR_MAX 255 -#define CL_SHRT_MAX 32767 -#define CL_SHRT_MIN (-32767-1) -#define CL_USHRT_MAX 65535 -#define CL_INT_MAX 2147483647 -#define CL_INT_MIN (-2147483647-1) -#define CL_UINT_MAX 0xffffffffU -#define CL_LONG_MAX ((cl_long) 0x7FFFFFFFFFFFFFFFLL) -#define CL_LONG_MIN ((cl_long) -0x7FFFFFFFFFFFFFFFLL - 1LL) -#define CL_ULONG_MAX ((cl_ulong) 0xFFFFFFFFFFFFFFFFULL) - -#define CL_FLT_DIG 6 -#define CL_FLT_MANT_DIG 24 -#define CL_FLT_MAX_10_EXP +38 -#define CL_FLT_MAX_EXP +128 -#define CL_FLT_MIN_10_EXP -37 -#define CL_FLT_MIN_EXP -125 -#define CL_FLT_RADIX 2 -#define CL_FLT_MAX 0x1.fffffep127f -#define CL_FLT_MIN 0x1.0p-126f -#define CL_FLT_EPSILON 0x1.0p-23f - -#define CL_DBL_DIG 15 -#define CL_DBL_MANT_DIG 53 -#define CL_DBL_MAX_10_EXP +308 -#define CL_DBL_MAX_EXP +1024 -#define CL_DBL_MIN_10_EXP -307 -#define CL_DBL_MIN_EXP -1021 -#define CL_DBL_RADIX 2 -#define CL_DBL_MAX 0x1.fffffffffffffp1023 -#define CL_DBL_MIN 0x1.0p-1022 -#define CL_DBL_EPSILON 0x1.0p-52 - -#define CL_M_E 2.718281828459045090796 -#define CL_M_LOG2E 1.442695040888963387005 -#define CL_M_LOG10E 0.434294481903251816668 -#define CL_M_LN2 0.693147180559945286227 -#define CL_M_LN10 2.302585092994045901094 -#define CL_M_PI 3.141592653589793115998 -#define CL_M_PI_2 1.570796326794896557999 -#define CL_M_PI_4 0.785398163397448278999 -#define CL_M_1_PI 0.318309886183790691216 -#define CL_M_2_PI 0.636619772367581382433 -#define CL_M_2_SQRTPI 1.128379167095512558561 -#define CL_M_SQRT2 1.414213562373095145475 -#define CL_M_SQRT1_2 0.707106781186547572737 - -#define CL_M_E_F 2.71828174591064f -#define CL_M_LOG2E_F 1.44269502162933f -#define CL_M_LOG10E_F 0.43429449200630f -#define CL_M_LN2_F 0.69314718246460f -#define CL_M_LN10_F 2.30258512496948f -#define CL_M_PI_F 3.14159274101257f -#define CL_M_PI_2_F 1.57079637050629f -#define CL_M_PI_4_F 0.78539818525314f -#define CL_M_1_PI_F 0.31830987334251f -#define CL_M_2_PI_F 0.63661974668503f -#define CL_M_2_SQRTPI_F 1.12837922573090f -#define CL_M_SQRT2_F 1.41421353816986f -#define CL_M_SQRT1_2_F 0.70710676908493f - -#if defined( __GNUC__ ) - #define CL_HUGE_VALF __builtin_huge_valf() - #define CL_HUGE_VAL __builtin_huge_val() - #define CL_NAN __builtin_nanf( "" ) -#else - #define CL_HUGE_VALF ((cl_float) 1e50) - #define CL_HUGE_VAL ((cl_double) 1e500) - float nanf( const char * ); - #define CL_NAN nanf( "" ) -#endif -#define CL_MAXFLOAT CL_FLT_MAX -#define CL_INFINITY CL_HUGE_VALF - -#endif - -#include - -/* Mirror types to GL types. Mirror types allow us to avoid deciding which 87s to load based on whether we are using GL or GLES here. */ -typedef unsigned int cl_GLuint; -typedef int cl_GLint; -typedef unsigned int cl_GLenum; - -/* - * Vector types - * - * Note: OpenCL requires that all types be naturally aligned. - * This means that vector types must be naturally aligned. - * For example, a vector of four floats must be aligned to - * a 16 byte boundary (calculated as 4 * the natural 4-byte - * alignment of the float). The alignment qualifiers here - * will only function properly if your compiler supports them - * and if you don't actively work to defeat them. For example, - * in order for a cl_float4 to be 16 byte aligned in a struct, - * the start of the struct must itself be 16-byte aligned. - * - * Maintaining proper alignment is the user's responsibility. - */ - -/* Define basic vector types */ -#if defined( __VEC__ ) - #include /* may be omitted depending on compiler. AltiVec spec provides no way to detect whether the header is required. */ - typedef vector unsigned char __cl_uchar16; - typedef vector signed char __cl_char16; - typedef vector unsigned short __cl_ushort8; - typedef vector signed short __cl_short8; - typedef vector unsigned int __cl_uint4; - typedef vector signed int __cl_int4; - typedef vector float __cl_float4; - #define __CL_UCHAR16__ 1 - #define __CL_CHAR16__ 1 - #define __CL_USHORT8__ 1 - #define __CL_SHORT8__ 1 - #define __CL_UINT4__ 1 - #define __CL_INT4__ 1 - #define __CL_FLOAT4__ 1 -#endif - -#if defined( __SSE__ ) - #if defined( __MINGW64__ ) - #include - #else - #include - #endif - #if defined( __GNUC__ ) - typedef float __cl_float4 __attribute__((vector_size(16))); - #else - typedef __m128 __cl_float4; - #endif - #define __CL_FLOAT4__ 1 -#endif - -#if defined( __SSE2__ ) - #if defined( __MINGW64__ ) - #include - #else - #include - #endif - #if defined( __GNUC__ ) - typedef cl_uchar __cl_uchar16 __attribute__((vector_size(16))); - typedef cl_char __cl_char16 __attribute__((vector_size(16))); - typedef cl_ushort __cl_ushort8 __attribute__((vector_size(16))); - typedef cl_short __cl_short8 __attribute__((vector_size(16))); - typedef cl_uint __cl_uint4 __attribute__((vector_size(16))); - typedef cl_int __cl_int4 __attribute__((vector_size(16))); - typedef cl_ulong __cl_ulong2 __attribute__((vector_size(16))); - typedef cl_long __cl_long2 __attribute__((vector_size(16))); - typedef cl_double __cl_double2 __attribute__((vector_size(16))); - #else - typedef __m128i __cl_uchar16; - typedef __m128i __cl_char16; - typedef __m128i __cl_ushort8; - typedef __m128i __cl_short8; - typedef __m128i __cl_uint4; - typedef __m128i __cl_int4; - typedef __m128i __cl_ulong2; - typedef __m128i __cl_long2; - typedef __m128d __cl_double2; - #endif - #define __CL_UCHAR16__ 1 - #define __CL_CHAR16__ 1 - #define __CL_USHORT8__ 1 - #define __CL_SHORT8__ 1 - #define __CL_INT4__ 1 - #define __CL_UINT4__ 1 - #define __CL_ULONG2__ 1 - #define __CL_LONG2__ 1 - #define __CL_DOUBLE2__ 1 -#endif - -#if defined( __MMX__ ) - #include - #if defined( __GNUC__ ) - typedef cl_uchar __cl_uchar8 __attribute__((vector_size(8))); - typedef cl_char __cl_char8 __attribute__((vector_size(8))); - typedef cl_ushort __cl_ushort4 __attribute__((vector_size(8))); - typedef cl_short __cl_short4 __attribute__((vector_size(8))); - typedef cl_uint __cl_uint2 __attribute__((vector_size(8))); - typedef cl_int __cl_int2 __attribute__((vector_size(8))); - typedef cl_ulong __cl_ulong1 __attribute__((vector_size(8))); - typedef cl_long __cl_long1 __attribute__((vector_size(8))); - typedef cl_float __cl_float2 __attribute__((vector_size(8))); - #else - typedef __m64 __cl_uchar8; - typedef __m64 __cl_char8; - typedef __m64 __cl_ushort4; - typedef __m64 __cl_short4; - typedef __m64 __cl_uint2; - typedef __m64 __cl_int2; - typedef __m64 __cl_ulong1; - typedef __m64 __cl_long1; - typedef __m64 __cl_float2; - #endif - #define __CL_UCHAR8__ 1 - #define __CL_CHAR8__ 1 - #define __CL_USHORT4__ 1 - #define __CL_SHORT4__ 1 - #define __CL_INT2__ 1 - #define __CL_UINT2__ 1 - #define __CL_ULONG1__ 1 - #define __CL_LONG1__ 1 - #define __CL_FLOAT2__ 1 -#endif - -#if defined( __AVX__ ) - #if defined( __MINGW64__ ) - #include - #else - #include - #endif - #if defined( __GNUC__ ) - typedef cl_float __cl_float8 __attribute__((vector_size(32))); - typedef cl_double __cl_double4 __attribute__((vector_size(32))); - #else - typedef __m256 __cl_float8; - typedef __m256d __cl_double4; - #endif - #define __CL_FLOAT8__ 1 - #define __CL_DOUBLE4__ 1 -#endif - -/* Define capabilities for anonymous struct members. */ -#if defined( __GNUC__) && ! defined( __STRICT_ANSI__ ) -#define __CL_HAS_ANON_STRUCT__ 1 -#define __CL_ANON_STRUCT__ __extension__ -#elif defined( _WIN32) && (_MSC_VER >= 1500) - /* Microsoft Developer Studio 2008 supports anonymous structs, but - * complains by default. */ -#define __CL_HAS_ANON_STRUCT__ 1 -#define __CL_ANON_STRUCT__ - /* Disable warning C4201: nonstandard extension used : nameless - * struct/union */ -#pragma warning( push ) -#pragma warning( disable : 4201 ) -#else -#define __CL_HAS_ANON_STRUCT__ 0 -#define __CL_ANON_STRUCT__ -#endif - -/* Define alignment keys */ -#if defined( __GNUC__ ) - #define CL_ALIGNED(_x) __attribute__ ((aligned(_x))) -#elif defined( _WIN32) && (_MSC_VER) - /* Alignment keys neutered on windows because MSVC can't swallow function arguments with alignment requirements */ - /* http://msdn.microsoft.com/en-us/library/373ak2y1%28VS.71%29.aspx */ - /* #include */ - /* #define CL_ALIGNED(_x) _CRT_ALIGN(_x) */ - #define CL_ALIGNED(_x) -#else - #warning Need to implement some method to align data here - #define CL_ALIGNED(_x) -#endif - -/* Indicate whether .xyzw, .s0123 and .hi.lo are supported */ -#if __CL_HAS_ANON_STRUCT__ - /* .xyzw and .s0123...{f|F} are supported */ - #define CL_HAS_NAMED_VECTOR_FIELDS 1 - /* .hi and .lo are supported */ - #define CL_HAS_HI_LO_VECTOR_FIELDS 1 -#endif - -/* Define cl_vector types */ - -/* ---- cl_charn ---- */ -typedef union -{ - cl_char CL_ALIGNED(2) s[2]; -#if __CL_HAS_ANON_STRUCT__ - __CL_ANON_STRUCT__ struct{ cl_char x, y; }; - __CL_ANON_STRUCT__ struct{ cl_char s0, s1; }; - __CL_ANON_STRUCT__ struct{ cl_char lo, hi; }; -#endif -#if defined( __CL_CHAR2__) - __cl_char2 v2; -#endif -}cl_char2; - -typedef union -{ - cl_char CL_ALIGNED(4) s[4]; -#if __CL_HAS_ANON_STRUCT__ - __CL_ANON_STRUCT__ struct{ cl_char x, y, z, w; }; - __CL_ANON_STRUCT__ struct{ cl_char s0, s1, s2, s3; }; - __CL_ANON_STRUCT__ struct{ cl_char2 lo, hi; }; -#endif -#if defined( __CL_CHAR2__) - __cl_char2 v2[2]; -#endif -#if defined( __CL_CHAR4__) - __cl_char4 v4; -#endif -}cl_char4; - -/* cl_char3 is identical in size, alignment and behavior to cl_char4. See section 6.1.5. */ -typedef cl_char4 cl_char3; - -typedef union -{ - cl_char CL_ALIGNED(8) s[8]; -#if __CL_HAS_ANON_STRUCT__ - __CL_ANON_STRUCT__ struct{ cl_char x, y, z, w; }; - __CL_ANON_STRUCT__ struct{ cl_char s0, s1, s2, s3, s4, s5, s6, s7; }; - __CL_ANON_STRUCT__ struct{ cl_char4 lo, hi; }; -#endif -#if defined( __CL_CHAR2__) - __cl_char2 v2[4]; -#endif -#if defined( __CL_CHAR4__) - __cl_char4 v4[2]; -#endif -#if defined( __CL_CHAR8__ ) - __cl_char8 v8; -#endif -}cl_char8; - -typedef union -{ - cl_char CL_ALIGNED(16) s[16]; -#if __CL_HAS_ANON_STRUCT__ - __CL_ANON_STRUCT__ struct{ cl_char x, y, z, w, __spacer4, __spacer5, __spacer6, __spacer7, __spacer8, __spacer9, sa, sb, sc, sd, se, sf; }; - __CL_ANON_STRUCT__ struct{ cl_char s0, s1, s2, s3, s4, s5, s6, s7, s8, s9, sA, sB, sC, sD, sE, sF; }; - __CL_ANON_STRUCT__ struct{ cl_char8 lo, hi; }; -#endif -#if defined( __CL_CHAR2__) - __cl_char2 v2[8]; -#endif -#if defined( __CL_CHAR4__) - __cl_char4 v4[4]; -#endif -#if defined( __CL_CHAR8__ ) - __cl_char8 v8[2]; -#endif -#if defined( __CL_CHAR16__ ) - __cl_char16 v16; -#endif -}cl_char16; - - -/* ---- cl_ucharn ---- */ -typedef union -{ - cl_uchar CL_ALIGNED(2) s[2]; -#if __CL_HAS_ANON_STRUCT__ - __CL_ANON_STRUCT__ struct{ cl_uchar x, y; }; - __CL_ANON_STRUCT__ struct{ cl_uchar s0, s1; }; - __CL_ANON_STRUCT__ struct{ cl_uchar lo, hi; }; -#endif -#if defined( __cl_uchar2__) - __cl_uchar2 v2; -#endif -}cl_uchar2; - -typedef union -{ - cl_uchar CL_ALIGNED(4) s[4]; -#if __CL_HAS_ANON_STRUCT__ - __CL_ANON_STRUCT__ struct{ cl_uchar x, y, z, w; }; - __CL_ANON_STRUCT__ struct{ cl_uchar s0, s1, s2, s3; }; - __CL_ANON_STRUCT__ struct{ cl_uchar2 lo, hi; }; -#endif -#if defined( __CL_UCHAR2__) - __cl_uchar2 v2[2]; -#endif -#if defined( __CL_UCHAR4__) - __cl_uchar4 v4; -#endif -}cl_uchar4; - -/* cl_uchar3 is identical in size, alignment and behavior to cl_uchar4. See section 6.1.5. */ -typedef cl_uchar4 cl_uchar3; - -typedef union -{ - cl_uchar CL_ALIGNED(8) s[8]; -#if __CL_HAS_ANON_STRUCT__ - __CL_ANON_STRUCT__ struct{ cl_uchar x, y, z, w; }; - __CL_ANON_STRUCT__ struct{ cl_uchar s0, s1, s2, s3, s4, s5, s6, s7; }; - __CL_ANON_STRUCT__ struct{ cl_uchar4 lo, hi; }; -#endif -#if defined( __CL_UCHAR2__) - __cl_uchar2 v2[4]; -#endif -#if defined( __CL_UCHAR4__) - __cl_uchar4 v4[2]; -#endif -#if defined( __CL_UCHAR8__ ) - __cl_uchar8 v8; -#endif -}cl_uchar8; - -typedef union -{ - cl_uchar CL_ALIGNED(16) s[16]; -#if __CL_HAS_ANON_STRUCT__ - __CL_ANON_STRUCT__ struct{ cl_uchar x, y, z, w, __spacer4, __spacer5, __spacer6, __spacer7, __spacer8, __spacer9, sa, sb, sc, sd, se, sf; }; - __CL_ANON_STRUCT__ struct{ cl_uchar s0, s1, s2, s3, s4, s5, s6, s7, s8, s9, sA, sB, sC, sD, sE, sF; }; - __CL_ANON_STRUCT__ struct{ cl_uchar8 lo, hi; }; -#endif -#if defined( __CL_UCHAR2__) - __cl_uchar2 v2[8]; -#endif -#if defined( __CL_UCHAR4__) - __cl_uchar4 v4[4]; -#endif -#if defined( __CL_UCHAR8__ ) - __cl_uchar8 v8[2]; -#endif -#if defined( __CL_UCHAR16__ ) - __cl_uchar16 v16; -#endif -}cl_uchar16; - - -/* ---- cl_shortn ---- */ -typedef union -{ - cl_short CL_ALIGNED(4) s[2]; -#if __CL_HAS_ANON_STRUCT__ - __CL_ANON_STRUCT__ struct{ cl_short x, y; }; - __CL_ANON_STRUCT__ struct{ cl_short s0, s1; }; - __CL_ANON_STRUCT__ struct{ cl_short lo, hi; }; -#endif -#if defined( __CL_SHORT2__) - __cl_short2 v2; -#endif -}cl_short2; - -typedef union -{ - cl_short CL_ALIGNED(8) s[4]; -#if __CL_HAS_ANON_STRUCT__ - __CL_ANON_STRUCT__ struct{ cl_short x, y, z, w; }; - __CL_ANON_STRUCT__ struct{ cl_short s0, s1, s2, s3; }; - __CL_ANON_STRUCT__ struct{ cl_short2 lo, hi; }; -#endif -#if defined( __CL_SHORT2__) - __cl_short2 v2[2]; -#endif -#if defined( __CL_SHORT4__) - __cl_short4 v4; -#endif -}cl_short4; - -/* cl_short3 is identical in size, alignment and behavior to cl_short4. See section 6.1.5. */ -typedef cl_short4 cl_short3; - -typedef union -{ - cl_short CL_ALIGNED(16) s[8]; -#if __CL_HAS_ANON_STRUCT__ - __CL_ANON_STRUCT__ struct{ cl_short x, y, z, w; }; - __CL_ANON_STRUCT__ struct{ cl_short s0, s1, s2, s3, s4, s5, s6, s7; }; - __CL_ANON_STRUCT__ struct{ cl_short4 lo, hi; }; -#endif -#if defined( __CL_SHORT2__) - __cl_short2 v2[4]; -#endif -#if defined( __CL_SHORT4__) - __cl_short4 v4[2]; -#endif -#if defined( __CL_SHORT8__ ) - __cl_short8 v8; -#endif -}cl_short8; - -typedef union -{ - cl_short CL_ALIGNED(32) s[16]; -#if __CL_HAS_ANON_STRUCT__ - __CL_ANON_STRUCT__ struct{ cl_short x, y, z, w, __spacer4, __spacer5, __spacer6, __spacer7, __spacer8, __spacer9, sa, sb, sc, sd, se, sf; }; - __CL_ANON_STRUCT__ struct{ cl_short s0, s1, s2, s3, s4, s5, s6, s7, s8, s9, sA, sB, sC, sD, sE, sF; }; - __CL_ANON_STRUCT__ struct{ cl_short8 lo, hi; }; -#endif -#if defined( __CL_SHORT2__) - __cl_short2 v2[8]; -#endif -#if defined( __CL_SHORT4__) - __cl_short4 v4[4]; -#endif -#if defined( __CL_SHORT8__ ) - __cl_short8 v8[2]; -#endif -#if defined( __CL_SHORT16__ ) - __cl_short16 v16; -#endif -}cl_short16; - - -/* ---- cl_ushortn ---- */ -typedef union -{ - cl_ushort CL_ALIGNED(4) s[2]; -#if __CL_HAS_ANON_STRUCT__ - __CL_ANON_STRUCT__ struct{ cl_ushort x, y; }; - __CL_ANON_STRUCT__ struct{ cl_ushort s0, s1; }; - __CL_ANON_STRUCT__ struct{ cl_ushort lo, hi; }; -#endif -#if defined( __CL_USHORT2__) - __cl_ushort2 v2; -#endif -}cl_ushort2; - -typedef union -{ - cl_ushort CL_ALIGNED(8) s[4]; -#if __CL_HAS_ANON_STRUCT__ - __CL_ANON_STRUCT__ struct{ cl_ushort x, y, z, w; }; - __CL_ANON_STRUCT__ struct{ cl_ushort s0, s1, s2, s3; }; - __CL_ANON_STRUCT__ struct{ cl_ushort2 lo, hi; }; -#endif -#if defined( __CL_USHORT2__) - __cl_ushort2 v2[2]; -#endif -#if defined( __CL_USHORT4__) - __cl_ushort4 v4; -#endif -}cl_ushort4; - -/* cl_ushort3 is identical in size, alignment and behavior to cl_ushort4. See section 6.1.5. */ -typedef cl_ushort4 cl_ushort3; - -typedef union -{ - cl_ushort CL_ALIGNED(16) s[8]; -#if __CL_HAS_ANON_STRUCT__ - __CL_ANON_STRUCT__ struct{ cl_ushort x, y, z, w; }; - __CL_ANON_STRUCT__ struct{ cl_ushort s0, s1, s2, s3, s4, s5, s6, s7; }; - __CL_ANON_STRUCT__ struct{ cl_ushort4 lo, hi; }; -#endif -#if defined( __CL_USHORT2__) - __cl_ushort2 v2[4]; -#endif -#if defined( __CL_USHORT4__) - __cl_ushort4 v4[2]; -#endif -#if defined( __CL_USHORT8__ ) - __cl_ushort8 v8; -#endif -}cl_ushort8; - -typedef union -{ - cl_ushort CL_ALIGNED(32) s[16]; -#if __CL_HAS_ANON_STRUCT__ - __CL_ANON_STRUCT__ struct{ cl_ushort x, y, z, w, __spacer4, __spacer5, __spacer6, __spacer7, __spacer8, __spacer9, sa, sb, sc, sd, se, sf; }; - __CL_ANON_STRUCT__ struct{ cl_ushort s0, s1, s2, s3, s4, s5, s6, s7, s8, s9, sA, sB, sC, sD, sE, sF; }; - __CL_ANON_STRUCT__ struct{ cl_ushort8 lo, hi; }; -#endif -#if defined( __CL_USHORT2__) - __cl_ushort2 v2[8]; -#endif -#if defined( __CL_USHORT4__) - __cl_ushort4 v4[4]; -#endif -#if defined( __CL_USHORT8__ ) - __cl_ushort8 v8[2]; -#endif -#if defined( __CL_USHORT16__ ) - __cl_ushort16 v16; -#endif -}cl_ushort16; - -/* ---- cl_intn ---- */ -typedef union -{ - cl_int CL_ALIGNED(8) s[2]; -#if __CL_HAS_ANON_STRUCT__ - __CL_ANON_STRUCT__ struct{ cl_int x, y; }; - __CL_ANON_STRUCT__ struct{ cl_int s0, s1; }; - __CL_ANON_STRUCT__ struct{ cl_int lo, hi; }; -#endif -#if defined( __CL_INT2__) - __cl_int2 v2; -#endif -}cl_int2; - -typedef union -{ - cl_int CL_ALIGNED(16) s[4]; -#if __CL_HAS_ANON_STRUCT__ - __CL_ANON_STRUCT__ struct{ cl_int x, y, z, w; }; - __CL_ANON_STRUCT__ struct{ cl_int s0, s1, s2, s3; }; - __CL_ANON_STRUCT__ struct{ cl_int2 lo, hi; }; -#endif -#if defined( __CL_INT2__) - __cl_int2 v2[2]; -#endif -#if defined( __CL_INT4__) - __cl_int4 v4; -#endif -}cl_int4; - -/* cl_int3 is identical in size, alignment and behavior to cl_int4. See section 6.1.5. */ -typedef cl_int4 cl_int3; - -typedef union -{ - cl_int CL_ALIGNED(32) s[8]; -#if __CL_HAS_ANON_STRUCT__ - __CL_ANON_STRUCT__ struct{ cl_int x, y, z, w; }; - __CL_ANON_STRUCT__ struct{ cl_int s0, s1, s2, s3, s4, s5, s6, s7; }; - __CL_ANON_STRUCT__ struct{ cl_int4 lo, hi; }; -#endif -#if defined( __CL_INT2__) - __cl_int2 v2[4]; -#endif -#if defined( __CL_INT4__) - __cl_int4 v4[2]; -#endif -#if defined( __CL_INT8__ ) - __cl_int8 v8; -#endif -}cl_int8; - -typedef union -{ - cl_int CL_ALIGNED(64) s[16]; -#if __CL_HAS_ANON_STRUCT__ - __CL_ANON_STRUCT__ struct{ cl_int x, y, z, w, __spacer4, __spacer5, __spacer6, __spacer7, __spacer8, __spacer9, sa, sb, sc, sd, se, sf; }; - __CL_ANON_STRUCT__ struct{ cl_int s0, s1, s2, s3, s4, s5, s6, s7, s8, s9, sA, sB, sC, sD, sE, sF; }; - __CL_ANON_STRUCT__ struct{ cl_int8 lo, hi; }; -#endif -#if defined( __CL_INT2__) - __cl_int2 v2[8]; -#endif -#if defined( __CL_INT4__) - __cl_int4 v4[4]; -#endif -#if defined( __CL_INT8__ ) - __cl_int8 v8[2]; -#endif -#if defined( __CL_INT16__ ) - __cl_int16 v16; -#endif -}cl_int16; - - -/* ---- cl_uintn ---- */ -typedef union -{ - cl_uint CL_ALIGNED(8) s[2]; -#if __CL_HAS_ANON_STRUCT__ - __CL_ANON_STRUCT__ struct{ cl_uint x, y; }; - __CL_ANON_STRUCT__ struct{ cl_uint s0, s1; }; - __CL_ANON_STRUCT__ struct{ cl_uint lo, hi; }; -#endif -#if defined( __CL_UINT2__) - __cl_uint2 v2; -#endif -}cl_uint2; - -typedef union -{ - cl_uint CL_ALIGNED(16) s[4]; -#if __CL_HAS_ANON_STRUCT__ - __CL_ANON_STRUCT__ struct{ cl_uint x, y, z, w; }; - __CL_ANON_STRUCT__ struct{ cl_uint s0, s1, s2, s3; }; - __CL_ANON_STRUCT__ struct{ cl_uint2 lo, hi; }; -#endif -#if defined( __CL_UINT2__) - __cl_uint2 v2[2]; -#endif -#if defined( __CL_UINT4__) - __cl_uint4 v4; -#endif -}cl_uint4; - -/* cl_uint3 is identical in size, alignment and behavior to cl_uint4. See section 6.1.5. */ -typedef cl_uint4 cl_uint3; - -typedef union -{ - cl_uint CL_ALIGNED(32) s[8]; -#if __CL_HAS_ANON_STRUCT__ - __CL_ANON_STRUCT__ struct{ cl_uint x, y, z, w; }; - __CL_ANON_STRUCT__ struct{ cl_uint s0, s1, s2, s3, s4, s5, s6, s7; }; - __CL_ANON_STRUCT__ struct{ cl_uint4 lo, hi; }; -#endif -#if defined( __CL_UINT2__) - __cl_uint2 v2[4]; -#endif -#if defined( __CL_UINT4__) - __cl_uint4 v4[2]; -#endif -#if defined( __CL_UINT8__ ) - __cl_uint8 v8; -#endif -}cl_uint8; - -typedef union -{ - cl_uint CL_ALIGNED(64) s[16]; -#if __CL_HAS_ANON_STRUCT__ - __CL_ANON_STRUCT__ struct{ cl_uint x, y, z, w, __spacer4, __spacer5, __spacer6, __spacer7, __spacer8, __spacer9, sa, sb, sc, sd, se, sf; }; - __CL_ANON_STRUCT__ struct{ cl_uint s0, s1, s2, s3, s4, s5, s6, s7, s8, s9, sA, sB, sC, sD, sE, sF; }; - __CL_ANON_STRUCT__ struct{ cl_uint8 lo, hi; }; -#endif -#if defined( __CL_UINT2__) - __cl_uint2 v2[8]; -#endif -#if defined( __CL_UINT4__) - __cl_uint4 v4[4]; -#endif -#if defined( __CL_UINT8__ ) - __cl_uint8 v8[2]; -#endif -#if defined( __CL_UINT16__ ) - __cl_uint16 v16; -#endif -}cl_uint16; - -/* ---- cl_longn ---- */ -typedef union -{ - cl_long CL_ALIGNED(16) s[2]; -#if __CL_HAS_ANON_STRUCT__ - __CL_ANON_STRUCT__ struct{ cl_long x, y; }; - __CL_ANON_STRUCT__ struct{ cl_long s0, s1; }; - __CL_ANON_STRUCT__ struct{ cl_long lo, hi; }; -#endif -#if defined( __CL_LONG2__) - __cl_long2 v2; -#endif -}cl_long2; - -typedef union -{ - cl_long CL_ALIGNED(32) s[4]; -#if __CL_HAS_ANON_STRUCT__ - __CL_ANON_STRUCT__ struct{ cl_long x, y, z, w; }; - __CL_ANON_STRUCT__ struct{ cl_long s0, s1, s2, s3; }; - __CL_ANON_STRUCT__ struct{ cl_long2 lo, hi; }; -#endif -#if defined( __CL_LONG2__) - __cl_long2 v2[2]; -#endif -#if defined( __CL_LONG4__) - __cl_long4 v4; -#endif -}cl_long4; - -/* cl_long3 is identical in size, alignment and behavior to cl_long4. See section 6.1.5. */ -typedef cl_long4 cl_long3; - -typedef union -{ - cl_long CL_ALIGNED(64) s[8]; -#if __CL_HAS_ANON_STRUCT__ - __CL_ANON_STRUCT__ struct{ cl_long x, y, z, w; }; - __CL_ANON_STRUCT__ struct{ cl_long s0, s1, s2, s3, s4, s5, s6, s7; }; - __CL_ANON_STRUCT__ struct{ cl_long4 lo, hi; }; -#endif -#if defined( __CL_LONG2__) - __cl_long2 v2[4]; -#endif -#if defined( __CL_LONG4__) - __cl_long4 v4[2]; -#endif -#if defined( __CL_LONG8__ ) - __cl_long8 v8; -#endif -}cl_long8; - -typedef union -{ - cl_long CL_ALIGNED(128) s[16]; -#if __CL_HAS_ANON_STRUCT__ - __CL_ANON_STRUCT__ struct{ cl_long x, y, z, w, __spacer4, __spacer5, __spacer6, __spacer7, __spacer8, __spacer9, sa, sb, sc, sd, se, sf; }; - __CL_ANON_STRUCT__ struct{ cl_long s0, s1, s2, s3, s4, s5, s6, s7, s8, s9, sA, sB, sC, sD, sE, sF; }; - __CL_ANON_STRUCT__ struct{ cl_long8 lo, hi; }; -#endif -#if defined( __CL_LONG2__) - __cl_long2 v2[8]; -#endif -#if defined( __CL_LONG4__) - __cl_long4 v4[4]; -#endif -#if defined( __CL_LONG8__ ) - __cl_long8 v8[2]; -#endif -#if defined( __CL_LONG16__ ) - __cl_long16 v16; -#endif -}cl_long16; - - -/* ---- cl_ulongn ---- */ -typedef union -{ - cl_ulong CL_ALIGNED(16) s[2]; -#if __CL_HAS_ANON_STRUCT__ - __CL_ANON_STRUCT__ struct{ cl_ulong x, y; }; - __CL_ANON_STRUCT__ struct{ cl_ulong s0, s1; }; - __CL_ANON_STRUCT__ struct{ cl_ulong lo, hi; }; -#endif -#if defined( __CL_ULONG2__) - __cl_ulong2 v2; -#endif -}cl_ulong2; - -typedef union -{ - cl_ulong CL_ALIGNED(32) s[4]; -#if __CL_HAS_ANON_STRUCT__ - __CL_ANON_STRUCT__ struct{ cl_ulong x, y, z, w; }; - __CL_ANON_STRUCT__ struct{ cl_ulong s0, s1, s2, s3; }; - __CL_ANON_STRUCT__ struct{ cl_ulong2 lo, hi; }; -#endif -#if defined( __CL_ULONG2__) - __cl_ulong2 v2[2]; -#endif -#if defined( __CL_ULONG4__) - __cl_ulong4 v4; -#endif -}cl_ulong4; - -/* cl_ulong3 is identical in size, alignment and behavior to cl_ulong4. See section 6.1.5. */ -typedef cl_ulong4 cl_ulong3; - -typedef union -{ - cl_ulong CL_ALIGNED(64) s[8]; -#if __CL_HAS_ANON_STRUCT__ - __CL_ANON_STRUCT__ struct{ cl_ulong x, y, z, w; }; - __CL_ANON_STRUCT__ struct{ cl_ulong s0, s1, s2, s3, s4, s5, s6, s7; }; - __CL_ANON_STRUCT__ struct{ cl_ulong4 lo, hi; }; -#endif -#if defined( __CL_ULONG2__) - __cl_ulong2 v2[4]; -#endif -#if defined( __CL_ULONG4__) - __cl_ulong4 v4[2]; -#endif -#if defined( __CL_ULONG8__ ) - __cl_ulong8 v8; -#endif -}cl_ulong8; - -typedef union -{ - cl_ulong CL_ALIGNED(128) s[16]; -#if __CL_HAS_ANON_STRUCT__ - __CL_ANON_STRUCT__ struct{ cl_ulong x, y, z, w, __spacer4, __spacer5, __spacer6, __spacer7, __spacer8, __spacer9, sa, sb, sc, sd, se, sf; }; - __CL_ANON_STRUCT__ struct{ cl_ulong s0, s1, s2, s3, s4, s5, s6, s7, s8, s9, sA, sB, sC, sD, sE, sF; }; - __CL_ANON_STRUCT__ struct{ cl_ulong8 lo, hi; }; -#endif -#if defined( __CL_ULONG2__) - __cl_ulong2 v2[8]; -#endif -#if defined( __CL_ULONG4__) - __cl_ulong4 v4[4]; -#endif -#if defined( __CL_ULONG8__ ) - __cl_ulong8 v8[2]; -#endif -#if defined( __CL_ULONG16__ ) - __cl_ulong16 v16; -#endif -}cl_ulong16; - - -/* --- cl_floatn ---- */ - -typedef union -{ - cl_float CL_ALIGNED(8) s[2]; -#if __CL_HAS_ANON_STRUCT__ - __CL_ANON_STRUCT__ struct{ cl_float x, y; }; - __CL_ANON_STRUCT__ struct{ cl_float s0, s1; }; - __CL_ANON_STRUCT__ struct{ cl_float lo, hi; }; -#endif -#if defined( __CL_FLOAT2__) - __cl_float2 v2; -#endif -}cl_float2; - -typedef union -{ - cl_float CL_ALIGNED(16) s[4]; -#if __CL_HAS_ANON_STRUCT__ - __CL_ANON_STRUCT__ struct{ cl_float x, y, z, w; }; - __CL_ANON_STRUCT__ struct{ cl_float s0, s1, s2, s3; }; - __CL_ANON_STRUCT__ struct{ cl_float2 lo, hi; }; -#endif -#if defined( __CL_FLOAT2__) - __cl_float2 v2[2]; -#endif -#if defined( __CL_FLOAT4__) - __cl_float4 v4; -#endif -}cl_float4; - -/* cl_float3 is identical in size, alignment and behavior to cl_float4. See section 6.1.5. */ -typedef cl_float4 cl_float3; - -typedef union -{ - cl_float CL_ALIGNED(32) s[8]; -#if __CL_HAS_ANON_STRUCT__ - __CL_ANON_STRUCT__ struct{ cl_float x, y, z, w; }; - __CL_ANON_STRUCT__ struct{ cl_float s0, s1, s2, s3, s4, s5, s6, s7; }; - __CL_ANON_STRUCT__ struct{ cl_float4 lo, hi; }; -#endif -#if defined( __CL_FLOAT2__) - __cl_float2 v2[4]; -#endif -#if defined( __CL_FLOAT4__) - __cl_float4 v4[2]; -#endif -#if defined( __CL_FLOAT8__ ) - __cl_float8 v8; -#endif -}cl_float8; - -typedef union -{ - cl_float CL_ALIGNED(64) s[16]; -#if __CL_HAS_ANON_STRUCT__ - __CL_ANON_STRUCT__ struct{ cl_float x, y, z, w, __spacer4, __spacer5, __spacer6, __spacer7, __spacer8, __spacer9, sa, sb, sc, sd, se, sf; }; - __CL_ANON_STRUCT__ struct{ cl_float s0, s1, s2, s3, s4, s5, s6, s7, s8, s9, sA, sB, sC, sD, sE, sF; }; - __CL_ANON_STRUCT__ struct{ cl_float8 lo, hi; }; -#endif -#if defined( __CL_FLOAT2__) - __cl_float2 v2[8]; -#endif -#if defined( __CL_FLOAT4__) - __cl_float4 v4[4]; -#endif -#if defined( __CL_FLOAT8__ ) - __cl_float8 v8[2]; -#endif -#if defined( __CL_FLOAT16__ ) - __cl_float16 v16; -#endif -}cl_float16; - -/* --- cl_doublen ---- */ - -typedef union -{ - cl_double CL_ALIGNED(16) s[2]; -#if __CL_HAS_ANON_STRUCT__ - __CL_ANON_STRUCT__ struct{ cl_double x, y; }; - __CL_ANON_STRUCT__ struct{ cl_double s0, s1; }; - __CL_ANON_STRUCT__ struct{ cl_double lo, hi; }; -#endif -#if defined( __CL_DOUBLE2__) - __cl_double2 v2; -#endif -}cl_double2; - -typedef union -{ - cl_double CL_ALIGNED(32) s[4]; -#if __CL_HAS_ANON_STRUCT__ - __CL_ANON_STRUCT__ struct{ cl_double x, y, z, w; }; - __CL_ANON_STRUCT__ struct{ cl_double s0, s1, s2, s3; }; - __CL_ANON_STRUCT__ struct{ cl_double2 lo, hi; }; -#endif -#if defined( __CL_DOUBLE2__) - __cl_double2 v2[2]; -#endif -#if defined( __CL_DOUBLE4__) - __cl_double4 v4; -#endif -}cl_double4; - -/* cl_double3 is identical in size, alignment and behavior to cl_double4. See section 6.1.5. */ -typedef cl_double4 cl_double3; - -typedef union -{ - cl_double CL_ALIGNED(64) s[8]; -#if __CL_HAS_ANON_STRUCT__ - __CL_ANON_STRUCT__ struct{ cl_double x, y, z, w; }; - __CL_ANON_STRUCT__ struct{ cl_double s0, s1, s2, s3, s4, s5, s6, s7; }; - __CL_ANON_STRUCT__ struct{ cl_double4 lo, hi; }; -#endif -#if defined( __CL_DOUBLE2__) - __cl_double2 v2[4]; -#endif -#if defined( __CL_DOUBLE4__) - __cl_double4 v4[2]; -#endif -#if defined( __CL_DOUBLE8__ ) - __cl_double8 v8; -#endif -}cl_double8; - -typedef union -{ - cl_double CL_ALIGNED(128) s[16]; -#if __CL_HAS_ANON_STRUCT__ - __CL_ANON_STRUCT__ struct{ cl_double x, y, z, w, __spacer4, __spacer5, __spacer6, __spacer7, __spacer8, __spacer9, sa, sb, sc, sd, se, sf; }; - __CL_ANON_STRUCT__ struct{ cl_double s0, s1, s2, s3, s4, s5, s6, s7, s8, s9, sA, sB, sC, sD, sE, sF; }; - __CL_ANON_STRUCT__ struct{ cl_double8 lo, hi; }; -#endif -#if defined( __CL_DOUBLE2__) - __cl_double2 v2[8]; -#endif -#if defined( __CL_DOUBLE4__) - __cl_double4 v4[4]; -#endif -#if defined( __CL_DOUBLE8__ ) - __cl_double8 v8[2]; -#endif -#if defined( __CL_DOUBLE16__ ) - __cl_double16 v16; -#endif -}cl_double16; - -/* Macro to facilitate debugging - * Usage: - * Place CL_PROGRAM_STRING_DEBUG_INFO on the line before the first line of your source. - * The first line ends with: CL_PROGRAM_STRING_DEBUG_INFO \" - * Each line thereafter of OpenCL C source must end with: \n\ - * The last line ends in "; - * - * Example: - * - * const char *my_program = CL_PROGRAM_STRING_DEBUG_INFO "\ - * kernel void foo( int a, float * b ) \n\ - * { \n\ - * // my comment \n\ - * *b[ get_global_id(0)] = a; \n\ - * } \n\ - * "; - * - * This should correctly set up the line, (column) and file information for your source - * string so you can do source level debugging. - */ -#define __CL_STRINGIFY( _x ) # _x -#define _CL_STRINGIFY( _x ) __CL_STRINGIFY( _x ) -#define CL_PROGRAM_STRING_DEBUG_INFO "#line " _CL_STRINGIFY(__LINE__) " \"" __FILE__ "\" \n\n" - -#ifdef __cplusplus -} -#endif - -#undef __CL_HAS_ANON_STRUCT__ -#undef __CL_ANON_STRUCT__ -#if defined( _WIN32) && (_MSC_VER >= 1500) -#pragma warning( pop ) -#endif - -#endif /* __CL_PLATFORM_H */ diff --git a/third_party/opencl/include/CL/opencl.h b/third_party/opencl/include/CL/opencl.h deleted file mode 100644 index 9855cd7..0000000 --- a/third_party/opencl/include/CL/opencl.h +++ /dev/null @@ -1,59 +0,0 @@ -/******************************************************************************* - * Copyright (c) 2008-2015 The Khronos Group Inc. - * - * Permission is hereby granted, free of charge, to any person obtaining a - * copy of this software and/or associated documentation files (the - * "Materials"), to deal in the Materials without restriction, including - * without limitation the rights to use, copy, modify, merge, publish, - * distribute, sublicense, and/or sell copies of the Materials, and to - * permit persons to whom the Materials are furnished to do so, subject to - * the following conditions: - * - * The above copyright notice and this permission notice shall be included - * in all copies or substantial portions of the Materials. - * - * MODIFICATIONS TO THIS FILE MAY MEAN IT NO LONGER ACCURATELY REFLECTS - * KHRONOS STANDARDS. THE UNMODIFIED, NORMATIVE VERSIONS OF KHRONOS - * SPECIFICATIONS AND HEADER INFORMATION ARE LOCATED AT - * https://www.khronos.org/registry/ - * - * THE MATERIALS ARE PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, - * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF - * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. - * IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY - * CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, - * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE - * MATERIALS OR THE USE OR OTHER DEALINGS IN THE MATERIALS. - ******************************************************************************/ - -/* $Revision: 11708 $ on $Date: 2010-06-13 23:36:24 -0700 (Sun, 13 Jun 2010) $ */ - -#ifndef __OPENCL_H -#define __OPENCL_H - -#ifdef __cplusplus -extern "C" { -#endif - -#ifdef __APPLE__ - -#include -#include -#include -#include - -#else - -#include -#include -#include -#include - -#endif - -#ifdef __cplusplus -} -#endif - -#endif /* __OPENCL_H */ - diff --git a/third_party/qrcode/QrCode.cc b/third_party/qrcode/QrCode.cc deleted file mode 100644 index b9de862..0000000 --- a/third_party/qrcode/QrCode.cc +++ /dev/null @@ -1,862 +0,0 @@ -/* - * QR Code generator library (C++) - * - * Copyright (c) Project Nayuki. (MIT License) - * https://www.nayuki.io/page/qr-code-generator-library - * - * Permission is hereby granted, free of charge, to any person obtaining a copy of - * this software and associated documentation files (the "Software"), to deal in - * the Software without restriction, including without limitation the rights to - * use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of - * the Software, and to permit persons to whom the Software is furnished to do so, - * subject to the following conditions: - * - The above copyright notice and this permission notice shall be included in - * all copies or substantial portions of the Software. - * - The Software is provided "as is", without warranty of any kind, express or - * implied, including but not limited to the warranties of merchantability, - * fitness for a particular purpose and noninfringement. In no event shall the - * authors or copyright holders be liable for any claim, damages or other - * liability, whether in an action of contract, tort or otherwise, arising from, - * out of or in connection with the Software or the use or other dealings in the - * Software. - */ - -#include -#include -#include -#include -#include -#include -#include -#include -#include "QrCode.hpp" - -using std::int8_t; -using std::uint8_t; -using std::size_t; -using std::vector; - - -namespace qrcodegen { - -QrSegment::Mode::Mode(int mode, int cc0, int cc1, int cc2) : - modeBits(mode) { - numBitsCharCount[0] = cc0; - numBitsCharCount[1] = cc1; - numBitsCharCount[2] = cc2; -} - - -int QrSegment::Mode::getModeBits() const { - return modeBits; -} - - -int QrSegment::Mode::numCharCountBits(int ver) const { - return numBitsCharCount[(ver + 7) / 17]; -} - - -const QrSegment::Mode QrSegment::Mode::NUMERIC (0x1, 10, 12, 14); -const QrSegment::Mode QrSegment::Mode::ALPHANUMERIC(0x2, 9, 11, 13); -const QrSegment::Mode QrSegment::Mode::BYTE (0x4, 8, 16, 16); -const QrSegment::Mode QrSegment::Mode::KANJI (0x8, 8, 10, 12); -const QrSegment::Mode QrSegment::Mode::ECI (0x7, 0, 0, 0); - - -QrSegment QrSegment::makeBytes(const vector &data) { - if (data.size() > static_cast(INT_MAX)) - throw std::length_error("Data too long"); - BitBuffer bb; - for (uint8_t b : data) - bb.appendBits(b, 8); - return QrSegment(Mode::BYTE, static_cast(data.size()), std::move(bb)); -} - - -QrSegment QrSegment::makeNumeric(const char *digits) { - BitBuffer bb; - int accumData = 0; - int accumCount = 0; - int charCount = 0; - for (; *digits != '\0'; digits++, charCount++) { - char c = *digits; - if (c < '0' || c > '9') - throw std::domain_error("String contains non-numeric characters"); - accumData = accumData * 10 + (c - '0'); - accumCount++; - if (accumCount == 3) { - bb.appendBits(static_cast(accumData), 10); - accumData = 0; - accumCount = 0; - } - } - if (accumCount > 0) // 1 or 2 digits remaining - bb.appendBits(static_cast(accumData), accumCount * 3 + 1); - return QrSegment(Mode::NUMERIC, charCount, std::move(bb)); -} - - -QrSegment QrSegment::makeAlphanumeric(const char *text) { - BitBuffer bb; - int accumData = 0; - int accumCount = 0; - int charCount = 0; - for (; *text != '\0'; text++, charCount++) { - const char *temp = std::strchr(ALPHANUMERIC_CHARSET, *text); - if (temp == nullptr) - throw std::domain_error("String contains unencodable characters in alphanumeric mode"); - accumData = accumData * 45 + static_cast(temp - ALPHANUMERIC_CHARSET); - accumCount++; - if (accumCount == 2) { - bb.appendBits(static_cast(accumData), 11); - accumData = 0; - accumCount = 0; - } - } - if (accumCount > 0) // 1 character remaining - bb.appendBits(static_cast(accumData), 6); - return QrSegment(Mode::ALPHANUMERIC, charCount, std::move(bb)); -} - - -vector QrSegment::makeSegments(const char *text) { - // Select the most efficient segment encoding automatically - vector result; - if (*text == '\0'); // Leave result empty - else if (isNumeric(text)) - result.push_back(makeNumeric(text)); - else if (isAlphanumeric(text)) - result.push_back(makeAlphanumeric(text)); - else { - vector bytes; - for (; *text != '\0'; text++) - bytes.push_back(static_cast(*text)); - result.push_back(makeBytes(bytes)); - } - return result; -} - - -QrSegment QrSegment::makeEci(long assignVal) { - BitBuffer bb; - if (assignVal < 0) - throw std::domain_error("ECI assignment value out of range"); - else if (assignVal < (1 << 7)) - bb.appendBits(static_cast(assignVal), 8); - else if (assignVal < (1 << 14)) { - bb.appendBits(2, 2); - bb.appendBits(static_cast(assignVal), 14); - } else if (assignVal < 1000000L) { - bb.appendBits(6, 3); - bb.appendBits(static_cast(assignVal), 21); - } else - throw std::domain_error("ECI assignment value out of range"); - return QrSegment(Mode::ECI, 0, std::move(bb)); -} - - -QrSegment::QrSegment(Mode md, int numCh, const std::vector &dt) : - mode(md), - numChars(numCh), - data(dt) { - if (numCh < 0) - throw std::domain_error("Invalid value"); -} - - -QrSegment::QrSegment(Mode md, int numCh, std::vector &&dt) : - mode(md), - numChars(numCh), - data(std::move(dt)) { - if (numCh < 0) - throw std::domain_error("Invalid value"); -} - - -int QrSegment::getTotalBits(const vector &segs, int version) { - int result = 0; - for (const QrSegment &seg : segs) { - int ccbits = seg.mode.numCharCountBits(version); - if (seg.numChars >= (1L << ccbits)) - return -1; // The segment's length doesn't fit the field's bit width - if (4 + ccbits > INT_MAX - result) - return -1; // The sum will overflow an int type - result += 4 + ccbits; - if (seg.data.size() > static_cast(INT_MAX - result)) - return -1; // The sum will overflow an int type - result += static_cast(seg.data.size()); - } - return result; -} - - -bool QrSegment::isAlphanumeric(const char *text) { - for (; *text != '\0'; text++) { - if (std::strchr(ALPHANUMERIC_CHARSET, *text) == nullptr) - return false; - } - return true; -} - - -bool QrSegment::isNumeric(const char *text) { - for (; *text != '\0'; text++) { - char c = *text; - if (c < '0' || c > '9') - return false; - } - return true; -} - - -QrSegment::Mode QrSegment::getMode() const { - return mode; -} - - -int QrSegment::getNumChars() const { - return numChars; -} - - -const std::vector &QrSegment::getData() const { - return data; -} - - -const char *QrSegment::ALPHANUMERIC_CHARSET = "0123456789ABCDEFGHIJKLMNOPQRSTUVWXYZ $%*+-./:"; - - - -int QrCode::getFormatBits(Ecc ecl) { - switch (ecl) { - case Ecc::LOW : return 1; - case Ecc::MEDIUM : return 0; - case Ecc::QUARTILE: return 3; - case Ecc::HIGH : return 2; - default: throw std::logic_error("Assertion error"); - } -} - - -QrCode QrCode::encodeText(const char *text, Ecc ecl) { - vector segs = QrSegment::makeSegments(text); - return encodeSegments(segs, ecl); -} - - -QrCode QrCode::encodeBinary(const vector &data, Ecc ecl) { - vector segs{QrSegment::makeBytes(data)}; - return encodeSegments(segs, ecl); -} - - -QrCode QrCode::encodeSegments(const vector &segs, Ecc ecl, - int minVersion, int maxVersion, int mask, bool boostEcl) { - if (!(MIN_VERSION <= minVersion && minVersion <= maxVersion && maxVersion <= MAX_VERSION) || mask < -1 || mask > 7) - throw std::invalid_argument("Invalid value"); - - // Find the minimal version number to use - int version, dataUsedBits; - for (version = minVersion; ; version++) { - int dataCapacityBits = getNumDataCodewords(version, ecl) * 8; // Number of data bits available - dataUsedBits = QrSegment::getTotalBits(segs, version); - if (dataUsedBits != -1 && dataUsedBits <= dataCapacityBits) - break; // This version number is found to be suitable - if (version >= maxVersion) { // All versions in the range could not fit the given data - std::ostringstream sb; - if (dataUsedBits == -1) - sb << "Segment too long"; - else { - sb << "Data length = " << dataUsedBits << " bits, "; - sb << "Max capacity = " << dataCapacityBits << " bits"; - } - throw data_too_long(sb.str()); - } - } - if (dataUsedBits == -1) - throw std::logic_error("Assertion error"); - - // Increase the error correction level while the data still fits in the current version number - for (Ecc newEcl : vector{Ecc::MEDIUM, Ecc::QUARTILE, Ecc::HIGH}) { // From low to high - if (boostEcl && dataUsedBits <= getNumDataCodewords(version, newEcl) * 8) - ecl = newEcl; - } - - // Concatenate all segments to create the data bit string - BitBuffer bb; - for (const QrSegment &seg : segs) { - bb.appendBits(static_cast(seg.getMode().getModeBits()), 4); - bb.appendBits(static_cast(seg.getNumChars()), seg.getMode().numCharCountBits(version)); - bb.insert(bb.end(), seg.getData().begin(), seg.getData().end()); - } - if (bb.size() != static_cast(dataUsedBits)) - throw std::logic_error("Assertion error"); - - // Add terminator and pad up to a byte if applicable - size_t dataCapacityBits = static_cast(getNumDataCodewords(version, ecl)) * 8; - if (bb.size() > dataCapacityBits) - throw std::logic_error("Assertion error"); - bb.appendBits(0, std::min(4, static_cast(dataCapacityBits - bb.size()))); - bb.appendBits(0, (8 - static_cast(bb.size() % 8)) % 8); - if (bb.size() % 8 != 0) - throw std::logic_error("Assertion error"); - - // Pad with alternating bytes until data capacity is reached - for (uint8_t padByte = 0xEC; bb.size() < dataCapacityBits; padByte ^= 0xEC ^ 0x11) - bb.appendBits(padByte, 8); - - // Pack bits into bytes in big endian - vector dataCodewords(bb.size() / 8); - for (size_t i = 0; i < bb.size(); i++) - dataCodewords[i >> 3] |= (bb.at(i) ? 1 : 0) << (7 - (i & 7)); - - // Create the QR Code object - return QrCode(version, ecl, dataCodewords, mask); -} - - -QrCode::QrCode(int ver, Ecc ecl, const vector &dataCodewords, int msk) : - // Initialize fields and check arguments - version(ver), - errorCorrectionLevel(ecl) { - if (ver < MIN_VERSION || ver > MAX_VERSION) - throw std::domain_error("Version value out of range"); - if (msk < -1 || msk > 7) - throw std::domain_error("Mask value out of range"); - size = ver * 4 + 17; - size_t sz = static_cast(size); - modules = vector >(sz, vector(sz)); // Initially all white - isFunction = vector >(sz, vector(sz)); - - // Compute ECC, draw modules - drawFunctionPatterns(); - const vector allCodewords = addEccAndInterleave(dataCodewords); - drawCodewords(allCodewords); - - // Do masking - if (msk == -1) { // Automatically choose best mask - long minPenalty = LONG_MAX; - for (int i = 0; i < 8; i++) { - applyMask(i); - drawFormatBits(i); - long penalty = getPenaltyScore(); - if (penalty < minPenalty) { - msk = i; - minPenalty = penalty; - } - applyMask(i); // Undoes the mask due to XOR - } - } - if (msk < 0 || msk > 7) - throw std::logic_error("Assertion error"); - this->mask = msk; - applyMask(msk); // Apply the final choice of mask - drawFormatBits(msk); // Overwrite old format bits - - isFunction.clear(); - isFunction.shrink_to_fit(); -} - - -int QrCode::getVersion() const { - return version; -} - - -int QrCode::getSize() const { - return size; -} - - -QrCode::Ecc QrCode::getErrorCorrectionLevel() const { - return errorCorrectionLevel; -} - - -int QrCode::getMask() const { - return mask; -} - - -bool QrCode::getModule(int x, int y) const { - return 0 <= x && x < size && 0 <= y && y < size && module(x, y); -} - - -std::string QrCode::toSvgString(int border) const { - if (border < 0) - throw std::domain_error("Border must be non-negative"); - if (border > INT_MAX / 2 || border * 2 > INT_MAX - size) - throw std::overflow_error("Border too large"); - - std::ostringstream sb; - sb << "\n"; - sb << "\n"; - sb << "\n"; - sb << "\t\n"; - sb << "\t\n"; - sb << "\n"; - return sb.str(); -} - - -void QrCode::drawFunctionPatterns() { - // Draw horizontal and vertical timing patterns - for (int i = 0; i < size; i++) { - setFunctionModule(6, i, i % 2 == 0); - setFunctionModule(i, 6, i % 2 == 0); - } - - // Draw 3 finder patterns (all corners except bottom right; overwrites some timing modules) - drawFinderPattern(3, 3); - drawFinderPattern(size - 4, 3); - drawFinderPattern(3, size - 4); - - // Draw numerous alignment patterns - const vector alignPatPos = getAlignmentPatternPositions(); - size_t numAlign = alignPatPos.size(); - for (size_t i = 0; i < numAlign; i++) { - for (size_t j = 0; j < numAlign; j++) { - // Don't draw on the three finder corners - if (!((i == 0 && j == 0) || (i == 0 && j == numAlign - 1) || (i == numAlign - 1 && j == 0))) - drawAlignmentPattern(alignPatPos.at(i), alignPatPos.at(j)); - } - } - - // Draw configuration data - drawFormatBits(0); // Dummy mask value; overwritten later in the constructor - drawVersion(); -} - - -void QrCode::drawFormatBits(int msk) { - // Calculate error correction code and pack bits - int data = getFormatBits(errorCorrectionLevel) << 3 | msk; // errCorrLvl is uint2, msk is uint3 - int rem = data; - for (int i = 0; i < 10; i++) - rem = (rem << 1) ^ ((rem >> 9) * 0x537); - int bits = (data << 10 | rem) ^ 0x5412; // uint15 - if (bits >> 15 != 0) - throw std::logic_error("Assertion error"); - - // Draw first copy - for (int i = 0; i <= 5; i++) - setFunctionModule(8, i, getBit(bits, i)); - setFunctionModule(8, 7, getBit(bits, 6)); - setFunctionModule(8, 8, getBit(bits, 7)); - setFunctionModule(7, 8, getBit(bits, 8)); - for (int i = 9; i < 15; i++) - setFunctionModule(14 - i, 8, getBit(bits, i)); - - // Draw second copy - for (int i = 0; i < 8; i++) - setFunctionModule(size - 1 - i, 8, getBit(bits, i)); - for (int i = 8; i < 15; i++) - setFunctionModule(8, size - 15 + i, getBit(bits, i)); - setFunctionModule(8, size - 8, true); // Always black -} - - -void QrCode::drawVersion() { - if (version < 7) - return; - - // Calculate error correction code and pack bits - int rem = version; // version is uint6, in the range [7, 40] - for (int i = 0; i < 12; i++) - rem = (rem << 1) ^ ((rem >> 11) * 0x1F25); - long bits = static_cast(version) << 12 | rem; // uint18 - if (bits >> 18 != 0) - throw std::logic_error("Assertion error"); - - // Draw two copies - for (int i = 0; i < 18; i++) { - bool bit = getBit(bits, i); - int a = size - 11 + i % 3; - int b = i / 3; - setFunctionModule(a, b, bit); - setFunctionModule(b, a, bit); - } -} - - -void QrCode::drawFinderPattern(int x, int y) { - for (int dy = -4; dy <= 4; dy++) { - for (int dx = -4; dx <= 4; dx++) { - int dist = std::max(std::abs(dx), std::abs(dy)); // Chebyshev/infinity norm - int xx = x + dx, yy = y + dy; - if (0 <= xx && xx < size && 0 <= yy && yy < size) - setFunctionModule(xx, yy, dist != 2 && dist != 4); - } - } -} - - -void QrCode::drawAlignmentPattern(int x, int y) { - for (int dy = -2; dy <= 2; dy++) { - for (int dx = -2; dx <= 2; dx++) - setFunctionModule(x + dx, y + dy, std::max(std::abs(dx), std::abs(dy)) != 1); - } -} - - -void QrCode::setFunctionModule(int x, int y, bool isBlack) { - size_t ux = static_cast(x); - size_t uy = static_cast(y); - modules .at(uy).at(ux) = isBlack; - isFunction.at(uy).at(ux) = true; -} - - -bool QrCode::module(int x, int y) const { - return modules.at(static_cast(y)).at(static_cast(x)); -} - - -vector QrCode::addEccAndInterleave(const vector &data) const { - if (data.size() != static_cast(getNumDataCodewords(version, errorCorrectionLevel))) - throw std::invalid_argument("Invalid argument"); - - // Calculate parameter numbers - int numBlocks = NUM_ERROR_CORRECTION_BLOCKS[static_cast(errorCorrectionLevel)][version]; - int blockEccLen = ECC_CODEWORDS_PER_BLOCK [static_cast(errorCorrectionLevel)][version]; - int rawCodewords = getNumRawDataModules(version) / 8; - int numShortBlocks = numBlocks - rawCodewords % numBlocks; - int shortBlockLen = rawCodewords / numBlocks; - - // Split data into blocks and append ECC to each block - vector > blocks; - const vector rsDiv = reedSolomonComputeDivisor(blockEccLen); - for (int i = 0, k = 0; i < numBlocks; i++) { - vector dat(data.cbegin() + k, data.cbegin() + (k + shortBlockLen - blockEccLen + (i < numShortBlocks ? 0 : 1))); - k += static_cast(dat.size()); - const vector ecc = reedSolomonComputeRemainder(dat, rsDiv); - if (i < numShortBlocks) - dat.push_back(0); - dat.insert(dat.end(), ecc.cbegin(), ecc.cend()); - blocks.push_back(std::move(dat)); - } - - // Interleave (not concatenate) the bytes from every block into a single sequence - vector result; - for (size_t i = 0; i < blocks.at(0).size(); i++) { - for (size_t j = 0; j < blocks.size(); j++) { - // Skip the padding byte in short blocks - if (i != static_cast(shortBlockLen - blockEccLen) || j >= static_cast(numShortBlocks)) - result.push_back(blocks.at(j).at(i)); - } - } - if (result.size() != static_cast(rawCodewords)) - throw std::logic_error("Assertion error"); - return result; -} - - -void QrCode::drawCodewords(const vector &data) { - if (data.size() != static_cast(getNumRawDataModules(version) / 8)) - throw std::invalid_argument("Invalid argument"); - - size_t i = 0; // Bit index into the data - // Do the funny zigzag scan - for (int right = size - 1; right >= 1; right -= 2) { // Index of right column in each column pair - if (right == 6) - right = 5; - for (int vert = 0; vert < size; vert++) { // Vertical counter - for (int j = 0; j < 2; j++) { - size_t x = static_cast(right - j); // Actual x coordinate - bool upward = ((right + 1) & 2) == 0; - size_t y = static_cast(upward ? size - 1 - vert : vert); // Actual y coordinate - if (!isFunction.at(y).at(x) && i < data.size() * 8) { - modules.at(y).at(x) = getBit(data.at(i >> 3), 7 - static_cast(i & 7)); - i++; - } - // If this QR Code has any remainder bits (0 to 7), they were assigned as - // 0/false/white by the constructor and are left unchanged by this method - } - } - } - if (i != data.size() * 8) - throw std::logic_error("Assertion error"); -} - - -void QrCode::applyMask(int msk) { - if (msk < 0 || msk > 7) - throw std::domain_error("Mask value out of range"); - size_t sz = static_cast(size); - for (size_t y = 0; y < sz; y++) { - for (size_t x = 0; x < sz; x++) { - bool invert; - switch (msk) { - case 0: invert = (x + y) % 2 == 0; break; - case 1: invert = y % 2 == 0; break; - case 2: invert = x % 3 == 0; break; - case 3: invert = (x + y) % 3 == 0; break; - case 4: invert = (x / 3 + y / 2) % 2 == 0; break; - case 5: invert = x * y % 2 + x * y % 3 == 0; break; - case 6: invert = (x * y % 2 + x * y % 3) % 2 == 0; break; - case 7: invert = ((x + y) % 2 + x * y % 3) % 2 == 0; break; - default: throw std::logic_error("Assertion error"); - } - modules.at(y).at(x) = modules.at(y).at(x) ^ (invert & !isFunction.at(y).at(x)); - } - } -} - - -long QrCode::getPenaltyScore() const { - long result = 0; - - // Adjacent modules in row having same color, and finder-like patterns - for (int y = 0; y < size; y++) { - bool runColor = false; - int runX = 0; - std::array runHistory = {}; - for (int x = 0; x < size; x++) { - if (module(x, y) == runColor) { - runX++; - if (runX == 5) - result += PENALTY_N1; - else if (runX > 5) - result++; - } else { - finderPenaltyAddHistory(runX, runHistory); - if (!runColor) - result += finderPenaltyCountPatterns(runHistory) * PENALTY_N3; - runColor = module(x, y); - runX = 1; - } - } - result += finderPenaltyTerminateAndCount(runColor, runX, runHistory) * PENALTY_N3; - } - // Adjacent modules in column having same color, and finder-like patterns - for (int x = 0; x < size; x++) { - bool runColor = false; - int runY = 0; - std::array runHistory = {}; - for (int y = 0; y < size; y++) { - if (module(x, y) == runColor) { - runY++; - if (runY == 5) - result += PENALTY_N1; - else if (runY > 5) - result++; - } else { - finderPenaltyAddHistory(runY, runHistory); - if (!runColor) - result += finderPenaltyCountPatterns(runHistory) * PENALTY_N3; - runColor = module(x, y); - runY = 1; - } - } - result += finderPenaltyTerminateAndCount(runColor, runY, runHistory) * PENALTY_N3; - } - - // 2*2 blocks of modules having same color - for (int y = 0; y < size - 1; y++) { - for (int x = 0; x < size - 1; x++) { - bool color = module(x, y); - if ( color == module(x + 1, y) && - color == module(x, y + 1) && - color == module(x + 1, y + 1)) - result += PENALTY_N2; - } - } - - // Balance of black and white modules - int black = 0; - for (const vector &row : modules) { - for (bool color : row) { - if (color) - black++; - } - } - int total = size * size; // Note that size is odd, so black/total != 1/2 - // Compute the smallest integer k >= 0 such that (45-5k)% <= black/total <= (55+5k)% - int k = static_cast((std::abs(black * 20L - total * 10L) + total - 1) / total) - 1; - result += k * PENALTY_N4; - return result; -} - - -vector QrCode::getAlignmentPatternPositions() const { - if (version == 1) - return vector(); - else { - int numAlign = version / 7 + 2; - int step = (version == 32) ? 26 : - (version*4 + numAlign*2 + 1) / (numAlign*2 - 2) * 2; - vector result; - for (int i = 0, pos = size - 7; i < numAlign - 1; i++, pos -= step) - result.insert(result.begin(), pos); - result.insert(result.begin(), 6); - return result; - } -} - - -int QrCode::getNumRawDataModules(int ver) { - if (ver < MIN_VERSION || ver > MAX_VERSION) - throw std::domain_error("Version number out of range"); - int result = (16 * ver + 128) * ver + 64; - if (ver >= 2) { - int numAlign = ver / 7 + 2; - result -= (25 * numAlign - 10) * numAlign - 55; - if (ver >= 7) - result -= 36; - } - if (!(208 <= result && result <= 29648)) - throw std::logic_error("Assertion error"); - return result; -} - - -int QrCode::getNumDataCodewords(int ver, Ecc ecl) { - return getNumRawDataModules(ver) / 8 - - ECC_CODEWORDS_PER_BLOCK [static_cast(ecl)][ver] - * NUM_ERROR_CORRECTION_BLOCKS[static_cast(ecl)][ver]; -} - - -vector QrCode::reedSolomonComputeDivisor(int degree) { - if (degree < 1 || degree > 255) - throw std::domain_error("Degree out of range"); - // Polynomial coefficients are stored from highest to lowest power, excluding the leading term which is always 1. - // For example the polynomial x^3 + 255x^2 + 8x + 93 is stored as the uint8 array {255, 8, 93}. - vector result(static_cast(degree)); - result.at(result.size() - 1) = 1; // Start off with the monomial x^0 - - // Compute the product polynomial (x - r^0) * (x - r^1) * (x - r^2) * ... * (x - r^{degree-1}), - // and drop the highest monomial term which is always 1x^degree. - // Note that r = 0x02, which is a generator element of this field GF(2^8/0x11D). - uint8_t root = 1; - for (int i = 0; i < degree; i++) { - // Multiply the current product by (x - r^i) - for (size_t j = 0; j < result.size(); j++) { - result.at(j) = reedSolomonMultiply(result.at(j), root); - if (j + 1 < result.size()) - result.at(j) ^= result.at(j + 1); - } - root = reedSolomonMultiply(root, 0x02); - } - return result; -} - - -vector QrCode::reedSolomonComputeRemainder(const vector &data, const vector &divisor) { - vector result(divisor.size()); - for (uint8_t b : data) { // Polynomial division - uint8_t factor = b ^ result.at(0); - result.erase(result.begin()); - result.push_back(0); - for (size_t i = 0; i < result.size(); i++) - result.at(i) ^= reedSolomonMultiply(divisor.at(i), factor); - } - return result; -} - - -uint8_t QrCode::reedSolomonMultiply(uint8_t x, uint8_t y) { - // Russian peasant multiplication - int z = 0; - for (int i = 7; i >= 0; i--) { - z = (z << 1) ^ ((z >> 7) * 0x11D); - z ^= ((y >> i) & 1) * x; - } - if (z >> 8 != 0) - throw std::logic_error("Assertion error"); - return static_cast(z); -} - - -int QrCode::finderPenaltyCountPatterns(const std::array &runHistory) const { - int n = runHistory.at(1); - if (n > size * 3) - throw std::logic_error("Assertion error"); - bool core = n > 0 && runHistory.at(2) == n && runHistory.at(3) == n * 3 && runHistory.at(4) == n && runHistory.at(5) == n; - return (core && runHistory.at(0) >= n * 4 && runHistory.at(6) >= n ? 1 : 0) - + (core && runHistory.at(6) >= n * 4 && runHistory.at(0) >= n ? 1 : 0); -} - - -int QrCode::finderPenaltyTerminateAndCount(bool currentRunColor, int currentRunLength, std::array &runHistory) const { - if (currentRunColor) { // Terminate black run - finderPenaltyAddHistory(currentRunLength, runHistory); - currentRunLength = 0; - } - currentRunLength += size; // Add white border to final run - finderPenaltyAddHistory(currentRunLength, runHistory); - return finderPenaltyCountPatterns(runHistory); -} - - -void QrCode::finderPenaltyAddHistory(int currentRunLength, std::array &runHistory) const { - if (runHistory.at(0) == 0) - currentRunLength += size; // Add white border to initial run - std::copy_backward(runHistory.cbegin(), runHistory.cend() - 1, runHistory.end()); - runHistory.at(0) = currentRunLength; -} - - -bool QrCode::getBit(long x, int i) { - return ((x >> i) & 1) != 0; -} - - -/*---- Tables of constants ----*/ - -const int QrCode::PENALTY_N1 = 3; -const int QrCode::PENALTY_N2 = 3; -const int QrCode::PENALTY_N3 = 40; -const int QrCode::PENALTY_N4 = 10; - - -const int8_t QrCode::ECC_CODEWORDS_PER_BLOCK[4][41] = { - // Version: (note that index 0 is for padding, and is set to an illegal value) - //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, 37, 38, 39, 40 Error correction level - {-1, 7, 10, 15, 20, 26, 18, 20, 24, 30, 18, 20, 24, 26, 30, 22, 24, 28, 30, 28, 28, 28, 28, 30, 30, 26, 28, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30}, // Low - {-1, 10, 16, 26, 18, 24, 16, 18, 22, 22, 26, 30, 22, 22, 24, 24, 28, 28, 26, 26, 26, 26, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28, 28}, // Medium - {-1, 13, 22, 18, 26, 18, 24, 18, 22, 20, 24, 28, 26, 24, 20, 30, 24, 28, 28, 26, 30, 28, 30, 30, 30, 30, 28, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30}, // Quartile - {-1, 17, 28, 22, 16, 22, 28, 26, 26, 24, 28, 24, 28, 22, 24, 24, 30, 28, 28, 26, 28, 30, 24, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30, 30}, // High -}; - -const int8_t QrCode::NUM_ERROR_CORRECTION_BLOCKS[4][41] = { - // Version: (note that index 0 is for padding, and is set to an illegal value) - //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, 37, 38, 39, 40 Error correction level - {-1, 1, 1, 1, 1, 1, 2, 2, 2, 2, 4, 4, 4, 4, 4, 6, 6, 6, 6, 7, 8, 8, 9, 9, 10, 12, 12, 12, 13, 14, 15, 16, 17, 18, 19, 19, 20, 21, 22, 24, 25}, // Low - {-1, 1, 1, 1, 2, 2, 4, 4, 4, 5, 5, 5, 8, 9, 9, 10, 10, 11, 13, 14, 16, 17, 17, 18, 20, 21, 23, 25, 26, 28, 29, 31, 33, 35, 37, 38, 40, 43, 45, 47, 49}, // Medium - {-1, 1, 1, 2, 2, 4, 4, 6, 6, 8, 8, 8, 10, 12, 16, 12, 17, 16, 18, 21, 20, 23, 23, 25, 27, 29, 34, 34, 35, 38, 40, 43, 45, 48, 51, 53, 56, 59, 62, 65, 68}, // Quartile - {-1, 1, 1, 2, 4, 4, 4, 5, 6, 8, 8, 11, 11, 16, 16, 18, 16, 19, 21, 25, 25, 25, 34, 30, 32, 35, 37, 40, 42, 45, 48, 51, 54, 57, 60, 63, 66, 70, 74, 77, 81}, // High -}; - - -data_too_long::data_too_long(const std::string &msg) : - std::length_error(msg) {} - - - -BitBuffer::BitBuffer() - : std::vector() {} - - -void BitBuffer::appendBits(std::uint32_t val, int len) { - if (len < 0 || len > 31 || val >> len != 0) - throw std::domain_error("Value out of range"); - for (int i = len - 1; i >= 0; i--) // Append bit by bit - this->push_back(((val >> i) & 1) != 0); -} - -} diff --git a/third_party/snpe/include/SnpeUdo/UdoBase.h b/third_party/snpe/include/SnpeUdo/UdoBase.h deleted file mode 100644 index 7b25679..0000000 --- a/third_party/snpe/include/SnpeUdo/UdoBase.h +++ /dev/null @@ -1,537 +0,0 @@ -//============================================================================== -// -// Copyright (c) 2019-2021 Qualcomm Technologies, Inc. -// All Rights Reserved. -// Confidential and Proprietary - Qualcomm Technologies, Inc. -// -//============================================================================== - -#ifndef SNPE_UDO_BASE_H -#define SNPE_UDO_BASE_H - -#include - -// Provide values to use for API version. -#define API_VERSION_MAJOR 1 -#define API_VERSION_MINOR 6 -#define API_VERSION_TEENY 0 - -/** @addtogroup c_plus_plus_apis C++ -@{ */ - -// Defines a bitmask of enum values. -typedef uint32_t SnpeUdo_Bitmask_t; -typedef SnpeUdo_Bitmask_t Udo_Bitmask_t; - -// A string of characters, rather than an array of bytes. -// Assumed to be UTF-8. -typedef char* SnpeUdo_String_t; -typedef SnpeUdo_String_t Udo_String_t; - -// The maximum allowable length of a SnpeUdo_String_t in bytes, -// including null terminator. SNPE will truncate strings longer -// than this. -#define SNPE_UDO_MAX_STRING_SIZE 1024 - -/** - * An enum which holds the various error types. - * The error types are divided to classes : - * 0 - 99 : generic errors - * 100 - 200 : errors related to configuration - * - */ -typedef enum -{ - /// No Error - SNPE_UDO_NO_ERROR = 0, UDO_NO_ERROR = 0, - /// Unsupported value for core type - SNPE_UDO_WRONG_CORE = 1, UDO_WRONG_CORE = 1, - /// Invalid attribute/argument passed into UDO API - SNPE_UDO_INVALID_ARGUMENT = 2, UDO_INVALID_ARGUMENT = 2, - /// Unsupported feature error - SNPE_UDO_UNSUPPORTED_FEATURE = 3, UDO_UNSUPPORTED_FEATURE = 3, - /// Error relating to memory allocation - SNPE_UDO_MEM_ALLOC_ERROR = 4, UDO_MEM_ALLOC_ERROR = 4, - /* Configuration Specific errors */ - /// No op with given attributes available in library - SNPE_UDO_WRONG_OPERATION = 100, UDO_WRONG_OPERATION = 100, - /// Unsupported value for core type in UDO configuration - SNPE_UDO_WRONG_CORE_TYPE = 101, UDO_WRONG_CORE_TYPE = 101, - /// Wrong number of params in UDO definition - SNPE_UDO_WRONG_NUM_OF_PARAMS = 102, UDO_WRONG_NUM_OF_PARAMS = 102, - /// Wrong number of dimensions for tensor(s) in UDO definition - SNPE_UDO_WRONG_NUM_OF_DIMENSIONS = 103, UDO_WRONG_NUM_OF_DIMENSIONS = 103, - /// Wrong number of input tensors in UDO definition - SNPE_UDO_WRONG_NUM_OF_INPUTS = 104, UDO_WRONG_NUM_OF_INPUTS = 104, - /// Wrong number of output tensors in UDO definition - SNPE_UDO_WRONG_NUM_OF_OUTPUTS = 105, UDO_WRONG_NUM_OF_OUTPUTS = 105, - SNPE_UDO_PROGRAM_CACHE_NOT_FOUND = 106, UDO_PROGRAM_CACHE_NOT_FOUND = 106, - SNPE_UDO_UNKNOWN_ERROR = 0xFFFFFFFF, UDO_UNKNOWN_ERROR = 0xFFFFFFFF -} SnpeUdo_ErrorType_t; - -typedef SnpeUdo_ErrorType_t Udo_ErrorType_t; - -/** - * An enum which holds the various data types. - * Designed to be used as single values or combined into a bitfield parameter - * (0x1, 0x2, 0x4, etc) - * \n FIXED_XX types are targeted for data in tensors. - * \n UINT / INT types are targeted for scalar params - */ -typedef enum -{ - /// data type: 16-bit floating point - SNPE_UDO_DATATYPE_FLOAT_16 = 0x01, UDO_DATATYPE_FLOAT_16 = 0x01, - /// data type: 32-bit floating point - SNPE_UDO_DATATYPE_FLOAT_32 = 0x02, UDO_DATATYPE_FLOAT_32 = 0x02, - /// data type: 4-bit fixed point - SNPE_UDO_DATATYPE_FIXED_4 = 0x04, UDO_DATATYPE_FIXED_4 = 0x04, - /// data type: 8-bit fixed point - SNPE_UDO_DATATYPE_FIXED_8 = 0x08, UDO_DATATYPE_FIXED_8 = 0x08, - /// data type: 16-bit fixed point - SNPE_UDO_DATATYPE_FIXED_16 = 0x10, UDO_DATATYPE_FIXED_16 = 0x10, - /// data type: 32-bit fixed point - SNPE_UDO_DATATYPE_FIXED_32 = 0x20, UDO_DATATYPE_FIXED_32 = 0x20, - /// data type: 8-bit unsigned integer - SNPE_UDO_DATATYPE_UINT_8 = 0x100, UDO_DATATYPE_UINT_8 = 0x100, - /// data type: 16-bit unsigned integer - SNPE_UDO_DATATYPE_UINT_16 = 0x200, UDO_DATATYPE_UINT_16 = 0x200, - /// data type: 32-bit unsigned integer - SNPE_UDO_DATATYPE_UINT_32 = 0x400, UDO_DATATYPE_UINT_32 = 0x400, - /// data type: 8-bit signed integer - SNPE_UDO_DATATYPE_INT_8 = 0x1000, UDO_DATATYPE_INT_8 = 0x1000, - /// data type: 16-bit signed integer - SNPE_UDO_DATATYPE_INT_16 = 0x2000, UDO_DATATYPE_INT_16 = 0x2000, - /// data type: 32-bit signed integer - SNPE_UDO_DATATYPE_INT_32 = 0x4000, UDO_DATATYPE_INT_32 = 0x4000, - SNPE_UDO_DATATYPE_LAST = 0xFFFFFFFF, UDO_DATATYPE_LAST = 0xFFFFFFFF -} SnpeUdo_DataType_t; - -typedef SnpeUdo_DataType_t Udo_DataType_t; - -/** - * An enum which holds the various layouts. - * Designed to be used as single values or combined into a bitfield parameter - * (0x1, 0x2, 0x4, etc) - */ -typedef enum -{ - /// data layout (4D): NHWC (batch-height-width-channel) - SNPE_UDO_LAYOUT_NHWC = 0x01, UDO_LAYOUT_NHWC = 0x01, - /// data layout (4D): NCHW (batch-channel-height-width) - SNPE_UDO_LAYOUT_NCHW = 0x02, UDO_LAYOUT_NCHW = 0x02, - /// data layout (5D): NDHWC (batch-dimension-height-width-channel) - SNPE_UDO_LAYOUT_NDHWC = 0x04, UDO_LAYOUT_NDHWC = 0x04, - SNPE_UDO_LAYOUT_GPU_OPTIMAL1 = 0x08, UDO_LAYOUT_GPU_OPTIMAL1 = 0x08, - SNPE_UDO_LAYOUT_GPU_OPTIMAL2 = 0x10, UDO_LAYOUT_GPU_OPTIMAL2 = 0x10, - SNPE_UDO_LAYOUT_DSP_OPTIMAL1 = 0x11, UDO_LAYOUT_DSP_OPTIMAL1 = 0x11, - SNPE_UDO_LAYOUT_DSP_OPTIMAL2 = 0x12, UDO_LAYOUT_DSP_OPTIMAL2 = 0x12, - // Indicates no data will be allocated for this tensor. - // Used to specify optional inputs/outputs positionally. - SNPE_UDO_LAYOUT_NULL = 0x13, UDO_LAYOUT_NULL = 0x13, - SNPE_UDO_LAYOUT_LAST = 0xFFFFFFFF, UDO_LAYOUT_LAST = 0xFFFFFFFF -} SnpeUdo_TensorLayout_t; - -typedef SnpeUdo_TensorLayout_t Udo_TensorLayout_t; - -/** - * An enum which holds the UDO library Core type . - * Designed to be used as single values or combined into a bitfield parameter - * (0x1, 0x2, 0x4, etc) - */ -typedef enum -{ - /// Library target IP Core is undefined - SNPE_UDO_CORETYPE_UNDEFINED = 0x00, UDO_CORETYPE_UNDEFINED = 0x00, - /// Library target IP Core is CPU - SNPE_UDO_CORETYPE_CPU = 0x01, UDO_CORETYPE_CPU = 0x01, - /// Library target IP Core is GPU - SNPE_UDO_CORETYPE_GPU = 0x02, UDO_CORETYPE_GPU = 0x02, - /// Library target IP Core is DSP - SNPE_UDO_CORETYPE_DSP = 0x04, UDO_CORETYPE_DSP = 0x04, - SNPE_UDO_CORETYPE_LAST = 0xFFFFFFFF, UDO_CORETYPE_LAST = 0xFFFFFFFF -} SnpeUdo_CoreType_t; - -typedef SnpeUdo_CoreType_t Udo_CoreType_t; - -/** - * An enum to specify the parameter type : Scalar or Tensor - */ -typedef enum -{ - /// UDO static param type: scalar - SNPE_UDO_PARAMTYPE_SCALAR = 0x00, UDO_PARAMTYPE_SCALAR = 0x00, - /// UDO static param type: string - SNPE_UDO_PARAMTYPE_STRING = 0x01, UDO_PARAMTYPE_STRING = 0x01, - /// UDO static param type: tensor - SNPE_UDO_PARAMTYPE_TENSOR = 0x02, UDO_PARAMTYPE_TENSOR = 0x02, - SNPE_UDO_PARAMTYPE_LAST = 0xFFFFFFFF, UDO_PARAMTYPE_LAST = 0xFFFFFFFF -} SnpeUdo_ParamType_t; - -typedef SnpeUdo_ParamType_t Udo_ParamType_t; - -/** - * An enum to specify quantization type - */ -typedef enum -{ - /// Tensor Quantization type: NONE. Signifies unquantized tensor data - SNPE_UDO_QUANTIZATION_NONE = 0x00, UDO_QUANTIZATION_NONE = 0x00, - /// Tensor Quantization type: Tensorflow-style - SNPE_UDO_QUANTIZATION_TF = 0x01, UDO_QUANTIZATION_TF = 0x01, - SNPE_UDO_QUANTIZATION_QMN = 0x02, UDO_QUANTIZATION_QMN = 0x02, - SNPE_UDO_QUANTIZATION_LAST = 0xFFFFFFFF, UDO_QUANTIZATION_LAST = 0xFFFFFFFF -} SnpeUdo_QuantizationType_t; - -typedef SnpeUdo_QuantizationType_t Udo_QuantizationType_t; - -/** - * @brief A struct which is used to provide a version number using 3 values : major, minor, teeny - * - */ -typedef struct -{ - /// version field: major - for backward-incompatible changes - uint32_t major; - /// version field: minor - for backward-compatible feature updates - uint32_t minor; - /// version field: teeny - for minor bug-fixes and clean-up - uint32_t teeny; -} SnpeUdo_Version_t; - -typedef SnpeUdo_Version_t Udo_Version_t; - -/** - * @brief A struct returned from version query, contains the Library version and API version - * - */ -typedef struct -{ - /// Version of UDO library. Controlled by users - SnpeUdo_Version_t libVersion; - /// Version of SNPE UDO API used in compiling library. Determined by SNPE - SnpeUdo_Version_t apiVersion; -} SnpeUdo_LibVersion_t; - -/** - * @brief A struct returned from version query, contains the package version - * - */ -typedef struct -{ - /// Version of UDO API used in package. - Udo_Version_t apiVersion; -} Udo_PkgVersion_t; - -/** - * @brief A union to hold the value of a generic type. Allows defining a parameter struct - * in a generic way, with a "value" location that holds the data regardless of the type. - * - */ -typedef union -{ - /// value type: float - float floatValue; - /// value type: unsigned 32-bit integer - uint32_t uint32Value; - /// value type: signed 32-bit integer - int32_t int32Value; - /// value type: unsigned 16-bit integer - uint16_t uint16Value; - /// value type: signed 16-bit integer - int16_t int16Value; - /// value type: unsigned 8-bit integer - uint8_t uint8Value; - /// value type: signed 8-bit integer - int8_t int8Value; -} SnpeUdo_Value_t; - -typedef SnpeUdo_Value_t Udo_Value_t; - -/** - * @brief A struct which defines a scalar parameter : name, data type, and union of values - * - */ -typedef struct -{ - /// The parameter data type : float, int, etc. - SnpeUdo_DataType_t dataType; - /// a union of specified type which holds the data - SnpeUdo_Value_t dataValue; -} SnpeUdo_ScalarParam_t; - -typedef SnpeUdo_ScalarParam_t Udo_ScalarParam_t; - -/** - * @brief A struct which defines the quantization parameters in case of Tensorflow style quantization - * - */ -typedef struct -{ - /// minimum value of the quantization range of data - float minValue; - /// maximum value of the quantization range of data - float maxValue; -} SnpeUdo_TFQuantize_t; - -typedef SnpeUdo_TFQuantize_t Udo_TFQuantize_t; - -/** - * @brief A struct which defines the quantization type, and union of supported quantization structs - * - */ -typedef struct -{ - /// quantization type (only TF-style currently supported) - SnpeUdo_QuantizationType_t quantizeType; - union - { - /// TF-style min-max quantization ranges - SnpeUdo_TFQuantize_t TFParams; - }; -} SnpeUdo_QuantizeParams_t; - -typedef SnpeUdo_QuantizeParams_t Udo_QuantizeParams_t; - -/** - * @brief A struct which defines the datatype associated with a specified core-type - * This should be used to denote the datatypes for a single tensor info, depending - * on the intended execution core. - * - */ -typedef struct -{ - /// The IP Core - SnpeUdo_CoreType_t coreType; - /// The associated datatype for this coreType - SnpeUdo_DataType_t dataType; -} SnpeUdo_PerCoreDatatype_t; - -typedef SnpeUdo_PerCoreDatatype_t Udo_PerCoreDatatype_t; - -/** - * @brief A struct which defines a tensor parameter : name, data type, layout, quantization, more. - * Also holds a pointer to the tensor data. - * - */ -typedef struct -{ - /// The maximum allowable dimensions of the tensor. The memory held in - /// _tensorData_ is guaranteed to be large enough for this. - uint32_t* maxDimensions; - /// The current dimensions of the tensor. An operation may modify the current - /// dimensions of its output, to indicate cases where the output has been - /// "resized". - /// Note that for static parameters, the current and max dimensions must - /// match. - uint32_t* currDimensions; - /// Quantization params applicable to the tensor. Currently only supports - /// Tensorflow quantization style. - SnpeUdo_QuantizeParams_t quantizeParams; - /// Number of dimensions to the tensor: 3D, 4D, etc. - uint32_t tensorRank; - /// The parameter data type: float, int, etc. - SnpeUdo_DataType_t dataType; - /// The tensor layout type: NCHW, NHWC, etc. - SnpeUdo_TensorLayout_t layout; - /// Opaque pointer to tensor data. User may be required to re-interpret the pointer - /// based on core-specific definitions. - void* tensorData; -} SnpeUdo_TensorParam_t; - -typedef SnpeUdo_TensorParam_t Udo_TensorParam_t; - -/** - * @brief A struct which defines tensor information for activation tensors only - * - * It describes an activation tensor object using its name, the intended layout and the datatype - * it will take depending on the intended runtime core. The repeated field indicates that - * that the tensor info describes several input/output activation tensors, which all share the - * aforementioned properties. - */ -typedef struct -{ - /// The tensor name - SnpeUdo_String_t tensorName; - /// The tensor layout type: NCHW, NHWC, etc. - SnpeUdo_TensorLayout_t layout; - /// The per core datatype: {SNPE_UDO_DATATYPE, SNPE_UDO_CORE_TYPE} - SnpeUdo_PerCoreDatatype_t* perCoreDatatype; - /// A boolean field indicating that this tensorinfo will be repeated e.x for ops such as Concat or Split - bool repeated; - /// A boolean field indicating whether input is static or not. - bool isStatic; -} SnpeUdo_TensorInfo_t; - -typedef SnpeUdo_TensorInfo_t Udo_TensorInfo_t; - -/** - * @brief struct which defines a UDO parameter - a union of scalar, tensor and string parameters - * - */ -typedef struct -{ - /// Type is scalar or tensor - SnpeUdo_ParamType_t paramType; - /// The param name, for example : "offset", "activation_type" - SnpeUdo_String_t paramName; - union - { - /// scalar param value - SnpeUdo_ScalarParam_t scalarParam; - /// tensor param value - SnpeUdo_TensorParam_t tensorParam; - /// string param value - SnpeUdo_String_t stringParam; - }; -} SnpeUdo_Param_t; - -typedef SnpeUdo_Param_t Udo_Param_t; - -/** - * @brief A struct which defines Operation information which is specific for IP core (CPU, GPU, DSP ...) - * - */ -typedef struct -{ - /// The IP Core - SnpeUdo_CoreType_t udoCoreType; - /// Bitmask, defines supported internal calculation types (like FLOAT_32, etc) - /// Based on SnpeUdo_DataType - SnpeUdo_Bitmask_t operationCalculationTypes; -} SnpeUdo_OpCoreInfo_t; - -typedef SnpeUdo_OpCoreInfo_t Udo_OpCoreInfo_t; - -/** - * @brief A struct which defines the common and core-specific Operation information - * - */ -typedef struct -{ - /// Operation type - SnpeUdo_String_t operationType; - /// A bitmask describing which IP Cores (CPU, GPU, DSP ...) support this operation - /// Translated based on SnpeUdo_CoreType - SnpeUdo_Bitmask_t supportedByCores; - /// Number of static parameters defined by the op - uint32_t numOfStaticParams; - /// Array of static parameters. Can be scalar or tensor params - SnpeUdo_Param_t* staticParams; - /// Number of input tensors this op receives - uint32_t numOfInputs; - /// Array of input tensor names to this operation - SnpeUdo_String_t* inputNames; - /// Number of output tensors this op receives - uint32_t numOfOutputs; - /// Array of output tensor names to this operation - SnpeUdo_String_t* outputNames; - /// Number of cores that the op can execute on - uint32_t numOfCoreInfo; - /// Array of per-core information entries - SnpeUdo_OpCoreInfo_t* opPerCoreInfo; - /// Array of input tensor infos for this operation - SnpeUdo_TensorInfo_t* inputInfos; - /// Array of output tensor infos for this operation - SnpeUdo_TensorInfo_t* outputInfos; -} SnpeUdo_OperationInfo_t; - -typedef SnpeUdo_OperationInfo_t Udo_OperationInfo_t; - -/** - * @brief A struct which provides the implementation library info : type, name - * - */ -typedef struct -{ - /// Defines the IP Core that this implementation library is targeting - SnpeUdo_CoreType_t udoCoreType; - /// library name. will be looked at in the standard library path - SnpeUdo_String_t libraryName; -} SnpeUdo_LibraryInfo_t; - -typedef SnpeUdo_LibraryInfo_t Udo_LibraryInfo_t; - -/** - * @brief A struct returned by the registration library and contains information on the UDO package : - * name, operations, libraries, etc. - * - */ -typedef struct -{ - /// A string containing the package name - SnpeUdo_String_t packageName; - /// A bitmask describing supported IP cores (CPU, GPU, DSP ...) - /// Translated based on SnpeUdo_CoreType - SnpeUdo_Bitmask_t supportedCoreTypes; - /// The number of implementation libraries in the package - uint32_t numOfImplementationLib; - /// Array of implementation libraries names/types - SnpeUdo_LibraryInfo_t* implementationLib; - /// A string containing all operation types separated by space - SnpeUdo_String_t operationsString; - /// Number of supported operations - uint32_t numOfOperations; - /// Array of Operation info structs. Each entry describes one - /// Operation (name, params, inputs, outputs) - SnpeUdo_OperationInfo_t* operationsInfo; -} SnpeUdo_RegInfo_t; - -typedef SnpeUdo_RegInfo_t Udo_RegInfo_t; - -/** -* @brief A struct returned by the implementation library and contains information on the -* specific library: name, IP Core, operations, etc. -* -*/ -typedef struct -{ - /// Defines the IP Core that this implementation library is targeting - SnpeUdo_CoreType_t udoCoreType; - /// A string containing the package name - SnpeUdo_String_t packageName; - /// A string containing all operation types separated by space - SnpeUdo_String_t operationsString; - /// Number of supported operations - uint32_t numOfOperations; -} SnpeUdo_ImpInfo_t; - -typedef SnpeUdo_ImpInfo_t Udo_ImpInfo_t; - -/** - * @brief This struct defines an operation. It is used for validation - * or creation of an operation. - * In case of using it for creation, the static params which are tensors - * contain pointers to the real data (weights, for example), and input/output - * tensors also include pointers to the buffers used. - */ -typedef struct -{ - /// The IP Core that the operation is defined for - CPU, GPU, DSP... - SnpeUdo_CoreType_t udoCoreType; - /// Operation type - SnpeUdo_String_t operationType; - /// The number of static parameters provided in the staticParams array. - /// this number has to match the number provided by the UDO Registration library information - uint32_t numOfStaticParams; - /// Array of static parameters - SnpeUdo_Param_t* staticParams; - /// The number of input parameters provided in inputs array. - /// this number has to match the number provided by the UDO Registration library information - uint32_t numOfInputs; - /// Array of input tensors, providing layout, data type, sizes, etc - /// When used to create an operation, also contains the initial location of the data - SnpeUdo_TensorParam_t* inputs; - /// The number of output parameters provided in inputs array. - /// this number has to match the number provided by the UDO Registration library information - uint32_t numOfOutputs; - /// Array of output tensors, providing layout, data type, sizes, etc - /// When used to create an operation, also contains the initial location of the data - SnpeUdo_TensorParam_t* outputs; -} SnpeUdo_OpDefinition_t; - -typedef SnpeUdo_OpDefinition_t Udo_OpDefinition_t; - -/** @} */ /* end_addtogroup c_plus_plus_apis C++ */ - -#endif //SNPE_UDO_BASE_H diff --git a/third_party/snpe/include/SnpeUdo/UdoImpl.h b/third_party/snpe/include/SnpeUdo/UdoImpl.h deleted file mode 100644 index a0cb648..0000000 --- a/third_party/snpe/include/SnpeUdo/UdoImpl.h +++ /dev/null @@ -1,343 +0,0 @@ -//============================================================================== -// -// Copyright (c) 2019-2021 Qualcomm Technologies, Inc. -// All Rights Reserved. -// Confidential and Proprietary - Qualcomm Technologies, Inc. -// -//============================================================================== - -#ifndef SNPE_UDO_IMPL_H -#define SNPE_UDO_IMPL_H - -#include - -#include "SnpeUdo/UdoShared.h" - -#ifdef __cplusplus -extern "C" -{ -#endif - -/** @addtogroup c_plus_plus_apis C++ -@{ */ - -typedef struct _SnpeUdo_OpFactory_t* SnpeUdo_OpFactory_t; -typedef struct _SnpeUdo_Operation_t* SnpeUdo_Operation_t; - -typedef SnpeUdo_OpFactory_t Udo_OpFactory_t; -typedef SnpeUdo_Operation_t Udo_Operation_t; - -/** - * @brief Initialize the shared library's data structures. Calling any other - * library function before this one will result in error. - * - * @param[in] globalInfrastructure Global core-specific infrastructure to be - * used by operations created in this library. The definition and - * semantics of this object will be defined in the corresponding - * implementation header for the core type. - * @return Error code - */ -SnpeUdo_ErrorType_t -SnpeUdo_initImplLibrary(void* globalInfrastructure); - -typedef SnpeUdo_ErrorType_t -(*SnpeUdo_InitImplLibraryFunction_t)(void*); - -/** - * @brief A function to query the API version of the UDO implementation library. - * The function populates a SnpeUdo_LibVersion_t struct, which contains a SnpeUdo_Version_t - * struct for API version and library version. - * - * @param[in, out] version A pointer to struct which contains major, minor, teeny information for - * library and api versions. - * - * @return Error code - */ -SnpeUdo_ErrorType_t -SnpeUdo_getImplVersion(SnpeUdo_LibVersion_t** version); - -typedef SnpeUdo_ErrorType_t -(*SnpeUdo_getImplVersion_t)(SnpeUdo_LibVersion_t** version); - -/** - * @brief Release the shared library's data structures, and invalidate any - * handles returned by the library. The behavior of any outstanding - * asynchronous calls made to this library when this function is called - * are undefined. All library functions (except SnpeUdo_initImplLibrary) will - * return an error after this function has been successfully called. - * - * It should be possible to call SnpeUdo_initImplLibrary after calling this - * function, and re-initialize the library. - * - * @return Error code - */ -SnpeUdo_ErrorType_t -SnpeUdo_terminateImplLibrary(void); - -typedef SnpeUdo_ErrorType_t -(*SnpeUdo_TerminateImplLibraryFunction_t)(void); - - -/** - * @brief A function to query info on the UDO implementation library. - * The function populates a structure which contains information about - * operations that are part of this library - * - * @param[in, out] implementationInfo A pointer to struct which contains information - * on the operations - * - * @return error code - * - */ -SnpeUdo_ErrorType_t -SnpeUdo_getImpInfo(SnpeUdo_ImpInfo_t** implementationInfo); - -typedef SnpeUdo_ErrorType_t -(*SnpeUdo_GetImpInfoFunction_t)(SnpeUdo_ImpInfo_t** implementationInfo); - -typedef SnpeUdo_GetImpInfoFunction_t Udo_GetImpInfoFunction_t; - -/** - * @brief A function to create an operation factory. - * The function receives the operation type, and an array of static parameters, - * and returns operation factory handler - * - * @param[in] udoCoreType The Core type to create the operation on. An error will - * be returned if this does not match the core type of the library. - * - * @param[in] perFactoryInfrastructure CreateOpFactory infrastructure appropriate to this - * core type. The definition and semantics of this object will be defined - * in the corresponding implementation header for the core type. - * - * @param[in] operationType A string containing Operation type. for example "MY_CONV" - * - * @param[in] numOfStaticParams The number of static parameters. - * - * @param[in] staticParams Array of static parameters - * - * @param[in,out] opFactory Handler to Operation Factory, to be used when creating operations - * - * @return Error Code - */ -SnpeUdo_ErrorType_t -SnpeUdo_createOpFactory(SnpeUdo_CoreType_t udoCoreType, - void* perFactoryInfrastructure, - SnpeUdo_String_t operationType, - uint32_t numOfStaticParams, - SnpeUdo_Param_t* staticParams, - SnpeUdo_OpFactory_t* opFactory); - -typedef SnpeUdo_ErrorType_t -(*SnpeUdo_CreateOpFactoryFunction_t)(SnpeUdo_CoreType_t, - void*, - SnpeUdo_String_t, - uint32_t, - SnpeUdo_Param_t*, - SnpeUdo_OpFactory_t*); - -typedef SnpeUdo_CreateOpFactoryFunction_t Udo_CreateOpFactoryFunction_t; - -/** - * @brief A function to release the resources allocated for an operation factory - * created by this library. - * - * @param[in] factory The operation factory to release. Upon success this handle will be invalidated. - * - * @return Error Code - */ -SnpeUdo_ErrorType_t -SnpeUdo_releaseOpFactory(SnpeUdo_OpFactory_t opFactory); - -typedef SnpeUdo_ErrorType_t -(*SnpeUdo_ReleaseOpFactoryFunction_t)(SnpeUdo_OpFactory_t); - -typedef SnpeUdo_ReleaseOpFactoryFunction_t Udo_ReleaseOpFactoryFunction_t; - -/** - * @brief A function to create an operation from the factory. - * The function receives array of inputs and array of outputs, and creates an operation - * instance, returning the operation instance handler. - * - * @param[in] opFactory OpFactory instance containing the parameters for this operation. - * - * @param[in] perOpInfrastructure Per-Op infrastructure for this operation. The definition - * and semantics of this object will be defined in the implementation header - * appropriate to this core type. - * - * @param[in] numOfInputs The number of input tensors this operation will receive. - * - * @param[in] inputs Array of input tensors, providing both the sizes and initial - * location of the data. - * - * @param[in] numOfOutputs Number of output tensors this operation will produce. - * - * @param[in] outputs Array of output tensors, providing both the sizes and - * initial location of the data. - * - * @param[in,out] operation Handle for newly created operation instance. - * - * @return Error Code - */ -SnpeUdo_ErrorType_t -SnpeUdo_createOperation(SnpeUdo_OpFactory_t opFactory, - void* perOpInfrastructure, - uint32_t numOfInputs, - SnpeUdo_TensorParam_t* inputs, - uint32_t numOfOutputs, - SnpeUdo_TensorParam_t* outputs, - SnpeUdo_Operation_t* operation); - -typedef SnpeUdo_ErrorType_t -(*SnpeUdo_CreateOperationFunction_t)(SnpeUdo_OpFactory_t, - void*, - uint32_t, - SnpeUdo_TensorParam_t*, - uint32_t, - SnpeUdo_TensorParam_t*, - SnpeUdo_Operation_t*); - -typedef SnpeUdo_CreateOperationFunction_t Udo_CreateOperationFunction_t; - -/** - * @brief A pointer to notification function. - * - * The notification function supports the non-blocking (e.g. asynchronous) execution use-case. - * In case an "executeUdoOp" function is called with "blocking" set to zero, and a - * notify function, this function will be called by the implementation library at the - * end of execution. The implementation library will pass the notify function the ID - * that was provided to it when "executeUdoOp" was called. - * - * @param[in] ID 32-bit value, that was provided to executeUdoOp by the calling entity. - * Can be used to track the notifications, in case of multiple execute calls issued. - * - * @return Error code - * - */ -typedef SnpeUdo_ErrorType_t -(*SnpeUdo_ExternalNotify_t)(const uint32_t ID); - -typedef SnpeUdo_ExternalNotify_t Udo_ExternalNotify_t; - -/** - * @brief Operation execution function. - * - * Calling this function will run the operation on set of inputs, generating a set of outputs. - * The call can be blocking (synchronous) or non-blocking (asynchronous). To support the - * non-blocking mode, the calling entity can pass an ID and a notification function. - * At the end of the execution this notification function would be called, passing it the ID. - * NOTE: Asynchronous execution mode not supported in this release. - * - * @param[in] operation handle to the operation on which execute is invoked - * @param[in] blocking flag to indicate execution mode. - * If set, execution is blocking, - * e.g SnpeUdo_executeOp call does not return until execution is done. - * If not set, SnpeUdo_executeOp returns immediately, and the - * library will call the notification function (if set) when execution is done. - * - * @param[in] ID 32-bit number that can be used by the calling entity to track execution - * in case of non-blocking execution. - * For example, it can be a sequence number, increased by one on each call. - * - * @param[in] notifyFunc Pointer to notification function. if the pointer is set, and execution is - * non-blocking, the library will call this function at end of execution, - * passing the number provided as ID - * - * @return Error code - * - */ -SnpeUdo_ErrorType_t -SnpeUdo_executeOp(SnpeUdo_Operation_t operation, - bool blocking, - const uint32_t ID, - SnpeUdo_ExternalNotify_t notifyFunc); - -typedef SnpeUdo_ErrorType_t -(*SnpeUdo_ExecuteOpFunction_t)(SnpeUdo_Operation_t, - bool, - const uint32_t, - SnpeUdo_ExternalNotify_t); - -typedef SnpeUdo_ExecuteOpFunction_t Udo_ExecuteOpFunction_t; - -/** - * @brief A function to setting the inputs & outputs. part of SnpeUdo_Operation struct, - * returned from creation of a new operation instance. - * Not supported in this release. - * - * This function allows the calling entity to change some of the inputs and outputs - * between calls to execute. - * Note that the change is limited to changing the pointer to the tensor data only. - * Any other change may be rejected by the implementation library, causing - * immediate invalidation of the operation instance - * - * @param[in] operation Operation on which IO tensors are set - * - * @param[in] inputs array of tensor parameters. The calling entity may provide a subset of the - * operation inputs, providing only those that it wants to change. - * - * @param[in] outputs array of tensor parameters. The calling entity may provide a subset of the - * operation outputs, providing only those that it wants to change. - * - * @return Error code - * - */ -SnpeUdo_ErrorType_t -SnpeUdo_setOpIO(SnpeUdo_Operation_t operation, - SnpeUdo_TensorParam_t* inputs, - SnpeUdo_TensorParam_t* outputs); - -typedef SnpeUdo_ErrorType_t -(*SnpeUdo_SetOpIOFunction_t)(SnpeUdo_Operation_t, - SnpeUdo_TensorParam_t*, - SnpeUdo_TensorParam_t*); - -typedef SnpeUdo_SetOpIOFunction_t Udo_SetOpIOFunction_t; - -/** - * @brief A function to return execution times. - * - * This function can be called to query the operation execution times on the IP core - * on which the operation is run. The time is provided in micro-seconds - * - * @param[in] operation Handle to operation whose execution time is being profiled - * - * @param[in,out] executionTime pointer to a uint32 value.This function writes the operation - * execution time in usec into this value. - * - * @return Error code - * - */ -SnpeUdo_ErrorType_t -SnpeUdo_profileOp(SnpeUdo_Operation_t operation, uint32_t *executionTime); - -typedef SnpeUdo_ErrorType_t -(*SnpeUdo_ProfileOpFunction_t)(SnpeUdo_Operation_t, uint32_t*); - -typedef SnpeUdo_ProfileOpFunction_t Udo_ProfileOpFunction_t; - -/** - * @brief A function to release the operation instance - * \n When it is called, the implementation library needs to release all resources - * allocated for this operation instance. - * \n Note that all function pointers which are part of SnpeUdo_Operation become - * invalid once releaseUdoOp call returns. - * - * @param[in] operation Handle to operation to be released - * @return Error code - * - */ -SnpeUdo_ErrorType_t -SnpeUdo_releaseOp(SnpeUdo_Operation_t operation); - -typedef SnpeUdo_ErrorType_t -(*SnpeUdo_ReleaseOpFunction_t)(SnpeUdo_Operation_t); - -typedef SnpeUdo_ReleaseOpFunction_t Udo_ReleaseOpFunction_t; - -/** @} */ /* end_addtogroup c_plus_plus_apis C++ */ - -#ifdef __cplusplus -} // extern "C" -#endif - -#endif //SNPE_UDO_IMPL_H diff --git a/third_party/snpe/include/SnpeUdo/UdoImplCpu.h b/third_party/snpe/include/SnpeUdo/UdoImplCpu.h deleted file mode 100644 index 3bbe063..0000000 --- a/third_party/snpe/include/SnpeUdo/UdoImplCpu.h +++ /dev/null @@ -1,44 +0,0 @@ -//============================================================================== -// -// Copyright (c) 2019-2020 Qualcomm Technologies, Inc. -// All Rights Reserved. -// Confidential and Proprietary - Qualcomm Technologies, Inc. -// -//============================================================================== - -// Header to be used by a CPU UDO Implementation library - -#ifndef SNPE_UDO_IMPL_CPU_H -#define SNPE_UDO_IMPL_CPU_H - -#include - -/** @addtogroup c_plus_plus_apis C++ -@{ */ - -/** - * @brief This struct provides the infrastructure needed by a developer of - * CPU UDO Implementation library. - * - * The framework/runtime which loads the CPU UDO implementation library provides - * this infrastructure data to the loaded library at the time of op factory creation. - * as an opaque pointer. It contains hooks for the UDO library to invoke supported - * functionality at the time of execution - * - * @param getData function pointer to retrieve raw tensor data from opaque pointer - * passed into the UDO when creating an instance. - * @param getDataSize function pointer to retrieve tensor data size from opaque pointer - */ - -typedef struct -{ - /// function pointer to retrieve raw tensor data from opaque pointer - /// passed into the UDO when creating an instance. - float* (*getData)(void*); - /// function pointer to retrieve tensor data size from opaque pointer - size_t (*getDataSize) (void*); -} SnpeUdo_CpuInfrastructure_t; - -/** @} */ /* end_addtogroup c_plus_plus_apis C++ */ - -#endif // SNPE_UDO_IMPL_CPU_H \ No newline at end of file diff --git a/third_party/snpe/include/SnpeUdo/UdoImplDsp.h b/third_party/snpe/include/SnpeUdo/UdoImplDsp.h deleted file mode 100644 index b97a649..0000000 --- a/third_party/snpe/include/SnpeUdo/UdoImplDsp.h +++ /dev/null @@ -1,207 +0,0 @@ -//============================================================================== -// -// Copyright (c) 2019-2021 Qualcomm Technologies, Inc. -// All Rights Reserved. -// Confidential and Proprietary - Qualcomm Technologies, Inc. -// -//============================================================================== - -//============================================================================== -/* - * THIS HEADER FILE IS COPIED FROM HEXAGON-NN PROJECT - * - */ -//============================================================================== - - -// Header to be used by a DSP Hexnn UDO Implementation library - -#ifndef SNPE_UDO_IMPL_DSP_H -#define SNPE_UDO_IMPL_DSP_H -#include -#include "SnpeUdo/UdoImpl.h" - -/** @addtogroup c_plus_plus_apis C++ -@{ */ - -/** - * @brief A function to validate that a set of params is supported by an operation - * This function is HexNN specific, use case is when registration library is not in use. - * Optional function. - * - * @param[in] operationType Operation type - * @param[in] numOfStaticParams Number of static params defined by the op - * @param[in] staticParams Array of static params to the op - * @return Error code, indicating if the operation can be created on this set of configuration or not. - * - */ - -SnpeUdo_ErrorType_t -SnpeUdo_validateOperation (SnpeUdo_String_t operationType, - uint32_t numOfStaticParams, - const SnpeUdo_Param_t* staticParams); - -typedef SnpeUdo_ErrorType_t (*SnpeUdo_ValidateOperationFunction_t) (SnpeUdo_String_t, - uint32_t, - const SnpeUdo_Param_t*); - -typedef SnpeUdo_ValidateOperationFunction_t Udo_ValidateOperationFunction_t; - -// enum used for indicating input/outout tensor data layouts on DSP, plain vs d32 -typedef enum { - SNPE_UDO_DSP_TENSOR_LAYOUT_PLAIN = 0x00, UDO_DSP_TENSOR_LAYOUT_PLAIN = 0x00, - SNPE_UDO_DSP_TENSOR_LAYOUT_D32 = 0x01, UDO_DSP_TENSOR_LAYOUT_D32 = 0x01 -} SnpeUdo_HexNNTensorLayout_t; - -typedef SnpeUdo_HexNNTensorLayout_t Udo_HexNNTensorLayout_t; - -/** - * @brief A function to query numbers of inputs and outputs, - * quantization type of each input and each output as arrays, - * and data layout (plain vs d32) of each input and each output as arrays - * of an operation. - * inputsQuantTypes and inputsLayouts should point to arrays of size numOfInputs - * outputsQuantTypes and outputsLayouts should point to arrays of size numOfOutputs - * - * Note: inputsLayouts and inputsLayouts can point to NULL, in this case, it is - * assumed all inputs and/or outputs have plain data layouts, i.e. no D32 - * - * @param[in] operationType Operation type - * @param[in] numOfStaticParams Number of static params defined by the op - * @param[in] staticParams Array of static params to the op - * @param[in,out] numOfInputs Number of input tensors to the op - * @param[in,out] inputsQuantTypes Array of Quantization info for each input tensor - * @param[in,out] inputsLayouts Array of layout type for each input tensor - * @param[in,out] numOfOutputs Number of output tensors to the op - * @param[in,out] outputsQuantTypes Array of Quantization info for each output tensor - * @param[in,out] outputsLayouts Array of layout type for each output tensor - * @return error code, indicating status of query - */ - -SnpeUdo_ErrorType_t -SnpeUdo_queryOperation (SnpeUdo_String_t operationType, - uint32_t numOfStaticParams, - const SnpeUdo_Param_t* staticParams, - uint32_t* numOfInputs, - SnpeUdo_QuantizationType_t** inputsQuantTypes, - SnpeUdo_HexNNTensorLayout_t** inputsLayouts, - uint32_t* numOfOutputs, - SnpeUdo_QuantizationType_t** outputsQuantTypes, - SnpeUdo_HexNNTensorLayout_t** outputsLayouts); - -typedef SnpeUdo_ErrorType_t (*SnpeUdo_QueryOperationFunction_t) (SnpeUdo_String_t, - uint32_t, - const SnpeUdo_Param_t*, - uint32_t*, - SnpeUdo_QuantizationType_t**, - SnpeUdo_HexNNTensorLayout_t**, - uint32_t*, - SnpeUdo_QuantizationType_t**, - SnpeUdo_HexNNTensorLayout_t**); - -typedef SnpeUdo_QueryOperationFunction_t Udo_QueryOperationFunction_t; - -// Global infrastructure functions supported by Hexagon-NN v2 -typedef void (*workerThread_t) (void* perOpInfrastructure, void* userData); -typedef int (*udoSetOutputTensorSize_t) (void* perOpInfrastructure, uint32_t outIdx, uint32_t size); -typedef int (*udoGetInputD32Paddings_t) (void* perOpInfrastructure, uint32_t inIdx, - uint32_t* heightPadBefore, uint32_t* heightPadAfter, - uint32_t* widthPadBefore, uint32_t* widthPadAfter, - uint32_t* depthPadBefore, uint32_t* depthPadAfter); -typedef int (*udoSetOutputD32ShapeSizePaddings_t) (void* perOpInfrastructure, uint32_t outIdx, - uint32_t batch, - uint32_t height, uint32_t heightPadBefore, uint32_t heightPadAfter, - uint32_t width, uint32_t widthPadBefore, uint32_t widthPadAfter, - uint32_t depth, uint32_t depthPadBefore, uint32_t depthPadAfter, - SnpeUdo_DataType_t dataType); -typedef void* (*udoMemalign_t) (size_t n, size_t size); -typedef void* (*udoMalloc_t) (size_t size); -typedef void* (*udoCalloc_t) (size_t n, size_t size); -typedef void (*udoFree_t) (void* ptr); -typedef uint32_t (*udoGetVtcmSize_t) (void* perOpInfrastructure); -typedef void* (*udoGetVtcmPtr_t) (void* perOpInfrastructure); -typedef uint32_t (*udoVtcmIsReal_t) (void* perOpInfrastructure); -typedef void (*udoRunWorkerThreads_t) (void* perOpInfrastructure, uint32_t nThreads, workerThread_t w, void* userData); - -typedef struct hexNNv2GlobalInfra { - udoSetOutputTensorSize_t udoSetOutputTensorSize; - udoGetInputD32Paddings_t udoGetInputD32Paddings; - udoSetOutputD32ShapeSizePaddings_t udoSetOutputD32ShapeSizePaddings; - udoMemalign_t udoMemalign; - udoMalloc_t udoMalloc; - udoCalloc_t udoCalloc; - udoFree_t udoFree; - udoGetVtcmSize_t udoGetVtcmSize; - udoGetVtcmPtr_t udoGetVtcmPtr; - udoVtcmIsReal_t udoVtcmIsReal; - udoRunWorkerThreads_t udoRunWorkerThreads; -} SnpeUdo_HexNNv2GlobalInfra_t; - -typedef SnpeUdo_HexNNv2GlobalInfra_t Udo_HexNNv2GlobalInfra_t; - -// hexnn types -typedef enum hexnnInfraType { - UDO_INFRA_HEXNN_V2, - UDO_INFRA_HEXNN_V3 // reserved, do not use -} SnpeUdo_HexNNInfraType_t; - -typedef SnpeUdo_HexNNInfraType_t Udo_HexNNInfraType_t; - -typedef struct { - Udo_CreateOpFactoryFunction_t create_op_factory; - Udo_CreateOperationFunction_t create_operation; - Udo_ExecuteOpFunction_t execute_op; - Udo_ReleaseOpFunction_t release_op; - Udo_ReleaseOpFactoryFunction_t release_op_factory; - Udo_ValidateOperationFunction_t validate_op; - Udo_QueryOperationFunction_t query_op; -} udo_func_package_t; - -/** - * @brief Infrastructures needed by a developer of DSP Hexnn UDO Implementation library. - * - * The framework/runtime which loads the Hexnn UDO implementation library provides - * this infrastructure to the loaded library by calling "SnpeUdo_initImplLibrary" - * function, and passing it (cast to void*). The Hexnn UDO library is expected - * to cast it back to this structure. - * - */ -typedef struct dspGlobalInfrastructure { - SnpeUdo_Version_t dspInfraVersion; // api version - SnpeUdo_HexNNInfraType_t infraType; - SnpeUdo_HexNNv2GlobalInfra_t hexNNv2Infra; -} SnpeUdo_DspGlobalInfrastructure_t; - -typedef SnpeUdo_DspGlobalInfrastructure_t Udo_DspGlobalInfrastructure_t; - -/** - * hexnn v2 per op factory infrastructure - * - * The framework/runtime passes per op factory infrastructure as a void pointer - * to HexNN UDO implementation library by calling function "SnpeUdo_createOpFactory". - * UDO implementation library is expected to cast it back to this following struct. - * - */ -typedef struct hexnnv2OpFactoryInfra { - unsigned long graphId; -} SnpeUdo_HexNNv2OpFactoryInfra_t; - -typedef SnpeUdo_HexNNv2OpFactoryInfra_t Udo_HexNNv2OpFactoryInfra_t; - -/** - * hexnn v2 per operation infrastructure - * - * The framework/runtime passes per operation infrastructure as a void pointer - * to HexNN UDO implementation library by calling function "SnpeUdo_createOperation". - * UDO implementation library is expected to cast it to the following type and save it. - * - * This is needed to be passed back into some functions from global infrastructure. - * - */ -typedef void* SnpeUdo_HexNNv2OpInfra_t; - -typedef SnpeUdo_HexNNv2OpInfra_t Udo_HexNNv2OpInfra_t; - -/** @} */ /* end_addtogroup c_plus_plus_apis C++ */ - -#endif // SNPE_UDO_IMPL_DSP_H diff --git a/third_party/snpe/include/SnpeUdo/UdoImplGpu.h b/third_party/snpe/include/SnpeUdo/UdoImplGpu.h deleted file mode 100644 index 1af654d..0000000 --- a/third_party/snpe/include/SnpeUdo/UdoImplGpu.h +++ /dev/null @@ -1,112 +0,0 @@ -//============================================================================== -// -// Copyright (c) 2019-2020 Qualcomm Technologies, Inc. -// All Rights Reserved. -// Confidential and Proprietary - Qualcomm Technologies, Inc. -// -//============================================================================== - -// Header to be used by a GPU UDO Implementation library - -#ifndef SNPE_UDO_IMPL_GPU_H -#define SNPE_UDO_IMPL_GPU_H - -#include "CL/cl.h" -#include "SnpeUdo/UdoBase.h" - -/** @addtogroup c_plus_plus_apis C++ -@{ */ - -/** - * This header defines version 0.0.0 of the GPU UDO Infrastructure. - * It defines the interpretation of the global and per-OpFactory infrastructure pointers - * as well as the interpretation of tensorData pointers. - * - * The per-Operation infrastructure pointer is defined to be null, and should not be used. - * - * The SnpeUdoTensorParam_t struct below provides the interpretation for - * the tensorData opaque pointer for SnpeUdoTensorParams representing inputs or outputs. - * - * The tensorData opaque pointer populated in SnpeUdoScalarParam_t structs should be interpreted - * as a host-readable data pointer. - * - */ - -/** - * @brief Function to retrieve opencl program from Program Cache repository. - * @param programCache is opaque pointer to Program Cache repository provided by - * SNPE GPU UDO runtime. - * @param programName is name associated with opencl program for UDO. - * @param program is pointer to opencl program which will be populated with - * valid opencl program if found in Program Cache repository. - * @return SnpeUdo_ErrorType_t is error type returned. SNPE_UDO_NO_ERROR is returned - * on success. - */ -typedef SnpeUdo_ErrorType_t (*SnpeUdo_getProgram_t) - (void* programCache, const char* programName, cl_program* program); - -/** - * @brief Function to store valid opencl program in Program Cache repository. - * @param programCache is opaque pointer to Program Cache repository provided by - * SNPE GPU UDO runtime. - * @param programName is name associated with opencl program for UDO. - * @param program is valid opencl program after program is built. - * @return SnpeUdo_ErrorType_t is error type returned. SNPE_UDO_NO_ERROR is returned - * on success. - * */ -typedef SnpeUdo_ErrorType_t (*SnpeUdo_storeProgram_t) - (void* programCache, const char * programName, cl_program program); - -/** - * @brief Global Infrastructure Definition for GPU UDO Implementations. - */ -typedef struct { - // Infrastructure definition version. This header is 0.0.0 - SnpeUdo_Version_t gpuInfraVersion; - SnpeUdo_getProgram_t SnpeUdo_getProgram; - SnpeUdo_storeProgram_t SnpeUdo_storeProgram; -} SnpeUdo_GpuInfrastructure_t; - -/** - * @brief Per OpFactory Infrastructure Definition for GPU UDO Implementations. - * @note This version of the infrastructure definition guarantees that the same - * Per OpFactory infrastructure pointer will be provided to all OpFactories - * in the same network. - */ -typedef struct -{ - cl_context context; - cl_command_queue commandQueue; - void* programCache; -} SnpeUdo_GpuOpFactoryInfrastructure_t; - -/** - * @brief Opaque tensorData definition for operation inputs and outputs. - * - * The following is a list of all SnpeUdoTensorLayout_t values supported by the - * GPU UDO implementation, and how the parameters of the struct should be - * interpreted in each case: - * - * SNPE_UDO_LAYOUT_NHWC: - * mem shall be single-element array, pointing to a cl buffer memory object. - * the dimensions of this object match the dimensions specified in the encompassing - * SnpeUdoTensorParam_t's currDimensions. - * - * memCount shall be 1. - * - * paddedRank and paddedDimensions are undefined and shall be ignored by the UDO - * implementation. - * - */ -typedef struct -{ - cl_mem* mem; - uint32_t memCount; - uint32_t paddedRank; - uint32_t* paddedDimensions; - -} SnpeUdo_GpuTensorData_t; - -/** @} */ /* end_addtogroup c_plus_plus_apis C++ */ - -#endif // SNPE_UDO_IMPL_GPU_H diff --git a/third_party/snpe/include/SnpeUdo/UdoReg.h b/third_party/snpe/include/SnpeUdo/UdoReg.h deleted file mode 100644 index a5d2398..0000000 --- a/third_party/snpe/include/SnpeUdo/UdoReg.h +++ /dev/null @@ -1,108 +0,0 @@ -//============================================================================== -// -// Copyright (c) 2019-2020 Qualcomm Technologies, Inc. -// All Rights Reserved. -// Confidential and Proprietary - Qualcomm Technologies, Inc. -// -//============================================================================== - -#ifndef SNPE_UDO_REG_H -#define SNPE_UDO_REG_H - -#include "SnpeUdo/UdoShared.h" - -#ifdef __cplusplus -extern "C" -{ -#endif - -/** @addtogroup c_plus_plus_apis C++ -@{ */ - -/** - * @brief Initialize the shared library's data structures. Calling any other - * library function before this one will result in an error being returned. - * - * @return Error code - */ -SnpeUdo_ErrorType_t -SnpeUdo_initRegLibrary(void); - -typedef SnpeUdo_ErrorType_t -(*SnpeUdo_InitRegLibraryFunction_t)(void); - -/** - * @brief A function to query the API version of the UDO registration library. - * The function populates a SnpeUdo_LibVersion_t struct, which contains a SnpeUdo_Version_t - * struct for API version and library version. - * - * @param[in, out] version A pointer to struct which contains major, minor, teeny information for - * library and api versions. - * - * @return Error code - */ -SnpeUdo_ErrorType_t -SnpeUdo_getRegLibraryVersion(SnpeUdo_LibVersion_t** version); - -typedef SnpeUdo_ErrorType_t -(*SnpeUdo_getRegLibraryVersion_t)(SnpeUdo_LibVersion_t** version); - -/** - * @brief Release the shared library's data structures, and invalidate any - * handles returned by the library. The behavior of any outstanding - * asynchronous calls made to this library when this function is called - * are undefined. All library functions (except SnpeUdo_InitRegLibrary) will - * return an error after this function has been successfully called. - * - * It should be possible to call SnpeUdo_InitRegLibrary after calling this - * function, and re-initialize the library. - * - * @return Error code - */ -SnpeUdo_ErrorType_t -SnpeUdo_terminateRegLibrary(void); - -typedef SnpeUdo_ErrorType_t -(*SnpeUdo_TerminateRegLibraryFunction_t)(void); - - -/** - * @brief A function to query the info on the UDO set. - * The function populates a structure which contains information about - * the package and operations contained in it. - * - * @param[in, out] registrationInfo A struct which contains information on the set of UDOs - * - * @return Error code - * - */ -SnpeUdo_ErrorType_t -SnpeUdo_getRegInfo(SnpeUdo_RegInfo_t** registrationInfo); - -typedef SnpeUdo_ErrorType_t -(*SnpeUdo_GetRegInfoFunction_t)(SnpeUdo_RegInfo_t** registrationInfo); - -/** - * @brief A function to validate that a set of params is supported by an operation - * The function receives an operation definition struct, and returns if this configuration is - * supported (e.g. if an operation can be created using this configuration) - * - * @param[in] opDefinition A struct of SnpeUdo_OpDefinition type, containing the information needed to - * validate that an operation can be created with this configuration. - * - * @return Error code, indicating is the operation can be created on this set or not. - * - */ -SnpeUdo_ErrorType_t -SnpeUdo_validateOperation(SnpeUdo_OpDefinition_t* opDefinition); - -typedef SnpeUdo_ErrorType_t -(*SnpeUdo_ValidateOperationFunction_t)(SnpeUdo_OpDefinition_t* opDefinition); - -/** @} */ /* end_addtogroup c_plus_plus_apis C++ */ - -#ifdef __cplusplus -} // extern "C" -#endif - -#endif //SNPE_UDO_REG_H diff --git a/third_party/snpe/include/SnpeUdo/UdoShared.h b/third_party/snpe/include/SnpeUdo/UdoShared.h deleted file mode 100644 index 418d9db..0000000 --- a/third_party/snpe/include/SnpeUdo/UdoShared.h +++ /dev/null @@ -1,48 +0,0 @@ -//============================================================================== -// -// Copyright (c) 2019-2021 Qualcomm Technologies, Inc. -// All Rights Reserved. -// Confidential and Proprietary - Qualcomm Technologies, Inc. -// -//============================================================================== - -#ifndef SNPE_UDO_SHARED_H -#define SNPE_UDO_SHARED_H - -#include "SnpeUdo/UdoBase.h" - -#ifdef __cplusplus -extern "C" -{ -#endif - -/** @addtogroup c_plus_plus_apis C++ -@{ */ - -/** - * @brief A function to return the various versions as they relate to the UDO - * The function returns a struct containing the the following: - * libVersion: the version of the implementation library compiled for the UDO. Set by user - * apiVersion: the version of the UDO API used in compiling the implementation library. - * Set by SNPE - * - * @param[in, out] version A pointer to Version struct of type SnpeUdo_LibVersion_t - * - * @return Error code - * - */ -SnpeUdo_ErrorType_t -SnpeUdo_getVersion (SnpeUdo_LibVersion_t** version); - -typedef SnpeUdo_ErrorType_t -(*SnpeUdo_GetVersionFunction_t) (SnpeUdo_LibVersion_t** version); - -typedef SnpeUdo_GetVersionFunction_t Udo_GetVersionFunction_t; - -#ifdef __cplusplus -} // extern "C" -#endif - -/** @} */ /* end_addtogroup c_plus_plus_apis C++ */ - -#endif // SNPE_UDO_SHARED_H diff --git a/third_party/snpe/larch64~HEAD b/third_party/snpe/larch64~HEAD new file mode 100644 index 0000000..2e2a1c3 --- /dev/null +++ b/third_party/snpe/larch64~HEAD @@ -0,0 +1 @@ +aarch64-ubuntu-gcc7.5 \ No newline at end of file diff --git a/third_party/snpe/x86_64-linux-clang/libSNPE.so b/third_party/snpe/x86_64-linux-clang/libSNPE.so deleted file mode 100644 index 0cee9ac..0000000 Binary files a/third_party/snpe/x86_64-linux-clang/libSNPE.so and /dev/null differ diff --git a/third_party/snpe/x86_64-linux-clang/libomp.so b/third_party/snpe/x86_64-linux-clang/libomp.so deleted file mode 100755 index 567e6ae..0000000 Binary files a/third_party/snpe/x86_64-linux-clang/libomp.so and /dev/null differ diff --git a/third_party/snpe/x86_64/libSNPE.so b/third_party/snpe/x86_64/libSNPE.so deleted file mode 100644 index 0cee9ac..0000000 Binary files a/third_party/snpe/x86_64/libSNPE.so and /dev/null differ diff --git a/third_party/snpe/x86_64/libomp.so b/third_party/snpe/x86_64/libomp.so deleted file mode 100755 index 567e6ae..0000000 Binary files a/third_party/snpe/x86_64/libomp.so and /dev/null differ diff --git a/tinygrad_repo/test/Dockerfile b/tinygrad_repo/test/Dockerfile deleted file mode 100644 index 22be7b4..0000000 --- a/tinygrad_repo/test/Dockerfile +++ /dev/null @@ -1,12 +0,0 @@ -FROM ubuntu:20.04 - -# Install python3.8, and pip3 -RUN apt-get update && apt-get install -y --no-install-recommends \ - python3.8 \ - python3-pip \ - && rm -rf /var/lib/apt/lists/* - -# Install python dependencies -COPY . ./tinygrad -WORKDIR tinygrad -RUN pip install -e . diff --git a/tinygrad_repo/test/__init__.py b/tinygrad_repo/test/__init__.py deleted file mode 100644 index e69de29..0000000 diff --git a/tinygrad_repo/test/external/dist/test_collectives.py b/tinygrad_repo/test/external/dist/test_collectives.py deleted file mode 100644 index a707e1d..0000000 --- a/tinygrad_repo/test/external/dist/test_collectives.py +++ /dev/null @@ -1,62 +0,0 @@ -from extra import dist -from tinygrad.jit import TinyJit -if __name__ == "__main__": - dist.preinit() - -from extra.dist import collectives -from tinygrad.helpers import CI, getenv -from tinygrad.tensor import Tensor -import numpy as np - -@TinyJit -def allreduce_jit(t:Tensor, cache_id=None) -> Tensor: - return collectives.allreduce(t, cache_id=cache_id).realize() - -SIZE = 2048 if not CI else 2 -SIZE_2 = 255 if not CI else 3 - -def run(): - # set a deterministic seed so that both ranks generate the same random tensor - Tensor.manual_seed(42) - - rank = getenv("RANK") - - # loop 3 times to make sure it works with the jit - for _ in range(3): - # create a tensor to send - t = Tensor.zeros(SIZE, SIZE) if rank != 0 else Tensor.ones(SIZE, SIZE) - t2 = allreduce_jit(t.contiguous().realize(), cache_id="test") - assert np.allclose(np.ones((SIZE, SIZE)), t2.numpy()), f"{t2.numpy()} wasn't ones" - - # reset jit - allreduce_jit.cnt = 0 - allreduce_jit.input_replace = {} - - # test uneven chunk sizes - for _ in range(3): - # create a tensor to send - t = Tensor.ones(SIZE_2, SIZE_2, SIZE_2) if rank == 0 else Tensor.zeros(SIZE_2, SIZE_2, SIZE_2) - t2 = allreduce_jit(t.contiguous().realize(), cache_id="test2") - assert np.allclose(np.ones((SIZE_2, SIZE_2, SIZE_2)), t2.numpy()), f"{t2.numpy()} wasn't ones" - - print(f"rank {rank} passed") - -if __name__ == "__main__": - if getenv("HIP"): - from tinygrad.runtime.ops_hip import HIP - devices = [f"hip:{i}" for i in range(HIP.device_count)] - else: - from tinygrad.runtime.ops_gpu import CL - devices = [f"gpu:{i}" for i in range(len(CL.devices))] if not CI else ["gpu:0", "gpu:0"] - world_size = len(devices) - - dist.init_oob(world_size) - - processes = [] - for rank, device in enumerate(devices): - processes.append(dist.spawn(rank, device, fn=run, args=())) - for p in processes: p.join() - - # exit with error code if any of the processes failed - for p in processes: - if p.exitcode != 0: exit(p.exitcode) diff --git a/tinygrad_repo/test/external/dist/test_world.py b/tinygrad_repo/test/external/dist/test_world.py deleted file mode 100644 index 28065e9..0000000 --- a/tinygrad_repo/test/external/dist/test_world.py +++ /dev/null @@ -1,68 +0,0 @@ -from extra import dist -from tinygrad.jit import TinyJit -if __name__ == "__main__": - dist.preinit() - -from extra.dist import world -from tinygrad.helpers import CI, getenv -from tinygrad.tensor import Tensor -import numpy as np - -@TinyJit -def send_jit(t, target_rank, cache_id=None) -> Tensor: - return world.send(t, target_rank, cache_id=cache_id).realize() - -@TinyJit -def recv_jit(t, target_rank, cache_id=None) -> Tensor: - return world.recv(t, target_rank, cache_id=cache_id).realize() - -SIZE = 2048 if not CI else 2 - -def run(): - # set a deterministic seed so that both ranks generate the same random tensor - Tensor.manual_seed(42) - - rank = getenv("RANK") - - # loop 3 times to make sure it works with the jit - for _ in range(3): - # create a tensor to send - t = Tensor.randn(SIZE, SIZE) - - # send to rank 1 - if rank == 0: - send_jit(t, 1, cache_id="test") - elif rank == 1: - t2 = Tensor.empty(SIZE, SIZE) - recv_jit(t2, 0, cache_id="test") - - # recv from rank 1 - if rank == 0: - t2 = Tensor.empty(SIZE, SIZE) - recv_jit(t2, 1, cache_id="test2") - elif rank == 1: - send_jit(t2, 0, cache_id="test2") - - # check that the received tensor is the same as the sent tensor - if rank == 0: - assert np.allclose(t.numpy(), t2.numpy()), f"{t2.numpy()} wasn't equal to {t.numpy()}" - - print(f"rank {rank} passed") - -if __name__ == "__main__": - if getenv("HIP"): - devices = ["hip:0", "hip:1"] - else: - devices = ["gpu:0", "gpu:1" if not CI else "gpu:0"] - world_size = len(devices) - - dist.init_oob(world_size) - - processes = [] - for rank, device in enumerate(devices): - processes.append(dist.spawn(rank, device, fn=run, args=())) - for p in processes: p.join() - - # exit with error code if any of the processes failed - for p in processes: - if p.exitcode != 0: exit(p.exitcode) diff --git a/tinygrad_repo/test/external/external_copy_benchmark.py b/tinygrad_repo/test/external/external_copy_benchmark.py deleted file mode 100644 index 9c1e61b..0000000 --- a/tinygrad_repo/test/external/external_copy_benchmark.py +++ /dev/null @@ -1,27 +0,0 @@ -import unittest -from tinygrad.helpers import prod -from tinygrad.ops import Device -from tinygrad.tensor import Tensor -from tinygrad.helpers import GlobalCounters -from tinygrad.jit import CacheCollector - -class TestCopy(unittest.TestCase): - def test_add1(self): - pts = [] - for i in range(16384, 16384*256, 16384): - t = Tensor.randn(i).realize() - CacheCollector.start() - t.assign(t+1).realize() - fxn, args, _ = CacheCollector.finish()[0] - GlobalCounters.reset() - def run(): return fxn(args, force_wait=True) - ct = min([run() for _ in range(10)]) - mb = prod(t.shape)*t.dtype.itemsize*2*1e-6 - print(f"{mb*1e3:.2f} kB, {ct*1e3:.2f} ms, {mb/ct:.2f} MB/s") - pts.append((mb, mb/ct)) - from matplotlib import pyplot as plt - plt.plot([x[0] for x in pts], [x[1] for x in pts]) - plt.show() - -if __name__ == '__main__': - unittest.main() \ No newline at end of file diff --git a/tinygrad_repo/test/external/external_llama_eval.py b/tinygrad_repo/test/external/external_llama_eval.py deleted file mode 100644 index dfbbcba..0000000 --- a/tinygrad_repo/test/external/external_llama_eval.py +++ /dev/null @@ -1,102 +0,0 @@ -from lm_eval.base import BaseLM -from lm_eval import evaluator, tasks -import torch, json, argparse - -from examples.llama import LLaMa -from tinygrad.tensor import Tensor -from tinygrad.ops import Device - -class LLaMaAdaptor(BaseLM): - def __init__( - self, - model_size="7B", - model_gen=1, - device="", - quantize=False, - batch_size=1, - max_batch_size=1, - do_sample=False, - temperature=1.0, - checkpoint_path="", - tokenizer_path="", - ): - super().__init__() - - if batch_size is None: - batch_size = 1 - self.do_sample = do_sample - self.temperature = temperature - self._device = device - - assert isinstance(model_gen, int) - assert isinstance(model_size, str) - assert isinstance(batch_size, int) - assert isinstance(checkpoint_path, str) - assert isinstance(tokenizer_path, str) - - self.llama = LLaMa.build(checkpoint_path, tokenizer_path, model_gen, model_size, quantize) - - @classmethod - def create_from_arg_string(cls, arg_string, additional_config=None): - kwargs = {el.split("=")[0]: el.split("=")[1] for el in arg_string.split(",")} - return cls(**kwargs, **additional_config) - - @property - def eot_token_id(self): - # we use EOT because end of *text* is more accurate for what we're doing than end of *sentence* - return self.llama.tokenizer.eos_id() - - @property - def max_length(self): - return 1024 - - @property - def max_gen_toks(self): - return 256 - - @property - def batch_size(self): - return 1 - - @property - def device(self): - return self._device - - def tok_encode(self, string: str): - return [self.llama.tokenizer.bos_id()] + self.llama.tokenizer.encode(string) - - def tok_decode(self, tokens): - return self.llama.tokenizer.decode(tokens) - - def _model_call(self, inps): - Tensor.no_grad = True - return torch.Tensor(self.llama.model(Tensor(inps.numpy()), 0).numpy()) - - def greedy_until(self, requests): - continuations = [] - for request in requests: - prompt, until = request[0], request[1]['until'] - output = self.llama.greedy_until(prompt, until, max_length=128, temperature=0.0) - continuations.append(output[len(prompt):]) - return continuations - - def _model_generate(self, context, max_length, eos_token_id): - raise NotImplementedError() - -if __name__ == '__main__': - print(f"using {Device.DEFAULT} backend") - - parser = argparse.ArgumentParser(description='Run LLaMA evals in tinygrad', formatter_class=argparse.ArgumentDefaultsHelpFormatter) - parser.add_argument('--size', type=str, default="7B", help="Size of model to use [7B, 13B, 30B, 65B] for Gen 1, [7B, 13B] for Gen 2") - parser.add_argument('--gen', type=int, default="1", help="Generation of the model to use [1, 2]") - parser.add_argument('--quantize', action='store_true', help="Quantize the weights to int8 in memory") - parser.add_argument('--eval', type=str, default="arc_easy", help="Run in evaluation mode") - parser.add_argument('--limit', type=int, default=None, help="Limit tests in eval") - parser.add_argument('--weights', type=str, default="./weights/LLaMa/", help="Location of the weights") - parser.add_argument('--tokenizer', type=str, default="./weights/LLaMa/tokenizer.model", help="Location of the tokenizer") - args = parser.parse_args() - - # run eval and exit - adaptor = LLaMaAdaptor(model_gen=args.gen, model_size=args.size, quantize=args.quantize, checkpoint_path=args.weights, tokenizer_path=args.tokenizer, device="cpu") - results = evaluator.evaluate(adaptor, tasks.get_task_dict(args.eval.split(",")), False, 0, args.limit) - print(json.dumps(results, indent=2)) diff --git a/tinygrad_repo/test/external/external_model_benchmark.py b/tinygrad_repo/test/external/external_model_benchmark.py deleted file mode 100644 index b784f11..0000000 --- a/tinygrad_repo/test/external/external_model_benchmark.py +++ /dev/null @@ -1,128 +0,0 @@ -import csv, pathlib, time, numpy as np -from os import getenv -import torch -torch.set_num_threads(1) -import onnx -from onnx.helper import tensor_dtype_to_np_dtype -import onnxruntime as ort -from onnx2torch import convert -from extra.utils import download_file -from extra.onnx import get_run_onnx -from tinygrad.helpers import OSX, DEBUG -from tinygrad.tensor import Tensor -from tinygrad.ops import Device - -MODELS = { - "resnet50": "https://github.com/onnx/models/raw/main/vision/classification/resnet/model/resnet50-caffe2-v1-9.onnx", - "openpilot": "https://github.com/commaai/openpilot/raw/v0.9.4/selfdrive/modeld/models/supercombo.onnx", - "efficientnet": "https://github.com/onnx/models/raw/main/vision/classification/efficientnet-lite4/model/efficientnet-lite4-11.onnx", - "shufflenet": "https://github.com/onnx/models/raw/main/vision/classification/shufflenet/model/shufflenet-9.onnx", - "commavq": "https://huggingface.co/commaai/commavq-gpt2m/resolve/main/gpt2m.onnx", - - # broken in torch MPS - #"zfnet": "https://github.com/onnx/models/raw/main/vision/classification/zfnet-512/model/zfnet512-9.onnx", - # TypeError: BatchNormalization() got an unexpected keyword argument 'is_test' - #"densenet": "https://github.com/onnx/models/raw/main/vision/classification/densenet-121/model/densenet-3.onnx", - # AssertionError: only onnx version >= 10 supported for slice - #"bert": "https://github.com/onnx/models/raw/main/text/machine_comprehension/bert-squad/model/bertsquad-8.onnx", - # really slow - #"resnet18": "https://github.com/onnx/models/raw/main/vision/classification/resnet/model/resnet18-v2-7.onnx", -} - -CSV = {} -open_csv = None -torch.manual_seed(1) - -def benchmark(mnm, nm, fxn): - tms = [] - for _ in range(3): - st = time.perf_counter_ns() - ret = fxn() - tms.append(time.perf_counter_ns() - st) - print(f"{mnm:15s} {nm:25s} {min(tms)*1e-6:7.2f} ms") - CSV[nm] = min(tms)*1e-6 - return min(tms), ret - -#BASE = pathlib.Path(__file__).parents[2] / "weights" / "onnx" -BASE = pathlib.Path("/tmp/onnx") -def benchmark_model(m, validate_outs=False): - global open_csv, CSV - CSV = {"model": m} - - fn = BASE / MODELS[m].split("/")[-1] - download_file(MODELS[m], fn) - onnx_model = onnx.load(fn) - output_names = [out.name for out in onnx_model.graph.output] - excluded = {inp.name for inp in onnx_model.graph.initializer} - input_shapes = {inp.name:tuple(x.dim_value if x.dim_value != 0 else 1 for x in inp.type.tensor_type.shape.dim) for inp in onnx_model.graph.input if inp.name not in excluded} - input_types = {inp.name: tensor_dtype_to_np_dtype(inp.type.tensor_type.elem_type) for inp in onnx_model.graph.input if inp.name not in excluded} - #input_types = {k:v if v!=np.float16 else np.float32 for k,v in input_types.items()} # cast - np_inputs = {k:torch.randn(shp).numpy().astype(input_types[k]) for k,shp in input_shapes.items()} - assert len(input_shapes) < 30, f"too many input shapes {len(input_shapes)}" - - # print input names - if DEBUG >= 2: print([inp.name for inp in onnx_model.graph.input if inp.name not in excluded]) - - for device in ["METAL" if OSX else "GPU", "CLANG"]: # + (["CUDA"] if torch.cuda.is_available() else []): - Device.DEFAULT = device - inputs = {k:Tensor(inp) for k,inp in np_inputs.items()} - tinygrad_model = get_run_onnx(onnx_model) - benchmark(m, f"tinygrad_{device.lower()}_jitless", lambda: {k:v.numpy() for k,v in tinygrad_model(inputs).items()}) - - from tinygrad.jit import TinyJit - tinygrad_jitted_model = TinyJit(lambda **kwargs: {k:v.realize() for k,v in tinygrad_model(kwargs).items()}) - for _ in range(3): {k:v.numpy() for k,v in tinygrad_jitted_model(**inputs).items()} - benchmark(m, f"tinygrad_{device.lower()}_jit", lambda: {k:v.numpy() for k,v in tinygrad_jitted_model(**inputs).items()}) - del inputs, tinygrad_model, tinygrad_jitted_model - - try: - torch_model = convert(onnx_model) - torch_inputs = [torch.tensor(x) for x in np_inputs.values()] - benchmark(m, "torch_cpu", lambda: torch_model(*torch_inputs)) - - torch_device = "mps" if OSX else "cuda" - torch_mps_model = torch_model.to(torch_device) - torch_mps_inputs = [x.to(torch_device) for x in torch_inputs] - benchmark(m, f"torch_{torch_device}", lambda: torch_mps_model(*torch_mps_inputs)) - except Exception as e: print(f"{m:16s}onnx2torch {type(e).__name__:>25}") - - # bench onnxruntime - ort_options = ort.SessionOptions() - ort_options.graph_optimization_level = ort.GraphOptimizationLevel.ORT_ENABLE_ALL - ort_options.log_severity_level = 3 # no warnings - for backend in ["CPU", "CUDA" if not OSX else "CoreML"]: # https://onnxruntime.ai/docs/execution-providers/ - provider = backend+"ExecutionProvider" - if provider not in ort.get_available_providers(): continue - ort_sess = ort.InferenceSession(str(fn), ort_options, [provider]) - benchmark(m, f"onnxruntime_{backend.lower()}", lambda: ort_sess.run(output_names, np_inputs)) - del ort_sess - - if validate_outs: - rtol, atol = 2e-3, 2e-3 # tolerance for fp16 models - inputs = {k:Tensor(inp) for k,inp in np_inputs.items()} - tinygrad_model = get_run_onnx(onnx_model) - tinygrad_out = tinygrad_model(inputs) - - ort_sess = ort.InferenceSession(str(fn), ort_options, ["CPUExecutionProvider"]) - onnx_out = ort_sess.run(output_names, np_inputs) - onnx_out = dict([*[(name,x) for name, x in zip(output_names, onnx_out)]]) - - assert_allclose(tinygrad_out, onnx_out, rtol=rtol, atol=atol) - print(f"{m:16s}outputs validated with rtol={rtol:.1e}, atol={atol:.1e}") - - if open_csv is None: - open_csv = csv.DictWriter(open('onnx_inference_speed.csv', 'w', newline=''), fieldnames=list(CSV.keys())) - open_csv.writeheader() - open_csv.writerow(CSV) - -def assert_allclose(tiny_out:dict, onnx_out:dict, rtol=1e-5, atol=1e-5): - assert len(tiny_out) == len(onnx_out) and tiny_out.keys() == onnx_out.keys() - for k in tiny_out.keys(): - tiny_v, onnx_v = tiny_out[k], onnx_out[k] - if tiny_v is None: assert tiny_v == onnx_v - else: np.testing.assert_allclose(tiny_v.numpy(), onnx_v, rtol=rtol, atol=atol, err_msg=f"For tensor '{k}' in {tiny_out.keys()}") - -if __name__ == "__main__": - if getenv("MODEL", "") != "": benchmark_model(getenv("MODEL", ""), True) - else: - for m in MODELS: benchmark_model(m, True) diff --git a/tinygrad_repo/test/external/external_multi_gpu.py b/tinygrad_repo/test/external/external_multi_gpu.py deleted file mode 100644 index 8edd67f..0000000 --- a/tinygrad_repo/test/external/external_multi_gpu.py +++ /dev/null @@ -1,70 +0,0 @@ -#!/usr/bin/env python3 -# cd disassemblers/ && git clone --recursive github.com:geohot/cuda_ioctl_sniffer.git -# LD_PRELOAD=$PWD/disassemblers/cuda_ioctl_sniffer/out/sniff.so GPU=1 python3 test/external/external_multi_gpu.py -import numpy as np -from tinygrad.tensor import Tensor -from tinygrad.helpers import colored -from tinygrad.helpers import Timing -from tinygrad.runtime.ops_gpu import CL - -# TODO: support multidevice in cuda -device = 'gpu' - -if __name__ == "__main__": - sz = 1024*1024*256 # 1 GB - #sz = 1024*64 - - with Timing("CPU creation: ", on_exit=lambda x: f", {(sz*4*2)/x:.2f} GB/sec"): - c0 = Tensor.ones(sz, device="cpu").realize() - c1 = (Tensor.ones(sz, device="cpu")/2).realize() - - with Timing("CPU -> 0: ", on_exit=lambda x: f", {(sz*4)/x:.2f} GB/sec"): - a0 = c0.to(f'{device}:0').realize() - CL.synchronize() - with Timing("CPU -> 1: ", on_exit=lambda x: f", {(sz*4)/x:.2f} GB/sec"): - b1 = c1.to(f'{device}:1').realize() - CL.synchronize() - - # cross copy. this is going through the CPU - with Timing("0 -> CPU -> 1: ", on_exit=lambda x: f", {(sz*4)/x:.2f} GB/sec"): - a1 = a0.to(f'{device}:1').realize() - CL.synchronize() - with Timing("1 -> CPU -> 0: ", on_exit=lambda x: f", {(sz*4)/x:.2f} GB/sec"): - b0 = b1.to(f'{device}:0').realize() - CL.synchronize() - - # sum - with Timing("0+0 -> 0 (sum): ", on_exit=lambda x: f", {(sz*4)/x:.2f} GB/sec"): - ab0 = (a0 + b0).realize() - CL.synchronize() - with Timing("1+1 -> 1 (sum): ", on_exit=lambda x: f", {(sz*4)/x:.2f} GB/sec"): - ab1 = (a1 + b1).realize() - CL.synchronize() - - # cross device sum (does this work?) - # is this making a copy first? is that copy through the CPU? - # the slowness comes from the *blocking* clprg call, is this pyopencl? - with Timing(colored("0+1 -> 0 (sum): ", "red"), on_exit=lambda x: f", {(sz*4)/x:.2f} GB/sec"): - abx0 = (a0 + b1).realize() - CL.synchronize() - - with Timing(colored("1+0 -> 1 (sum): ", "red"), on_exit=lambda x: f", {(sz*4)/x:.2f} GB/sec"): - abx1 = (b1 + a0).realize() - CL.synchronize() - - # copy back - # NOTE: half of this slowness is caused by allocating memory on the CPU - with Timing("0 -> CPU: ", on_exit=lambda x: f", {(sz*4)/x:.2f} GB/sec"): - cc0 = ab0.numpy() - with Timing("1 -> CPU: ", on_exit=lambda x: f", {(sz*4)/x:.2f} GB/sec"): - cc1 = ab1.numpy() - - # same - print("testing") - np.testing.assert_allclose(cc0, cc1) - - # devices - print(ab0) - print(ab1) - print(abx0) - print(abx1) diff --git a/tinygrad_repo/test/external/external_osx_profiling.py b/tinygrad_repo/test/external/external_osx_profiling.py deleted file mode 100644 index 6f9b215..0000000 --- a/tinygrad_repo/test/external/external_osx_profiling.py +++ /dev/null @@ -1,41 +0,0 @@ -from tinygrad.runtime.ops_gpu import CLProgram, CL, CLBuffer -from tinygrad.helpers import dtypes -import time - -N = 1000000 -a = CLBuffer(N, dtypes.float32) -b = CLBuffer(N, dtypes.float32) -c = CLBuffer(N, dtypes.float32) - -prg = CLProgram("test", """__kernel void test(__global float *a, __global float *b, __global float *c) { - int idx = get_global_id(0); - a[idx] = b[idx] + c[idx]; -}""") -prg.clprgs[0](CL.cl_queue[0], [N,], None, a._buf, b._buf, c._buf) -t1 = time.monotonic_ns() -e1 = prg.clprgs[0](CL.cl_queue[0], [N,], None, a._buf, b._buf, c._buf) -CL.synchronize() -t2 = time.monotonic_ns() -time.sleep(3) -t3 = time.monotonic_ns() -e2 = prg.clprgs[0](CL.cl_queue[0], [N,], None, a._buf, b._buf, c._buf) -CL.synchronize() -t4 = time.monotonic_ns() - -print(e1.profile.queued) -print(e1.profile.submit) -print(e1.profile.start) -print(e1.profile.end) - -print(e1, e2) -print(t2-t1, e1.profile.end - e1.profile.start) -print(t4-t3, e2.profile.end - e2.profile.start) -print(t3-t2, e2.profile.queued-e1.profile.end) -print((t3-t2) / (e2.profile.start-e1.profile.end), "ratio") - -print("ratio since boot", t1/e1.profile.start) - -print(e1.profile.start) -print(e1.profile.end) -print(e2.profile.start) -print(e2.profile.end) diff --git a/tinygrad_repo/test/external/external_test_allocator_on_models.py b/tinygrad_repo/test/external/external_test_allocator_on_models.py deleted file mode 100644 index 04911a6..0000000 --- a/tinygrad_repo/test/external/external_test_allocator_on_models.py +++ /dev/null @@ -1,125 +0,0 @@ -#!/usr/bin/env python -import unittest, gc -import numpy as np -from tinygrad.tensor import Tensor -from tinygrad.nn.state import get_state_dict -from tinygrad.helpers import GlobalCounters -from tinygrad.runtime.lib import RawBuffer, LRUAllocator -from tinygrad.helpers import dtypes, prod -from tinygrad.ops import Device -from test.helpers import derandomize_model - -from examples.llama import Transformer - -ALLOCATED_DEV_BUFS = 0 -class FakeDeviceBuffer: - def __init__(self, sz, dt, device): - self.id = 1 - self.size = sz - self.dtype = dt - self.device = device - - global ALLOCATED_DEV_BUFS - ALLOCATED_DEV_BUFS += 1 -class FakeAllocator(LRUAllocator): - def _do_alloc(self, size, dtype, device, **kwargs): return FakeDeviceBuffer(size, dtype, device) - def _do_free(self, buf): - buf.id -= 1 - assert buf.id == 0, f"Free should be called once, but {buf.id}" - def __del__(self): # Fake allocator should clear all buffers after each test. - for v in self.cached_buffers.values(): - for buf, _ in v: self._free_buffer(buf) - -FAKE_GLOBAL_ALLOCATOR = None -class FakeBuffer(RawBuffer): - def __init__(self, size, dtype, device='0'): - global FAKE_GLOBAL_ALLOCATOR - super().__init__(size, dtype, allocator=FAKE_GLOBAL_ALLOCATOR, **{'device': device}) - assert self._buf.size == size and self._buf.dtype == dtype and self._buf.device == device, "This allocator requires 100% match of dtype and size." - @classmethod - def fromCPU(cls, x:np.ndarray, **kwargs): return cls(prod(x.shape), dtypes.from_np(x.dtype), **kwargs) - def toCPU(self): return np.empty(self.size, dtype=self.dtype.np) -class FakeProgram: - def __init__(self, name:str, prg:str): pass - def __call__(self, *bufs, global_size, local_size, wait=False): pass - -def helper_test_correctness(gen, train): - from tinygrad.runtime.ops_gpu import CL, CLAllocator - old_alloc = CL.cl_allocator - CL.cl_allocator = CLAllocator(0) - no_alloc_result = train(*gen()).numpy() - Device[Device.DEFAULT].synchronize() - CL.cl_allocator = CLAllocator(512<<30) # Test cache correctness, so cache as much as possible, 512gb - for _ in range(4): - GlobalCounters.reset() - np.testing.assert_allclose(train(*gen()).numpy(), no_alloc_result, rtol=1e-3, atol=1e-5) - Device[Device.DEFAULT].synchronize() - assert len(CL.cl_allocator.cached_buffers) != 0, "Cache must be used" - CL.cl_allocator = old_alloc - -def __helper_test_alloc_count(gen, train): - was_alloc = ALLOCATED_DEV_BUFS - for _ in range(2): - train(*gen()) - return ALLOCATED_DEV_BUFS - was_alloc - -def helper_test_alloc_count(mm, gen, train): - global FAKE_GLOBAL_ALLOCATOR - backup_program = Device[Device.DEFAULT].runtime - backup_buffer = Device[Device.DEFAULT].buffer - Device[Device.DEFAULT].runtime = FakeProgram - Device[Device.DEFAULT].buffer = FakeBuffer - Device[Device.DEFAULT].method_cache.clear() - FAKE_GLOBAL_ALLOCATOR = FakeAllocator(16<<30) - new_allocs = __helper_test_alloc_count(gen, train) - Device[Device.DEFAULT].method_cache.clear() - FAKE_GLOBAL_ALLOCATOR = FakeAllocator(0) - old_allocs = __helper_test_alloc_count(gen, train) - print(f"{mm}: llama: old allocs count {old_allocs}, new allocs count {new_allocs}") - assert new_allocs < old_allocs, f"Hmm, doesn't cache work any more?" - Device[Device.DEFAULT].runtime = backup_program - Device[Device.DEFAULT].buffer = backup_buffer - FAKE_GLOBAL_ALLOCATOR = None - -def check_gc(): - if Device.DEFAULT == "GPU": - gc.collect() # Need to collect Tensors. - from extra.introspection import print_objects - assert print_objects() == 0 - -class TestAllocators(unittest.TestCase): - @unittest.skipUnless(Device.DEFAULT == "GPU", "Not Implemented") - def test_lru_allocator_tiny_llama(self): - old_type = Tensor.default_type - Tensor.default_type = dtypes.float16 - - args_tiny = {"dim": 1024, "multiple_of": 256, "n_heads": 8, "n_layers": 8, "norm_eps": 1e-05, "vocab_size": 1000} - def __test(): - model = Transformer(**args_tiny) - derandomize_model(model) - def test(t): return model(t, 0).realize() - helper_test_correctness(lambda: (Tensor([[1,]]),), test) - __test() - Tensor.default_type = old_type - check_gc() - - @unittest.skipUnless(Device.DEFAULT == "GPU", "Not Implemented") - def test_lru_allocator_tiny_llama_alloc_counts(self): - args_tiny = {"dim": 1024, "multiple_of": 256, "n_heads": 8, "n_layers": 8, "norm_eps": 1e-05, "vocab_size": 1000} - def test_alloc_count(t): - model = Transformer(**args_tiny) - for v in get_state_dict(model).values(): v.assign(Tensor.empty(*v.shape, dtype=v.dtype)) - return model(t, 0).realize() - helper_test_alloc_count("llama", lambda: (Tensor([[2,]]),), test_alloc_count) - check_gc() - - @unittest.skip("huge for CI") - def test_stable_diffusion(self): - from examples.stable_diffusion import UNetModel - model = UNetModel() - derandomize_model(model) - def test(t, t2): return model(t, 801, t2).realize() - helper_test_correctness(lambda: (Tensor.randn(1, 4, 16, 16),Tensor.randn(1, 77, 768)), test) - -if __name__ == "__main__": - unittest.main() diff --git a/tinygrad_repo/test/external/external_test_embedding.py b/tinygrad_repo/test/external/external_test_embedding.py deleted file mode 100644 index 9d6bd7f..0000000 --- a/tinygrad_repo/test/external/external_test_embedding.py +++ /dev/null @@ -1,8 +0,0 @@ -from tinygrad.tensor import Tensor -from tinygrad.nn import Embedding - -if __name__ == "__main__": - vocab_size = 50257 - dim = 128 - test = Embedding(vocab_size, dim) - ret = test(Tensor([[1,2,3]])).numpy() diff --git a/tinygrad_repo/test/external/external_test_gpu_ast.py b/tinygrad_repo/test/external/external_test_gpu_ast.py deleted file mode 100644 index 0c98552..0000000 --- a/tinygrad_repo/test/external/external_test_gpu_ast.py +++ /dev/null @@ -1,208 +0,0 @@ -#!/usr/bin/env python -import unittest -import numpy as np -from tinygrad.ops import LazyOp, ReduceOps, BinaryOps, UnaryOps, MovementOps -from tinygrad.shape.shapetracker import ShapeTracker, View, ZeroView -from tinygrad.runtime.ops_gpu import GPUBuffer, CLProgram, CLCodegen -#from tinygrad.runtime.ops_metal import MetalBuffer as GPUBuffer, MetalProgram as CLProgram, MetalCodegen as CLCodegen -from tinygrad.helpers import getenv -from extra.lib_test_ast import test_ast - -import platform -OSX = platform.system() == "Darwin" - -def compile_and_test_ast(ast, local_size=None): - k = CLCodegen(ast) - prg = k.codegen().build(CLProgram) - if local_size is not None: prg.local_size = local_size - for i in range(5): prg(prg.lower(k.bufs)) - if getenv("TEST", 0): test_ast(k) - -class TestAST(unittest.TestCase): - def test_conv_zeroview_ast(self): - buf0 = GPUBuffer(shape=ShapeTracker(shape=(1, 1, 3, 4), views=[View((1, 1, 3, 4), (2, 2, 2, 1), -3), ZeroView((1, 1, 1, 2), ((0, 1), (0, 1), (-1, 2), (-1, 3))), View((1, 1, 3, 4), (0, 0, 4, 1), 0)])) - buf1 = GPUBuffer(shape=ShapeTracker(shape=(1, 1, 3, 4), views=[View((1, 1, 3, 4), (0, 0, 0, 0), 0)])) - op1 = LazyOp(BinaryOps.MUL, (buf0,buf1,), None) - ast = LazyOp(UnaryOps.RELU, (op1,), None) - compile_and_test_ast(ast) - - def test_cifar_conv(self): - buf0 = GPUBuffer(shape=ShapeTracker(shape=(512, 1, 128, 32, 32, 64, 3, 3), views=[View((512, 64, 34, 34), (65536, 1024, 32, 1), -33), ZeroView((512, 64, 32, 32), ((0, 512), (0, 64), (-1, 33), (-1, 33))), View((512, 1, 128, 32, 32, 64, 3, 3), (73984, 73984, 0, 34, 1, 1156, 34, 1), 0)]), hostbuf=GPUBuffer(shape=(512, 64, 32, 32), force_create=True)) - buf1 = GPUBuffer(shape=ShapeTracker(shape=(512, 1, 128, 32, 32, 64, 3, 3), views=[View((512, 1, 128, 32, 32, 64, 3, 3), (0, 0, 576, 0, 0, 9, 3, 1), 0)]), hostbuf=GPUBuffer(shape=(128, 64, 3, 3), force_create=True)) - op0 = LazyOp(BinaryOps.MUL, (buf0,buf1,), None) - ast = LazyOp(ReduceOps.SUM, (op0,), (512, 1, 128, 32, 32, 1, 1, 1)) - compile_and_test_ast(ast) - - def test_cifar_conv_backward(self): - buf0 = GPUBuffer(shape=ShapeTracker(shape=(256, 1, 512, 3, 3, 512, 8, 8), views=[View((256, 512, 10, 10), (64, 16384, 8, 1), -9), ZeroView((256, 512, 8, 8), ((0, 256), (0, 512), (-1, 9), (-1, 9))), View((256, 1, 512, 3, 3, 512, 8, 8), (51200, 51200, 0, 10, 1, 100, 10, 1), 0)]), hostbuf=GPUBuffer(shape=(512, 256, 8, 8), force_create=True)) - buf1 = GPUBuffer(shape=ShapeTracker(shape=(256, 1, 512, 3, 3, 512, 8, 8), views=[View((256, 1, 512, 3, 3, 512, 8, 8), (0, 0, 64, 0, 0, 32768, 8, 1), 0)]), hostbuf=GPUBuffer(shape=(512, 512, 8, 8), force_create=True)) - op0 = LazyOp(BinaryOps.MUL, (buf0,buf1,), None) - op1 = LazyOp(ReduceOps.SUM, (op0,), (256, 1, 512, 3, 3, 1, 1, 1)) - ast = LazyOp(MovementOps.RESHAPE, (op1,), (256, 512, 3, 3)) - compile_and_test_ast(ast) - - def test_first_op_conv(self): - buf0 = GPUBuffer(shape=ShapeTracker(shape=(1, 64, 128, 8, 4, 3, 3, 3, 4), views=[View((1, 130, 258, 1, 12), (393216, 3072, 12, 12, 1), -3084), ZeroView((1, 128, 256, 1, 12), ((0, 1), (-1, 129), (-1, 257), (0, 1), (0, 12))), View((1, 64, 128, 8, 4, 3, 3, 3, 4), (0, 6192, 24, 0, 0, 3096, 12, 4, 1), 0)]), hostbuf=GPUBuffer(shape=(128, 768, 4), force_create=True)) - buf1 = GPUBuffer(shape=ShapeTracker(shape=(1, 64, 128, 8, 4, 3, 3, 3, 4), views=[View((1, 64, 128, 8, 4, 3, 3, 3, 4), (0, 0, 0, 432, 4, 144, 16, 48, 1), 0)]), hostbuf=GPUBuffer(shape=(8, 108, 4), force_create=True)) - op0 = LazyOp(BinaryOps.MUL, (buf0,buf1,), None) - op1 = LazyOp(ReduceOps.SUM, (op0,), (1, 64, 128, 8, 4, 1, 1, 1, 1)) - buf2 = GPUBuffer(shape=ShapeTracker(shape=(1, 64, 128, 8, 4, 1, 1, 1, 1), views=[View((1, 64, 128, 8, 4, 1, 1, 1, 1), (0, 0, 0, 4, 1, 1, 1, 1, 1), 0)]), hostbuf=GPUBuffer(shape=(32,), force_create=True)) - op2 = LazyOp(BinaryOps.ADD, (op1,buf2,), None) - op3 = LazyOp(UnaryOps.RELU, (op2,), None) - buf3 = GPUBuffer(shape=ShapeTracker(shape=(1, 64, 128, 8, 4, 1, 1, 1, 1), views=[View((1, 64, 128, 8, 4, 1, 1, 1, 1), (0, 0, 0, 0, 0, 1, 1, 1, 1), 0)]), hostbuf=GPUBuffer(shape=(1,), backing=np.array([1.], dtype=np.float32))) - buf4 = GPUBuffer(shape=ShapeTracker(shape=(1, 64, 128, 8, 4, 1, 1, 1, 1), views=[View((1, 64, 128, 8, 4, 1, 1, 1, 1), (0, 0, 0, 0, 0, 1, 1, 1, 1), 0)]), hostbuf=GPUBuffer(shape=(1,), backing=np.array([1.], dtype=np.float32))) - op4 = LazyOp(UnaryOps.EXP, (op2,), None) - op5 = LazyOp(BinaryOps.SUB, (buf4,op4,), None) - op6 = LazyOp(UnaryOps.RELU, (op5,), None) - op7 = LazyOp(BinaryOps.MUL, (buf3,op6,), None) - op8 = LazyOp(BinaryOps.SUB, (op3,op7,), None) - ast = LazyOp(MovementOps.RESHAPE, (op8,), (64, 1024, 4)) - compile_and_test_ast(ast) - - def test_second_op_conv(self): - buf0 = GPUBuffer(shape=ShapeTracker(shape=(1, 64, 128, 8, 4, 1, 1, 3, 3), views=[View((1, 66, 130, 32, 1), (262144, 4096, 32, 1, 1), -4128), ZeroView((1, 64, 128, 32, 1), ((0, 1), (-1, 65), (-1, 129), (0, 32), (0, 1))), View((1, 64, 128, 8, 4, 1, 1, 3, 3), (266240, 4160, 32, 4, 1, 12480, 12480, 4160, 32), 0)]), hostbuf=GPUBuffer(shape=(64, 1024, 4), force_create=True)) - buf1 = GPUBuffer(shape=ShapeTracker(shape=(1, 64, 128, 8, 4, 1, 1, 3, 3), views=[View((1, 64, 128, 8, 4, 1, 1, 3, 3), (0, 0, 0, 36, 1, 0, 0, 12, 4), 0)]), hostbuf=GPUBuffer(shape=(8, 9, 4), force_create=True)) - op0 = LazyOp(BinaryOps.MUL, (buf0,buf1,), None) - op1 = LazyOp(ReduceOps.SUM, (op0,), (1, 64, 128, 8, 4, 1, 1, 1, 1)) - buf2 = GPUBuffer(shape=ShapeTracker(shape=(1, 64, 128, 8, 4, 1, 1, 1, 1), views=[View((1, 64, 128, 8, 4, 1, 1, 1, 1), (0, 0, 0, 4, 1, 1, 1, 1, 1), 0)]), hostbuf=GPUBuffer(shape=(32,), force_create=True)) - op2 = LazyOp(BinaryOps.ADD, (op1,buf2,), None) - op3 = LazyOp(UnaryOps.RELU, (op2,), None) - buf3 = GPUBuffer(shape=ShapeTracker(shape=(1, 64, 128, 8, 4, 1, 1, 1, 1), views=[View((1, 64, 128, 8, 4, 1, 1, 1, 1), (0, 0, 0, 0, 0, 1, 1, 1, 1), 0)]), hostbuf=GPUBuffer(shape=(1,), backing=np.array([1.], dtype=np.float32))) - buf4 = GPUBuffer(shape=ShapeTracker(shape=(1, 64, 128, 8, 4, 1, 1, 1, 1), views=[View((1, 64, 128, 8, 4, 1, 1, 1, 1), (0, 0, 0, 0, 0, 1, 1, 1, 1), 0)]), hostbuf=GPUBuffer(shape=(1,), backing=np.array([1.], dtype=np.float32))) - op4 = LazyOp(UnaryOps.EXP, (op2,), None) - op5 = LazyOp(BinaryOps.SUB, (buf4,op4,), None) - op6 = LazyOp(UnaryOps.RELU, (op5,), None) - op7 = LazyOp(BinaryOps.MUL, (buf3,op6,), None) - op8 = LazyOp(BinaryOps.SUB, (op3,op7,), None) - ast = LazyOp(MovementOps.RESHAPE, (op8,), (64, 1024, 4)) - compile_and_test_ast(ast) - - def test_third_op_conv(self): - buf0 = GPUBuffer(shape=ShapeTracker(shape=(1, 64, 128, 4, 4, 1, 1, 8, 4), views=[View((1, 64, 128, 4, 4, 1, 1, 8, 4), (0, 4096, 32, 0, 0, 0, 0, 4, 1), 0)]), hostbuf=GPUBuffer(shape=(64, 1024, 4), force_create=True)) - buf1 = GPUBuffer(shape=ShapeTracker(shape=(1, 64, 128, 4, 4, 1, 1, 8, 4), views=[View((1, 64, 128, 4, 4, 1, 1, 8, 4), (0, 0, 0, 128, 4, 0, 0, 16, 1), 0)]), hostbuf=GPUBuffer(shape=(4, 32, 4), force_create=True)) - op0 = LazyOp(BinaryOps.MUL, (buf0,buf1,), None) - op1 = LazyOp(ReduceOps.SUM, (op0,), (1, 64, 128, 4, 4, 1, 1, 1, 1)) - buf2 = GPUBuffer(shape=ShapeTracker(shape=(1, 64, 128, 4, 4, 1, 1, 1, 1), views=[View((1, 64, 128, 4, 4, 1, 1, 1, 1), (0, 0, 0, 4, 1, 1, 1, 1, 1), 0)]), hostbuf=GPUBuffer(shape=(16,), force_create=True)) - op2 = LazyOp(BinaryOps.ADD, (op1,buf2,), None) - ast = LazyOp(MovementOps.RESHAPE, (op2,), (64, 512, 4)) - compile_and_test_ast(ast) - - # VALIDHACKS=1 IMAGE=2 DEBUG=4 PYTHONPATH="." GPU=1 OPT=2 python3 test/external_test_gpu_ast.py TestAST.test_reduce_op - # 164 time 27.75 ms running re_S128_4 with [128] None count 4 runtime 1016.06 us 2.07 GFLOPS () -> (128, 1) - # 169 time 22.51 ms running matmul with [4, 16, 128] [4, 16, 16] count 5 runtime 110.08 us 19.06 GFLOPS ('-DMATMUL',) -> (128, 1) - def test_reduce_op(self): - buf0 = GPUBuffer(shape=ShapeTracker(shape=(1, 1, 1, 128, 4, 1, 1, 512, 4), views=[View((1, 1, 1, 128, 4, 1, 1, 512, 4), (0, 0, 0, 0, 0, 0, 0, 4, 1), 0)]), hostbuf=GPUBuffer(shape=(1, 512, 4), force_create=True)) - buf1 = GPUBuffer(shape=ShapeTracker(shape=(1, 1, 1, 128, 4, 1, 1, 512, 4), views=[View((1, 1, 1, 128, 4, 1, 1, 512, 4), (0, 0, 0, 8192, 4, 0, 0, 16, 1), 0)]), hostbuf=GPUBuffer(shape=(128, 2048, 4), force_create=True)) - op0 = LazyOp(BinaryOps.MUL, (buf0,buf1,), None) - op1 = LazyOp(ReduceOps.SUM, (op0,), (1, 1, 1, 128, 4, 1, 1, 1, 1)) - buf2 = GPUBuffer(shape=ShapeTracker(shape=(1, 1, 1, 128, 4, 1, 1, 1, 1), views=[View((1, 1, 1, 128, 4, 1, 1, 1, 1), (512, 512, 512, 4, 1, 1, 1, 1, 1), 0)]), hostbuf=GPUBuffer(shape=(512,), force_create=True)) - op2 = LazyOp(BinaryOps.ADD, (op1,buf2,), None) - op3 = LazyOp(UnaryOps.RELU, (op2,), None) - ast = LazyOp(MovementOps.RESHAPE, (op3,), (1, 128, 4)) - compile_and_test_ast(ast) - - def test_alt_reduce_op(self): - buf0 = GPUBuffer(shape=ShapeTracker(shape=(1, 1, 1, 1, 1, 128, 4, 1, 1, 512, 4), views=[View((1, 1, 1, 1, 1, 128, 4, 1, 1, 512, 4), (0, 0, 0, 0, 0, 0, 0, 0, 0, 4, 1), 0)]), hostbuf=GPUBuffer(shape=(1, 512, 4), force_create=True)) - buf1 = GPUBuffer(shape=ShapeTracker(shape=(1, 1, 1, 1, 1, 128, 4, 1, 1, 512, 4), views=[View((1, 1, 1, 1, 1, 128, 4, 1, 1, 512, 4), (0, 0, 0, 0, 0, 8192, 4, 0, 0, 16, 1), 0)]), hostbuf=GPUBuffer(shape=(128, 2048, 4), force_create=True)) - op0 = LazyOp(BinaryOps.MUL, (buf0,buf1,), None) - op1 = LazyOp(ReduceOps.SUM, (op0,), (1, 1, 1, 1, 1, 128, 4, 1, 1, 1, 1)) - buf2 = GPUBuffer(shape=ShapeTracker(shape=(1, 1, 1, 1, 1, 128, 4, 1, 1, 1, 1), views=[View((1, 1, 1, 1, 1, 128, 4, 1, 1, 1, 1), (0, 0, 0, 0, 0, 4, 1, 0, 0, 0, 0), 0)]), hostbuf=GPUBuffer(shape=(512,), force_create=True)) - op2 = LazyOp(BinaryOps.ADD, (op1,buf2,), None) - buf3 = GPUBuffer(shape=ShapeTracker(shape=(1, 1, 1, 1, 1, 128, 4, 1, 1, 1, 1), views=[View((1, 1, 1, 1, 1, 128, 4, 1, 1, 1, 1), (0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0), 0)]), hostbuf=GPUBuffer(shape=(1,), force_create=True)) - op3 = LazyOp(BinaryOps.MAX, (op2,buf3,), None) - ast = LazyOp(MovementOps.RESHAPE, (op3,), (1, 128, 4)) - compile_and_test_ast(ast) - - # re_S32_16_36_6 is fast - def test_1x1_36_6(self): # 36 <- 6 - buf0 = GPUBuffer(shape=ShapeTracker(shape=(1, 32, 64, 1, 1, 36, 4, 1, 1, 6, 4), views=[View((1, 32, 64, 1, 1, 36, 4, 1, 1, 6, 4), (0, 1536, 24, 0, 0, 0, 0, 0, 0, 4, 1), 0)]), hostbuf=GPUBuffer(shape=(32, 384, 4), force_create=True)) - buf1 = GPUBuffer(shape=ShapeTracker(shape=(1, 32, 64, 1, 1, 36, 4, 1, 1, 6, 4), views=[View((1, 32, 64, 1, 1, 36, 4, 1, 1, 6, 4), (0, 0, 0, 0, 0, 96, 4, 0, 0, 16, 1), 0)]), hostbuf=GPUBuffer(shape=(36, 24, 4), force_create=True)) - op0 = LazyOp(BinaryOps.MUL, (buf0,buf1,), None) - op1 = LazyOp(ReduceOps.SUM, (op0,), (1, 32, 64, 1, 1, 36, 4, 1, 1, 1, 1)) - buf2 = GPUBuffer(shape=ShapeTracker(shape=(1, 32, 64, 1, 1, 36, 4, 1, 1, 1, 1), views=[View((1, 32, 64, 1, 1, 36, 4, 1, 1, 1, 1), (0, 0, 0, 0, 0, 4, 1, 0, 0, 0, 0), 0)]), hostbuf=GPUBuffer(shape=(144,), force_create=True)) - op2 = LazyOp(BinaryOps.ADD, (op1,buf2,), None) - buf3 = GPUBuffer(shape=ShapeTracker(shape=(1, 32, 64, 1, 1, 36, 4, 1, 1, 1, 1), views=[View((1, 32, 64, 1, 1, 36, 4, 1, 1, 1, 1), (0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0), 0)]), hostbuf=GPUBuffer(shape=(1,), force_create=True)) - op3 = LazyOp(BinaryOps.MAX, (op2,buf3,), None) - buf4 = GPUBuffer(shape=ShapeTracker(shape=(1, 32, 64, 1, 1, 36, 4, 1, 1, 1, 1), views=[View((1, 32, 64, 1, 1, 36, 4, 1, 1, 1, 1), (0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0), 0)]), hostbuf=GPUBuffer(shape=(1,), backing=np.array([1.], dtype=np.float32))) - op4 = LazyOp(UnaryOps.EXP, (op2,), None) - op5 = LazyOp(BinaryOps.SUB, (buf4,op4,), None) - buf5 = GPUBuffer(shape=ShapeTracker(shape=(1, 32, 64, 1, 1, 36, 4, 1, 1, 1, 1), views=[View((1, 32, 64, 1, 1, 36, 4, 1, 1, 1, 1), (0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0), 0)]), hostbuf=GPUBuffer(shape=(1,), force_create=True)) - op6 = LazyOp(BinaryOps.MAX, (op5,buf5,), None) - op7 = LazyOp(BinaryOps.SUB, (op3,op6,), None) - ast = LazyOp(MovementOps.RESHAPE, (op7,), (32, 2304, 4)) - compile_and_test_ast(ast, None if OSX else (16, 16, 4)) - - # re_S32_16_6_36 is slow - def test_1x1_6_36(self): # 6 <- 36 - buf0 = GPUBuffer(shape=ShapeTracker(shape=(1, 32, 64, 1, 1, 6, 4, 1, 1, 36, 4), views=[View((1, 32, 64, 1, 1, 6, 4, 1, 1, 36, 4), (0, 9216, 144, 0, 0, 0, 0, 0, 0, 4, 1), 0)]), hostbuf=GPUBuffer(shape=(32, 2304, 4), force_create=True)) - buf1 = GPUBuffer(shape=ShapeTracker(shape=(1, 32, 64, 1, 1, 6, 4, 1, 1, 36, 4), views=[View((1, 32, 64, 1, 1, 6, 4, 1, 1, 36, 4), (0, 0, 0, 0, 0, 576, 4, 0, 0, 16, 1), 0)]), hostbuf=GPUBuffer(shape=(6, 144, 4), force_create=True)) - op0 = LazyOp(BinaryOps.MUL, (buf0,buf1,), None) - op1 = LazyOp(ReduceOps.SUM, (op0,), (1, 32, 64, 1, 1, 6, 4, 1, 1, 1, 1)) - buf2 = GPUBuffer(shape=ShapeTracker(shape=(1, 32, 64, 1, 1, 6, 4, 1, 1, 1, 1), views=[View((1, 32, 64, 1, 1, 6, 4, 1, 1, 1, 1), (0, 0, 0, 0, 0, 4, 1, 0, 0, 0, 0), 0)]), hostbuf=GPUBuffer(shape=(24,), force_create=True)) - op2 = LazyOp(BinaryOps.ADD, (op1,buf2,), None) - buf3 = GPUBuffer(shape=ShapeTracker(shape=(1, 32, 64, 1, 1, 6, 4, 1, 1, 1, 1), views=[View((1, 32, 64, 1, 1, 6, 4, 1, 1, 1, 1), (0, 1536, 24, 0, 0, 4, 1, 0, 0, 0, 0), 0)]), hostbuf=GPUBuffer(shape=(32, 384, 4), force_create=True)) - op3 = LazyOp(BinaryOps.ADD, (op2,buf3,), None) - ast = LazyOp(MovementOps.RESHAPE, (op3,), (32, 384, 4)) - compile_and_test_ast(ast, (6, 16, 4)) - - # re_S32_16_6_24 - def test_1x1_6_24(self): - buf0 = GPUBuffer(shape=ShapeTracker(shape=(1, 32, 64, 1, 1, 6, 4, 1, 1, 24, 4), views=[View((1, 32, 64, 1, 1, 6, 4, 1, 1, 24, 4), (0, 6144, 96, 0, 0, 0, 0, 0, 0, 4, 1), 0)]), hostbuf=GPUBuffer(shape=(32, 1536, 4), force_create=True)) - buf1 = GPUBuffer(shape=ShapeTracker(shape=(1, 32, 64, 1, 1, 6, 4, 1, 1, 24, 4), views=[View((1, 32, 64, 1, 1, 6, 4, 1, 1, 24, 4), (0, 0, 0, 0, 0, 384, 4, 0, 0, 16, 1), 0)]), hostbuf=GPUBuffer(shape=(6, 96, 4), force_create=True)) - op0 = LazyOp(BinaryOps.MUL, (buf0,buf1,), None) - op1 = LazyOp(ReduceOps.SUM, (op0,), (1, 32, 64, 1, 1, 6, 4, 1, 1, 1, 1)) - #buf2 = GPUBuffer(shape=ShapeTracker(shape=(1, 32, 64, 1, 1, 6, 4, 1, 1, 1, 1), views=[View((1, 32, 64, 1, 1, 6, 4, 1, 1, 1, 1), (0, 0, 0, 0, 0, 4, 1, 0, 0, 0, 0), 0)]), hostbuf=GPUBuffer(shape=(24,), force_create=True)) - #op2 = LazyOp(BinaryOps.ADD, (op1,buf2,), None) - ast = LazyOp(MovementOps.RESHAPE, (op1,), (32, 384, 4)) - compile_and_test_ast(ast, (6, 4, 8)) - - def test_full_reduce_op(self): - buf0 = GPUBuffer(shape=ShapeTracker(shape=(1, 512), views=[View((1, 512), (512, 1), 0)]), hostbuf=GPUBuffer(shape=(1, 1, 1, 128, 4, 1, 1, 1, 1), force_create=True)) - buf1 = GPUBuffer(shape=ShapeTracker(shape=(1, 512), views=[View((1, 512), (0, 1), 0)]), hostbuf=GPUBuffer(shape=(512,), force_create=True)) - op0 = LazyOp(BinaryOps.ADD, (buf0,buf1,), None) - buf2 = GPUBuffer(shape=ShapeTracker(shape=(1, 512), views=[View((1, 512), (0, 0), 0)]), hostbuf=GPUBuffer(shape=(1,), backing=np.array([2.], dtype=np.float32))) - op1 = LazyOp(BinaryOps.POW, (op0,buf2,), None) - op2 = LazyOp(ReduceOps.SUM, (op1,), (1, 1)) - buf3 = GPUBuffer(shape=ShapeTracker(shape=(1, 1), views=[View((1, 1), (0, 0), 0)]), hostbuf=GPUBuffer(shape=(1,), backing=np.array([0.5], dtype=np.float32))) - op3 = LazyOp(BinaryOps.POW, (op2,buf3,), None) - buf4 = GPUBuffer(shape=ShapeTracker(shape=(1, 1), views=[View((1, 1), (0, 0), 0)]), hostbuf=GPUBuffer(shape=(1,), backing=np.array([1.e-12], dtype=np.float32))) - op4 = LazyOp(BinaryOps.SUB, (op3,buf4,), None) - op5 = LazyOp(UnaryOps.RELU, (op4,), None) - buf5 = GPUBuffer(shape=ShapeTracker(shape=(1, 1), views=[View((1, 1), (0, 0), 0)]), hostbuf=GPUBuffer(shape=(1,), backing=np.array([1.e-12], dtype=np.float32))) - op6 = LazyOp(BinaryOps.ADD, (op5,buf5,), None) - buf6 = GPUBuffer(shape=ShapeTracker(shape=(1, 1), views=[View((1, 1), (0, 0), 0)]), hostbuf=GPUBuffer(shape=(1,), backing=np.array([3.4e+38], dtype=np.float32))) - op7 = LazyOp(BinaryOps.SUB, (op3,buf6,), None) - op8 = LazyOp(UnaryOps.RELU, (op7,), None) - op9 = LazyOp(BinaryOps.SUB, (op6,op8,), None) - op10 = LazyOp(UnaryOps.RECIPROCAL, (op9,), None) - ast = LazyOp(MovementOps.RESHAPE, (op10,), (1, 1)) - compile_and_test_ast(ast) - - def test_1239_reduce(self): - buf0 = GPUBuffer(shape=ShapeTracker(shape=(1, 1, 1, 1239, 4, 1, 1, 64, 4), views=[View((1, 1, 1, 1239, 4, 1, 1, 64, 4), (0, 0, 0, 0, 0, 0, 0, 4, 1), 0)]), hostbuf=GPUBuffer(shape=(1, 64, 4), force_create=True)) - buf1 = GPUBuffer(shape=ShapeTracker(shape=(1, 1, 1, 1239, 4, 1, 1, 64, 4), views=[View((1, 1, 1, 1239, 4, 1, 1, 64, 4), (0, 0, 0, 1024, 4, 0, 0, 16, 1), 0)]), hostbuf=GPUBuffer(shape=(1239, 256, - 4), force_create=True)) - op0 = LazyOp(BinaryOps.MUL, (buf0,buf1,), None) - op1 = LazyOp(ReduceOps.SUM, (op0,), (1, 1, 1, 1239, 4, 1, 1, 1, 1)) - ast = LazyOp(MovementOps.RESHAPE, (op1,), (1, 1, 1, 1, 4956)) - compile_and_test_ast(ast) - - def test_enet_first_conv_bs32(self): - buf0 = GPUBuffer(shape=ShapeTracker(shape=(8, 1, 32, 112, 112, 3, 3, 3), views=[View((8, 3, 225, 225), (150528, 50176, 224, 1), 0), ZeroView((8, 3, 224, 224), ((0, 8), (0, 3), (0, 225), (0, 225))), View((8, 1, 32, 112, 112, 3, 3, 3), (151875, 151875, 0, 450, 2, 50625, 225, 1), 0)]), hostbuf=GPUBuffer(shape=(8, 3, 224, 224), force_create=True)) - buf1 = GPUBuffer(shape=ShapeTracker(shape=(8, 1, 32, 112, 112, 3, 3, 3), views=[View((8, 1, 32, 112, 112, 3, 3, 3), (0, 0, 27, 0, 0, 9, 3, 1), 0)]), hostbuf=GPUBuffer(shape=(32, 3, 3, 3), force_create=True)) - op0 = LazyOp(BinaryOps.MUL, (buf0,buf1,), None) - op1 = LazyOp(ReduceOps.SUM, (op0,), (8, 1, 32, 112, 112, 1, 1, 1)) - ast = LazyOp(MovementOps.RESHAPE, (op1,), (8, 32, 112, 112)) - compile_and_test_ast(ast) - - def test_enet_reduce_bs32(self): - buf0 = GPUBuffer(shape=ShapeTracker(shape=(3, 1, 32, 3, 3, 32, 112, 112), views=[View((3, 32, 225, 225), (50176, 150528, 224, 1), 0), ZeroView((3, 32, 224, 224), ((0, 3), (0, 32), (0, 225), (0, 225))), View((3, 1, 32, 3, 3, 32, 112, 112), (1620000, 1620000, 0, 225, 1, 50625, 450, 2), 0)]), hostbuf=GPUBuffer(shape=(32, 3, 224, 224), force_create=True)) - buf1 = GPUBuffer(shape=ShapeTracker(shape=(3, 1, 32, 3, 3, 32, 112, 112), views=[View((3, 1, 32, 3, 3, 32, 112, 112), (0, 12845056, 401408, 0, 0, 12544, 112, 1), 0)]), hostbuf=GPUBuffer(shape=(1, 1, 32, 1, 1, 32, 112, 112), force_create=True)) - op0 = LazyOp(BinaryOps.MUL, (buf0,buf1,), None) - op1 = LazyOp(ReduceOps.SUM, (op0,), (3, 1, 32, 3, 3, 1, 1, 1)) - ast = LazyOp(MovementOps.RESHAPE, (op1,), (3, 32, 3, 3)) - compile_and_test_ast(ast) - - -if __name__ == '__main__': - unittest.main() diff --git a/tinygrad_repo/test/external/external_test_image.py b/tinygrad_repo/test/external/external_test_image.py deleted file mode 100644 index 3e246ee..0000000 --- a/tinygrad_repo/test/external/external_test_image.py +++ /dev/null @@ -1,52 +0,0 @@ -#!/usr/bin/env python -import os -import unittest -import numpy as np -if 'IMAGE' not in os.environ: - os.environ['IMAGE'] = '2' -os.environ['GPU'] = '1' -os.environ['OPT'] = '2' -from tinygrad.tensor import Tensor -from tinygrad.nn import Conv2d -Tensor.no_grad = True - -class TestImage(unittest.TestCase): - def test_create_image(self): - t = Tensor.ones(128, 128, 1) - t = t.reshape(128, 32, 4) + 3 - t.realize() - np.testing.assert_array_equal(t.numpy(), np.ones((128,32,4))*4) - - def test_sum_image(self): - t1 = Tensor.ones(16, 16, 1).reshape(16, 4, 4) + 3 - t1.realize() - t1 = t1.sum() - t1.realize() - assert t1.numpy() == 16*4*4*4, f"got {t1.numpy()}" - - def test_add_image(self): - t1 = Tensor.ones(16, 16, 1).reshape(16, 4, 4) + 3 - t2 = Tensor.ones(16, 16, 1).reshape(16, 4, 4) + 4 - t1.realize() - t2.realize() - t3 = t1 + t2 - t3.realize() - np.testing.assert_array_equal(t3.numpy(), np.ones((16,4,4))*9) - - def test_padded_conv(self): - bs, in_chans, out_chans = 1,12,32 - tiny_conv = Conv2d(in_chans, out_chans, 3, bias=None, padding=1) - tiny_dat = Tensor.ones(bs, 12, 64, 128) - tiny_conv(tiny_dat).realize() - - def test_op_conv(self): - bs, in_chans, out_chans = 1,12,32 - tiny_conv = Conv2d(in_chans, out_chans, 3, bias=None, padding=1) - tiny_dconv = Conv2d(out_chans, out_chans, 1, bias=None, padding=0) - tiny_dat = Tensor.ones(bs, 12, 64, 128) - p2 = tiny_conv(tiny_dat).relu() - p2 = tiny_dconv(p2) - p2.realize() - -if __name__ == '__main__': - unittest.main() diff --git a/tinygrad_repo/test/external/external_test_jit_on_models.py b/tinygrad_repo/test/external/external_test_jit_on_models.py deleted file mode 100644 index f03615b..0000000 --- a/tinygrad_repo/test/external/external_test_jit_on_models.py +++ /dev/null @@ -1,45 +0,0 @@ -#!/usr/bin/env python -import unittest -import numpy as np -from tinygrad.tensor import Tensor -from tinygrad.jit import TinyJit, JIT_SUPPORTED_DEVICE -from tinygrad.helpers import dtypes, CI -from tinygrad.ops import Device -from test.helpers import derandomize_model - -from examples.llama import Transformer - -def helper_test_jitted_correctness(gen, train, train_jit): - nojit = train(*gen()).numpy() - for _ in range(5): jit = train_jit(*gen()).numpy() - np.testing.assert_allclose(nojit, jit, rtol=1e-3, atol=1e-5) - -@unittest.skipUnless(Device.DEFAULT in JIT_SUPPORTED_DEVICE, "needs JIT") -class TestJittedModels(unittest.TestCase): - def test_jitted_tiny_llama(self): - old_type = Tensor.default_type - Tensor.default_type = dtypes.float16 - - args_tiny = {"dim": 1024, "multiple_of": 256, "n_heads": 8, "n_layers": 8, "norm_eps": 1e-05, "vocab_size": 1000} - model = Transformer(**args_tiny) - derandomize_model(model) - def test(t): return model(t, 0).realize() - - @TinyJit - def test_jit(t): return model(t, 0).realize() - helper_test_jitted_correctness(lambda: (Tensor([[1,]]),), test, test_jit) - Tensor.default_type = old_type - - @unittest.skipUnless(not CI, "huge for CI") - def test_jitted_stable_diffusion(self): - from examples.stable_diffusion import UNetModel - model = UNetModel() - derandomize_model(model) - def test(t, t2): return model(t, 801, t2).realize() - - @TinyJit - def test_jit(t, t2): return model(t, 801, t2).realize() - helper_test_jitted_correctness(lambda: (Tensor.randn(1, 4, 16, 16),Tensor.randn(1, 77, 768)), test, test_jit) - -if __name__ == "__main__": - unittest.main() diff --git a/tinygrad_repo/test/external/external_test_onnx_backend.py b/tinygrad_repo/test/external/external_test_onnx_backend.py deleted file mode 100644 index bb41463..0000000 --- a/tinygrad_repo/test/external/external_test_onnx_backend.py +++ /dev/null @@ -1,208 +0,0 @@ -import unittest -from onnx.backend.base import Backend, BackendRep -import onnx.backend.test -import numpy as np -from tinygrad.tensor import Tensor -from typing import Any, Tuple -from tinygrad.helpers import getenv, CI - -# pip3 install tabulate -pytest_plugins = 'onnx.backend.test.report', - -from extra.onnx import get_run_onnx - -class TinygradModel(BackendRep): - def __init__(self, run_onnx, input_names): - super().__init__() - self.fxn = run_onnx - self.input_names = input_names - - def run(self, inputs: Any, **kwargs: Any) -> Tuple[Any, ...]: - real_inputs = {k:v for k,v in zip(self.input_names, inputs)} - ret = self.fxn(real_inputs, debug=True) - return tuple(x.numpy() if isinstance(x, Tensor) else [i.numpy() for i in x] if isinstance(x, list) else np.array(x) for x in ret.values()) - -class TinygradBackend(Backend): - @classmethod - def prepare(cls, model, device): - input_all = [x.name for x in model.graph.input] - input_initializer = [x.name for x in model.graph.initializer] - net_feed_input = [x for x in input_all if x not in input_initializer] - print("prepare", cls, device, net_feed_input) - run_onnx = get_run_onnx(model) - return TinygradModel(run_onnx, net_feed_input) - - @classmethod - def supports_device(cls, device: str) -> bool: - return device == "CPU" - -backend_test = onnx.backend.test.BackendTest(TinygradBackend, __name__) - -# no support for reduce with multiply (needs llop) -backend_test.exclude('test_reduce_prod_*') - -# TODO figure out why it's returning wrong values, geohotstan's uneducated guess is it's due to imprecision from float64 (double) -> float32 -# see Type Constraints: https://onnx.ai/onnx/operators/onnx_aionnxpreviewtraining_Adam.html#type-constraints -backend_test.exclude('test_adam_multiple_cpu') -backend_test.exclude('test_nesterov_momentum_cpu') - -# we only support float32 -backend_test.exclude('uint8') -backend_test.exclude('uint16') -backend_test.exclude('uint32') -backend_test.exclude('uint64') -backend_test.exclude('int8') -backend_test.exclude('int16') -backend_test.exclude('float64') -backend_test.exclude('string') - -backend_test.exclude('test_pow_types_int*') -backend_test.exclude('test_cast_*') -backend_test.exclude('test_castlike_*') -backend_test.exclude('test_convinteger_*') -backend_test.exclude('test_matmulinteger_*') - -backend_test.exclude('test_reduce_log_sum_exp*') # dependent on actual float64 implementation for backends -backend_test.exclude('test_operator_add*') # dependent on float64 math. Without it values default to 0 or inf - -# we don't support indexes -# backend_test.exclude('test_argmax_*') # Needs more work: select_last_index -# backend_test.exclude('test_argmin_*') # Needs more work: select_last_index -backend_test.exclude('test_nonzero_*') - -# no support for mod -backend_test.exclude('test_mod_*') - -# no boolean ops (2d, 3d, 4d) -backend_test.exclude('test_bitshift_*') - -# no scatternd gathernd -backend_test.exclude('test_gathernd_*') -backend_test.exclude('test_scatternd_*') - -# no quantize -backend_test.exclude('test_dynamicquantizelinear_*') -backend_test.exclude('test_qlinearmatmul_*') -backend_test.exclude('test_qlinearconv_*') -backend_test.exclude('test_quantizelinear_*') - -# no rnn -backend_test.exclude('test_gru_*') -backend_test.exclude('test_rnn_*') -backend_test.exclude('test_lstm_*') -backend_test.exclude('test_simple_rnn_*') - -# no control flow -backend_test.exclude('test_if_*') -backend_test.exclude('test_loop*') -backend_test.exclude('test_range_float_type_positive_delta_expanded_cpu') # requires loop - -# unsupported (strange) ops -backend_test.exclude('test_bitwise_*') -backend_test.exclude('test_blackmanwindow_*') -backend_test.exclude('test_bernoulli_*') -backend_test.exclude('test_cumsum_*') -backend_test.exclude('test_det_*') - -backend_test.exclude('test_tril_zero_cpu') # TODO: zero array support -backend_test.exclude('test_triu_zero_cpu') # TODO: zero array support - -backend_test.exclude('test_col2im_*') -backend_test.exclude('test_hammingwindow_*') -backend_test.exclude('test_hannwindow_*') -backend_test.exclude('test_hardmax_*') -backend_test.exclude('test_gridsample_*') -backend_test.exclude('test_dft_*') -backend_test.exclude('test_einsum_*') -backend_test.exclude('test_strnorm_*') -backend_test.exclude('test_unique_*') -backend_test.exclude('test_sequence_*') -backend_test.exclude('test_nonmaxsuppression_*') -backend_test.exclude('test_reversesequence_*') -backend_test.exclude('test_roialign_*') -backend_test.exclude('test_top_k_*') -backend_test.exclude('test_tfidfvectorizer_*') -backend_test.exclude('test_stft_*') -backend_test.exclude('test_melweightmatrix_*') - -# more strange ops -backend_test.exclude('test_basic_deform_conv_*') -backend_test.exclude('test_deform_conv_*') -backend_test.exclude('test_lppool_*') -backend_test.exclude('test_depthtospace_*') -backend_test.exclude('test_spacetodepth_*') -backend_test.exclude('test_scan*') -backend_test.exclude('test_split_to_sequence_*') -backend_test.exclude('test_resize_downsample_scales_cubic_*') # unsure how to implement cubic -backend_test.exclude('test_resize_downsample_sizes_cubic_*') # unsure how to implement cubic -backend_test.exclude('test_resize_upsample_scales_cubic_*') # unsure how to implement cubic -backend_test.exclude('test_resize_upsample_sizes_cubic_*') # unsure how to implement cubic - -# rest of the failing tests -backend_test.exclude('test_averagepool_2d_dilations_cpu') # dilations != 1 not supported for avgpool -backend_test.exclude('test_convtranspose_autopad_same_cpu') # TODO geohotstan has no idea how this is done, autopad requires output_shape but output_shape requires pads from autopad -backend_test.exclude('test_optional_has_element_empty_optional_input_cpu') # Attempts to create Tensor from None -backend_test.exclude('test_range_int32_type_negative_delta_expanded_cpu') # AttributeProto.GRAPH not implemented -backend_test.exclude('test_reshape_allowzero_reordered_cpu') # reshaping to 0 shape -backend_test.exclude('test_resize_downsample_scales_linear_antialias_cpu') # antialias not implemented -backend_test.exclude('test_resize_downsample_sizes_linear_antialias_cpu') # antialias not implemented -backend_test.exclude('test_resize_tf_crop_and_resize_cpu') # unsure about fill value after clip -backend_test.exclude('test_operator_addconstant_cpu') # bad data type - -# issue 1556 https://github.com/tinygrad/tinygrad/issues/1556 -backend_test.exclude('test_isinf_cpu') -backend_test.exclude('test_isinf_negative_cpu') -backend_test.exclude('test_isinf_positive_cpu') -backend_test.exclude('test_isnan_cpu') - -# issue 1791 fast math messes with these https://github.com/tinygrad/tinygrad/issues/1791 -backend_test.exclude('test_resize_upsample_sizes_nearest_axes_2_3_cpu') -backend_test.exclude('test_resize_upsample_sizes_nearest_axes_3_2_cpu') -backend_test.exclude('test_resize_upsample_sizes_nearest_cpu') - -# issue 2067 potentially also a fastmath issue https://github.com/tinygrad/tinygrad/issues/2067 -if getenv('METAL'): - backend_test.exclude('test_maxpool_2d_pads_cpu') - backend_test.exclude('test_maxpool_2d_same_lower_cpu') - -# Don't know how to treat special TensorProto like TensorProto.FLOAT8E4M3FN -if getenv("CPU") or getenv("TORCH"): - backend_test.exclude('test_dequantizelinear_axis_cpu') - backend_test.exclude('test_dequantizelinear_cpu') - -# compiled backends cannot reshape to and from 0 -if getenv('LLVM') or getenv('GPU') or getenv('CLANG') or getenv('METAL') or getenv('CUDA'): - backend_test.exclude('test_slice_start_out_of_bounds_cpu') - backend_test.exclude('test_constantofshape_int_shape_zero_cpu') - -if getenv('GPU') or getenv('METAL'): - backend_test.exclude('test_mish_cpu') # weird inaccuracy - backend_test.exclude('test_mish_expanded_cpu') # weird inaccuracy - backend_test.exclude('test_eyelike_with_dtype_cpu') # backend does not support dtype: Double - -# Segfaults in CI -if (getenv('LLVM') or getenv('CUDA')) and CI: - backend_test.exclude('test_max_float16_cpu') - backend_test.exclude('test_min_float16_cpu') - -# disable model tests for now since they are slow -if not getenv("MODELTESTS"): - for x in backend_test.test_suite: - if 'OnnxBackendRealModelTest' in str(type(x)): - backend_test.exclude(str(x).split(" ")[0]) -else: - # model tests all pass! - backend_test.include('test_resnet50') - backend_test.include('test_inception_v1') - backend_test.include('test_inception_v2') - backend_test.include('test_densenet121') - backend_test.include('test_shufflenet') - backend_test.include('test_squeezenet') - backend_test.include('test_bvlc_alexnet') - backend_test.include('test_zfnet512') - backend_test.include('test_vgg19') - -globals().update(backend_test.enable_report().test_cases) - -if __name__ == '__main__': - unittest.main() diff --git a/tinygrad_repo/test/external/external_test_opt.py b/tinygrad_repo/test/external/external_test_opt.py deleted file mode 100644 index 1e3b01e..0000000 --- a/tinygrad_repo/test/external/external_test_opt.py +++ /dev/null @@ -1,392 +0,0 @@ -#!/usr/bin/env python -import os - -import torch -if "OPT" not in os.environ: - os.environ["OPT"] = "2" - -import gc -import numpy as np - -import unittest -from tinygrad.tensor import Tensor, Device -from tinygrad import nn -from tinygrad.helpers import getenv -from tinygrad.nn import optim -from tinygrad.helpers import GlobalCounters -from tinygrad.lazy import PUSH_PERMUTES -from tinygrad.jit import CacheCollector - -class CLCache: - def __init__(self, allowed=None, strict=False, preclear=True): self.allowed, self.strict, self.preclear = allowed, strict, preclear - def __enter__(self): - if self.preclear: - gc.collect() - for x in [x for x in gc.get_objects() if isinstance(x, Tensor)]: - x.realize() - GlobalCounters.reset() - CacheCollector.start() - print("cache: entering") - def __exit__(self, type, value, traceback): - cache = CacheCollector.finish() - print(f"cache: exiting with size {len(cache)}", f"allowed {self.allowed}" if self.allowed is not None else "") - if self.allowed is not None: - assert len(cache) <= self.allowed and (not self.strict or len(cache) == self.allowed), f"used too many kernels! {len(cache)} > {self.allowed}" - -from models.convnext import ConvNeXt -from models.efficientnet import EfficientNet -from models.resnet import ResNet18 -from models.vit import ViT -from tinygrad.nn.state import get_parameters - -@unittest.skipUnless(Device.DEFAULT == "GPU", "Not Implemented") -class TestInferenceMinKernels(unittest.TestCase): - def setUp(self): - Tensor.training = False - - @unittest.skipIf(not PUSH_PERMUTES, "this test requires PUSH_PERMUTES") - def test_convnext(self): - model = ConvNeXt() - for p in get_parameters(model): p.assign(np.zeros(p.shape, dtype=p.dtype.np)) - img = Tensor.randn(1, 3, 224, 224) - with CLCache(129): - model(img).realize() - - def test_enet(self): - model = EfficientNet(getenv("ENET_NUM", 0), has_se=False) - for p in get_parameters(model): p.assign(np.zeros(p.shape, dtype=p.dtype.np)) - img = Tensor.randn(1, 3, 224, 224) - with CLCache(51): - model.forward(img).realize() - - def test_enet_se(self): - model = EfficientNet(getenv("ENET_NUM", 0), has_se=True) - for p in get_parameters(model): p.assign(np.zeros(p.shape, dtype=p.dtype.np)) - img = Tensor.randn(1, 3, 224, 224) - # TODO: this seems very high - with CLCache(115): - model.forward(img).realize() - - def test_resnet(self): - model = ResNet18() - for p in get_parameters(model): p.assign(np.zeros(p.shape, dtype=p.dtype.np)) - img = Tensor.randn(1, 3, 224, 224) - with CLCache(26): - model.forward(img).realize() - - def test_vit(self): - model = ViT(embed_dim=192, num_heads=3) - for p in get_parameters(model): p.assign(np.zeros(p.shape, dtype=p.dtype.np)) - img = Tensor.randn(1, 3, 224, 224) - with CLCache(222): # NOTE: this is way too high - out = model.forward(img) - assert len(CacheCollector.cache) == 0, "ViT prerealized?" - out.realize() - - def test_llama(self): - from examples.llama import Transformer - args_tiny = {"dim": 512, "multiple_of": 256, "n_heads": 8, "n_layers": 4, "norm_eps": 1e-05, "vocab_size": 1000} - model = Transformer(**args_tiny) - for p in get_parameters(model): p.assign(np.zeros(p.shape, dtype=p.dtype.np)) - with CLCache(85): - model(Tensor([[1,2,3,4]]), 0).realize() - -@unittest.skipUnless(Device.DEFAULT == "GPU", "Not Implemented") -class TestOptBinOp(unittest.TestCase): - def _test_no_binop_rerun(self, f1, f2=None, allowed=1): - a = Tensor.randn(16, 16) - b = Tensor.randn(16, 16) - with CLCache(): - c = f1(a, b) - if f2 is not None: d = f2(a, b) - c.realize() - if f2 is not None: d.realize() - assert len(CacheCollector.cache) == allowed, "binop was rerun!" - if f2 is not None: np.testing.assert_allclose(c.numpy().ravel(), d.numpy().ravel(), rtol=1e-3, atol=1e-5) - - def test_no_binop_rerun(self): return self._test_no_binop_rerun(lambda a,b: a*b, lambda a,b: (a*b).reshape(16, 16, 1)) - def test_no_binop_rerun_alt(self): return self._test_no_binop_rerun(lambda a,b: (a*b).reshape(16, 16, 1), lambda a,b: a*b) - def test_no_binop_rerun_reduce_broadcast(self): return self._test_no_binop_rerun(lambda a,b: a.sum()+b, lambda a,b: a.sum().reshape(1,1)+b, allowed=2) - @unittest.skip("this test started failing with the new change, based movementop issue") - def test_no_binop_rerun_transposed(self): return self._test_no_binop_rerun(lambda a,b: (a.T*b.T).T, lambda a,b: a*b) - def test_no_binop_rerun_mid_reshape(self): return self._test_no_binop_rerun(lambda a,b: (a*b).reshape(256)+a.reshape(256)) - - # currently non working tests - #def test_no_binop_rerun_preshape(self): return self._test_no_binop_rerun(lambda a,b: a.reshape(16, 16, 1)*b.reshape(16, 16, 1), lambda a,b: a*b) - #def test_no_binop_rerun_reduce(self): return self._test_no_binop_rerun(lambda a,b: (a*b).sum(), lambda a,b: (a*b).reshape(16, 16, 1).sum()) - #def test_no_binop_rerun_reduce_alt(self): return self._test_no_binop_rerun(lambda a,b: a.sum(1)+b[0], lambda a,b: a.sum(1).reshape(1,16)+b[0]) - -@unittest.skipUnless(Device.DEFAULT == "GPU", "Not Implemented") -class TestOptReduceLoop(unittest.TestCase): - @unittest.skip("this is broken") - def test_loop_left(self): - a = Tensor.randn(16, 16) - b = Tensor.randn(16, 16) - with CLCache(): - t = a.sum(0) - b = t.reshape(16,1).expand(16,16).sum(0) - c = (t+b) - c.realize() - assert len(CacheCollector.cache) == 2, "loop left fusion broken" - - def test_loop_right(self): - a = Tensor.randn(16, 16) - b = Tensor.randn(16, 16) - with CLCache(): - t = a.sum(0) - b = t.reshape(16,1).expand(16,16).sum(0) - c = (b+t) - c.realize() - assert len(CacheCollector.cache) == 2, "loop right fusion broken" - -@unittest.skipUnless(Device.DEFAULT == "GPU", "Not Implemented") -class TestOptWChild(unittest.TestCase): - def test_unrealized_child(self): - a = Tensor.randn(16, 16) - b = Tensor.randn(16, 16) - with CLCache(): - c = (a*b).sum() - d = c+1 - e = c+2 - d.realize() - assert len(CacheCollector.cache) == 2, "don't fuse if you have children" - -@unittest.skipUnless(Device.DEFAULT == "GPU", "Not Implemented") -class TestOpt(unittest.TestCase): - def test_muladd(self): - a,b,c = [Tensor.ones(2,2) for _ in range(3)] - with CLCache(): - d = a * b + c - d.realize() - assert len(CacheCollector.cache) == 1, "optimizer didn't fold muladd" - np.testing.assert_allclose(d.numpy(), np.ones((2,2))*2, rtol=1e-5) - - def test_fold_reduce_elementwise(self): - img = Tensor.ones(32) - addme = Tensor.ones(1) - with CLCache(): - ret = img.sum() + addme - ret.realize() - assert len(CacheCollector.cache) == 1, "optimizer didn't fold reduce/elementwise" - assert ret.numpy()[0] == 33 - - def test_fold_batchnorm(self): - with Tensor.train(): - img = Tensor.ones(1,32,4,4) - bn = nn.BatchNorm2d(32, track_running_stats=False) - with CLCache(): - img_bn = bn(img).realize() - print(img_bn) - assert len(CacheCollector.cache) == 3, f"optimizer didn't fold batchnorm, got {len(CacheCollector.cache)}" - # Tensor.training = False - - def test_fold_conv_sgd(self): - with Tensor.train(): - img = Tensor.ones(2,3,4,4) - c1 = nn.Conv2d(3,32,3) - opt = optim.SGD(get_parameters(c1)) - with CLCache(): - opt.zero_grad() - c1(img).relu().sum().backward() - opt.step() - # TODO: this should be 4, but the sum output child stays around - # with pushing_permutes it can be 3 - # TODO: broken with optim fixes - assert len(CacheCollector.cache) in [4,5,6], f"optimizer didn't fold conv-backward SGD, got {len(CacheCollector.cache)}" - # Tensor.training = False - - def test_fold_2convs_sgd(self): - with Tensor.train(): - img = Tensor.ones(2,3,64,64) - c1 = nn.Conv2d(3,16,3,bias=False) - c2 = nn.Conv2d(16,32,3,bias=False) - opt = optim.SGD(get_parameters([c1, c2])) - with CLCache(allowed=9): - opt.zero_grad() - c2(c1(img).relu()).relu().sum().backward() - opt.step() - # Tensor.training = False - - def test_fold_4convs_sgd(self): - with Tensor.train(): - img = Tensor.ones(2,3,64,64) - c1 = nn.Conv2d(3,4,3,bias=False) - c2 = nn.Conv2d(4,8,3,bias=False) - c3 = nn.Conv2d(8,16,3,bias=False) - c4 = nn.Conv2d(16,32,3,bias=False) - opt = optim.SGD(get_parameters([c1, c2, c3, c4])) - with CLCache(allowed=19): - opt.zero_grad() - c4(c3(c2(c1(img).relu()).relu()).relu()).relu().sum().backward() - opt.step() - # Tensor.training = False - - def test_fold_conv_batchnorm_sgd(self): - with Tensor.train(): - img = Tensor.ones(1,3,4,4) - c1 = nn.Conv2d(3,32,3) - bn = nn.BatchNorm2d(32, track_running_stats=False) - opt = optim.SGD(get_parameters([c1, bn])) - with CLCache(allowed=18): # this is too high - img_bn = bn(c1(img)).elu().sum() - opt.zero_grad() - img_bn.backward() - opt.step() - # Tensor.training = False - - def test_fold_conv_batchnorm_notrain(self): - img = Tensor.ones(1,3,8,8) - c1 = nn.Conv2d(3,32,3) - bn = nn.BatchNorm2d(32, track_running_stats=False) - # precache the bn - img_conv = bn(c1(img)).relu().realize() - with CLCache(): - img_conv = bn(c1(img)).relu().realize() - assert len(CacheCollector.cache) == 1, f"optimizer didn't fold conv-batchnorm at test time, got {len(CacheCollector.cache)}" - - def test_fold_conv_batchnorm(self): - with Tensor.train(): - img = Tensor.ones(1,3,8,8) - c1 = nn.Conv2d(3,32,3) - bn = nn.BatchNorm2d(32, track_running_stats=False) - with CLCache(): - img_conv = bn(c1(img)).relu().realize() - print(img_conv) - assert len(CacheCollector.cache) == 4, f"optimizer didn't fold conv-batchnorm, got {len(CacheCollector.cache)}" - - def test_fold_conv_elu(self): - img = Tensor.ones(1,4,8,8) - c1 = nn.Conv2d(4, 4, kernel_size=3) - c2 = nn.Conv2d(4, 4, kernel_size=3) - with CLCache(): - img_conv = img.sequential([c1, Tensor.elu, c2, Tensor.elu]).realize() - print(img_conv) - assert len(CacheCollector.cache) == 2, "optimizer didn't fold conv/elu" - - def test_fold_conv_relu(self): - img = Tensor.ones(1,4,8,8) - c1 = nn.Conv2d(4, 4, kernel_size=3) - c2 = nn.Conv2d(4, 4, kernel_size=3) - with CLCache(): - img_conv = img.sequential([c1, Tensor.relu, c2, Tensor.relu]).realize() - print(img_conv) - assert len(CacheCollector.cache) == 2, "optimizer didn't fold conv/relu" - - def test_fold_conv_relu_nobias(self): - img = Tensor.ones(1,4,8,8) - c1 = nn.Conv2d(4, 4, kernel_size=3, bias=False) - c2 = nn.Conv2d(4, 4, kernel_size=3, bias=False) - with CLCache(): - img_conv = img.sequential([c1, Tensor.relu, c2, Tensor.relu]).realize() - print(img_conv) - assert len(CacheCollector.cache) == 2, "optimizer didn't fold conv/relu" - - def test_permute_was_pushed(self): - a = Tensor.randn(16, 16, 16) - with CLCache(): - c = a.sum(2) - d = c.permute(1,0).contiguous() - d.realize() - cache_len = len(CacheCollector.cache) - np.testing.assert_allclose(a.numpy().sum(2).transpose(1,0), d.numpy(), rtol=1e-3, atol=1e-5) - if PUSH_PERMUTES: assert cache_len == 1, "permute wasn't pushed!" - - def test_permute_was_pushed_through_contract_reshape(self): - a = Tensor.randn(4, 4, 4, 4, 4) - with CLCache(): - c = a.sum(-1) - d = c.reshape(16,16).permute(1,0).contiguous() - d.realize() - cache_len = len(CacheCollector.cache) - np.testing.assert_allclose(a.numpy().sum(-1).reshape(16,16).transpose(1,0), d.numpy(), rtol=1e-3, atol=1e-5) - if PUSH_PERMUTES: assert cache_len == 1, "permute wasn't pushed!" - - def test_permute_was_pushed_through_contractw1s_reshape(self): - a = Tensor.randn(4, 4, 4, 4, 4) - with CLCache(): - c = a.sum(-1) - d = c.reshape(16,1,16).permute(2,1,0).contiguous() - d.realize() - cache_len = len(CacheCollector.cache) - np.testing.assert_allclose(a.numpy().sum(-1).reshape(16,1,16).transpose(2,1,0), d.numpy(), rtol=1e-3, atol=1e-5) - if PUSH_PERMUTES: assert cache_len == 1, "permute wasn't pushed!" - - # TODO: push permute through expansion reshape - @unittest.skip("expansion can't push expand permute yet") - @unittest.skipIf(not PUSH_PERMUTES, "this test requires PUSH_PERMUTES") - def test_permute_was_pushed_through_expand_reshape(self): - a = Tensor.randn(16, 16, 16) - with CLCache(): - c = a.sum(2) - d = c.reshape(4,4,4,4).permute(2,3,0,1).contiguous() - d.realize() - cache_len = len(CacheCollector.cache) - np.testing.assert_allclose(a.numpy().sum(2).transpose(1,0).reshape(4,4,4,4), d.numpy(), rtol=1e-3, atol=1e-5) - if PUSH_PERMUTES: assert cache_len == 1, "permute wasn't pushed!" - - @unittest.skipIf(PUSH_PERMUTES, "this test is broken with PUSH_PERMUTES") - def test_no_reduceop_rerun(self): - a = Tensor.randn(16, 16, 16) - with CLCache(): - c = a.sum(2) - d = a.sum(2).permute(1,0) - c.realize() - d.realize() - cache_len = len(CacheCollector.cache) - np.testing.assert_allclose(c.numpy().transpose(1,0), d.numpy(), rtol=1e-3, atol=1e-5) - assert cache_len == 1, "reduceop was rerun!" - - @unittest.skipIf(PUSH_PERMUTES, "this test is broken with PUSH_PERMUTES") - def test_no_reduceop_rerun_alt(self): - a = Tensor.randn(16, 16, 16) - with CLCache(): - c = a.sum(2).permute(1,0) - d = a.sum(2) - c.realize() - d.realize() - cache_len = len(CacheCollector.cache) - np.testing.assert_allclose(c.numpy(), d.numpy().transpose(1,0), rtol=1e-3, atol=1e-5) - assert cache_len == 1, "reduceop was rerun!" - - def test_fold_with_contiguous(self): - a = Tensor.randn(16, 16, 16) - b = Tensor.randn(16, 16) - with CLCache(): - c = (a.sum(2).contiguous() + b).contiguous() - c.realize() - cache_len = len(CacheCollector.cache) - assert cache_len == 1, "contiguous wasn't folded" - - def _test_fold_expand_reduce_helper(self, n, m, axis, allowed): - b = torch.ones(n, m).sum(axis).reshape(n, 1).expand(n, m).sum(axis) - with CLCache(allowed=allowed): - a = Tensor.ones(n, m).sum(axis).reshape(n, 1).expand(n, m).sum(axis) - a.realize() - cache_len = len(CacheCollector.cache) - np.testing.assert_allclose(a.numpy(), b.numpy(), rtol=1e-3, atol=1e-5) - return cache_len - - def test_expand_reduce_is_folded_on_same_axis(self): - for axis in [0, 1]: - for n in [4, 8, 16]: - b = torch.ones(n, n).sum(axis).reshape(n, 1).expand(n, n).sum(axis) - with CLCache(allowed=2): - a = Tensor.ones(n, n).sum(axis).reshape(n, 1).expand(n, n).sum(axis) - a.realize() - cache_len = len(CacheCollector.cache) - np.testing.assert_allclose(a.numpy(), b.numpy(), rtol=1e-3, atol=1e-5) - return cache_len - - def test_expand_reduce_is_not_folded_on_different_axes(self): - axis1, axis2 = 0, 1 - for n in [4, 8, 16]: - b = torch.ones(n, n).sum(axis1).reshape(n, 1).expand(n, n).sum(axis2) - with CLCache(allowed=3): - a = Tensor.ones(n, n).sum(axis1).reshape(n, 1).expand(n, n).sum(axis2) - a.realize() - cache_len = len(CacheCollector.cache) - np.testing.assert_allclose(a.numpy(), b.numpy(), rtol=1e-3, atol=1e-5) - return cache_len - -if __name__ == '__main__': - unittest.main() diff --git a/tinygrad_repo/test/external/external_test_optim.py b/tinygrad_repo/test/external/external_test_optim.py deleted file mode 100644 index 2851f11..0000000 --- a/tinygrad_repo/test/external/external_test_optim.py +++ /dev/null @@ -1,75 +0,0 @@ -#!/usr/bin/env python -import unittest -import numpy as np -import tensorflow as tf -import tensorflow_addons as tfa -from tinygrad.tensor import Tensor -from tinygrad.nn.optim import LAMB - -np.random.seed(1337) -x_init = np.random.randn(1,4).astype(np.float32) -W_init = np.random.randn(4,4).astype(np.float32) -m_init = np.random.randn(1,4).astype(np.float32) - -class TinyNet: - def __init__(self): - self.x = Tensor(x_init.copy(), requires_grad=True) - self.W = Tensor(W_init.copy(), requires_grad=True) - self.m = Tensor(m_init.copy()) - - def forward(self): - out = self.x.matmul(self.W).relu() - out = out.log_softmax(1) - out = out.mul(self.m).add(self.m).sum() - return out - -class TinyNetTF: - def __init__(self): - self.x = tf.Variable(x_init.copy(), trainable=True) - self.W = tf.Variable(W_init.copy(), trainable=True) - self.m = tf.constant(m_init.copy()) - - def forward(self): - out = tf.matmul(self.x, self.W) - out = tf.nn.relu(out) - out = tf.nn.log_softmax(out, axis=1) - out = tf.multiply(out, self.m) + self.m - out = tf.reduce_sum(out) - return out - -def step(optim, steps=1, kwargs={}): - net = TinyNet() - optim = optim([net.x, net.W], **kwargs) - for _ in range(steps): - out = net.forward() - optim.zero_grad() - out.backward() - optim.step() - return net.x.detach().numpy(), net.W.detach().numpy() - -def step_tf(optim, steps=1, kwargs={}): - net = TinyNetTF() - optim = optim(**kwargs) - for _ in range(steps): - with tf.GradientTape() as tape: - out = net.forward() - grads = tape.gradient(out, [net.x, net.W]) - optim.apply_gradients(zip(grads, [net.x, net.W])) - return net.x.numpy(), net.W.numpy() - -class ExternalTestOptim(unittest.TestCase): - def _test_optim(self, tinygrad_optim, tensorflow_optim, steps, opts, atol, rtol): - for x,y in zip(step(tinygrad_optim, steps, kwargs=opts), - step_tf(tensorflow_optim, steps, kwargs=opts)): - np.testing.assert_allclose(x, y, atol=atol, rtol=rtol) - - def _test_lamb(self, steps, opts, atol, rtol): self._test_optim(LAMB, tfa.optimizers.LAMB, steps, opts, atol, rtol) - - def test_lamb(self): self._test_lamb(1, {'lr': 0.001}, 1e-5, 0) - def test_lamb_high_lr(self): self._test_lamb(1, {'lr': 10}, 1e-5, 1e-5) - - def test_multistep_lamb(self): self._test_lamb(10, {'lr': 0.001}, 1e-5, 0) - def test_multistep_lamb_high_lr(self): self._test_lamb(10, {'lr': 10}, 1e-5, 3e-4) - -if __name__ == '__main__': - unittest.main() diff --git a/tinygrad_repo/test/external/external_test_speed_llama.py b/tinygrad_repo/test/external/external_test_speed_llama.py deleted file mode 100644 index 7635fc8..0000000 --- a/tinygrad_repo/test/external/external_test_speed_llama.py +++ /dev/null @@ -1,57 +0,0 @@ -# NOTE: this only tests the speed of the LLaMA codegen, it doesn't actually run the net -import unittest, time -import numpy as np -from examples.llama import Transformer, MODEL_PARAMS -from test.test_net_speed import start_profile, stop_profile -from tinygrad.tensor import Tensor -from tinygrad.ops import Device -from tinygrad.nn.state import get_state_dict -from tinygrad.ops import Compiled -from tinygrad.helpers import dtypes, prod -from tinygrad.runtime.lib import RawBuffer - -class FakeProgram: - def __init__(self, name:str, prg:str): pass - def __call__(self, *bufs, global_size, local_size, wait=False): pass - -class RawFakeBuffer(RawBuffer): - @classmethod - def fromCPU(cls, x:np.ndarray, **kwargs): return cls(prod(x.shape), dtypes.from_np(x.dtype), **kwargs) - def toCPU(self): return np.empty(self.size, dtype=self.dtype.np) - -class TestLLaMASpeed(unittest.TestCase): - @unittest.skipIf(not isinstance(Device[Device.DEFAULT], Compiled), "only test for compiled backends") - def test_llama_compile(self): - backup_program = Device[Device.DEFAULT].runtime - backup_buffer = Device[Device.DEFAULT].buffer - Device[Device.DEFAULT].runtime = FakeProgram - Device[Device.DEFAULT].buffer = RawFakeBuffer - - print("testing llama python run time") - model = Transformer(**MODEL_PARAMS["1"]["7B"]["args"]) - print("built model") - # assign fake tensors to the values - for v in get_state_dict(model).values(): v.assign(Tensor.empty(*v.shape, dtype=v.dtype)) - print("assigned empty tensors, doing warmup") - - def run_llama(st, empty_method_cache=True): - if empty_method_cache: Device[Device.DEFAULT].method_cache.clear() - tms = [time.perf_counter()] - for i in range(10): - model(Tensor([[2]]), i).realize() - tms.append(time.perf_counter()) - timings = [(tms[i+1]-tms[i])*1000 for i in range(len(tms)-1)] - print(f"{st:15s} mean runtime: {sum(timings)/len(timings):7.2f}ms, runs: ", ", ".join(f'{x:7.2f}' for x in timings)) - - run_llama("codegen") - run_llama("methodcache", False) - - pr = start_profile() - run_llama("profile") - stop_profile(pr, sort='time', frac=0.1) - - Device[Device.DEFAULT].runtime = backup_program - Device[Device.DEFAULT].buffer = backup_buffer - -if __name__ == '__main__': - unittest.main() diff --git a/tinygrad_repo/test/external/external_test_uops_graphing.py b/tinygrad_repo/test/external/external_test_uops_graphing.py deleted file mode 100644 index 85885a3..0000000 --- a/tinygrad_repo/test/external/external_test_uops_graphing.py +++ /dev/null @@ -1,44 +0,0 @@ -#!/usr/bin/env python -import unittest -from tinygrad.tensor import Tensor -from tinygrad.codegen.linearizer import Linearizer -from tinygrad.renderer.opencl import OpenCLRenderer -from tinygrad.graph import graph_uops -from tinygrad.nn import Conv2d - -class TestUopsGraph(unittest.TestCase): - def test_matmul(self): - N = 1024 - a = Tensor.rand(N,N) - b = Tensor.rand(N,N) - si = (a@b).lazydata.schedule()[-1] - lin = Linearizer(si.ast) - lin.hand_coded_optimizations() - print(lin.colored_shape()) - uops = lin.linearize().uops - graph_uops(uops) - for u in uops: print(u) - print(OpenCLRenderer("matmul", uops)[0]) - - def test_reduce(self): - a = Tensor.rand(1024*1024) - si = a.sum().lazydata.schedule()[-1] - lin = Linearizer(si.ast) - lin.hand_coded_optimizations() - uops = lin.linearize().uops - graph_uops(uops) - #print(OpenCLRenderer("reduce", uops)[0]) - - def test_conv(self): - x = Tensor.rand(1,3,16,16) - c = Conv2d(3, 16, (3,3)) - si = c(x).elu().lazydata.schedule()[-1] - lin = Linearizer(si.ast) - lin.hand_coded_optimizations() - uops = lin.linearize().uops - graph_uops(uops) - print(lin.colored_shape()) - print(OpenCLRenderer("conv", uops)[0]) - -if __name__ == '__main__': - unittest.main() diff --git a/tinygrad_repo/test/external/external_test_yolo.py b/tinygrad_repo/test/external/external_test_yolo.py deleted file mode 100644 index 3631cab..0000000 --- a/tinygrad_repo/test/external/external_test_yolo.py +++ /dev/null @@ -1,36 +0,0 @@ -import io -import unittest -from pathlib import Path - -import cv2 -import requests # type: ignore -import numpy as np - -from tinygrad.tensor import Tensor -from examples.yolov3 import Darknet, infer, show_labels -from extra.utils import fetch - -chicken_img = cv2.imread(str(Path(__file__).parent / 'efficientnet/Chicken.jpg')) -car_img = cv2.imread(str(Path(__file__).parent / 'efficientnet/car.jpg')) - -class TestYOLO(unittest.TestCase): - @classmethod - def setUpClass(cls): - cls.model = Darknet(fetch("https://raw.githubusercontent.com/pjreddie/darknet/master/cfg/yolov3.cfg")) - print("Loading weights file (237MB). This might take a while…") - cls.model.load_weights("https://pjreddie.com/media/files/yolov3.weights") - - @classmethod - def tearDownClass(cls): - del cls.model - - def test_chicken(self): - labels = show_labels(infer(self.model, chicken_img), confidence=0.56) - self.assertEqual(labels, ["bird"]) - - def test_car(self): - labels = show_labels(infer(self.model, car_img)) - self.assertEqual(labels, ["car"]) - -if __name__ == '__main__': - unittest.main() diff --git a/tinygrad_repo/test/external/external_test_yolov8.py b/tinygrad_repo/test/external/external_test_yolov8.py deleted file mode 100644 index df5ae04..0000000 --- a/tinygrad_repo/test/external/external_test_yolov8.py +++ /dev/null @@ -1,76 +0,0 @@ -import numpy as np -from extra.utils import fetch, download_file, get_child -from examples.yolov8 import YOLOv8, get_variant_multiples, preprocess, postprocess, label_predictions -from pathlib import Path -import unittest -import io, cv2, os -import onnxruntime as ort -import ultralytics -from tinygrad.nn.state import safe_load, load_state_dict - -class TestYOLOv8(unittest.TestCase): - def test_all_load_weights(self): - for variant in ['n', 's', 'm', 'l', 'x']: - weights_location = Path(__file__).parents[2] / "weights" / f'yolov8{variant}.safetensors' - download_file(f'https://gitlab.com/r3sist/yolov8_weights/-/raw/master/yolov8{variant}.safetensors', weights_location) - - depth, width, ratio = get_variant_multiples(variant) - TinyYolov8 = YOLOv8(w=width, r=ratio, d=depth, num_classes=80) - state_dict = safe_load(weights_location) - load_state_dict(TinyYolov8, state_dict) - print(f'successfully loaded weights for yolov{variant}') - - def test_predictions(self): - test_image_urls = ['https://raw.githubusercontent.com/ultralytics/yolov5/master/data/images/bus.jpg', 'https://www.aljazeera.com/wp-content/uploads/2022/10/2022-04-28T192650Z_1186456067_UP1EI4S1I0P14_RTRMADP_3_SOCCER-ENGLAND-MUN-CHE-REPORT.jpg'] - variant = 'n' - weights_location = Path(__file__).parents[2] / "weights" / f'yolov8{variant}.safetensors' - depth, width, ratio = get_variant_multiples(variant) - TinyYolov8 = YOLOv8(w=width, r=ratio, d=depth, num_classes=80) - state_dict = safe_load(weights_location) - load_state_dict(TinyYolov8, state_dict) - - for i in range(len(test_image_urls)): - img_stream = io.BytesIO(fetch(test_image_urls[i])) - img = cv2.imdecode(np.frombuffer(img_stream.read(), np.uint8), 1) - test_image = preprocess([img]) - predictions = TinyYolov8(test_image) - post_predictions = postprocess(preds=predictions, img=test_image, orig_imgs=[img]) - labels = label_predictions(post_predictions) - assert labels == {5: 1, 0: 4, 11: 1} if i == 0 else labels == {0: 13, 29: 1, 32: 1} - - def test_forward_pass_torch_onnx(self): - variant = 'n' - weights_location_onnx = Path(__file__).parents[2] / "weights" / f'yolov8{variant}.onnx' - weights_location_pt = Path(__file__).parents[2] / "weights" / f'yolov8{variant}.pt' - weights_location = Path(__file__).parents[2] / "weights" / f'yolov8{variant}.safetensors' - - download_file(f'https://github.com/ultralytics/assets/releases/download/v0.0.0/yolov8{variant}.pt', weights_location_pt) - # the ultralytics export prints a lot of unneccesary things - if not weights_location_onnx.is_file(): - model = ultralytics.YOLO(model=weights_location_pt, task='Detect') - model.export(format="onnx",imgsz=[640, 480]) - - depth, width, ratio = get_variant_multiples(variant) - TinyYolov8 = YOLOv8(w=width, r=ratio, d=depth, num_classes=80) - state_dict = safe_load(weights_location) - load_state_dict(TinyYolov8, state_dict) - - image_location = [np.frombuffer(io.BytesIO(fetch('https://raw.githubusercontent.com/ultralytics/yolov5/master/data/images/bus.jpg')).read(), np.uint8)] - orig_image = [cv2.imdecode(image_location[0], 1)] - - input_image = preprocess(orig_image) - - onnx_session = ort.InferenceSession(weights_location_onnx) - onnx_input_name = onnx_session.get_inputs()[0].name - onnx_output_name = onnx_session.get_outputs()[0].name - onnx_output = onnx_session.run([onnx_output_name], {onnx_input_name: input_image.numpy()}) - - tiny_output = TinyYolov8(input_image) - - # currently rtol is 0.025 because there is a 1-2% difference in our predictions - # because of the zero padding in SPPF module (line 280) maxpooling layers rather than the -infinity in torch. - # This difference does not make a difference "visually". - np.testing.assert_allclose(onnx_output[0], tiny_output.numpy(), atol=5e-4, rtol=0.025) - -if __name__ == '__main__': - unittest.main() diff --git a/tinygrad_repo/test/external/fuzz_shapetracker.py b/tinygrad_repo/test/external/fuzz_shapetracker.py deleted file mode 100644 index cb012c2..0000000 --- a/tinygrad_repo/test/external/fuzz_shapetracker.py +++ /dev/null @@ -1,61 +0,0 @@ -import random -from tinygrad.helpers import DEBUG -from test.unit.test_shapetracker import CheckingShapeTracker -random.seed(42) - -def do_permute(st): - perm = list(range(0, len(st.shape))) - random.shuffle(perm) - perm = tuple(perm) - if DEBUG >= 1: print("st.permute(", perm, ")") - st.permute(perm) - -def do_pad(st): - c = random.randint(0, len(st.shape)-1) - pad = tuple((random.randint(0,2), random.randint(0,2)) if i==c else (0,0) for i in range(len(st.shape))) - if DEBUG >= 1: print("st.pad(", pad, ")") - st.pad(pad) - -def do_reshape_split_one(st): - c = random.randint(0, len(st.shape)-1) - poss = [n for n in [1,2,3,4,5] if st.shape[c]%n == 0] - spl = random.choice(poss) - shp = st.shape[0:c] + (st.shape[c]//spl, spl) + st.shape[c+1:] - if DEBUG >= 1: print("st.reshape(", shp, ")") - st.reshape(shp) - -def do_reshape_combine_two(st): - if len(st.shape) < 2: return - c = random.randint(0, len(st.shape)-2) - shp = st.shape[:c] + (st.shape[c] * st.shape[c+1], ) + st.shape[c+2:] - if DEBUG >= 1: print("st.reshape(", shp, ")") - st.reshape(shp) - -def do_shrink(st): - c = random.randint(0, len(st.shape)-1) - while 1: - shrink = tuple((random.randint(0,s), random.randint(0,s)) if i == c else (0,s) for i,s in enumerate(st.shape)) - if all(x= 1: print("st.shrink(", shrink, ")") - st.shrink(shrink) - -def do_stride(st): - c = random.randint(0, len(st.shape)-1) - stride = tuple(random.choice([-2,-1,2]) if i==c else 1 for i in range(len(st.shape))) - if DEBUG >= 1: print("st.stride(", stride, ")") - st.stride(stride) - -def do_expand(st): - c = [i for i,s in enumerate(st.shape) if s==1] - if len(c) == 0: return - c = random.choice(c) - expand = tuple(random.choice([2,3,4]) if i==c else s for i,s in enumerate(st.shape)) - if DEBUG >= 1: print("st.expand(", expand, ")") - st.expand(expand) - -if __name__ == "__main__": - ops = [do_permute, do_pad, do_shrink, do_reshape_split_one, do_reshape_combine_two, do_stride, do_expand] - for _ in range(200): - st = CheckingShapeTracker((random.randint(2, 10), random.randint(2, 10), random.randint(2, 10))) - for i in range(8): random.choice(ops)(st) - st.assert_same() diff --git a/tinygrad_repo/test/external/fuzz_symbolic.py b/tinygrad_repo/test/external/fuzz_symbolic.py deleted file mode 100644 index 290930d..0000000 --- a/tinygrad_repo/test/external/fuzz_symbolic.py +++ /dev/null @@ -1,69 +0,0 @@ -import itertools -import random -from tinygrad.helpers import DEBUG -from tinygrad.shape.symbolic import Variable -random.seed(42) - -def add_v(expr, rng=None): - if rng is None: rng = random.randint(0,2) - return expr + v[rng], rng - -def div(expr, rng=None): - if rng is None: rng = random.randint(1,9) - return expr // rng, rng - -def mul(expr, rng=None): - if rng is None: rng = random.randint(-4,4) - return expr * rng, rng - -def mod(expr, rng=None): - if rng is None: rng = random.randint(1,9) - return expr % rng, rng - -def add_num(expr, rng=None): - if rng is None: rng = random.randint(-4,4) - return expr + rng, rng - -def lt(expr, rng=None): - if rng is None: rng = random.randint(-4,4) - return expr < rng, rng - -def ge(expr, rng=None): - if rng is None: rng = random.randint(-4,4) - return expr >= rng, rng - -def le(expr, rng=None): - if rng is None: rng = random.randint(-4,4) - return expr <= rng, rng - -def gt(expr, rng=None): - if rng is None: rng = random.randint(-4,4) - return expr > rng, rng - -if __name__ == "__main__": - ops = [add_v, div, mul, add_num, mod] - for _ in range(1000): - upper_bounds = [*list(range(1, 10)), 16, 32, 64, 128, 256] - u1 = Variable("v1", 0, random.choice(upper_bounds)) - u2 = Variable("v2", 0, random.choice(upper_bounds)) - u3 = Variable("v3", 0, random.choice(upper_bounds)) - v = [u1,u2,u3] - tape = [random.choice(ops) for _ in range(random.randint(2, 30))] - # 10% of the time, add one of lt, le, gt, ge - if random.random() < 0.1: tape.append(random.choice([lt, le, gt, ge])) - expr = Variable.num(0) - rngs = [] - for t in tape: - expr, rng = t(expr) - if DEBUG >= 1: print(t.__name__, rng) - rngs.append(rng) - if DEBUG >=1: print(expr) - space = list(itertools.product(range(u1.min, u1.max+1), range(u2.min, u2.max+1), range(u3.min, u3.max+1))) - volume = len(space) - for (v1, v2, v3) in random.sample(space, min(100, volume)): - v = [v1,v2,v3] - rn = 0 - for t,r in zip(tape, rngs): rn, _ = t(rn, r) - num = eval(expr.render()) - assert num == rn, f"mismatched {expr.render()} at {v1=} {v2=} {v3=} = {num} != {rn}" - if DEBUG >= 1: print(f"matched {expr.render()} at {v1=} {v2=} {v3=} = {num} == {rn}") diff --git a/tinygrad_repo/test/external/graph_batchnorm.py b/tinygrad_repo/test/external/graph_batchnorm.py deleted file mode 100644 index 59e3b79..0000000 --- a/tinygrad_repo/test/external/graph_batchnorm.py +++ /dev/null @@ -1,61 +0,0 @@ -import unittest -from tinygrad.nn.state import get_parameters -from tinygrad.tensor import Tensor -from tinygrad.nn import Conv2d, BatchNorm2d, optim - -def model_step(lm): - with Tensor.train(): - x = Tensor.ones(8,12,128,256, requires_grad=False) - optimizer = optim.SGD(get_parameters(lm), lr=0.001) - loss = lm.forward(x).sum() - optimizer.zero_grad() - loss.backward() - del x,loss - optimizer.step() - -class TestBatchnorm(unittest.TestCase): - def test_conv(self): - class LilModel: - def __init__(self): - self.c = Conv2d(12, 32, 3, padding=1, bias=False) - def forward(self, x): - return self.c(x).relu() - lm = LilModel() - model_step(lm) - - def test_two_conv(self): - class LilModel: - def __init__(self): - self.c = Conv2d(12, 32, 3, padding=1, bias=False) - self.c2 = Conv2d(32, 32, 3, padding=1, bias=False) - def forward(self, x): - return self.c2(self.c(x)).relu() - lm = LilModel() - model_step(lm) - - def test_two_conv_bn(self): - class LilModel: - def __init__(self): - self.c = Conv2d(12, 24, 3, padding=1, bias=False) - self.bn = BatchNorm2d(24, track_running_stats=False) - self.c2 = Conv2d(24, 32, 3, padding=1, bias=False) - self.bn2 = BatchNorm2d(32, track_running_stats=False) - def forward(self, x): - x = self.bn(self.c(x)).relu() - return self.bn2(self.c2(x)).relu() - lm = LilModel() - model_step(lm) - - def test_conv_bn(self): - class LilModel: - def __init__(self): - self.c = Conv2d(12, 32, 3, padding=1, bias=False) - self.bn = BatchNorm2d(32, track_running_stats=False) - def forward(self, x): - return self.bn(self.c(x)).relu() - lm = LilModel() - model_step(lm) - - -if __name__ == '__main__': - unittest.main() diff --git a/tinygrad_repo/test/external/test_example.py b/tinygrad_repo/test/external/test_example.py deleted file mode 100644 index 5af94e5..0000000 --- a/tinygrad_repo/test/external/test_example.py +++ /dev/null @@ -1,74 +0,0 @@ -import unittest -import numpy as np -from tinygrad.ops import Device -from tinygrad.tensor import Tensor -from tinygrad.helpers import getenv, CI - -def multidevice_test(fxn): - exclude_devices = getenv("EXCLUDE_DEVICES", "").split(",") - def ret(self): - for device in Device._buffers: - if device in ["DISK", "SHM", "FAKE"]: continue - if not CI: print(device) - if device in exclude_devices: - if not CI: print(f"WARNING: {device} test is excluded") - continue - with self.subTest(device=device): - try: - Device[device] - except Exception: - if not CI: print(f"WARNING: {device} test isn't running") - continue - fxn(self, device) - return ret - -class TestExample(unittest.TestCase): - @multidevice_test - def test_convert_to_cpu(self, device): - a = Tensor([[1,2],[3,4]], device=device) - assert a.numpy().shape == (2,2) - b = a.cpu() - assert b.numpy().shape == (2,2) - - @multidevice_test - def test_2_plus_3(self, device): - a = Tensor([2], device=device) - b = Tensor([3], device=device) - result = a + b - print(f"{a.numpy()} + {b.numpy()} = {result.numpy()}") - assert result.numpy()[0] == 5. - - @multidevice_test - def test_example_readme(self, device): - x = Tensor.eye(3, device=device, requires_grad=True) - y = Tensor([[2.0,0,-2.0]], device=device, requires_grad=True) - z = y.matmul(x).sum() - z.backward() - - x.grad.numpy() # dz/dx - y.grad.numpy() # dz/dy - - assert x.grad.device == device - assert y.grad.device == device - - @multidevice_test - def test_example_matmul(self, device): - try: - Device[device] - except Exception: - print(f"WARNING: {device} test isn't running") - return - - x = Tensor.eye(64, device=device, requires_grad=True) - y = Tensor.eye(64, device=device, requires_grad=True) - z = y.matmul(x).sum() - z.backward() - - x.grad.numpy() # dz/dx - y.grad.numpy() # dz/dy - - assert x.grad.device == device - assert y.grad.device == device - -if __name__ == '__main__': - unittest.main() diff --git a/tinygrad_repo/test/extra/test_export_model.py b/tinygrad_repo/test/extra/test_export_model.py deleted file mode 100644 index 675e46d..0000000 --- a/tinygrad_repo/test/extra/test_export_model.py +++ /dev/null @@ -1,50 +0,0 @@ -import unittest -from extra.export_model import export_model, EXPORT_SUPPORTED_DEVICE -from tinygrad.tensor import Tensor, Device -import json - -class MockMultiInputModel: - def forward(self, x1, x2, x3): - return x1 + x2 + x3 - -class MockMultiOutputModel: - def __call__(self, x1): - return x1 + 2.0, x1.pad(((0, 0), (0, 1))) + 1.0 - -# TODO: move compile_efficientnet tests here -@unittest.skipUnless(Device.DEFAULT in EXPORT_SUPPORTED_DEVICE, f"Model export is not supported on {Device.DEFAULT}") -class TextModelExport(unittest.TestCase): - def test_multi_input_model_export(self): - model = MockMultiInputModel() - inputs = [Tensor.rand(2,2), Tensor.rand(2,2), Tensor.rand(2,2)] - prg, inp_sizes, _, _ = export_model(model, "", *inputs) - prg = json.loads(prg) - - assert len(inputs) == len(prg["inputs"]) == len(inp_sizes), f"Model and exported inputs don't match: mdl={len(inputs)}, prg={len(prg['inputs'])}, inp_sizes={len(inp_sizes)}" - - for i in range(len(inputs)): - assert f"input{i}" in inp_sizes, f"input{i} not captured in inp_sizes" - assert f"input{i}" in prg["buffers"], f"input{i} not captured in exported buffers" - - for i, exported_input in enumerate(prg["inputs"]): - assert inputs[i].dtype.name == exported_input["dtype"], f"Model and exported input dtype don't match: mdl={inputs[i].dtype.name}, prg={exported_input['dtype']}" - - def test_multi_output_model_export(self): - model = MockMultiOutputModel() - input = Tensor.rand(2,2) - outputs = model(input) - prg, _, out_sizes, _ = export_model(model, "", input) - prg = json.loads(prg) - - assert len(outputs) == len(prg["outputs"]) == len(out_sizes), f"Model and exported outputs don't match: mdl={len(outputs)}, prg={len(prg['outputs'])}, inp_sizes={len(out_sizes)}" - - for i in range(len(outputs)): - assert f"output{i}" in out_sizes, f"output{i} not captured in out_sizes" - assert f"output{i}" in prg["buffers"], f"output{i} not captured in exported buffers" - - for i, exported_output in enumerate(prg["outputs"]): - assert outputs[i].dtype.name == exported_output["dtype"], f"Model and exported output dtype don't match: mdl={outputs[i].dtype.name}, prg={exported_output['dtype']}" - - -if __name__ == '__main__': - unittest.main() diff --git a/tinygrad_repo/test/extra/test_extra_helpers.py b/tinygrad_repo/test/extra/test_extra_helpers.py deleted file mode 100644 index 6832b97..0000000 --- a/tinygrad_repo/test/extra/test_extra_helpers.py +++ /dev/null @@ -1,57 +0,0 @@ -#!/usr/bin/env python -import os, cloudpickle, tempfile, unittest, subprocess -from extra.helpers import enable_early_exec, cross_process, _CloudpickleFunctionWrapper - -def normalize_line_endings(s): return s.replace(b'\r\n', b'\n') - -class TestEarlyExec(unittest.TestCase): - def setUp(self) -> None: - self.early_exec = enable_early_exec() - - def early_exec_py_file(self, file_content, exec_args): - with tempfile.NamedTemporaryFile(suffix=".py", delete=False) as temp: - temp.write(file_content) - temp_path = temp.name - try: - output = self.early_exec((["python3", temp_path] + exec_args, None)) - return output - finally: - os.remove(temp_path) - - def test_enable_early_exec(self): - output = self.early_exec_py_file(b'print("Hello, world!")', []) - self.assertEqual(b"Hello, world!\n", normalize_line_endings(output)) - - def test_enable_early_exec_with_arg(self): - output = self.early_exec_py_file(b'import sys\nprint("Hello, " + sys.argv[1] + "!")', ["world"]) - self.assertEqual(b"Hello, world!\n", normalize_line_endings(output)) - - def test_enable_early_exec_process_exception(self): - with self.assertRaises(subprocess.CalledProcessError): - self.early_exec_py_file(b'raise Exception("Test exception")', []) - - def test_enable_early_exec_type_exception(self): - with self.assertRaises(TypeError): - self.early_exec((["python3"], "print('Hello, world!')")) - -class TestCrossProcess(unittest.TestCase): - - def test_cross_process(self): - def _iterate(): - for i in range(10): yield i - results = list(cross_process(_iterate)) - self.assertEqual(list(range(10)), results) - - def test_cross_process_exception(self): - def _iterate(): - for i in range(10): - if i == 5: raise ValueError("Test exception") - yield i - with self.assertRaises(ValueError): list(cross_process(_iterate)) - - def test_CloudpickleFunctionWrapper(self): - def add(x, y): return x + y - self.assertEqual(7, cloudpickle.loads(cloudpickle.dumps(_CloudpickleFunctionWrapper(add)))(3, 4)) - -if __name__ == '__main__': - unittest.main() \ No newline at end of file diff --git a/tinygrad_repo/test/extra/test_lr_scheduler.py b/tinygrad_repo/test/extra/test_lr_scheduler.py deleted file mode 100644 index 9aa9b86..0000000 --- a/tinygrad_repo/test/extra/test_lr_scheduler.py +++ /dev/null @@ -1,107 +0,0 @@ -import numpy as np -import torch -import unittest -from tinygrad.tensor import Tensor -from tinygrad.nn.state import get_parameters -from tinygrad.nn.optim import Adam -from extra.lr_scheduler import MultiStepLR, ReduceLROnPlateau, CosineAnnealingLR, OneCycleLR -from extra.training import train, evaluate -from extra.datasets import fetch_mnist -import pytest - -pytestmark = [pytest.mark.exclude_cuda, pytest.mark.exclude_gpu] - -np.random.seed(1337) -Tensor.manual_seed(1337) - -X_train, Y_train, X_test, Y_test = fetch_mnist() - -class TinyBobNet: - def __init__(self): - self.l1 = Tensor.scaled_uniform(784, 128) - self.l2 = Tensor.scaled_uniform(128, 10) - - def parameters(self): - return get_parameters(self) - - def forward(self, x): - return x.dot(self.l1).relu().dot(self.l2).log_softmax() - -def lr_scheduler_training(sched_fn=None, args=None): - model = TinyBobNet() - optim = Adam(model.parameters(), lr=0.01) - if sched_fn is not None: sched = sched_fn(optim, **args) - for _ in range(25): - train(model, X_train, Y_train, optim, 100) - if sched_fn is not None: - if isinstance(sched, ReduceLROnPlateau): - sched.step(evaluate(model, X_test, Y_test)) - else: - sched.step() - return evaluate(model, X_test, Y_test) - -def current_lr(optim): return optim.param_groups[0]['lr'] if hasattr(optim, 'param_groups') else optim.lr -def get_lrs(optim, sched, epochs, steps=1, accs=None): - lr = current_lr(optim) - if not isinstance(lr, float): lr = lr.numpy()[0] - lrs = [lr] - for e in range(epochs): - for _ in range(steps): - optim.step() - sched.step() if accs is None else sched.step(accs[e]) - lr = current_lr(optim) - if not isinstance(lr, float): lr = lr.numpy()[0] - lrs.append(lr) - return lrs - -class TestLrScheduler(unittest.TestCase): - def _test_lr_scheduler(self, tinygrad_sched, torch_sched, epochs, opts, atol, rtol): - accs = opts.pop('accs', None) - tinygrad_optim, torch_optim = Adam([], lr=0.01), torch.optim.Adam([torch.tensor([0.], requires_grad=True)], lr=0.01) - tinygrad_sched, torch_sched = tinygrad_sched(tinygrad_optim, **opts), torch_sched(torch_optim, **opts) - - tinygrad_lrs = get_lrs(tinygrad_optim, tinygrad_sched, epochs, accs=accs) - torch_lrs = get_lrs(torch_optim, torch_sched, epochs, accs=accs) - - np.testing.assert_allclose(tinygrad_lrs, torch_lrs, atol=atol, rtol=rtol) - - def _test_multisteplr(self, epochs, opts, atol, rtol): - self._test_lr_scheduler(MultiStepLR, torch.optim.lr_scheduler.MultiStepLR, epochs, opts, atol, rtol) - def _test_reducelronplateau(self, epochs, opts, atol, rtol): - opts['accs'] = np.random.randn(epochs) - self._test_lr_scheduler(ReduceLROnPlateau, torch.optim.lr_scheduler.ReduceLROnPlateau, epochs, opts, atol, rtol) - def _test_cosineannealinglr(self, epochs, opts, atol, rtol): - opts['T_max'] = epochs - self._test_lr_scheduler(CosineAnnealingLR, torch.optim.lr_scheduler.CosineAnnealingLR, epochs, opts, atol, rtol) - def _test_onecyclelr(self, epochs, opts, atol, rtol): - opts['total_steps'] = epochs - self._test_lr_scheduler(OneCycleLR, torch.optim.lr_scheduler.OneCycleLR, epochs, opts, atol, rtol) - - def test_multisteplr(self): self._test_multisteplr(10, {'milestones': [1, 2, 7]}, 1e-6, 1e-6) - def test_multisteplr_gamma(self): self._test_multisteplr(10, {'milestones': [1, 2, 7], 'gamma': 0.1337}, 1e-6, 1e-6) - - def test_reducelronplateau(self): self._test_reducelronplateau(100, {}, 1e-6, 1e-6) - def test_reducelronplateau_max(self): self._test_reducelronplateau(100, {'mode': 'max'}, 1e-6, 1e-6) - def test_reducelronplateau_factor(self): self._test_reducelronplateau(100, {'factor': 0.1337}, 1e-6, 1e-6) - def test_reducelronplateau_patience(self): self._test_reducelronplateau(100, {'patience': 3}, 1e-6, 1e-6) - def test_reducelronplateau_threshold(self): self._test_reducelronplateau(100, {'threshold': 1e-6}, 1e-6, 1e-6) - def test_reducelronplateau_threshold_mode(self): self._test_reducelronplateau(100, {'threshold_mode': 'abs'}, 1e-6, 1e-6) - - def test_cosineannealinglr(self): self._test_cosineannealinglr(100, {}, 1e-6, 1e-6) - def test_cosineannealinglr_eta_min(self): self._test_cosineannealinglr(100, {'eta_min': 0.001}, 1e-6, 1e-6) - - def test_onecyclelr(self): self._test_onecyclelr(1000, {'pct_start': 0.3, 'anneal_strategy': 'linear', - 'cycle_momentum': False, 'div_factor': 25.0, - 'final_div_factor': 10000.0, 'max_lr':1e-5}, 1e-6, 1e-6) - @unittest.skip("slow") - def test_training(self): - without = lr_scheduler_training() - sched_fns = [MultiStepLR, ReduceLROnPlateau, CosineAnnealingLR, OneCycleLR] - argss = [{'milestones': [5, 7, 10, 15], 'gamma': 0.5}, {'factor': 0.5, 'patience': 2}, {'T_max': 25, 'eta_min': 0.001}, - {'pct_start': 0.3, 'anneal_strategy': 'linear', 'cycle_momentum': False, 'div_factor': 25.0, 'final_div_factor': 10000.0, 'max_lr':1e-5, 'total_steps': 25}] - for sched_fn, args in zip(sched_fns, argss): - with_sched = lr_scheduler_training(sched_fn, args) - assert with_sched > without - -if __name__ == '__main__': - unittest.main() diff --git a/tinygrad_repo/test/extra/test_utils.py b/tinygrad_repo/test/extra/test_utils.py deleted file mode 100644 index 2c0b831..0000000 --- a/tinygrad_repo/test/extra/test_utils.py +++ /dev/null @@ -1,106 +0,0 @@ -#!/usr/bin/env python -import io, unittest -import os -import tempfile -from unittest.mock import patch, MagicMock - -import torch -import numpy as np -from tinygrad.helpers import CI -from extra.utils import fetch, temp, download_file -from tinygrad.nn.state import torch_load -from PIL import Image - -@unittest.skipIf(CI, "no internet tests in CI") -class TestFetch(unittest.TestCase): - def test_fetch_bad_http(self): - self.assertRaises(AssertionError, fetch, 'http://httpstat.us/500') - self.assertRaises(AssertionError, fetch, 'http://httpstat.us/404') - self.assertRaises(AssertionError, fetch, 'http://httpstat.us/400') - - def test_fetch_small(self): - assert(len(fetch('https://google.com'))>0) - - def test_fetch_img(self): - img = fetch("https://media.istockphoto.com/photos/hen-picture-id831791190") - pimg = Image.open(io.BytesIO(img)) - assert pimg.size == (705, 1024) - -class TestFetchRelative(unittest.TestCase): - def setUp(self): - self.working_dir = os.getcwd() - self.tempdir = tempfile.TemporaryDirectory() - os.chdir(self.tempdir.name) - with open('test_file.txt', 'x') as f: - f.write("12345") - - def tearDown(self): - os.chdir(self.working_dir) - self.tempdir.cleanup() - - #test ./ - def test_fetch_relative_dotslash(self): - self.assertEqual(b'12345', fetch("./test_file.txt")) - - #test ../ - def test_fetch_relative_dotdotslash(self): - os.mkdir('test_file_path') - os.chdir('test_file_path') - self.assertEqual(b'12345', fetch("../test_file.txt")) - -class TestDownloadFile(unittest.TestCase): - def setUp(self): - from pathlib import Path - self.test_file = Path(temp("test_download_file/test_file.txt")) - - def tearDown(self): - os.remove(self.test_file) - os.removedirs(self.test_file.parent) - - @patch('requests.get') - def test_download_file_with_mkdir(self, mock_requests): - mock_response = MagicMock() - mock_response.iter_content.return_value = [b'1234', b'5678'] - mock_response.status_code = 200 - mock_response.headers = {'content-length': '8'} - mock_requests.return_value = mock_response - self.assertFalse(self.test_file.parent.exists()) - download_file("https://www.mock.com/fake.txt", self.test_file, skip_if_exists=False) - self.assertTrue(self.test_file.parent.exists()) - self.assertTrue(self.test_file.is_file()) - self.assertEqual('12345678', self.test_file.read_text()) - -class TestUtils(unittest.TestCase): - def test_fake_torch_load_zipped(self): self._test_fake_torch_load_zipped() - def test_fake_torch_load_zipped_float16(self): self._test_fake_torch_load_zipped(isfloat16=True) - def _test_fake_torch_load_zipped(self, isfloat16=False): - class LayerWithOffset(torch.nn.Module): - def __init__(self): - super(LayerWithOffset, self).__init__() - d = torch.randn(16) - self.param1 = torch.nn.Parameter( - d.as_strided([2, 2], [1, 2], storage_offset=5) - ) - self.param2 = torch.nn.Parameter( - d.as_strided([2, 2], [1, 2], storage_offset=4) - ) - - model = torch.nn.Sequential( - torch.nn.Linear(4, 8), - torch.nn.Linear(8, 3), - LayerWithOffset() - ) - if isfloat16: model = model.half() - - path = temp(f"test_load_{isfloat16}.pt") - torch.save(model.state_dict(), path) - model2 = torch_load(path) - - for name, a in model.state_dict().items(): - b = model2[name] - a, b = a.numpy(), b.numpy() - assert a.shape == b.shape - assert a.dtype == b.dtype - assert np.array_equal(a, b) -if __name__ == '__main__': - unittest.main() diff --git a/tinygrad_repo/test/helpers.py b/tinygrad_repo/test/helpers.py deleted file mode 100644 index a7e42fa..0000000 --- a/tinygrad_repo/test/helpers.py +++ /dev/null @@ -1,15 +0,0 @@ -from tinygrad.ops import LazyOp, LoadOps -from tinygrad.nn.state import get_parameters - -# for speed -def derandomize(x): - if isinstance(x, LazyOp): - new_op = LoadOps.EMPTY if x.op == LoadOps.RAND else x.op - return LazyOp(new_op, tuple([derandomize(s) for s in x.src]), x.arg) - x.op = derandomize(x.op) - return x - -def derandomize_model(model): - for p in get_parameters(model): - p.lazydata = derandomize(p.lazydata) - p.realize() diff --git a/tinygrad_repo/test/models/efficientnet/Chicken.jpg b/tinygrad_repo/test/models/efficientnet/Chicken.jpg deleted file mode 100644 index 9dd4815..0000000 Binary files a/tinygrad_repo/test/models/efficientnet/Chicken.jpg and /dev/null differ diff --git a/tinygrad_repo/test/models/efficientnet/car.jpg b/tinygrad_repo/test/models/efficientnet/car.jpg deleted file mode 100644 index 32154e0..0000000 Binary files a/tinygrad_repo/test/models/efficientnet/car.jpg and /dev/null differ diff --git a/tinygrad_repo/test/models/efficientnet/imagenet1000_clsidx_to_labels.txt b/tinygrad_repo/test/models/efficientnet/imagenet1000_clsidx_to_labels.txt deleted file mode 100644 index 2e3ae32..0000000 --- a/tinygrad_repo/test/models/efficientnet/imagenet1000_clsidx_to_labels.txt +++ /dev/null @@ -1,1000 +0,0 @@ -{0: 'tench, Tinca tinca', - 1: 'goldfish, Carassius auratus', - 2: 'great white shark, white shark, man-eater, man-eating shark, Carcharodon carcharias', - 3: 'tiger shark, Galeocerdo cuvieri', - 4: 'hammerhead, hammerhead shark', - 5: 'electric ray, crampfish, numbfish, torpedo', - 6: 'stingray', - 7: 'cock', - 8: 'hen', - 9: 'ostrich, Struthio camelus', - 10: 'brambling, Fringilla montifringilla', - 11: 'goldfinch, Carduelis carduelis', - 12: 'house finch, linnet, Carpodacus mexicanus', - 13: 'junco, snowbird', - 14: 'indigo bunting, indigo finch, indigo bird, Passerina cyanea', - 15: 'robin, American robin, Turdus migratorius', - 16: 'bulbul', - 17: 'jay', - 18: 'magpie', - 19: 'chickadee', - 20: 'water ouzel, dipper', - 21: 'kite', - 22: 'bald eagle, American eagle, Haliaeetus leucocephalus', - 23: 'vulture', - 24: 'great grey owl, great gray owl, Strix nebulosa', - 25: 'European fire salamander, Salamandra salamandra', - 26: 'common newt, Triturus vulgaris', - 27: 'eft', - 28: 'spotted salamander, Ambystoma maculatum', - 29: 'axolotl, mud puppy, Ambystoma mexicanum', - 30: 'bullfrog, Rana catesbeiana', - 31: 'tree frog, tree-frog', - 32: 'tailed frog, bell toad, ribbed toad, tailed toad, Ascaphus trui', - 33: 'loggerhead, loggerhead turtle, Caretta caretta', - 34: 'leatherback turtle, leatherback, leathery turtle, Dermochelys coriacea', - 35: 'mud turtle', - 36: 'terrapin', - 37: 'box turtle, box tortoise', - 38: 'banded gecko', - 39: 'common iguana, iguana, Iguana iguana', - 40: 'American chameleon, anole, Anolis carolinensis', - 41: 'whiptail, whiptail lizard', - 42: 'agama', - 43: 'frilled lizard, Chlamydosaurus kingi', - 44: 'alligator lizard', - 45: 'Gila monster, Heloderma suspectum', - 46: 'green lizard, Lacerta viridis', - 47: 'African chameleon, Chamaeleo chamaeleon', - 48: 'Komodo dragon, Komodo lizard, dragon lizard, giant lizard, Varanus komodoensis', - 49: 'African crocodile, Nile crocodile, Crocodylus niloticus', - 50: 'American alligator, Alligator mississipiensis', - 51: 'triceratops', - 52: 'thunder snake, worm snake, Carphophis amoenus', - 53: 'ringneck snake, ring-necked snake, ring snake', - 54: 'hognose snake, puff adder, sand viper', - 55: 'green snake, grass snake', - 56: 'king snake, kingsnake', - 57: 'garter snake, grass snake', - 58: 'water snake', - 59: 'vine snake', - 60: 'night snake, Hypsiglena torquata', - 61: 'boa constrictor, Constrictor constrictor', - 62: 'rock python, rock snake, Python sebae', - 63: 'Indian cobra, Naja naja', - 64: 'green mamba', - 65: 'sea snake', - 66: 'horned viper, cerastes, sand viper, horned asp, Cerastes cornutus', - 67: 'diamondback, diamondback rattlesnake, Crotalus adamanteus', - 68: 'sidewinder, horned rattlesnake, Crotalus cerastes', - 69: 'trilobite', - 70: 'harvestman, daddy longlegs, Phalangium opilio', - 71: 'scorpion', - 72: 'black and gold garden spider, Argiope aurantia', - 73: 'barn spider, Araneus cavaticus', - 74: 'garden spider, Aranea diademata', - 75: 'black widow, Latrodectus mactans', - 76: 'tarantula', - 77: 'wolf spider, hunting spider', - 78: 'tick', - 79: 'centipede', - 80: 'black grouse', - 81: 'ptarmigan', - 82: 'ruffed grouse, partridge, Bonasa umbellus', - 83: 'prairie chicken, prairie grouse, prairie fowl', - 84: 'peacock', - 85: 'quail', - 86: 'partridge', - 87: 'African grey, African gray, Psittacus erithacus', - 88: 'macaw', - 89: 'sulphur-crested cockatoo, Kakatoe galerita, Cacatua galerita', - 90: 'lorikeet', - 91: 'coucal', - 92: 'bee eater', - 93: 'hornbill', - 94: 'hummingbird', - 95: 'jacamar', - 96: 'toucan', - 97: 'drake', - 98: 'red-breasted merganser, Mergus serrator', - 99: 'goose', - 100: 'black swan, Cygnus atratus', - 101: 'tusker', - 102: 'echidna, spiny anteater, anteater', - 103: 'platypus, duckbill, duckbilled platypus, duck-billed platypus, Ornithorhynchus anatinus', - 104: 'wallaby, brush kangaroo', - 105: 'koala, koala bear, kangaroo bear, native bear, Phascolarctos cinereus', - 106: 'wombat', - 107: 'jellyfish', - 108: 'sea anemone, anemone', - 109: 'brain coral', - 110: 'flatworm, platyhelminth', - 111: 'nematode, nematode worm, roundworm', - 112: 'conch', - 113: 'snail', - 114: 'slug', - 115: 'sea slug, nudibranch', - 116: 'chiton, coat-of-mail shell, sea cradle, polyplacophore', - 117: 'chambered nautilus, pearly nautilus, nautilus', - 118: 'Dungeness crab, Cancer magister', - 119: 'rock crab, Cancer irroratus', - 120: 'fiddler crab', - 121: 'king crab, Alaska crab, Alaskan king crab, Alaska king crab, Paralithodes camtschatica', - 122: 'American lobster, Northern lobster, Maine lobster, Homarus americanus', - 123: 'spiny lobster, langouste, rock lobster, crawfish, crayfish, sea crawfish', - 124: 'crayfish, crawfish, crawdad, crawdaddy', - 125: 'hermit crab', - 126: 'isopod', - 127: 'white stork, Ciconia ciconia', - 128: 'black stork, Ciconia nigra', - 129: 'spoonbill', - 130: 'flamingo', - 131: 'little blue heron, Egretta caerulea', - 132: 'American egret, great white heron, Egretta albus', - 133: 'bittern', - 134: 'crane', - 135: 'limpkin, Aramus pictus', - 136: 'European gallinule, Porphyrio porphyrio', - 137: 'American coot, marsh hen, mud hen, water hen, Fulica americana', - 138: 'bustard', - 139: 'ruddy turnstone, Arenaria interpres', - 140: 'red-backed sandpiper, dunlin, Erolia alpina', - 141: 'redshank, Tringa totanus', - 142: 'dowitcher', - 143: 'oystercatcher, oyster catcher', - 144: 'pelican', - 145: 'king penguin, Aptenodytes patagonica', - 146: 'albatross, mollymawk', - 147: 'grey whale, gray whale, devilfish, Eschrichtius gibbosus, Eschrichtius robustus', - 148: 'killer whale, killer, orca, grampus, sea wolf, Orcinus orca', - 149: 'dugong, Dugong dugon', - 150: 'sea lion', - 151: 'Chihuahua', - 152: 'Japanese spaniel', - 153: 'Maltese dog, Maltese terrier, Maltese', - 154: 'Pekinese, Pekingese, Peke', - 155: 'Shih-Tzu', - 156: 'Blenheim spaniel', - 157: 'papillon', - 158: 'toy terrier', - 159: 'Rhodesian ridgeback', - 160: 'Afghan hound, Afghan', - 161: 'basset, basset hound', - 162: 'beagle', - 163: 'bloodhound, sleuthhound', - 164: 'bluetick', - 165: 'black-and-tan coonhound', - 166: 'Walker hound, Walker foxhound', - 167: 'English foxhound', - 168: 'redbone', - 169: 'borzoi, Russian wolfhound', - 170: 'Irish wolfhound', - 171: 'Italian greyhound', - 172: 'whippet', - 173: 'Ibizan hound, Ibizan Podenco', - 174: 'Norwegian elkhound, elkhound', - 175: 'otterhound, otter hound', - 176: 'Saluki, gazelle hound', - 177: 'Scottish deerhound, deerhound', - 178: 'Weimaraner', - 179: 'Staffordshire bullterrier, Staffordshire bull terrier', - 180: 'American Staffordshire terrier, Staffordshire terrier, American pit bull terrier, pit bull terrier', - 181: 'Bedlington terrier', - 182: 'Border terrier', - 183: 'Kerry blue terrier', - 184: 'Irish terrier', - 185: 'Norfolk terrier', - 186: 'Norwich terrier', - 187: 'Yorkshire terrier', - 188: 'wire-haired fox terrier', - 189: 'Lakeland terrier', - 190: 'Sealyham terrier, Sealyham', - 191: 'Airedale, Airedale terrier', - 192: 'cairn, cairn terrier', - 193: 'Australian terrier', - 194: 'Dandie Dinmont, Dandie Dinmont terrier', - 195: 'Boston bull, Boston terrier', - 196: 'miniature schnauzer', - 197: 'giant schnauzer', - 198: 'standard schnauzer', - 199: 'Scotch terrier, Scottish terrier, Scottie', - 200: 'Tibetan terrier, chrysanthemum dog', - 201: 'silky terrier, Sydney silky', - 202: 'soft-coated wheaten terrier', - 203: 'West Highland white terrier', - 204: 'Lhasa, Lhasa apso', - 205: 'flat-coated retriever', - 206: 'curly-coated retriever', - 207: 'golden retriever', - 208: 'Labrador retriever', - 209: 'Chesapeake Bay retriever', - 210: 'German short-haired pointer', - 211: 'vizsla, Hungarian pointer', - 212: 'English setter', - 213: 'Irish setter, red setter', - 214: 'Gordon setter', - 215: 'Brittany spaniel', - 216: 'clumber, clumber spaniel', - 217: 'English springer, English springer spaniel', - 218: 'Welsh springer spaniel', - 219: 'cocker spaniel, English cocker spaniel, cocker', - 220: 'Sussex spaniel', - 221: 'Irish water spaniel', - 222: 'kuvasz', - 223: 'schipperke', - 224: 'groenendael', - 225: 'malinois', - 226: 'briard', - 227: 'kelpie', - 228: 'komondor', - 229: 'Old English sheepdog, bobtail', - 230: 'Shetland sheepdog, Shetland sheep dog, Shetland', - 231: 'collie', - 232: 'Border collie', - 233: 'Bouvier des Flandres, Bouviers des Flandres', - 234: 'Rottweiler', - 235: 'German shepherd, German shepherd dog, German police dog, alsatian', - 236: 'Doberman, Doberman pinscher', - 237: 'miniature pinscher', - 238: 'Greater Swiss Mountain dog', - 239: 'Bernese mountain dog', - 240: 'Appenzeller', - 241: 'EntleBucher', - 242: 'boxer', - 243: 'bull mastiff', - 244: 'Tibetan mastiff', - 245: 'French bulldog', - 246: 'Great Dane', - 247: 'Saint Bernard, St Bernard', - 248: 'Eskimo dog, husky', - 249: 'malamute, malemute, Alaskan malamute', - 250: 'Siberian husky', - 251: 'dalmatian, coach dog, carriage dog', - 252: 'affenpinscher, monkey pinscher, monkey dog', - 253: 'basenji', - 254: 'pug, pug-dog', - 255: 'Leonberg', - 256: 'Newfoundland, Newfoundland dog', - 257: 'Great Pyrenees', - 258: 'Samoyed, Samoyede', - 259: 'Pomeranian', - 260: 'chow, chow chow', - 261: 'keeshond', - 262: 'Brabancon griffon', - 263: 'Pembroke, Pembroke Welsh corgi', - 264: 'Cardigan, Cardigan Welsh corgi', - 265: 'toy poodle', - 266: 'miniature poodle', - 267: 'standard poodle', - 268: 'Mexican hairless', - 269: 'timber wolf, grey wolf, gray wolf, Canis lupus', - 270: 'white wolf, Arctic wolf, Canis lupus tundrarum', - 271: 'red wolf, maned wolf, Canis rufus, Canis niger', - 272: 'coyote, prairie wolf, brush wolf, Canis latrans', - 273: 'dingo, warrigal, warragal, Canis dingo', - 274: 'dhole, Cuon alpinus', - 275: 'African hunting dog, hyena dog, Cape hunting dog, Lycaon pictus', - 276: 'hyena, hyaena', - 277: 'red fox, Vulpes vulpes', - 278: 'kit fox, Vulpes macrotis', - 279: 'Arctic fox, white fox, Alopex lagopus', - 280: 'grey fox, gray fox, Urocyon cinereoargenteus', - 281: 'tabby, tabby cat', - 282: 'tiger cat', - 283: 'Persian cat', - 284: 'Siamese cat, Siamese', - 285: 'Egyptian cat', - 286: 'cougar, puma, catamount, mountain lion, painter, panther, Felis concolor', - 287: 'lynx, catamount', - 288: 'leopard, Panthera pardus', - 289: 'snow leopard, ounce, Panthera uncia', - 290: 'jaguar, panther, Panthera onca, Felis onca', - 291: 'lion, king of beasts, Panthera leo', - 292: 'tiger, Panthera tigris', - 293: 'cheetah, chetah, Acinonyx jubatus', - 294: 'brown bear, bruin, Ursus arctos', - 295: 'American black bear, black bear, Ursus americanus, Euarctos americanus', - 296: 'ice bear, polar bear, Ursus Maritimus, Thalarctos maritimus', - 297: 'sloth bear, Melursus ursinus, Ursus ursinus', - 298: 'mongoose', - 299: 'meerkat, mierkat', - 300: 'tiger beetle', - 301: 'ladybug, ladybeetle, lady beetle, ladybird, ladybird beetle', - 302: 'ground beetle, carabid beetle', - 303: 'long-horned beetle, longicorn, longicorn beetle', - 304: 'leaf beetle, chrysomelid', - 305: 'dung beetle', - 306: 'rhinoceros beetle', - 307: 'weevil', - 308: 'fly', - 309: 'bee', - 310: 'ant, emmet, pismire', - 311: 'grasshopper, hopper', - 312: 'cricket', - 313: 'walking stick, walkingstick, stick insect', - 314: 'cockroach, roach', - 315: 'mantis, mantid', - 316: 'cicada, cicala', - 317: 'leafhopper', - 318: 'lacewing, lacewing fly', - 319: "dragonfly, darning needle, devil's darning needle, sewing needle, snake feeder, snake doctor, mosquito hawk, skeeter hawk", - 320: 'damselfly', - 321: 'admiral', - 322: 'ringlet, ringlet butterfly', - 323: 'monarch, monarch butterfly, milkweed butterfly, Danaus plexippus', - 324: 'cabbage butterfly', - 325: 'sulphur butterfly, sulfur butterfly', - 326: 'lycaenid, lycaenid butterfly', - 327: 'starfish, sea star', - 328: 'sea urchin', - 329: 'sea cucumber, holothurian', - 330: 'wood rabbit, cottontail, cottontail rabbit', - 331: 'hare', - 332: 'Angora, Angora rabbit', - 333: 'hamster', - 334: 'porcupine, hedgehog', - 335: 'fox squirrel, eastern fox squirrel, Sciurus niger', - 336: 'marmot', - 337: 'beaver', - 338: 'guinea pig, Cavia cobaya', - 339: 'sorrel', - 340: 'zebra', - 341: 'hog, pig, grunter, squealer, Sus scrofa', - 342: 'wild boar, boar, Sus scrofa', - 343: 'warthog', - 344: 'hippopotamus, hippo, river horse, Hippopotamus amphibius', - 345: 'ox', - 346: 'water buffalo, water ox, Asiatic buffalo, Bubalus bubalis', - 347: 'bison', - 348: 'ram, tup', - 349: 'bighorn, bighorn sheep, cimarron, Rocky Mountain bighorn, Rocky Mountain sheep, Ovis canadensis', - 350: 'ibex, Capra ibex', - 351: 'hartebeest', - 352: 'impala, Aepyceros melampus', - 353: 'gazelle', - 354: 'Arabian camel, dromedary, Camelus dromedarius', - 355: 'llama', - 356: 'weasel', - 357: 'mink', - 358: 'polecat, fitch, foulmart, foumart, Mustela putorius', - 359: 'black-footed ferret, ferret, Mustela nigripes', - 360: 'otter', - 361: 'skunk, polecat, wood pussy', - 362: 'badger', - 363: 'armadillo', - 364: 'three-toed sloth, ai, Bradypus tridactylus', - 365: 'orangutan, orang, orangutang, Pongo pygmaeus', - 366: 'gorilla, Gorilla gorilla', - 367: 'chimpanzee, chimp, Pan troglodytes', - 368: 'gibbon, Hylobates lar', - 369: 'siamang, Hylobates syndactylus, Symphalangus syndactylus', - 370: 'guenon, guenon monkey', - 371: 'patas, hussar monkey, Erythrocebus patas', - 372: 'baboon', - 373: 'macaque', - 374: 'langur', - 375: 'colobus, colobus monkey', - 376: 'proboscis monkey, Nasalis larvatus', - 377: 'marmoset', - 378: 'capuchin, ringtail, Cebus capucinus', - 379: 'howler monkey, howler', - 380: 'titi, titi monkey', - 381: 'spider monkey, Ateles geoffroyi', - 382: 'squirrel monkey, Saimiri sciureus', - 383: 'Madagascar cat, ring-tailed lemur, Lemur catta', - 384: 'indri, indris, Indri indri, Indri brevicaudatus', - 385: 'Indian elephant, Elephas maximus', - 386: 'African elephant, Loxodonta africana', - 387: 'lesser panda, red panda, panda, bear cat, cat bear, Ailurus fulgens', - 388: 'giant panda, panda, panda bear, coon bear, Ailuropoda melanoleuca', - 389: 'barracouta, snoek', - 390: 'eel', - 391: 'coho, cohoe, coho salmon, blue jack, silver salmon, Oncorhynchus kisutch', - 392: 'rock beauty, Holocanthus tricolor', - 393: 'anemone fish', - 394: 'sturgeon', - 395: 'gar, garfish, garpike, billfish, Lepisosteus osseus', - 396: 'lionfish', - 397: 'puffer, pufferfish, blowfish, globefish', - 398: 'abacus', - 399: 'abaya', - 400: "academic gown, academic robe, judge's robe", - 401: 'accordion, piano accordion, squeeze box', - 402: 'acoustic guitar', - 403: 'aircraft carrier, carrier, flattop, attack aircraft carrier', - 404: 'airliner', - 405: 'airship, dirigible', - 406: 'altar', - 407: 'ambulance', - 408: 'amphibian, amphibious vehicle', - 409: 'analog clock', - 410: 'apiary, bee house', - 411: 'apron', - 412: 'ashcan, trash can, garbage can, wastebin, ash bin, ash-bin, ashbin, dustbin, trash barrel, trash bin', - 413: 'assault rifle, assault gun', - 414: 'backpack, back pack, knapsack, packsack, rucksack, haversack', - 415: 'bakery, bakeshop, bakehouse', - 416: 'balance beam, beam', - 417: 'balloon', - 418: 'ballpoint, ballpoint pen, ballpen, Biro', - 419: 'Band Aid', - 420: 'banjo', - 421: 'bannister, banister, balustrade, balusters, handrail', - 422: 'barbell', - 423: 'barber chair', - 424: 'barbershop', - 425: 'barn', - 426: 'barometer', - 427: 'barrel, cask', - 428: 'barrow, garden cart, lawn cart, wheelbarrow', - 429: 'baseball', - 430: 'basketball', - 431: 'bassinet', - 432: 'bassoon', - 433: 'bathing cap, swimming cap', - 434: 'bath towel', - 435: 'bathtub, bathing tub, bath, tub', - 436: 'beach wagon, station wagon, wagon, estate car, beach waggon, station waggon, waggon', - 437: 'beacon, lighthouse, beacon light, pharos', - 438: 'beaker', - 439: 'bearskin, busby, shako', - 440: 'beer bottle', - 441: 'beer glass', - 442: 'bell cote, bell cot', - 443: 'bib', - 444: 'bicycle-built-for-two, tandem bicycle, tandem', - 445: 'bikini, two-piece', - 446: 'binder, ring-binder', - 447: 'binoculars, field glasses, opera glasses', - 448: 'birdhouse', - 449: 'boathouse', - 450: 'bobsled, bobsleigh, bob', - 451: 'bolo tie, bolo, bola tie, bola', - 452: 'bonnet, poke bonnet', - 453: 'bookcase', - 454: 'bookshop, bookstore, bookstall', - 455: 'bottlecap', - 456: 'bow', - 457: 'bow tie, bow-tie, bowtie', - 458: 'brass, memorial tablet, plaque', - 459: 'brassiere, bra, bandeau', - 460: 'breakwater, groin, groyne, mole, bulwark, seawall, jetty', - 461: 'breastplate, aegis, egis', - 462: 'broom', - 463: 'bucket, pail', - 464: 'buckle', - 465: 'bulletproof vest', - 466: 'bullet train, bullet', - 467: 'butcher shop, meat market', - 468: 'cab, hack, taxi, taxicab', - 469: 'caldron, cauldron', - 470: 'candle, taper, wax light', - 471: 'cannon', - 472: 'canoe', - 473: 'can opener, tin opener', - 474: 'cardigan', - 475: 'car mirror', - 476: 'carousel, carrousel, merry-go-round, roundabout, whirligig', - 477: "carpenter's kit, tool kit", - 478: 'carton', - 479: 'car wheel', - 480: 'cash machine, cash dispenser, automated teller machine, automatic teller machine, automated teller, automatic teller, ATM', - 481: 'cassette', - 482: 'cassette player', - 483: 'castle', - 484: 'catamaran', - 485: 'CD player', - 486: 'cello, violoncello', - 487: 'cellular telephone, cellular phone, cellphone, cell, mobile phone', - 488: 'chain', - 489: 'chainlink fence', - 490: 'chain mail, ring mail, mail, chain armor, chain armour, ring armor, ring armour', - 491: 'chain saw, chainsaw', - 492: 'chest', - 493: 'chiffonier, commode', - 494: 'chime, bell, gong', - 495: 'china cabinet, china closet', - 496: 'Christmas stocking', - 497: 'church, church building', - 498: 'cinema, movie theater, movie theatre, movie house, picture palace', - 499: 'cleaver, meat cleaver, chopper', - 500: 'cliff dwelling', - 501: 'cloak', - 502: 'clog, geta, patten, sabot', - 503: 'cocktail shaker', - 504: 'coffee mug', - 505: 'coffeepot', - 506: 'coil, spiral, volute, whorl, helix', - 507: 'combination lock', - 508: 'computer keyboard, keypad', - 509: 'confectionery, confectionary, candy store', - 510: 'container ship, containership, container vessel', - 511: 'convertible', - 512: 'corkscrew, bottle screw', - 513: 'cornet, horn, trumpet, trump', - 514: 'cowboy boot', - 515: 'cowboy hat, ten-gallon hat', - 516: 'cradle', - 517: 'crane', - 518: 'crash helmet', - 519: 'crate', - 520: 'crib, cot', - 521: 'Crock Pot', - 522: 'croquet ball', - 523: 'crutch', - 524: 'cuirass', - 525: 'dam, dike, dyke', - 526: 'desk', - 527: 'desktop computer', - 528: 'dial telephone, dial phone', - 529: 'diaper, nappy, napkin', - 530: 'digital clock', - 531: 'digital watch', - 532: 'dining table, board', - 533: 'dishrag, dishcloth', - 534: 'dishwasher, dish washer, dishwashing machine', - 535: 'disk brake, disc brake', - 536: 'dock, dockage, docking facility', - 537: 'dogsled, dog sled, dog sleigh', - 538: 'dome', - 539: 'doormat, welcome mat', - 540: 'drilling platform, offshore rig', - 541: 'drum, membranophone, tympan', - 542: 'drumstick', - 543: 'dumbbell', - 544: 'Dutch oven', - 545: 'electric fan, blower', - 546: 'electric guitar', - 547: 'electric locomotive', - 548: 'entertainment center', - 549: 'envelope', - 550: 'espresso maker', - 551: 'face powder', - 552: 'feather boa, boa', - 553: 'file, file cabinet, filing cabinet', - 554: 'fireboat', - 555: 'fire engine, fire truck', - 556: 'fire screen, fireguard', - 557: 'flagpole, flagstaff', - 558: 'flute, transverse flute', - 559: 'folding chair', - 560: 'football helmet', - 561: 'forklift', - 562: 'fountain', - 563: 'fountain pen', - 564: 'four-poster', - 565: 'freight car', - 566: 'French horn, horn', - 567: 'frying pan, frypan, skillet', - 568: 'fur coat', - 569: 'garbage truck, dustcart', - 570: 'gasmask, respirator, gas helmet', - 571: 'gas pump, gasoline pump, petrol pump, island dispenser', - 572: 'goblet', - 573: 'go-kart', - 574: 'golf ball', - 575: 'golfcart, golf cart', - 576: 'gondola', - 577: 'gong, tam-tam', - 578: 'gown', - 579: 'grand piano, grand', - 580: 'greenhouse, nursery, glasshouse', - 581: 'grille, radiator grille', - 582: 'grocery store, grocery, food market, market', - 583: 'guillotine', - 584: 'hair slide', - 585: 'hair spray', - 586: 'half track', - 587: 'hammer', - 588: 'hamper', - 589: 'hand blower, blow dryer, blow drier, hair dryer, hair drier', - 590: 'hand-held computer, hand-held microcomputer', - 591: 'handkerchief, hankie, hanky, hankey', - 592: 'hard disc, hard disk, fixed disk', - 593: 'harmonica, mouth organ, harp, mouth harp', - 594: 'harp', - 595: 'harvester, reaper', - 596: 'hatchet', - 597: 'holster', - 598: 'home theater, home theatre', - 599: 'honeycomb', - 600: 'hook, claw', - 601: 'hoopskirt, crinoline', - 602: 'horizontal bar, high bar', - 603: 'horse cart, horse-cart', - 604: 'hourglass', - 605: 'iPod', - 606: 'iron, smoothing iron', - 607: "jack-o'-lantern", - 608: 'jean, blue jean, denim', - 609: 'jeep, landrover', - 610: 'jersey, T-shirt, tee shirt', - 611: 'jigsaw puzzle', - 612: 'jinrikisha, ricksha, rickshaw', - 613: 'joystick', - 614: 'kimono', - 615: 'knee pad', - 616: 'knot', - 617: 'lab coat, laboratory coat', - 618: 'ladle', - 619: 'lampshade, lamp shade', - 620: 'laptop, laptop computer', - 621: 'lawn mower, mower', - 622: 'lens cap, lens cover', - 623: 'letter opener, paper knife, paperknife', - 624: 'library', - 625: 'lifeboat', - 626: 'lighter, light, igniter, ignitor', - 627: 'limousine, limo', - 628: 'liner, ocean liner', - 629: 'lipstick, lip rouge', - 630: 'Loafer', - 631: 'lotion', - 632: 'loudspeaker, speaker, speaker unit, loudspeaker system, speaker system', - 633: "loupe, jeweler's loupe", - 634: 'lumbermill, sawmill', - 635: 'magnetic compass', - 636: 'mailbag, postbag', - 637: 'mailbox, letter box', - 638: 'maillot', - 639: 'maillot, tank suit', - 640: 'manhole cover', - 641: 'maraca', - 642: 'marimba, xylophone', - 643: 'mask', - 644: 'matchstick', - 645: 'maypole', - 646: 'maze, labyrinth', - 647: 'measuring cup', - 648: 'medicine chest, medicine cabinet', - 649: 'megalith, megalithic structure', - 650: 'microphone, mike', - 651: 'microwave, microwave oven', - 652: 'military uniform', - 653: 'milk can', - 654: 'minibus', - 655: 'miniskirt, mini', - 656: 'minivan', - 657: 'missile', - 658: 'mitten', - 659: 'mixing bowl', - 660: 'mobile home, manufactured home', - 661: 'Model T', - 662: 'modem', - 663: 'monastery', - 664: 'monitor', - 665: 'moped', - 666: 'mortar', - 667: 'mortarboard', - 668: 'mosque', - 669: 'mosquito net', - 670: 'motor scooter, scooter', - 671: 'mountain bike, all-terrain bike, off-roader', - 672: 'mountain tent', - 673: 'mouse, computer mouse', - 674: 'mousetrap', - 675: 'moving van', - 676: 'muzzle', - 677: 'nail', - 678: 'neck brace', - 679: 'necklace', - 680: 'nipple', - 681: 'notebook, notebook computer', - 682: 'obelisk', - 683: 'oboe, hautboy, hautbois', - 684: 'ocarina, sweet potato', - 685: 'odometer, hodometer, mileometer, milometer', - 686: 'oil filter', - 687: 'organ, pipe organ', - 688: 'oscilloscope, scope, cathode-ray oscilloscope, CRO', - 689: 'overskirt', - 690: 'oxcart', - 691: 'oxygen mask', - 692: 'packet', - 693: 'paddle, boat paddle', - 694: 'paddlewheel, paddle wheel', - 695: 'padlock', - 696: 'paintbrush', - 697: "pajama, pyjama, pj's, jammies", - 698: 'palace', - 699: 'panpipe, pandean pipe, syrinx', - 700: 'paper towel', - 701: 'parachute, chute', - 702: 'parallel bars, bars', - 703: 'park bench', - 704: 'parking meter', - 705: 'passenger car, coach, carriage', - 706: 'patio, terrace', - 707: 'pay-phone, pay-station', - 708: 'pedestal, plinth, footstall', - 709: 'pencil box, pencil case', - 710: 'pencil sharpener', - 711: 'perfume, essence', - 712: 'Petri dish', - 713: 'photocopier', - 714: 'pick, plectrum, plectron', - 715: 'pickelhaube', - 716: 'picket fence, paling', - 717: 'pickup, pickup truck', - 718: 'pier', - 719: 'piggy bank, penny bank', - 720: 'pill bottle', - 721: 'pillow', - 722: 'ping-pong ball', - 723: 'pinwheel', - 724: 'pirate, pirate ship', - 725: 'pitcher, ewer', - 726: "plane, carpenter's plane, woodworking plane", - 727: 'planetarium', - 728: 'plastic bag', - 729: 'plate rack', - 730: 'plow, plough', - 731: "plunger, plumber's helper", - 732: 'Polaroid camera, Polaroid Land camera', - 733: 'pole', - 734: 'police van, police wagon, paddy wagon, patrol wagon, wagon, black Maria', - 735: 'poncho', - 736: 'pool table, billiard table, snooker table', - 737: 'pop bottle, soda bottle', - 738: 'pot, flowerpot', - 739: "potter's wheel", - 740: 'power drill', - 741: 'prayer rug, prayer mat', - 742: 'printer', - 743: 'prison, prison house', - 744: 'projectile, missile', - 745: 'projector', - 746: 'puck, hockey puck', - 747: 'punching bag, punch bag, punching ball, punchball', - 748: 'purse', - 749: 'quill, quill pen', - 750: 'quilt, comforter, comfort, puff', - 751: 'racer, race car, racing car', - 752: 'racket, racquet', - 753: 'radiator', - 754: 'radio, wireless', - 755: 'radio telescope, radio reflector', - 756: 'rain barrel', - 757: 'recreational vehicle, RV, R.V.', - 758: 'reel', - 759: 'reflex camera', - 760: 'refrigerator, icebox', - 761: 'remote control, remote', - 762: 'restaurant, eating house, eating place, eatery', - 763: 'revolver, six-gun, six-shooter', - 764: 'rifle', - 765: 'rocking chair, rocker', - 766: 'rotisserie', - 767: 'rubber eraser, rubber, pencil eraser', - 768: 'rugby ball', - 769: 'rule, ruler', - 770: 'running shoe', - 771: 'safe', - 772: 'safety pin', - 773: 'saltshaker, salt shaker', - 774: 'sandal', - 775: 'sarong', - 776: 'sax, saxophone', - 777: 'scabbard', - 778: 'scale, weighing machine', - 779: 'school bus', - 780: 'schooner', - 781: 'scoreboard', - 782: 'screen, CRT screen', - 783: 'screw', - 784: 'screwdriver', - 785: 'seat belt, seatbelt', - 786: 'sewing machine', - 787: 'shield, buckler', - 788: 'shoe shop, shoe-shop, shoe store', - 789: 'shoji', - 790: 'shopping basket', - 791: 'shopping cart', - 792: 'shovel', - 793: 'shower cap', - 794: 'shower curtain', - 795: 'ski', - 796: 'ski mask', - 797: 'sleeping bag', - 798: 'slide rule, slipstick', - 799: 'sliding door', - 800: 'slot, one-armed bandit', - 801: 'snorkel', - 802: 'snowmobile', - 803: 'snowplow, snowplough', - 804: 'soap dispenser', - 805: 'soccer ball', - 806: 'sock', - 807: 'solar dish, solar collector, solar furnace', - 808: 'sombrero', - 809: 'soup bowl', - 810: 'space bar', - 811: 'space heater', - 812: 'space shuttle', - 813: 'spatula', - 814: 'speedboat', - 815: "spider web, spider's web", - 816: 'spindle', - 817: 'sports car, sport car', - 818: 'spotlight, spot', - 819: 'stage', - 820: 'steam locomotive', - 821: 'steel arch bridge', - 822: 'steel drum', - 823: 'stethoscope', - 824: 'stole', - 825: 'stone wall', - 826: 'stopwatch, stop watch', - 827: 'stove', - 828: 'strainer', - 829: 'streetcar, tram, tramcar, trolley, trolley car', - 830: 'stretcher', - 831: 'studio couch, day bed', - 832: 'stupa, tope', - 833: 'submarine, pigboat, sub, U-boat', - 834: 'suit, suit of clothes', - 835: 'sundial', - 836: 'sunglass', - 837: 'sunglasses, dark glasses, shades', - 838: 'sunscreen, sunblock, sun blocker', - 839: 'suspension bridge', - 840: 'swab, swob, mop', - 841: 'sweatshirt', - 842: 'swimming trunks, bathing trunks', - 843: 'swing', - 844: 'switch, electric switch, electrical switch', - 845: 'syringe', - 846: 'table lamp', - 847: 'tank, army tank, armored combat vehicle, armoured combat vehicle', - 848: 'tape player', - 849: 'teapot', - 850: 'teddy, teddy bear', - 851: 'television, television system', - 852: 'tennis ball', - 853: 'thatch, thatched roof', - 854: 'theater curtain, theatre curtain', - 855: 'thimble', - 856: 'thresher, thrasher, threshing machine', - 857: 'throne', - 858: 'tile roof', - 859: 'toaster', - 860: 'tobacco shop, tobacconist shop, tobacconist', - 861: 'toilet seat', - 862: 'torch', - 863: 'totem pole', - 864: 'tow truck, tow car, wrecker', - 865: 'toyshop', - 866: 'tractor', - 867: 'trailer truck, tractor trailer, trucking rig, rig, articulated lorry, semi', - 868: 'tray', - 869: 'trench coat', - 870: 'tricycle, trike, velocipede', - 871: 'trimaran', - 872: 'tripod', - 873: 'triumphal arch', - 874: 'trolleybus, trolley coach, trackless trolley', - 875: 'trombone', - 876: 'tub, vat', - 877: 'turnstile', - 878: 'typewriter keyboard', - 879: 'umbrella', - 880: 'unicycle, monocycle', - 881: 'upright, upright piano', - 882: 'vacuum, vacuum cleaner', - 883: 'vase', - 884: 'vault', - 885: 'velvet', - 886: 'vending machine', - 887: 'vestment', - 888: 'viaduct', - 889: 'violin, fiddle', - 890: 'volleyball', - 891: 'waffle iron', - 892: 'wall clock', - 893: 'wallet, billfold, notecase, pocketbook', - 894: 'wardrobe, closet, press', - 895: 'warplane, military plane', - 896: 'washbasin, handbasin, washbowl, lavabo, wash-hand basin', - 897: 'washer, automatic washer, washing machine', - 898: 'water bottle', - 899: 'water jug', - 900: 'water tower', - 901: 'whiskey jug', - 902: 'whistle', - 903: 'wig', - 904: 'window screen', - 905: 'window shade', - 906: 'Windsor tie', - 907: 'wine bottle', - 908: 'wing', - 909: 'wok', - 910: 'wooden spoon', - 911: 'wool, woolen, woollen', - 912: 'worm fence, snake fence, snake-rail fence, Virginia fence', - 913: 'wreck', - 914: 'yawl', - 915: 'yurt', - 916: 'web site, website, internet site, site', - 917: 'comic book', - 918: 'crossword puzzle, crossword', - 919: 'street sign', - 920: 'traffic light, traffic signal, stoplight', - 921: 'book jacket, dust cover, dust jacket, dust wrapper', - 922: 'menu', - 923: 'plate', - 924: 'guacamole', - 925: 'consomme', - 926: 'hot pot, hotpot', - 927: 'trifle', - 928: 'ice cream, icecream', - 929: 'ice lolly, lolly, lollipop, popsicle', - 930: 'French loaf', - 931: 'bagel, beigel', - 932: 'pretzel', - 933: 'cheeseburger', - 934: 'hotdog, hot dog, red hot', - 935: 'mashed potato', - 936: 'head cabbage', - 937: 'broccoli', - 938: 'cauliflower', - 939: 'zucchini, courgette', - 940: 'spaghetti squash', - 941: 'acorn squash', - 942: 'butternut squash', - 943: 'cucumber, cuke', - 944: 'artichoke, globe artichoke', - 945: 'bell pepper', - 946: 'cardoon', - 947: 'mushroom', - 948: 'Granny Smith', - 949: 'strawberry', - 950: 'orange', - 951: 'lemon', - 952: 'fig', - 953: 'pineapple, ananas', - 954: 'banana', - 955: 'jackfruit, jak, jack', - 956: 'custard apple', - 957: 'pomegranate', - 958: 'hay', - 959: 'carbonara', - 960: 'chocolate sauce, chocolate syrup', - 961: 'dough', - 962: 'meat loaf, meatloaf', - 963: 'pizza, pizza pie', - 964: 'potpie', - 965: 'burrito', - 966: 'red wine', - 967: 'espresso', - 968: 'cup', - 969: 'eggnog', - 970: 'alp', - 971: 'bubble', - 972: 'cliff, drop, drop-off', - 973: 'coral reef', - 974: 'geyser', - 975: 'lakeside, lakeshore', - 976: 'promontory, headland, head, foreland', - 977: 'sandbar, sand bar', - 978: 'seashore, coast, seacoast, sea-coast', - 979: 'valley, vale', - 980: 'volcano', - 981: 'ballplayer, baseball player', - 982: 'groom, bridegroom', - 983: 'scuba diver', - 984: 'rapeseed', - 985: 'daisy', - 986: "yellow lady's slipper, yellow lady-slipper, Cypripedium calceolus, Cypripedium parviflorum", - 987: 'corn', - 988: 'acorn', - 989: 'hip, rose hip, rosehip', - 990: 'buckeye, horse chestnut, conker', - 991: 'coral fungus', - 992: 'agaric', - 993: 'gyromitra', - 994: 'stinkhorn, carrion fungus', - 995: 'earthstar', - 996: 'hen-of-the-woods, hen of the woods, Polyporus frondosus, Grifola frondosa', - 997: 'bolete', - 998: 'ear, spike, capitulum', - 999: 'toilet tissue, toilet paper, bathroom tissue'} \ No newline at end of file diff --git a/tinygrad_repo/test/models/test_bert.py b/tinygrad_repo/test/models/test_bert.py deleted file mode 100644 index 86588e0..0000000 --- a/tinygrad_repo/test/models/test_bert.py +++ /dev/null @@ -1,57 +0,0 @@ -#!/usr/bin/env python -import unittest -import numpy as np -from tinygrad.tensor import Tensor -from tinygrad.ops import Device -import torch - -def get_question_samp(bsz, seq_len, vocab_size, seed): - np.random.seed(seed) - in_ids= np.random.randint(vocab_size, size=(bsz, seq_len)) - mask = np.random.choice([True, False], size=(bsz, seq_len)) - seg_ids = np.random.randint(1, size=(bsz, seq_len)) - return in_ids, mask, seg_ids - -def set_equal_weights(mdl, torch_mdl): - from tinygrad.nn.state import get_state_dict - state, torch_state = get_state_dict(mdl), torch_mdl.state_dict() - assert len(state) == len(torch_state) - for k, v in state.items(): - assert k in torch_state - torch_state[k].copy_(torch.from_numpy(v.numpy())) - torch_mdl.eval() - -class TestBert(unittest.TestCase): - def test_questions(self): - from models.bert import BertForQuestionAnswering - from transformers import BertForQuestionAnswering as TorchBertForQuestionAnswering - from transformers import BertConfig - - # small - config = { - 'vocab_size':24, 'hidden_size':2, 'num_hidden_layers':2, 'num_attention_heads':2, - 'intermediate_size':32, 'hidden_dropout_prob':0.1, 'attention_probs_dropout_prob':0.1, - 'max_position_embeddings':512, 'type_vocab_size':2 - } - - # Create in tinygrad - Tensor.manual_seed(1337) - mdl = BertForQuestionAnswering(**config) - - # Create in torch - with torch.no_grad(): - torch_mdl = TorchBertForQuestionAnswering(BertConfig(**config)) - - set_equal_weights(mdl, torch_mdl) - - seeds = (1337, 3141) - bsz, seq_len = 1, 16 - for _, seed in enumerate(seeds): - in_ids, mask, seg_ids = get_question_samp(bsz, seq_len, config['vocab_size'], seed) - out = mdl(Tensor(in_ids), Tensor(mask), Tensor(seg_ids)) - torch_out = torch_mdl.forward(torch.from_numpy(in_ids).long(), torch.from_numpy(mask), torch.from_numpy(seg_ids).long())[:2] - torch_out = torch.cat(torch_out).unsqueeze(2) - np.testing.assert_allclose(out.numpy(), torch_out.detach().numpy(), atol=5e-4, rtol=5e-4) - -if __name__ == '__main__': - unittest.main() diff --git a/tinygrad_repo/test/models/test_efficientnet.py b/tinygrad_repo/test/models/test_efficientnet.py deleted file mode 100644 index 76108a5..0000000 --- a/tinygrad_repo/test/models/test_efficientnet.py +++ /dev/null @@ -1,115 +0,0 @@ -import ast -import pathlib -import sys -import unittest - -import numpy as np -from PIL import Image - -from tinygrad.helpers import getenv -from tinygrad.tensor import Tensor -from models.efficientnet import EfficientNet -from models.vit import ViT -from models.resnet import ResNet50 - -def _load_labels(): - labels_filename = pathlib.Path(__file__).parent / 'efficientnet/imagenet1000_clsidx_to_labels.txt' - return ast.literal_eval(labels_filename.read_text()) - -_LABELS = _load_labels() - -def preprocess(img, new=False): - # preprocess image - aspect_ratio = img.size[0] / img.size[1] - img = img.resize((int(224*max(aspect_ratio,1.0)), int(224*max(1.0/aspect_ratio,1.0)))) - - img = np.array(img) - y0, x0 =(np.asarray(img.shape)[:2] - 224) // 2 - img = img[y0: y0 + 224, x0: x0 + 224] - - # low level preprocess - if new: - img = img.astype(np.float32) - img -= [127.0, 127.0, 127.0] - img /= [128.0, 128.0, 128.0] - img = img[None] - else: - img = np.moveaxis(img, [2, 0, 1], [0, 1, 2]) - img = img.astype(np.float32)[:3].reshape(1, 3, 224, 224) - img /= 255.0 - img -= np.array([0.485, 0.456, 0.406]).reshape((1, -1, 1, 1)) - img /= np.array([0.229, 0.224, 0.225]).reshape((1, -1, 1, 1)) - return img - - -def _infer(model: EfficientNet, img, bs=1): - Tensor.training = False - img = preprocess(img) - # run the net - if bs > 1: img = img.repeat(bs, axis=0) - out = model.forward(Tensor(img)).cpu() - return _LABELS[np.argmax(out.numpy()[0])] - -chicken_img = Image.open(pathlib.Path(__file__).parent / 'efficientnet/Chicken.jpg') -car_img = Image.open(pathlib.Path(__file__).parent / 'efficientnet/car.jpg') - -class TestEfficientNet(unittest.TestCase): - @classmethod - def setUpClass(cls): - cls.model = EfficientNet(number=getenv("NUM")) - cls.model.load_from_pretrained() - - @classmethod - def tearDownClass(cls): - del cls.model - - def test_chicken(self): - label = _infer(self.model, chicken_img) - self.assertEqual(label, "hen") - - def test_chicken_bigbatch(self): - label = _infer(self.model, chicken_img, 2) - self.assertEqual(label, "hen") - - def test_car(self): - label = _infer(self.model, car_img) - self.assertEqual(label, "sports car, sport car") - -class TestViT(unittest.TestCase): - @classmethod - def setUpClass(cls): - cls.model = ViT() - cls.model.load_from_pretrained() - - @classmethod - def tearDownClass(cls): - del cls.model - - def test_chicken(self): - label = _infer(self.model, chicken_img) - self.assertEqual(label, "cock") - - def test_car(self): - label = _infer(self.model, car_img) - self.assertEqual(label, "racer, race car, racing car") - -class TestResNet(unittest.TestCase): - @classmethod - def setUpClass(cls): - cls.model = ResNet50() - cls.model.load_from_pretrained() - - @classmethod - def tearDownClass(cls): - del cls.model - - def test_chicken(self): - label = _infer(self.model, chicken_img) - self.assertEqual(label, "hen") - - def test_car(self): - label = _infer(self.model, car_img) - self.assertEqual(label, "sports car, sport car") - -if __name__ == '__main__': - unittest.main() diff --git a/tinygrad_repo/test/models/test_end2end.py b/tinygrad_repo/test/models/test_end2end.py deleted file mode 100644 index 8ea00b0..0000000 --- a/tinygrad_repo/test/models/test_end2end.py +++ /dev/null @@ -1,165 +0,0 @@ -import torch -from torch import nn -import unittest -import numpy as np -from tinygrad.nn.state import get_parameters, get_state_dict -from tinygrad.nn import optim, Linear, Conv2d, BatchNorm2d -from tinygrad.tensor import Tensor -from extra.datasets import fetch_mnist -from tinygrad.helpers import CI - -def compare_tiny_torch(model, model_torch, X, Y): - with Tensor.train(): - model_torch.train() - model_state_dict = get_state_dict(model) - for k,v in model_torch.named_parameters(): - if not CI: print(f"initting {k} from torch") - model_state_dict[k].assign(Tensor(v.detach().numpy())).realize() - - optimizer = optim.SGD(get_parameters(model), lr=0.001) - optimizer_torch = torch.optim.SGD(model_torch.parameters(), lr=0.001) - - Xt = torch.Tensor(X.numpy()) - np.testing.assert_allclose(X.numpy(), Xt.detach().numpy()) - - out = model(X) - loss = (out * Y).mean() - if not CI: print(loss.realize().numpy()) - - out_torch = model_torch(torch.Tensor(X.numpy())) - loss_torch = (out_torch * torch.Tensor(Y.numpy())).mean() - if not CI: print(loss_torch.detach().numpy()) - - # assert losses match - np.testing.assert_allclose(loss.realize().numpy(), loss_torch.detach().numpy(), atol=1e-4) - - # zero and backward - optimizer.zero_grad() - loss.backward() - optimizer_torch.zero_grad() - loss_torch.backward() - - for k,v in list(model_torch.named_parameters())[::-1]: - g = model_state_dict[k].grad.numpy() - gt = v.grad.detach().numpy() - if not CI: print("testing grads", k) - np.testing.assert_allclose(g, gt, atol=1e-3, err_msg=f'grad mismatch {k}') - - # take the steps - optimizer.step() - optimizer_torch.step() - - # assert weights match (they don't!) - for k,v in model_torch.named_parameters(): - if not CI: print("testing weight", k) - np.testing.assert_allclose(model_state_dict[k].numpy(), v.detach().numpy(), atol=1e-3, err_msg=f'weight mismatch {k}') - -def get_mnist_data(): - X_train, Y_train, X_test, Y_test = fetch_mnist() - BS = 32 - num_classes = 10 - X = Tensor(X_test[0:BS].astype(np.float32)) - Y = np.zeros((BS, num_classes), np.float32) - Y[range(BS),Y_test[0:BS]] = -1.0*num_classes - return X, Tensor(Y) - -class TestEnd2End(unittest.TestCase): - @classmethod - def setUpClass(cls): - cls.X, cls.Y = get_mnist_data() - - def setUp(self): - torch.manual_seed(123) - - def test_linear_mnist(self): - class LinTiny: - def __init__(self, has_batchnorm=False): - self.l1 = Linear(784, 128) - self.l2 = Linear(128, 10) - self.bn1 = BatchNorm2d(128) if has_batchnorm else lambda x: x - def __call__(self, x): - return self.l2(self.l1(x)).relu().log_softmax(-1) - class LinTorch(nn.Module): - def __init__(self, has_batchnorm=False): - super().__init__() - self.l1 = nn.Linear(784, 128) - self.l2 = nn.Linear(128, 10) - def forward(self, x): - return self.l2(self.l1(x)).relu().log_softmax(-1) - compare_tiny_torch(LinTiny(), LinTorch(), self.X, self.Y) - - def test_bn_mnist(self): - class LinTiny: - def __init__(self): - self.l1 = Linear(784, 128) - self.l2 = Linear(128, 10) - self.bn1 = BatchNorm2d(128) - def __call__(self, x): - return self.l2(self.bn1(self.l1(x).reshape(x.shape[0], -1, 1, 1)).reshape(x.shape[0], -1).relu()).log_softmax(-1) - class LinTorch(nn.Module): - def __init__(self): - super().__init__() - self.l1 = nn.Linear(784, 128) - self.l2 = nn.Linear(128, 10) - self.bn1 = nn.BatchNorm2d(128) - def forward(self, x): - return self.l2(self.bn1(self.l1(x).reshape(x.shape[0], -1, 1, 1)).reshape(x.shape[0], -1).relu()).log_softmax(-1) - compare_tiny_torch(LinTiny(), LinTorch(), self.X, self.Y) - - def test_bn_alone(self): - np.random.seed(1337) - X = Tensor(np.random.randn(32, 10, 1, 1).astype(np.float32)) - Y = Tensor(np.random.randn(32, 10, 1, 1).astype(np.float32)) - compare_tiny_torch(BatchNorm2d(10), nn.BatchNorm2d(10), X, Y) - - def test_bn_linear(self): - BS, K = 2, 1 - eps = 0 - X = Tensor([1,0]).reshape(BS, K, 1, 1) - Y = Tensor([-1,0]).reshape(BS, K, 1, 1) - class LinTiny: - def __init__(self): - self.l1 = Conv2d(K, K, 1, bias=False) - self.bn1 = BatchNorm2d(K, affine=False, track_running_stats=False, eps=eps) - def __call__(self, x): return self.bn1(self.l1(x)) - class LinTorch(nn.Module): - def __init__(self): - super().__init__() - self.l1 = nn.Conv2d(K, K, 1, bias=False) - self.bn1 = nn.BatchNorm2d(K, affine=False, track_running_stats=False, eps=eps) - def forward(self, x): return self.bn1(self.l1(x)) - model_torch = LinTorch() - with torch.no_grad(): - model_torch.l1.weight[:] = 1. - compare_tiny_torch(LinTiny(), model_torch, X, Y) - - def test_conv_mnist(self): - class LinTiny: - def __init__(self, has_batchnorm=False): - self.c1 = Conv2d(1, 8, 3, stride=2) - self.c2 = Conv2d(8, 16, 3, stride=2) - self.l1 = Linear(16*6*6, 10) - if has_batchnorm: - self.bn1, self.bn2 = BatchNorm2d(8), BatchNorm2d(16) - else: - self.bn1, self.bn2 = lambda x: x, lambda x: x - def __call__(self, x): - return self.l1(self.bn2(self.c2(self.bn1(self.c1(x)).relu())).relu().reshape(x.shape[0], -1)).log_softmax(-1) - class LinTorch(nn.Module): - def __init__(self, has_batchnorm=False): - super().__init__() - self.c1 = nn.Conv2d(1, 8, 3, stride=2) - self.c2 = nn.Conv2d(8, 16, 3, stride=2) - self.l1 = nn.Linear(16*6*6, 10) - if has_batchnorm: - self.bn1, self.bn2 = nn.BatchNorm2d(8), nn.BatchNorm2d(16) - else: - self.bn1, self.bn2 = lambda x: x, lambda x: x - def forward(self, x): - return self.l1(self.bn2(self.c2(self.bn1(self.c1(x)).relu())).relu().reshape(x.shape[0], -1)).log_softmax(-1) - for has_batchnorm in [False, True]: - with self.subTest(has_batchnorm=has_batchnorm): - compare_tiny_torch(LinTiny(has_batchnorm), LinTorch(has_batchnorm), self.X.reshape((-1, 1, 28, 28)), self.Y) - -if __name__ == "__main__": - unittest.main() diff --git a/tinygrad_repo/test/models/test_mnist.py b/tinygrad_repo/test/models/test_mnist.py deleted file mode 100644 index f3f37c3..0000000 --- a/tinygrad_repo/test/models/test_mnist.py +++ /dev/null @@ -1,116 +0,0 @@ -#!/usr/bin/env python -import unittest -import numpy as np -from tinygrad.nn.state import get_parameters -from tinygrad.tensor import Tensor, Device -from tinygrad.nn import optim, BatchNorm2d -from extra.training import train, evaluate -from extra.datasets import fetch_mnist -import pytest - -pytestmark = [pytest.mark.exclude_gpu, pytest.mark.exclude_clang] - -# load the mnist dataset -X_train, Y_train, X_test, Y_test = fetch_mnist() - -# create a model -class TinyBobNet: - def __init__(self): - self.l1 = Tensor.scaled_uniform(784, 128) - self.l2 = Tensor.scaled_uniform(128, 10) - - def parameters(self): - return get_parameters(self) - - def forward(self, x): - return x.dot(self.l1).relu().dot(self.l2).log_softmax() - -# create a model with a conv layer -class TinyConvNet: - def __init__(self, has_batchnorm=False): - # https://keras.io/examples/vision/mnist_convnet/ - conv = 3 - #inter_chan, out_chan = 32, 64 - inter_chan, out_chan = 8, 16 # for speed - self.c1 = Tensor.scaled_uniform(inter_chan,1,conv,conv) - self.c2 = Tensor.scaled_uniform(out_chan,inter_chan,conv,conv) - self.l1 = Tensor.scaled_uniform(out_chan*5*5, 10) - if has_batchnorm: - self.bn1 = BatchNorm2d(inter_chan) - self.bn2 = BatchNorm2d(out_chan) - else: - self.bn1, self.bn2 = lambda x: x, lambda x: x - - def parameters(self): - return get_parameters(self) - - def forward(self, x:Tensor): - x = x.reshape(shape=(-1, 1, 28, 28)) # hacks - x = self.bn1(x.conv2d(self.c1)).relu().max_pool2d() - x = self.bn2(x.conv2d(self.c2)).relu().max_pool2d() - x = x.reshape(shape=[x.shape[0], -1]) - return x.dot(self.l1).log_softmax() - -class TestMNIST(unittest.TestCase): - def test_sgd_onestep(self): - np.random.seed(1337) - model = TinyBobNet() - optimizer = optim.SGD(model.parameters(), lr=0.001) - train(model, X_train, Y_train, optimizer, BS=69, steps=1) - for p in model.parameters(): p.realize() - - def test_sgd_threestep(self): - np.random.seed(1337) - model = TinyBobNet() - optimizer = optim.SGD(model.parameters(), lr=0.001) - train(model, X_train, Y_train, optimizer, BS=69, steps=3) - - def test_sgd_sixstep(self): - np.random.seed(1337) - model = TinyBobNet() - optimizer = optim.SGD(model.parameters(), lr=0.001) - train(model, X_train, Y_train, optimizer, BS=69, steps=6, noloss=True) - - def test_adam_onestep(self): - np.random.seed(1337) - model = TinyBobNet() - optimizer = optim.Adam(model.parameters(), lr=0.001) - train(model, X_train, Y_train, optimizer, BS=69, steps=1) - for p in model.parameters(): p.realize() - - def test_adam_threestep(self): - np.random.seed(1337) - model = TinyBobNet() - optimizer = optim.Adam(model.parameters(), lr=0.001) - train(model, X_train, Y_train, optimizer, BS=69, steps=3) - - def test_conv_onestep(self): - np.random.seed(1337) - model = TinyConvNet() - optimizer = optim.SGD(model.parameters(), lr=0.001) - train(model, X_train, Y_train, optimizer, BS=69, steps=1, noloss=True) - for p in model.parameters(): p.realize() - - def test_conv(self): - np.random.seed(1337) - model = TinyConvNet() - optimizer = optim.Adam(model.parameters(), lr=0.001) - train(model, X_train, Y_train, optimizer, steps=100) - assert evaluate(model, X_test, Y_test) > 0.93 # torch gets 0.9415 sometimes - - def test_conv_with_bn(self): - np.random.seed(1337) - model = TinyConvNet(has_batchnorm=True) - optimizer = optim.AdamW(model.parameters(), lr=0.003) - train(model, X_train, Y_train, optimizer, steps=200) - assert evaluate(model, X_test, Y_test) > 0.94 - - def test_sgd(self): - np.random.seed(1337) - model = TinyBobNet() - optimizer = optim.SGD(model.parameters(), lr=0.001) - train(model, X_train, Y_train, optimizer, steps=600) - assert evaluate(model, X_test, Y_test) > 0.94 # CPU gets 0.9494 sometimes - -if __name__ == '__main__': - unittest.main() diff --git a/tinygrad_repo/test/models/test_onnx.py b/tinygrad_repo/test/models/test_onnx.py deleted file mode 100644 index feffdab..0000000 --- a/tinygrad_repo/test/models/test_onnx.py +++ /dev/null @@ -1,143 +0,0 @@ -#!/usr/bin/env python -import os -import time -import io -import unittest -import numpy as np -import onnx -from extra.utils import fetch, temp -from extra.onnx import get_run_onnx -from tinygrad.tensor import Tensor -from tinygrad.helpers import CI -import pytest - -pytestmark = [pytest.mark.exclude_gpu, pytest.mark.exclude_clang] - -def run_onnx_torch(onnx_model, inputs): - import torch - from onnx2torch import convert - torch_model = convert(onnx_model).float() - with torch.no_grad(): - torch_out = torch_model(*[torch.tensor(x) for x in inputs.values()]) - return torch_out - -OPENPILOT_MODEL = "https://github.com/commaai/openpilot/raw/v0.9.4/selfdrive/modeld/models/supercombo.onnx" - -np.random.seed(1337) - -class TestOnnxModel(unittest.TestCase): - def test_benchmark_openpilot_model(self): - dat = fetch(OPENPILOT_MODEL) - onnx_model = onnx.load(io.BytesIO(dat)) - run_onnx = get_run_onnx(onnx_model) - def get_inputs(): - np_inputs = { - "input_imgs": np.random.randn(*(1, 12, 128, 256)), - "big_input_imgs": np.random.randn(*(1, 12, 128, 256)), - "desire": np.zeros((1, 100, 8)), - "traffic_convention": np.array([[1., 0.]]), - "nav_features": np.zeros((1, 256)), - "features_buffer": np.zeros((1, 99, 128)), - } - inputs = {k:Tensor(v.astype(np.float32), requires_grad=False) for k,v in np_inputs.items()} - return inputs - - for _ in range(7): - inputs = get_inputs() - st = time.monotonic() - tinygrad_out = run_onnx(inputs)['outputs'] - mt = time.monotonic() - tinygrad_out.realize() - mt2 = time.monotonic() - tinygrad_out = tinygrad_out.numpy() - et = time.monotonic() - if not CI: print(f"ran openpilot model in {(et-st)*1000.0:.2f} ms, waited {(mt2-mt)*1000.0:.2f} ms for realize, {(et-mt2)*1000.0:.2f} ms for GPU queue") - - if not CI: - import cProfile - import pstats - inputs = get_inputs() - pr = cProfile.Profile(timer=time.perf_counter_ns, timeunit=1e-6) - pr.enable() - tinygrad_out = run_onnx(inputs)['outputs'] - tinygrad_out.realize() - tinygrad_out = tinygrad_out.numpy() - if not CI: - pr.disable() - stats = pstats.Stats(pr) - stats.dump_stats(temp("net.prof")) - os.system(f"flameprof {temp('net.prof')} > {temp('prof.svg')}") - ps = stats.sort_stats(pstats.SortKey.TIME) - ps.print_stats(30) - - def test_openpilot_model(self): - dat = fetch(OPENPILOT_MODEL) - onnx_model = onnx.load(io.BytesIO(dat)) - run_onnx = get_run_onnx(onnx_model) - print("got run_onnx") - inputs = { - "input_imgs": np.random.randn(*(1, 12, 128, 256)), - "big_input_imgs": np.random.randn(*(1, 12, 128, 256)), - "desire": np.zeros((1, 100, 8)), - "traffic_convention": np.array([[1., 0.]]), - "nav_features": np.zeros((1, 256)), - "features_buffer": np.zeros((1, 99, 128)), - } - inputs = {k:v.astype(np.float32) for k,v in inputs.items()} - - st = time.monotonic() - print("****** run onnx ******") - tinygrad_out = run_onnx(inputs)['outputs'] - mt = time.monotonic() - print("****** realize ******") - tinygrad_out.realize() - mt2 = time.monotonic() - tinygrad_out = tinygrad_out.numpy() - et = time.monotonic() - print(f"ran openpilot model in {(et-st)*1000.0:.2f} ms, waited {(mt2-mt)*1000.0:.2f} ms for realize, {(et-mt2)*1000.0:.2f} ms for GPU queue") - - Tensor.no_grad = True - torch_out = run_onnx_torch(onnx_model, inputs).numpy() - Tensor.no_grad = False - print(tinygrad_out, torch_out) - np.testing.assert_allclose(torch_out, tinygrad_out, atol=1e-4, rtol=1e-2) - - def test_efficientnet(self): - dat = fetch("https://github.com/onnx/models/raw/main/vision/classification/efficientnet-lite4/model/efficientnet-lite4-11.onnx") - input_name, input_new = "images:0", True - self._test_model(dat, input_name, input_new) - - def test_shufflenet(self): - dat = fetch("https://github.com/onnx/models/raw/main/vision/classification/shufflenet/model/shufflenet-9.onnx") - print(f"shufflenet downloaded : {len(dat)/1e6:.2f} MB") - input_name, input_new = "gpu_0/data_0", False - self._test_model(dat, input_name, input_new) - - @unittest.skip("test is very slow") - def test_resnet(self): - # NOTE: many onnx models can't be run right now due to max pool with strides != kernel_size - dat = fetch("https://github.com/onnx/models/raw/main/vision/classification/resnet/model/resnet18-v2-7.onnx") - print(f"resnet downloaded : {len(dat)/1e6:.2f} MB") - input_name, input_new = "data", False - self._test_model(dat, input_name, input_new) - - def _test_model(self, dat, input_name, input_new, debug=False): - onnx_model = onnx.load(io.BytesIO(dat)) - print("onnx loaded") - from test.models.test_efficientnet import chicken_img, car_img, preprocess, _LABELS - run_onnx = get_run_onnx(onnx_model) - - def run(img): - inputs = {input_name: preprocess(img, new=input_new)} - tinygrad_out = list(run_onnx(inputs, debug=debug).values())[0].numpy() - return tinygrad_out.argmax() - - cls = run(chicken_img) - print(cls, _LABELS[cls]) - assert _LABELS[cls] == "hen" or _LABELS[cls] == "cock" - cls = run(car_img) - print(cls, _LABELS[cls]) - assert "car" in _LABELS[cls] or _LABELS[cls] == "convertible" - -if __name__ == "__main__": - unittest.main() diff --git a/tinygrad_repo/test/models/test_real_world.py b/tinygrad_repo/test/models/test_real_world.py deleted file mode 100644 index 31c8102..0000000 --- a/tinygrad_repo/test/models/test_real_world.py +++ /dev/null @@ -1,100 +0,0 @@ -import unittest, time -import numpy as np -from tinygrad.tensor import Tensor -from tinygrad.nn import optim -from tinygrad.nn.state import get_parameters -from tinygrad.jit import TinyJit, JIT_SUPPORTED_DEVICE -from tinygrad.ops import Device, GlobalCounters -from tinygrad.helpers import CI, dtypes, getenv, prod -from test.helpers import derandomize_model - -from examples.gpt2 import Transformer as GPT2Transformer, MODEL_PARAMS as GPT2_MODEL_PARAMS -from examples.hlb_cifar10 import SpeedyResNet -from examples.llama import Transformer as LLaMaTransformer, MODEL_PARAMS as LLAMA_MODEL_PARAMS -from examples.stable_diffusion import UNetModel - -def helper_test(nm, gen, train, max_memory_allowed, max_kernels_allowed, all_jitted=False): - tms = [] - for _ in range(4): - GlobalCounters.reset() - GlobalCounters.mem_used = 0 - Device[Device.DEFAULT].synchronize() - st = time.perf_counter_ns() - train(*gen()) - Device[Device.DEFAULT].synchronize() - tms.append(time.perf_counter_ns() - st) - - kernels_used = len(train.jit_cache) if hasattr(train, "jit_cache") else None - print(f"{nm}: used {GlobalCounters.mem_used/1e9:.2f} GB and {kernels_used} kernels in {min(tms)/1e6:.2f} ms") - assert GlobalCounters.mem_used/1e9 < max_memory_allowed, f"{nm} used more than {max_memory_allowed:.2f} GB" - assert not kernels_used or kernels_used <= max_kernels_allowed, f"{nm} used more than {max_kernels_allowed} kernels" - if all_jitted: - assert kernels_used > 0 and kernels_used == GlobalCounters.kernel_count, f"only {kernels_used} out of {GlobalCounters.kernel_count} were jitted" - -class TestRealWorld(unittest.TestCase): - def setUp(self): - self.old_type = Tensor.default_type - np.random.seed(2002) - - def tearDown(self): - Tensor.default_type = self.old_type - - @unittest.skipUnless(not CI, "too big for CI") - def test_stable_diffusion(self): - model = UNetModel() - derandomize_model(model) - @TinyJit - def test(t, t2): return model(t, 801, t2).realize() - helper_test("test_sd", lambda: (Tensor.randn(1, 4, 64, 64),Tensor.randn(1, 77, 768)), test, 18.0, 967) - - @unittest.skipUnless(Device.DEFAULT in JIT_SUPPORTED_DEVICE and Device.DEFAULT not in ["LLVM"], "needs JIT, too long on CI LLVM") - def test_llama(self): - Tensor.default_type = dtypes.float16 - - args_tiny = {"dim": 1024, "multiple_of": 256, "n_heads": 8, "n_layers": 8, "norm_eps": 1e-05, "vocab_size": 1000} - model = LLaMaTransformer(**(args_tiny if CI else LLAMA_MODEL_PARAMS["1"]["7B"]["args"])) - derandomize_model(model) - @TinyJit - def test(t): return model(t, 0).realize() - # NOTE: only test one pass, not testing the dynamic shape autoregressive part - helper_test("test_llama", lambda: (Tensor([[1,]]),), test, 0.22 if CI else 13.5, 126 if CI else 486, all_jitted=True) - - @unittest.skipUnless(Device.DEFAULT in JIT_SUPPORTED_DEVICE and (Device.DEFAULT not in ["LLVM"] or not CI), "needs JIT, too long on CI LLVM") - def test_gpt2(self): - Tensor.default_type = dtypes.float16 - - args_tiny = {"dim": 1024, "n_heads": 8, "n_layers": 8, "norm_eps": 1e-5, "vocab_size": 1000} - model = GPT2Transformer(**(args_tiny if CI else GPT2_MODEL_PARAMS["gpt2-medium"])) - derandomize_model(model) - @TinyJit - def test(t): return model(t, 0).realize() - helper_test("test_gpt2", lambda: (Tensor([[1,]]),), test, 0.21 if CI else 0.9, 129 if CI else 369, all_jitted=True) - - @unittest.skipUnless(Device.DEFAULT in JIT_SUPPORTED_DEVICE and (Device.DEFAULT not in ["LLVM", "CLANG"] or not CI), "needs JIT, too long on CI LLVM and CLANG") - def test_train_cifar(self): - # TODO: with default device - #old_default = Device.DEFAULT - #Device.DEFAULT = "FAKE" - #Device['fake'].codegen = Device[old_default].codegen - - with Tensor.train(): - model = SpeedyResNet(Tensor.ones((12,3,2,2))) - optimizer = optim.SGD(get_parameters(model), lr=0.01, momentum=0.8, nesterov=True, weight_decay=0.15) - - BS = 32 if CI else 512 - - @TinyJit - def train(X): - out = model(X) - loss = out.mean() - optimizer.zero_grad() - loss.backward() - optimizer.step() - - helper_test("train_cifar", lambda: (Tensor.randn(BS, 3, 32, 32),), train, (1.0/48)*BS, 154) # it's 154 on metal - - # reset device - #Device.DEFAULT = old_default - -if __name__ == '__main__': - unittest.main() diff --git a/tinygrad_repo/test/models/test_rnnt.py b/tinygrad_repo/test/models/test_rnnt.py deleted file mode 100644 index 51a934b..0000000 --- a/tinygrad_repo/test/models/test_rnnt.py +++ /dev/null @@ -1,47 +0,0 @@ -#!/usr/bin/env python -import unittest -import numpy as np -from tinygrad.tensor import Tensor -from models.rnnt import LSTM -import torch - -class TestRNNT(unittest.TestCase): - def test_lstm(self): - BS, SQ, IS, HS, L = 2, 20, 40, 128, 2 - - # create in torch - with torch.no_grad(): - torch_layer = torch.nn.LSTM(IS, HS, L) - - # create in tinygrad - layer = LSTM(IS, HS, L, 0.0) - - # copy weights - with torch.no_grad(): - layer.cells[0].weights_ih.assign(Tensor(torch_layer.weight_ih_l0.numpy())) - layer.cells[0].weights_hh.assign(Tensor(torch_layer.weight_hh_l0.numpy())) - layer.cells[0].bias_ih.assign(Tensor(torch_layer.bias_ih_l0.numpy())) - layer.cells[0].bias_hh.assign(Tensor(torch_layer.bias_hh_l0.numpy())) - layer.cells[1].weights_ih.assign(Tensor(torch_layer.weight_ih_l1.numpy())) - layer.cells[1].weights_hh.assign(Tensor(torch_layer.weight_hh_l1.numpy())) - layer.cells[1].bias_ih.assign(Tensor(torch_layer.bias_ih_l1.numpy())) - layer.cells[1].bias_hh.assign(Tensor(torch_layer.bias_hh_l1.numpy())) - - # test initial hidden - for _ in range(3): - x = Tensor.randn(SQ, BS, IS) - z, hc = layer(x, None) - torch_x = torch.tensor(x.numpy()) - torch_z, torch_hc = torch_layer(torch_x) - np.testing.assert_allclose(z.numpy(), torch_z.detach().numpy(), atol=5e-3, rtol=5e-3) - - # test passing hidden - for _ in range(3): - x = Tensor.randn(SQ, BS, IS) - z, hc = layer(x, hc) - torch_x = torch.tensor(x.numpy()) - torch_z, torch_hc = torch_layer(torch_x, torch_hc) - np.testing.assert_allclose(z.numpy(), torch_z.detach().numpy(), atol=5e-3, rtol=5e-3) - -if __name__ == '__main__': - unittest.main() diff --git a/tinygrad_repo/test/models/test_train.py b/tinygrad_repo/test/models/test_train.py deleted file mode 100644 index b987ee3..0000000 --- a/tinygrad_repo/test/models/test_train.py +++ /dev/null @@ -1,83 +0,0 @@ -import unittest -import time -import numpy as np -from tinygrad.nn.state import get_parameters -from tinygrad.nn import optim -from tinygrad.tensor import Device -from tinygrad.helpers import getenv -from extra.training import train -from models.convnext import ConvNeXt -from models.efficientnet import EfficientNet -from models.transformer import Transformer -from models.vit import ViT -from models.resnet import ResNet18 -import pytest - -pytestmark = [pytest.mark.exclude_gpu, pytest.mark.exclude_clang] - -BS = getenv("BS", 2) - -def train_one_step(model,X,Y): - params = get_parameters(model) - pcount = 0 - for p in params: - pcount += np.prod(p.shape) - optimizer = optim.SGD(params, lr=0.001) - print("stepping %r with %.1fM params bs %d" % (type(model), pcount/1e6, BS)) - st = time.time() - train(model, X, Y, optimizer, steps=1, BS=BS) - et = time.time()-st - print("done in %.2f ms" % (et*1000.)) - -def check_gc(): - if Device.DEFAULT == "GPU": - from extra.introspection import print_objects - assert print_objects() == 0 - -class TestTrain(unittest.TestCase): - def test_convnext(self): - model = ConvNeXt(depths=[1], dims=[16]) - X = np.zeros((BS,3,224,224), dtype=np.float32) - Y = np.zeros((BS), dtype=np.int32) - train_one_step(model,X,Y) - check_gc() - - def test_efficientnet(self): - model = EfficientNet(0) - X = np.zeros((BS,3,224,224), dtype=np.float32) - Y = np.zeros((BS), dtype=np.int32) - train_one_step(model,X,Y) - check_gc() - - @unittest.skipIf(Device.DEFAULT == "WEBGPU", "too many buffers for webgpu") - def test_vit(self): - model = ViT() - X = np.zeros((BS,3,224,224), dtype=np.float32) - Y = np.zeros((BS,), dtype=np.int32) - train_one_step(model,X,Y) - check_gc() - - def test_transformer(self): - # this should be small GPT-2, but the param count is wrong - # (real ff_dim is 768*4) - model = Transformer(syms=10, maxlen=6, layers=12, embed_dim=768, num_heads=12, ff_dim=768//4) - X = np.zeros((BS,6), dtype=np.float32) - Y = np.zeros((BS,6), dtype=np.int32) - train_one_step(model,X,Y) - check_gc() - - def test_resnet(self): - X = np.zeros((BS, 3, 224, 224), dtype=np.float32) - Y = np.zeros((BS), dtype=np.int32) - for resnet_v in [ResNet18]: - model = resnet_v() - model.load_from_pretrained() - train_one_step(model, X, Y) - check_gc() - - def test_bert(self): - # TODO: write this - pass - -if __name__ == '__main__': - unittest.main() diff --git a/tinygrad_repo/test/models/test_waifu2x.py b/tinygrad_repo/test/models/test_waifu2x.py deleted file mode 100644 index 0b34ae0..0000000 --- a/tinygrad_repo/test/models/test_waifu2x.py +++ /dev/null @@ -1,25 +0,0 @@ -#!/usr/bin/env python -import pathlib -import unittest -import numpy as np -from tinygrad.tensor import Tensor -from tinygrad.ops import Device - -class TestVGG7(unittest.TestCase): - def test_vgg7(self): - from examples.vgg7_helpers.waifu2x import Vgg7, image_load - - # Create in tinygrad - Tensor.manual_seed(1337) - mdl = Vgg7() - mdl.load_from_pretrained() - - # Scale up an image - test_x = image_load(pathlib.Path(__file__).parent / 'waifu2x/input.png') - test_y = image_load(pathlib.Path(__file__).parent / 'waifu2x/output.png') - scaled = mdl.forward_tiled(test_x, 156) - scaled = np.fmax(0, np.fmin(1, scaled)) - np.testing.assert_allclose(scaled, test_y, atol=5e-3, rtol=5e-3) - -if __name__ == '__main__': - unittest.main() diff --git a/tinygrad_repo/test/models/test_whisper.py b/tinygrad_repo/test/models/test_whisper.py deleted file mode 100644 index b68dea5..0000000 --- a/tinygrad_repo/test/models/test_whisper.py +++ /dev/null @@ -1,25 +0,0 @@ -import unittest -import pathlib -from tinygrad.ops import Device -from examples.whisper import init_whisper, transcribe_file - -@unittest.skipUnless(Device.DEFAULT == "METAL", "Some non-metal backends spend too long trying to allocate a 20GB array") -class TestWhisper(unittest.TestCase): - @classmethod - def setUpClass(cls): - model, enc = init_whisper("tiny.en") - cls.model = model - cls.enc = enc - - @classmethod - def tearDownClass(cls): - del cls.model - del cls.enc - - def test_transcribe_file(self): - # Audio generated with the command on MacOS: - # say "Could you please let me out of the box?" --file-format=WAVE --data-format=LEUI8@16000 -o test - # We use the WAVE type because it's easier to decode in CI test environments - filename = str(pathlib.Path(__file__).parent / "whisper/test.wav") - transcription = transcribe_file(self.model, self.enc, filename) - self.assertEqual("<|startoftranscript|><|notimestamps|> Could you please let me out of the box?<|endoftext|>", transcription) diff --git a/tinygrad_repo/test/models/waifu2x/input.png b/tinygrad_repo/test/models/waifu2x/input.png deleted file mode 100644 index 9ae415a..0000000 Binary files a/tinygrad_repo/test/models/waifu2x/input.png and /dev/null differ diff --git a/tinygrad_repo/test/models/waifu2x/output.png b/tinygrad_repo/test/models/waifu2x/output.png deleted file mode 100644 index b105a2e..0000000 Binary files a/tinygrad_repo/test/models/waifu2x/output.png and /dev/null differ diff --git a/tinygrad_repo/test/models/whisper/test.wav b/tinygrad_repo/test/models/whisper/test.wav deleted file mode 100644 index eb93898..0000000 Binary files a/tinygrad_repo/test/models/whisper/test.wav and /dev/null differ diff --git a/tinygrad_repo/test/test_allocators.py b/tinygrad_repo/test/test_allocators.py deleted file mode 100644 index 5fd91fc..0000000 --- a/tinygrad_repo/test/test_allocators.py +++ /dev/null @@ -1,136 +0,0 @@ -#!/usr/bin/env python -import unittest -import numpy as np -from weakref import ref -from tinygrad.helpers import GlobalCounters -from tinygrad.runtime.lib import RawBuffer, LRUAllocator -from tinygrad.helpers import dtypes, prod -from tinygrad.ops import Device -from tinygrad.tensor import Tensor - -def check_gc(): - if Device.DEFAULT == "GPU": - from extra.introspection import print_objects - assert print_objects() == 0 - -class FakeDeviceBuffer: - def __init__(self, sz, dt, device): - self.id = 1 - self.size = sz - self.dtype = dt - self.device = device - def __del__(self): - assert self.id == 0, "Should called _do_free() before" - -class FakeAllocator(LRUAllocator): - def _do_alloc(self, size, dtype, device, **kwargs): return FakeDeviceBuffer(size, dtype, device) - def _do_free(self, buf): - buf.id -= 1 - assert buf.id == 0, f"Free should be called once, but {buf.id}" - def __del__(self): # Fake allocator should clear all buffers after each test. - for v in self.cached_buffers.values(): - for buf, _ in v: self._free_buffer(buf) - -FAKE_GLOBAL_ALLOCATOR = None -class FakeBuffer(RawBuffer): - def __init__(self, size, dtype, device='0'): - global FAKE_GLOBAL_ALLOCATOR - super().__init__(size, dtype, allocator=FAKE_GLOBAL_ALLOCATOR, **{'device': device}) - assert self._buf.size == size and self._buf.dtype == dtype and self._buf.device == device, "This allocator requires 100% match of dtype and size." - @classmethod - def fromCPU(cls, x:np.ndarray, **kwargs): return cls(prod(x.shape), dtypes.from_np(x.dtype), **kwargs) - def toCPU(self): return np.empty(self.size, dtype=self.dtype.np) - -def alloc(allocator, size, dtype, **kwargs): - global FAKE_GLOBAL_ALLOCATOR - FAKE_GLOBAL_ALLOCATOR = allocator - buf = FakeBuffer(size, dtype, **kwargs) - assert buf.dtype == dtype and buf.size == size - FAKE_GLOBAL_ALLOCATOR = None - return buf - -def alloc_free_trace(allocator, size, dtype, **kwargs): - buf = alloc(allocator, size, dtype, **kwargs) - return ref(buf._buf) - -def cmp_trace_and_buf(buf, trace_ref): return trace_ref and trace_ref() == buf._buf - -class TestAllocators(unittest.TestCase): - def test_lru_allocator_reusage(self): - mc, mu = GlobalCounters.mem_cached, GlobalCounters.mem_used - def test(): - lru_allocator = FakeAllocator(2048) - traced_buf = alloc_free_trace(lru_allocator, 16, dtypes.float32) - assert GlobalCounters.mem_cached - mc == 16*dtypes.float32.itemsize, "Buffer should be cached" - for _ in range(32): - def __test(): - buf = alloc(lru_allocator, 16, dtypes.float32) - assert cmp_trace_and_buf(buf, traced_buf), "Buffer should be reused" - __test() - - usedbuf = alloc(lru_allocator, 16, dtypes.float32) - for _ in range(32): - def __test(): - buf = alloc(lru_allocator, 16, dtypes.float32) - assert usedbuf != buf, "Nobody should get used buffer" - __test() - assert GlobalCounters.mem_used - mu == 16*dtypes.float32.itemsize, "Only usedbuf is still allocated." - test() - check_gc() - - def test_lru_allocator_cache_free(self): - mc, mu = GlobalCounters.mem_cached, GlobalCounters.mem_used - def test(): - lru_allocator = FakeAllocator(128) - refs = [] - for _ in range(32): - refs.append(alloc_free_trace(lru_allocator, 16, dtypes.float32)) - for sz in range(1, 32): - alloc_free_trace(lru_allocator, sz, dtypes.float32) - assert GlobalCounters.mem_used + GlobalCounters.mem_cached - mc - mu <= 128, "Should not allocate on device more than allowed (128)" - for r in refs: assert r() is None, "All refs should be dead, since buffers were cleared from cache" - test() - check_gc() - - def test_lru_allocator_multidevice(self): - def test(): - lru_allocator = FakeAllocator(256) - refs=[] - for i in range(8): - refs.append(alloc_free_trace(lru_allocator, 16, dtypes.float32, device=str(i))) - for i in range(64): - def __test(): - dev = str(i % 8) - buf = alloc(lru_allocator, 16, dtypes.float32, device=dev) - assert cmp_trace_and_buf(buf, refs[i%8]), "Buffer should be reused" - __test() - for r in refs: assert r() is not None, "All refs should be cached" - test() - check_gc() - - @unittest.skip("failing in CI") - def test_gpu_copyout(self): - def test(): - from tinygrad.runtime.ops_gpu import CL - - # Allocation to init the allocator. - tx = Tensor.rand(1) - tx.realize() - free_space = CL.cl_allocator.free_space[tx.lazydata.realized._device] - - # Spawning 128mb objects to fill half of free_space - will_allocate = free_space // 3 - trash_allocation_size = free_space // 2 - - def sp(): - trash_buffer = Tensor.rand(trash_allocation_size // 4) - trash_buffer.realize() - sp() - - xx = Tensor.rand(will_allocate // 4) - _ = xx.numpy() - test() - check_gc() - -if __name__ == "__main__": - unittest.main() diff --git a/tinygrad_repo/test/test_assign.py b/tinygrad_repo/test/test_assign.py deleted file mode 100644 index 02b9521..0000000 --- a/tinygrad_repo/test/test_assign.py +++ /dev/null @@ -1,67 +0,0 @@ -#!/usr/bin/env python -import unittest -import numpy as np -from tinygrad.tensor import Tensor -from tinygrad.ops import Device -from tinygrad.helpers import dtypes - -N = 200 # has to be bigger than the cache to fail - -class TestAssign(unittest.TestCase): - def test_simple_assignment(self): - a = Tensor(np.arange(N*N, dtype=np.float32)).reshape(N,N) - b = Tensor(np.arange(N*N, dtype=np.float32)).reshape(N,N) - a.realize() - b.realize() - ba1 = a.lazydata.realized - bb1 = b.lazydata.realized - a += b - a.realize() - ba2 = a.lazydata.realized - assert ba1 == ba2 and ba1 != bb1 - np.testing.assert_allclose(a.numpy(), (np.arange(N*N)*2).reshape((N,N))) - - @unittest.skipIf(Device.DEFAULT == "CPU" or Device.DEFAULT == "TORCH", "questionable tests") - def test_permuted_assignment(self): - a = Tensor(np.arange(N*N, dtype=np.float32)).reshape(N,N) - b = Tensor(np.arange(N*N, dtype=np.float32)).reshape(N,N) - a.realize() - b.realize() - ba1 = a.lazydata.realized - bb1 = b.lazydata.realized - a = a.permute(1,0) - a += b - a.realize() - ba2 = a.lazydata.realized - assert ba1 != ba2 and ba1 != bb1 - np.testing.assert_allclose(a.numpy(), np.arange(N*N).reshape((N,N)) + np.arange(N*N).reshape((N,N)).transpose(1,0)) - - def test_post_permuted_assignment(self): - a = Tensor(np.arange(N*N, dtype=np.float32)).reshape(N,N) - b = Tensor(np.arange(N*N, dtype=np.float32)).reshape(N,N) - a.realize() - b.realize() - #GlobalCounters.cache = [] - ba1 = a.lazydata.realized - bb1 = b.lazydata.realized - a.assign(a.permute(1,0) + b) # this should not work! - a.realize() - ba2 = a.lazydata.realized - # NOTE: don't test that it's assigned - #assert ba1 == ba2 and ba1 != bb1 - np.testing.assert_allclose(a.numpy(), np.arange(N*N).reshape((N,N)) + np.arange(N*N).reshape((N,N)).transpose(1,0)) - - # TODO: is there a way to sneak in a permute such that it returns the wrong answer? - - def test_cast_assignment(self): - a = Tensor(np.arange(N*N, dtype=np.float32)).reshape(N,N) - a.realize() - oba1 = a.lazydata.output_buffer - a.assign(a.cast(dtypes.int32).realize()) - a.realize() - oba2 = a.lazydata.output_buffer - assert oba1 is None and oba2 is None - np.testing.assert_allclose(a.numpy(), np.arange(N*N,dtype=np.int32).reshape((N,N))) - -if __name__ == "__main__": - unittest.main() diff --git a/tinygrad_repo/test/test_conv.py b/tinygrad_repo/test/test_conv.py deleted file mode 100644 index 097da19..0000000 --- a/tinygrad_repo/test/test_conv.py +++ /dev/null @@ -1,147 +0,0 @@ -import unittest -import numpy as np -from tinygrad.tensor import Tensor, Device -import pytest - -pytestmark = [pytest.mark.exclude_cuda] - -class TestConv(unittest.TestCase): - def test_simple(self): - x = Tensor.ones(1,12,128,256).contiguous().realize() - w = Tensor.ones(32,12,3,3).contiguous().realize() - ret = x.conv2d(w, stride=(2,2), padding=(1,1)).numpy() - # it's not 108 around the padding - assert (ret[:, :, 1:-1, 1:-1] == 108).all() - assert ret[0,0,0,0] == 48 - assert ret[0,0,0,1] == 72 - - def test_simple_rand(self): - x = Tensor.rand(1,12,128,256) - w = Tensor.rand(32,12,3,3) - ret = x.conv2d(w, stride=(2,2), padding=(1,1)).numpy() - - def test_many_simple(self): - x = Tensor(np.arange(8*2*8).reshape(1,8,2,8).astype(np.float32)) - #w = Tensor(np.arange(8*8*1*1).reshape(8,8,1,1).astype(np.float32)) - w = Tensor.eye(8).reshape((8,8,1,1)) - ret = x.conv2d(w, stride=(1,2), padding=(0,0)).numpy() - print(ret) - - def test_lazycache(self): - Tensor.no_grad = True - x = Tensor.rand(1, 32) - y = Tensor.rand(32) - out = x + y.reshape((1,32,1)).reshape((1,32)) + y.reshape((1,32,1)).reshape((1,32)) - out.numpy() - Tensor.no_grad = False - - def test_simple_biased(self): - C = 8 - x = Tensor.rand(1,C,5,5) - w = Tensor.eye(C).reshape((C,C,1,1)) - b = Tensor(np.arange(C).astype(np.float32)) - ret = Tensor.conv2d(x,w,b).relu().conv2d(w,b) - - print(ret.numpy()) - - def test_two_binops_no_rerun(self): - Tensor.no_grad = True - x = Tensor.randn(1,12,128,256) - w = Tensor.randn(32,12,3,3) - out = x.conv2d(w, stride=(2,2), padding=(1,1)) - r1, r2 = out.relu(), (out-1) - np.testing.assert_allclose(r1.numpy(), np.maximum(out.numpy(), 0)) - np.testing.assert_allclose(r2.numpy(), out.numpy() - 1) - Tensor.no_grad = False - - def test_two_overlapping_binops_no_rerun(self): - Tensor.no_grad = True - x = Tensor.randn(1,12,128,256) - w = Tensor.randn(32,12,3,3) - out = x.conv2d(w, stride=(2,2), padding=(1,1)) - r1, r2 = out.relu(), out.elu() - np.testing.assert_allclose(r1.numpy(), np.maximum(out.numpy(), 0)) - np.testing.assert_allclose(r2.numpy(), np.where(out.numpy() > 0, out.numpy(), (np.exp(out.numpy()) - 1)), atol=1e-5) - Tensor.no_grad = False - - @unittest.skipIf(Device.DEFAULT != "TORCH", "Takes too long to compile for Compiled backends") - def test_two_overlapping_binops_no_rerun_wino(self): - Tensor.no_grad = True - old_wino = Tensor.wino - Tensor.wino = True - x = Tensor.randn(1,4,16,16) - w = Tensor.randn(6,4,3,3) - out = x.conv2d(w, padding=(1,1)) - r1, r2 = out.relu(), out.elu() - np.testing.assert_allclose(r1.numpy(), np.maximum(out.numpy(), 0)) - np.testing.assert_allclose(r2.numpy(), np.where(out.numpy() > 0, out.numpy(), (np.exp(out.numpy()) - 1)), atol=1e-5) - Tensor.wino = old_wino - Tensor.no_grad = False - - def test_first_three(self): - Tensor.no_grad = True - x = Tensor.rand(1,12,128,256) - - w = Tensor.rand(32,12,3,3) - x = x.conv2d(w, stride=(2,2), padding=(1,1)).elu() - - w = Tensor.rand(32,1,3,3) - x = x.conv2d(w, padding=(1,1), groups=32).elu() - - w = Tensor.rand(16,32,1,1) - x = x.conv2d(w).elu() - - x = x.numpy() - print(x.shape) - Tensor.no_grad = False - - def test_elu(self): - Tensor.no_grad = True - x = Tensor.rand(1,12,128,256) - - w = Tensor.rand(32,12,3,3) - x = x.conv2d(w, stride=(2,2), padding=(1,1)) - - x = x.elu() - - w = Tensor.rand(32,1,3,3) - x = x.conv2d(w, padding=(1,1), groups=32) - out = x.numpy() - Tensor.no_grad = False - - def test_reduce_relu(self): - Tensor.no_grad = True - x = Tensor.rand(1,12,128,256) - x = x.sum(keepdim=True).relu() - out = x.numpy() - Tensor.no_grad = False - - def test_bias(self): - Tensor.no_grad = True - from tinygrad.nn import Conv2d - x = Tensor.rand(1,12,128,256) - c = Conv2d(12, 32, 3) - x = c(x).relu() - w = Tensor.uniform(32, 1, 3, 3) - x = x.conv2d(w, groups=32) - out = x.numpy() - Tensor.no_grad = False - - def test_multiadd(self): - w = Tensor.rand(32) - x = Tensor.rand(32).relu() - (w+x).numpy() - - def test_reorder(self): - x = Tensor.rand(1,12,128,256) - w = Tensor.rand(12,12,3,3) - x = x.conv2d(w, padding=(1,1)) - print(x.shape) - x = x.reshape((1, 12, 256, 128)) - x += 1 - x += 1 - x = x.reshape((1, 12, 128, 256)) - x.numpy() - -if __name__ == '__main__': - unittest.main() \ No newline at end of file diff --git a/tinygrad_repo/test/test_conv_shapetracker.py b/tinygrad_repo/test/test_conv_shapetracker.py deleted file mode 100644 index 9a4642f..0000000 --- a/tinygrad_repo/test/test_conv_shapetracker.py +++ /dev/null @@ -1,27 +0,0 @@ -#!/usr/bin/env python -import unittest -from tinygrad.tensor import Tensor, Device -from tinygrad.nn import Conv2d -from tinygrad.jit import CacheCollector -import pytest - -pytestmark = pytest.mark.webgpu - -#@unittest.skipUnless(Device.DEFAULT == "GPU", "Only GPU supports cache") -@unittest.skip("with JIT changes, you only get the raw buffer") -class TestConvShapetracker(unittest.TestCase): - def test_conv_3x3_one_view(self): - inp = Tensor.randn(1,16,10,10).realize() - conv = Conv2d(16, 32, (3,3)) - conv(inp).realize() - CacheCollector.start() - conv(inp).realize() - test = CacheCollector.finish() - assert len(test) == 1, f"conv should only have one kernel {[x[0].name for x in test]}" - print(test[0][0].prg) - for arg in test[0][1]: - print(arg.st) - assert len(arg.st.views) == 1 - -if __name__ == '__main__': - unittest.main() diff --git a/tinygrad_repo/test/test_custom_function.py b/tinygrad_repo/test/test_custom_function.py deleted file mode 100644 index 7d4cca0..0000000 --- a/tinygrad_repo/test/test_custom_function.py +++ /dev/null @@ -1,107 +0,0 @@ -# this is an example of how you can write terrible DSP compute breaking ops like warpPerspective -# here we use a CUSTOM op to write atan2 - -import unittest -import numpy as np -from typing import Optional, Tuple -from tinygrad.helpers import prod, dtypes - -# *** first, we implement the atan2 op at the lowest level *** -# `atan2_gpu` for GPUBuffers and `atan2_cpu` for CPUBuffers -from tinygrad.lazy import LazyBuffer, create_lazybuffer -from tinygrad.ops import ASTRunner, Device -from tinygrad.shape.shapetracker import ShapeTracker -import pytest - -pytestmark = pytest.mark.webgpu - -# we don't always have GPU support, so the type signature is the abstract CompiledBuffer instead of GPUBuffer -def atan2_gpu(ret:LazyBuffer, a:LazyBuffer, b:LazyBuffer): - assert a.device == "GPU" and b.device == "GPU", "gpu function requires GPUBuffers" - assert a.dtype == b.dtype and a.dtype == dtypes.float32, "gpu function only supports float32" - ret.realized = Device[ret.device].buffer(prod(ret.shape), ret.dtype) - ASTRunner("atan2_gpu", """ - __kernel void atan2_gpu(global float *c, global float *a, global float *b) { - int idx = get_global_id(0); - c[idx] = atan2(a[idx], b[idx]); - }""", global_size=[prod(ret.shape)]).build(Device[ret.device].compiler, Device[ret.device].runtime).exec([ret.realized, a.realized, b.realized]) - return ret.realized - -def atan2_cpu(ret:LazyBuffer, a:LazyBuffer, b:LazyBuffer): - return Device[ret.device].from_underlying(np.arctan2(a.realized._buf, b.realized._buf)) - -# *** second, we write the ATan2 mlop *** -# NOTE: The derivative of atan2 doesn't need a custom op! https://www.liquisearch.com/atan2/derivative -# In general, it is also optional to write a backward function, just your backward pass won't work without it - -from tinygrad.ops import LazyOp, LoadOps, BinaryOps, UnaryOps -from tinygrad.lazy import LazyBuffer -from tinygrad.tensor import Function - -class ATan2(Function): - def forward(self, a:LazyBuffer, b:LazyBuffer) -> LazyBuffer: - assert prod(a.shape) == prod(b.shape) and a.device == b.device, "shape or device mismatch" - self.a, self.b = a, b - ast = LazyOp(LoadOps.CUSTOM, (a.contiguous(), b.contiguous()), {"GPU": atan2_gpu, "CPU": atan2_cpu}[a.device]) - return create_lazybuffer(a.device, ShapeTracker.from_shape(a.shape), LoadOps, ast, max(a.dtype, b.dtype)) - def backward(self, grad_output:LazyBuffer) -> Tuple[Optional[LazyBuffer], Optional[LazyBuffer]]: - denom = (self.a.e(BinaryOps.MUL, self.a)).e(BinaryOps.ADD, self.b.e(BinaryOps.MUL, self.b)) - return grad_output.e(BinaryOps.MUL, self.b.e(BinaryOps.DIV, denom)) if self.needs_input_grad[0] else None, \ - grad_output.e(BinaryOps.MUL, self.a.const(0).e(BinaryOps.SUB, self.a).e(BinaryOps.DIV, denom)) if self.needs_input_grad[1] else None - -# *** third, we use our lovely new mlop in some tests *** - -from tinygrad.tensor import Tensor - -@unittest.skipUnless(Device.DEFAULT in ["CPU", "GPU"], "atan2 is only implemented for CPU and GPU") -class TestCustomFunction(unittest.TestCase): - def test_atan2_forward(self): - # create some random Tensors, permute them just because we can - a = Tensor.randn(4,4,requires_grad=True).permute(1,0) - b = Tensor.randn(4,4,requires_grad=True).permute(1,0) - - # run the forward pass. note: up until the .numpy(), it's all lazy - c = ATan2.apply(a, b) - print(c.numpy()) - - # check the forward pass (in numpy) - np.testing.assert_allclose(c.numpy(), np.arctan2(a.numpy(), b.numpy()), atol=1e-5) - - # fun fact, this never actually calls forward, so it works in all the backends - def test_atan2_backward(self): - # have to go forward before we can go backward - a = Tensor.randn(4,4,requires_grad=True).permute(1,0) - b = Tensor.randn(4,4,requires_grad=True).permute(1,0) - c = ATan2.apply(a, b) - - # run the backward pass - c.mean().backward() - assert a.grad is not None and b.grad is not None, "tinygrad didn't compute gradients" - print(a.grad.numpy()) - print(b.grad.numpy()) - - # check the backward pass (in torch) - import torch - ta, tb = torch.tensor(a.numpy(), requires_grad=True), torch.tensor(b.numpy(), requires_grad=True) - tc = torch.atan2(ta, tb) - tc.mean().backward() - assert ta.grad is not None and tb.grad is not None, "torch didn't compute gradients" - np.testing.assert_allclose(a.grad.numpy(), ta.grad.numpy(), atol=1e-5) - np.testing.assert_allclose(b.grad.numpy(), tb.grad.numpy(), atol=1e-5) - - def test_atan2_jit(self): - # custom ops even work in the JIT! - from tinygrad.jit import TinyJit - - @TinyJit - def jitted_atan2(a:Tensor, b:Tensor) -> Tensor: - return ATan2.apply(a, b).realize() - - for _ in range(5): - a = Tensor.randn(4,4,requires_grad=True).permute(1,0) - b = Tensor.randn(4,4,requires_grad=True).permute(1,0) - c = jitted_atan2(a, b) - np.testing.assert_allclose(c.numpy(), np.arctan2(a.numpy(), b.numpy()), atol=1e-5) - -if __name__ == "__main__": - unittest.main() diff --git a/tinygrad_repo/test/test_dtype.py b/tinygrad_repo/test/test_dtype.py deleted file mode 100644 index 8b55153..0000000 --- a/tinygrad_repo/test/test_dtype.py +++ /dev/null @@ -1,182 +0,0 @@ -import unittest -import numpy as np -from tinygrad.helpers import CI, DTYPES_DICT, getenv, DType, DEBUG, ImageDType, PtrDType -from tinygrad.ops import Device -from tinygrad.tensor import Tensor, dtypes -from typing import Any, List -from extra.utils import OSX, temp - -def is_dtype_supported(dtype: DType): - # for GPU, cl_khr_fp16 isn't supported (except now we don't need it!) - # for LLVM, it segfaults because it can't link to the casting function - if dtype == dtypes.half: return not (CI and Device.DEFAULT in ["GPU", "LLVM"]) and Device.DEFAULT != "WEBGPU" and getenv("CUDACPU") != 1 - if dtype == dtypes.bfloat16: return False # numpy doesn't support bf16, tested separately in TestBFloat16DType - if dtype == dtypes.float64: return Device.DEFAULT not in ["WEBGPU", "METAL"] and not OSX - if dtype in [dtypes.int8, dtypes.uint8]: return Device.DEFAULT not in ["WEBGPU"] - if dtype in [dtypes.int16, dtypes.uint16]: return Device.DEFAULT not in ["WEBGPU", "TORCH"] - if dtype == dtypes.uint32: return Device.DEFAULT not in ["TORCH"] - if dtype in [dtypes.int64, dtypes.uint64]: return Device.DEFAULT not in ["WEBGPU", "TORCH"] - if dtype == dtypes.bool: - # host-shareablity is a requirement for storage buffers, but 'bool' type is not host-shareable - if Device.DEFAULT == "WEBGPU": return False - # TODO remove triton from here once internal casting is fixed. CAST of fp32s between 0-1 is broken in triton - if getenv("TRITON") == 1: return False - return True - -def get_available_cast_dtypes(dtype: DType) -> List[DType]: return [v for k, v in DTYPES_DICT.items() if v != dtype and is_dtype_supported(v) and not k.startswith("_")] # dont cast internal dtypes - -def _test_to_np(a:Tensor, np_dtype, target): - if DEBUG >= 2: print(a) - na = a.numpy() - if DEBUG >= 2: print(na, na.dtype, a.lazydata.realized) - try: - assert na.dtype == np_dtype - np.testing.assert_allclose(na, target) - except AssertionError as e: - raise AssertionError(f"\ntensor {a.numpy()} does not match target {target} with np_dtype {np_dtype}") from e - -def _assert_eq(tensor:Tensor, target_dtype:DType, target): - if DEBUG >= 2: print(tensor.numpy()) - try: - assert tensor.dtype == target_dtype - np.testing.assert_allclose(tensor.numpy(), target) - except AssertionError as e: - raise AssertionError(f"\ntensor {tensor.numpy()} dtype {tensor.dtype} does not match target {target} with dtype {target_dtype}") from e - -def _test_op(fxn, target_dtype:DType, target): _assert_eq(fxn(), target_dtype, target) -def _test_cast(a:Tensor, target_dtype:DType): _test_op(lambda: a.cast(target_dtype), target_dtype, a.numpy().astype(target_dtype.np).tolist()) -def _test_bitcast(a:Tensor, target_dtype:DType, target): _test_op(lambda: a.bitcast(target_dtype), target_dtype, target) - -class TestDType(unittest.TestCase): - DTYPE: Any = None - DATA: Any = None - @classmethod - def setUpClass(cls): - if not is_dtype_supported(cls.DTYPE): raise unittest.SkipTest("dtype not supported") - cls.DATA = np.random.randint(0, 100, size=10, dtype=cls.DTYPE.np).tolist() if dtypes.is_int(cls.DTYPE) else np.random.choice([True, False], size=10).tolist() if cls.DTYPE == dtypes.bool else np.random.uniform(0, 1, size=10).tolist() - def setUp(self): - if self.DTYPE is None: raise unittest.SkipTest("base class") - - def test_to_np(self): _test_to_np(Tensor(self.DATA, dtype=self.DTYPE), self.DTYPE.np, np.array(self.DATA, dtype=self.DTYPE.np)) - - def test_casts_to(self): list(map( - lambda dtype: _test_cast(Tensor(self.DATA, dtype=dtype), self.DTYPE), - get_available_cast_dtypes(self.DTYPE) - )) - def test_casts_from(self): list(map( - lambda dtype: _test_cast(Tensor(self.DATA, dtype=self.DTYPE), dtype), - get_available_cast_dtypes(self.DTYPE) - )) - - def test_upcast_ops(self): list(map( - lambda dtype: _test_ops(a_dtype=self.DTYPE, b_dtype=dtype, target_dtype=dtype) if dtype.sz > self.DTYPE.sz else None, - get_available_cast_dtypes(self.DTYPE) - )) - def test_upcast_to_ops(self): list(map( - lambda dtype: _test_ops(a_dtype=dtype, b_dtype=self.DTYPE, target_dtype=self.DTYPE) if dtype.sz < self.DTYPE.sz else None, - get_available_cast_dtypes(self.DTYPE) - )) - -def _test_ops(a_dtype:DType, b_dtype:DType, target_dtype:DType): - if not is_dtype_supported(a_dtype) or not is_dtype_supported(b_dtype): raise unittest.SkipTest("dtype not supported") - _assert_eq(Tensor([1,2,3,4], dtype=a_dtype)+Tensor([1,2,3,4], dtype=b_dtype), target_dtype, [2,4,6,8]) - _assert_eq(Tensor([1,2,3,4], dtype=a_dtype)*Tensor([1,2,3,4], dtype=b_dtype), target_dtype, [1,4,9,16]) - _assert_eq(Tensor([[1,2],[3,4]], dtype=a_dtype)@Tensor.eye(2, dtype=b_dtype), target_dtype, [[1,2],[3,4]]) - _assert_eq(Tensor([1,1,1,1], dtype=a_dtype)+Tensor.ones((4,4), dtype=b_dtype), target_dtype, 2*Tensor.ones(4,4).numpy()) - -class TestBFloat16DType(unittest.TestCase): - def setUp(self): - if not is_dtype_supported(dtypes.bfloat16): raise unittest.SkipTest("bfloat16 not supported") - def test_bf16_to_float(self): - with self.assertRaises(AssertionError): - _test_cast(Tensor([100000], dtype=dtypes.bfloat16), dtypes.float32, [100000]) - - def test_float_to_bf16(self): - with self.assertRaises(AssertionError): - _test_cast(Tensor([100000], dtype=dtypes.float32), dtypes.bfloat16, [100000]) - - # torch.tensor([10000, -1, -1000, -10000, 20]).type(torch.bfloat16) - - def test_bf16(self): - t = Tensor([10000, -1, -1000, -10000, 20]).cast(dtypes.bfloat16) - t.realize() - back = t.cast(dtypes.float32) - assert tuple(back.numpy().tolist()) == (9984., -1, -1000, -9984, 20) - - def test_bf16_disk_write_read(self): - t = Tensor([10000, -1, -1000, -10000, 20]).cast(dtypes.float32) - t.to(f"disk:{temp('f32')}").realize() - - # hack to "cast" f32 -> bf16 - dat = open(temp('f32'), "rb").read() - adat = b''.join([dat[i+2:i+4] for i in range(0, len(dat), 4)]) - with open(temp('bf16'), "wb") as f: f.write(adat) - - t = Tensor.empty(5, dtype=dtypes.bfloat16, device=f"disk:{temp('bf16')}").llvm().realize() - back = t.cast(dtypes.float32) - assert tuple(back.numpy().tolist()) == (9984., -1, -1000, -9984, 20) - -class TestHalfDtype(TestDType): DTYPE = dtypes.half - -class TestFloatDType(TestDType): DTYPE = dtypes.float - -class TestDoubleDtype(TestDType): DTYPE = dtypes.double - -class TestInt8Dtype(TestDType): - DTYPE = dtypes.int8 - @unittest.skipIf(getenv("CUDA",0)==1 or getenv("PTX", 0)==1, "cuda saturation works differently") - def test_int8_to_uint8_negative(self): _test_op(lambda: Tensor([-1, -2, -3, -4], dtype=dtypes.int8).cast(dtypes.uint8), dtypes.uint8, [255, 254, 253, 252]) - -class TestUint8Dtype(TestDType): - DTYPE = dtypes.uint8 - @unittest.skipIf(getenv("CUDA",0)==1 or getenv("PTX", 0)==1, "cuda saturation works differently") - def test_uint8_to_int8_overflow(self): _test_op(lambda: Tensor([255, 254, 253, 252], dtype=dtypes.uint8).cast(dtypes.int8), dtypes.int8, [-1, -2, -3, -4]) - -@unittest.skipIf(Device.DEFAULT not in {"CPU", "TORCH"}, "only bitcast in CPU and TORCH") -class TestBitCast(unittest.TestCase): - def test_float32_bitcast_to_int32(self): _test_bitcast(Tensor([1,2,3,4], dtype=dtypes.float32), dtypes.int32, [1065353216, 1073741824, 1077936128, 1082130432]) - @unittest.skipIf(Device.DEFAULT == "TORCH", "no uint32 in torch") - def test_float32_bitcast_to_uint32(self): _test_bitcast(Tensor([1,2,3,4], dtype=dtypes.float32), dtypes.uint32, [1065353216, 1073741824, 1077936128, 1082130432]) - def test_int32_bitcast_to_float32(self): _test_bitcast(Tensor([1065353216, 1073741824, 1077936128, 1082130432], dtype=dtypes.int32), dtypes.float32, [1.0, 2.0, 3.0, 4.0]) - - # NOTE: these are the same as normal casts - def test_int8_bitcast_to_uint8(self): _test_bitcast(Tensor([-1, -2, -3, -4], dtype=dtypes.int8), dtypes.uint8, [255, 254, 253, 252]) - def test_uint8_bitcast_to_int8(self): _test_bitcast(Tensor([255, 254, 253, 252], dtype=dtypes.uint8), dtypes.int8, [-1, -2, -3, -4]) - @unittest.skipIf(Device.DEFAULT == "TORCH", "no uint64 in torch") - def test_int64_bitcast_to_uint64(self): _test_bitcast(Tensor([-1, -2, -3, -4], dtype=dtypes.int64), dtypes.uint64, [18446744073709551615, 18446744073709551614, 18446744073709551613, 18446744073709551612]) - @unittest.skipIf(Device.DEFAULT == "TORCH", "no uint64 in torch") - def test_uint64_bitcast_to_int64(self): _test_bitcast(Tensor([18446744073709551615, 18446744073709551614, 18446744073709551613, 18446744073709551612], dtype=dtypes.uint64), dtypes.int64, [-1, -2, -3, -4]) - - def test_shape_change_bitcast(self): - with self.assertRaises(AssertionError): - _test_bitcast(Tensor([100000], dtype=dtypes.float32), dtypes.uint8, [100000]) - -class TestInt16Dtype(TestDType): DTYPE = dtypes.int16 -class TestUint16Dtype(TestDType): DTYPE = dtypes.uint16 - -class TestInt32Dtype(TestDType): DTYPE = dtypes.int32 -class TestUint32Dtype(TestDType): DTYPE = dtypes.uint32 - -class TestInt64Dtype(TestDType): DTYPE = dtypes.int64 -class TestUint64Dtype(TestDType): DTYPE = dtypes.uint64 - -class TestBoolDtype(TestDType): DTYPE = dtypes.bool - -class TestEqStrDType(unittest.TestCase): - def test_image_ne(self): - assert dtypes.float == dtypes.float32, "float doesn't match?" - assert dtypes.imagef((1,2,4)) != dtypes.imageh((1,2,4)), "different image dtype doesn't match" - assert dtypes.imageh((1,2,4)) != dtypes.imageh((1,4,2)), "different shape doesn't match" - assert dtypes.imageh((1,2,4)) == dtypes.imageh((1,2,4)), "same shape matches" - assert isinstance(dtypes.imageh((1,2,4)), ImageDType) - def test_ptr_ne(self): - # TODO: is this the wrong behavior? - assert PtrDType(dtypes.float32) == dtypes.float32 - #assert PtrDType(dtypes.float32) == PtrDType(dtypes.float32) - #assert PtrDType(dtypes.float32) != dtypes.float32 - def test_strs(self): - self.assertEqual(str(dtypes.imagef((1,2,4))), "dtypes.imagef((1, 2, 4))") - self.assertEqual(str(PtrDType(dtypes.float32)), "ptr.dtypes.float") - -if __name__ == '__main__': - unittest.main() diff --git a/tinygrad_repo/test/test_gc.py b/tinygrad_repo/test/test_gc.py deleted file mode 100644 index 49773dd..0000000 --- a/tinygrad_repo/test/test_gc.py +++ /dev/null @@ -1,37 +0,0 @@ -#!/usr/bin/env python -import gc -import unittest -import numpy as np -from tinygrad.tensor import Tensor - -def tensors_allocated(): - return sum([isinstance(x, Tensor) for x in gc.get_objects()]) - -class TestGC(unittest.TestCase): - - def test_gc(self): - a = Tensor.zeros(4, 4, requires_grad=True) - b = Tensor.zeros(4, 4, requires_grad=True) - (a*b).mean().backward() - assert(tensors_allocated() > 0) - del a,b - assert(tensors_allocated() == 0) - - def test_gc_complex(self): - a = Tensor(np.zeros((4, 4), dtype=np.float32), requires_grad=True) - b = Tensor(np.zeros((4, 4), dtype=np.float32), requires_grad=True) - assert(tensors_allocated() == 2) - (a*b).mean().backward() - assert(tensors_allocated() == 4) - del b - assert(tensors_allocated() == 2) - b = Tensor(np.zeros((4, 4), dtype=np.float32), requires_grad=True) - print(tensors_allocated()) - (a*b).mean().backward() - print(tensors_allocated()) - assert(tensors_allocated() == 4) - del b - assert(tensors_allocated() == 2) - -if __name__ == '__main__': - unittest.main() diff --git a/tinygrad_repo/test/test_jit.py b/tinygrad_repo/test/test_jit.py deleted file mode 100644 index bb2bafe..0000000 --- a/tinygrad_repo/test/test_jit.py +++ /dev/null @@ -1,194 +0,0 @@ -#!/usr/bin/env python -import unittest -import numpy as np -from tinygrad.tensor import Tensor, Device -from tinygrad.jit import TinyJit, JIT_SUPPORTED_DEVICE -import pytest - -pytestmark = pytest.mark.webgpu - -# NOTE: METAL fails, might be platform and optimization options dependent. -@unittest.skipUnless(Device.DEFAULT in JIT_SUPPORTED_DEVICE and Device.DEFAULT not in ["METAL", "WEBGPU"], f"no JIT on {Device.DEFAULT}") -class TestJit(unittest.TestCase): - def test_simple_jit(self): - @TinyJit - def add(a, b): return (a+b).realize() - for _ in range(5): - a = Tensor.randn(10, 10) - b = Tensor.randn(10, 10) - c = add(a, b) - np.testing.assert_allclose(c.numpy(), a.numpy()+b.numpy(), atol=1e-4, rtol=1e-5) - assert len(add.jit_cache) == 1 - - def test_jit_multiple_outputs(self): - @TinyJit - def f(a, b): return (a+b).realize(), (a-b).realize(), (a*b).realize() - for _ in range(5): - a = Tensor.randn(10, 10) - b = Tensor.randn(10, 10) - c, d, e = f(a, b) - np.testing.assert_allclose(c.numpy(), a.numpy()+b.numpy(), atol=1e-4, rtol=1e-5) - np.testing.assert_allclose(d.numpy(), a.numpy()-b.numpy(), atol=1e-4, rtol=1e-5) - np.testing.assert_allclose(e.numpy(), a.numpy()*b.numpy(), atol=1e-4, rtol=1e-5) - assert len(f.jit_cache) == 3 - - def test_nothing_jitted(self): - @TinyJit - def add(a, b): return a+b - with self.assertRaises(AssertionError): - for _ in range(5): - a = Tensor.randn(10, 10) - b = Tensor.randn(10, 10) - c = add(a, b) - - def test_jit_shape_mismatch(self): - @TinyJit - def add(a, b): return (a+b).realize() - for _ in range(5): - a = Tensor.randn(10, 10) - b = Tensor.randn(10, 10) - c = add(a, b) - bad = Tensor.randn(20, 20) - with self.assertRaises(AssertionError): - add(a, bad) - - def test_jit_shape_views_mismatch(self): - @TinyJit - def add(a): return (a+1).realize() - with self.assertRaises(AssertionError): - for i in range(1,5): - # a has an offset that the kernel doesn't know about - a = Tensor.randn(10, 10).realize()[:, i:i+2] - add(a) - - def test_jit_duplicate_fail(self): - # the jit doesn't support duplicate arguments - @TinyJit - def add(a, b): return (a+b).realize() - a = Tensor.randn(10, 10) - with self.assertRaises(AssertionError): - add(a, a) - - def test_kwargs_jit(self): - @TinyJit - def add_kwargs(first, second): return (first+second).realize() - for _ in range(5): - a = Tensor.randn(10, 10) - b = Tensor.randn(10, 10) - c = add_kwargs(first=a, second=b) - np.testing.assert_allclose(c.numpy(), a.numpy()+b.numpy(), atol=1e-4, rtol=1e-5) - assert len(add_kwargs.jit_cache) == 1 - - def test_array_jit(self): - @TinyJit - def add_array(a, arr): return (a+arr[0]).realize() - for i in range(5): - a = Tensor.randn(10, 10) - b = Tensor.randn(10, 10) - a.realize(), b.realize() - c = add_array(a, [b]) - if i >= 2: - # should fail once jitted since jit can't handle arrays - np.testing.assert_allclose(np.any(np.not_equal(c.numpy(),a.numpy()+b.numpy())), True, atol=1e-4, rtol=1e-5) - else: - np.testing.assert_allclose(c.numpy(), a.numpy()+b.numpy(), atol=1e-4, rtol=1e-5) - assert len(add_array.jit_cache) == 1 - - def test_method_jit(self): - class Fun: - def __init__(self): - self.a = Tensor.randn(10, 10) - @TinyJit - def __call__(self, b:Tensor) -> Tensor: - return (self.a+b).realize() - fun = Fun() - for _ in range(5): - b = Tensor.randn(10, 10) - c = fun(b) - np.testing.assert_allclose(c.numpy(), fun.a.numpy()+b.numpy(), atol=1e-4, rtol=1e-5) - assert len(fun.__call__.func.__self__.jit_cache) == 1 - - def test_jit_size1_input(self): - @TinyJit - def f(a, b): return (a+b).realize() - a = Tensor([1, 2, 3]) - for i in range(5): - np.testing.assert_allclose(f(a, Tensor([i])).numpy(), (a+i).numpy(), atol=1e-4, rtol=1e-5) - assert len(f.jit_cache) == 1 - - def test_jit_output_non_tensor_fail(self): - @TinyJit - def f(a, b, i): return (a+b).realize(), i - output1, output2 = [], [] - expect1, expect2 = [], [] - for i in range(5): - a = Tensor.randn(10, 10) - b = Tensor.randn(10, 10) - o1, o2 = f(a, b, i) - output1.append(o1.numpy().copy()) - output2.append(o2) - expect1.append(a.numpy().copy()+b.numpy().copy()) - expect2.append(i) - np.testing.assert_allclose(output1, expect1, atol=1e-4, rtol=1e-5) - # the jit only works with Tensor outputs - assert output2 != expect2 - assert len(f.jit_cache) == 1 - - @unittest.skip("random isn't working in JIT") - def test_jit_random_regen(self): - def f(a, b): - rn = Tensor.randn(*a.shape) - return ((a+b)*rn).realize() - a = Tensor.randn(10, 10) - b = Tensor.randn(10, 10) - - Tensor._seed = 1234 - jf = TinyJit(f) - res = set() - for _ in range(5): - o1 = jf(a, b) - res.add(o1.numpy()[0][0]) - assert len(res) == 5, "All values should be different, rand works in jit." - - Tensor._seed = 1234 - jf2 = TinyJit(f) - res2 = set() - for _ in range(5): - o1 = jf2(a, b) - res2.add(o1.numpy()[0][0]) - assert len(res2) == 5, "All values should be different, rand works in jit." - assert res == res2, "Jit rand is not reproducible with the same seed" - - Tensor._seed = 3421 - jf3 = TinyJit(f) - res3 = set() - for _ in range(5): - o1 = jf3(a, b) - res3.add(o1.numpy()[0][0]) - assert len(res3) == 5, "All values should be different, rand works in jit." - assert res3 != res2, "Jit rand is diff with diff seeds" - - def test_jit_realization_and_sampling(self): - w = Tensor.eye(5) - - @TinyJit - def foo (x): return w.dot(x).realize() - - arg = [ - Tensor([1,2,3,4,5]), - Tensor([1,3,3,4,6]), - Tensor([1,2,5,4,7]), - Tensor([0,2,3,1,0]), - ] - - Y = [foo(e).numpy() for e in arg] - - foo(Tensor([7,7,7,7,7])) - want = [[1., 2., 3., 4., 5.], - [1., 3., 3., 4., 6.], - [1., 2., 5., 4., 7.], - [0., 2., 3., 1., 0.]] - np.testing.assert_allclose(want, Y) - -if __name__ == '__main__': - unittest.main() \ No newline at end of file diff --git a/tinygrad_repo/test/test_kernel_cache.py b/tinygrad_repo/test/test_kernel_cache.py deleted file mode 100644 index 82a38f5..0000000 --- a/tinygrad_repo/test/test_kernel_cache.py +++ /dev/null @@ -1,54 +0,0 @@ -#!/usr/bin/env python -import unittest -import secrets -import string -from tinygrad.tensor import Tensor -from tinygrad.ops import Device -from tinygrad.helpers import diskcache - -def generate_random_string(length=16): - alphabet = string.ascii_letters + string.digits - return ''.join(secrets.choice(alphabet) for _ in range(length)) - -compile_call_count = 0 - -@diskcache -def helper_test_compile(prg:str) -> bytes: - global compile_call_count - compile_call_count += 1 - return prg.encode() - -class TestKernelCache(unittest.TestCase): - def test_compile_cache(self): - prg1 = generate_random_string(64) + "a" - prg2 = generate_random_string(64) + "b" - cold_compile_res = helper_test_compile(prg1) - warm_compile_res = helper_test_compile(prg1) - assert cold_compile_res == warm_compile_res == prg1.encode() - assert compile_call_count == 1 - - prg2_res = helper_test_compile(prg2) - assert prg2_res == prg2.encode() - assert compile_call_count == 2 - - def test_kernel_cache_in_action(self): - if Device.DEFAULT not in ["CLANG"]: - self.skipTest("No custom kernel cache is implemented") - - a = Tensor.rand(4,4) - b = Tensor.rand(4,4) - x = a + b - x.realize() - - orig_compile_func = Device['CLANG'].compiler - Device['CLANG'].compiler = None # making it not callable - - a1 = Tensor.rand(4,4) - b1 = Tensor.rand(4,4) - x1 = a1 + b1 - x1.realize() # Same kernel should be from cache. - - Device['CLANG'].compiler = orig_compile_func - -if __name__ == "__main__": - unittest.main() diff --git a/tinygrad_repo/test/test_lazybuffer.py b/tinygrad_repo/test/test_lazybuffer.py deleted file mode 100644 index c8209ca..0000000 --- a/tinygrad_repo/test/test_lazybuffer.py +++ /dev/null @@ -1,73 +0,0 @@ -#!/usr/bin/env python -import numpy as np -import unittest -from tinygrad.lazy import LazyBuffer -from tinygrad.ops import Device -from tinygrad.tensor import Tensor -from tinygrad.shape.symbolic import Variable -from tinygrad.jit import CacheCollector - -class TestLazyBuffer(unittest.TestCase): - def test_fromcpu_buffer_sharing(self): - a = np.arange(8) - assert LazyBuffer.fromCPU(a).realized._buf is a - - def test_fromcpu_shape_tracker(self): - def helper(a: np.ndarray): - print(a.shape, a.strides, a.flags.c_contiguous) - b = LazyBuffer.fromCPU(a) - #assert b.st.contiguous == a.flags.c_contiguous - assert b.st.shape == a.shape - np.testing.assert_equal(a, Tensor(b).numpy()) - - for ndims in range(1, 4): - a = np.random.randn(*(4,)*ndims).astype(np.float32) - for stride in [-2, 1, 2]: - for start in [0, 1]: - helper(a[(slice(start, None, stride),)*ndims]) - - def test_shuffle_pad_ops_cmpeq(self): - y = Tensor([1]).cat(Tensor([1]) == 0).numpy() - z = Tensor([1, 0]).numpy() - np.testing.assert_allclose(y, z) - - def test_shuffle_pad_ops_div(self): - y = Tensor([1]).cat(Tensor([1]).div(Tensor([2.0]))).numpy() - z = Tensor([1, 0.5]).numpy() - np.testing.assert_allclose(y, z) - - def test_shuffle_pad_ops_log(self): - y = Tensor([1]).cat(Tensor([1]).log()).numpy() - z = Tensor([1, 0]).numpy() - np.testing.assert_allclose(y, z) - - def test_shuffle_pad_ops_exp(self): - y = Tensor([1]).cat(Tensor([1]).exp()).numpy() - z = Tensor([1, np.e]).numpy() - np.testing.assert_allclose(y, z) - - @unittest.skipUnless(Device.DEFAULT in ["METAL", "CUDA", "GPU"], "Only GPU backends supports cache") - def test_children_count(self): - a = Tensor.ones(8,8,8) - d1 = a.sum((0)) - d2 = a.sum((0)).reshape(32,2) - assert len(d1.lazydata.op.src[0].children) == 1 - in1 = d1.reshape(16,4) - d3 = in1.reshape(8,8) - assert len(d3.lazydata.op.src[0].children) == 2 - - CacheCollector.start() - l = Tensor.ones(8,8) - r = Tensor.ones(8,8) - dd = d1 + l - dd.realize() - de = d3 + r - de.realize() - cache = CacheCollector.finish() - assert len(cache) == 3 - assert cache[0][0].name.startswith("r_") # Reduce should not merged 2 times. - assert cache[1][0].name.startswith("E_") - assert cache[2][0].name.startswith("E_") - -if __name__ == "__main__": - unittest.main() diff --git a/tinygrad_repo/test/test_lazyop.py b/tinygrad_repo/test/test_lazyop.py deleted file mode 100644 index 271b91c..0000000 --- a/tinygrad_repo/test/test_lazyop.py +++ /dev/null @@ -1,21 +0,0 @@ -import unittest -from tinygrad.tensor import Tensor - -# stuff needed to unpack a kernel -from tinygrad.ops import LazyOp, TernaryOps, BinaryOps, UnaryOps, ReduceOps, BufferOps, MemBuffer, ConstBuffer -from tinygrad.helpers import dtypes -from tinygrad.shape.shapetracker import ShapeTracker -from tinygrad.shape.view import View -from tinygrad.shape.symbolic import Variable -inf, nan = float('inf'), float('nan') - -class TestLazyOp(unittest.TestCase): - def test_lazyop_str(self): - t = Tensor.rand(10) + Tensor.rand(10) - s = t.lazydata.schedule() - ast = s[-1].ast - ast_remade = eval(str(ast)) - self.assertEqual(ast, ast_remade) - -if __name__ == '__main__': - unittest.main() diff --git a/tinygrad_repo/test/test_linearizer.py b/tinygrad_repo/test/test_linearizer.py deleted file mode 100644 index dd4e897..0000000 --- a/tinygrad_repo/test/test_linearizer.py +++ /dev/null @@ -1,492 +0,0 @@ -import numpy as np -import unittest, os - -from tinygrad.codegen.kernel import Opt, OptOps, tensor_cores -from tinygrad.codegen.linearizer import Linearizer, UOps -from tinygrad.ops import Compiled, Device, LoadOps -from tinygrad.tensor import Tensor -from tinygrad.jit import CacheCollector -from tinygrad.realize import run_schedule -from tinygrad.helpers import dtypes, prod - -class TestLinearizer(unittest.TestCase): - def test_arg_dedup(self): - if not isinstance(Device[Device.DEFAULT], Compiled): - self.skipTest("Only Compiled supports cache") - a, b = Tensor.randn(4), Tensor.randn(4) - np_a, np_b = a.numpy(), b.numpy() - CacheCollector.start() - c = ((a.shrink(((0, 2),)) - a.shrink(((2, 4),))) - (b.shrink(((0, 2),)) - b.shrink(((2, 4),)))).realize() - rawbufs = CacheCollector.finish()[0][1] - assert len(rawbufs) == 3 and set(rawbufs[1:]) == {a.lazydata.realized, b.lazydata.realized} - np_c = (np_a[:2] - np_a[2:]) - (np_b[:2] - np_b[2:]) - np.testing.assert_allclose(np_c, c.numpy(), atol=1e-4, rtol=1e-4) - - def test_load_dedup(self): - # for different leaves in the AST, the same loads may occur. - - if not isinstance(Device[Device.DEFAULT], Compiled): - self.skipTest("Only Compiled uses linearizer") - - a = Tensor.randn(4).realize() - # these are of size 3 to avoid float4 coalesce - r = a[:-1] + a[1:] - - k = Linearizer(r.lazydata.schedule()[-1].ast) - k.upcast() - k.linearize() - num_loads = len([uop for uop in k.uops if uop.uop == UOps.LOAD]) - assert num_loads <= 4, "more load uops than needed" - assert num_loads >= 4, "unexpected number of uops, maybe this test needs updating?" - - def test_upcast_cse(self): - # when upcasting, within a subtree, there may be common expressions. - - if not isinstance(Device[Device.DEFAULT], Compiled): - self.skipTest("Only Compiled uses linearizer") - - a, b = Tensor.randn(1).realize(), Tensor.randn(1).realize() - r = a.expand([2]) + b.expand([2]) - - k = Linearizer(r.lazydata.schedule()[-1].ast) - k.upcast() - k.linearize() - num_ops = len([uop for uop in k.uops if uop.uop == UOps.ALU]) - assert num_ops <= 1, "more alu uops than needed" - - def test_zero_fold(self): - if not isinstance(Device[Device.DEFAULT], Compiled): - self.skipTest("Only Compiled uses linearizer") - - a, b = Tensor.randn(1).realize(), Tensor.randn(1).realize() - r = Tensor.stack([a, b]) - - k = Linearizer(r.lazydata.schedule()[-1].ast) - k.upcast() - k.linearize() - num_ops = len([uop for uop in k.uops if uop.uop == UOps.ALU]) - assert num_ops == 0, "more alu uops than needed" - - @unittest.skip("constant folding not supported yet") - def test_constant_fold(self): - if not isinstance(Device[Device.DEFAULT], Compiled): - self.skipTest("Only Compiled uses linearizer") - - a, b = Tensor(2), Tensor(3) - r = a * b - - k = Linearizer(r.lazydata.schedule()[-1][0]) - k.linearize() - num_ops = len([uop for uop in k.uops if uop.uop in [UOps.LOAD, UOps.ALU]]) - assert num_ops <= 0, "more load or alu uops than needed" - - def test_tensor_cores(self): - if not isinstance(Device[Device.DEFAULT], Compiled): - self.skipTest("Only Compiled uses linearizer") - if Device.DEFAULT not in tensor_cores: - self.skipTest("No tensor cores for device") - - for tc in tensor_cores[Device.DEFAULT]: - if tc.arch is not None and tc.arch != os.uname().machine: continue - a, b = Tensor.rand(tc.dims[0], tc.dims[2], dtype=tc.dtype_in), Tensor.rand(tc.dims[2], tc.dims[1], dtype=tc.dtype_in) - np_a, np_b = a.numpy(), b.numpy() - if tc.dtype_out != tc.dtype_in: - r = (a.reshape(tc.dims[0], 1, tc.dims[2]) * b.permute(1,0).reshape(1, tc.dims[1], tc.dims[2])).cast(tc.dtype_out).sum(axis=2) - else: - r = a @ b - realized_ast, _ = helper_realized_ast(r) - k = Linearizer(realized_ast) - k.apply_tensor_cores(1) - k.linearize() - assert len([uop for uop in k.uops if uop.uop == UOps.WMMA]) == 1, "tensor core not triggered" - np_c = np_a @ np_b - np.testing.assert_allclose(np_c, r.numpy(), atol=5e-3, rtol=1e-4) - - def test_limit_dims_to_max_5d_global(self): - t = Tensor.rand(3, 4, 5, 6, 7).pad(((1, 1), (1, 1), (1, 1), (1, 1), (1, 1))) + 1 - sched = [si for si in t.lazydata.schedule() if si.ast.op not in LoadOps] - assert len(sched) == 1 - lin = Linearizer(sched[0].ast) - assert lin.full_shape[:lin.global_dims] == (5, 6, 7, 8, 9) - lin.limit_dims_to_max(global_max=[16, 16, 16], local_max=[16, 16, 16]) - -def helper_realized_ast(r:Tensor): - s = r.lazydata.schedule() - run_schedule(s[:-1]) # run all kernels except the last one - # now all input LazyBuffers buffers in s[-1] should be realized - output_buffer = Device[s[-1].out.device].buffer(prod((s if isinstance(s, int) else s.max for s in s[-1].out.shape)), s[-1].out.dtype, **s[-1].out._device_extra_args()) # allocate an output buffer - return s[-1].ast, [output_buffer] + [l.realized for l in s[-1].inputs] - -class TestFloat4(unittest.TestCase): - def setUp(self): - if not isinstance(Device[Device.DEFAULT], Compiled) or not Device[Device.DEFAULT].linearizer_opts.supports_float4: - self.skipTest("Device does not support float4") - - @staticmethod - def count_float4(k): - return (len([uop for uop in k.uops if uop.uop == UOps.LOAD and uop.dtype == dtypes._float4]), - len([uop for uop in k.uops if uop.uop == UOps.STORE and len(uop.vin) == 3 and uop.vin[2].dtype == dtypes._float4])) - - # TODO: express opts below as auto opts - - def test_float4_basic(self): - a = Tensor.rand(2, 8).realize() - b = Tensor.rand(2, 8).realize() - c = a + b - - s = c.lazydata.schedule()[0] - k = Linearizer(s.ast) - k.hand_coded_optimizations() - k.linearize() - - assert TestFloat4.count_float4(k) == (2, 1) - - def test_float4_multidim(self): - a = Tensor.rand(2, 8).realize() - b = Tensor.rand(2, 8).realize() - c = a + b - - s = c.lazydata.schedule()[0] - k = Linearizer(s.ast) - k.shift_to(0, 4) # float4 dimension - k.shift_to(0, 2, insert_before=k.shape_len-1) - k.upcast() - k.upcast() - k.local_dims += 1 - k.linearize() - - assert TestFloat4.count_float4(k) == (4, 2) - - def test_float4_unaligned_load(self): - a = Tensor.rand(9).realize().shrink(((1, 9),)) - b = Tensor.rand(9).realize().shrink(((1, 9),)) - c = a + b - - s = c.lazydata.schedule()[0] - k = Linearizer(s.ast) - k.hand_coded_optimizations() # implicit trigger float4 dim - k.linearize() - - assert TestFloat4.count_float4(k) == (0, 1) - - def test_float4_multidim_unaligned_load(self): - a = Tensor.rand(2, 9).realize().shrink(((0, 2), (1, 9),)) - b = Tensor.rand(2, 9).realize().shrink(((0, 2), (1, 9),)) - c = a + b - - s = c.lazydata.schedule()[0] - k = Linearizer(s.ast) - k.shift_to(len(k.full_unupcasted_shape)-1, 4) # manual trigger float4 dim - k.upcast() - k.shift_to(len(k.full_unupcasted_shape)-1, 2, insert_before=k.shape_len-1) - k.upcast() - k.local_dims += 1 - k.linearize() - - assert TestFloat4.count_float4(k) == (0, 2) - - def test_float4_sometimes_unaligned(self): - a = Tensor.rand(1, 1, 8).realize() - b = Tensor.rand(1, 1, 5).realize().shrink(((0, 1), (0, 1), (1, 5))) - c = a.conv2d(b) - # only the first and last conv dot products are aligned in a, and b is never aligned, so no - # float4 should be emitted (the reduce axis of size 4 is the float4 axis here) - - s = c.lazydata.schedule()[0] - k = Linearizer(s.ast) - k.upcast() - k.linearize() - - assert TestFloat4.count_float4(k) == (0, 0) - - def test_float4_multidim_sometimes_unaligned(self): - a = Tensor.rand(1, 1, 7).realize() - b = Tensor.rand(1, 1, 5).realize().shrink(((0, 1), (0, 1), (1, 5))) - c = a.conv2d(b) - # the first conv dot product is aligned in a. If we upcast the output and reduce - # dimension, then we could do float4 for only that one set of loads, but we currently - # don't. - - s = c.lazydata.schedule()[0] - k = Linearizer(s.ast) - k.upcast() - k.upcast() - k.linearize() - - assert TestFloat4.count_float4(k) == (0, 1) - - def test_float4_noncontiguous(self): - a = Tensor.rand(4, 2).realize() - b = Tensor.rand(4, 2).realize() - c = a + b - - # we will upcast the top axis of sz 4. they should not be coalesced into float4, - # since the top axis is not contiguous. - - s = c.lazydata.schedule()[0] - k = Linearizer(s.ast) - k.shift_to(0, 4, top=True) # top axes are float4 axes - k.upcast() - k.linearize() - - assert TestFloat4.count_float4(k) == (0, 0) - - def test_float4_expand(self): - a = Tensor.rand(9).realize().shrink(((1, 9),)) - b = Tensor.rand(2).realize().reshape((2, 1)).expand((2,4)).reshape((8,)) - c = a + b - - # we will upcast the top axis of sz 4. they should not be coalesced into float4, - # since the top axis is not contiguous. - - s = c.lazydata.schedule()[0] - k = Linearizer(s.ast) - k.shift_to(0, 4) # float4 axis - k.upcast() - k.linearize() - - assert TestFloat4.count_float4(k) == (0, 1) - - def test_float4_heterogeneous(self): - a = Tensor.rand(8).realize() - b = Tensor.rand(9).realize().shrink(((1, 9),)) - c = a + b - - # should float4 b but not a - - s = c.lazydata.schedule()[0] - k = Linearizer(s.ast) - k.shift_to(0, 4) # float4 axis - k.upcast() - k.linearize() - - assert TestFloat4.count_float4(k) == (1, 1) - -class TestHandCodedOpts(unittest.TestCase): - def setUp(self): - if not isinstance(Device[Device.DEFAULT], Compiled): - self.skipTest("Device does not use linearizer") - - def test_masked_upcast(self): - layer_1 = Tensor.cat(*[Tensor.rand(5) for _ in range(4)]) - layer_2 = Tensor.cat(layer_1.unsqueeze(0), Tensor.rand(6, 20)) - - s = layer_2.lazydata.schedule()[-1] - k = Linearizer(s.ast) - k.hand_coded_optimizations() - assert len(k.bufs) == 6 # make sure all ops are done in one kernel - # masked upcast should upcast masked axis of size 7 - # masked upcast should not upcast large (20) last axis - # float4/other hcopt shouldn't upcast last axis, since we already have 7 upcast, and the last axis is not very contiguous - assert k.upcasted == 1 and k.full_shape[-1] == 7 - - def test_masked_upcast_wino(self): - monster = Tensor.stack([Tensor.stack([Tensor.rand(16) for _ in range(6)]) for _ in range(6)]) - - s = monster.lazydata.schedule()[-1] - k = Linearizer(s.ast) - k.hand_coded_optimizations() - assert len(k.bufs) == 37 # make sure all ops are done in one kernel - # should upcast the two Tensor.stacks - assert k.upcasted >= 2 and k.full_shape[k.shape_len-k.upcasted:k.shape_len].count(6) == 2 - - def test_masked_upcast_wino_full(self): - old_wino = Tensor.wino - Tensor.wino = True - x,w = Tensor.rand(1,4,9,9, requires_grad=True).realize(), Tensor.rand(4,4,3,3, requires_grad=True).realize() - out = Tensor.conv2d(x,w, padding=1) - upcasts = [] - # collect upcasts of tile transform kernels - for i, si in enumerate(out.lazydata.schedule()): - k = Linearizer(si.ast) - k.hand_coded_optimizations() - if k.reduceop is not None: continue # not a tile transform kernel (there is a gemm reduce kernel) - if len(k.bufs) < 100: continue # not a tile transform kernel (there's a permute kernel at the end) - upcasts.append(tuple(k.full_shape[k.shape_len - k.upcasted:k.shape_len])) - assert len(upcasts) == 3 # 3 transformation matrices - assert upcasts.count((6, 6)) == 2 and upcasts.count((4, 4)) == 1 - - out.mean().backward() - for si in x.grad.lazydata.schedule() + w.grad.lazydata.schedule(): - k = Linearizer(si.ast) - k.hand_coded_optimizations() - k.linearize() - if len(k.bufs) < 20: continue # not a tile transform kernel - # heuristic number to make sure that at least some upcasts but not too many upcasts are being done - assert 6 <= prod(k.full_shape[k.shape_len - k.upcasted:k.shape_len]) <= 49 - - Tensor.wino = old_wino - - def test_masked_upcast_many(self): - layer_1 = Tensor.cat(Tensor.rand(3, 4), Tensor.rand(4, 4)) - layer_2 = Tensor.cat(layer_1.unsqueeze(0), Tensor.rand(6, 7, 4)) - layer_3 = Tensor.cat(layer_2.unsqueeze(0), Tensor.rand(6, 7, 7, 4)) - - s = layer_3.lazydata.schedule()[-1] - k = Linearizer(s.ast) - k.hand_coded_optimizations() - assert len(k.bufs) == 5 # make sure all ops are done in one kernel - # check that we don't do too many upcasts - assert prod(k.full_shape[k.shape_len-k.upcasted:k.shape_len]) <= 49 - -def helper_linearizer_opt(r:Tensor, opts=[], apply_tc=False): - wanna_output = None - realized_ast, real_bufs = helper_realized_ast(r) - - def check_opt(opts, create_k, to_prg): - k = create_k() - if apply_tc: - k.apply_tensor_cores(1, opts) - else: - for opt in opts: - k.apply_opt(opt) - prg = to_prg(k) - real_bufs[0] = real_bufs[0].fromCPU(np.zeros((real_bufs[0].size, ), dtype=real_bufs[0].dtype.np)) # Zero to check that all values are filled - prg.exec(real_bufs, force_wait=True) - np.testing.assert_allclose(wanna_output, real_bufs[0].toCPU(), atol=1e-4, rtol=1e-4) - - # Get baseline, which is not optimized at all. - k = Linearizer(realized_ast) - prg = Device[Device.DEFAULT].to_program(k) - prg.exec(real_bufs, force_wait=True) - wanna_output = real_bufs[0].toCPU().copy() - - # Check correctness of handcoded optimiztions. - k = Linearizer(realized_ast) - k.hand_coded_optimizations() - prg = Device[Device.DEFAULT].to_program(k) - real_bufs[0] = real_bufs[0].fromCPU(np.zeros((real_bufs[0].size, ), dtype=real_bufs[0].dtype.np)) # Zero to check that all values are filled - prg.exec(real_bufs, force_wait=True) - np.testing.assert_allclose(wanna_output, real_bufs[0].toCPU(), atol=1e-4, rtol=1e-4) - for x in opts: # Check custom transformations if any. - check_opt(x, lambda: Linearizer(realized_ast), Device[Device.DEFAULT].to_program) - -class TestLinearizerOpts(unittest.TestCase): - def test_local_and_grouped_reduce(self): - if not isinstance(Device[Device.DEFAULT], Compiled) or not Device[Device.DEFAULT].linearizer_opts.has_local or not Device[Device.DEFAULT].linearizer_opts.has_shared: - self.skipTest("Only Compiled uses linearizer with locals and shared") - - N = 128 - Tensor.manual_seed(1882) - a = Tensor.rand(4, 4, N, N) - b = Tensor.rand(4, 4, N) - r = (b.sqrt() + ((a+1).sum(axis=3).exp())) - helper_linearizer_opt(r, [ - [Opt(OptOps.LOCAL, 0, 2)], - [Opt(OptOps.LOCAL, 0, 8)], - [Opt(OptOps.LOCAL, 0, 16)], # Checking how it works with locals - [Opt(OptOps.GROUPTOP, 0, 2)], - [Opt(OptOps.GROUPTOP, 0, 32)], - [Opt(OptOps.GROUPTOP, 0, 64)], # Checking how it works with grouped reduce - [Opt(OptOps.LOCAL, 0, 2), Opt(OptOps.GROUPTOP, 0, 2)], - [Opt(OptOps.LOCAL, 0, 16), Opt(OptOps.GROUPTOP, 0, 16)], - [Opt(OptOps.LOCAL, 0, 32), Opt(OptOps.GROUPTOP, 0, 2)], - [Opt(OptOps.LOCAL, 0, 2), Opt(OptOps.GROUPTOP, 0, 64)], # Checking how it works with locals + grouped reduce - [Opt(OptOps.LOCAL, 0, 2), Opt(OptOps.GROUPTOP, 0, 2), Opt(OptOps.UPCAST, 0, 8), Opt(OptOps.UNROLL, 1, 4)], # Checking how it works with locals + grouped reduce + upcasts - ]) - - def test_upcasts(self): - if not isinstance(Device[Device.DEFAULT], Compiled): - self.skipTest("Only Compiled uses linearizer") - - N = 16 - Tensor.manual_seed(1772) - a = Tensor.rand(N, N) - b = Tensor.rand(N, N) - r = (a+b).sqrt() * ((a+1).exp()) - helper_linearizer_opt(r, [ - [Opt(OptOps.UPCAST, 0, 2)], - [Opt(OptOps.UPCAST, 0, 4)], - [Opt(OptOps.UPCAST, 0, 8)], # Checking how it works with upcasts - ]) - - def test_full_upcast(self): - if not isinstance(Device[Device.DEFAULT], Compiled): - self.skipTest("Only Compiled uses linearizer") - - Tensor.manual_seed(1772) - a = Tensor.rand(4) - b = Tensor.rand(4) - r = (a+b).sqrt() * ((a+1).exp()) - helper_linearizer_opt(r, [ - [Opt(OptOps.UPCAST, 0, 4)], # Checking how it works with upcasts - ]) - - def test_matmul(self): - if not isinstance(Device[Device.DEFAULT], Compiled) or not Device[Device.DEFAULT].linearizer_opts.has_local or not Device[Device.DEFAULT].linearizer_opts.has_shared: - self.skipTest("Only Compiled uses linearizer with locals and shared") - - N = 128 - Tensor.manual_seed(1552) - a = Tensor.rand(N, N) - b = Tensor.rand(N, N) - r = a@b - helper_linearizer_opt(r, [ - [Opt(OptOps.UPCAST, 0, 2)], - [Opt(OptOps.UPCAST, 0, 4), Opt(OptOps.UPCAST, 1, 4)], # Checking how it works with upcasts - [Opt(OptOps.LOCAL, 0, 2)], - [Opt(OptOps.LOCAL, 1, 32)], - [Opt(OptOps.LOCAL, 0, 4), Opt(OptOps.LOCAL, 1, 4)], - [Opt(OptOps.LOCAL, 0, 4), Opt(OptOps.LOCAL, 1, 32)], - [Opt(OptOps.LOCAL, 0, 16), Opt(OptOps.LOCAL, 1, 8)], # Checking how it works with locals - [Opt(OptOps.GROUPTOP, 0, 2)], - [Opt(OptOps.GROUPTOP, 0, 32)], - [Opt(OptOps.GROUPTOP, 0, 32), Opt(OptOps.UNROLL, 0, 4)], # Checking how it works with grouped_reduce - [Opt(OptOps.LOCAL, 0, 2), Opt(OptOps.LOCAL, 1, 2), Opt(OptOps.GROUPTOP, 0, 32)], - [Opt(OptOps.LOCAL, 0, 8), Opt(OptOps.GROUPTOP, 0, 32)], - [Opt(OptOps.LOCAL, 0, 4), Opt(OptOps.LOCAL, 0, 8), Opt(OptOps.GROUPTOP, 0, 4)], # Checking how it works with local+grouped_reduce - [Opt(OptOps.LOCAL, 0, 4), Opt(OptOps.LOCAL, 0, 4), Opt(OptOps.GROUPTOP, 0, 8), Opt(OptOps.UNROLL, 0, 4), Opt(OptOps.UPCAST, 0, 4), Opt(OptOps.UPCAST, 1, 2)], # Checking all together - [Opt(OptOps.LOCAL, 0, 4), Opt(OptOps.LOCAL, 0, 4), Opt(OptOps.GROUPTOP, 0, 8), Opt(OptOps.UNROLL, 0, 4), Opt(OptOps.UPCAST, 0, 8)], # Full global upcast + local - ]) - - def test_double_reduce(self): - if not isinstance(Device[Device.DEFAULT], Compiled) or not Device[Device.DEFAULT].linearizer_opts.has_local or not Device[Device.DEFAULT].linearizer_opts.has_shared: - self.skipTest("Only Compiled uses linearizer with locals and shared") - - N = 128 - Tensor.manual_seed(1552) - a = Tensor.rand(8, N, 8, N) - r = a.sum(axis=(1,3)) - helper_linearizer_opt(r, [ - # openCL / GPU=1 is 256 max threads - [Opt(OptOps.GROUPTOP, 0, 2)], [Opt(OptOps.GROUPTOP, 0, 32)], - [Opt(OptOps.GROUPTOP, 1, 2)], [Opt(OptOps.GROUPTOP, 1, 32)], # Checking how it works with 1 grouped_reduce. - [Opt(OptOps.GROUPTOP, 0, 2), Opt(OptOps.GROUPTOP, 1, 2)], - [Opt(OptOps.GROUPTOP, 0, 16), Opt(OptOps.GROUPTOP, 1, 2)], - [Opt(OptOps.GROUPTOP, 0, 4), Opt(OptOps.GROUPTOP, 1, 64)], # Checking how it works with 2 grouped_reduces. - [Opt(OptOps.GROUPTOP, 0, 16), Opt(OptOps.GROUPTOP, 1, 2), Opt(OptOps.UNROLL, 0, 4)], - [Opt(OptOps.GROUPTOP, 0, 2), Opt(OptOps.GROUPTOP, 1, 32), Opt(OptOps.UNROLL, 2, 4)], # Checking how it works with 2 grouped_reduces + upcasts. - [Opt(OptOps.LOCAL, 0, 4), Opt(OptOps.LOCAL, 1, 4), Opt(OptOps.GROUPTOP, 0, 4), Opt(OptOps.GROUPTOP, 1, 4)], - [Opt(OptOps.LOCAL, 0, 4), Opt(OptOps.LOCAL, 1, 4), Opt(OptOps.GROUPTOP, 0, 2), Opt(OptOps.GROUPTOP, 1, 32), Opt(OptOps.UNROLL, 1, 4)], # Checking how it works with 2 grouped_reduces + upcasts + locals. - [Opt(OptOps.LOCAL, 0, 2), Opt(OptOps.LOCAL, 1, 2), Opt(OptOps.GROUPTOP, 0, 8), Opt(OptOps.GROUPTOP, 1, 4), Opt(OptOps.UPCAST, 0, 2)], - [Opt(OptOps.LOCAL, 0, 2), Opt(OptOps.LOCAL, 1, 2), Opt(OptOps.GROUPTOP, 0, 8), Opt(OptOps.GROUPTOP, 1, 4), Opt(OptOps.UPCAST, 0, 2), Opt(OptOps.UNROLL, 0, 4), Opt(OptOps.UNROLL, 1, 4)], # Checking how it works with 2 grouped_reduces + upcasts + locals. - [Opt(OptOps.LOCAL, 0, 4), Opt(OptOps.LOCAL, 1, 4), Opt(OptOps.GROUPTOP, 0, 4), Opt(OptOps.GROUPTOP, 1, 4), Opt(OptOps.UPCAST, 0, 2), Opt(OptOps.UPCAST, 0, 2)], # No globals - ]) - - def test_tensor_core_opts(self): - if not isinstance(Device[Device.DEFAULT], Compiled) or not Device[Device.DEFAULT].linearizer_opts.has_local: - self.skipTest("Only Compiled uses linearizer with locals") - if Device.DEFAULT not in tensor_cores: - self.skipTest("No tensor cores for device") - - N = 128 - Tensor.manual_seed(1552) - a = Tensor.rand(N, N) - b = Tensor.rand(N, N) - r = a@b - helper_linearizer_opt(r, [ - [Opt(OptOps.UPCAST, 0, 4)], - [Opt(OptOps.UPCAST, 1, 4)], - [Opt(OptOps.UPCAST, 0, 4), Opt(OptOps.UPCAST, 1, 4)], # check upcasts - [Opt(OptOps.UNROLL, 0, 2)], # check last unroll - [Opt(OptOps.LASTLOCAL, 0, 4)], # check last local - [Opt(OptOps.UPCAST, 0, 4), Opt(OptOps.UNROLL, 0, 2)], # check combo of last unroll and last local - [Opt(OptOps.UPCAST, 0, 4), Opt(OptOps.UPCAST, 1, 4), Opt(OptOps.UNROLL, 0, 2)], - [Opt(OptOps.UPCAST, 0, 4), Opt(OptOps.UPCAST, 1, 4), Opt(OptOps.UNROLL, 0, 4)], - [Opt(OptOps.UPCAST, 0, 4), Opt(OptOps.UPCAST, 1, 4), Opt(OptOps.UNROLL, 0, 4), Opt(OptOps.LASTLOCAL, 0, 2)], - # [Opt(OptOps.GROUP, 0, 2)] # doesn't work because group_for_reduce dims become early locals (conflicting with TC) - ], apply_tc=True) - - -if __name__ == '__main__': - unittest.main() diff --git a/tinygrad_repo/test/test_linearizer_failures.py b/tinygrad_repo/test/test_linearizer_failures.py deleted file mode 100644 index 71b20ab..0000000 --- a/tinygrad_repo/test/test_linearizer_failures.py +++ /dev/null @@ -1,21 +0,0 @@ -import unittest -from tinygrad.codegen.linearizer import Linearizer -from tinygrad.ops import Device - -# stuff needed to unpack a kernel -from tinygrad.ops import LazyOp, TernaryOps, BinaryOps, UnaryOps, ReduceOps, BufferOps, MemBuffer, ConstBuffer -from tinygrad.helpers import dtypes -from tinygrad.shape.shapetracker import ShapeTracker -from tinygrad.shape.view import View -from tinygrad.shape.symbolic import Variable -inf, nan = float('inf'), float('nan') - -class TestLinearizerFailures(unittest.TestCase): - @unittest.skip("this is currently failing") - def test_failure_1(self): - ast = LazyOp(op=BinaryOps.ADD, src=(LazyOp(op=BinaryOps.ADD, src=(LazyOp(op=ReduceOps.SUM, src=(LazyOp(op=BufferOps.MEM, src=(), arg=MemBuffer(idx=1, dtype=dtypes.float, st=ShapeTracker(views=(View(shape=(32, 16, 16), strides=(16, 1, 0), offset=0, mask=None, contiguous=False),)))),), arg=(32, 16, 1)), LazyOp(op=BufferOps.MEM, src=(), arg=MemBuffer(idx=2, dtype=dtypes.float, st=ShapeTracker(views=(View(shape=(32, 16, 1), strides=(0, 1, 0), offset=0, mask=None, contiguous=False),))))), arg=None), LazyOp(op=BufferOps.MEM, src=(), arg=MemBuffer(idx=1, dtype=dtypes.float, st=ShapeTracker(views=(View(shape=(32, 16, 1), strides=(16, 1, 0), offset=0, mask=None, contiguous=True),))))), arg=None) - lin = Linearizer(ast) - prg = Device[Device.DEFAULT].to_program(lin) - -if __name__ == '__main__': - unittest.main() diff --git a/tinygrad_repo/test/test_net_speed.py b/tinygrad_repo/test/test_net_speed.py deleted file mode 100644 index 69675b1..0000000 --- a/tinygrad_repo/test/test_net_speed.py +++ /dev/null @@ -1,102 +0,0 @@ -#!/usr/bin/env python -import time -import cProfile -import pstats -import unittest -import torch -from tinygrad.tensor import Tensor, Device -import pytest - -pytestmark = [pytest.mark.exclude_cuda, pytest.mark.exclude_gpu, pytest.mark.exclude_clang] - -def start_profile(): - import time - pr = cProfile.Profile(timer=lambda: int(time.time()*1e9), timeunit=1e-6) - pr.enable() - return pr - -def stop_profile(pr, sort='cumtime', frac=0.2): - pr.disable() - ps = pstats.Stats(pr) - ps.strip_dirs() - ps.sort_stats(sort) - ps.print_stats(frac) - -class TestConvSpeed(unittest.TestCase): - - def test_mnist(self): - # https://keras.io/examples/vision/mnist_convnet/ - conv = 3 - inter_chan, out_chan = 32, 64 - - # ****** torch baseline ******* - - torch.backends.mkldnn.enabled = False - - conv = 3 - inter_chan, out_chan = 32, 64 - c1 = torch.randn(inter_chan,1,conv,conv, requires_grad=True) - c2 = torch.randn(out_chan,inter_chan,conv,conv, requires_grad=True) - l1 = torch.randn(out_chan*5*5, 10, requires_grad=True) - - c2d = torch.nn.functional.conv2d - mp = torch.nn.MaxPool2d((2,2)) - lsm = torch.nn.LogSoftmax(dim=1) - - cnt = 5 - fpt, bpt = 0.0, 0.0 - for i in range(cnt): - et0 = time.time() - x = torch.randn(128, 1, 28, 28, requires_grad=True) - x = mp(c2d(x,c1).relu()) - x = mp(c2d(x,c2).relu()) - x = x.reshape(x.shape[0], -1) - out = lsm(x.matmul(l1)) - out = out.mean() - et1 = time.time() - out.backward() - et2 = time.time() - fpt += (et1-et0) - bpt += (et2-et1) - - fpt_baseline = (fpt*1000/cnt) - bpt_baseline = (bpt*1000/cnt) - print("torch forward pass: %.3f ms" % fpt_baseline) - print("torch backward pass: %.3f ms" % bpt_baseline) - - # ****** tinygrad compare ******* - - c1 = Tensor(c1.detach().numpy(), requires_grad=True) - c2 = Tensor(c2.detach().numpy(), requires_grad=True) - l1 = Tensor(l1.detach().numpy(), requires_grad=True) - - cnt = 5 - fpt, bpt = 0.0, 0.0 - for i in range(1+cnt): - et0 = time.time() - x = Tensor.randn(128, 1, 28, 28) - x = x.conv2d(c1).relu().avg_pool2d() - x = x.conv2d(c2).relu().max_pool2d() - x = x.reshape(shape=(x.shape[0], -1)) - out = x.dot(l1).log_softmax() - out = out.mean() - out.realize() - et1 = time.time() - out.backward() - [x.grad.realize() for x in [c1, c2, l1]] - et2 = time.time() - if i == 0: - pr = start_profile() - else: - fpt += (et1-et0) - bpt += (et2-et1) - - stop_profile(pr, sort='time') - fpt = (fpt*1000/cnt) - bpt = (bpt*1000/cnt) - print("forward pass: %.3f ms, %.2fx off baseline %.3f ms" % (fpt, fpt/fpt_baseline, fpt_baseline)) - print("backward pass: %.3f ms, %.2fx off baseline %.3f ms" % (bpt, bpt/bpt_baseline, bpt_baseline)) - - -if __name__ == '__main__': - unittest.main() diff --git a/tinygrad_repo/test/test_nn.py b/tinygrad_repo/test/test_nn.py deleted file mode 100644 index 7770864..0000000 --- a/tinygrad_repo/test/test_nn.py +++ /dev/null @@ -1,339 +0,0 @@ -#!/usr/bin/env python -import unittest -import numpy as np -from extra.utils import WINDOWS -from tinygrad.helpers import CI -from tinygrad.jit import TinyJit -from tinygrad.tensor import Tensor, Device -from tinygrad.nn import BatchNorm2d, Conv1d, ConvTranspose1d, Conv2d, ConvTranspose2d, Linear, GroupNorm, LayerNorm, LayerNorm2d, Embedding, InstanceNorm -import torch -import pytest - -pytestmark = [pytest.mark.exclude_cuda] - -class TestNN(unittest.TestCase): - def test_sparse_cat_cross_entropy(self): - input = torch.randn(3, 5) - target = torch.empty(3, dtype=torch.long).random_(5) - loss_fun = torch.nn.CrossEntropyLoss(reduction='mean') - loss = loss_fun(input, target) - - input_tiny = Tensor(input.detach().numpy()) - taret_tiny = Tensor(target.detach().numpy()) - loss_tiny = input_tiny.sparse_categorical_crossentropy(taret_tiny) - - np.testing.assert_allclose(loss_tiny.numpy(), loss.detach().numpy(), atol=1e-5, rtol=1e-6) - - def test_batchnorm2d(self, training=False): - szs = [4, 8, 16, 32] - for sz in szs: - # create in tinygrad - Tensor.training = training - bn = BatchNorm2d(sz, eps=1e-5, track_running_stats=training) - bn.weight = Tensor.randn(sz) - bn.bias = Tensor.randn(sz) - bn.running_mean = Tensor.randn(sz) - bn.running_var = Tensor.randn(sz) - bn.running_var.numpy()[bn.running_var.numpy() < 0] = 0 - - # create in torch - with torch.no_grad(): - tbn = torch.nn.BatchNorm2d(sz).eval() - tbn.training = training - tbn.weight[:] = torch.tensor(bn.weight.numpy()) - tbn.bias[:] = torch.tensor(bn.bias.numpy()) - tbn.running_mean[:] = torch.tensor(bn.running_mean.numpy()) - tbn.running_var[:] = torch.tensor(bn.running_var.numpy()) - - np.testing.assert_allclose(bn.running_mean.numpy(), tbn.running_mean.detach().numpy(), rtol=1e-5, atol=1e-6) - np.testing.assert_allclose(bn.running_var.numpy(), tbn.running_var.detach().numpy(), rtol=1e-5, atol=1e-6) - - # trial - inn = Tensor.randn(2, sz, 3, 3) - - # in tinygrad - outt = bn(inn) - - # in torch - toutt = tbn(torch.tensor(inn.numpy())) - - # close - np.testing.assert_allclose(outt.numpy(), toutt.detach().numpy(), rtol=5e-4, atol=1e-6) - - np.testing.assert_allclose(bn.running_mean.numpy(), tbn.running_mean.detach().numpy(), rtol=1e-5, atol=1e-6) - - np.testing.assert_allclose(bn.running_var.numpy(), tbn.running_var.detach().numpy(), rtol=1e-5, atol=1e-6) - - def test_batchnorm2d_training(self): - self.test_batchnorm2d(True) - - def test_linear(self): - def _test_linear(x): - - # create in tinygrad - model = Linear(in_dim, out_dim) - z = model(x) - - # create in torch - with torch.no_grad(): - torch_layer = torch.nn.Linear(in_dim, out_dim).eval() - torch_layer.weight[:] = torch.tensor(model.weight.numpy(), dtype=torch.float32) - torch_layer.bias[:] = torch.tensor(model.bias.numpy(), dtype=torch.float32) - torch_x = torch.tensor(x.numpy(), dtype=torch.float32) - torch_z = torch_layer(torch_x) - - # test - np.testing.assert_allclose(z.numpy(), torch_z.detach().numpy(), atol=5e-4, rtol=1e-5) - - BS, T, in_dim, out_dim = 4, 2, 8, 16 - _test_linear(Tensor.randn(BS, in_dim)) - _test_linear(Tensor.randn(BS, T, in_dim)) # test with more dims - - def test_conv1d(self): - BS, C1, W = 4, 16, 224//4 - C2, K, S, P = 64, 7, 2, 1 - - # create in tinygrad - layer = Conv1d(C1, C2, kernel_size=K, stride=S, padding=P) - - # create in torch - with torch.no_grad(): - torch_layer = torch.nn.Conv1d(C1, C2, kernel_size=K, stride=S, padding=P).eval() - torch_layer.weight[:] = torch.tensor(layer.weight.numpy(), dtype=torch.float32) - torch_layer.bias[:] = torch.tensor(layer.bias.numpy(), dtype=torch.float32) - - # test - x = Tensor.uniform(BS, C1, W) - z = layer(x) - torch_x = torch.tensor(x.numpy()) - torch_z = torch_layer(torch_x) - np.testing.assert_allclose(z.numpy(), torch_z.detach().numpy(), atol=5e-4, rtol=1e-5) - - def test_conv2d(self): - BS, C1, H, W = 4, 16, 224//4, 224//4 - C2, K, S, P = 64, 7, 2, 1 - - # create in tinygrad - layer = Conv2d(C1, C2, kernel_size=K, stride=S, padding=P) - - # create in torch - with torch.no_grad(): - torch_layer = torch.nn.Conv2d(C1, C2, kernel_size=K, stride=S, padding=P).eval() - torch_layer.weight[:] = torch.tensor(layer.weight.numpy(), dtype=torch.float32) - torch_layer.bias[:] = torch.tensor(layer.bias.numpy(), dtype=torch.float32) - - # test - x = Tensor.uniform(BS, C1, H, W) - z = layer(x) - torch_x = torch.tensor(x.numpy()) - torch_z = torch_layer(torch_x) - np.testing.assert_allclose(z.numpy(), torch_z.detach().numpy(), atol=5e-4, rtol=1e-5) - - @unittest.skipIf(Device.DEFAULT != "TORCH", "Takes too long to compile for Compiled backends") - def test_conv2d_winograd(self): - BS, C1, H, W = 2, 8, 16, 16 - C2, K, S, P = 8, 3, 1, 1 - - old_wino = Tensor.wino - Tensor.wino = True - - # create in tinygrad - layer = Conv2d(C1, C2, kernel_size=K, stride=S, padding=P) - layer.weight.requires_grad = True - layer.bias.requires_grad = True - - # create in torch - torch_layer = torch.nn.Conv2d(C1, C2, kernel_size=K, stride=S, padding=P).eval() - torch_layer.weight = torch.nn.Parameter(torch.tensor(layer.weight.numpy(), dtype=torch.float32)) - torch_layer.bias = torch.nn.Parameter(torch.tensor(layer.bias.numpy(), dtype=torch.float32)) - - # test - x = Tensor.uniform(BS, C1, H, W, requires_grad=True) - z = layer(x) - torch_x = torch.tensor(x.numpy(), requires_grad=True) - torch_z = torch_layer(torch_x) - np.testing.assert_allclose(z.numpy(), torch_z.detach().numpy(), atol=5e-4, rtol=1e-5) - - m = z.mean() - m.backward() - gw = layer.weight.grad.realize() - gb = layer.bias.grad.realize() - gx = x.grad.realize() - - torch_z.mean().backward() - np.testing.assert_allclose(gw.numpy(), torch_layer.weight.grad.numpy(), atol=5e-4, rtol=1e-5) - np.testing.assert_allclose(gb.numpy(), torch_layer.bias.grad.numpy(), atol=5e-4, rtol=1e-5) - np.testing.assert_allclose(gx.numpy(), torch_x.grad.numpy(), atol=5e-4, rtol=1e-5) - - Tensor.wino = old_wino - - @unittest.skipIf(CI and (WINDOWS or Device.DEFAULT == "WEBGPU"), "runs out of memory in CI") - def test_conv_transpose1d(self): - BS, C1, W = 4, 16, 224//4 - C2, K, S, P = 64, 7, 2, 1 - - # create in tinygrad - layer = ConvTranspose1d(C1, C2, kernel_size=K, stride=S, padding=P) - - # create in torch - with torch.no_grad(): - torch_layer = torch.nn.ConvTranspose1d(C1, C2, kernel_size=K, stride=S, padding=P).eval() - torch_layer.weight[:] = torch.tensor(layer.weight.numpy(), dtype=torch.float32) - torch_layer.bias[:] = torch.tensor(layer.bias.numpy(), dtype=torch.float32) - - # test - x = Tensor.uniform(BS, C1, W) - z = layer(x) - torch_x = torch.tensor(x.numpy()) - torch_z = torch_layer(torch_x) - np.testing.assert_allclose(z.numpy(), torch_z.detach().numpy(), atol=5e-4, rtol=1e-5) - - @unittest.skipIf(CI and (WINDOWS or Device.DEFAULT == "WEBGPU"), "runs out of memory in CI") - def test_conv_transpose2d(self): - BS, C1, H, W = 4, 16, 224//4, 224//4 - C2, K, S, P = 64, 7, 2, 1 - - # create in tinygrad - layer = ConvTranspose2d(C1, C2, kernel_size=K, stride=S, padding=P) - - # create in torch - with torch.no_grad(): - torch_layer = torch.nn.ConvTranspose2d(C1, C2, kernel_size=K, stride=S, padding=P).eval() - torch_layer.weight[:] = torch.tensor(layer.weight.numpy(), dtype=torch.float32) - torch_layer.bias[:] = torch.tensor(layer.bias.numpy(), dtype=torch.float32) - - # test - x = Tensor.uniform(BS, C1, H, W) - z = layer(x) - torch_x = torch.tensor(x.numpy()) - torch_z = torch_layer(torch_x) - np.testing.assert_allclose(z.numpy(), torch_z.detach().numpy(), atol=5e-4, rtol=1e-5) - - def test_groupnorm(self): - BS, H, W, C, G = 20, 10, 10, 6, 3 - - # create in tinygrad - layer = GroupNorm(G, C) - - # create in torch - with torch.no_grad(): - torch_layer = torch.nn.GroupNorm(G, C).eval() - torch_layer.weight[:] = torch.tensor(layer.weight.numpy(), dtype=torch.float32) - torch_layer.bias[:] = torch.tensor(layer.bias.numpy(), dtype=torch.float32) - - # test - x = Tensor.randn(BS, C, H, W) - z = layer(x) - torch_x = torch.tensor(x.numpy()) - torch_z = torch_layer(torch_x) - np.testing.assert_allclose(z.numpy(), torch_z.detach().numpy(), atol=5e-3, rtol=5e-3) - - def test_layernorm(self): - N, C, H, W = 20, 5, 10, 10 - - # create in tinygrad - layer = LayerNorm([H, W]) - - # create in torch - with torch.no_grad(): - torch_layer = torch.nn.LayerNorm([H, W]).eval() - torch_layer.weight[:] = torch.tensor(layer.weight.numpy(), dtype=torch.float32) - torch_layer.bias[:] = torch.tensor(layer.bias.numpy(), dtype=torch.float32) - - # test - x = Tensor.randn(N, C, H, W) - z = layer(x) - torch_x = torch.tensor(x.numpy()) - torch_z = torch_layer(torch_x) - np.testing.assert_allclose(z.numpy(), torch_z.detach().numpy(), atol=5e-3, rtol=5e-3) - - def test_layernorm_2d(self): - N, C, H, W = 20, 5, 10, 10 - - # create in tinygrad - layer = LayerNorm2d(C) - - # create in torch - with torch.no_grad(): - torch_layer = torch.nn.LayerNorm([C]).eval() - torch_layer.weight[:] = torch.tensor(layer.weight.numpy(), dtype=torch.float32) - torch_layer.bias[:] = torch.tensor(layer.bias.numpy(), dtype=torch.float32) - - # test - x = Tensor.randn(N, C, H, W) - z = layer(x) - torch_x = torch.tensor(x.numpy()) - torch_z = torch_layer(torch_x.permute(0,2,3,1)).permute(0,3,1,2) - - def test_instancenorm_2d(self): - N, C, H, W = 20, 5, 10, 10 - - # create in tinygrad - layer = InstanceNorm(C) - - # create in torch - with torch.no_grad(): - torch_layer = torch.nn.InstanceNorm2d(C, affine=True).eval() - torch_layer.weight[:] = torch.tensor(layer.weight.numpy(), dtype=torch.float32) - torch_layer.bias[:] = torch.tensor(layer.bias.numpy(), dtype=torch.float32) - - # test - x = Tensor.randn(N, C, H, W) - z = layer(x) - torch_x = torch.tensor(x.numpy()) - torch_z = torch_layer(torch_x) - np.testing.assert_allclose(z.numpy(), torch_z.detach().numpy(), atol=5e-3, rtol=5e-3) - np.testing.assert_allclose(z.numpy(), torch_z.detach().numpy(), atol=5e-3, rtol=5e-3) - - def test_instancenorm_3d(self): - N, C, D, H, W = 20, 5, 3, 10, 10 - - # create in tinygrad - layer = InstanceNorm(C) - - # create in torch - with torch.no_grad(): - torch_layer = torch.nn.InstanceNorm3d(C, affine=True).eval() - torch_layer.weight[:] = torch.tensor(layer.weight.numpy(), dtype=torch.float32) - torch_layer.bias[:] = torch.tensor(layer.bias.numpy(), dtype=torch.float32) - - # test - x = Tensor.randn(N, C, D, H, W) - z = layer(x) - torch_x = torch.tensor(x.numpy()) - torch_z = torch_layer(torch_x) - np.testing.assert_allclose(z.numpy(), torch_z.detach().numpy(), atol=5e-3, rtol=5e-3) - np.testing.assert_allclose(z.numpy(), torch_z.detach().numpy(), atol=5e-3, rtol=5e-3) - - def test_embedding(self): - B, T, C, VS = 4, 10, 20, 28 - - # create in tinygrad - layer = Embedding(VS, C) - - with torch.no_grad(): - torch_layer = torch.nn.Embedding(VS, C).eval() - torch_layer.weight[:] = torch.tensor(layer.weight.numpy(), dtype=torch.float32) - - # test - x = Tensor(np.random.randint(0, VS, (B, T)).astype(np.float32)) - z = layer(x) - torch_x = torch.tensor(x.numpy().astype(np.int32)) - torch_z = torch_layer(torch_x) - np.testing.assert_allclose(z.numpy(), torch_z.detach().numpy(), atol=1e-8, rtol=1e-8) - - # test with jit enabled - @TinyJit - def layer_jit(x): - return layer(x).realize() - - for _ in range(3): - x = Tensor(np.random.randint(0, VS, (B, T)).astype(np.float32)) - z = layer_jit(x) - torch_x = torch.tensor(x.numpy().astype(np.int32)) - torch_z = torch_layer(torch_x) - np.testing.assert_allclose(z.numpy(), torch_z.detach().numpy(), atol=1e-8, rtol=1e-8) - - -if __name__ == '__main__': - unittest.main() diff --git a/tinygrad_repo/test/test_ops.py b/tinygrad_repo/test/test_ops.py deleted file mode 100644 index edac7ab..0000000 --- a/tinygrad_repo/test/test_ops.py +++ /dev/null @@ -1,1245 +0,0 @@ -import torch -import time -import math -import numpy as np -import unittest -from tinygrad.tensor import Tensor -from tinygrad.helpers import getenv, IMAGE, DEBUG, CI, dtypes, Context, NOOPT -from tinygrad.ops import Device - -if CI: - import warnings - warnings.filterwarnings("ignore", message="Non-empty compiler output encountered") - -FORWARD_ONLY = getenv("FORWARD_ONLY", 0) -PRINT_TENSORS = getenv("PRINT_TENSORS", 0) -def helper_test_op(shps, torch_fxn, tinygrad_fxn=None, atol=1e-6, rtol=1e-3, grad_atol=1e-4, grad_rtol=1e-3, forward_only=False, vals=None, a=-0.5, b=3): - if tinygrad_fxn is None: tinygrad_fxn = torch_fxn - ts, tst = prepare_test_op(a, b, shps, vals, forward_only) - - st = time.monotonic() - out = torch_fxn(*ts) - torch_fp = time.monotonic() - st - - st = time.monotonic() - ret = tinygrad_fxn(*tst).realize() - tinygrad_fp = time.monotonic() - st - - def compare(s, x,y,atol,rtol): - if PRINT_TENSORS: print(s, x, y) - assert x.shape == y.shape, f"shape mismatch: tinygrad={x.shape} | torch={y.shape}" - try: - np.testing.assert_allclose(x,y, atol=atol, rtol=rtol) - except Exception: - raise Exception(f"{s} failed shape {x.shape}") - - if DEBUG >= 6: - np.set_printoptions(linewidth=200, suppress=True) - print(ret.numpy()) - print(out.detach().numpy()) - compare("forward pass", ret.numpy(), out.detach().numpy(), atol=atol, rtol=rtol) - - torch_fbp, tinygrad_fbp = np.nan, np.nan - if not forward_only and not FORWARD_ONLY: - st = time.monotonic() - (out+1).square().mean().backward() - torch_fbp = time.monotonic() - st - - st = time.monotonic() - (ret+1).square().mean().backward() - for tt in tst: tt.grad.realize() - tinygrad_fbp = time.monotonic() - st - - for i, (t, tt) in enumerate(zip(ts, tst)): - compare(f"backward pass tensor {i}", tt.grad.numpy(), t.grad.detach().numpy(), atol=grad_atol, rtol=grad_rtol) - - if not CI: print("\ntesting %40r torch/tinygrad fp: %.2f / %.2f ms bp: %.2f / %.2f ms " % (shps, torch_fp*1000, tinygrad_fp*1000, torch_fbp*1000, tinygrad_fbp*1000), end="") - -def prepare_test_op(a, b, shps, vals, forward_only=False): - torch.manual_seed(0) - np.random.seed(0) - if shps is None: ts = [torch.tensor(x, requires_grad=(not forward_only)) for x in vals] - else: ts = [torch.tensor((np.random.random(size=x) + a) * b, requires_grad=(not forward_only), dtype=torch.float32) for x in shps] - tst = [Tensor(x.detach().numpy(), requires_grad=(not forward_only and not FORWARD_ONLY)) for x in ts] - return ts, tst - -class TestOps(unittest.TestCase): - - def helper_test_exception(self, shps, torch_fxn, tinygrad_fxn, expected, exact=False, vals=None, a=-0.5, b=3): - ts, tst = prepare_test_op(a, b, shps, vals) - with self.assertRaises(expected) as torch_cm: - torch_fxn(*ts) - with self.assertRaises(expected) as tinygrad_cm: - tinygrad_fxn(*tst) - if exact: self.assertEqual(str(torch_cm.exception), str(tinygrad_cm.exception)) - if not CI: print("\ntesting %40r torch/tinygrad exception: %s / %s" % (shps, torch_cm.exception, tinygrad_cm.exception), end="") - - def test_full_like(self): - a = Tensor([[1,2,3],[4,5,6]]) - b = torch.tensor([[1,2,3],[4,5,6]]) - helper_test_op([], lambda: torch.full_like(b, 4), lambda: Tensor.full_like(a, 4), forward_only=True) - def test_full(self): - helper_test_op([], lambda: torch.full((45,65), 4), lambda: Tensor.full((45,65), 4), forward_only=True) - def test_zeros(self): - helper_test_op([], lambda: torch.zeros(45,65), lambda: Tensor.zeros(45,65), forward_only=True) - helper_test_op([], lambda: torch.zeros([45,65]), lambda: Tensor.zeros([45,65]), forward_only=True) - helper_test_op([], lambda: torch.zeros([]), lambda: Tensor.zeros([]), forward_only=True) - def test_zeros_like(self): - a = Tensor([[1,2,3],[4,5,6]]) - b = torch.tensor([[1,2,3],[4,5,6]]) - helper_test_op([], lambda: torch.zeros_like(b), lambda: Tensor.zeros_like(a), forward_only=True) - def test_empty_0(self): - helper_test_op([], lambda: torch.empty(45,65)*0/0, lambda: Tensor.empty(45,65)*0/0, forward_only=True) - def test_ones(self): - helper_test_op([], lambda: torch.ones(45,65), lambda: Tensor.ones(45,65), forward_only=True) - helper_test_op([], lambda: torch.ones([45,65]), lambda: Tensor.ones([45,65]), forward_only=True) - helper_test_op([], lambda: torch.ones([]), lambda: Tensor.ones([]), forward_only=True) - def test_ones_like(self): - a = Tensor([[1,2,3],[4,5,6]]) - b = torch.tensor([[1,2,3],[4,5,6]]) - helper_test_op([], lambda: torch.ones_like(b), lambda: Tensor.ones_like(a), forward_only=True) - def test_eye(self): - helper_test_op([], lambda: torch.eye(10), lambda: Tensor.eye(10), forward_only=True) - helper_test_op([], lambda: torch.eye(1), lambda: Tensor.eye(1), forward_only=True) - - def test_chunk(self): - tor = torch.arange(13).repeat(8, 1).chunk(6, 1) - ten = Tensor.arange(13).repeat((8, 1)).chunk(6, 1) - assert len(tor) == len(ten) - for i in range(len(tor)): - helper_test_op([], lambda: tor[i], lambda: ten[i], forward_only=True) - - tor = torch.arange(13).repeat(8, 1).chunk(6, 0) - ten = Tensor.arange(13).repeat((8, 1)).chunk(6, 0) - assert len(tor) == len(ten) - for i in range(len(tor)): - helper_test_op([], lambda: tor[i], lambda: ten[i], forward_only=True) - - tor = torch.arange(13).repeat(8, 1).chunk(3, -1) - ten = Tensor.arange(13).repeat((8, 1)).chunk(3, -1) - assert len(tor) == len(ten) - for i in range(len(tor)): - helper_test_op([], lambda: tor[i], lambda: ten[i], forward_only=True) - - tor = torch.arange(13).repeat(8, 3, 3).chunk(3, -2) - ten = Tensor.arange(13).repeat((8, 3, 3)).chunk(3, -2) - assert len(tor) == len(ten) - for i in range(len(tor)): - helper_test_op([], lambda: tor[i], lambda: ten[i], forward_only=True) - - def test_arange(self): - helper_test_op([], lambda: torch.arange(10), lambda: Tensor.arange(10), forward_only=True) - helper_test_op([], lambda: torch.arange(5, 10, 3), lambda: Tensor.arange(5, 10, 3), forward_only=True) - helper_test_op([], lambda: torch.arange(10, 5, -3), lambda: Tensor.arange(10, 5, -3), forward_only=True) - helper_test_op([], lambda: torch.arange(11, 5, -3), lambda: Tensor.arange(11, 5, -3), forward_only=True) - def test_arange_simple(self): - helper_test_op([], lambda: torch.arange(10), lambda: Tensor.arange(10), forward_only=True) - def test_arange_big(self): - helper_test_op([], lambda: torch.arange(256), lambda: Tensor.arange(256), forward_only=True) - - def test_where(self): - helper_test_op( - [(100,)], - lambda x: torch.where(x > 0.5, 4, 2), - lambda x: (x > 0.5).where(4, 2), forward_only=True) - - for shps in [[(8,),(1,),(1,)], [(10,10),(10,),(10,)], [(100,)]*3, [(10,10)]*3]: - helper_test_op( - shps, - lambda x, a, b: torch.where(x > 0.5, a, b), - lambda x, a, b: (x > 0.5).where(a, b), forward_only=True) - - def test_where_permute(self): - helper_test_op( - [(5, 5)], - lambda x: torch.where(x > 0.5, 4, 2).permute((1, 0)), - lambda x: (x > 0.5).where(4, 2).permute((1, 0)), forward_only=True) - - def _test_cmp(self, fxn, reverse=True): - for shps in [[(3, 4, 5), (3, 4, 5)], [(3, 4, 5), (5,)], [(5,), (3, 4, 5)]]: - helper_test_op(shps, fxn, fxn, forward_only=True) - helper_test_op(None, fxn, fxn, forward_only=True, vals=[[0.,1,2], [2.,1,0]]) - helper_test_op(None, lambda x,y: fxn(x,2), lambda x,y: fxn(x,2), forward_only=True, vals=[[0.,1,2], [2.,1,0]]) - helper_test_op(None, fxn, fxn, forward_only=True, vals=[[True, True, False], [False,True,False]]) - if reverse: helper_test_op(None, lambda x,y: fxn(2,y), lambda x,y: fxn(2,y), forward_only=True, vals=[[0.,1,2], [2.,1,0]]) - - def test_cmp_eq(self): self._test_cmp(lambda x,y: x==y, reverse=False) - def test_cmp_gt(self): self._test_cmp(lambda x,y: x>y) - def test_cmp_ge(self): self._test_cmp(lambda x,y: x>=y) - def test_cmp_lt(self): self._test_cmp(lambda x,y: x0, "no 1d dot for images") - def test_dot_1d(self): - helper_test_op([(65), (65)], lambda x,y: x.matmul(y), Tensor.dot, atol=1e-4) - helper_test_op([(65), (65,45)], lambda x,y: x.matmul(y), Tensor.dot, atol=1e-4) - helper_test_op([(45,65), (65)], lambda x,y: x.matmul(y), Tensor.dot, atol=1e-4) - helper_test_op([(32,45,65), (65)], lambda x,y: x.matmul(y), Tensor.dot, atol=1e-4) - helper_test_op([(65), (32,65,45)], lambda x,y: x.matmul(y), Tensor.dot, atol=1e-4) - self.helper_test_exception([(4), (1,2)], lambda x, y: x.matmul(y), Tensor.dot, expected=(RuntimeError, AssertionError)) - self.helper_test_exception([(2,1), (4)], lambda x, y: x.matmul(y), Tensor.dot, expected=(RuntimeError, AssertionError)) - self.helper_test_exception([(1), (4)], lambda x, y: x.matmul(y), Tensor.dot, expected=(RuntimeError, AssertionError)) - def test_dot(self): - helper_test_op([(45,65), (65,100)], lambda x,y: x.matmul(y), Tensor.dot, atol=1e-4) - helper_test_op([(32,45,65), (32,65,100)], lambda x,y: x.matmul(y), Tensor.dot, atol=1e-4) - self.helper_test_exception([(2, 4), (1, 3)], lambda x, y: x.matmul(y), Tensor.dot, expected=(RuntimeError, AssertionError)) - self.helper_test_exception([(2, 1), (4, 3)], lambda x, y: x.matmul(y), Tensor.dot, expected=(RuntimeError, AssertionError)) - with self.assertRaises(AssertionError): - a = Tensor(3.14) - a.matmul(a) - def test_simple_cumsum(self): - helper_test_op([(1024)], lambda x: torch.cumsum(x, dim=0), lambda x: Tensor.cumsum(x, axis=0), atol=1e-6) - def test_cumsum(self): - helper_test_op([(20)], lambda x: torch.cumsum(x, dim=0), lambda x: Tensor.cumsum(x, axis=0), atol=1e-6) - helper_test_op([(20,30)], lambda x: torch.cumsum(x, dim=0), lambda x: Tensor.cumsum(x, axis=0), atol=1e-6) - helper_test_op([(20,30)], lambda x: torch.cumsum(x, dim=1), lambda x: Tensor.cumsum(x, axis=1), atol=1e-6) - helper_test_op([(20,30,40)], lambda x: torch.cumsum(x, dim=2), lambda x: Tensor.cumsum(x, axis=2), atol=1e-6) - helper_test_op([(20,30,40)], lambda x: torch.cumsum(x, dim=-1), lambda x: Tensor.cumsum(x, axis=-1), atol=1e-6) - - def test_argmax(self): - self.assertEqual(torch.Tensor([2,2]).argmax().numpy(), Tensor([2,2]).argmax().numpy()) # check if returns first index for same max - helper_test_op([(10,20)], lambda x: x.argmax(), lambda x: x.argmax(), forward_only=True) - helper_test_op([(10,20)], lambda x: x.argmax(0, False), lambda x: x.argmax(0, False), forward_only=True) - helper_test_op([(10,20)], lambda x: x.argmax(1, False), lambda x: x.argmax(1, False), forward_only=True) - helper_test_op([(10,20)], lambda x: x.argmax(1, True), lambda x: x.argmax(1, True), forward_only=True) - def test_argmin(self): - self.assertEqual(torch.Tensor([2, 2]).argmin().numpy(), Tensor([2, 2]).argmin().numpy()) - helper_test_op([(10,20)], lambda x: x.argmin(), lambda x: x.argmin(), forward_only=True) - helper_test_op([(10,20)], lambda x: x.argmin(0, False), lambda x: x.argmin(0, False), forward_only=True) - helper_test_op([(10,20)], lambda x: x.argmin(1, False), lambda x: x.argmin(1, False), forward_only=True) - helper_test_op([(10,20)], lambda x: x.argmin(1, True), lambda x: x.argmin(1, True), forward_only=True) - - def test_matmul_simple(self): - helper_test_op([(4), (4,4)], lambda x,y: x.matmul(y), Tensor.dot, atol=1e-4) - def test_matmul(self): - helper_test_op([(64), (64,99)], lambda x,y: x.matmul(y), Tensor.dot, atol=1e-4) - - @unittest.skipIf(IMAGE>0, "no batched matmul on images") - def test_matmul_batched(self): - helper_test_op([(3), (1,3,3,5)], lambda x,y: x.matmul(y), Tensor.dot, atol=1e-4) - - @unittest.skipIf(IMAGE>0, "no batched matmul on images") - def test_matmul_batched_vector(self): - helper_test_op([(4,3), (1,3,3,5)], lambda x,y: x.matmul(y), Tensor.dot, atol=1e-4) - def test_small_gemm(self): - helper_test_op([(8,8), (8,8)], lambda x,y: x.matmul(y), lambda x,y: x@y, atol=1e-3) - def test_small_gemm_eye(self): - helper_test_op(None, lambda x,y: x.matmul(y), lambda x,y: x@y, atol=1e-3, vals=[np.eye(8).astype(np.float32), np.eye(8).astype(np.float32)]) - def test_gemm(self): - helper_test_op([(64,64), (64,64)], lambda x,y: x.matmul(y), Tensor.dot, atol=1e-3) - def test_big_gemm(self): - helper_test_op([(256,256), (256,256)], lambda x,y: x.matmul(y), Tensor.dot, atol=1e-3) - def test_broadcastdot(self): - helper_test_op([(10,45,65), (65,45)], lambda x,y: x @ y, Tensor.dot, atol=1e-4) - with self.assertRaises(AssertionError): - a = Tensor(3.14) - b = Tensor.ones(3,3) - a @ b - def test_multidot(self): - helper_test_op([(10,45,65), (10,65,45)], lambda x,y: x @ y, Tensor.dot, atol=1e-4) - helper_test_op([(3,3,45,65), (3,3,65,45)], lambda x,y: x @ y, Tensor.dot, atol=1e-4) - def test_sum_simple(self): - helper_test_op(None, lambda x: x.sum(), Tensor.sum, vals=[[1.,1.]]) - def test_sum_full(self): - helper_test_op([(16384)], lambda x: x.sum(), lambda x: x.sum()) - def test_sum_small_full(self): - helper_test_op([(45,5)], lambda x: x.sum(), Tensor.sum) - def test_sum_relu(self): - helper_test_op([(3,4,5)], lambda x: x.relu().sum().relu(), lambda x: x.relu().sum().relu()) - def test_sum(self): - helper_test_op([(45,3)], lambda x: x.sum(), Tensor.sum) - helper_test_op([(3,4,5,6)], lambda x: x.sum(axis=3), lambda x: Tensor.sum(x, axis=3)) - helper_test_op([(3,4,5,6)], lambda x: x.sum(axis=(1,3)), lambda x: Tensor.sum(x, axis=(1,3))) - helper_test_op([(3,4,5,6)], lambda x: x.sum(axis=(0,2)), lambda x: Tensor.sum(x, axis=(0,2))) - helper_test_op([(3,4,5,6)], lambda x: x.sum(axis=(1,2)), lambda x: Tensor.sum(x, axis=(1,2))) - helper_test_op([(3,4,5,6)], lambda x: x.sum(axis=1), lambda x: Tensor.sum(x, axis=1)) - helper_test_op([()], lambda x: x.sum(), Tensor.sum) - def test_min(self): - helper_test_op([(3,3)], lambda x: x.min(), Tensor.min) - helper_test_op([(45,3)], lambda x: x.min(), Tensor.min) - helper_test_op([(45,3)], lambda x: x.min().mul(0.5), lambda x: Tensor.min(x).mul(0.5)) - helper_test_op([()], lambda x: x.min(), Tensor.min) - def test_max(self): - helper_test_op([(45,3)], lambda x: x.max(), Tensor.max) - helper_test_op([(45,3)], lambda x: x.max().mul(0.5), lambda x: Tensor.max(x).mul(0.5)) - helper_test_op(None, lambda x: x.max().mul(0.5), lambda x: Tensor.max(x).mul(0.5), - vals=[ - [[1.0,1.0,0.0,1.0]], - ]) - helper_test_op([(3,4,5,6)], lambda x: x.max(axis=1)[0], lambda x: Tensor.max(x, axis=1)) - helper_test_op([()], lambda x: x.max(), Tensor.max) - def test_mean(self): - helper_test_op([(3,4,5,6)], lambda x: x.mean()) - helper_test_op([()], lambda x: x.mean()) - def test_mean_axis(self): - helper_test_op([(3,4,5,6)], lambda x: x.mean(axis=(1,2)), lambda x: Tensor.mean(x, axis=(1,2))) - def test_std(self): - helper_test_op([(45, 65, 85)], lambda x: torch.std(x), lambda x: Tensor.std(x)) - helper_test_op([(45, 65, 85)], lambda x: torch.std(x, dim=None, correction=0), lambda x: Tensor.std(x, correction=0)) - helper_test_op([(45, 65, 85)], lambda x: torch.std(x, dim=None, correction=5), lambda x: Tensor.std(x, correction=5)) - def test_std_axis(self): - helper_test_op([(45, 65, 85)], lambda x: torch.std(x, dim=0), lambda x: Tensor.std(x, axis=0)) - helper_test_op([(45, 65, 85)], lambda x: torch.std(x, dim=2), lambda x: Tensor.std(x, axis=2)) - helper_test_op([(45, 65, 85)], lambda x: torch.std(x, dim=[1, 2]), lambda x: Tensor.std(x, axis=[1, 2])) - helper_test_op([(45, 65, 85)], lambda x: torch.std(x, dim=None), lambda x: Tensor.std(x, axis=None)) - helper_test_op([(45, 65, 85)], lambda x: torch.std(x, correction=0, dim=0), lambda x: Tensor.std(x, axis=0, correction=0)) - helper_test_op([(45, 65, 85)], lambda x: torch.std(x, correction=0, dim=2), lambda x: Tensor.std(x, axis=2, correction=0)) - helper_test_op([(45, 65, 85)], lambda x: torch.std(x, correction=0, dim=[1, 2]), lambda x: Tensor.std(x, axis=[1, 2], correction=0)) - helper_test_op([(45, 65, 85)], lambda x: torch.std(x, correction=0, dim=None), lambda x: Tensor.std(x, axis=None, correction=0)) - def test_std_keepdim(self): - helper_test_op([(45, 65, 85)], lambda x: torch.std(x, dim=None, keepdim=True), lambda x: Tensor.std(x, keepdim=True)) - helper_test_op([(45, 65, 85)], lambda x: torch.std(x, dim=0, keepdim=True, correction=0), lambda x: Tensor.std(x, keepdim=True, correction=0, axis=0)) - def test_log_softmax(self): - helper_test_op([(45,65)], lambda x: torch.nn.LogSoftmax(dim=1)(x), Tensor.log_softmax, atol=1e-7, grad_atol=1e-7) - helper_test_op([()], lambda x: torch.nn.LogSoftmax(dim=0)(x), Tensor.log_softmax, atol=1e-7, grad_atol=1e-7) - def test_log_softmax_other_axis(self): - helper_test_op([(10,10,10)], lambda x: x.log_softmax(0), lambda x: x.log_softmax(0), atol=1e-7, grad_atol=1e-7) - helper_test_op([(10,10,10)], lambda x: x.log_softmax(1), lambda x: x.log_softmax(1), atol=1e-7, grad_atol=1e-7) - helper_test_op([(10,10,10)], lambda x: x.log_softmax(2), lambda x: x.log_softmax(2), atol=1e-7, grad_atol=1e-7) - def test_tanh(self): - helper_test_op([(45,65)], lambda x: x.tanh(), Tensor.tanh, atol=1e-6, grad_atol=1e-6) - helper_test_op([(45,65)], lambda x: x.tanh(), Tensor.tanh, atol=1e-6, grad_atol=1e-6, a=-100) - helper_test_op([()], lambda x: x.tanh(), Tensor.tanh, atol=1e-6, grad_atol=1e-6) - def test_hardtanh(self): - for val in range(10, 30, 5): - helper_test_op([(45,65)], lambda x: torch.nn.functional.hardtanh(x,-val, val), lambda x: x.hardtanh(-val, val), atol=1e-6, grad_atol=1e-6) - helper_test_op([()], lambda x: torch.nn.functional.hardtanh(x,-val, val), lambda x: x.hardtanh(-val, val), atol=1e-6, grad_atol=1e-6) - def test_topo_sort(self): - helper_test_op([(45,65)], lambda x: (x+x)*x, lambda x: x.add(x).mul(x), atol=1e-6, grad_atol=1e-6) - helper_test_op([()], lambda x: (x+x)*x, lambda x: x.add(x).mul(x), atol=1e-6, grad_atol=1e-6) - - def test_scalar_mul(self): - helper_test_op([(45,65)], lambda x: x*2, lambda x: x*2) - helper_test_op([()], lambda x: x*2, lambda x: x*2) - def test_scalar_rmul(self): - helper_test_op([(45,65)], lambda x: 2*x, lambda x: 2*x) - helper_test_op([()], lambda x: 2*x, lambda x: 2*x) - def test_scalar_sub(self): - helper_test_op([(45,65)], lambda x: x-2, lambda x: x-2) - helper_test_op([()], lambda x: x-2, lambda x: x-2) - def test_scalar_rsub(self): - helper_test_op([(45,65)], lambda x: 2-x, lambda x: 2-x) - helper_test_op([()], lambda x: 2-x, lambda x: 2-x) - def test_flip_eye_crash(self): - helper_test_op([], lambda: (torch.eye(10)@torch.eye(10).flip(0)), - lambda: (Tensor.eye(10)@Tensor.eye(10).flip(0)), forward_only=True) - - @unittest.skipIf(Device.DEFAULT == "WEBGPU", "this test uses more than 8 bufs passing the WEBGPU limit") #TODO: remove after #1461 - def test_broadcast_full(self): - for torch_op, tinygrad_op in [(torch.add, Tensor.add), (torch.sub, Tensor.sub), (torch.mul, Tensor.mul), - (torch.div, Tensor.div)]: #, (torch.pow, Tensor.pow)]: - for shapes in [((5,13,24,16), (5,1,24,1)), ((1,3,1,7,1), (2,1,5,1,8))]: - with self.subTest(op=torch_op.__name__, shapes=shapes): - helper_test_op(shapes, torch_op, tinygrad_op, a=-0.5 if tinygrad_op != Tensor.pow else 0.0) - - def test_broadcast_simple(self): - helper_test_op([(45,65), (45,1)], lambda x,y: x/y, lambda x,y: x/y) - helper_test_op([(45,65), ()], lambda x,y: x/y, lambda x,y: x/y) - - @unittest.skipIf(Device.DEFAULT == "WEBGPU", "this test uses more than 8 bufs passing the WEBGPU limit") #TODO: remove after #1461 - def test_broadcast_partial(self): - for torch_op, tinygrad_op in [(torch.add, Tensor.add), (torch.sub, Tensor.sub), (torch.mul, Tensor.mul), - (torch.div, Tensor.div)]: #, (torch.pow, Tensor.pow)]: - for shapes in [((1,32,32,32), (1,32,1,1)), ((5,13,24,16,2), (1,13,24,1,1)), - ((4,1), (4,5)), ((1,4), (5,4))]: - with self.subTest(op=torch_op.__name__, shapes=shapes): - # NOTE: ANE backwards? - helper_test_op(shapes, torch_op, tinygrad_op, a=-0.5 if tinygrad_op != Tensor.pow else 0.0) - - def test_slice_in_bounds_1dim(self): - helper_test_op([(3)], lambda x: x[1:3], lambda x: x[1:3]) - helper_test_op([(3)], lambda x: x[0:2], lambda x: x[0:2]) - helper_test_op([(3)], lambda x: x[-2:2], lambda x: x[-2:2]) - - def test_slice_on_0dim_tensor(self): - helper_test_op([()], lambda x: x[None], lambda x: x[None]) - - with self.assertRaises(IndexError): - a = Tensor(3.14) - a[0] - - def test_slice_int_indexing(self): - helper_test_op([(3)], lambda x: x[1], lambda x: x[1]) - helper_test_op([(3)], lambda x: x[-2], lambda x: x[-2]) - helper_test_op([(10,10)], lambda x: x[1], lambda x: x[1]) - helper_test_op([(3,3,3)], lambda x: x[1,1,1], lambda x: x[1,1,1]) - - def test_slice_in_bounds_multidim(self): - helper_test_op([(3,3,3)], lambda x: x[1:2], lambda x: x[1:2]) - helper_test_op([(3,3,3)], lambda x: x[1:2, 2], lambda x: x[1:2, 2]) - helper_test_op([(3,3,3)], lambda x: x[1:2, 1:2], lambda x: x[1:2, 1:2]) - helper_test_op([(3,3,3)], lambda x: x[1:2, 1:2, 0:-1], lambda x: x[1:2, 1:2, 0:-1]) - - def test_slice_with_none(self): - helper_test_op([(3,3,3)], lambda x: x[None], lambda x: x[None]) - helper_test_op([(3,3,3)], lambda x: x[1:2, None], lambda x: x[1:2, None]) - helper_test_op([(3,3,3)], lambda x: x[1:2, None, 1:2], lambda x: x[1:2, None, 1:2]) - helper_test_op([(3,3,3)], lambda x: x[1:2, 1:2, None, -1], lambda x: x[1:2, 1:2, None, -1]) - - def test_slice_one_endpoint_out_of_bounds(self): - helper_test_op([(3,3,3)], lambda x: x[0:4], lambda x: x[0:4]) - helper_test_op([(3,3,3)], lambda x: x[-6:4], lambda x: x[-6:4]) - helper_test_op([(3,3,3)], lambda x: x[1:50], lambda x: x[1:50]) - helper_test_op([(3,3,3)], lambda x: x[1:50, 1:2, -1], lambda x: x[1:50, 1:2, -1]) - - def test_slice_stride_gt_one(self): - helper_test_op([(7,5,10)], lambda x: x[::2, ::3, ::4], lambda x: x[::2, ::3, ::4]) - helper_test_op([(7,5,10)], lambda x: x[1:5:2, ::3, ::4], lambda x: x[1:5:2, ::3, ::4]) - helper_test_op([(7,5,10)], lambda x: x[1:5:2, 3, ::4], lambda x: x[1:5:2, 3, ::4]) - helper_test_op([(7,5,10)], lambda x: x[1:5:2, None, None, 3, None, ::4], lambda x: x[1:5:2, None, None, 3, None, ::4]) - - def test_slice_negative_strides(self): - # Torch doesn't support slicing with negative steps - a = np.random.randn(10, 10, 10).astype(np.float32) - t = Tensor(a) - np.testing.assert_allclose(a[::-1], t[::-1].numpy()) - np.testing.assert_allclose(a[::-2], t[::-2].numpy()) - np.testing.assert_allclose(a[:, 2:0:-1], t[:, 2:0:-1].numpy()) - np.testing.assert_allclose(a[:, 2:0:-1, 3:1:-2], t[:, 2:0:-1, 3:1:-2].numpy()) - np.testing.assert_allclose(a[4:0:-3, 2:0:-1, -1:-5:-2], t[4:0:-3, 2:0:-1, -1:-5:-2].numpy()) - - @unittest.skip("No suppport for tensors with 0s in shape") - def test_slice_both_endpoints_out_of_bounds(self): - helper_test_op([(3,3,3)], lambda x: x[5:10], lambda x: x[5:10], forward_only=True) - helper_test_op([(3,3,3)], lambda x: x[-15:-7], lambda x: x[-15:-7], forward_only=True) - - @unittest.skip("No suppport for tensors with 0s in shape") - def test_slice_start_gt_end(self): - helper_test_op([(3,3,3)], lambda x: x[-2:2], lambda x: x[-2:2], forward_only=True) - helper_test_op([(3,3,3)], lambda x: x[-2:-5], lambda x: x[-2:-5], forward_only=True) - - @unittest.skip("No suppport for tensors with 0s in shape") - def test_slice_empty(self): - helper_test_op([(10,10)], lambda x: x[1:1], lambda x: x[1:1], forward_only=True) - - @unittest.skip("No suppport for tensors with 0s in shape") - def test_slice_zero_in_shape(self): - helper_test_op([(10,10)], lambda x: x[1:1], lambda x: x[1:1]) # x.shape = (0, 10) - helper_test_op([(3,3,3)], lambda x: x[-2:-5], lambda x: x[-2:-5]) # x.shape = (0, 3, 3) - - def test_slice_errors(self): - a = Tensor.ones(4, 3) - with self.assertRaises(IndexError): - a[1, 77, 77, 77] # IndexError: (finds too many indices before the out of bounds) - a[1, 77] # IndexError: (out of bounds). - a[0, -77] - a[..., ...] # IndexError: only single ellipsis - - def test_slice_ellipsis(self): - helper_test_op([(3,3,3,3)], lambda x: x[..., 0], lambda x: x[..., 0]) - helper_test_op([(3,3,3,3)], lambda x: x[0, ...], lambda x: x[0, ...]) - helper_test_op([(3,3,3,3)], lambda x: x[0, ..., 0], lambda x: x[0, ..., 0]) - helper_test_op([(3,3,3,3)], lambda x: x[0:3, ..., 2:3], lambda x: x[0:3, ..., 2:3]) - helper_test_op([(3,3,3,3)], lambda x: x[None, 0:3, ..., 0, None], lambda x: x[None, 0:3, ..., 0, None]) - - def test_pad2d(self): - helper_test_op([(3,3,3,3)], lambda x: torch.nn.functional.pad(x, (1,2,3,4)), lambda x: x.pad2d(padding=(1,2,3,4))) - helper_test_op([(3,3,3,3)], lambda x: torch.nn.functional.pad(x, (-1,2,-3,4)), lambda x: x.pad2d(padding=(-1,2,-3,4))) - helper_test_op([(3,3,3,3)], lambda x: torch.nn.functional.pad(x, (1,2,3,4), value=5), lambda x: x.pad2d(padding=(1,2,3,4),value=5)) - helper_test_op([(3,3,3,3)], lambda x: torch.nn.functional.pad(x, (-1,2,-3,4), value=5), lambda x: x.pad2d(padding=(-1,2,-3,4),value=5)) - def test_pad(self): - helper_test_op([(3,3)], lambda x: torch.nn.functional.pad(x, (1,2,3,4)),lambda x: x.pad(((3,4),(1,2)))) - helper_test_op([(3,3)], lambda x: torch.nn.functional.pad(x, (1,2,3,4), value=5), lambda x: x.pad(((3,4), (1,2)), value=5)) - helper_test_op([(3,3)], lambda x: torch.nn.functional.pad(x, (1,2,3,4), value=float("inf")), lambda x: x.pad(((3,4), (1,2)), value=float("inf"))) - helper_test_op([(3,3)], lambda x: torch.nn.functional.pad(x, (1,2,3,4), value=float("-inf")), lambda x: x.pad(((3,4), (1,2)), value=float("-inf"))) - - def test_transpose(self): - helper_test_op([(3,3,3)], lambda x: x.transpose(1,2), lambda x: x.transpose(1,2)) - helper_test_op([(3,3,3)], lambda x: x.transpose(0,2), lambda x: x.transpose(0,2)) - helper_test_op([(1,2,3,4)], lambda x: x.movedim((3,0,2,1),(0,1,2,3)), lambda x: x.permute(order=(3,0,2,1))) - helper_test_op([(3,4,5,6)], lambda x: x.movedim((3,2,1,0),(0,1,2,3)), lambda x: x.permute(order=(3,2,1,0))) - helper_test_op([()], lambda x: x.permute(()), lambda x: x.permute(())) - - def test_reshape(self): - helper_test_op([(4,3,6,6)], lambda x: torch.reshape(x, (-1,3,6,6)), lambda x: x.reshape(shape=(-1,3,6,6))) - helper_test_op([(4,3,6,6)], lambda x: torch.reshape(x, (-1,1,6,6)), lambda x: x.reshape(shape=(-1,1,6,6))) - helper_test_op([()], lambda x: torch.reshape(x, []), lambda x: x.reshape([])) - helper_test_op([(1,)], lambda x: torch.reshape(x, []), lambda x: x.reshape([])) - helper_test_op([()], lambda x: torch.reshape(x, [1]), lambda x: x.reshape([1])) - - with self.assertRaises(AssertionError): - x = Tensor.ones((4,3,6,6)) - x.reshape([]) - - def test_flip(self): - helper_test_op([(4,3,6,6)], lambda x: torch.flip(x, (0,)), lambda x: x.flip(axis=(0,))) - helper_test_op([(4,3,6,6)], lambda x: torch.flip(x, (0,1)), lambda x: x.flip(axis=(0,1))) - helper_test_op([(4,3,6,6)], lambda x: torch.flip(x, (0,1,3)), lambda x: x.flip(axis=(0,1,3))) - helper_test_op([(4,3,6,6)], lambda x: torch.flip(x, (3,)), lambda x: x.flip(axis=(3,))) - helper_test_op([(4,3,6,6)], lambda x: torch.flip(x, (0,1,3)).flip((0,)), lambda x: x.flip(axis=(0,1,3)).flip(0)) - helper_test_op([(4,3,6,6)], lambda x: torch.flip(x, (3,)), lambda x: x.flip(axis=(-1,))) - helper_test_op([()], lambda x: torch.flip(x, ()), lambda x: x.flip(axis=())) - helper_test_op([(1,)], lambda x: torch.flip(x, ()), lambda x: x.flip(axis=())) - helper_test_op([(4, 3, 6, 6)], lambda x: torch.flip(x, ()), lambda x: x.flip(axis=())) - - def test_squeeze(self): - helper_test_op([(1,3,6,6)], lambda x: torch.squeeze(x, 0), lambda x: x.squeeze(dim=0)) - helper_test_op([(4,3,1,6)], lambda x: torch.squeeze(x, 1), lambda x: x.squeeze(dim=1)) - helper_test_op([(4,3,6,6)], lambda x: torch.squeeze(x, 3), lambda x: x.squeeze(dim=3)) - self.helper_test_exception([(4,3,6,6)], lambda x: torch.squeeze(x, 50), lambda x: x.squeeze(dim=50), expected=IndexError, exact=True) - self.helper_test_exception([(4,3,6,6)], lambda x: torch.squeeze(x, -50), lambda x: x.squeeze(dim=-50), expected=IndexError, exact=True) - helper_test_op([(4,3,6,1)], lambda x: torch.squeeze(x, -1), lambda x: x.squeeze(dim=-1)) - helper_test_op([(4,3,6,6)], lambda x: torch.squeeze(x), lambda x: x.squeeze()) - helper_test_op([(1,3,6,6)], lambda x: torch.squeeze(x), lambda x: x.squeeze()) - helper_test_op([(2,3,1)], lambda x: torch.squeeze(x), lambda x: x.squeeze()) - helper_test_op([()], lambda x: torch.squeeze(x, -1), lambda x: x.squeeze(dim=-1)) - helper_test_op([()], lambda x: torch.squeeze(x, 0), lambda x: x.squeeze(dim=0)) - self.helper_test_exception([()], lambda x: torch.squeeze(x, 10), lambda x: x.squeeze(dim=10), expected=IndexError, exact=True) - helper_test_op([()], lambda x: torch.squeeze(x), lambda x: x.squeeze()) - - def test_unsqueeze(self): - helper_test_op([(4,3,6,6)], lambda x: torch.unsqueeze(x, 0), lambda x: x.unsqueeze(dim=0)) - helper_test_op([(4,3,6,6)], lambda x: torch.unsqueeze(x, 4), lambda x: x.unsqueeze(dim=4)) - helper_test_op([(4,3,6,6)], lambda x: torch.unsqueeze(x, -1), lambda x: x.unsqueeze(dim=-1)) - helper_test_op([(4,3,6,6)], lambda x: torch.unsqueeze(x, -3), lambda x: x.unsqueeze(dim=-3)) - helper_test_op([()], lambda x: torch.unsqueeze(x, 0), lambda x: x.unsqueeze(dim=0)) - - def test_flatten(self): - for axis in range(3): - helper_test_op([(4,3,6,6)], lambda x: torch.flatten(x, start_dim=axis), lambda x: x.flatten(axis)) - helper_test_op([()], lambda x: x.flatten(), lambda x: x.flatten()) - helper_test_op([(1,)], lambda x: x.flatten(), lambda x: x.flatten()) - - def test_detach(self): - helper_test_op([(4,3,6,6)], lambda x: x.detach(), lambda x: x.detach(), forward_only=True) - helper_test_op([()], lambda x: x.detach(), lambda x: x.detach(), forward_only=True) - - def test_expand(self): - arg = (4,3,2,6) - helper_test_op([(4,3,1,6)], lambda x: x.expand(arg), lambda x: x.expand(shape=arg)) - helper_test_op([()], lambda x: x.expand([]), lambda x: x.expand(shape=[])) - - @unittest.skip("very slow") - def test_sd_big_conv(self): - # internal shape (1, 1, 512, 62, 62, 512, 3, 3) overflows a int - helper_test_op([(1,256,64,64), (512,256,3,3)], - lambda x,w: torch.nn.functional.conv2d(x, w), - lambda x,w: x.conv2d(w), atol=1e-2) - - @unittest.skip("slow") - def test_large_bs_conv(self): - # large batch size can cause OpenCL image to exceed max image height on macOS - # (or cause the conv kernel to overflow short sampling coords) - helper_test_op([(4096,3,3,3), (1,3,3,3)], - lambda x,w: torch.nn.functional.conv2d(x, w), - lambda x,w: x.conv2d(w), atol=1e-4, rtol=1e-2) - - @unittest.skip("slow") - def test_large_ic_conv(self): - # large input channel count can cause OpenCL image to exceed max image width on macOS - helper_test_op([(1,2048,3,3), (1,2048,3,3)], - lambda x,w: torch.nn.functional.conv2d(x, w), - lambda x,w: x.conv2d(w), atol=1e-4) - - def test_biased_conv2d(self): - C = 8 - helper_test_op([(1,C,5,5), (C,C,1,1), (C,)], - lambda x,w,b: torch.nn.functional.conv2d(torch.nn.functional.conv2d(x,w,b).relu(),w,b), - lambda x,w,b: Tensor.conv2d(x,w,b).relu().conv2d(w,b), atol=1e-4) - - def test_simple_conv2d(self): - helper_test_op([(1,4,9,9), (4,4,3,3)], - lambda x,w: torch.nn.functional.conv2d(x,w).relu(), - lambda x,w: Tensor.conv2d(x,w).relu(), atol=1e-4, grad_rtol=1e-5) - - def test_simple_conv2d_noopt(self): - # useful with IMAGE enabled - with Context(NOOPT=1): - self.test_simple_conv2d() - - @unittest.skipIf(IMAGE>0, "no conv3d on images") - def test_simple_conv3d(self): - helper_test_op([(1,4,9,9,9), (4,4,3,3,3)], - lambda x,w: torch.nn.functional.conv3d(x,w).relu(), - lambda x,w: Tensor.conv2d(x,w).relu(), atol=1e-4, grad_rtol=1e-5) - - @unittest.skipIf(IMAGE>0, "no conv3d on images") - def test_padded_conv3d(self): - helper_test_op([(1,4,9,9,9), (4,4,3,3,3)], - lambda x,w: torch.nn.functional.conv3d(x,w,padding=1).relu(), - lambda x,w: Tensor.conv2d(x,w,padding=[1,1,1,1,1,1]).relu(), atol=1e-4, grad_rtol=1e-5) - - def test_simple_conv2d_m4(self): - helper_test_op([(1,16,18,18), (16,16,3,3)], - lambda x,w: torch.nn.functional.conv2d(x,w).relu(), - lambda x,w: Tensor.conv2d(x,w).relu(), atol=1e-4, grad_rtol=1e-5) - - def test_simple_conv2d_1x1(self): - helper_test_op([(1,4,9,9), (4,4,1,1)], - lambda x,w: torch.nn.functional.conv2d(x,w).relu(), - lambda x,w: Tensor.conv2d(x,w).relu(), atol=1e-4, grad_rtol=1e-5) - - def test_simple_conv2d_1x1_m4(self): - helper_test_op([(1,16,32,32), (16,16,1,1)], - lambda x,w: torch.nn.functional.conv2d(x,w).relu(), - lambda x,w: Tensor.conv2d(x,w).relu(), atol=1e-4, grad_rtol=1e-5) - - def test_nested_conv2d(self): - helper_test_op([(1,32,9,9), (32,32,3,3), (32,32,3,3)], - lambda x,w1,w2: torch.nn.functional.conv2d(torch.nn.functional.conv2d(x,w1).relu(), w2).relu(), - lambda x,w1,w2: x.conv2d(w1).relu().conv2d(w2).relu(), atol=1e-4, grad_rtol=1e-5) - - # expect reduce nodes == 3 - def test_simple_conv2d_nhwc(self): - # weights (from tf): filter_height x filter_width x in_channels x out_channels - helper_test_op([(2,9,9,10), (3,3,10,20)], - lambda x,w: torch.nn.functional.conv2d(x.permute(0,3,1,2),w.permute(3,2,0,1)).relu(), - lambda x,w: Tensor.conv2d(x.permute(0,3,1,2),w.permute(3,2,0,1)).relu(), atol=1e-4, grad_rtol=1e-5) - - def test_simple_conv2d_batched(self): - helper_test_op([(2,4,9,9), (4,4,3,3)], - lambda x,w: torch.nn.functional.conv2d(x,w).relu(), - lambda x,w: Tensor.conv2d(x,w).relu(), atol=1e-4, grad_rtol=1e-5) - - # conv transpose - - def test_simple_conv_transpose2d(self): - helper_test_op([(2,4,9,9), (4,4,3,3)], - lambda x,w: torch.nn.functional.conv_transpose2d(x,w).relu(), - lambda x,w: Tensor.conv_transpose2d(x,w).relu(), atol=1e-4, grad_rtol=1e-5) - - def test_bias_conv_transpose2d(self): - helper_test_op([(2,4,9,9), (4,4,3,3), (4,)], - lambda x,w,b: torch.nn.functional.conv_transpose2d(x,w,b).relu(), - lambda x,w,b: Tensor.conv_transpose2d(x,w,b).relu(), atol=1e-4, grad_rtol=1e-5) - - def test_grouped_conv_transpose2d(self): - helper_test_op([(2,4,9,9), (4,4,3,3)], - lambda x,w: torch.nn.functional.conv_transpose2d(x,w,groups=2).relu(), - lambda x,w: Tensor.conv_transpose2d(x,w,groups=2).relu(), atol=1e-4, grad_rtol=1e-5) - - def test_padded_conv_transpose2d(self): - for padding in [(1,2), (2,1), 2, 1, 0]: - helper_test_op([(2,4,9,9), (4,4,3,3)], - lambda x,w: torch.nn.functional.conv_transpose2d(x,w,padding=padding).relu(), - lambda x,w: Tensor.conv_transpose2d(x,w,padding=padding).relu(), atol=1e-4, grad_rtol=1e-5) - - def test_dilated_conv_transpose2d(self): - for dilation in [(1,2), (2,1), 2, 1]: - helper_test_op([(2,4,9,9), (4,4,3,3)], - lambda x,w: torch.nn.functional.conv_transpose2d(x,w,dilation=dilation).relu(), - lambda x,w: Tensor.conv_transpose2d(x,w,dilation=dilation).relu(), atol=1e-4, grad_rtol=1e-5) - - def test_strided_conv_transpose2d(self): - for stride in [(2,1), (1,2), 1]: - helper_test_op([(2,4,4,5), (4,4,3,3)], - lambda x,w: torch.nn.functional.conv_transpose2d(x,w, stride=stride).relu(), - lambda x,w: Tensor.conv_transpose2d(x,w,stride=stride).relu(), atol=1e-4, grad_rtol=1e-5) - - @unittest.skipIf(Device.DEFAULT == "METAL" and CI, "broken in METAL CI") - def test_output_padded_conv_transpose2d(self): - for output_padding, stride in [((1,1), (2,3)), ((2,1), (3,2))]: - helper_test_op([(2,4,6,5), (4,4,3,3),(4,)], - lambda x,w,b: torch.nn.functional.conv_transpose2d(x,w,b,output_padding=output_padding,stride=stride).relu(), - lambda x,w,b: Tensor.conv_transpose2d(x,w,b,output_padding=output_padding,stride=stride).relu(), atol=1e-4, grad_rtol=1e-5) - - @unittest.skipIf(IMAGE>0, "no conv3d on images") - def test_simple_conv_transpose3d(self): - helper_test_op([(2,4,9,9,9), (4,4,3,3,3)], - lambda x,w: torch.nn.functional.conv_transpose3d(x,w).relu(), - lambda x,w: Tensor.conv_transpose2d(x,w).relu(), atol=1e-4, grad_rtol=1e-5) - - @unittest.skipIf((IMAGE>0), "no conv1d on images") - def test_conv1d(self): - for bs in [1,8]: - for cin in [1,3]: - for H in [1,2,5]: - for groups in [1,3] if cin == 3 and H == 5 else [1]: - with self.subTest(batch_size=bs, channels=cin, groups=groups, height=H): - helper_test_op([(bs,cin,11), (6,cin//groups,H)], - lambda x,w: torch.nn.functional.conv1d(x,w,groups=groups).relu(), - lambda x,w: Tensor.conv2d(x,w,groups=groups).relu(), atol=1e-4, grad_rtol=1e-5) - - @unittest.skipIf(IMAGE>0, "no conv1d on images") - def test_simple_padding_conv1d(self): - bs = 6 - cin = 2 - groups = 1 - H = 5 - p = (1,1) - helper_test_op([(bs,cin,11), (6,cin//groups,H)], - lambda x,w: torch.nn.functional.conv1d(torch.nn.functional.pad(x, p),w).relu(), - lambda x,w: Tensor.conv2d(x,w,padding=p).relu(), atol=1e-4) - - @unittest.skipIf(IMAGE>0, "no conv1d on images") - def test_strided_conv1d_simple(self): - bs, H = 2, 3 - helper_test_op([(bs,1,5), (1,1,H)], - lambda x,w: torch.nn.functional.conv1d(x,w,stride=2).relu(), - lambda x,w: Tensor.conv2d(x,w,stride=2).relu(), atol=1e-4) - - @unittest.skipIf(IMAGE>0, "no conv1d on images") - def test_asymmetric_padding_conv1d(self): - for p in [(0,1), (2,1), (2,0)]: - with self.subTest(padding := p): - for n in [3,4]: - for k in [2]: - helper_test_op([(1,1,n), (1,1,k)], - lambda x,w: torch.nn.functional.conv1d(torch.nn.functional.pad(x, p),w).relu(), - lambda x,w: Tensor.conv2d(x,w,padding=p).relu(), atol=1e-4) - helper_test_op([(1,1,n), (1,1,k)], - lambda x,w: torch.nn.functional.conv1d(torch.nn.functional.pad(x, p),w).relu(), - lambda x,w: Tensor.conv2d(x,w,padding=p).relu(), atol=1e-4) - - def _test_conv2d(self, bs=1, cin=1): - for H in [1,2,3]: - for W in [1,2,3,5]: - for groups in [1,3] if cin == 3 and H == 3 and W == 3 else [1]: - with self.subTest(batch_size=bs, channels=cin, groups=groups, height=H, width=W): - helper_test_op([(bs,cin,11,7), (6,cin//groups,H,W)], - lambda x,w: torch.nn.functional.conv2d(x,w,groups=groups).relu(), - lambda x,w: Tensor.conv2d(x,w,groups=groups).relu(), atol=1e-4, grad_rtol=1e-5) - def test_conv2d(self): self._test_conv2d(bs=1, cin=3) - def test_conv2d_bs_4_cin_3(self): self._test_conv2d(bs=4, cin=3) - def test_conv2d_bs_1_cin_1(self): self._test_conv2d(bs=1, cin=1) - def test_conv2d_bs_4_cin_1(self): self._test_conv2d(bs=4, cin=1) - - def test_large_input_conv2d(self): - bs = 4 - cin = 16 - groups = 1 - H = 5 - W = 2 - helper_test_op([(bs,cin,64,64), (6,cin//groups,H,W)], - lambda x,w: torch.nn.functional.conv2d(x,w,groups=groups).relu(), - # needed to relax tolerance on NVIDIA - lambda x,w: Tensor.conv2d(x,w,groups=groups).relu(), atol=1e-3, grad_rtol=1e-5) - - def test_simple_grouped_conv2d(self): - bs = 1 - groups = 2 - rcout = 1 - cin = 2 - helper_test_op([(bs,groups*cin,1,1), (groups*rcout,cin,1,1)], - lambda x,w: torch.nn.functional.conv2d(x,w,groups=groups).relu(), - lambda x,w: Tensor.conv2d(x,w,groups=groups).relu(), atol=1e-4, grad_rtol=1e-5) - - def test_medium_grouped_conv2d(self): - bs = 1 - groups = 2 - rcout = 2 - cin = 2 - helper_test_op([(bs,groups*cin,1,1), (groups*rcout,cin,1,1)], - lambda x,w: torch.nn.functional.conv2d(x,w,groups=groups).relu(), - lambda x,w: Tensor.conv2d(x,w,groups=groups).relu(), atol=1e-4, grad_rtol=1e-5) - - def test_depthwise_conv2d(self): - bs = 1 - groups = 32 - rcout = 1 - cin = 1 - helper_test_op([(bs,groups*cin,32,32), (groups*rcout,cin,1,1)], - lambda x,w: torch.nn.functional.conv2d(x,w,groups=groups).relu(), - lambda x,w: Tensor.conv2d(x,w,groups=groups).relu(), atol=1e-4, grad_rtol=1e-5) - - def test_grouped_conv2d(self): - bs = 4 - groups = 5 - rcout = 7 - cin = 3 - helper_test_op([(bs,groups*cin,5,5), (groups*rcout,cin,3,3)], - lambda x,w: torch.nn.functional.conv2d(x,w,groups=groups).relu(), - lambda x,w: Tensor.conv2d(x,w,groups=groups).relu(), atol=1e-4, grad_rtol=1e-5) - - def test_fancy_conv2d(self): - bs = 2 - cin = 3 - cout = 1 - groups = 3 - H,W = 3,3 - helper_test_op([(bs,cin,11,28), (groups*cout,cin//groups,H,W)], - lambda x,w: torch.nn.functional.conv2d(x,w,groups=groups).relu(), - lambda x,w: Tensor.conv2d(x,w,groups=groups).relu(), atol=1e-4, grad_rtol=1e-5) - - def test_strided_conv2d_simple(self): - bs,H,W = 2,3,1 - helper_test_op([(bs,1,5,1), (1,1,H,W)], - lambda x,w: torch.nn.functional.conv2d(x,w,stride=2).relu(), - lambda x,w: Tensor.conv2d(x,w,stride=2).relu(), atol=1e-4) - - def test_strided_conv2d(self): - bs = 4 - cin = 3 - H,W = 3,3 - with self.subTest(stride := 2): - helper_test_op([(bs,cin,11,28), (4,cin,H,W)], - lambda x,w: torch.nn.functional.conv2d(x,w,stride=2).relu(), - lambda x,w: Tensor.conv2d(x,w,stride=stride).relu(), atol=1e-4) - with self.subTest(stride := (2,1)): - helper_test_op([(bs,cin,11,28), (4,cin,H,W)], - lambda x,w: torch.nn.functional.conv2d(x,w,stride=stride).relu(), - lambda x,w: Tensor.conv2d(x,w,stride=(2,1)).relu(), atol=1e-4) - - def test_negative_padding_conv2d(self): - n,k = 10, 3 - helper_test_op([(1,1,n,n), (1,1,k,k)], - lambda x,w: torch.nn.functional.conv2d(x[:, :, 1:-1, 1:-1],w).relu(), - lambda x,w: Tensor.conv2d(x,w,padding=-1).relu(), atol=1e-4) - helper_test_op([(1,1,n,n), (1,1,k,k)], - lambda x,w: torch.nn.functional.conv2d(x[:, :, 1:, 1:],w).relu(), - lambda x,w: Tensor.conv2d(x,w,padding=(-1,0,-1,0)).relu(), atol=1e-4) - - def test_simple_padding_conv2d(self): - p = (1,1,1,1) - helper_test_op(None, - lambda x,w: torch.nn.functional.conv2d(torch.nn.functional.pad(x, p),w).relu(), - lambda x,w: Tensor.conv2d(x,w,padding=p).relu(), atol=1e-4, vals=[[[[[2.,3.]]]], [[[[1.]]]]]) - - def test_asymmetric_padding_conv2d(self): - for p in [(0,1,0,1), (2,1,2,1), (2,0,2,1)]: - with self.subTest(padding := p): - for n in [3,4]: - for k in [2]: - helper_test_op([(1,1,n,n), (1,1,k,k)], - lambda x,w: torch.nn.functional.conv2d(torch.nn.functional.pad(x, p),w).relu(), - lambda x,w: Tensor.conv2d(x,w,padding=p).relu(), atol=1e-4) - helper_test_op([(1,1,n,n), (1,1,k,k)], - lambda x,w: torch.nn.functional.conv2d(torch.nn.functional.pad(x, p),w).relu(), - lambda x,w: Tensor.conv2d(x,w,padding=p).relu(), atol=1e-4) - - @unittest.skipIf(Device.DEFAULT == "METAL" and CI, "broken in METAL CI") - def test_padded_conv2d_p21(self): - bs,cin,H,W,padding = 4, 3, 3, 3, (2,1) - helper_test_op([(bs,cin,11,28), (4,cin,H,W)], - lambda x,w: torch.nn.functional.conv2d(x,w,padding=padding).relu(), - lambda x,w: Tensor.conv2d(x,w,padding=padding).relu(), atol=1e-4) - - @unittest.skipIf(Device.DEFAULT == "METAL" and CI, "broken in METAL CI") - def test_padded_conv2d_p22(self): - bs,cin,H,W,padding = 4, 3, 3, 3, (2,2) - helper_test_op([(bs,cin,11,28), (4,cin,H,W)], - lambda x,w: torch.nn.functional.conv2d(x,w,padding=padding).relu(), - lambda x,w: Tensor.conv2d(x,w,padding=padding).relu(), atol=1e-4) - - def test_padded_conv2d_1x1(self): - bs,cin,H,W,padding = 4, 3, 1, 1, 2 - helper_test_op([(bs,cin,11,28), (4,cin,H,W)], - lambda x,w: torch.nn.functional.conv2d(x,w,padding=padding).relu(), - lambda x,w: Tensor.conv2d(x,w,padding=padding).relu(), atol=1e-4) - - def test_padded_conv2d_bs1(self): - bs,cin,H,W,padding = 1, 3, 3, 3, 1 - helper_test_op([(bs,cin,11,28), (4,cin,H,W)], - lambda x,w: torch.nn.functional.conv2d(x,w,padding=padding).relu(), - lambda x,w: Tensor.conv2d(x,w,padding=padding).relu(), atol=1e-4) - - def test_padding_add(self): - helper_test_op([(64,64), (60,60)], - lambda x,w: x+torch.nn.functional.pad(w, (2,2,2,2)), - lambda x,w: x+w.pad2d((2,2,2,2))) - - def test_dilated_conv2d(self): - bs = 4 - cin = 3 - H,W = 3,3 - for d in [2, (2,1)]: - with self.subTest(dilation := d): - helper_test_op([(bs,cin,11,28), (4,cin,H,W)], - lambda x,w: torch.nn.functional.conv2d(x,w,dilation=dilation).relu(), - lambda x,w: Tensor.conv2d(x,w,dilation=dilation).relu(), atol=1e-4) - - def test_maxpool2d_simple(self): - ksz = (2,2) - helper_test_op([(1,1,2,3)], - lambda x: torch.nn.functional.max_pool2d(x, kernel_size=ksz), - lambda x: Tensor.max_pool2d(x, kernel_size=ksz)) - - def test_maxpool2d(self): - for ksz in [(2,2), (3,3), 2, 3, (3,2), (5,5), (5,1)]: - with self.subTest(kernel_size=ksz): - helper_test_op([(32,2,110,28)], - lambda x: torch.nn.functional.max_pool2d(x, kernel_size=ksz), - lambda x: Tensor.max_pool2d(x, kernel_size=ksz)) - - def test_maxpool2d_bigger_stride(self): - for stride in [(2,3), (3,2), 2, 3]: - with self.subTest(stride=stride): - helper_test_op([(32,2,110,28)], - lambda x: torch.nn.functional.max_pool2d(x, kernel_size=(2,2), stride=stride), - lambda x: Tensor.max_pool2d(x, kernel_size=(2,2), stride=stride)) - - @unittest.skipIf(Device.DEFAULT == "CUDA", "CUDA fails on this") - def test_maxpool2d_unit_stride(self): - helper_test_op([(32,2,110,28)], - lambda x: torch.nn.functional.max_pool2d(x, kernel_size=(5,5), stride=1), - lambda x: Tensor.max_pool2d(x, kernel_size=(5,5), stride=1)) - - def test_maxpool2d_smaller_stride(self): - for stride in [(2,3), (3,2), 2, 3]: - with self.subTest(stride=stride): - helper_test_op([(32,2,110,28)], - lambda x: torch.nn.functional.max_pool2d(x, kernel_size=(5,5), stride=stride), - lambda x: Tensor.max_pool2d(x, kernel_size=(5,5), stride=stride)) - - def test_maxpool2d_dilation(self): - for dilation in [(2, 3), (3, 2), 2, 3]: - helper_test_op([(32,2,110,28)], - lambda x: torch.nn.functional.max_pool2d(x, kernel_size=(5,5), dilation=dilation), - lambda x: Tensor.max_pool2d(x, kernel_size=(5,5), dilation=dilation)) - - def test_avgpool2d(self): - shape = (32,2,111,28) - for ksz in [(2,2), (3,3), (3,2), (5,5), (5,1)]: - with self.subTest(kernel_size=ksz): - helper_test_op([shape], - lambda x: torch.nn.functional.avg_pool2d(x, kernel_size=ksz), - lambda x: Tensor.avg_pool2d(x, kernel_size=ksz), rtol=1e-5) - - def test_global_avgpool2d(self): - helper_test_op([(32,2,111,28)], - lambda x: torch.nn.functional.avg_pool2d(x, kernel_size=(111,28)), - lambda x: Tensor.avg_pool2d(x, kernel_size=(111,28)), rtol=1e-5) - - def test_cat(self): - for dim in range(-2, 3): - helper_test_op([(45,65,9), (45,65,9), (45,65,9)], lambda x,y,z: torch.cat((x,y,z), dim), lambda x,y,z: x.cat(y, z, dim=dim)) - - with self.assertRaises(AssertionError): - a = Tensor(3.14) - a.cat(a) - - def test_multicat(self): - for dim in range(-1, 2): - helper_test_op([(45,65), (45,65), (45,65)], lambda x,y,z: torch.cat((x,y,z), dim), lambda x,y,z: x.cat(y, z, dim=dim)) - - def test_stack(self): - x = Tensor.randn(45, 65, 3) - - for dim in range(-1, 3): - helper_test_op([(45, 65, 3), (45, 65, 3), (45, 65, 3)], lambda x, y, z: torch.stack((x, y, z), dim=dim), lambda x, y, z: Tensor.stack([x, y, z], dim=dim)) - - with self.assertRaises(IndexError): - Tensor.stack([x], dim=77) - - a = Tensor(3.14) - np.testing.assert_allclose(Tensor.stack([a, a]).numpy(), Tensor([3.14, 3.14]).numpy()) - - def test_repeat(self): - x = Tensor.randn(4, 6, 3) - base_repeats = [2, 4, 3] - - for reps in [[], [4], [2, 1], [3, 2, 2]]: - repeats = base_repeats + reps - helper_test_op([(4, 6, 3)], lambda x: x.repeat(*repeats), lambda x: x.repeat(repeats)) - helper_test_op([()], lambda x: x.repeat(*repeats), lambda x: x.repeat(repeats)) - - with self.assertRaises(AssertionError): - x.repeat((2, 4)) - - with self.assertRaises(AssertionError): - x.repeat((2, 0, 4)) - - def test_clip(self): - helper_test_op([(45,65)], lambda x: x.clip(-2.3, 1.2), lambda x: x.clip(-2.3, 1.2)) - - def test_matvecmat(self): - helper_test_op([(1,128), (128,128), (128,128)], lambda x,y,z: (x@y).relu()@z, atol=1e-4) - - def test_matvec(self): - helper_test_op([(1,128), (128,128)], lambda x,y: (x@y).relu(), atol=1e-4) - - # this was the failure in llama early realizing freqs_cis - def test_double_slice(self): - helper_test_op([(4,4)], lambda x: x[:, 1:2][1:2]) - helper_test_op([(4,4)], lambda x: x[1:3][1:2]) - helper_test_op([(4,4)], lambda x: x[:, 1:2][0:1]) - helper_test_op([(4,4)], lambda x: x[:, 1:2][:, 0:1]) - - @unittest.skip("this test is broken #862") - def test_max_inf(self): - n = Tensor([1, float("nan")]).max().numpy() - assert math.isnan(n.item()), f"{n.item()} is not nan" - - def test_inf_where(self): - x = Tensor.full((3, 3), float("inf")) - n = (x < 0).where(x, 1).numpy() - assert np.all(n == 1.) - - def _get_index_randoms(self): - # indices cannot have gradient - # TODO currently does not support IndexError for out of bounds idx values - a = torch.randint(low=-1, high=1, size=(2,1,1,1,1,1), dtype=torch.int64, requires_grad=False) - b = torch.randint(high=1, size=(1,3,1,1,1,1), dtype=torch.int64, requires_grad=False) - c = torch.randint(low=-5, high=5, size=(1,1,4,1,1,1), dtype=torch.int64, requires_grad=False) - d = torch.randint(high=4, size=(2,1,1,5,1,1), dtype=torch.int64, requires_grad=False) - e = torch.randint(high=1, size=(1,1,1,1,6,1), dtype=torch.int64, requires_grad=False) - i, j, k, o, p = [Tensor(tor.detach().numpy().astype(np.int32), dtype=dtypes.int32, requires_grad=False) for tor in [a,b,c,d,e]] - return a,b,c,d,e,i,j,k,o,p - - def test_slice_fancy_indexing_no_dim_collapse(self): - a,b,c,d,e,i,j,k,o,p = self._get_index_randoms() - # no dim collapse from int or dim injection from None - helper_test_op([(2,5,6,5,3,4)], lambda x: x[a,b,c,d,e], lambda x: x[i,j,k,o,p]) - helper_test_op([(2,5,6,5,3,4)], lambda x: x[:,b,c,d,:], lambda x: x[:,j,k,o,:]) - helper_test_op([(2,5,6,5,3,4)], lambda x: x[a,b,...], lambda x: x[i,j,...]) - helper_test_op([(2,5,6,5,3,4)], lambda x: x[a,...,e], lambda x: x[i,...,p]) - helper_test_op([(2,5,6,5,3,4)], lambda x: x[...,c,:,e], lambda x: x[...,k,:,p]) - - def test_slice_fancy_indexing_dim_collapse_int(self): - a,b,c,d,e,i,j,k,o,p = self._get_index_randoms() - # dim collapse from int - helper_test_op([(2,5,6,5,3,4)], lambda x: x[1,b,c,d,e], lambda x: x[1,j,k,o,p]) - helper_test_op([(2,5,6,5,3,4)], lambda x: x[a,b,3,d,e], lambda x: x[i,j,3,o,p]) - helper_test_op([(2,5,6,5,3,4)], lambda x: x[1,b,2,d,2], lambda x: x[1,j,2,o,2]) - helper_test_op([(2,5,6,5,3,4)], lambda x: x[a,2,2,2,e], lambda x: x[i,2,2,2,p]) - helper_test_op([(2,5,6,5,3,4)], lambda x: x[1,:,3:11:2,d,0:2], lambda x: x[1,:,3:11:2,o,0:2]) - - def test_slice_fancy_indexing_dim_inject_none(self): - a,b,c,d,e,i,j,k,o,p = self._get_index_randoms() - # dim injection from None - helper_test_op([(2,5,6,5,3,4)], lambda x: x[None,b,c,d,e], lambda x: x[None,j,k,o,p]) - helper_test_op([(2,5,6,5,3,4)], lambda x: x[a,b,c,d,None], lambda x: x[i,j,k,o,None]) - helper_test_op([(2,5,6,5,3,4)], lambda x: x[a,b,None,d,e], lambda x: x[i,j,None,o,p]) - helper_test_op([(2,5,6,5,3,4)], lambda x: x[None,b,c,d,None], lambda x: x[None,j,k,o,None]) - helper_test_op([(2,5,6,5,3,4)], lambda x: x[a,:,None,d,e], lambda x: x[i,:,None,o,p]) - - def test_slice_fancy_indexing_dim_inject_and_collapse(self): - a,b,c,d,e,i,j,k,o,p = self._get_index_randoms() - # dim injection and collapse - helper_test_op([(2,5,6,5,3,4)], lambda x: x[1,b,None,d,1], lambda x: x[1,j,None,o,1]) - helper_test_op([(2,5,6,5,3,4)], lambda x: x[None,b,2,d,None], lambda x: x[None,j,2,o,None]) - helper_test_op([(2,5,6,5,3,4)], lambda x: x[...,1,d,None], lambda x: x[...,1,o,None]) - - def test_slice_fancy_indexing_with_idx(self): - # indexing using idx with different dim - helper_test_op([(2,3)], lambda x: x[torch.tensor([[0,0,0],[0,0,0]]), torch.tensor(1)], lambda x: x[Tensor([[0,0,0],[0,0,0]]), Tensor(1)]) - helper_test_op([(2,3)], lambda x: x[torch.tensor([1]), torch.tensor([[0,0,0],[0,0,0]])], lambda x: x[Tensor([1]), Tensor([[0,0,0],[0,0,0]])]) - - def test_gather(self): - # indices cannot have gradient - # indices cannot be negative (torch gather) - b = torch.randint(3, size=[3,4,5], dtype=torch.int64, requires_grad=False) - a = Tensor(b.detach().numpy().astype(np.int32), dtype=dtypes.int32, requires_grad=False) - helper_test_op([(4,5,6)], lambda x: x.gather(index=b, dim=0), lambda x: x.gather(idx=a, dim=0)) - helper_test_op([(4,5,6)], lambda x: x.gather(index=b, dim=1), lambda x: x.gather(idx=a, dim=1)) - helper_test_op([(4,5,6)], lambda x: x.gather(index=b, dim=2), lambda x: x.gather(idx=a, dim=2)) - helper_test_op([(3,4,5)], lambda x: x.gather(index=b, dim=0), lambda x: x.gather(idx=a, dim=0)) - self.helper_test_exception([(4,5,6)], lambda x: x.gather(index=torch.tensor([1], dtype=torch.int64), dim=0), lambda x: x.gather(idx=Tensor([1], dtype=dtypes.int32), dim=0), expected=(RuntimeError, AssertionError)) - self.helper_test_exception([(2,1,1)], lambda x: x.gather(index=b, dim=0), lambda x: x.gather(idx=a, dim=0), expected=(RuntimeError, AssertionError)) - - def test_scaled_product_attention(self): - helper_test_op([(32,8,16,64), (32,8,16,64), (32,8,16,64)], lambda x,y,z: torch.nn.functional.scaled_dot_product_attention(x,y,z), lambda x,y,z: Tensor.scaled_dot_product_attention(x,y,z)) - helper_test_op([(32,8,16,64), (32,8,16,64), (32,8,16,64), (32,8,16,16)], lambda x,y,z,m: torch.nn.functional.scaled_dot_product_attention(x,y,z,attn_mask=m), lambda x,y,z,m: Tensor.scaled_dot_product_attention(x,y,z,attn_mask=m)) - helper_test_op([(32,8,16,64), (32,8,16,64), (32,8,16,64)], lambda x,y,z: torch.nn.functional.scaled_dot_product_attention(x,y,z,is_causal=True), lambda x,y,z: Tensor.scaled_dot_product_attention(x,y,z,is_causal=True)) - - def test_binary_crossentropy(self): - helper_test_op([(32,10), (32,10)], lambda x,y: torch.nn.functional.binary_cross_entropy(x.sigmoid(),torch.clip(y,0,1)), lambda x,y: x.sigmoid().binary_crossentropy(y.clip(0,1))) - helper_test_op([(32,10), (32,10)], lambda x,y: torch.nn.functional.binary_cross_entropy_with_logits(x,torch.clip(y,0,1)), lambda x,y: x.binary_crossentropy_logits(y.clip(0,1))) - helper_test_op([(32,10), (32,10)], lambda x,y: torch.nn.functional.binary_cross_entropy_with_logits(x,torch.clip(y,0,1)), lambda x,y: x.sigmoid().binary_crossentropy(y.clip(0,1))) - helper_test_op([(32,10), (32,10)], lambda x,y: torch.nn.functional.binary_cross_entropy(x.sigmoid(),torch.clip(y,0,1)), lambda x,y: x.binary_crossentropy_logits(y.clip(0,1))) - -if __name__ == '__main__': - np.random.seed(1337) - unittest.main(verbosity=2) diff --git a/tinygrad_repo/test/test_optim.py b/tinygrad_repo/test/test_optim.py deleted file mode 100644 index df1e53f..0000000 --- a/tinygrad_repo/test/test_optim.py +++ /dev/null @@ -1,98 +0,0 @@ -import numpy as np -import torch -import unittest -from tinygrad.tensor import Tensor -from tinygrad.nn.optim import Adam, SGD, AdamW -import pytest - -pytestmark = pytest.mark.exclude_cuda - -np.random.seed(1337) -x_init = np.random.randn(1,4).astype(np.float32) -W_init = np.random.randn(4,4).astype(np.float32) -m_init = np.random.randn(1,4).astype(np.float32) - -class TinyNet: - def __init__(self, tensor): - self.x = tensor(x_init.copy(), requires_grad=True) - self.W = tensor(W_init.copy(), requires_grad=True) - self.m = tensor(m_init.copy()) - - def forward(self): - out = self.x.matmul(self.W).relu() - # print(out.detach().numpy()) - out = out.log_softmax(1) - out = out.mul(self.m).add(self.m).sum() - return out - -def step(tensor, optim, steps=1, kwargs={}): - net = TinyNet(tensor) - optim = optim([net.x, net.W], **kwargs) - for _ in range(steps): - out = net.forward() - optim.zero_grad() - out.backward() - optim.step() - return net.x.detach().numpy(), net.W.detach().numpy() - -class TestOptim(unittest.TestCase): - - def _test_optim(self, tinygrad_optim, torch_optim, steps, opts, atol, rtol): - for x,y in zip(step(Tensor, tinygrad_optim, steps, kwargs=opts), - step(torch.tensor, torch_optim, steps, kwargs=opts)): - np.testing.assert_allclose(x, y, atol=atol, rtol=rtol) - - def _test_sgd(self, steps, opts, atol, rtol): self._test_optim(SGD, torch.optim.SGD, steps, opts, atol, rtol) - def _test_adam(self, steps, opts, atol, rtol): self._test_optim(Adam, torch.optim.Adam, steps, opts, atol, rtol) - def _test_adamw(self, steps, opts, atol, rtol): self._test_optim(AdamW, torch.optim.AdamW, steps, opts, atol, rtol) - - def test_sgd(self): self._test_sgd(1, {'lr': 0.001}, 1e-6, 0) - def test_sgd_high_lr(self): self._test_sgd(1, {'lr': 10}, 1e-6, 1e-5) - def test_sgd_wd(self): self._test_sgd(1, {'lr': 0.001, 'weight_decay': 0.1}, 1e-6, 0) - def test_sgd_high_lr_wd(self): self._test_sgd(1, {'lr': 10, 'weight_decay': 0.1}, 1e-6, 1e-5) - - def test_multistep_sgd(self): self._test_sgd(10, {'lr': 0.001}, 1e-6, 0) - def test_multistep_sgd_high_lr(self): self._test_sgd(10, {'lr': 10}, 1e-6, 3e-4) - def test_multistep_sgd_wd(self): self._test_sgd(10, {'lr': 0.001, 'weight_decay': 0.1}, 1e-6, 0) - def test_multistep_sgd_high_lr_wd(self): self._test_sgd(10, {'lr': 9, 'weight_decay': 0.1}, 1e-6, 3e-4) - - def test_multistep_sgd_momentum(self): self._test_sgd(10, {'lr': 0.001, 'momentum': 0.9}, 1e-6, 0) - def test_multistep_sgd_high_lr_momentum(self): self._test_sgd(10, {'lr': 10, 'momentum': 0.9}, 1e-5, 3e-4) - def test_multistep_sgd_momentum_wd(self): self._test_sgd(10, {'lr': 0.001, 'momentum': 0.9, 'weight_decay': 0.1}, 1e-6, 0) - def test_multistep_sgd_high_lr_momentum_wd(self): self._test_sgd(10, {'lr': 10, 'momentum': 0.9, 'weight_decay': 0.1}, 1e-5, 3e-4) - - def test_multistep_sgd_nesterov_momentum(self): self._test_sgd(10, {'lr': 0.001, 'momentum': 0.9, 'nesterov': True}, 1e-5, 0) - def test_multistep_sgd_high_lr_nesterov_momentum(self): self._test_sgd(10, {'lr': 10, 'momentum': 0.9, 'nesterov': True}, 1e-5, 3e-4) - def test_multistep_sgd_nesterov_momentum_wd(self): self._test_sgd(10, {'lr': 0.001, 'momentum': 0.9, 'nesterov': True, 'weight_decay': 0.1}, 1e-5, 0) - def test_multistep_sgd_high_lr_nesterov_momentum_wd(self): self._test_sgd(10, {'lr': 9, 'momentum': 0.9, 'nesterov': True, 'weight_decay': 0.1}, 1e-5, 3e-4) - - def test_adam(self): self._test_adam(1, {'lr': 0.001}, 1e-5, 0) - def test_adam_high_lr(self): self._test_adam(1, {'lr': 10}, 1e-4, 1e-4) - def test_adamw(self): self._test_adamw(1, {'lr': 0.001}, 1e-5, 0) - def test_adamw_high_lr(self): self._test_adamw(1, {'lr': 10}, 1e-4, 1e-4) - - def test_multistep_adam(self): self._test_adam(10, {'lr': 0.001}, 1e-5, 0) - def test_multistep_adam_high_lr(self): self._test_adam(10, {'lr': 10}, 2e-4, 5e-4) - - def test_multistep_adamw(self): self._test_adamw(10, {'lr': 0.001}, 1e-5, 0) - def test_multistep_adamw_high_lr(self): self._test_adamw(10, {'lr': 10}, 5e-4, 2e-3) - - def test_duped_weights(self): - for Opt in [Adam, AdamW, SGD]: - losses = [] - for i in range(2): - w = Tensor(x_init.copy()) - opt = Opt([w], lr=0.1) if i == 0 else Opt([w, w], lr=0.1) - - loss = None - for _ in range(3): - loss = w.sum() - opt.zero_grad() - loss.backward() - opt.step() - losses.append(loss.numpy()) - - np.testing.assert_allclose(losses[0], losses[1], atol=1e-4, rtol=0) - -if __name__ == '__main__': - unittest.main() \ No newline at end of file diff --git a/tinygrad_repo/test/test_randomness.py b/tinygrad_repo/test/test_randomness.py deleted file mode 100644 index cf1b018..0000000 --- a/tinygrad_repo/test/test_randomness.py +++ /dev/null @@ -1,115 +0,0 @@ -import math -import unittest -import numpy as np -import torch -from tinygrad.tensor import Tensor -import tinygrad.nn as nn -import pytest -from tinygrad.helpers import dtypes -from functools import partial - -pytestmark = pytest.mark.webgpu - -# https://gist.github.com/devries/11405101 -def ksprob(a): - fac, total, termbf = 2.0, 0.0, 0.0 - a2 = -2.0 * a * a - for j in range(1, 101): - term = fac * math.exp(a2 * j * j) - total += term - if math.fabs(term) <= 0.001 * termbf or math.fabs(term) <= 1e-8 * total: - return total - fac = -fac - termbf = math.fabs(term) - return 1.0 - -def kstest(l1, l2): - n1, n2 = len(l1), len(l2) - l1.sort() - l2.sort() - j1, j2, d, fn1, fn2 = 0, 0, 0.0, 0.0, 0.0 - while j1 < n1 and j2 < n2: - d1, d2 = l1[j1], l2[j2] - if d1 <= d2: - fn1 = (float(j1) + 1.0) / float(n1) - j1 += 1 - if d2 <= d1: - fn2 = (float(j2) + 1.0) / float(n2) - j2 += 1 - dtemp = math.fabs(fn2 - fn1) - if dtemp > d: - d = dtemp - ne = float(n1 * n2) / float(n1 + n2) - nesq = math.sqrt(ne) - prob = ksprob((nesq + 0.12 + 0.11 / nesq) * d) - return prob - -def equal_distribution(tiny_func, torch_func=None, numpy_func=None, shape=(20, 23), alpha=0.05): - Tensor.manual_seed(1337) - torch.manual_seed(1337) - np.random.seed(1337) - assert not (torch_func is None and numpy_func is None), "no function to compare with" - x = tiny_func(*shape).numpy().flatten() - if numpy_func is not None: y = numpy_func(shape).flatten() - if torch_func is not None: z = torch_func(shape).numpy().flatten() - return (numpy_func is None or kstest(x, y) >= alpha) and (torch_func is None or kstest(x, z) >= alpha) - -def normal_test(func, shape=(20, 23), alpha=0.05): return equal_distribution(func, numpy_func=lambda x: np.random.randn(*x), shape=shape, alpha=alpha) - -class TestRandomness(unittest.TestCase): - def test_rand(self): - self.assertFalse(normal_test(Tensor.rand)) - self.assertTrue(equal_distribution(Tensor.rand, torch.rand, lambda x: np.random.rand(*x))) - - def test_randn(self): - self.assertTrue(normal_test(Tensor.randn)) - self.assertTrue(equal_distribution(Tensor.randn, torch.randn, lambda x: np.random.randn(*x))) - - def test_normal(self): - self.assertTrue(normal_test(Tensor.normal)) - self.assertTrue(equal_distribution(Tensor.normal, lambda x: torch.nn.init.normal_(torch.empty(x), mean=0, std=1), lambda x: np.random.normal(loc=0, scale=1, size=x))) - - def test_uniform(self): - self.assertFalse(normal_test(Tensor.uniform)) - self.assertTrue(equal_distribution(Tensor.uniform, lambda x: torch.nn.init.uniform_(torch.empty(x)), lambda x: np.random.uniform(size=x))) - self.assertTrue(equal_distribution(partial(Tensor.uniform, low=-100, high=100, dtype=dtypes.int32), numpy_func=lambda x: np.random.randint(low=-100, high=100, size=x))) - - def test_scaled_uniform(self): - self.assertFalse(normal_test(Tensor.scaled_uniform)) - self.assertTrue(equal_distribution(Tensor.scaled_uniform, lambda x: torch.nn.init.uniform_(torch.empty(x), a=-1, b=1) / math.sqrt(math.prod(x)), lambda x: np.random.uniform(-1, 1, size=x) / math.sqrt(math.prod(x)))) - - def test_glorot_uniform(self): - self.assertFalse(normal_test(Tensor.glorot_uniform)) - self.assertTrue(equal_distribution(Tensor.glorot_uniform, lambda x: torch.nn.init.xavier_uniform_(torch.empty(x)), lambda x: np.random.uniform(-1, 1, size=x) * math.sqrt(6 / (x[0] + math.prod(x[1:]))))) - - def test_kaiming_uniform(self): - Tensor.manual_seed(1337) - torch.manual_seed(1337) - np.random.seed(1337) - for shape in [(128, 64, 3, 3), (20, 24)]: - self.assertTrue(equal_distribution(Tensor.kaiming_uniform, lambda x: torch.nn.init.kaiming_uniform_(torch.empty(x)), shape=shape)) - - def test_kaiming_normal(self): - Tensor.manual_seed(1337) - torch.manual_seed(1337) - np.random.seed(1337) - for shape in [(128, 64, 3, 3), (20, 24)]: - self.assertTrue(equal_distribution(Tensor.kaiming_normal, lambda x: torch.nn.init.kaiming_normal_(torch.empty(x)), shape=shape)) - - def test_conv2d_init(self): - params = (128, 256, (3,3)) - assert equal_distribution(lambda *_: nn.Conv2d(*params).weight, lambda _: torch.nn.Conv2d(*params).weight.detach()) - assert equal_distribution(lambda *_: nn.Conv2d(*params).bias, lambda _: torch.nn.Conv2d(*params).bias.detach()) - - def test_linear_init(self): - params = (64, 64) - assert equal_distribution(lambda *_: nn.Linear(*params).weight, lambda _: torch.nn.Linear(*params).weight.detach()) - assert equal_distribution(lambda *_: nn.Linear(*params).bias, lambda _: torch.nn.Linear(*params).bias.detach()) - - def test_bn_init(self): - params = (64,) - assert equal_distribution(lambda *_: nn.BatchNorm2d(*params).weight, lambda _: torch.nn.BatchNorm2d(*params).weight.detach()) - assert equal_distribution(lambda *_: nn.BatchNorm2d(*params).bias, lambda _: torch.nn.BatchNorm2d(*params).bias.detach()) - -if __name__ == "__main__": - unittest.main() diff --git a/tinygrad_repo/test/test_schedule.py b/tinygrad_repo/test/test_schedule.py deleted file mode 100644 index 32af9ea..0000000 --- a/tinygrad_repo/test/test_schedule.py +++ /dev/null @@ -1,335 +0,0 @@ -# this will be the new test_ops for the next level -# schedule confirms the right things are capable of fusing -# NOTE: this has overlap with external_test_opt.py - -import unittest -from typing import List, Optional -from tinygrad.tensor import Tensor -from tinygrad.ops import LoadOps, Device, Compiled -from tinygrad.helpers import DEBUG, dtypes -from tinygrad.codegen.linearizer import Linearizer -from tinygrad.graph import log_schedule_item, print_tree -from tinygrad import nn - -def check_schedule(t:Tensor, allowed:int, to_prerealize:Optional[List[Tensor]]=None, filter_loadops=True): - seen = set() - if to_prerealize: - for pre in to_prerealize: - for s in pre.lazydata.schedule(seen.copy()): - log_schedule_item(s) - seen.add(s.out) - sched = t.lazydata.schedule(seen) - for s in sched: log_schedule_item(s) - if filter_loadops: sched = [s for s in sched if s.ast.op not in LoadOps] - if len(sched) != allowed: print(f"SCHEDULE ISSUE, expecting {allowed} got {len(sched)}") - if len(sched) != allowed or DEBUG >= 3: - for i, s in enumerate(sched): - print("op", i) - print_tree(s.ast) - assert len(sched) == allowed - # test the (non loadops) ops linearize - for s in sched: - if s.ast.op in LoadOps: continue - l = Linearizer(s.ast) - l.hand_coded_optimizations() - l.linearize() - -class TestSchedule(unittest.TestCase): - def test_basic_binop_fusion(self): - a = Tensor.empty(10) - b = Tensor.empty(10) - c = Tensor.empty(10) - d = a+b+c - check_schedule(d, 1) - - def test_basic_binop_fusion_deep(self): - a = Tensor.empty(10) - b = Tensor.empty(10) - c = Tensor.empty(10) - d = Tensor.empty(10) - e = a+b+c+d - check_schedule(e, 1) - - def test_mulacc_fusion(self): - a = Tensor.empty(10) - b = Tensor.empty(10) - c = (a*b).sum() - check_schedule(c, 1) - - def test_mulacc_relu_fusion(self): - a = Tensor.empty(10) - b = Tensor.empty(10) - c = (a*b).sum().relu() - check_schedule(c, 1) - - def test_binop_reshape_fusion(self): - a = Tensor.empty(10) - b = Tensor.empty(10) - c = Tensor.empty(5,2) - d = (a+b).reshape(5,2)+c - check_schedule(d, 1) - - def test_binop_permute_fusion(self): - a = Tensor.empty(2,5) - b = Tensor.empty(2,5) - c = Tensor.empty(5,2) - d = (a+b).permute(1,0)+c - check_schedule(d, 1) - - @unittest.skipIf(not isinstance(Device[Device.DEFAULT], Compiled) or Device.DEFAULT == "LLVM", "only test for compiled backends") - def test_constants_are_embedded(self): - a = Tensor.empty(3,3) * 2 - check_schedule(a, 2, filter_loadops=False) - - def test_binop_elu_fusion(self): - a = Tensor.empty(10) - b = a.elu() - check_schedule(b, 1) - - def test_binop_reshape_reduce_fusion(self): - a = Tensor.empty(100) - b = Tensor.empty(100) - c = (a+b).reshape(10, 10).sum(axis=0, keepdim=True) - check_schedule(c, 1) - - def test_reduce_reshape_binop_fusion(self): - a = Tensor.empty(10,10) - b = Tensor.empty(10) - c = a.sum(axis=0) + b - check_schedule(c, 1) - - @unittest.skip("not pushing permutes through reduces") - def test_reduce_permute_binop_fusion(self): - a = Tensor.empty(10,10,10) - b = Tensor.empty(10,10,1) - c = a.sum(axis=0, keepdim=True).permute(2,1,0) + b - check_schedule(c, 1) - - def test_binop_early_reshape_reduce_fusion(self): - a = Tensor.empty(100) - b = Tensor.empty(100) - c = Tensor.empty(10,10) - d = ((a+b).reshape(10,10) + c).sum(axis=0) - check_schedule(d, 1) - - def test_diamond_folded(self): - a = Tensor.empty(10) - b = Tensor.empty(10) - c = Tensor.empty(10) - d = Tensor.empty(10) - ab = a+b - e = (ab+c) + (ab+d) - check_schedule(e, 1) - - def test_cache_binaryop(self): - a = Tensor.empty(10) - b = Tensor.empty(10) - c = a+b - d = a+b - check_schedule(d, 0, [c]) - - @unittest.skip("failing in old lazy") - def test_cache_binaryop_reshaped(self): - a = Tensor.empty(10) - b = Tensor.empty(10) - c = a+b - d = a.reshape(10,1)+b.reshape(10,1) - check_schedule(d, 0, [c]) - - def test_cache_binaryop_transpose(self): - a = Tensor.empty(10,10) - b = Tensor.empty(10,10) - c = (a.T*b.T).T #.contiguous() - d = a*b - check_schedule(d, 0, [c]) - - def test_cache_two_reduceops(self): - a = Tensor.empty(10) - b = a.sum() - c = a.sum() - bc = b+c - check_schedule(bc, 1) - - def test_fold_double_unary(self): - y = Tensor.empty(2) - out = y.sum(keepdim=True).sqrt().__neg__() - check_schedule(out, 1) - - #@unittest.skip("may want to reconsider this") - def test_fold_batchnorm(self): - with Tensor.train(): - img = Tensor.empty(1,32,4,4) - bn = nn.BatchNorm2d(32, track_running_stats=False) - out = bn(img) - check_schedule(out, 3) - - def test_fold_conv_relu(self): - c1 = nn.Conv2d(3,16,3) - - # run - img = Tensor.ones(2,3,64,64) - out = c1(img).relu() - check_schedule(out, 1, [c1.weight, c1.bias]) - - def test_fold_conv_elu(self): - c1 = nn.Conv2d(3,16,3) - - # run - img = Tensor.rand(2,3,64,64) - out = c1(img).elu() - check_schedule(out, 1, [c1.weight, c1.bias]) - - def test_two_sum(self): - img = Tensor.empty(64,64) - x = (img.sum(0) + img.sum(1)) - out = x.relu() - del x # is 3 without this - check_schedule(out, 2) - - @unittest.skip("failing in old lazy") - def test_push_permute_through_reshape(self): - a = Tensor.empty(16,16) - b = Tensor.empty(16,16) - c = (a+b).reshape(4,4,4,4).permute(2,3,0,1).contiguous() - check_schedule(c, 1) - - @unittest.skip("failing in old lazy") - def test_push_permute_through_reshape_alt(self): - a = Tensor.empty(4,4,4,4) - b = Tensor.empty(4,4,4,4) - c = (a+b).reshape(16,16).permute(1,0).contiguous() - check_schedule(c, 1) - - def test_no_binop_rerun(self): - a = Tensor.empty(16) - b = Tensor.empty(16) - c = a+b - d = (a+b).reshape(16,1) - check_schedule(d, 0, [c]) - - def test_multi_permute_should_collapse(self): - a = Tensor.empty(4,4,4,4) - b = Tensor.empty(16) - c = a.sum((0,1)).cast(dtypes.float16).permute(1,0).reshape(4,4,1).permute(1,0,2).reshape(16) + b - check_schedule(c, 1) - - @unittest.skip("failing in old lazy") - def test_fancy_reshape_fusion(self): - a = Tensor.empty(10) - b = Tensor.empty(10) - c = a+b - d = a.reshape(10,1)+b.reshape(10,1) - out = c.sum() + d.sum() - check_schedule(out, 1) - - # NOTE: for this to pass, LazyViews must be children of LazyBuffers so the (a+b) runs first - @unittest.skip("not real world") - def test_children_dont_push(self): - a = Tensor.empty(10, 10, 1) - b = Tensor.empty(10, 10, 1) - d = (a+b).expand(10, 10, 10) - e = (a+b).permute(2,1,0) - f = d+e - check_schedule(f, 2) - - def test_dont_fuse_binops_with_children(self): - a = Tensor.empty(10) - b = Tensor.empty(10) - c = Tensor.empty(10) - keep_me = a+b - e = keep_me.sum() # give keep_me a child (NOTE: BinaryOps won't be a child since it will instant fuse) - d = keep_me+c - check_schedule(d, 2) - check_schedule(keep_me, 0, [d]) - - @unittest.skip("failing in old lazy") - def test_permute_breaks_fusion(self): - a = Tensor.empty(10, 10, 10) - b = Tensor.empty(10, 10) - c = (a.sum(axis=2) + b).permute(1,0) - d = c.permute(1,0) - check_schedule(d, 1) - - def test_some_permute_fusion(self): - a = Tensor.empty(8192, 16) - b = Tensor.empty(1, 16) - d = (a.T + b.expand(8192, 16).T) - c = a + b.expand(8192, 16) - e = d.T - check_schedule(c, 1) - check_schedule(e, 1) - - # this is the failing case in openpilot...it's very simple like this - @unittest.skip("failing in old lazy") - def test_image_conv_fusion(self): - from tinygrad.features.image import image_conv2d - w1 = Tensor.empty(16, 16, 1, 1) - b1 = Tensor.empty(16) - w2 = Tensor.empty(16, 16, 1, 1) - b2 = Tensor.empty(16) - w3 = Tensor.empty(16, 16, 1, 1) - b3 = Tensor.empty(16) - - x = Tensor.empty(1, 16, 32, 32) - x = base = image_conv2d(x, w1, b1) - x = image_conv2d(x, w2, b2) + base - x = image_conv2d(x, w3, b3) - - # NOOP, 3 convs, contiguous - check_schedule(x, 5) - - def test_image_conv_fusion_minimal(self): - b1 = Tensor.empty(16) - b2 = Tensor.empty(16) - def p(x): return x.permute(1,0).contiguous().reshape(32,16,1).expand(32,16,16).sum(axis=2).permute(1,0) - - x = Tensor.empty(16, 32) - x = base = p(x) + b1.reshape(16,1) - x = p(x) - x = x + b2.reshape(16,1) - x = x + base - del base - x = p(x) - check_schedule(x, 4) - - def test_image_conv_fusion_more_minimal(self): - b1 = Tensor.empty(16) - def p(x): return x.permute(1,0).contiguous().reshape(32,16,1).expand(32,16,16).sum(axis=2).permute(1,0) - - x = Tensor.empty(16, 32) - x = base = p(x) + b1.reshape(16,1) - x = p(x) - del base - check_schedule(x, 3) - - def test_resnet_block(self): - from models.resnet import BasicBlock - Tensor.training = False - bb = BasicBlock(64,64) - - x = Tensor.empty(1, 64, 32, 32) - out = bb(x) - check_schedule(out, 4) - - def test_contiguous_while_contiguous(self): - x = Tensor.empty(1, 64, 32, 32) - out = x.contiguous() - check_schedule(out, 1, filter_loadops=False) - - def test_contiguous_while_not_contiguous(self): - x = Tensor.empty(1, 64, 32, 32) - out = x.permute(0,2,3,1).contiguous() - check_schedule(out, 2, filter_loadops=False) - - def test_double_from(self): - x = Tensor([1,2,3,4]) - out = x.to('cpu') - check_schedule(out, 0, filter_loadops=False) - - def test_pow_const_tensor(self): - x = Tensor([1,2,3,4]) - out = x ** Tensor(2) - check_schedule(out, 1) - -if __name__ == '__main__': - unittest.main(verbosity=2) diff --git a/tinygrad_repo/test/test_search.py b/tinygrad_repo/test/test_search.py deleted file mode 100644 index 400c04a..0000000 --- a/tinygrad_repo/test/test_search.py +++ /dev/null @@ -1,19 +0,0 @@ -import unittest - -from tinygrad.codegen.linearizer import Linearizer -from tinygrad.features.search import time_linearizer -from tinygrad.ops import Compiled, Device, LoadOps -from tinygrad.tensor import Tensor - -class TestTimeLinearizer(unittest.TestCase): - def setUp(self) -> None: - if not isinstance(Device[Device.DEFAULT], Compiled): raise unittest.SkipTest("only test for compiled backends") - - def test_reasonable_time(self): - si = [si for si in Tensor([1,2,3,4]).add(1).lazydata.schedule() if si.ast.op not in LoadOps][0] - rawbufs = [Device[Device.DEFAULT].buffer(si.out.st.size(), si.out.dtype)] + [Device[Device.DEFAULT].buffer(x.st.size(), x.dtype) for x in si.inputs] - tm = time_linearizer(Linearizer(si.ast), rawbufs, allow_test_size=False, cnt=10) - assert tm > 0 and tm != float('inf') - -if __name__ == '__main__': - unittest.main() diff --git a/tinygrad_repo/test/test_specific_conv.py b/tinygrad_repo/test/test_specific_conv.py deleted file mode 100644 index ac28e6c..0000000 --- a/tinygrad_repo/test/test_specific_conv.py +++ /dev/null @@ -1,57 +0,0 @@ -import unittest -from tinygrad.tensor import Tensor -from tinygrad.helpers import dtypes -from tinygrad.ops import Device -import pytest -# similar to test/external/external_test_gpu_ast.py, but universal - -pytestmark = pytest.mark.exclude_cuda - -class TestSpecific(unittest.TestCase): - # from openpilot - - # 1x1 6 <- 24 - def test_1x1_6_24(self): - x = Tensor.randn(1, 24*4, 32, 64) - w = Tensor.randn(6*4, 24*4, 1, 1) - x.conv2d(w).permute(0,2,3,1).reshape(32, 384, 4).contiguous().realize() - - def test_vec_mul(self): - # this forces it to be an image... - x = Tensor.ones(1, 512, 4).contiguous().reshape(1, 2048) - w = Tensor.randn(2048, 512) - (x @ w).reshape(1, 128, 4).contiguous().realize() - - @unittest.skipIf(Device.DEFAULT in ["LLVM", "WEBGPU"], "Broken on LLVM and webgpu") - def test_big_vec_mul(self): - # from LLaMA - # 0 buffer<4096, dtypes.float> [View((1024, 1, 1, 4), (4, 0, 0, 1), 0, None)] - # 1 buffer<4096, dtypes.float> [View((1024, 1024, 4, 4), (0, 4, 1, 0), 0, None)] - # 2 buffer<16777216, dtypes.half> [View((1024, 1024, 4, 4), (16384, 4, 1, 4096), 0, None)] - x = Tensor.randn(4096).realize() - w = Tensor.randn(4096, 4096, device='cpu').cast(dtypes.float16).to(Device.DEFAULT).realize() - (x @ w.T).realize() - - # from https://dl.acm.org/doi/pdf/10.1145/3495243.3517020 - - # ~260 GFLOPS on Adreno 640, should be 260*(720/890)*(596/710) = 176.5 on downclocked 630 - # we get 170 - def test_1x1_28_28(self): - x = Tensor.randn(1, 256, 28, 28) - w = Tensor.randn(256, 256, 1, 1) - x.conv2d(w).permute(0,2,3,1).reshape(28, 28*256//4, 4).contiguous().realize() - - # 132 GFLOPS on Adreno 640, should be 132*(720/890)*(596/710) = 90 on downclocked 630 - # gets 54 with broken opt, 74 without opt, and 146 if we pad and opt 3! - def test_3x3_28_28_stride_2(self): - x = Tensor.randn(1, 288, 36, 36) - w = Tensor.randn(384, 288, 3, 3) - x.conv2d(w, stride=2).permute(0,2,3,1).reshape(17, 17*384//4, 4).contiguous().realize() - - def test_3x3_28_28_stride_2_padded(self): - x = Tensor.randn(1, 288, 36, 36) - w = Tensor.randn(384, 288, 3, 3) - x.conv2d(w, stride=2, padding=1).permute(0,2,3,1).reshape(18, 18*384//4, 4).contiguous().realize() - -if __name__ == '__main__': - unittest.main() \ No newline at end of file diff --git a/tinygrad_repo/test/test_speed_v_torch.py b/tinygrad_repo/test/test_speed_v_torch.py deleted file mode 100644 index 0537d82..0000000 --- a/tinygrad_repo/test/test_speed_v_torch.py +++ /dev/null @@ -1,288 +0,0 @@ -import os -os.environ["NVIDIA_TF32_OVERRIDE"] = "0" -os.environ["MKL_NUM_THREADS"] = "1" -os.environ["NUMEXPR_NUM_THREADS"] = "1" -os.environ["OMP_NUM_THREADS"] = "1" -import unittest -import torch -torch.set_num_threads(1) -import time -import numpy as np -np.set_printoptions(linewidth=160) -from tinygrad.ops import Device -from tinygrad.helpers import GlobalCounters -from tinygrad.tensor import Tensor -from tinygrad.nn import Conv2d -from tinygrad.helpers import colored, getenv, CI -from tinygrad.jit import TinyJit -import pytest - -pytestmark = [pytest.mark.exclude_cuda, pytest.mark.exclude_gpu, pytest.mark.exclude_clang] - -IN_CHANS = [int(x) for x in getenv("IN_CHANS", "4,16,64").split(",")] - -torch_dt = torch.float16 if getenv("HALF", 0) else torch.float32 -torch_device = torch.device('mps' if getenv("MPS", 0) else ('cuda' if getenv("TORCHCUDA", 0) else 'cpu')) -if str(torch_device) == "mps": - import torch.mps - sync = lambda: torch.mps.synchronize() -elif str(torch_device) == "cuda": - import torch.cuda - sync = lambda: torch.cuda.synchronize() -else: - sync = lambda: None - -def colorize_float(x): - ret = f"{x:7.2f}x" - if x < 0.75: - return colored(ret, 'green') - elif x > 1.15: - return colored(ret, 'red') - else: - return colored(ret, 'yellow') - -save_ops, save_mem = 0, 0 -CNT = getenv("CNT", 8) -def helper_test_speed(f1, *args): - global save_ops, save_mem - ets = [] - ret = None - cache_defeat = np.zeros((2048,2048)) - for i in range(CNT): - del ret - - # operation cache defeats - args = [(x+1).realize() if isinstance(x, Tensor) else (None if x is None else (x+1)) for x in args] - - # force syncing - [x.numpy() if isinstance(x, Tensor) or str(torch_device) == "cpu" else x.cpu().numpy() for x in args if x is not None] - - # clear 32MB global memory cache (CPU and global memory only) - cache_defeat += 1 - - # manual pre sync - if isinstance(args[0], Tensor): Device[args[0].device].synchronize() - else: sync() - - GlobalCounters.global_ops = 0 - GlobalCounters.global_mem = 0 - st = time.perf_counter() - ret = f1(*args) - if isinstance(ret, Tensor): Device[ret.device].synchronize() - else: sync() - et = (time.perf_counter() - st) * 1000 - if i >= 1: ets.append(et) - if GlobalCounters.global_ops: - save_ops, save_mem = GlobalCounters.global_ops, GlobalCounters.global_mem - return ret.numpy() if isinstance(ret, Tensor) else ret.cpu().numpy(), np.min(ets) - -def helper_test_generic_square(name, N, f1, f2, onearg=False): - torch.manual_seed(0) - torch_a = (torch.rand(N, N, dtype=torch_dt) - 0.5).to(torch_device) - torch_b = (torch.rand(N, N, dtype=torch_dt) - 0.5).to(torch_device) if not onearg else None - - tiny_a = Tensor(torch_a.cpu().numpy()) - tiny_b = Tensor(torch_b.cpu().numpy()) if not onearg else None - - helper_test_generic(f"{name:30s} {N:5d}x{N:5d}", f1, (torch_a, torch_b), TinyJit(lambda a,b:f2(a,b).realize()), (tiny_a, tiny_b)) - -def helper_test_matvec(name, N, M): - torch.manual_seed(0) - torch_a = (torch.rand(N, dtype=torch_dt) - 0.5).to(torch_device) - torch_b = (torch.rand(N, M, dtype=torch_dt) - 0.5).to(torch_device) - - tiny_a = Tensor(torch_a.cpu().numpy()) - tiny_b = Tensor(torch_b.cpu().numpy()) - - helper_test_generic(f"{name:30s} {N:5d}x{M:5d}", lambda a,b: a@b, (torch_a, torch_b), TinyJit(lambda a,b:(a@b).realize()), (tiny_a, tiny_b)) - -prefix = None -def helper_test_generic(name, f1, f1_args, f2, f2_args): - global prefix - with torch.no_grad(): - val_torch, et_torch = helper_test_speed(f1, *f1_args) - val_tinygrad, et_tinygrad = helper_test_speed(f2, *f2_args) - - desc = "faster" if et_torch > et_tinygrad else "slower" - flops = save_ops*1e-6 - mem = save_mem*1e-6 - print(("\r" if not CI else "")+f"{name:42s} {et_torch:7.2f} ms ({flops/et_torch:8.2f} GFLOPS {mem/et_torch:8.2f} GB/s) in torch, {et_tinygrad:7.2f} ms ({flops/et_tinygrad:8.2f} GFLOPS {mem/et_tinygrad:8.2f} GB/s) in tinygrad, {colorize_float(et_tinygrad/et_torch)} {desc} {flops:10.2f} MOPS {mem:8.2f} MB") - np.testing.assert_allclose(val_tinygrad, val_torch, atol=1e-3, rtol=1e-3) - -def helper_test_conv(bs, in_chans, out_chans, kernel_size, img_size_y, img_size_x): - torch.manual_seed(0) - torch_dat = torch.rand(bs, in_chans, img_size_y, img_size_x, dtype=torch_dt).to(torch_device) - torch_conv = torch.nn.Conv2d(in_chans, out_chans, kernel_size, bias=None, dtype=torch_dt).to(torch_device) - - tiny_dat = Tensor(torch_dat.cpu().numpy()) - tiny_conv = Conv2d(in_chans, out_chans, kernel_size, bias=None) - tiny_conv.weight = Tensor(torch_conv.weight.detach().cpu().numpy()) - - def f1(torch_dat): return torch_conv(torch_dat) - def f2(tiny_dat): return tiny_conv(tiny_dat).realize() - helper_test_generic(f"conv bs:{bs:3d} chans:{in_chans:3d} -> {out_chans:3d} k:{kernel_size}", f1, (torch_dat,), TinyJit(f2), (tiny_dat,)) - -@unittest.skipIf(getenv("BIG") == 0, "no big tests") -class TestBigSpeed(unittest.TestCase): - def test_add(self): - def f(a, b): return a+b - helper_test_generic_square('add', 8192, f, f) - def test_exp(self): - def f(a, b): return a.exp() - helper_test_generic_square('exp', 8192, f, f, onearg=True) - def test_gemm_2048(self): - def f(a, b): return a @ b - helper_test_generic_square('gemm', 2048, f, f) - def test_gemm_4096(self): - def f(a, b): return a @ b - helper_test_generic_square('gemm', 4096, f, f) - def test_large_conv_1x1(self): helper_test_conv(bs=32, in_chans=128, out_chans=128, kernel_size=1, img_size_y=128, img_size_x=128) - def test_large_conv_3x3(self): helper_test_conv(bs=4, in_chans=128, out_chans=128, kernel_size=3, img_size_y=130, img_size_x=130) - def test_large_conv_5x5(self): helper_test_conv(bs=4, in_chans=128, out_chans=128, kernel_size=5, img_size_y=132, img_size_x=132) - def test_matvec_4096_16384(self): helper_test_matvec('matvec_4096_16384', 4096, 16384) - def test_matvec_16384_4096(self): helper_test_matvec('matvec_16384_4096', 16384, 4096) - -@unittest.skipIf(getenv("BIG") == 1, "only big tests") -class TestSpeed(unittest.TestCase): - def test_sub(self): - def f(a, b): return a-b - helper_test_generic_square('sub', 4096, f, f) - - @unittest.skipIf(CI and Device.DEFAULT == "WEBGPU", "breaking on webgpu CI") - def test_pow(self): - def f(a, b): return a.pow(b) - helper_test_generic_square('pow', 2048, f, f) - - def test_sum(self): - def f(a, b): return a.sum() - helper_test_generic_square('sum', 2048, f, f, onearg=True) - helper_test_generic_square('sum', 4096, f, f, onearg=True) - - def test_partial_sum(self): - R = 256 - def f(a, b): return a.reshape(int(4096//R), int(4096*R)).sum(axis=1) - helper_test_generic_square('partial_sum', 4096, f, f, onearg=True) - - @unittest.skip("not really used in models") - def test_cumsum(self): - def f0(a, b): return a.cumsum(axis=0) - def f1(a, b): return a.cumsum(axis=1) - helper_test_generic_square('cumsum_0', 256, f0, f0, onearg=True) - helper_test_generic_square('cumsum_1', 256, f1, f1, onearg=True) - - def test_cat(self): - helper_test_generic_square('cat_0', 256, lambda x,y: torch.cat((x,y),dim=0), lambda x,y: x.cat(y,dim=0)) - helper_test_generic_square('cat_1', 256, lambda x,y: torch.cat((x,y),dim=1), lambda x,y: x.cat(y,dim=1)) - - def test_array_packing(self): - N = 2048 - def f(a, b): return a.reshape(N, N // 32, 32).permute(1,0,2).contiguous() - helper_test_generic_square('array_packing', N, f, f, onearg=True) - - def test_permute(self): - for N in [1024, 4096]: - # this is a 64MB tensor, M1 L1 cache is 128kB - # to fit easily in L1, rotations should be 128x128 chunks. 128x128 is also the AMX size - def f(a, b): return a.permute(1,0).contiguous() - helper_test_generic_square('permute', N, f, f, onearg=True) - - def test_double_permute(self): - N = 64 - torch.manual_seed(0) - torch_a = (torch.rand(N, N, N, N, dtype=torch_dt) - 0.5).to(torch_device) - tiny_a = Tensor(torch_a.cpu().numpy()) - def f(a): return a.permute(1,0,3,2).contiguous() - helper_test_generic(f"double_permute {tiny_a.shape}", f, (torch_a,), TinyJit(lambda a: f(a).realize()), (tiny_a,)) - - def test_neg(self): - def f(a, b): return -a - helper_test_generic_square('neg', 4096, f, f, onearg=True) - - def test_exp(self): - def f(a, b): return a.exp() - helper_test_generic_square('exp', 2048, f, f, onearg=True) - - def test_relu(self): - def f(a, b): return a.relu() - helper_test_generic_square('relu', 4096, f, f, onearg=True) - - def test_max(self): - def f(a, b): return a.max() - helper_test_generic_square('max', 4096, f, f, onearg=True) - - def test_mul_sum(self): - def f(a, b): return (a*b).sum() - helper_test_generic_square('mul_sum', 4096, f, f) - - def test_add(self): - for N in [1, 1024, 4096]: - def f(a, b): return a + b - helper_test_generic_square('add', N, f, f) - - def test_add_constant(self): - def f(a, b): return a+2.0 - helper_test_generic_square('add_constant', 4096, f, f, onearg=True) - - def test_add_sq(self): - def f(a, b): return a*a + b*b - helper_test_generic_square('add_sq', 4096, f, f) - - def test_gemm(self): - def f(a, b): return a @ b - helper_test_generic_square('gemm', 1024, f, f) - - def test_gemm_small(self): - def f(a, b): return a @ b - helper_test_generic_square('gemm', 256, f, f) - - def test_gemm_unrolled(self): - N = 512 - def f1(a, b): return a@b.T - def f2(a, b): return (a.reshape(N, 1, N).expand(N, N, N) * b.reshape(1, N, N).expand(N, N, N)).sum(axis=2) - helper_test_generic_square('gemm_unrolled', N, f1, f2) - - def test_gemm_unrolled_permute_l(self): - N = 512 - def f1(a, b): return a.T@b.T - def f2(a, b): return (a.permute(1,0).reshape(N, 1, N).expand(N, N, N) * b.reshape(1, N, N).expand(N, N, N)).sum(axis=2) - helper_test_generic_square('gemm_unrolled_permute_l', N, f1, f2) - - def test_gemm_unrolled_permute_r(self): - N = 512 - def f1(a, b): return a@b - def f2(a, b): return (a.reshape(N, 1, N).expand(N, N, N) * b.permute(1,0).reshape(1, N, N).expand(N, N, N)).sum(axis=2) - helper_test_generic_square('gemm_unrolled_permute_r', N, f1, f2) - - def test_gemm_unrolled_permute_lr(self): - N = 512 - def f1(a, b): return a.T@b - def f2(a, b): return (a.permute(1,0).reshape(N, 1, N).expand(N, N, N) * b.permute(1,0).reshape(1, N, N).expand(N, N, N)).sum(axis=2) - helper_test_generic_square('gemm_unrolled_permute_lr', N, f1, f2) - - def test_matvec_1024_1024(self): helper_test_matvec('matvec_1024_1024', 1024, 1024) - def test_matvec_1024_4096(self): helper_test_matvec('matvec_1024_4096', 1024, 4096) - def test_matvec_4096_1024(self): helper_test_matvec('matvec_4096_1024', 4096, 1024) - def test_matvec_4096_4096(self): helper_test_matvec('matvec_4096_4096', 4096, 4096) - - def test_openpilot_conv2d(self): - bs, in_chans, out_chans = 1,12,32 - torch.manual_seed(0) - torch_dat = torch.rand(bs, 64, 128, 12, dtype=torch_dt).to(torch_device) - torch_conv = torch.nn.Conv2d(in_chans, out_chans, 3, bias=None, padding=1, dtype=torch_dt).to(torch_device) - - tiny_dat = Tensor(torch_dat.cpu().numpy()) - tiny_conv = Conv2d(in_chans, out_chans, 3, bias=None, padding=1) - tiny_conv.weight = Tensor(torch_conv.weight.detach().cpu().numpy()) - - def f1(torch_dat): return torch_conv(torch_dat.permute(0,3,1,2)) - def f2(tiny_dat): return tiny_conv(tiny_dat.permute(0,3,1,2)).realize() - helper_test_generic(f"conv bs:{bs:3d} chans:{in_chans:3d} -> {out_chans:3d} k:3", f1, (torch_dat,), TinyJit(f2), (tiny_dat,)) - - def test_conv2d(self): - for bs in [32]: - for in_chans in IN_CHANS: - for out_chans in [32]: - helper_test_conv(bs, in_chans, out_chans, 3, 34, 34) - -if __name__ == '__main__': - unittest.main() diff --git a/tinygrad_repo/test/test_symbolic_jit.py b/tinygrad_repo/test/test_symbolic_jit.py deleted file mode 100644 index f2f0fd8..0000000 --- a/tinygrad_repo/test/test_symbolic_jit.py +++ /dev/null @@ -1,181 +0,0 @@ -import unittest -from tinygrad.jit import TinyJit -from tinygrad.helpers import getenv -from tinygrad.shape.symbolic import Variable -from tinygrad.tensor import Tensor, Device -import numpy as np - -@unittest.skipIf(getenv("ARM64") or getenv("PTX"), "ARM64 and PTX are not supported") -@unittest.skipUnless(Device.DEFAULT in ["GPU", "METAL", "CLANG", "CUDA", "LLVM"], f"{Device.DEFAULT} is not supported") -class TestSymbolicJit(unittest.TestCase): - def test_plus1(self): - def f(a): return (a+1).realize() - jf = TinyJit(f) - for i in range(1, 5): - vi = Variable("i", 1, 10).bind(i) - a = Tensor.rand(3, i) - symbolic = jf(a.reshape(3, vi)).reshape(3, i).numpy() - expected = f(a).numpy() - np.testing.assert_allclose(symbolic, expected, atol=1e-6, rtol=1e-6) - assert len(jf.jit_cache) == 1 - - def test_reshape_inside_plus1(self): - def f(a, jit=False, jit_ctx=None): - if jit: a = a.reshape(3, Variable("i", 1, 10).bind(a.shape[1])) - return (a+1).realize() - jf = TinyJit(f) - for i in range(1, 5): - vi = Variable("i", 1, 10) - a = Tensor.rand(3, i) - symbolic = jf(a, jit=True, jit_ctx={vi: i}).reshape(3, i).numpy() - expected = f(a).numpy() - np.testing.assert_allclose(symbolic, expected, atol=1e-6, rtol=1e-6) - assert len(jf.jit_cache) == 1 - - def test_add(self): - def f(a, b): return (a+b).realize() - jf = TinyJit(f) - for i in range(1, 5): - vi = Variable("i", 1, 10).bind(i) - a = Tensor.rand(3, i) - b = Tensor.rand(3, i) - symbolic = jf(a.reshape(3, vi), b.reshape(3, vi)).reshape(3, i).numpy() - expected = f(a, b).numpy() - np.testing.assert_allclose(symbolic, expected, atol=1e-6, rtol=1e-6) - assert len(jf.jit_cache) == 1 - - def test_matmul(self): - def f(a, b): return (a@b).realize() - jf = TinyJit(f) - for i in range(1, 5): - vi = Variable("i", 1, 10).bind(i) - a = Tensor.rand(3, i) - b = Tensor.rand(i, 5) - symbolic = jf(a.reshape(3, vi), b.reshape(vi, 5)).numpy() - expected = f(a, b).numpy() - np.testing.assert_allclose(symbolic, expected, atol=1e-6, rtol=1e-6) - assert len(jf.jit_cache) == 1 - - def test_mixed_with_no_symbol_kernel(self): - def f(a, b): - s = (a@b).realize() - s = (s+s).realize() # this one does not have symbols in input - return s - jf = TinyJit(f) - for i in range(1, 5): - vi = Variable("i", 1, 10).bind(i) - a = Tensor.rand(3, i) - b = Tensor.rand(i, 5) - symbolic = jf(a.reshape(3, vi), b.reshape(vi, 5)).numpy() - expected = f(a, b).numpy() - np.testing.assert_allclose(symbolic, expected, atol=1e-6, rtol=1e-6) - assert len(jf.jit_cache) == 2 - - def test_attention(self): - def f(q, k, v): return Tensor.scaled_dot_product_attention(q.transpose(1, 2), k.transpose(1, 2), v.transpose(1, 2)).realize() - jf = TinyJit(f) - for i in range(1, 5): - vi = Variable("i", 1, 10).bind(i) - q = Tensor.rand(2, 1, 4, 8) - k = Tensor.rand(2, i, 4, 8) - v = Tensor.rand(2, i, 4, 8) - symbolic = jf(q, k.reshape(2, vi, 4, 8), v.reshape(2, vi, 4, 8)).reshape(2, 4, 1, 8).numpy() - expected = f(q, k, v).numpy() - np.testing.assert_allclose(symbolic, expected, atol=1e-6, rtol=1e-6) - assert len(jf.jit_cache) == 6 - - def test_cat_dim0(self): - def f(a, b): return a.cat(b, dim=0).realize() - jf = TinyJit(f) - for i in range(1, 5): - vi = Variable("i", 1, 10).bind(i) - a = Tensor.rand(i, 3) - b = Tensor.rand(2, 3) - symbolic = jf(a.reshape(vi, 3), b).reshape(i+2, 3).numpy() - expected = f(a, b).numpy() - np.testing.assert_allclose(symbolic, expected, atol=1e-6, rtol=1e-6) - assert len(jf.jit_cache) == 1 - - def test_cat_dim1(self): - def f(a, b): return a.cat(b, dim=1).realize() - jf = TinyJit(f) - for i in range(1, 5): - vi = Variable("i", 1, 10).bind(i) - a = Tensor.rand(3, i) - b = Tensor.rand(3, 2) - symbolic = jf(a.reshape(3, vi), b).reshape(3, i+2).numpy() - expected = f(a, b).numpy() - np.testing.assert_allclose(symbolic, expected, atol=1e-6, rtol=1e-6) - assert len(jf.jit_cache) == 1 - - def test_cat_dim0_two_vars(self): - def f(a, b): return a.cat(b, dim=0).realize() - jf = TinyJit(f) - for i in range(1, 5): - for j in range(1, 5): - vi = Variable("i", 1, 10).bind(i) - vj = Variable("j", 1, 10).bind(j) - a = Tensor.rand(i, 3) - b = Tensor.rand(j, 3) - symbolic = jf(a.reshape(vi, 3), b.reshape(vj, 3)).reshape(i+j, 3).numpy() - expected = f(a, b).numpy() - np.testing.assert_allclose(symbolic, expected, atol=1e-6, rtol=1e-6) - assert len(jf.jit_cache) == 1 - - def test_cat_dim1_two_vars(self): - def f(a, b): return a.cat(b, dim=1).realize() - jf = TinyJit(f) - for i in range(1, 5): - for j in range(1, 5): - vi = Variable("i", 1, 10).bind(i) - vj = Variable("j", 1, 10).bind(j) - a = Tensor.rand(3, i) - b = Tensor.rand(3, j) - symbolic = jf(a.reshape(3, vi), b.reshape(3, vj)).reshape(3, i+j).numpy() - expected = f(a, b).numpy() - np.testing.assert_allclose(symbolic, expected, atol=1e-6, rtol=1e-6) - assert len(jf.jit_cache) == 1 - - def test_two_vars_plus1(self): - def f(a, b): return (a@b+1).realize() - jf = TinyJit(f) - for i in range(1, 5): - for j in range(1, 5): - vi = Variable("i", 1, 10).bind(i) - vj = Variable("j", 1, 10).bind(j) - a = Tensor.rand(i, 3) - b = Tensor.rand(3, j) - symbolic = jf(a.reshape(vi, 3), b.reshape(3, vj)).reshape(i, j).numpy() - expected = f(a, b).numpy() - np.testing.assert_allclose(symbolic, expected, atol=1e-6, rtol=1e-6) - assert len(jf.jit_cache) == 1 - - def test_jit_symbolic_shape_mismatch(self): - @TinyJit - def add(a, b): return (a+b).realize() - for i in range(1, 5): - vi = Variable("i", 1, 10).bind(i) - a = Tensor.rand(3, i).reshape(3, vi) - b = Tensor.rand(3, i).reshape(3, vi) - c = add(a, b) - vi2 = Variable("i", 1, 10).bind(7) - a = Tensor.rand(3, 7).reshape(3, vi2) - bad = Tensor.rand(4, 7).reshape(4, vi2) - with self.assertRaises(AssertionError): - add(a, bad) - - def test_shrink(self): - # shrink is a movement, so we pair it with a simple function to test the JIT interaction - def f(a): return (a+1).realize() - jf = TinyJit(f) - for i in range(1, 5): - vi = Variable("i", 1, 10).bind(i) - a = Tensor.rand(7, 11) - symbolic = a.shrink(((3,5),(vi,vi+2))) - symbolic = jf(symbolic).numpy() - expected = f(a.shrink(((3,5),(i,i+2)))).numpy() - np.testing.assert_allclose(symbolic, expected, atol=1e-6, rtol=1e-6) - assert len(jf.jit_cache) == 1 - -if __name__ == '__main__': - unittest.main() \ No newline at end of file diff --git a/tinygrad_repo/test/test_symbolic_ops.py b/tinygrad_repo/test/test_symbolic_ops.py deleted file mode 100644 index c446899..0000000 --- a/tinygrad_repo/test/test_symbolic_ops.py +++ /dev/null @@ -1,124 +0,0 @@ -import unittest -from tinygrad.jit import JIT_SUPPORTED_DEVICE -from tinygrad.shape.symbolic import Variable -from tinygrad.helpers import getenv -from tinygrad.tensor import Tensor, Device -import numpy as np - -@unittest.skipIf(getenv("ARM64") or getenv("PTX"), "ARM64 and PTX are not supported") -@unittest.skipUnless(Device.DEFAULT in JIT_SUPPORTED_DEVICE and Device.DEFAULT not in ["HIP", "WEBGPU"], f"{Device.DEFAULT} is not supported") -class TestSymbolicOps(unittest.TestCase): - def test_plus1(self): - def f(a): return (a+1).realize() - for i in range(1, 5): - vi = Variable("i", 1, 10).bind(i) - a = Tensor.rand(3, i) - symbolic = f(a.reshape(3, vi)).reshape(3, i).numpy() - expected = f(a).numpy() - np.testing.assert_allclose(symbolic, expected, atol=1e-6, rtol=1e-6) - - def test_add(self): - def f(a, b): return (a+b).realize() - for i in range(1, 5): - vi = Variable("i", 1, 10).bind(i) - a = Tensor.rand(3, i) - b = Tensor.rand(3, i) - symbolic = f(a.reshape(3, vi), b.reshape(3, vi)).reshape(3, i).numpy() - expected = f(a, b).numpy() - np.testing.assert_allclose(symbolic, expected, atol=1e-6, rtol=1e-6) - - def test_matmul(self): - def f(a, b): return (a@b).realize() - for i in range(1, 5): - vi = Variable("i", 1, 10).bind(i) - a = Tensor.rand(3, i) - b = Tensor.rand(i, 5) - symbolic = f(a.reshape(3, vi), b.reshape(vi, 5)).numpy() - expected = f(a, b).numpy() - np.testing.assert_allclose(symbolic, expected, atol=1e-6, rtol=1e-6) - - def test_attention(self, dropout_p=0.0): - def f(q, k, v): return Tensor.scaled_dot_product_attention(q.transpose(1, 2), k.transpose(1, 2), v.transpose(1, 2), dropout_p=dropout_p).realize() - for i in range(1, 5): - vi = Variable("i", 1, 10).bind(i) - q = Tensor.rand(2, 1, 4, 8) - k = Tensor.rand(2, i, 4, 8) - v = Tensor.rand(2, i, 4, 8) - symbolic = f(q, k.reshape(2, vi, 4, 8), v.reshape(2, vi, 4, 8)).reshape(2, 4, 1, 8).numpy() - expected = f(q, k, v).numpy() - np.testing.assert_allclose(symbolic, expected, atol=1e-6, rtol=1e-6) - - def test_attention_training(self): - with Tensor.train(): - self.test_attention(dropout_p=0.0) - with self.assertRaises(AssertionError): - # symbolic shape dropout is not supported - self.test_attention(dropout_p=0.5) - - def test_cat_dim0(self): - def f(a, b): return a.cat(b, dim=0).realize() - for i in range(1, 5): - vi = Variable("i", 1, 10).bind(i) - a = Tensor.rand(i, 3) - b = Tensor.rand(2, 3) - symbolic = f(a.reshape(vi, 3), b).reshape(i+2, 3).numpy() - expected = f(a, b).numpy() - np.testing.assert_allclose(symbolic, expected, atol=1e-6, rtol=1e-6) - - def test_cat_dim1(self): - def f(a, b): return a.cat(b, dim=1).realize() - for i in range(1, 5): - vi = Variable("i", 1, 10).bind(i) - a = Tensor.rand(3, i) - b = Tensor.rand(3, 2) - symbolic = f(a.reshape(3, vi), b).reshape(3, i+2).numpy() - expected = f(a, b).numpy() - np.testing.assert_allclose(symbolic, expected, atol=1e-6, rtol=1e-6) - - def test_cat_dim0_two_vars(self): - def f(a, b): return a.cat(b, dim=0).realize() - for i in range(1, 5): - for j in range(1, 5): - vi = Variable("i", 1, 10).bind(i) - vj = Variable("j", 1, 10).bind(j) - a = Tensor.rand(i, 3) - b = Tensor.rand(j, 3) - symbolic = f(a.reshape(vi, 3), b.reshape(vj, 3)).reshape(i+j, 3).numpy() - expected = f(a, b).numpy() - np.testing.assert_allclose(symbolic, expected, atol=1e-6, rtol=1e-6) - - def test_cat_dim1_two_vars(self): - def f(a, b): return a.cat(b, dim=1).realize() - for i in range(1, 5): - for j in range(1, 5): - vi = Variable("i", 1, 10).bind(i) - vj = Variable("j", 1, 10).bind(j) - a = Tensor.rand(3, i) - b = Tensor.rand(3, j) - symbolic = f(a.reshape(3, vi), b.reshape(3, vj)).reshape(3, i+j).numpy() - expected = f(a, b).numpy() - np.testing.assert_allclose(symbolic, expected, atol=1e-6, rtol=1e-6) - - def test_two_vars_plus1(self): - def f(a, b): return (a@b+1).realize() - for i in range(1, 5): - for j in range(1, 5): - vi = Variable("i", 1, 10).bind(i) - vj = Variable("j", 1, 10).bind(j) - a = Tensor.rand(i, 3) - b = Tensor.rand(3, j) - symbolic = f(a.reshape(vi, 3), b.reshape(3, vj)).reshape(i, j).numpy() - expected = f(a, b).numpy() - np.testing.assert_allclose(symbolic, expected, atol=1e-6, rtol=1e-6) - - def test_shrink(self): - for i in range(1, 5): - vi = Variable("i", 1, 10).bind(i) - a = Tensor.rand(7, 11) - symbolic = a.shrink(((3,5),(vi,vi+2))) - symbolic = symbolic.numpy() - expected = a.shrink(((3,5),(i,i+2))).numpy() - np.testing.assert_allclose(symbolic, expected, atol=1e-6, rtol=1e-6) - -if __name__ == '__main__': - unittest.main() \ No newline at end of file diff --git a/tinygrad_repo/test/test_symbolic_shapetracker.py b/tinygrad_repo/test/test_symbolic_shapetracker.py deleted file mode 100644 index 1e0b4fe..0000000 --- a/tinygrad_repo/test/test_symbolic_shapetracker.py +++ /dev/null @@ -1,173 +0,0 @@ -import unittest -from tinygrad.shape.shapetracker import ShapeTracker, View -from tinygrad.shape.symbolic import Variable -from tinygrad.tensor import Tensor - -class TestSymbolic(unittest.TestCase): - def test_symbolic_st(self): - x = Variable("x", 1, 100) - st = ShapeTracker.from_shape((x, 3)) - assert st.shape == (x, 3) - assert st.real_strides() == (3, 1) - - def test_expr_idxs(self): - x = Variable("x", 1, 100) - st = ShapeTracker.from_shape((x, 3)) - idxs = [Variable("x", 0, 100), Variable("y", 0, 100)] - e1, e2 = st.expr_idxs(idxs) - assert e1.render() == "((x*3)+y)" - assert e2.render() == "1" - st = st.permute((1, 0)) - e1, e2 = st.expr_idxs(idxs) - assert e1.render() == "((y*3)+x)" - assert e2.render() == "1" - - def test_cat_dim0_strides(self): - i = Variable("i", 1, 5).bind(3) - j = Variable("j", 1, 5).bind(3) - k = Variable("k", 1, 5).bind(3) - t = Tensor.rand(3, 4).reshape(i, 4).cat(Tensor.rand(3, 4).reshape(j, 4), dim=0).cat(Tensor.rand(3, 4).reshape(k, 4), dim=0) - st = t.lazydata.st - assert st.shape == (i+j+k, 4) - assert st.real_strides() == (4, 1) - t = Tensor.rand(3, 3).reshape(i, 3).cat(Tensor.rand(3, 3).reshape(i, 3), dim=0).cat(Tensor.rand(3, 3), dim=0) - st = t.lazydata.st - assert st.shape == (2*i+3, 3) - assert st.real_strides() == (3, 1) - - def test_cat_dim1_strides(self): - i = Variable("i", 1, 5).bind(4) - j = Variable("j", 1, 5).bind(4) - k = Variable("k", 1, 5).bind(4) - t = Tensor.rand(3, 4).reshape(3, i).cat(Tensor.rand(3, 4).reshape(3, j), dim=1).cat(Tensor.rand(3, 4).reshape(3, k), dim=1) - st = t.lazydata.st - assert st.shape == (3, i+j+k) - assert st.real_strides() == (i+j+k, 1) - -class TestSymbolicVarVals(unittest.TestCase): - def test_var_vals_empty(self): - assert ShapeTracker.from_shape((3, 4, 5)).var_vals == {} - - def test_var_vals_shape(self): - x = Variable("x", 1, 100).bind(3) - assert ShapeTracker.from_shape((x, 3)).var_vals == {Variable("x", 1, 100): 3} - - def test_var_vals_offset(self): - x = Variable("x", 1, 100).bind(3) - st = ShapeTracker.from_shape((4, 3)).shrink(((x, x+1), (0, 3))) - assert st.real_offset() == x * 3 - assert st.var_vals == {Variable("x", 1, 100): 3} - - def test_var_vals_mask(self): - x = Variable("x", 1, 100).bind(3) - view = View.create(shape=(3,4), strides=(4,1), offset=0, mask=((0, x), (0, 4))) - st = ShapeTracker(views=(view,)) - assert st.var_vals == {Variable("x", 1, 100): 3} - - def test_var_vals_complex(self): - x = Variable("x", 1, 100).bind(3) - y = Variable("y", 1, 100).bind(4) - z = Variable("z", 1, 100).bind(5) - st = ShapeTracker.from_shape((x, 5, y)).shrink(((0, x), (z, z+1), (0, 3))) - assert st.real_offset() == y * z - assert st.var_vals == {Variable("x", 1, 100): 3, Variable("y", 1, 100):4, Variable("z", 1, 100): 5} - - def test_shrink_reshape(self): - x = Variable("x", 1, 100).bind(3) - st = ShapeTracker.from_shape((10, 10, 10)).shrink(((x, x+3), (3, 7), (2, 5))) - st = st.reshape((3*4*3,)) - assert st.var_vals == {Variable("x", 1, 100): 3} - -class TestShapeTrackerUnbind(unittest.TestCase): - def test_view_unbind(self): - v = Variable("v", 1, 100) - bv = Variable("v", 1, 100).bind(3) - assert View.create(shape=(bv, 4)).unbind() == View.create(shape=(v, 4)) - - def test_reshape_unbind(self): - v = Variable("v", 1, 100) - bv = Variable("v", 1, 100).bind(3) - t = Tensor.rand(3, 4).reshape(bv, 4) - assert t.lazydata.st.unbind() == ShapeTracker((View.create(shape=(v, 4)),)) - - def test_shrink_unbind(self): - v = Variable("v", 1, 100) - bv = Variable("v", 1, 100).bind(2) - t = Tensor.rand(3, 4).shrink(((bv, bv+1), (0, 4))) - assert t.lazydata.st.unbind() == ShapeTracker((View.create(shape=(1, 4), offset=4*v),)) - -class TestSymbolicReshape(unittest.TestCase): - def test_reshape_into_symbols_simple(self): - for i in range(1, 6): - vi = Variable("i", 1, 5).bind(i) - t = Tensor.rand(i, 4).reshape(vi, 4) - assert t.shape == (vi, 4) - t = Tensor.rand(i, 6).reshape(vi, 2, 3) - assert t.shape == (vi, 2, 3) - - def test_reshape_symbols_reshape_ints(self): - for i in range(1, 6): - vi = Variable("i", 1, 5).bind(i) - t = Tensor.rand(i, 4).reshape(vi, 4) - assert t.shape == (vi, 4) - t = t.reshape(i, 4) - assert t.shape == (i, 4) - - def test_reshape_into_symbols_bad_shape(self): - vi = Variable("i", 1, 10).bind(4) - with self.assertRaises(AssertionError): - t = Tensor.rand(4, 6).reshape(vi, 6).reshape(1, 77) # reshape to a different size new shape through symbolic shape - with self.assertRaises(AssertionError): - t = Tensor.rand(3, 4).reshape(3, (vi+1)) # reshape into non-Variable Node - - def test_two_symbol_reshape(self): - for i in range(1, 6): - for j in range(1, 6): - vi = Variable("i", 1, 5).bind(i) - vj = Variable("j", 1, 5).bind(j) - t = Tensor.rand(i, j).reshape(vi, vj) - assert t.shape == (vi, vj) - # NOTE: this is currently not allowed - # t = t.reshape(1, vi*vj) - # assert t.shape == (1, vi*vj) - t = t.reshape(vj, vi) - assert t.shape == (vj, vi) - -class TestSymbolicExpand(unittest.TestCase): - def test_expand_into_symbols(self): - # TODO: enfore expand only into bound variables - vi = Variable("i", 1, 5) - vj = Variable("j", 1, 5) - a = Tensor([[1], [2], [3]]).expand((3, vi)) - assert a.shape == (3, vi) - a = a.reshape(3, vi, 1).expand((3, vi, vj)) - assert a.shape == (3, vi, vj) - - def test_plus_expands_constant(self): - for i in range(1, 6): - vi = Variable("i", 1, 5).bind(i) - a = Tensor.rand(3, i).reshape(3, vi) - a = a + 1 - assert a.shape == (3, vi) - -class TestSymbolicShrink(unittest.TestCase): - def test_shrink_symbols(self): - vi = Variable("i", 1, 5) - t = Tensor.rand(3, 5).shrink(((0, 2), (vi, vi+1))) - assert t.shape == (2, 1) - -class TestSymbolicShapeExpr(unittest.TestCase): - def test_symbolic_expr_idxs(self): - # taken from symbolic shape llama - i = Variable("i", 1, 120) - gidx0 = Variable("gidx0", 0, i) - lidx1 = Variable("lidx1", 0, 7) - idx = (gidx0, lidx1, Variable.num(1)) - shape = (i+1, 8, 4) - strides = (1, (i*4)+4, i+1) - st = ShapeTracker((View.create(shape, strides), )) - idx, valid = st.expr_idxs(idx) - assert idx.render() == "((lidx1*((i*4)+4))+1+gidx0+i)" - -if __name__ == '__main__': - unittest.main() \ No newline at end of file diff --git a/tinygrad_repo/test/test_tensor.py b/tinygrad_repo/test/test_tensor.py deleted file mode 100644 index bb81e02..0000000 --- a/tinygrad_repo/test/test_tensor.py +++ /dev/null @@ -1,266 +0,0 @@ -import numpy as np -import torch -import struct -import unittest, copy -import mmap -from tinygrad.tensor import Tensor, Device -from tinygrad.helpers import dtypes -from extra.gradcheck import numerical_jacobian, jacobian, gradcheck -from extra.utils import temp - -x_init = np.random.randn(1,3).astype(np.float32) -U_init = np.random.randn(3,3).astype(np.float32) -V_init = np.random.randn(3,3).astype(np.float32) -W_init = np.random.randn(3,3).astype(np.float32) -m_init = np.random.randn(1,3).astype(np.float32) - -class TestTinygrad(unittest.TestCase): - def test_zerodim_initialization(self): - a = Tensor(55) - b = Tensor(3.14) - - self.assertEqual(a.shape, ()) - self.assertEqual(b.shape, ()) - - def test_plus_equals(self): - a = Tensor.randn(10,10) - b = Tensor.randn(10,10) - c = a + b - val1 = c.numpy() - a += b - val2 = a.numpy() - np.testing.assert_allclose(val1, val2) - - def test_backward_pass(self): - def test_tinygrad(): - x = Tensor(x_init, requires_grad=True) - W = Tensor(W_init, requires_grad=True) - m = Tensor(m_init) - out = x.dot(W).relu() - out = out.log_softmax() - out = out.mul(m).add(m).sum() - out.backward() - return out.numpy(), x.grad.numpy(), W.grad.numpy() - - def test_pytorch(): - x = torch.tensor(x_init, requires_grad=True) - W = torch.tensor(W_init, requires_grad=True) - m = torch.tensor(m_init) - out = x.matmul(W).relu() - out = torch.nn.functional.log_softmax(out, dim=1) - out = out.mul(m).add(m).sum() - out.backward() - return out.detach().numpy(), x.grad, W.grad - - for x,y in zip(test_tinygrad(), test_pytorch()): - np.testing.assert_allclose(x, y, atol=1e-5) - - @unittest.skipIf(Device.DEFAULT == "WEBGPU", "this test uses more than 8 bufs which breaks webgpu") #TODO: remove after #1461 - def test_backward_pass_diamond_model(self): - def test_tinygrad(): - u = Tensor(U_init, requires_grad=True) - v = Tensor(V_init, requires_grad=True) - w = Tensor(W_init, requires_grad=True) - x = u.mul(v).relu() - y = u.mul(w).relu() - out = x.add(y).mul(y).relu() - out = out.log_softmax() - out = out.sum() - out.backward() - return out.numpy(), u.grad.numpy(), v.grad.numpy(), w.grad.numpy() - - def test_pytorch(): - u = torch.tensor(U_init, requires_grad=True) - v = torch.tensor(V_init, requires_grad=True) - w = torch.tensor(W_init, requires_grad=True) - x = u.mul(v).relu() - y = u.mul(w).relu() - out = x.add(y).mul(y).relu() - out = torch.nn.functional.log_softmax(out, dim=1) - out = out.sum() - out.backward() - return out.detach().numpy(), u.grad, v.grad, w.grad - - for x,y in zip(test_tinygrad(), test_pytorch()): - np.testing.assert_allclose(x, y, atol=1e-5) - - def test_nograd(self): - x = Tensor(x_init, requires_grad=False) - m = Tensor(m_init, requires_grad=False) - W = Tensor(W_init, requires_grad=True) - tmp = x.mul(m) - mm = tmp.matmul(W) - out = mm.relu() - out = out.sum() - out.backward() - assert x.grad is None - assert m.grad is None - assert tmp.grad is None - assert mm.grad is not None - assert W.grad is not None - - def test_dropout(self): - with Tensor.train(): - n, rate = 1_000_000, 0.1 - w = Tensor.ones(n).dropout(rate) - non_zeros = np.count_nonzero(w.numpy()) - expected = n * (1 - rate) - np.testing.assert_allclose(non_zeros, expected, rtol=2e-3) - - def test_jacobian(self): - W = np.random.RandomState(42069).random((10, 5)).astype(np.float32) - x = np.random.RandomState(69420).random((1, 10)).astype(np.float32) - - torch_x = torch.tensor(x, requires_grad=True) - torch_W = torch.tensor(W, requires_grad=True) - torch_func = lambda x: torch.nn.functional.log_softmax(x.matmul(torch_W).relu(), dim=1) - PJ = torch.autograd.functional.jacobian(torch_func, torch_x).squeeze().numpy() - - tiny_x = Tensor(x, requires_grad=True) - tiny_W = Tensor(W, requires_grad=True) - tiny_func = lambda x: x.dot(tiny_W).relu().log_softmax() - J = jacobian(tiny_func, tiny_x) - NJ = numerical_jacobian(tiny_func, tiny_x) - - np.testing.assert_allclose(PJ, J, atol = 1e-5) - np.testing.assert_allclose(PJ, NJ, atol = 1e-3) - - def test_gradcheck(self): - W = np.random.RandomState(1337).random((10, 5)).astype(np.float32) - x = np.random.RandomState(7331).random((1, 10)).astype(np.float32) - - tiny_x = Tensor(x, requires_grad=True) - tiny_W = Tensor(W, requires_grad=True) - tiny_func = lambda x: x.dot(tiny_W).relu().log_softmax() - - self.assertTrue(gradcheck(tiny_func, tiny_x, eps = 1e-3)) - - # coarse approx. since a "big" eps and the non-linearities of the model - self.assertFalse(gradcheck(tiny_func, tiny_x, eps = 1e-5)) - - def test_random_fns_are_deterministic_with_seed(self): - for random_fn in [Tensor.randn, Tensor.normal, Tensor.uniform, Tensor.scaled_uniform, Tensor.glorot_uniform, Tensor.kaiming_normal]: - with self.subTest(msg=f"Tensor.{random_fn.__name__}"): - Tensor.manual_seed(1337) - a = random_fn(10,10).realize() - Tensor.manual_seed(1337) - b = random_fn(10,10).realize() - np.testing.assert_allclose(a.numpy(), b.numpy()) - - def test_randn_isnt_inf_on_zero(self): - # simulate failure case of rand handing a zero to randn - original_rand, Tensor.rand = Tensor.rand, Tensor.zeros - try: self.assertNotIn(np.inf, Tensor.randn(16).numpy()) - except: raise - finally: Tensor.rand = original_rand - - def test_zeros_like_has_same_dtype(self): - for datatype in [dtypes.float16, dtypes.float32, dtypes.int8, dtypes.int32, dtypes.int64, dtypes.uint8]: - a = Tensor([1, 2, 3], dtype=datatype) - b = Tensor.zeros_like(a) - assert a.dtype == b.dtype, f"a.dtype and b.dtype should be {datatype}" - assert a.shape == b.shape, f"shape mismatch (Tensor.zeros_like){a.shape} != (torch){b.shape}" - - a = Tensor([1, 2, 3]) - b = Tensor.zeros_like(a, dtype=dtypes.int8) - assert a.dtype != b.dtype and a.dtype == dtypes.float32 and b.dtype == dtypes.int8, "a.dtype should be float and b.dtype should be char" - assert a.shape == b.shape, f"shape mismatch (Tensor.zeros_like){a.shape} != (torch){b.shape}" - - def test_ones_like_has_same_dtype_and_shape(self): - for datatype in [dtypes.float16, dtypes.float32, dtypes.int8, dtypes.int32, dtypes.int64, dtypes.uint8]: - a = Tensor([1, 2, 3], dtype=datatype) - b = Tensor.ones_like(a) - assert a.dtype == b.dtype, f"a.dtype and b.dtype should be {datatype}" - assert a.shape == b.shape, f"shape mismatch (Tensor.ones_like){a.shape} != (torch){b.shape}" - - a = Tensor([1, 2, 3]) - b = Tensor.ones_like(a, dtype=dtypes.int8) - assert a.dtype != b.dtype and a.dtype == dtypes.float32 and b.dtype == dtypes.int8, "a.dtype should be float and b.dtype should be char" - assert a.shape == b.shape, f"shape mismatch (Tensor.ones_like){a.shape} != (torch){b.shape}" - - def test_ndim(self): - assert Tensor.randn(1).ndim == 1 - assert Tensor.randn(2,2,2).ndim == 3 - assert Tensor.randn(1,1,1,1,1,1).ndim == 6 - - def test_argfix(self): - self.assertEqual(Tensor.zeros().shape, ()) - self.assertEqual(Tensor.ones().shape, ()) - - self.assertEqual(Tensor.zeros([]).shape, ()) - self.assertEqual(Tensor.ones([]).shape, ()) - - self.assertEqual(Tensor.zeros(tuple()).shape, ()) - self.assertEqual(Tensor.ones(tuple()).shape, ()) - - self.assertEqual(Tensor.zeros(1).shape, (1,)) - self.assertEqual(Tensor.ones(1).shape, (1,)) - - self.assertEqual(Tensor.zeros(1,10,20).shape, (1,10,20)) - self.assertEqual(Tensor.ones(1,10,20).shape, (1,10,20)) - - self.assertEqual(Tensor.zeros([1]).shape, (1,)) - self.assertEqual(Tensor.ones([1]).shape, (1,)) - - self.assertEqual(Tensor.zeros([10,20,40]).shape, (10,20,40)) - self.assertEqual(Tensor.ones([10,20,40]).shape, (10,20,40)) - - def test_numel(self): - assert Tensor.randn(10, 10).numel() == 100 - assert Tensor.randn(1,2,5).numel() == 10 - assert Tensor.randn(1,1,1,1,1,1).numel() == 1 - assert Tensor([]).numel() == 0 - # assert Tensor.randn(1,0,2,5) == 0 # TODO: fix empty tensors - - def test_element_size(self): - for _, dtype in dtypes.fields().items(): - assert dtype.itemsize == Tensor.randn(3, dtype=dtype).element_size(), f"Tensor.element_size() not matching Tensor.dtype.itemsize for {dtype}" - - def test_deepwalk_ctx_check(self): - layer = Tensor.uniform(1, 1, requires_grad=True) - x = Tensor.randn(1, 1, 1) - x.dot(layer).mean().backward() - x = Tensor.randn(1, 1, 1) - x.dot(layer).mean().backward() - - def test_zerosized_tensors(self): - Tensor([]).realize() - Tensor([]).numpy() - - def test_tensor_ndarray_dtype(self): - arr = np.array([1]) # where dtype is implicitly int64 - assert Tensor(arr).dtype == dtypes.int64 - assert Tensor(arr, dtype=dtypes.float32).dtype == dtypes.float32 # check if ndarray correctly casts to Tensor dtype - assert Tensor(arr, dtype=dtypes.float64).dtype == dtypes.float64 # check that it works for something else - - def test_tensor_list_dtype(self): - arr = [1] - assert Tensor(arr).dtype == Tensor.default_type - assert Tensor(arr, dtype=dtypes.float32).dtype == dtypes.float32 - assert Tensor(arr, dtype=dtypes.float64).dtype == dtypes.float64 - - def test_tensor_copy(self): - x = copy.deepcopy(Tensor.ones((3,3,3))) - np.testing.assert_allclose(x.numpy(), np.ones((3,3,3))) - - def test_copy_from_disk(self): - t = Tensor.randn(30, device="CPU").to(f"disk:{temp('test_copy_from_disk')}") - a = t[10:20] - dev = a.to(Device.DEFAULT) - np.testing.assert_allclose(a.numpy(), dev.numpy()) - - # Regression test for https://github.com/tinygrad/tinygrad/issues/1751 - def test_copy_from_numpy_unaligned(self): - # 2**15 is the minimum for repro - arr = np.random.randn(2**15).astype(dtypes.float.np) - fn = temp('test_copy_from_numpy_unaligned') - with open(fn, 'wb') as f: f.write(b't' + arr.tobytes()) - with open(fn, "a+b") as f: memview = memoryview(mmap.mmap(f.fileno(), arr.nbytes + 1)) - ua_arr = np.frombuffer(memview[1:], dtype=arr.dtype, count=arr.shape[0]) - np.testing.assert_allclose(arr, ua_arr) - assert not ua_arr.flags.aligned - # force device copy - to() is opt'd away - Tensor(dev)/1 is ignored - np.testing.assert_allclose(ua_arr, (Tensor(ua_arr)/Tensor(1)).numpy()) - -if __name__ == '__main__': - unittest.main() diff --git a/tinygrad_repo/test/test_uops.py b/tinygrad_repo/test/test_uops.py deleted file mode 100644 index a18523b..0000000 --- a/tinygrad_repo/test/test_uops.py +++ /dev/null @@ -1,99 +0,0 @@ -from typing import Optional, Tuple, Any, List -import unittest, math -import numpy as np -from tinygrad.helpers import dtypes, getenv, DType, PtrDType -from tinygrad.tensor import Device -from tinygrad.ops import UnaryOps, BinaryOps, TernaryOps, ASTRunner, Compiled -from tinygrad.codegen.linearizer import UOps, UOp - -def _uops_to_prg(uops): - src, runtime_args = Device[Device.DEFAULT].renderer("test", uops) - return ASTRunner("test", src, - [1] if Device[Device.DEFAULT].linearizer_opts.has_local else None, [1] if Device[Device.DEFAULT].linearizer_opts.has_local else None, - runtime_args=runtime_args).build(Device[Device.DEFAULT].compiler, Device[Device.DEFAULT].runtime) - -def uop(uops:List[UOp], uop:UOps, dtype:Optional[DType], vin:Tuple[UOp, ...], arg:Any=None) -> UOp: - uops.append(UOp(uop, dtype, tuple(vin), arg, len(uops))) - return uops[-1] - -def _test_single_value(vals, op, dtype): - uops = [] - buf_store = uop(uops, UOps.DEFINE_GLOBAL, PtrDType(dtype), (), ('data0', dtype)) - buf_loads = [uop(uops, UOps.DEFINE_GLOBAL, PtrDType(dtype), (), (f'data{i+1}', dtype)) for i in range(len(vals))] - loads = (uop(uops, UOps.LOAD, dtype, [buf_loads[i], uop(uops, UOps.CONST, dtypes.int32, (), 0)]) for i in range(len(vals))) - alu = uop(uops, UOps.ALU, dtype, loads, op) - uop(uops, UOps.STORE, None, (buf_store, uop(uops, UOps.CONST, dtypes.int32, (), 0), alu)) - buf = Device[Device.DEFAULT].buffer(1, dtype) - buf2 = [Device[Device.DEFAULT].buffer.fromCPU(np.array([a], dtype=dtype.np)) for a in vals] - prg = _uops_to_prg(uops) - prg([buf]+buf2) - return buf.toCPU()[0] - -def _test_single_value_const(vals, op, dtype): - uops = [] - buf_store = uop(uops, UOps.DEFINE_GLOBAL, PtrDType(dtype), (), ('data0', dtype)) - loads = (uop(uops, UOps.CONST, dtype, [], a) for a in vals) - alu = uop(uops, UOps.ALU, dtype, loads, op) - uop(uops, UOps.STORE, None, (buf_store, uop(uops, UOps.CONST, dtypes.int32, (), 0), alu)) - buf = Device[Device.DEFAULT].buffer(1, dtype) - prg = _uops_to_prg(uops) - prg([buf]) - return buf.toCPU()[0] - -class TestUOps(unittest.TestCase): - def _equal(self, v1, v2): - if not (math.isnan(v1) and math.isnan(v2)): self.assertAlmostEqual(v1, v2, places=5) - - def _test_uop_fxn(self, bop, fxn, dt=dtypes.float32): - for f in [_test_single_value, _test_single_value_const]: - for a in [-2.0, 0.0, 1.0]: - self._equal(f([a], bop, dt), fxn(a)) - - def _test_bop_fxn(self, bop, fxn, dt=dtypes.float32, no_b_zero=False): - for f in [_test_single_value, _test_single_value_const]: - for a in [-2.0, 0.0, 1.0]: - for b in [-3.0, 1.0] + ([] if no_b_zero else [0.0]): - self._equal(f([a,b], bop, dt), fxn(a,b)) - - def _test_top_fxn(self, bop, fxn, dt=dtypes.float32): - for f in [_test_single_value, _test_single_value_const]: - for a in [-2.0, 0, 1]: - for b in [-3.0, 3.0]: - for c in [-4.0, 4.0]: - self._equal(f([a,b,c], bop, dt), fxn(a,b,c)) - -@unittest.skipIf(not isinstance(Device[Device.DEFAULT], Compiled), "only test for compiled backends") -class TestFloatUOps(TestUOps): - def test_neg(self): self._test_uop_fxn(UnaryOps.NEG, lambda a: -a) - def test_exp2(self): self._test_uop_fxn(UnaryOps.EXP2, lambda a: np.exp2(a)) - def test_log2(self): self._test_uop_fxn(UnaryOps.LOG2, lambda a: math.log2(a) if a > 0 else float('-inf' if a==0 else 'nan')) - def test_sin(self): self._test_uop_fxn(UnaryOps.SIN, lambda a: math.sin(a)) - def test_sqrt(self): self._test_uop_fxn(UnaryOps.SQRT, lambda a: math.sqrt(a) if a >= 0 else float('nan')) - # this is not on most backends - #def test_recip(self): self._test_uop_fxn(UnaryOps.RECIP, lambda a: 1.0/a if a != 0 else float('inf')) - - def test_add(self): self._test_bop_fxn(BinaryOps.ADD, lambda a,b: a+b) - def test_sub(self): self._test_bop_fxn(BinaryOps.SUB, lambda a,b: a-b) - def test_mul(self): self._test_bop_fxn(BinaryOps.MUL, lambda a,b: a*b) - def test_div(self): self._test_bop_fxn(BinaryOps.DIV, lambda a,b: a/b if b != 0 else a*float('inf')) - def test_max(self): self._test_bop_fxn(BinaryOps.MAX, lambda a,b: max(a,b)) - def test_cmplt(self): self._test_bop_fxn(BinaryOps.CMPLT, lambda a,b: float(a setTimeout(resolve, time)); -} - -function cleanup(err) { - res.kill(); - if(err != null) { - console.error(err); - process.exit(1); - } -} - -async function waitForText(selector, text) { - let n = 0; - let ready = false; - while (n < 10) { - const res = await (await selector.getProperty("textContent")).jsonValue(); - console.log(`waiting for text ${text} got ${res}`); - if(res == text) { - ready = true; - break - } - await timeout(2000); - n += 1 - } - return ready; -} - -puppeteer.launch({ headless: false, args: ["--enable-unsafe-webgpu"]}).then(async browser => { - const page = await browser.newPage(); - page.on("console", message => console.log(`message from console ${message.text()}`)) - .on("pageerror", ({ message }) => console.log(`error from page ${message}`)) - - const res = await page.goto("http://localhost:8000/examples/index.html"); - if(res.status() != 200) throw new Error("Failed to load page"); - const textSelector = await page.waitForSelector("#result"); - const buttonSelector = await page.waitForSelector("input[type=button]"); - const ready = await waitForText(textSelector, "ready"); - if(!ready) throw new Error("Failed to load page"); - await buttonSelector.evaluate(e => e.click()); - const done = await waitForText(textSelector, "hen"); - if(!done) throw new Error("failed to get hen"); - browser.close(); - cleanup(null); -}).catch(err => { - cleanup(err); -}); \ No newline at end of file diff --git a/tinygrad_repo/test/test_winograd.py b/tinygrad_repo/test/test_winograd.py deleted file mode 100644 index 297bff8..0000000 --- a/tinygrad_repo/test/test_winograd.py +++ /dev/null @@ -1,40 +0,0 @@ -import unittest -from tinygrad.helpers import Timing, CI -from tinygrad.tensor import Tensor -from tinygrad.ops import LoadOps -from tinygrad.codegen.linearizer import Linearizer -from test.test_net_speed import start_profile, stop_profile - -class TestWinograd(unittest.TestCase): - def setUp(self): - self.old = Tensor.wino - Tensor.wino = 1 - def tearDown(self): Tensor.wino = self.old - - def test_speed(self): - x = Tensor.empty(1,4,9,9) - w = Tensor.empty(4,4,3,3) - - with Timing("running conv: "): - out = Tensor.conv2d(x, w) - - with Timing("scheduling: "): - sched = out.lazydata.schedule() - - for i,s in enumerate(sched): - if s.ast.op in LoadOps: continue - ops = s.ast.get_lazyops() - with Timing(f"linearize {i} with {len(ops):4d} ops: "): - l = Linearizer(s.ast) - l.hand_coded_optimizations() - l.linearize() - - def test_profile(self): - x,w = Tensor.rand(1,4,9,9).realize(), Tensor.rand(4,4,3,3).realize() - if not CI: pr = start_profile() - out = Tensor.conv2d(x,w).realize() - if not CI: stop_profile(pr, sort='time') - out.numpy() - -if __name__ == '__main__': - unittest.main(verbosity=2) \ No newline at end of file diff --git a/tinygrad_repo/test/unit/test_disk_cache.py b/tinygrad_repo/test/unit/test_disk_cache.py deleted file mode 100644 index 29b9b52..0000000 --- a/tinygrad_repo/test/unit/test_disk_cache.py +++ /dev/null @@ -1,66 +0,0 @@ -import unittest -import pickle -from tinygrad.helpers import diskcache_get, diskcache_put - -def remote_get(table,q,k): q.put(diskcache_get(table, k)) -def remote_put(table,k,v): diskcache_put(table, k, v) - -class DiskCache(unittest.TestCase): - def test_putget(self): - table = "test_putget" - diskcache_put(table, "hello", "world") - self.assertEqual(diskcache_get(table, "hello"), "world") - diskcache_put(table, "hello", "world2") - self.assertEqual(diskcache_get(table, "hello"), "world2") - - def test_putcomplex(self): - table = "test_putcomplex" - diskcache_put(table, "k", ("complex", 123, "object")) - ret = diskcache_get(table, "k") - self.assertEqual(ret, ("complex", 123, "object")) - - def test_getotherprocess(self): - table = "test_getotherprocess" - from multiprocessing import Process, Queue - diskcache_put(table, "k", "getme") - q = Queue() - p = Process(target=remote_get, args=(table,q,"k")) - p.start() - p.join() - self.assertEqual(q.get(), "getme") - - def test_putotherprocess(self): - table = "test_putotherprocess" - from multiprocessing import Process - p = Process(target=remote_put, args=(table,"k", "remote")) - p.start() - p.join() - self.assertEqual(diskcache_get(table, "k"), "remote") - - def test_no_table(self): - self.assertIsNone(diskcache_get("faketable", "k")) - - def test_ret(self): - table = "test_ret" - self.assertEqual(diskcache_put(table, "key", ("vvs",)), ("vvs",)) - - def test_non_str_key(self): - table = "test_non_str_key" - diskcache_put(table, 4, 5) - self.assertEqual(diskcache_get(table, 4), 5) - self.assertEqual(diskcache_get(table, "4"), 5) - - def test_dict_key(self): - table = "test_dict_key" - fancy_key = {"hello": "world", "goodbye": 7, "good": True, "pkl": pickle.dumps("cat")} - fancy_key2 = {"hello": "world", "goodbye": 8, "good": True, "pkl": pickle.dumps("cat")} - fancy_key3 = {"hello": "world", "goodbye": 8, "good": True, "pkl": pickle.dumps("dog")} - diskcache_put(table, fancy_key, 5) - self.assertEqual(diskcache_get(table, fancy_key), 5) - diskcache_put(table, fancy_key2, 8) - self.assertEqual(diskcache_get(table, fancy_key2), 8) - self.assertEqual(diskcache_get(table, fancy_key), 5) - self.assertEqual(diskcache_get(table, fancy_key3), None) - -if __name__ == "__main__": - unittest.main() diff --git a/tinygrad_repo/test/unit/test_disk_tensor.py b/tinygrad_repo/test/unit/test_disk_tensor.py deleted file mode 100644 index d77a31f..0000000 --- a/tinygrad_repo/test/unit/test_disk_tensor.py +++ /dev/null @@ -1,150 +0,0 @@ -import pathlib -import unittest -import numpy as np -from tinygrad.tensor import Tensor, Device -from tinygrad.nn.state import safe_load, safe_save, get_state_dict, torch_load -from tinygrad.helpers import dtypes -from tinygrad.runtime.ops_disk import RawDiskBuffer -from tinygrad.helpers import Timing -from extra.utils import fetch_as_file, temp - -def compare_weights_both(url): - import torch - fn = fetch_as_file(url) - tg_weights = get_state_dict(torch_load(fn)) - torch_weights = get_state_dict(torch.load(fn), tensor_type=torch.Tensor) - assert list(tg_weights.keys()) == list(torch_weights.keys()) - for k in tg_weights: - np.testing.assert_equal(tg_weights[k].numpy(), torch_weights[k].numpy(), err_msg=f"mismatch at {k}, {tg_weights[k].shape}") - print(f"compared {len(tg_weights)} weights") - -class TestTorchLoad(unittest.TestCase): - # pytorch pkl format - def test_load_enet(self): compare_weights_both("https://github.com/lukemelas/EfficientNet-PyTorch/releases/download/1.0/efficientnet-b0-355c32eb.pth") - # pytorch zip format - def test_load_enet_alt(self): compare_weights_both("https://download.pytorch.org/models/efficientnet_b0_rwightman-3dd342df.pth") - # pytorch zip format - def test_load_convnext(self): compare_weights_both('https://dl.fbaipublicfiles.com/convnext/convnext_tiny_1k_224_ema.pth') - # TODO: support pytorch tar format with minimal lines - #def test_load_resnet(self): compare_weights_both('https://download.pytorch.org/models/resnet50-19c8e357.pth') - -test_fn = pathlib.Path(__file__).parents[2] / "weights/LLaMA/7B/consolidated.00.pth" -#test_size = test_fn.stat().st_size -test_size = 1024*1024*1024*2 - -# sudo su -c 'sync; echo 1 > /proc/sys/vm/drop_caches' && python3 test/unit/test_disk_tensor.py TestRawDiskBuffer.test_readinto_read_speed -@unittest.skipIf(not test_fn.exists(), "download LLaMA weights for read in speed tests") -class TestRawDiskBuffer(unittest.TestCase): - def test_readinto_read_speed(self): - tst = np.empty(test_size, np.uint8) - with open(test_fn, "rb") as f: - with Timing("copy in ", lambda et_ns: f" {test_size/et_ns:.2f} GB/s"): - f.readinto(tst) - - def test_mmap_read_speed(self): - db = RawDiskBuffer(test_size, dtype=dtypes.uint8, device=test_fn) - tst = np.empty(test_size, np.uint8) - with Timing("copy in ", lambda et_ns: f" {test_size/et_ns:.2f} GB/s"): - np.copyto(tst, db.toCPU()) -@unittest.skipIf(Device.DEFAULT == "WEBGPU", "webgpu doesn't support uint8 datatype") -class TestSafetensors(unittest.TestCase): - def test_real_safetensors(self): - import torch - from safetensors.torch import save_file - torch.manual_seed(1337) - tensors = { - "weight1": torch.randn((16, 16)), - "weight2": torch.arange(0, 17, dtype=torch.uint8), - "weight3": torch.arange(0, 17, dtype=torch.int32).reshape(17,1,1), - "weight4": torch.arange(0, 2, dtype=torch.uint8), - } - save_file(tensors, temp("model.safetensors")) - - ret = safe_load(temp("model.safetensors")) - for k,v in tensors.items(): np.testing.assert_array_equal(ret[k].numpy(), v.numpy()) - safe_save(ret, temp("model.safetensors_alt")) - with open(temp("model.safetensors"), "rb") as f: - with open(temp("model.safetensors_alt"), "rb") as g: - assert f.read() == g.read() - ret2 = safe_load(temp("model.safetensors_alt")) - for k,v in tensors.items(): np.testing.assert_array_equal(ret2[k].numpy(), v.numpy()) - - def test_efficientnet_safetensors(self): - from models.efficientnet import EfficientNet - model = EfficientNet(0) - state_dict = get_state_dict(model) - safe_save(state_dict, temp("eff0")) - state_dict_loaded = safe_load(temp("eff0")) - assert sorted(list(state_dict_loaded.keys())) == sorted(list(state_dict.keys())) - for k,v in state_dict.items(): - np.testing.assert_array_equal(v.numpy(), state_dict_loaded[k].numpy()) - - # load with the real safetensors - from safetensors import safe_open - with safe_open(temp("eff0"), framework="pt", device="cpu") as f: - assert sorted(list(f.keys())) == sorted(list(state_dict.keys())) - for k in f.keys(): - np.testing.assert_array_equal(f.get_tensor(k).numpy(), state_dict[k].numpy()) - - def test_huggingface_enet_safetensors(self): - # test a real file - fn = fetch_as_file("https://huggingface.co/timm/mobilenetv3_small_075.lamb_in1k/resolve/main/model.safetensors") - state_dict = safe_load(fn) - assert len(state_dict.keys()) == 244 - assert 'blocks.2.2.se.conv_reduce.weight' in state_dict - assert state_dict['blocks.0.0.bn1.num_batches_tracked'].numpy() == 276570 - assert state_dict['blocks.2.0.bn2.num_batches_tracked'].numpy() == 276570 - - def test_metadata(self): - metadata = {"hello": "world"} - safe_save({}, temp('metadata.safetensors'), metadata) - import struct - with open(temp('metadata.safetensors'), 'rb') as f: - dat = f.read() - sz = struct.unpack(">Q", dat[0:8])[0] - import json - assert json.loads(dat[8:8+sz])['__metadata__']['hello'] == 'world' - -def helper_test_disk_tensor(fn, data, np_fxn, tinygrad_fxn=None): - if tinygrad_fxn is None: tinygrad_fxn = np_fxn - pathlib.Path(temp(fn)).unlink(missing_ok=True) - tinygrad_tensor = Tensor(data, device="CPU").to(f"disk:{temp(fn)}") - numpy_arr = np.array(data) - tinygrad_fxn(tinygrad_tensor) - np_fxn(numpy_arr) - np.testing.assert_allclose(tinygrad_tensor.numpy(), numpy_arr) - -class TestDiskTensor(unittest.TestCase): - def test_empty(self): - pathlib.Path(temp("dt1")).unlink(missing_ok=True) - Tensor.empty(100, 100, device=f"disk:{temp('dt1')}") - - def test_write_ones(self): - pathlib.Path(temp("dt2")).unlink(missing_ok=True) - - out = Tensor.ones(10, 10, device="CPU") - outdisk = out.to(f"disk:{temp('dt2')}") - print(outdisk) - outdisk.realize() - del out, outdisk - - # test file - with open(temp("dt2"), "rb") as f: - assert f.read() == b"\x00\x00\x80\x3F" * 100 - - # test load alt - reloaded = Tensor.empty(10, 10, device=f"disk:{temp('dt2')}") - out = reloaded.numpy() - assert np.all(out == 1.) - - def test_assign_slice(self): - def assign(x,s,y): x[s] = y - helper_test_disk_tensor("dt3", [0,1,2,3], lambda x: assign(x, slice(0,2), [13, 12])) - helper_test_disk_tensor("dt4", [[0,1,2,3],[4,5,6,7]], lambda x: assign(x, slice(0,1), [[13, 12, 11, 10]])) - - def test_reshape(self): - helper_test_disk_tensor("dt5", [1,2,3,4,5], lambda x: x.reshape((1,5))) - helper_test_disk_tensor("dt6", [1,2,3,4], lambda x: x.reshape((2,2))) - -if __name__ == "__main__": - unittest.main() diff --git a/tinygrad_repo/test/unit/test_flopcounter.py b/tinygrad_repo/test/unit/test_flopcounter.py deleted file mode 100644 index 22f91ee..0000000 --- a/tinygrad_repo/test/unit/test_flopcounter.py +++ /dev/null @@ -1,44 +0,0 @@ -#!/usr/bin/env python -import unittest -from tinygrad.ops import LazyOp, BinaryOps, ReduceOps, get_lazyop_info, BufferOps, MemBuffer -from tinygrad.shape.shapetracker import ShapeTracker -from tinygrad.helpers import dtypes - -class TestFlopCounter(unittest.TestCase): - def setUp(self): - self.buf0 = LazyOp(BufferOps.MEM, (), MemBuffer(1, dtypes.float32, ShapeTracker.from_shape((4,)))) - self.buf1 = LazyOp(BufferOps.MEM, (), MemBuffer(2, dtypes.float32, ShapeTracker.from_shape((4,)))) - - def test_flops_add(self): - op0 = LazyOp(BinaryOps.ADD, (self.buf0,self.buf1,), None) - info = get_lazyop_info(op0) - self.assertEqual(info.flops, 4) - - def test_flops_add_twice(self): - op0 = LazyOp(BinaryOps.ADD, (self.buf0,self.buf1,), None) - op1 = LazyOp(BinaryOps.ADD, (op0,self.buf1,), None) - info = get_lazyop_info(op1) - self.assertEqual(info.flops, 8) - - def test_flops_add_self(self): - op0 = LazyOp(BinaryOps.ADD, (self.buf0,self.buf1,), None) - op1 = LazyOp(BinaryOps.ADD, (op0,op0,), None) - info = get_lazyop_info(op1) - self.assertEqual(info.flops, 8) - - def test_flops_add_roundabout_self(self): - op0 = LazyOp(BinaryOps.ADD, (self.buf0,self.buf1,), None) - op1 = LazyOp(BinaryOps.ADD, (op0,self.buf1,), None) - op2 = LazyOp(BinaryOps.ADD, (op0,op1,), None) - info = get_lazyop_info(op2) - self.assertEqual(info.flops, 12) - - def test_flops_red(self): - op0 = LazyOp(BinaryOps.MUL, (self.buf0,self.buf1,), None) - op1 = LazyOp(ReduceOps.SUM, (op0,), (1,)) - op2 = LazyOp(BinaryOps.ADD, (op1, op1,), None) - info = get_lazyop_info(op2) - self.assertEqual(info.flops, 9) - -if __name__ == '__main__': - unittest.main() diff --git a/tinygrad_repo/test/unit/test_helpers.py b/tinygrad_repo/test/unit/test_helpers.py deleted file mode 100644 index 60d00c7..0000000 --- a/tinygrad_repo/test/unit/test_helpers.py +++ /dev/null @@ -1,142 +0,0 @@ -import unittest -import numpy as np -from tinygrad.helpers import Context, ContextVar, DType, dtypes, merge_dicts, strip_parens, prod -from tinygrad.shape.symbolic import Variable, NumNode - -VARIABLE = ContextVar("VARIABLE", 0) - -class TestContextVars(unittest.TestCase): - # Ensuring that the test does not modify variables outside the tests. - ctx = Context() - def setUp(self): TestContextVars.ctx.__enter__() - def tearDown(self): TestContextVars.ctx.__exit__() - - def test_initial_value_is_set(self): - _TMP = ContextVar("_TMP", 5) - self.assertEqual(_TMP.value, 5) - - def test_multiple_creation_ignored(self): - _TMP2 = ContextVar("_TMP2", 1) - _TMP2 = ContextVar("_TMP2", 2) - self.assertEqual(_TMP2.value, 1) - - def test_new_var_inside_context(self): - # Creating a _new_ variable inside a context should not have any effect on its scope (?) - with Context(VARIABLE=1): - _TMP3 = ContextVar("_TMP3", 1) - _TMP3 = ContextVar("_TMP3", 2) - self.assertEqual(_TMP3.value, 1) - - def test_value_accross_modules(self): - # Mocking module import by invoking the code but not in our globals(). - exec('from tinygrad.helpers import ContextVar;C = ContextVar("C", 13)', {}) # pylint:disable=exec-used - # It should not matter that the first creation was in another module. - C = ContextVar("C", 0) - self.assertEqual(C.value, 13) - - def test_assignment_across_modules(self): - B = ContextVar("B", 1) - # local assignment - B.value = 2 - self.assertEqual(B.value, 2) - # Assignment in another module. - exec('from tinygrad.helpers import ContextVar;B = ContextVar("B", 0);B.value = 3;', {}) # pylint:disable=exec-used - # Assignment in another module should affect this one as well. - self.assertEqual(B.value, 3) - - def test_context_assignment(self): - with Context(VARIABLE=1): - self.assertEqual(VARIABLE.value, 1) - self.assertEqual(VARIABLE.value, 0) - - def test_unknown_param_to_context(self): - with self.assertRaises(KeyError): - with Context(SOMETHING_ELSE=1): - pass - - def test_inside_context_assignment(self): - with Context(VARIABLE=4): - # What you can and cannot do inside a context. - # 1. This type of statement has no effect. - VARIABLE = ContextVar("VARIABLE", 0) - self.assertTrue(VARIABLE >= 4, "ContextVars inside contextmanager may not set a new value") - - # 2. The call syntax however has a local effect. - VARIABLE.value = 13 - self.assertTrue(VARIABLE.value == 13, "Call syntax however works inside a contextmanager.") - - # Related to 2. above. Note that VARIABLE is back to 0 again as expected. - self.assertEqual(VARIABLE.value, 0) - - def test_new_var_inside_context_other_module(self): - with Context(VARIABLE=1): - _NEW2 = ContextVar("_NEW2", 0) - _NEW2 = ContextVar("_NEW2", 1) - self.assertEqual(_NEW2.value, 0) - - code = """\ -from tinygrad.helpers import Context, ContextVar -with Context(VARIABLE=1): - _NEW3 = ContextVar("_NEW3", 0)""" - exec(code, {}) # pylint:disable=exec-used - # While _NEW3 was created in an outside scope it should still work the same as above. - _NEW3 = ContextVar("_NEW3", 1) - self.assertEqual(_NEW3.value, 0) - - def test_nested_context(self): - with Context(VARIABLE=1): - with Context(VARIABLE=2): - with Context(VARIABLE=3): - self.assertEqual(VARIABLE.value, 3) - self.assertEqual(VARIABLE.value, 2) - self.assertEqual(VARIABLE.value, 1) - self.assertEqual(VARIABLE.value, 0) - - def test_decorator(self): - @Context(VARIABLE=1, DEBUG=4) - def test(): - self.assertEqual(VARIABLE.value, 1) - - self.assertEqual(VARIABLE.value, 0) - test() - self.assertEqual(VARIABLE.value, 0) - - def test_context_exit_reverts_updated_values(self): - D = ContextVar("D", 1) - D.value = 2 - with Context(D=3): - ... - assert D.value == 2, f"Expected D to be 2, but was {D.value}. Indicates that Context.__exit__ did not restore to the correct value." - -class TestMergeDicts(unittest.TestCase): - def test_merge_dicts(self): - a = {"a": 1, "b": 2} - b = {"a": 1, "c": 3} - c = {} - d = {"a": 2, "b": 2} - assert merge_dicts([a, b]) == {"a": 1, "b": 2, "c": 3} - assert merge_dicts([a, c]) == a - assert merge_dicts([a, b, c]) == {"a": 1, "b": 2, "c": 3} - with self.assertRaises(AssertionError): - merge_dicts([a, d]) - -class TestDtypes(unittest.TestCase): - def test_dtypes_fields(self): - fields = dtypes.fields() - self.assertTrue(all(isinstance(value, DType) for value in fields.values())) - self.assertTrue(all(issubclass(value.np, np.generic) for value in fields.values() if value.np is not None)) - -class TestStripParens(unittest.TestCase): - def test_simple(self): self.assertEqual("1+2", strip_parens("(1+2)")) - def test_nested(self): self.assertEqual("1+(2+3)", strip_parens("(1+(2+3))")) - def test_casted_no_strip(self): self.assertEqual("(int)(1+2)", strip_parens("(int)(1+2)")) - -class TestProd(unittest.TestCase): - def test_empty(self): self.assertEqual(1, prod(tuple())) - def test_ints(self): self.assertEqual(30, prod((2, 3, 5))) - def test_variable(self): self.assertEqual("(a*12)", prod((Variable("a", 1, 5), 3, 4)).render()) - def test_variable_order(self): self.assertEqual("(a*12)", prod((3, 4, Variable("a", 1, 5))).render()) - def test_num_nodes(self): self.assertEqual(NumNode(6), prod((NumNode(2), NumNode(3)))) - -if __name__ == '__main__': - unittest.main() \ No newline at end of file diff --git a/tinygrad_repo/test/unit/test_shapetracker.py b/tinygrad_repo/test/unit/test_shapetracker.py deleted file mode 100644 index 3786725..0000000 --- a/tinygrad_repo/test/unit/test_shapetracker.py +++ /dev/null @@ -1,663 +0,0 @@ -#!/usr/bin/env python -import unittest -import numpy as np -from tinygrad.helpers import prod, DEBUG -from tinygrad.shape.shapetracker import ShapeTracker, View, get_contraction -from tinygrad.shape.symbolic import Variable -from itertools import product - -def shapetracker_getitem(st, val): - locals = {"idx": val, "valid": 1} - idx, valid = st.expr_node() - exec(f"valid={valid.render()};idx={idx.render()}", None, locals) - return locals["idx"] if locals["valid"] else -1 - -class CheckingShapeTracker: - def __init__(self, shape): - self.st = ShapeTracker.from_shape(shape) - self.t = np.arange(prod(shape), dtype=np.int32).reshape(shape) - - @property - def shape(self): - return self.t.shape - - def simplify(self): - self.st = self.st.simplify() - return self - - def reshape(self, new_shape): - self.st = self.st.reshape(new_shape) - self.t = self.t.reshape(new_shape) - return self - - def permute(self, axis): - self.st = self.st.permute(axis) - self.t = np.transpose(self.t, axis) - return self - - def expand(self, new_shape): - self.st = self.st.expand(new_shape) - self.t = np.broadcast_to(self.t, new_shape) - return self - - def flip(self, axis): - self.st = self.st.stride(tuple(-1 if i in axis else 1 for i in range(len(self.shape)))) - self.t = np.flip(self.t, axis) - return self - - def shrink(self, arg): - self.st = self.st.shrink(arg) - self.t = self.t[tuple([slice(x[0], x[1]) for x in arg])] - return self - - def pad(self, arg): - self.st = self.st.pad(arg) - self.t = np.pad(self.t, arg, constant_values=-1) - return self - - def stride(self, arg): - self.st = self.st.stride(arg) - self.t = self.t[tuple([slice(None, None, x) for x in arg])] - return self - - def __getitem__(self, val): - return self.t.flatten()[val] - - @property - def views(self): return self.st.views - - @property - def contiguous(self): return self.st.contiguous - - def assert_same(self): - x = [shapetracker_getitem(self.st, i) for i in range(prod(self.st.shape))] - y = [self[i] for i in range(prod(self.shape))] - idx, valid = self.st.expr_node() - if DEBUG >= 1: print(x, y, self.st.shape, self.shape, idx.render(), valid.render(), self.st) - assert self.st.shape == self.shape - assert x == y, f"mismatch shapetracker:{x} real:{y}" - -class TestRealIssues(unittest.TestCase): - def test_reshape_doesnt_multiview(self): - self.st = ShapeTracker((View.create((256, 256, 2, 2, 2, 2, 2, 256, 8, 2), (0, 8, 0, 4, 0, 0, 2, 16384, 2048, 1), 0, None),)) - self.st.reshape((128, 2, 256, 2, 2, 2, 2, 2, 256, 8, 2)) - assert len(self.st.views) == 1 - -class TestRealDoesntSimplify(unittest.TestCase): - def tearDown(self): - st = self.st.real_strides() - print(st) - self.st = self.st.simplify() - assert len(self.st.views) != 1 - assert None in st - - def test_1(self): - self.st = ShapeTracker(( - View.create((8, 3, 1, 2, 11, 1), (33, 11, 0, 0, 1, 0), 0, None), - View.create((8, 6, 11), (66, 11, 1), 0, None))) - assert self.st.real_strides() == (33, None, 1) - - def test_2(self): - self.st = ShapeTracker(( - View.create((2, 2, 4, 3, 3), (72, 9, 18, -3, -1), 8, None), - View.create((4, 4, 3, 3), (36, 9, 3, 1), 0, None))) - assert self.st.real_strides() == (None, 18, -3, -1) - -class TestRealStrides(unittest.TestCase): - def test_1(self): - self.st = ShapeTracker(( - View.create((2048,), (1,), 0, ((0, 512),)), - View.create((16, 32, 4), (128, 4, 1), 0, None))) - st = self.st.real_strides() - print(self.st, st) - assert st == (None, 4, 1) - -class TestRealSimplifies(unittest.TestCase): - def tearDown(self): - st = self.st.real_strides() - self.st = self.st.simplify() - assert len(self.st.views) == 1 - print(self.st.views[-1].strides, st) - assert self.st.views[-1].strides == st - - def test_1(self): - self.st = ShapeTracker(( - View.create((1, 3, 2, 11, 4, 28), (0, 308, 0, 28, 0, 1), 0, None), - View.create((1, 3, 2, 11, 26, 1, 1, 3), (0, 2464, 0, 112, 1, 0, 0, 29), 0, None))) - - def test_2(self): - self.st = ShapeTracker(( - View.create((8, 3, 3, 11, 2, 28), (924, 308, 0, 28, 0, 1), 0, None), - View.create((8, 1, 6, 10, 28, 3, 2, 1), (5544, 0, 0, 56, 1, 1848, 672, 0), 0, None))) - -class TestIndexExpressions2d(unittest.TestCase): - - def setUp(self): - shapes = [(30, 5), (15, 10), (15, 1), (5, 10), (5, 1)] # Make sure dim0 is a multiple of 5, one of the tests divides this dimension by 5 - offsets = [0, 1, 15, 28, 10000] - self.sts = [ShapeTracker((View.create(base_shape, offset=offset),)) for base_shape in shapes for offset in offsets] - self.offset = [Variable.num(offset) for base_shape in shapes for offset in offsets] - self.shapes = [shape for shape in shapes for offset in offsets] - self.node_exprs = [] - self.idxs_exprs = [] - - def tearDown(self): - for st, offset, shape, node_expr, idxs_expr in zip(self.sts, self.offset, self.shapes, self.node_exprs, self.idxs_exprs): - numel = prod(shape) - assert node_expr(self.default_idx(st.shape)) == st.expr_node()[0] - assert node_expr(self.default_idx(st.shape)) == st.expr_node(None)[0] - assert node_expr(self.default_idx(st.shape)) == st.expr_node('idx')[0] - self.check_bounds(node_expr(self.default_idx(st.shape)), offset, numel) - for idx in [(0, numel-1), (7, 203), (2, 5), (0, 0), (numel, numel), (0, numel), (0, numel+1), (numel+100, numel+100)]: - idx = Variable("idx", idx[0], idx[1]) - assert node_expr(idx) == st.expr_node(idx)[0] - self.check_bounds(node_expr(idx), offset, numel) - - assert idxs_expr(self.default_idxs(st.shape)) == st.expr_idxs()[0] - assert idxs_expr(self.default_idxs(st.shape)) == st.expr_idxs(None)[0] - self.check_bounds(idxs_expr(self.default_idxs(st.shape)), offset, numel) - idx0s = [(0,0), (0, min(1, st.shape[0]-1)), (0, st.shape[0]-1), (min(3, st.shape[0]-1), min(6, st.shape[0]-1)), (st.shape[0]-1, st.shape[0]-1)] - idx1s = [(0,0), (0, min(1, st.shape[1]-1)), (0, st.shape[1]-1), (min(3, st.shape[1]-1), min(6, st.shape[1]-1)), (st.shape[1]-1, st.shape[1]-1)] - idx2s = [(0,0), (0, min(1, st.shape[2]-1)), (0, st.shape[2]-1), (min(3, st.shape[2]-1), min(6, st.shape[2]-1)), (st.shape[2]-1, st.shape[2]-1)] if len(st.shape) == 3 else [None for _ in idx0s] - for idx0, idx1, idx2 in product(idx0s, idx1s, idx2s): - idxs = [Variable(f"idx{i}", idx[0], idx[1]) for i, idx in enumerate((idx0, idx1, idx2)) if idx is not None] - assert idxs_expr(idxs) == st.expr_idxs(idxs)[0] - self.check_bounds(idxs_expr(idxs), offset, numel) - - def default_idx(self, shape): - return Variable("idx", 0, prod(shape)-1) - - def default_idxs(self, shape): - return [Variable(f"idx{i}", 0, d-1) for i,d in enumerate(shape)] - - def check_bounds(self, expr, offset, numel): - assert expr.min >= offset - assert expr.max <= offset + numel - 1 - - def test_noop(self): - for st, base_shape, offset in zip(self.sts, self.shapes, self.offset): - self.node_exprs.append(lambda idx, base_shape=base_shape, offset=offset: idx%prod(base_shape) + offset) - self.idxs_exprs.append(lambda idxs, base_shape=base_shape, offset=offset: idxs[0]*base_shape[1] + idxs[1] + offset) - - def test_permute(self): - new_st = [] - for st, base_shape, offset in zip(self.sts, self.shapes, self.offset): - st = st.permute((1, 0)) - self.node_exprs.append(lambda idx, base_shape=base_shape, offset=offset: idx%base_shape[0]*base_shape[1] + idx//base_shape[0]%base_shape[1] + offset) - self.idxs_exprs.append(lambda idxs, base_shape=base_shape, offset=offset: idxs[0] + idxs[1]*base_shape[1] + offset) - new_st.append(st) - self.sts = new_st - - def test_reshape(self): - new_st = [] - for st, base_shape, offset in zip(self.sts, self.shapes, self.offset): - st = st.reshape((base_shape[0], 1, base_shape[1])) - self.node_exprs.append(lambda idx, base_shape=base_shape, offset=offset: idx%prod(base_shape) + offset) - self.idxs_exprs.append(lambda idxs, base_shape=base_shape, offset=offset: idxs[0]*base_shape[1] + idxs[2] + offset) - new_st.append(st) - self.sts = new_st - - def test_reshape_expand(self): - new_st = [] - for st, base_shape, offset in zip(self.sts, self.shapes, self.offset): - st = st.reshape((base_shape[0], 1, base_shape[1])) - st = st.expand((base_shape[0], base_shape[1], base_shape[1])) - self.node_exprs.append(lambda idx, base_shape=base_shape, offset=offset: idx//(base_shape[1]*base_shape[1])%base_shape[0]*base_shape[1] + idx%base_shape[1] + offset) - self.idxs_exprs.append(lambda idxs, base_shape=base_shape, offset=offset: idxs[0]*base_shape[1] + idxs[2] + offset) - new_st.append(st) - self.sts = new_st - - def test_permute_reshape_1(self): # This tests multiple views - new_st = [] - for st, base_shape, offset in zip(self.sts, self.shapes, self.offset): - st = st.permute((1, 0)) - st = st.reshape((base_shape[0]//5, 1, base_shape[1]*5)) - self.node_exprs.append(lambda idx, base_shape=base_shape, offset=offset: idx%prod(base_shape)%base_shape[0]*base_shape[1] + idx//base_shape[0]%base_shape[1] + offset) - self.idxs_exprs.append(lambda idxs, base_shape=base_shape, offset=offset: (idxs[0]*(base_shape[1]*5)+idxs[2])%base_shape[0]*base_shape[1] + (idxs[0]*(base_shape[1]*5)+idxs[2])//base_shape[0] + offset) - new_st.append(st) - self.sts = new_st - - def test_permute_reshape_2(self): - new_st = [] - for st, base_shape, offset in zip(self.sts, self.shapes, self.offset): - st = st.permute((1, 0)) - st = st.reshape((1, base_shape[0]//5, base_shape[1]*5)) - self.node_exprs.append(lambda idx, base_shape=base_shape, offset=offset: idx%prod(base_shape)%base_shape[0]*base_shape[1] + idx//base_shape[0]%base_shape[1] + offset) - self.idxs_exprs.append(lambda idxs, base_shape=base_shape, offset=offset: (idxs[1]*(base_shape[1]*5)+idxs[2])%base_shape[0]*base_shape[1] + (idxs[1]*(base_shape[1]*5)+idxs[2])//base_shape[0] + offset) - new_st.append(st) - self.sts = new_st - -class TestSimplifyingShapeTracker(unittest.TestCase): - def setUp(self): - self.st = CheckingShapeTracker((1, 10)) - - def tearDown(self): - self.st.assert_same() - - # multiview simplify - def test_expand_contract_simple(self): - self.st = self.st.expand((10, 10)) - self.st = self.st.reshape((100,)) - print(self.st.views) - assert(len(self.st.views) == 2) - self.st = self.st.reshape((10, 10)) - print(self.st.views) - - self.st = self.st.simplify() - print(self.st.views) - assert(len(self.st.views) == 1) - - # multiview simplify - def test_expand_contract_different_shape(self): - self.st.expand((10, 10)) - self.st.reshape((100,)) - print(self.st.views) - assert(len(self.st.views) == 2) - self.st.reshape((2, 5, 2, 5)) - print(self.st.views) - - self.st = self.st.simplify() - print(self.st.views) - assert(len(self.st.views) == 1) - - # multiview simplify - def test_expand_contract_still_complex(self): - self.st.expand((10, 10)) - self.st.reshape((100,)) - print(self.st.views) - assert(len(self.st.views) == 2) - self.st.reshape((5, 20)) - - self.st = self.st.simplify() - print(self.st.views) - assert(len(self.st.views) == 2) - -# Tensor.zeros(2, 4).permute(1,0).reshape(2, 4) -# (d1*4 + d0%4), d1=x//4, d0=x%4 = ((x//4)*4) + (x%4)%4 - -class TestComplexShapeTracker(unittest.TestCase): - def test_add_1s(self): - self.st = CheckingShapeTracker((4, 4)) - self.st.permute((1,0)) - self.st.reshape((1,4,1,4,1)) - assert not self.st.contiguous - self.st.permute((0,3,2,1,4)) - assert self.st.contiguous - - def test_permute_1s_simple(self): - self.st = CheckingShapeTracker((1, 16, 9,9)) - self.st.permute((1,0,2,3)) - assert self.st.contiguous - self.st = CheckingShapeTracker((2, 16, 9,9)) - self.st.permute((1,0,2,3)) - assert not self.st.contiguous - - def test_remove_1s_simple(self): - self.st = CheckingShapeTracker((1, 16, 1, 1)) - self.st.reshape((16,)) - assert self.st.contiguous - - def test_remove_1s(self): - self.st = CheckingShapeTracker((1, 4, 1, 4, 1)) - self.st.permute((0,3,2,1,4)) - self.st.reshape((4,4)) - assert not self.st.contiguous - self.st.permute((1,0)) - assert self.st.contiguous - - def test_permute_reshape(self): - self.st = CheckingShapeTracker((4, 4)) - self.st.permute((1,0)) - self.st.reshape((2, 2, 2, 2)) - # TODO: should also be tested by test_super_complex - assert len(self.st.views) == 1 - - def test_factorize_split(self): - self.st = CheckingShapeTracker((4, 4)) - self.st.permute((1,0)) - self.st.reshape((2, 2, 2, 2)) - self.st.permute((2,3,0,1)) - assert self.st.contiguous - - def test_factorize_combine(self): - self.st = CheckingShapeTracker((4, 4, 4)) - self.st.permute((2, 0, 1)) - self.st.reshape((4, 16)) - self.st.permute((1, 0)) - assert self.st.contiguous - - def test_factorize_combine_add_ones(self): - self.st = CheckingShapeTracker((4, 4, 4)) - self.st.permute((2, 0, 1)) - self.st.reshape((4, 16, 1, 1)) - self.st.permute((1, 0, 2, 3)) - assert self.st.contiguous - - def test_fancy_factorize(self): - self.st = CheckingShapeTracker((32, 3, 3, 1)) - self.st.reshape((8, 4, 3, 3)) - assert len(self.st.views) == 1 - - def test_super_complex_2_fail(self): - self.st = CheckingShapeTracker((4, 4, 4)) - self.st.permute((2, 0, 1)) - self.st.reshape((16, 4)) - assert len(self.st.views) != 1 - - def test_work(self): - self.st = CheckingShapeTracker((64, 1024, 4)) - self.st.reshape((1, 64, 128, 32)) - self.st.permute((0, 3, 1, 2)) - self.st.reshape((1, 32, 1, 64, 128)) - self.st.permute((0, 3, 4, 1, 2)) - assert self.st.contiguous - - def test_work2(self): - self.st = CheckingShapeTracker((64, 1024, 4)) - self.st.reshape((1, 64, 128, 32)) - self.st.permute((0, 3, 1, 2)) - self.st.reshape((1, 1, 32, 64, 128)) - self.st.permute((0, 3, 4, 1, 2)) - self.st.reshape((64, 1024, 4)) - print(self.st.views) - assert self.st.contiguous - -class TestSingleShapeTracker(unittest.TestCase): - def setUp(self): - self.st = CheckingShapeTracker((7,4)) - - def tearDown(self): - self.st.assert_same() - - def test_reshape(self): - self.st.reshape((7,1,4)) - assert self.st.contiguous - - def test_permute(self): - self.st.permute((1,0)) - assert not self.st.contiguous - - def test_shrink(self): - self.st.shrink(((1,2), (0,4))) - assert not self.st.contiguous - - def test_double_permute(self): - self.st.permute((1,0)) - self.st.permute((1,0)) - assert self.st.contiguous - - def test_reshape_permute(self): - self.st.reshape((7,1,4)) - self.st.permute((0,1,2)) - assert self.st.contiguous - - def test_reshape_permute_yes(self): - self.st.reshape((7,1,4)) - self.st.permute((0,2,1)) - assert self.st.contiguous - - def test_reshape_permute_no(self): - self.st.reshape((4,7)) - self.st.permute((1,0)) - assert not self.st.contiguous - -class TestShapeTrackerFuzzFailures(unittest.TestCase): - def setUp(self): - self.st = CheckingShapeTracker((3,3,3)) - def tearDown(self): - self.st.assert_same() - @unittest.skip("simplify doesn't work in this case") - def test_case_1(self): - self.st.shrink(((1, 2), (1, 3), (1, 3))) - self.st.reshape((1, 4)) - self.st.shrink(((0, 1), (1, 3))) - print(self.st.st) - self.st = self.st.simplify() - print(self.st.st) - def test_case_2(self): - self.st.stride( (1, 1, -2) ) - self.st.reshape( (3, 6) ) - self.st.shrink( ((1, 2), (1, 5)) ) - self.st.stride( (1, -1) ) - def test_case_3(self): - self.st.shrink( ((0, 2), (0, 2), (0, 1)) ) - self.st.permute( (1, 0, 2) ) - self.st.reshape( (4,) ) - self.st.shrink( ((0, 3),) ) - self.st.stride( (-1,) ) - def test_case_4(self): - self.st.reshape( (3, 3, 3, 1) ) - self.st.pad( ((0, 0), (0, 0), (0, 0), (1, 1)) ) - self.st.shrink( ((0, 2), (1, 2), (0, 2), (0, 1)) ) - self.st.expand( (2, 1, 2, 3) ) - -class TestMaskedShapeTracker(unittest.TestCase): - def test_pad_1x1(self): - self.st = CheckingShapeTracker((1,1)) - self.st.pad(((1,1), (1,1))) - self.st.assert_same() - - def test_pad_2x2(self): - self.st = CheckingShapeTracker((2,2)) - self.st.pad(((1,1), (1,1))) - self.st.assert_same() - -class TestShapeTracker(unittest.TestCase): - def setUp(self): - self.st = CheckingShapeTracker((7,4)) - self.apply = lambda fxn: [fxn(x) for x in [self.st]] - - def tearDown(self): - self.st.assert_same() - - def test_noop(self): - pass - - def test_simple_split(self): - self.test_permute() - self.apply(lambda x: x.reshape((prod(self.st.shape), ))) - - def test_simple_pad(self): - self.st.pad(((1,1), (1,1))) - - def test_pad_shrink(self): - self.st.pad(((1,1), (1,1))) - self.st.shrink(((0,4), (0,4))) - - def test_pad_one_sided(self): - self.st.pad(((0,1), (0,0))) - - def test_pad_reshape(self): - self.st.pad(((0,1), (0,0))) - self.st.reshape((8*4,)) - - def test_pad_pad(self): - self.st.pad(((1,1), (1,1))) - self.st.pad(((1,1), (1,1))) - - def test_pad_permute(self): - self.st.pad(((1,1), (2,2))) - self.st.permute((1,0)) - - def test_pad_expand(self): - self.st.reshape((7,4,1)) - self.st.pad(((1,1), (1,1), (0,0))) - self.st.expand((9,6,4)) - - def test_pad_expand_alt(self): - self.st.pad(((1,1), (1,1))) - self.st.reshape((9,6,1)) - self.st.expand((9,6,4)) - - def test_pad_stride(self): - self.st.pad(((1,4), (1,3))) - self.st.stride((2,2)) - - def test_pad_stride_neg(self): - self.st.pad(((1,2), (1,0))) - self.st.stride((-1,-1)) - - def test_pad_stride_both(self): - self.st.pad(((1,2), (1,0))) - self.st.stride((-2,-2)) - - def test_shrink_pad(self): - self.st.shrink(((0,4), (0,4))) - self.st.pad(((1,1), (1,1))) - - def test_reshape(self): - new_shape = self.st.shape[::-1] - self.apply(lambda x: x.reshape(new_shape)) - - def test_permute(self): - if len(self.st.shape) == 2: self.apply(lambda x: x.permute((1,0))) - elif len(self.st.shape) == 3: self.apply(lambda x: x.permute((2,0,1))) - - def test_reshape_with_1(self): - new_shape = (self.st.shape[0], 1, self.st.shape[1]) - self.apply(lambda x: x.reshape(new_shape)) - - def test_expand(self): - self.test_reshape_with_1() - new_shape = list(self.st.shape) - new_shape[1] = 2 - self.apply(lambda x: x.expand(tuple(new_shape))) - - def test_flip_0(self): - self.apply(lambda x: x.flip((0,))) - - def test_flip_1(self): - self.apply(lambda x: x.flip((1,))) - - def test_flip_01(self): - self.apply(lambda x: x.flip((0,1))) - - def test_slice_0(self): - self.apply(lambda x: x.shrink(((1, x.shape[0]), (0, x.shape[1])))) - - def test_slice_1(self): - self.apply(lambda x: x.shrink(((0, x.shape[0]), (1, x.shape[1])))) - - def test_slice_1c1(self): - self.apply(lambda x: x.shrink(((0, 1), (0, 1)))) - - def test_slice_1c2(self): - self.apply(lambda x: x.shrink(((1, 2), (1, 2)))) - - def test_double_permute(self): - self.apply(lambda x: x.permute((1, 0))) - self.apply(lambda x: x.permute((1, 0))) - - def test_slice_permute(self): - self.apply(lambda x: x.shrink(((0, 2), (2, 4)))) - self.apply(lambda x: x.permute((1, 0))) - - def test_slice_expand(self): - self.apply(lambda x: x.shrink(((0, 2), (3, 4)))) - self.apply(lambda x: x.expand((2, 10))) - - def test_double_stride(self): - self.apply(lambda x: x.stride((1, 2))) - self.apply(lambda x: x.stride((2, 1))) - - def test_stride(self): self.apply(lambda x: x.stride((2,1))) - def test_stride_int(self): self.apply(lambda x: x.stride((1,2))) - def test_stride_2(self): self.apply(lambda x: x.stride((2,2))) - def test_stride_n(self): self.apply(lambda x: x.stride((-2,1))) - def test_stride_int_n(self): self.apply(lambda x: x.stride((-1,2))) - def test_stride_2_n(self): self.apply(lambda x: x.stride((-2,-2))) - - def test_reshape_then_permute(self): - self.test_reshape() - self.test_permute() - - def test_reshape_then_expand(self): - self.test_reshape() - self.test_expand() - - def test_permute_then_reshape(self): - self.test_permute() - self.test_reshape() - - def test_expand_then_reshape(self): - self.test_expand() - self.test_reshape() - - def test_combo(self): - self.test_permute() - self.test_reshape() - self.test_slice_1() - self.test_expand() - self.test_permute() - -class TestGetContraction(unittest.TestCase): - def test_contraction(self): - r = get_contraction((1,2,3,4), (2,3,4)) - self.assertEqual(r, [[0, 1], [2], [3]]) - - r = get_contraction((2,1,3,4), (2,3,4)) - self.assertEqual(r, [[0], [1, 2], [3]]) - - r = get_contraction((1,2,3,1,4), (1,2,3,4)) - self.assertEqual(r, [[0], [1], [2], [3, 4]]) - - r = get_contraction((1,2,3,1,4,1,1), (2,3,4)) - self.assertEqual(r, [[0, 1], [2], [3, 4, 5, 6]]) - - r = get_contraction((1,2,3,4), (1,2,3*4)) - self.assertEqual(r, [[0], [1], [2, 3]]) - - r = get_contraction((1,2,3,4), (2,1,3,4)) - self.assertEqual(r, [[0, 1], [], [2], [3]]) - - r = get_contraction((1,2,3,4), (1,1,2*3*4,1)) - self.assertEqual(r, [[0], [], [1,2,3], []]) - - r = get_contraction((2,1,3,4), (1,2,3,4)) - self.assertEqual(r, [[], [0], [1, 2], [3]]) - - r = get_contraction((1,2,3,4), (2*3*4,1,1,1)) - self.assertEqual(r, [[0, 1, 2, 3], [], [], []]) - - r = get_contraction((4,4,4,4), (16,1,16)) - self.assertEqual(r, [[0, 1], [], [2, 3]]) - - r = get_contraction((1,2,3,4,1,1,1), (2,3,4)) - self.assertEqual(r, [[0, 1], [2], [3, 4, 5, 6]]) - - r = get_contraction((1,2,3,4), (1,2,3,4,1)) - self.assertEqual(r, [[0], [1], [2], [3], []]) - - r = get_contraction((14,1,384,14,1,1,1,1), (1,14,384,14)) - self.assertEqual(r, [[], [0], [1,2], [3,4,5,6,7]]) - - r = get_contraction((14,1,384,1,14,1,1,1,1), (1,14,384,14)) - self.assertEqual(r, [[], [0], [1,2], [3,4,5,6,7,8]]) - - r = get_contraction((512, 512), (1, 1, 512, 1, 1, 1, 1, 512)) - self.assertEqual(r, [[], [], [0], [], [], [], [], [1]]) - - r = get_contraction((1,2,3,4), (1,2,6,2)) - self.assertEqual(r, None) - - def test_contraction_ones(self): - r = get_contraction((1,), (1,1,1)) - self.assertEqual(r, [[0], [], []]) - - r = get_contraction((1,1), (1,1,1)) - self.assertEqual(r, [[0], [1], []]) - - r = get_contraction((1,1,1,1), (1,)) - self.assertEqual(r, [[0,1,2,3]]) - - r = get_contraction((1,1,1,1), (1,1)) - self.assertEqual(r, [[0], [1,2,3]]) - - r = get_contraction((1,1,1,1), (1,1,1)) - self.assertEqual(r, [[0], [1], [2,3]]) - - r = get_contraction((1,1,1,1), (1,1,1,1)) - self.assertEqual(r, [[0], [1], [2], [3]]) - -if __name__ == '__main__': - unittest.main() diff --git a/tinygrad_repo/test/unit/test_shm_tensor.py b/tinygrad_repo/test/unit/test_shm_tensor.py deleted file mode 100644 index 7708066..0000000 --- a/tinygrad_repo/test/unit/test_shm_tensor.py +++ /dev/null @@ -1,39 +0,0 @@ -import unittest -import multiprocessing.shared_memory as shared_memory -from tinygrad.helpers import CI -from tinygrad.runtime.ops_shm import RawShmBuffer -from tinygrad.tensor import Tensor, Device -import numpy as np - -class TestRawShmBuffer(unittest.TestCase): - def test_e2e(self): - t = Tensor.randn(2, 2, 2).realize() - - # copy to shm - shm_name = (s := shared_memory.SharedMemory(create=True, size=t.nbytes())).name - s.close() - t_shm = t.to(f"shm:{shm_name}").realize() - - # copy from shm - t2 = t_shm.to(Device.DEFAULT).realize() - - assert np.allclose(t.numpy(), t2.numpy()) - s.unlink() - - @unittest.skipIf(CI, "CI doesn't like big shared memory") - def test_e2e_big(self): - t = Tensor.randn(2048, 2048, 8).realize() - - # copy to shm - shm_name = (s := shared_memory.SharedMemory(create=True, size=t.nbytes())).name - s.close() - t_shm = t.to(f"shm:{shm_name}").realize() - - # copy from shm - t2 = t_shm.to(Device.DEFAULT).realize() - - assert np.allclose(t.numpy(), t2.numpy()) - s.unlink() - -if __name__ == "__main__": - unittest.main() diff --git a/tinygrad_repo/test/unit/test_symbolic.py b/tinygrad_repo/test/unit/test_symbolic.py deleted file mode 100644 index 4f97a93..0000000 --- a/tinygrad_repo/test/unit/test_symbolic.py +++ /dev/null @@ -1,448 +0,0 @@ -#!/usr/bin/env python -import unittest -from tinygrad.shape.symbolic import Node, MulNode, SumNode, Variable, NumNode, LtNode, sym_render, sym_infer, create_rednode - -class TestSymbolic(unittest.TestCase): - def helper_test_variable(self, v, n, m, s): - self.assertEqual(v.render(), s) - self.assertEqual(v.min, n) - self.assertEqual(v.max, m) - - def test_ge(self): - self.helper_test_variable(Variable("a", 3, 8)>=77, 0, 0, "0") - self.helper_test_variable(Variable("a", 3, 8)>=9, 0, 0, "0") - self.helper_test_variable(Variable("a", 3, 8)>=8, 0, 1, "((a*-1)<-7)") - self.helper_test_variable(Variable("a", 3, 8)>=4, 0, 1, "((a*-1)<-3)") - self.helper_test_variable(Variable("a", 3, 8)>=3, 1, 1, "1") - self.helper_test_variable(Variable("a", 3, 8)>=2, 1, 1, "1") - - def test_lt(self): - self.helper_test_variable(Variable("a", 3, 8)<77, 1, 1, "1") - self.helper_test_variable(Variable("a", 3, 8)<9, 1, 1, "1") - self.helper_test_variable(Variable("a", 3, 8)<8, 0, 1, "(a<8)") - self.helper_test_variable(Variable("a", 3, 8)<4, 0, 1, "(a<4)") - self.helper_test_variable(Variable("a", 3, 8)<3, 0, 0, "0") - self.helper_test_variable(Variable("a", 3, 8)<2, 0, 0, "0") - - def test_ge_divides(self): - expr = (Variable("idx", 0, 511)*4 + Variable("FLOAT4_INDEX", 0, 3)) < 512 - self.helper_test_variable(expr, 0, 1, "(idx<128)") - - def test_ge_divides_and(self): - expr = Variable.ands([(Variable("idx1", 0, 511)*4 + Variable("FLOAT4_INDEX", 0, 3)) < 512, - (Variable("idx2", 0, 511)*4 + Variable("FLOAT4_INDEX", 0, 3)) < 512]) - self.helper_test_variable(expr, 0, 1, "((idx1<128) and (idx2<128))") - expr = Variable.ands([(Variable("idx1", 0, 511)*4 + Variable("FLOAT4_INDEX", 0, 3)) < 512, - (Variable("idx2", 0, 511)*4 + Variable("FLOAT8_INDEX", 0, 7)) < 512]) - self.helper_test_variable(expr//4, 0, 1, "((((FLOAT8_INDEX//4)+idx2)<128) and ((idx1//4)<32))") - - def test_lt_factors(self): - expr = Variable.ands([(Variable("idx1", 0, 511)*4 + Variable("FLOAT4_INDEX", 0, 256)) < 512]) - self.helper_test_variable(expr, 0, 1, "(((idx1*4)+FLOAT4_INDEX)<512)") - - def test_div_becomes_num(self): - assert isinstance(Variable("a", 2, 3)//2, NumNode) - - def test_var_becomes_num(self): - assert isinstance(Variable("a", 2, 2), NumNode) - - def test_equality(self): - idx1 = Variable("idx1", 0, 3) - idx2 = Variable("idx2", 0, 3) - assert idx1 == idx1 - assert idx1 != idx2 - assert idx1*4 == idx1*4 - assert idx1*4 != idx1*3 - assert idx1*4 != idx1+4 - assert idx1*4 != idx2*4 - assert idx1+idx2 == idx1+idx2 - assert idx1+idx2 == idx2+idx1 - assert idx1+idx2 != idx2 - - def test_factorize(self): - a = Variable("a", 0, 8) - self.helper_test_variable(a*2+a*3, 0, 8*5, "(a*5)") - - def test_factorize_no_mul(self): - a = Variable("a", 0, 8) - self.helper_test_variable(a+a*3, 0, 8*4, "(a*4)") - - def test_neg(self): - self.helper_test_variable(-Variable("a", 0, 8), -8, 0, "(a*-1)") - - def test_add_1(self): - self.helper_test_variable(Variable("a", 0, 8)+1, 1, 9, "(1+a)") - - def test_add_num_1(self): - self.helper_test_variable(Variable("a", 0, 8)+Variable.num(1), 1, 9, "(1+a)") - - def test_sub_1(self): - self.helper_test_variable(Variable("a", 0, 8)-1, -1, 7, "(-1+a)") - - def test_sub_num_1(self): - self.helper_test_variable(Variable("a", 0, 8)-Variable.num(1), -1, 7, "(-1+a)") - - def test_mul_0(self): - self.helper_test_variable(Variable("a", 0, 8)*0, 0, 0, "0") - - def test_mul_1(self): - self.helper_test_variable(Variable("a", 0, 8)*1, 0, 8, "a") - - def test_mul_neg_1(self): - self.helper_test_variable((Variable("a", 0, 2)*-1)//3, -1, 0, "((((a*-1)+3)//3)+-1)") - - def test_mul_2(self): - self.helper_test_variable(Variable("a", 0, 8)*2, 0, 16, "(a*2)") - - def test_div_1(self): - self.helper_test_variable(Variable("a", 0, 8)//1, 0, 8, "a") - - def test_mod_1(self): - self.helper_test_variable(Variable("a", 0, 8)%1, 0, 0, "0") - - def test_add_min_max(self): - self.helper_test_variable(Variable("a", 0, 8) * 2 + 12, 12, 16+12, "((a*2)+12)") - - def test_div_min_max(self): - self.helper_test_variable(Variable("a", 0, 7) // 2, 0, 3, "(a//2)") - - def test_div_neg_min_max(self): - self.helper_test_variable(Variable("a", 0, 7) // -2, -3, 0, "((a//2)*-1)") - - def test_sum_div_min_max(self): - self.helper_test_variable(Variable.sum([Variable("a", 0, 7), Variable("b", 0, 3)]) // 2, 0, 5, "((a+b)//2)") - - def test_sum_div_factor(self): - self.helper_test_variable(Variable.sum([Variable("a", 0, 7)*4, Variable("b", 0, 3)*4]) // 2, 0, 20, "((a*2)+(b*2))") - - def test_sum_div_some_factor(self): - self.helper_test_variable(Variable.sum([Variable("a", 0, 7)*5, Variable("b", 0, 3)*4]) // 2, 0, 23, "(((a*5)//2)+(b*2))") - - def test_sum_div_some_partial_factor(self): - self.helper_test_variable(Variable.sum([Variable("a", 0, 7)*6, Variable("b", 0, 7)*6]) // 16, 0, 5, "(((a*3)+(b*3))//8)") - self.helper_test_variable(Variable.sum([Variable.num(16), Variable("a", 0, 7)*6, Variable("b", 0, 7)*6]) // 16, 1, 6, "((((a*3)+(b*3))//8)+1)") - - def test_sum_div_no_factor(self): - self.helper_test_variable(Variable.sum([Variable("a", 0, 7)*5, Variable("b", 0, 3)*5]) // 2, 0, 25, "(((a*5)+(b*5))//2)") - - def test_mod_factor(self): - # NOTE: even though the mod max is 50, it can't know this without knowing about the mul - self.helper_test_variable(Variable.sum([Variable("a", 0, 7)*100, Variable("b", 0, 3)*50]) % 100, 0, 99, "((b*50)%100)") - - def test_mod_to_sub(self): - # This is mod reduction - self.helper_test_variable((1+Variable("a",1,2))%2, 0, 1, (Variable("a",1,2)-1).render()) - - def test_sum_div_const(self): - self.helper_test_variable(Variable.sum([Variable("a", 0, 7)*4, Variable.num(3)]) // 4, 0, 7, "a") - - def test_sum_div_const_big(self): - self.helper_test_variable(Variable.sum([Variable("a", 0, 7)*4, Variable.num(3)]) // 16, 0, 1, "(a//4)") - - def test_sum_lt_fold(self): - self.helper_test_variable(Variable.sum([Variable("a", 0, 7) * 4, Variable("b", 0, 3)]) < 16, 0, 1, "(a<4)") - self.helper_test_variable(Variable.sum([Variable("a", 0, 7) * 4, Variable("b", 0, 4)]) < 16, 0, 1, "(((a*4)+b)<16)") - - def test_mod_mul(self): - self.helper_test_variable((Variable("a", 0, 5)*10)%9, 0, 5, "a") - - def test_mod_mod(self): - self.helper_test_variable((Variable("a", 0, 31)%12)%4, 0, 3, "(a%4)") - self.helper_test_variable(((4*Variable("a", 0, 31)) % 12) % 4, 0, 0, "0") - self.helper_test_variable((Variable("a", 0, 31) % 4) % 12, 0, 3, "(a%4)") - - def test_mul_mul(self): - self.helper_test_variable((Variable("a", 0, 5)*10)*9, 0, 5*10*9, "(a*90)") - - def test_mul_lt(self): - self.helper_test_variable((Variable("a", 0, 5)*4)<13, 0, 1, "(a<4)") - self.helper_test_variable((Variable("a", 0, 5)*4)<16, 0, 1, "(a<4)") - self.helper_test_variable((Variable("a", 0, 5)*4)>11, 0, 1, "((a*-1)<-2)") - self.helper_test_variable((Variable("a", 0, 5)*4)>12, 0, 1, "((a*-1)<-3)") - - def test_div_div(self): - self.helper_test_variable((Variable("a", 0, 1800)//10)//9, 0, 20, "(a//90)") - - def test_distribute_mul(self): - self.helper_test_variable(Variable.sum([Variable("a", 0, 3), Variable("b", 0, 5)])*3, 0, 24, "((a*3)+(b*3))") - - def test_mod_mul_sum(self): - self.helper_test_variable(Variable.sum([Variable("b", 0, 2), Variable("a", 0, 5)*10])%9, 0, 7, "(a+b)") - - def test_sum_0(self): - self.helper_test_variable(Variable.sum([Variable("a", 0, 7)]), 0, 7, "a") - - def test_mod_remove(self): - self.helper_test_variable(Variable("a", 0, 6)%100, 0, 6, "a") - - def test_big_mod(self): - # NOTE: we no longer support negative variables - #self.helper_test_variable(Variable("a", -20, 20)%10, -9, 9, "(a%10)") - #self.helper_test_variable(Variable("a", -20, 0)%10, -9, 0, "(a%10)") - #self.helper_test_variable(Variable("a", -20, 1)%10, -9, 1, "(a%10)") - self.helper_test_variable(Variable("a", 0, 20)%10, 0, 9, "(a%10)") - #self.helper_test_variable(Variable("a", -1, 20)%10, -1, 9, "(a%10)") - - def test_gt_remove(self): - self.helper_test_variable(Variable("a", 0, 6) >= 25, 0, 0, "0") - - def test_lt_remove(self): - self.helper_test_variable(Variable("a", 0, 6) < -3, 0, 0, "0") - self.helper_test_variable(Variable("a", 0, 6) < 3, 0, 1, "(a<3)") - self.helper_test_variable(Variable("a", 0, 6) < 8, 1, 1, "1") - - def test_lt_sum_remove(self): - self.helper_test_variable((Variable("a", 0, 6) + 2) < 3, 0, 1, "(a<1)") - - def test_and_fold(self): - self.helper_test_variable(Variable.ands([Variable.num(0), Variable("a", 0, 1)]), 0, 0, "0") - - def test_and_remove(self): - self.helper_test_variable(Variable.ands([Variable.num(1), Variable("a", 0, 1)]), 0, 1, "a") - - def test_mod_factor_negative(self): - self.helper_test_variable(Variable.sum([Variable.num(-29), Variable("a", 0, 10), Variable("b", 0, 10)*28]) % 28, 0, 27, "((27+a)%28)") - self.helper_test_variable(Variable.sum([Variable.num(-29), Variable("a", 0, 100), Variable("b", 0, 10)*28]) % 28, 0, 27, "((27+a)%28)") - - def test_sum_combine_num(self): - self.helper_test_variable(Variable.sum([Variable.num(29), Variable("a", 0, 10), Variable.num(-23)]), 6, 16, "(6+a)") - - def test_sum_num_hoisted_and_factors_cancel_out(self): - self.helper_test_variable(Variable.sum([Variable("a", 0, 1) * -4 + 1, Variable("a", 0, 1) * 4]), 1, 1, "1") - - def test_div_factor(self): - self.helper_test_variable(Variable.sum([Variable.num(-40), Variable("a", 0, 10)*2, Variable("b", 0, 10)*40]) // 40, -1, 9, "(-1+b)") - - def test_mul_div(self): - self.helper_test_variable((Variable("a", 0, 10)*4)//4, 0, 10, "a") - - def test_mul_div_factor_mul(self): - self.helper_test_variable((Variable("a", 0, 10)*8)//4, 0, 20, "(a*2)") - - def test_mul_div_factor_div(self): - self.helper_test_variable((Variable("a", 0, 10)*4)//8, 0, 5, "(a//2)") - - def test_div_remove(self): - self.helper_test_variable(Variable.sum([Variable("idx0", 0, 127)*4, Variable("idx2", 0, 3)])//4, 0, 127, "idx0") - - def test_div_numerator_negative(self): - self.helper_test_variable((Variable("idx", 0, 9)*-10)//11, -9, 0, "((((idx*-10)+99)//11)+-9)") - - def test_div_into_mod(self): - self.helper_test_variable((Variable("idx", 0, 16)*4)%8//4, 0, 1, "(idx%2)") - -class TestSymbolicNumeric(unittest.TestCase): - def helper_test_numeric(self, f): - # TODO: why are the negative tests broken? (even if we did support negative variables) - #MIN, MAX = -10, 10 - MIN, MAX = 0, 10 - # one number - for i in range(MIN, MAX): - v = f(Variable.num(i)) - #print(i, f(i), v.min, v.max) - self.assertEqual(v.min, v.max) - self.assertEqual(v.min, f(i)) - for kmin in range(MIN, MAX): - for kmax in range(MIN, MAX): - if kmin > kmax: continue - v = f(Variable("tmp", kmin, kmax)) - values = [f(rv) for rv in range(kmin, kmax+1)] - # the min and max may not be exact - self.assertLessEqual(v.min, min(values)) - self.assertGreaterEqual(v.max, max(values)) - - def test_mod_4(self): self.helper_test_numeric(lambda x: (x%4)) - def test_div_4(self): self.helper_test_numeric(lambda x: (x//4)) - def test_plus_1_div_2(self): self.helper_test_numeric(lambda x: (x+1)//2) - def test_plus_1_mod_2(self): self.helper_test_numeric(lambda x: (x+1)%2) - def test_times_2(self): self.helper_test_numeric(lambda x: x*2) - def test_times_2_plus_3(self): self.helper_test_numeric(lambda x: x*2 + 3) - def test_times_2_plus_3_mod_4(self): self.helper_test_numeric(lambda x: (x*2 + 3)%4) - def test_times_2_plus_3_div_4(self): self.helper_test_numeric(lambda x: (x*2 + 3)//4) - def test_times_2_plus_3_div_4_mod_4(self): self.helper_test_numeric(lambda x: ((x*2 + 3)//4)%4) - -class TestSymbolicVars(unittest.TestCase): - def test_simple(self): - z = NumNode(0) - a = Variable("a", 0, 10) - b = Variable("b", 0, 10) - c = Variable("c", 0, 10) - assert z.vars() == z.vars() == [] - assert a.vars() == a.vars() == [a] - m = MulNode(a, 3) - assert m.vars() == [a] - s = SumNode([a, b, c]) - assert s.vars() == [a, b, c] - - def test_compound(self): - a = Variable("a", 0, 10) - b = Variable("b", 0, 10) - c = Variable("c", 0, 10) - assert (a + b * c).vars() == [a, b, c] - assert (a % 3 + b // 5).vars() == [a, b] - assert (a + b + c - a).vars() == [b, c] - -class TestSymbolicMinMax(unittest.TestCase): - def test_min_max_known(self): - a = Variable("a", 1, 8) - assert max(1, a) == max(a, 1) == a - assert min(1, a) == min(a, 1) == 1 - -class TestSymRender(unittest.TestCase): - def test_sym_render(self): - a = Variable("a", 1, 8) - b = Variable("b", 1, 10) - assert sym_render(a) == "a" - assert sym_render(1) == "1" - assert sym_render(a+1) == "(1+a)" - assert sym_render(a*b) == "(a*b)" - -class TestSymInfer(unittest.TestCase): - def test_sym_infer(self): - a = Variable("a", 0, 10) - b = Variable("b", 0, 10) - c = Variable("c", 0, 10) - var_vals = {a: 2, b: 3, c: 4} - assert sym_infer(5, var_vals) == 5 - assert sym_infer(a, var_vals) == 2 - assert sym_infer(b, var_vals) == 3 - assert sym_infer(a+b, var_vals) == 5 - assert sym_infer(a-b, var_vals) == -1 - assert sym_infer(a+b+c, var_vals) == 9 - assert sym_infer(a*b, var_vals) == 6 - assert sym_infer(a*b+c, var_vals) == 10 - -class TestSymbolicSymbolicOps(unittest.TestCase): - def test_node_divmod_node(self): - i = Variable("i", 1, 10) - idx0 = Variable("idx0", 0, i*3-1) - assert NumNode(0) // (Variable("i", 1, 10)*128) == 0 - assert NumNode(0) % (Variable("i", 1, 10)*128) == 0 - assert NumNode(127) // (Variable("i", 1, 10)*128) == 0 - assert NumNode(127) % (Variable("i", 1, 10)*128) == 127 - assert 127 // (Variable("i", 1, 10)*128) == 0 - assert 127 % (Variable("i", 1, 10)*128) == 127 - assert NumNode(128) // (Variable("i", 1, 10)*128 + 128) == 0 - assert NumNode(128) % (Variable("i", 1, 10)*128 + 128) == 128 - assert 128 // (Variable("i", 1, 10)*128 + 128) == 0 - assert 128 % (Variable("i", 1, 10)*128 + 128) == 128 - assert 0 // (Variable("i", 1, 10)*128) == 0 - assert 0 % (Variable("i", 1, 10)*128) == 0 - assert idx0 // (i*3) == 0 - assert idx0 % (i*3) == idx0 - assert i // i == 1 - assert i % i == 0 - assert 128 // NumNode(4) == 32 - assert 128 % NumNode(4) == 0 - assert NumNode(128) // NumNode(4) == 32 - assert NumNode(128) % NumNode(4) == 0 - - def test_mulnode_divmod_node(self): - i = Variable("i", 1, 10) - idx0 = Variable("idx0", 0, 31) - assert (idx0*(i*4+4)) // (i+1) == (idx0*4) - assert (idx0*(i*4+4)) % (i+1) == 0 - assert (idx0*i) % i == 0 - - def test_sumnode_divmod_sumnode(self): - i = Variable("i", 1, 10) - idx0 = Variable("idx0", 0, 7) - idx1 = Variable("idx1", 0, 3) - idx2 = Variable("idx2", 0, i) - assert (idx0*(i*4+4)+idx1*(i+1)+idx2) // (i+1) == idx0*4+idx1 - assert (idx0*(i*4+4)+idx1*(i+1)+idx2) % (i+1) == idx2 - assert (i+1) // (i*128+128) == 0 - assert (i+1) % (i*128+128) == (i+1) - assert (i+1+idx2) // (i+1) == 1 - assert (i+1+idx2) % (i+1) == idx2 - assert (idx0*(i*4+4)+i+1+idx2) // (i+1) == idx0*4+1 - assert (idx0*(i*4+4)+i+1+idx2) % (i+1) == idx2 - assert (i*128+128)*2 // (i*128+128) == 2 - assert (i*128+128)*2 % (i*128+128) == 0 - - def test_sumnode_divmod_sumnode_complex(self): - i = Variable("i", 1, 1024) - gidx0 = Variable("gidx0", 0, i) - lidx1 = Variable("lidx1", 0, 7) - ridx2 = Variable("ridx1", 0, 31) - assert ((i*128+128)*2 + gidx0*128 + lidx1*(i*512+512) + ridx2*4) // (i*128+128) == 2 + lidx1*4 - assert ((i*128+128)*2 + gidx0*128 + lidx1*(i*512+512) + ridx2*4) % (i*128+128) == gidx0*128 + ridx2*4 - assert ((gidx0*128+i*128+ridx2*4+129)) // (i*128+128) == 1 - assert ((gidx0*128+i*128+ridx2*4+129)) % (i*128+128) == gidx0*128 + ridx2*4 + 1 - assert (ridx2*(i*4+4)+1+i+gidx0) // (i*128+128) == 0 - assert (ridx2*(i*4+4)+1+i+gidx0) % (i*128+128) == (ridx2*(i*4+4)+1+i+gidx0) - - def test_node_lt_node(self): - a = Variable("a", 1, 5) - b = Variable("b", 6, 9) - c = Variable("c", 1, 10) - d = Variable("d", 5, 10) - # if the value is always the same, it folds to num - assert (a < b) == 1 - assert (b < a) == 0 - assert (d < a) == 0 - # if it remains as a LtNode, bool is always true and (min, max) == (0, 1) - assert isinstance((a < c), LtNode) and (a < c).min == 0 and (a < c).max == 1 - assert a < c - assert isinstance((a > c), LtNode) and (a > c).min == 0 and (a > c).max == 1 - # same when comparing with a constant - assert a < 3 and (a < 3).min == 0 and (a < 3).max == 1 - assert a > 3 and (a > 3).min == 0 and (a > 3).max == 1 - - def test_num_node_mul_node(self): - a = Variable("a", 1, 5) - b = NumNode(2) * a - assert b == a * 2 - assert isinstance(b, MulNode) - b = NumNode(1) * a - assert b == a - assert isinstance(b, Variable) - b = NumNode(0) * a - assert b == 0 - assert isinstance(b, NumNode) - - def test_num_node_expand(self): - a = NumNode(42) - assert a.expand() == [a] - - def test_variable_expand(self): - a = Variable("a", 5, 7) - assert a.expand() == [a] - - def test_variable_expand_expr_none(self): - a = Variable(None, 5, 7) - assert a.expand() == [NumNode(5), NumNode(6), NumNode(7)] - - def test_mul_node_expand(self): - a = Variable(None, 5, 7) - m = MulNode(a, 3) - assert m.expand() == [NumNode(15), NumNode(18), NumNode(21)] - - b = Variable("b", 1, 3) - n = MulNode(b, 3) - assert n.expand() == [Variable("b", 1, 3)*3] - - def test_sum_node_expand(self): - a = Variable(None, 1, 3) - b = Variable("b", 5, 7) - - s1 = create_rednode(SumNode, [a, b]) - assert s1.expand() == [Variable.sum([NumNode(i),b]) for i in range(1,4)] - - def test_multi_expand(self): - a = Variable("a", 1, 3) - b = Variable("b", 14, 17) - s1 = create_rednode(SumNode, [a, b]) - # expand increments earlier variables faster than later variables (as specified in the argument) - # this behavior was just copied from before, no idea why this should be true - assert s1.expand((a, b)) == [NumNode(x + y) for x in range(b.min, b.max + 1) for y in range(a.min, a.max + 1)] - - def test_substitute(self): - a = Variable(None, 1, 3) - b = a + 1 - c = b.substitute({a: NumNode(1)}) - assert c == NumNode(2) - - -if __name__ == '__main__': - unittest.main() diff --git a/tools/CTF.md b/tools/CTF.md deleted file mode 100644 index a14a41d..0000000 --- a/tools/CTF.md +++ /dev/null @@ -1,20 +0,0 @@ -## CTF -Welcome to the first part of the comma CTF! - -* all the flags are contained in this route: `0c7f0c7f0c7f0c7f|2021-10-13--13-00-00` -* there's 2 flags in each segment, with roughly increasing difficulty -* everything you'll need to find the flags is in the openpilot repo - * grep is also your friend - * first, [setup](https://github.com/commaai/openpilot/tree/master/tools#setup-your-pc) your PC - * read the docs & checkout out the tools in tools/ and selfdrive/debug/ - * tip: once you get the replay and UI up, start by familiarizing yourself with seeking in replay - -getting started -```bash -# start the route reply -cd tools/replay -./replay '0c7f0c7f0c7f0c7f|2021-10-13--13-00-00' --dcam --ecam - -# start the UI in another terminal -selfdrive/ui/ui -``` diff --git a/tools/README.md b/tools/README.md deleted file mode 100644 index 9044875..0000000 --- a/tools/README.md +++ /dev/null @@ -1,80 +0,0 @@ -# openpilot tools - -## System Requirements - -openpilot is developed and tested on **Ubuntu 20.04**, which is the primary development target aside from the [supported embedded hardware](https://github.com/commaai/openpilot#running-on-a-dedicated-device-in-a-car). - -Running natively on any other system is not recommended and will require modifications. On Windows you can use WSL, and on macOS or incompatible Linux systems, it is recommended to use the dev containers. - -## Native setup on Ubuntu 20.04 - -**1. Clone openpilot** - -NOTE: This repository uses Git LFS for large files. Ensure you have [Git LFS](https://git-lfs.com/) installed and set up before cloning or working with it. - -Either do a partial clone for faster download: -``` bash -git clone --filter=blob:none --recurse-submodules --also-filter-submodules https://github.com/commaai/openpilot.git -``` - -or do a full clone: -``` bash -git clone --recurse-submodules https://github.com/commaai/openpilot.git -``` - -**2. Run the setup script** - -``` bash -cd openpilot -git lfs pull -tools/ubuntu_setup.sh -``` - -Activate a shell with the Python dependencies installed: -``` bash -poetry shell -``` - -**3. Build openpilot** - -``` bash -scons -u -j$(nproc) --nosr -``` - -## Dev Container on any Linux or macOS - -openpilot supports [Dev Containers](https://containers.dev/). Dev containers provide customizable and consistent development environment wrapped inside a container. This means you can develop in a designated environment matching our primary development target, regardless of your local setup. - -Dev containers are supported in [multiple editors and IDEs](https://containers.dev/supporting), including Visual Studio Code. Use the following [guide](https://code.visualstudio.com/docs/devcontainers/containers) to start using them with VSCode. - -#### X11 forwarding on macOS - -GUI apps like `ui` or `cabana` can also run inside the container by leveraging X11 forwarding. To make use of it on macOS, additional configuration steps must be taken. Follow [these](https://gist.github.com/sorny/969fe55d85c9b0035b0109a31cbcb088) steps to setup X11 forwarding on macOS. - -## WSL on Windows - -[Windows Subsystem for Linux (WSL)](https://docs.microsoft.com/en-us/windows/wsl/about) should provide a similar experience to native Ubuntu. [WSL 2](https://docs.microsoft.com/en-us/windows/wsl/compare-versions) specifically has been reported by several users to be a seamless experience. - -Follow [these instructions](https://docs.microsoft.com/en-us/windows/wsl/install) to setup the WSL and install the `Ubuntu-20.04` distribution. Once your Ubuntu WSL environment is setup, follow the Linux setup instructions to finish setting up your environment. See [these instructions](https://learn.microsoft.com/en-us/windows/wsl/tutorials/gui-apps) for running GUI apps. - -**NOTE**: If you are running WSL and any GUIs are failing (segfaulting or other strange issues) even after following the steps above, you may need to enable software rendering with `LIBGL_ALWAYS_SOFTWARE=1`, e.g. `LIBGL_ALWAYS_SOFTWARE=1 selfdrive/ui/ui`. - -## CTF -Learn about the openpilot ecosystem and tools by playing our [CTF](/tools/CTF.md). - -## Directory Structure - -``` -├── ubuntu_setup.sh # Setup script for Ubuntu -├── mac_setup.sh # Setup script for macOS -├── cabana/ # View and plot CAN messages from drives or in realtime -├── joystick/ # Control your car with a joystick -├── lib/ # Libraries to support the tools and reading openpilot logs -├── plotjuggler/ # A tool to plot openpilot logs -├── replay/ # Replay drives and mock openpilot services -├── scripts/ # Miscellaneous scripts -├── serial/ # Tools for using the comma serial -├── sim/ # Run openpilot in a simulator -├── ssh/ # SSH into a comma device -└── webcam/ # Run openpilot on a PC with webcams -``` diff --git a/tools/bodyteleop/.gitignore b/tools/bodyteleop/.gitignore deleted file mode 100644 index adeab99..0000000 --- a/tools/bodyteleop/.gitignore +++ /dev/null @@ -1,4 +0,0 @@ -av -av-10.0.0/* -key.pem -cert.pem \ No newline at end of file diff --git a/tools/cabana/.gitignore b/tools/cabana/.gitignore deleted file mode 100644 index 362a51f..0000000 --- a/tools/cabana/.gitignore +++ /dev/null @@ -1,6 +0,0 @@ -moc_* -*.moc - -cabana -dbc/car_fingerprint_to_dbc.json -tests/test_cabana diff --git a/tools/cabana/README.md b/tools/cabana/README.md deleted file mode 100644 index 53723ef..0000000 --- a/tools/cabana/README.md +++ /dev/null @@ -1,32 +0,0 @@ -# Cabana - -Cabana is a tool developed to view raw CAN data. One use for this is creating and editing [CAN Dictionaries](http://socialledge.com/sjsu/index.php/DBC_Format) (DBC files), and the tool provides direct integration with [commaai/opendbc](https://github.com/commaai/opendbc) (a collection of DBC files), allowing you to load the DBC files direct from source, and save to your fork. In addition, you can load routes from [comma connect](https://connect.comma.ai). - -## Usage Instructions - -```bash -$ ./cabana -h -Usage: ./cabana [options] route - -Options: - -h, --help Displays help on commandline options. - --help-all Displays help including Qt specific options. - --demo use a demo route instead of providing your own - --qcam load qcamera - --ecam load wide road camera - --stream read can messages from live streaming - --panda read can messages from panda - --panda-serial read can messages from panda with given serial - --socketcan read can messages from given SocketCAN device - --zmq the ip address on which to receive zmq - messages - --data_dir local directory with routes - --no-vipc do not output video - --dbc dbc file to open - -Arguments: - route the drive to replay. find your drives at - connect.comma.ai -``` - -See [openpilot wiki](https://github.com/commaai/openpilot/wiki/Cabana) diff --git a/tools/cabana/SConscript b/tools/cabana/SConscript deleted file mode 100644 index d557b3a..0000000 --- a/tools/cabana/SConscript +++ /dev/null @@ -1,41 +0,0 @@ -Import('qt_env', 'arch', 'common', 'messaging', 'visionipc', 'replay_lib', 'cereal', 'widgets') - -base_frameworks = qt_env['FRAMEWORKS'] -base_libs = [common, messaging, cereal, visionipc, 'qt_util', 'zmq', 'capnp', 'kj', 'm', 'ssl', 'crypto', 'pthread'] + qt_env["LIBS"] - -if arch == "Darwin": - base_frameworks.append('OpenCL') - base_frameworks.append('QtCharts') - base_frameworks.append('QtSerialBus') -else: - base_libs.append('OpenCL') - base_libs.append('Qt5Charts') - base_libs.append('Qt5SerialBus') - -qt_libs = ['qt_util'] + base_libs - -cabana_env = qt_env.Clone() -cabana_libs = [widgets, cereal, messaging, visionipc, replay_lib, 'panda', 'avutil', 'avcodec', 'avformat', 'bz2', 'curl', 'yuv', 'usb-1.0'] + qt_libs -opendbc_path = '-DOPENDBC_FILE_PATH=\'"%s"\'' % (cabana_env.Dir("../../opendbc").abspath) -cabana_env['CXXFLAGS'] += [opendbc_path] - -# build assets -assets = "assets/assets.cc" -assets_src = "assets/assets.qrc" -cabana_env.Command(assets, assets_src, f"rcc $SOURCES -o $TARGET") -cabana_env.Depends(assets, Glob('/assets/*', exclude=[assets, assets_src, "assets/assets.o"])) - -cabana_lib = cabana_env.Library("cabana_lib", ['mainwin.cc', 'streams/socketcanstream.cc', 'streams/pandastream.cc', 'streams/devicestream.cc', 'streams/livestream.cc', 'streams/abstractstream.cc', 'streams/replaystream.cc', 'binaryview.cc', 'historylog.cc', 'videowidget.cc', 'signalview.cc', - 'dbc/dbc.cc', 'dbc/dbcfile.cc', 'dbc/dbcmanager.cc', - 'chart/chartswidget.cc', 'chart/chart.cc', 'chart/signalselector.cc', 'chart/tiplabel.cc', 'chart/sparkline.cc', - 'commands.cc', 'messageswidget.cc', 'streamselector.cc', 'settings.cc', 'util.cc', 'detailwidget.cc', 'tools/findsimilarbits.cc', 'tools/findsignal.cc'], LIBS=cabana_libs, FRAMEWORKS=base_frameworks) -cabana_env.Program('cabana', ['cabana.cc', cabana_lib, assets], LIBS=cabana_libs, FRAMEWORKS=base_frameworks) - -if GetOption('extras'): - cabana_env.Program('tests/test_cabana', ['tests/test_runner.cc', 'tests/test_cabana.cc', cabana_lib], LIBS=[cabana_libs]) - -output_json_file = 'tools/cabana/dbc/car_fingerprint_to_dbc.json' -generate_dbc = cabana_env.Command('#' + output_json_file, - ['dbc/generate_dbc_json.py'], - "python3 tools/cabana/dbc/generate_dbc_json.py --out " + output_json_file) -cabana_env.Depends(generate_dbc, ["#common", "#selfdrive/boardd", '#opendbc', "#cereal", Glob("#opendbc/*.dbc")]) diff --git a/tools/cabana/assets/.gitignore b/tools/cabana/assets/.gitignore deleted file mode 100644 index 283034c..0000000 --- a/tools/cabana/assets/.gitignore +++ /dev/null @@ -1 +0,0 @@ -*.cc diff --git a/tools/cabana/assets/assets.qrc b/tools/cabana/assets/assets.qrc deleted file mode 100644 index 6a8e5a3..0000000 --- a/tools/cabana/assets/assets.qrc +++ /dev/null @@ -1,6 +0,0 @@ - - - ../../../third_party/bootstrap/bootstrap-icons.svg - cabana-icon.png - - diff --git a/tools/cabana/assets/cabana-icon.png b/tools/cabana/assets/cabana-icon.png deleted file mode 100644 index 86add80..0000000 Binary files a/tools/cabana/assets/cabana-icon.png and /dev/null differ diff --git a/tools/cabana/binaryview.cc b/tools/cabana/binaryview.cc deleted file mode 100644 index c72ebf9..0000000 --- a/tools/cabana/binaryview.cc +++ /dev/null @@ -1,458 +0,0 @@ -#include "tools/cabana/binaryview.h" - -#include - -#include -#include -#include -#include -#include -#include -#include -#include - -#include "tools/cabana/commands.h" - -// BinaryView - -const int CELL_HEIGHT = 36; -const int VERTICAL_HEADER_WIDTH = 30; -inline int get_bit_pos(const QModelIndex &index) { return flipBitPos(index.row() * 8 + index.column()); } - -BinaryView::BinaryView(QWidget *parent) : QTableView(parent) { - model = new BinaryViewModel(this); - setModel(model); - delegate = new BinaryItemDelegate(this); - setItemDelegate(delegate); - horizontalHeader()->setSectionResizeMode(QHeaderView::Stretch); - horizontalHeader()->setFont(QFontDatabase::systemFont(QFontDatabase::FixedFont)); - verticalHeader()->setSectionsClickable(false); - verticalHeader()->setSectionResizeMode(QHeaderView::Fixed); - verticalHeader()->setDefaultSectionSize(CELL_HEIGHT); - horizontalHeader()->hide(); - setShowGrid(false); - setMouseTracking(true); - setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOff); - - QObject::connect(dbc(), &DBCManager::DBCFileChanged, this, &BinaryView::refresh); - QObject::connect(UndoStack::instance(), &QUndoStack::indexChanged, this, &BinaryView::refresh); - - addShortcuts(); - setWhatsThis(R"( - Binary View
- - Shortcuts
- Delete Signal: -  x , -  Backspace , -  Delete 
- Change endianness:  e 
- Change singedness:  s 
- Open chart: -  c , -  p , -  g  - )"); -} - -void BinaryView::addShortcuts() { - // Delete (x, backspace, delete) - QShortcut *shortcut_delete_x = new QShortcut(QKeySequence(Qt::Key_X), this); - QShortcut *shortcut_delete_backspace = new QShortcut(QKeySequence(Qt::Key_Backspace), this); - QShortcut *shortcut_delete_delete = new QShortcut(QKeySequence(Qt::Key_Delete), this); - QObject::connect(shortcut_delete_delete, &QShortcut::activated, shortcut_delete_x, &QShortcut::activated); - QObject::connect(shortcut_delete_backspace, &QShortcut::activated, shortcut_delete_x, &QShortcut::activated); - QObject::connect(shortcut_delete_x, &QShortcut::activated, [=]{ - if (hovered_sig != nullptr) { - UndoStack::push(new RemoveSigCommand(model->msg_id, hovered_sig)); - hovered_sig = nullptr; - } - }); - - // Change endianness (e) - QShortcut *shortcut_endian = new QShortcut(QKeySequence(Qt::Key_E), this); - QObject::connect(shortcut_endian, &QShortcut::activated, [=]{ - if (hovered_sig != nullptr) { - cabana::Signal s = *hovered_sig; - s.is_little_endian = !s.is_little_endian; - emit editSignal(hovered_sig, s); - } - }); - - // Change signedness (s) - QShortcut *shortcut_sign = new QShortcut(QKeySequence(Qt::Key_S), this); - QObject::connect(shortcut_sign, &QShortcut::activated, [=]{ - if (hovered_sig != nullptr) { - cabana::Signal s = *hovered_sig; - s.is_signed = !s.is_signed; - emit editSignal(hovered_sig, s); - } - }); - - // Open chart (c, p, g) - QShortcut *shortcut_plot = new QShortcut(QKeySequence(Qt::Key_P), this); - QShortcut *shortcut_plot_g = new QShortcut(QKeySequence(Qt::Key_G), this); - QShortcut *shortcut_plot_c = new QShortcut(QKeySequence(Qt::Key_C), this); - QObject::connect(shortcut_plot_g, &QShortcut::activated, shortcut_plot, &QShortcut::activated); - QObject::connect(shortcut_plot_c, &QShortcut::activated, shortcut_plot, &QShortcut::activated); - QObject::connect(shortcut_plot, &QShortcut::activated, [=]{ - if (hovered_sig != nullptr) { - emit showChart(model->msg_id, hovered_sig, true, false); - } - }); -} - -QSize BinaryView::minimumSizeHint() const { - return {(horizontalHeader()->minimumSectionSize() + 1) * 9 + VERTICAL_HEADER_WIDTH + 2, - CELL_HEIGHT * std::min(model->rowCount(), 10) + 2}; -} - -void BinaryView::highlight(const cabana::Signal *sig) { - if (sig != hovered_sig) { - for (int i = 0; i < model->items.size(); ++i) { - auto &item_sigs = model->items[i].sigs; - if ((sig && item_sigs.contains(sig)) || (hovered_sig && item_sigs.contains(hovered_sig))) { - auto index = model->index(i / model->columnCount(), i % model->columnCount()); - emit model->dataChanged(index, index, {Qt::DisplayRole}); - } - } - - hovered_sig = sig; - emit signalHovered(hovered_sig); - } -} - -void BinaryView::setSelection(const QRect &rect, QItemSelectionModel::SelectionFlags flags) { - auto index = indexAt(viewport()->mapFromGlobal(QCursor::pos())); - if (!anchor_index.isValid() || !index.isValid()) - return; - - QItemSelection selection; - auto [start, size, is_lb] = getSelection(index); - for (int i = 0; i < size; ++i) { - int pos = is_lb ? flipBitPos(start + i) : flipBitPos(start) + i; - selection << QItemSelectionRange{model->index(pos / 8, pos % 8)}; - } - selectionModel()->select(selection, flags); -} - -void BinaryView::mousePressEvent(QMouseEvent *event) { - resize_sig = nullptr; - if (auto index = indexAt(event->pos()); index.isValid() && index.column() != 8) { - anchor_index = index; - auto item = (const BinaryViewModel::Item *)anchor_index.internalPointer(); - int bit_pos = get_bit_pos(anchor_index); - for (auto s : item->sigs) { - if (bit_pos == s->lsb || bit_pos == s->msb) { - int idx = flipBitPos(bit_pos == s->lsb ? s->msb : s->lsb); - anchor_index = model->index(idx / 8, idx % 8); - resize_sig = s; - break; - } - } - } - event->accept(); -} - -void BinaryView::highlightPosition(const QPoint &pos) { - if (auto index = indexAt(viewport()->mapFromGlobal(pos)); index.isValid()) { - auto item = (BinaryViewModel::Item *)index.internalPointer(); - const cabana::Signal *sig = item->sigs.isEmpty() ? nullptr : item->sigs.back(); - highlight(sig); - } -} - -void BinaryView::mouseMoveEvent(QMouseEvent *event) { - highlightPosition(event->globalPos()); - QTableView::mouseMoveEvent(event); -} - -void BinaryView::mouseReleaseEvent(QMouseEvent *event) { - QTableView::mouseReleaseEvent(event); - - auto release_index = indexAt(event->pos()); - if (release_index.isValid() && anchor_index.isValid()) { - if (selectionModel()->hasSelection()) { - auto sig = resize_sig ? *resize_sig : cabana::Signal{}; - std::tie(sig.start_bit, sig.size, sig.is_little_endian) = getSelection(release_index); - resize_sig ? emit editSignal(resize_sig, sig) - : UndoStack::push(new AddSigCommand(model->msg_id, sig)); - } else { - auto item = (const BinaryViewModel::Item *)anchor_index.internalPointer(); - if (item && item->sigs.size() > 0) - emit signalClicked(item->sigs.back()); - } - } - clearSelection(); - anchor_index = QModelIndex(); - resize_sig = nullptr; -} - -void BinaryView::leaveEvent(QEvent *event) { - highlight(nullptr); - QTableView::leaveEvent(event); -} - -void BinaryView::setMessage(const MessageId &message_id) { - model->msg_id = message_id; - verticalScrollBar()->setValue(0); - refresh(); -} - -void BinaryView::refresh() { - clearSelection(); - anchor_index = QModelIndex(); - resize_sig = nullptr; - hovered_sig = nullptr; - model->refresh(); - highlightPosition(QCursor::pos()); -} - -QSet BinaryView::getOverlappingSignals() const { - QSet overlapping; - for (const auto &item : model->items) { - if (item.sigs.size() > 1) { - for (auto s : item.sigs) { - if (s->type == cabana::Signal::Type::Normal) overlapping += s; - } - } - } - return overlapping; -} - -std::tuple BinaryView::getSelection(QModelIndex index) { - if (index.column() == 8) { - index = model->index(index.row(), 7); - } - bool is_lb = true; - if (resize_sig) { - is_lb = resize_sig->is_little_endian; - } else if (settings.drag_direction == Settings::DragDirection::MsbFirst) { - is_lb = index < anchor_index; - } else if (settings.drag_direction == Settings::DragDirection::LsbFirst) { - is_lb = !(index < anchor_index); - } else if (settings.drag_direction == Settings::DragDirection::AlwaysLE) { - is_lb = true; - } else if (settings.drag_direction == Settings::DragDirection::AlwaysBE) { - is_lb = false; - } - - int cur_bit_pos = get_bit_pos(index); - int anchor_bit_pos = get_bit_pos(anchor_index); - int start_bit = is_lb ? std::min(cur_bit_pos, anchor_bit_pos) : get_bit_pos(std::min(index, anchor_index)); - int size = is_lb ? std::abs(cur_bit_pos - anchor_bit_pos) + 1 : std::abs(flipBitPos(cur_bit_pos) - flipBitPos(anchor_bit_pos)) + 1; - return {start_bit, size, is_lb}; -} - -// BinaryViewModel - -void BinaryViewModel::refresh() { - beginResetModel(); - items.clear(); - if (auto dbc_msg = dbc()->msg(msg_id)) { - row_count = dbc_msg->size; - items.resize(row_count * column_count); - for (auto sig : dbc_msg->getSignals()) { - for (int j = 0; j < sig->size; ++j) { - int pos = sig->is_little_endian ? flipBitPos(sig->start_bit + j) : flipBitPos(sig->start_bit) + j; - int idx = column_count * (pos / 8) + pos % 8; - if (idx >= items.size()) { - qWarning() << "signal " << sig->name << "out of bounds.start_bit:" << sig->start_bit << "size:" << sig->size; - break; - } - if (j == 0) sig->is_little_endian ? items[idx].is_lsb = true : items[idx].is_msb = true; - if (j == sig->size - 1) sig->is_little_endian ? items[idx].is_msb = true : items[idx].is_lsb = true; - - auto &sigs = items[idx].sigs; - sigs.push_back(sig); - if (sigs.size() > 1) { - std::sort(sigs.begin(), sigs.end(), [](auto l, auto r) { return l->size > r->size; }); - } - } - } - } else { - row_count = can->lastMessage(msg_id).dat.size(); - items.resize(row_count * column_count); - } - int valid_rows = std::min(can->lastMessage(msg_id).dat.size(), row_count); - for (int i = 0; i < valid_rows * column_count; ++i) { - items[i].valid = true; - } - endResetModel(); - updateState(); -} - -void BinaryViewModel::updateItem(int row, int col, uint8_t val, const QColor &color) { - auto &item = items[row * column_count + col]; - if (item.val != val || item.bg_color != color) { - item.val = val; - item.bg_color = color; - auto idx = index(row, col); - emit dataChanged(idx, idx, {Qt::DisplayRole}); - } -} - -void BinaryViewModel::updateState() { - const auto &last_msg = can->lastMessage(msg_id); - const auto &binary = last_msg.dat; - // data size may changed. - if (binary.size() > row_count) { - beginInsertRows({}, row_count, binary.size() - 1); - row_count = binary.size(); - items.resize(row_count * column_count); - endInsertRows(); - } - - const double max_f = 255.0; - const double factor = 0.25; - const double scaler = max_f / log2(1.0 + factor); - for (int i = 0; i < binary.size(); ++i) { - for (int j = 0; j < 8; ++j) { - auto &item = items[i * column_count + j]; - int val = ((binary[i] >> (7 - j)) & 1) != 0 ? 1 : 0; - // Bit update frequency based highlighting - double offset = !item.sigs.empty() ? 50 : 0; - auto n = last_msg.last_changes[i].bit_change_counts[j]; - double min_f = n == 0 ? offset : offset + 25; - double alpha = std::clamp(offset + log2(1.0 + factor * (double)n / (double)last_msg.count) * scaler, min_f, max_f); - auto color = item.bg_color; - color.setAlpha(alpha); - updateItem(i, j, val, color); - } - updateItem(i, 8, binary[i], last_msg.colors[i]); - } -} - -QVariant BinaryViewModel::headerData(int section, Qt::Orientation orientation, int role) const { - if (orientation == Qt::Vertical) { - switch (role) { - case Qt::DisplayRole: return section; - case Qt::SizeHintRole: return QSize(VERTICAL_HEADER_WIDTH, 0); - case Qt::TextAlignmentRole: return Qt::AlignCenter; - } - } - return {}; -} - -QVariant BinaryViewModel::data(const QModelIndex &index, int role) const { - auto item = (const BinaryViewModel::Item *)index.internalPointer(); - return role == Qt::ToolTipRole && item && !item->sigs.empty() ? signalToolTip(item->sigs.back()) : QVariant(); -} - -// BinaryItemDelegate - -BinaryItemDelegate::BinaryItemDelegate(QObject *parent) : QStyledItemDelegate(parent) { - small_font.setPixelSize(8); - hex_font = QFontDatabase::systemFont(QFontDatabase::FixedFont); - hex_font.setBold(true); - - bin_text_table[0].setText("0"); - bin_text_table[1].setText("1"); - for (int i = 0; i < 256; ++i) { - hex_text_table[i].setText(QStringLiteral("%1").arg(i, 2, 16, QLatin1Char('0')).toUpper()); - hex_text_table[i].prepare({}, hex_font); - } -} - -bool BinaryItemDelegate::hasSignal(const QModelIndex &index, int dx, int dy, const cabana::Signal *sig) const { - if (!index.isValid()) return false; - auto model = (const BinaryViewModel*)(index.model()); - int idx = (index.row() + dy) * model->columnCount() + index.column() + dx; - return (idx >=0 && idx < model->items.size()) ? model->items[idx].sigs.contains(sig) : false; -} - -void BinaryItemDelegate::paint(QPainter *painter, const QStyleOptionViewItem &option, const QModelIndex &index) const { - auto item = (const BinaryViewModel::Item *)index.internalPointer(); - BinaryView *bin_view = (BinaryView *)parent(); - painter->save(); - - if (index.column() == 8) { - if (item->valid) { - painter->setFont(hex_font); - painter->fillRect(option.rect, item->bg_color); - } - } else if (option.state & QStyle::State_Selected) { - auto color = bin_view->resize_sig ? bin_view->resize_sig->color : option.palette.color(QPalette::Active, QPalette::Highlight); - painter->fillRect(option.rect, color); - painter->setPen(option.palette.color(QPalette::BrightText)); - } else if (!bin_view->selectionModel()->hasSelection() || !item->sigs.contains(bin_view->resize_sig)) { // not resizing - if (item->sigs.size() > 0) { - for (auto &s : item->sigs) { - if (s == bin_view->hovered_sig) { - painter->fillRect(option.rect, s->color.darker(125)); // 4/5x brightness - } else { - drawSignalCell(painter, option, index, s); - } - } - } else if (item->valid && item->bg_color.alpha() > 0) { - painter->fillRect(option.rect, item->bg_color); - } - auto color_role = item->sigs.contains(bin_view->hovered_sig) ? QPalette::BrightText : QPalette::Text; - painter->setPen(option.palette.color(color_role)); - } - - if (item->sigs.size() > 1) { - painter->fillRect(option.rect, QBrush(Qt::darkGray, Qt::Dense7Pattern)); - } else if (!item->valid) { - painter->fillRect(option.rect, QBrush(Qt::darkGray, Qt::BDiagPattern)); - } - if (item->valid) { - utils::drawStaticText(painter, option.rect, index.column() == 8 ? hex_text_table[item->val] : bin_text_table[item->val]); - } - if (item->is_msb || item->is_lsb) { - painter->setFont(small_font); - painter->drawText(option.rect.adjusted(8, 0, -8, -3), Qt::AlignRight | Qt::AlignBottom, item->is_msb ? "M" : "L"); - } - painter->restore(); -} - -// Draw border on edge of signal -void BinaryItemDelegate::drawSignalCell(QPainter *painter, const QStyleOptionViewItem &option, - const QModelIndex &index, const cabana::Signal *sig) const { - bool draw_left = !hasSignal(index, -1, 0, sig); - bool draw_top = !hasSignal(index, 0, -1, sig); - bool draw_right = !hasSignal(index, 1, 0, sig); - bool draw_bottom = !hasSignal(index, 0, 1, sig); - - const int spacing = 2; - QRect rc = option.rect.adjusted(draw_left * 3, draw_top * spacing, draw_right * -3, draw_bottom * -spacing); - QRegion subtract; - if (!draw_top) { - if (!draw_left && !hasSignal(index, -1, -1, sig)) { - subtract += QRect{rc.left(), rc.top(), 3, spacing}; - } else if (!draw_right && !hasSignal(index, 1, -1, sig)) { - subtract += QRect{rc.right() - 2, rc.top(), 3, spacing}; - } - } - if (!draw_bottom) { - if (!draw_left && !hasSignal(index, -1, 1, sig)) { - subtract += QRect{rc.left(), rc.bottom() - (spacing - 1), 3, spacing}; - } else if (!draw_right && !hasSignal(index, 1, 1, sig)) { - subtract += QRect{rc.right() - 2, rc.bottom() - (spacing - 1), 3, spacing}; - } - } - painter->setClipRegion(QRegion(rc).subtracted(subtract)); - - auto item = (const BinaryViewModel::Item *)index.internalPointer(); - QColor color = sig->color; - color.setAlpha(item->bg_color.alpha()); - // Mixing the signal colour with the Base background color to fade it - painter->fillRect(rc, option.palette.color(QPalette::Base)); - painter->fillRect(rc, color); - - // Draw edges - color = sig->color.darker(125); - painter->setPen(QPen(color, 1)); - if (draw_left) painter->drawLine(rc.topLeft(), rc.bottomLeft()); - if (draw_right) painter->drawLine(rc.topRight(), rc.bottomRight()); - if (draw_bottom) painter->drawLine(rc.bottomLeft(), rc.bottomRight()); - if (draw_top) painter->drawLine(rc.topLeft(), rc.topRight()); - - if (!subtract.isEmpty()) { - // fill gaps inside corners. - painter->setPen(QPen(color, 2, Qt::SolidLine, Qt::SquareCap, Qt::MiterJoin)); - for (auto &r : subtract) { - painter->drawRect(r); - } - } -} diff --git a/tools/cabana/binaryview.h b/tools/cabana/binaryview.h deleted file mode 100644 index 584910d..0000000 --- a/tools/cabana/binaryview.h +++ /dev/null @@ -1,92 +0,0 @@ -#pragma once - -#include -#include - -#include -#include -#include -#include - -#include "tools/cabana/dbc/dbcmanager.h" -#include "tools/cabana/streams/abstractstream.h" - -class BinaryItemDelegate : public QStyledItemDelegate { -public: - BinaryItemDelegate(QObject *parent); - void paint(QPainter *painter, const QStyleOptionViewItem &option, const QModelIndex &index) const override; - bool hasSignal(const QModelIndex &index, int dx, int dy, const cabana::Signal *sig) const; - void drawSignalCell(QPainter* painter, const QStyleOptionViewItem &option, const QModelIndex &index, const cabana::Signal *sig) const; - - QFont small_font, hex_font; - std::array hex_text_table; - std::array bin_text_table; -}; - -class BinaryViewModel : public QAbstractTableModel { -public: - BinaryViewModel(QObject *parent) : QAbstractTableModel(parent) {} - void refresh(); - void updateState(); - void updateItem(int row, int col, uint8_t val, const QColor &color); - QVariant headerData(int section, Qt::Orientation orientation, int role = Qt::DisplayRole) const override; - QVariant data(const QModelIndex &index, int role = Qt::DisplayRole) const override; - int rowCount(const QModelIndex &parent = QModelIndex()) const override { return row_count; } - int columnCount(const QModelIndex &parent = QModelIndex()) const override { return column_count; } - QModelIndex index(int row, int column, const QModelIndex &parent = QModelIndex()) const override { - return createIndex(row, column, (void *)&items[row * column_count + column]); - } - Qt::ItemFlags flags(const QModelIndex &index) const override { - return (index.column() == column_count - 1) ? Qt::ItemIsEnabled : Qt::ItemIsEnabled | Qt::ItemIsSelectable; - } - - struct Item { - QColor bg_color = QColor(102, 86, 169, 255); - bool is_msb = false; - bool is_lsb = false; - uint8_t val; - QList sigs; - bool valid = false; - }; - std::vector items; - - MessageId msg_id; - int row_count = 0; - const int column_count = 9; -}; - -class BinaryView : public QTableView { - Q_OBJECT - -public: - BinaryView(QWidget *parent = nullptr); - void setMessage(const MessageId &message_id); - void highlight(const cabana::Signal *sig); - QSet getOverlappingSignals() const; - inline void updateState() { model->updateState(); } - QSize minimumSizeHint() const override; - -signals: - void signalClicked(const cabana::Signal *sig); - void signalHovered(const cabana::Signal *sig); - void editSignal(const cabana::Signal *origin_s, cabana::Signal &s); - void showChart(const MessageId &id, const cabana::Signal *sig, bool show, bool merge); - -private: - void addShortcuts(); - void refresh(); - std::tuple getSelection(QModelIndex index); - void setSelection(const QRect &rect, QItemSelectionModel::SelectionFlags flags) override; - void mousePressEvent(QMouseEvent *event) override; - void mouseMoveEvent(QMouseEvent *event) override; - void mouseReleaseEvent(QMouseEvent *event) override; - void leaveEvent(QEvent *event) override; - void highlightPosition(const QPoint &pt); - - QModelIndex anchor_index; - BinaryViewModel *model; - BinaryItemDelegate *delegate; - const cabana::Signal *resize_sig = nullptr; - const cabana::Signal *hovered_sig = nullptr; - friend class BinaryItemDelegate; -}; diff --git a/tools/cabana/cabana.cc b/tools/cabana/cabana.cc deleted file mode 100644 index 205d795..0000000 --- a/tools/cabana/cabana.cc +++ /dev/null @@ -1,109 +0,0 @@ -#include -#include - -#include "selfdrive/ui/qt/util.h" -#include "tools/cabana/mainwin.h" -#include "tools/cabana/streamselector.h" -#include "tools/cabana/streams/devicestream.h" -#include "tools/cabana/streams/pandastream.h" -#include "tools/cabana/streams/replaystream.h" -#include "tools/cabana/streams/socketcanstream.h" - -int main(int argc, char *argv[]) { - QCoreApplication::setApplicationName("Cabana"); - QCoreApplication::setAttribute(Qt::AA_ShareOpenGLContexts); - initApp(argc, argv, false); - QApplication app(argc, argv); - app.setApplicationDisplayName("Cabana"); - app.setWindowIcon(QIcon(":cabana-icon.png")); - - UnixSignalHandler signalHandler; - utils::setTheme(settings.theme); - - QCommandLineParser cmd_parser; - cmd_parser.addHelpOption(); - cmd_parser.addPositionalArgument("route", "the drive to replay. find your drives at connect.comma.ai"); - cmd_parser.addOption({"demo", "use a demo route instead of providing your own"}); - cmd_parser.addOption({"qcam", "load qcamera"}); - cmd_parser.addOption({"ecam", "load wide road camera"}); - cmd_parser.addOption({"dcam", "load driver camera"}); - cmd_parser.addOption({"stream", "read can messages from live streaming"}); - cmd_parser.addOption({"panda", "read can messages from panda"}); - cmd_parser.addOption({"panda-serial", "read can messages from panda with given serial", "panda-serial"}); - if (SocketCanStream::available()) { - cmd_parser.addOption({"socketcan", "read can messages from given SocketCAN device", "socketcan"}); - } - cmd_parser.addOption({"zmq", "the ip address on which to receive zmq messages", "zmq"}); - cmd_parser.addOption({"data_dir", "local directory with routes", "data_dir"}); - cmd_parser.addOption({"no-vipc", "do not output video"}); - cmd_parser.addOption({"dbc", "dbc file to open", "dbc"}); - cmd_parser.process(app); - - QString dbc_file = cmd_parser.isSet("dbc") ? cmd_parser.value("dbc") : ""; - - AbstractStream *stream = nullptr; - if (cmd_parser.isSet("stream")) { - stream = new DeviceStream(&app, cmd_parser.value("zmq")); - } else if (cmd_parser.isSet("panda") || cmd_parser.isSet("panda-serial")) { - PandaStreamConfig config = {}; - if (cmd_parser.isSet("panda-serial")) { - config.serial = cmd_parser.value("panda-serial"); - } - try { - stream = new PandaStream(&app, config); - } catch (std::exception &e) { - qWarning() << e.what(); - return 0; - } - } else if (cmd_parser.isSet("socketcan")) { - SocketCanStreamConfig config = {}; - config.device = cmd_parser.value("socketcan"); - stream = new SocketCanStream(&app, config); - } else { - uint32_t replay_flags = REPLAY_FLAG_NONE; - if (cmd_parser.isSet("ecam")) replay_flags |= REPLAY_FLAG_ECAM; - if (cmd_parser.isSet("qcam")) replay_flags |= REPLAY_FLAG_QCAMERA; - if (cmd_parser.isSet("dcam")) replay_flags |= REPLAY_FLAG_DCAM; - if (cmd_parser.isSet("no-vipc")) replay_flags |= REPLAY_FLAG_NO_VIPC; - - const QStringList args = cmd_parser.positionalArguments(); - QString route; - if (args.size() > 0) { - route = args.first(); - } else if (cmd_parser.isSet("demo")) { - route = DEMO_ROUTE; - } - if (!route.isEmpty()) { - auto replay_stream = new ReplayStream(&app); - if (!replay_stream->loadRoute(route, cmd_parser.value("data_dir"), replay_flags)) { - return 0; - } - stream = replay_stream; - } - } - - int ret = 0; - { - MainWindow w; - QTimer::singleShot(0, [&]() { - if (!stream) { - StreamSelector dlg(&stream); - dlg.exec(); - dbc_file = dlg.dbcFile(); - } - if (!stream) { - stream = new DummyStream(&app); - } - stream->start(); - if (!dbc_file.isEmpty()) { - w.loadFile(dbc_file); - } - w.show(); - }); - - ret = app.exec(); - } - - delete can; - return ret; -} diff --git a/tools/cabana/chart/chart.cc b/tools/cabana/chart/chart.cc deleted file mode 100644 index 6f08a9f..0000000 --- a/tools/cabana/chart/chart.cc +++ /dev/null @@ -1,865 +0,0 @@ -#include "tools/cabana/chart/chart.h" - -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include "tools/cabana/chart/chartswidget.h" - -// ChartAxisElement's padding is 4 (https://codebrowser.dev/qt5/qtcharts/src/charts/axis/chartaxiselement_p.h.html) -const int AXIS_X_TOP_MARGIN = 4; -// Define a small value of epsilon to compare double values -const float EPSILON = 0.000001; -static inline bool xLessThan(const QPointF &p, float x) { return p.x() < (x - EPSILON); } - -ChartView::ChartView(const std::pair &x_range, ChartsWidget *parent) - : charts_widget(parent), QChartView(parent) { - series_type = (SeriesType)settings.chart_series_type; - chart()->setBackgroundVisible(false); - axis_x = new QValueAxis(this); - axis_y = new QValueAxis(this); - chart()->addAxis(axis_x, Qt::AlignBottom); - chart()->addAxis(axis_y, Qt::AlignLeft); - chart()->legend()->layout()->setContentsMargins(0, 0, 0, 0); - chart()->legend()->setShowToolTips(true); - chart()->setMargins({0, 0, 0, 0}); - - axis_x->setRange(x_range.first, x_range.second); - - tip_label = new TipLabel(this); - createToolButtons(); - setRubberBand(QChartView::HorizontalRubberBand); - setMouseTracking(true); - setTheme(settings.theme == DARK_THEME ? QChart::QChart::ChartThemeDark : QChart::ChartThemeLight); - signal_value_font.setPointSize(9); - - QObject::connect(axis_y, &QValueAxis::rangeChanged, this, &ChartView::resetChartCache); - QObject::connect(axis_y, &QAbstractAxis::titleTextChanged, this, &ChartView::resetChartCache); - QObject::connect(window()->windowHandle(), &QWindow::screenChanged, this, &ChartView::resetChartCache); - - QObject::connect(dbc(), &DBCManager::signalRemoved, this, &ChartView::signalRemoved); - QObject::connect(dbc(), &DBCManager::signalUpdated, this, &ChartView::signalUpdated); - QObject::connect(dbc(), &DBCManager::msgRemoved, this, &ChartView::msgRemoved); - QObject::connect(dbc(), &DBCManager::msgUpdated, this, &ChartView::msgUpdated); -} - -void ChartView::createToolButtons() { - move_icon = new QGraphicsPixmapItem(utils::icon("grip-horizontal"), chart()); - move_icon->setToolTip(tr("Drag and drop to move chart")); - - QToolButton *remove_btn = new ToolButton("x", tr("Remove Chart")); - close_btn_proxy = new QGraphicsProxyWidget(chart()); - close_btn_proxy->setWidget(remove_btn); - close_btn_proxy->setZValue(chart()->zValue() + 11); - - menu = new QMenu(this); - // series types - auto change_series_group = new QActionGroup(menu); - change_series_group->setExclusive(true); - QStringList types{tr("Line"), tr("Step Line"), tr("Scatter")}; - for (int i = 0; i < types.size(); ++i) { - QAction *act = new QAction(types[i], change_series_group); - act->setData(i); - act->setCheckable(true); - act->setChecked(i == (int)series_type); - menu->addAction(act); - } - menu->addSeparator(); - menu->addAction(tr("Manage Signals"), this, &ChartView::manageSignals); - split_chart_act = menu->addAction(tr("Split Chart"), [this]() { charts_widget->splitChart(this); }); - - QToolButton *manage_btn = new ToolButton("list", ""); - manage_btn->setMenu(menu); - manage_btn->setPopupMode(QToolButton::InstantPopup); - manage_btn->setStyleSheet("QToolButton::menu-indicator { image: none; }"); - manage_btn_proxy = new QGraphicsProxyWidget(chart()); - manage_btn_proxy->setWidget(manage_btn); - manage_btn_proxy->setZValue(chart()->zValue() + 11); - - close_act = new QAction(tr("Close"), this); - QObject::connect(close_act, &QAction::triggered, [this] () { charts_widget->removeChart(this); }); - QObject::connect(remove_btn, &QToolButton::clicked, close_act, &QAction::triggered); - QObject::connect(change_series_group, &QActionGroup::triggered, [this](QAction *action) { - setSeriesType((SeriesType)action->data().toInt()); - }); -} - -QSize ChartView::sizeHint() const { - return {CHART_MIN_WIDTH, settings.chart_height}; -} - -void ChartView::setTheme(QChart::ChartTheme theme) { - chart()->setTheme(theme); - if (theme == QChart::ChartThemeDark) { - axis_x->setTitleBrush(palette().text()); - axis_x->setLabelsBrush(palette().text()); - axis_y->setTitleBrush(palette().text()); - axis_y->setLabelsBrush(palette().text()); - chart()->legend()->setLabelColor(palette().color(QPalette::Text)); - } - for (auto &s : sigs) { - s.series->setColor(s.sig->color); - } -} - -void ChartView::addSignal(const MessageId &msg_id, const cabana::Signal *sig) { - if (hasSignal(msg_id, sig)) return; - - QXYSeries *series = createSeries(series_type, sig->color); - sigs.push_back({.msg_id = msg_id, .sig = sig, .series = series}); - updateSeries(sig); - updateSeriesPoints(); - updateTitle(); - emit charts_widget->seriesChanged(); -} - -bool ChartView::hasSignal(const MessageId &msg_id, const cabana::Signal *sig) const { - return std::any_of(sigs.cbegin(), sigs.cend(), [&](auto &s) { return s.msg_id == msg_id && s.sig == sig; }); -} - -void ChartView::removeIf(std::function predicate) { - int prev_size = sigs.size(); - for (auto it = sigs.begin(); it != sigs.end(); /**/) { - if (predicate(*it)) { - chart()->removeSeries(it->series); - it->series->deleteLater(); - it = sigs.erase(it); - } else { - ++it; - } - } - if (sigs.empty()) { - charts_widget->removeChart(this); - } else if (sigs.size() != prev_size) { - emit charts_widget->seriesChanged(); - updateAxisY(); - resetChartCache(); - } -} - -void ChartView::signalUpdated(const cabana::Signal *sig) { - if (std::any_of(sigs.cbegin(), sigs.cend(), [=](auto &s) { return s.sig == sig; })) { - for (const auto &s : sigs) { - if (s.sig == sig && s.series->color() != sig->color) { - setSeriesColor(s.series, sig->color); - } - } - updateTitle(); - updateSeries(sig); - } -} - -void ChartView::msgUpdated(MessageId id) { - if (std::any_of(sigs.cbegin(), sigs.cend(), [=](auto &s) { return s.msg_id.address == id.address; })) { - updateTitle(); - } -} - -void ChartView::manageSignals() { - SignalSelector dlg(tr("Manage Chart"), this); - for (auto &s : sigs) { - dlg.addSelected(s.msg_id, s.sig); - } - if (dlg.exec() == QDialog::Accepted) { - auto items = dlg.seletedItems(); - for (auto s : items) { - addSignal(s->msg_id, s->sig); - } - removeIf([&](auto &s) { - return std::none_of(items.cbegin(), items.cend(), [&](auto &it) { return s.msg_id == it->msg_id && s.sig == it->sig; }); - }); - } -} - -void ChartView::resizeEvent(QResizeEvent *event) { - qreal left, top, right, bottom; - chart()->layout()->getContentsMargins(&left, &top, &right, &bottom); - move_icon->setPos(left, top); - close_btn_proxy->setPos(rect().right() - right - close_btn_proxy->size().width(), top); - int x = close_btn_proxy->pos().x() - manage_btn_proxy->size().width() - style()->pixelMetric(QStyle::PM_LayoutHorizontalSpacing); - manage_btn_proxy->setPos(x, top); - if (align_to > 0) { - updatePlotArea(align_to, true); - } - QChartView::resizeEvent(event); -} - -void ChartView::updatePlotArea(int left_pos, bool force) { - if (align_to != left_pos || force) { - align_to = left_pos; - - qreal left, top, right, bottom; - chart()->layout()->getContentsMargins(&left, &top, &right, &bottom); - QSizeF legend_size = chart()->legend()->layout()->minimumSize(); - legend_size.setWidth(manage_btn_proxy->sceneBoundingRect().left() - move_icon->sceneBoundingRect().right()); - chart()->legend()->setGeometry({move_icon->sceneBoundingRect().topRight(), legend_size}); - - // add top space for signal value - int adjust_top = chart()->legend()->geometry().height() + QFontMetrics(signal_value_font).height() + 3; - adjust_top = std::max(adjust_top, manage_btn_proxy->sceneBoundingRect().height() + style()->pixelMetric(QStyle::PM_LayoutTopMargin)); - // add right space for x-axis label - QSizeF x_label_size = QFontMetrics(axis_x->labelsFont()).size(Qt::TextSingleLine, QString::number(axis_x->max(), 'f', 2)); - x_label_size += QSizeF{5, 5}; - chart()->setPlotArea(rect().adjusted(align_to + left, adjust_top + top, -x_label_size.width() / 2 - right, -x_label_size.height() - bottom)); - chart()->layout()->invalidate(); - resetChartCache(); - } -} - -void ChartView::updateTitle() { - for (QLegendMarker *marker : chart()->legend()->markers()) { - QObject::connect(marker, &QLegendMarker::clicked, this, &ChartView::handleMarkerClicked, Qt::UniqueConnection); - } - - // Use CSS to draw titles in the WindowText color - auto tmp = palette().color(QPalette::WindowText); - auto titleColorCss = tmp.name(QColor::HexArgb); - // Draw message details in similar color, but slightly fade it to the background - tmp.setAlpha(180); - auto msgColorCss = tmp.name(QColor::HexArgb); - - for (auto &s : sigs) { - auto decoration = s.series->isVisible() ? "none" : "line-through"; - s.series->setName(QString("%3 %5 %6") - .arg(decoration, titleColorCss, s.sig->name, - msgColorCss, msgName(s.msg_id), s.msg_id.toString())); - } - split_chart_act->setEnabled(sigs.size() > 1); - resetChartCache(); -} - -void ChartView::updatePlot(double cur, double min, double max) { - cur_sec = cur; - if (min != axis_x->min() || max != axis_x->max()) { - axis_x->setRange(min, max); - updateAxisY(); - updateSeriesPoints(); - // update tooltip - if (tooltip_x >= 0) { - showTip(chart()->mapToValue({tooltip_x, 0}).x()); - } - resetChartCache(); - } - viewport()->update(); -} - -void ChartView::updateSeriesPoints() { - // Show points when zoomed in enough - for (auto &s : sigs) { - auto begin = std::lower_bound(s.vals.cbegin(), s.vals.cend(), axis_x->min(), xLessThan); - auto end = std::lower_bound(begin, s.vals.cend(), axis_x->max(), xLessThan); - if (begin != end) { - int num_points = std::max((end - begin), 1); - QPointF right_pt = end == s.vals.cend() ? s.vals.back() : *end; - double pixels_per_point = (chart()->mapToPosition(right_pt).x() - chart()->mapToPosition(*begin).x()) / num_points; - - if (series_type == SeriesType::Scatter) { - qreal size = std::clamp(pixels_per_point / 2.0, 2.0, 8.0); - if (s.series->useOpenGL()) { - size *= devicePixelRatioF(); - } - ((QScatterSeries *)s.series)->setMarkerSize(size); - } else { - s.series->setPointsVisible(pixels_per_point > 20); - } - } - } -} - -void ChartView::appendCanEvents(const cabana::Signal *sig, const std::vector &events, - std::vector &vals, std::vector &step_vals) { - vals.reserve(vals.size() + events.capacity()); - step_vals.reserve(step_vals.size() + events.capacity() * 2); - - double value = 0; - const uint64_t begin_mono_time = can->routeStartTime() * 1e9; - for (const CanEvent *e : events) { - if (sig->getValue(e->dat, e->size, &value)) { - const double ts = (e->mono_time - std::min(e->mono_time, begin_mono_time)) / 1e9; - vals.emplace_back(ts, value); - if (!step_vals.empty()) - step_vals.emplace_back(ts, step_vals.back().y()); - step_vals.emplace_back(ts, value); - } - } -} - -void ChartView::updateSeries(const cabana::Signal *sig, const MessageEventsMap *msg_new_events) { - for (auto &s : sigs) { - if (!sig || s.sig == sig) { - if (!msg_new_events) { - s.vals.clear(); - s.step_vals.clear(); - } - auto events = msg_new_events ? msg_new_events : &can->eventsMap(); - auto it = events->find(s.msg_id); - if (it == events->end() || it->second.empty()) continue; - - if (s.vals.empty() || (it->second.back()->mono_time / 1e9 - can->routeStartTime()) > s.vals.back().x()) { - appendCanEvents(s.sig, it->second, s.vals, s.step_vals); - } else { - std::vector vals, step_vals; - appendCanEvents(s.sig, it->second, vals, step_vals); - s.vals.insert(std::lower_bound(s.vals.begin(), s.vals.end(), vals.front().x(), xLessThan), - vals.begin(), vals.end()); - s.step_vals.insert(std::lower_bound(s.step_vals.begin(), s.step_vals.end(), step_vals.front().x(), xLessThan), - step_vals.begin(), step_vals.end()); - } - - if (!can->liveStreaming()) { - s.segment_tree.build(s.vals); - } - s.series->replace(QVector::fromStdVector(series_type == SeriesType::StepLine ? s.step_vals : s.vals)); - } - } - updateAxisY(); - // invoke resetChartCache in ui thread - QMetaObject::invokeMethod(this, &ChartView::resetChartCache, Qt::QueuedConnection); -} - -// auto zoom on yaxis -void ChartView::updateAxisY() { - if (sigs.empty()) return; - - double min = std::numeric_limits::max(); - double max = std::numeric_limits::lowest(); - QString unit = sigs[0].sig->unit; - - for (auto &s : sigs) { - if (!s.series->isVisible()) continue; - - // Only show unit when all signals have the same unit - if (unit != s.sig->unit) { - unit.clear(); - } - - auto first = std::lower_bound(s.vals.cbegin(), s.vals.cend(), axis_x->min(), xLessThan); - auto last = std::lower_bound(first, s.vals.cend(), axis_x->max(), xLessThan); - s.min = std::numeric_limits::max(); - s.max = std::numeric_limits::lowest(); - if (can->liveStreaming()) { - for (auto it = first; it != last; ++it) { - if (it->y() < s.min) s.min = it->y(); - if (it->y() > s.max) s.max = it->y(); - } - } else { - std::tie(s.min, s.max) = s.segment_tree.minmax(std::distance(s.vals.cbegin(), first), std::distance(s.vals.cbegin(), last)); - } - min = std::min(min, s.min); - max = std::max(max, s.max); - } - if (min == std::numeric_limits::max()) min = 0; - if (max == std::numeric_limits::lowest()) max = 0; - - if (axis_y->titleText() != unit) { - axis_y->setTitleText(unit); - y_label_width = 0; // recalc width - } - - double delta = std::abs(max - min) < 1e-3 ? 1 : (max - min) * 0.05; - auto [min_y, max_y, tick_count] = getNiceAxisNumbers(min - delta, max + delta, 3); - if (min_y != axis_y->min() || max_y != axis_y->max() || y_label_width == 0) { - axis_y->setRange(min_y, max_y); - axis_y->setTickCount(tick_count); - - int n = std::max(int(-std::floor(std::log10((max_y - min_y) / (tick_count - 1)))), 0); - int max_label_width = 0; - QFontMetrics fm(axis_y->labelsFont()); - for (int i = 0; i < tick_count; i++) { - qreal value = min_y + (i * (max_y - min_y) / (tick_count - 1)); - max_label_width = std::max(max_label_width, fm.width(QString::number(value, 'f', n))); - } - - int title_spacing = unit.isEmpty() ? 0 : QFontMetrics(axis_y->titleFont()).size(Qt::TextSingleLine, unit).height(); - y_label_width = title_spacing + max_label_width + 15; - axis_y->setLabelFormat(QString("%.%1f").arg(n)); - emit axisYLabelWidthChanged(y_label_width); - } -} - -std::tuple ChartView::getNiceAxisNumbers(qreal min, qreal max, int tick_count) { - qreal range = niceNumber((max - min), true); // range with ceiling - qreal step = niceNumber(range / (tick_count - 1), false); - min = std::floor(min / step); - max = std::ceil(max / step); - tick_count = int(max - min) + 1; - return {min * step, max * step, tick_count}; -} - -// nice numbers can be expressed as form of 1*10^n, 2* 10^n or 5*10^n -qreal ChartView::niceNumber(qreal x, bool ceiling) { - qreal z = std::pow(10, std::floor(std::log10(x))); //find corresponding number of the form of 10^n than is smaller than x - qreal q = x / z; //q<10 && q>=1; - if (ceiling) { - if (q <= 1.0) q = 1; - else if (q <= 2.0) q = 2; - else if (q <= 5.0) q = 5; - else q = 10; - } else { - if (q < 1.5) q = 1; - else if (q < 3.0) q = 2; - else if (q < 7.0) q = 5; - else q = 10; - } - return q * z; -} - -void ChartView::leaveEvent(QEvent *event) { - if (tip_label->isVisible()) { - charts_widget->showValueTip(-1); - } - QChartView::leaveEvent(event); -} - -QPixmap getBlankShadowPixmap(const QPixmap &px, int radius) { - QGraphicsDropShadowEffect *e = new QGraphicsDropShadowEffect; - e->setColor(QColor(40, 40, 40, 245)); - e->setOffset(0, 0); - e->setBlurRadius(radius); - - qreal dpr = px.devicePixelRatio(); - QPixmap blank(px.size()); - blank.setDevicePixelRatio(dpr); - blank.fill(Qt::white); - - QGraphicsScene scene; - QGraphicsPixmapItem item(blank); - item.setGraphicsEffect(e); - scene.addItem(&item); - - QPixmap shadow(px.size() + QSize(radius * dpr * 2, radius * dpr * 2)); - shadow.setDevicePixelRatio(dpr); - shadow.fill(Qt::transparent); - QPainter p(&shadow); - scene.render(&p, {QPoint(), shadow.size() / dpr}, item.boundingRect().adjusted(-radius, -radius, radius, radius)); - return shadow; -} - -static QPixmap getDropPixmap(const QPixmap &src) { - static QPixmap shadow_px; - const int radius = 10; - if (shadow_px.size() != src.size() + QSize(radius * 2, radius * 2)) { - shadow_px = getBlankShadowPixmap(src, radius); - } - QPixmap px = shadow_px; - QPainter p(&px); - QRectF target_rect(QPointF(radius, radius), src.size() / src.devicePixelRatio()); - p.drawPixmap(target_rect.topLeft(), src); - p.setCompositionMode(QPainter::CompositionMode_DestinationIn); - p.fillRect(target_rect, QColor(0, 0, 0, 200)); - return px; -} - -void ChartView::contextMenuEvent(QContextMenuEvent *event) { - QMenu context_menu(this); - context_menu.addActions(menu->actions()); - context_menu.addSeparator(); - context_menu.addAction(charts_widget->undo_zoom_action); - context_menu.addAction(charts_widget->redo_zoom_action); - context_menu.addSeparator(); - context_menu.addAction(close_act); - context_menu.exec(event->globalPos()); -} - -void ChartView::mousePressEvent(QMouseEvent *event) { - if (event->button() == Qt::LeftButton && move_icon->sceneBoundingRect().contains(event->pos())) { - QMimeData *mimeData = new QMimeData; - mimeData->setData(CHART_MIME_TYPE, QByteArray::number((qulonglong)this)); - QPixmap px = grab().scaledToWidth(CHART_MIN_WIDTH * viewport()->devicePixelRatio(), Qt::SmoothTransformation); - charts_widget->stopAutoScroll(); - QDrag *drag = new QDrag(this); - drag->setMimeData(mimeData); - drag->setPixmap(getDropPixmap(px)); - drag->setHotSpot(-QPoint(5, 5)); - drag->exec(Qt::CopyAction | Qt::MoveAction, Qt::MoveAction); - } else if (event->button() == Qt::LeftButton && QApplication::keyboardModifiers().testFlag(Qt::ShiftModifier)) { - // Save current playback state when scrubbing - resume_after_scrub = !can->isPaused(); - if (resume_after_scrub) { - can->pause(true); - } - is_scrubbing = true; - } else { - QChartView::mousePressEvent(event); - } -} - -void ChartView::mouseReleaseEvent(QMouseEvent *event) { - auto rubber = findChild(); - if (event->button() == Qt::LeftButton && rubber && rubber->isVisible()) { - rubber->hide(); - auto rect = rubber->geometry().normalized(); - // Prevent zooming/seeking past the end of the route - double min = std::clamp(chart()->mapToValue(rect.topLeft()).x(), 0., can->totalSeconds()); - double max = std::clamp(chart()->mapToValue(rect.bottomRight()).x(), 0., can->totalSeconds()); - if (rubber->width() <= 0) { - // no rubber dragged, seek to mouse position - can->seekTo(min); - } else if (rubber->width() > 10 && (max - min) > 0.01) { // Minimum range is 10 milliseconds. - charts_widget->zoom_undo_stack->push(new ZoomCommand(charts_widget, {min, max})); - } else { - viewport()->update(); - } - event->accept(); - } else if (event->button() == Qt::RightButton) { - charts_widget->zoom_undo_stack->undo(); - event->accept(); - } else { - QGraphicsView::mouseReleaseEvent(event); - } - - // Resume playback if we were scrubbing - is_scrubbing = false; - if (resume_after_scrub) { - can->pause(false); - resume_after_scrub = false; - } -} - -void ChartView::mouseMoveEvent(QMouseEvent *ev) { - const auto plot_area = chart()->plotArea(); - // Scrubbing - if (is_scrubbing && QApplication::keyboardModifiers().testFlag(Qt::ShiftModifier)) { - if (plot_area.contains(ev->pos())) { - can->seekTo(std::clamp(chart()->mapToValue(ev->pos()).x(), 0., can->totalSeconds())); - } - } - - auto rubber = findChild(); - bool is_zooming = rubber && rubber->isVisible(); - clearTrackPoints(); - - if (!is_zooming && plot_area.contains(ev->pos())) { - const double sec = chart()->mapToValue(ev->pos()).x(); - charts_widget->showValueTip(sec); - } else if (tip_label->isVisible()) { - charts_widget->showValueTip(-1); - } - - QChartView::mouseMoveEvent(ev); - if (is_zooming) { - QRect rubber_rect = rubber->geometry(); - rubber_rect.setLeft(std::max(rubber_rect.left(), (int)plot_area.left())); - rubber_rect.setRight(std::min(rubber_rect.right(), (int)plot_area.right())); - if (rubber_rect != rubber->geometry()) { - rubber->setGeometry(rubber_rect); - } - viewport()->update(); - } -} - -void ChartView::showTip(double sec) { - QRect tip_area(0, chart()->plotArea().top(), rect().width(), chart()->plotArea().height()); - QRect visible_rect = charts_widget->chartVisibleRect(this).intersected(tip_area); - if (visible_rect.isEmpty()) { - tip_label->hide(); - return; - } - - tooltip_x = chart()->mapToPosition({sec, 0}).x(); - qreal x = -1; - QStringList text_list; - for (auto &s : sigs) { - if (s.series->isVisible()) { - QString value = "--"; - // use reverse iterator to find last item <= sec. - auto it = std::lower_bound(s.vals.crbegin(), s.vals.crend(), sec, [](auto &p, double x) { return p.x() > x; }); - if (it != s.vals.crend() && it->x() >= axis_x->min()) { - value = QString::number(it->y()); - s.track_pt = *it; - x = std::max(x, chart()->mapToPosition(*it).x()); - } - QString name = sigs.size() > 1 ? s.sig->name + ": " : ""; - QString min = s.min == std::numeric_limits::max() ? "--" : QString::number(s.min); - QString max = s.max == std::numeric_limits::lowest() ? "--" : QString::number(s.max); - text_list << QString("%2%3 (%4, %5)") - .arg(s.series->color().name(), name, value, min, max); - } - } - if (x < 0) { - x = tooltip_x; - } - QPoint pt(x, chart()->plotArea().top()); - text_list.push_front(QString::number(chart()->mapToValue({x, 0}).x(), 'f', 3)); - QString text = "

" % text_list.join("
") % "

"; - tip_label->showText(pt, text, this, visible_rect); - viewport()->update(); -} - -void ChartView::hideTip() { - clearTrackPoints(); - tooltip_x = -1; - tip_label->hide(); - viewport()->update(); -} - -void ChartView::dragEnterEvent(QDragEnterEvent *event) { - if (event->mimeData()->hasFormat(CHART_MIME_TYPE)) { - drawDropIndicator(event->source() != this); - event->acceptProposedAction(); - } -} - -void ChartView::dragMoveEvent(QDragMoveEvent *event) { - if (event->mimeData()->hasFormat(CHART_MIME_TYPE)) { - event->setDropAction(event->source() == this ? Qt::MoveAction : Qt::CopyAction); - event->accept(); - } - charts_widget->startAutoScroll(); -} - -void ChartView::dropEvent(QDropEvent *event) { - if (event->mimeData()->hasFormat(CHART_MIME_TYPE)) { - if (event->source() != this) { - ChartView *source_chart = (ChartView *)event->source(); - for (auto &s : source_chart->sigs) { - source_chart->chart()->removeSeries(s.series); - addSeries(s.series); - } - sigs.insert(sigs.end(), std::move_iterator(source_chart->sigs.begin()), std::move_iterator(source_chart->sigs.end())); - updateAxisY(); - updateTitle(); - startAnimation(); - - source_chart->sigs.clear(); - charts_widget->removeChart(source_chart); - event->acceptProposedAction(); - } - can_drop = false; - } -} - -void ChartView::resetChartCache() { - chart_pixmap = QPixmap(); - viewport()->update(); -} - -void ChartView::startAnimation() { - QGraphicsOpacityEffect *eff = new QGraphicsOpacityEffect(this); - viewport()->setGraphicsEffect(eff); - QPropertyAnimation *a = new QPropertyAnimation(eff, "opacity"); - a->setDuration(250); - a->setStartValue(0.3); - a->setEndValue(1); - a->setEasingCurve(QEasingCurve::InBack); - a->start(QPropertyAnimation::DeleteWhenStopped); -} - -void ChartView::paintEvent(QPaintEvent *event) { - if (!can->liveStreaming()) { - if (chart_pixmap.isNull()) { - const qreal dpr = viewport()->devicePixelRatioF(); - chart_pixmap = QPixmap(viewport()->size() * dpr); - chart_pixmap.setDevicePixelRatio(dpr); - QPainter p(&chart_pixmap); - p.setRenderHints(QPainter::Antialiasing); - drawBackground(&p, viewport()->rect()); - scene()->setSceneRect(viewport()->rect()); - scene()->render(&p, viewport()->rect()); - } - - QPainter painter(viewport()); - painter.setRenderHints(QPainter::Antialiasing); - painter.drawPixmap(QPoint(), chart_pixmap); - if (can_drop) { - painter.setPen(QPen(palette().color(QPalette::Highlight), 4)); - painter.drawRect(viewport()->rect()); - } - QRectF exposed_rect = mapToScene(event->region().boundingRect()).boundingRect(); - drawForeground(&painter, exposed_rect); - } else { - QChartView::paintEvent(event); - } -} - -void ChartView::drawBackground(QPainter *painter, const QRectF &rect) { - painter->fillRect(rect, palette().color(QPalette::Base)); -} - -void ChartView::drawForeground(QPainter *painter, const QRectF &rect) { - drawTimeline(painter); - drawSignalValue(painter); - // draw track points - painter->setPen(Qt::NoPen); - qreal track_line_x = -1; - for (auto &s : sigs) { - if (!s.track_pt.isNull() && s.series->isVisible()) { - painter->setBrush(s.series->color().darker(125)); - QPointF pos = chart()->mapToPosition(s.track_pt); - painter->drawEllipse(pos, 5.5, 5.5); - track_line_x = std::max(track_line_x, pos.x()); - } - } - if (track_line_x > 0) { - auto plot_area = chart()->plotArea(); - painter->setPen(QPen(Qt::darkGray, 1, Qt::DashLine)); - painter->drawLine(QPointF{track_line_x, plot_area.top()}, QPointF{track_line_x, plot_area.bottom()}); - } - - // paint points. OpenGL mode lacks certain features (such as showing points) - painter->setPen(Qt::NoPen); - for (auto &s : sigs) { - if (s.series->useOpenGL() && s.series->isVisible() && s.series->pointsVisible()) { - auto first = std::lower_bound(s.vals.cbegin(), s.vals.cend(), axis_x->min(), xLessThan); - auto last = std::lower_bound(first, s.vals.cend(), axis_x->max(), xLessThan); - painter->setBrush(s.series->color()); - for (auto it = first; it != last; ++it) { - painter->drawEllipse(chart()->mapToPosition(*it), 4, 4); - } - } - } - - drawRubberBandTimeRange(painter); -} - -void ChartView::drawRubberBandTimeRange(QPainter *painter) { - auto rubber = findChild(); - if (rubber && rubber->isVisible() && rubber->width() > 1) { - painter->setPen(Qt::white); - auto rubber_rect = rubber->geometry().normalized(); - for (const auto &pt : {rubber_rect.bottomLeft(), rubber_rect.bottomRight()}) { - QString sec = QString::number(chart()->mapToValue(pt).x(), 'f', 2); - auto r = painter->fontMetrics().boundingRect(sec).adjusted(-6, -AXIS_X_TOP_MARGIN, 6, AXIS_X_TOP_MARGIN); - pt == rubber_rect.bottomLeft() ? r.moveTopRight(pt + QPoint{0, 2}) : r.moveTopLeft(pt + QPoint{0, 2}); - painter->fillRect(r, Qt::gray); - painter->drawText(r, Qt::AlignCenter, sec); - } - } -} - -void ChartView::drawTimeline(QPainter *painter) { - const auto plot_area = chart()->plotArea(); - // draw vertical time line - qreal x = std::clamp(chart()->mapToPosition(QPointF{cur_sec, 0}).x(), plot_area.left(), plot_area.right()); - painter->setPen(QPen(chart()->titleBrush().color(), 2)); - painter->drawLine(QPointF{x, plot_area.top()}, QPointF{x, plot_area.bottom() + 1}); - - // draw current time under the axis-x - QString time_str = QString::number(cur_sec, 'f', 2); - QSize time_str_size = QFontMetrics(axis_x->labelsFont()).size(Qt::TextSingleLine, time_str) + QSize(8, 2); - QRectF time_str_rect(QPointF(x - time_str_size.width() / 2.0, plot_area.bottom() + AXIS_X_TOP_MARGIN), time_str_size); - QPainterPath path; - path.addRoundedRect(time_str_rect, 3, 3); - painter->fillPath(path, settings.theme == DARK_THEME ? Qt::darkGray : Qt::gray); - painter->setPen(palette().color(QPalette::BrightText)); - painter->setFont(axis_x->labelsFont()); - painter->drawText(time_str_rect, Qt::AlignCenter, time_str); -} - -void ChartView::drawSignalValue(QPainter *painter) { - auto item_group = qgraphicsitem_cast(chart()->legend()->childItems()[0]); - assert(item_group != nullptr); - auto legend_markers = item_group->childItems(); - assert(legend_markers.size() == sigs.size()); - - painter->setFont(signal_value_font); - painter->setPen(chart()->legend()->labelColor()); - int i = 0; - for (auto &s : sigs) { - auto it = std::lower_bound(s.vals.crbegin(), s.vals.crend(), cur_sec, - [](auto &p, double x) { return p.x() > x + EPSILON; }); - QString value = (it != s.vals.crend() && it->x() >= axis_x->min()) ? s.sig->formatValue(it->y()) : "--"; - QRectF marker_rect = legend_markers[i++]->sceneBoundingRect(); - QRectF value_rect(marker_rect.bottomLeft() - QPoint(0, 1), marker_rect.size()); - QString elided_val = painter->fontMetrics().elidedText(value, Qt::ElideRight, value_rect.width()); - painter->drawText(value_rect, Qt::AlignHCenter | Qt::AlignTop, elided_val); - } -} - -QXYSeries *ChartView::createSeries(SeriesType type, QColor color) { - QXYSeries *series = nullptr; - if (type == SeriesType::Line) { - series = new QLineSeries(this); - chart()->legend()->setMarkerShape(QLegend::MarkerShapeRectangle); - } else if (type == SeriesType::StepLine) { - series = new QLineSeries(this); - chart()->legend()->setMarkerShape(QLegend::MarkerShapeFromSeries); - } else { - series = new QScatterSeries(this); - static_cast(series)->setBorderColor(color); - chart()->legend()->setMarkerShape(QLegend::MarkerShapeCircle); - } - series->setColor(color); - // TODO: Due to a bug in CameraWidget the camera frames - // are drawn instead of the graphs on MacOS. Re-enable OpenGL when fixed -#ifndef __APPLE__ - series->setUseOpenGL(true); - // Qt doesn't properly apply device pixel ratio in OpenGL mode - QPen pen = series->pen(); - pen.setWidthF(2.0 * devicePixelRatioF()); - series->setPen(pen); -#endif - addSeries(series); - return series; -} - -void ChartView::addSeries(QXYSeries *series) { - setSeriesColor(series, series->color()); - chart()->addSeries(series); - series->attachAxis(axis_x); - series->attachAxis(axis_y); - - // disables the delivery of mouse events to the opengl widget. - // this enables the user to select the zoom area when the mouse press on the data point. - auto glwidget = findChild(); - if (glwidget && !glwidget->testAttribute(Qt::WA_TransparentForMouseEvents)) { - glwidget->setAttribute(Qt::WA_TransparentForMouseEvents); - } -} - -void ChartView::setSeriesColor(QXYSeries *series, QColor color) { - auto existing_series = chart()->series(); - for (auto s : existing_series) { - if (s != series && std::abs(color.hueF() - qobject_cast(s)->color().hueF()) < 0.1) { - // use different color to distinguish it from others. - auto last_color = qobject_cast(existing_series.back())->color(); - color.setHsvF(std::fmod(last_color.hueF() + 60 / 360.0, 1.0), - QRandomGenerator::global()->bounded(35, 100) / 100.0, - QRandomGenerator::global()->bounded(85, 100) / 100.0); - break; - } - } - series->setColor(color); -} - -void ChartView::setSeriesType(SeriesType type) { - if (type != series_type) { - series_type = type; - for (auto &s : sigs) { - chart()->removeSeries(s.series); - s.series->deleteLater(); - } - for (auto &s : sigs) { - s.series = createSeries(series_type, s.sig->color); - s.series->replace(QVector::fromStdVector(series_type == SeriesType::StepLine ? s.step_vals : s.vals)); - } - updateSeriesPoints(); - updateTitle(); - } -} - -void ChartView::handleMarkerClicked() { - auto marker = qobject_cast(sender()); - Q_ASSERT(marker); - if (sigs.size() > 1) { - auto series = marker->series(); - series->setVisible(!series->isVisible()); - marker->setVisible(true); - updateAxisY(); - updateTitle(); - } -} diff --git a/tools/cabana/chart/chart.h b/tools/cabana/chart/chart.h deleted file mode 100644 index d690a14..0000000 --- a/tools/cabana/chart/chart.h +++ /dev/null @@ -1,123 +0,0 @@ -#pragma once - -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -using namespace QtCharts; - -#include "tools/cabana/chart/tiplabel.h" -#include "tools/cabana/dbc/dbcmanager.h" -#include "tools/cabana/streams/abstractstream.h" - -enum class SeriesType { - Line = 0, - StepLine, - Scatter -}; - -class ChartsWidget; -class ChartView : public QChartView { - Q_OBJECT - -public: - ChartView(const std::pair &x_range, ChartsWidget *parent = nullptr); - void addSignal(const MessageId &msg_id, const cabana::Signal *sig); - bool hasSignal(const MessageId &msg_id, const cabana::Signal *sig) const; - void updateSeries(const cabana::Signal *sig = nullptr, const MessageEventsMap *msg_new_events = nullptr); - void updatePlot(double cur, double min, double max); - void setSeriesType(SeriesType type); - void updatePlotArea(int left, bool force = false); - void showTip(double sec); - void hideTip(); - void startAnimation(); - - struct SigItem { - MessageId msg_id; - const cabana::Signal *sig = nullptr; - QXYSeries *series = nullptr; - std::vector vals; - std::vector step_vals; - QPointF track_pt{}; - SegmentTree segment_tree; - double min = 0; - double max = 0; - }; - -signals: - void axisYLabelWidthChanged(int w); - -private slots: - void signalUpdated(const cabana::Signal *sig); - void manageSignals(); - void handleMarkerClicked(); - void msgUpdated(MessageId id); - void msgRemoved(MessageId id) { removeIf([=](auto &s) { return s.msg_id.address == id.address && !dbc()->msg(id); }); } - void signalRemoved(const cabana::Signal *sig) { removeIf([=](auto &s) { return s.sig == sig; }); } - -private: - void appendCanEvents(const cabana::Signal *sig, const std::vector &events, - std::vector &vals, std::vector &step_vals); - void createToolButtons(); - void addSeries(QXYSeries *series); - void contextMenuEvent(QContextMenuEvent *event) override; - void mousePressEvent(QMouseEvent *event) override; - void mouseReleaseEvent(QMouseEvent *event) override; - void mouseMoveEvent(QMouseEvent *ev) override; - void dragEnterEvent(QDragEnterEvent *event) override; - void dragLeaveEvent(QDragLeaveEvent *event) override { drawDropIndicator(false); } - void dragMoveEvent(QDragMoveEvent *event) override; - void dropEvent(QDropEvent *event) override; - void leaveEvent(QEvent *event) override; - void resizeEvent(QResizeEvent *event) override; - QSize sizeHint() const override; - void updateAxisY(); - void updateTitle(); - void resetChartCache(); - void setTheme(QChart::ChartTheme theme); - void paintEvent(QPaintEvent *event) override; - void drawForeground(QPainter *painter, const QRectF &rect) override; - void drawBackground(QPainter *painter, const QRectF &rect) override; - void drawDropIndicator(bool draw) { if (std::exchange(can_drop, draw) != can_drop) viewport()->update(); } - void drawSignalValue(QPainter *painter); - void drawTimeline(QPainter *painter); - void drawRubberBandTimeRange(QPainter *painter); - std::tuple getNiceAxisNumbers(qreal min, qreal max, int tick_count); - qreal niceNumber(qreal x, bool ceiling); - QXYSeries *createSeries(SeriesType type, QColor color); - void setSeriesColor(QXYSeries *, QColor color); - void updateSeriesPoints(); - void removeIf(std::function predicate); - inline void clearTrackPoints() { for (auto &s : sigs) s.track_pt = {}; } - - int y_label_width = 0; - int align_to = 0; - QValueAxis *axis_x; - QValueAxis *axis_y; - QMenu *menu; - QAction *split_chart_act; - QAction *close_act; - QGraphicsPixmapItem *move_icon; - QGraphicsProxyWidget *close_btn_proxy; - QGraphicsProxyWidget *manage_btn_proxy; - TipLabel *tip_label; - std::vector sigs; - double cur_sec = 0; - SeriesType series_type = SeriesType::Line; - bool is_scrubbing = false; - bool resume_after_scrub = false; - QPixmap chart_pixmap; - bool can_drop = false; - double tooltip_x = -1; - QFont signal_value_font; - ChartsWidget *charts_widget; - friend class ChartsWidget; -}; diff --git a/tools/cabana/chart/chartswidget.cc b/tools/cabana/chart/chartswidget.cc deleted file mode 100644 index 63d6091..0000000 --- a/tools/cabana/chart/chartswidget.cc +++ /dev/null @@ -1,539 +0,0 @@ -#include "tools/cabana/chart/chartswidget.h" - -#include - -#include -#include -#include -#include -#include -#include - -#include "tools/cabana/chart/chart.h" - -const int MAX_COLUMN_COUNT = 4; -const int CHART_SPACING = 4; - -ChartsWidget::ChartsWidget(QWidget *parent) : QFrame(parent) { - align_timer = new QTimer(this); - auto_scroll_timer = new QTimer(this); - setFrameStyle(QFrame::StyledPanel | QFrame::Plain); - QVBoxLayout *main_layout = new QVBoxLayout(this); - main_layout->setContentsMargins(0, 0, 0, 0); - main_layout->setSpacing(0); - - // toolbar - QToolBar *toolbar = new QToolBar(tr("Charts"), this); - int icon_size = style()->pixelMetric(QStyle::PM_SmallIconSize); - toolbar->setIconSize({icon_size, icon_size}); - - auto new_plot_btn = new ToolButton("file-plus", tr("New Chart")); - auto new_tab_btn = new ToolButton("window-stack", tr("New Tab")); - toolbar->addWidget(new_plot_btn); - toolbar->addWidget(new_tab_btn); - toolbar->addWidget(title_label = new QLabel()); - title_label->setContentsMargins(0, 0, style()->pixelMetric(QStyle::PM_LayoutHorizontalSpacing), 0); - - QMenu *menu = new QMenu(this); - for (int i = 0; i < MAX_COLUMN_COUNT; ++i) { - menu->addAction(tr("%1").arg(i + 1), [=]() { setColumnCount(i + 1); }); - } - columns_action = toolbar->addAction(""); - columns_action->setMenu(menu); - qobject_cast(toolbar->widgetForAction(columns_action))->setPopupMode(QToolButton::InstantPopup); - - QLabel *stretch_label = new QLabel(this); - stretch_label->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Preferred); - toolbar->addWidget(stretch_label); - - range_lb_action = toolbar->addWidget(range_lb = new QLabel(this)); - range_slider = new LogSlider(1000, Qt::Horizontal, this); - range_slider->setMaximumWidth(200); - range_slider->setToolTip(tr("Set the chart range")); - range_slider->setRange(1, settings.max_cached_minutes * 60); - range_slider->setSingleStep(1); - range_slider->setPageStep(60); // 1 min - range_slider_action = toolbar->addWidget(range_slider); - - // zoom controls - zoom_undo_stack = new QUndoStack(this); - toolbar->addAction(undo_zoom_action = zoom_undo_stack->createUndoAction(this)); - undo_zoom_action->setIcon(utils::icon("arrow-counterclockwise")); - toolbar->addAction(redo_zoom_action = zoom_undo_stack->createRedoAction(this)); - redo_zoom_action->setIcon(utils::icon("arrow-clockwise")); - reset_zoom_action = toolbar->addWidget(reset_zoom_btn = new ToolButton("zoom-out", tr("Reset Zoom"))); - reset_zoom_btn->setToolButtonStyle(Qt::ToolButtonTextBesideIcon); - - toolbar->addWidget(remove_all_btn = new ToolButton("x-square", tr("Remove all charts"))); - toolbar->addWidget(dock_btn = new ToolButton("")); - main_layout->addWidget(toolbar); - - // tabbar - tabbar = new TabBar(this); - tabbar->setAutoHide(true); - tabbar->setExpanding(false); - tabbar->setDrawBase(true); - tabbar->setAcceptDrops(true); - tabbar->setChangeCurrentOnDrag(true); - tabbar->setUsesScrollButtons(true); - main_layout->addWidget(tabbar); - - // charts - charts_container = new ChartsContainer(this); - charts_container->setSizePolicy(QSizePolicy::Preferred, QSizePolicy::Fixed); - charts_scroll = new QScrollArea(this); - charts_scroll->viewport()->setBackgroundRole(QPalette::Base); - charts_scroll->setFrameStyle(QFrame::NoFrame); - charts_scroll->setWidgetResizable(true); - charts_scroll->setWidget(charts_container); - charts_scroll->setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOff); - main_layout->addWidget(charts_scroll); - - // init settings - current_theme = settings.theme; - column_count = std::clamp(settings.chart_column_count, 1, MAX_COLUMN_COUNT); - max_chart_range = std::clamp(settings.chart_range, 1, settings.max_cached_minutes * 60); - display_range = {0, max_chart_range}; - range_slider->setValue(max_chart_range); - updateToolBar(); - - align_timer->setSingleShot(true); - QObject::connect(align_timer, &QTimer::timeout, this, &ChartsWidget::alignCharts); - QObject::connect(auto_scroll_timer, &QTimer::timeout, this, &ChartsWidget::doAutoScroll); - QObject::connect(dbc(), &DBCManager::DBCFileChanged, this, &ChartsWidget::removeAll); - QObject::connect(can, &AbstractStream::eventsMerged, this, &ChartsWidget::eventsMerged); - QObject::connect(can, &AbstractStream::msgsReceived, this, &ChartsWidget::updateState); - QObject::connect(range_slider, &QSlider::valueChanged, this, &ChartsWidget::setMaxChartRange); - QObject::connect(new_plot_btn, &QToolButton::clicked, this, &ChartsWidget::newChart); - QObject::connect(remove_all_btn, &QToolButton::clicked, this, &ChartsWidget::removeAll); - QObject::connect(reset_zoom_btn, &QToolButton::clicked, this, &ChartsWidget::zoomReset); - QObject::connect(&settings, &Settings::changed, this, &ChartsWidget::settingChanged); - QObject::connect(new_tab_btn, &QToolButton::clicked, this, &ChartsWidget::newTab); - QObject::connect(this, &ChartsWidget::seriesChanged, this, &ChartsWidget::updateTabBar); - QObject::connect(tabbar, &QTabBar::tabCloseRequested, this, &ChartsWidget::removeTab); - QObject::connect(tabbar, &QTabBar::currentChanged, [this](int index) { - if (index != -1) updateLayout(true); - }); - QObject::connect(dock_btn, &QToolButton::clicked, [this]() { - emit dock(!docking); - docking = !docking; - updateToolBar(); - }); - - newTab(); - setWhatsThis(tr(R"( - Chart view
- - )")); -} - -void ChartsWidget::newTab() { - static int tab_unique_id = 0; - int idx = tabbar->addTab(""); - tabbar->setTabData(idx, tab_unique_id++); - tabbar->setCurrentIndex(idx); - updateTabBar(); -} - -void ChartsWidget::removeTab(int index) { - int id = tabbar->tabData(index).toInt(); - for (auto &c : tab_charts[id]) { - removeChart(c); - } - tab_charts.erase(id); - tabbar->removeTab(index); - updateTabBar(); -} - -void ChartsWidget::updateTabBar() { - for (int i = 0; i < tabbar->count(); ++i) { - const auto &charts_in_tab = tab_charts[tabbar->tabData(i).toInt()]; - tabbar->setTabText(i, QString("Tab %1 (%2)").arg(i + 1).arg(charts_in_tab.count())); - } -} - -void ChartsWidget::eventsMerged(const MessageEventsMap &new_events) { - QFutureSynchronizer future_synchronizer; - for (auto c : charts) { - future_synchronizer.addFuture(QtConcurrent::run(c, &ChartView::updateSeries, nullptr, &new_events)); - } -} - -void ChartsWidget::setZoom(double min, double max) { - zoomed_range = {min, max}; - is_zoomed = zoomed_range != display_range; - updateToolBar(); - updateState(); - emit rangeChanged(min, max, is_zoomed); -} - -void ChartsWidget::zoomReset() { - setZoom(display_range.first, display_range.second); - zoom_undo_stack->clear(); -} - -QRect ChartsWidget::chartVisibleRect(ChartView *chart) { - const QRect visible_rect(-charts_container->pos(), charts_scroll->viewport()->size()); - return chart->rect().intersected(QRect(chart->mapFrom(charts_container, visible_rect.topLeft()), visible_rect.size())); -} - -void ChartsWidget::showValueTip(double sec) { - for (auto c : currentCharts()) { - sec >= 0 ? c->showTip(sec) : c->hideTip(); - } -} - -void ChartsWidget::updateState() { - if (charts.isEmpty()) return; - - const double cur_sec = can->currentSec(); - if (!is_zoomed) { - double pos = (cur_sec - display_range.first) / std::max(1.0, max_chart_range); - if (pos < 0 || pos > 0.8) { - display_range.first = std::max(0.0, cur_sec - max_chart_range * 0.1); - } - double max_sec = std::min(display_range.first + max_chart_range, can->totalSeconds()); - display_range.first = std::max(0.0, max_sec - max_chart_range); - display_range.second = display_range.first + max_chart_range; - } else if (cur_sec < (zoomed_range.first - 0.1) || cur_sec >= zoomed_range.second) { - // loop in zoomed range - can->seekTo(zoomed_range.first); - } - - const auto &range = is_zoomed ? zoomed_range : display_range; - for (auto c : charts) { - c->updatePlot(cur_sec, range.first, range.second); - } -} - -void ChartsWidget::setMaxChartRange(int value) { - max_chart_range = settings.chart_range = range_slider->value(); - updateToolBar(); - updateState(); -} - -void ChartsWidget::updateToolBar() { - title_label->setText(tr("Charts: %1").arg(charts.size())); - columns_action->setText(tr("Column: %1").arg(column_count)); - range_lb->setText(utils::formatSeconds(max_chart_range)); - range_lb_action->setVisible(!is_zoomed); - range_slider_action->setVisible(!is_zoomed); - undo_zoom_action->setVisible(is_zoomed); - redo_zoom_action->setVisible(is_zoomed); - reset_zoom_action->setVisible(is_zoomed); - reset_zoom_btn->setText(is_zoomed ? tr("%1-%2").arg(zoomed_range.first, 0, 'f', 2).arg(zoomed_range.second, 0, 'f', 2) : ""); - remove_all_btn->setEnabled(!charts.isEmpty()); - dock_btn->setIcon(docking ? "arrow-up-right-square" : "arrow-down-left-square"); - dock_btn->setToolTip(docking ? tr("Undock charts") : tr("Dock charts")); -} - -void ChartsWidget::settingChanged() { - if (std::exchange(current_theme, settings.theme) != current_theme) { - undo_zoom_action->setIcon(utils::icon("arrow-counterclockwise")); - redo_zoom_action->setIcon(utils::icon("arrow-clockwise")); - auto theme = settings.theme == DARK_THEME ? QChart::QChart::ChartThemeDark : QChart::ChartThemeLight; - for (auto c : charts) { - c->setTheme(theme); - } - } - range_slider->setRange(1, settings.max_cached_minutes * 60); - for (auto c : charts) { - c->setFixedHeight(settings.chart_height); - c->setSeriesType((SeriesType)settings.chart_series_type); - c->resetChartCache(); - } -} - -ChartView *ChartsWidget::findChart(const MessageId &id, const cabana::Signal *sig) { - for (auto c : charts) - if (c->hasSignal(id, sig)) return c; - return nullptr; -} - -ChartView *ChartsWidget::createChart() { - auto chart = new ChartView(is_zoomed ? zoomed_range : display_range, this); - chart->setFixedHeight(settings.chart_height); - chart->setMinimumWidth(CHART_MIN_WIDTH); - chart->setSizePolicy(QSizePolicy::MinimumExpanding, QSizePolicy::Fixed); - QObject::connect(chart, &ChartView::axisYLabelWidthChanged, align_timer, qOverload<>(&QTimer::start)); - charts.push_front(chart); - currentCharts().push_front(chart); - updateLayout(true); - updateToolBar(); - return chart; -} - -void ChartsWidget::showChart(const MessageId &id, const cabana::Signal *sig, bool show, bool merge) { - ChartView *chart = findChart(id, sig); - if (show && !chart) { - chart = merge && currentCharts().size() > 0 ? currentCharts().front() : createChart(); - chart->addSignal(id, sig); - updateState(); - } else if (!show && chart) { - chart->removeIf([&](auto &s) { return s.msg_id == id && s.sig == sig; }); - } -} - -void ChartsWidget::splitChart(ChartView *src_chart) { - if (src_chart->sigs.size() > 1) { - for (auto it = src_chart->sigs.begin() + 1; it != src_chart->sigs.end(); /**/) { - auto c = createChart(); - src_chart->chart()->removeSeries(it->series); - - // Restore to the original color - it->series->setColor(it->sig->color); - - c->addSeries(it->series); - c->sigs.emplace_back(std::move(*it)); - c->updateAxisY(); - c->updateTitle(); - it = src_chart->sigs.erase(it); - } - src_chart->updateAxisY(); - src_chart->updateTitle(); - QTimer::singleShot(0, src_chart, &ChartView::resetChartCache); - } -} - -void ChartsWidget::setColumnCount(int n) { - n = std::clamp(n, 1, MAX_COLUMN_COUNT); - if (column_count != n) { - column_count = settings.chart_column_count = n; - updateToolBar(); - updateLayout(); - } -} - -void ChartsWidget::updateLayout(bool force) { - auto charts_layout = charts_container->charts_layout; - int n = MAX_COLUMN_COUNT; - for (; n > 1; --n) { - if ((n * CHART_MIN_WIDTH + (n - 1) * charts_layout->horizontalSpacing()) < charts_layout->geometry().width()) break; - } - - bool show_column_cb = n > 1; - columns_action->setVisible(show_column_cb); - - n = std::min(column_count, n); - auto ¤t_charts = currentCharts(); - if ((current_charts.size() != charts_layout->count() || n != current_column_count) || force) { - current_column_count = n; - charts_container->setUpdatesEnabled(false); - for (auto c : charts) { - c->setVisible(false); - } - for (int i = 0; i < current_charts.size(); ++i) { - charts_layout->addWidget(current_charts[i], i / n, i % n); - if (current_charts[i]->sigs.empty()) { - // the chart will be resized after add signal. delay setVisible to reduce flicker. - QTimer::singleShot(0, current_charts[i], [c = current_charts[i]]() { c->setVisible(true); }); - } else { - current_charts[i]->setVisible(true); - } - } - charts_container->setUpdatesEnabled(true); - } -} - -void ChartsWidget::startAutoScroll() { - auto_scroll_timer->start(50); -} - -void ChartsWidget::stopAutoScroll() { - auto_scroll_timer->stop(); - auto_scroll_count = 0; -} - -void ChartsWidget::doAutoScroll() { - QScrollBar *scroll = charts_scroll->verticalScrollBar(); - if (auto_scroll_count < scroll->pageStep()) { - ++auto_scroll_count; - } - - int value = scroll->value(); - QPoint pos = charts_scroll->viewport()->mapFromGlobal(QCursor::pos()); - QRect area = charts_scroll->viewport()->rect(); - - if (pos.y() - area.top() < settings.chart_height / 2) { - scroll->setValue(value - auto_scroll_count); - } else if (area.bottom() - pos.y() < settings.chart_height / 2) { - scroll->setValue(value + auto_scroll_count); - } - bool vertical_unchanged = value == scroll->value(); - if (vertical_unchanged) { - stopAutoScroll(); - } else { - // mouseMoveEvent to updates the drag-selection rectangle - const QPoint globalPos = charts_scroll->viewport()->mapToGlobal(pos); - const QPoint windowPos = charts_scroll->window()->mapFromGlobal(globalPos); - QMouseEvent mm(QEvent::MouseMove, pos, windowPos, globalPos, - Qt::NoButton, Qt::LeftButton, Qt::NoModifier, Qt::MouseEventSynthesizedByQt); - QApplication::sendEvent(charts_scroll->viewport(), &mm); - } -} - -QSize ChartsWidget::minimumSizeHint() const { - return QSize(CHART_MIN_WIDTH, QWidget::minimumSizeHint().height()); -} - -void ChartsWidget::resizeEvent(QResizeEvent *event) { - QWidget::resizeEvent(event); - updateLayout(); -} - -void ChartsWidget::newChart() { - SignalSelector dlg(tr("New Chart"), this); - if (dlg.exec() == QDialog::Accepted) { - auto items = dlg.seletedItems(); - if (!items.isEmpty()) { - auto c = createChart(); - for (auto it : items) { - c->addSignal(it->msg_id, it->sig); - } - } - } -} - -void ChartsWidget::removeChart(ChartView *chart) { - charts.removeOne(chart); - chart->deleteLater(); - for (auto &[_, list] : tab_charts) { - list.removeOne(chart); - } - updateToolBar(); - updateLayout(true); - alignCharts(); - emit seriesChanged(); -} - -void ChartsWidget::removeAll() { - while (tabbar->count() > 1) { - tabbar->removeTab(1); - } - tab_charts.clear(); - - if (!charts.isEmpty()) { - for (auto c : charts) { - delete c; - } - charts.clear(); - emit seriesChanged(); - } - zoomReset(); -} - -void ChartsWidget::alignCharts() { - int plot_left = 0; - for (auto c : charts) { - plot_left = std::max(plot_left, c->y_label_width); - } - plot_left = std::max((plot_left / 10) * 10 + 10, 50); - for (auto c : charts) { - c->updatePlotArea(plot_left); - } -} - -bool ChartsWidget::eventFilter(QObject *obj, QEvent *event) { - if (obj != this && event->type() == QEvent::Close) { - emit dock_btn->clicked(); - return true; - } - return false; -} - -bool ChartsWidget::event(QEvent *event) { - bool back_button = false; - switch (event->type()) { - case QEvent::MouseButtonPress: { - QMouseEvent *ev = static_cast(event); - back_button = ev->button() == Qt::BackButton; - break; - } - case QEvent::NativeGesture: { - QNativeGestureEvent *ev = static_cast(event); - back_button = (ev->value() == 180); - break; - } - case QEvent::WindowActivate: - case QEvent::WindowDeactivate: - case QEvent::FocusIn: - case QEvent::FocusOut: - case QEvent::Leave: - showValueTip(-1); - break; - default: - break; - } - - if (back_button) { - zoom_undo_stack->undo(); - return true; - } - return QFrame::event(event); -} - -// ChartsContainer - -ChartsContainer::ChartsContainer(ChartsWidget *parent) : charts_widget(parent), QWidget(parent) { - setAcceptDrops(true); - setBackgroundRole(QPalette::Window); - QVBoxLayout *charts_main_layout = new QVBoxLayout(this); - charts_main_layout->setContentsMargins(0, CHART_SPACING, 0, CHART_SPACING); - charts_layout = new QGridLayout(); - charts_layout->setSpacing(CHART_SPACING); - charts_main_layout->addLayout(charts_layout); - charts_main_layout->addStretch(0); -} - -void ChartsContainer::dragEnterEvent(QDragEnterEvent *event) { - if (event->mimeData()->hasFormat(CHART_MIME_TYPE)) { - event->acceptProposedAction(); - drawDropIndicator(event->pos()); - } -} - -void ChartsContainer::dropEvent(QDropEvent *event) { - if (event->mimeData()->hasFormat(CHART_MIME_TYPE)) { - auto w = getDropAfter(event->pos()); - auto chart = qobject_cast(event->source()); - if (w != chart) { - for (auto &[_, list] : charts_widget->tab_charts) { - list.removeOne(chart); - } - int to = w ? charts_widget->currentCharts().indexOf(w) + 1 : 0; - charts_widget->currentCharts().insert(to, chart); - charts_widget->updateLayout(true); - charts_widget->updateTabBar(); - event->acceptProposedAction(); - chart->startAnimation(); - } - drawDropIndicator({}); - } -} - -void ChartsContainer::paintEvent(QPaintEvent *ev) { - if (!drop_indictor_pos.isNull() && !childAt(drop_indictor_pos)) { - QRect r; - if (auto insert_after = getDropAfter(drop_indictor_pos)) { - QRect area = insert_after->geometry(); - r = QRect(area.left(), area.bottom() + 1, area.width(), CHART_SPACING); - } else { - r = geometry(); - r.setHeight(CHART_SPACING); - } - - QPainter p(this); - p.setPen(QPen(palette().highlight(), 2)); - p.drawLine(r.topLeft() + QPoint(1, 0), r.bottomLeft() + QPoint(1, 0)); - p.drawLine(r.topLeft() + QPoint(0, r.height() / 2), r.topRight() + QPoint(0, r.height() / 2)); - p.drawLine(r.topRight(), r.bottomRight()); - } -} - -ChartView *ChartsContainer::getDropAfter(const QPoint &pos) const { - auto it = std::find_if(charts_widget->currentCharts().crbegin(), charts_widget->currentCharts().crend(), [&pos](auto c) { - auto area = c->geometry(); - return pos.x() >= area.left() && pos.x() <= area.right() && pos.y() >= area.bottom(); - }); - return it == charts_widget->currentCharts().crend() ? nullptr : *it; -} diff --git a/tools/cabana/chart/chartswidget.h b/tools/cabana/chart/chartswidget.h deleted file mode 100644 index a39b4d7..0000000 --- a/tools/cabana/chart/chartswidget.h +++ /dev/null @@ -1,130 +0,0 @@ -#pragma once - -#include -#include - -#include -#include -#include -#include -#include -#include - -#include "tools/cabana/chart/signalselector.h" -#include "tools/cabana/dbc/dbcmanager.h" -#include "tools/cabana/streams/abstractstream.h" - -const int CHART_MIN_WIDTH = 300; -const QString CHART_MIME_TYPE = "application/x-cabanachartview"; - -class ChartView; -class ChartsWidget; - -class ChartsContainer : public QWidget { -public: - ChartsContainer(ChartsWidget *parent); - void dragEnterEvent(QDragEnterEvent *event) override; - void dropEvent(QDropEvent *event) override; - void dragLeaveEvent(QDragLeaveEvent *event) override { drawDropIndicator({}); } - void drawDropIndicator(const QPoint &pt) { drop_indictor_pos = pt; update(); } - void paintEvent(QPaintEvent *ev) override; - ChartView *getDropAfter(const QPoint &pos) const; - - QGridLayout *charts_layout; - ChartsWidget *charts_widget; - QPoint drop_indictor_pos; -}; - -class ChartsWidget : public QFrame { - Q_OBJECT - -public: - ChartsWidget(QWidget *parent = nullptr); - void showChart(const MessageId &id, const cabana::Signal *sig, bool show, bool merge); - inline bool hasSignal(const MessageId &id, const cabana::Signal *sig) { return findChart(id, sig) != nullptr; } - -public slots: - void setColumnCount(int n); - void removeAll(); - void setZoom(double min, double max); - -signals: - void dock(bool floating); - void rangeChanged(double min, double max, bool is_zommed); - void seriesChanged(); - -private: - QSize minimumSizeHint() const override; - void resizeEvent(QResizeEvent *event) override; - bool event(QEvent *event) override; - void alignCharts(); - void newChart(); - ChartView *createChart(); - void removeChart(ChartView *chart); - void splitChart(ChartView *chart); - QRect chartVisibleRect(ChartView *chart); - void eventsMerged(const MessageEventsMap &new_events); - void updateState(); - void zoomReset(); - void startAutoScroll(); - void stopAutoScroll(); - void doAutoScroll(); - void updateToolBar(); - void updateTabBar(); - void setMaxChartRange(int value); - void updateLayout(bool force = false); - void settingChanged(); - void showValueTip(double sec); - bool eventFilter(QObject *obj, QEvent *event) override; - void newTab(); - void removeTab(int index); - inline QList ¤tCharts() { return tab_charts[tabbar->tabData(tabbar->currentIndex()).toInt()]; } - ChartView *findChart(const MessageId &id, const cabana::Signal *sig); - - QLabel *title_label; - QLabel *range_lb; - LogSlider *range_slider; - QAction *range_lb_action; - QAction *range_slider_action; - bool docking = true; - ToolButton *dock_btn; - - QAction *undo_zoom_action; - QAction *redo_zoom_action; - QAction *reset_zoom_action; - ToolButton *reset_zoom_btn; - QUndoStack *zoom_undo_stack; - - ToolButton *remove_all_btn; - QList charts; - std::unordered_map> tab_charts; - TabBar *tabbar; - ChartsContainer *charts_container; - QScrollArea *charts_scroll; - uint32_t max_chart_range = 0; - bool is_zoomed = false; - std::pair display_range; - std::pair zoomed_range; - QAction *columns_action; - int column_count = 1; - int current_column_count = 0; - int auto_scroll_count = 0; - QTimer *auto_scroll_timer; - QTimer *align_timer; - int current_theme = 0; - friend class ZoomCommand; - friend class ChartView; - friend class ChartsContainer; -}; - -class ZoomCommand : public QUndoCommand { -public: - ZoomCommand(ChartsWidget *charts, std::pair range) : charts(charts), range(range), QUndoCommand() { - prev_range = charts->is_zoomed ? charts->zoomed_range : charts->display_range; - setText(QObject::tr("Zoom to %1-%2").arg(range.first, 0, 'f', 2).arg(range.second, 0, 'f', 2)); - } - void undo() override { charts->setZoom(prev_range.first, prev_range.second); } - void redo() override { charts->setZoom(range.first, range.second); } - ChartsWidget *charts; - std::pair prev_range, range; -}; diff --git a/tools/cabana/chart/signalselector.cc b/tools/cabana/chart/signalselector.cc deleted file mode 100644 index 0ddb212..0000000 --- a/tools/cabana/chart/signalselector.cc +++ /dev/null @@ -1,108 +0,0 @@ -#include "tools/cabana/chart/signalselector.h" - -#include -#include -#include -#include -#include -#include -#include - -#include "tools/cabana/streams/abstractstream.h" - -SignalSelector::SignalSelector(QString title, QWidget *parent) : QDialog(parent) { - setWindowTitle(title); - QGridLayout *main_layout = new QGridLayout(this); - - // left column - main_layout->addWidget(new QLabel(tr("Available Signals")), 0, 0); - main_layout->addWidget(msgs_combo = new QComboBox(this), 1, 0); - msgs_combo->setEditable(true); - msgs_combo->lineEdit()->setPlaceholderText(tr("Select a msg...")); - msgs_combo->setInsertPolicy(QComboBox::NoInsert); - msgs_combo->completer()->setCompletionMode(QCompleter::PopupCompletion); - msgs_combo->completer()->setFilterMode(Qt::MatchContains); - - main_layout->addWidget(available_list = new QListWidget(this), 2, 0); - - // buttons - QVBoxLayout *btn_layout = new QVBoxLayout(); - QPushButton *add_btn = new QPushButton(utils::icon("chevron-right"), "", this); - add_btn->setEnabled(false); - QPushButton *remove_btn = new QPushButton(utils::icon("chevron-left"), "", this); - remove_btn->setEnabled(false); - btn_layout->addStretch(0); - btn_layout->addWidget(add_btn); - btn_layout->addWidget(remove_btn); - btn_layout->addStretch(0); - main_layout->addLayout(btn_layout, 0, 1, 3, 1); - - // right column - main_layout->addWidget(new QLabel(tr("Selected Signals")), 0, 2); - main_layout->addWidget(selected_list = new QListWidget(this), 1, 2, 2, 1); - - auto buttonBox = new QDialogButtonBox(QDialogButtonBox::Ok | QDialogButtonBox::Cancel); - main_layout->addWidget(buttonBox, 3, 2); - - for (const auto &[id, _] : can->lastMessages()) { - if (auto m = dbc()->msg(id)) { - msgs_combo->addItem(QString("%1 (%2)").arg(m->name).arg(id.toString()), QVariant::fromValue(id)); - } - } - msgs_combo->model()->sort(0); - msgs_combo->setCurrentIndex(-1); - - QObject::connect(msgs_combo, qOverload(&QComboBox::currentIndexChanged), this, &SignalSelector::updateAvailableList); - QObject::connect(available_list, &QListWidget::currentRowChanged, [=](int row) { add_btn->setEnabled(row != -1); }); - QObject::connect(selected_list, &QListWidget::currentRowChanged, [=](int row) { remove_btn->setEnabled(row != -1); }); - QObject::connect(available_list, &QListWidget::itemDoubleClicked, this, &SignalSelector::add); - QObject::connect(selected_list, &QListWidget::itemDoubleClicked, this, &SignalSelector::remove); - QObject::connect(add_btn, &QPushButton::clicked, [this]() { if (auto item = available_list->currentItem()) add(item); }); - QObject::connect(remove_btn, &QPushButton::clicked, [this]() { if (auto item = selected_list->currentItem()) remove(item); }); - QObject::connect(buttonBox, &QDialogButtonBox::accepted, this, &QDialog::accept); - QObject::connect(buttonBox, &QDialogButtonBox::rejected, this, &QDialog::reject); -} - -void SignalSelector::add(QListWidgetItem *item) { - auto it = (ListItem *)item; - addItemToList(selected_list, it->msg_id, it->sig, true); - delete item; -} - -void SignalSelector::remove(QListWidgetItem *item) { - auto it = (ListItem *)item; - if (it->msg_id == msgs_combo->currentData().value()) { - addItemToList(available_list, it->msg_id, it->sig); - } - delete item; -} - -void SignalSelector::updateAvailableList(int index) { - if (index == -1) return; - available_list->clear(); - MessageId msg_id = msgs_combo->itemData(index).value(); - auto selected_items = seletedItems(); - for (auto s : dbc()->msg(msg_id)->getSignals()) { - bool is_selected = std::any_of(selected_items.begin(), selected_items.end(), [=, sig = s](auto it) { return it->msg_id == msg_id && it->sig == sig; }); - if (!is_selected) { - addItemToList(available_list, msg_id, s); - } - } -} - -void SignalSelector::addItemToList(QListWidget *parent, const MessageId id, const cabana::Signal *sig, bool show_msg_name) { - QString text = QString(" %1").arg(sig->color.name(), sig->name); - if (show_msg_name) text += QString(" %0 %1").arg(msgName(id), id.toString()); - - QLabel *label = new QLabel(text); - label->setContentsMargins(5, 0, 5, 0); - auto new_item = new ListItem(id, sig, parent); - new_item->setSizeHint(label->sizeHint()); - parent->setItemWidget(new_item, label); -} - -QList SignalSelector::seletedItems() { - QList ret; - for (int i = 0; i < selected_list->count(); ++i) ret.push_back((ListItem *)selected_list->item(i)); - return ret; -} diff --git a/tools/cabana/chart/signalselector.h b/tools/cabana/chart/signalselector.h deleted file mode 100644 index f46779f..0000000 --- a/tools/cabana/chart/signalselector.h +++ /dev/null @@ -1,30 +0,0 @@ -#pragma once - -#include -#include -#include - -#include "tools/cabana/dbc/dbcmanager.h" - -class SignalSelector : public QDialog { -public: - struct ListItem : public QListWidgetItem { - ListItem(const MessageId &msg_id, const cabana::Signal *sig, QListWidget *parent) : msg_id(msg_id), sig(sig), QListWidgetItem(parent) {} - MessageId msg_id; - const cabana::Signal *sig; - }; - - SignalSelector(QString title, QWidget *parent); - QList seletedItems(); - inline void addSelected(const MessageId &id, const cabana::Signal *sig) { addItemToList(selected_list, id, sig, true); } - -private: - void updateAvailableList(int index); - void addItemToList(QListWidget *parent, const MessageId id, const cabana::Signal *sig, bool show_msg_name = false); - void add(QListWidgetItem *item); - void remove(QListWidgetItem *item); - - QComboBox *msgs_combo; - QListWidget *available_list; - QListWidget *selected_list; -}; diff --git a/tools/cabana/chart/sparkline.cc b/tools/cabana/chart/sparkline.cc deleted file mode 100644 index 42608c0..0000000 --- a/tools/cabana/chart/sparkline.cc +++ /dev/null @@ -1,59 +0,0 @@ -#include "tools/cabana/chart/sparkline.h" - -#include -#include -#include - -#include "tools/cabana/streams/abstractstream.h" - -void Sparkline::update(const MessageId &msg_id, const cabana::Signal *sig, double last_msg_ts, int range, QSize size) { - const auto &msgs = can->events(msg_id); - uint64_t ts = (last_msg_ts + can->routeStartTime()) * 1e9; - uint64_t first_ts = (ts > range * 1e9) ? ts - range * 1e9 : 0; - auto first = std::lower_bound(msgs.cbegin(), msgs.cend(), first_ts, CompareCanEvent()); - auto last = std::upper_bound(first, msgs.cend(), ts, CompareCanEvent()); - - if (first != last && !size.isEmpty()) { - points.clear(); - double value = 0; - for (auto it = first; it != last; ++it) { - if (sig->getValue((*it)->dat, (*it)->size, &value)) { - points.emplace_back(((*it)->mono_time - (*first)->mono_time) / 1e9, value); - } - } - const auto [min, max] = std::minmax_element(points.begin(), points.end(), - [](auto &l, auto &r) { return l.y() < r.y(); }); - min_val = min->y() == max->y() ? min->y() - 1 : min->y(); - max_val = min->y() == max->y() ? max->y() + 1 : max->y(); - freq_ = points.size() / std::max(points.back().x() - points.front().x(), 1.0); - render(sig->color, range, size); - } else { - pixmap = QPixmap(); - } -} - -void Sparkline::render(const QColor &color, int range, QSize size) { - const double xscale = (size.width() - 1) / (double)range; - const double yscale = (size.height() - 3) / (max_val - min_val); - for (auto &v : points) { - v = QPoint(v.x() * xscale, 1 + std::abs(v.y() - max_val) * yscale); - } - - qreal dpr = qApp->devicePixelRatio(); - size *= dpr; - if (size != pixmap.size()) { - pixmap = QPixmap(size); - } - pixmap.setDevicePixelRatio(dpr); - pixmap.fill(Qt::transparent); - QPainter painter(&pixmap); - painter.setRenderHint(QPainter::Antialiasing, points.size() < 500); - painter.setPen(color); - painter.drawPolyline(points.data(), points.size()); - painter.setPen(QPen(color, 3)); - if ((points.back().x() - points.front().x()) / points.size() > 8) { - painter.drawPoints(points.data(), points.size()); - } else { - painter.drawPoint(points.back()); - } -} diff --git a/tools/cabana/chart/sparkline.h b/tools/cabana/chart/sparkline.h deleted file mode 100644 index 3bdd8a3..0000000 --- a/tools/cabana/chart/sparkline.h +++ /dev/null @@ -1,24 +0,0 @@ -#pragma once - -#include -#include -#include - -#include "tools/cabana/dbc/dbc.h" - -class Sparkline { -public: - void update(const MessageId &msg_id, const cabana::Signal *sig, double last_msg_ts, int range, QSize size); - inline double freq() const { return freq_; } - bool isEmpty() const { return pixmap.isNull(); } - - QPixmap pixmap; - double min_val = 0; - double max_val = 0; - -private: - void render(const QColor &color, int range, QSize size); - - std::vector points; - double freq_ = 0; -}; diff --git a/tools/cabana/chart/tiplabel.cc b/tools/cabana/chart/tiplabel.cc deleted file mode 100644 index f5c9cc9..0000000 --- a/tools/cabana/chart/tiplabel.cc +++ /dev/null @@ -1,55 +0,0 @@ -#include "tools/cabana/chart/tiplabel.h" - -#include - -#include -#include -#include - -#include "tools/cabana/settings.h" - -TipLabel::TipLabel(QWidget *parent) : QLabel(parent, Qt::ToolTip | Qt::FramelessWindowHint) { - setForegroundRole(QPalette::ToolTipText); - setBackgroundRole(QPalette::ToolTipBase); - QFont font; - font.setPointSizeF(8.34563465); - setFont(font); - auto palette = QToolTip::palette(); - if (settings.theme != DARK_THEME) { - palette.setColor(QPalette::ToolTipBase, QApplication::palette().color(QPalette::Base)); - palette.setColor(QPalette::ToolTipText, QRgb(0x404044)); // same color as chart label brush - } - setPalette(palette); - ensurePolished(); - setMargin(1 + style()->pixelMetric(QStyle::PM_ToolTipLabelFrameWidth, nullptr, this)); - setAttribute(Qt::WA_ShowWithoutActivating); - setTextFormat(Qt::RichText); - setVisible(false); -} - -void TipLabel::showText(const QPoint &pt, const QString &text, QWidget *w, const QRect &rect) { - setText(text); - if (!text.isEmpty()) { - QSize extra(1, 1); - resize(sizeHint() + extra); - QPoint tip_pos(pt.x() + 8, rect.top() + 2); - if (tip_pos.x() + size().width() >= rect.right()) { - tip_pos.rx() = pt.x() - size().width() - 8; - } - if (rect.contains({tip_pos, size()})) { - move(w->mapToGlobal(tip_pos)); - setVisible(true); - return; - } - } - setVisible(false); -} - -void TipLabel::paintEvent(QPaintEvent *ev) { - QStylePainter p(this); - QStyleOptionFrame opt; - opt.init(this); - p.drawPrimitive(QStyle::PE_PanelTipLabel, opt); - p.end(); - QLabel::paintEvent(ev); -} diff --git a/tools/cabana/chart/tiplabel.h b/tools/cabana/chart/tiplabel.h deleted file mode 100644 index ac6e09e..0000000 --- a/tools/cabana/chart/tiplabel.h +++ /dev/null @@ -1,10 +0,0 @@ -#pragma once - -#include - -class TipLabel : public QLabel { -public: - TipLabel(QWidget *parent = nullptr); - void showText(const QPoint &pt, const QString &sec, QWidget *w, const QRect &rect); - void paintEvent(QPaintEvent *ev) override; -}; diff --git a/tools/cabana/commands.cc b/tools/cabana/commands.cc deleted file mode 100644 index 5286172..0000000 --- a/tools/cabana/commands.cc +++ /dev/null @@ -1,124 +0,0 @@ -#include - -#include "tools/cabana/commands.h" - -// EditMsgCommand - -EditMsgCommand::EditMsgCommand(const MessageId &id, const QString &name, int size, - const QString &node, const QString &comment, QUndoCommand *parent) - : id(id), new_name(name), new_size(size), new_node(node), new_comment(comment), QUndoCommand(parent) { - if (auto msg = dbc()->msg(id)) { - old_name = msg->name; - old_size = msg->size; - old_node = msg->transmitter; - old_comment = msg->comment; - setText(QObject::tr("edit message %1:%2").arg(name).arg(id.address)); - } else { - setText(QObject::tr("new message %1:%2").arg(name).arg(id.address)); - } -} - -void EditMsgCommand::undo() { - if (old_name.isEmpty()) - dbc()->removeMsg(id); - else - dbc()->updateMsg(id, old_name, old_size, old_node, old_comment); -} - -void EditMsgCommand::redo() { - dbc()->updateMsg(id, new_name, new_size, new_node, new_comment); -} - -// RemoveMsgCommand - -RemoveMsgCommand::RemoveMsgCommand(const MessageId &id, QUndoCommand *parent) : id(id), QUndoCommand(parent) { - if (auto msg = dbc()->msg(id)) { - message = *msg; - setText(QObject::tr("remove message %1:%2").arg(message.name).arg(id.address)); - } -} - -void RemoveMsgCommand::undo() { - if (!message.name.isEmpty()) { - dbc()->updateMsg(id, message.name, message.size, message.transmitter, message.comment); - for (auto s : message.getSignals()) - dbc()->addSignal(id, *s); - } -} - -void RemoveMsgCommand::redo() { - if (!message.name.isEmpty()) - dbc()->removeMsg(id); -} - -// AddSigCommand - -AddSigCommand::AddSigCommand(const MessageId &id, const cabana::Signal &sig, QUndoCommand *parent) - : id(id), signal(sig), QUndoCommand(parent) { - setText(QObject::tr("add signal %1 to %2:%3").arg(sig.name).arg(msgName(id)).arg(id.address)); -} - -void AddSigCommand::undo() { - dbc()->removeSignal(id, signal.name); - if (msg_created) dbc()->removeMsg(id); -} - -void AddSigCommand::redo() { - if (auto msg = dbc()->msg(id); !msg) { - msg_created = true; - dbc()->updateMsg(id, dbc()->newMsgName(id), can->lastMessage(id).dat.size(), "", ""); - } - signal.name = dbc()->newSignalName(id); - signal.max = std::pow(2, signal.size) - 1; - dbc()->addSignal(id, signal); -} - -// RemoveSigCommand - -RemoveSigCommand::RemoveSigCommand(const MessageId &id, const cabana::Signal *sig, QUndoCommand *parent) - : id(id), QUndoCommand(parent) { - sigs.push_back(*sig); - if (sig->type == cabana::Signal::Type::Multiplexor) { - for (const auto &s : dbc()->msg(id)->sigs) { - if (s->type == cabana::Signal::Type::Multiplexed) { - sigs.push_back(*s); - } - } - } - setText(QObject::tr("remove signal %1 from %2:%3").arg(sig->name).arg(msgName(id)).arg(id.address)); -} - -void RemoveSigCommand::undo() { for (const auto &s : sigs) dbc()->addSignal(id, s); } -void RemoveSigCommand::redo() { for (const auto &s : sigs) dbc()->removeSignal(id, s.name); } - -// EditSignalCommand - -EditSignalCommand::EditSignalCommand(const MessageId &id, const cabana::Signal *sig, const cabana::Signal &new_sig, QUndoCommand *parent) - : id(id), QUndoCommand(parent) { - sigs.push_back({*sig, new_sig}); - if (sig->type == cabana::Signal::Type::Multiplexor && new_sig.type == cabana::Signal::Type::Normal) { - // convert all multiplexed signals to normal signals - auto msg = dbc()->msg(id); - assert(msg); - for (const auto &s : msg->sigs) { - if (s->type == cabana::Signal::Type::Multiplexed) { - auto new_s = *s; - new_s.type = cabana::Signal::Type::Normal; - sigs.push_back({*s, new_s}); - } - } - } - setText(QObject::tr("edit signal %1 in %2:%3").arg(sig->name).arg(msgName(id)).arg(id.address)); -} - -void EditSignalCommand::undo() { for (const auto &s : sigs) dbc()->updateSignal(id, s.second.name, s.first); } -void EditSignalCommand::redo() { for (const auto &s : sigs) dbc()->updateSignal(id, s.first.name, s.second); } - -namespace UndoStack { - -QUndoStack *instance() { - static QUndoStack *undo_stack = new QUndoStack(qApp); - return undo_stack; -} - -} // namespace UndoStack diff --git a/tools/cabana/commands.h b/tools/cabana/commands.h deleted file mode 100644 index 0736d9b..0000000 --- a/tools/cabana/commands.h +++ /dev/null @@ -1,72 +0,0 @@ -#pragma once - -#include - -#include -#include - -#include "tools/cabana/dbc/dbcmanager.h" -#include "tools/cabana/streams/abstractstream.h" - -class EditMsgCommand : public QUndoCommand { -public: - EditMsgCommand(const MessageId &id, const QString &name, int size, const QString &node, - const QString &comment, QUndoCommand *parent = nullptr); - void undo() override; - void redo() override; - -private: - const MessageId id; - QString old_name, new_name, old_comment, new_comment, old_node, new_node; - int old_size = 0, new_size = 0; -}; - -class RemoveMsgCommand : public QUndoCommand { -public: - RemoveMsgCommand(const MessageId &id, QUndoCommand *parent = nullptr); - void undo() override; - void redo() override; - -private: - const MessageId id; - cabana::Msg message; -}; - -class AddSigCommand : public QUndoCommand { -public: - AddSigCommand(const MessageId &id, const cabana::Signal &sig, QUndoCommand *parent = nullptr); - void undo() override; - void redo() override; - -private: - const MessageId id; - bool msg_created = false; - cabana::Signal signal = {}; -}; - -class RemoveSigCommand : public QUndoCommand { -public: - RemoveSigCommand(const MessageId &id, const cabana::Signal *sig, QUndoCommand *parent = nullptr); - void undo() override; - void redo() override; - -private: - const MessageId id; - QList sigs; -}; - -class EditSignalCommand : public QUndoCommand { -public: - EditSignalCommand(const MessageId &id, const cabana::Signal *sig, const cabana::Signal &new_sig, QUndoCommand *parent = nullptr); - void undo() override; - void redo() override; - -private: - const MessageId id; - QList> sigs; // QList<{old_sig, new_sig}> -}; - -namespace UndoStack { - QUndoStack *instance(); - inline void push(QUndoCommand *cmd) { instance()->push(cmd); } -}; diff --git a/tools/cabana/dbc/dbc.cc b/tools/cabana/dbc/dbc.cc deleted file mode 100644 index a0e523d..0000000 --- a/tools/cabana/dbc/dbc.cc +++ /dev/null @@ -1,211 +0,0 @@ -#include "tools/cabana/dbc/dbc.h" - -#include - -#include "tools/cabana/util.h" - -uint qHash(const MessageId &item) { - return qHash(item.source) ^ qHash(item.address); -} - -// cabana::Msg - -cabana::Msg::~Msg() { - for (auto s : sigs) { - delete s; - } -} - -cabana::Signal *cabana::Msg::addSignal(const cabana::Signal &sig) { - auto s = sigs.emplace_back(new cabana::Signal(sig)); - update(); - return s; -} - -cabana::Signal *cabana::Msg::updateSignal(const QString &sig_name, const cabana::Signal &new_sig) { - auto s = sig(sig_name); - if (s) { - *s = new_sig; - update(); - } - return s; -} - -void cabana::Msg::removeSignal(const QString &sig_name) { - auto it = std::find_if(sigs.begin(), sigs.end(), [&](auto &s) { return s->name == sig_name; }); - if (it != sigs.end()) { - delete *it; - sigs.erase(it); - update(); - } -} - -cabana::Msg &cabana::Msg::operator=(const cabana::Msg &other) { - address = other.address; - name = other.name; - size = other.size; - comment = other.comment; - - for (auto s : sigs) delete s; - sigs.clear(); - for (auto s : other.sigs) { - sigs.push_back(new cabana::Signal(*s)); - } - - update(); - return *this; -} - -cabana::Signal *cabana::Msg::sig(const QString &sig_name) const { - auto it = std::find_if(sigs.begin(), sigs.end(), [&](auto &s) { return s->name == sig_name; }); - return it != sigs.end() ? *it : nullptr; -} - -int cabana::Msg::indexOf(const cabana::Signal *sig) const { - for (int i = 0; i < sigs.size(); ++i) { - if (sigs[i] == sig) return i; - } - return -1; -} - -QString cabana::Msg::newSignalName() { - QString new_name; - for (int i = 1; /**/; ++i) { - new_name = QString("NEW_SIGNAL_%1").arg(i); - if (sig(new_name) == nullptr) break; - } - return new_name; -} - -void cabana::Msg::update() { - if (transmitter.isEmpty()) { - transmitter = DEFAULT_NODE_NAME; - } - mask.assign(size, 0x00); - multiplexor = nullptr; - - // sort signals - std::sort(sigs.begin(), sigs.end(), [](auto l, auto r) { - return std::tie(r->type, l->multiplex_value, l->start_bit, l->name) < - std::tie(l->type, r->multiplex_value, r->start_bit, r->name); - }); - - for (auto sig : sigs) { - if (sig->type == cabana::Signal::Type::Multiplexor) { - multiplexor = sig; - } - sig->update(); - - // update mask - int i = sig->msb / 8; - int bits = sig->size; - while (i >= 0 && i < size && bits > 0) { - int lsb = (int)(sig->lsb / 8) == i ? sig->lsb : i * 8; - int msb = (int)(sig->msb / 8) == i ? sig->msb : (i + 1) * 8 - 1; - - int sz = msb - lsb + 1; - int shift = (lsb - (i * 8)); - - mask[i] |= ((1ULL << sz) - 1) << shift; - - bits -= size; - i = sig->is_little_endian ? i - 1 : i + 1; - } - } - - for (auto sig : sigs) { - sig->multiplexor = sig->type == cabana::Signal::Type::Multiplexed ? multiplexor : nullptr; - if (!sig->multiplexor) { - if (sig->type == cabana::Signal::Type::Multiplexed) { - sig->type = cabana::Signal::Type::Normal; - } - sig->multiplex_value = 0; - } - } -} - -// cabana::Signal - -void cabana::Signal::update() { - updateMsbLsb(*this); - if (receiver_name.isEmpty()) { - receiver_name = DEFAULT_NODE_NAME; - } - - float h = 19 * (float)lsb / 64.0; - h = fmod(h, 1.0); - size_t hash = qHash(name); - float s = 0.25 + 0.25 * (float)(hash & 0xff) / 255.0; - float v = 0.75 + 0.25 * (float)((hash >> 8) & 0xff) / 255.0; - - color = QColor::fromHsvF(h, s, v); - precision = std::max(num_decimals(factor), num_decimals(offset)); -} - -QString cabana::Signal::formatValue(double value) const { - // Show enum string - int64_t raw_value = round((value - offset) / factor); - for (const auto &[val, desc] : val_desc) { - if (std::abs(raw_value - val) < 1e-6) { - return desc; - } - } - - QString val_str = QString::number(value, 'f', precision); - if (!unit.isEmpty()) { - val_str += " " + unit; - } - return val_str; -} - -bool cabana::Signal::getValue(const uint8_t *data, size_t data_size, double *val) const { - if (multiplexor && get_raw_value(data, data_size, *multiplexor) != multiplex_value) { - return false; - } - *val = get_raw_value(data, data_size, *this); - return true; -} - -bool cabana::Signal::operator==(const cabana::Signal &other) const { - return name == other.name && size == other.size && - start_bit == other.start_bit && - msb == other.msb && lsb == other.lsb && - is_signed == other.is_signed && is_little_endian == other.is_little_endian && - factor == other.factor && offset == other.offset && - min == other.min && max == other.max && comment == other.comment && unit == other.unit && val_desc == other.val_desc && - multiplex_value == other.multiplex_value && type == other.type && receiver_name == other.receiver_name; -} - -// helper functions - -double get_raw_value(const uint8_t *data, size_t data_size, const cabana::Signal &sig) { - int64_t val = 0; - - int i = sig.msb / 8; - int bits = sig.size; - while (i >= 0 && i < data_size && bits > 0) { - int lsb = (int)(sig.lsb / 8) == i ? sig.lsb : i * 8; - int msb = (int)(sig.msb / 8) == i ? sig.msb : (i + 1) * 8 - 1; - int size = msb - lsb + 1; - - uint64_t d = (data[i] >> (lsb - (i * 8))) & ((1ULL << size) - 1); - val |= d << (bits - size); - - bits -= size; - i = sig.is_little_endian ? i - 1 : i + 1; - } - if (sig.is_signed) { - val -= ((val >> (sig.size - 1)) & 0x1) ? (1ULL << sig.size) : 0; - } - return val * sig.factor + sig.offset; -} - -void updateMsbLsb(cabana::Signal &s) { - if (s.is_little_endian) { - s.lsb = s.start_bit; - s.msb = s.start_bit + s.size - 1; - } else { - s.lsb = flipBitPos(flipBitPos(s.start_bit) + s.size - 1); - s.msb = s.start_bit; - } -} diff --git a/tools/cabana/dbc/dbc.h b/tools/cabana/dbc/dbc.h deleted file mode 100644 index e07903e..0000000 --- a/tools/cabana/dbc/dbc.h +++ /dev/null @@ -1,122 +0,0 @@ -#pragma once - -#include -#include -#include -#include - -#include -#include -#include -#include - - -const QString UNTITLED = "untitled"; -const QString DEFAULT_NODE_NAME = "XXX"; - -struct MessageId { - uint8_t source = 0; - uint32_t address = 0; - - QString toString() const { - return QString("%1:%2").arg(source).arg(address, 1, 16); - } - - bool operator==(const MessageId &other) const { - return source == other.source && address == other.address; - } - - bool operator!=(const MessageId &other) const { - return !(*this == other); - } - - bool operator<(const MessageId &other) const { - return std::pair{source, address} < std::pair{other.source, other.address}; - } - - bool operator>(const MessageId &other) const { - return std::pair{source, address} > std::pair{other.source, other.address}; - } -}; - -uint qHash(const MessageId &item); -Q_DECLARE_METATYPE(MessageId); - -template <> -struct std::hash { - std::size_t operator()(const MessageId &k) const noexcept { return qHash(k); } -}; - -typedef QList> ValueDescription; - -namespace cabana { - -class Signal { -public: - Signal() = default; - Signal(const Signal &other) = default; - void update(); - bool getValue(const uint8_t *data, size_t data_size, double *val) const; - QString formatValue(double value) const; - bool operator==(const cabana::Signal &other) const; - inline bool operator!=(const cabana::Signal &other) const { return !(*this == other); } - - enum class Type { - Normal = 0, - Multiplexed, - Multiplexor - }; - - Type type = Type::Normal; - QString name; - int start_bit, msb, lsb, size; - double factor = 1.0; - double offset = 0; - bool is_signed; - bool is_little_endian; - double min, max; - QString unit; - QString comment; - QString receiver_name; - ValueDescription val_desc; - int precision = 0; - QColor color; - - // Multiplexed - int multiplex_value = 0; - Signal *multiplexor = nullptr; -}; - -class Msg { -public: - Msg() = default; - Msg(const Msg &other) { *this = other; } - ~Msg(); - cabana::Signal *addSignal(const cabana::Signal &sig); - cabana::Signal *updateSignal(const QString &sig_name, const cabana::Signal &sig); - void removeSignal(const QString &sig_name); - Msg &operator=(const Msg &other); - int indexOf(const cabana::Signal *sig) const; - cabana::Signal *sig(const QString &sig_name) const; - QString newSignalName(); - void update(); - inline const std::vector &getSignals() const { return sigs; } - - uint32_t address; - QString name; - uint32_t size; - QString comment; - QString transmitter; - std::vector sigs; - - std::vector mask; - cabana::Signal *multiplexor = nullptr; -}; - -} // namespace cabana - -// Helper functions -double get_raw_value(const uint8_t *data, size_t data_size, const cabana::Signal &sig); -void updateMsbLsb(cabana::Signal &s); -inline int flipBitPos(int start_bit) { return 8 * (start_bit / 8) + 7 - start_bit % 8; } -inline QString doubleToString(double value) { return QString::number(value, 'g', std::numeric_limits::digits10); } diff --git a/tools/cabana/dbc/dbcfile.cc b/tools/cabana/dbc/dbcfile.cc deleted file mode 100644 index a22d979..0000000 --- a/tools/cabana/dbc/dbcfile.cc +++ /dev/null @@ -1,240 +0,0 @@ -#include "tools/cabana/dbc/dbcfile.h" - -#include -#include -#include -#include - -DBCFile::DBCFile(const QString &dbc_file_name) { - QFile file(dbc_file_name); - if (file.open(QIODevice::ReadOnly)) { - name_ = QFileInfo(dbc_file_name).baseName(); - filename = dbc_file_name; - // Remove auto save file extension - if (dbc_file_name.endsWith(AUTO_SAVE_EXTENSION)) { - filename.chop(AUTO_SAVE_EXTENSION.length()); - } - parse(file.readAll()); - } else { - throw std::runtime_error("Failed to open file."); - } -} - -DBCFile::DBCFile(const QString &name, const QString &content) : name_(name), filename("") { - // Open from clipboard - parse(content); -} - -bool DBCFile::save() { - assert(!filename.isEmpty()); - if (writeContents(filename)) { - cleanupAutoSaveFile(); - return true; - } - return false; -} - -bool DBCFile::saveAs(const QString &new_filename) { - filename = new_filename; - return save(); -} - -bool DBCFile::autoSave() { - return !filename.isEmpty() && writeContents(filename + AUTO_SAVE_EXTENSION); -} - -void DBCFile::cleanupAutoSaveFile() { - if (!filename.isEmpty()) { - QFile::remove(filename + AUTO_SAVE_EXTENSION); - } -} - -bool DBCFile::writeContents(const QString &fn) { - QFile file(fn); - if (file.open(QIODevice::WriteOnly)) { - file.write(generateDBC().toUtf8()); - return true; - } - return false; -} - -void DBCFile::updateMsg(const MessageId &id, const QString &name, uint32_t size, const QString &node, const QString &comment) { - auto &m = msgs[id.address]; - m.address = id.address; - m.name = name; - m.size = size; - m.transmitter = node.isEmpty() ? DEFAULT_NODE_NAME : node; - m.comment = comment; -} - -cabana::Msg *DBCFile::msg(uint32_t address) { - auto it = msgs.find(address); - return it != msgs.end() ? &it->second : nullptr; -} - -cabana::Msg *DBCFile::msg(const QString &name) { - auto it = std::find_if(msgs.begin(), msgs.end(), [&name](auto &m) { return m.second.name == name; }); - return it != msgs.end() ? &(it->second) : nullptr; -} - -int DBCFile::signalCount() { - return std::accumulate(msgs.cbegin(), msgs.cend(), 0, [](int &n, const auto &m) { return n + m.second.sigs.size(); }); -} - -void DBCFile::parse(const QString &content) { - static QRegularExpression bo_regexp(R"(^BO_ (\w+) (\w+) *: (\w+) (\w+))"); - static QRegularExpression sg_regexp(R"(^SG_ (\w+) : (\d+)\|(\d+)@(\d+)([\+|\-]) \(([0-9.+\-eE]+),([0-9.+\-eE]+)\) \[([0-9.+\-eE]+)\|([0-9.+\-eE]+)\] \"(.*)\" (.*))"); - static QRegularExpression sgm_regexp(R"(^SG_ (\w+) (\w+) *: (\d+)\|(\d+)@(\d+)([\+|\-]) \(([0-9.+\-eE]+),([0-9.+\-eE]+)\) \[([0-9.+\-eE]+)\|([0-9.+\-eE]+)\] \"(.*)\" (.*))"); - static QRegularExpression msg_comment_regexp(R"(^CM_ BO_ *(\w+) *\"([^"]*)\"\s*;)"); - static QRegularExpression sg_comment_regexp(R"(^CM_ SG_ *(\w+) *(\w+) *\"([^"]*)\"\s*;)"); - static QRegularExpression val_regexp(R"(VAL_ (\w+) (\w+) (\s*[-+]?[0-9]+\s+\".+?\"[^;]*))"); - - int line_num = 0; - QString line; - auto dbc_assert = [&line_num, &line, this](bool condition, const QString &msg = "") { - if (!condition) throw std::runtime_error(QString("[%1:%2]%3: %4").arg(filename).arg(line_num).arg(msg).arg(line).toStdString()); - }; - auto get_sig = [this](uint32_t address, const QString &name) -> cabana::Signal * { - auto m = (cabana::Msg *)msg(address); - return m ? (cabana::Signal *)m->sig(name) : nullptr; - }; - - msgs.clear(); - QTextStream stream((QString *)&content); - cabana::Msg *current_msg = nullptr; - int multiplexor_cnt = 0; - while (!stream.atEnd()) { - ++line_num; - QString raw_line = stream.readLine(); - line = raw_line.trimmed(); - if (line.startsWith("BO_ ")) { - multiplexor_cnt = 0; - auto match = bo_regexp.match(line); - dbc_assert(match.hasMatch()); - auto address = match.captured(1).toUInt(); - dbc_assert(msgs.count(address) == 0, QString("Duplicate message address: %1").arg(address)); - current_msg = &msgs[address]; - current_msg->address = address; - current_msg->name = match.captured(2); - current_msg->size = match.captured(3).toULong(); - current_msg->transmitter = match.captured(4).trimmed(); - } else if (line.startsWith("SG_ ")) { - int offset = 0; - auto match = sg_regexp.match(line); - if (!match.hasMatch()) { - match = sgm_regexp.match(line); - offset = 1; - } - dbc_assert(match.hasMatch()); - dbc_assert(current_msg, "No Message"); - auto name = match.captured(1); - dbc_assert(current_msg->sig(name) == nullptr, "Duplicate signal name"); - cabana::Signal s{}; - if (offset == 1) { - auto indicator = match.captured(2); - if (indicator == "M") { - // Only one signal within a single message can be the multiplexer switch. - dbc_assert(++multiplexor_cnt < 2, "Multiple multiplexor"); - s.type = cabana::Signal::Type::Multiplexor; - } else { - s.type = cabana::Signal::Type::Multiplexed; - s.multiplex_value = indicator.mid(1).toInt(); - } - } - s.name = name; - s.start_bit = match.captured(offset + 2).toInt(); - s.size = match.captured(offset + 3).toInt(); - s.is_little_endian = match.captured(offset + 4).toInt() == 1; - s.is_signed = match.captured(offset + 5) == "-"; - s.factor = match.captured(offset + 6).toDouble(); - s.offset = match.captured(offset + 7).toDouble(); - s.min = match.captured(8 + offset).toDouble(); - s.max = match.captured(9 + offset).toDouble(); - s.unit = match.captured(10 + offset); - s.receiver_name = match.captured(11 + offset).trimmed(); - - current_msg->sigs.push_back(new cabana::Signal(s)); - } else if (line.startsWith("VAL_ ")) { - auto match = val_regexp.match(line); - dbc_assert(match.hasMatch()); - if (auto s = get_sig(match.captured(1).toUInt(), match.captured(2))) { - QStringList desc_list = match.captured(3).trimmed().split('"'); - for (int i = 0; i < desc_list.size(); i += 2) { - auto val = desc_list[i].trimmed(); - if (!val.isEmpty() && (i + 1) < desc_list.size()) { - auto desc = desc_list[i + 1].trimmed(); - s->val_desc.push_back({val.toDouble(), desc}); - } - } - } - } else if (line.startsWith("CM_ BO_")) { - if (!line.endsWith("\";")) { - int pos = stream.pos() - raw_line.length() - 1; - line = content.mid(pos, content.indexOf("\";", pos)); - } - auto match = msg_comment_regexp.match(line); - dbc_assert(match.hasMatch()); - if (auto m = (cabana::Msg *)msg(match.captured(1).toUInt())) { - m->comment = match.captured(2).trimmed(); - } - } else if (line.startsWith("CM_ SG_ ")) { - if (!line.endsWith("\";")) { - int pos = stream.pos() - raw_line.length() - 1; - line = content.mid(pos, content.indexOf("\";", pos)); - } - auto match = sg_comment_regexp.match(line); - dbc_assert(match.hasMatch()); - if (auto s = get_sig(match.captured(1).toUInt(), match.captured(2))) { - s->comment = match.captured(3).trimmed(); - } - } - } - - for (auto &[_, m] : msgs) { - m.update(); - } -} - -QString DBCFile::generateDBC() { - QString dbc_string, signal_comment, message_comment, val_desc; - for (const auto &[address, m] : msgs) { - const QString transmitter = m.transmitter.isEmpty() ? DEFAULT_NODE_NAME : m.transmitter; - dbc_string += QString("BO_ %1 %2: %3 %4\n").arg(address).arg(m.name).arg(m.size).arg(transmitter); - if (!m.comment.isEmpty()) { - message_comment += QString("CM_ BO_ %1 \"%2\";\n").arg(address).arg(m.comment); - } - for (auto sig : m.getSignals()) { - QString multiplexer_indicator; - if (sig->type == cabana::Signal::Type::Multiplexor) { - multiplexer_indicator = "M "; - } else if (sig->type == cabana::Signal::Type::Multiplexed) { - multiplexer_indicator = QString("m%1 ").arg(sig->multiplex_value); - } - dbc_string += QString(" SG_ %1 %2: %3|%4@%5%6 (%7,%8) [%9|%10] \"%11\" %12\n") - .arg(sig->name) - .arg(multiplexer_indicator) - .arg(sig->start_bit) - .arg(sig->size) - .arg(sig->is_little_endian ? '1' : '0') - .arg(sig->is_signed ? '-' : '+') - .arg(doubleToString(sig->factor)) - .arg(doubleToString(sig->offset)) - .arg(doubleToString(sig->min)) - .arg(doubleToString(sig->max)) - .arg(sig->unit) - .arg(sig->receiver_name.isEmpty() ? DEFAULT_NODE_NAME : sig->receiver_name); - if (!sig->comment.isEmpty()) { - signal_comment += QString("CM_ SG_ %1 %2 \"%3\";\n").arg(address).arg(sig->name).arg(sig->comment); - } - if (!sig->val_desc.isEmpty()) { - QStringList text; - for (auto &[val, desc] : sig->val_desc) { - text << QString("%1 \"%2\"").arg(val).arg(desc); - } - val_desc += QString("VAL_ %1 %2 %3;\n").arg(address).arg(sig->name).arg(text.join(" ")); - } - } - dbc_string += "\n"; - } - return dbc_string + message_comment + signal_comment + val_desc; -} diff --git a/tools/cabana/dbc/dbcfile.h b/tools/cabana/dbc/dbcfile.h deleted file mode 100644 index ade6b24..0000000 --- a/tools/cabana/dbc/dbcfile.h +++ /dev/null @@ -1,41 +0,0 @@ -#pragma once - -#include - -#include "tools/cabana/dbc/dbc.h" - -const QString AUTO_SAVE_EXTENSION = ".tmp"; - -class DBCFile { -public: - DBCFile(const QString &dbc_file_name); - DBCFile(const QString &name, const QString &content); - ~DBCFile() {} - - bool save(); - bool saveAs(const QString &new_filename); - bool autoSave(); - bool writeContents(const QString &fn); - void cleanupAutoSaveFile(); - QString generateDBC(); - - void updateMsg(const MessageId &id, const QString &name, uint32_t size, const QString &node, const QString &comment); - inline void removeMsg(const MessageId &id) { msgs.erase(id.address); } - - inline const std::map &getMessages() const { return msgs; } - cabana::Msg *msg(uint32_t address); - cabana::Msg *msg(const QString &name); - inline cabana::Msg *msg(const MessageId &id) { return msg(id.address); } - - int signalCount(); - inline int msgCount() { return msgs.size(); } - inline QString name() { return name_.isEmpty() ? "untitled" : name_; } - inline bool isEmpty() { return (signalCount() == 0) && name_.isEmpty(); } - - QString filename; - -private: - void parse(const QString &content); - std::map msgs; - QString name_; -}; diff --git a/tools/cabana/dbc/dbcmanager.cc b/tools/cabana/dbc/dbcmanager.cc deleted file mode 100644 index 87a7d96..0000000 --- a/tools/cabana/dbc/dbcmanager.cc +++ /dev/null @@ -1,202 +0,0 @@ -#include "tools/cabana/dbc/dbcmanager.h" - -#include -#include - -bool DBCManager::open(const SourceSet &sources, const QString &dbc_file_name, QString *error) { - try { - auto it = std::find_if(dbc_files.begin(), dbc_files.end(), - [&](auto &f) { return f.second && f.second->filename == dbc_file_name; }); - auto file = (it != dbc_files.end()) ? it->second : std::make_shared(dbc_file_name); - for (auto s : sources) { - dbc_files[s] = file; - } - } catch (std::exception &e) { - if (error) *error = e.what(); - return false; - } - - emit DBCFileChanged(); - return true; -} - -bool DBCManager::open(const SourceSet &sources, const QString &name, const QString &content, QString *error) { - try { - auto file = std::make_shared(name, content); - for (auto s : sources) { - dbc_files[s] = file; - } - } catch (std::exception &e) { - if (error) *error = e.what(); - return false; - } - - emit DBCFileChanged(); - return true; -} - -void DBCManager::close(const SourceSet &sources) { - for (auto s : sources) { - dbc_files[s] = nullptr; - } - emit DBCFileChanged(); -} - -void DBCManager::close(DBCFile *dbc_file) { - for (auto &[_, f] : dbc_files) { - if (f.get() == dbc_file) f = nullptr; - } - emit DBCFileChanged(); -} - -void DBCManager::closeAll() { - dbc_files.clear(); - emit DBCFileChanged(); -} - -void DBCManager::addSignal(const MessageId &id, const cabana::Signal &sig) { - if (auto m = msg(id)) { - if (auto s = m->addSignal(sig)) { - emit signalAdded(id, s); - emit maskUpdated(); - } - } -} - -void DBCManager::updateSignal(const MessageId &id, const QString &sig_name, const cabana::Signal &sig) { - if (auto m = msg(id)) { - if (auto s = m->updateSignal(sig_name, sig)) { - emit signalUpdated(s); - emit maskUpdated(); - } - } -} - -void DBCManager::removeSignal(const MessageId &id, const QString &sig_name) { - if (auto m = msg(id)) { - if (auto s = m->sig(sig_name)) { - emit signalRemoved(s); - m->removeSignal(sig_name); - emit maskUpdated(); - } - } -} - -void DBCManager::updateMsg(const MessageId &id, const QString &name, uint32_t size, const QString &node, const QString &comment) { - auto dbc_file = findDBCFile(id); - assert(dbc_file); // This should be impossible - dbc_file->updateMsg(id, name, size, node, comment); - emit msgUpdated(id); -} - -void DBCManager::removeMsg(const MessageId &id) { - auto dbc_file = findDBCFile(id); - assert(dbc_file); // This should be impossible - dbc_file->removeMsg(id); - emit msgRemoved(id); - emit maskUpdated(); -} - -QString DBCManager::newMsgName(const MessageId &id) { - return QString("NEW_MSG_") + QString::number(id.address, 16).toUpper(); -} - -QString DBCManager::newSignalName(const MessageId &id) { - auto m = msg(id); - return m ? m->newSignalName() : ""; -} - -const std::vector &DBCManager::mask(const MessageId &id) { - static std::vector empty_mask; - auto m = msg(id); - return m ? m->mask : empty_mask; -} - -const std::map &DBCManager::getMessages(uint8_t source) { - static std::map empty_msgs; - auto dbc_file = findDBCFile(source); - return dbc_file ? dbc_file->getMessages() : empty_msgs; -} - -cabana::Msg *DBCManager::msg(const MessageId &id) { - auto dbc_file = findDBCFile(id); - return dbc_file ? dbc_file->msg(id) : nullptr; -} - -cabana::Msg *DBCManager::msg(uint8_t source, const QString &name) { - auto dbc_file = findDBCFile(source); - return dbc_file ? dbc_file->msg(name) : nullptr; -} - -QStringList DBCManager::signalNames() { - // Used for autocompletion - QStringList ret; - for (auto &f : allDBCFiles()) { - for (auto &[_, m] : f->getMessages()) { - for (auto sig : m.getSignals()) { - ret << sig->name; - } - } - } - ret.sort(); - ret.removeDuplicates(); - return ret; -} - -int DBCManager::signalCount(const MessageId &id) { - auto m = msg(id); - return m ? m->sigs.size() : 0; -} - -int DBCManager::signalCount() { - auto files = allDBCFiles(); - return std::accumulate(files.cbegin(), files.cend(), 0, [](int &n, auto &f) { return n + f->signalCount(); }); -} - -int DBCManager::msgCount() { - auto files = allDBCFiles(); - return std::accumulate(files.cbegin(), files.cend(), 0, [](int &n, auto &f) { return n + f->msgCount(); }); -} - -int DBCManager::dbcCount() { - return allDBCFiles().size(); -} - -int DBCManager::nonEmptyDBCCount() { - auto files = allDBCFiles(); - return std::count_if(files.cbegin(), files.cend(), [](auto &f) { return !f->isEmpty(); }); -} - -DBCFile *DBCManager::findDBCFile(const uint8_t source) { - // Find DBC file that matches id.source, fall back to SOURCE_ALL if no specific DBC is found - auto it = dbc_files.count(source) ? dbc_files.find(source) : dbc_files.find(-1); - return it != dbc_files.end() ? it->second.get() : nullptr; -} - -std::set DBCManager::allDBCFiles() { - std::set files; - for (const auto &[_, f] : dbc_files) { - if (f) files.insert(f.get()); - } - return files; -} - -const SourceSet DBCManager::sources(const DBCFile *dbc_file) const { - SourceSet sources; - for (auto &[s, f] : dbc_files) { - if (f.get() == dbc_file) sources.insert(s); - } - return sources; -} - -QString toString(const SourceSet &ss) { - return std::accumulate(ss.cbegin(), ss.cend(), QString(), [](QString str, int source) { - if (!str.isEmpty()) str += ", "; - return str + (source == -1 ? QStringLiteral("all") : QString::number(source)); - }); -} - -DBCManager *dbc() { - static DBCManager dbc_manager(nullptr); - return &dbc_manager; -} diff --git a/tools/cabana/dbc/dbcmanager.h b/tools/cabana/dbc/dbcmanager.h deleted file mode 100644 index 53a77a2..0000000 --- a/tools/cabana/dbc/dbcmanager.h +++ /dev/null @@ -1,74 +0,0 @@ -#pragma once - -#include -#include -#include -#include -#include - -#include "tools/cabana/dbc/dbcfile.h" - -typedef std::set SourceSet; -const SourceSet SOURCE_ALL = {-1}; -const int INVALID_SOURCE = 0xff; -inline bool operator<(const std::shared_ptr &l, const std::shared_ptr &r) { return l.get() < r.get(); } - -class DBCManager : public QObject { - Q_OBJECT - -public: - DBCManager(QObject *parent) : QObject(parent) {} - ~DBCManager() {} - bool open(const SourceSet &sources, const QString &dbc_file_name, QString *error = nullptr); - bool open(const SourceSet &sources, const QString &name, const QString &content, QString *error = nullptr); - void close(const SourceSet &sources); - void close(DBCFile *dbc_file); - void closeAll(); - - void addSignal(const MessageId &id, const cabana::Signal &sig); - void updateSignal(const MessageId &id, const QString &sig_name, const cabana::Signal &sig); - void removeSignal(const MessageId &id, const QString &sig_name); - - void updateMsg(const MessageId &id, const QString &name, uint32_t size, const QString &node, const QString &comment); - void removeMsg(const MessageId &id); - - QString newMsgName(const MessageId &id); - QString newSignalName(const MessageId &id); - const std::vector& mask(const MessageId &id); - - const std::map &getMessages(uint8_t source); - cabana::Msg *msg(const MessageId &id); - cabana::Msg* msg(uint8_t source, const QString &name); - - QStringList signalNames(); - int signalCount(const MessageId &id); - int signalCount(); - int msgCount(); - int dbcCount(); - int nonEmptyDBCCount(); - - const SourceSet sources(const DBCFile *dbc_file) const; - DBCFile *findDBCFile(const uint8_t source); - inline DBCFile *findDBCFile(const MessageId &id) { return findDBCFile(id.source); } - std::set allDBCFiles(); - -signals: - void signalAdded(MessageId id, const cabana::Signal *sig); - void signalRemoved(const cabana::Signal *sig); - void signalUpdated(const cabana::Signal *sig); - void msgUpdated(MessageId id); - void msgRemoved(MessageId id); - void DBCFileChanged(); - void maskUpdated(); - -private: - std::map> dbc_files; -}; - -DBCManager *dbc(); - -QString toString(const SourceSet &ss); -inline QString msgName(const MessageId &id) { - auto msg = dbc()->msg(id); - return msg ? msg->name : UNTITLED; -} diff --git a/tools/cabana/dbc/generate_dbc_json.py b/tools/cabana/dbc/generate_dbc_json.py deleted file mode 100644 index da19e27..0000000 --- a/tools/cabana/dbc/generate_dbc_json.py +++ /dev/null @@ -1,24 +0,0 @@ -#!/usr/bin/env python3 -import argparse -import json - -from openpilot.selfdrive.car.car_helpers import get_interface_attr - - -def generate_dbc_json() -> str: - all_cars_by_brand = get_interface_attr("CAR_INFO") - all_dbcs_by_brand = get_interface_attr("DBC") - dbc_map = {car: all_dbcs_by_brand[brand][car]['pt'] for brand, cars in all_cars_by_brand.items() for car in cars if car != 'mock'} - return json.dumps(dict(sorted(dbc_map.items())), indent=2) - - -if __name__ == "__main__": - parser = argparse.ArgumentParser(description="Generate mapping for all car fingerprints to DBC names and outputs json file", - formatter_class=argparse.ArgumentDefaultsHelpFormatter) - - parser.add_argument("--out", required=True, help="Generated json filepath") - args = parser.parse_args() - - with open(args.out, 'w') as f: - f.write(generate_dbc_json()) - print(f"Generated and written to {args.out}") diff --git a/tools/cabana/detailwidget.cc b/tools/cabana/detailwidget.cc deleted file mode 100644 index 7befadb..0000000 --- a/tools/cabana/detailwidget.cc +++ /dev/null @@ -1,276 +0,0 @@ -#include "tools/cabana/detailwidget.h" - -#include -#include -#include - -#include "tools/cabana/commands.h" -#include "tools/cabana/mainwin.h" - -// DetailWidget - -DetailWidget::DetailWidget(ChartsWidget *charts, QWidget *parent) : charts(charts), QWidget(parent) { - QVBoxLayout *main_layout = new QVBoxLayout(this); - main_layout->setContentsMargins(0, 0, 0, 0); - - // tabbar - tabbar = new TabBar(this); - tabbar->setUsesScrollButtons(true); - tabbar->setAutoHide(true); - tabbar->setContextMenuPolicy(Qt::CustomContextMenu); - main_layout->addWidget(tabbar); - - // message title - QHBoxLayout *title_layout = new QHBoxLayout(); - title_layout->setContentsMargins(3, 6, 3, 0); - auto spacer = new QSpacerItem(0, 1); - title_layout->addItem(spacer); - title_layout->addWidget(name_label = new ElidedLabel(this), 1); - name_label->setStyleSheet("QLabel{font-weight:bold;}"); - name_label->setAlignment(Qt::AlignCenter); - auto edit_btn = new ToolButton("pencil", tr("Edit Message")); - title_layout->addWidget(edit_btn); - title_layout->addWidget(remove_btn = new ToolButton("x-lg", tr("Remove Message"))); - spacer->changeSize(edit_btn->sizeHint().width() * 2 + 9, 1); - main_layout->addLayout(title_layout); - - // warning - warning_widget = new QWidget(this); - QHBoxLayout *warning_hlayout = new QHBoxLayout(warning_widget); - warning_hlayout->addWidget(warning_icon = new QLabel(this), 0, Qt::AlignTop); - warning_hlayout->addWidget(warning_label = new QLabel(this), 1, Qt::AlignLeft); - warning_widget->hide(); - main_layout->addWidget(warning_widget); - - // msg widget - splitter = new QSplitter(Qt::Vertical, this); - splitter->addWidget(binary_view = new BinaryView(this)); - splitter->addWidget(signal_view = new SignalView(charts, this)); - binary_view->setSizePolicy(QSizePolicy::Preferred, QSizePolicy::Minimum); - signal_view->setSizePolicy(QSizePolicy::Preferred, QSizePolicy::Expanding); - splitter->setStretchFactor(0, 0); - splitter->setStretchFactor(1, 1); - - tab_widget = new QTabWidget(this); - tab_widget->setStyleSheet("QTabWidget::pane {border: none; margin-bottom: -2px;}"); - tab_widget->setTabPosition(QTabWidget::South); - tab_widget->addTab(splitter, utils::icon("file-earmark-ruled"), "&Msg"); - tab_widget->addTab(history_log = new LogsWidget(this), utils::icon("stopwatch"), "&Logs"); - main_layout->addWidget(tab_widget); - - QObject::connect(edit_btn, &QToolButton::clicked, this, &DetailWidget::editMsg); - QObject::connect(remove_btn, &QToolButton::clicked, this, &DetailWidget::removeMsg); - QObject::connect(binary_view, &BinaryView::signalHovered, signal_view, &SignalView::signalHovered); - QObject::connect(binary_view, &BinaryView::signalClicked, [this](const cabana::Signal *s) { signal_view->selectSignal(s, true); }); - QObject::connect(binary_view, &BinaryView::editSignal, signal_view->model, &SignalModel::saveSignal); - QObject::connect(binary_view, &BinaryView::showChart, charts, &ChartsWidget::showChart); - QObject::connect(signal_view, &SignalView::showChart, charts, &ChartsWidget::showChart); - QObject::connect(signal_view, &SignalView::highlight, binary_view, &BinaryView::highlight); - QObject::connect(tab_widget, &QTabWidget::currentChanged, [this]() { updateState(); }); - QObject::connect(can, &AbstractStream::msgsReceived, this, &DetailWidget::updateState); - QObject::connect(dbc(), &DBCManager::DBCFileChanged, this, &DetailWidget::refresh); - QObject::connect(UndoStack::instance(), &QUndoStack::indexChanged, this, &DetailWidget::refresh); - QObject::connect(tabbar, &QTabBar::customContextMenuRequested, this, &DetailWidget::showTabBarContextMenu); - QObject::connect(tabbar, &QTabBar::currentChanged, [this](int index) { - if (index != -1) { - setMessage(tabbar->tabData(index).value()); - } - }); - QObject::connect(tabbar, &QTabBar::tabCloseRequested, tabbar, &QTabBar::removeTab); - QObject::connect(charts, &ChartsWidget::seriesChanged, signal_view, &SignalView::updateChartState); -} - -void DetailWidget::showTabBarContextMenu(const QPoint &pt) { - int index = tabbar->tabAt(pt); - if (index >= 0) { - QMenu menu(this); - menu.addAction(tr("Close Other Tabs")); - if (menu.exec(tabbar->mapToGlobal(pt))) { - tabbar->moveTab(index, 0); - tabbar->setCurrentIndex(0); - while (tabbar->count() > 1) { - tabbar->removeTab(1); - } - } - } -} - -void DetailWidget::setMessage(const MessageId &message_id) { - if (std::exchange(msg_id, message_id) == message_id) return; - - tabbar->blockSignals(true); - int index = tabbar->count() - 1; - for (/**/; index >= 0; --index) { - if (tabbar->tabData(index).value() == message_id) break; - } - if (index == -1) { - index = tabbar->addTab(message_id.toString()); - tabbar->setTabData(index, QVariant::fromValue(message_id)); - tabbar->setTabToolTip(index, msgName(message_id)); - } - tabbar->setCurrentIndex(index); - tabbar->blockSignals(false); - - setUpdatesEnabled(false); - signal_view->setMessage(msg_id); - binary_view->setMessage(msg_id); - history_log->setMessage(msg_id); - refresh(); - setUpdatesEnabled(true); -} - -void DetailWidget::refresh() { - QStringList warnings; - auto msg = dbc()->msg(msg_id); - if (msg) { - if (msg_id.source == INVALID_SOURCE) { - warnings.push_back(tr("No messages received.")); - } else if (msg->size != can->lastMessage(msg_id).dat.size()) { - warnings.push_back(tr("Message size (%1) is incorrect.").arg(msg->size)); - } - for (auto s : binary_view->getOverlappingSignals()) { - warnings.push_back(tr("%1 has overlapping bits.").arg(s->name)); - } - } else { - warnings.push_back(tr("Drag-Select in binary view to create new signal.")); - } - - QString msg_name = msg ? QString("%1 (%2)").arg(msg->name, msg->transmitter) : msgName(msg_id); - name_label->setText(msg_name); - name_label->setToolTip(msg_name); - remove_btn->setEnabled(msg != nullptr); - - if (!warnings.isEmpty()) { - warning_label->setText(warnings.join('\n')); - warning_icon->setPixmap(utils::icon(msg ? "exclamation-triangle" : "info-circle")); - } - warning_widget->setVisible(!warnings.isEmpty()); -} - -void DetailWidget::updateState(const std::set *msgs) { - if ((msgs && !msgs->count(msg_id))) - return; - - if (tab_widget->currentIndex() == 0) - binary_view->updateState(); - else - history_log->updateState(); -} - -void DetailWidget::editMsg() { - auto msg = dbc()->msg(msg_id); - int size = msg ? msg->size : can->lastMessage(msg_id).dat.size(); - EditMessageDialog dlg(msg_id, msgName(msg_id), size, this); - if (dlg.exec()) { - UndoStack::push(new EditMsgCommand(msg_id, dlg.name_edit->text().trimmed(), dlg.size_spin->value(), - dlg.node->text().trimmed(), dlg.comment_edit->toPlainText().trimmed())); - } -} - -void DetailWidget::removeMsg() { - UndoStack::push(new RemoveMsgCommand(msg_id)); -} - -// EditMessageDialog - -EditMessageDialog::EditMessageDialog(const MessageId &msg_id, const QString &title, int size, QWidget *parent) - : original_name(title), msg_id(msg_id), QDialog(parent) { - setWindowTitle(tr("Edit message: %1").arg(msg_id.toString())); - QFormLayout *form_layout = new QFormLayout(this); - - form_layout->addRow("", error_label = new QLabel); - error_label->setVisible(false); - form_layout->addRow(tr("Name"), name_edit = new QLineEdit(title, this)); - name_edit->setValidator(new NameValidator(name_edit)); - - form_layout->addRow(tr("Size"), size_spin = new QSpinBox(this)); - // TODO: limit the maximum? - size_spin->setMinimum(1); - size_spin->setValue(size); - - form_layout->addRow(tr("Node"), node = new QLineEdit(this)); - node->setValidator(new NameValidator(name_edit)); - form_layout->addRow(tr("Comment"), comment_edit = new QTextEdit(this)); - form_layout->addRow(btn_box = new QDialogButtonBox(QDialogButtonBox::Ok | QDialogButtonBox::Cancel)); - - if (auto msg = dbc()->msg(msg_id)) { - node->setText(msg->transmitter); - comment_edit->setText(msg->comment); - } - validateName(name_edit->text()); - setFixedWidth(parent->width() * 0.9); - connect(name_edit, &QLineEdit::textEdited, this, &EditMessageDialog::validateName); - connect(btn_box, &QDialogButtonBox::accepted, this, &QDialog::accept); - connect(btn_box, &QDialogButtonBox::rejected, this, &QDialog::reject); -} - -void EditMessageDialog::validateName(const QString &text) { - bool valid = text.compare(UNTITLED, Qt::CaseInsensitive) != 0; - error_label->setVisible(false); - if (!text.isEmpty() && valid && text != original_name) { - valid = dbc()->msg(msg_id.source, text) == nullptr; - if (!valid) { - error_label->setText(tr("Name already exists")); - error_label->setVisible(true); - } - } - btn_box->button(QDialogButtonBox::Ok)->setEnabled(valid); -} - -// CenterWidget - -CenterWidget::CenterWidget(QWidget *parent) : QWidget(parent) { - QVBoxLayout *main_layout = new QVBoxLayout(this); - main_layout->setContentsMargins(0, 0, 0, 0); - main_layout->addWidget(welcome_widget = createWelcomeWidget()); -} - -void CenterWidget::setMessage(const MessageId &msg_id) { - if (!detail_widget) { - delete welcome_widget; - welcome_widget = nullptr; - layout()->addWidget(detail_widget = new DetailWidget(((MainWindow*)parentWidget())->charts_widget, this)); - } - detail_widget->setMessage(msg_id); -} - -void CenterWidget::clear() { - delete detail_widget; - detail_widget = nullptr; - if (!welcome_widget) { - layout()->addWidget(welcome_widget = createWelcomeWidget()); - } -} - -QWidget *CenterWidget::createWelcomeWidget() { - QWidget *w = new QWidget(this); - QVBoxLayout *main_layout = new QVBoxLayout(w); - main_layout->addStretch(0); - QLabel *logo = new QLabel("CABANA"); - logo->setAlignment(Qt::AlignCenter); - logo->setStyleSheet("font-size:50px;font-weight:bold;"); - main_layout->addWidget(logo); - - auto newShortcutRow = [](const QString &title, const QString &key) { - QHBoxLayout *hlayout = new QHBoxLayout(); - auto btn = new QToolButton(); - btn->setText(key); - btn->setEnabled(false); - hlayout->addWidget(new QLabel(title), 0, Qt::AlignRight); - hlayout->addWidget(btn, 0, Qt::AlignLeft); - return hlayout; - }; - - auto lb = new QLabel(tr("<-Select a message to view details")); - lb->setAlignment(Qt::AlignHCenter); - main_layout->addWidget(lb); - main_layout->addLayout(newShortcutRow("Pause", "Space")); - main_layout->addLayout(newShortcutRow("Help", "F1")); - main_layout->addLayout(newShortcutRow("WhatsThis", "Shift+F1")); - main_layout->addStretch(0); - - w->setStyleSheet("QLabel{color:darkGray;}"); - w->setBackgroundRole(QPalette::Base); - w->setAutoFillBackground(true); - return w; -} diff --git a/tools/cabana/detailwidget.h b/tools/cabana/detailwidget.h deleted file mode 100644 index 15e1ee5..0000000 --- a/tools/cabana/detailwidget.h +++ /dev/null @@ -1,69 +0,0 @@ -#pragma once - -#include -#include -#include -#include -#include - -#include "selfdrive/ui/qt/widgets/controls.h" -#include "tools/cabana/binaryview.h" -#include "tools/cabana/chart/chartswidget.h" -#include "tools/cabana/historylog.h" -#include "tools/cabana/signalview.h" - -class EditMessageDialog : public QDialog { -public: - EditMessageDialog(const MessageId &msg_id, const QString &title, int size, QWidget *parent); - void validateName(const QString &text); - - MessageId msg_id; - QString original_name; - QDialogButtonBox *btn_box; - QLineEdit *name_edit; - QLineEdit *node; - QTextEdit *comment_edit; - QLabel *error_label; - QSpinBox *size_spin; -}; - -class DetailWidget : public QWidget { - Q_OBJECT - -public: - DetailWidget(ChartsWidget *charts, QWidget *parent); - void setMessage(const MessageId &message_id); - void refresh(); - -private: - void showTabBarContextMenu(const QPoint &pt); - void editMsg(); - void removeMsg(); - void updateState(const std::set *msgs = nullptr); - - MessageId msg_id; - QLabel *warning_icon, *warning_label; - ElidedLabel *name_label; - QWidget *warning_widget; - TabBar *tabbar; - QTabWidget *tab_widget; - QToolButton *remove_btn; - LogsWidget *history_log; - BinaryView *binary_view; - SignalView *signal_view; - ChartsWidget *charts; - QSplitter *splitter; -}; - -class CenterWidget : public QWidget { - Q_OBJECT -public: - CenterWidget(QWidget *parent); - void setMessage(const MessageId &msg_id); - void clear(); - -private: - QWidget *createWelcomeWidget(); - DetailWidget *detail_widget = nullptr; - QWidget *welcome_widget = nullptr; -}; diff --git a/tools/cabana/historylog.cc b/tools/cabana/historylog.cc deleted file mode 100644 index b3440b5..0000000 --- a/tools/cabana/historylog.cc +++ /dev/null @@ -1,306 +0,0 @@ -#include "tools/cabana/historylog.h" - -#include - -#include -#include -#include - -#include "tools/cabana/commands.h" - -QVariant HistoryLogModel::data(const QModelIndex &index, int role) const { - const bool show_signals = display_signals_mode && sigs.size() > 0; - const auto &m = messages[index.row()]; - if (role == Qt::DisplayRole) { - if (index.column() == 0) { - return QString::number((m.mono_time / (double)1e9) - can->routeStartTime(), 'f', 2); - } - int i = index.column() - 1; - return show_signals ? QString::number(m.sig_values[i], 'f', sigs[i]->precision) : QString(); - } else if (role == ColorsRole) { - return QVariant::fromValue((void *)(&m.colors)); - } else if (role == BytesRole) { - return QVariant::fromValue((void *)(&m.data)); - } else if (role == Qt::TextAlignmentRole) { - return (uint32_t)(Qt::AlignRight | Qt::AlignVCenter); - } - return {}; -} - -void HistoryLogModel::setMessage(const MessageId &message_id) { - msg_id = message_id; -} - -void HistoryLogModel::refresh(bool fetch_message) { - beginResetModel(); - sigs.clear(); - if (auto dbc_msg = dbc()->msg(msg_id)) { - sigs = dbc_msg->getSignals(); - } - last_fetch_time = 0; - has_more_data = true; - messages.clear(); - hex_colors = {}; - if (fetch_message) { - updateState(); - } - endResetModel(); -} - -QVariant HistoryLogModel::headerData(int section, Qt::Orientation orientation, int role) const { - if (orientation == Qt::Horizontal) { - const bool show_signals = display_signals_mode && !sigs.empty(); - if (role == Qt::DisplayRole || role == Qt::ToolTipRole) { - if (section == 0) { - return "Time"; - } - if (show_signals) { - QString name = sigs[section - 1]->name; - if (!sigs[section - 1]->unit.isEmpty()) { - name += QString(" (%1)").arg(sigs[section - 1]->unit); - } - return name; - } else { - return "Data"; - } - } else if (role == Qt::BackgroundRole && section > 0 && show_signals) { - // Alpha-blend the signal color with the background to ensure contrast - QColor sigColor = sigs[section - 1]->color; - sigColor.setAlpha(128); - return QBrush(sigColor); - } - } - return {}; -} - -void HistoryLogModel::setDynamicMode(int state) { - dynamic_mode = state != 0; - refresh(); -} - -void HistoryLogModel::setDisplayType(int type) { - display_signals_mode = type == 0; - refresh(); -} - -void HistoryLogModel::segmentsMerged() { - if (!dynamic_mode) { - has_more_data = true; - } -} - -void HistoryLogModel::setFilter(int sig_idx, const QString &value, std::function cmp) { - filter_sig_idx = sig_idx; - filter_value = value.toDouble(); - filter_cmp = value.isEmpty() ? nullptr : cmp; -} - -void HistoryLogModel::updateState() { - uint64_t current_time = (can->lastMessage(msg_id).ts + can->routeStartTime()) * 1e9 + 1; - auto new_msgs = dynamic_mode ? fetchData(current_time, last_fetch_time) : fetchData(0); - if (!new_msgs.empty()) { - beginInsertRows({}, 0, new_msgs.size() - 1); - messages.insert(messages.begin(), std::move_iterator(new_msgs.begin()), std::move_iterator(new_msgs.end())); - endInsertRows(); - } - has_more_data = new_msgs.size() >= batch_size; - last_fetch_time = current_time; -} - -void HistoryLogModel::fetchMore(const QModelIndex &parent) { - if (!messages.empty()) { - auto new_msgs = fetchData(messages.back().mono_time); - if (!new_msgs.empty()) { - beginInsertRows({}, messages.size(), messages.size() + new_msgs.size() - 1); - messages.insert(messages.end(), std::move_iterator(new_msgs.begin()), std::move_iterator(new_msgs.end())); - endInsertRows(); - } - has_more_data = new_msgs.size() >= batch_size; - } -} - -template -std::deque HistoryLogModel::fetchData(InputIt first, InputIt last, uint64_t min_time) { - std::deque msgs; - std::vector values(sigs.size()); - for (; first != last && (*first)->mono_time > min_time; ++first) { - const CanEvent *e = *first; - for (int i = 0; i < sigs.size(); ++i) { - sigs[i]->getValue(e->dat, e->size, &values[i]); - } - if (!filter_cmp || filter_cmp(values[filter_sig_idx], filter_value)) { - auto &m = msgs.emplace_back(); - m.mono_time = e->mono_time; - m.data.assign(e->dat, e->dat + e->size); - m.sig_values = values; - if (msgs.size() >= batch_size && min_time == 0) { - return msgs; - } - } - } - return msgs; -} - -std::deque HistoryLogModel::fetchData(uint64_t from_time, uint64_t min_time) { - const auto &events = can->events(msg_id); - const auto freq = can->lastMessage(msg_id).freq; - const bool update_colors = !display_signals_mode || sigs.empty(); - const std::vector no_mask; - const auto speed = can->getSpeed(); - if (dynamic_mode) { - auto first = std::upper_bound(events.rbegin(), events.rend(), from_time, [](uint64_t ts, auto e) { - return ts > e->mono_time; - }); - auto msgs = fetchData(first, events.rend(), min_time); - if (update_colors && (min_time > 0 || messages.empty())) { - for (auto it = msgs.rbegin(); it != msgs.rend(); ++it) { - hex_colors.compute(msg_id, it->data.data(), it->data.size(), it->mono_time / (double)1e9, speed, no_mask, freq); - it->colors = hex_colors.colors; - } - } - return msgs; - } else { - assert(min_time == 0); - auto first = std::upper_bound(events.cbegin(), events.cend(), from_time, CompareCanEvent()); - auto msgs = fetchData(first, events.cend(), 0); - if (update_colors) { - for (auto it = msgs.begin(); it != msgs.end(); ++it) { - hex_colors.compute(msg_id, it->data.data(), it->data.size(), it->mono_time / (double)1e9, speed, no_mask, freq); - it->colors = hex_colors.colors; - } - } - return msgs; - } -} - -// HeaderView - -QSize HeaderView::sectionSizeFromContents(int logicalIndex) const { - static const QSize time_col_size = fontMetrics().boundingRect({0, 0, 200, 200}, defaultAlignment(), "000000.000").size() + QSize(10, 6); - if (logicalIndex == 0) { - return time_col_size; - } else { - int default_size = qMax(100, (rect().width() - time_col_size.width()) / (model()->columnCount() - 1)); - QString text = model()->headerData(logicalIndex, this->orientation(), Qt::DisplayRole).toString(); - const QRect rect = fontMetrics().boundingRect({0, 0, default_size, 2000}, defaultAlignment(), text.replace(QChar('_'), ' ')); - QSize size = rect.size() + QSize{10, 6}; - return QSize{qMax(size.width(), default_size), size.height()}; - } -} - -void HeaderView::paintSection(QPainter *painter, const QRect &rect, int logicalIndex) const { - auto bg_role = model()->headerData(logicalIndex, Qt::Horizontal, Qt::BackgroundRole); - if (bg_role.isValid()) { - painter->fillRect(rect, bg_role.value()); - } - QString text = model()->headerData(logicalIndex, Qt::Horizontal, Qt::DisplayRole).toString(); - painter->setPen(palette().color(settings.theme == DARK_THEME ? QPalette::BrightText : QPalette::Text)); - painter->drawText(rect.adjusted(5, 3, -5, -3), defaultAlignment(), text.replace(QChar('_'), ' ')); -} - -// LogsWidget - -LogsWidget::LogsWidget(QWidget *parent) : QFrame(parent) { - setFrameStyle(QFrame::StyledPanel | QFrame::Plain); - QVBoxLayout *main_layout = new QVBoxLayout(this); - main_layout->setContentsMargins(0, 0, 0, 0); - main_layout->setSpacing(0); - - QWidget *toolbar = new QWidget(this); - toolbar->setAutoFillBackground(true); - QHBoxLayout *h = new QHBoxLayout(toolbar); - - filters_widget = new QWidget(this); - QHBoxLayout *filter_layout = new QHBoxLayout(filters_widget); - filter_layout->setContentsMargins(0, 0, 0, 0); - filter_layout->addWidget(display_type_cb = new QComboBox(this)); - filter_layout->addWidget(signals_cb = new QComboBox(this)); - filter_layout->addWidget(comp_box = new QComboBox(this)); - filter_layout->addWidget(value_edit = new QLineEdit(this)); - h->addWidget(filters_widget); - h->addStretch(0); - h->addWidget(dynamic_mode = new QCheckBox(tr("Dynamic")), 0, Qt::AlignRight); - - display_type_cb->addItems({"Signal", "Hex"}); - display_type_cb->setToolTip(tr("Display signal value or raw hex value")); - comp_box->addItems({">", "=", "!=", "<"}); - value_edit->setClearButtonEnabled(true); - value_edit->setValidator(new DoubleValidator(this)); - dynamic_mode->setChecked(true); - dynamic_mode->setEnabled(!can->liveStreaming()); - - main_layout->addWidget(toolbar); - QFrame *line = new QFrame(this); - line->setFrameStyle(QFrame::HLine | QFrame::Sunken); - main_layout->addWidget(line); - main_layout->addWidget(logs = new QTableView(this)); - logs->setModel(model = new HistoryLogModel(this)); - delegate = new MessageBytesDelegate(this); - logs->setHorizontalHeader(new HeaderView(Qt::Horizontal, this)); - logs->horizontalHeader()->setDefaultAlignment(Qt::AlignRight | (Qt::Alignment)Qt::TextWordWrap); - logs->horizontalHeader()->setSectionResizeMode(QHeaderView::ResizeToContents); - logs->verticalHeader()->setSectionResizeMode(QHeaderView::Fixed); - logs->verticalHeader()->setDefaultSectionSize(delegate->sizeForBytes(8).height()); - logs->verticalHeader()->setVisible(false); - logs->setFrameShape(QFrame::NoFrame); - - QObject::connect(display_type_cb, qOverload(&QComboBox::activated), [this](int index) { - logs->setItemDelegateForColumn(1, index == 1 ? delegate : nullptr); - model->setDisplayType(index); - }); - QObject::connect(dynamic_mode, &QCheckBox::stateChanged, model, &HistoryLogModel::setDynamicMode); - QObject::connect(signals_cb, SIGNAL(activated(int)), this, SLOT(setFilter())); - QObject::connect(comp_box, SIGNAL(activated(int)), this, SLOT(setFilter())); - QObject::connect(value_edit, &QLineEdit::textChanged, this, &LogsWidget::setFilter); - QObject::connect(can, &AbstractStream::seekedTo, model, &HistoryLogModel::refresh); - QObject::connect(dbc(), &DBCManager::DBCFileChanged, this, &LogsWidget::refresh); - QObject::connect(UndoStack::instance(), &QUndoStack::indexChanged, this, &LogsWidget::refresh); - QObject::connect(can, &AbstractStream::eventsMerged, model, &HistoryLogModel::segmentsMerged); -} - -void LogsWidget::setMessage(const MessageId &message_id) { - model->setMessage(message_id); - refresh(); -} - -void LogsWidget::refresh() { - model->setFilter(0, "", nullptr); - model->refresh(isVisible()); - bool has_signal = model->sigs.size(); - if (has_signal) { - signals_cb->clear(); - for (auto s : model->sigs) { - signals_cb->addItem(s->name); - } - } - logs->setItemDelegateForColumn(1, !has_signal || display_type_cb->currentIndex() == 1 ? delegate : nullptr); - value_edit->clear(); - comp_box->setCurrentIndex(0); - filters_widget->setVisible(has_signal); -} - -void LogsWidget::setFilter() { - if (value_edit->text().isEmpty() && !value_edit->isModified()) return; - - std::function cmp = nullptr; - switch (comp_box->currentIndex()) { - case 0: cmp = std::greater{}; break; - case 1: cmp = std::equal_to{}; break; - case 2: cmp = [](double l, double r) { return l != r; }; break; // not equal - case 3: cmp = std::less{}; break; - } - model->setFilter(signals_cb->currentIndex(), value_edit->text(), cmp); - model->refresh(); -} - -void LogsWidget::updateState() { - if (isVisible() && dynamic_mode->isChecked()) { - model->updateState(); - } -} - -void LogsWidget::showEvent(QShowEvent *event) { - if (dynamic_mode->isChecked() || model->canFetchMore({}) && model->rowCount() == 0) { - model->refresh(); - } -} diff --git a/tools/cabana/historylog.h b/tools/cabana/historylog.h deleted file mode 100644 index 154b139..0000000 --- a/tools/cabana/historylog.h +++ /dev/null @@ -1,94 +0,0 @@ -#pragma once - -#include -#include - -#include -#include -#include -#include -#include - -#include "tools/cabana/dbc/dbcmanager.h" -#include "tools/cabana/streams/abstractstream.h" -#include "tools/cabana/util.h" - -class HeaderView : public QHeaderView { -public: - HeaderView(Qt::Orientation orientation, QWidget *parent = nullptr) : QHeaderView(orientation, parent) {} - QSize sectionSizeFromContents(int logicalIndex) const override; - void paintSection(QPainter *painter, const QRect &rect, int logicalIndex) const; -}; - -class HistoryLogModel : public QAbstractTableModel { - Q_OBJECT - -public: - HistoryLogModel(QObject *parent) : QAbstractTableModel(parent) {} - void setMessage(const MessageId &message_id); - void updateState(); - void setFilter(int sig_idx, const QString &value, std::function cmp); - QVariant headerData(int section, Qt::Orientation orientation, int role = Qt::DisplayRole) const override; - QVariant data(const QModelIndex &index, int role = Qt::DisplayRole) const override; - void fetchMore(const QModelIndex &parent) override; - inline bool canFetchMore(const QModelIndex &parent) const override { return has_more_data; } - int rowCount(const QModelIndex &parent = QModelIndex()) const override { return messages.size(); } - int columnCount(const QModelIndex &parent = QModelIndex()) const override { - return display_signals_mode && !sigs.empty() ? sigs.size() + 1 : 2; - } - void refresh(bool fetch_message = true); - -public slots: - void setDisplayType(int type); - void setDynamicMode(int state); - void segmentsMerged(); - -public: - struct Message { - uint64_t mono_time = 0; - std::vector sig_values; - std::vector data; - std::vector colors; - }; - - template - std::deque fetchData(InputIt first, InputIt last, uint64_t min_time); - std::deque fetchData(uint64_t from_time, uint64_t min_time = 0); - - MessageId msg_id; - CanData hex_colors; - bool has_more_data = true; - const int batch_size = 50; - int filter_sig_idx = -1; - double filter_value = 0; - uint64_t last_fetch_time = 0; - std::function filter_cmp = nullptr; - std::deque messages; - std::vector sigs; - bool dynamic_mode = true; - bool display_signals_mode = true; -}; - -class LogsWidget : public QFrame { - Q_OBJECT - -public: - LogsWidget(QWidget *parent); - void setMessage(const MessageId &message_id); - void updateState(); - void showEvent(QShowEvent *event) override; - -private slots: - void setFilter(); - -private: - void refresh(); - - QTableView *logs; - HistoryLogModel *model; - QCheckBox *dynamic_mode; - QComboBox *signals_cb, *comp_box, *display_type_cb; - QLineEdit *value_edit; - QWidget *filters_widget; - MessageBytesDelegate *delegate; -}; diff --git a/tools/cabana/mainwin.cc b/tools/cabana/mainwin.cc deleted file mode 100644 index f7f2fba..0000000 --- a/tools/cabana/mainwin.cc +++ /dev/null @@ -1,697 +0,0 @@ -#include "tools/cabana/mainwin.h" - -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include "tools/cabana/commands.h" -#include "tools/cabana/streamselector.h" -#include "tools/cabana/tools/findsignal.h" -#include "tools/replay/replay.h" - -MainWindow::MainWindow() : QMainWindow() { - loadFingerprints(); - createDockWindows(); - setCentralWidget(center_widget = new CenterWidget(this)); - createActions(); - createStatusBar(); - createShortcuts(); - - // save default window state to allow resetting it - default_state = saveState(); - - // restore states - restoreGeometry(settings.geometry); - if (isMaximized()) { - setGeometry(QApplication::desktop()->availableGeometry(this)); - } - restoreState(settings.window_state); - - // install handlers - static auto static_main_win = this; - qRegisterMetaType("uint64_t"); - qRegisterMetaType("SourceSet"); - qRegisterMetaType("ReplyMsgType"); - installDownloadProgressHandler([](uint64_t cur, uint64_t total, bool success) { - emit static_main_win->updateProgressBar(cur, total, success); - }); - qInstallMessageHandler([](QtMsgType type, const QMessageLogContext &context, const QString &msg) { - if (type == QtDebugMsg) std::cout << msg.toStdString() << std::endl; - emit static_main_win->showMessage(msg, 2000); - }); - installMessageHandler([](ReplyMsgType type, const std::string msg) { - qInfo() << QString::fromStdString(msg); - }); - - setStyleSheet(QString(R"(QMainWindow::separator { - width: %1px; /* when vertical */ - height: %1px; /* when horizontal */ - })").arg(style()->pixelMetric(QStyle::PM_SplitterWidth))); - - QObject::connect(this, &MainWindow::showMessage, statusBar(), &QStatusBar::showMessage); - QObject::connect(this, &MainWindow::updateProgressBar, this, &MainWindow::updateDownloadProgress); - QObject::connect(dbc(), &DBCManager::DBCFileChanged, this, &MainWindow::DBCFileChanged); - QObject::connect(UndoStack::instance(), &QUndoStack::cleanChanged, this, &MainWindow::undoStackCleanChanged); - QObject::connect(UndoStack::instance(), &QUndoStack::indexChanged, this, &MainWindow::undoStackIndexChanged); - QObject::connect(&settings, &Settings::changed, this, &MainWindow::updateStatus); - QObject::connect(StreamNotifier::instance(), &StreamNotifier::changingStream, this, &MainWindow::changingStream); - QObject::connect(StreamNotifier::instance(), &StreamNotifier::streamStarted, this, &MainWindow::streamStarted); -} - -void MainWindow::loadFingerprints() { - QFile json_file(QApplication::applicationDirPath() + "/dbc/car_fingerprint_to_dbc.json"); - if (json_file.open(QIODevice::ReadOnly)) { - fingerprint_to_dbc = QJsonDocument::fromJson(json_file.readAll()); - } - // get opendbc names - for (auto fn : QDir(OPENDBC_FILE_PATH).entryList({"*.dbc"}, QDir::Files, QDir::Name)) { - opendbc_names << QFileInfo(fn).baseName(); - } -} - -void MainWindow::createActions() { - // File menu - QMenu *file_menu = menuBar()->addMenu(tr("&File")); - file_menu->addAction(tr("Open Stream..."), this, &MainWindow::openStream); - close_stream_act = file_menu->addAction(tr("Close stream"), this, &MainWindow::closeStream); - close_stream_act->setEnabled(false); - file_menu->addSeparator(); - - file_menu->addAction(tr("New DBC File"), [this]() { newFile(); }, QKeySequence::New); - file_menu->addAction(tr("Open DBC File..."), [this]() { openFile(); }, QKeySequence::Open); - - manage_dbcs_menu = file_menu->addMenu(tr("Manage &DBC Files")); - - open_recent_menu = file_menu->addMenu(tr("Open &Recent")); - for (int i = 0; i < MAX_RECENT_FILES; ++i) { - recent_files_acts[i] = new QAction(this); - recent_files_acts[i]->setVisible(false); - QObject::connect(recent_files_acts[i], &QAction::triggered, this, &MainWindow::openRecentFile); - open_recent_menu->addAction(recent_files_acts[i]); - } - updateRecentFileActions(); - - file_menu->addSeparator(); - QMenu *load_opendbc_menu = file_menu->addMenu(tr("Load DBC from commaai/opendbc")); - // load_opendbc_menu->setStyleSheet("QMenu { menu-scrollable: true; }"); - for (const auto &dbc_name : opendbc_names) { - load_opendbc_menu->addAction(dbc_name, [this, name = dbc_name]() { loadDBCFromOpendbc(name); }); - } - - file_menu->addAction(tr("Load DBC From Clipboard"), [=]() { loadFromClipboard(); }); - - file_menu->addSeparator(); - save_dbc = file_menu->addAction(tr("Save DBC..."), this, &MainWindow::save, QKeySequence::Save); - save_dbc_as = file_menu->addAction(tr("Save DBC As..."), this, &MainWindow::saveAs, QKeySequence::SaveAs); - copy_dbc_to_clipboard = file_menu->addAction(tr("Copy DBC To Clipboard"), this, &MainWindow::saveToClipboard); - - file_menu->addSeparator(); - file_menu->addAction(tr("Settings..."), this, &MainWindow::setOption, QKeySequence::Preferences); - - file_menu->addSeparator(); - file_menu->addAction(tr("E&xit"), qApp, &QApplication::closeAllWindows, QKeySequence::Quit); - - // Edit Menu - QMenu *edit_menu = menuBar()->addMenu(tr("&Edit")); - auto undo_act = UndoStack::instance()->createUndoAction(this, tr("&Undo")); - undo_act->setShortcuts(QKeySequence::Undo); - edit_menu->addAction(undo_act); - auto redo_act = UndoStack::instance()->createRedoAction(this, tr("&Rndo")); - redo_act->setShortcuts(QKeySequence::Redo); - edit_menu->addAction(redo_act); - edit_menu->addSeparator(); - - QMenu *commands_menu = edit_menu->addMenu(tr("Command &List")); - QWidgetAction *commands_act = new QWidgetAction(this); - commands_act->setDefaultWidget(new QUndoView(UndoStack::instance())); - commands_menu->addAction(commands_act); - - // View Menu - QMenu *view_menu = menuBar()->addMenu(tr("&View")); - auto act = view_menu->addAction(tr("Full Screen"), this, &MainWindow::toggleFullScreen, QKeySequence::FullScreen); - addAction(act); - view_menu->addSeparator(); - view_menu->addAction(messages_dock->toggleViewAction()); - view_menu->addAction(video_dock->toggleViewAction()); - view_menu->addSeparator(); - view_menu->addAction(tr("Reset Window Layout"), [this]() { restoreState(default_state); }); - - // Tools Menu - tools_menu = menuBar()->addMenu(tr("&Tools")); - tools_menu->addAction(tr("Find &Similar Bits"), this, &MainWindow::findSimilarBits); - tools_menu->addAction(tr("&Find Signal"), this, &MainWindow::findSignal); - - // Help Menu - QMenu *help_menu = menuBar()->addMenu(tr("&Help")); - help_menu->addAction(tr("Help"), this, &MainWindow::onlineHelp, QKeySequence::HelpContents); - help_menu->addAction(tr("About &Qt"), qApp, &QApplication::aboutQt); -} - -void MainWindow::createDockWindows() { - messages_dock = new QDockWidget(tr("MESSAGES"), this); - messages_dock->setObjectName("MessagesPanel"); - messages_dock->setAllowedAreas(Qt::LeftDockWidgetArea | Qt::RightDockWidgetArea | Qt::TopDockWidgetArea | Qt::BottomDockWidgetArea); - messages_dock->setFeatures(QDockWidget::DockWidgetMovable | QDockWidget::DockWidgetFloatable | QDockWidget::DockWidgetClosable); - addDockWidget(Qt::LeftDockWidgetArea, messages_dock); - - video_dock = new QDockWidget("", this); - video_dock->setObjectName(tr("VideoPanel")); - video_dock->setAllowedAreas(Qt::LeftDockWidgetArea | Qt::RightDockWidgetArea); - video_dock->setFeatures(QDockWidget::DockWidgetMovable | QDockWidget::DockWidgetFloatable | QDockWidget::DockWidgetClosable); - addDockWidget(Qt::RightDockWidgetArea, video_dock); -} - -void MainWindow::createDockWidgets() { - messages_widget = new MessagesWidget(this); - messages_dock->setWidget(messages_widget); - - // right panel - charts_widget = new ChartsWidget(this); - QWidget *charts_container = new QWidget(this); - charts_layout = new QVBoxLayout(charts_container); - charts_layout->setContentsMargins(0, 0, 0, 0); - charts_layout->addWidget(charts_widget); - - // splitter between video and charts - video_splitter = new QSplitter(Qt::Vertical, this); - video_widget = new VideoWidget(this); - video_splitter->addWidget(video_widget); - QObject::connect(charts_widget, &ChartsWidget::rangeChanged, video_widget, &VideoWidget::updateTimeRange); - - video_splitter->addWidget(charts_container); - video_splitter->setStretchFactor(1, 1); - video_splitter->restoreState(settings.video_splitter_state); - video_splitter->handle(1)->setEnabled(!can->liveStreaming()); - video_dock->setWidget(video_splitter); - QObject::connect(charts_widget, &ChartsWidget::dock, this, &MainWindow::dockCharts); -} - -void MainWindow::createStatusBar() { - progress_bar = new QProgressBar(); - progress_bar->setRange(0, 100); - progress_bar->setTextVisible(true); - progress_bar->setFixedSize({300, 16}); - progress_bar->setVisible(false); - statusBar()->addWidget(new QLabel(tr("For Help, Press F1"))); - statusBar()->addPermanentWidget(progress_bar); - - statusBar()->addPermanentWidget(status_label = new QLabel(this)); - updateStatus(); -} - -void MainWindow::createShortcuts() { - auto shortcut = new QShortcut(QKeySequence(Qt::Key_Space), this, nullptr, nullptr, Qt::ApplicationShortcut); - QObject::connect(shortcut, &QShortcut::activated, []() { can->pause(!can->isPaused()); }); - // TODO: add more shortcuts here. -} - -void MainWindow::undoStackIndexChanged(int index) { - int count = UndoStack::instance()->count(); - if (count >= 0) { - QString command_text; - if (index == count) { - command_text = (count == prev_undostack_count ? "Redo " : "") + UndoStack::instance()->text(index - 1); - } else if (index < prev_undostack_index) { - command_text = tr("Undo %1").arg(UndoStack::instance()->text(index)); - } else if (index > prev_undostack_index) { - command_text = tr("Redo %1").arg(UndoStack::instance()->text(index - 1)); - } - statusBar()->showMessage(command_text, 2000); - } - prev_undostack_index = index; - prev_undostack_count = count; - autoSave(); - updateLoadSaveMenus(); -} - -void MainWindow::undoStackCleanChanged(bool clean) { - if (clean) { - prev_undostack_index = 0; - prev_undostack_count = 0; - } - setWindowModified(!clean); -} - -void MainWindow::DBCFileChanged() { - UndoStack::instance()->clear(); - updateLoadSaveMenus(); -} - -void MainWindow::openStream() { - AbstractStream *stream = nullptr; - StreamSelector dlg(&stream, this); - if (dlg.exec()) { - if (!dlg.dbcFile().isEmpty()) { - loadFile(dlg.dbcFile()); - } - stream->start(); - statusBar()->showMessage(tr("Route %1 loaded").arg(can->routeName()), 2000); - } -} - -void MainWindow::closeStream() { - AbstractStream *stream = new DummyStream(this); - stream->start(); - if (dbc()->nonEmptyDBCCount() > 0) { - emit dbc()->DBCFileChanged(); - } - statusBar()->showMessage(tr("stream closed")); -} - -void MainWindow::newFile(SourceSet s) { - closeFile(s); - dbc()->open(s, "", ""); -} - -void MainWindow::openFile(SourceSet s) { - remindSaveChanges(); - QString fn = QFileDialog::getOpenFileName(this, tr("Open File"), settings.last_dir, "DBC (*.dbc)"); - if (!fn.isEmpty()) { - loadFile(fn, s); - } -} - -void MainWindow::loadFile(const QString &fn, SourceSet s) { - if (!fn.isEmpty()) { - closeFile(s); - - QString dbc_fn = fn; - // Prompt user to load auto saved file if it exists. - if (QFile::exists(fn + AUTO_SAVE_EXTENSION)) { - auto ret = QMessageBox::question(this, tr("Auto saved DBC found"), tr("Auto saved DBC file from previous session found. Do you want to load it instead?")); - if (ret == QMessageBox::Yes) { - dbc_fn += AUTO_SAVE_EXTENSION; - UndoStack::instance()->resetClean(); // Force user to save on close so the auto saved file is not lost - } - } - - QString error; - if (dbc()->open(s, dbc_fn, &error)) { - updateRecentFiles(fn); - statusBar()->showMessage(tr("DBC File %1 loaded").arg(fn), 2000); - } else { - QMessageBox msg_box(QMessageBox::Warning, tr("Failed to load DBC file"), tr("Failed to parse DBC file %1").arg(fn)); - msg_box.setDetailedText(error); - msg_box.exec(); - } - } -} - -void MainWindow::openRecentFile() { - if (auto action = qobject_cast(sender())) { - loadFile(action->data().toString()); - } -} - -void MainWindow::loadDBCFromOpendbc(const QString &name) { - QString opendbc_file_path = QString("%1/%2.dbc").arg(OPENDBC_FILE_PATH, name); - loadFile(opendbc_file_path); -} - -void MainWindow::loadFromClipboard(SourceSet s, bool close_all) { - closeFile(s); - - QString dbc_str = QGuiApplication::clipboard()->text(); - QString error; - bool ret = dbc()->open(s, "", dbc_str, &error); - if (ret && dbc()->msgCount() > 0) { - QMessageBox::information(this, tr("Load From Clipboard"), tr("DBC Successfully Loaded!")); - } else { - QMessageBox msg_box(QMessageBox::Warning, tr("Failed to load DBC from clipboard"), tr("Make sure that you paste the text with correct format.")); - msg_box.setDetailedText(error); - msg_box.exec(); - } -} - -void MainWindow::changingStream() { - center_widget->clear(); - delete messages_widget; - delete video_splitter; -} - -void MainWindow::streamStarted() { - bool has_stream = dynamic_cast(can) == nullptr; - close_stream_act->setEnabled(has_stream); - tools_menu->setEnabled(has_stream); - createDockWidgets(); - - video_dock->setWindowTitle(can->routeName()); - if (can->liveStreaming() || video_splitter->sizes()[0] == 0) { - // display video at minimum size. - video_splitter->setSizes({1, 1}); - } - // Don't overwrite already loaded DBC - if (!dbc()->msgCount()) { - newFile(); - } - - QObject::connect(messages_widget, &MessagesWidget::msgSelectionChanged, center_widget, &CenterWidget::setMessage); - QObject::connect(can, &AbstractStream::eventsMerged, this, &MainWindow::eventsMerged); - QObject::connect(can, &AbstractStream::sourcesUpdated, this, &MainWindow::updateLoadSaveMenus); -} - -void MainWindow::eventsMerged() { - if (!can->liveStreaming() && std::exchange(car_fingerprint, can->carFingerprint()) != car_fingerprint) { - video_dock->setWindowTitle(tr("ROUTE: %1 FINGERPRINT: %2") - .arg(can->routeName()) - .arg(car_fingerprint.isEmpty() ? tr("Unknown Car") : car_fingerprint)); - // Don't overwrite already loaded DBC - if (!dbc()->msgCount() && !car_fingerprint.isEmpty()) { - auto dbc_name = fingerprint_to_dbc[car_fingerprint]; - if (dbc_name != QJsonValue::Undefined) { - // Prevent dialog that load autosaved file from blocking replay->start(). - QTimer::singleShot(0, this, [dbc_name, this]() { loadDBCFromOpendbc(dbc_name.toString()); }); - } - } - } -} - -void MainWindow::save() { - // Save all open DBC files - for (auto dbc_file : dbc()->allDBCFiles()) { - if (dbc_file->isEmpty()) continue; - saveFile(dbc_file); - } -} - -void MainWindow::saveAs() { - // Save as all open DBC files. Should not be called with more than 1 file open - for (auto dbc_file : dbc()->allDBCFiles()) { - if (dbc_file->isEmpty()) continue; - saveFileAs(dbc_file); - } -} - -void MainWindow::autoSave() { - if (!UndoStack::instance()->isClean()) { - for (auto dbc_file : dbc()->allDBCFiles()) { - if (!dbc_file->filename.isEmpty()) { - dbc_file->autoSave(); - } - } - } -} - -void MainWindow::cleanupAutoSaveFile() { - for (auto dbc_file : dbc()->allDBCFiles()) { - dbc_file->cleanupAutoSaveFile(); - } -} - -void MainWindow::closeFile(SourceSet s) { - remindSaveChanges(); - if (s == SOURCE_ALL) { - dbc()->closeAll(); - } else { - dbc()->close(s); - } -} - -void MainWindow::closeFile(DBCFile *dbc_file) { - assert(dbc_file != nullptr); - remindSaveChanges(); - dbc()->close(dbc_file); - // Ensure we always have at least one file open - if (dbc()->dbcCount() == 0) { - newFile(); - } -} - -void MainWindow::saveFile(DBCFile *dbc_file) { - assert(dbc_file != nullptr); - if (!dbc_file->filename.isEmpty()) { - dbc_file->save(); - updateLoadSaveMenus(); - UndoStack::instance()->setClean(); - statusBar()->showMessage(tr("File saved"), 2000); - } else if (!dbc_file->isEmpty()) { - saveFileAs(dbc_file); - } -} - -void MainWindow::saveFileAs(DBCFile *dbc_file) { - QString title = tr("Save File (bus: %1)").arg(toString(dbc()->sources(dbc_file))); - QString fn = QFileDialog::getSaveFileName(this, title, QDir::cleanPath(settings.last_dir + "/untitled.dbc"), tr("DBC (*.dbc)")); - if (!fn.isEmpty()) { - dbc_file->saveAs(fn); - UndoStack::instance()->setClean(); - statusBar()->showMessage(tr("File saved as %1").arg(fn), 2000); - updateRecentFiles(fn); - updateLoadSaveMenus(); - } -} - -void MainWindow::saveToClipboard() { - // Copy all open DBC files to clipboard. Should not be called with more than 1 file open - for (auto dbc_file : dbc()->allDBCFiles()) { - if (dbc_file->isEmpty()) continue; - saveFileToClipboard(dbc_file); - } -} - -void MainWindow::saveFileToClipboard(DBCFile *dbc_file) { - assert(dbc_file != nullptr); - QGuiApplication::clipboard()->setText(dbc_file->generateDBC()); - QMessageBox::information(this, tr("Copy To Clipboard"), tr("DBC Successfully copied!")); -} - -void MainWindow::updateLoadSaveMenus() { - int cnt = dbc()->nonEmptyDBCCount(); - save_dbc->setText(cnt > 1 ? tr("Save %1 DBCs...").arg(cnt) : tr("Save DBC...")); - save_dbc->setEnabled(cnt > 0); - save_dbc_as->setEnabled(cnt == 1); - - // TODO: Support clipboard for multiple files - copy_dbc_to_clipboard->setEnabled(cnt == 1); - - manage_dbcs_menu->clear(); - manage_dbcs_menu->setEnabled(dynamic_cast(can) == nullptr); - - for (int source : can->sources) { - if (source >= 64) continue; // Sent and blocked buses are handled implicitly - - SourceSet ss = {source, uint8_t(source + 128), uint8_t(source + 192)}; - - QMenu *bus_menu = new QMenu(this); - bus_menu->addAction(tr("New DBC File..."), [=]() { newFile(ss); }); - bus_menu->addAction(tr("Open DBC File..."), [=]() { openFile(ss); }); - bus_menu->addAction(tr("Load DBC From Clipboard..."), [=]() { loadFromClipboard(ss, false); }); - - // Show sub-menu for each dbc for this source. - QString file_name = "No DBCs loaded"; - if (auto dbc_file = dbc()->findDBCFile(source)) { - bus_menu->addSeparator(); - bus_menu->addAction(dbc_file->name() + " (" + toString(dbc()->sources(dbc_file)) + ")")->setEnabled(false); - bus_menu->addAction(tr("Save..."), [=]() { saveFile(dbc_file); }); - bus_menu->addAction(tr("Save As..."), [=]() { saveFileAs(dbc_file); }); - bus_menu->addAction(tr("Copy to Clipboard..."), [=]() { saveFileToClipboard(dbc_file); }); - bus_menu->addAction(tr("Remove from this bus..."), [=]() { closeFile(ss); }); - bus_menu->addAction(tr("Remove from all buses..."), [=]() { closeFile(dbc_file); }); - - file_name = dbc_file->name(); - } - - manage_dbcs_menu->addMenu(bus_menu); - bus_menu->setTitle(tr("Bus %1 (%2)").arg(source).arg(file_name)); - } - - QStringList title; - for (auto f : dbc()->allDBCFiles()) { - title.push_back(tr("(%1) %2").arg(toString(dbc()->sources(f)), f->name())); - } - setWindowFilePath(title.join(" | ")); -} - -void MainWindow::updateRecentFiles(const QString &fn) { - settings.recent_files.removeAll(fn); - settings.recent_files.prepend(fn); - while (settings.recent_files.size() > MAX_RECENT_FILES) { - settings.recent_files.removeLast(); - } - settings.last_dir = QFileInfo(fn).absolutePath(); - updateRecentFileActions(); -} - -void MainWindow::updateRecentFileActions() { - int num_recent_files = std::min(settings.recent_files.size(), MAX_RECENT_FILES); - - for (int i = 0; i < num_recent_files; ++i) { - QString text = tr("&%1 %2").arg(i + 1).arg(QFileInfo(settings.recent_files[i]).fileName()); - recent_files_acts[i]->setText(text); - recent_files_acts[i]->setData(settings.recent_files[i]); - recent_files_acts[i]->setVisible(true); - } - for (int i = num_recent_files; i < MAX_RECENT_FILES; ++i) { - recent_files_acts[i]->setVisible(false); - } - open_recent_menu->setEnabled(num_recent_files > 0); -} - -void MainWindow::remindSaveChanges() { - bool discard_changes = false; - while (!UndoStack::instance()->isClean() && !discard_changes) { - QString text = tr("You have unsaved changes. Press ok to save them, cancel to discard."); - int ret = (QMessageBox::question(this, tr("Unsaved Changes"), text, QMessageBox::Ok | QMessageBox::Cancel)); - if (ret == QMessageBox::Ok) { - save(); - } else { - discard_changes = true; - } - } - UndoStack::instance()->clear(); -} - -void MainWindow::updateDownloadProgress(uint64_t cur, uint64_t total, bool success) { - if (success && cur < total) { - progress_bar->setValue((cur / (double)total) * 100); - progress_bar->setFormat(tr("Downloading %p% (%1)").arg(formattedDataSize(total).c_str())); - progress_bar->show(); - } else { - progress_bar->hide(); - } -} - -void MainWindow::updateStatus() { - status_label->setText(tr("Cached Minutes:%1 FPS:%2").arg(settings.max_cached_minutes).arg(settings.fps)); -} - -void MainWindow::dockCharts(bool dock) { - if (dock && floating_window) { - floating_window->removeEventFilter(charts_widget); - charts_layout->insertWidget(0, charts_widget, 1); - floating_window->deleteLater(); - floating_window = nullptr; - } else if (!dock && !floating_window) { - floating_window = new QWidget(this); - floating_window->setWindowFlags(Qt::Window); - floating_window->setWindowTitle("Charts"); - floating_window->setLayout(new QVBoxLayout()); - floating_window->layout()->addWidget(charts_widget); - floating_window->installEventFilter(charts_widget); - floating_window->showMaximized(); - } -} - -void MainWindow::closeEvent(QCloseEvent *event) { - cleanupAutoSaveFile(); - remindSaveChanges(); - - installDownloadProgressHandler(nullptr); - qInstallMessageHandler(nullptr); - - if (floating_window) - floating_window->deleteLater(); - - // save states - settings.geometry = saveGeometry(); - settings.window_state = saveState(); - if (!can->liveStreaming()) { - settings.video_splitter_state = video_splitter->saveState(); - } - settings.message_header_state = messages_widget->saveHeaderState(); - - QWidget::closeEvent(event); -} - -void MainWindow::setOption() { - SettingsDlg dlg(this); - dlg.exec(); -} - -void MainWindow::findSimilarBits() { - FindSimilarBitsDlg *dlg = new FindSimilarBitsDlg(this); - QObject::connect(dlg, &FindSimilarBitsDlg::openMessage, messages_widget, &MessagesWidget::selectMessage); - dlg->show(); -} - -void MainWindow::findSignal() { - FindSignalDlg *dlg = new FindSignalDlg(this); - QObject::connect(dlg, &FindSignalDlg::openMessage, messages_widget, &MessagesWidget::selectMessage); - dlg->show(); -} - -void MainWindow::onlineHelp() { - if (auto help = findChild()) { - help->close(); - } else { - help = new HelpOverlay(this); - help->setGeometry(rect()); - help->show(); - help->raise(); - } -} - -void MainWindow::toggleFullScreen() { - if (isFullScreen()) { - menuBar()->show(); - statusBar()->show(); - showNormal(); - showMaximized(); - } else { - menuBar()->hide(); - statusBar()->hide(); - showFullScreen(); - } -} - -// HelpOverlay -HelpOverlay::HelpOverlay(MainWindow *parent) : QWidget(parent) { - setAttribute(Qt::WA_NoSystemBackground, true); - setAttribute(Qt::WA_TranslucentBackground, true); - setAttribute(Qt::WA_DeleteOnClose); - parent->installEventFilter(this); -} - -void HelpOverlay::paintEvent(QPaintEvent *event) { - QPainter painter(this); - painter.fillRect(rect(), QColor(0, 0, 0, 50)); - MainWindow *parent = (MainWindow *)parentWidget(); - drawHelpForWidget(painter, parent->findChild()); - drawHelpForWidget(painter, parent->findChild()); - drawHelpForWidget(painter, parent->findChild()); - drawHelpForWidget(painter, parent->findChild()); - drawHelpForWidget(painter, parent->findChild()); -} - -void HelpOverlay::drawHelpForWidget(QPainter &painter, QWidget *w) { - if (w && w->isVisible() && !w->whatsThis().isEmpty()) { - QPoint pt = mapFromGlobal(w->mapToGlobal(w->rect().center())); - if (rect().contains(pt)) { - QTextDocument document; - document.setHtml(w->whatsThis()); - QSize doc_size = document.size().toSize(); - QPoint topleft = {pt.x() - doc_size.width() / 2, pt.y() - doc_size.height() / 2}; - painter.translate(topleft); - painter.fillRect(QRect{{0, 0}, doc_size}, palette().toolTipBase()); - document.drawContents(&painter); - painter.translate(-topleft); - } - } -} - -bool HelpOverlay::eventFilter(QObject *obj, QEvent *event) { - if (obj == parentWidget() && event->type() == QEvent::Resize) { - QResizeEvent *resize_event = (QResizeEvent *)(event); - setGeometry(QRect{QPoint(0, 0), resize_event->size()}); - } - return false; -} - -void HelpOverlay::mouseReleaseEvent(QMouseEvent *event) { - close(); -} diff --git a/tools/cabana/mainwin.h b/tools/cabana/mainwin.h deleted file mode 100644 index 1a889b8..0000000 --- a/tools/cabana/mainwin.h +++ /dev/null @@ -1,117 +0,0 @@ -#pragma once - -#include -#include -#include -#include -#include -#include -#include -#include - -#include "tools/cabana/chart/chartswidget.h" -#include "tools/cabana/dbc/dbcmanager.h" -#include "tools/cabana/detailwidget.h" -#include "tools/cabana/messageswidget.h" -#include "tools/cabana/videowidget.h" -#include "tools/cabana/tools/findsimilarbits.h" - -class MainWindow : public QMainWindow { - Q_OBJECT - -public: - MainWindow(); - void dockCharts(bool dock); - void showStatusMessage(const QString &msg, int timeout = 0) { statusBar()->showMessage(msg, timeout); } - void loadFile(const QString &fn, SourceSet s = SOURCE_ALL); - ChartsWidget *charts_widget = nullptr; - -public slots: - void openStream(); - void closeStream(); - void changingStream(); - void streamStarted(); - - void newFile(SourceSet s = SOURCE_ALL); - void openFile(SourceSet s = SOURCE_ALL); - void openRecentFile(); - void loadDBCFromOpendbc(const QString &name); - void save(); - void saveAs(); - void saveToClipboard(); - -signals: - void showMessage(const QString &msg, int timeout); - void updateProgressBar(uint64_t cur, uint64_t total, bool success); - -protected: - void remindSaveChanges(); - void closeFile(SourceSet s = SOURCE_ALL); - void closeFile(DBCFile *dbc_file); - void saveFile(DBCFile *dbc_file); - void saveFileAs(DBCFile *dbc_file); - void saveFileToClipboard(DBCFile *dbc_file); - void loadFingerprints(); - void loadFromClipboard(SourceSet s = SOURCE_ALL, bool close_all = true); - void autoSave(); - void cleanupAutoSaveFile(); - void updateRecentFiles(const QString &fn); - void updateRecentFileActions(); - void createActions(); - void createDockWindows(); - void createStatusBar(); - void createShortcuts(); - void closeEvent(QCloseEvent *event) override; - void DBCFileChanged(); - void updateDownloadProgress(uint64_t cur, uint64_t total, bool success); - void setOption(); - void findSimilarBits(); - void findSignal(); - void undoStackCleanChanged(bool clean); - void undoStackIndexChanged(int index); - void onlineHelp(); - void toggleFullScreen(); - void updateStatus(); - void updateLoadSaveMenus(); - void createDockWidgets(); - void eventsMerged(); - - VideoWidget *video_widget = nullptr; - QDockWidget *video_dock; - QDockWidget *messages_dock; - MessagesWidget *messages_widget = nullptr; - CenterWidget *center_widget; - QWidget *floating_window = nullptr; - QVBoxLayout *charts_layout; - QProgressBar *progress_bar; - QLabel *status_label; - QJsonDocument fingerprint_to_dbc; - QStringList opendbc_names; - QSplitter *video_splitter = nullptr; - enum { MAX_RECENT_FILES = 15 }; - QAction *recent_files_acts[MAX_RECENT_FILES] = {}; - QMenu *open_recent_menu = nullptr; - QMenu *manage_dbcs_menu = nullptr; - QMenu *tools_menu = nullptr; - QAction *close_stream_act = nullptr; - QAction *save_dbc = nullptr; - QAction *save_dbc_as = nullptr; - QAction *copy_dbc_to_clipboard = nullptr; - QString car_fingerprint; - int prev_undostack_index = 0; - int prev_undostack_count = 0; - QByteArray default_state; - friend class OnlineHelp; -}; - -class HelpOverlay : public QWidget { - Q_OBJECT -public: - HelpOverlay(MainWindow *parent); - -protected: - void drawHelpForWidget(QPainter &painter, QWidget *w); - void paintEvent(QPaintEvent *event) override; - void mouseReleaseEvent(QMouseEvent *event) override; - bool eventFilter(QObject *obj, QEvent *event) override; -}; diff --git a/tools/cabana/messageswidget.cc b/tools/cabana/messageswidget.cc deleted file mode 100644 index aba655d..0000000 --- a/tools/cabana/messageswidget.cc +++ /dev/null @@ -1,442 +0,0 @@ -#include "tools/cabana/messageswidget.h" - -#include -#include - -#include -#include -#include -#include -#include -#include - -#include "tools/cabana/commands.h" - -MessagesWidget::MessagesWidget(QWidget *parent) : menu(new QMenu(this)), QWidget(parent) { - QVBoxLayout *main_layout = new QVBoxLayout(this); - main_layout->setContentsMargins(0, 0, 0, 0); - main_layout->setSpacing(0); - // toolbar - main_layout->addWidget(createToolBar()); - // message table - main_layout->addWidget(view = new MessageView(this)); - view->setItemDelegate(delegate = new MessageBytesDelegate(view, settings.multiple_lines_hex)); - view->setModel(model = new MessageListModel(this)); - view->setHeader(header = new MessageViewHeader(this)); - view->setSortingEnabled(true); - view->sortByColumn(MessageListModel::Column::NAME, Qt::AscendingOrder); - view->setAllColumnsShowFocus(true); - view->setEditTriggers(QAbstractItemView::NoEditTriggers); - view->setItemsExpandable(false); - view->setIndentation(0); - view->setRootIsDecorated(false); - view->setUniformRowHeights(!settings.multiple_lines_hex); - - // Must be called before setting any header parameters to avoid overriding - restoreHeaderState(settings.message_header_state); - header->setSectionsMovable(true); - header->setSectionResizeMode(MessageListModel::Column::DATA, QHeaderView::Fixed); - header->setStretchLastSection(true); - header->setContextMenuPolicy(Qt::CustomContextMenu); - - // suppress - QHBoxLayout *suppress_layout = new QHBoxLayout(); - suppress_layout->addWidget(suppress_add = new QPushButton("Suppress Highlighted")); - suppress_layout->addWidget(suppress_clear = new QPushButton()); - suppress_clear->setToolTip(tr("Clear suppressed")); - suppress_layout->addStretch(1); - QCheckBox *suppress_defined_signals = new QCheckBox(tr("Suppress Signals"), this); - suppress_defined_signals->setToolTip(tr("Suppress defined signals")); - suppress_defined_signals->setChecked(settings.suppress_defined_signals); - suppress_layout->addWidget(suppress_defined_signals); - main_layout->addLayout(suppress_layout); - - // signals/slots - QObject::connect(menu, &QMenu::aboutToShow, this, &MessagesWidget::menuAboutToShow); - QObject::connect(header, &MessageViewHeader::customContextMenuRequested, this, &MessagesWidget::headerContextMenuEvent); - QObject::connect(view->horizontalScrollBar(), &QScrollBar::valueChanged, header, &MessageViewHeader::updateHeaderPositions); - QObject::connect(suppress_defined_signals, &QCheckBox::stateChanged, can, &AbstractStream::suppressDefinedSignals); - QObject::connect(can, &AbstractStream::msgsReceived, model, &MessageListModel::msgsReceived); - QObject::connect(dbc(), &DBCManager::DBCFileChanged, model, &MessageListModel::dbcModified); - QObject::connect(UndoStack::instance(), &QUndoStack::indexChanged, model, &MessageListModel::dbcModified); - QObject::connect(model, &MessageListModel::modelReset, [this]() { - if (current_msg_id) { - selectMessage(*current_msg_id); - } - view->updateBytesSectionSize(); - updateTitle(); - }); - QObject::connect(view->selectionModel(), &QItemSelectionModel::currentChanged, [=](const QModelIndex ¤t, const QModelIndex &previous) { - if (current.isValid() && current.row() < model->items_.size()) { - const auto &id = model->items_[current.row()].id; - if (!current_msg_id || id != *current_msg_id) { - current_msg_id = id; - emit msgSelectionChanged(*current_msg_id); - } - } - }); - QObject::connect(suppress_add, &QPushButton::clicked, this, &MessagesWidget::suppressHighlighted); - QObject::connect(suppress_clear, &QPushButton::clicked, this, &MessagesWidget::suppressHighlighted); - suppressHighlighted(); - - setWhatsThis(tr(R"( - Message View
- - Byte color
- constant changing
- increasing
- decreasing - )")); -} - -QToolBar *MessagesWidget::createToolBar() { - QToolBar *toolbar = new QToolBar(this); - toolbar->setIconSize({12, 12}); - toolbar->addWidget(num_msg_label = new QLabel(this)); - num_msg_label->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Preferred); - - auto views_btn = toolbar->addAction(utils::icon("three-dots"), tr("View...")); - views_btn->setMenu(menu); - auto view_button = qobject_cast(toolbar->widgetForAction(views_btn)); - view_button->setPopupMode(QToolButton::InstantPopup); - view_button->setToolButtonStyle(Qt::ToolButtonIconOnly); - view_button->setStyleSheet("QToolButton::menu-indicator { image: none; }"); - return toolbar; -} - -void MessagesWidget::updateTitle() { - auto stats = std::accumulate( - model->items_.begin(), model->items_.end(), std::pair(), - [](const auto &pair, const auto &item) { - auto m = dbc()->msg(item.id); - return m ? std::make_pair(pair.first + 1, pair.second + m->sigs.size()) : pair; - }); - num_msg_label->setText(tr("%1 Messages (%2 DBC Messages, %3 Signals)") - .arg(model->items_.size()).arg(stats.first).arg(stats.second)); -} - -void MessagesWidget::selectMessage(const MessageId &msg_id) { - auto it = std::find_if(model->items_.cbegin(), model->items_.cend(), - [&msg_id](auto &item) { return item.id == msg_id; }); - if (it != model->items_.cend()) { - view->setCurrentIndex(model->index(std::distance(model->items_.cbegin(), it), 0)); - } -} - -void MessagesWidget::suppressHighlighted() { - if (sender() == suppress_add) { - size_t n = can->suppressHighlighted(); - suppress_clear->setText(tr("Clear (%1)").arg(n)); - suppress_clear->setEnabled(true); - } else { - can->clearSuppressed(); - suppress_clear->setText(tr("Clear")); - suppress_clear->setEnabled(false); - } -} - -void MessagesWidget::headerContextMenuEvent(const QPoint &pos) { - menu->exec(header->mapToGlobal(pos)); -} - -void MessagesWidget::menuAboutToShow() { - menu->clear(); - for (int i = 0; i < header->count(); ++i) { - int logical_index = header->logicalIndex(i); - auto action = menu->addAction(model->headerData(logical_index, Qt::Horizontal).toString(), - [=](bool checked) { header->setSectionHidden(logical_index, !checked); }); - action->setCheckable(true); - action->setChecked(!header->isSectionHidden(logical_index)); - // Can't hide the name column - action->setEnabled(logical_index > 0); - } - menu->addSeparator(); - auto action = menu->addAction(tr("Mutlti-Line bytes"), this, &MessagesWidget::setMultiLineBytes); - action->setCheckable(true); - action->setChecked(settings.multiple_lines_hex); -} - -void MessagesWidget::setMultiLineBytes(bool multi) { - settings.multiple_lines_hex = multi; - delegate->setMultipleLines(multi); - view->setUniformRowHeights(!multi); - view->updateBytesSectionSize(); - view->doItemsLayout(); -} - -// MessageListModel - -QVariant MessageListModel::headerData(int section, Qt::Orientation orientation, int role) const { - if (orientation == Qt::Horizontal && role == Qt::DisplayRole) { - switch (section) { - case Column::NAME: return tr("Name"); - case Column::SOURCE: return tr("Bus"); - case Column::ADDRESS: return tr("ID"); - case Column::NODE: return tr("Node"); - case Column::FREQ: return tr("Freq"); - case Column::COUNT: return tr("Count"); - case Column::DATA: return tr("Bytes"); - } - } - return {}; -} - -QVariant MessageListModel::data(const QModelIndex &index, int role) const { - if (!index.isValid() || index.row() >= items_.size()) return {}; - - auto getFreq = [](const CanData &d) { - if (d.freq > 0 && (can->currentSec() - d.ts - 1.0 / settings.fps) < (5.0 / d.freq)) { - return d.freq >= 0.95 ? QString::number(std::nearbyint(d.freq)) : QString::number(d.freq, 'f', 2); - } else { - return QStringLiteral("--"); - } - }; - - const auto &item = items_[index.row()]; - const auto &data = can->lastMessage(item.id); - if (role == Qt::DisplayRole) { - switch (index.column()) { - case Column::NAME: return item.name; - case Column::SOURCE: return item.id.source != INVALID_SOURCE ? QString::number(item.id.source) : "N/A"; - case Column::ADDRESS: return QString::number(item.id.address, 16); - case Column::NODE: return item.node; - case Column::FREQ: return item.id.source != INVALID_SOURCE ? getFreq(data) : "N/A"; - case Column::COUNT: return item.id.source != INVALID_SOURCE ? QString::number(data.count) : "N/A"; - case Column::DATA: return item.id.source != INVALID_SOURCE ? "" : "N/A"; - } - } else if (role == ColorsRole) { - return QVariant::fromValue((void*)(&data.colors)); - } else if (role == BytesRole && index.column() == Column::DATA && item.id.source != INVALID_SOURCE) { - return QVariant::fromValue((void*)(&data.dat)); - } else if (role == Qt::ToolTipRole && index.column() == Column::NAME) { - auto msg = dbc()->msg(item.id); - auto tooltip = item.name; - if (msg && !msg->comment.isEmpty()) tooltip += "
" + msg->comment + ""; - return tooltip; - } - return {}; -} - -void MessageListModel::setFilterStrings(const QMap &filters) { - filters_ = filters; - filterAndSort(); -} - -void MessageListModel::dbcModified() { - dbc_messages_.clear(); - for (const auto &[_, m] : dbc()->getMessages(-1)) { - dbc_messages_.insert(MessageId{.source = INVALID_SOURCE, .address = m.address}); - } - filterAndSort(); -} - -void MessageListModel::sortItems(std::vector &items) { - auto do_sort = [order = sort_order](std::vector &m, auto proj) { - std::stable_sort(m.begin(), m.end(), [order, proj = std::move(proj)](auto &l, auto &r) { - return order == Qt::AscendingOrder ? proj(l) < proj(r) : proj(l) > proj(r); - }); - }; - switch (sort_column) { - case Column::NAME: do_sort(items, [](auto &item) { return std::tie(item.name, item.id); }); break; - case Column::SOURCE: do_sort(items, [](auto &item) { return std::tie(item.id.source, item.id); }); break; - case Column::ADDRESS: do_sort(items, [](auto &item) { return std::tie(item.id.address, item.id);}); break; - case Column::NODE: do_sort(items, [](auto &item) { return std::tie(item.node, item.id);}); break; - case Column::FREQ: do_sort(items, [](auto &item) { return std::make_pair(can->lastMessage(item.id).freq, item.id); }); break; - case Column::COUNT: do_sort(items, [](auto &item) { return std::make_pair(can->lastMessage(item.id).count, item.id); }); break; - } -} - -static bool parseRange(const QString &filter, uint32_t value, int base = 10) { - // Parse out filter string into a range (e.g. "1" -> {1, 1}, "1-3" -> {1, 3}, "1-" -> {1, inf}) - unsigned int min = std::numeric_limits::min(); - unsigned int max = std::numeric_limits::max(); - auto s = filter.split('-'); - bool ok = s.size() >= 1 && s.size() <= 2; - if (ok && !s[0].isEmpty()) min = s[0].toUInt(&ok, base); - if (ok && s.size() == 1) { - max = min; - } else if (ok && s.size() == 2 && !s[1].isEmpty()) { - max = s[1].toUInt(&ok, base); - } - return ok && value >= min && value <= max; -} - -bool MessageListModel::match(const MessageListModel::Item &item) { - if (filters_.isEmpty()) - return true; - - bool match = true; - const auto &data = can->lastMessage(item.id); - for (auto it = filters_.cbegin(); it != filters_.cend() && match; ++it) { - const QString &txt = it.value(); - switch (it.key()) { - case Column::NAME: { - match = item.name.contains(txt, Qt::CaseInsensitive); - if (!match) { - const auto m = dbc()->msg(item.id); - match = m && std::any_of(m->sigs.cbegin(), m->sigs.cend(), - [&txt](const auto &s) { return s->name.contains(txt, Qt::CaseInsensitive); }); - } - break; - } - case Column::SOURCE: - match = parseRange(txt, item.id.source); - break; - case Column::ADDRESS: - match = QString::number(item.id.address, 16).contains(txt, Qt::CaseInsensitive); - match = match || parseRange(txt, item.id.address, 16); - break; - case Column::NODE: - match = item.node.contains(txt, Qt::CaseInsensitive); - break; - case Column::FREQ: - // TODO: Hide stale messages? - match = parseRange(txt, data.freq); - break; - case Column::COUNT: - match = parseRange(txt, data.count); - break; - case Column::DATA: - match = utils::toHex(data.dat).contains(txt, Qt::CaseInsensitive); - break; - } - } - return match; -} - -void MessageListModel::filterAndSort() { - // merge CAN and DBC messages - std::vector all_messages; - all_messages.reserve(can->lastMessages().size() + dbc_messages_.size()); - auto dbc_msgs = dbc_messages_; - for (const auto &[id, m] : can->lastMessages()) { - all_messages.push_back(id); - dbc_msgs.erase(MessageId{.source = INVALID_SOURCE, .address = id.address}); - } - all_messages.insert(all_messages.end(), dbc_msgs.begin(), dbc_msgs.end()); - - // filter and sort - std::vector items; - for (const auto &id : all_messages) { - auto msg = dbc()->msg(id); - Item item = {.id = id, - .name = msg ? msg->name : UNTITLED, - .node = msg ? msg->transmitter : QString()}; - if (match(item)) - items.emplace_back(item); - } - sortItems(items); - - if (items_ != items) { - beginResetModel(); - items_ = std::move(items); - endResetModel(); - } -} - -void MessageListModel::msgsReceived(const std::set *new_msgs, bool has_new_ids) { - if (has_new_ids || filters_.contains(Column::FREQ) || filters_.contains(Column::COUNT) || filters_.contains(Column::DATA)) { - filterAndSort(); - } - for (int i = 0; i < items_.size(); ++i) { - if (!new_msgs || new_msgs->count(items_[i].id)) { - for (int col = Column::FREQ; col < columnCount(); ++col) - emit dataChanged(index(i, col), index(i, col), {Qt::DisplayRole}); - } - } -} - -void MessageListModel::sort(int column, Qt::SortOrder order) { - if (column != Column::DATA) { - sort_column = column; - sort_order = order; - filterAndSort(); - } -} - -// MessageView - -void MessageView::drawRow(QPainter *painter, const QStyleOptionViewItem &option, const QModelIndex &index) const { - QTreeView::drawRow(painter, option, index); - const int gridHint = style()->styleHint(QStyle::SH_Table_GridLineColor, &option, this); - const QColor gridColor = QColor::fromRgba(static_cast(gridHint)); - QPen old_pen = painter->pen(); - painter->setPen(gridColor); - painter->drawLine(option.rect.left(), option.rect.bottom(), option.rect.right(), option.rect.bottom()); - - auto y = option.rect.y(); - painter->translate(visualRect(model()->index(0, 0)).x() - indentation() - .5, -.5); - for (int i = 0; i < header()->count(); ++i) { - painter->translate(header()->sectionSize(header()->logicalIndex(i)), 0); - painter->drawLine(0, y, 0, y + option.rect.height()); - } - painter->setPen(old_pen); - painter->resetTransform(); -} - -void MessageView::dataChanged(const QModelIndex &topLeft, const QModelIndex &bottomRight, const QVector &roles) { - // Bypass the slow call to QTreeView::dataChanged. - // QTreeView::dataChanged will invalidate the height cache and that's what we don't need in MessageView. - QAbstractItemView::dataChanged(topLeft, bottomRight, roles); -} - -void MessageView::updateBytesSectionSize() { - auto delegate = ((MessageBytesDelegate *)itemDelegate()); - int max_bytes = 8; - if (!delegate->multipleLines()) { - for (const auto &[_, m] : can->lastMessages()) { - max_bytes = std::max(max_bytes, m.dat.size()); - } - } - header()->resizeSection(MessageListModel::Column::DATA, delegate->sizeForBytes(max_bytes).width()); -} - -// MessageViewHeader - -MessageViewHeader::MessageViewHeader(QWidget *parent) : QHeaderView(Qt::Horizontal, parent) { - QObject::connect(this, &QHeaderView::sectionResized, this, &MessageViewHeader::updateHeaderPositions); - QObject::connect(this, &QHeaderView::sectionMoved, this, &MessageViewHeader::updateHeaderPositions); -} - -void MessageViewHeader::updateFilters() { - QMap filters; - for (int i = 0; i < count(); i++) { - if (editors[i] && !editors[i]->text().isEmpty()) { - filters[i] = editors[i]->text(); - } - } - qobject_cast(model())->setFilterStrings(filters); -} - -void MessageViewHeader::updateHeaderPositions() { - QSize sz = QHeaderView::sizeHint(); - for (int i = 0; i < count(); i++) { - if (editors[i]) { - int h = editors[i]->sizeHint().height(); - editors[i]->setGeometry(sectionViewportPosition(i), sz.height(), sectionSize(i), h); - editors[i]->setHidden(isSectionHidden(i)); - } - } -} - -void MessageViewHeader::updateGeometries() { - for (int i = 0; i < count(); i++) { - if (!editors[i]) { - QString column_name = model()->headerData(i, Qt::Horizontal, Qt::DisplayRole).toString(); - editors[i] = new QLineEdit(this); - editors[i]->setClearButtonEnabled(true); - editors[i]->setPlaceholderText(tr("Filter %1").arg(column_name)); - - QObject::connect(editors[i], &QLineEdit::textChanged, this, &MessageViewHeader::updateFilters); - } - } - setViewportMargins(0, 0, 0, editors[0] ? editors[0]->sizeHint().height() : 0); - - QHeaderView::updateGeometries(); - updateHeaderPositions(); -} - -QSize MessageViewHeader::sizeHint() const { - QSize sz = QHeaderView::sizeHint(); - return editors[0] ? QSize(sz.width(), sz.height() + editors[0]->height() + 1) : sz; -} diff --git a/tools/cabana/messageswidget.h b/tools/cabana/messageswidget.h deleted file mode 100644 index 4f54941..0000000 --- a/tools/cabana/messageswidget.h +++ /dev/null @@ -1,116 +0,0 @@ -#pragma once - -#include -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include - -#include "tools/cabana/dbc/dbcmanager.h" -#include "tools/cabana/streams/abstractstream.h" - -class MessageListModel : public QAbstractTableModel { -Q_OBJECT - -public: - enum Column { - NAME = 0, - SOURCE, - ADDRESS, - NODE, - FREQ, - COUNT, - DATA, - }; - - MessageListModel(QObject *parent) : QAbstractTableModel(parent) {} - QVariant headerData(int section, Qt::Orientation orientation, int role = Qt::DisplayRole) const override; - int columnCount(const QModelIndex &parent = QModelIndex()) const override { return Column::DATA + 1; } - QVariant data(const QModelIndex &index, int role = Qt::DisplayRole) const; - int rowCount(const QModelIndex &parent = QModelIndex()) const override { return items_.size(); } - void sort(int column, Qt::SortOrder order = Qt::AscendingOrder) override; - void setFilterStrings(const QMap &filters); - void msgsReceived(const std::set *new_msgs, bool has_new_ids); - void filterAndSort(); - void dbcModified(); - - struct Item { - MessageId id; - QString name; - QString node; - bool operator==(const Item &other) const { - return id == other.id && name == other.name && node == other.node; - } - }; - std::vector items_; - -private: - void sortItems(std::vector &items); - bool match(const MessageListModel::Item &id); - - QMap filters_; - std::set dbc_messages_; - int sort_column = 0; - Qt::SortOrder sort_order = Qt::AscendingOrder; -}; - -class MessageView : public QTreeView { - Q_OBJECT -public: - MessageView(QWidget *parent) : QTreeView(parent) {} - void drawRow(QPainter *painter, const QStyleOptionViewItem &option, const QModelIndex &index) const override; - void drawBranches(QPainter *painter, const QRect &rect, const QModelIndex &index) const override {} - void dataChanged(const QModelIndex &topLeft, const QModelIndex &bottomRight, const QVector &roles = QVector()) override; - void updateBytesSectionSize(); -}; - -class MessageViewHeader : public QHeaderView { - // https://stackoverflow.com/a/44346317 - Q_OBJECT -public: - MessageViewHeader(QWidget *parent); - void updateHeaderPositions(); - void updateGeometries() override; - QSize sizeHint() const override; - void updateFilters(); - - QMap editors; -}; - -class MessagesWidget : public QWidget { - Q_OBJECT - -public: - MessagesWidget(QWidget *parent); - void selectMessage(const MessageId &message_id); - QByteArray saveHeaderState() const { return view->header()->saveState(); } - bool restoreHeaderState(const QByteArray &state) const { return view->header()->restoreState(state); } - void suppressHighlighted(); - -signals: - void msgSelectionChanged(const MessageId &message_id); - -protected: - QToolBar *createToolBar(); - void headerContextMenuEvent(const QPoint &pos); - void menuAboutToShow(); - void setMultiLineBytes(bool multi); - void updateTitle(); - - MessageView *view; - MessageViewHeader *header; - MessageBytesDelegate *delegate; - std::optional current_msg_id; - MessageListModel *model; - QPushButton *suppress_add; - QPushButton *suppress_clear; - QLabel *num_msg_label; - QMenu *menu; -}; diff --git a/tools/cabana/settings.cc b/tools/cabana/settings.cc deleted file mode 100644 index 17de0a1..0000000 --- a/tools/cabana/settings.cc +++ /dev/null @@ -1,139 +0,0 @@ -#include "tools/cabana/settings.h" - -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include "tools/cabana/util.h" - -Settings settings; - -template -void settings_op(SettingOperation op) { - QSettings s("cabana"); - op(s, "absolute_time", settings.absolute_time); - op(s, "fps", settings.fps); - op(s, "max_cached_minutes", settings.max_cached_minutes); - op(s, "chart_height", settings.chart_height); - op(s, "chart_range", settings.chart_range); - op(s, "chart_column_count", settings.chart_column_count); - op(s, "last_dir", settings.last_dir); - op(s, "last_route_dir", settings.last_route_dir); - op(s, "window_state", settings.window_state); - op(s, "geometry", settings.geometry); - op(s, "video_splitter_state", settings.video_splitter_state); - op(s, "recent_files", settings.recent_files); - op(s, "message_header_state", settings.message_header_state); - op(s, "chart_series_type", settings.chart_series_type); - op(s, "theme", settings.theme); - op(s, "sparkline_range", settings.sparkline_range); - op(s, "multiple_lines_hex", settings.multiple_lines_hex); - op(s, "log_livestream", settings.log_livestream); - op(s, "log_path", settings.log_path); - op(s, "drag_direction", (int &)settings.drag_direction); - op(s, "suppress_defined_signals", settings.suppress_defined_signals); -} - -Settings::Settings() { - last_dir = last_route_dir = QDir::homePath(); - log_path = QStandardPaths::writableLocation(QStandardPaths::HomeLocation) + "/cabana_live_stream/"; - settings_op([](QSettings &s, const QString &key, auto &value) { - if (auto v = s.value(key); v.canConvert>()) - value = v.value>(); - }); -} - -Settings::~Settings() { - settings_op([](QSettings &s, const QString &key, auto &v) { s.setValue(key, v); }); -} - -// SettingsDlg - -SettingsDlg::SettingsDlg(QWidget *parent) : QDialog(parent) { - setWindowTitle(tr("Settings")); - QVBoxLayout *main_layout = new QVBoxLayout(this); - QGroupBox *groupbox = new QGroupBox("General"); - QFormLayout *form_layout = new QFormLayout(groupbox); - - form_layout->addRow(tr("Color Theme"), theme = new QComboBox(this)); - theme->setToolTip(tr("You may need to restart cabana after changes theme")); - theme->addItems({tr("Automatic"), tr("Light"), tr("Dark")}); - theme->setCurrentIndex(settings.theme); - - form_layout->addRow("FPS", fps = new QSpinBox(this)); - fps->setRange(10, 100); - fps->setSingleStep(10); - fps->setValue(settings.fps); - - form_layout->addRow(tr("Max Cached Minutes"), cached_minutes = new QSpinBox(this)); - cached_minutes->setRange(5, 60); - cached_minutes->setSingleStep(1); - cached_minutes->setValue(settings.max_cached_minutes); - main_layout->addWidget(groupbox); - - groupbox = new QGroupBox("New Signal Settings"); - form_layout = new QFormLayout(groupbox); - form_layout->addRow(tr("Drag Direction"), drag_direction = new QComboBox(this)); - drag_direction->addItems({tr("MSB First"), tr("LSB First"), tr("Always Little Endian"), tr("Always Big Endian")}); - drag_direction->setCurrentIndex(settings.drag_direction); - main_layout->addWidget(groupbox); - - groupbox = new QGroupBox("Chart"); - form_layout = new QFormLayout(groupbox); - form_layout->addRow(tr("Default Series Type"), chart_series_type = new QComboBox(this)); - chart_series_type->addItems({tr("Line"), tr("Step Line"), tr("Scatter")}); - chart_series_type->setCurrentIndex(settings.chart_series_type); - - form_layout->addRow(tr("Chart Height"), chart_height = new QSpinBox(this)); - chart_height->setRange(100, 500); - chart_height->setSingleStep(10); - chart_height->setValue(settings.chart_height); - main_layout->addWidget(groupbox); - - log_livestream = new QGroupBox(tr("Enable live stream logging"), this); - log_livestream->setCheckable(true); - QHBoxLayout *path_layout = new QHBoxLayout(log_livestream); - path_layout->addWidget(log_path = new QLineEdit(settings.log_path, this)); - log_path->setReadOnly(true); - auto browse_btn = new QPushButton(tr("B&rowse...")); - path_layout->addWidget(browse_btn); - main_layout->addWidget(log_livestream); - - auto buttonBox = new QDialogButtonBox(QDialogButtonBox::Ok | QDialogButtonBox::Cancel); - main_layout->addWidget(buttonBox); - setFixedSize(400, sizeHint().height()); - - QObject::connect(browse_btn, &QPushButton::clicked, [this]() { - QString fn = QFileDialog::getExistingDirectory( - this, tr("Log File Location"), - QStandardPaths::writableLocation(QStandardPaths::HomeLocation), - QFileDialog::ShowDirsOnly | QFileDialog::DontResolveSymlinks); - if (!fn.isEmpty()) { - log_path->setText(fn); - } - }); - QObject::connect(buttonBox, &QDialogButtonBox::rejected, this, &QDialog::reject); - QObject::connect(buttonBox, &QDialogButtonBox::accepted, this, &SettingsDlg::save); -} - -void SettingsDlg::save() { - if (std::exchange(settings.theme, theme->currentIndex()) != settings.theme) { - // set theme before emit changed - utils::setTheme(settings.theme); - } - settings.fps = fps->value(); - settings.max_cached_minutes = cached_minutes->value(); - settings.chart_series_type = chart_series_type->currentIndex(); - settings.chart_height = chart_height->value(); - settings.log_livestream = log_livestream->isChecked(); - settings.log_path = log_path->text(); - settings.drag_direction = (Settings::DragDirection)drag_direction->currentIndex(); - emit settings.changed(); - QDialog::accept(); -} diff --git a/tools/cabana/settings.h b/tools/cabana/settings.h deleted file mode 100644 index e75c519..0000000 --- a/tools/cabana/settings.h +++ /dev/null @@ -1,67 +0,0 @@ -#pragma once - -#include -#include -#include -#include -#include -#include - -#define LIGHT_THEME 1 -#define DARK_THEME 2 - -class Settings : public QObject { - Q_OBJECT - -public: - enum DragDirection { - MsbFirst, - LsbFirst, - AlwaysLE, - AlwaysBE, - }; - - Settings(); - ~Settings(); - - bool absolute_time = false; - int fps = 10; - int max_cached_minutes = 30; - int chart_height = 200; - int chart_column_count = 1; - int chart_range = 3 * 60; // 3 minutes - int chart_series_type = 0; - int theme = 0; - int sparkline_range = 15; // 15 seconds - bool multiple_lines_hex = false; - bool log_livestream = true; - bool suppress_defined_signals = false; - QString log_path; - QString last_dir; - QString last_route_dir; - QByteArray geometry; - QByteArray video_splitter_state; - QByteArray window_state; - QStringList recent_files; - QByteArray message_header_state; - DragDirection drag_direction = MsbFirst; - -signals: - void changed(); -}; - -class SettingsDlg : public QDialog { -public: - SettingsDlg(QWidget *parent); - void save(); - QSpinBox *fps; - QSpinBox *cached_minutes; - QSpinBox *chart_height; - QComboBox *chart_series_type; - QComboBox *theme; - QGroupBox *log_livestream; - QLineEdit *log_path; - QComboBox *drag_direction; -}; - -extern Settings settings; diff --git a/tools/cabana/signalview.cc b/tools/cabana/signalview.cc deleted file mode 100644 index 7eb647b..0000000 --- a/tools/cabana/signalview.cc +++ /dev/null @@ -1,727 +0,0 @@ -#include "tools/cabana/signalview.h" - -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include "tools/cabana/commands.h" - -// SignalModel - -static QString signalTypeToString(cabana::Signal::Type type) { - if (type == cabana::Signal::Type::Multiplexor) return "Multiplexor Signal"; - else if (type == cabana::Signal::Type::Multiplexed) return "Multiplexed Signal"; - else return "Normal Signal"; -} - -SignalModel::SignalModel(QObject *parent) : root(new Item), QAbstractItemModel(parent) { - QObject::connect(dbc(), &DBCManager::DBCFileChanged, this, &SignalModel::refresh); - QObject::connect(dbc(), &DBCManager::msgUpdated, this, &SignalModel::handleMsgChanged); - QObject::connect(dbc(), &DBCManager::msgRemoved, this, &SignalModel::handleMsgChanged); - QObject::connect(dbc(), &DBCManager::signalAdded, this, &SignalModel::handleSignalAdded); - QObject::connect(dbc(), &DBCManager::signalUpdated, this, &SignalModel::handleSignalUpdated); - QObject::connect(dbc(), &DBCManager::signalRemoved, this, &SignalModel::handleSignalRemoved); -} - -void SignalModel::insertItem(SignalModel::Item *parent_item, int pos, const cabana::Signal *sig) { - Item *item = new Item{.sig = sig, .parent = parent_item, .title = sig->name, .type = Item::Sig}; - parent_item->children.insert(pos, item); - QString titles[]{"Name", "Size", "Receiver Nodes", "Little Endian", "Signed", "Offset", "Factor", "Type", - "Multiplex Value", "Extra Info", "Unit", "Comment", "Minimum Value", "Maximum Value", "Value Table"}; - for (int i = 0; i < std::size(titles); ++i) { - item->children.push_back(new Item{.sig = sig, .parent = item, .title = titles[i], .type = (Item::Type)(i + Item::Name)}); - } -} - -void SignalModel::setMessage(const MessageId &id) { - msg_id = id; - filter_str = ""; - refresh(); -} - -void SignalModel::setFilter(const QString &txt) { - filter_str = txt; - refresh(); -} - -void SignalModel::refresh() { - beginResetModel(); - root.reset(new SignalModel::Item); - if (auto msg = dbc()->msg(msg_id)) { - for (auto s : msg->getSignals()) { - if (filter_str.isEmpty() || s->name.contains(filter_str, Qt::CaseInsensitive)) { - insertItem(root.get(), root->children.size(), s); - } - } - } - endResetModel(); -} - -SignalModel::Item *SignalModel::getItem(const QModelIndex &index) const { - auto item = index.isValid() ? (SignalModel::Item *)index.internalPointer() : nullptr; - return item ? item : root.get(); -} - -int SignalModel::rowCount(const QModelIndex &parent) const { - if (parent.isValid() && parent.column() > 0) return 0; - - auto parent_item = getItem(parent); - int row_count = parent_item->children.size(); - if (parent_item->type == Item::Sig && !parent_item->extra_expanded) { - row_count -= (Item::Desc - Item::ExtraInfo); - } - return row_count; -} - -Qt::ItemFlags SignalModel::flags(const QModelIndex &index) const { - if (!index.isValid()) return Qt::NoItemFlags; - - auto item = getItem(index); - Qt::ItemFlags flags = Qt::ItemIsSelectable | Qt::ItemIsEnabled; - if (index.column() == 1 && item->type != Item::Sig && item->type != Item::ExtraInfo) { - flags |= (item->type == Item::Endian || item->type == Item::Signed) ? Qt::ItemIsUserCheckable : Qt::ItemIsEditable; - } - if (item->type == Item::MultiplexValue && item->sig->type != cabana::Signal::Type::Multiplexed) { - flags &= ~Qt::ItemIsEnabled; - } - return flags; -} - -int SignalModel::signalRow(const cabana::Signal *sig) const { - for (int i = 0; i < root->children.size(); ++i) { - if (root->children[i]->sig == sig) return i; - } - return -1; -} - -QModelIndex SignalModel::index(int row, int column, const QModelIndex &parent) const { - if (parent.isValid() && parent.column() != 0) return {}; - - auto parent_item = getItem(parent); - if (parent_item && row < parent_item->children.size()) { - return createIndex(row, column, parent_item->children[row]); - } - return {}; -} - -QModelIndex SignalModel::parent(const QModelIndex &index) const { - if (!index.isValid()) return {}; - Item *parent_item = getItem(index)->parent; - return !parent_item || parent_item == root.get() ? QModelIndex() : createIndex(parent_item->row(), 0, parent_item); -} - -QVariant SignalModel::data(const QModelIndex &index, int role) const { - if (index.isValid()) { - const Item *item = getItem(index); - if (role == Qt::DisplayRole || role == Qt::EditRole) { - if (index.column() == 0) { - return item->type == Item::Sig ? item->sig->name : item->title; - } else { - switch (item->type) { - case Item::Sig: return item->sig_val; - case Item::Name: return item->sig->name; - case Item::Size: return item->sig->size; - case Item::Node: return item->sig->receiver_name; - case Item::SignalType: return signalTypeToString(item->sig->type); - case Item::MultiplexValue: return item->sig->multiplex_value; - case Item::Offset: return doubleToString(item->sig->offset); - case Item::Factor: return doubleToString(item->sig->factor); - case Item::Unit: return item->sig->unit; - case Item::Comment: return item->sig->comment; - case Item::Min: return doubleToString(item->sig->min); - case Item::Max: return doubleToString(item->sig->max); - case Item::Desc: { - QStringList val_desc; - for (auto &[val, desc] : item->sig->val_desc) { - val_desc << QString("%1 \"%2\"").arg(val).arg(desc); - } - return val_desc.join(" "); - } - default: break; - } - } - } else if (role == Qt::CheckStateRole && index.column() == 1) { - if (item->type == Item::Endian) return item->sig->is_little_endian ? Qt::Checked : Qt::Unchecked; - if (item->type == Item::Signed) return item->sig->is_signed ? Qt::Checked : Qt::Unchecked; - } else if (role == Qt::DecorationRole && index.column() == 0 && item->type == Item::ExtraInfo) { - return utils::icon(item->parent->extra_expanded ? "chevron-compact-down" : "chevron-compact-up"); - } else if (role == Qt::ToolTipRole && item->type == Item::Sig) { - return (index.column() == 0) ? signalToolTip(item->sig) : QString(); - } - } - return {}; -} - -bool SignalModel::setData(const QModelIndex &index, const QVariant &value, int role) { - if (role != Qt::EditRole && role != Qt::CheckStateRole) return false; - - Item *item = getItem(index); - cabana::Signal s = *item->sig; - switch (item->type) { - case Item::Name: s.name = value.toString(); break; - case Item::Size: s.size = value.toInt(); break; - case Item::Node: s.receiver_name = value.toString().trimmed(); break; - case Item::SignalType: s.type = (cabana::Signal::Type)value.toInt(); break; - case Item::MultiplexValue: s.multiplex_value = value.toInt(); break; - case Item::Endian: s.is_little_endian = value.toBool(); break; - case Item::Signed: s.is_signed = value.toBool(); break; - case Item::Offset: s.offset = value.toDouble(); break; - case Item::Factor: s.factor = value.toDouble(); break; - case Item::Unit: s.unit = value.toString(); break; - case Item::Comment: s.comment = value.toString(); break; - case Item::Min: s.min = value.toDouble(); break; - case Item::Max: s.max = value.toDouble(); break; - case Item::Desc: s.val_desc = value.value(); break; - default: return false; - } - bool ret = saveSignal(item->sig, s); - emit dataChanged(index, index, {Qt::DisplayRole, Qt::EditRole, Qt::CheckStateRole}); - return ret; -} - -void SignalModel::showExtraInfo(const QModelIndex &index) { - auto item = getItem(index); - if (item->type == Item::ExtraInfo) { - if (!item->parent->extra_expanded) { - item->parent->extra_expanded = true; - beginInsertRows(index.parent(), Item::ExtraInfo - 2, Item::Desc - 2); - endInsertRows(); - } else { - item->parent->extra_expanded = false; - beginRemoveRows(index.parent(), Item::ExtraInfo - 2, Item::Desc - 2); - endRemoveRows(); - } - } -} - -bool SignalModel::saveSignal(const cabana::Signal *origin_s, cabana::Signal &s) { - auto msg = dbc()->msg(msg_id); - if (s.name != origin_s->name && msg->sig(s.name) != nullptr) { - QString text = tr("There is already a signal with the same name '%1'").arg(s.name); - QMessageBox::warning(nullptr, tr("Failed to save signal"), text); - return false; - } - - if (s.is_little_endian != origin_s->is_little_endian) { - s.start_bit = flipBitPos(s.start_bit); - } - UndoStack::push(new EditSignalCommand(msg_id, origin_s, s)); - return true; -} - -void SignalModel::handleMsgChanged(MessageId id) { - if (id.address == msg_id.address) { - refresh(); - } -} - -void SignalModel::handleSignalAdded(MessageId id, const cabana::Signal *sig) { - if (id == msg_id) { - if (filter_str.isEmpty()) { - int i = dbc()->msg(msg_id)->indexOf(sig); - beginInsertRows({}, i, i); - insertItem(root.get(), i, sig); - endInsertRows(); - } else if (sig->name.contains(filter_str, Qt::CaseInsensitive)) { - refresh(); - } - } -} - -void SignalModel::handleSignalUpdated(const cabana::Signal *sig) { - if (int row = signalRow(sig); row != -1) { - emit dataChanged(index(row, 0), index(row, 1), {Qt::DisplayRole, Qt::EditRole, Qt::CheckStateRole}); - - if (filter_str.isEmpty()) { - // move row when the order changes. - int to = dbc()->msg(msg_id)->indexOf(sig); - if (to != row) { - beginMoveRows({}, row, row, {}, to > row ? to + 1 : to); - root->children.move(row, to); - endMoveRows(); - } - } - } -} - -void SignalModel::handleSignalRemoved(const cabana::Signal *sig) { - if (int row = signalRow(sig); row != -1) { - beginRemoveRows({}, row, row); - delete root->children.takeAt(row); - endRemoveRows(); - } -} - -// SignalItemDelegate - -SignalItemDelegate::SignalItemDelegate(QObject *parent) : QStyledItemDelegate(parent) { - name_validator = new NameValidator(this); - node_validator = new QRegExpValidator(QRegExp("^\\w+(,\\w+)*$"), this); - double_validator = new DoubleValidator(this); - - label_font.setPointSize(8); - minmax_font.setPixelSize(10); -} - -QSize SignalItemDelegate::sizeHint(const QStyleOptionViewItem &option, const QModelIndex &index) const { - int width = option.widget->size().width() / 2; - if (index.column() == 0) { - int spacing = option.widget->style()->pixelMetric(QStyle::PM_TreeViewIndentation) + color_label_width + 8; - auto text = index.data(Qt::DisplayRole).toString(); - auto item = (SignalModel::Item *)index.internalPointer(); - if (item->type == SignalModel::Item::Sig && item->sig->type != cabana::Signal::Type::Normal) { - text += item->sig->type == cabana::Signal::Type::Multiplexor ? QString(" M ") : QString(" m%1 ").arg(item->sig->multiplex_value); - spacing += (option.widget->style()->pixelMetric(QStyle::PM_FocusFrameHMargin) + 1) * 2; - } - auto it = width_cache.find(text); - if (it == width_cache.end()) { - it = width_cache.insert(text, option.fontMetrics.width(text)); - } - width = std::min(option.widget->size().width() / 3.0, it.value() + spacing); - } - return {width, option.fontMetrics.height()}; -} - -void SignalItemDelegate::updateEditorGeometry(QWidget *editor, const QStyleOptionViewItem &option, const QModelIndex &index) const { - auto item = (SignalModel::Item *)index.internalPointer(); - if (editor && item->type == SignalModel::Item::Sig && index.column() == 1) { - QRect geom = option.rect; - geom.setLeft(geom.right() - editor->sizeHint().width()); - editor->setGeometry(geom); - button_size = geom.size(); - return; - } - QStyledItemDelegate::updateEditorGeometry(editor, option, index); -} - -void SignalItemDelegate::paint(QPainter *painter, const QStyleOptionViewItem &option, const QModelIndex &index) const { - auto item = (SignalModel::Item *)index.internalPointer(); - if (item && item->type == SignalModel::Item::Sig) { - painter->setRenderHint(QPainter::Antialiasing); - if (option.state & QStyle::State_Selected) { - painter->fillRect(option.rect, option.palette.brush(QPalette::Normal, QPalette::Highlight)); - } - - int h_margin = option.widget->style()->pixelMetric(QStyle::PM_FocusFrameHMargin) + 1; - int v_margin = option.widget->style()->pixelMetric(QStyle::PM_FocusFrameVMargin); - QRect r = option.rect.adjusted(h_margin, v_margin, -h_margin, -v_margin); - if (index.column() == 0) { - // color label - QPainterPath path; - QRect icon_rect{r.x(), r.y(), color_label_width, r.height()}; - path.addRoundedRect(icon_rect, 3, 3); - painter->setPen(item->highlight ? Qt::white : Qt::black); - painter->setFont(label_font); - painter->fillPath(path, item->sig->color.darker(item->highlight ? 125 : 0)); - painter->drawText(icon_rect, Qt::AlignCenter, QString::number(item->row() + 1)); - - r.setLeft(icon_rect.right() + h_margin * 2); - // multiplexer indicator - if (item->sig->type != cabana::Signal::Type::Normal) { - QString indicator = item->sig->type == cabana::Signal::Type::Multiplexor ? QString(" M ") : QString(" m%1 ").arg(item->sig->multiplex_value); - QRect indicator_rect{r.x(), r.y(), option.fontMetrics.width(indicator), r.height()}; - painter->setBrush(Qt::gray); - painter->setPen(Qt::NoPen); - painter->drawRoundedRect(indicator_rect, 3, 3); - painter->setPen(Qt::white); - painter->drawText(indicator_rect, Qt::AlignCenter, indicator); - r.setLeft(indicator_rect.right() + h_margin * 2); - } - - // name - auto text = option.fontMetrics.elidedText(index.data(Qt::DisplayRole).toString(), Qt::ElideRight, r.width()); - painter->setPen(option.palette.color(option.state & QStyle::State_Selected ? QPalette::HighlightedText : QPalette::Text)); - painter->setFont(option.font); - painter->drawText(r, option.displayAlignment, text); - } else if (index.column() == 1 && !item->sparkline.pixmap.isNull()) { - // sparkline - QSize sparkline_size = item->sparkline.pixmap.size() / item->sparkline.pixmap.devicePixelRatio(); - painter->drawPixmap(QRect(r.topLeft(), sparkline_size), item->sparkline.pixmap); - // min-max value - painter->setPen(option.palette.color(option.state & QStyle::State_Selected ? QPalette::HighlightedText : QPalette::Text)); - QRect rect = r.adjusted(sparkline_size.width() + 1, 0, 0, 0); - int value_adjust = 10; - if (!item->sparkline.isEmpty() && (item->highlight || option.state & QStyle::State_Selected)) { - painter->drawLine(rect.topLeft(), rect.bottomLeft()); - rect.adjust(5, -v_margin, 0, v_margin); - painter->setFont(minmax_font); - QString min = QString::number(item->sparkline.min_val); - QString max = QString::number(item->sparkline.max_val); - painter->drawText(rect, Qt::AlignLeft | Qt::AlignTop, max); - painter->drawText(rect, Qt::AlignLeft | Qt::AlignBottom, min); - QFontMetrics fm(minmax_font); - value_adjust = std::max(fm.width(min), fm.width(max)) + 5; - } else if (!item->sparkline.isEmpty() && item->sig->type == cabana::Signal::Type::Multiplexed) { - // display freq of multiplexed signal - painter->setFont(label_font); - QString freq = QString("%1 hz").arg(item->sparkline.freq(), 0, 'g', 2); - painter->drawText(rect.adjusted(5, 0, 0, 0), Qt::AlignLeft | Qt::AlignVCenter, freq); - value_adjust = QFontMetrics(label_font).width(freq) + 10; - } - // signal value - painter->setFont(option.font); - rect.adjust(value_adjust, 0, -button_size.width(), 0); - auto text = option.fontMetrics.elidedText(index.data(Qt::DisplayRole).toString(), Qt::ElideRight, rect.width()); - painter->drawText(rect, Qt::AlignRight | Qt::AlignVCenter, text); - } - } else { - QStyledItemDelegate::paint(painter, option, index); - } -} - -QWidget *SignalItemDelegate::createEditor(QWidget *parent, const QStyleOptionViewItem &option, const QModelIndex &index) const { - auto item = (SignalModel::Item *)index.internalPointer(); - if (item->type == SignalModel::Item::Name || item->type == SignalModel::Item::Node || item->type == SignalModel::Item::Offset || - item->type == SignalModel::Item::Factor || item->type == SignalModel::Item::MultiplexValue || - item->type == SignalModel::Item::Min || item->type == SignalModel::Item::Max) { - QLineEdit *e = new QLineEdit(parent); - e->setFrame(false); - if (item->type == SignalModel::Item::Name) e->setValidator(name_validator); - else if (item->type == SignalModel::Item::Node) e->setValidator(node_validator); - else e->setValidator(double_validator); - - if (item->type == SignalModel::Item::Name) { - QCompleter *completer = new QCompleter(dbc()->signalNames(), e); - completer->setCaseSensitivity(Qt::CaseInsensitive); - completer->setFilterMode(Qt::MatchContains); - e->setCompleter(completer); - } - return e; - } else if (item->type == SignalModel::Item::Size) { - QSpinBox *spin = new QSpinBox(parent); - spin->setFrame(false); - spin->setRange(1, 64); - return spin; - } else if (item->type == SignalModel::Item::SignalType) { - QComboBox *c = new QComboBox(parent); - c->addItem(signalTypeToString(cabana::Signal::Type::Normal), (int)cabana::Signal::Type::Normal); - if (!dbc()->msg(((SignalModel *)index.model())->msg_id)->multiplexor) { - c->addItem(signalTypeToString(cabana::Signal::Type::Multiplexor), (int)cabana::Signal::Type::Multiplexor); - } else if (item->sig->type != cabana::Signal::Type::Multiplexor) { - c->addItem(signalTypeToString(cabana::Signal::Type::Multiplexed), (int)cabana::Signal::Type::Multiplexed); - } - return c; - } else if (item->type == SignalModel::Item::Desc) { - ValueDescriptionDlg dlg(item->sig->val_desc, parent); - dlg.setWindowTitle(item->sig->name); - if (dlg.exec()) { - ((QAbstractItemModel *)index.model())->setData(index, QVariant::fromValue(dlg.val_desc)); - } - return nullptr; - } - return QStyledItemDelegate::createEditor(parent, option, index); -} - -void SignalItemDelegate::setModelData(QWidget *editor, QAbstractItemModel *model, const QModelIndex &index) const { - auto item = (SignalModel::Item *)index.internalPointer(); - if (item->type == SignalModel::Item::SignalType) { - model->setData(index, ((QComboBox*)editor)->currentData().toInt()); - return; - } - QStyledItemDelegate::setModelData(editor, model, index); -} - -// SignalView - -SignalView::SignalView(ChartsWidget *charts, QWidget *parent) : charts(charts), QFrame(parent) { - setFrameStyle(QFrame::StyledPanel | QFrame::Plain); - // title bar - QWidget *title_bar = new QWidget(this); - QHBoxLayout *hl = new QHBoxLayout(title_bar); - hl->addWidget(signal_count_lb = new QLabel()); - filter_edit = new QLineEdit(this); - QRegularExpression re("\\S+"); - filter_edit->setValidator(new QRegularExpressionValidator(re, this)); - filter_edit->setClearButtonEnabled(true); - filter_edit->setPlaceholderText(tr("Filter Signal")); - hl->addWidget(filter_edit); - hl->addStretch(1); - - // WARNING: increasing the maximum range can result in severe performance degradation. - // 30s is a reasonable value at present. - const int max_range = 30; // 30s - settings.sparkline_range = std::clamp(settings.sparkline_range, 1, max_range); - hl->addWidget(sparkline_label = new QLabel()); - hl->addWidget(sparkline_range_slider = new QSlider(Qt::Horizontal, this)); - sparkline_range_slider->setRange(1, max_range); - sparkline_range_slider->setValue(settings.sparkline_range); - sparkline_range_slider->setToolTip(tr("Sparkline time range")); - - auto collapse_btn = new ToolButton("dash-square", tr("Collapse All")); - collapse_btn->setIconSize({12, 12}); - hl->addWidget(collapse_btn); - - // tree view - tree = new TreeView(this); - tree->setModel(model = new SignalModel(this)); - tree->setItemDelegate(delegate = new SignalItemDelegate(this)); - tree->setFrameShape(QFrame::NoFrame); - tree->setHeaderHidden(true); - tree->setMouseTracking(true); - tree->setExpandsOnDoubleClick(false); - tree->setEditTriggers(QAbstractItemView::AllEditTriggers); - tree->header()->setSectionResizeMode(0, QHeaderView::ResizeToContents); - tree->header()->setStretchLastSection(true); - tree->setMinimumHeight(300); - - // Use a distinctive background for the whole row containing a QSpinBox or QLineEdit - QString nodeBgColor = palette().color(QPalette::AlternateBase).name(QColor::HexArgb); - tree->setStyleSheet(QString("QSpinBox{background-color:%1;border:none;} QLineEdit{background-color:%1;}").arg(nodeBgColor)); - - QVBoxLayout *main_layout = new QVBoxLayout(this); - main_layout->setContentsMargins(0, 0, 0, 0); - main_layout->setSpacing(0); - main_layout->addWidget(title_bar); - main_layout->addWidget(tree); - updateToolBar(); - - QObject::connect(filter_edit, &QLineEdit::textEdited, model, &SignalModel::setFilter); - QObject::connect(sparkline_range_slider, &QSlider::valueChanged, this, &SignalView::setSparklineRange); - QObject::connect(collapse_btn, &QPushButton::clicked, tree, &QTreeView::collapseAll); - QObject::connect(tree, &QAbstractItemView::clicked, this, &SignalView::rowClicked); - QObject::connect(tree, &QTreeView::viewportEntered, [this]() { emit highlight(nullptr); }); - QObject::connect(tree, &QTreeView::entered, [this](const QModelIndex &index) { emit highlight(model->getItem(index)->sig); }); - QObject::connect(model, &QAbstractItemModel::modelReset, this, &SignalView::rowsChanged); - QObject::connect(model, &QAbstractItemModel::rowsRemoved, this, &SignalView::rowsChanged); - QObject::connect(dbc(), &DBCManager::signalAdded, this, &SignalView::handleSignalAdded); - QObject::connect(dbc(), &DBCManager::signalUpdated, this, &SignalView::handleSignalUpdated); - QObject::connect(tree->verticalScrollBar(), &QScrollBar::valueChanged, [this]() { updateState(); }); - QObject::connect(tree->verticalScrollBar(), &QScrollBar::rangeChanged, [this]() { updateState(); }); - QObject::connect(can, &AbstractStream::msgsReceived, this, &SignalView::updateState); - QObject::connect(tree->header(), &QHeaderView::sectionResized, [this](int logicalIndex, int oldSize, int newSize) { - if (logicalIndex == 1) { - value_column_width = newSize; - updateState(); - } - }); - - setWhatsThis(tr(R"( - Signal view
- - )")); -} - -void SignalView::setMessage(const MessageId &id) { - max_value_width = 0; - filter_edit->clear(); - model->setMessage(id); -} - -void SignalView::rowsChanged() { - for (int i = 0; i < model->rowCount(); ++i) { - auto index = model->index(i, 1); - if (!tree->indexWidget(index)) { - QWidget *w = new QWidget(this); - QHBoxLayout *h = new QHBoxLayout(w); - int v_margin = style()->pixelMetric(QStyle::PM_FocusFrameVMargin); - int h_margin = style()->pixelMetric(QStyle::PM_FocusFrameHMargin); - h->setContentsMargins(0, v_margin, -h_margin, v_margin); - h->setSpacing(style()->pixelMetric(QStyle::PM_ToolBarItemSpacing)); - - auto remove_btn = new ToolButton("x", tr("Remove signal")); - auto plot_btn = new ToolButton("graph-up", ""); - plot_btn->setCheckable(true); - h->addWidget(plot_btn); - h->addWidget(remove_btn); - - tree->setIndexWidget(index, w); - auto sig = model->getItem(index)->sig; - QObject::connect(remove_btn, &QToolButton::clicked, [=]() { UndoStack::push(new RemoveSigCommand(model->msg_id, sig)); }); - QObject::connect(plot_btn, &QToolButton::clicked, [=](bool checked) { - emit showChart(model->msg_id, sig, checked, QGuiApplication::keyboardModifiers() & Qt::ShiftModifier); - }); - } - } - updateToolBar(); - updateChartState(); - updateState(); -} - -void SignalView::rowClicked(const QModelIndex &index) { - auto item = model->getItem(index); - if (item->type == SignalModel::Item::Sig) { - auto sig_index = model->index(index.row(), 0, index.parent()); - tree->setExpanded(sig_index, !tree->isExpanded(sig_index)); - } else if (item->type == SignalModel::Item::ExtraInfo) { - model->showExtraInfo(index); - } -} - -void SignalView::selectSignal(const cabana::Signal *sig, bool expand) { - if (int row = model->signalRow(sig); row != -1) { - auto idx = model->index(row, 0); - if (expand) { - tree->setExpanded(idx, !tree->isExpanded(idx)); - } - tree->scrollTo(idx, QAbstractItemView::PositionAtTop); - tree->setCurrentIndex(idx); - } -} - -void SignalView::updateChartState() { - int i = 0; - for (auto item : model->root->children) { - bool chart_opened = charts->hasSignal(model->msg_id, item->sig); - auto buttons = tree->indexWidget(model->index(i, 1))->findChildren(); - if (buttons.size() > 0) { - buttons[0]->setChecked(chart_opened); - buttons[0]->setToolTip(chart_opened ? tr("Close Plot") : tr("Show Plot\nSHIFT click to add to previous opened plot")); - } - ++i; - } -} - -void SignalView::signalHovered(const cabana::Signal *sig) { - auto &children = model->root->children; - for (int i = 0; i < children.size(); ++i) { - bool highlight = children[i]->sig == sig; - if (std::exchange(children[i]->highlight, highlight) != highlight) { - emit model->dataChanged(model->index(i, 0), model->index(i, 0), {Qt::DecorationRole}); - emit model->dataChanged(model->index(i, 1), model->index(i, 1), {Qt::DisplayRole}); - } - } -} - -void SignalView::updateToolBar() { - signal_count_lb->setText(tr("Signals: %1").arg(model->rowCount())); - sparkline_label->setText(utils::formatSeconds(settings.sparkline_range)); -} - -void SignalView::setSparklineRange(int value) { - settings.sparkline_range = value; - updateToolBar(); - updateState(); -} - -void SignalView::handleSignalAdded(MessageId id, const cabana::Signal *sig) { - if (id.address == model->msg_id.address) { - selectSignal(sig); - } -} - -void SignalView::handleSignalUpdated(const cabana::Signal *sig) { - if (int row = model->signalRow(sig); row != -1) - updateState(); -} - -void SignalView::updateState(const std::set *msgs) { - const auto &last_msg = can->lastMessage(model->msg_id); - if (model->rowCount() == 0 || (msgs && !msgs->count(model->msg_id)) || last_msg.dat.size() == 0) return; - - for (auto item : model->root->children) { - double value = 0; - if (item->sig->getValue(last_msg.dat.data(), last_msg.dat.size(), &value)) { - item->sig_val = item->sig->formatValue(value); - } - max_value_width = std::max(max_value_width, fontMetrics().width(item->sig_val)); - } - - QModelIndex top = tree->indexAt(QPoint(0, 0)); - if (top.isValid()) { - // update visible sparkline - int first_visible_row = top.parent().isValid() ? top.parent().row() + 1 : top.row(); - int last_visible_row = model->rowCount() - 1; - QModelIndex bottom = tree->indexAt(tree->viewport()->rect().bottomLeft()); - if (bottom.isValid()) { - last_visible_row = bottom.parent().isValid() ? bottom.parent().row() : bottom.row(); - } - - const static int min_max_width = QFontMetrics(delegate->minmax_font).width("-000.00") + 5; - int available_width = value_column_width - delegate->button_size.width(); - int value_width = std::min(max_value_width + min_max_width, available_width / 2); - QSize size(available_width - value_width, - delegate->button_size.height() - style()->pixelMetric(QStyle::PM_FocusFrameVMargin) * 2); - QFutureSynchronizer synchronizer; - for (int i = first_visible_row; i <= last_visible_row; ++i) { - auto item = model->getItem(model->index(i, 1)); - synchronizer.addFuture(QtConcurrent::run( - &item->sparkline, &Sparkline::update, model->msg_id, item->sig, last_msg.ts, settings.sparkline_range, size)); - } - } - - for (int i = 0; i < model->rowCount(); ++i) { - emit model->dataChanged(model->index(i, 1), model->index(i, 1), {Qt::DisplayRole}); - } -} - -void SignalView::resizeEvent(QResizeEvent* event) { - updateState(); - QFrame::resizeEvent(event); -} - -// ValueDescriptionDlg - -ValueDescriptionDlg::ValueDescriptionDlg(const ValueDescription &descriptions, QWidget *parent) : QDialog(parent) { - QHBoxLayout *toolbar_layout = new QHBoxLayout(); - QPushButton *add = new QPushButton(utils::icon("plus"), ""); - QPushButton *remove = new QPushButton(utils::icon("dash"), ""); - remove->setEnabled(false); - toolbar_layout->addWidget(add); - toolbar_layout->addWidget(remove); - toolbar_layout->addStretch(0); - - table = new QTableWidget(descriptions.size(), 2, this); - table->setItemDelegate(new Delegate(this)); - table->setHorizontalHeaderLabels({"Value", "Description"}); - table->horizontalHeader()->setStretchLastSection(true); - table->setSelectionBehavior(QAbstractItemView::SelectRows); - table->setSelectionMode(QAbstractItemView::SingleSelection); - table->setEditTriggers(QAbstractItemView::DoubleClicked | QAbstractItemView::EditKeyPressed); - table->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding); - - int row = 0; - for (auto &[val, desc] : descriptions) { - table->setItem(row, 0, new QTableWidgetItem(QString::number(val))); - table->setItem(row, 1, new QTableWidgetItem(desc)); - ++row; - } - - auto btn_box = new QDialogButtonBox(QDialogButtonBox::Ok | QDialogButtonBox::Cancel); - QVBoxLayout *main_layout = new QVBoxLayout(this); - main_layout->addLayout(toolbar_layout); - main_layout->addWidget(table); - main_layout->addWidget(btn_box); - setMinimumWidth(500); - - QObject::connect(btn_box, &QDialogButtonBox::accepted, this, &ValueDescriptionDlg::save); - QObject::connect(btn_box, &QDialogButtonBox::rejected, this, &QDialog::reject); - QObject::connect(add, &QPushButton::clicked, [this]() { - table->setRowCount(table->rowCount() + 1); - table->setItem(table->rowCount() - 1, 0, new QTableWidgetItem); - table->setItem(table->rowCount() - 1, 1, new QTableWidgetItem); - }); - QObject::connect(remove, &QPushButton::clicked, [this]() { table->removeRow(table->currentRow()); }); - QObject::connect(table, &QTableWidget::itemSelectionChanged, [=]() { - remove->setEnabled(table->currentRow() != -1); - }); -} - -void ValueDescriptionDlg::save() { - for (int i = 0; i < table->rowCount(); ++i) { - QString val = table->item(i, 0)->text().trimmed(); - QString desc = table->item(i, 1)->text().trimmed(); - if (!val.isEmpty() && !desc.isEmpty()) { - val_desc.push_back({val.toDouble(), desc}); - } - } - QDialog::accept(); -} - -QWidget *ValueDescriptionDlg::Delegate::createEditor(QWidget *parent, const QStyleOptionViewItem &option, const QModelIndex &index) const { - QLineEdit *edit = new QLineEdit(parent); - edit->setFrame(false); - if (index.column() == 0) { - edit->setValidator(new DoubleValidator(parent)); - } - return edit; -} diff --git a/tools/cabana/signalview.h b/tools/cabana/signalview.h deleted file mode 100644 index 30978f9..0000000 --- a/tools/cabana/signalview.h +++ /dev/null @@ -1,149 +0,0 @@ -#pragma once - -#include -#include - -#include -#include -#include -#include -#include -#include -#include - -#include "tools/cabana/chart/chartswidget.h" -#include "tools/cabana/chart/sparkline.h" - -class SignalModel : public QAbstractItemModel { - Q_OBJECT -public: - struct Item { - enum Type {Root, Sig, Name, Size, Node, Endian, Signed, Offset, Factor, SignalType, MultiplexValue, ExtraInfo, Unit, Comment, Min, Max, Desc }; - ~Item() { qDeleteAll(children); } - inline int row() { return parent->children.indexOf(this); } - - Type type = Type::Root; - Item *parent = nullptr; - QList children; - - const cabana::Signal *sig = nullptr; - QString title; - bool highlight = false; - bool extra_expanded = false; - QString sig_val = "-"; - Sparkline sparkline; - }; - - SignalModel(QObject *parent); - int rowCount(const QModelIndex &parent = QModelIndex()) const override; - int columnCount(const QModelIndex &parent = QModelIndex()) const override { return 2; } - QVariant data(const QModelIndex &index, int role = Qt::DisplayRole) const override; - QModelIndex index(int row, int column, const QModelIndex &parent = QModelIndex()) const override; - QModelIndex parent(const QModelIndex &index) const override; - Qt::ItemFlags flags(const QModelIndex &index) const override; - bool setData(const QModelIndex &index, const QVariant &value, int role = Qt::EditRole) override; - void setMessage(const MessageId &id); - void setFilter(const QString &txt); - bool saveSignal(const cabana::Signal *origin_s, cabana::Signal &s); - Item *getItem(const QModelIndex &index) const; - int signalRow(const cabana::Signal *sig) const; - void showExtraInfo(const QModelIndex &index); - -private: - void insertItem(SignalModel::Item *parent_item, int pos, const cabana::Signal *sig); - void handleSignalAdded(MessageId id, const cabana::Signal *sig); - void handleSignalUpdated(const cabana::Signal *sig); - void handleSignalRemoved(const cabana::Signal *sig); - void handleMsgChanged(MessageId id); - void refresh(); - - MessageId msg_id; - QString filter_str; - std::unique_ptr root; - friend class SignalView; - friend class SignalItemDelegate; -}; - -class ValueDescriptionDlg : public QDialog { -public: - ValueDescriptionDlg(const ValueDescription &descriptions, QWidget *parent); - ValueDescription val_desc; - -private: - struct Delegate : public QStyledItemDelegate { - Delegate(QWidget *parent) : QStyledItemDelegate(parent) {} - QWidget *createEditor(QWidget *parent, const QStyleOptionViewItem &option, const QModelIndex &index) const override; - }; - - void save(); - QTableWidget *table; -}; - -class SignalItemDelegate : public QStyledItemDelegate { -public: - SignalItemDelegate(QObject *parent); - void paint(QPainter *painter, const QStyleOptionViewItem &option, const QModelIndex &index) const override; - QSize sizeHint(const QStyleOptionViewItem &option, const QModelIndex &index) const override; - QWidget *createEditor(QWidget *parent, const QStyleOptionViewItem &option, const QModelIndex &index) const override; - void updateEditorGeometry(QWidget *editor, const QStyleOptionViewItem &option, const QModelIndex &index) const override; - void setModelData(QWidget *editor, QAbstractItemModel *model, const QModelIndex &index) const override; - - QValidator *name_validator, *double_validator, *node_validator; - QFont label_font, minmax_font; - const int color_label_width = 18; - mutable QSize button_size; - mutable QHash width_cache; -}; - -class SignalView : public QFrame { - Q_OBJECT - -public: - SignalView(ChartsWidget *charts, QWidget *parent); - void setMessage(const MessageId &id); - void signalHovered(const cabana::Signal *sig); - void updateChartState(); - void selectSignal(const cabana::Signal *sig, bool expand = false); - void rowClicked(const QModelIndex &index); - SignalModel *model = nullptr; - -signals: - void highlight(const cabana::Signal *sig); - void showChart(const MessageId &id, const cabana::Signal *sig, bool show, bool merge); - -private: - void rowsChanged(); - void resizeEvent(QResizeEvent* event) override; - void updateToolBar(); - void setSparklineRange(int value); - void handleSignalAdded(MessageId id, const cabana::Signal *sig); - void handleSignalUpdated(const cabana::Signal *sig); - void updateState(const std::set *msgs = nullptr); - - struct TreeView : public QTreeView { - TreeView(QWidget *parent) : QTreeView(parent) {} - void rowsInserted(const QModelIndex &parent, int start, int end) override { - ((SignalView *)parentWidget())->rowsChanged(); - // update widget geometries in QTreeView::rowsInserted - QTreeView::rowsInserted(parent, start, end); - } - void dataChanged(const QModelIndex &topLeft, const QModelIndex &bottomRight, const QVector &roles = QVector()) override { - // Bypass the slow call to QTreeView::dataChanged. - QAbstractItemView::dataChanged(topLeft, bottomRight, roles); - } - void leaveEvent(QEvent *event) override { - emit static_cast(parentWidget())->highlight(nullptr); - QTreeView::leaveEvent(event); - } - }; - int max_value_width = 0; - int value_column_width = 0; - TreeView *tree; - QLabel *sparkline_label; - QSlider *sparkline_range_slider; - QLineEdit *filter_edit; - ChartsWidget *charts; - QLabel *signal_count_lb; - SignalItemDelegate *delegate; - friend SignalItemDelegate; -}; diff --git a/tools/cabana/streams/abstractstream.cc b/tools/cabana/streams/abstractstream.cc deleted file mode 100644 index 8a20086..0000000 --- a/tools/cabana/streams/abstractstream.cc +++ /dev/null @@ -1,286 +0,0 @@ -#include "tools/cabana/streams/abstractstream.h" - -#include -#include - -#include "common/timing.h" -#include "tools/cabana/settings.h" - -static const int EVENT_NEXT_BUFFER_SIZE = 6 * 1024 * 1024; // 6MB - -AbstractStream *can = nullptr; - -StreamNotifier *StreamNotifier::instance() { - static StreamNotifier notifier; - return ¬ifier; -} - -AbstractStream::AbstractStream(QObject *parent) : QObject(parent) { - assert(parent != nullptr); - event_buffer_ = std::make_unique(EVENT_NEXT_BUFFER_SIZE); - - QObject::connect(this, &AbstractStream::privateUpdateLastMsgsSignal, this, &AbstractStream::updateLastMessages, Qt::QueuedConnection); - QObject::connect(this, &AbstractStream::seekedTo, this, &AbstractStream::updateLastMsgsTo); - QObject::connect(dbc(), &DBCManager::DBCFileChanged, this, &AbstractStream::updateMasks); - QObject::connect(dbc(), &DBCManager::maskUpdated, this, &AbstractStream::updateMasks); - QObject::connect(this, &AbstractStream::streamStarted, [this]() { - emit StreamNotifier::instance()->changingStream(); - delete can; - can = this; - emit StreamNotifier::instance()->streamStarted(); - }); -} - -void AbstractStream::updateMasks() { - std::lock_guard lk(mutex_); - masks_.clear(); - if (!settings.suppress_defined_signals) - return; - - for (const auto s : sources) { - for (const auto &[address, m] : dbc()->getMessages(s)) { - masks_[{.source = (uint8_t)s, .address = address}] = m.mask; - } - } - // clear bit change counts - for (auto &[id, m] : messages_) { - auto &mask = masks_[id]; - const int size = std::min(mask.size(), m.last_changes.size()); - for (int i = 0; i < size; ++i) { - for (int j = 0; j < 8; ++j) { - if (((mask[i] >> (7 - j)) & 1) != 0) m.last_changes[i].bit_change_counts[j] = 0; - } - } - } -} - -void AbstractStream::suppressDefinedSignals(bool suppress) { - settings.suppress_defined_signals = suppress; - updateMasks(); -} - -size_t AbstractStream::suppressHighlighted() { - std::lock_guard lk(mutex_); - size_t cnt = 0; - const double cur_ts = currentSec(); - for (auto &[_, m] : messages_) { - for (auto &last_change : m.last_changes) { - const double dt = cur_ts - last_change.ts; - if (dt < 2.0) { - last_change.suppressed = true; - } - // clear bit change counts - last_change.bit_change_counts.fill(0); - cnt += last_change.suppressed; - } - } - return cnt; -} - -void AbstractStream::clearSuppressed() { - std::lock_guard lk(mutex_); - for (auto &[_, m] : messages_) { - std::for_each(m.last_changes.begin(), m.last_changes.end(), [](auto &c) { c.suppressed = false; }); - } -} - -void AbstractStream::updateLastMessages() { - auto prev_src_size = sources.size(); - auto prev_msg_size = last_msgs.size(); - std::set msgs; - { - std::lock_guard lk(mutex_); - for (const auto &id : new_msgs_) { - const auto &can_data = messages_[id]; - current_sec_ = std::max(current_sec_, can_data.ts); - last_msgs[id] = can_data; - sources.insert(id.source); - } - msgs = std::move(new_msgs_); - } - - if (sources.size() != prev_src_size) { - updateMasks(); - emit sourcesUpdated(sources); - } - emit msgsReceived(&msgs, prev_msg_size != last_msgs.size()); -} - -void AbstractStream::updateEvent(const MessageId &id, double sec, const uint8_t *data, uint8_t size) { - std::lock_guard lk(mutex_); - messages_[id].compute(id, data, size, sec, getSpeed(), masks_[id]); - new_msgs_.insert(id); -} - -const std::vector &AbstractStream::events(const MessageId &id) const { - static std::vector empty_events; - auto it = events_.find(id); - return it != events_.end() ? it->second : empty_events; -} - -const CanData &AbstractStream::lastMessage(const MessageId &id) { - static CanData empty_data = {}; - auto it = last_msgs.find(id); - return it != last_msgs.end() ? it->second : empty_data; -} - -// it is thread safe to update data in updateLastMsgsTo. -// updateLastMsgsTo is always called in UI thread. -void AbstractStream::updateLastMsgsTo(double sec) { - new_msgs_.clear(); - messages_.clear(); - - current_sec_ = sec; - uint64_t last_ts = (sec + routeStartTime()) * 1e9; - for (const auto &[id, ev] : events_) { - auto it = std::upper_bound(ev.begin(), ev.end(), last_ts, CompareCanEvent()); - if (it != ev.begin()) { - auto prev = std::prev(it); - double ts = (*prev)->mono_time / 1e9 - routeStartTime(); - auto &m = messages_[id]; - m.compute(id, (*prev)->dat, (*prev)->size, ts, getSpeed(), {}); - m.count = std::distance(ev.begin(), prev) + 1; - } - } - - bool id_changed = messages_.size() != last_msgs.size() || - std::any_of(messages_.cbegin(), messages_.cend(), - [this](const auto &m) { return !last_msgs.count(m.first); }); - last_msgs = messages_; - emit msgsReceived(nullptr, id_changed); -} - -const CanEvent *AbstractStream::newEvent(uint64_t mono_time, const cereal::CanData::Reader &c) { - auto dat = c.getDat(); - CanEvent *e = (CanEvent *)event_buffer_->allocate(sizeof(CanEvent) + sizeof(uint8_t) * dat.size()); - e->src = c.getSrc(); - e->address = c.getAddress(); - e->mono_time = mono_time; - e->size = dat.size(); - memcpy(e->dat, (uint8_t *)dat.begin(), e->size); - return e; -} - -void AbstractStream::mergeEvents(const std::vector &events) { - static MessageEventsMap msg_events; - std::for_each(msg_events.begin(), msg_events.end(), [](auto &e) { e.second.clear(); }); - for (auto e : events) { - msg_events[{.source = e->src, .address = e->address}].push_back(e); - } - - if (!events.empty()) { - for (const auto &[id, new_e] : msg_events) { - if (!new_e.empty()) { - auto &e = events_[id]; - auto pos = std::upper_bound(e.cbegin(), e.cend(), new_e.front()->mono_time, CompareCanEvent()); - e.insert(pos, new_e.cbegin(), new_e.cend()); - } - } - auto pos = std::upper_bound(all_events_.cbegin(), all_events_.cend(), events.front()->mono_time, CompareCanEvent()); - all_events_.insert(pos, events.cbegin(), events.cend()); - emit eventsMerged(msg_events); - } - lastest_event_ts = all_events_.empty() ? 0 : all_events_.back()->mono_time; -} - -// CanData - -namespace { - -enum Color { GREYISH_BLUE, CYAN, RED}; -QColor getColor(int c) { - constexpr int start_alpha = 128; - static const QColor colors[] = { - [GREYISH_BLUE] = QColor(102, 86, 169, start_alpha / 2), - [CYAN] = QColor(0, 187, 255, start_alpha), - [RED] = QColor(255, 0, 0, start_alpha), - }; - return settings.theme == LIGHT_THEME ? colors[c] : colors[c].lighter(135); -} - -inline QColor blend(const QColor &a, const QColor &b) { - return QColor((a.red() + b.red()) / 2, (a.green() + b.green()) / 2, (a.blue() + b.blue()) / 2, (a.alpha() + b.alpha()) / 2); -} - -// Calculate the frequency of the past minute. -double calc_freq(const MessageId &msg_id, double current_sec) { - const auto &events = can->events(msg_id); - uint64_t cur_mono_time = (can->routeStartTime() + current_sec) * 1e9; - uint64_t first_mono_time = std::max(0, cur_mono_time - 59 * 1e9); - auto first = std::lower_bound(events.begin(), events.end(), first_mono_time, CompareCanEvent()); - auto second = std::lower_bound(first, events.end(), cur_mono_time, CompareCanEvent()); - if (first != events.end() && second != events.end()) { - double duration = ((*second)->mono_time - (*first)->mono_time) / 1e9; - uint32_t count = std::distance(first, second); - return count / std::max(1.0, duration); - } - return 0; -} - -} // namespace - -void CanData::compute(const MessageId &msg_id, const uint8_t *can_data, const int size, double current_sec, - double playback_speed, const std::vector &mask, double in_freq) { - ts = current_sec; - ++count; - - if (auto sec = seconds_since_boot(); (sec - last_freq_update_ts) >= 1) { - last_freq_update_ts = sec; - freq = !in_freq ? calc_freq(msg_id, ts) : in_freq; - } - - if (dat.size() != size) { - dat.resize(size); - colors.assign(size, QColor(0, 0, 0, 0)); - last_changes.resize(size); - std::for_each(last_changes.begin(), last_changes.end(), [current_sec](auto &c) { c.ts = current_sec; }); - } else { - constexpr int periodic_threshold = 10; - constexpr float fade_time = 2.0; - const float alpha_delta = 1.0 / (freq + 1) / (fade_time * playback_speed); - - for (int i = 0; i < size; ++i) { - auto &last_change = last_changes[i]; - - uint8_t mask_byte = last_change.suppressed ? 0x00 : 0xFF; - if (i < mask.size()) mask_byte &= ~(mask[i]); - - const uint8_t last = dat[i] & mask_byte; - const uint8_t cur = can_data[i] & mask_byte; - if (last != cur) { - const int delta = cur - last; - // Keep track if signal is changing randomly, or mostly moving in the same direction - if (std::signbit(delta) == std::signbit(last_change.delta)) { - last_change.same_delta_counter = std::min(16, last_change.same_delta_counter + 1); - } else { - last_change.same_delta_counter = std::max(0, last_change.same_delta_counter - 4); - } - - const double delta_t = ts - last_change.ts; - // Mostly moves in the same direction, color based on delta up/down - if (delta_t * freq > periodic_threshold || last_change.same_delta_counter > 8) { - // Last change was while ago, choose color based on delta up or down - colors[i] = getColor(cur > last ? CYAN : RED); - } else { - // Periodic changes - colors[i] = blend(colors[i], getColor(GREYISH_BLUE)); - } - - // Track bit level changes - const uint8_t tmp = (cur ^ last); - for (int bit = 0; bit < 8; bit++) { - if (tmp & (1 << (7 - bit))) { - last_change.bit_change_counts[bit] += 1; - } - } - - last_change.ts = ts; - last_change.delta = delta; - } else { - // Fade out - colors[i].setAlphaF(std::max(0.0, colors[i].alphaF() - alpha_delta)); - } - } - } - memcpy(dat.data(), can_data, size); -} diff --git a/tools/cabana/streams/abstractstream.h b/tools/cabana/streams/abstractstream.h deleted file mode 100644 index 6c9c025..0000000 --- a/tools/cabana/streams/abstractstream.h +++ /dev/null @@ -1,157 +0,0 @@ -#pragma once - -#include -#include -#include -#include -#include -#include - -#include -#include - -#include "cereal/messaging/messaging.h" -#include "tools/cabana/dbc/dbcmanager.h" -#include "tools/cabana/util.h" - -struct CanData { - void compute(const MessageId &msg_id, const uint8_t *dat, const int size, double current_sec, - double playback_speed, const std::vector &mask, double in_freq = 0); - - double ts = 0.; - uint32_t count = 0; - double freq = 0; - std::vector dat; - std::vector colors; - - struct ByteLastChange { - double ts; - int delta; - int same_delta_counter; - bool suppressed; - std::array bit_change_counts; - }; - std::vector last_changes; - double last_freq_update_ts = 0; -}; - -struct CanEvent { - uint8_t src; - uint32_t address; - uint64_t mono_time; - uint8_t size; - uint8_t dat[]; -}; - -struct CompareCanEvent { - constexpr bool operator()(const CanEvent *const e, uint64_t ts) const { return e->mono_time < ts; } - constexpr bool operator()(uint64_t ts, const CanEvent *const e) const { return ts < e->mono_time; } -}; - -struct BusConfig { - int can_speed_kbps = 500; - int data_speed_kbps = 2000; - bool can_fd = false; -}; - -typedef std::unordered_map> MessageEventsMap; - -class AbstractStream : public QObject { - Q_OBJECT - -public: - AbstractStream(QObject *parent); - virtual ~AbstractStream() {} - virtual void start() = 0; - virtual bool liveStreaming() const { return true; } - virtual void seekTo(double ts) {} - virtual QString routeName() const = 0; - virtual QString carFingerprint() const { return ""; } - virtual QDateTime beginDateTime() const { return {}; } - virtual double routeStartTime() const { return 0; } - inline double currentSec() const { return current_sec_; } - virtual double totalSeconds() const { return lastEventMonoTime() / 1e9 - routeStartTime(); } - virtual void setSpeed(float speed) {} - virtual double getSpeed() { return 1; } - virtual bool isPaused() const { return false; } - virtual void pause(bool pause) {} - - inline const std::unordered_map &lastMessages() const { return last_msgs; } - inline const MessageEventsMap &eventsMap() const { return events_; } - inline const std::vector &allEvents() const { return all_events_; } - const CanData &lastMessage(const MessageId &id); - const std::vector &events(const MessageId &id) const; - - size_t suppressHighlighted(); - void clearSuppressed(); - void suppressDefinedSignals(bool suppress); - -signals: - void paused(); - void resume(); - void seekedTo(double sec); - void streamStarted(); - void eventsMerged(const MessageEventsMap &events_map); - void msgsReceived(const std::set *new_msgs, bool has_new_ids); - void sourcesUpdated(const SourceSet &s); - void privateUpdateLastMsgsSignal(); - -public: - SourceSet sources; - -protected: - void mergeEvents(const std::vector &events); - const CanEvent *newEvent(uint64_t mono_time, const cereal::CanData::Reader &c); - void updateEvent(const MessageId &id, double sec, const uint8_t *data, uint8_t size); - uint64_t lastEventMonoTime() const { return lastest_event_ts; } - - std::vector all_events_; - uint64_t lastest_event_ts = 0; - -private: - void updateLastMessages(); - void updateLastMsgsTo(double sec); - void updateMasks(); - - double current_sec_ = 0; - MessageEventsMap events_; - std::unordered_map last_msgs; - std::unique_ptr event_buffer_; - - // Members accessed in multiple threads. (mutex protected) - std::mutex mutex_; - std::set new_msgs_; - std::unordered_map messages_; - std::unordered_map> masks_; -}; - -class AbstractOpenStreamWidget : public QWidget { -public: - AbstractOpenStreamWidget(AbstractStream **stream, QWidget *parent = nullptr) : stream(stream), QWidget(parent) {} - virtual bool open() = 0; - virtual QString title() = 0; - -protected: - AbstractStream **stream = nullptr; -}; - -class DummyStream : public AbstractStream { - Q_OBJECT -public: - DummyStream(QObject *parent) : AbstractStream(parent) {} - QString routeName() const override { return tr("No Stream"); } - void start() override { emit streamStarted(); } -}; - -class StreamNotifier : public QObject { - Q_OBJECT -public: - StreamNotifier(QObject *parent = nullptr) : QObject(parent) {} - static StreamNotifier* instance(); -signals: - void streamStarted(); - void changingStream(); -}; - -// A global pointer referring to the unique AbstractStream object -extern AbstractStream *can; diff --git a/tools/cabana/streams/devicestream.cc b/tools/cabana/streams/devicestream.cc deleted file mode 100644 index 8050739..0000000 --- a/tools/cabana/streams/devicestream.cc +++ /dev/null @@ -1,70 +0,0 @@ -#include "tools/cabana/streams/devicestream.h" - -#include -#include - -#include -#include -#include -#include -#include -#include - -// DeviceStream - -DeviceStream::DeviceStream(QObject *parent, QString address) : zmq_address(address), LiveStream(parent) { -} - -void DeviceStream::streamThread() { - zmq_address.isEmpty() ? unsetenv("ZMQ") : setenv("ZMQ", "1", 1); - - std::unique_ptr context(Context::create()); - std::string address = zmq_address.isEmpty() ? "127.0.0.1" : zmq_address.toStdString(); - std::unique_ptr sock(SubSocket::create(context.get(), "can", address)); - assert(sock != NULL); - // run as fast as messages come in - while (!QThread::currentThread()->isInterruptionRequested()) { - std::unique_ptr msg(sock->receive(true)); - if (!msg) { - QThread::msleep(50); - continue; - } - handleEvent(kj::ArrayPtr((capnp::word*)msg->getData(), msg->getSize() / sizeof(capnp::word))); - } -} - -AbstractOpenStreamWidget *DeviceStream::widget(AbstractStream **stream) { - return new OpenDeviceWidget(stream); -} - -// OpenDeviceWidget - -OpenDeviceWidget::OpenDeviceWidget(AbstractStream **stream) : AbstractOpenStreamWidget(stream) { - QRadioButton *msgq = new QRadioButton(tr("MSGQ")); - QRadioButton *zmq = new QRadioButton(tr("ZMQ")); - ip_address = new QLineEdit(this); - ip_address->setPlaceholderText(tr("Enter device Ip Address")); - QString ip_range = "(?:[0-1]?[0-9]?[0-9]|2[0-4][0-9]|25[0-5])"; - QString pattern("^" + ip_range + "\\." + ip_range + "\\." + ip_range + "\\." + ip_range + "$"); - QRegularExpression re(pattern); - ip_address->setValidator(new QRegularExpressionValidator(re, this)); - - group = new QButtonGroup(this); - group->addButton(msgq, 0); - group->addButton(zmq, 1); - - QFormLayout *form_layout = new QFormLayout(this); - form_layout->addRow(msgq); - form_layout->addRow(zmq, ip_address); - QObject::connect(group, qOverload(&QButtonGroup::buttonToggled), [=](QAbstractButton *button, bool checked) { - ip_address->setEnabled(button == zmq && checked); - }); - zmq->setChecked(true); -} - -bool OpenDeviceWidget::open() { - QString ip = ip_address->text().isEmpty() ? "127.0.0.1" : ip_address->text(); - bool msgq = group->checkedId() == 0; - *stream = new DeviceStream(qApp, msgq ? "" : ip); - return true; -} diff --git a/tools/cabana/streams/devicestream.h b/tools/cabana/streams/devicestream.h deleted file mode 100644 index a65f073..0000000 --- a/tools/cabana/streams/devicestream.h +++ /dev/null @@ -1,30 +0,0 @@ -#pragma once - -#include "tools/cabana/streams/livestream.h" - -class DeviceStream : public LiveStream { - Q_OBJECT -public: - DeviceStream(QObject *parent, QString address = {}); - static AbstractOpenStreamWidget *widget(AbstractStream **stream); - inline QString routeName() const override { - return QString("Live Streaming From %1").arg(zmq_address.isEmpty() ? "127.0.0.1" : zmq_address); - } - -protected: - void streamThread() override; - const QString zmq_address; -}; - -class OpenDeviceWidget : public AbstractOpenStreamWidget { - Q_OBJECT - -public: - OpenDeviceWidget(AbstractStream **stream); - bool open() override; - QString title() override { return tr("&Device"); } - -private: - QLineEdit *ip_address; - QButtonGroup *group; -}; diff --git a/tools/cabana/streams/livestream.cc b/tools/cabana/streams/livestream.cc deleted file mode 100644 index 4e1f6d7..0000000 --- a/tools/cabana/streams/livestream.cc +++ /dev/null @@ -1,140 +0,0 @@ -#include "tools/cabana/streams/livestream.h" - -#include -#include -#include -#include - -#include "common/timing.h" -#include "common/util.h" - -struct LiveStream::Logger { - Logger() : start_ts(seconds_since_epoch()), segment_num(-1) {} - - void write(kj::ArrayPtr data) { - int n = (seconds_since_epoch() - start_ts) / 60.0; - if (std::exchange(segment_num, n) != segment_num) { - QString dir = QString("%1/%2--%3") - .arg(settings.log_path) - .arg(QDateTime::fromSecsSinceEpoch(start_ts).toString("yyyy-MM-dd--hh-mm-ss")) - .arg(n); - util::create_directories(dir.toStdString(), 0755); - fs.reset(new std::ofstream((dir + "/rlog").toStdString(), std::ios::binary | std::ios::out)); - } - - auto bytes = data.asBytes(); - fs->write((const char*)bytes.begin(), bytes.size()); - } - - std::unique_ptr fs; - int segment_num; - uint64_t start_ts; -}; - -LiveStream::LiveStream(QObject *parent) : AbstractStream(parent) { - if (settings.log_livestream) { - logger = std::make_unique(); - } - stream_thread = new QThread(this); - - QObject::connect(&settings, &Settings::changed, this, &LiveStream::startUpdateTimer); - QObject::connect(stream_thread, &QThread::started, [=]() { streamThread(); }); - QObject::connect(stream_thread, &QThread::finished, stream_thread, &QThread::deleteLater); -} - -void LiveStream::startUpdateTimer() { - update_timer.stop(); - update_timer.start(1000.0 / settings.fps, this); - timer_id = update_timer.timerId(); -} - -void LiveStream::start() { - emit streamStarted(); - stream_thread->start(); - startUpdateTimer(); - begin_date_time = QDateTime::currentDateTime(); -} - -LiveStream::~LiveStream() { - update_timer.stop(); - stream_thread->requestInterruption(); - stream_thread->quit(); - stream_thread->wait(); -} - -// called in streamThread -void LiveStream::handleEvent(kj::ArrayPtr data) { - if (logger) { - logger->write(data); - } - - capnp::FlatArrayMessageReader reader(data); - auto event = reader.getRoot(); - if (event.which() == cereal::Event::Which::CAN) { - const uint64_t mono_time = event.getLogMonoTime(); - std::lock_guard lk(lock); - for (const auto &c : event.getCan()) { - received_events_.push_back(newEvent(mono_time, c)); - } - } -} - -void LiveStream::timerEvent(QTimerEvent *event) { - if (event->timerId() == timer_id) { - { - // merge events received from live stream thread. - std::lock_guard lk(lock); - mergeEvents(received_events_); - received_events_.clear(); - } - if (!all_events_.empty()) { - begin_event_ts = all_events_.front()->mono_time; - updateEvents(); - return; - } - } - QObject::timerEvent(event); -} - -void LiveStream::updateEvents() { - static double prev_speed = 1.0; - - if (first_update_ts == 0) { - first_update_ts = nanos_since_boot(); - first_event_ts = current_event_ts = all_events_.back()->mono_time; - } - - if (paused_ || prev_speed != speed_) { - prev_speed = speed_; - first_update_ts = nanos_since_boot(); - first_event_ts = current_event_ts; - return; - } - - uint64_t last_ts = post_last_event && speed_ == 1.0 - ? all_events_.back()->mono_time - : first_event_ts + (nanos_since_boot() - first_update_ts) * speed_; - auto first = std::upper_bound(all_events_.cbegin(), all_events_.cend(), current_event_ts, CompareCanEvent()); - auto last = std::upper_bound(first, all_events_.cend(), last_ts, CompareCanEvent()); - - for (auto it = first; it != last; ++it) { - const CanEvent *e = *it; - MessageId id = {.source = e->src, .address = e->address}; - updateEvent(id, (e->mono_time - begin_event_ts) / 1e9, e->dat, e->size); - current_event_ts = e->mono_time; - } - emit privateUpdateLastMsgsSignal(); -} - -void LiveStream::seekTo(double sec) { - sec = std::max(0.0, sec); - first_update_ts = nanos_since_boot(); - current_event_ts = first_event_ts = std::min(sec * 1e9 + begin_event_ts, lastEventMonoTime()); - post_last_event = (first_event_ts == lastEventMonoTime()); - emit seekedTo((current_event_ts - begin_event_ts) / 1e9); -} - -void LiveStream::pause(bool pause) { - paused_ = pause; - emit(pause ? paused() : resume()); -} diff --git a/tools/cabana/streams/livestream.h b/tools/cabana/streams/livestream.h deleted file mode 100644 index 7a0f8cd..0000000 --- a/tools/cabana/streams/livestream.h +++ /dev/null @@ -1,52 +0,0 @@ -#pragma once - -#include -#include - -#include - -#include "tools/cabana/streams/abstractstream.h" - -class LiveStream : public AbstractStream { - Q_OBJECT - -public: - LiveStream(QObject *parent); - virtual ~LiveStream(); - void start() override; - inline QDateTime beginDateTime() const { return begin_date_time; } - inline double routeStartTime() const override { return begin_event_ts / 1e9; } - void setSpeed(float speed) override { speed_ = speed; } - double getSpeed() override { return speed_; } - bool isPaused() const override { return paused_; } - void pause(bool pause) override; - void seekTo(double sec) override; - -protected: - virtual void streamThread() = 0; - void handleEvent(kj::ArrayPtr event); - -private: - void startUpdateTimer(); - void timerEvent(QTimerEvent *event) override; - void updateEvents(); - - std::mutex lock; - QThread *stream_thread; - std::vector received_events_; - - int timer_id; - QBasicTimer update_timer; - - QDateTime begin_date_time; - uint64_t begin_event_ts = 0; - uint64_t current_event_ts = 0; - uint64_t first_event_ts = 0; - uint64_t first_update_ts = 0; - bool post_last_event = true; - double speed_ = 1; - bool paused_ = false; - - struct Logger; - std::unique_ptr logger; -}; diff --git a/tools/cabana/streams/pandastream.cc b/tools/cabana/streams/pandastream.cc deleted file mode 100644 index bea1fd7..0000000 --- a/tools/cabana/streams/pandastream.cc +++ /dev/null @@ -1,220 +0,0 @@ -#include "tools/cabana/streams/pandastream.h" - -#include -#include -#include -#include -#include -#include -#include - -// TODO: remove clearLayout -static void clearLayout(QLayout* layout) { - while (layout->count() > 0) { - QLayoutItem* item = layout->takeAt(0); - if (QWidget* widget = item->widget()) { - widget->deleteLater(); - } - if (QLayout* childLayout = item->layout()) { - clearLayout(childLayout); - } - delete item; - } -} - -PandaStream::PandaStream(QObject *parent, PandaStreamConfig config_) : config(config_), LiveStream(parent) { - if (config.serial.isEmpty()) { - auto serials = Panda::list(); - if (serials.size() == 0) { - throw std::runtime_error("No panda found"); - } - config.serial = QString::fromStdString(serials[0]); - } - - qDebug() << "Connecting to panda with serial" << config.serial; - if (!connect()) { - throw std::runtime_error("Failed to connect to panda"); - } -} - -bool PandaStream::connect() { - try { - panda.reset(new Panda(config.serial.toStdString())); - config.bus_config.resize(3); - qDebug() << "Connected"; - } catch (const std::exception& e) { - return false; - } - - panda->set_safety_model(cereal::CarParams::SafetyModel::SILENT); - - for (int bus = 0; bus < config.bus_config.size(); bus++) { - panda->set_can_speed_kbps(bus, config.bus_config[bus].can_speed_kbps); - - // CAN-FD - if (panda->hw_type == cereal::PandaState::PandaType::RED_PANDA || panda->hw_type == cereal::PandaState::PandaType::RED_PANDA_V2) { - if (config.bus_config[bus].can_fd) { - panda->set_data_speed_kbps(bus, config.bus_config[bus].data_speed_kbps); - } else { - // Hack to disable can-fd by setting data speed to a low value - panda->set_data_speed_kbps(bus, 10); - } - } - - } - return true; -} - -void PandaStream::streamThread() { - std::vector raw_can_data; - - while (!QThread::currentThread()->isInterruptionRequested()) { - QThread::msleep(1); - - if (!panda->connected()) { - qDebug() << "Connection to panda lost. Attempting reconnect."; - if (!connect()){ - QThread::msleep(1000); - continue; - } - } - - raw_can_data.clear(); - if (!panda->can_receive(raw_can_data)) { - qDebug() << "failed to receive"; - continue; - } - - MessageBuilder msg; - auto evt = msg.initEvent(); - auto canData = evt.initCan(raw_can_data.size()); - for (uint i = 0; isend_heartbeat(false); - } -} - -AbstractOpenStreamWidget *PandaStream::widget(AbstractStream **stream) { - return new OpenPandaWidget(stream); -} - -// OpenPandaWidget - -OpenPandaWidget::OpenPandaWidget(AbstractStream **stream) : AbstractOpenStreamWidget(stream) { - QVBoxLayout *main_layout = new QVBoxLayout(this); - main_layout->addStretch(1); - - QFormLayout *form_layout = new QFormLayout(); - - QHBoxLayout *serial_layout = new QHBoxLayout(); - serial_edit = new QComboBox(); - serial_edit->setFixedWidth(300); - serial_layout->addWidget(serial_edit); - - QPushButton *refresh = new QPushButton(tr("Refresh")); - refresh->setFixedWidth(100); - serial_layout->addWidget(refresh); - form_layout->addRow(tr("Serial"), serial_layout); - main_layout->addLayout(form_layout); - - config_layout = new QFormLayout(); - main_layout->addLayout(config_layout); - - main_layout->addStretch(1); - - QObject::connect(refresh, &QPushButton::clicked, this, &OpenPandaWidget::refreshSerials); - QObject::connect(serial_edit, &QComboBox::currentTextChanged, this, &OpenPandaWidget::buildConfigForm); - - // Populate serials - refreshSerials(); - buildConfigForm(); -} - -void OpenPandaWidget::refreshSerials() { - serial_edit->clear(); - for (auto serial : Panda::list()) { - serial_edit->addItem(QString::fromStdString(serial)); - } -} - -void OpenPandaWidget::buildConfigForm() { - clearLayout(config_layout); - QString serial = serial_edit->currentText(); - - bool has_fd = false; - bool has_panda = !serial.isEmpty(); - - if (has_panda) { - try { - Panda panda = Panda(serial.toStdString()); - has_fd = (panda.hw_type == cereal::PandaState::PandaType::RED_PANDA) || (panda.hw_type == cereal::PandaState::PandaType::RED_PANDA_V2); - } catch (const std::exception& e) { - has_panda = false; - } - } - - if (has_panda) { - config.serial = serial; - config.bus_config.resize(3); - for (int i = 0; i < config.bus_config.size(); i++) { - QHBoxLayout *bus_layout = new QHBoxLayout; - - // CAN Speed - bus_layout->addWidget(new QLabel(tr("CAN Speed (kbps):"))); - QComboBox *can_speed = new QComboBox; - for (int j = 0; j < std::size(speeds); j++) { - can_speed->addItem(QString::number(speeds[j])); - - if (data_speeds[j] == config.bus_config[i].can_speed_kbps) { - can_speed->setCurrentIndex(j); - } - } - QObject::connect(can_speed, qOverload(&QComboBox::currentIndexChanged), [=](int index) {config.bus_config[i].can_speed_kbps = speeds[index];}); - bus_layout->addWidget(can_speed); - - // CAN-FD Speed - if (has_fd) { - QCheckBox *enable_fd = new QCheckBox("CAN-FD"); - bus_layout->addWidget(enable_fd); - bus_layout->addWidget(new QLabel(tr("Data Speed (kbps):"))); - QComboBox *data_speed = new QComboBox; - for (int j = 0; j < std::size(data_speeds); j++) { - data_speed->addItem(QString::number(data_speeds[j])); - - if (data_speeds[j] == config.bus_config[i].data_speed_kbps) { - data_speed->setCurrentIndex(j); - } - } - - data_speed->setEnabled(false); - bus_layout->addWidget(data_speed); - - QObject::connect(data_speed, qOverload(&QComboBox::currentIndexChanged), [=](int index) {config.bus_config[i].data_speed_kbps = data_speeds[index];}); - QObject::connect(enable_fd, &QCheckBox::stateChanged, data_speed, &QComboBox::setEnabled); - QObject::connect(enable_fd, &QCheckBox::stateChanged, [=](int state) {config.bus_config[i].can_fd = (bool)state;}); - } - - config_layout->addRow(tr("Bus %1:").arg(i), bus_layout); - } - } else { - config.serial = ""; - config_layout->addWidget(new QLabel(tr("No panda found"))); - } -} - -bool OpenPandaWidget::open() { - try { - *stream = new PandaStream(qApp, config); - } catch (std::exception &e) { - QMessageBox::warning(nullptr, tr("Warning"), tr("Failed to connect to panda: '%1'").arg(e.what())); - return false; - } - return true; -} diff --git a/tools/cabana/streams/pandastream.h b/tools/cabana/streams/pandastream.h deleted file mode 100644 index 919156f..0000000 --- a/tools/cabana/streams/pandastream.h +++ /dev/null @@ -1,52 +0,0 @@ -#pragma once - -#include -#include - -#include -#include - -#include "tools/cabana/streams/livestream.h" -#include "selfdrive/boardd/panda.h" - -const uint32_t speeds[] = {10U, 20U, 50U, 100U, 125U, 250U, 500U, 1000U}; -const uint32_t data_speeds[] = {10U, 20U, 50U, 100U, 125U, 250U, 500U, 1000U, 2000U, 5000U}; - -struct PandaStreamConfig { - QString serial = ""; - std::vector bus_config; -}; - -class PandaStream : public LiveStream { - Q_OBJECT -public: - PandaStream(QObject *parent, PandaStreamConfig config_ = {}); - static AbstractOpenStreamWidget *widget(AbstractStream **stream); - inline QString routeName() const override { - return QString("Live Streaming From Panda %1").arg(config.serial); - } - -protected: - void streamThread() override; - bool connect(); - - std::unique_ptr panda; - PandaStreamConfig config = {}; -}; - -class OpenPandaWidget : public AbstractOpenStreamWidget { - Q_OBJECT - -public: - OpenPandaWidget(AbstractStream **stream); - bool open() override; - QString title() override { return tr("&Panda"); } - -private: - void refreshSerials(); - void buildConfigForm(); - - QComboBox *serial_edit; - QFormLayout *config_layout; - PandaStreamConfig config = {}; -}; diff --git a/tools/cabana/streams/replaystream.cc b/tools/cabana/streams/replaystream.cc deleted file mode 100644 index c61c81d..0000000 --- a/tools/cabana/streams/replaystream.cc +++ /dev/null @@ -1,145 +0,0 @@ -#include "tools/cabana/streams/replaystream.h" - -#include -#include -#include -#include -#include - -ReplayStream::ReplayStream(QObject *parent) : AbstractStream(parent) { - unsetenv("ZMQ"); - setenv("COMMA_CACHE", "/tmp/comma_download_cache", 1); - - // TODO: Remove when OpenpilotPrefix supports ZMQ -#ifndef __APPLE__ - op_prefix = std::make_unique(); -#endif - - QObject::connect(&settings, &Settings::changed, this, [this]() { - if (replay) replay->setSegmentCacheLimit(settings.max_cached_minutes); - }); -} - -static bool event_filter(const Event *e, void *opaque) { - return ((ReplayStream *)opaque)->eventFilter(e); -} - -void ReplayStream::mergeSegments() { - for (auto &[n, seg] : replay->segments()) { - if (seg && seg->isLoaded() && !processed_segments.count(n)) { - processed_segments.insert(n); - - std::vector new_events; - new_events.reserve(seg->log->events.size()); - for (auto it = seg->log->events.cbegin(); it != seg->log->events.cend(); ++it) { - if ((*it)->which == cereal::Event::Which::CAN) { - const uint64_t ts = (*it)->mono_time; - for (const auto &c : (*it)->event.getCan()) { - new_events.push_back(newEvent(ts, c)); - } - } - } - mergeEvents(new_events); - } - } -} - -bool ReplayStream::loadRoute(const QString &route, const QString &data_dir, uint32_t replay_flags) { - replay.reset(new Replay(route, {"can", "roadEncodeIdx", "driverEncodeIdx", "wideRoadEncodeIdx", "carParams"}, - {}, nullptr, replay_flags, data_dir, this)); - replay->setSegmentCacheLimit(settings.max_cached_minutes); - replay->installEventFilter(event_filter, this); - QObject::connect(replay.get(), &Replay::seekedTo, this, &AbstractStream::seekedTo); - QObject::connect(replay.get(), &Replay::segmentsMerged, this, &ReplayStream::mergeSegments); - QObject::connect(replay.get(), &Replay::qLogLoaded, this, &ReplayStream::qLogLoaded, Qt::QueuedConnection); - return replay->load(); -} - -void ReplayStream::start() { - emit streamStarted(); - replay->start(); -} - -bool ReplayStream::eventFilter(const Event *event) { - static double prev_update_ts = 0; - if (event->which == cereal::Event::Which::CAN) { - double current_sec = event->mono_time / 1e9 - routeStartTime(); - for (const auto &c : event->event.getCan()) { - MessageId id = {.source = c.getSrc(), .address = c.getAddress()}; - const auto dat = c.getDat(); - updateEvent(id, current_sec, (const uint8_t*)dat.begin(), dat.size()); - } - } - - double ts = millis_since_boot(); - if ((ts - prev_update_ts) > (1000.0 / settings.fps)) { - emit privateUpdateLastMsgsSignal(); - prev_update_ts = ts; - } - return true; -} - -void ReplayStream::pause(bool pause) { - replay->pause(pause); - emit(pause ? paused() : resume()); -} - - -AbstractOpenStreamWidget *ReplayStream::widget(AbstractStream **stream) { - return new OpenReplayWidget(stream); -} - -// OpenReplayWidget - -OpenReplayWidget::OpenReplayWidget(AbstractStream **stream) : AbstractOpenStreamWidget(stream) { - // TODO: get route list from api.comma.ai - QGridLayout *grid_layout = new QGridLayout(this); - grid_layout->addWidget(new QLabel(tr("Route")), 0, 0); - grid_layout->addWidget(route_edit = new QLineEdit(this), 0, 1); - route_edit->setPlaceholderText(tr("Enter remote route name or click browse to select a local route")); - auto file_btn = new QPushButton(tr("Browse..."), this); - grid_layout->addWidget(file_btn, 0, 2); - - grid_layout->addWidget(new QLabel(tr("Camera")), 1, 0); - QHBoxLayout *camera_layout = new QHBoxLayout(); - for (auto c : {tr("Road camera"), tr("Driver camera"), tr("Wide road camera")}) - camera_layout->addWidget(cameras.emplace_back(new QCheckBox(c, this))); - camera_layout->addStretch(1); - grid_layout->addItem(camera_layout, 1, 1); - - setMinimumWidth(550); - QObject::connect(file_btn, &QPushButton::clicked, [=]() { - QString dir = QFileDialog::getExistingDirectory(this, tr("Open Local Route"), settings.last_route_dir); - if (!dir.isEmpty()) { - route_edit->setText(dir); - settings.last_route_dir = QFileInfo(dir).absolutePath(); - } - }); -} - -bool OpenReplayWidget::open() { - QString route = route_edit->text(); - QString data_dir; - if (int idx = route.lastIndexOf('/'); idx != -1) { - data_dir = route.mid(0, idx + 1); - route = route.mid(idx + 1); - } - - bool is_valid_format = Route::parseRoute(route).str.size() > 0; - if (!is_valid_format) { - QMessageBox::warning(nullptr, tr("Warning"), tr("Invalid route format: '%1'").arg(route)); - } else { - auto replay_stream = std::make_unique(qApp); - uint32_t flags = REPLAY_FLAG_NONE; - if (cameras[1]->isChecked()) flags |= REPLAY_FLAG_DCAM; - if (cameras[2]->isChecked()) flags |= REPLAY_FLAG_ECAM; - if (flags == REPLAY_FLAG_NONE && !cameras[0]->isChecked()) flags = REPLAY_FLAG_NO_VIPC; - - if (replay_stream->loadRoute(route, data_dir, flags)) { - *stream = replay_stream.release(); - } else { - QMessageBox::warning(nullptr, tr("Warning"), tr("Failed to load route: '%1'").arg(route)); - } - } - return *stream != nullptr; -} diff --git a/tools/cabana/streams/replaystream.h b/tools/cabana/streams/replaystream.h deleted file mode 100644 index b4e4be4..0000000 --- a/tools/cabana/streams/replaystream.h +++ /dev/null @@ -1,57 +0,0 @@ -#pragma once - -#include -#include -#include -#include -#include - -#include "common/prefix.h" -#include "tools/cabana/streams/abstractstream.h" -#include "tools/replay/replay.h" - -class ReplayStream : public AbstractStream { - Q_OBJECT - -public: - ReplayStream(QObject *parent); - void start() override; - bool loadRoute(const QString &route, const QString &data_dir, uint32_t replay_flags = REPLAY_FLAG_NONE); - bool eventFilter(const Event *event); - void seekTo(double ts) override { replay->seekTo(std::max(double(0), ts), false); } - bool liveStreaming() const override { return false; } - inline QString routeName() const override { return replay->route()->name(); } - inline QString carFingerprint() const override { return replay->carFingerprint().c_str(); } - double totalSeconds() const override { return replay->totalSeconds(); } - inline QDateTime beginDateTime() const { return replay->route()->datetime(); } - inline double routeStartTime() const override { return replay->routeStartTime() / (double)1e9; } - inline const Route *route() const { return replay->route(); } - inline void setSpeed(float speed) override { replay->setSpeed(speed); } - inline float getSpeed() const { return replay->getSpeed(); } - inline Replay *getReplay() const { return replay.get(); } - inline bool isPaused() const override { return replay->isPaused(); } - void pause(bool pause) override; - static AbstractOpenStreamWidget *widget(AbstractStream **stream); - -signals: - void qLogLoaded(int segnum, std::shared_ptr qlog); - -private: - void mergeSegments(); - std::unique_ptr replay = nullptr; - std::set processed_segments; - std::unique_ptr op_prefix; -}; - -class OpenReplayWidget : public AbstractOpenStreamWidget { - Q_OBJECT - -public: - OpenReplayWidget(AbstractStream **stream); - bool open() override; - QString title() override { return tr("&Replay"); } - -private: - QLineEdit *route_edit; - std::vector cameras; -}; diff --git a/tools/cabana/streams/socketcanstream.cc b/tools/cabana/streams/socketcanstream.cc deleted file mode 100644 index 0f13b99..0000000 --- a/tools/cabana/streams/socketcanstream.cc +++ /dev/null @@ -1,115 +0,0 @@ -#include "tools/cabana/streams/socketcanstream.h" - -#include -#include -#include -#include -#include -#include - -SocketCanStream::SocketCanStream(QObject *parent, SocketCanStreamConfig config_) : config(config_), LiveStream(parent) { - if (!available()) { - throw std::runtime_error("SocketCAN plugin not available"); - } - - qDebug() << "Connecting to SocketCAN device" << config.device; - if (!connect()) { - throw std::runtime_error("Failed to connect to SocketCAN device"); - } -} - -bool SocketCanStream::available() { - return QCanBus::instance()->plugins().contains("socketcan"); -} - -bool SocketCanStream::connect() { - // Connecting might generate some warnings about missing socketcan/libsocketcan libraries - // These are expected and can be ignored, we don't need the advanced features of libsocketcan - QString errorString; - device.reset(QCanBus::instance()->createDevice("socketcan", config.device, &errorString)); - - if (!device) { - qDebug() << "Failed to create SocketCAN device" << errorString; - return false; - } - - if (!device->connectDevice()) { - qDebug() << "Failed to connect to device"; - return false; - } - - return true; -} - -void SocketCanStream::streamThread() { - while (!QThread::currentThread()->isInterruptionRequested()) { - QThread::msleep(1); - - auto frames = device->readAllFrames(); - if (frames.size() == 0) continue; - - MessageBuilder msg; - auto evt = msg.initEvent(); - auto canData = evt.initCan(frames.size()); - - for (uint i = 0; i < frames.size(); i++) { - if (!frames[i].isValid()) continue; - - canData[i].setAddress(frames[i].frameId()); - canData[i].setSrc(0); - - auto payload = frames[i].payload(); - canData[i].setDat(kj::arrayPtr((uint8_t*)payload.data(), payload.size())); - } - - handleEvent(capnp::messageToFlatArray(msg)); - } -} - -AbstractOpenStreamWidget *SocketCanStream::widget(AbstractStream **stream) { - return new OpenSocketCanWidget(stream); -} - -OpenSocketCanWidget::OpenSocketCanWidget(AbstractStream **stream) : AbstractOpenStreamWidget(stream) { - QVBoxLayout *main_layout = new QVBoxLayout(this); - main_layout->addStretch(1); - - QFormLayout *form_layout = new QFormLayout(); - - QHBoxLayout *device_layout = new QHBoxLayout(); - device_edit = new QComboBox(); - device_edit->setFixedWidth(300); - device_layout->addWidget(device_edit); - - QPushButton *refresh = new QPushButton(tr("Refresh")); - refresh->setFixedWidth(100); - device_layout->addWidget(refresh); - form_layout->addRow(tr("Device"), device_layout); - main_layout->addLayout(form_layout); - - main_layout->addStretch(1); - - QObject::connect(refresh, &QPushButton::clicked, this, &OpenSocketCanWidget::refreshDevices); - QObject::connect(device_edit, &QComboBox::currentTextChanged, this, [=]{ config.device = device_edit->currentText(); }); - - // Populate devices - refreshDevices(); -} - -void OpenSocketCanWidget::refreshDevices() { - device_edit->clear(); - for (auto device : QCanBus::instance()->availableDevices(QStringLiteral("socketcan"))) { - device_edit->addItem(device.name()); - } -} - - -bool OpenSocketCanWidget::open() { - try { - *stream = new SocketCanStream(qApp, config); - } catch (std::exception &e) { - QMessageBox::warning(nullptr, tr("Warning"), tr("Failed to connect to SocketCAN device: '%1'").arg(e.what())); - return false; - } - return true; -} diff --git a/tools/cabana/streams/socketcanstream.h b/tools/cabana/streams/socketcanstream.h deleted file mode 100644 index e0fb826..0000000 --- a/tools/cabana/streams/socketcanstream.h +++ /dev/null @@ -1,48 +0,0 @@ -#pragma once - -#include - -#include -#include -#include -#include - -#include "tools/cabana/streams/livestream.h" - -struct SocketCanStreamConfig { - QString device = ""; // TODO: support multiple devices/buses at once -}; - -class SocketCanStream : public LiveStream { - Q_OBJECT -public: - SocketCanStream(QObject *parent, SocketCanStreamConfig config_ = {}); - static AbstractOpenStreamWidget *widget(AbstractStream **stream); - static bool available(); - - inline QString routeName() const override { - return QString("Live Streaming From Socket CAN %1").arg(config.device); - } - -protected: - void streamThread() override; - bool connect(); - - SocketCanStreamConfig config = {}; - std::unique_ptr device; -}; - -class OpenSocketCanWidget : public AbstractOpenStreamWidget { - Q_OBJECT - -public: - OpenSocketCanWidget(AbstractStream **stream); - bool open() override; - QString title() override { return tr("&SocketCAN"); } - -private: - void refreshDevices(); - - QComboBox *device_edit; - SocketCanStreamConfig config = {}; -}; diff --git a/tools/cabana/streamselector.cc b/tools/cabana/streamselector.cc deleted file mode 100644 index 07755c0..0000000 --- a/tools/cabana/streamselector.cc +++ /dev/null @@ -1,71 +0,0 @@ -#include "tools/cabana/streamselector.h" - -#include -#include -#include -#include - -#include "streams/socketcanstream.h" -#include "tools/cabana/streams/devicestream.h" -#include "tools/cabana/streams/pandastream.h" -#include "tools/cabana/streams/replaystream.h" -#include "tools/cabana/streams/socketcanstream.h" - -StreamSelector::StreamSelector(AbstractStream **stream, QWidget *parent) : QDialog(parent) { - setWindowTitle(tr("Open stream")); - QVBoxLayout *main_layout = new QVBoxLayout(this); - - QWidget *w = new QWidget(this); - QVBoxLayout *layout = new QVBoxLayout(w); - tab = new QTabWidget(this); - tab->setTabBarAutoHide(true); - layout->addWidget(tab); - - QHBoxLayout *dbc_layout = new QHBoxLayout(); - dbc_file = new QLineEdit(this); - dbc_file->setReadOnly(true); - dbc_file->setPlaceholderText(tr("Choose a dbc file to open")); - QPushButton *file_btn = new QPushButton(tr("Browse...")); - dbc_layout->addWidget(new QLabel(tr("dbc File"))); - dbc_layout->addWidget(dbc_file); - dbc_layout->addWidget(file_btn); - layout->addLayout(dbc_layout); - - QFrame *line = new QFrame(this); - line->setFrameStyle(QFrame::HLine | QFrame::Sunken); - layout->addWidget(line); - - main_layout->addWidget(w); - auto btn_box = new QDialogButtonBox(QDialogButtonBox::Open | QDialogButtonBox::Cancel); - main_layout->addWidget(btn_box); - - addStreamWidget(ReplayStream::widget(stream)); - addStreamWidget(PandaStream::widget(stream)); - if (SocketCanStream::available()) { - addStreamWidget(SocketCanStream::widget(stream)); - } - addStreamWidget(DeviceStream::widget(stream)); - - QObject::connect(btn_box, &QDialogButtonBox::rejected, this, &QDialog::reject); - QObject::connect(btn_box, &QDialogButtonBox::accepted, [=]() { - btn_box->button(QDialogButtonBox::Open)->setEnabled(false); - w->setEnabled(false); - if (((AbstractOpenStreamWidget *)tab->currentWidget())->open()) { - accept(); - } else { - btn_box->button(QDialogButtonBox::Open)->setEnabled(true); - w->setEnabled(true); - } - }); - QObject::connect(file_btn, &QPushButton::clicked, [this]() { - QString fn = QFileDialog::getOpenFileName(this, tr("Open File"), settings.last_dir, "DBC (*.dbc)"); - if (!fn.isEmpty()) { - dbc_file->setText(fn); - settings.last_dir = QFileInfo(fn).absolutePath(); - } - }); -} - -void StreamSelector::addStreamWidget(AbstractOpenStreamWidget *w) { - tab->addTab(w, w->title()); -} diff --git a/tools/cabana/streamselector.h b/tools/cabana/streamselector.h deleted file mode 100644 index 19b438d..0000000 --- a/tools/cabana/streamselector.h +++ /dev/null @@ -1,20 +0,0 @@ -#pragma once - -#include -#include -#include - -#include "tools/cabana/streams/abstractstream.h" - -class StreamSelector : public QDialog { - Q_OBJECT - -public: - StreamSelector(AbstractStream **stream, QWidget *parent = nullptr); - void addStreamWidget(AbstractOpenStreamWidget *w); - QString dbcFile() const { return dbc_file->text(); } - -private: - QLineEdit *dbc_file; - QTabWidget *tab; -}; diff --git a/tools/cabana/tests/test_cabana.cc b/tools/cabana/tests/test_cabana.cc deleted file mode 100644 index f6884a2..0000000 --- a/tools/cabana/tests/test_cabana.cc +++ /dev/null @@ -1,87 +0,0 @@ - -#undef INFO -#include "catch2/catch.hpp" -#include "tools/replay/logreader.h" -#include "tools/cabana/dbc/dbcmanager.h" -#include "tools/cabana/streams/abstractstream.h" - -const std::string TEST_RLOG_URL = "https://commadataci.blob.core.windows.net/openpilotci/0c94aa1e1296d7c6/2021-05-05--19-48-37/0/rlog.bz2"; - -TEST_CASE("DBCFile::generateDBC") { - QString fn = QString("%1/%2.dbc").arg(OPENDBC_FILE_PATH, "tesla_can"); - DBCFile dbc_origin(fn); - DBCFile dbc_from_generated("", dbc_origin.generateDBC()); - - REQUIRE(dbc_origin.msgCount() == dbc_from_generated.msgCount()); - auto &msgs = dbc_origin.getMessages(); - auto &new_msgs = dbc_from_generated.getMessages(); - for (auto &[id, m] : msgs) { - auto &new_m = new_msgs.at(id); - REQUIRE(m.name == new_m.name); - REQUIRE(m.size == new_m.size); - REQUIRE(m.getSignals().size() == new_m.getSignals().size()); - auto sigs = m.getSignals(); - auto new_sigs = new_m.getSignals(); - for (int i = 0; i < sigs.size(); ++i) { - REQUIRE(*sigs[i] == *new_sigs[i]); - } - } -} - -TEST_CASE("parse_dbc") { - QString content = R"( -BO_ 160 message_1: 8 EON - SG_ signal_1 : 0|12@1+ (1,0) [0|4095] "unit" XXX - SG_ signal_2 : 12|1@1+ (1.0,0.0) [0.0|1] "" XXX - -BO_ 162 message_1: 8 XXX - SG_ signal_1 M : 0|12@1+ (1,0) [0|4095] "unit" XXX - SG_ signal_2 M4 : 12|1@1+ (1.0,0.0) [0.0|1] "" XXX - -VAL_ 160 signal_1 0 "disabled" 1.2 "initializing" 2 "fault"; - -CM_ BO_ 160 "message comment" ; -CM_ SG_ 160 signal_1 "signal comment"; -CM_ SG_ 160 signal_2 "multiple line comment -1 -2 -";)"; - - DBCFile file("", content); - auto msg = file.msg(160); - REQUIRE(msg != nullptr); - REQUIRE(msg->name == "message_1"); - REQUIRE(msg->size == 8); - REQUIRE(msg->comment == "message comment"); - REQUIRE(msg->sigs.size() == 2); - REQUIRE(msg->transmitter == "EON"); - REQUIRE(file.msg("message_1") != nullptr); - - auto sig_1 = msg->sigs[0]; - REQUIRE(sig_1->name == "signal_1"); - REQUIRE(sig_1->start_bit == 0); - REQUIRE(sig_1->size == 12); - REQUIRE(sig_1->min == 0); - REQUIRE(sig_1->max == 4095); - REQUIRE(sig_1->unit == "unit"); - REQUIRE(sig_1->comment == "signal comment"); - REQUIRE(sig_1->receiver_name == "XXX"); - REQUIRE(sig_1->val_desc.size() == 3); - REQUIRE(sig_1->val_desc[0] == std::pair{0, "disabled"}); - REQUIRE(sig_1->val_desc[1] == std::pair{1.2, "initializing"}); - REQUIRE(sig_1->val_desc[2] == std::pair{2, "fault"}); - - auto &sig_2 = msg->sigs[1]; - REQUIRE(sig_2->comment == "multiple line comment \n1\n2"); - - // multiplexed signals - msg = file.msg(162); - REQUIRE(msg != nullptr); - REQUIRE(msg->sigs.size() == 2); - REQUIRE(msg->sigs[0]->type == cabana::Signal::Type::Multiplexor); - REQUIRE(msg->sigs[1]->type == cabana::Signal::Type::Multiplexed); - REQUIRE(msg->sigs[1]->multiplex_value == 4); - REQUIRE(msg->sigs[1]->start_bit == 12); - REQUIRE(msg->sigs[1]->size == 1); - REQUIRE(msg->sigs[1]->receiver_name == "XXX"); -} diff --git a/tools/cabana/tests/test_runner.cc b/tools/cabana/tests/test_runner.cc deleted file mode 100644 index b20ac86..0000000 --- a/tools/cabana/tests/test_runner.cc +++ /dev/null @@ -1,10 +0,0 @@ -#define CATCH_CONFIG_RUNNER -#include "catch2/catch.hpp" -#include - -int main(int argc, char **argv) { - // unit tests for Qt - QCoreApplication app(argc, argv); - const int res = Catch::Session().run(argc, argv); - return (res < 0xff ? res : 0xff); -} diff --git a/tools/cabana/tools/findsignal.cc b/tools/cabana/tools/findsignal.cc deleted file mode 100644 index 387a912..0000000 --- a/tools/cabana/tools/findsignal.cc +++ /dev/null @@ -1,269 +0,0 @@ -#include "tools/cabana/tools/findsignal.h" - -#include -#include -#include -#include -#include -#include -#include - -// FindSignalModel - -QVariant FindSignalModel::headerData(int section, Qt::Orientation orientation, int role) const { - static QString titles[] = {"Id", "Start Bit, size", "(time, value)"}; - if (role != Qt::DisplayRole) return {}; - return orientation == Qt::Horizontal ? titles[section] : QString::number(section + 1); -} - -QVariant FindSignalModel::data(const QModelIndex &index, int role) const { - if (role == Qt::DisplayRole) { - const auto &s = filtered_signals[index.row()]; - switch (index.column()) { - case 0: return s.id.toString(); - case 1: return QString("%1, %2").arg(s.sig.start_bit).arg(s.sig.size); - case 2: return s.values.join(" "); - } - } - return {}; -} - -void FindSignalModel::search(std::function cmp) { - beginResetModel(); - - std::mutex lock; - const auto prev_sigs = !histories.isEmpty() ? histories.back() : initial_signals; - filtered_signals.clear(); - filtered_signals.reserve(prev_sigs.size()); - QtConcurrent::blockingMap(prev_sigs, [&](auto &s) { - const auto &events = can->events(s.id); - auto first = std::upper_bound(events.cbegin(), events.cend(), s.mono_time, CompareCanEvent()); - auto last = events.cend(); - if (last_time < std::numeric_limits::max()) { - last = std::upper_bound(events.cbegin(), events.cend(), last_time, CompareCanEvent()); - } - - auto it = std::find_if(first, last, [&](const CanEvent *e) { return cmp(get_raw_value(e->dat, e->size, s.sig)); }); - if (it != last) { - auto values = s.values; - values += QString("(%1, %2)").arg((*it)->mono_time / 1e9 - can->routeStartTime(), 0, 'f', 2).arg(get_raw_value((*it)->dat, (*it)->size, s.sig)); - std::lock_guard lk(lock); - filtered_signals.push_back({.id = s.id, .mono_time = (*it)->mono_time, .sig = s.sig, .values = values}); - } - }); - histories.push_back(filtered_signals); - - endResetModel(); -} - -void FindSignalModel::undo() { - if (!histories.isEmpty()) { - beginResetModel(); - histories.pop_back(); - filtered_signals.clear(); - if (!histories.isEmpty()) filtered_signals = histories.back(); - endResetModel(); - } -} - -void FindSignalModel::reset() { - beginResetModel(); - histories.clear(); - filtered_signals.clear(); - initial_signals.clear(); - endResetModel(); -} - -// FindSignalDlg -FindSignalDlg::FindSignalDlg(QWidget *parent) : QDialog(parent, Qt::WindowFlags() | Qt::Window) { - setWindowTitle(tr("Find Signal")); - setAttribute(Qt::WA_DeleteOnClose); - QVBoxLayout *main_layout = new QVBoxLayout(this); - - // Messages group - message_group = new QGroupBox(tr("Messages"), this); - QFormLayout *message_layout = new QFormLayout(message_group); - message_layout->addRow(tr("Bus"), bus_edit = new QLineEdit()); - bus_edit->setPlaceholderText(tr("comma-seperated values. Leave blank for all")); - message_layout->addRow(tr("Address"), address_edit = new QLineEdit()); - address_edit->setPlaceholderText(tr("comma-seperated hex values. Leave blank for all")); - QHBoxLayout *hlayout = new QHBoxLayout(); - hlayout->addWidget(first_time_edit = new QLineEdit("0")); - hlayout->addWidget(new QLabel("-")); - hlayout->addWidget(last_time_edit = new QLineEdit("MAX")); - hlayout->addWidget(new QLabel("seconds")); - hlayout->addStretch(0); - message_layout->addRow(tr("Time"), hlayout); - - // Signal group - properties_group = new QGroupBox(tr("Signal")); - QFormLayout *property_layout = new QFormLayout(properties_group); - property_layout->setFieldGrowthPolicy(QFormLayout::FieldsStayAtSizeHint); - - hlayout = new QHBoxLayout(); - hlayout->addWidget(min_size = new QSpinBox); - hlayout->addWidget(new QLabel("-")); - hlayout->addWidget(max_size = new QSpinBox); - hlayout->addWidget(litter_endian = new QCheckBox(tr("Little endian"))); - hlayout->addWidget(is_signed = new QCheckBox(tr("Signed"))); - hlayout->addStretch(0); - min_size->setRange(1, 64); - max_size->setRange(1, 64); - min_size->setValue(8); - max_size->setValue(8); - litter_endian->setChecked(true); - property_layout->addRow(tr("Size"), hlayout); - property_layout->addRow(tr("Factor"), factor_edit = new QLineEdit("1.0")); - property_layout->addRow(tr("Offset"), offset_edit = new QLineEdit("0.0")); - - // find group - QGroupBox *find_group = new QGroupBox(tr("Find signal"), this); - QVBoxLayout *vlayout = new QVBoxLayout(find_group); - hlayout = new QHBoxLayout(); - hlayout->addWidget(new QLabel(tr("Value"))); - hlayout->addWidget(compare_cb = new QComboBox(this)); - hlayout->addWidget(value1 = new QLineEdit); - hlayout->addWidget(to_label = new QLabel("-")); - hlayout->addWidget(value2 = new QLineEdit); - hlayout->addWidget(undo_btn = new QPushButton(tr("Undo prev find"), this)); - hlayout->addWidget(search_btn = new QPushButton(tr("Find"))); - hlayout->addWidget(reset_btn = new QPushButton(tr("Reset"), this)); - vlayout->addLayout(hlayout); - - compare_cb->addItems({"=", ">", ">=", "!=", "<", "<=", "between"}); - value1->setFocus(Qt::OtherFocusReason); - value2->setVisible(false); - to_label->setVisible(false); - undo_btn->setEnabled(false); - reset_btn->setEnabled(false); - - auto double_validator = new DoubleValidator(this); - for (auto edit : {value1, value2, factor_edit, offset_edit, first_time_edit, last_time_edit}) { - edit->setValidator(double_validator); - } - - vlayout->addWidget(view = new QTableView(this)); - view->setContextMenuPolicy(Qt::CustomContextMenu); - view->horizontalHeader()->setStretchLastSection(true); - view->horizontalHeader()->setSelectionMode(QAbstractItemView::NoSelection); - view->setSelectionBehavior(QAbstractItemView::SelectRows); - view->setModel(model = new FindSignalModel(this)); - - hlayout = new QHBoxLayout(); - hlayout->addWidget(message_group); - hlayout->addWidget(properties_group); - main_layout->addLayout(hlayout); - main_layout->addWidget(find_group); - main_layout->addWidget(stats_label = new QLabel()); - - setMinimumSize({700, 650}); - QObject::connect(search_btn, &QPushButton::clicked, this, &FindSignalDlg::search); - QObject::connect(undo_btn, &QPushButton::clicked, model, &FindSignalModel::undo); - QObject::connect(model, &QAbstractItemModel::modelReset, this, &FindSignalDlg::modelReset); - QObject::connect(reset_btn, &QPushButton::clicked, model, &FindSignalModel::reset); - QObject::connect(view, &QTableView::customContextMenuRequested, this, &FindSignalDlg::customMenuRequested); - QObject::connect(view, &QTableView::doubleClicked, [this](const QModelIndex &index) { - if (index.isValid()) emit openMessage(model->filtered_signals[index.row()].id); - }); - QObject::connect(compare_cb, qOverload(&QComboBox::currentIndexChanged), [=](int index) { - to_label->setVisible(index == compare_cb->count() - 1); - value2->setVisible(index == compare_cb->count() - 1); - }); -} - -void FindSignalDlg::search() { - if (model->histories.isEmpty()) { - setInitialSignals(); - } - auto v1 = value1->text().toDouble(); - auto v2 = value2->text().toDouble(); - std::function cmp = nullptr; - switch (compare_cb->currentIndex()) { - case 0: cmp = [v1](double v) { return v == v1;}; break; - case 1: cmp = [v1](double v) { return v > v1;}; break; - case 2: cmp = [v1](double v) { return v >= v1;}; break; - case 3: cmp = [v1](double v) { return v != v1;}; break; - case 4: cmp = [v1](double v) { return v < v1;}; break; - case 5: cmp = [v1](double v) { return v <= v1;}; break; - case 6: cmp = [v1, v2](double v) { return v >= v1 && v <= v2;}; break; - } - properties_group->setEnabled(false); - message_group->setEnabled(false); - search_btn->setEnabled(false); - stats_label->setVisible(false); - search_btn->setText("Finding ...."); - QTimer::singleShot(0, this, [=]() { model->search(cmp); }); -} - -void FindSignalDlg::setInitialSignals() { - QSet buses; - for (auto bus : bus_edit->text().trimmed().split(",")) { - bus = bus.trimmed(); - if (!bus.isEmpty()) buses.insert(bus.toUShort()); - } - - QSet addresses; - for (auto addr : address_edit->text().trimmed().split(",")) { - addr = addr.trimmed(); - if (!addr.isEmpty()) addresses.insert(addr.toULong(nullptr, 16)); - } - - cabana::Signal sig{}; - sig.is_little_endian = litter_endian->isChecked(); - sig.is_signed = is_signed->isChecked(); - sig.factor = factor_edit->text().toDouble(); - sig.offset = offset_edit->text().toDouble(); - - double first_time_val = first_time_edit->text().toDouble(); - double last_time_val = last_time_edit->text().toDouble(); - auto [first_sec, last_sec] = std::minmax(first_time_val, last_time_val); - uint64_t first_time = (can->routeStartTime() + first_sec) * 1e9; - model->last_time = std::numeric_limits::max(); - if (last_sec > 0) { - model->last_time = (can->routeStartTime() + last_sec) * 1e9; - } - model->initial_signals.clear(); - - for (const auto &[id, m] : can->lastMessages()) { - if (buses.isEmpty() || buses.contains(id.source) && (addresses.isEmpty() || addresses.contains(id.address))) { - const auto &events = can->events(id); - auto e = std::lower_bound(events.cbegin(), events.cend(), first_time, CompareCanEvent()); - if (e != events.cend()) { - const int total_size = m.dat.size() * 8; - for (int size = min_size->value(); size <= max_size->value(); ++size) { - for (int start = 0; start <= total_size - size; ++start) { - FindSignalModel::SearchSignal s{.id = id, .mono_time = first_time, .sig = sig}; - s.sig.start_bit = start; - s.sig.size = size; - updateMsbLsb(s.sig); - s.value = get_raw_value((*e)->dat, (*e)->size, s.sig); - model->initial_signals.push_back(s); - } - } - } - } - } -} - -void FindSignalDlg::modelReset() { - properties_group->setEnabled(model->histories.isEmpty()); - message_group->setEnabled(model->histories.isEmpty()); - search_btn->setText(model->histories.isEmpty() ? tr("Find") : tr("Find Next")); - reset_btn->setEnabled(!model->histories.isEmpty()); - undo_btn->setEnabled(model->histories.size() > 1); - search_btn->setEnabled(model->rowCount() > 0 || model->histories.isEmpty()); - stats_label->setVisible(true); - stats_label->setText(tr("%1 matches. right click on an item to create signal. double click to open message").arg(model->filtered_signals.size())); -} - -void FindSignalDlg::customMenuRequested(const QPoint &pos) { - if (auto index = view->indexAt(pos); index.isValid()) { - QMenu menu(this); - menu.addAction(tr("Create Signal")); - if (menu.exec(view->mapToGlobal(pos))) { - auto &s = model->filtered_signals[index.row()]; - UndoStack::push(new AddSigCommand(s.id, s.sig)); - emit openMessage(s.id); - } - } -} diff --git a/tools/cabana/tools/findsignal.h b/tools/cabana/tools/findsignal.h deleted file mode 100644 index 5ef7461..0000000 --- a/tools/cabana/tools/findsignal.h +++ /dev/null @@ -1,64 +0,0 @@ -#pragma once - -#include -#include - -#include -#include -#include -#include -#include - -#include "tools/cabana/commands.h" -#include "tools/cabana/settings.h" - -class FindSignalModel : public QAbstractTableModel { -public: - struct SearchSignal { - MessageId id = {}; - uint64_t mono_time = 0; - cabana::Signal sig = {}; - double value = 0.; - QStringList values; - }; - - FindSignalModel(QObject *parent) : QAbstractTableModel(parent) {} - QVariant headerData(int section, Qt::Orientation orientation, int role = Qt::DisplayRole) const override; - QVariant data(const QModelIndex &index, int role = Qt::DisplayRole) const override; - int columnCount(const QModelIndex &parent = QModelIndex()) const override { return 3; } - int rowCount(const QModelIndex &parent = QModelIndex()) const override { return std::min(filtered_signals.size(), 300); } - void search(std::function cmp); - void reset(); - void undo(); - - QList filtered_signals; - QList initial_signals; - QList> histories; - uint64_t last_time = std::numeric_limits::max(); -}; - -class FindSignalDlg : public QDialog { - Q_OBJECT -public: - FindSignalDlg(QWidget *parent); - -signals: - void openMessage(const MessageId &id); - -private: - void search(); - void modelReset(); - void setInitialSignals(); - void customMenuRequested(const QPoint &pos); - - QLineEdit *value1, *value2, *factor_edit, *offset_edit; - QLineEdit *bus_edit, *address_edit, *first_time_edit, *last_time_edit; - QComboBox *compare_cb; - QSpinBox *min_size, *max_size; - QCheckBox *litter_endian, *is_signed; - QPushButton *search_btn, *reset_btn, *undo_btn; - QGroupBox *properties_group, *message_group; - QTableView *view; - QLabel *to_label, *stats_label; - FindSignalModel *model; -}; diff --git a/tools/cabana/tools/findsimilarbits.cc b/tools/cabana/tools/findsimilarbits.cc deleted file mode 100644 index c3c6597..0000000 --- a/tools/cabana/tools/findsimilarbits.cc +++ /dev/null @@ -1,160 +0,0 @@ -#include "tools/cabana/tools/findsimilarbits.h" - -#include - -#include -#include -#include -#include -#include -#include -#include - -#include "tools/cabana/dbc/dbcmanager.h" -#include "tools/cabana/streams/abstractstream.h" - -FindSimilarBitsDlg::FindSimilarBitsDlg(QWidget *parent) : QDialog(parent, Qt::WindowFlags() | Qt::Window) { - setWindowTitle(tr("Find similar bits")); - setAttribute(Qt::WA_DeleteOnClose); - - QVBoxLayout *main_layout = new QVBoxLayout(this); - - QHBoxLayout *src_layout = new QHBoxLayout(); - src_bus_combo = new QComboBox(this); - find_bus_combo = new QComboBox(this); - for (auto cb : {src_bus_combo, find_bus_combo}) { - for (uint8_t bus : can->sources) { - cb->addItem(QString::number(bus), bus); - } - } - - msg_cb = new QComboBox(this); - // TODO: update when src_bus_combo changes - for (auto &[address, msg] : dbc()->getMessages(-1)) { - msg_cb->addItem(msg.name, address); - } - msg_cb->model()->sort(0); - msg_cb->setCurrentIndex(0); - - byte_idx_sb = new QSpinBox(this); - byte_idx_sb->setFixedWidth(50); - byte_idx_sb->setRange(0, 63); - - bit_idx_sb = new QSpinBox(this); - bit_idx_sb->setFixedWidth(50); - bit_idx_sb->setRange(0, 7); - - src_layout->addWidget(new QLabel(tr("Bus"))); - src_layout->addWidget(src_bus_combo); - src_layout->addWidget(msg_cb); - src_layout->addWidget(new QLabel(tr("Byte Index"))); - src_layout->addWidget(byte_idx_sb); - src_layout->addWidget(new QLabel(tr("Bit Index"))); - src_layout->addWidget(bit_idx_sb); - src_layout->addStretch(0); - - QHBoxLayout *find_layout = new QHBoxLayout(); - find_layout->addWidget(new QLabel(tr("Bus"))); - find_layout->addWidget(find_bus_combo); - find_layout->addWidget(new QLabel(tr("Equal"))); - equal_combo = new QComboBox(this); - equal_combo->addItems({"Yes", "No"}); - find_layout->addWidget(equal_combo); - min_msgs = new QLineEdit(this); - min_msgs->setValidator(new QIntValidator(this)); - min_msgs->setText("100"); - find_layout->addWidget(new QLabel(tr("Min msg count"))); - find_layout->addWidget(min_msgs); - search_btn = new QPushButton(tr("&Find"), this); - find_layout->addWidget(search_btn); - find_layout->addStretch(0); - - QGridLayout *grid_layout = new QGridLayout(); - grid_layout->addWidget(new QLabel("Find From:"), 0, 0); - grid_layout->addLayout(src_layout, 0, 1); - grid_layout->addWidget(new QLabel("Find In:"), 1, 0); - grid_layout->addLayout(find_layout, 1, 1); - main_layout->addLayout(grid_layout); - - table = new QTableWidget(this); - table->setSelectionBehavior(QAbstractItemView::SelectRows); - table->setSelectionMode(QAbstractItemView::SingleSelection); - table->setEditTriggers(QAbstractItemView::NoEditTriggers); - table->horizontalHeader()->setStretchLastSection(true); - main_layout->addWidget(table); - - setMinimumSize({700, 500}); - QObject::connect(search_btn, &QPushButton::clicked, this, &FindSimilarBitsDlg::find); - QObject::connect(table, &QTableWidget::doubleClicked, [this](const QModelIndex &index) { - if (index.isValid()) { - MessageId msg_id = {.source = (uint8_t)find_bus_combo->currentData().toUInt(), .address = table->item(index.row(), 0)->text().toUInt(0, 16)}; - emit openMessage(msg_id); - } - }); -} - -void FindSimilarBitsDlg::find() { - search_btn->setEnabled(false); - table->clear(); - uint32_t selected_address = msg_cb->currentData().toUInt(); - auto msg_mismatched = calcBits(src_bus_combo->currentText().toUInt(), selected_address, byte_idx_sb->value(), bit_idx_sb->value(), - find_bus_combo->currentText().toUInt(), equal_combo->currentIndex() == 0, min_msgs->text().toInt()); - table->setRowCount(msg_mismatched.size()); - table->setColumnCount(6); - table->setHorizontalHeaderLabels({"address", "byte idx", "bit idx", "mismatches", "total msgs", "% mismatched"}); - for (int i = 0; i < msg_mismatched.size(); ++i) { - auto &m = msg_mismatched[i]; - table->setItem(i, 0, new QTableWidgetItem(QString("%1").arg(m.address, 1, 16))); - table->setItem(i, 1, new QTableWidgetItem(QString::number(m.byte_idx))); - table->setItem(i, 2, new QTableWidgetItem(QString::number(m.bit_idx))); - table->setItem(i, 3, new QTableWidgetItem(QString::number(m.mismatches))); - table->setItem(i, 4, new QTableWidgetItem(QString::number(m.total))); - table->setItem(i, 5, new QTableWidgetItem(QString::number(m.perc, 'f', 2))); - } - search_btn->setEnabled(true); -} - -QList FindSimilarBitsDlg::calcBits(uint8_t bus, uint32_t selected_address, int byte_idx, - int bit_idx, uint8_t find_bus, bool equal, int min_msgs_cnt) { - QHash> mismatches; - QHash msg_count; - const auto &events = can->allEvents(); - int bit_to_find = -1; - for (const CanEvent *e : events) { - if (e->src == bus) { - if (e->address == selected_address && e->size > byte_idx) { - bit_to_find = ((e->dat[byte_idx] >> (7 - bit_idx)) & 1) != 0; - } - } - if (e->src == find_bus) { - ++msg_count[e->address]; - if (bit_to_find == -1) continue; - - auto &mismatched = mismatches[e->address]; - if (mismatched.size() < e->size * 8) { - mismatched.resize(e->size * 8); - } - for (int i = 0; i < e->size; ++i) { - for (int j = 0; j < 8; ++j) { - int bit = ((e->dat[i] >> (7 - j)) & 1) != 0; - mismatched[i * 8 + j] += equal ? (bit != bit_to_find) : (bit == bit_to_find); - } - } - } - } - - QList result; - result.reserve(mismatches.size()); - for (auto it = mismatches.begin(); it != mismatches.end(); ++it) { - if (auto cnt = msg_count[it.key()]; cnt > min_msgs_cnt) { - auto &mismatched = it.value(); - for (int i = 0; i < mismatched.size(); ++i) { - if (float perc = (mismatched[i] / (double)cnt) * 100; perc < 50) { - result.push_back({it.key(), (uint32_t)i / 8, (uint32_t)i % 8, mismatched[i], cnt, perc}); - } - } - } - } - std::sort(result.begin(), result.end(), [](auto &l, auto &r) { return l.perc < r.perc; }); - return result; -} diff --git a/tools/cabana/tools/findsimilarbits.h b/tools/cabana/tools/findsimilarbits.h deleted file mode 100644 index 77bfac1..0000000 --- a/tools/cabana/tools/findsimilarbits.h +++ /dev/null @@ -1,34 +0,0 @@ -#pragma once - -#include -#include -#include -#include -#include - -#include "tools/cabana/dbc/dbcmanager.h" - -class FindSimilarBitsDlg : public QDialog { - Q_OBJECT - -public: - FindSimilarBitsDlg(QWidget *parent); - -signals: - void openMessage(const MessageId &msg_id); - -private: - struct mismatched_struct { - uint32_t address, byte_idx, bit_idx, mismatches, total; - float perc; - }; - QList calcBits(uint8_t bus, uint32_t selected_address, int byte_idx, int bit_idx, uint8_t find_bus, - bool equal, int min_msgs_cnt); - void find(); - - QTableWidget *table; - QComboBox *src_bus_combo, *find_bus_combo, *msg_cb, *equal_combo; - QSpinBox *byte_idx_sb, *bit_idx_sb; - QPushButton *search_btn; - QLineEdit *min_msgs; -}; diff --git a/tools/cabana/util.cc b/tools/cabana/util.cc deleted file mode 100644 index f984230..0000000 --- a/tools/cabana/util.cc +++ /dev/null @@ -1,283 +0,0 @@ -#include "tools/cabana/util.h" - -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include -#include -#include - -#include "selfdrive/ui/qt/util.h" - -// SegmentTree - -void SegmentTree::build(const std::vector &arr) { - size = arr.size(); - tree.resize(4 * size); // size of the tree is 4 times the size of the array - if (size > 0) { - build_tree(arr, 1, 0, size - 1); - } -} - -void SegmentTree::build_tree(const std::vector &arr, int n, int left, int right) { - if (left == right) { - const double y = arr[left].y(); - tree[n] = {y, y}; - } else { - const int mid = (left + right) >> 1; - build_tree(arr, 2 * n, left, mid); - build_tree(arr, 2 * n + 1, mid + 1, right); - tree[n] = {std::min(tree[2 * n].first, tree[2 * n + 1].first), std::max(tree[2 * n].second, tree[2 * n + 1].second)}; - } -} - -std::pair SegmentTree::get_minmax(int n, int left, int right, int range_left, int range_right) const { - if (range_left > right || range_right < left) - return {std::numeric_limits::max(), std::numeric_limits::lowest()}; - if (range_left <= left && range_right >= right) - return tree[n]; - int mid = (left + right) >> 1; - auto l = get_minmax(2 * n, left, mid, range_left, range_right); - auto r = get_minmax(2 * n + 1, mid + 1, right, range_left, range_right); - return {std::min(l.first, r.first), std::max(l.second, r.second)}; -} - -// MessageBytesDelegate - -MessageBytesDelegate::MessageBytesDelegate(QObject *parent, bool multiple_lines) : multiple_lines(multiple_lines), QStyledItemDelegate(parent) { - fixed_font = QFontDatabase::systemFont(QFontDatabase::FixedFont); - byte_size = QFontMetrics(fixed_font).size(Qt::TextSingleLine, "00 ") + QSize(0, 2); - for (int i = 0; i < 256; ++i) { - hex_text_table[i].setText(QStringLiteral("%1").arg(i, 2, 16, QLatin1Char('0')).toUpper()); - hex_text_table[i].prepare({}, fixed_font); - } - h_margin = QApplication::style()->pixelMetric(QStyle::PM_FocusFrameHMargin) + 1; - v_margin = QApplication::style()->pixelMetric(QStyle::PM_FocusFrameVMargin) + 1; -} - -QSize MessageBytesDelegate::sizeForBytes(int n) const { - int rows = multiple_lines ? std::max(1, n / 8) : 1; - return {(n / rows) * byte_size.width() + h_margin * 2, rows * byte_size.height() + v_margin * 2}; -} - -QSize MessageBytesDelegate::sizeHint(const QStyleOptionViewItem &option, const QModelIndex &index) const { - auto data = index.data(BytesRole); - return sizeForBytes(data.isValid() ? static_cast *>(data.value())->size() : 0); -} - -void MessageBytesDelegate::paint(QPainter *painter, const QStyleOptionViewItem &option, const QModelIndex &index) const { - auto data = index.data(BytesRole); - if (!data.isValid()) { - return QStyledItemDelegate::paint(painter, option, index); - } - - QFont old_font = painter->font(); - QPen old_pen = painter->pen(); - if (option.state & QStyle::State_Selected) { - painter->fillRect(option.rect, option.palette.brush(QPalette::Normal, QPalette::Highlight)); - } - const QPoint pt{option.rect.left() + h_margin, option.rect.top() + v_margin}; - painter->setFont(fixed_font); - - const auto &bytes = *static_cast*>(data.value()); - const auto &colors = *static_cast*>(index.data(ColorsRole).value()); - for (int i = 0; i < bytes.size(); ++i) { - int row = !multiple_lines ? 0 : i / 8; - int column = !multiple_lines ? i : i % 8; - QRect r = QRect({pt.x() + column * byte_size.width(), pt.y() + row * byte_size.height()}, byte_size); - if (i < colors.size() && colors[i].alpha() > 0) { - if (option.state & QStyle::State_Selected) { - painter->setPen(option.palette.color(QPalette::Text)); - painter->fillRect(r, option.palette.color(QPalette::Window)); - } - painter->fillRect(r, colors[i]); - } else if (option.state & QStyle::State_Selected) { - painter->setPen(option.palette.color(QPalette::HighlightedText)); - } - utils::drawStaticText(painter, r, hex_text_table[bytes[i]]); - } - painter->setFont(old_font); - painter->setPen(old_pen); -} - -// TabBar - -int TabBar::addTab(const QString &text) { - int index = QTabBar::addTab(text); - QToolButton *btn = new ToolButton("x", tr("Close Tab")); - int width = style()->pixelMetric(QStyle::PM_TabCloseIndicatorWidth, nullptr, btn); - int height = style()->pixelMetric(QStyle::PM_TabCloseIndicatorHeight, nullptr, btn); - btn->setFixedSize({width, height}); - setTabButton(index, QTabBar::RightSide, btn); - QObject::connect(btn, &QToolButton::clicked, this, &TabBar::closeTabClicked); - return index; -} - -void TabBar::closeTabClicked() { - QObject *object = sender(); - for (int i = 0; i < count(); ++i) { - if (tabButton(i, QTabBar::RightSide) == object) { - emit tabCloseRequested(i); - break; - } - } -} - -// UnixSignalHandler - -UnixSignalHandler::UnixSignalHandler(QObject *parent) : QObject(nullptr) { - if (::socketpair(AF_UNIX, SOCK_STREAM, 0, sig_fd)) { - qFatal("Couldn't create TERM socketpair"); - } - - sn = new QSocketNotifier(sig_fd[1], QSocketNotifier::Read, this); - connect(sn, &QSocketNotifier::activated, this, &UnixSignalHandler::handleSigTerm); - std::signal(SIGINT, signalHandler); - std::signal(SIGTERM, UnixSignalHandler::signalHandler); -} - -UnixSignalHandler::~UnixSignalHandler() { - ::close(sig_fd[0]); - ::close(sig_fd[1]); -} - -void UnixSignalHandler::signalHandler(int s) { - ::write(sig_fd[0], &s, sizeof(s)); -} - -void UnixSignalHandler::handleSigTerm() { - sn->setEnabled(false); - int tmp; - ::read(sig_fd[1], &tmp, sizeof(tmp)); - - printf("\nexiting...\n"); - qApp->closeAllWindows(); - qApp->exit(); -} - -// NameValidator - -NameValidator::NameValidator(QObject *parent) : QRegExpValidator(QRegExp("^(\\w+)"), parent) {} - -QValidator::State NameValidator::validate(QString &input, int &pos) const { - input.replace(' ', '_'); - return QRegExpValidator::validate(input, pos); -} - -DoubleValidator::DoubleValidator(QObject *parent) : QDoubleValidator(parent) { - // Match locale of QString::toDouble() instead of system - QLocale locale(QLocale::C); - locale.setNumberOptions(QLocale::RejectGroupSeparator); - setLocale(locale); -} - -namespace utils { -QPixmap icon(const QString &id) { - bool dark_theme = settings.theme == DARK_THEME; - QPixmap pm; - QString key = "bootstrap_" % id % (dark_theme ? "1" : "0"); - if (!QPixmapCache::find(key, &pm)) { - pm = bootstrapPixmap(id); - if (dark_theme) { - QPainter p(&pm); - p.setCompositionMode(QPainter::CompositionMode_SourceIn); - p.fillRect(pm.rect(), QColor("#bbbbbb")); - } - QPixmapCache::insert(key, pm); - } - return pm; -} - -void setTheme(int theme) { - auto style = QApplication::style(); - if (!style) return; - - static int prev_theme = 0; - if (theme != prev_theme) { - prev_theme = theme; - QPalette new_palette; - if (theme == DARK_THEME) { - // "Darcula" like dark theme - new_palette.setColor(QPalette::Window, QColor("#353535")); - new_palette.setColor(QPalette::WindowText, QColor("#bbbbbb")); - new_palette.setColor(QPalette::Base, QColor("#3c3f41")); - new_palette.setColor(QPalette::AlternateBase, QColor("#3c3f41")); - new_palette.setColor(QPalette::ToolTipBase, QColor("#3c3f41")); - new_palette.setColor(QPalette::ToolTipText, QColor("#bbb")); - new_palette.setColor(QPalette::Text, QColor("#bbbbbb")); - new_palette.setColor(QPalette::Button, QColor("#3c3f41")); - new_palette.setColor(QPalette::ButtonText, QColor("#bbbbbb")); - new_palette.setColor(QPalette::Highlight, QColor("#2f65ca")); - new_palette.setColor(QPalette::HighlightedText, QColor("#bbbbbb")); - new_palette.setColor(QPalette::BrightText, QColor("#f0f0f0")); - new_palette.setColor(QPalette::Disabled, QPalette::ButtonText, QColor("#777777")); - new_palette.setColor(QPalette::Disabled, QPalette::WindowText, QColor("#777777")); - new_palette.setColor(QPalette::Disabled, QPalette::Text, QColor("#777777")); - new_palette.setColor(QPalette::Light, QColor("#777777")); - new_palette.setColor(QPalette::Dark, QColor("#353535")); - } else { - new_palette = style->standardPalette(); - } - qApp->setPalette(new_palette); - style->polish(qApp); - for (auto w : QApplication::allWidgets()) { - w->setPalette(new_palette); - } - } -} - -QString formatSeconds(double sec, bool include_milliseconds, bool absolute_time) { - QString format = absolute_time ? "yyyy-MM-dd hh:mm:ss" - : (sec > 60 * 60 ? "hh:mm:ss" : "mm:ss"); - if (include_milliseconds) format += ".zzz"; - return QDateTime::fromMSecsSinceEpoch(sec * 1000).toString(format); -} - -} // namespace utils - -int num_decimals(double num) { - const QString string = QString::number(num); - auto dot_pos = string.indexOf('.'); - return dot_pos == -1 ? 0 : string.size() - dot_pos - 1; -} - -QString signalToolTip(const cabana::Signal *sig) { - return QObject::tr(R"( - %1
- Start Bit: %2 Size: %3
- MSB: %4 LSB: %5
- Little Endian: %6 Signed: %7
- )").arg(sig->name).arg(sig->start_bit).arg(sig->size).arg(sig->msb).arg(sig->lsb) - .arg(sig->is_little_endian ? "Y" : "N").arg(sig->is_signed ? "Y" : "N"); -} - -// MonotonicBuffer - -void *MonotonicBuffer::allocate(size_t bytes, size_t alignment) { - assert(bytes > 0); - void *p = std::align(alignment, bytes, current_buf, available); - if (p == nullptr) { - available = next_buffer_size = std::max(next_buffer_size, bytes); - current_buf = buffers.emplace_back(std::aligned_alloc(alignment, next_buffer_size)); - next_buffer_size *= growth_factor; - p = current_buf; - } - - current_buf = (char *)current_buf + bytes; - available -= bytes; - return p; -} - -MonotonicBuffer::~MonotonicBuffer() { - for (auto buf : buffers) { - free(buf); - } -} diff --git a/tools/cabana/util.h b/tools/cabana/util.h deleted file mode 100644 index 158321f..0000000 --- a/tools/cabana/util.h +++ /dev/null @@ -1,179 +0,0 @@ -#pragma once - -#include -#include -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include "tools/cabana/dbc/dbc.h" -#include "tools/cabana/settings.h" - -class LogSlider : public QSlider { - Q_OBJECT - -public: - LogSlider(double factor, Qt::Orientation orientation, QWidget *parent = nullptr) : factor(factor), QSlider(orientation, parent) {} - - void setRange(double min, double max) { - log_min = factor * std::log10(min); - log_max = factor * std::log10(max); - QSlider::setRange(min, max); - setValue(QSlider::value()); - } - int value() const { - double v = log_min + (log_max - log_min) * ((QSlider::value() - minimum()) / double(maximum() - minimum())); - return std::lround(std::pow(10, v / factor)); - } - void setValue(int v) { - double log_v = std::clamp(factor * std::log10(v), log_min, log_max); - v = minimum() + (maximum() - minimum()) * ((log_v - log_min) / (log_max - log_min)); - QSlider::setValue(v); - } - -private: - double factor, log_min = 0, log_max = 1; -}; - -enum { - ColorsRole = Qt::UserRole + 1, - BytesRole = Qt::UserRole + 2 -}; - -class SegmentTree { -public: - SegmentTree() = default; - void build(const std::vector &arr); - inline std::pair minmax(int left, int right) const { return get_minmax(1, 0, size - 1, left, right); } - -private: - std::pair get_minmax(int n, int left, int right, int range_left, int range_right) const; - void build_tree(const std::vector &arr, int n, int left, int right); - std::vector> tree; - int size = 0; -}; - -class MessageBytesDelegate : public QStyledItemDelegate { - Q_OBJECT -public: - MessageBytesDelegate(QObject *parent, bool multiple_lines = false); - void paint(QPainter *painter, const QStyleOptionViewItem &option, const QModelIndex &index) const override; - QSize sizeHint(const QStyleOptionViewItem &option, const QModelIndex &index) const override; - bool multipleLines() const { return multiple_lines; } - void setMultipleLines(bool v) { multiple_lines = v; } - QSize sizeForBytes(int n) const; - -private: - std::array hex_text_table; - QFont fixed_font; - QSize byte_size = {}; - bool multiple_lines = false; - int h_margin, v_margin; -}; - -class NameValidator : public QRegExpValidator { - Q_OBJECT -public: - NameValidator(QObject *parent=nullptr); - QValidator::State validate(QString &input, int &pos) const override; -}; - -class DoubleValidator : public QDoubleValidator { - Q_OBJECT -public: - DoubleValidator(QObject *parent = nullptr); -}; - -namespace utils { -QPixmap icon(const QString &id); -void setTheme(int theme); -QString formatSeconds(double sec, bool include_milliseconds = false, bool absolute_time = false); -inline void drawStaticText(QPainter *p, const QRect &r, const QStaticText &text) { - auto size = (r.size() - text.size()) / 2; - p->drawStaticText(r.left() + size.width(), r.top() + size.height(), text); -} -inline QString toHex(const std::vector &dat, char separator = '\0') { - return QByteArray::fromRawData((const char *)dat.data(), dat.size()).toHex(separator).toUpper(); -} - -} - -class ToolButton : public QToolButton { - Q_OBJECT -public: - ToolButton(const QString &icon, const QString &tooltip = {}, QWidget *parent = nullptr) : QToolButton(parent) { - setIcon(icon); - setToolTip(tooltip); - setAutoRaise(true); - const int metric = QApplication::style()->pixelMetric(QStyle::PM_SmallIconSize); - setIconSize({metric, metric}); - theme = settings.theme; - connect(&settings, &Settings::changed, this, &ToolButton::updateIcon); - } - void setIcon(const QString &icon) { - icon_str = icon; - QToolButton::setIcon(utils::icon(icon_str)); - } - -private: - void updateIcon() { if (std::exchange(theme, settings.theme) != theme) setIcon(icon_str); } - QString icon_str; - int theme; -}; - -class TabBar : public QTabBar { - Q_OBJECT - -public: - TabBar(QWidget *parent) : QTabBar(parent) {} - int addTab(const QString &text); - -private: - void closeTabClicked(); -}; - -class UnixSignalHandler : public QObject { - Q_OBJECT - -public: - UnixSignalHandler(QObject *parent = nullptr); - ~UnixSignalHandler(); - static void signalHandler(int s); - -public slots: - void handleSigTerm(); - -private: - inline static int sig_fd[2] = {}; - QSocketNotifier *sn; -}; - -class MonotonicBuffer { -public: - MonotonicBuffer(size_t initial_size) : next_buffer_size(initial_size) {} - ~MonotonicBuffer(); - void *allocate(size_t bytes, size_t alignment = 16ul); - void deallocate(void *p) {} - -private: - void *current_buf = nullptr; - size_t next_buffer_size = 0; - size_t available = 0; - std::deque buffers; - static constexpr float growth_factor = 1.5; -}; - -int num_decimals(double num); -QString signalToolTip(const cabana::Signal *sig); diff --git a/tools/cabana/videowidget.cc b/tools/cabana/videowidget.cc deleted file mode 100644 index a6fd0b2..0000000 --- a/tools/cabana/videowidget.cc +++ /dev/null @@ -1,411 +0,0 @@ -#include "tools/cabana/videowidget.h" - -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include "tools/cabana/streams/replaystream.h" - -const int MIN_VIDEO_HEIGHT = 100; -const int THUMBNAIL_MARGIN = 3; - -static const QColor timeline_colors[] = { - [(int)TimelineType::None] = QColor(111, 143, 175), - [(int)TimelineType::Engaged] = QColor(0, 163, 108), - [(int)TimelineType::UserFlag] = Qt::magenta, - [(int)TimelineType::AlertInfo] = Qt::green, - [(int)TimelineType::AlertWarning] = QColor(255, 195, 0), - [(int)TimelineType::AlertCritical] = QColor(199, 0, 57), -}; - -VideoWidget::VideoWidget(QWidget *parent) : QFrame(parent) { - setFrameStyle(QFrame::StyledPanel | QFrame::Plain); - auto main_layout = new QVBoxLayout(this); - if (!can->liveStreaming()) - main_layout->addWidget(createCameraWidget()); - main_layout->addLayout(createPlaybackController()); - - setSizePolicy(QSizePolicy::Preferred, QSizePolicy::Maximum); - QObject::connect(can, &AbstractStream::paused, this, &VideoWidget::updatePlayBtnState); - QObject::connect(can, &AbstractStream::resume, this, &VideoWidget::updatePlayBtnState); - QObject::connect(can, &AbstractStream::msgsReceived, this, &VideoWidget::updateState); - - updatePlayBtnState(); - setWhatsThis(tr(R"( - Video
- - Timeline color -
%1%2%4%5%6%7
- - - - - - -
Disengaged Engaged
User Flag Info
Warning Critical
- Shortcuts
- Pause/Resume:  space  - )").arg(timeline_colors[(int)TimelineType::None].name(), - timeline_colors[(int)TimelineType::Engaged].name(), - timeline_colors[(int)TimelineType::UserFlag].name(), - timeline_colors[(int)TimelineType::AlertInfo].name(), - timeline_colors[(int)TimelineType::AlertWarning].name(), - timeline_colors[(int)TimelineType::AlertCritical].name())); -} - -QHBoxLayout *VideoWidget::createPlaybackController() { - QHBoxLayout *layout = new QHBoxLayout(); - layout->addWidget(seek_backward_btn = new ToolButton("rewind", tr("Seek backward"))); - layout->addWidget(play_btn = new ToolButton("play", tr("Play"))); - layout->addWidget(seek_forward_btn = new ToolButton("fast-forward", tr("Seek forward"))); - - if (can->liveStreaming()) { - layout->addWidget(skip_to_end_btn = new ToolButton("skip-end", tr("Skip to the end"), this)); - QObject::connect(skip_to_end_btn, &QToolButton::clicked, [this]() { - // set speed to 1.0 - speed_btn->menu()->actions()[7]->setChecked(true); - can->pause(false); - can->seekTo(can->totalSeconds() + 1); - }); - } - - layout->addWidget(time_btn = new QToolButton); - time_btn->setToolTip(settings.absolute_time ? tr("Elapsed time") : tr("Absolute time")); - time_btn->setAutoRaise(true); - layout->addStretch(0); - - if (!can->liveStreaming()) { - layout->addWidget(loop_btn = new ToolButton("repeat", tr("Loop playback"))); - QObject::connect(loop_btn, &QToolButton::clicked, this, &VideoWidget::loopPlaybackClicked); - } - - // speed selector - layout->addWidget(speed_btn = new QToolButton(this)); - speed_btn->setAutoRaise(true); - speed_btn->setMenu(new QMenu(speed_btn)); - speed_btn->setPopupMode(QToolButton::InstantPopup); - QActionGroup *speed_group = new QActionGroup(this); - speed_group->setExclusive(true); - - int max_width = 0; - QFont font = speed_btn->font(); - font.setBold(true); - speed_btn->setFont(font); - QFontMetrics fm(font); - for (float speed : {0.01, 0.02, 0.05, 0.1, 0.2, 0.5, 0.8, 1., 2., 3., 5.}) { - QString name = QString("%1x").arg(speed); - max_width = std::max(max_width, fm.width(name) + fm.horizontalAdvance(QLatin1Char(' ')) * 2); - - QAction *act = new QAction(name, speed_group); - act->setCheckable(true); - QObject::connect(act, &QAction::toggled, [this, speed]() { - can->setSpeed(speed); - speed_btn->setText(QString("%1x ").arg(speed)); - }); - speed_btn->menu()->addAction(act); - if (speed == 1.0)act->setChecked(true); - } - speed_btn->setMinimumWidth(max_width + style()->pixelMetric(QStyle::PM_MenuButtonIndicator)); - - QObject::connect(play_btn, &QToolButton::clicked, []() { can->pause(!can->isPaused()); }); - QObject::connect(seek_backward_btn, &QToolButton::clicked, []() { can->seekTo(can->currentSec() - 1); }); - QObject::connect(seek_forward_btn, &QToolButton::clicked, []() { can->seekTo(can->currentSec() + 1); }); - QObject::connect(time_btn, &QToolButton::clicked, [this]() { - settings.absolute_time = !settings.absolute_time; - time_btn->setToolTip(settings.absolute_time ? tr("Elapsed time") : tr("Absolute time")); - updateState(); - }); - return layout; -} - -QWidget *VideoWidget::createCameraWidget() { - QWidget *w = new QWidget(this); - QVBoxLayout *l = new QVBoxLayout(w); - l->setContentsMargins(0, 0, 0, 0); - l->setSpacing(0); - - l->addWidget(camera_tab = new TabBar(w)); - camera_tab->setAutoHide(true); - camera_tab->setExpanding(false); - - QStackedLayout *stacked = new QStackedLayout(); - stacked->setStackingMode(QStackedLayout::StackAll); - stacked->addWidget(cam_widget = new CameraWidget("camerad", VISION_STREAM_ROAD, false)); - cam_widget->setMinimumHeight(MIN_VIDEO_HEIGHT); - cam_widget->setSizePolicy(QSizePolicy::Preferred, QSizePolicy::MinimumExpanding); - stacked->addWidget(alert_label = new InfoLabel(this)); - l->addLayout(stacked); - - l->addWidget(slider = new Slider(w)); - slider->setSingleStep(0); - - setMaximumTime(can->totalSeconds()); - QObject::connect(slider, &QSlider::sliderReleased, [this]() { can->seekTo(slider->currentSecond()); }); - QObject::connect(slider, &Slider::updateMaximumTime, this, &VideoWidget::setMaximumTime, Qt::QueuedConnection); - QObject::connect(static_cast(can), &ReplayStream::qLogLoaded, slider, &Slider::parseQLog); - QObject::connect(cam_widget, &CameraWidget::clicked, []() { can->pause(!can->isPaused()); }); - QObject::connect(cam_widget, &CameraWidget::vipcAvailableStreamsUpdated, this, &VideoWidget::vipcAvailableStreamsUpdated); - QObject::connect(camera_tab, &QTabBar::currentChanged, [this](int index) { - if (index != -1) cam_widget->setStreamType((VisionStreamType)camera_tab->tabData(index).toInt()); - }); - return w; -} - -void VideoWidget::vipcAvailableStreamsUpdated(std::set streams) { - static const QString stream_names[] = { - [VISION_STREAM_ROAD] = "Road camera", - [VISION_STREAM_WIDE_ROAD] = "Wide road camera", - [VISION_STREAM_DRIVER] = "Driver camera"}; - - for (int i = 0; i < streams.size(); ++i) { - if (camera_tab->count() <= i) { - camera_tab->addTab(QString()); - } - int type = *std::next(streams.begin(), i); - camera_tab->setTabText(i, stream_names[type]); - camera_tab->setTabData(i, type); - } - while (camera_tab->count() > streams.size()) { - camera_tab->removeTab(camera_tab->count() - 1); - } -} - -void VideoWidget::loopPlaybackClicked() { - auto replay = qobject_cast(can)->getReplay(); - if (!replay) return; - - if (replay->hasFlag(REPLAY_FLAG_NO_LOOP)) { - replay->removeFlag(REPLAY_FLAG_NO_LOOP); - loop_btn->setIcon("repeat"); - } else { - replay->addFlag(REPLAY_FLAG_NO_LOOP); - loop_btn->setIcon("repeat-1"); - } -} - -void VideoWidget::setMaximumTime(double sec) { - maximum_time = sec; - slider->setTimeRange(0, sec); -} - -void VideoWidget::updateTimeRange(double min, double max, bool is_zoomed) { - if (can->liveStreaming()) { - skip_to_end_btn->setEnabled(!is_zoomed); - return; - } - is_zoomed ? slider->setTimeRange(min, max) - : slider->setTimeRange(0, maximum_time); -} - -QString VideoWidget::formatTime(double sec, bool include_milliseconds) { - if (settings.absolute_time) - sec = can->beginDateTime().addMSecs(sec * 1000).toMSecsSinceEpoch() / 1000.0; - return utils::formatSeconds(sec, include_milliseconds, settings.absolute_time); -} - -void VideoWidget::updateState() { - if (slider) { - if (!slider->isSliderDown()) - slider->setCurrentSecond(can->currentSec()); - alert_label->showAlert(slider->alertInfo(can->currentSec())); - time_btn->setText(QString("%1 / %2").arg(formatTime(can->currentSec(), true), - formatTime(slider->maximum() / slider->factor))); - } else { - time_btn->setText(formatTime(can->currentSec(), true)); - } -} - -void VideoWidget::updatePlayBtnState() { - play_btn->setIcon(can->isPaused() ? "play" : "pause"); - play_btn->setToolTip(can->isPaused() ? tr("Play") : tr("Pause")); -} - -// Slider - -Slider::Slider(QWidget *parent) : QSlider(Qt::Horizontal, parent) { - thumbnail_label = new InfoLabel(parent); - setMouseTracking(true); -} - -AlertInfo Slider::alertInfo(double seconds) { - uint64_t mono_time = (seconds + can->routeStartTime()) * 1e9; - auto alert_it = alerts.lower_bound(mono_time); - bool has_alert = (alert_it != alerts.end()) && ((alert_it->first - mono_time) <= 1e8); - return has_alert ? alert_it->second : AlertInfo{}; -} - -QPixmap Slider::thumbnail(double seconds) { - uint64_t mono_time = (seconds + can->routeStartTime()) * 1e9; - auto it = thumbnails.lowerBound(mono_time); - return it != thumbnails.end() ? it.value() : QPixmap(); -} - -void Slider::setTimeRange(double min, double max) { - assert(min < max); - setRange(min * factor, max * factor); -} - -void Slider::parseQLog(int segnum, std::shared_ptr qlog) { - const auto &segments = qobject_cast(can)->route()->segments(); - if (segments.size() > 0 && segnum == segments.rbegin()->first && !qlog->events.empty()) { - emit updateMaximumTime(qlog->events.back()->mono_time / 1e9 - can->routeStartTime()); - } - - std::mutex mutex; - QtConcurrent::blockingMap(qlog->events.cbegin(), qlog->events.cend(), [&mutex, this](const Event *e) { - if (e->which == cereal::Event::Which::THUMBNAIL) { - auto thumb = e->event.getThumbnail(); - auto data = thumb.getThumbnail(); - if (QPixmap pm; pm.loadFromData(data.begin(), data.size(), "jpeg")) { - QPixmap scaled = pm.scaledToHeight(MIN_VIDEO_HEIGHT - THUMBNAIL_MARGIN * 2, Qt::SmoothTransformation); - std::lock_guard lk(mutex); - thumbnails[thumb.getTimestampEof()] = scaled; - } - } else if (e->which == cereal::Event::Which::CONTROLS_STATE) { - auto cs = e->event.getControlsState(); - if (cs.getAlertType().size() > 0 && cs.getAlertText1().size() > 0 && - cs.getAlertSize() != cereal::ControlsState::AlertSize::NONE) { - std::lock_guard lk(mutex); - alerts.emplace(e->mono_time, AlertInfo{cs.getAlertStatus(), cs.getAlertText1().cStr(), cs.getAlertText2().cStr()}); - } - } - }); - update(); -} - -void Slider::paintEvent(QPaintEvent *ev) { - QPainter p(this); - QRect r = rect().adjusted(0, 4, 0, -4); - p.fillRect(r, timeline_colors[(int)TimelineType::None]); - double min = minimum() / factor; - double max = maximum() / factor; - - auto fillRange = [&](double begin, double end, const QColor &color) { - if (begin > max || end < min) return; - r.setLeft(((std::max(min, begin) - min) / (max - min)) * width()); - r.setRight(((std::min(max, end) - min) / (max - min)) * width()); - p.fillRect(r, color); - }; - - const auto replay = qobject_cast(can)->getReplay(); - for (auto [begin, end, type] : replay->getTimeline()) { - fillRange(begin, end, timeline_colors[(int)type]); - } - - QColor empty_color = palette().color(QPalette::Window); - empty_color.setAlpha(160); - for (const auto &[n, seg] : replay->segments()) { - if (!(seg && seg->isLoaded())) - fillRange(n * 60.0, (n + 1) * 60.0, empty_color); - } - - QStyleOptionSlider opt; - opt.initFrom(this); - opt.minimum = minimum(); - opt.maximum = maximum(); - opt.subControls = QStyle::SC_SliderHandle; - opt.sliderPosition = value(); - style()->drawComplexControl(QStyle::CC_Slider, &opt, &p); -} - -void Slider::mousePressEvent(QMouseEvent *e) { - QSlider::mousePressEvent(e); - if (e->button() == Qt::LeftButton && !isSliderDown()) { - setValue(minimum() + ((maximum() - minimum()) * e->x()) / width()); - emit sliderReleased(); - } -} - -void Slider::mouseMoveEvent(QMouseEvent *e) { - int pos = std::clamp(e->pos().x(), 0, width()); - double seconds = (minimum() + pos * ((maximum() - minimum()) / (double)width())) / factor; - QPixmap thumb = thumbnail(seconds); - if (!thumb.isNull()) { - int x = std::clamp(pos - thumb.width() / 2, THUMBNAIL_MARGIN, width() - thumb.width() - THUMBNAIL_MARGIN + 1); - int y = -thumb.height() - THUMBNAIL_MARGIN; - thumbnail_label->showPixmap(mapToParent(QPoint(x, y)), utils::formatSeconds(seconds), thumb, alertInfo(seconds)); - } else { - thumbnail_label->hide(); - } - QSlider::mouseMoveEvent(e); -} - -bool Slider::event(QEvent *event) { - switch (event->type()) { - case QEvent::WindowActivate: - case QEvent::WindowDeactivate: - case QEvent::FocusIn: - case QEvent::FocusOut: - case QEvent::Leave: - thumbnail_label->hide(); - break; - default: - break; - } - return QSlider::event(event); -} - -// InfoLabel - -InfoLabel::InfoLabel(QWidget *parent) : QWidget(parent, Qt::WindowStaysOnTopHint) { - setAttribute(Qt::WA_ShowWithoutActivating); - setVisible(false); -} - -void InfoLabel::showPixmap(const QPoint &pt, const QString &sec, const QPixmap &pm, const AlertInfo &alert) { - second = sec; - pixmap = pm; - alert_info = alert; - setGeometry(QRect(pt, pm.size())); - setVisible(true); - update(); -} - -void InfoLabel::showAlert(const AlertInfo &alert) { - alert_info = alert; - pixmap = {}; - setVisible(!alert_info.text1.isEmpty()); - update(); -} - -void InfoLabel::paintEvent(QPaintEvent *event) { - QPainter p(this); - p.setPen(QPen(palette().color(QPalette::BrightText), 2)); - if (!pixmap.isNull()) { - p.drawPixmap(0, 0, pixmap); - p.drawRect(rect()); - p.drawText(rect().adjusted(0, 0, 0, -THUMBNAIL_MARGIN), second, Qt::AlignHCenter | Qt::AlignBottom); - } - if (alert_info.text1.size() > 0) { - QColor color = timeline_colors[(int)TimelineType::AlertInfo]; - if (alert_info.status == cereal::ControlsState::AlertStatus::USER_PROMPT) { - color = timeline_colors[(int)TimelineType::AlertWarning]; - } else if (alert_info.status == cereal::ControlsState::AlertStatus::CRITICAL) { - color = timeline_colors[(int)TimelineType::AlertCritical]; - } - color.setAlphaF(0.5); - QString text = alert_info.text1; - if (!alert_info.text2.isEmpty()) { - text += "\n" + alert_info.text2; - } - - if (!pixmap.isNull()) { - QFont font; - font.setPixelSize(11); - p.setFont(font); - } - QRect text_rect = rect().adjusted(2, 2, -2, -2); - QRect r = p.fontMetrics().boundingRect(text_rect, Qt::AlignTop | Qt::AlignHCenter | Qt::TextWordWrap, text); - p.fillRect(text_rect.left(), r.top(), text_rect.width(), r.height(), color); - p.drawText(text_rect, Qt::AlignTop | Qt::AlignHCenter | Qt::TextWordWrap, text); - } -} diff --git a/tools/cabana/videowidget.h b/tools/cabana/videowidget.h deleted file mode 100644 index 67c2c8a..0000000 --- a/tools/cabana/videowidget.h +++ /dev/null @@ -1,90 +0,0 @@ -#pragma once - -#include -#include -#include - -#include -#include -#include -#include - -#include "selfdrive/ui/qt/widgets/cameraview.h" -#include "tools/cabana/util.h" -#include "tools/replay/logreader.h" - -struct AlertInfo { - cereal::ControlsState::AlertStatus status; - QString text1; - QString text2; -}; - -class InfoLabel : public QWidget { -public: - InfoLabel(QWidget *parent); - void showPixmap(const QPoint &pt, const QString &sec, const QPixmap &pm, const AlertInfo &alert); - void showAlert(const AlertInfo &alert); - void paintEvent(QPaintEvent *event) override; - QPixmap pixmap; - QString second; - AlertInfo alert_info; -}; - -class Slider : public QSlider { - Q_OBJECT - -public: - Slider(QWidget *parent); - double currentSecond() const { return value() / factor; } - void setCurrentSecond(double sec) { setValue(sec * factor); } - void setTimeRange(double min, double max); - AlertInfo alertInfo(double sec); - QPixmap thumbnail(double sec); - void parseQLog(int segnum, std::shared_ptr qlog); - - const double factor = 1000.0; - -signals: - void updateMaximumTime(double); - -private: - void mousePressEvent(QMouseEvent *e) override; - void mouseMoveEvent(QMouseEvent *e) override; - bool event(QEvent *event) override; - void paintEvent(QPaintEvent *ev) override; - - QMap thumbnails; - std::map alerts; - InfoLabel *thumbnail_label; -}; - -class VideoWidget : public QFrame { - Q_OBJECT - -public: - VideoWidget(QWidget *parnet = nullptr); - void updateTimeRange(double min, double max, bool is_zommed); - void setMaximumTime(double sec); - -protected: - QString formatTime(double sec, bool include_milliseconds = false); - void updateState(); - void updatePlayBtnState(); - QWidget *createCameraWidget(); - QHBoxLayout *createPlaybackController(); - void loopPlaybackClicked(); - void vipcAvailableStreamsUpdated(std::set streams); - - CameraWidget *cam_widget; - double maximum_time = 0; - QToolButton *time_btn = nullptr; - ToolButton *seek_backward_btn = nullptr; - ToolButton *play_btn = nullptr; - ToolButton *seek_forward_btn = nullptr; - ToolButton *loop_btn = nullptr; - QToolButton *speed_btn = nullptr; - ToolButton *skip_to_end_btn = nullptr; - InfoLabel *alert_label = nullptr; - Slider *slider = nullptr; - QTabBar *camera_tab = nullptr; -}; diff --git a/tools/camerastream/compressed_vipc.py b/tools/camerastream/compressed_vipc.py deleted file mode 100644 index c6e05a0..0000000 --- a/tools/camerastream/compressed_vipc.py +++ /dev/null @@ -1,139 +0,0 @@ -#!/usr/bin/env python3 -import av -import os -import sys -import argparse -import numpy as np -import multiprocessing -import time - -import cereal.messaging as messaging -from cereal.visionipc import VisionIpcServer, VisionStreamType - -W, H = 1928, 1208 -V4L2_BUF_FLAG_KEYFRAME = 8 - -ENCODE_SOCKETS = { - VisionStreamType.VISION_STREAM_ROAD: "roadEncodeData", - VisionStreamType.VISION_STREAM_WIDE_ROAD: "wideRoadEncodeData", - VisionStreamType.VISION_STREAM_DRIVER: "driverEncodeData", -} - -def decoder(addr, vst, nvidia, debug=False): - vipc_server = VisionIpcServer("camerad") - vipc_server.create_buffers(vst, 4, False, W, H) - vipc_server.start_listener() - - sock_name = ENCODE_SOCKETS[vst] - if debug: - print("start decoder for %s" % sock_name) - if nvidia: - os.environ["NV_LOW_LATENCY"] = "3" # both bLowLatency and CUVID_PKT_ENDOFPICTURE - sys.path += os.environ["LD_LIBRARY_PATH"].split(":") - import PyNvCodec as nvc - - nvDec = nvc.PyNvDecoder(W, H, nvc.PixelFormat.NV12, nvc.CudaVideoCodec.HEVC, 0) - cc1 = nvc.ColorspaceConversionContext(nvc.ColorSpace.BT_709, nvc.ColorRange.JPEG) - conv_yuv = nvc.PySurfaceConverter(W, H, nvc.PixelFormat.NV12, nvc.PixelFormat.YUV420, 0) - nvDwn_yuv = nvc.PySurfaceDownloader(W, H, nvc.PixelFormat.YUV420, 0) - img_yuv = np.ndarray((H*W//2*3), dtype=np.uint8) - else: - codec = av.CodecContext.create("hevc", "r") - - os.environ["ZMQ"] = "1" - messaging.context = messaging.Context() - sock = messaging.sub_sock(sock_name, None, addr=addr, conflate=False) - cnt = 0 - last_idx = -1 - seen_iframe = False - - time_q = [] - while 1: - msgs = messaging.drain_sock(sock, wait_for_one=True) - for evt in msgs: - evta = getattr(evt, evt.which()) - if debug and evta.idx.encodeId != 0 and evta.idx.encodeId != (last_idx+1): - print("DROP PACKET!") - last_idx = evta.idx.encodeId - if not seen_iframe and not (evta.idx.flags & V4L2_BUF_FLAG_KEYFRAME): - if debug: - print("waiting for iframe") - continue - time_q.append(time.monotonic()) - network_latency = (int(time.time()*1e9) - evta.unixTimestampNanos)/1e6 - frame_latency = ((evta.idx.timestampEof/1e9) - (evta.idx.timestampSof/1e9))*1000 - process_latency = ((evt.logMonoTime/1e9) - (evta.idx.timestampEof/1e9))*1000 - - # put in header (first) - if not seen_iframe: - if nvidia: - nvDec.DecodeSurfaceFromPacket(np.frombuffer(evta.header, dtype=np.uint8)) - else: - codec.decode(av.packet.Packet(evta.header)) - seen_iframe = True - - if nvidia: - rawSurface = nvDec.DecodeSurfaceFromPacket(np.frombuffer(evta.data, dtype=np.uint8)) - if rawSurface.Empty(): - if debug: - print("DROP SURFACE") - continue - convSurface = conv_yuv.Execute(rawSurface, cc1) - nvDwn_yuv.DownloadSingleSurface(convSurface, img_yuv) - else: - frames = codec.decode(av.packet.Packet(evta.data)) - if len(frames) == 0: - if debug: - print("DROP SURFACE") - continue - assert len(frames) == 1 - img_yuv = frames[0].to_ndarray(format=av.video.format.VideoFormat('yuv420p')).flatten() - uv_offset = H*W - y = img_yuv[:uv_offset] - uv = img_yuv[uv_offset:].reshape(2, -1).ravel('F') - img_yuv = np.hstack((y, uv)) - - vipc_server.send(vst, img_yuv.data, cnt, int(time_q[0]*1e9), int(time.monotonic()*1e9)) - cnt += 1 - - pc_latency = (time.monotonic()-time_q[0])*1000 - time_q = time_q[1:] - if debug: - print("%2d %4d %.3f %.3f roll %6.2f ms latency %6.2f ms + %6.2f ms + %6.2f ms = %6.2f ms" - % (len(msgs), evta.idx.encodeId, evt.logMonoTime/1e9, evta.idx.timestampEof/1e6, frame_latency, - process_latency, network_latency, pc_latency, process_latency+network_latency+pc_latency ), len(evta.data), sock_name) - -class CompressedVipc: - def __init__(self, addr, vision_streams, nvidia=False, debug=False): - self.procs = [] - for vst in vision_streams: - p = multiprocessing.Process(target=decoder, args=(addr, vst, nvidia, debug)) - p.start() - self.procs.append(p) - - def join(self): - for p in self.procs: - p.join() - - def kill(self): - for p in self.procs: - p.terminate() - self.join() - -if __name__ == "__main__": - parser = argparse.ArgumentParser(description="Decode video streams and broadcast on VisionIPC") - parser.add_argument("addr", help="Address of comma three") - parser.add_argument("--nvidia", action="store_true", help="Use nvidia instead of ffmpeg") - parser.add_argument("--cams", default="0,1,2", help="Cameras to decode") - parser.add_argument("--silent", action="store_true", help="Suppress debug output") - args = parser.parse_args() - - vision_streams = [ - VisionStreamType.VISION_STREAM_ROAD, - VisionStreamType.VISION_STREAM_WIDE_ROAD, - VisionStreamType.VISION_STREAM_DRIVER, - ] - - vsts = [vision_streams[int(x)] for x in args.cams.split(",")] - cvipc = CompressedVipc(args.addr, vsts, args.nvidia, debug=(not args.silent)) - cvipc.join() diff --git a/tools/camerastream/receive.py b/tools/camerastream/receive.py deleted file mode 100644 index bf6929c..0000000 --- a/tools/camerastream/receive.py +++ /dev/null @@ -1,44 +0,0 @@ -#!/usr/bin/env python -import os -import sys -import numpy as np -os.environ['ZMQ'] = '1' - -from openpilot.common.window import Window -import cereal.messaging as messaging - -# start camerad with 'SEND_ROAD=1 SEND_DRIVER=1 SEND_WIDE_ROAD=1 XMIN=771 XMAX=1156 YMIN=483 YMAX=724 ./camerad' -# also start bridge -# then run this "./receive.py " - -if "FULL" in os.environ: - SCALE = 2 - XMIN, XMAX = 0, 1927 - YMIN, YMAX = 0, 1207 -else: - SCALE = 1 - XMIN = 771 - XMAX = 1156 - YMIN = 483 - YMAX = 724 -H, W = ((YMAX-YMIN+1)//SCALE, (XMAX-XMIN+1)//SCALE) - -if __name__ == '__main__': - cameras = ['roadCameraState', 'wideRoadCameraState', 'driverCameraState'] - if "CAM" in os.environ: - cam = int(os.environ['CAM']) - cameras = cameras[cam:cam+1] - sm = messaging.SubMaster(cameras, addr=sys.argv[1]) - win = Window(W*len(cameras), H) - bdat = np.zeros((H, W*len(cameras), 3), dtype=np.uint8) - - while 1: - sm.update() - for i,k in enumerate(cameras): - if sm.updated[k]: - #print("update", k) - bgr_raw = sm[k].image - dat = np.frombuffer(bgr_raw, dtype=np.uint8).reshape(H, W, 3)[:, :, [2,1,0]] - bdat[:, W*i:W*(i+1)] = dat - win.draw(bdat) - diff --git a/tools/install_python_dependencies.sh b/tools/install_python_dependencies.sh deleted file mode 100644 index 6753aff..0000000 --- a/tools/install_python_dependencies.sh +++ /dev/null @@ -1,86 +0,0 @@ -#!/usr/bin/env bash -set -e - -DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null && pwd )" -ROOT=$DIR/../ -cd $ROOT - -RC_FILE="${HOME}/.$(basename ${SHELL})rc" -if [ "$(uname)" == "Darwin" ] && [ $SHELL == "/bin/bash" ]; then - RC_FILE="$HOME/.bash_profile" -fi - -if ! command -v "pyenv" > /dev/null 2>&1; then - echo "pyenv install ..." - curl -L https://github.com/pyenv/pyenv-installer/raw/master/bin/pyenv-installer | bash - PYENV_PATH_SETUP="export PATH=\$HOME/.pyenv/bin:\$HOME/.pyenv/shims:\$PATH" -fi - -if [ -z "$PYENV_SHELL" ] || [ -n "$PYENV_PATH_SETUP" ]; then - echo "pyenvrc setup ..." - cat < "${HOME}/.pyenvrc" -if [ -z "\$PYENV_ROOT" ]; then - $PYENV_PATH_SETUP - export PYENV_ROOT="\$HOME/.pyenv" - eval "\$(pyenv init -)" - eval "\$(pyenv virtualenv-init -)" -fi -EOF - - SOURCE_PYENVRC="source ~/.pyenvrc" - if ! grep "^$SOURCE_PYENVRC$" $RC_FILE > /dev/null; then - printf "\n$SOURCE_PYENVRC\n" >> $RC_FILE - fi - - eval "$SOURCE_PYENVRC" - # $(pyenv init -) produces a function which is broken on bash 3.2 which ships on macOS - if [ $(uname) == "Darwin" ]; then - unset -f pyenv - fi -fi - -export MAKEFLAGS="-j$(nproc)" - -PYENV_PYTHON_VERSION=$(cat $ROOT/.python-version) -if ! pyenv prefix ${PYENV_PYTHON_VERSION} &> /dev/null; then - # no pyenv update on mac - if [ "$(uname)" == "Linux" ]; then - echo "pyenv update ..." - pyenv update - fi - echo "python ${PYENV_PYTHON_VERSION} install ..." - CONFIGURE_OPTS="--enable-shared" pyenv install -f ${PYENV_PYTHON_VERSION} -fi -eval "$(pyenv init --path)" - -echo "update pip" -pip install pip==23.3 -pip install poetry==1.6.1 - -poetry config virtualenvs.prefer-active-python true --local -poetry config virtualenvs.in-project true --local - -echo "PYTHONPATH=${PWD}" > $ROOT/.env -if [[ "$(uname)" == 'Darwin' ]]; then - echo "# msgq doesn't work on mac" >> $ROOT/.env - echo "export ZMQ=1" >> $ROOT/.env - echo "export OBJC_DISABLE_INITIALIZE_FORK_SAFETY=YES" >> $ROOT/.env -fi - -poetry self add poetry-dotenv-plugin@^0.1.0 - -echo "pip packages install..." -poetry install --no-cache --no-root -pyenv rehash - -[ -n "$POETRY_VIRTUALENVS_CREATE" ] && RUN="" || RUN="poetry run" - -if [ "$(uname)" != "Darwin" ]; then - echo "pre-commit hooks install..." - shopt -s nullglob - for f in .pre-commit-config.yaml */.pre-commit-config.yaml; do - if [ -e "$ROOT/$(dirname $f)/.git" ]; then - $RUN pre-commit install -c "$f" - fi - done -fi diff --git a/tools/install_ubuntu_dependencies.sh b/tools/install_ubuntu_dependencies.sh deleted file mode 100644 index 78a01f2..0000000 --- a/tools/install_ubuntu_dependencies.sh +++ /dev/null @@ -1,135 +0,0 @@ -#!/usr/bin/env bash -set -e - -SUDO="" - -# Use sudo if not root -if [[ ! $(id -u) -eq 0 ]]; then - if [[ -z $(which sudo) ]]; then - echo "Please install sudo or run as root" - exit 1 - fi - SUDO="sudo" -fi - -# Install packages present in all supported versions of Ubuntu -function install_ubuntu_common_requirements() { - $SUDO apt-get update - $SUDO apt-get install -y --no-install-recommends \ - autoconf \ - build-essential \ - ca-certificates \ - casync \ - clang \ - cmake \ - make \ - cppcheck \ - libtool \ - gcc-arm-none-eabi \ - bzip2 \ - liblzma-dev \ - libarchive-dev \ - libbz2-dev \ - capnproto \ - libcapnp-dev \ - curl \ - libcurl4-openssl-dev \ - git \ - git-lfs \ - ffmpeg \ - libavformat-dev \ - libavcodec-dev \ - libavdevice-dev \ - libavutil-dev \ - libavfilter-dev \ - libeigen3-dev \ - libffi-dev \ - libglew-dev \ - libgles2-mesa-dev \ - libglfw3-dev \ - libglib2.0-0 \ - libncurses5-dev \ - libncursesw5-dev \ - libomp-dev \ - libopencv-dev \ - libpng16-16 \ - libportaudio2 \ - libssl-dev \ - libsqlite3-dev \ - libusb-1.0-0-dev \ - libzmq3-dev \ - libsystemd-dev \ - locales \ - opencl-headers \ - ocl-icd-libopencl1 \ - ocl-icd-opencl-dev \ - clinfo \ - portaudio19-dev \ - qml-module-qtquick2 \ - qtmultimedia5-dev \ - qtlocation5-dev \ - qtpositioning5-dev \ - qttools5-dev-tools \ - libqt5sql5-sqlite \ - libqt5svg5-dev \ - libqt5charts5-dev \ - libqt5serialbus5-dev \ - libqt5x11extras5-dev \ - libreadline-dev \ - libdw1 \ - valgrind -} - -# Install Ubuntu 22.04 LTS packages -function install_ubuntu_lts_latest_requirements() { - install_ubuntu_common_requirements - - $SUDO apt-get install -y --no-install-recommends \ - g++-12 \ - qtbase5-dev \ - qtchooser \ - qt5-qmake \ - qtbase5-dev-tools \ - python3-dev -} - -# Install Ubuntu 20.04 packages -function install_ubuntu_focal_requirements() { - install_ubuntu_common_requirements - - $SUDO apt-get install -y --no-install-recommends \ - libavresample-dev \ - qt5-default \ - python-dev -} - -# Detect OS using /etc/os-release file -if [ -f "/etc/os-release" ]; then - source /etc/os-release - case "$VERSION_CODENAME" in - "jammy") - install_ubuntu_lts_latest_requirements - ;; - "kinetic") - install_ubuntu_lts_latest_requirements - ;; - "focal") - install_ubuntu_focal_requirements - ;; - *) - echo "$ID $VERSION_ID is unsupported. This setup script is written for Ubuntu 20.04." - read -p "Would you like to attempt installation anyway? " -n 1 -r - echo "" - if [[ ! $REPLY =~ ^[Yy]$ ]]; then - exit 1 - fi - if [ "$UBUNTU_CODENAME" = "jammy" ] || [ "$UBUNTU_CODENAME" = "kinetic" ]; then - install_ubuntu_lts_latest_requirements - else - install_ubuntu_focal_requirements - fi - esac -else - echo "No /etc/os-release in the system" - exit 1 -fi diff --git a/tools/latencylogger/README.md b/tools/latencylogger/README.md deleted file mode 100644 index c40ec1b..0000000 --- a/tools/latencylogger/README.md +++ /dev/null @@ -1,92 +0,0 @@ -# LatencyLogger - -LatencyLogger is a tool to track the time from first pixel to actuation. Timestamps are printed in a table as well as plotted in a graph. Start openpilot with `LOG_TIMESTAMPS=1` set to enable the necessary logging. - -## Usage - -``` -$ python latency_logger.py -h -usage: latency_logger.py [-h] [--relative] [--demo] [--plot] [route_or_segment_name] - -A tool for analyzing openpilot's end-to-end latency - -positional arguments: - route_or_segment_name - The route to print (default: None) - -optional arguments: - -h, --help show this help message and exit - --relative Make timestamps relative to the start of each frame (default: False) - --demo Use the demo route instead of providing one (default: False) - --plot If a plot should be generated (default: False) - --offset Offset service to better visualize overlap (default: False) -``` -To timestamp an event, use `LOGT("msg")` in c++ code or `cloudlog.timestamp("msg")` in python code. If the print is warning for frameId assignment ambiguity, use `LOGT(frameId ,"msg")`. - -## Examples - -Timestamps are visualized as diamonds - -| | Relative | Absolute | -| ------------- | ------------- | ------------- | -| Inline | ![inrel](https://user-images.githubusercontent.com/42323981/170559939-465df3b1-bf87-46d5-b5ee-5cc87dc49470.png) | ![inabs](https://user-images.githubusercontent.com/42323981/170559985-a82f87e7-82c4-4e48-a348-4221568dd589.png) | -| Offset | ![offrel](https://user-images.githubusercontent.com/42323981/170559854-93fba90f-acc4-4d08-b317-d3f8fc649ea8.png) | ![offabs](https://user-images.githubusercontent.com/42323981/170559782-06ed5599-d4e3-4701-ad78-5c1eec6cb61e.png) | - -Printed timestamps of a frame with internal durations. -``` -Frame ID: 1202 - camerad - wideRoadCameraState start of frame 0.0 - roadCameraState start of frame 0.049583 - wideRoadCameraState published 35.01206 - WideRoadCamera: Image set 35.020028 - roadCameraState published 38.508261 - RoadCamera: Image set 38.520344 - RoadCamera: Transformed 38.616176 - wideRoadCameraState.processingTime 3.152403049170971 - roadCameraState.processingTime 6.453451234847307 - modeld - Image added 40.909841 - Extra image added 42.515027 - Execution finished 63.002552 - modelV2 published 63.148747 - modelV2.modelExecutionTime 23.62649142742157 - modelV2.gpuExecutionTime 0.0 - plannerd - lateralPlan published 66.915049 - longitudinalPlan published 69.715999 - lateralPlan.solverExecutionTime 0.8170719956979156 - longitudinalPlan.solverExecutionTime 0.5619999719783664 - controlsd - Data sampled 70.217763 - Events updated 71.037178 - sendcan published 72.278775 - controlsState published 72.825226 - Data sampled 80.008354 - Events updated 80.787666 - sendcan published 81.849682 - controlsState published 82.238323 - Data sampled 90.521123 - Events updated 91.626003 - sendcan published 93.413218 - controlsState published 94.143989 - Data sampled 100.991497 - Events updated 101.973774 - sendcan published 103.565575 - controlsState published 104.146088 - Data sampled 110.284387 - Events updated 111.183541 - sendcan published 112.981692 - controlsState published 113.731994 - boardd - sending sendcan to panda: 250027001751393037323631 81.928119 - sendcan sent to panda: 250027001751393037323631 82.164834 - sending sendcan to panda: 250027001751393037323631 93.569986 - sendcan sent to panda: 250027001751393037323631 93.92795 - sending sendcan to panda: 250027001751393037323631 103.689167 - sendcan sent to panda: 250027001751393037323631 104.012235 - sending sendcan to panda: 250027001751393037323631 113.109555 - sendcan sent to panda: 250027001751393037323631 113.525487 - sending sendcan to panda: 250027001751393037323631 122.508434 - sendcan sent to panda: 250027001751393037323631 122.834314 -``` diff --git a/tools/latencylogger/latency_logger.py b/tools/latencylogger/latency_logger.py deleted file mode 100644 index f2adc97..0000000 --- a/tools/latencylogger/latency_logger.py +++ /dev/null @@ -1,244 +0,0 @@ -#!/usr/bin/env python3 -import argparse -import json -import matplotlib.patches as mpatches -import matplotlib.pyplot as plt -import mpld3 -import sys -from bisect import bisect_left, bisect_right -from collections import defaultdict - -from openpilot.tools.lib.logreader import logreader_from_route_or_segment - -DEMO_ROUTE = "9f583b1d93915c31|2022-05-18--10-49-51--0" - -SERVICES = ['camerad', 'modeld', 'plannerd', 'controlsd', 'boardd'] -# Retrieve controlsd frameId from lateralPlan, mismatch with longitudinalPlan will be ignored -MONOTIME_KEYS = ['modelMonoTime', 'lateralPlanMonoTime'] -MSGQ_TO_SERVICE = { - 'roadCameraState': 'camerad', - 'wideRoadCameraState': 'camerad', - 'modelV2': 'modeld', - 'lateralPlan': 'plannerd', - 'longitudinalPlan': 'plannerd', - 'sendcan': 'controlsd', - 'controlsState': 'controlsd' -} -SERVICE_TO_DURATIONS = { - 'camerad': ['processingTime'], - 'modeld': ['modelExecutionTime', 'gpuExecutionTime'], - 'plannerd': ['solverExecutionTime'], -} - -def read_logs(lr): - data = defaultdict(lambda: defaultdict(lambda: defaultdict(list))) - mono_to_frame = {} - frame_mismatches = [] - frame_id_fails = 0 - latest_sendcan_monotime = 0 - for msg in lr: - if msg.which() == 'sendcan': - latest_sendcan_monotime = msg.logMonoTime - continue - - if msg.which() in MSGQ_TO_SERVICE: - service = MSGQ_TO_SERVICE[msg.which()] - msg_obj = getattr(msg, msg.which()) - - frame_id = -1 - if hasattr(msg_obj, "frameId"): - frame_id = msg_obj.frameId - else: - continue_outer = False - for key in MONOTIME_KEYS: - if hasattr(msg_obj, key): - if getattr(msg_obj, key) == 0: - # Filter out controlsd messages which arrive before the camera loop - continue_outer = True - elif getattr(msg_obj, key) in mono_to_frame: - frame_id = mono_to_frame[getattr(msg_obj, key)] - if continue_outer: - continue - if frame_id == -1: - frame_id_fails += 1 - continue - mono_to_frame[msg.logMonoTime] = frame_id - data['timestamp'][frame_id][service].append((msg.which()+" published", msg.logMonoTime)) - - next_service = SERVICES[SERVICES.index(service)+1] - if not data['start'][frame_id][next_service]: - data['start'][frame_id][next_service] = msg.logMonoTime - data['end'][frame_id][service] = msg.logMonoTime - - if service in SERVICE_TO_DURATIONS: - for duration in SERVICE_TO_DURATIONS[service]: - data['duration'][frame_id][service].append((msg.which()+"."+duration, getattr(msg_obj, duration))) - - if service == SERVICES[0]: - data['timestamp'][frame_id][service].append((msg.which()+" start of frame", msg_obj.timestampSof)) - if not data['start'][frame_id][service]: - data['start'][frame_id][service] = msg_obj.timestampSof - elif msg.which() == 'controlsState': - # Sendcan is published before controlsState, but the frameId is retrieved in CS - data['timestamp'][frame_id][service].append(("sendcan published", latest_sendcan_monotime)) - elif msg.which() == 'modelV2': - if msg_obj.frameIdExtra != frame_id: - frame_mismatches.append(frame_id) - - if frame_id_fails > 20: - print("Warning, many frameId fetch fails", frame_id_fails) - if len(frame_mismatches) > 20: - print("Warning, many frame mismatches", len(frame_mismatches)) - return (data, frame_mismatches) - -# This is not needed in 3.10 as a "key" parameter is added to bisect -class KeyifyList(object): - def __init__(self, inner, key): - self.inner = inner - self.key = key - def __len__(self): - return len(self.inner) - def __getitem__(self, k): - return self.key(self.inner[k]) - -def find_frame_id(time, service, start_times, end_times): - left = bisect_left(KeyifyList(list(start_times.items()), - lambda x: x[1][service] if x[1][service] else -1), time) - 1 - right = bisect_right(KeyifyList(list(end_times.items()), - lambda x: x[1][service] if x[1][service] else float("inf")), time) - return left, right - -def find_t0(start_times, frame_id=-1): - frame_id = frame_id if frame_id > -1 else min(start_times.keys()) - m = max(start_times.keys()) - while frame_id <= m: - for service in SERVICES: - if start_times[frame_id][service]: - return start_times[frame_id][service] - frame_id += 1 - raise Exception('No start time has been set') - -def insert_cloudlogs(lr, timestamps, start_times, end_times): - # at least one cloudlog must be made in controlsd - - t0 = find_t0(start_times) - failed_inserts = 0 - latest_controls_frameid = 0 - for msg in lr: - if msg.which() == "logMessage": - jmsg = json.loads(msg.logMessage) - if "timestamp" in jmsg['msg']: - time = int(jmsg['msg']['timestamp']['time']) - service = jmsg['ctx']['daemon'] - event = jmsg['msg']['timestamp']['event'] - if time < t0: - # Filter out controlsd messages which arrive before the camera loop - continue - - if "frame_id" in jmsg['msg']['timestamp']: - timestamps[int(jmsg['msg']['timestamp']['frame_id'])][service].append((event, time)) - continue - - if service == "boardd": - timestamps[latest_controls_frameid][service].append((event, time)) - end_times[latest_controls_frameid][service] = time - else: - frame_id = find_frame_id(time, service, start_times, end_times) - if frame_id: - if frame_id[0] != frame_id[1]: - event += " (warning: ambiguity)" - frame_id = frame_id[0] - if service == 'controlsd': - latest_controls_frameid = frame_id - timestamps[frame_id][service].append((event, time)) - else: - failed_inserts += 1 - - if latest_controls_frameid == 0: - print("Warning: failed to bind boardd logs to a frame ID. Add a timestamp cloudlog in controlsd.") - elif failed_inserts > len(timestamps): - print(f"Warning: failed to bind {failed_inserts} cloudlog timestamps to a frame ID") - -def print_timestamps(timestamps, durations, start_times, relative): - t0 = find_t0(start_times) - for frame_id in timestamps.keys(): - print('='*80) - print("Frame ID:", frame_id) - if relative: - t0 = find_t0(start_times, frame_id) - - for service in SERVICES: - print(" "+service) - events = timestamps[frame_id][service] - for event, time in sorted(events, key = lambda x: x[1]): - print(" "+'%-53s%-53s' %(event, str((time-t0)/1e6))) - for event, time in durations[frame_id][service]: - print(" "+'%-53s%-53s' %(event, str(time*1000))) - -def graph_timestamps(timestamps, start_times, end_times, relative, offset_services=False, title=""): - # mpld3 doesn't convert properly to D3 font sizes - plt.rcParams.update({'font.size': 18}) - - t0 = find_t0(start_times) - fig, ax = plt.subplots() - ax.set_xlim(0, 130 if relative else 750) - ax.set_ylim(0, 17) - ax.set_xlabel('Time (milliseconds)') - colors = ['blue', 'green', 'red', 'yellow', 'purple'] - offsets = [[0, -5*j] for j in range(len(SERVICES))] if offset_services else None - height = 0.3 if offset_services else 0.9 - assert len(colors) == len(SERVICES), 'Each service needs a color' - - points = {"x": [], "y": [], "labels": []} - for i, (frame_id, services) in enumerate(timestamps.items()): - if relative: - t0 = find_t0(start_times, frame_id) - service_bars = [] - for service, events in services.items(): - if start_times[frame_id][service] and end_times[frame_id][service]: - start = start_times[frame_id][service] - end = end_times[frame_id][service] - service_bars.append(((start-t0)/1e6,(end-start)/1e6)) - for event in events: - points['x'].append((event[1]-t0)/1e6) - points['y'].append(i) - points['labels'].append(event[0]) - ax.broken_barh(service_bars, (i-height/2, height), facecolors=(colors), alpha=0.5, offsets=offsets) - - scatter = ax.scatter(points['x'], points['y'], marker='d', edgecolor='black') - tooltip = mpld3.plugins.PointLabelTooltip(scatter, labels=points['labels']) - mpld3.plugins.connect(fig, tooltip) - - plt.title(title) - # Set size relative window size is not trivial: https://github.com/mpld3/mpld3/issues/65 - fig.set_size_inches(18, 9) - plt.legend(handles=[mpatches.Patch(color=colors[i], label=SERVICES[i]) for i in range(len(SERVICES))]) - return fig - -def get_timestamps(lr): - lr = list(lr) - data, frame_mismatches = read_logs(lr) - insert_cloudlogs(lr, data['timestamp'], data['start'], data['end']) - return data, frame_mismatches - -if __name__ == "__main__": - parser = argparse.ArgumentParser(description="A tool for analyzing openpilot's end-to-end latency", - formatter_class = argparse.ArgumentDefaultsHelpFormatter) - parser.add_argument("--relative", action="store_true", help="Make timestamps relative to the start of each frame") - parser.add_argument("--demo", action="store_true", help="Use the demo route instead of providing one") - parser.add_argument("--plot", action="store_true", help="If a plot should be generated") - parser.add_argument("--offset", action="store_true", help="Vertically offset service to better visualize overlap") - parser.add_argument("route_or_segment_name", nargs='?', help="The route to print") - - if len(sys.argv) == 1: - parser.print_help() - sys.exit() - args = parser.parse_args() - - r = DEMO_ROUTE if args.demo else args.route_or_segment_name.strip() - lr = logreader_from_route_or_segment(r, sort_by_time=True) - - data, _ = get_timestamps(lr) - print_timestamps(data['timestamp'], data['duration'], data['start'], args.relative) - if args.plot: - mpld3.show(graph_timestamps(data['timestamp'], data['start'], data['end'], args.relative, offset_services=args.offset, title=r)) diff --git a/tools/mac_setup.sh b/tools/mac_setup.sh deleted file mode 100644 index 9ec2097..0000000 --- a/tools/mac_setup.sh +++ /dev/null @@ -1,115 +0,0 @@ -#!/usr/bin/env bash - -set -e - -if [ -z "$SKIP_PROMPT" ]; then - echo "--------------- macOS support ---------------" - echo "Running openpilot natively on macOS is not officially supported." - echo "It might build, some parts of it might work, but it's not fully tested, so there might be some issues." - echo - echo "Check out devcontainers for a seamless experience (see tools/README.md)." - echo "-------------------------------------------------" - echo -n "Are you sure you want to continue? [y/N] " - read -r response - if [[ ! "$response" =~ ^([yY][eE][sS]|[yY])+$ ]]; then - exit 1 - fi -fi - -DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null && pwd )" -ROOT="$(cd $DIR/../ && pwd)" -ARCH=$(uname -m) - -if [[ $SHELL == "/bin/zsh" ]]; then - RC_FILE="$HOME/.zshrc" -elif [[ $SHELL == "/bin/bash" ]]; then - RC_FILE="$HOME/.bash_profile" -fi - -# Install brew if required -if [[ $(command -v brew) == "" ]]; then - echo "Installing Hombrew" - /bin/bash -c "$(curl -fsSL https://raw.githubusercontent.com/Homebrew/install/master/install.sh)" - echo "[ ] installed brew t=$SECONDS" - - # make brew available now - if [[ $ARCH == "x86_64" ]]; then - echo 'eval "$(/usr/local/homebrew/bin/brew shellenv)"' >> $RC_FILE - eval "$(/usr/local/homebrew/bin/brew shellenv)" - else - echo 'eval "$(/opt/homebrew/bin/brew shellenv)"' >> $RC_FILE - eval "$(/opt/homebrew/bin/brew shellenv)" - fi -fi - -brew bundle --file=- <<-EOS -brew "catch2" -brew "cmake" -brew "cppcheck" -brew "git-lfs" -brew "zlib" -brew "bzip2" -brew "capnp" -brew "coreutils" -brew "eigen" -brew "ffmpeg" -brew "glfw" -brew "libarchive" -brew "libusb" -brew "libtool" -brew "llvm" -brew "openssl@3.0" -brew "pyenv" -brew "pyenv-virtualenv" -brew "qt@5" -brew "zeromq" -brew "gcc@13" -cask "gcc-arm-embedded" -brew "portaudio" -EOS - -echo "[ ] finished brew install t=$SECONDS" - -BREW_PREFIX=$(brew --prefix) - -# archive backend tools for pip dependencies -export LDFLAGS="$LDFLAGS -L${BREW_PREFIX}/opt/zlib/lib" -export LDFLAGS="$LDFLAGS -L${BREW_PREFIX}/opt/bzip2/lib" -export CPPFLAGS="$CPPFLAGS -I${BREW_PREFIX}/opt/zlib/include" -export CPPFLAGS="$CPPFLAGS -I${BREW_PREFIX}/opt/bzip2/include" - -# pycurl curl/openssl backend dependencies -export LDFLAGS="$LDFLAGS -L${BREW_PREFIX}/opt/openssl@3/lib" -export CPPFLAGS="$CPPFLAGS -I${BREW_PREFIX}/opt/openssl@3/include" -export PYCURL_CURL_CONFIG=/usr/bin/curl-config -export PYCURL_SSL_LIBRARY=openssl - -# install python dependencies -$DIR/install_python_dependencies.sh -echo "[ ] installed python dependencies t=$SECONDS" - -# brew does not link qt5 by default -# check if qt5 can be linked, if not, prompt the user to link it -QT_BIN_LOCATION="$(command -v lupdate || :)" -if [ -n "$QT_BIN_LOCATION" ]; then - # if qt6 is linked, prompt the user to unlink it and link the right version - QT_BIN_VERSION="$(lupdate -version | awk '{print $NF}')" - if [[ ! "$QT_BIN_VERSION" =~ 5\.[0-9]+\.[0-9]+ ]]; then - echo - echo "lupdate/lrelease available at PATH is $QT_BIN_VERSION" - if [[ "$QT_BIN_LOCATION" == "$(brew --prefix)/"* ]]; then - echo "Run the following command to link qt5:" - echo "brew unlink qt@6 && brew link qt@5" - else - echo "Remove conflicting qt entries from PATH and run the following command to link qt5:" - echo "brew link qt@5" - fi - fi -else - brew link qt@5 -fi - -echo -echo "---- OPENPILOT SETUP DONE ----" -echo "Open a new shell or configure your active shell env by running:" -echo "source $RC_FILE" diff --git a/tools/plotjuggler/.gitignore b/tools/plotjuggler/.gitignore deleted file mode 100644 index 45559d0..0000000 --- a/tools/plotjuggler/.gitignore +++ /dev/null @@ -1,3 +0,0 @@ -bin/ -bin -*.rlog diff --git a/tools/plotjuggler/README.md b/tools/plotjuggler/README.md deleted file mode 100644 index ca99461..0000000 --- a/tools/plotjuggler/README.md +++ /dev/null @@ -1,74 +0,0 @@ -# PlotJuggler - -[PlotJuggler](https://github.com/facontidavide/PlotJuggler) is a tool to quickly visualize time series data, and we've written plugins to parse openpilot logs. Check out our plugins: https://github.com/commaai/PlotJuggler. - -## Installation - -Once you've [set up the openpilot environment](../README.md), this command will download PlotJuggler and install our plugins: - -`cd tools/plotjuggler && ./juggle.py --install` - -## Usage - -``` -$ ./juggle.py -h -usage: juggle.py [-h] [--demo] [--qlog] [--ci] [--can] [--stream] [--layout [LAYOUT]] [--install] [--dbc DBC] - [route_or_segment_name] [segment_count] - -A helper to run PlotJuggler on openpilot routes - -positional arguments: - route_or_segment_name - The route or segment name to plot (cabana share URL accepted) (default: None) - segment_count The number of segments to plot (default: None) - -optional arguments: - -h, --help show this help message and exit - --demo Use the demo route instead of providing one (default: False) - --qlog Use qlogs (default: False) - --ci Download data from openpilot CI bucket (default: False) - --can Parse CAN data (default: False) - --stream Start PlotJuggler in streaming mode (default: False) - --layout [LAYOUT] Run PlotJuggler with a pre-defined layout (default: None) - --install Install or update PlotJuggler + plugins (default: False) - --dbc DBC Set the DBC name to load for parsing CAN data. If not set, the DBC will be automatically - inferred from the logs. (default: None) - -``` - -Examples using route name: - -`./juggle.py "a2a0ccea32023010|2023-07-27--13-01-19"` - -Examples using segment name: - -`./juggle.py "a2a0ccea32023010|2023-07-27--13-01-19--1"` - -## Streaming - -Explore live data from your car! Follow these steps to stream from your comma device to your laptop: -- Enable wifi tethering on your comma device -- [SSH into your device](https://github.com/commaai/openpilot/wiki/SSH) and run `cd /data/openpilot && ./cereal/messaging/bridge` -- On your laptop, connect to the device's wifi hotspot -- Start PlotJuggler with `ZMQ=1 ./juggle.py --stream`, find the `Cereal Subscriber` plugin in the dropdown under Streaming, and click `Start`. - -If streaming to PlotJuggler from a replay on your PC, simply run: `./juggle.py --stream` and start the cereal subscriber. - -## Demo - -For a quick demo, go through the installation step and run this command: - -`./juggle.py --demo --qlog --layout=layouts/demo.xml` - -## Layouts - -If you create a layout that's useful for others, consider upstreaming it. - -### Tuning - -Use this layout to improve your car's tuning and generate plots for tuning PRs. Also see the [tuning wiki](https://github.com/commaai/openpilot/wiki/Tuning) and tuning PR template. - -`--layout layouts/tuning.xml` - - -![screenshot](https://i.imgur.com/cizHCH3.png) diff --git a/tools/plotjuggler/juggle.py b/tools/plotjuggler/juggle.py deleted file mode 100644 index 02858b1..0000000 --- a/tools/plotjuggler/juggle.py +++ /dev/null @@ -1,180 +0,0 @@ -#!/usr/bin/env python3 -import os -import sys -import multiprocessing -import platform -import shutil -import subprocess -import tarfile -import tempfile -import requests -import argparse - -from openpilot.common.basedir import BASEDIR -from openpilot.selfdrive.test.openpilotci import get_url -from openpilot.tools.lib.logreader import LogReader -from openpilot.tools.lib.route import Route, SegmentName -from openpilot.tools.lib.helpers import save_log -from urllib.parse import urlparse, parse_qs - -juggle_dir = os.path.dirname(os.path.realpath(__file__)) - -DEMO_ROUTE = "a2a0ccea32023010|2023-07-27--13-01-19" -RELEASES_URL="https://github.com/commaai/PlotJuggler/releases/download/latest" -INSTALL_DIR = os.path.join(juggle_dir, "bin") -PLOTJUGGLER_BIN = os.path.join(juggle_dir, "bin/plotjuggler") -MINIMUM_PLOTJUGGLER_VERSION = (3, 5, 2) -MAX_STREAMING_BUFFER_SIZE = 1000 - -def install(): - m = f"{platform.system()}-{platform.machine()}" - supported = ("Linux-x86_64", "Darwin-arm64", "Darwin-x86_64") - if m not in supported: - raise Exception(f"Unsupported platform: '{m}'. Supported platforms: {supported}") - - if os.path.exists(INSTALL_DIR): - shutil.rmtree(INSTALL_DIR) - os.mkdir(INSTALL_DIR) - - url = os.path.join(RELEASES_URL, m + ".tar.gz") - with requests.get(url, stream=True, timeout=10) as r, tempfile.NamedTemporaryFile() as tmp: - r.raise_for_status() - with open(tmp.name, 'wb') as tmpf: - for chunk in r.iter_content(chunk_size=1024*1024): - tmpf.write(chunk) - - with tarfile.open(tmp.name) as tar: - tar.extractall(path=INSTALL_DIR) - - -def get_plotjuggler_version(): - out = subprocess.check_output([PLOTJUGGLER_BIN, "-v"], encoding="utf-8").strip() - version = out.split(" ")[1] - return tuple(map(int, version.split("."))) - - -def load_segment(segment_name): - if segment_name is None: - return [] - - try: - return list(LogReader(segment_name)) - except (AssertionError, ValueError) as e: - print(f"Error parsing {segment_name}: {e}") - return [] - - -def start_juggler(fn=None, dbc=None, layout=None, route_or_segment_name=None): - env = os.environ.copy() - env["BASEDIR"] = BASEDIR - env["PATH"] = f"{INSTALL_DIR}:{os.getenv('PATH', '')}" - if dbc: - env["DBC_NAME"] = dbc - - extra_args = "" - if fn is not None: - extra_args += f" -d {fn}" - if layout is not None: - extra_args += f" -l {layout}" - if route_or_segment_name is not None: - extra_args += f" --window_title \"{route_or_segment_name}\"" - - cmd = f'{PLOTJUGGLER_BIN} --buffer_size {MAX_STREAMING_BUFFER_SIZE} --plugin_folders {INSTALL_DIR}{extra_args}' - subprocess.call(cmd, shell=True, env=env, cwd=juggle_dir) - - -def juggle_route(route_or_segment_name, segment_count, qlog, can, layout, dbc=None, ci=False): - segment_start = 0 - if 'cabana' in route_or_segment_name: - query = parse_qs(urlparse(route_or_segment_name).query) - route_or_segment_name = query["route"][0] - - if route_or_segment_name.startswith(("http://", "https://", "cd:/")) or os.path.isfile(route_or_segment_name): - logs = [route_or_segment_name] - elif ci: - route_or_segment_name = SegmentName(route_or_segment_name, allow_route_name=True) - route = route_or_segment_name.route_name.canonical_name - segment_start = max(route_or_segment_name.segment_num, 0) - logs = [get_url(route, i) for i in range(100)] # Assume there not more than 100 segments - else: - route_or_segment_name = SegmentName(route_or_segment_name, allow_route_name=True) - segment_start = max(route_or_segment_name.segment_num, 0) - - if route_or_segment_name.segment_num != -1 and segment_count is None: - segment_count = 1 - - r = Route(route_or_segment_name.route_name.canonical_name, route_or_segment_name.data_dir) - logs = r.qlog_paths() if qlog else r.log_paths() - - segment_end = segment_start + segment_count if segment_count else None - logs = logs[segment_start:segment_end] - - if None in logs: - resp = input(f"{logs.count(None)}/{len(logs)} of the rlogs in this segment are missing, would you like to fall back to the qlogs? (y/n) ") - if resp == 'y': - logs = r.qlog_paths()[segment_start:segment_end] - else: - print("Please try a different route or segment") - return - - all_data = [] - with multiprocessing.Pool(24) as pool: - for d in pool.map(load_segment, logs): - all_data += d - - if not can: - all_data = [d for d in all_data if d.which() not in ['can', 'sendcan']] - - # Infer DBC name from logs - if dbc is None: - for cp in [m for m in all_data if m.which() == 'carParams']: - try: - DBC = __import__(f"openpilot.selfdrive.car.{cp.carParams.carName}.values", fromlist=['DBC']).DBC - dbc = DBC[cp.carParams.carFingerprint]['pt'] - except Exception: - pass - break - - with tempfile.NamedTemporaryFile(suffix='.rlog', dir=juggle_dir) as tmp: - save_log(tmp.name, all_data, compress=False) - del all_data - start_juggler(tmp.name, dbc, layout, route_or_segment_name) - - -if __name__ == "__main__": - parser = argparse.ArgumentParser(description="A helper to run PlotJuggler on openpilot routes", - formatter_class=argparse.ArgumentDefaultsHelpFormatter) - - parser.add_argument("--demo", action="store_true", help="Use the demo route instead of providing one") - parser.add_argument("--qlog", action="store_true", help="Use qlogs") - parser.add_argument("--ci", action="store_true", help="Download data from openpilot CI bucket") - parser.add_argument("--can", action="store_true", help="Parse CAN data") - parser.add_argument("--stream", action="store_true", help="Start PlotJuggler in streaming mode") - parser.add_argument("--layout", nargs='?', help="Run PlotJuggler with a pre-defined layout") - parser.add_argument("--install", action="store_true", help="Install or update PlotJuggler + plugins") - parser.add_argument("--dbc", help="Set the DBC name to load for parsing CAN data. If not set, the DBC will be automatically inferred from the logs.") - parser.add_argument("route_or_segment_name", nargs='?', help="The route or segment name to plot (cabana share URL accepted)") - parser.add_argument("segment_count", type=int, nargs='?', help="The number of segments to plot") - - if len(sys.argv) == 1: - parser.print_help() - sys.exit() - args = parser.parse_args() - - if args.install: - install() - sys.exit() - - if not os.path.exists(PLOTJUGGLER_BIN): - print("PlotJuggler is missing. Downloading...") - install() - - if get_plotjuggler_version() < MINIMUM_PLOTJUGGLER_VERSION: - print("PlotJuggler is out of date. Installing update...") - install() - - if args.stream: - start_juggler(layout=args.layout) - else: - route_or_segment_name = DEMO_ROUTE if args.demo else args.route_or_segment_name.strip() - juggle_route(route_or_segment_name, args.segment_count, args.qlog, args.can, args.layout, args.dbc, args.ci) diff --git a/tools/plotjuggler/layouts/CAN-bus-debug.xml b/tools/plotjuggler/layouts/CAN-bus-debug.xml deleted file mode 100644 index f5b74ae..0000000 --- a/tools/plotjuggler/layouts/CAN-bus-debug.xml +++ /dev/null @@ -1,86 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/tools/plotjuggler/layouts/camera-timings.xml b/tools/plotjuggler/layouts/camera-timings.xml deleted file mode 100644 index f91cbd3..0000000 --- a/tools/plotjuggler/layouts/camera-timings.xml +++ /dev/null @@ -1,148 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/tools/plotjuggler/layouts/can-states.xml b/tools/plotjuggler/layouts/can-states.xml deleted file mode 100644 index 8c76151..0000000 --- a/tools/plotjuggler/layouts/can-states.xml +++ /dev/null @@ -1,72 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/tools/plotjuggler/layouts/controls_mismatch_debug.xml b/tools/plotjuggler/layouts/controls_mismatch_debug.xml deleted file mode 100644 index 54586d6..0000000 --- a/tools/plotjuggler/layouts/controls_mismatch_debug.xml +++ /dev/null @@ -1,60 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/tools/plotjuggler/layouts/demo.xml b/tools/plotjuggler/layouts/demo.xml deleted file mode 100644 index 7026221..0000000 --- a/tools/plotjuggler/layouts/demo.xml +++ /dev/null @@ -1,104 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - prevX = 0 -prevY = 0 -is_first = true - if (is_first) then - is_first = false - prevX = time - prevY = value -end - -dx = time - prevX -dy = value - prevY -prevX = time -prevY = value - -return dy/dx - /carState/vEgo - - - - - - diff --git a/tools/plotjuggler/layouts/gps_vs_llk.xml b/tools/plotjuggler/layouts/gps_vs_llk.xml deleted file mode 100644 index 4498071..0000000 --- a/tools/plotjuggler/layouts/gps_vs_llk.xml +++ /dev/null @@ -1,83 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - R = 6378.137 -- Radius of earth in KM - -- Compute the Haversine distance between --- two points defined by latitude and longitude. --- Return the distance in meters -lat1, lon1 = value, v1 -lat2, lon2 = v2, v3 -dLat = (lat2 - lat1) * math.pi / 180 -dLon = (lon2 - lon1) * math.pi / 180 -a = math.sin(dLat/2) * math.sin(dLat/2) + -math.cos(lat1 * math.pi / 180) * math.cos(lat2 * math.pi / 180) * -math.sin(dLon/2) * math.sin(dLon/2) -c = 2 * math.atan(math.sqrt(a), math.sqrt(1-a)) -d = R * c -distance = d * 1000 -- meters -return distance - /gpsLocationExternal/latitude - - /gpsLocationExternal/longitude - /liveLocationKalman/positionGeodetic/value/0 - /liveLocationKalman/positionGeodetic/value/1 - - - - - - - diff --git a/tools/plotjuggler/layouts/longitudinal.xml b/tools/plotjuggler/layouts/longitudinal.xml deleted file mode 100644 index 33a24f7..0000000 --- a/tools/plotjuggler/layouts/longitudinal.xml +++ /dev/null @@ -1,59 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/tools/plotjuggler/layouts/max-torque-debug.xml b/tools/plotjuggler/layouts/max-torque-debug.xml deleted file mode 100644 index 20a49c2..0000000 --- a/tools/plotjuggler/layouts/max-torque-debug.xml +++ /dev/null @@ -1,92 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - if (v3 == 0 and v4 == 1) then - return (value * v1 ^ 2) - (v2 * 9.81) -end -return 0 - /controlsState/curvature - - /carState/vEgo - /liveParameters/roll - /carState/steeringPressed - /carControl/latActive - - - - - return (value * v1 ^ 2) - (v2 * 9.81) - /controlsState/desiredCurvature - - /carState/vEgo - /liveParameters/roll - - - - - return (value * v1 ^ 2) - (v2 * 9.81) - /controlsState/curvature - - /carState/vEgo - /liveParameters/roll - - - - - - - diff --git a/tools/plotjuggler/layouts/system_lag_debug.xml b/tools/plotjuggler/layouts/system_lag_debug.xml deleted file mode 100644 index b169934..0000000 --- a/tools/plotjuggler/layouts/system_lag_debug.xml +++ /dev/null @@ -1,68 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/tools/plotjuggler/layouts/thermal_debug.xml b/tools/plotjuggler/layouts/thermal_debug.xml deleted file mode 100644 index 0a0a077..0000000 --- a/tools/plotjuggler/layouts/thermal_debug.xml +++ /dev/null @@ -1,107 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/tools/plotjuggler/layouts/torque-controller.xml b/tools/plotjuggler/layouts/torque-controller.xml deleted file mode 100644 index 4432559..0000000 --- a/tools/plotjuggler/layouts/torque-controller.xml +++ /dev/null @@ -1,92 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - return value * 3.6 - /carState/vEgo - - - - return value * 2.23694 - /carState/vEgo - - - - return (value * v1 ^ 2) - (v2 * 9.81) - /controlsState/desiredCurvature - - /carState/vEgo - /liveParameters/roll - - - - - return (value * v1 ^ 2) - (v2 * 9.81) - /controlsState/curvature - - /carState/vEgo - /liveParameters/roll - - - - - - - diff --git a/tools/plotjuggler/layouts/tuning.xml b/tools/plotjuggler/layouts/tuning.xml deleted file mode 100644 index 503e726..0000000 --- a/tools/plotjuggler/layouts/tuning.xml +++ /dev/null @@ -1,291 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - engage_delay = 5 -last_bad_time = -engage_delay - curvature = value / v3 -pressed = v1 -enabled = v2 - -if (pressed == 1 or enabled == 0) then - last_bad_time = time -end - -if (time > last_bad_time + engage_delay) then - return curvature -else - return 0 -end - /liveLocationKalman/angularVelocityCalibrated/value/2 - - /carState/steeringPressed - /carControl/enabled - /liveLocationKalman/velocityCalibrated/value/0 - - - - engage_delay = 5 -last_bad_time = -engage_delay - curvature = value -pressed = v1 -enabled = v2 - -if (pressed == 1 or enabled == 0) then - last_bad_time = time -end - -if (time > last_bad_time + engage_delay) then - return value -else - return 0 -end - /controlsState/curvature - - /carState/steeringPressed - /carControl/enabled - - - - engage_delay = 5 -last_bad_time = -engage_delay - curvature = value -pressed = v1 -enabled = v2 - -if (pressed == 1 or enabled == 0) then - last_bad_time = time -end - -if (time > last_bad_time + engage_delay) then - return value -else - return 0 -end - /lateralPlan/curvatures/0 - - /carState/steeringPressed - /carControl/enabled - - - - engage_delay = 5 -last_bad_time = -engage_delay - accel = value -brake = v1 -gas = v2 -enabled = v3 - -if (brake ~= 0 or gas ~= 0 or enabled == 0) then - last_bad_time = time -end - -if (time > last_bad_time + engage_delay) then - return value -else - return 0 -end - /carState/aEgo - - /carState/brakePressed - /carState/gasPressed - /carControl/enabled - - - - engage_delay = 5 -last_bad_time = -engage_delay - accel = value -brake = v1 -gas = v2 -enabled = v3 - -if (brake ~= 0 or gas ~= 0 or enabled == 0) then - last_bad_time = time -end - -if (time > last_bad_time + engage_delay) then - return value -else - return 0 -end - /longitudinalPlan/accels/0 - - /carState/brakePressed - /carState/gasPressed - /carControl/enabled - - - - engage_delay = 5 -last_bad_time = -engage_delay - accel = value -brake = v1 -gas = v2 -enabled = v3 - -if (brake ~= 0 or gas ~= 0 or enabled == 0) then - last_bad_time = time -end - -if (time > last_bad_time + engage_delay) then - return value -else - return 0 -end - /carControl/actuators/accel - - /carState/brakePressed - /carState/gasPressed - /carControl/enabled - - - - - - - diff --git a/tools/plotjuggler/layouts/ublox-debug.xml b/tools/plotjuggler/layouts/ublox-debug.xml deleted file mode 100644 index d595a9e..0000000 --- a/tools/plotjuggler/layouts/ublox-debug.xml +++ /dev/null @@ -1,44 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/tools/plotjuggler/test_plotjuggler.py b/tools/plotjuggler/test_plotjuggler.py deleted file mode 100644 index b002331..0000000 --- a/tools/plotjuggler/test_plotjuggler.py +++ /dev/null @@ -1,52 +0,0 @@ -#!/usr/bin/env python3 -import os -import glob -import signal -import subprocess -import time -import unittest - -from openpilot.common.basedir import BASEDIR -from openpilot.common.timeout import Timeout -from openpilot.tools.plotjuggler.juggle import install - -PJ_DIR = os.path.join(BASEDIR, "tools/plotjuggler") - -class TestPlotJuggler(unittest.TestCase): - - def test_demo(self): - install() - - pj = os.path.join(PJ_DIR, "juggle.py") - with subprocess.Popen(f'QT_QPA_PLATFORM=offscreen {pj} --demo None 1 --qlog', - stderr=subprocess.PIPE, shell=True, start_new_session=True) as p: - # Wait for "Done reading Rlog data" signal from the plugin - output = "\n" - with Timeout(180, error_msg=output): - while output.splitlines()[-1] != "Done reading Rlog data": - output += p.stderr.readline().decode("utf-8") - - # ensure plotjuggler didn't crash after exiting the plugin - time.sleep(15) - self.assertEqual(p.poll(), None) - os.killpg(os.getpgid(p.pid), signal.SIGTERM) - - # TODO: also test that layouts successfully load - def test_layouts(self): - bad_strings = ( - # if a previously loaded file is defined, - # PJ will throw a warning when loading the layout - "fileInfo", - "previouslyLoaded_Datafiles", - ) - for fn in glob.glob(os.path.join(PJ_DIR, "layouts/*")): - name = os.path.basename(fn) - with self.subTest(layout=name): - with open(fn) as f: - layout = f.read() - violations = [s for s in bad_strings if s in layout] - assert len(violations) == 0, f"These should be stripped out of the layout: {str(violations)}" - - -if __name__ == "__main__": - unittest.main() diff --git a/tools/replay/.gitignore b/tools/replay/.gitignore deleted file mode 100644 index 83f0e99..0000000 --- a/tools/replay/.gitignore +++ /dev/null @@ -1,5 +0,0 @@ -moc_* -*.moc - -replay -tests/test_replay diff --git a/tools/replay/README.md b/tools/replay/README.md deleted file mode 100644 index 91e8917..0000000 --- a/tools/replay/README.md +++ /dev/null @@ -1,87 +0,0 @@ -# Replay - -## Replay driving data - -`replay` replays all the messages logged while running openpilot. - -```bash -# Log in via browser to have access to routes from your comma account -python tools/lib/auth.py - -# Start a replay -tools/replay/replay - -# Example: -tools/replay/replay 'a2a0ccea32023010|2023-07-27--13-01-19' -# or use --demo to replay the default demo route: -tools/replay/replay --demo - -# watch the replay with the normal openpilot UI -cd selfdrive/ui && ./ui - -# or try out a debug visualizer: -python replay/ui.py -``` - -## usage - -``` bash -$ tools/replay/replay -h -Usage: tools/replay/replay [options] route -Mock openpilot components by publishing logged messages. - -Options: - -h, --help Displays this help. - -a, --allow whitelist of services to send - -b, --block blacklist of services to send - -s, --start start from - --demo use a demo route instead of providing your own - --dcam load driver camera - --ecam load wide road camera - -Arguments: - route the drive to replay. find your drives at - connect.comma.ai -``` - -## watch3 - -watch all three cameras simultaneously from your comma three routes with watch3 - -simply replay a route using the `--dcam` and `--ecam` flags: - -```bash -# start a replay -cd tools/replay && ./replay --demo --dcam --ecam - -# then start watch3 -cd selfdrive/ui && ./watch3 -``` - -![](https://i.imgur.com/IeaOdAb.png) - -## Stream CAN messages to your device - -Replay CAN messages as they were recorded using a [panda jungle](https://comma.ai/shop/products/panda-jungle). The jungle has 6x OBD-C ports for connecting all your comma devices. Check out the [jungle repo](https://github.com/commaai/panda_jungle) for more info. - -In order to run your device as if it was in a car: -* connect a panda jungle to your PC -* connect a comma device or panda to the jungle via OBD-C -* run `can_replay.py` - -``` bash -batman:replay$ ./can_replay.py -h -usage: can_replay.py [-h] [route_or_segment_name] - -Replay CAN messages from a route to all connected pandas and jungles -in a loop. - -positional arguments: - route_or_segment_name - The route or segment name to replay. If not - specified, a default public route will be - used. (default: None) - -optional arguments: - -h, --help show this help message and exit -``` diff --git a/tools/replay/SConscript b/tools/replay/SConscript deleted file mode 100644 index db84470..0000000 --- a/tools/replay/SConscript +++ /dev/null @@ -1,21 +0,0 @@ -Import('env', 'qt_env', 'arch', 'common', 'messaging', 'visionipc', 'cereal') - -base_frameworks = qt_env['FRAMEWORKS'] -base_libs = [common, messaging, cereal, visionipc, 'zmq', - 'capnp', 'kj', 'm', 'ssl', 'crypto', 'pthread', 'qt_util'] + qt_env["LIBS"] - -if arch == "Darwin": - base_frameworks.append('OpenCL') -else: - base_libs.append('OpenCL') - -qt_env['CXXFLAGS'] += ["-Wno-deprecated-declarations"] - -replay_lib_src = ["replay.cc", "consoleui.cc", "camera.cc", "filereader.cc", "logreader.cc", "framereader.cc", "route.cc", "util.cc"] -replay_lib = qt_env.Library("qt_replay", replay_lib_src, LIBS=base_libs, FRAMEWORKS=base_frameworks) -Export('replay_lib') -replay_libs = [replay_lib, 'avutil', 'avcodec', 'avformat', 'bz2', 'curl', 'yuv', 'ncurses'] + base_libs -qt_env.Program("replay", ["main.cc"], LIBS=replay_libs, FRAMEWORKS=base_frameworks) - -if GetOption('extras'): - qt_env.Program('tests/test_replay', ['tests/test_runner.cc', 'tests/test_replay.cc'], LIBS=[replay_libs, base_libs]) diff --git a/tools/replay/__init__.py b/tools/replay/__init__.py deleted file mode 100644 index e69de29..0000000 diff --git a/tools/replay/camera.cc b/tools/replay/camera.cc deleted file mode 100644 index 49f3010..0000000 --- a/tools/replay/camera.cc +++ /dev/null @@ -1,103 +0,0 @@ -#include "tools/replay/camera.h" - -#include -#include - -#include "third_party/linux/include/msm_media_info.h" -#include "tools/replay/util.h" - -std::tuple get_nv12_info(int width, int height) { - int nv12_width = VENUS_Y_STRIDE(COLOR_FMT_NV12, width); - int nv12_height = VENUS_Y_SCANLINES(COLOR_FMT_NV12, height); - assert(nv12_width == VENUS_UV_STRIDE(COLOR_FMT_NV12, width)); - assert(nv12_height / 2 == VENUS_UV_SCANLINES(COLOR_FMT_NV12, height)); - size_t nv12_buffer_size = 2346 * nv12_width; // comes from v4l2_format.fmt.pix_mp.plane_fmt[0].sizeimage - return {nv12_width, nv12_height, nv12_buffer_size}; -} - -CameraServer::CameraServer(std::pair camera_size[MAX_CAMERAS]) { - for (int i = 0; i < MAX_CAMERAS; ++i) { - std::tie(cameras_[i].width, cameras_[i].height) = camera_size[i]; - } - startVipcServer(); -} - -CameraServer::~CameraServer() { - for (auto &cam : cameras_) { - if (cam.thread.joinable()) { - cam.queue.push({}); - cam.thread.join(); - } - } - vipc_server_.reset(nullptr); -} - -void CameraServer::startVipcServer() { - vipc_server_.reset(new VisionIpcServer("camerad")); - for (auto &cam : cameras_) { - if (cam.width > 0 && cam.height > 0) { - rInfo("camera[%d] frame size %dx%d", cam.type, cam.width, cam.height); - auto [nv12_width, nv12_height, nv12_buffer_size] = get_nv12_info(cam.width, cam.height); - vipc_server_->create_buffers_with_sizes(cam.stream_type, YUV_BUFFER_COUNT, false, cam.width, cam.height, - nv12_buffer_size, nv12_width, nv12_width * nv12_height); - if (!cam.thread.joinable()) { - cam.thread = std::thread(&CameraServer::cameraThread, this, std::ref(cam)); - } - } - } - vipc_server_->start_listener(); -} - -void CameraServer::cameraThread(Camera &cam) { - auto read_frame = [&](FrameReader *fr, int frame_id) { - VisionBuf *yuv_buf = vipc_server_->get_buffer(cam.stream_type); - assert(yuv_buf); - bool ret = fr->get(frame_id, yuv_buf); - return ret ? yuv_buf : nullptr; - }; - - while (true) { - const auto [fr, eidx] = cam.queue.pop(); - if (!fr) break; - - const int id = eidx.getSegmentId(); - bool prefetched = (id == cam.cached_id && eidx.getSegmentNum() == cam.cached_seg); - auto yuv = prefetched ? cam.cached_buf : read_frame(fr, id); - if (yuv) { - VisionIpcBufExtra extra = { - .frame_id = eidx.getFrameId(), - .timestamp_sof = eidx.getTimestampSof(), - .timestamp_eof = eidx.getTimestampEof(), - }; - yuv->set_frame_id(eidx.getFrameId()); - vipc_server_->send(yuv, &extra); - } else { - rError("camera[%d] failed to get frame: %lu", cam.type, eidx.getSegmentId()); - } - - cam.cached_id = id + 1; - cam.cached_seg = eidx.getSegmentNum(); - cam.cached_buf = read_frame(fr, cam.cached_id); - - --publishing_; - } -} - -void CameraServer::pushFrame(CameraType type, FrameReader *fr, const cereal::EncodeIndex::Reader &eidx) { - auto &cam = cameras_[type]; - if (cam.width != fr->width || cam.height != fr->height) { - cam.width = fr->width; - cam.height = fr->height; - waitForSent(); - startVipcServer(); - } - - ++publishing_; - cam.queue.push({fr, eidx}); -} - -void CameraServer::waitForSent() { - while (publishing_ > 0) { - std::this_thread::yield(); - } -} diff --git a/tools/replay/camera.h b/tools/replay/camera.h deleted file mode 100644 index 9f43c5a..0000000 --- a/tools/replay/camera.h +++ /dev/null @@ -1,45 +0,0 @@ -#pragma once - -#include - -#include -#include -#include - -#include "cereal/visionipc/visionipc_server.h" -#include "common/queue.h" -#include "tools/replay/framereader.h" -#include "tools/replay/logreader.h" - -std::tuple get_nv12_info(int width, int height); - -class CameraServer { -public: - CameraServer(std::pair camera_size[MAX_CAMERAS] = nullptr); - ~CameraServer(); - void pushFrame(CameraType type, FrameReader* fr, const cereal::EncodeIndex::Reader& eidx); - void waitForSent(); - -protected: - struct Camera { - CameraType type; - VisionStreamType stream_type; - int width; - int height; - std::thread thread; - SafeQueue> queue; - int cached_id = -1; - int cached_seg = -1; - VisionBuf * cached_buf; - }; - void startVipcServer(); - void cameraThread(Camera &cam); - - Camera cameras_[MAX_CAMERAS] = { - {.type = RoadCam, .stream_type = VISION_STREAM_ROAD}, - {.type = DriverCam, .stream_type = VISION_STREAM_DRIVER}, - {.type = WideRoadCam, .stream_type = VISION_STREAM_WIDE_ROAD}, - }; - std::atomic publishing_ = 0; - std::unique_ptr vipc_server_; -}; diff --git a/tools/replay/can_replay.py b/tools/replay/can_replay.py deleted file mode 100644 index 032c298..0000000 --- a/tools/replay/can_replay.py +++ /dev/null @@ -1,107 +0,0 @@ -#!/usr/bin/env python3 -import argparse -import os -import time -import threading -import multiprocessing -from tqdm import tqdm - -os.environ['FILEREADER_CACHE'] = '1' - -from openpilot.common.realtime import config_realtime_process, Ratekeeper, DT_CTRL -from openpilot.selfdrive.boardd.boardd import can_capnp_to_can_list -from openpilot.tools.plotjuggler.juggle import load_segment -from openpilot.tools.lib.logreader import logreader_from_route_or_segment -from panda import Panda, PandaJungle - -def send_thread(s, flock): - if "Jungle" in str(type(s)): - if "FLASH" in os.environ: - with flock: - s.flash() - - for i in [0, 1, 2, 3, 0xFFFF]: - s.can_clear(i) - s.set_ignition(False) - time.sleep(5) - s.set_ignition(True) - s.set_panda_power(True) - else: - s.set_safety_mode(Panda.SAFETY_ALLOUTPUT) - s.set_can_loopback(False) - - idx = 0 - ign = True - rk = Ratekeeper(1 / DT_CTRL, print_delay_threshold=None) - while True: - # handle ignition cycling - if ENABLE_IGN: - i = (rk.frame*DT_CTRL) % (IGN_ON + IGN_OFF) < IGN_ON - if i != ign: - ign = i - s.set_ignition(ign) - - snd = CAN_MSGS[idx] - snd = list(filter(lambda x: x[-1] <= 2, snd)) - s.can_send_many(snd) - idx = (idx + 1) % len(CAN_MSGS) - - # Drain panda message buffer - s.can_recv() - rk.keep_time() - - -def connect(): - config_realtime_process(3, 55) - - serials = {} - flashing_lock = threading.Lock() - while True: - # look for new devices - for p in [Panda, PandaJungle]: - if p is None: - continue - - for s in p.list(): - if s not in serials: - print("starting send thread for", s) - serials[s] = threading.Thread(target=send_thread, args=(p(s), flashing_lock)) - serials[s].start() - - # try to join all send threads - cur_serials = serials.copy() - for s, t in cur_serials.items(): - t.join(0.01) - if not t.is_alive(): - del serials[s] - - time.sleep(1) - - -if __name__ == "__main__": - parser = argparse.ArgumentParser(description="Replay CAN messages from a route to all connected pandas and jungles in a loop.", - formatter_class=argparse.ArgumentDefaultsHelpFormatter) - parser.add_argument("route_or_segment_name", nargs='?', help="The route or segment name to replay. If not specified, a default public route will be used.") - args = parser.parse_args() - - print("Loading log...") - if args.route_or_segment_name is None: - ROUTE = "77611a1fac303767/2020-03-24--09-50-38" - REPLAY_SEGS = list(range(10, 16)) # route has 82 segments available - CAN_MSGS = [] - logs = [f"https://commadataci.blob.core.windows.net/openpilotci/{ROUTE}/{i}/rlog.bz2" for i in REPLAY_SEGS] - with multiprocessing.Pool(24) as pool: - for lr in tqdm(pool.map(load_segment, logs)): - CAN_MSGS += [can_capnp_to_can_list(m.can) for m in lr if m.which() == 'can'] - else: - lr = logreader_from_route_or_segment(args.route_or_segment_name) - CAN_MSGS = [can_capnp_to_can_list(m.can) for m in lr if m.which() == 'can'] - - # set both to cycle ignition - IGN_ON = int(os.getenv("ON", "0")) - IGN_OFF = int(os.getenv("OFF", "0")) - ENABLE_IGN = IGN_ON > 0 and IGN_OFF > 0 - if ENABLE_IGN: - print(f"Cycling ignition: on for {IGN_ON}s, off for {IGN_OFF}s") - - connect() diff --git a/tools/replay/consoleui.cc b/tools/replay/consoleui.cc deleted file mode 100644 index 54056c6..0000000 --- a/tools/replay/consoleui.cc +++ /dev/null @@ -1,374 +0,0 @@ -#include "tools/replay/consoleui.h" - -#include -#include -#include -#include - -#include - -#include "common/util.h" -#include "common/version.h" - -namespace { - -const int BORDER_SIZE = 3; - -const std::initializer_list> keyboard_shortcuts[] = { - { - {"s", "+10s"}, - {"shift+s", "-10s"}, - {"m", "+60s"}, - {"shift+m", "-60s"}, - {"space", "Pause/Resume"}, - {"e", "Next Engagement"}, - {"d", "Next Disengagement"}, - {"t", "Next User Tag"}, - {"i", "Next Info"}, - {"w", "Next Warning"}, - {"c", "Next Critical"}, - }, - { - {"enter", "Enter seek request"}, - {"+/-", "Playback speed"}, - {"q", "Exit"}, - }, -}; - -enum Color { - Default, - Debug, - Yellow, - Green, - Red, - Cyan, - BrightWhite, - Engaged, - Disengaged, -}; - -void add_str(WINDOW *w, const char *str, Color color = Color::Default, bool bold = false) { - if (color != Color::Default) wattron(w, COLOR_PAIR(color)); - if (bold) wattron(w, A_BOLD); - waddstr(w, str); - if (bold) wattroff(w, A_BOLD); - if (color != Color::Default) wattroff(w, COLOR_PAIR(color)); -} - -} // namespace - -ConsoleUI::ConsoleUI(Replay *replay, QObject *parent) : replay(replay), sm({"carState", "liveParameters"}), QObject(parent) { - // Initialize curses - initscr(); - clear(); - curs_set(false); - cbreak(); // Line buffering disabled. pass on everything - noecho(); - keypad(stdscr, true); - nodelay(stdscr, true); // non-blocking getchar() - - // Initialize all the colors. https://www.ditig.com/256-colors-cheat-sheet - start_color(); - init_pair(Color::Debug, 246, COLOR_BLACK); // #949494 - init_pair(Color::Yellow, 184, COLOR_BLACK); - init_pair(Color::Red, COLOR_RED, COLOR_BLACK); - init_pair(Color::Cyan, COLOR_CYAN, COLOR_BLACK); - init_pair(Color::BrightWhite, 15, COLOR_BLACK); - init_pair(Color::Disengaged, COLOR_BLUE, COLOR_BLUE); - init_pair(Color::Engaged, 28, 28); - init_pair(Color::Green, 34, COLOR_BLACK); - - initWindows(); - - qRegisterMetaType("uint64_t"); - qRegisterMetaType("ReplyMsgType"); - installMessageHandler([this](ReplyMsgType type, const std::string msg) { - emit logMessageSignal(type, QString::fromStdString(msg)); - }); - installDownloadProgressHandler([this](uint64_t cur, uint64_t total, bool success) { - emit updateProgressBarSignal(cur, total, success); - }); - - QObject::connect(replay, &Replay::streamStarted, this, &ConsoleUI::updateSummary); - QObject::connect(¬ifier, SIGNAL(activated(int)), SLOT(readyRead())); - QObject::connect(this, &ConsoleUI::updateProgressBarSignal, this, &ConsoleUI::updateProgressBar); - QObject::connect(this, &ConsoleUI::logMessageSignal, this, &ConsoleUI::logMessage); - - sm_timer.callOnTimeout(this, &ConsoleUI::updateStatus); - sm_timer.start(100); - getch_timer.start(1000, this); - readyRead(); -} - -ConsoleUI::~ConsoleUI() { - endwin(); -} - -void ConsoleUI::initWindows() { - getmaxyx(stdscr, max_height, max_width); - w.fill(nullptr); - w[Win::Title] = newwin(1, max_width, 0, 0); - w[Win::Stats] = newwin(2, max_width - 2 * BORDER_SIZE, 2, BORDER_SIZE); - w[Win::Timeline] = newwin(4, max_width - 2 * BORDER_SIZE, 5, BORDER_SIZE); - w[Win::TimelineDesc] = newwin(1, 100, 10, BORDER_SIZE); - w[Win::CarState] = newwin(3, 100, 12, BORDER_SIZE); - w[Win::DownloadBar] = newwin(1, 100, 16, BORDER_SIZE); - if (int log_height = max_height - 27; log_height > 4) { - w[Win::LogBorder] = newwin(log_height, max_width - 2 * (BORDER_SIZE - 1), 17, BORDER_SIZE - 1); - box(w[Win::LogBorder], 0, 0); - w[Win::Log] = newwin(log_height - 2, max_width - 2 * BORDER_SIZE, 18, BORDER_SIZE); - scrollok(w[Win::Log], true); - } - w[Win::Help] = newwin(5, max_width - (2 * BORDER_SIZE), max_height - 6, BORDER_SIZE); - - // set the title bar - wbkgd(w[Win::Title], A_REVERSE); - mvwprintw(w[Win::Title], 0, 3, "openpilot replay %s", COMMA_VERSION); - - // show windows on the real screen - refresh(); - displayTimelineDesc(); - displayHelp(); - updateSummary(); - updateTimeline(); - for (auto win : w) { - if (win) wrefresh(win); - } -} - -void ConsoleUI::timerEvent(QTimerEvent *ev) { - if (ev->timerId() != getch_timer.timerId()) return; - - if (is_term_resized(max_height, max_width)) { - for (auto win : w) { - if (win) delwin(win); - } - endwin(); - clear(); - refresh(); - initWindows(); - rWarning("resize term %dx%d", max_height, max_width); - } - updateTimeline(); -} - -void ConsoleUI::updateStatus() { - auto write_item = [this](int y, int x, const char *key, const std::string &value, const std::string &unit, - bool bold = false, Color color = Color::BrightWhite) { - auto win = w[Win::CarState]; - wmove(win, y, x); - add_str(win, key); - add_str(win, value.c_str(), color, bold); - add_str(win, unit.c_str()); - }; - static const std::pair status_text[] = { - {"loading...", Color::Red}, - {"playing", Color::Green}, - {"paused...", Color::Yellow}, - }; - - sm.update(0); - - if (status != Status::Paused) { - auto events = replay->events(); - uint64_t current_mono_time = replay->routeStartTime() + replay->currentSeconds() * 1e9; - bool playing = !events->empty() && events->back()->mono_time > current_mono_time; - status = playing ? Status::Playing : Status::Waiting; - } - auto [status_str, status_color] = status_text[status]; - write_item(0, 0, "STATUS: ", status_str, " ", false, status_color); - std::string current_segment = " - " + std::to_string((int)(replay->currentSeconds() / 60)); - write_item(0, 25, "TIME: ", replay->currentDateTime().toString("ddd MMMM dd hh:mm:ss").toStdString(), current_segment, true); - - auto p = sm["liveParameters"].getLiveParameters(); - write_item(1, 0, "STIFFNESS: ", util::string_format("%.2f %%", p.getStiffnessFactor() * 100), " "); - write_item(1, 25, "SPEED: ", util::string_format("%.2f", sm["carState"].getCarState().getVEgo()), " m/s"); - write_item(2, 0, "STEER RATIO: ", util::string_format("%.2f", p.getSteerRatio()), ""); - auto angle_offsets = util::string_format("%.2f|%.2f", p.getAngleOffsetAverageDeg(), p.getAngleOffsetDeg()); - write_item(2, 25, "ANGLE OFFSET(AVG|INSTANT): ", angle_offsets, " deg"); - - wrefresh(w[Win::CarState]); -} - -void ConsoleUI::displayHelp() { - for (int i = 0; i < std::size(keyboard_shortcuts); ++i) { - wmove(w[Win::Help], i * 2, 0); - for (auto &[key, desc] : keyboard_shortcuts[i]) { - wattron(w[Win::Help], A_REVERSE); - waddstr(w[Win::Help], (' ' + key + ' ').c_str()); - wattroff(w[Win::Help], A_REVERSE); - waddstr(w[Win::Help], (' ' + desc + ' ').c_str()); - } - } - wrefresh(w[Win::Help]); -} - -void ConsoleUI::displayTimelineDesc() { - std::tuple indicators[]{ - {Color::Engaged, " Engaged ", false}, - {Color::Disengaged, " Disengaged ", false}, - {Color::Green, " Info ", true}, - {Color::Yellow, " Warning ", true}, - {Color::Red, " Critical ", true}, - {Color::Cyan, " User Tag ", true}, - }; - for (auto [color, name, bold] : indicators) { - add_str(w[Win::TimelineDesc], "__", color, bold); - add_str(w[Win::TimelineDesc], name); - } -} - -void ConsoleUI::logMessage(ReplyMsgType type, const QString &msg) { - if (auto win = w[Win::Log]) { - Color color = Color::Default; - if (type == ReplyMsgType::Debug) { - color = Color::Debug; - } else if (type == ReplyMsgType::Warning) { - color = Color::Yellow; - } else if (type == ReplyMsgType::Critical) { - color = Color::Red; - } - add_str(win, qPrintable(msg + "\n"), color); - wrefresh(win); - } -} - -void ConsoleUI::updateProgressBar(uint64_t cur, uint64_t total, bool success) { - werase(w[Win::DownloadBar]); - if (success && cur < total) { - const int width = 35; - const float progress = cur / (double)total; - const int pos = width * progress; - wprintw(w[Win::DownloadBar], "Downloading [%s>%s] %d%% %s", std::string(pos, '=').c_str(), - std::string(width - pos, ' ').c_str(), int(progress * 100.0), formattedDataSize(total).c_str()); - } - wrefresh(w[Win::DownloadBar]); -} - -void ConsoleUI::updateSummary() { - const auto &route = replay->route(); - mvwprintw(w[Win::Stats], 0, 0, "Route: %s, %lu segments", qPrintable(route->name()), route->segments().size()); - mvwprintw(w[Win::Stats], 1, 0, "Car Fingerprint: %s", replay->carFingerprint().c_str()); - wrefresh(w[Win::Stats]); -} - -void ConsoleUI::updateTimeline() { - auto win = w[Win::Timeline]; - int width = getmaxx(win); - werase(win); - - wattron(win, COLOR_PAIR(Color::Disengaged)); - mvwhline(win, 1, 0, ' ', width); - mvwhline(win, 2, 0, ' ', width); - wattroff(win, COLOR_PAIR(Color::Disengaged)); - - const int total_sec = replay->totalSeconds(); - for (auto [begin, end, type] : replay->getTimeline()) { - int start_pos = (begin / total_sec) * width; - int end_pos = (end / total_sec) * width; - if (type == TimelineType::Engaged) { - mvwchgat(win, 1, start_pos, end_pos - start_pos + 1, A_COLOR, Color::Engaged, NULL); - mvwchgat(win, 2, start_pos, end_pos - start_pos + 1, A_COLOR, Color::Engaged, NULL); - } else if (type == TimelineType::UserFlag) { - mvwchgat(win, 3, start_pos, end_pos - start_pos + 1, ACS_S3, Color::Cyan, NULL); - } else { - auto color_id = Color::Green; - if (type != TimelineType::AlertInfo) { - color_id = type == TimelineType::AlertWarning ? Color::Yellow : Color::Red; - } - mvwchgat(win, 3, start_pos, end_pos - start_pos + 1, ACS_S3, color_id, NULL); - } - } - - int cur_pos = ((double)replay->currentSeconds() / total_sec) * width; - wattron(win, COLOR_PAIR(Color::BrightWhite)); - mvwaddch(win, 0, cur_pos, ACS_VLINE); - mvwaddch(win, 3, cur_pos, ACS_VLINE); - wattroff(win, COLOR_PAIR(Color::BrightWhite)); - wrefresh(win); -} - -void ConsoleUI::readyRead() { - int c; - while ((c = getch()) != ERR) { - handleKey(c); - } -} - -void ConsoleUI::pauseReplay(bool pause) { - replay->pause(pause); - status = pause ? Status::Paused : Status::Waiting; -} - -void ConsoleUI::handleKey(char c) { - if (c == '\n') { - // pause the replay and blocking getchar() - pauseReplay(true); - updateStatus(); - getch_timer.stop(); - curs_set(true); - nodelay(stdscr, false); - - // Wait for user input - rWarning("Waiting for input..."); - int y = getmaxy(stdscr) - 9; - move(y, BORDER_SIZE); - add_str(stdscr, "Enter seek request: ", Color::BrightWhite, true); - refresh(); - - // Seek to choice - echo(); - int choice = 0; - scanw((char *)"%d", &choice); - noecho(); - pauseReplay(false); - replay->seekTo(choice, false); - - // Clean up and turn off the blocking mode - move(y, 0); - clrtoeol(); - nodelay(stdscr, true); - curs_set(false); - refresh(); - getch_timer.start(1000, this); - - } else if (c == '+' || c == '=') { - auto it = std::upper_bound(speed_array.begin(), speed_array.end(), replay->getSpeed()); - if (it != speed_array.end()) { - rWarning("playback speed: %.1fx", *it); - replay->setSpeed(*it); - } - } else if (c == '_' || c == '-') { - auto it = std::lower_bound(speed_array.begin(), speed_array.end(), replay->getSpeed()); - if (it != speed_array.begin()) { - auto prev = std::prev(it); - rWarning("playback speed: %.1fx", *prev); - replay->setSpeed(*prev); - } - } else if (c == 'e') { - replay->seekToFlag(FindFlag::nextEngagement); - } else if (c == 'd') { - replay->seekToFlag(FindFlag::nextDisEngagement); - } else if (c == 't') { - replay->seekToFlag(FindFlag::nextUserFlag); - } else if (c == 'i') { - replay->seekToFlag(FindFlag::nextInfo); - } else if (c == 'w') { - replay->seekToFlag(FindFlag::nextWarning); - } else if (c == 'c') { - replay->seekToFlag(FindFlag::nextCritical); - } else if (c == 'm') { - replay->seekTo(+60, true); - } else if (c == 'M') { - replay->seekTo(-60, true); - } else if (c == 's') { - replay->seekTo(+10, true); - } else if (c == 'S') { - replay->seekTo(-10, true); - } else if (c == ' ') { - pauseReplay(!replay->isPaused()); - } else if (c == 'q' || c == 'Q') { - replay->stop(); - qApp->exit(); - } -} diff --git a/tools/replay/consoleui.h b/tools/replay/consoleui.h deleted file mode 100644 index 6ed44bc..0000000 --- a/tools/replay/consoleui.h +++ /dev/null @@ -1,51 +0,0 @@ -#pragma once - -#include -#include -#include -#include -#include -#include - -#include "tools/replay/replay.h" -#include - -class ConsoleUI : public QObject { - Q_OBJECT - -public: - ConsoleUI(Replay *replay, QObject *parent = 0); - ~ConsoleUI(); - inline static const std::array speed_array = {0.2f, 0.5f, 1.0f, 2.0f, 3.0f}; - -private: - void initWindows(); - void handleKey(char c); - void displayHelp(); - void displayTimelineDesc(); - void updateTimeline(); - void updateSummary(); - void updateStatus(); - void pauseReplay(bool pause); - - enum Status { Waiting, Playing, Paused }; - enum Win { Title, Stats, Log, LogBorder, DownloadBar, Timeline, TimelineDesc, Help, CarState, Max}; - std::array w{}; - SubMaster sm; - Replay *replay; - QBasicTimer getch_timer; - QTimer sm_timer; - QSocketNotifier notifier{0, QSocketNotifier::Read, this}; - int max_width, max_height; - Status status = Status::Waiting; - -signals: - void updateProgressBarSignal(uint64_t cur, uint64_t total, bool success); - void logMessageSignal(ReplyMsgType type, const QString &msg); - -private slots: - void readyRead(); - void timerEvent(QTimerEvent *ev); - void updateProgressBar(uint64_t cur, uint64_t total, bool success); - void logMessage(ReplyMsgType type, const QString &msg); -}; diff --git a/tools/replay/filereader.cc b/tools/replay/filereader.cc deleted file mode 100644 index 22af7f5..0000000 --- a/tools/replay/filereader.cc +++ /dev/null @@ -1,46 +0,0 @@ -#include "tools/replay/filereader.h" - -#include - -#include "common/util.h" -#include "system/hardware/hw.h" -#include "tools/replay/util.h" - -std::string cacheFilePath(const std::string &url) { - static std::string cache_path = [] { - const std::string comma_cache = Path::download_cache_root(); - util::create_directories(comma_cache, 0755); - return comma_cache.back() == '/' ? comma_cache : comma_cache + "/"; - }(); - - return cache_path + sha256(getUrlWithoutQuery(url)); -} - -std::string FileReader::read(const std::string &file, std::atomic *abort) { - const bool is_remote = file.find("https://") == 0; - const std::string local_file = is_remote ? cacheFilePath(file) : file; - std::string result; - - if ((!is_remote || cache_to_local_) && util::file_exists(local_file)) { - result = util::read_file(local_file); - } else if (is_remote) { - result = download(file, abort); - if (cache_to_local_ && !result.empty()) { - std::ofstream fs(local_file, std::ios::binary | std::ios::out); - fs.write(result.data(), result.size()); - } - } - return result; -} - -std::string FileReader::download(const std::string &url, std::atomic *abort) { - for (int i = 0; i <= max_retries_ && !(abort && *abort); ++i) { - if (i > 0) rWarning("download failed, retrying %d", i); - - std::string result = httpGet(url, chunk_size_, abort); - if (!result.empty()) { - return result; - } - } - return {}; -} diff --git a/tools/replay/filereader.h b/tools/replay/filereader.h deleted file mode 100644 index 34aa91e..0000000 --- a/tools/replay/filereader.h +++ /dev/null @@ -1,20 +0,0 @@ -#pragma once - -#include -#include - -class FileReader { -public: - FileReader(bool cache_to_local, size_t chunk_size = 0, int retries = 3) - : cache_to_local_(cache_to_local), chunk_size_(chunk_size), max_retries_(retries) {} - virtual ~FileReader() {} - std::string read(const std::string &file, std::atomic *abort = nullptr); - -private: - std::string download(const std::string &url, std::atomic *abort); - size_t chunk_size_; - int max_retries_; - bool cache_to_local_; -}; - -std::string cacheFilePath(const std::string &url); diff --git a/tools/replay/framereader.cc b/tools/replay/framereader.cc deleted file mode 100644 index 303f0c6..0000000 --- a/tools/replay/framereader.cc +++ /dev/null @@ -1,251 +0,0 @@ -#include "tools/replay/framereader.h" -#include "tools/replay/util.h" - -#include -#include -#include "third_party/libyuv/include/libyuv.h" - -#ifdef __APPLE__ -#define HW_DEVICE_TYPE AV_HWDEVICE_TYPE_VIDEOTOOLBOX -#define HW_PIX_FMT AV_PIX_FMT_VIDEOTOOLBOX -#else -#define HW_DEVICE_TYPE AV_HWDEVICE_TYPE_CUDA -#define HW_PIX_FMT AV_PIX_FMT_CUDA -#endif - -namespace { - -struct buffer_data { - const uint8_t *data; - int64_t offset; - size_t size; -}; - -int readPacket(void *opaque, uint8_t *buf, int buf_size) { - struct buffer_data *bd = (struct buffer_data *)opaque; - assert(bd->offset <= bd->size); - buf_size = std::min((size_t)buf_size, (size_t)(bd->size - bd->offset)); - if (!buf_size) return AVERROR_EOF; - - memcpy(buf, bd->data + bd->offset, buf_size); - bd->offset += buf_size; - return buf_size; -} - -enum AVPixelFormat get_hw_format(AVCodecContext *ctx, const enum AVPixelFormat *pix_fmts) { - enum AVPixelFormat *hw_pix_fmt = reinterpret_cast(ctx->opaque); - for (const enum AVPixelFormat *p = pix_fmts; *p != -1; p++) { - if (*p == *hw_pix_fmt) return *p; - } - rWarning("Please run replay with the --no-hw-decoder flag!"); - // fallback to YUV420p - *hw_pix_fmt = AV_PIX_FMT_NONE; - return AV_PIX_FMT_YUV420P; -} - -} // namespace - -FrameReader::FrameReader() { - av_log_set_level(AV_LOG_QUIET); -} - -FrameReader::~FrameReader() { - for (AVPacket *pkt : packets) { - av_packet_free(&pkt); - } - - if (decoder_ctx) avcodec_free_context(&decoder_ctx); - if (input_ctx) avformat_close_input(&input_ctx); - if (hw_device_ctx) av_buffer_unref(&hw_device_ctx); - - if (avio_ctx_) { - av_freep(&avio_ctx_->buffer); - avio_context_free(&avio_ctx_); - } -} - -bool FrameReader::load(const std::string &url, bool no_hw_decoder, std::atomic *abort, bool local_cache, int chunk_size, int retries) { - FileReader f(local_cache, chunk_size, retries); - std::string data = f.read(url, abort); - if (data.empty()) { - rWarning("URL %s returned no data", url.c_str()); - return false; - } - - return load((std::byte *)data.data(), data.size(), no_hw_decoder, abort); -} - -bool FrameReader::load(const std::byte *data, size_t size, bool no_hw_decoder, std::atomic *abort) { - input_ctx = avformat_alloc_context(); - if (!input_ctx) { - rError("Error calling avformat_alloc_context"); - return false; - } - - struct buffer_data bd = { - .data = (const uint8_t*)data, - .offset = 0, - .size = size, - }; - const int avio_ctx_buffer_size = 64 * 1024; - unsigned char *avio_ctx_buffer = (unsigned char *)av_malloc(avio_ctx_buffer_size); - avio_ctx_ = avio_alloc_context(avio_ctx_buffer, avio_ctx_buffer_size, 0, &bd, readPacket, nullptr, nullptr); - input_ctx->pb = avio_ctx_; - - input_ctx->probesize = 10 * 1024 * 1024; // 10MB - int ret = avformat_open_input(&input_ctx, nullptr, nullptr, nullptr); - if (ret != 0) { - char err_str[1024] = {0}; - av_strerror(ret, err_str, std::size(err_str)); - rError("Error loading video - %s", err_str); - return false; - } - - ret = avformat_find_stream_info(input_ctx, nullptr); - if (ret < 0) { - rError("cannot find a video stream in the input file"); - return false; - } - - AVStream *video = input_ctx->streams[0]; - const AVCodec *decoder = avcodec_find_decoder(video->codecpar->codec_id); - if (!decoder) return false; - - decoder_ctx = avcodec_alloc_context3(decoder); - ret = avcodec_parameters_to_context(decoder_ctx, video->codecpar); - if (ret != 0) return false; - - width = (decoder_ctx->width + 3) & ~3; - height = decoder_ctx->height; - - if (has_hw_decoder && !no_hw_decoder) { - if (!initHardwareDecoder(HW_DEVICE_TYPE)) { - rWarning("No device with hardware decoder found. fallback to CPU decoding."); - } - } - - ret = avcodec_open2(decoder_ctx, decoder, nullptr); - if (ret < 0) { - rError("avcodec_open2 failed %d", ret); - return false; - } - - packets.reserve(60 * 20); // 20fps, one minute - while (!(abort && *abort)) { - AVPacket *pkt = av_packet_alloc(); - ret = av_read_frame(input_ctx, pkt); - if (ret < 0) { - av_packet_free(&pkt); - valid_ = (ret == AVERROR_EOF); - break; - } - packets.push_back(pkt); - // some stream seems to contain no keyframes - key_frames_count_ += pkt->flags & AV_PKT_FLAG_KEY; - } - valid_ = valid_ && !packets.empty(); - return valid_; -} - -bool FrameReader::initHardwareDecoder(AVHWDeviceType hw_device_type) { - for (int i = 0;; i++) { - const AVCodecHWConfig *config = avcodec_get_hw_config(decoder_ctx->codec, i); - if (!config) { - rWarning("decoder %s does not support hw device type %s.", decoder_ctx->codec->name, - av_hwdevice_get_type_name(hw_device_type)); - return false; - } - if (config->methods & AV_CODEC_HW_CONFIG_METHOD_HW_DEVICE_CTX && config->device_type == hw_device_type) { - hw_pix_fmt = config->pix_fmt; - break; - } - } - - int ret = av_hwdevice_ctx_create(&hw_device_ctx, hw_device_type, nullptr, nullptr, 0); - if (ret < 0) { - hw_pix_fmt = AV_PIX_FMT_NONE; - has_hw_decoder = false; - rWarning("Failed to create specified HW device %d.", ret); - return false; - } - - decoder_ctx->hw_device_ctx = av_buffer_ref(hw_device_ctx); - decoder_ctx->opaque = &hw_pix_fmt; - decoder_ctx->get_format = get_hw_format; - return true; -} - -bool FrameReader::get(int idx, VisionBuf *buf) { - assert(buf != nullptr); - if (!valid_ || idx < 0 || idx >= packets.size()) { - return false; - } - return decode(idx, buf); -} - -bool FrameReader::decode(int idx, VisionBuf *buf) { - int from_idx = idx; - if (idx != prev_idx + 1 && key_frames_count_ > 1) { - // seeking to the nearest key frame - for (int i = idx; i >= 0; --i) { - if (packets[i]->flags & AV_PKT_FLAG_KEY) { - from_idx = i; - break; - } - } - } - prev_idx = idx; - - for (int i = from_idx; i <= idx; ++i) { - AVFrame *f = decodeFrame(packets[i]); - if (f && i == idx) { - return copyBuffers(f, buf); - } - } - return false; -} - -AVFrame *FrameReader::decodeFrame(AVPacket *pkt) { - int ret = avcodec_send_packet(decoder_ctx, pkt); - if (ret < 0) { - rError("Error sending a packet for decoding: %d", ret); - return nullptr; - } - - av_frame_.reset(av_frame_alloc()); - ret = avcodec_receive_frame(decoder_ctx, av_frame_.get()); - if (ret != 0) { - rError("avcodec_receive_frame error: %d", ret); - return nullptr; - } - - if (av_frame_->format == hw_pix_fmt) { - hw_frame.reset(av_frame_alloc()); - if ((ret = av_hwframe_transfer_data(hw_frame.get(), av_frame_.get(), 0)) < 0) { - rError("error transferring the data from GPU to CPU"); - return nullptr; - } - return hw_frame.get(); - } else { - return av_frame_.get(); - } -} - -bool FrameReader::copyBuffers(AVFrame *f, VisionBuf *buf) { - assert(f != nullptr && buf != nullptr); - if (hw_pix_fmt == HW_PIX_FMT) { - for (int i = 0; i < height/2; i++) { - memcpy(buf->y + (i*2 + 0)*buf->stride, f->data[0] + (i*2 + 0)*f->linesize[0], width); - memcpy(buf->y + (i*2 + 1)*buf->stride, f->data[0] + (i*2 + 1)*f->linesize[0], width); - memcpy(buf->uv + i*buf->stride, f->data[1] + i*f->linesize[1], width); - } - } else { - libyuv::I420ToNV12(f->data[0], f->linesize[0], - f->data[1], f->linesize[1], - f->data[2], f->linesize[2], - buf->y, buf->stride, - buf->uv, buf->stride, - width, height); - } - return true; -} diff --git a/tools/replay/framereader.h b/tools/replay/framereader.h deleted file mode 100644 index bb72ac8..0000000 --- a/tools/replay/framereader.h +++ /dev/null @@ -1,51 +0,0 @@ -#pragma once - -#include -#include -#include - -#include "cereal/visionipc/visionbuf.h" -#include "tools/replay/filereader.h" - -extern "C" { -#include -#include -} - -struct AVFrameDeleter { - void operator()(AVFrame* frame) const { av_frame_free(&frame); } -}; - -class FrameReader { -public: - FrameReader(); - ~FrameReader(); - bool load(const std::string &url, bool no_hw_decoder = false, std::atomic *abort = nullptr, bool local_cache = false, - int chunk_size = -1, int retries = 0); - bool load(const std::byte *data, size_t size, bool no_hw_decoder = false, std::atomic *abort = nullptr); - bool get(int idx, VisionBuf *buf); - int getYUVSize() const { return width * height * 3 / 2; } - size_t getFrameCount() const { return packets.size(); } - bool valid() const { return valid_; } - - int width = 0, height = 0; - -private: - bool initHardwareDecoder(AVHWDeviceType hw_device_type); - bool decode(int idx, VisionBuf *buf); - AVFrame * decodeFrame(AVPacket *pkt); - bool copyBuffers(AVFrame *f, VisionBuf *buf); - - std::vector packets; - std::unique_ptrav_frame_, hw_frame; - AVFormatContext *input_ctx = nullptr; - AVCodecContext *decoder_ctx = nullptr; - int key_frames_count_ = 0; - bool valid_ = false; - AVIOContext *avio_ctx_ = nullptr; - - AVPixelFormat hw_pix_fmt = AV_PIX_FMT_NONE; - AVBufferRef *hw_device_ctx = nullptr; - int prev_idx = -1; - inline static std::atomic has_hw_decoder = true; -}; diff --git a/tools/replay/lib/__init__.py b/tools/replay/lib/__init__.py deleted file mode 100644 index e69de29..0000000 diff --git a/tools/replay/lib/ui_helpers.py b/tools/replay/lib/ui_helpers.py deleted file mode 100644 index e350b89..0000000 --- a/tools/replay/lib/ui_helpers.py +++ /dev/null @@ -1,268 +0,0 @@ -import itertools -from typing import Any, Dict, Tuple - -import matplotlib.pyplot as plt -import numpy as np -import pygame - -from matplotlib.backends.backend_agg import FigureCanvasAgg - -from openpilot.common.transformations.camera import (eon_f_frame_size, eon_f_focal_length, - tici_f_frame_size, tici_f_focal_length, - get_view_frame_from_calib_frame) -from openpilot.selfdrive.controls.radard import RADAR_TO_CAMERA - - -RED = (255, 0, 0) -GREEN = (0, 255, 0) -BLUE = (0, 0, 255) -YELLOW = (255, 255, 0) -BLACK = (0, 0, 0) -WHITE = (255, 255, 255) - -_FULL_FRAME_SIZE = { -} - -class UIParams: - lidar_x, lidar_y, lidar_zoom = 384, 960, 6 - lidar_car_x, lidar_car_y = lidar_x / 2., lidar_y / 1.1 - car_hwidth = 1.7272 / 2 * lidar_zoom - car_front = 2.6924 * lidar_zoom - car_back = 1.8796 * lidar_zoom - car_color = 110 -UP = UIParams - -_BB_TO_FULL_FRAME = {} -_CALIB_BB_TO_FULL = {} -_FULL_FRAME_TO_BB = {} -_INTRINSICS = {} - -eon_f_qcam_frame_size = (480, 360) -tici_f_qcam_frame_size = (528, 330) - -cams = [(eon_f_frame_size, eon_f_focal_length, eon_f_frame_size), - (tici_f_frame_size, tici_f_focal_length, tici_f_frame_size), - (eon_f_qcam_frame_size, eon_f_focal_length, eon_f_frame_size), - (tici_f_qcam_frame_size, tici_f_focal_length, tici_f_frame_size)] -for size, focal, full_size in cams: - sz = size[0] * size[1] - _BB_SCALE = size[0] / 640. - _BB_TO_FULL_FRAME[sz] = np.asarray([ - [_BB_SCALE, 0., 0.], - [0., _BB_SCALE, 0.], - [0., 0., 1.]]) - calib_scale = full_size[0] / 640. - _CALIB_BB_TO_FULL[sz] = np.asarray([ - [calib_scale, 0., 0.], - [0., calib_scale, 0.], - [0., 0., 1.]]) - _FULL_FRAME_TO_BB[sz] = np.linalg.inv(_BB_TO_FULL_FRAME[sz]) - _FULL_FRAME_SIZE[sz] = (size[0], size[1]) - _INTRINSICS[sz] = np.array([ - [focal, 0., full_size[0] / 2.], - [0., focal, full_size[1] / 2.], - [0., 0., 1.]]) - - -METER_WIDTH = 20 - -class Calibration: - def __init__(self, num_px, rpy, intrinsic): - self.intrinsic = intrinsic - self.extrinsics_matrix = get_view_frame_from_calib_frame(rpy[0], rpy[1], rpy[2], 0.0)[:,:3] - self.zoom = _CALIB_BB_TO_FULL[num_px][0, 0] - - def car_space_to_ff(self, x, y, z): - car_space_projective = np.column_stack((x, y, z)).T - - ep = self.extrinsics_matrix.dot(car_space_projective) - kep = self.intrinsic.dot(ep) - return (kep[:-1, :] / kep[-1, :]).T - - def car_space_to_bb(self, x, y, z): - pts = self.car_space_to_ff(x, y, z) - return pts / self.zoom - - -_COLOR_CACHE : Dict[Tuple[int, int, int], Any] = {} -def find_color(lidar_surface, color): - if color in _COLOR_CACHE: - return _COLOR_CACHE[color] - tcolor = 0 - ret = 255 - for x in lidar_surface.get_palette(): - if x[0:3] == color: - ret = tcolor - break - tcolor += 1 - _COLOR_CACHE[color] = ret - return ret - - -def to_topdown_pt(y, x): - px, py = x * UP.lidar_zoom + UP.lidar_car_x, -y * UP.lidar_zoom + UP.lidar_car_y - if px > 0 and py > 0 and px < UP.lidar_x and py < UP.lidar_y: - return int(px), int(py) - return -1, -1 - - -def draw_path(path, color, img, calibration, top_down, lid_color=None, z_off=0): - x, y, z = np.asarray(path.x), np.asarray(path.y), np.asarray(path.z) + z_off - pts = calibration.car_space_to_bb(x, y, z) - pts = np.round(pts).astype(int) - - # draw lidar path point on lidar - # find color in 8 bit - if lid_color is not None and top_down is not None: - tcolor = find_color(top_down[0], lid_color) - for i in range(len(x)): - px, py = to_topdown_pt(x[i], y[i]) - if px != -1: - top_down[1][px, py] = tcolor - - height, width = img.shape[:2] - for x, y in pts: - if 1 < x < width - 1 and 1 < y < height - 1: - for a, b in itertools.permutations([-1, 0, -1], 2): - img[y + a, x + b] = color - - -def init_plots(arr, name_to_arr_idx, plot_xlims, plot_ylims, plot_names, plot_colors, plot_styles): - color_palette = { "r": (1, 0, 0), - "g": (0, 1, 0), - "b": (0, 0, 1), - "k": (0, 0, 0), - "y": (1, 1, 0), - "p": (0, 1, 1), - "m": (1, 0, 1)} - - dpi = 90 - fig = plt.figure(figsize=(575 / dpi, 600 / dpi), dpi=dpi) - canvas = FigureCanvasAgg(fig) - - fig.set_facecolor((0.2, 0.2, 0.2)) - - axs = [] - for pn in range(len(plot_ylims)): - ax = fig.add_subplot(len(plot_ylims), 1, len(axs)+1) - ax.set_xlim(plot_xlims[pn][0], plot_xlims[pn][1]) - ax.set_ylim(plot_ylims[pn][0], plot_ylims[pn][1]) - ax.patch.set_facecolor((0.4, 0.4, 0.4)) - axs.append(ax) - - plots, idxs, plot_select = [], [], [] - for i, pl_list in enumerate(plot_names): - for j, item in enumerate(pl_list): - plot, = axs[i].plot(arr[:, name_to_arr_idx[item]], - label=item, - color=color_palette[plot_colors[i][j]], - linestyle=plot_styles[i][j]) - plots.append(plot) - idxs.append(name_to_arr_idx[item]) - plot_select.append(i) - axs[i].set_title(", ".join(f"{nm} ({cl})" - for (nm, cl) in zip(pl_list, plot_colors[i], strict=False)), fontsize=10) - axs[i].tick_params(axis="x", colors="white") - axs[i].tick_params(axis="y", colors="white") - axs[i].title.set_color("white") - - if i < len(plot_ylims) - 1: - axs[i].set_xticks([]) - - canvas.draw() - - def draw_plots(arr): - for ax in axs: - ax.draw_artist(ax.patch) - for i in range(len(plots)): - plots[i].set_ydata(arr[:, idxs[i]]) - axs[plot_select[i]].draw_artist(plots[i]) - - raw_data = canvas.buffer_rgba() - plot_surface = pygame.image.frombuffer(raw_data, canvas.get_width_height(), "RGBA").convert() - return plot_surface - - return draw_plots - - -def pygame_modules_have_loaded(): - return pygame.display.get_init() and pygame.font.get_init() - - -def plot_model(m, img, calibration, top_down): - if calibration is None or top_down is None: - return - - for lead in m.leadsV3: - if lead.prob < 0.5: - continue - - x, y = lead.x[0], lead.y[0] - x_std = lead.xStd[0] - x -= RADAR_TO_CAMERA - - _, py_top = to_topdown_pt(x + x_std, y) - px, py_bottom = to_topdown_pt(x - x_std, y) - top_down[1][int(round(px - 4)):int(round(px + 4)), py_top:py_bottom] = find_color(top_down[0], YELLOW) - - for path, prob, _ in zip(m.laneLines, m.laneLineProbs, m.laneLineStds, strict=True): - color = (0, int(255 * prob), 0) - draw_path(path, color, img, calibration, top_down, YELLOW) - - for edge, std in zip(m.roadEdges, m.roadEdgeStds, strict=True): - prob = max(1 - std, 0) - color = (int(255 * prob), 0, 0) - draw_path(edge, color, img, calibration, top_down, RED) - - color = (255, 0, 0) - draw_path(m.position, color, img, calibration, top_down, RED, 1.22) - - -def plot_lead(rs, top_down): - for lead in [rs.leadOne, rs.leadTwo]: - if not lead.status: - continue - - x = lead.dRel - px_left, py = to_topdown_pt(x, -10) - px_right, _ = to_topdown_pt(x, 10) - top_down[1][px_left:px_right, py] = find_color(top_down[0], RED) - - -def maybe_update_radar_points(lt, lid_overlay): - ar_pts = [] - if lt is not None: - ar_pts = {} - for track in lt: - ar_pts[track.trackId] = [track.dRel, track.yRel, track.vRel, track.aRel, track.oncoming, track.stationary] - for ids, pt in ar_pts.items(): - # negative here since radar is left positive - px, py = to_topdown_pt(pt[0], -pt[1]) - if px != -1: - if pt[-1]: - color = 240 - elif pt[-2]: - color = 230 - else: - color = 255 - if int(ids) == 1: - lid_overlay[px - 2:px + 2, py - 10:py + 10] = 100 - else: - lid_overlay[px - 2:px + 2, py - 2:py + 2] = color - -def get_blank_lid_overlay(UP): - lid_overlay = np.zeros((UP.lidar_x, UP.lidar_y), 'uint8') - # Draw the car. - lid_overlay[int(round(UP.lidar_car_x - UP.car_hwidth)):int( - round(UP.lidar_car_x + UP.car_hwidth)), int(round(UP.lidar_car_y - - UP.car_front))] = UP.car_color - lid_overlay[int(round(UP.lidar_car_x - UP.car_hwidth)):int( - round(UP.lidar_car_x + UP.car_hwidth)), int(round(UP.lidar_car_y + - UP.car_back))] = UP.car_color - lid_overlay[int(round(UP.lidar_car_x - UP.car_hwidth)), int( - round(UP.lidar_car_y - UP.car_front)):int(round( - UP.lidar_car_y + UP.car_back))] = UP.car_color - lid_overlay[int(round(UP.lidar_car_x + UP.car_hwidth)), int( - round(UP.lidar_car_y - UP.car_front)):int(round( - UP.lidar_car_y + UP.car_back))] = UP.car_color - return lid_overlay diff --git a/tools/replay/logreader.cc b/tools/replay/logreader.cc deleted file mode 100644 index c92ff47..0000000 --- a/tools/replay/logreader.cc +++ /dev/null @@ -1,98 +0,0 @@ -#include "tools/replay/logreader.h" - -#include -#include "tools/replay/filereader.h" -#include "tools/replay/util.h" - -Event::Event(const kj::ArrayPtr &amsg, bool frame) : reader(amsg), frame(frame) { - words = kj::ArrayPtr(amsg.begin(), reader.getEnd()); - event = reader.getRoot(); - which = event.which(); - mono_time = event.getLogMonoTime(); - - // 1) Send video data at t=timestampEof/timestampSof - // 2) Send encodeIndex packet at t=logMonoTime - if (frame) { - auto idx = capnp::AnyStruct::Reader(event).getPointerSection()[0].getAs(); - // C2 only has eof set, and some older routes have neither - uint64_t sof = idx.getTimestampSof(); - uint64_t eof = idx.getTimestampEof(); - if (sof > 0) { - mono_time = sof; - } else if (eof > 0) { - mono_time = eof; - } - } -} - -// class LogReader - -LogReader::LogReader(size_t memory_pool_block_size) { -#ifdef HAS_MEMORY_RESOURCE - const size_t buf_size = sizeof(Event) * memory_pool_block_size; - mbr_ = std::make_unique(buf_size); -#endif - events.reserve(memory_pool_block_size); -} - -LogReader::~LogReader() { - for (Event *e : events) { - delete e; - } -} - -bool LogReader::load(const std::string &url, std::atomic *abort, bool local_cache, int chunk_size, int retries) { - raw_ = FileReader(local_cache, chunk_size, retries).read(url, abort); - if (raw_.empty()) return false; - - if (url.find(".bz2") != std::string::npos) { - raw_ = decompressBZ2(raw_, abort); - if (raw_.empty()) return false; - } - return parse(abort); -} - -bool LogReader::load(const std::byte *data, size_t size, std::atomic *abort) { - raw_.assign((const char *)data, size); - return parse(abort); -} - -bool LogReader::parse(std::atomic *abort) { - try { - kj::ArrayPtr words((const capnp::word *)raw_.data(), raw_.size() / sizeof(capnp::word)); - while (words.size() > 0 && !(abort && *abort)) { -#ifdef HAS_MEMORY_RESOURCE - Event *evt = new (mbr_.get()) Event(words); -#else - Event *evt = new Event(words); -#endif - // Add encodeIdx packet again as a frame packet for the video stream - if (evt->which == cereal::Event::ROAD_ENCODE_IDX || - evt->which == cereal::Event::DRIVER_ENCODE_IDX || - evt->which == cereal::Event::WIDE_ROAD_ENCODE_IDX) { - -#ifdef HAS_MEMORY_RESOURCE - Event *frame_evt = new (mbr_.get()) Event(words, true); -#else - Event *frame_evt = new Event(words, true); -#endif - - events.push_back(frame_evt); - } - - words = kj::arrayPtr(evt->reader.getEnd(), words.end()); - events.push_back(evt); - } - } catch (const kj::Exception &e) { - rWarning("failed to parse log : %s", e.getDescription().cStr()); - if (!events.empty()) { - rWarning("read %zu events from corrupt log", events.size()); - } - } - - if (!events.empty() && !(abort && *abort)) { - std::sort(events.begin(), events.end(), Event::lessThan()); - return true; - } - return false; -} diff --git a/tools/replay/logreader.h b/tools/replay/logreader.h deleted file mode 100644 index 73f822d..0000000 --- a/tools/replay/logreader.h +++ /dev/null @@ -1,67 +0,0 @@ -#pragma once - -#if __has_include() -#define HAS_MEMORY_RESOURCE 1 -#include -#endif - -#include -#include -#include - -#include "cereal/gen/cpp/log.capnp.h" -#include "system/camerad/cameras/camera_common.h" - -const CameraType ALL_CAMERAS[] = {RoadCam, DriverCam, WideRoadCam}; -const int MAX_CAMERAS = std::size(ALL_CAMERAS); -const int DEFAULT_EVENT_MEMORY_POOL_BLOCK_SIZE = 65000; - -class Event { -public: - Event(cereal::Event::Which which, uint64_t mono_time) : reader(kj::ArrayPtr{}) { - // construct a dummy Event for binary search, e.g std::upper_bound - this->which = which; - this->mono_time = mono_time; - } - Event(const kj::ArrayPtr &amsg, bool frame = false); - inline kj::ArrayPtr bytes() const { return words.asBytes(); } - - struct lessThan { - inline bool operator()(const Event *l, const Event *r) { - return l->mono_time < r->mono_time || (l->mono_time == r->mono_time && l->which < r->which); - } - }; - -#if HAS_MEMORY_RESOURCE - void *operator new(size_t size, std::pmr::monotonic_buffer_resource *mbr) { - return mbr->allocate(size); - } - void operator delete(void *ptr) { - // No-op. memory used by EventMemoryPool increases monotonically until the logReader is destroyed. - } -#endif - - uint64_t mono_time; - cereal::Event::Which which; - cereal::Event::Reader event; - capnp::FlatArrayMessageReader reader; - kj::ArrayPtr words; - bool frame; -}; - -class LogReader { -public: - LogReader(size_t memory_pool_block_size = DEFAULT_EVENT_MEMORY_POOL_BLOCK_SIZE); - ~LogReader(); - bool load(const std::string &url, std::atomic *abort = nullptr, - bool local_cache = false, int chunk_size = -1, int retries = 0); - bool load(const std::byte *data, size_t size, std::atomic *abort = nullptr); - std::vector events; - -private: - bool parse(std::atomic *abort); - std::string raw_; -#ifdef HAS_MEMORY_RESOURCE - std::unique_ptr mbr_; -#endif -}; diff --git a/tools/replay/main.cc b/tools/replay/main.cc deleted file mode 100644 index a0c0724..0000000 --- a/tools/replay/main.cc +++ /dev/null @@ -1,83 +0,0 @@ -#include -#include - -#include "common/prefix.h" -#include "tools/replay/consoleui.h" -#include "tools/replay/replay.h" - -int main(int argc, char *argv[]) { -#ifdef __APPLE__ - // With all sockets opened, we might hit the default limit of 256 on macOS - util::set_file_descriptor_limit(1024); -#endif - - QCoreApplication app(argc, argv); - - const std::tuple flags[] = { - {"dcam", REPLAY_FLAG_DCAM, "load driver camera"}, - {"ecam", REPLAY_FLAG_ECAM, "load wide road camera"}, - {"no-loop", REPLAY_FLAG_NO_LOOP, "stop at the end of the route"}, - {"no-cache", REPLAY_FLAG_NO_FILE_CACHE, "turn off local cache"}, - {"qcam", REPLAY_FLAG_QCAMERA, "load qcamera"}, - {"no-hw-decoder", REPLAY_FLAG_NO_HW_DECODER, "disable HW video decoding"}, - {"no-vipc", REPLAY_FLAG_NO_VIPC, "do not output video"}, - {"all", REPLAY_FLAG_ALL_SERVICES, "do output all messages including uiDebug, userFlag" - ". this may causes issues when used along with UI"} - }; - - QCommandLineParser parser; - parser.setApplicationDescription("Mock openpilot components by publishing logged messages."); - parser.addHelpOption(); - parser.addPositionalArgument("route", "the drive to replay. find your drives at connect.comma.ai"); - parser.addOption({{"a", "allow"}, "whitelist of services to send", "allow"}); - parser.addOption({{"b", "block"}, "blacklist of services to send", "block"}); - parser.addOption({{"c", "cache"}, "cache segments in memory. default is 5", "n"}); - parser.addOption({{"s", "start"}, "start from ", "seconds"}); - parser.addOption({"x", QString("playback . between %1 - %2") - .arg(ConsoleUI::speed_array.front()).arg(ConsoleUI::speed_array.back()), "speed"}); - parser.addOption({"demo", "use a demo route instead of providing your own"}); - parser.addOption({"data_dir", "local directory with routes", "data_dir"}); - parser.addOption({"prefix", "set OPENPILOT_PREFIX", "prefix"}); - for (auto &[name, _, desc] : flags) { - parser.addOption({name, desc}); - } - - parser.process(app); - const QStringList args = parser.positionalArguments(); - if (args.empty() && !parser.isSet("demo")) { - parser.showHelp(); - } - - const QString route = args.empty() ? DEMO_ROUTE : args.first(); - QStringList allow = parser.value("allow").isEmpty() ? QStringList{} : parser.value("allow").split(","); - QStringList block = parser.value("block").isEmpty() ? QStringList{} : parser.value("block").split(","); - - uint32_t replay_flags = REPLAY_FLAG_NONE; - for (const auto &[name, flag, _] : flags) { - if (parser.isSet(name)) { - replay_flags |= flag; - } - } - - std::unique_ptr op_prefix; - auto prefix = parser.value("prefix"); - if (!prefix.isEmpty()) { - op_prefix.reset(new OpenpilotPrefix(prefix.toStdString())); - } - - Replay *replay = new Replay(route, allow, block, nullptr, replay_flags, parser.value("data_dir"), &app); - if (!parser.value("c").isEmpty()) { - replay->setSegmentCacheLimit(parser.value("c").toInt()); - } - if (!parser.value("x").isEmpty()) { - replay->setSpeed(std::clamp(parser.value("x").toFloat(), - ConsoleUI::speed_array.front(), ConsoleUI::speed_array.back())); - } - if (!replay->load()) { - return 0; - } - - ConsoleUI console_ui(replay); - replay->start(parser.value("start").toInt()); - return app.exec(); -} diff --git a/tools/replay/replay.cc b/tools/replay/replay.cc deleted file mode 100644 index 9657375..0000000 --- a/tools/replay/replay.cc +++ /dev/null @@ -1,428 +0,0 @@ -#include "tools/replay/replay.h" - -#include -#include - -#include -#include "cereal/services.h" -#include "common/params.h" -#include "common/timing.h" -#include "tools/replay/util.h" - -Replay::Replay(QString route, QStringList allow, QStringList block, SubMaster *sm_, - uint32_t flags, QString data_dir, QObject *parent) : sm(sm_), flags_(flags), QObject(parent) { - if (!(flags_ & REPLAY_FLAG_ALL_SERVICES)) { - block << "uiDebug" << "userFlag"; - } - auto event_struct = capnp::Schema::from().asStruct(); - sockets_.resize(event_struct.getUnionFields().size()); - for (const auto &[name, _] : services) { - if (!block.contains(name.c_str()) && (allow.empty() || allow.contains(name.c_str()))) { - uint16_t which = event_struct.getFieldByName(name).getProto().getDiscriminantValue(); - sockets_[which] = name.c_str(); - } - } - - std::vector s; - std::copy_if(sockets_.begin(), sockets_.end(), std::back_inserter(s), - [](const char *name) { return name != nullptr; }); - qDebug() << "services " << s; - qDebug() << "loading route " << route; - - if (sm == nullptr) { - pm = std::make_unique(s); - } - route_ = std::make_unique(route, data_dir); - events_ = std::make_unique>(); - new_events_ = std::make_unique>(); -} - -Replay::~Replay() { - stop(); -} - -void Replay::stop() { - if (!stream_thread_ && segments_.empty()) return; - - rInfo("shutdown: in progress..."); - if (stream_thread_ != nullptr) { - exit_ = updating_events_ = true; - stream_cv_.notify_one(); - stream_thread_->quit(); - stream_thread_->wait(); - stream_thread_ = nullptr; - } - camera_server_.reset(nullptr); - timeline_future.waitForFinished(); - segments_.clear(); - rInfo("shutdown: done"); -} - -bool Replay::load() { - if (!route_->load()) { - qCritical() << "failed to load route" << route_->name() - << "from" << (route_->dir().isEmpty() ? "server" : route_->dir()); - return false; - } - - for (auto &[n, f] : route_->segments()) { - bool has_log = !f.rlog.isEmpty() || !f.qlog.isEmpty(); - bool has_video = !f.road_cam.isEmpty() || !f.qcamera.isEmpty(); - if (has_log && (has_video || hasFlag(REPLAY_FLAG_NO_VIPC))) { - segments_.insert({n, nullptr}); - } - } - if (segments_.empty()) { - qCritical() << "no valid segments in route" << route_->name(); - return false; - } - rInfo("load route %s with %zu valid segments", qPrintable(route_->name()), segments_.size()); - return true; -} - -void Replay::start(int seconds) { - seekTo(route_->identifier().segment_id * 60 + seconds, false); -} - -void Replay::updateEvents(const std::function &lambda) { - // set updating_events to true to force stream thread release the lock and wait for events_updated. - updating_events_ = true; - { - std::unique_lock lk(stream_lock_); - events_updated_ = lambda(); - updating_events_ = false; - } - stream_cv_.notify_one(); -} - -void Replay::seekTo(double seconds, bool relative) { - seconds = relative ? seconds + currentSeconds() : seconds; - updateEvents([&]() { - seconds = std::max(double(0.0), seconds); - int seg = (int)seconds / 60; - if (segments_.find(seg) == segments_.end()) { - rWarning("can't seek to %d s segment %d is invalid", seconds, seg); - return true; - } - - rInfo("seeking to %d s, segment %d", (int)seconds, seg); - current_segment_ = seg; - cur_mono_time_ = route_start_ts_ + seconds * 1e9; - emit seekedTo(seconds); - return isSegmentMerged(seg); - }); - queueSegment(); -} - -void Replay::seekToFlag(FindFlag flag) { - if (auto next = find(flag)) { - seekTo(*next - 2, false); // seek to 2 seconds before next - } -} - -void Replay::buildTimeline() { - uint64_t engaged_begin = 0; - bool engaged = false; - - auto alert_status = cereal::ControlsState::AlertStatus::NORMAL; - auto alert_size = cereal::ControlsState::AlertSize::NONE; - uint64_t alert_begin = 0; - std::string alert_type; - - const TimelineType timeline_types[] = { - [(int)cereal::ControlsState::AlertStatus::NORMAL] = TimelineType::AlertInfo, - [(int)cereal::ControlsState::AlertStatus::USER_PROMPT] = TimelineType::AlertWarning, - [(int)cereal::ControlsState::AlertStatus::CRITICAL] = TimelineType::AlertCritical, - }; - - const auto &route_segments = route_->segments(); - for (auto it = route_segments.cbegin(); it != route_segments.cend() && !exit_; ++it) { - std::shared_ptr log(new LogReader()); - if (!log->load(it->second.qlog.toStdString(), &exit_, !hasFlag(REPLAY_FLAG_NO_FILE_CACHE), 0, 3)) continue; - - for (const Event *e : log->events) { - if (e->which == cereal::Event::Which::CONTROLS_STATE) { - auto cs = e->event.getControlsState(); - - if (engaged != cs.getEnabled()) { - if (engaged) { - std::lock_guard lk(timeline_lock); - timeline.push_back({toSeconds(engaged_begin), toSeconds(e->mono_time), TimelineType::Engaged}); - } - engaged_begin = e->mono_time; - engaged = cs.getEnabled(); - } - - if (alert_type != cs.getAlertType().cStr() || alert_status != cs.getAlertStatus()) { - if (!alert_type.empty() && alert_size != cereal::ControlsState::AlertSize::NONE) { - std::lock_guard lk(timeline_lock); - timeline.push_back({toSeconds(alert_begin), toSeconds(e->mono_time), timeline_types[(int)alert_status]}); - } - alert_begin = e->mono_time; - alert_type = cs.getAlertType().cStr(); - alert_size = cs.getAlertSize(); - alert_status = cs.getAlertStatus(); - } - } else if (e->which == cereal::Event::Which::USER_FLAG) { - std::lock_guard lk(timeline_lock); - timeline.push_back({toSeconds(e->mono_time), toSeconds(e->mono_time), TimelineType::UserFlag}); - } - } - std::sort(timeline.begin(), timeline.end(), [](auto &l, auto &r) { return std::get<2>(l) < std::get<2>(r); }); - emit qLogLoaded(it->first, log); - } -} - -std::optional Replay::find(FindFlag flag) { - int cur_ts = currentSeconds(); - for (auto [start_ts, end_ts, type] : getTimeline()) { - if (type == TimelineType::Engaged) { - if (flag == FindFlag::nextEngagement && start_ts > cur_ts) { - return start_ts; - } else if (flag == FindFlag::nextDisEngagement && end_ts > cur_ts) { - return end_ts; - } - } else if (start_ts > cur_ts) { - if ((flag == FindFlag::nextUserFlag && type == TimelineType::UserFlag) || - (flag == FindFlag::nextInfo && type == TimelineType::AlertInfo) || - (flag == FindFlag::nextWarning && type == TimelineType::AlertWarning) || - (flag == FindFlag::nextCritical && type == TimelineType::AlertCritical)) { - return start_ts; - } - } - } - return std::nullopt; -} - -void Replay::pause(bool pause) { - updateEvents([=]() { - rWarning("%s at %.2f s", pause ? "paused..." : "resuming", currentSeconds()); - paused_ = pause; - return true; - }); -} - -void Replay::setCurrentSegment(int n) { - if (current_segment_.exchange(n) != n) { - QMetaObject::invokeMethod(this, &Replay::queueSegment, Qt::QueuedConnection); - } -} - -void Replay::segmentLoadFinished(bool success) { - if (!success) { - Segment *seg = qobject_cast(sender()); - rWarning("failed to load segment %d, removing it from current replay list", seg->seg_num); - updateEvents([&]() { - segments_.erase(seg->seg_num); - return true; - }); - } - queueSegment(); -} - -void Replay::queueSegment() { - auto cur = segments_.lower_bound(current_segment_.load()); - if (cur == segments_.end()) return; - - auto begin = std::prev(cur, std::min(segment_cache_limit / 2, std::distance(segments_.begin(), cur))); - auto end = std::next(begin, std::min(segment_cache_limit, segments_.size())); - // load one segment at a time - auto it = std::find_if(cur, end, [](auto &it) { return !it.second || !it.second->isLoaded(); }); - if (it != end && !it->second) { - rDebug("loading segment %d...", it->first); - it->second = std::make_unique(it->first, route_->at(it->first), flags_); - QObject::connect(it->second.get(), &Segment::loadFinished, this, &Replay::segmentLoadFinished); - } - - mergeSegments(begin, end); - - // free segments out of current semgnt window. - std::for_each(segments_.begin(), begin, [](auto &e) { e.second.reset(nullptr); }); - std::for_each(end, segments_.end(), [](auto &e) { e.second.reset(nullptr); }); - - // start stream thread - const auto &cur_segment = cur->second; - if (stream_thread_ == nullptr && cur_segment->isLoaded()) { - startStream(cur_segment.get()); - emit streamStarted(); - } -} - -void Replay::mergeSegments(const SegmentMap::iterator &begin, const SegmentMap::iterator &end) { - std::vector segments_need_merge; - size_t new_events_size = 0; - for (auto it = begin; it != end; ++it) { - if (it->second && it->second->isLoaded()) { - segments_need_merge.push_back(it->first); - new_events_size += it->second->log->events.size(); - } - } - - if (segments_need_merge != segments_merged_) { - std::string s; - for (int i = 0; i < segments_need_merge.size(); ++i) { - s += std::to_string(segments_need_merge[i]); - if (i != segments_need_merge.size() - 1) s += ", "; - } - rDebug("merge segments %s", s.c_str()); - new_events_->clear(); - new_events_->reserve(new_events_size); - for (int n : segments_need_merge) { - size_t size = new_events_->size(); - const auto &events = segments_[n]->log->events; - std::copy_if(events.begin(), events.end(), std::back_inserter(*new_events_), - [this](auto e) { return e->which < sockets_.size() && sockets_[e->which] != nullptr; }); - std::inplace_merge(new_events_->begin(), new_events_->begin() + size, new_events_->end(), Event::lessThan()); - } - - if (stream_thread_) { - emit segmentsMerged(); - } - updateEvents([&]() { - events_.swap(new_events_); - segments_merged_ = segments_need_merge; - // Do not wake up the stream thread if the current segment has not been merged. - return isSegmentMerged(current_segment_) || (segments_.count(current_segment_) == 0); - }); - } -} - -void Replay::startStream(const Segment *cur_segment) { - const auto &events = cur_segment->log->events; - - // each segment has an INIT_DATA - route_start_ts_ = events.front()->mono_time; - cur_mono_time_ += route_start_ts_ - 1; - - // write CarParams - auto it = std::find_if(events.begin(), events.end(), [](auto e) { return e->which == cereal::Event::Which::CAR_PARAMS; }); - if (it != events.end()) { - car_fingerprint_ = (*it)->event.getCarParams().getCarFingerprint(); - capnp::MallocMessageBuilder builder; - builder.setRoot((*it)->event.getCarParams()); - auto words = capnp::messageToFlatArray(builder); - auto bytes = words.asBytes(); - Params().put("CarParams", (const char *)bytes.begin(), bytes.size()); - Params().put("CarParamsPersistent", (const char *)bytes.begin(), bytes.size()); - } else { - rWarning("failed to read CarParams from current segment"); - } - - // start camera server - if (!hasFlag(REPLAY_FLAG_NO_VIPC)) { - std::pair camera_size[MAX_CAMERAS] = {}; - for (auto type : ALL_CAMERAS) { - if (auto &fr = cur_segment->frames[type]) { - camera_size[type] = {fr->width, fr->height}; - } - } - camera_server_ = std::make_unique(camera_size); - } - - emit segmentsMerged(); - // start stream thread - stream_thread_ = new QThread(); - QObject::connect(stream_thread_, &QThread::started, [=]() { stream(); }); - QObject::connect(stream_thread_, &QThread::finished, stream_thread_, &QThread::deleteLater); - stream_thread_->start(); - - timeline_future = QtConcurrent::run(this, &Replay::buildTimeline); -} - -void Replay::publishMessage(const Event *e) { - if (event_filter && event_filter(e, filter_opaque)) return; - - if (sm == nullptr) { - auto bytes = e->bytes(); - int ret = pm->send(sockets_[e->which], (capnp::byte *)bytes.begin(), bytes.size()); - if (ret == -1) { - rWarning("stop publishing %s due to multiple publishers error", sockets_[e->which]); - sockets_[e->which] = nullptr; - } - } else { - sm->update_msgs(nanos_since_boot(), {{sockets_[e->which], e->event}}); - } -} - -void Replay::publishFrame(const Event *e) { - static const std::map cam_types{ - {cereal::Event::ROAD_ENCODE_IDX, RoadCam}, - {cereal::Event::DRIVER_ENCODE_IDX, DriverCam}, - {cereal::Event::WIDE_ROAD_ENCODE_IDX, WideRoadCam}, - }; - if ((e->which == cereal::Event::DRIVER_ENCODE_IDX && !hasFlag(REPLAY_FLAG_DCAM)) || - (e->which == cereal::Event::WIDE_ROAD_ENCODE_IDX && !hasFlag(REPLAY_FLAG_ECAM))) { - return; - } - auto eidx = capnp::AnyStruct::Reader(e->event).getPointerSection()[0].getAs(); - if (eidx.getType() == cereal::EncodeIndex::Type::FULL_H_E_V_C && isSegmentMerged(eidx.getSegmentNum())) { - CameraType cam = cam_types.at(e->which); - camera_server_->pushFrame(cam, segments_[eidx.getSegmentNum()]->frames[cam].get(), eidx); - } -} - -void Replay::stream() { - cereal::Event::Which cur_which = cereal::Event::Which::INIT_DATA; - double prev_replay_speed = speed_; - std::unique_lock lk(stream_lock_); - - while (true) { - stream_cv_.wait(lk, [=]() { return exit_ || (events_updated_ && !paused_); }); - events_updated_ = false; - if (exit_) break; - - Event cur_event(cur_which, cur_mono_time_); - auto eit = std::upper_bound(events_->begin(), events_->end(), &cur_event, Event::lessThan()); - if (eit == events_->end()) { - rInfo("waiting for events..."); - continue; - } - - uint64_t evt_start_ts = cur_mono_time_; - uint64_t loop_start_ts = nanos_since_boot(); - - for (auto end = events_->end(); !updating_events_ && eit != end; ++eit) { - const Event *evt = (*eit); - cur_which = evt->which; - cur_mono_time_ = evt->mono_time; - setCurrentSegment(toSeconds(cur_mono_time_) / 60); - - if (sockets_[cur_which] != nullptr) { - // keep time - long etime = (cur_mono_time_ - evt_start_ts) / speed_; - long rtime = nanos_since_boot() - loop_start_ts; - long behind_ns = etime - rtime; - // if behind_ns is greater than 1 second, it means that an invalid segment is skipped by seeking/replaying - if (behind_ns >= 1 * 1e9 || speed_ != prev_replay_speed) { - // reset event start times - evt_start_ts = cur_mono_time_; - loop_start_ts = nanos_since_boot(); - prev_replay_speed = speed_; - } else if (behind_ns > 0) { - precise_nano_sleep(behind_ns); - } - - if (!evt->frame) { - publishMessage(evt); - } else if (camera_server_) { - if (speed_ > 1.0) { - camera_server_->waitForSent(); - } - publishFrame(evt); - } - } - } - // wait for frame to be sent before unlock.(frameReader may be deleted after unlock) - if (camera_server_) { - camera_server_->waitForSent(); - } - - if (eit == events_->end() && !hasFlag(REPLAY_FLAG_NO_LOOP)) { - int last_segment = segments_.empty() ? 0 : segments_.rbegin()->first; - if (current_segment_ >= last_segment && isSegmentMerged(last_segment)) { - rInfo("reaches the end of route, restart from beginning"); - QMetaObject::invokeMethod(this, std::bind(&Replay::seekTo, this, 0, false), Qt::QueuedConnection); - } - } - } -} diff --git a/tools/replay/replay.h b/tools/replay/replay.h deleted file mode 100644 index 1a74b69..0000000 --- a/tools/replay/replay.h +++ /dev/null @@ -1,146 +0,0 @@ -#pragma once - -#include -#include -#include -#include -#include -#include -#include -#include - -#include - -#include "tools/replay/camera.h" -#include "tools/replay/route.h" - -const QString DEMO_ROUTE = "a2a0ccea32023010|2023-07-27--13-01-19"; - -// one segment uses about 100M of memory -constexpr int MIN_SEGMENTS_CACHE = 5; - -enum REPLAY_FLAGS { - REPLAY_FLAG_NONE = 0x0000, - REPLAY_FLAG_DCAM = 0x0002, - REPLAY_FLAG_ECAM = 0x0004, - REPLAY_FLAG_NO_LOOP = 0x0010, - REPLAY_FLAG_NO_FILE_CACHE = 0x0020, - REPLAY_FLAG_QCAMERA = 0x0040, - REPLAY_FLAG_NO_HW_DECODER = 0x0100, - REPLAY_FLAG_NO_VIPC = 0x0400, - REPLAY_FLAG_ALL_SERVICES = 0x0800, -}; - -enum class FindFlag { - nextEngagement, - nextDisEngagement, - nextUserFlag, - nextInfo, - nextWarning, - nextCritical -}; - -enum class TimelineType { None, Engaged, AlertInfo, AlertWarning, AlertCritical, UserFlag }; -typedef bool (*replayEventFilter)(const Event *, void *); -Q_DECLARE_METATYPE(std::shared_ptr); - -class Replay : public QObject { - Q_OBJECT - -public: - Replay(QString route, QStringList allow, QStringList block, SubMaster *sm = nullptr, - uint32_t flags = REPLAY_FLAG_NONE, QString data_dir = "", QObject *parent = 0); - ~Replay(); - bool load(); - void start(int seconds = 0); - void stop(); - void pause(bool pause); - void seekToFlag(FindFlag flag); - void seekTo(double seconds, bool relative); - inline bool isPaused() const { return paused_; } - // the filter is called in streaming thread.try to return quickly from it to avoid blocking streaming. - // the filter function must return true if the event should be filtered. - // otherwise it must return false. - inline void installEventFilter(replayEventFilter filter, void *opaque) { - filter_opaque = opaque; - event_filter = filter; - } - inline int segmentCacheLimit() const { return segment_cache_limit; } - inline void setSegmentCacheLimit(int n) { segment_cache_limit = std::max(MIN_SEGMENTS_CACHE, n); } - inline bool hasFlag(REPLAY_FLAGS flag) const { return flags_ & flag; } - inline void addFlag(REPLAY_FLAGS flag) { flags_ |= flag; } - inline void removeFlag(REPLAY_FLAGS flag) { flags_ &= ~flag; } - inline const Route* route() const { return route_.get(); } - inline double currentSeconds() const { return double(cur_mono_time_ - route_start_ts_) / 1e9; } - inline QDateTime currentDateTime() const { return route_->datetime().addSecs(currentSeconds()); } - inline uint64_t routeStartTime() const { return route_start_ts_; } - inline double toSeconds(uint64_t mono_time) const { return (mono_time - route_start_ts_) / 1e9; } - inline int totalSeconds() const { return (!segments_.empty()) ? (segments_.rbegin()->first + 1) * 60 : 0; } - inline void setSpeed(float speed) { speed_ = speed; } - inline float getSpeed() const { return speed_; } - inline const std::vector *events() const { return events_.get(); } - inline const std::map> &segments() const { return segments_; } - inline const std::string &carFingerprint() const { return car_fingerprint_; } - inline const std::vector> getTimeline() { - std::lock_guard lk(timeline_lock); - return timeline; - } - -signals: - void streamStarted(); - void segmentsMerged(); - void seekedTo(double sec); - void qLogLoaded(int segnum, std::shared_ptr qlog); - -protected slots: - void segmentLoadFinished(bool success); - -protected: - typedef std::map> SegmentMap; - std::optional find(FindFlag flag); - void startStream(const Segment *cur_segment); - void stream(); - void setCurrentSegment(int n); - void queueSegment(); - void mergeSegments(const SegmentMap::iterator &begin, const SegmentMap::iterator &end); - void updateEvents(const std::function& lambda); - void publishMessage(const Event *e); - void publishFrame(const Event *e); - void buildTimeline(); - inline bool isSegmentMerged(int n) { - return std::find(segments_merged_.begin(), segments_merged_.end(), n) != segments_merged_.end(); - } - - QThread *stream_thread_ = nullptr; - std::mutex stream_lock_; - std::condition_variable stream_cv_; - std::atomic updating_events_ = false; - std::atomic current_segment_ = 0; - SegmentMap segments_; - // the following variables must be protected with stream_lock_ - std::atomic exit_ = false; - bool paused_ = false; - bool events_updated_ = false; - uint64_t route_start_ts_ = 0; - std::atomic cur_mono_time_ = 0; - std::unique_ptr> events_; - std::unique_ptr> new_events_; - std::vector segments_merged_; - - // messaging - SubMaster *sm = nullptr; - std::unique_ptr pm; - std::vector sockets_; - std::unique_ptr route_; - std::unique_ptr camera_server_; - std::atomic flags_ = REPLAY_FLAG_NONE; - - std::mutex timeline_lock; - QFuture timeline_future; - std::vector> timeline; - std::string car_fingerprint_; - std::atomic speed_ = 1.0; - replayEventFilter event_filter = nullptr; - void *filter_opaque = nullptr; - int segment_cache_limit = MIN_SEGMENTS_CACHE; -}; diff --git a/tools/replay/route.cc b/tools/replay/route.cc deleted file mode 100644 index d0ddf7f..0000000 --- a/tools/replay/route.cc +++ /dev/null @@ -1,144 +0,0 @@ -#include "tools/replay/route.h" - -#include -#include -#include -#include -#include -#include -#include - -#include "selfdrive/ui/qt/api.h" -#include "system/hardware/hw.h" -#include "tools/replay/replay.h" -#include "tools/replay/util.h" - -Route::Route(const QString &route, const QString &data_dir) : data_dir_(data_dir) { - route_ = parseRoute(route); -} - -RouteIdentifier Route::parseRoute(const QString &str) { - QRegExp rx(R"(^(?:([a-z0-9]{16})([|_/]))?(\d{4}-\d{2}-\d{2}--\d{2}-\d{2}-\d{2})(?:(--|/)(\d*))?$)"); - if (rx.indexIn(str) == -1) return {}; - - const QStringList list = rx.capturedTexts(); - return {.dongle_id = list[1], .timestamp = list[3], .segment_id = list[5].toInt(), .str = list[1] + "|" + list[3]}; -} - -bool Route::load() { - if (route_.str.isEmpty() || (data_dir_.isEmpty() && route_.dongle_id.isEmpty())) { - rInfo("invalid route format"); - return false; - } - date_time_ = QDateTime::fromString(route_.timestamp, "yyyy-MM-dd--HH-mm-ss"); - return data_dir_.isEmpty() ? loadFromServer() : loadFromLocal(); -} - -bool Route::loadFromServer() { - QEventLoop loop; - HttpRequest http(nullptr, !Hardware::PC()); - QObject::connect(&http, &HttpRequest::requestDone, [&](const QString &json, bool success, QNetworkReply::NetworkError error) { - if (error == QNetworkReply::ContentAccessDenied || error == QNetworkReply::AuthenticationRequiredError) { - qWarning() << ">> Unauthorized. Authenticate with tools/lib/auth.py <<"; - } - - loop.exit(success ? loadFromJson(json) : 0); - }); - http.sendRequest(CommaApi::BASE_URL + "/v1/route/" + route_.str + "/files"); - return loop.exec(); -} - -bool Route::loadFromJson(const QString &json) { - QRegExp rx(R"(\/(\d+)\/)"); - for (const auto &value : QJsonDocument::fromJson(json.trimmed().toUtf8()).object()) { - for (const auto &url : value.toArray()) { - QString url_str = url.toString(); - if (rx.indexIn(url_str) != -1) { - addFileToSegment(rx.cap(1).toInt(), url_str); - } - } - } - return !segments_.empty(); -} - -bool Route::loadFromLocal() { - QDir log_dir(data_dir_); - for (const auto &folder : log_dir.entryList(QDir::Dirs | QDir::NoDot | QDir::NoDotDot, QDir::NoSort)) { - int pos = folder.lastIndexOf("--"); - if (pos != -1 && folder.left(pos) == route_.timestamp) { - const int seg_num = folder.mid(pos + 2).toInt(); - QDir segment_dir(log_dir.filePath(folder)); - for (const auto &f : segment_dir.entryList(QDir::Files)) { - addFileToSegment(seg_num, segment_dir.absoluteFilePath(f)); - } - } - } - return !segments_.empty(); -} - -void Route::addFileToSegment(int n, const QString &file) { - QString name = QUrl(file).fileName(); - - const int pos = name.lastIndexOf("--"); - name = pos != -1 ? name.mid(pos + 2) : name; - - if (name == "rlog.bz2" || name == "rlog") { - segments_[n].rlog = file; - } else if (name == "qlog.bz2" || name == "qlog") { - segments_[n].qlog = file; - } else if (name == "fcamera.hevc") { - segments_[n].road_cam = file; - } else if (name == "dcamera.hevc") { - segments_[n].driver_cam = file; - } else if (name == "ecamera.hevc") { - segments_[n].wide_road_cam = file; - } else if (name == "qcamera.ts") { - segments_[n].qcamera = file; - } -} - -// class Segment - -Segment::Segment(int n, const SegmentFile &files, uint32_t flags) : seg_num(n), flags(flags) { - // [RoadCam, DriverCam, WideRoadCam, log]. fallback to qcamera/qlog - const std::array file_list = { - (flags & REPLAY_FLAG_QCAMERA) || files.road_cam.isEmpty() ? files.qcamera : files.road_cam, - flags & REPLAY_FLAG_DCAM ? files.driver_cam : "", - flags & REPLAY_FLAG_ECAM ? files.wide_road_cam : "", - files.rlog.isEmpty() ? files.qlog : files.rlog, - }; - for (int i = 0; i < file_list.size(); ++i) { - if (!file_list[i].isEmpty() && (!(flags & REPLAY_FLAG_NO_VIPC) || i >= MAX_CAMERAS)) { - ++loading_; - synchronizer_.addFuture(QtConcurrent::run(this, &Segment::loadFile, i, file_list[i].toStdString())); - } - } -} - -Segment::~Segment() { - disconnect(); - abort_ = true; - synchronizer_.setCancelOnWait(true); - synchronizer_.waitForFinished(); -} - -void Segment::loadFile(int id, const std::string file) { - const bool local_cache = !(flags & REPLAY_FLAG_NO_FILE_CACHE); - bool success = false; - if (id < MAX_CAMERAS) { - frames[id] = std::make_unique(); - success = frames[id]->load(file, flags & REPLAY_FLAG_NO_HW_DECODER, &abort_, local_cache, 20 * 1024 * 1024, 3); - } else { - log = std::make_unique(); - success = log->load(file, &abort_, local_cache, 0, 3); - } - - if (!success) { - // abort all loading jobs. - abort_ = true; - } - - if (--loading_ == 0) { - emit loadFinished(!abort_); - } -} diff --git a/tools/replay/route.h b/tools/replay/route.h deleted file mode 100644 index 4dad7a1..0000000 --- a/tools/replay/route.h +++ /dev/null @@ -1,75 +0,0 @@ -#pragma once - -#include -#include -#include - -#include -#include - -#include "tools/replay/framereader.h" -#include "tools/replay/logreader.h" -#include "tools/replay/util.h" - -struct RouteIdentifier { - QString dongle_id; - QString timestamp; - int segment_id; - QString str; -}; - -struct SegmentFile { - QString rlog; - QString qlog; - QString road_cam; - QString driver_cam; - QString wide_road_cam; - QString qcamera; -}; - -class Route { -public: - Route(const QString &route, const QString &data_dir = {}); - bool load(); - inline const QString &name() const { return route_.str; } - inline const QDateTime datetime() const { return date_time_; } - inline const QString &dir() const { return data_dir_; } - inline const RouteIdentifier &identifier() const { return route_; } - inline const std::map &segments() const { return segments_; } - inline const SegmentFile &at(int n) { return segments_.at(n); } - static RouteIdentifier parseRoute(const QString &str); - -protected: - bool loadFromLocal(); - bool loadFromServer(); - bool loadFromJson(const QString &json); - void addFileToSegment(int seg_num, const QString &file); - RouteIdentifier route_ = {}; - QString data_dir_; - std::map segments_; - QDateTime date_time_; -}; - -class Segment : public QObject { - Q_OBJECT - -public: - Segment(int n, const SegmentFile &files, uint32_t flags); - ~Segment(); - inline bool isLoaded() const { return !loading_ && !abort_; } - - const int seg_num = 0; - std::unique_ptr log; - std::unique_ptr frames[MAX_CAMERAS] = {}; - -signals: - void loadFinished(bool success); - -protected: - void loadFile(int id, const std::string file); - - std::atomic abort_ = false; - std::atomic loading_ = 0; - QFutureSynchronizer synchronizer_; - uint32_t flags; -}; diff --git a/tools/replay/tests/test_replay.cc b/tools/replay/tests/test_replay.cc deleted file mode 100644 index 1873daa..0000000 --- a/tools/replay/tests/test_replay.cc +++ /dev/null @@ -1,220 +0,0 @@ -#include -#include - -#include -#include - -#include "catch2/catch.hpp" -#include "common/util.h" -#include "tools/replay/replay.h" -#include "tools/replay/util.h" - -const std::string TEST_RLOG_URL = "https://commadataci.blob.core.windows.net/openpilotci/0c94aa1e1296d7c6/2021-05-05--19-48-37/0/rlog.bz2"; -const std::string TEST_RLOG_CHECKSUM = "5b966d4bb21a100a8c4e59195faeb741b975ccbe268211765efd1763d892bfb3"; - -bool download_to_file(const std::string &url, const std::string &local_file, int chunk_size = 5 * 1024 * 1024, int retries = 3) { - do { - if (httpDownload(url, local_file, chunk_size)) { - return true; - } - std::this_thread::sleep_for(std::chrono::milliseconds(500)); - } while (--retries >= 0); - return false; -} - -TEST_CASE("httpMultiPartDownload") { - char filename[] = "/tmp/XXXXXX"; - close(mkstemp(filename)); - - const size_t chunk_size = 5 * 1024 * 1024; - std::string content; - SECTION("download to file") { - REQUIRE(download_to_file(TEST_RLOG_URL, filename, chunk_size)); - content = util::read_file(filename); - } - SECTION("download to buffer") { - for (int i = 0; i < 3 && content.empty(); ++i) { - content = httpGet(TEST_RLOG_URL, chunk_size); - std::this_thread::sleep_for(std::chrono::milliseconds(500)); - } - REQUIRE(!content.empty()); - } - REQUIRE(content.size() == 9112651); - REQUIRE(sha256(content) == TEST_RLOG_CHECKSUM); -} - -TEST_CASE("FileReader") { - auto enable_local_cache = GENERATE(true, false); - std::string cache_file = cacheFilePath(TEST_RLOG_URL); - system(("rm " + cache_file + " -f").c_str()); - - FileReader reader(enable_local_cache); - std::string content = reader.read(TEST_RLOG_URL); - REQUIRE(sha256(content) == TEST_RLOG_CHECKSUM); - if (enable_local_cache) { - REQUIRE(sha256(util::read_file(cache_file)) == TEST_RLOG_CHECKSUM); - } else { - REQUIRE(util::file_exists(cache_file) == false); - } -} - -TEST_CASE("LogReader") { - SECTION("corrupt log") { - FileReader reader(true); - std::string corrupt_content = reader.read(TEST_RLOG_URL); - corrupt_content.resize(corrupt_content.length() / 2); - corrupt_content = decompressBZ2(corrupt_content); - LogReader log; - REQUIRE(log.load((std::byte *)corrupt_content.data(), corrupt_content.size())); - REQUIRE(log.events.size() > 0); - } -} - -void read_segment(int n, const SegmentFile &segment_file, uint32_t flags) { - QEventLoop loop; - Segment segment(n, segment_file, flags); - QObject::connect(&segment, &Segment::loadFinished, [&]() { - REQUIRE(segment.isLoaded() == true); - REQUIRE(segment.log != nullptr); - REQUIRE(segment.frames[RoadCam] != nullptr); - if (flags & REPLAY_FLAG_DCAM) { - REQUIRE(segment.frames[DriverCam] != nullptr); - } - if (flags & REPLAY_FLAG_ECAM) { - REQUIRE(segment.frames[WideRoadCam] != nullptr); - } - - // test LogReader & FrameReader - REQUIRE(segment.log->events.size() > 0); - REQUIRE(std::is_sorted(segment.log->events.begin(), segment.log->events.end(), Event::lessThan())); - - for (auto cam : ALL_CAMERAS) { - auto &fr = segment.frames[cam]; - if (!fr) continue; - - if (cam == RoadCam || cam == WideRoadCam) { - REQUIRE(fr->getFrameCount() == 1200); - } - auto [nv12_width, nv12_height, nv12_buffer_size] = get_nv12_info(fr->width, fr->height); - VisionBuf buf; - buf.allocate(nv12_buffer_size); - buf.init_yuv(fr->width, fr->height, nv12_width, nv12_width * nv12_height); - // sequence get 100 frames - for (int i = 0; i < 100; ++i) { - REQUIRE(fr->get(i, &buf)); - } - } - - loop.quit(); - }); - loop.exec(); -} - -std::string download_demo_route() { - static std::string data_dir; - - if (data_dir == "") { - char tmp_path[] = "/tmp/root_XXXXXX"; - data_dir = mkdtemp(tmp_path); - - Route remote_route(DEMO_ROUTE); - assert(remote_route.load()); - - // Create a local route from remote for testing - const std::string route_name = DEMO_ROUTE.mid(17).toStdString(); - for (int i = 0; i < 2; ++i) { - std::string log_path = util::string_format("%s/%s--%d/", data_dir.c_str(), route_name.c_str(), i); - util::create_directories(log_path, 0755); - REQUIRE(download_to_file(remote_route.at(i).rlog.toStdString(), log_path + "rlog.bz2")); - REQUIRE(download_to_file(remote_route.at(i).driver_cam.toStdString(), log_path + "dcamera.hevc")); - REQUIRE(download_to_file(remote_route.at(i).wide_road_cam.toStdString(), log_path + "ecamera.hevc")); - REQUIRE(download_to_file(remote_route.at(i).qcamera.toStdString(), log_path + "qcamera.ts")); - } - } - - return data_dir; -} - - -TEST_CASE("Local route") { - std::string data_dir = download_demo_route(); - - auto flags = GENERATE(REPLAY_FLAG_DCAM | REPLAY_FLAG_ECAM, REPLAY_FLAG_QCAMERA); - Route route(DEMO_ROUTE, QString::fromStdString(data_dir)); - REQUIRE(route.load()); - REQUIRE(route.segments().size() == 2); - for (int i = 0; i < route.segments().size(); ++i) { - read_segment(i, route.at(i), flags); - } -} - -TEST_CASE("Remote route") { - auto flags = GENERATE(REPLAY_FLAG_DCAM | REPLAY_FLAG_ECAM, REPLAY_FLAG_QCAMERA); - Route route(DEMO_ROUTE); - REQUIRE(route.load()); - REQUIRE(route.segments().size() == 13); - for (int i = 0; i < 2; ++i) { - read_segment(i, route.at(i), flags); - } -} - -// helper class for unit tests -class TestReplay : public Replay { - public: - TestReplay(const QString &route, uint32_t flags = REPLAY_FLAG_NO_FILE_CACHE | REPLAY_FLAG_NO_VIPC) : Replay(route, {}, {}, nullptr, flags) {} - void test_seek(); - void testSeekTo(int seek_to); -}; - -void TestReplay::testSeekTo(int seek_to) { - seekTo(seek_to, false); - - while (true) { - std::unique_lock lk(stream_lock_); - stream_cv_.wait(lk, [=]() { return events_updated_ == true; }); - events_updated_ = false; - if (cur_mono_time_ != route_start_ts_ + seek_to * 1e9) { - // wake up by the previous merging, skip it. - continue; - } - - Event cur_event(cereal::Event::Which::INIT_DATA, cur_mono_time_); - auto eit = std::upper_bound(events_->begin(), events_->end(), &cur_event, Event::lessThan()); - if (eit == events_->end()) { - qDebug() << "waiting for events..."; - continue; - } - - REQUIRE(std::is_sorted(events_->begin(), events_->end(), Event::lessThan())); - const int seek_to_segment = seek_to / 60; - const int event_seconds = ((*eit)->mono_time - route_start_ts_) / 1e9; - current_segment_ = event_seconds / 60; - INFO("seek to [" << seek_to << "s segment " << seek_to_segment << "], events [" << event_seconds << "s segment" << current_segment_ << "]"); - REQUIRE(event_seconds >= seek_to); - if (event_seconds > seek_to) { - auto it = segments_.lower_bound(seek_to_segment); - REQUIRE(it->first == current_segment_); - } - break; - } -} - -void TestReplay::test_seek() { - // create a dummy stream thread - stream_thread_ = new QThread(this); - QEventLoop loop; - std::thread thread = std::thread([&]() { - for (int i = 0; i < 10; ++i) { - testSeekTo(util::random_int(0, 2 * 60)); - } - loop.quit(); - }); - loop.exec(); - thread.join(); -} - -TEST_CASE("Replay") { - TestReplay replay(DEMO_ROUTE); - REQUIRE(replay.load()); - replay.test_seek(); -} diff --git a/tools/replay/tests/test_runner.cc b/tools/replay/tests/test_runner.cc deleted file mode 100644 index b20ac86..0000000 --- a/tools/replay/tests/test_runner.cc +++ /dev/null @@ -1,10 +0,0 @@ -#define CATCH_CONFIG_RUNNER -#include "catch2/catch.hpp" -#include - -int main(int argc, char **argv) { - // unit tests for Qt - QCoreApplication app(argc, argv); - const int res = Catch::Session().run(argc, argv); - return (res < 0xff ? res : 0xff); -} diff --git a/tools/replay/ui.py b/tools/replay/ui.py deleted file mode 100644 index 05e8bde..0000000 --- a/tools/replay/ui.py +++ /dev/null @@ -1,228 +0,0 @@ -#!/usr/bin/env python3 -import argparse -import os -import sys - -import cv2 -import numpy as np -import pygame - -import cereal.messaging as messaging -from openpilot.common.numpy_fast import clip -from openpilot.common.basedir import BASEDIR -from openpilot.tools.replay.lib.ui_helpers import (_BB_TO_FULL_FRAME, UP, - _INTRINSICS, BLACK, GREEN, - YELLOW, Calibration, - get_blank_lid_overlay, init_plots, - maybe_update_radar_points, plot_lead, - plot_model, - pygame_modules_have_loaded) -from cereal.visionipc import VisionIpcClient, VisionStreamType - -os.environ['BASEDIR'] = BASEDIR - -ANGLE_SCALE = 5.0 - -def ui_thread(addr): - cv2.setNumThreads(1) - pygame.init() - pygame.font.init() - assert pygame_modules_have_loaded() - - disp_info = pygame.display.Info() - max_height = disp_info.current_h - - hor_mode = os.getenv("HORIZONTAL") is not None - hor_mode = True if max_height < 960+300 else hor_mode - - if hor_mode: - size = (640+384+640, 960) - write_x = 5 - write_y = 680 - else: - size = (640+384, 960+300) - write_x = 645 - write_y = 970 - - pygame.display.set_caption("openpilot debug UI") - screen = pygame.display.set_mode(size, pygame.DOUBLEBUF) - - alert1_font = pygame.font.SysFont("arial", 30) - alert2_font = pygame.font.SysFont("arial", 20) - info_font = pygame.font.SysFont("arial", 15) - - camera_surface = pygame.surface.Surface((640, 480), 0, 24).convert() - top_down_surface = pygame.surface.Surface((UP.lidar_x, UP.lidar_y), 0, 8) - - sm = messaging.SubMaster(['carState', 'longitudinalPlan', 'carControl', 'radarState', 'liveCalibration', 'controlsState', - 'liveTracks', 'modelV2', 'liveParameters', 'lateralPlan'], addr=addr) - - img = np.zeros((480, 640, 3), dtype='uint8') - imgff = None - num_px = 0 - calibration = None - - lid_overlay_blank = get_blank_lid_overlay(UP) - - # plots - name_to_arr_idx = { "gas": 0, - "computer_gas": 1, - "user_brake": 2, - "computer_brake": 3, - "v_ego": 4, - "v_pid": 5, - "angle_steers_des": 6, - "angle_steers": 7, - "angle_steers_k": 8, - "steer_torque": 9, - "v_override": 10, - "v_cruise": 11, - "a_ego": 12, - "a_target": 13} - - plot_arr = np.zeros((100, len(name_to_arr_idx.values()))) - - plot_xlims = [(0, plot_arr.shape[0]), (0, plot_arr.shape[0]), (0, plot_arr.shape[0]), (0, plot_arr.shape[0])] - plot_ylims = [(-0.1, 1.1), (-ANGLE_SCALE, ANGLE_SCALE), (0., 75.), (-3.0, 2.0)] - plot_names = [["gas", "computer_gas", "user_brake", "computer_brake"], - ["angle_steers", "angle_steers_des", "angle_steers_k", "steer_torque"], - ["v_ego", "v_override", "v_pid", "v_cruise"], - ["a_ego", "a_target"]] - plot_colors = [["b", "b", "g", "r", "y"], - ["b", "g", "y", "r"], - ["b", "g", "r", "y"], - ["b", "r"]] - plot_styles = [["-", "-", "-", "-", "-"], - ["-", "-", "-", "-"], - ["-", "-", "-", "-"], - ["-", "-"]] - - draw_plots = init_plots(plot_arr, name_to_arr_idx, plot_xlims, plot_ylims, plot_names, plot_colors, plot_styles) - - vipc_client = VisionIpcClient("camerad", VisionStreamType.VISION_STREAM_ROAD, True) - while 1: - list(pygame.event.get()) - - screen.fill((64, 64, 64)) - lid_overlay = lid_overlay_blank.copy() - top_down = top_down_surface, lid_overlay - - # ***** frame ***** - if not vipc_client.is_connected(): - vipc_client.connect(True) - - yuv_img_raw = vipc_client.recv() - - if yuv_img_raw is None or not yuv_img_raw.data.any(): - continue - - imgff = np.frombuffer(yuv_img_raw.data, dtype=np.uint8).reshape((len(yuv_img_raw.data) // vipc_client.stride, vipc_client.stride)) - num_px = vipc_client.width * vipc_client.height - bgr = cv2.cvtColor(imgff[:vipc_client.height * 3 // 2, :vipc_client.width], cv2.COLOR_YUV2RGB_NV12) - - zoom_matrix = _BB_TO_FULL_FRAME[num_px] - cv2.warpAffine(bgr, zoom_matrix[:2], (img.shape[1], img.shape[0]), dst=img, flags=cv2.WARP_INVERSE_MAP) - - intrinsic_matrix = _INTRINSICS[num_px] - - sm.update(0) - - w = sm['controlsState'].lateralControlState.which() - if w == 'lqrStateDEPRECATED': - angle_steers_k = sm['controlsState'].lateralControlState.lqrStateDEPRECATED.steeringAngleDeg - elif w == 'indiState': - angle_steers_k = sm['controlsState'].lateralControlState.indiState.steeringAngleDeg - else: - angle_steers_k = np.inf - - plot_arr[:-1] = plot_arr[1:] - plot_arr[-1, name_to_arr_idx['angle_steers']] = sm['carState'].steeringAngleDeg - plot_arr[-1, name_to_arr_idx['angle_steers_des']] = sm['carControl'].actuators.steeringAngleDeg - plot_arr[-1, name_to_arr_idx['angle_steers_k']] = angle_steers_k - plot_arr[-1, name_to_arr_idx['gas']] = sm['carState'].gas - # TODO gas is deprecated - plot_arr[-1, name_to_arr_idx['computer_gas']] = clip(sm['carControl'].actuators.accel/4.0, 0.0, 1.0) - plot_arr[-1, name_to_arr_idx['user_brake']] = sm['carState'].brake - plot_arr[-1, name_to_arr_idx['steer_torque']] = sm['carControl'].actuators.steer * ANGLE_SCALE - # TODO brake is deprecated - plot_arr[-1, name_to_arr_idx['computer_brake']] = clip(-sm['carControl'].actuators.accel/4.0, 0.0, 1.0) - plot_arr[-1, name_to_arr_idx['v_ego']] = sm['carState'].vEgo - plot_arr[-1, name_to_arr_idx['v_pid']] = sm['controlsState'].vPid - plot_arr[-1, name_to_arr_idx['v_cruise']] = sm['carState'].cruiseState.speed - plot_arr[-1, name_to_arr_idx['a_ego']] = sm['carState'].aEgo - - if len(sm['longitudinalPlan'].accels): - plot_arr[-1, name_to_arr_idx['a_target']] = sm['longitudinalPlan'].accels[0] - - if sm.rcv_frame['modelV2']: - plot_model(sm['modelV2'], img, calibration, top_down) - - if sm.rcv_frame['radarState']: - plot_lead(sm['radarState'], top_down) - - # draw all radar points - maybe_update_radar_points(sm['liveTracks'], top_down[1]) - - if sm.updated['liveCalibration'] and num_px: - rpyCalib = np.asarray(sm['liveCalibration'].rpyCalib) - calibration = Calibration(num_px, rpyCalib, intrinsic_matrix) - - # *** blits *** - pygame.surfarray.blit_array(camera_surface, img.swapaxes(0, 1)) - screen.blit(camera_surface, (0, 0)) - - # display alerts - alert_line1 = alert1_font.render(sm['controlsState'].alertText1, True, (255, 0, 0)) - alert_line2 = alert2_font.render(sm['controlsState'].alertText2, True, (255, 0, 0)) - screen.blit(alert_line1, (180, 150)) - screen.blit(alert_line2, (180, 190)) - - if hor_mode: - screen.blit(draw_plots(plot_arr), (640+384, 0)) - else: - screen.blit(draw_plots(plot_arr), (0, 600)) - - pygame.surfarray.blit_array(*top_down) - screen.blit(top_down[0], (640, 0)) - - SPACING = 25 - - lines = [ - info_font.render("ENABLED", True, GREEN if sm['controlsState'].enabled else BLACK), - info_font.render("SPEED: " + str(round(sm['carState'].vEgo, 1)) + " m/s", True, YELLOW), - info_font.render("LONG CONTROL STATE: " + str(sm['controlsState'].longControlState), True, YELLOW), - info_font.render("LONG MPC SOURCE: " + str(sm['longitudinalPlan'].longitudinalPlanSource), True, YELLOW), - None, - info_font.render("ANGLE OFFSET (AVG): " + str(round(sm['liveParameters'].angleOffsetAverageDeg, 2)) + " deg", True, YELLOW), - info_font.render("ANGLE OFFSET (INSTANT): " + str(round(sm['liveParameters'].angleOffsetDeg, 2)) + " deg", True, YELLOW), - info_font.render("STIFFNESS: " + str(round(sm['liveParameters'].stiffnessFactor * 100., 2)) + " %", True, YELLOW), - info_font.render("STEER RATIO: " + str(round(sm['liveParameters'].steerRatio, 2)), True, YELLOW) - ] - - for i, line in enumerate(lines): - if line is not None: - screen.blit(line, (write_x, write_y + i * SPACING)) - - # this takes time...vsync or something - pygame.display.flip() - -def get_arg_parser(): - parser = argparse.ArgumentParser( - description="Show replay data in a UI.", - formatter_class=argparse.ArgumentDefaultsHelpFormatter) - - parser.add_argument("ip_address", nargs="?", default="127.0.0.1", - help="The ip address on which to receive zmq messages.") - - parser.add_argument("--frame-address", default=None, - help="The frame address (fully qualified ZMQ endpoint for frames) on which to receive zmq messages.") - return parser - -if __name__ == "__main__": - args = get_arg_parser().parse_args(sys.argv[1:]) - - if args.ip_address != "127.0.0.1": - os.environ["ZMQ"] = "1" - messaging.context = messaging.Context() - - ui_thread(args.ip_address) diff --git a/tools/replay/unlog_ci_segment.py b/tools/replay/unlog_ci_segment.py deleted file mode 100644 index ae97ad4..0000000 --- a/tools/replay/unlog_ci_segment.py +++ /dev/null @@ -1,108 +0,0 @@ -#!/usr/bin/env python3 - -import argparse -import bisect -import select -import sys -import termios -import time -import tty -from collections import defaultdict - -import cereal.messaging as messaging -from openpilot.tools.lib.framereader import FrameReader -from openpilot.tools.lib.logreader import LogReader -from openpilot.selfdrive.test.openpilotci import get_url - -IGNORE = ['initData', 'sentinel'] - - -def input_ready(): - return select.select([sys.stdin], [], [], 0) == ([sys.stdin], [], []) - - -def replay(route, segment, loop): - route = route.replace('|', '/') - - lr = LogReader(get_url(route, segment)) - fr = FrameReader(get_url(route, segment, "fcamera"), readahead=True) - - # Build mapping from frameId to segmentId from roadEncodeIdx, type == fullHEVC - msgs = [m for m in lr if m.which() not in IGNORE] - msgs = sorted(msgs, key=lambda m: m.logMonoTime) - times = [m.logMonoTime for m in msgs] - frame_idx = {m.roadEncodeIdx.frameId: m.roadEncodeIdx.segmentId for m in msgs if m.which() == 'roadEncodeIdx' and m.roadEncodeIdx.type == 'fullHEVC'} - - socks = {} - lag = 0.0 - i = 0 - max_i = len(msgs) - 2 - - while True: - msg = msgs[i].as_builder() - next_msg = msgs[i + 1] - - start_time = time.time() - w = msg.which() - - if w == 'roadCameraState': - try: - img = fr.get(frame_idx[msg.roadCameraState.frameId], pix_fmt="rgb24") - img = img[0][:, :, ::-1] # Convert RGB to BGR, which is what the camera outputs - msg.roadCameraState.image = img.flatten().tobytes() - except (KeyError, ValueError): - pass - - if w not in socks: - socks[w] = messaging.pub_sock(w) - - try: - if socks[w]: - socks[w].send(msg.to_bytes()) - except messaging.messaging_pyx.MultiplePublishersError: - socks[w] = None - - lag += (next_msg.logMonoTime - msg.logMonoTime) / 1e9 - lag -= time.time() - start_time - - dt = max(lag, 0.0) - lag -= dt - time.sleep(dt) - - if lag < -1.0 and i % 1000 == 0: - print(f"{-lag:.2f} s behind") - - if input_ready(): - key = sys.stdin.read(1) - - # Handle pause - if key == " ": - while True: - if input_ready() and sys.stdin.read(1) == " ": - break - time.sleep(0.01) - - # Handle seek - dt = defaultdict(int, s=10, S=-10)[key] - new_time = msgs[i].logMonoTime + dt * 1e9 - i = bisect.bisect_left(times, new_time) - - i = (i + 1) % max_i if loop else min(i + 1, max_i) - - -if __name__ == "__main__": - parser = argparse.ArgumentParser() - parser.add_argument("--loop", action='store_true') - parser.add_argument("route") - parser.add_argument("segment") - args = parser.parse_args() - - orig_settings = termios.tcgetattr(sys.stdin) - tty.setcbreak(sys.stdin) - - try: - replay(args.route, args.segment, args.loop) - termios.tcsetattr(sys.stdin, termios.TCSADRAIN, orig_settings) - except Exception: - termios.tcsetattr(sys.stdin, termios.TCSADRAIN, orig_settings) - raise diff --git a/tools/replay/util.cc b/tools/replay/util.cc deleted file mode 100644 index b4f72d0..0000000 --- a/tools/replay/util.cc +++ /dev/null @@ -1,331 +0,0 @@ -#include "tools/replay/util.h" - -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include "common/timing.h" -#include "common/util.h" - -ReplayMessageHandler message_handler = nullptr; -void installMessageHandler(ReplayMessageHandler handler) { message_handler = handler; } - -void logMessage(ReplyMsgType type, const char *fmt, ...) { - static std::mutex lock; - std::lock_guard lk(lock); - - char *msg_buf = nullptr; - va_list args; - va_start(args, fmt); - int ret = vasprintf(&msg_buf, fmt, args); - va_end(args); - if (ret <= 0 || !msg_buf) return; - - if (message_handler) { - message_handler(type, msg_buf); - } else { - if (type == ReplyMsgType::Debug) { - std::cout << "\033[38;5;248m" << msg_buf << "\033[00m" << std::endl; - } else if (type == ReplyMsgType::Warning) { - std::cout << "\033[38;5;227m" << msg_buf << "\033[00m" << std::endl; - } else if (type == ReplyMsgType::Critical) { - std::cout << "\033[38;5;196m" << msg_buf << "\033[00m" << std::endl; - } else { - std::cout << msg_buf << std::endl; - } - } - - free(msg_buf); -} - -namespace { - -struct CURLGlobalInitializer { - CURLGlobalInitializer() { curl_global_init(CURL_GLOBAL_DEFAULT); } - ~CURLGlobalInitializer() { curl_global_cleanup(); } -}; - -static CURLGlobalInitializer curl_initializer; - -template -struct MultiPartWriter { - T *buf; - size_t *total_written; - size_t offset; - size_t end; - - size_t write(char *data, size_t size, size_t count) { - size_t bytes = size * count; - if ((offset + bytes) > end) return 0; - - if constexpr (std::is_same::value) { - memcpy(buf->data() + offset, data, bytes); - } else if constexpr (std::is_same::value) { - buf->seekp(offset); - buf->write(data, bytes); - } - - offset += bytes; - *total_written += bytes; - return bytes; - } -}; - -template -size_t write_cb(char *data, size_t size, size_t count, void *userp) { - auto w = (MultiPartWriter *)userp; - return w->write(data, size, count); -} - -size_t dumy_write_cb(char *data, size_t size, size_t count, void *userp) { return size * count; } - -struct DownloadStats { - void installDownloadProgressHandler(DownloadProgressHandler handler) { - std::lock_guard lk(lock); - download_progress_handler = handler; - } - - void add(const std::string &url, uint64_t total_bytes) { - std::lock_guard lk(lock); - items[url] = {0, total_bytes}; - } - - void remove(const std::string &url) { - std::lock_guard lk(lock); - items.erase(url); - } - - void update(const std::string &url, uint64_t downloaded, bool success = true) { - std::lock_guard lk(lock); - items[url].first = downloaded; - - auto stat = std::accumulate(items.begin(), items.end(), std::pair{}, [=](auto &a, auto &b){ - return std::pair{a.first + b.second.first, a.second + b.second.second}; - }); - double tm = millis_since_boot(); - if (download_progress_handler && ((tm - prev_tm) > 500 || !success || stat.first >= stat.second)) { - download_progress_handler(stat.first, stat.second, success); - prev_tm = tm; - } - } - - std::mutex lock; - std::map> items; - double prev_tm = 0; - DownloadProgressHandler download_progress_handler = nullptr; -}; - -static DownloadStats download_stats; - -} // namespace - -void installDownloadProgressHandler(DownloadProgressHandler handler) { - download_stats.installDownloadProgressHandler(handler); -} - -std::string formattedDataSize(size_t size) { - if (size < 1024) { - return std::to_string(size) + " B"; - } else if (size < 1024 * 1024) { - return util::string_format("%.2f KB", (float)size / 1024); - } else { - return util::string_format("%.2f MB", (float)size / (1024 * 1024)); - } -} - -size_t getRemoteFileSize(const std::string &url, std::atomic *abort) { - CURL *curl = curl_easy_init(); - if (!curl) return -1; - - curl_easy_setopt(curl, CURLOPT_URL, url.c_str()); - curl_easy_setopt(curl, CURLOPT_WRITEFUNCTION, dumy_write_cb); - curl_easy_setopt(curl, CURLOPT_HEADER, 1); - curl_easy_setopt(curl, CURLOPT_NOBODY, 1); - - CURLM *cm = curl_multi_init(); - curl_multi_add_handle(cm, curl); - int still_running = 1; - while (still_running > 0 && !(abort && *abort)) { - CURLMcode mc = curl_multi_perform(cm, &still_running); - if (!mc) curl_multi_wait(cm, nullptr, 0, 1000, nullptr); - } - - double content_length = -1; - curl_easy_getinfo(curl, CURLINFO_CONTENT_LENGTH_DOWNLOAD, &content_length); - curl_multi_remove_handle(cm, curl); - curl_easy_cleanup(curl); - curl_multi_cleanup(cm); - return content_length > 0 ? (size_t)content_length : 0; -} - -std::string getUrlWithoutQuery(const std::string &url) { - size_t idx = url.find("?"); - return (idx == std::string::npos ? url : url.substr(0, idx)); -} - -template -bool httpDownload(const std::string &url, T &buf, size_t chunk_size, size_t content_length, std::atomic *abort) { - download_stats.add(url, content_length); - - int parts = 1; - if (chunk_size > 0 && content_length > 10 * 1024 * 1024) { - parts = std::nearbyint(content_length / (float)chunk_size); - parts = std::clamp(parts, 1, 5); - } - - CURLM *cm = curl_multi_init(); - size_t written = 0; - std::map> writers; - const int part_size = content_length / parts; - for (int i = 0; i < parts; ++i) { - CURL *eh = curl_easy_init(); - writers[eh] = { - .buf = &buf, - .total_written = &written, - .offset = (size_t)(i * part_size), - .end = i == parts - 1 ? content_length : (i + 1) * part_size, - }; - curl_easy_setopt(eh, CURLOPT_WRITEFUNCTION, write_cb); - curl_easy_setopt(eh, CURLOPT_WRITEDATA, (void *)(&writers[eh])); - curl_easy_setopt(eh, CURLOPT_URL, url.c_str()); - curl_easy_setopt(eh, CURLOPT_RANGE, util::string_format("%d-%d", writers[eh].offset, writers[eh].end - 1).c_str()); - curl_easy_setopt(eh, CURLOPT_HTTPGET, 1); - curl_easy_setopt(eh, CURLOPT_NOSIGNAL, 1); - curl_easy_setopt(eh, CURLOPT_FOLLOWLOCATION, 1); - - curl_multi_add_handle(cm, eh); - } - - int still_running = 1; - while (still_running > 0 && !(abort && *abort)) { - curl_multi_wait(cm, nullptr, 0, 1000, nullptr); - curl_multi_perform(cm, &still_running); - download_stats.update(url, written); - } - - CURLMsg *msg; - int msgs_left = -1; - int complete = 0; - while ((msg = curl_multi_info_read(cm, &msgs_left)) && !(abort && *abort)) { - if (msg->msg == CURLMSG_DONE) { - if (msg->data.result == CURLE_OK) { - long res_status = 0; - curl_easy_getinfo(msg->easy_handle, CURLINFO_RESPONSE_CODE, &res_status); - if (res_status == 206) { - complete++; - } else { - rWarning("Download failed: http error code: %d", res_status); - } - } else { - rWarning("Download failed: connection failure: %d", msg->data.result); - } - } - } - - bool success = complete == parts; - download_stats.update(url, written, success); - download_stats.remove(url); - - for (const auto &[e, w] : writers) { - curl_multi_remove_handle(cm, e); - curl_easy_cleanup(e); - } - curl_multi_cleanup(cm); - - return success; -} - -std::string httpGet(const std::string &url, size_t chunk_size, std::atomic *abort) { - size_t size = getRemoteFileSize(url, abort); - if (size == 0) return {}; - - std::string result(size, '\0'); - return httpDownload(url, result, chunk_size, size, abort) ? result : ""; -} - -bool httpDownload(const std::string &url, const std::string &file, size_t chunk_size, std::atomic *abort) { - size_t size = getRemoteFileSize(url, abort); - if (size == 0) return false; - - std::ofstream of(file, std::ios::binary | std::ios::out); - of.seekp(size - 1).write("\0", 1); - return httpDownload(url, of, chunk_size, size, abort); -} - -std::string decompressBZ2(const std::string &in, std::atomic *abort) { - return decompressBZ2((std::byte *)in.data(), in.size(), abort); -} - -std::string decompressBZ2(const std::byte *in, size_t in_size, std::atomic *abort) { - if (in_size == 0) return {}; - - bz_stream strm = {}; - int bzerror = BZ2_bzDecompressInit(&strm, 0, 0); - assert(bzerror == BZ_OK); - - strm.next_in = (char *)in; - strm.avail_in = in_size; - std::string out(in_size * 5, '\0'); - do { - strm.next_out = (char *)(&out[strm.total_out_lo32]); - strm.avail_out = out.size() - strm.total_out_lo32; - - const char *prev_write_pos = strm.next_out; - bzerror = BZ2_bzDecompress(&strm); - if (bzerror == BZ_OK && prev_write_pos == strm.next_out) { - // content is corrupt - bzerror = BZ_STREAM_END; - rWarning("decompressBZ2 error : content is corrupt"); - break; - } - - if (bzerror == BZ_OK && strm.avail_in > 0 && strm.avail_out == 0) { - out.resize(out.size() * 2); - } - } while (bzerror == BZ_OK && !(abort && *abort)); - - BZ2_bzDecompressEnd(&strm); - if (bzerror == BZ_STREAM_END && !(abort && *abort)) { - out.resize(strm.total_out_lo32); - return out; - } - return {}; -} - -void precise_nano_sleep(long sleep_ns) { - const long estimate_ns = 1 * 1e6; // 1ms - struct timespec req = {.tv_nsec = estimate_ns}; - uint64_t start_sleep = nanos_since_boot(); - while (sleep_ns > estimate_ns) { - nanosleep(&req, nullptr); - uint64_t end_sleep = nanos_since_boot(); - sleep_ns -= (end_sleep - start_sleep); - start_sleep = end_sleep; - } - // spin wait - if (sleep_ns > 0) { - while ((nanos_since_boot() - start_sleep) <= sleep_ns) { - std::this_thread::yield(); - } - } -} - -std::string sha256(const std::string &str) { - unsigned char hash[SHA256_DIGEST_LENGTH]; - SHA256_CTX sha256; - SHA256_Init(&sha256); - SHA256_Update(&sha256, str.c_str(), str.size()); - SHA256_Final(hash, &sha256); - return util::hexdump(hash, SHA256_DIGEST_LENGTH); -} diff --git a/tools/replay/util.h b/tools/replay/util.h deleted file mode 100644 index 6c80809..0000000 --- a/tools/replay/util.h +++ /dev/null @@ -1,34 +0,0 @@ -#pragma once - -#include -#include -#include - -enum class ReplyMsgType { - Info, - Debug, - Warning, - Critical -}; - -typedef std::function ReplayMessageHandler; -void installMessageHandler(ReplayMessageHandler); -void logMessage(ReplyMsgType type, const char* fmt, ...); - -#define rInfo(fmt, ...) ::logMessage(ReplyMsgType::Info, fmt, ## __VA_ARGS__) -#define rDebug(fmt, ...) ::logMessage(ReplyMsgType::Debug, fmt, ## __VA_ARGS__) -#define rWarning(fmt, ...) ::logMessage(ReplyMsgType::Warning, fmt, ## __VA_ARGS__) -#define rError(fmt, ...) ::logMessage(ReplyMsgType::Critical , fmt, ## __VA_ARGS__) - -std::string sha256(const std::string &str); -void precise_nano_sleep(long sleep_ns); -std::string decompressBZ2(const std::string &in, std::atomic *abort = nullptr); -std::string decompressBZ2(const std::byte *in, size_t in_size, std::atomic *abort = nullptr); -std::string getUrlWithoutQuery(const std::string &url); -size_t getRemoteFileSize(const std::string &url, std::atomic *abort = nullptr); -std::string httpGet(const std::string &url, size_t chunk_size = 0, std::atomic *abort = nullptr); - -typedef std::function DownloadProgressHandler; -void installDownloadProgressHandler(DownloadProgressHandler); -bool httpDownload(const std::string &url, const std::string &file, size_t chunk_size = 0, std::atomic *abort = nullptr); -std::string formattedDataSize(size_t size); diff --git a/tools/scripts/fetch_image_from_route.py b/tools/scripts/fetch_image_from_route.py deleted file mode 100644 index b59e7c8..0000000 --- a/tools/scripts/fetch_image_from_route.py +++ /dev/null @@ -1,43 +0,0 @@ -#!/usr/bin/env python3 -import sys - -if len(sys.argv) < 4: - print(f"{sys.argv[0]} [front|wide|driver]") - print('example: ./fetch_image_from_route.py "02c45f73a2e5c6e9|2020-06-01--18-03-08" 3 500 driver') - exit(0) - -cameras = { - "front": "cameras", - "wide": "ecameras", - "driver": "dcameras" -} - -import requests -from PIL import Image -from openpilot.tools.lib.auth_config import get_token -from openpilot.tools.lib.framereader import FrameReader - -jwt = get_token() - -route = sys.argv[1] -segment = int(sys.argv[2]) -frame = int(sys.argv[3]) -camera = cameras[sys.argv[4]] if len(sys.argv) > 4 and sys.argv[4] in cameras else "cameras" - -url = f'https://api.commadotai.com/v1/route/{route}/files' -r = requests.get(url, headers={"Authorization": f"JWT {jwt}"}, timeout=10) -assert r.status_code == 200 -print("got api response") - -segments = r.json()[camera] -if segment >= len(segments): - raise Exception("segment %d not found, got %d segments" % (segment, len(segments))) - -fr = FrameReader(segments[segment]) -if frame >= fr.frame_count: - raise Exception("frame %d not found, got %d frames" % (frame, fr.frame_count)) - -im = Image.fromarray(fr.get(frame, count=1, pix_fmt="rgb24")[0]) -fn = f"uxxx_{route.replace('|', '_')}_{segment}_{frame}.png" -im.save(fn) -print(f"saved {fn}") diff --git a/tools/scripts/save_ubloxraw_stream.py b/tools/scripts/save_ubloxraw_stream.py deleted file mode 100644 index 541252d..0000000 --- a/tools/scripts/save_ubloxraw_stream.py +++ /dev/null @@ -1,59 +0,0 @@ -#!/usr/bin/env python -import argparse -import os -import sys -from openpilot.common.basedir import BASEDIR -from openpilot.tools.lib.logreader import MultiLogIterator -from openpilot.tools.lib.route import Route - -os.environ['BASEDIR'] = BASEDIR - - -def get_arg_parser(): - parser = argparse.ArgumentParser( - description="Unlogging and save to file", - formatter_class=argparse.ArgumentDefaultsHelpFormatter) - - parser.add_argument("data_dir", nargs='?', - help="Path to directory in which log and camera files are located.") - parser.add_argument("route_name", type=(lambda x: x.replace("#", "|")), nargs="?", - help="The route whose messages will be published.") - parser.add_argument("--out_path", nargs='?', default='/data/ubloxRaw.stream', - help="Output pickle file path") - return parser - - -def main(argv): - args = get_arg_parser().parse_args(sys.argv[1:]) - if not args.data_dir: - print('Data directory invalid.') - return - - if not args.route_name: - # Extract route name from path - args.route_name = os.path.basename(args.data_dir) - args.data_dir = os.path.dirname(args.data_dir) - - route = Route(args.route_name, args.data_dir) - lr = MultiLogIterator(route.log_paths()) - - with open(args.out_path, 'wb') as f: - try: - done = False - i = 0 - while not done: - msg = next(lr) - if not msg: - break - smsg = msg.as_builder() - typ = smsg.which() - if typ == 'ubloxRaw': - f.write(smsg.to_bytes()) - i += 1 - except StopIteration: - print('All done') - print(f'Writed {i} msgs') - - -if __name__ == "__main__": - sys.exit(main(sys.argv[1:])) diff --git a/tools/scripts/setup_ssh_keys.py b/tools/scripts/setup_ssh_keys.py deleted file mode 100644 index 699765e..0000000 --- a/tools/scripts/setup_ssh_keys.py +++ /dev/null @@ -1,23 +0,0 @@ -#!/usr/bin/env python3 - -import requests -from openpilot.common.params import Params -import sys - - -if __name__ == "__main__": - if len(sys.argv) < 2: - print(f"{sys.argv[0]} ") - exit(1) - - username = sys.argv[1] - keys = requests.get(f"https://github.com/{username}.keys", timeout=10) - - if keys.status_code == 200: - params = Params() - params.put_bool("SshEnabled", True) - params.put("GithubSshKeys", keys.text) - params.put("GithubUsername", username) - print("Setup ssh keys successfully") - else: - print("Error getting public keys from github") diff --git a/tools/serial/README.md b/tools/serial/README.md deleted file mode 100644 index 6a2950a..0000000 --- a/tools/serial/README.md +++ /dev/null @@ -1,21 +0,0 @@ -# comma serial - -The comma serial gets you access to a low level serial console on your comma three, while providing a stable 12V to power the device. - -The serial is available on the [comma shop](https://comma.ai/shop/products/comma-serial). - -## setup - -* Connect all three cables to the serial -* Connect the USB A to your computer -* Connect the USB-C to the OBD-C port on your comma three - -## usage - -``` -sudo screen /dev/ttyUSB0 115200 -``` -or use `connect.sh` to run the previous command in a loop. - - -The username and password are both `comma`. diff --git a/tools/serial/connect.sh b/tools/serial/connect.sh deleted file mode 100644 index a073310..0000000 --- a/tools/serial/connect.sh +++ /dev/null @@ -1,8 +0,0 @@ -#!/bin/bash - -while true; do - if ls /dev/serial/by-id/usb-FTDI_FT230X* 2> /dev/null; then - sudo screen /dev/serial/by-id/usb-FTDI_FT230X* 115200 - fi - sleep 0.005 -done diff --git a/tools/sim/Dockerfile.sim b/tools/sim/Dockerfile.sim deleted file mode 100644 index a183002..0000000 --- a/tools/sim/Dockerfile.sim +++ /dev/null @@ -1,37 +0,0 @@ -FROM ghcr.io/commaai/openpilot-base-cl:latest - -RUN apt-get update && apt-get install -y --no-install-recommends \ - tmux \ - vim \ - && rm -rf /var/lib/apt/lists/* - -# get same tmux config used on NEOS for debugging -RUN cd $HOME && \ - curl -O https://raw.githubusercontent.com/commaai/eon-neos-builder/master/devices/eon/home/.tmux.conf - -ENV OPENPILOT_PATH /tmp/openpilot -ENV PYTHONPATH ${OPENPILOT_PATH}:${PYTHONPATH} - -RUN mkdir -p ${OPENPILOT_PATH} -WORKDIR ${OPENPILOT_PATH} - -COPY SConstruct ${OPENPILOT_PATH} - -COPY ./openpilot ${OPENPILOT_PATH}/openpilot -COPY ./body ${OPENPILOT_PATH}/body -COPY ./third_party ${OPENPILOT_PATH}/third_party -COPY ./site_scons ${OPENPILOT_PATH}/site_scons -COPY ./rednose ${OPENPILOT_PATH}/rednose -COPY ./rednose_repo/site_scons ${OPENPILOT_PATH}/rednose_repo/site_scons -COPY ./common ${OPENPILOT_PATH}/common -COPY ./opendbc ${OPENPILOT_PATH}/opendbc -COPY ./cereal ${OPENPILOT_PATH}/cereal -COPY ./panda ${OPENPILOT_PATH}/panda -COPY ./selfdrive ${OPENPILOT_PATH}/selfdrive -COPY ./system ${OPENPILOT_PATH}/system -COPY ./tools ${OPENPILOT_PATH}/tools -COPY ./release ${OPENPILOT_PATH}/release - -RUN --mount=type=bind,source=.ci_cache/scons_cache,target=/tmp/scons_cache,rw scons -j$(nproc) --cache-readonly - -RUN python -c "from openpilot.selfdrive.test.helpers import set_params_enabled; set_params_enabled()" diff --git a/tools/sim/Dockerfile.sim_nvidia b/tools/sim/Dockerfile.sim_nvidia deleted file mode 100644 index 5e5dd26..0000000 --- a/tools/sim/Dockerfile.sim_nvidia +++ /dev/null @@ -1,21 +0,0 @@ -FROM ubuntu:20.04 - -ENV DEBIAN_FRONTEND=noninteractive -RUN apt-get update && \ - apt-get install -y --no-install-recommends \ - apt-utils \ - sudo \ - ssh \ - curl \ - ca-certificates \ - git \ - git-lfs && \ - rm -rf /var/lib/apt/lists/* - -RUN curl -fsSL https://get.docker.com -o get-docker.sh && \ - sudo sh get-docker.sh && \ - distribution=$(. /etc/os-release;echo $ID$VERSION_ID) && \ - curl -s -L https://nvidia.github.io/nvidia-docker/gpgkey | sudo apt-key add - && \ - curl -s -L https://nvidia.github.io/nvidia-docker/$distribution/nvidia-docker.list | sudo tee /etc/apt/sources.list.d/nvidia-docker.list && \ - sudo apt-get update && \ - sudo apt-get install -y nvidia-docker2 diff --git a/tools/sim/README.md b/tools/sim/README.md deleted file mode 100644 index 0892e77..0000000 --- a/tools/sim/README.md +++ /dev/null @@ -1,84 +0,0 @@ -openpilot in simulator -===================== - -openpilot implements a [bridge](run_bridge.py) that allows it to run in the [MetaDrive simulator](https://github.com/metadriverse/metadrive) or [CARLA simulator](https://carla.org/). - -## Launching openpilot -First, start openpilot. -``` bash -# Run locally -./tools/sim/launch_openpilot.sh -``` - -## Bridge usage -``` -$ ./run_bridge.py -h -usage: run_bridge.py [-h] [--joystick] [--high_quality] [--dual_camera] [--simulator SIMULATOR] [--town TOWN] [--spawn_point NUM_SELECTED_SPAWN_POINT] [--host HOST] [--port PORT] - -Bridge between the simulator and openpilot. - -options: - -h, --help show this help message and exit - --joystick - --high_quality - --dual_camera - --simulator SIMULATOR - --town TOWN - --spawn_point NUM_SELECTED_SPAWN_POINT - --host HOST - --port PORT -``` - -#### Bridge Controls: -- To engage openpilot press 2, then press 1 to increase the speed and 2 to decrease. -- To disengage, press "S" (simulates a user brake) - -#### All inputs: - -``` -| key | functionality | -|------|-----------------------| -| 1 | Cruise Resume / Accel | -| 2 | Cruise Set / Decel | -| 3 | Cruise Cancel | -| r | Reset Simulation | -| i | Toggle Ignition | -| q | Exit all | -| wasd | Control manually | -``` - -## MetaDrive - -### Launching Metadrive -Start bridge processes located in tools/sim: -``` bash -./run_bridge.py --simulator metadrive -``` - -## Carla - -CARLA is also partially supported, though the performance is not great. It needs to be manually installed with: - -```bash -poetry install --with=carla -``` - -openpilot doesn't have any extreme hardware requirements, however CARLA requires an NVIDIA graphics card and is very resource-intensive and may not run smoothly on your system. -For this case, we have the simulator in low quality by default. - -You can also check out the [CARLA python documentation](https://carla.readthedocs.io/en/latest/python_api/) to find more parameters to tune that might increase performance on your system. - -### Launching Carla -Start Carla simulator and bridge processes located in tools/sim: -``` bash -# Terminal 1 -./start_carla.sh - -# Terminal 2 -./run_bridge.py --simulator carla -``` - -## Further Reading - -The following resources contain more details and troubleshooting tips. -* [CARLA on the openpilot wiki](https://github.com/commaai/openpilot/wiki/CARLA) diff --git a/tools/sim/__init__.py b/tools/sim/__init__.py deleted file mode 100644 index e69de29..0000000 diff --git a/tools/sim/bridge/__init__.py b/tools/sim/bridge/__init__.py deleted file mode 100644 index e69de29..0000000 diff --git a/tools/sim/bridge/carla/carla_bridge.py b/tools/sim/bridge/carla/carla_bridge.py deleted file mode 100644 index dc2377d..0000000 --- a/tools/sim/bridge/carla/carla_bridge.py +++ /dev/null @@ -1,22 +0,0 @@ -from openpilot.tools.sim.bridge.common import SimulatorBridge -from openpilot.tools.sim.bridge.carla.carla_world import CarlaWorld - - -class CarlaBridge(SimulatorBridge): - TICKS_PER_FRAME = 5 - - def __init__(self, arguments): - super().__init__(arguments) - self.host = arguments.host - self.port = arguments.port - self.town = arguments.town - self.num_selected_spawn_point = arguments.num_selected_spawn_point - - def spawn_world(self): - import carla - - client = carla.Client(self.host, self.port) - client.set_timeout(5) - - return CarlaWorld(client, high_quality=self.high_quality, dual_camera=self.dual_camera, - num_selected_spawn_point=self.num_selected_spawn_point, town=self.town) \ No newline at end of file diff --git a/tools/sim/bridge/carla/carla_world.py b/tools/sim/bridge/carla/carla_world.py deleted file mode 100644 index 14b300e..0000000 --- a/tools/sim/bridge/carla/carla_world.py +++ /dev/null @@ -1,145 +0,0 @@ -import numpy as np - -from openpilot.common.params import Params -from openpilot.tools.sim.lib.common import SimulatorState, vec3 -from openpilot.tools.sim.bridge.common import World -from openpilot.tools.sim.lib.camerad import W, H - - -class CarlaWorld(World): - def __init__(self, client, high_quality, dual_camera, num_selected_spawn_point, town): - super().__init__(dual_camera) - import carla - - low_quality_layers = carla.MapLayer(carla.MapLayer.Ground | carla.MapLayer.Walls | carla.MapLayer.Decals) - - layers = carla.MapLayer.All if high_quality else low_quality_layers - - world = client.load_world(town, map_layers=layers) - - settings = world.get_settings() - settings.fixed_delta_seconds = 0.01 - world.apply_settings(settings) - - world.set_weather(carla.WeatherParameters.ClearSunset) - - self.world = world - world_map = world.get_map() - - blueprint_library = world.get_blueprint_library() - - vehicle_bp = blueprint_library.filter('vehicle.tesla.*')[1] - vehicle_bp.set_attribute('role_name', 'hero') - spawn_points = world_map.get_spawn_points() - assert len(spawn_points) > num_selected_spawn_point, \ - f'''No spawn point {num_selected_spawn_point}, try a value between 0 and {len(spawn_points)} for this town.''' - self.spawn_point = spawn_points[num_selected_spawn_point] - self.vehicle = world.spawn_actor(vehicle_bp, self.spawn_point) - - physics_control = self.vehicle.get_physics_control() - physics_control.mass = 2326 - physics_control.torque_curve = [[20.0, 500.0], [5000.0, 500.0]] - physics_control.gear_switch_time = 0.0 - self.vehicle.apply_physics_control(physics_control) - - self.vc: carla.VehicleControl = carla.VehicleControl(throttle=0, steer=0, brake=0, reverse=False) - self.max_steer_angle: float = self.vehicle.get_physics_control().wheels[0].max_steer_angle - self.params = Params() - - self.steer_ratio = 15 - - self.carla_objects = [] - - transform = carla.Transform(carla.Location(x=0.8, z=1.13)) - - def create_camera(fov, callback): - blueprint = blueprint_library.find('sensor.camera.rgb') - blueprint.set_attribute('image_size_x', str(W)) - blueprint.set_attribute('image_size_y', str(H)) - blueprint.set_attribute('fov', str(fov)) - blueprint.set_attribute('sensor_tick', str(1/20)) - if not high_quality: - blueprint.set_attribute('enable_postprocess_effects', 'False') - camera = world.spawn_actor(blueprint, transform, attach_to=self.vehicle) - camera.listen(callback) - return camera - - self.road_camera = create_camera(fov=40, callback=self.cam_callback_road) - if dual_camera: - self.road_wide_camera = create_camera(fov=120, callback=self.cam_callback_wide_road) # fov bigger than 120 shows unwanted artifacts - else: - self.road_wide_camera = None - - # re-enable IMU - imu_bp = blueprint_library.find('sensor.other.imu') - imu_bp.set_attribute('sensor_tick', '0.01') - self.imu = world.spawn_actor(imu_bp, transform, attach_to=self.vehicle) - - gps_bp = blueprint_library.find('sensor.other.gnss') - self.gps = world.spawn_actor(gps_bp, transform, attach_to=self.vehicle) - self.params.put_bool("UbloxAvailable", True) - - self.carla_objects = [self.imu, self.gps, self.road_camera, self.road_wide_camera, self.vehicle] - - def close(self): - for s in self.carla_objects: - if s is not None: - try: - s.destroy() - except Exception as e: - print("Failed to destroy carla object", e) - - def carla_image_to_rgb(self, image): - rgb = np.frombuffer(image.raw_data, dtype=np.dtype("uint8")) - rgb = np.reshape(rgb, (H, W, 4)) - return np.ascontiguousarray(rgb[:, :, [0, 1, 2]]) - - def cam_callback_road(self, image): - with self.image_lock: - self.road_image = self.carla_image_to_rgb(image) - - def cam_callback_wide_road(self, image): - with self.image_lock: - self.wide_road_image = self.carla_image_to_rgb(image) - - def apply_controls(self, steer_angle, throttle_out, brake_out): - self.vc.throttle = throttle_out - - steer_carla = steer_angle * -1 / (self.max_steer_angle * self.steer_ratio) - steer_carla = np.clip(steer_carla, -1, 1) - - self.vc.steer = steer_carla - self.vc.brake = brake_out - self.vehicle.apply_control(self.vc) - - def read_sensors(self, simulator_state: SimulatorState): - simulator_state.imu.bearing = self.imu.get_transform().rotation.yaw - - simulator_state.imu.accelerometer = vec3( - self.imu.get_acceleration().x, - self.imu.get_acceleration().y, - self.imu.get_acceleration().z - ) - - simulator_state.imu.gyroscope = vec3( - self.imu.get_angular_velocity().x, - self.imu.get_angular_velocity().y, - self.imu.get_angular_velocity().z - ) - - simulator_state.gps.from_xy([self.vehicle.get_location().x, self.vehicle.get_location().y]) - - simulator_state.velocity = self.vehicle.get_velocity() - simulator_state.valid = True - simulator_state.steering_angle = self.vc.steer * self.max_steer_angle - - def read_cameras(self): - pass # cameras are read within a callback for carla - - def tick(self): - self.world.tick() - - def reset(self): - import carla - self.vehicle.set_transform(self.spawn_point) - self.vehicle.set_target_velocity(carla.Vector3D()) diff --git a/tools/sim/bridge/common.py b/tools/sim/bridge/common.py deleted file mode 100644 index a0e6538..0000000 --- a/tools/sim/bridge/common.py +++ /dev/null @@ -1,186 +0,0 @@ -import signal -import threading -import functools - -from multiprocessing import Process, Queue -from abc import ABC, abstractmethod -from typing import Optional - -from openpilot.common.params import Params -from openpilot.common.numpy_fast import clip -from openpilot.common.realtime import Ratekeeper -from openpilot.selfdrive.test.helpers import set_params_enabled -from openpilot.selfdrive.car.honda.values import CruiseButtons -from openpilot.tools.sim.lib.common import SimulatorState, World -from openpilot.tools.sim.lib.simulated_car import SimulatedCar -from openpilot.tools.sim.lib.simulated_sensors import SimulatedSensors -from openpilot.tools.sim.lib.keyboard_ctrl import KEYBOARD_HELP - - -def rk_loop(function, hz, exit_event: threading.Event): - rk = Ratekeeper(hz, None) - while not exit_event.is_set(): - function() - rk.keep_time() - - -class SimulatorBridge(ABC): - TICKS_PER_FRAME = 5 - - def __init__(self, arguments): - set_params_enabled() - self.params = Params() - - self.rk = Ratekeeper(100, None) - - self.dual_camera = arguments.dual_camera - self.high_quality = arguments.high_quality - - self._exit_event = threading.Event() - self._threads = [] - self._keep_alive = True - self.started = False - signal.signal(signal.SIGTERM, self._on_shutdown) - self._exit = threading.Event() - self.simulator_state = SimulatorState() - - self.world: Optional[World] = None - - self.past_startup_engaged = False - - def _on_shutdown(self, signal, frame): - self.shutdown() - - def shutdown(self): - self._keep_alive = False - - def bridge_keep_alive(self, q: Queue, retries: int): - try: - self._run(q) - finally: - self.close() - - def close(self): - self.started = False - self._exit_event.set() - - if self.world is not None: - self.world.close() - - def run(self, queue, retries=-1): - bridge_p = Process(name="bridge", target=self.bridge_keep_alive, args=(queue, retries)) - bridge_p.start() - return bridge_p - - def print_status(self): - print( - f""" -Keyboard Commands: -{KEYBOARD_HELP} - -State: -Ignition: {self.simulator_state.ignition} Engaged: {self.simulator_state.is_engaged} - """) - - @abstractmethod - def spawn_world(self) -> World: - pass - - def _run(self, q: Queue): - self.world = self.spawn_world() - - self.simulated_car = SimulatedCar() - self.simulated_sensors = SimulatedSensors(self.dual_camera) - - self.simulated_car_thread = threading.Thread(target=rk_loop, args=(functools.partial(self.simulated_car.update, self.simulator_state), - 100, self._exit_event)) - self.simulated_car_thread.start() - - self.simulated_camera_thread = threading.Thread(target=rk_loop, args=(functools.partial(self.simulated_sensors.send_camera_images, self.world), - 20, self._exit_event)) - self.simulated_camera_thread.start() - - # Simulation tends to be slow in the initial steps. This prevents lagging later - for _ in range(20): - self.world.tick() - - while self._keep_alive: - throttle_out = steer_out = brake_out = 0.0 - throttle_op = steer_op = brake_op = 0.0 - - self.simulator_state.cruise_button = 0 - self.simulator_state.left_blinker = False - self.simulator_state.right_blinker = False - - throttle_manual = steer_manual = brake_manual = 0. - - # Read manual controls - if not q.empty(): - message = q.get() - m = message.split('_') - if m[0] == "steer": - steer_manual = float(m[1]) - elif m[0] == "throttle": - throttle_manual = float(m[1]) - elif m[0] == "brake": - brake_manual = float(m[1]) - elif m[0] == "cruise": - if m[1] == "down": - self.simulator_state.cruise_button = CruiseButtons.DECEL_SET - elif m[1] == "up": - self.simulator_state.cruise_button = CruiseButtons.RES_ACCEL - elif m[1] == "cancel": - self.simulator_state.cruise_button = CruiseButtons.CANCEL - elif m[1] == "main": - self.simulator_state.cruise_button = CruiseButtons.MAIN - elif m[0] == "blinker": - if m[1] == "left": - self.simulator_state.left_blinker = True - elif m[1] == "right": - self.simulator_state.right_blinker = True - elif m[0] == "ignition": - self.simulator_state.ignition = not self.simulator_state.ignition - elif m[0] == "reset": - self.world.reset() - elif m[0] == "quit": - break - - self.simulator_state.user_brake = brake_manual - self.simulator_state.user_gas = throttle_manual - self.simulator_state.user_torque = steer_manual * 10000 - - steer_manual = steer_manual * -40 - - # Update openpilot on current sensor state - self.simulated_sensors.update(self.simulator_state, self.world) - - self.simulated_car.sm.update(0) - controlsState = self.simulated_car.sm['controlsState'] - self.simulator_state.is_engaged = controlsState.active - - if self.simulator_state.is_engaged: - throttle_op = clip(self.simulated_car.sm['carControl'].actuators.accel / 1.6, 0.0, 1.0) - brake_op = clip(-self.simulated_car.sm['carControl'].actuators.accel / 4.0, 0.0, 1.0) - steer_op = self.simulated_car.sm['carControl'].actuators.steeringAngleDeg - - self.past_startup_engaged = True - elif not self.past_startup_engaged and controlsState.engageable: - self.simulator_state.cruise_button = CruiseButtons.DECEL_SET # force engagement on startup - - throttle_out = throttle_op if self.simulator_state.is_engaged else throttle_manual - brake_out = brake_op if self.simulator_state.is_engaged else brake_manual - steer_out = steer_op if self.simulator_state.is_engaged else steer_manual - - self.world.apply_controls(steer_out, throttle_out, brake_out) - self.world.read_sensors(self.simulator_state) - - if self.rk.frame % self.TICKS_PER_FRAME == 0: - self.world.tick() - self.world.read_cameras() - - if self.rk.frame % 25 == 0: - self.print_status() - - self.started = True - - self.rk.keep_time() diff --git a/tools/sim/bridge/metadrive/metadrive_bridge.py b/tools/sim/bridge/metadrive/metadrive_bridge.py deleted file mode 100644 index fa946e1..0000000 --- a/tools/sim/bridge/metadrive/metadrive_bridge.py +++ /dev/null @@ -1,119 +0,0 @@ -import numpy as np - -from metadrive.component.sensors.rgb_camera import RGBCamera -from metadrive.component.sensors.base_camera import _cuda_enable -from metadrive.component.map.pg_map import MapGenerateMethod -from panda3d.core import Vec3, Texture, GraphicsOutput - -from openpilot.tools.sim.bridge.common import SimulatorBridge -from openpilot.tools.sim.bridge.metadrive.metadrive_world import MetaDriveWorld -from openpilot.tools.sim.lib.camerad import W, H - - -C3_POSITION = Vec3(0, 0, 1) - - -class CopyRamRGBCamera(RGBCamera): - """Camera which copies its content into RAM during the render process, for faster image grabbing.""" - def __init__(self, *args, **kwargs): - super().__init__(*args, **kwargs) - self.cpu_texture = Texture() - self.buffer.addRenderTexture(self.cpu_texture, GraphicsOutput.RTMCopyRam) - - def get_rgb_array_cpu(self): - origin_img = self.cpu_texture - img = np.frombuffer(origin_img.getRamImage().getData(), dtype=np.uint8) - img = img.reshape((origin_img.getYSize(), origin_img.getXSize(), -1)) - img = img[:,:,:3] # RGBA to RGB - # img = np.swapaxes(img, 1, 0) - img = img[::-1] # Flip on vertical axis - return img - - -class RGBCameraWide(CopyRamRGBCamera): - def __init__(self, *args, **kwargs): - super(RGBCameraWide, self).__init__(*args, **kwargs) - cam = self.get_cam() - cam.setPos(C3_POSITION) - lens = self.get_lens() - lens.setFov(160) - -class RGBCameraRoad(CopyRamRGBCamera): - def __init__(self, *args, **kwargs): - super(RGBCameraRoad, self).__init__(*args, **kwargs) - cam = self.get_cam() - cam.setPos(C3_POSITION) - lens = self.get_lens() - lens.setFov(40) - - -def straight_block(length): - return { - "id": "S", - "pre_block_socket_index": 0, - "length": length - } - -def curve_block(length, angle=45, direction=0): - return { - "id": "C", - "pre_block_socket_index": 0, - "length": length, - "radius": length, - "angle": angle, - "dir": direction - } - - -class MetaDriveBridge(SimulatorBridge): - TICKS_PER_FRAME = 5 - - def __init__(self, args): - self.should_render = False - - super(MetaDriveBridge, self).__init__(args) - - def spawn_world(self): - sensors = { - "rgb_road": (RGBCameraRoad, W, H, ) - } - - if self.dual_camera: - sensors["rgb_wide"] = (RGBCameraWide, W, H) - - config = dict( - use_render=self.should_render, - vehicle_config=dict( - enable_reverse=False, - image_source="rgb_road", - spawn_longitude=15 - ), - sensors=sensors, - image_on_cuda=_cuda_enable, - image_observation=True, - interface_panel=[], - out_of_route_done=False, - on_continuous_line_done=False, - crash_vehicle_done=False, - crash_object_done=False, - traffic_density=0.0, # traffic is incredibly expensive - map_config=dict( - type=MapGenerateMethod.PG_MAP_FILE, - config=[ - None, - straight_block(120), - curve_block(240, 90), - straight_block(120), - curve_block(240, 90), - straight_block(120), - curve_block(240, 90), - straight_block(120), - curve_block(240, 90), - ] - ), - decision_repeat=1, - physics_world_step_size=self.TICKS_PER_FRAME/100, - preload_models=False - ) - - return MetaDriveWorld(config) diff --git a/tools/sim/bridge/metadrive/metadrive_process.py b/tools/sim/bridge/metadrive/metadrive_process.py deleted file mode 100644 index 3d21c0e..0000000 --- a/tools/sim/bridge/metadrive/metadrive_process.py +++ /dev/null @@ -1,99 +0,0 @@ -import math -import numpy as np - -from collections import namedtuple -from multiprocessing.connection import Connection - -from metadrive.engine.core.engine_core import EngineCore -from metadrive.engine.core.image_buffer import ImageBuffer -from metadrive.envs.metadrive_env import MetaDriveEnv -from metadrive.obs.image_obs import ImageObservation - -from openpilot.common.realtime import Ratekeeper -from openpilot.tools.sim.lib.common import vec3 -from openpilot.tools.sim.lib.camerad import W, H - - -metadrive_state = namedtuple("metadrive_state", ["velocity", "position", "bearing", "steering_angle"]) - -def apply_metadrive_patches(): - # By default, metadrive won't try to use cuda images unless it's used as a sensor for vehicles, so patch that in - def add_image_sensor_patched(self, name: str, cls, args): - if self.global_config["image_on_cuda"]:# and name == self.global_config["vehicle_config"]["image_source"]: - sensor = cls(*args, self, cuda=True) - else: - sensor = cls(*args, self, cuda=False) - assert isinstance(sensor, ImageBuffer), "This API is for adding image sensor" - self.sensors[name] = sensor - - EngineCore.add_image_sensor = add_image_sensor_patched - - # we aren't going to use the built-in observation stack, so disable it to save time - def observe_patched(self, vehicle): - return self.state - - ImageObservation.observe = observe_patched - - def arrive_destination_patch(self, vehicle): - return False - - MetaDriveEnv._is_arrive_destination = arrive_destination_patch - -def metadrive_process(dual_camera: bool, config: dict, camera_array, controls_recv: Connection, state_send: Connection, exit_event): - apply_metadrive_patches() - - road_image = np.frombuffer(camera_array.get_obj(), dtype=np.uint8).reshape((H, W, 3)) - - env = MetaDriveEnv(config) - - def reset(): - env.reset() - env.vehicle.config["max_speed_km_h"] = 1000 - - reset() - - def get_cam_as_rgb(cam): - cam = env.engine.sensors[cam] - img = cam.perceive(env.vehicle, clip=False) - if type(img) != np.ndarray: - img = img.get() # convert cupy array to numpy - return img - - rk = Ratekeeper(100, None) - - steer_ratio = 15 - vc = [0,0] - - while not exit_event.is_set(): - state = metadrive_state( - velocity=vec3(x=float(env.vehicle.velocity[0]), y=float(env.vehicle.velocity[1]), z=0), - position=env.vehicle.position, - bearing=float(math.degrees(env.vehicle.heading_theta)), - steering_angle=env.vehicle.steering * env.vehicle.MAX_STEERING - ) - - state_send.send(state) - - if controls_recv.poll(0): - while controls_recv.poll(0): - steer_angle, gas, should_reset = controls_recv.recv() - - steer_metadrive = steer_angle * 1 / (env.vehicle.MAX_STEERING * steer_ratio) - steer_metadrive = np.clip(steer_metadrive, -1, 1) - - vc = [steer_metadrive, gas] - - if should_reset: - reset() - - if rk.frame % 5 == 0: - obs, _, terminated, _, info = env.step(vc) - - if terminated: - reset() - - #if dual_camera: - # wide_road_image = get_cam_as_rgb("rgb_wide") - road_image[...] = get_cam_as_rgb("rgb_road") - - rk.keep_time() \ No newline at end of file diff --git a/tools/sim/bridge/metadrive/metadrive_world.py b/tools/sim/bridge/metadrive/metadrive_world.py deleted file mode 100644 index 3705f19..0000000 --- a/tools/sim/bridge/metadrive/metadrive_world.py +++ /dev/null @@ -1,75 +0,0 @@ -import ctypes -import functools -import multiprocessing -import numpy as np -import time - -from multiprocessing import Pipe, Array -from openpilot.tools.sim.bridge.metadrive.metadrive_process import metadrive_process, metadrive_state -from openpilot.tools.sim.lib.common import SimulatorState, World -from openpilot.tools.sim.lib.camerad import W, H - - -class MetaDriveWorld(World): - def __init__(self, config, dual_camera = False): - super().__init__(dual_camera) - self.camera_array = Array(ctypes.c_uint8, W*H*3) - self.road_image = np.frombuffer(self.camera_array.get_obj(), dtype=np.uint8).reshape((H, W, 3)) - - self.controls_send, self.controls_recv = Pipe() - self.state_send, self.state_recv = Pipe() - - self.exit_event = multiprocessing.Event() - - self.metadrive_process = multiprocessing.Process(name="metadrive process", target= - functools.partial(metadrive_process, dual_camera, config, - self.camera_array, self.controls_recv, self.state_send, self.exit_event)) - self.metadrive_process.start() - - print("----------------------------------------------------------") - print("---- Spawning Metadrive world, this might take awhile ----") - print("----------------------------------------------------------") - - self.state_recv.recv() # wait for a state message to ensure metadrive is launched - - self.steer_ratio = 15 - self.vc = [0.0,0.0] - self.reset_time = 0 - self.should_reset = False - - def apply_controls(self, steer_angle, throttle_out, brake_out): - if (time.monotonic() - self.reset_time) > 2: - self.vc[0] = steer_angle - - if throttle_out: - self.vc[1] = throttle_out - else: - self.vc[1] = -brake_out - else: - self.vc[0] = 0 - self.vc[1] = 0 - - self.controls_send.send([*self.vc, self.should_reset]) - self.should_reset = False - - def read_sensors(self, state: SimulatorState): - while self.state_recv.poll(0): - md_state: metadrive_state = self.state_recv.recv() - state.velocity = md_state.velocity - state.bearing = md_state.bearing - state.steering_angle = md_state.steering_angle - state.gps.from_xy(md_state.position) - state.valid = True - - def read_cameras(self): - pass - - def tick(self): - pass - - def reset(self): - self.should_reset = True - - def close(self): - self.exit_event.set() - self.metadrive_process.join() diff --git a/tools/sim/build_container.sh b/tools/sim/build_container.sh deleted file mode 100644 index 81afb82..0000000 --- a/tools/sim/build_container.sh +++ /dev/null @@ -1,10 +0,0 @@ -#!/bin/bash - -DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd )" -cd $DIR/../../ - -docker pull ghcr.io/commaai/openpilot-base-cl:latest -docker build \ - --cache-from ghcr.io/commaai/openpilot-sim:latest \ - -t ghcr.io/commaai/openpilot-sim:latest \ - -f tools/sim/Dockerfile.sim . diff --git a/tools/sim/launch_openpilot.sh b/tools/sim/launch_openpilot.sh deleted file mode 100644 index 9532537..0000000 --- a/tools/sim/launch_openpilot.sh +++ /dev/null @@ -1,21 +0,0 @@ -#!/bin/bash - -export PASSIVE="0" -export NOBOARD="1" -export SIMULATION="1" -export SKIP_FW_QUERY="1" -export FINGERPRINT="HONDA CIVIC 2016" - -export BLOCK="${BLOCK},camerad,loggerd,encoderd,micd,logmessaged" -if [[ "$CI" ]]; then - # TODO: offscreen UI should work - export BLOCK="${BLOCK},ui" -fi - -python -c "from openpilot.selfdrive.test.helpers import set_params_enabled; set_params_enabled()" - -SCRIPT_DIR=$(dirname "$0") -OPENPILOT_DIR=$SCRIPT_DIR/../../ - -DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null && pwd )" -cd $OPENPILOT_DIR/selfdrive/manager && exec ./manager.py diff --git a/tools/sim/lib/__init__.py b/tools/sim/lib/__init__.py deleted file mode 100644 index e69de29..0000000 diff --git a/tools/sim/lib/camerad.py b/tools/sim/lib/camerad.py deleted file mode 100644 index 4621347..0000000 --- a/tools/sim/lib/camerad.py +++ /dev/null @@ -1,70 +0,0 @@ -import numpy as np -import os -import pyopencl as cl -import pyopencl.array as cl_array - -from cereal.visionipc import VisionIpcServer, VisionStreamType -from cereal import messaging - -from openpilot.common.basedir import BASEDIR -from openpilot.tools.sim.lib.common import W, H - -class Camerad: - """Simulates the camerad daemon""" - def __init__(self, dual_camera): - self.pm = messaging.PubMaster(['roadCameraState', 'wideRoadCameraState']) - - self.frame_road_id = 0 - self.frame_wide_id = 0 - self.vipc_server = VisionIpcServer("camerad") - - self.vipc_server.create_buffers(VisionStreamType.VISION_STREAM_ROAD, 5, False, W, H) - if dual_camera: - self.vipc_server.create_buffers(VisionStreamType.VISION_STREAM_WIDE_ROAD, 5, False, W, H) - - self.vipc_server.start_listener() - - # set up for pyopencl rgb to yuv conversion - self.ctx = cl.create_some_context() - self.queue = cl.CommandQueue(self.ctx) - cl_arg = f" -DHEIGHT={H} -DWIDTH={W} -DRGB_STRIDE={W * 3} -DUV_WIDTH={W // 2} -DUV_HEIGHT={H // 2} -DRGB_SIZE={W * H} -DCL_DEBUG " - - kernel_fn = os.path.join(BASEDIR, "tools/sim/rgb_to_nv12.cl") - with open(kernel_fn) as f: - prg = cl.Program(self.ctx, f.read()).build(cl_arg) - self.krnl = prg.rgb_to_nv12 - self.Wdiv4 = W // 4 if (W % 4 == 0) else (W + (4 - W % 4)) // 4 - self.Hdiv4 = H // 4 if (H % 4 == 0) else (H + (4 - H % 4)) // 4 - - def cam_send_yuv_road(self, yuv): - self._send_yuv(yuv, self.frame_road_id, 'roadCameraState', VisionStreamType.VISION_STREAM_ROAD) - self.frame_road_id += 1 - - def cam_send_yuv_wide_road(self, yuv): - self._send_yuv(yuv, self.frame_wide_id, 'wideRoadCameraState', VisionStreamType.VISION_STREAM_WIDE_ROAD) - self.frame_wide_id += 1 - - # Returns: yuv bytes - def rgb_to_yuv(self, rgb): - assert rgb.shape == (H, W, 3), f"{rgb.shape}" - assert rgb.dtype == np.uint8 - - rgb_cl = cl_array.to_device(self.queue, rgb) - yuv_cl = cl_array.empty_like(rgb_cl) - self.krnl(self.queue, (self.Wdiv4, self.Hdiv4), None, rgb_cl.data, yuv_cl.data).wait() - yuv = np.resize(yuv_cl.get(), rgb.size // 2) - return yuv.data.tobytes() - - def _send_yuv(self, yuv, frame_id, pub_type, yuv_type): - eof = int(frame_id * 0.05 * 1e9) - self.vipc_server.send(yuv_type, yuv, frame_id, eof, eof) - - dat = messaging.new_message(pub_type) - msg = { - "frameId": frame_id, - "transform": [1.0, 0.0, 0.0, - 0.0, 1.0, 0.0, - 0.0, 0.0, 1.0] - } - setattr(dat, pub_type, msg) - self.pm.send(pub_type, dat) \ No newline at end of file diff --git a/tools/sim/lib/common.py b/tools/sim/lib/common.py deleted file mode 100644 index b7aa66f..0000000 --- a/tools/sim/lib/common.py +++ /dev/null @@ -1,94 +0,0 @@ -import math -import threading -import numpy as np - -from abc import ABC, abstractmethod -from collections import namedtuple - -W, H = 1928, 1208 - - -vec3 = namedtuple("vec3", ["x", "y", "z"]) - -class GPSState: - def __init__(self): - self.latitude = 0 - self.longitude = 0 - self.altitude = 0 - - def from_xy(self, xy): - """Simulates a lat/lon from an xy coordinate on a plane, for simple simlation. TODO: proper global projection?""" - BASE_LAT = 32.75308505188913 - BASE_LON = -117.2095393365393 - DEG_TO_METERS = 100000 - - self.latitude = float(BASE_LAT + xy[0] / DEG_TO_METERS) - self.longitude = float(BASE_LON + xy[1] / DEG_TO_METERS) - self.altitude = 0 - - -class IMUState: - def __init__(self): - self.accelerometer: vec3 = vec3(0,0,0) - self.gyroscope: vec3 = vec3(0,0,0) - self.bearing: float = 0 - - -class SimulatorState: - def __init__(self): - self.valid = False - self.is_engaged = False - self.ignition = True - - self.velocity: vec3 = None - self.bearing: float = 0 - self.gps = GPSState() - self.imu = IMUState() - - self.steering_angle: float = 0 - - self.user_gas: float = 0 - self.user_brake: float = 0 - self.user_torque: float = 0 - - self.cruise_button = 0 - - self.left_blinker = False - self.right_blinker = False - - @property - def speed(self): - return math.sqrt(self.velocity.x ** 2 + self.velocity.y ** 2 + self.velocity.z ** 2) - - -class World(ABC): - def __init__(self, dual_camera): - self.dual_camera = dual_camera - - self.image_lock = threading.Lock() - self.road_image = np.zeros((H, W, 3), dtype=np.uint8) - self.wide_road_image = np.zeros((H, W, 3), dtype=np.uint8) - - @abstractmethod - def apply_controls(self, steer_sim, throttle_out, brake_out): - pass - - @abstractmethod - def tick(self): - pass - - @abstractmethod - def read_sensors(self, simulator_state: SimulatorState): - pass - - @abstractmethod - def read_cameras(self): - pass - - @abstractmethod - def close(self): - pass - - @abstractmethod - def reset(self): - pass \ No newline at end of file diff --git a/tools/sim/lib/keyboard_ctrl.py b/tools/sim/lib/keyboard_ctrl.py deleted file mode 100644 index c37f6ea..0000000 --- a/tools/sim/lib/keyboard_ctrl.py +++ /dev/null @@ -1,94 +0,0 @@ -import sys -import termios -import time - -from termios import (BRKINT, CS8, CSIZE, ECHO, ICANON, ICRNL, IEXTEN, INPCK, - ISTRIP, IXON, PARENB, VMIN, VTIME) -from typing import NoReturn - -# Indexes for termios list. -IFLAG = 0 -OFLAG = 1 -CFLAG = 2 -LFLAG = 3 -ISPEED = 4 -OSPEED = 5 -CC = 6 - -STDIN_FD = sys.stdin.fileno() - - -KEYBOARD_HELP = """ - | key | functionality | - |------|-----------------------| - | 1 | Cruise Resume / Accel | - | 2 | Cruise Set / Decel | - | 3 | Cruise Cancel | - | r | Reset Simulation | - | i | Toggle Ignition | - | q | Exit all | - | wasd | Control manually | -""" - - -def getch() -> str: - old_settings = termios.tcgetattr(STDIN_FD) - try: - # set - mode = old_settings.copy() - mode[IFLAG] &= ~(BRKINT | ICRNL | INPCK | ISTRIP | IXON) - #mode[OFLAG] &= ~(OPOST) - mode[CFLAG] &= ~(CSIZE | PARENB) - mode[CFLAG] |= CS8 - mode[LFLAG] &= ~(ECHO | ICANON | IEXTEN) - mode[CC][VMIN] = 1 - mode[CC][VTIME] = 0 - termios.tcsetattr(STDIN_FD, termios.TCSAFLUSH, mode) - - ch = sys.stdin.read(1) - finally: - termios.tcsetattr(STDIN_FD, termios.TCSADRAIN, old_settings) - return ch - -def keyboard_poll_thread(q: 'Queue[str]'): - while True: - c = getch() - if c == '1': - q.put("cruise_up") - elif c == '2': - q.put("cruise_down") - elif c == '3': - q.put("cruise_cancel") - elif c == 'w': - q.put("throttle_%f" % 1.0) - elif c == 'a': - q.put("steer_%f" % 0.15) - elif c == 's': - q.put("brake_%f" % 1.0) - elif c == 'd': - q.put("steer_%f" % -0.15) - elif c == 'z': - q.put("blinker_left") - elif c == 'x': - q.put("blinker_right") - elif c == 'i': - q.put("ignition") - elif c == 'r': - q.put("reset") - elif c == 'q': - q.put("quit") - break - -def test(q: 'Queue[str]') -> NoReturn: - while True: - print([q.get_nowait() for _ in range(q.qsize())] or None) - time.sleep(0.25) - -if __name__ == '__main__': - from multiprocessing import Process, Queue - q: Queue[str] = Queue() - p = Process(target=test, args=(q,)) - p.daemon = True - p.start() - - keyboard_poll_thread(q) diff --git a/tools/sim/lib/manual_ctrl.py b/tools/sim/lib/manual_ctrl.py deleted file mode 100644 index 04e228c..0000000 --- a/tools/sim/lib/manual_ctrl.py +++ /dev/null @@ -1,188 +0,0 @@ -#!/usr/bin/env python3 -# set up wheel -import array -import os -import struct -from fcntl import ioctl -from typing import NoReturn, Dict, List - -# Iterate over the joystick devices. -print('Available devices:') -for fn in os.listdir('/dev/input'): - if fn.startswith('js'): - print(f' /dev/input/{fn}') - -# We'll store the states here. -axis_states: Dict[str, float] = {} -button_states: Dict[str, float] = {} - -# These constants were borrowed from linux/input.h -axis_names = { - 0x00 : 'x', - 0x01 : 'y', - 0x02 : 'z', - 0x03 : 'rx', - 0x04 : 'ry', - 0x05 : 'rz', - 0x06 : 'trottle', - 0x07 : 'rudder', - 0x08 : 'wheel', - 0x09 : 'gas', - 0x0a : 'brake', - 0x10 : 'hat0x', - 0x11 : 'hat0y', - 0x12 : 'hat1x', - 0x13 : 'hat1y', - 0x14 : 'hat2x', - 0x15 : 'hat2y', - 0x16 : 'hat3x', - 0x17 : 'hat3y', - 0x18 : 'pressure', - 0x19 : 'distance', - 0x1a : 'tilt_x', - 0x1b : 'tilt_y', - 0x1c : 'tool_width', - 0x20 : 'volume', - 0x28 : 'misc', -} - -button_names = { - 0x120 : 'trigger', - 0x121 : 'thumb', - 0x122 : 'thumb2', - 0x123 : 'top', - 0x124 : 'top2', - 0x125 : 'pinkie', - 0x126 : 'base', - 0x127 : 'base2', - 0x128 : 'base3', - 0x129 : 'base4', - 0x12a : 'base5', - 0x12b : 'base6', - 0x12f : 'dead', - 0x130 : 'a', - 0x131 : 'b', - 0x132 : 'c', - 0x133 : 'x', - 0x134 : 'y', - 0x135 : 'z', - 0x136 : 'tl', - 0x137 : 'tr', - 0x138 : 'tl2', - 0x139 : 'tr2', - 0x13a : 'select', - 0x13b : 'start', - 0x13c : 'mode', - 0x13d : 'thumbl', - 0x13e : 'thumbr', - - 0x220 : 'dpad_up', - 0x221 : 'dpad_down', - 0x222 : 'dpad_left', - 0x223 : 'dpad_right', - - # XBox 360 controller uses these codes. - 0x2c0 : 'dpad_left', - 0x2c1 : 'dpad_right', - 0x2c2 : 'dpad_up', - 0x2c3 : 'dpad_down', -} - -axis_name_list: List[str] = [] -button_name_list: List[str] = [] - -def wheel_poll_thread(q: 'Queue[str]') -> NoReturn: - # Open the joystick device. - fn = '/dev/input/js0' - print(f'Opening {fn}...') - jsdev = open(fn, 'rb') - - # Get the device name. - #buf = bytearray(63) - buf = array.array('B', [0] * 64) - ioctl(jsdev, 0x80006a13 + (0x10000 * len(buf)), buf) # JSIOCGNAME(len) - js_name = buf.tobytes().rstrip(b'\x00').decode('utf-8') - print(f'Device name: {js_name}') - - # Get number of axes and buttons. - buf = array.array('B', [0]) - ioctl(jsdev, 0x80016a11, buf) # JSIOCGAXES - num_axes = buf[0] - - buf = array.array('B', [0]) - ioctl(jsdev, 0x80016a12, buf) # JSIOCGBUTTONS - num_buttons = buf[0] - - # Get the axis map. - buf = array.array('B', [0] * 0x40) - ioctl(jsdev, 0x80406a32, buf) # JSIOCGAXMAP - - for _axis in buf[:num_axes]: - axis_name = axis_names.get(_axis, f'unknown(0x{_axis:02x})') - axis_name_list.append(axis_name) - axis_states[axis_name] = 0.0 - - # Get the button map. - buf = array.array('H', [0] * 200) - ioctl(jsdev, 0x80406a34, buf) # JSIOCGBTNMAP - - for btn in buf[:num_buttons]: - btn_name = button_names.get(btn, f'unknown(0x{btn:03x})') - button_name_list.append(btn_name) - button_states[btn_name] = 0 - - print('%d axes found: %s' % (num_axes, ', '.join(axis_name_list))) - print('%d buttons found: %s' % (num_buttons, ', '.join(button_name_list))) - - # Enable FF - import evdev - from evdev import ecodes, InputDevice - device = evdev.list_devices()[0] - evtdev = InputDevice(device) - val = 24000 - evtdev.write(ecodes.EV_FF, ecodes.FF_AUTOCENTER, val) - - while True: - evbuf = jsdev.read(8) - value, mtype, number = struct.unpack('4xhBB', evbuf) - # print(mtype, number, value) - if mtype & 0x02: # wheel & paddles - axis = axis_name_list[number] - - if axis == "z": # gas - fvalue = value / 32767.0 - axis_states[axis] = fvalue - normalized = (1 - fvalue) * 50 - q.put(f"throttle_{normalized:f}") - - elif axis == "rz": # brake - fvalue = value / 32767.0 - axis_states[axis] = fvalue - normalized = (1 - fvalue) * 50 - q.put(f"brake_{normalized:f}") - - elif axis == "x": # steer angle - fvalue = value / 32767.0 - axis_states[axis] = fvalue - normalized = fvalue - q.put(f"steer_{normalized:f}") - - elif mtype & 0x01: # buttons - if value == 1: # press down - if number in [0, 19]: # X - q.put("cruise_down") - - elif number in [3, 18]: # triangle - q.put("cruise_up") - - elif number in [1, 6]: # square - q.put("cruise_cancel") - - elif number in [10, 21]: # R3 - q.put("reverse_switch") - -if __name__ == '__main__': - from multiprocessing import Process, Queue - q: Queue[str] = Queue() - p = Process(target=wheel_poll_thread, args=(q,)) - p.start() diff --git a/tools/sim/lib/simulated_car.py b/tools/sim/lib/simulated_car.py deleted file mode 100644 index ab60fad..0000000 --- a/tools/sim/lib/simulated_car.py +++ /dev/null @@ -1,119 +0,0 @@ -import cereal.messaging as messaging - -from opendbc.can.packer import CANPacker -from opendbc.can.parser import CANParser -from openpilot.selfdrive.boardd.boardd_api_impl import can_list_to_can_capnp -from openpilot.selfdrive.car import crc8_pedal -from openpilot.tools.sim.lib.common import SimulatorState - - -class SimulatedCar: - """Simulates a honda civic 2016 (panda state + can messages) to OpenPilot""" - packer = CANPacker("honda_civic_touring_2016_can_generated") - rpacker = CANPacker("acura_ilx_2016_nidec") - - def __init__(self): - self.pm = messaging.PubMaster(['can', 'pandaStates']) - self.sm = messaging.SubMaster(['carControl', 'controlsState', 'carParams']) - self.cp = self.get_car_can_parser() - self.idx = 0 - - @staticmethod - def get_car_can_parser(): - dbc_f = 'honda_civic_touring_2016_can_generated' - checks = [ - (0xe4, 100), - (0x1fa, 50), - (0x200, 50), - ] - return CANParser(dbc_f, checks, 0) - - def send_can_messages(self, simulator_state: SimulatorState): - if not simulator_state.valid: - return - - msg = [] - - # *** powertrain bus *** - - speed = simulator_state.speed * 3.6 # convert m/s to kph - msg.append(self.packer.make_can_msg("ENGINE_DATA", 0, {"XMISSION_SPEED": speed})) - msg.append(self.packer.make_can_msg("WHEEL_SPEEDS", 0, { - "WHEEL_SPEED_FL": speed, - "WHEEL_SPEED_FR": speed, - "WHEEL_SPEED_RL": speed, - "WHEEL_SPEED_RR": speed - })) - - msg.append(self.packer.make_can_msg("SCM_BUTTONS", 0, {"CRUISE_BUTTONS": simulator_state.cruise_button})) - - values = { - "COUNTER_PEDAL": self.idx & 0xF, - "INTERCEPTOR_GAS": simulator_state.user_gas * 2**12, - "INTERCEPTOR_GAS2": simulator_state.user_gas * 2**12, - } - checksum = crc8_pedal(self.packer.make_can_msg("GAS_SENSOR", 0, values)[2][:-1]) - values["CHECKSUM_PEDAL"] = checksum - msg.append(self.packer.make_can_msg("GAS_SENSOR", 0, values)) - - msg.append(self.packer.make_can_msg("GEARBOX", 0, {"GEAR": 4, "GEAR_SHIFTER": 8})) - msg.append(self.packer.make_can_msg("GAS_PEDAL_2", 0, {})) - msg.append(self.packer.make_can_msg("SEATBELT_STATUS", 0, {"SEATBELT_DRIVER_LATCHED": 1})) - msg.append(self.packer.make_can_msg("STEER_STATUS", 0, {"STEER_TORQUE_SENSOR": simulator_state.user_torque})) - msg.append(self.packer.make_can_msg("STEERING_SENSORS", 0, {"STEER_ANGLE": simulator_state.steering_angle})) - msg.append(self.packer.make_can_msg("VSA_STATUS", 0, {})) - msg.append(self.packer.make_can_msg("STANDSTILL", 0, {"WHEELS_MOVING": 1 if simulator_state.speed >= 1.0 else 0})) - msg.append(self.packer.make_can_msg("STEER_MOTOR_TORQUE", 0, {})) - msg.append(self.packer.make_can_msg("EPB_STATUS", 0, {})) - msg.append(self.packer.make_can_msg("DOORS_STATUS", 0, {})) - msg.append(self.packer.make_can_msg("CRUISE_PARAMS", 0, {})) - msg.append(self.packer.make_can_msg("CRUISE", 0, {})) - msg.append(self.packer.make_can_msg("SCM_FEEDBACK", 0, - { - "MAIN_ON": 1, - "LEFT_BLINKER": simulator_state.left_blinker, - "RIGHT_BLINKER": simulator_state.right_blinker - })) - msg.append(self.packer.make_can_msg("POWERTRAIN_DATA", 0, - { - "ACC_STATUS": int(simulator_state.is_engaged), - "PEDAL_GAS": simulator_state.user_gas, - "BRAKE_PRESSED": simulator_state.user_brake > 0 - })) - msg.append(self.packer.make_can_msg("HUD_SETTING", 0, {})) - msg.append(self.packer.make_can_msg("CAR_SPEED", 0, {})) - - # *** cam bus *** - msg.append(self.packer.make_can_msg("STEERING_CONTROL", 2, {})) - msg.append(self.packer.make_can_msg("ACC_HUD", 2, {})) - msg.append(self.packer.make_can_msg("LKAS_HUD", 2, {})) - msg.append(self.packer.make_can_msg("BRAKE_COMMAND", 2, {})) - - # *** radar bus *** - if self.idx % 5 == 0: - msg.append(self.rpacker.make_can_msg("RADAR_DIAGNOSTIC", 1, {"RADAR_STATE": 0x79})) - for i in range(16): - msg.append(self.rpacker.make_can_msg("TRACK_%d" % i, 1, {"LONG_DIST": 255.5})) - - self.pm.send('can', can_list_to_can_capnp(msg)) - - def send_panda_state(self, simulator_state): - self.sm.update(0) - dat = messaging.new_message('pandaStates', 1) - dat.valid = True - dat.pandaStates[0] = { - 'ignitionLine': simulator_state.ignition, - 'pandaType': "blackPanda", - 'controlsAllowed': True, - 'safetyModel': 'hondaNidec', - 'alternativeExperience': self.sm["carParams"].alternativeExperience - } - self.pm.send('pandaStates', dat) - - def update(self, simulator_state: SimulatorState): - self.send_can_messages(simulator_state) - - if self.idx % 50 == 0: # only send panda states at 2hz - self.send_panda_state(simulator_state) - - self.idx += 1 \ No newline at end of file diff --git a/tools/sim/lib/simulated_sensors.py b/tools/sim/lib/simulated_sensors.py deleted file mode 100644 index 4520ed3..0000000 --- a/tools/sim/lib/simulated_sensors.py +++ /dev/null @@ -1,125 +0,0 @@ -import time - -from cereal import log -import cereal.messaging as messaging - -from openpilot.common.params import Params -from openpilot.common.realtime import DT_DMON -from openpilot.tools.sim.lib.camerad import Camerad - -from typing import TYPE_CHECKING -if TYPE_CHECKING: - from openpilot.tools.sim.lib.common import World, SimulatorState - - -class SimulatedSensors: - """Simulates the C3 sensors (acc, gyro, gps, peripherals, dm state, cameras) to OpenPilot""" - - def __init__(self, dual_camera=False): - self.pm = messaging.PubMaster(['accelerometer', 'gyroscope', 'gpsLocationExternal', 'driverStateV2', 'driverMonitoringState', 'peripheralState']) - self.camerad = Camerad(dual_camera=dual_camera) - self.last_perp_update = 0 - self.last_dmon_update = 0 - - def send_imu_message(self, simulator_state: 'SimulatorState'): - for _ in range(5): - dat = messaging.new_message('accelerometer') - dat.accelerometer.sensor = 4 - dat.accelerometer.type = 0x10 - dat.accelerometer.timestamp = dat.logMonoTime # TODO: use the IMU timestamp - dat.accelerometer.init('acceleration') - dat.accelerometer.acceleration.v = [simulator_state.imu.accelerometer.x, simulator_state.imu.accelerometer.y, simulator_state.imu.accelerometer.z] - self.pm.send('accelerometer', dat) - - # copied these numbers from locationd - dat = messaging.new_message('gyroscope') - dat.gyroscope.sensor = 5 - dat.gyroscope.type = 0x10 - dat.gyroscope.timestamp = dat.logMonoTime # TODO: use the IMU timestamp - dat.gyroscope.init('gyroUncalibrated') - dat.gyroscope.gyroUncalibrated.v = [simulator_state.imu.gyroscope.x, simulator_state.imu.gyroscope.y, simulator_state.imu.gyroscope.z] - self.pm.send('gyroscope', dat) - - def send_gps_message(self, simulator_state: 'SimulatorState'): - if not simulator_state.valid: - return - - # transform vel from carla to NED - # north is -Y in CARLA - velNED = [ - -simulator_state.velocity.y, # north/south component of NED is negative when moving south - simulator_state.velocity.x, # positive when moving east, which is x in carla - simulator_state.velocity.z, - ] - - for _ in range(10): - dat = messaging.new_message('gpsLocationExternal') - dat.gpsLocationExternal = { - "unixTimestampMillis": int(time.time() * 1000), - "flags": 1, # valid fix - "accuracy": 1.0, - "verticalAccuracy": 1.0, - "speedAccuracy": 0.1, - "bearingAccuracyDeg": 0.1, - "vNED": velNED, - "bearingDeg": simulator_state.imu.bearing, - "latitude": simulator_state.gps.latitude, - "longitude": simulator_state.gps.longitude, - "altitude": simulator_state.gps.altitude, - "speed": simulator_state.speed, - "source": log.GpsLocationData.SensorSource.ublox, - } - - self.pm.send('gpsLocationExternal', dat) - - def send_peripheral_state(self): - dat = messaging.new_message('peripheralState') - dat.valid = True - dat.peripheralState = { - 'pandaType': log.PandaState.PandaType.blackPanda, - 'voltage': 12000, - 'current': 5678, - 'fanSpeedRpm': 1000 - } - Params().put_bool("ObdMultiplexingEnabled", False) - self.pm.send('peripheralState', dat) - - def send_fake_driver_monitoring(self): - # dmonitoringmodeld output - dat = messaging.new_message('driverStateV2') - dat.driverStateV2.leftDriverData.faceOrientation = [0., 0., 0.] - dat.driverStateV2.leftDriverData.faceProb = 1.0 - dat.driverStateV2.rightDriverData.faceOrientation = [0., 0., 0.] - dat.driverStateV2.rightDriverData.faceProb = 1.0 - self.pm.send('driverStateV2', dat) - - # dmonitoringd output - dat = messaging.new_message('driverMonitoringState') - dat.driverMonitoringState = { - "faceDetected": True, - "isDistracted": False, - "awarenessStatus": 1., - } - self.pm.send('driverMonitoringState', dat) - - def send_camera_images(self, world: 'World'): - with world.image_lock: - yuv = self.camerad.rgb_to_yuv(world.road_image) - self.camerad.cam_send_yuv_road(yuv) - - if world.dual_camera: - yuv = self.camerad.rgb_to_yuv(world.wide_road_image) - self.camerad.cam_send_yuv_wide_road(yuv) - - def update(self, simulator_state: 'SimulatorState', world: 'World'): - now = time.time() - self.send_imu_message(simulator_state) - self.send_gps_message(simulator_state) - - if (now - self.last_dmon_update) > DT_DMON/2: - self.send_fake_driver_monitoring() - self.last_dmon_update = now - - if (now - self.last_perp_update) > 0.25: - self.send_peripheral_state() - self.last_perp_update = now \ No newline at end of file diff --git a/tools/sim/rgb_to_nv12.cl b/tools/sim/rgb_to_nv12.cl deleted file mode 100644 index 54816d5..0000000 --- a/tools/sim/rgb_to_nv12.cl +++ /dev/null @@ -1,119 +0,0 @@ -#define RGB_TO_Y(r, g, b) ((((mul24(b, 13) + mul24(g, 65) + mul24(r, 33)) + 64) >> 7) + 16) -#define RGB_TO_U(r, g, b) ((mul24(b, 56) - mul24(g, 37) - mul24(r, 19) + 0x8080) >> 8) -#define RGB_TO_V(r, g, b) ((mul24(r, 56) - mul24(g, 47) - mul24(b, 9) + 0x8080) >> 8) -#define AVERAGE(x, y, z, w) ((convert_ushort(x) + convert_ushort(y) + convert_ushort(z) + convert_ushort(w) + 1) >> 1) - -inline void convert_2_ys(__global uchar * out_yuv, int yi, const uchar8 rgbs1) { - uchar2 yy = (uchar2)( - RGB_TO_Y(rgbs1.s2, rgbs1.s1, rgbs1.s0), - RGB_TO_Y(rgbs1.s5, rgbs1.s4, rgbs1.s3) - ); -#ifdef CL_DEBUG - if(yi >= RGB_SIZE) - printf("Y vector2 overflow, %d > %d\n", yi, RGB_SIZE); -#endif - vstore2(yy, 0, out_yuv + yi); -} - -inline void convert_4_ys(__global uchar * out_yuv, int yi, const uchar8 rgbs1, const uchar8 rgbs3) { - const uchar4 yy = (uchar4)( - RGB_TO_Y(rgbs1.s2, rgbs1.s1, rgbs1.s0), - RGB_TO_Y(rgbs1.s5, rgbs1.s4, rgbs1.s3), - RGB_TO_Y(rgbs3.s0, rgbs1.s7, rgbs1.s6), - RGB_TO_Y(rgbs3.s3, rgbs3.s2, rgbs3.s1) - ); -#ifdef CL_DEBUG - if(yi > RGB_SIZE - 4) - printf("Y vector4 overflow, %d > %d\n", yi, RGB_SIZE - 4); -#endif - vstore4(yy, 0, out_yuv + yi); -} - -inline void convert_uv(__global uchar * out_yuv, int uvi, - const uchar8 rgbs1, const uchar8 rgbs2) { - // U & V: average of 2x2 pixels square - const short ab = AVERAGE(rgbs1.s0, rgbs1.s3, rgbs2.s0, rgbs2.s3); - const short ag = AVERAGE(rgbs1.s1, rgbs1.s4, rgbs2.s1, rgbs2.s4); - const short ar = AVERAGE(rgbs1.s2, rgbs1.s5, rgbs2.s2, rgbs2.s5); -#ifdef CL_DEBUG - if(uvi >= RGB_SIZE + RGB_SIZE / 2) - printf("UV overflow, %d >= %d\n", uvi, RGB_SIZE + RGB_SIZE / 2); -#endif - out_yuv[uvi] = RGB_TO_U(ar, ag, ab); - out_yuv[uvi+1] = RGB_TO_V(ar, ag, ab); -} - -inline void convert_2_uvs(__global uchar * out_yuv, int uvi, - const uchar8 rgbs1, const uchar8 rgbs2, const uchar8 rgbs3, const uchar8 rgbs4) { - // U & V: average of 2x2 pixels square - const short ab1 = AVERAGE(rgbs1.s0, rgbs1.s3, rgbs2.s0, rgbs2.s3); - const short ag1 = AVERAGE(rgbs1.s1, rgbs1.s4, rgbs2.s1, rgbs2.s4); - const short ar1 = AVERAGE(rgbs1.s2, rgbs1.s5, rgbs2.s2, rgbs2.s5); - const short ab2 = AVERAGE(rgbs1.s6, rgbs3.s1, rgbs2.s6, rgbs4.s1); - const short ag2 = AVERAGE(rgbs1.s7, rgbs3.s2, rgbs2.s7, rgbs4.s2); - const short ar2 = AVERAGE(rgbs3.s0, rgbs3.s3, rgbs4.s0, rgbs4.s3); - uchar4 uv = (uchar4)( - RGB_TO_U(ar1, ag1, ab1), - RGB_TO_V(ar1, ag1, ab1), - RGB_TO_U(ar2, ag2, ab2), - RGB_TO_V(ar2, ag2, ab2) - ); -#ifdef CL_DEBUG1 - if(uvi > RGB_SIZE + RGB_SIZE / 2 - 4) - printf("UV2 overflow, %d >= %d\n", uvi, RGB_SIZE + RGB_SIZE / 2 - 2); -#endif - vstore4(uv, 0, out_yuv + uvi); -} - -__kernel void rgb_to_nv12(__global uchar const * const rgb, - __global uchar * out_yuv) -{ - const int dx = get_global_id(0); - const int dy = get_global_id(1); - const int col = mul24(dx, 4); // Current column in rgb image - const int row = mul24(dy, 4); // Current row in rgb image - const int bgri_start = mad24(row, RGB_STRIDE, mul24(col, 3)); // Start offset of rgb data being converted - const int yi_start = mad24(row, WIDTH, col); // Start offset in the target yuv buffer - int uvi = mad24(row / 2, WIDTH, RGB_SIZE + col); - int num_col = min(WIDTH - col, 4); - int num_row = min(HEIGHT - row, 4); - if(num_row == 4) { - const uchar8 rgbs0_0 = vload8(0, rgb + bgri_start); - const uchar8 rgbs0_1 = vload8(0, rgb + bgri_start + 8); - const uchar8 rgbs1_0 = vload8(0, rgb + bgri_start + RGB_STRIDE); - const uchar8 rgbs1_1 = vload8(0, rgb + bgri_start + RGB_STRIDE + 8); - const uchar8 rgbs2_0 = vload8(0, rgb + bgri_start + RGB_STRIDE * 2); - const uchar8 rgbs2_1 = vload8(0, rgb + bgri_start + RGB_STRIDE * 2 + 8); - const uchar8 rgbs3_0 = vload8(0, rgb + bgri_start + RGB_STRIDE * 3); - const uchar8 rgbs3_1 = vload8(0, rgb + bgri_start + RGB_STRIDE * 3 + 8); - if(num_col == 4) { - convert_4_ys(out_yuv, yi_start, rgbs0_0, rgbs0_1); - convert_4_ys(out_yuv, yi_start + WIDTH, rgbs1_0, rgbs1_1); - convert_4_ys(out_yuv, yi_start + WIDTH * 2, rgbs2_0, rgbs2_1); - convert_4_ys(out_yuv, yi_start + WIDTH * 3, rgbs3_0, rgbs3_1); - convert_2_uvs(out_yuv, uvi, rgbs0_0, rgbs1_0, rgbs0_1, rgbs1_1); - convert_2_uvs(out_yuv, uvi + WIDTH, rgbs2_0, rgbs3_0, rgbs2_1, rgbs3_1); - } else if(num_col == 2) { - convert_2_ys(out_yuv, yi_start, rgbs0_0); - convert_2_ys(out_yuv, yi_start + WIDTH, rgbs1_0); - convert_2_ys(out_yuv, yi_start + WIDTH * 2, rgbs2_0); - convert_2_ys(out_yuv, yi_start + WIDTH * 3, rgbs3_0); - convert_uv(out_yuv, uvi, rgbs0_0, rgbs1_0); - convert_uv(out_yuv, uvi + WIDTH, rgbs2_0, rgbs3_0); - } - } else { - const uchar8 rgbs0_0 = vload8(0, rgb + bgri_start); - const uchar8 rgbs0_1 = vload8(0, rgb + bgri_start + 8); - const uchar8 rgbs1_0 = vload8(0, rgb + bgri_start + RGB_STRIDE); - const uchar8 rgbs1_1 = vload8(0, rgb + bgri_start + RGB_STRIDE + 8); - if(num_col == 4) { - convert_4_ys(out_yuv, yi_start, rgbs0_0, rgbs0_1); - convert_4_ys(out_yuv, yi_start + WIDTH, rgbs1_0, rgbs1_1); - convert_2_uvs(out_yuv, uvi, rgbs0_0, rgbs1_0, rgbs0_1, rgbs1_1); - } else if(num_col == 2) { - convert_2_ys(out_yuv, yi_start, rgbs0_0); - convert_2_ys(out_yuv, yi_start + WIDTH, rgbs1_0); - convert_uv(out_yuv, uvi, rgbs0_0, rgbs1_0); - } - } -} diff --git a/tools/sim/run_bridge.py b/tools/sim/run_bridge.py deleted file mode 100644 index 99617b1..0000000 --- a/tools/sim/run_bridge.py +++ /dev/null @@ -1,54 +0,0 @@ -#!/usr/bin/env python -import argparse -import os - -from typing import Any -from multiprocessing import Queue - -from openpilot.tools.sim.bridge.common import SimulatorBridge -from openpilot.tools.sim.bridge.carla.carla_bridge import CarlaBridge -from openpilot.tools.sim.bridge.metadrive.metadrive_bridge import MetaDriveBridge - - -def parse_args(add_args=None): - parser = argparse.ArgumentParser(description='Bridge between the simulator and openpilot.') - parser.add_argument('--joystick', action='store_true') - parser.add_argument('--high_quality', action='store_true') - parser.add_argument('--dual_camera', action='store_true') - parser.add_argument('--simulator', dest='simulator', type=str, default='metadrive') - - # Carla specific - parser.add_argument('--town', type=str, default='Town04_Opt') - parser.add_argument('--spawn_point', dest='num_selected_spawn_point', type=int, default=16) - parser.add_argument('--host', dest='host', type=str, default=os.environ.get("CARLA_HOST", '127.0.0.1')) - parser.add_argument('--port', dest='port', type=int, default=2000) - - return parser.parse_args(add_args) - -if __name__ == "__main__": - q: Any = Queue() - args = parse_args() - - simulator_bridge: SimulatorBridge - if args.simulator == "carla": - simulator_bridge = CarlaBridge(args) - elif args.simulator == "metadrive": - simulator_bridge = MetaDriveBridge(args) - else: - raise AssertionError("simulator type not supported") - p = simulator_bridge.run(q) - - if args.joystick: - # start input poll for joystick - from openpilot.tools.sim.lib.manual_ctrl import wheel_poll_thread - - wheel_poll_thread(q) - else: - # start input poll for keyboard - from openpilot.tools.sim.lib.keyboard_ctrl import keyboard_poll_thread - - keyboard_poll_thread(q) - - simulator_bridge.shutdown() - - p.join() diff --git a/tools/sim/start_carla.sh b/tools/sim/start_carla.sh deleted file mode 100644 index f14e0ef..0000000 --- a/tools/sim/start_carla.sh +++ /dev/null @@ -1,34 +0,0 @@ -#!/bin/bash - -# Requires nvidia docker - https://github.com/NVIDIA/nvidia-docker -if ! $(apt list --installed | grep -q nvidia-container-toolkit); then - read -p "Nvidia docker is required. Do you want to install it now? (y/n)"; - if [ "${REPLY}" == "y" ]; then - distribution=$(. /etc/os-release;echo $ID$VERSION_ID) - echo $distribution - curl -s -L https://nvidia.github.io/nvidia-docker/gpgkey | sudo apt-key add - - curl -s -L https://nvidia.github.io/nvidia-docker/$distribution/nvidia-docker.list | sudo tee /etc/apt/sources.list.d/nvidia-docker.list - sudo apt-get update && sudo apt-get install -y nvidia-docker2 # Also installs docker-ce and nvidia-container-toolkit - sudo systemctl restart docker - else - exit 0 - fi -fi - -docker pull carlasim/carla:0.9.14 - -EXTRA_ARGS="-it" -if [[ "$DETACH" ]]; then - EXTRA_ARGS="-d" -fi - -docker kill carla_sim || true -docker run \ - --name carla_sim \ - --rm \ - --gpus all \ - --net=host \ - -v /tmp/.X11-unix:/tmp/.X11-unix:rw \ - $EXTRA_ARGS \ - carlasim/carla:0.9.14 \ - /bin/bash ./CarlaUE4.sh -opengl -nosound -RenderOffScreen -benchmark -fps=20 -quality-level=Low diff --git a/tools/sim/start_openpilot_docker.sh b/tools/sim/start_openpilot_docker.sh deleted file mode 100644 index 54f4995..0000000 --- a/tools/sim/start_openpilot_docker.sh +++ /dev/null @@ -1,37 +0,0 @@ -#!/bin/bash - -DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" >/dev/null && pwd)" -cd $DIR - -OPENPILOT_DIR="/tmp/openpilot" -if ! [[ -z "$MOUNT_OPENPILOT" ]]; then - OPENPILOT_DIR="$(dirname $(dirname $DIR))" - EXTRA_ARGS="-v $OPENPILOT_DIR:$OPENPILOT_DIR -e PYTHONPATH=$OPENPILOT_DIR:$PYTHONPATH" -fi - -if [[ "$CI" ]]; then - CMD="CI=1 ${OPENPILOT_DIR}/tools/sim/tests/test_carla_integration.py" -else - # expose X to the container - xhost +local:root - - docker pull ghcr.io/commaai/openpilot-sim:latest - CMD="./tmux_script.sh $*" - EXTRA_ARGS="${EXTRA_ARGS} -it" -fi - -docker kill openpilot_client || true -docker run --net=host\ - --name openpilot_client \ - --rm \ - --gpus all \ - --device=/dev/dri:/dev/dri \ - --device=/dev/input:/dev/input \ - -v /tmp/.X11-unix:/tmp/.X11-unix \ - --shm-size 1G \ - -e DISPLAY=$DISPLAY \ - -e QT_X11_NO_MITSHM=1 \ - -w "$OPENPILOT_DIR/tools/sim" \ - $EXTRA_ARGS \ - ghcr.io/commaai/openpilot-sim:latest \ - /bin/bash -c "$CMD" diff --git a/tools/sim/tests/__init__.py b/tools/sim/tests/__init__.py deleted file mode 100644 index e69de29..0000000 diff --git a/tools/sim/tests/test_carla_bridge.py b/tools/sim/tests/test_carla_bridge.py deleted file mode 100644 index 3a654c9..0000000 --- a/tools/sim/tests/test_carla_bridge.py +++ /dev/null @@ -1,45 +0,0 @@ -#!/usr/bin/env python3 -import subprocess -import time -import unittest -from subprocess import Popen - -from openpilot.selfdrive.manager.helpers import unblock_stdout -from openpilot.tools.sim.run_bridge import parse_args -from openpilot.tools.sim.bridge.carla.carla_bridge import CarlaBridge -from openpilot.tools.sim.tests.test_sim_bridge import SIM_DIR, TestSimBridgeBase - -from typing import Optional - -class TestCarlaBridge(TestSimBridgeBase): - """ - Tests need Carla simulator to run - """ - carla_process: Optional[Popen] = None - - def setUp(self): - super().setUp() - - # We want to make sure that carla_sim docker isn't still running. - subprocess.run("docker rm -f carla_sim", shell=True, stderr=subprocess.PIPE, check=False) - self.carla_process = subprocess.Popen("./start_carla.sh", cwd=SIM_DIR) - - # Too many lagging messages in bridge.py can cause a crash. This prevents it. - unblock_stdout() - # Wait 10 seconds to startup carla - time.sleep(10) - - def create_bridge(self): - return CarlaBridge(parse_args([])) - - def tearDown(self): - super().tearDown() - - # Stop carla simulator by removing docker container - subprocess.run("docker rm -f carla_sim", shell=True, stderr=subprocess.PIPE, check=False) - if self.carla_process is not None: - self.carla_process.wait() - - -if __name__ == "__main__": - unittest.main() diff --git a/tools/sim/tests/test_metadrive_bridge.py b/tools/sim/tests/test_metadrive_bridge.py deleted file mode 100644 index 2c53465..0000000 --- a/tools/sim/tests/test_metadrive_bridge.py +++ /dev/null @@ -1,15 +0,0 @@ -#!/usr/bin/env python3 -import unittest - -from openpilot.tools.sim.run_bridge import parse_args -from openpilot.tools.sim.bridge.metadrive.metadrive_bridge import MetaDriveBridge -from openpilot.tools.sim.tests.test_sim_bridge import TestSimBridgeBase - - -class TestMetaDriveBridge(TestSimBridgeBase): - def create_bridge(self): - return MetaDriveBridge(parse_args([])) - - -if __name__ == "__main__": - unittest.main() diff --git a/tools/sim/tests/test_sim_bridge.py b/tools/sim/tests/test_sim_bridge.py deleted file mode 100644 index 2654526..0000000 --- a/tools/sim/tests/test_sim_bridge.py +++ /dev/null @@ -1,88 +0,0 @@ -import os -import subprocess -import time -import unittest - -from multiprocessing import Queue - -from cereal import messaging -from openpilot.common.basedir import BASEDIR - -SIM_DIR = os.path.join(BASEDIR, "tools/sim") - -class TestSimBridgeBase(unittest.TestCase): - @classmethod - def setUpClass(cls): - if cls is TestSimBridgeBase: - raise unittest.SkipTest("Don't run this base class, run test_carla_bridge.py instead") - - def setUp(self): - self.processes = [] - - def test_engage(self): - # Startup manager and bridge.py. Check processes are running, then engage and verify. - p_manager = subprocess.Popen("./launch_openpilot.sh", cwd=SIM_DIR) - self.processes.append(p_manager) - - sm = messaging.SubMaster(['controlsState', 'onroadEvents', 'managerState']) - q = Queue() - carla_bridge = self.create_bridge() - p_bridge = carla_bridge.run(q, retries=10) - self.processes.append(p_bridge) - - max_time_per_step = 60 - - # Wait for bridge to startup - start_waiting = time.monotonic() - while not carla_bridge.started and time.monotonic() < start_waiting + max_time_per_step: - time.sleep(0.1) - self.assertEqual(p_bridge.exitcode, None, f"Bridge process should be running, but exited with code {p_bridge.exitcode}") - - start_time = time.monotonic() - no_car_events_issues_once = False - car_event_issues = [] - not_running = [] - while time.monotonic() < start_time + max_time_per_step: - sm.update() - - not_running = [p.name for p in sm['managerState'].processes if not p.running and p.shouldBeRunning] - car_event_issues = [event.name for event in sm['onroadEvents'] if any([event.noEntry, event.softDisable, event.immediateDisable])] - - if sm.all_alive() and len(car_event_issues) == 0 and len(not_running) == 0: - no_car_events_issues_once = True - break - - self.assertTrue(no_car_events_issues_once, - f"Failed because no messages received, or CarEvents '{car_event_issues}' or processes not running '{not_running}'") - - start_time = time.monotonic() - min_counts_control_active = 100 - control_active = 0 - - while time.monotonic() < start_time + max_time_per_step: - sm.update() - - q.put("cruise_down") # Try engaging - - if sm.all_alive() and sm['controlsState'].active: - control_active += 1 - - if control_active == min_counts_control_active: - break - - self.assertEqual(min_counts_control_active, control_active, f"Simulator did not engage a minimal of {min_counts_control_active} steps was {control_active}") - - def tearDown(self): - print("Test shutting down. CommIssues are acceptable") - for p in reversed(self.processes): - p.terminate() - - for p in reversed(self.processes): - if isinstance(p, subprocess.Popen): - p.wait(15) - else: - p.join(15) - - -if __name__ == "__main__": - unittest.main() diff --git a/tools/sim/tmux_script.sh b/tools/sim/tmux_script.sh deleted file mode 100644 index 2a1e749..0000000 --- a/tools/sim/tmux_script.sh +++ /dev/null @@ -1,6 +0,0 @@ -#!/bin/bash -tmux new -d -s carla-sim -tmux send-keys "./launch_openpilot.sh" ENTER -tmux neww -tmux send-keys "./run_bridge.py $*" ENTER -tmux a -t carla-sim diff --git a/tools/ssh/README.md b/tools/ssh/README.md deleted file mode 100644 index 588ea71..0000000 --- a/tools/ssh/README.md +++ /dev/null @@ -1,72 +0,0 @@ -# SSH - -## Quick Start - -In order to SSH into your device, you'll need a GitHub account with SSH keys. See this [GitHub article](https://docs.github.com/en/github/authenticating-to-github/connecting-to-github-with-ssh) for getting your account setup with SSH keys. - -* Enable SSH in your device's settings -* Enter your GitHub username in the device's settings -* Connect to your device - * Username: `comma` - * Port: `22` or `8022` - -Here's an example command for connecting to your device using its tethered connection:
-`ssh comma@192.168.43.1` - -For doing development work on device, it's recommended to use [SSH agent forwarding](https://docs.github.com/en/developers/overview/using-ssh-agent-forwarding). - -## Notes - -The public keys are only fetched from your GitHub account once. In order to update your device's authorized keys, you'll need to re-enter your GitHub username. - -The `id_rsa` key in this directory only works while your device is in the setup state with no software installed. After installation, that default key will be removed. - -See the [community wiki](https://github.com/commaai/openpilot/wiki/SSH) for more detailed instructions and information. - -# Connecting to ssh.comma.ai -SSH into your comma device from anywhere with `ssh.comma.ai`. Requires a [comma prime subscription](https://comma.ai/connect). - -## Setup - -With software version 0.6.1 or newer, enter your GitHub username on your device under Developer Settings. Your GitHub authorized public keys will become your authorized SSH keys for `ssh.comma.ai`. You can add any additional keys in `/system/comma/home/.ssh/authorized_keys.persist`. - -## Recommended .ssh/config - -With the below SSH configuration, you can type `ssh comma-{dongleid}` to connect to your device through `ssh.comma.ai`.
-For example: `ssh comma-ffffffffffffffff` - -``` -Host comma-* - Port 22 - User comma - IdentityFile ~/.ssh/my_github_key - ProxyCommand ssh %h@ssh.comma.ai -W %h:%p -Host ssh.comma.ai - Hostname ssh.comma.ai - Port 22 - IdentityFile ~/.ssh/my_github_key -``` - -## One-off connection - -``` -ssh -i ~/.ssh/my_github_key -o ProxyCommand="ssh -i ~/.ssh/my_github_key -W %h:%p -p %p %h@ssh.comma.ai" comma@ffffffffffffffff -``` -(Replace `ffffffffffffffff` with your dongle_id) - -## ssh.comma.ai host key fingerprint - -``` -Host key fingerprint is SHA256:X22GOmfjGb9J04IA2+egtdaJ7vW9Fbtmpz9/x8/W1X4 -+---[RSA 4096]----+ -| | -| | -| . | -| + o | -| S = + +..| -| + @ = .=| -| . B @ ++=| -| o * B XE| -| .o o OB/| -+----[SHA256]-----+ -``` diff --git a/tools/ssh/id_rsa b/tools/ssh/id_rsa deleted file mode 100644 index 3f269af..0000000 --- a/tools/ssh/id_rsa +++ /dev/null @@ -1,28 +0,0 @@ ------BEGIN RSA PRIVATE KEY----- -MIIEvAIBADANBgkqhkiG9w0BAQEFAASCBKYwggSiAgEAAoIBAQC+iXXq30Tq+J5N -Kat3KWHCzcmwZ55nGh6WggAqECa5CasBlM9VeROpVu3beA+5h0MibRgbD4DMtVXB -t6gEvZ8nd04E7eLA9LTZyFDZ7SkSOVj4oXOQsT0GnJmKrASW5KslTWqVzTfo2XCt -Z+004ikLxmyFeBO8NOcErW1pa8gFdQDToH9FrA7kgysic/XVESTOoe7XlzRoe/eZ -acEQ+jtnmFd21A4aEADkk00Ahjr0uKaJiLUAPatxs2icIXWpgYtfqqtaKF23wSt6 -1OTu6cAwXbOWr3m+IUSRUO0IRzEIQS3z1jfd1svgzSgSSwZ1Lhj4AoKxIEAIc8qJ -rO4uymCJAgMBAAECggEBAISFevxHGdoL3Z5xkw6oO5SQKO2GxEeVhRzNgmu/HA+q -x8OryqD6O1CWY4037kft6iWxlwiLOdwna2P25ueVM3LxqdQH2KS4DmlCx+kq6FwC -gv063fQPMhC9LpWimvaQSPEC7VUPjQlo4tPY6sTTYBUOh0A1ihRm/x7juKuQCWix -Cq8C/DVnB1X4mGj+W3nJc5TwVJtgJbbiBrq6PWrhvB/3qmkxHRL7dU2SBb2iNRF1 -LLY30dJx/cD73UDKNHrlrsjk3UJc29Mp4/MladKvUkRqNwlYxSuAtJV0nZ3+iFkL -s3adSTHdJpClQer45R51rFDlVsDz2ZBpb/hRNRoGDuECgYEA6A1EixLq7QYOh3cb -Xhyh3W4kpVvA/FPfKH1OMy3ONOD/Y9Oa+M/wthW1wSoRL2n+uuIW5OAhTIvIEivj -6bAZsTT3twrvOrvYu9rx9aln4p8BhyvdjeW4kS7T8FP5ol6LoOt2sTP3T1LOuJPO -uQvOjlKPKIMh3c3RFNWTnGzMPa0CgYEA0jNiPLxP3A2nrX0keKDI+VHuvOY88gdh -0W5BuLMLovOIDk9aQFIbBbMuW1OTjHKv9NK+Lrw+YbCFqOGf1dU/UN5gSyE8lX/Q -FsUGUqUZx574nJZnOIcy3ONOnQLcvHAQToLFAGUd7PWgP3CtHkt9hEv2koUwL4vo -ikTP1u9Gkc0CgYEA2apoWxPZrY963XLKBxNQecYxNbLFaWq67t3rFnKm9E8BAICi -4zUaE5J1tMVi7Vi9iks9Ml9SnNyZRQJKfQ+kaebHXbkyAaPmfv+26rqHKboA0uxA -nDOZVwXX45zBkp6g1sdHxJx8JLoGEnkC9eyvSi0C//tRLx86OhLErXwYcNkCf1it -VMRKrWYoXJTUNo6tRhvodM88UnnIo3u3CALjhgU4uC1RTMHV4ZCGBwiAOb8GozSl -s5YD1E1iKwEULloHnK6BIh6P5v8q7J6uf/xdqoKMjlWBHgq6/roxKvkSPA1DOZ3l -jTadcgKFnRUmc+JT9p/ZbCxkA/ALFg8++G+0ghECgYA8vG3M/utweLvq4RI7l7U7 -b+i2BajfK2OmzNi/xugfeLjY6k2tfQGRuv6ppTjehtji2uvgDWkgjJUgPfZpir3I -RsVMUiFgloWGHETOy0Qvc5AwtqTJFLTD1Wza2uBilSVIEsg6Y83Gickh+ejOmEsY -6co17RFaAZHwGfCFFjO76Q== ------END RSA PRIVATE KEY----- diff --git a/tools/tuning/measure_steering_accuracy.py b/tools/tuning/measure_steering_accuracy.py deleted file mode 100644 index c615608..0000000 --- a/tools/tuning/measure_steering_accuracy.py +++ /dev/null @@ -1,159 +0,0 @@ -#!/usr/bin/env python3 -# type: ignore - -import os -import time -import argparse -import signal -from collections import defaultdict - -import cereal.messaging as messaging -from openpilot.tools.lib.logreader import logreader_from_route_or_segment - -def sigint_handler(signal, frame): - exit(0) -signal.signal(signal.SIGINT, sigint_handler) - -class SteeringAccuracyTool: - all_groups = {"germany": (45, "45 - up m/s // 162 - up km/h // 101 - up mph"), - "veryfast": (35, "35 - 45 m/s // 126 - 162 km/h // 78 - 101 mph"), - "fast": (25, "25 - 35 m/s // 90 - 126 km/h // 56 - 78 mph"), - "medium": (15, "15 - 25 m/s // 54 - 90 km/h // 34 - 56 mph"), - "slow": (5, " 5 - 15 m/s // 18 - 54 km/h // 11 - 34 mph"), - "crawl": (0, " 0 - 5 m/s // 0 - 18 km/h // 0 - 11 mph")} - - def __init__(self, args): - self.msg_cnt = 0 - self.cnt = 0 - self.total_error = 0 - - if args.group == "all": - self.display_groups = self.all_groups.keys() - elif args.group in self.all_groups.keys(): - self.display_groups = [args.group] - else: - raise ValueError("invalid speed group, see help") - - self.speed_group_stats = {} - for group in self.all_groups: - self.speed_group_stats[group] = defaultdict(lambda: {'err': 0, "cnt": 0, "=": 0, "+": 0, "-": 0, "steer": 0, "limited": 0, "saturated": 0, "dpp": 0}) - - def update(self, sm): - self.msg_cnt += 1 - - lateralControlState = sm['controlsState'].lateralControlState - control_type = list(lateralControlState.to_dict().keys())[0] - control_state = lateralControlState.__getattr__(control_type) - - v_ego = sm['carState'].vEgo - active = sm['controlsState'].active - steer = sm['carControl'].actuatorsOutput.steer - standstill = sm['carState'].standstill - steer_limited = abs(sm['carControl'].actuators.steer - sm['carControl'].actuatorsOutput.steer) > 1e-2 - overriding = sm['carState'].steeringPressed - changing_lanes = sm['lateralPlan'].laneChangeState != 0 - d_path_points = sm['lateralPlan'].dPathPoints - # must be engaged, not at standstill, not overriding steering, and not changing lanes - if active and not standstill and not overriding and not changing_lanes: - self.cnt += 1 - - # wait 5 seconds after engage / standstill / override / lane change - if self.cnt >= 500: - actual_angle = control_state.steeringAngleDeg - desired_angle = control_state.steeringAngleDesiredDeg - - # calculate error before rounding, then round for stats grouping - angle_error = abs(desired_angle - actual_angle) - actual_angle = round(actual_angle, 1) - desired_angle = round(desired_angle, 1) - angle_error = round(angle_error, 2) - angle_abs = int(abs(round(desired_angle, 0))) - - for group, group_props in self.all_groups.items(): - if v_ego > group_props[0]: - # collect stats - self.speed_group_stats[group][angle_abs]["cnt"] += 1 - self.speed_group_stats[group][angle_abs]["err"] += angle_error - self.speed_group_stats[group][angle_abs]["steer"] += abs(steer) - if len(d_path_points): - self.speed_group_stats[group][angle_abs]["dpp"] += abs(d_path_points[0]) - if steer_limited: - self.speed_group_stats[group][angle_abs]["limited"] += 1 - if control_state.saturated: - self.speed_group_stats[group][angle_abs]["saturated"] += 1 - if actual_angle == desired_angle: - self.speed_group_stats[group][angle_abs]["="] += 1 - else: - if desired_angle == 0.: - overshoot = True - else: - overshoot = desired_angle < actual_angle if desired_angle > 0. else desired_angle > actual_angle - self.speed_group_stats[group][angle_abs]["+" if overshoot else "-"] += 1 - break - else: - self.cnt = 0 - - if self.msg_cnt % 100 == 0: - print(chr(27) + "[2J") - if self.cnt != 0: - print("COLLECTING ...\n") - else: - print("DISABLED (not active, standstill, steering override, or lane change)\n") - for group in self.display_groups: - if len(self.speed_group_stats[group]) > 0: - print(f"speed group: {group:10s} {self.all_groups[group][1]:>96s}") - print(f" {'-'*118}") - for k in sorted(self.speed_group_stats[group].keys()): - v = self.speed_group_stats[group][k] - print(f' {k:#2}° | actuator:{int(v["steer"] / v["cnt"] * 100):#3}% \ - | error: {round(v["err"] / v["cnt"], 2):2.2f}° | -:{int(v["-"] / v["cnt"] * 100):#3}% \ - | =:{int(v["="] / v["cnt"] * 100):#3}% | +:{int(v["+"] / v["cnt"] * 100):#3}% | lim:{v["limited"]:#5} \ - | sat:{v["saturated"]:#5} | path dev: {round(v["dpp"] / v["cnt"], 2):2.2f}m | total: {v["cnt"]:#5}') - print("") - - -if __name__ == "__main__": - - parser = argparse.ArgumentParser(description='Steering accuracy measurement tool') - parser.add_argument('--route', help="route name") - parser.add_argument('--addr', default='127.0.0.1', help="IP address for optional ZMQ listener, default to msgq") - parser.add_argument('--group', default='all', help="speed group to display, [crawl|slow|medium|fast|veryfast|germany|all], default to all") - parser.add_argument('--cache', default=False, action='store_true', help="use cached data, default to False") - args = parser.parse_args() - - if args.cache: - os.environ['FILEREADER_CACHE'] = '1' - - tool = SteeringAccuracyTool(args) - - if args.route is not None: - print(f"loading {args.route}...") - lr = logreader_from_route_or_segment(args.route, sort_by_time=True) - - sm = {} - for msg in lr: - if msg.which() == 'carState': - sm['carState'] = msg.carState - elif msg.which() == 'carControl': - sm['carControl'] = msg.carControl - elif msg.which() == 'controlsState': - sm['controlsState'] = msg.controlsState - elif msg.which() == 'lateralPlan': - sm['lateralPlan'] = msg.lateralPlan - - if msg.which() == 'carControl' and 'carState' in sm and 'controlsState' in sm and 'lateralPlan' in sm: - tool.update(sm) - - else: - if args.addr != "127.0.0.1": - os.environ["ZMQ"] = "1" - messaging.context = messaging.Context() - - carControl = messaging.sub_sock('carControl', addr=args.addr, conflate=True) - sm = messaging.SubMaster(['carState', 'carControl', 'controlsState', 'lateralPlan'], addr=args.addr) - time.sleep(1) # Make sure all submaster data is available before going further - - print("waiting for messages...") - while messaging.recv_one(carControl): - sm.update() - tool.update(sm) diff --git a/tools/ubuntu_setup.sh b/tools/ubuntu_setup.sh deleted file mode 100644 index 1bdeb50..0000000 --- a/tools/ubuntu_setup.sh +++ /dev/null @@ -1,15 +0,0 @@ -#!/usr/bin/env bash - -set -e - -DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null && pwd )" - -# NOTE: this is used in a docker build, so do not run any scripts here. - -$DIR/install_ubuntu_dependencies.sh -$DIR/install_python_dependencies.sh - -echo -echo "---- OPENPILOT SETUP DONE ----" -echo "Open a new shell or configure your active shell env by running:" -echo "source ~/.bashrc" diff --git a/tools/webcam/Dockerfile b/tools/webcam/Dockerfile deleted file mode 100644 index 78a25e8..0000000 --- a/tools/webcam/Dockerfile +++ /dev/null @@ -1,41 +0,0 @@ -FROM ghcr.io/commaai/openpilot-base:latest - -ENV PYTHONUNBUFFERED 1 -ENV PYTHONPATH /tmp/openpilot:${PYTHONPATH} - -# Install opencv -ENV OPENCV_VERSION '4.2.0' -ENV DEBIAN_FRONTEND=noninteractive -RUN apt-get update && apt-get install -y --no-install-recommends \ - libvtk6-dev \ - libdc1394-22-dev \ - libavcodec-dev \ - libavformat-dev \ - libswscale-dev \ - libtheora-dev \ - libvorbis-dev \ - libxvidcore-dev \ - libx264-dev \ - yasm \ - libopencore-amrnb-dev \ - libopencore-amrwb-dev \ - libv4l-dev \ - libxine2-dev \ - libtbb-dev \ - && rm -rf /var/lib/apt/lists/* && \ - - mkdir /tmp/opencv_build && \ - cd /tmp/opencv_build && \ - - curl -L -O https://github.com/opencv/opencv/archive/${OPENCV_VERSION}.tar.gz && \ - tar -xvf ${OPENCV_VERSION}.tar.gz && \ - mv opencv-${OPENCV_VERSION} OpenCV && \ - cd OpenCV && mkdir build && cd build && \ - cmake -DWITH_OPENGL=ON -DFORCE_VTK=ON -DWITH_TBB=ON -DWITH_GDAL=ON \ - -DWITH_XINE=ON -DENABLE_PRECOMPILED_HEADERS=OFF -DBUILD_TESTS=OFF \ - -DBUILD_PERF_TESTS=OFF -DBUILD_EXAMPLES=OFF -DBUILD_opencv_apps=OFF .. && \ - make -j8 && \ - make install && \ - ldconfig && \ - - cd / && rm -rf /tmp/* diff --git a/tools/webcam/README.md b/tools/webcam/README.md deleted file mode 100644 index 3491f72..0000000 --- a/tools/webcam/README.md +++ /dev/null @@ -1,45 +0,0 @@ -# NOTE: this README is outdated. #24590 tracks adding back webcam support - -# Run openpilot with webcam on PC - -What's needed: -- Ubuntu 20.04 -- GPU (recommended) -- Two USB webcams, at least 720p and 78 degrees FOV (e.g. Logitech C920/C615) -- [Car harness](https://comma.ai/shop/products/comma-car-harness) with black panda to connect to your car -- [Panda paw](https://comma.ai/shop/products/panda-paw) or USB-A to USB-A cable to connect panda to your computer -That's it! - -## Setup openpilot -``` -cd ~ -git clone https://github.com/commaai/openpilot.git -``` -- Follow [this readme](https://github.com/commaai/openpilot/tree/master/tools) to install the requirements -- Add line "export PYTHONPATH=$HOME/openpilot" to your ~/.bashrc -- Install tensorflow 2.2 and nvidia drivers: nvidia-xxx/cuda10.0/cudnn7.6.5 -- Install [OpenCL Driver](https://registrationcenter-download.intel.com/akdlm/irc_nas/vcp/15532/l_opencl_p_18.1.0.015.tgz) -- Install [OpenCV4](https://www.pyimagesearch.com/2018/08/15/how-to-install-opencv-4-on-ubuntu/) (ignore the Python part) - -## Build openpilot for webcam -``` -cd ~/openpilot -``` -- check out system/camerad/cameras/camera_webcam.cc lines 72 and 146 before building if any camera is upside down -``` -USE_WEBCAM=1 scons -j$(nproc) -``` - -## Connect the hardware -- Connect the road facing camera first, then the driver facing camera -- (default indexes are 1 and 2; can be modified in system/camerad/cameras/camera_webcam.cc) -- Connect your computer to panda - -## GO -``` -cd ~/openpilot/selfdrive/manager -NOSENSOR=1 USE_WEBCAM=1 ./manager.py -``` -- Start the car, then the UI should show the road webcam's view -- Adjust and secure the webcams (you can run tools/webcam/front_mount_helper.py to help mount the driver camera) -- Finish calibration and engage! diff --git a/tools/webcam/front_mount_helper.py b/tools/webcam/front_mount_helper.py deleted file mode 100644 index 0b7b676..0000000 --- a/tools/webcam/front_mount_helper.py +++ /dev/null @@ -1,35 +0,0 @@ -#!/usr/bin/env python -import numpy as np - -# copied from openpilot.common.transformations/camera.py -eon_dcam_focal_length = 860.0 # pixels -webcam_focal_length = 908.0 # pixels - -eon_dcam_intrinsics = np.array([ - [eon_dcam_focal_length, 0, 1152/2.], - [ 0, eon_dcam_focal_length, 864/2.], - [ 0, 0, 1]]) - -webcam_intrinsics = np.array([ - [webcam_focal_length, 0., 1280/2.], - [ 0., webcam_focal_length, 720/2.], - [ 0., 0., 1.]]) - -cam_id = 2 - -if __name__ == "__main__": - import cv2 - - trans_webcam_to_eon_front = np.dot(eon_dcam_intrinsics, np.linalg.inv(webcam_intrinsics)) - - cap = cv2.VideoCapture(cam_id) - cap.set(cv2.CAP_PROP_FRAME_WIDTH, 1280) - cap.set(cv2.CAP_PROP_FRAME_HEIGHT, 720) - - while (True): - ret, img = cap.read() - if ret: - img = cv2.warpPerspective(img, trans_webcam_to_eon_front, (1152, 864), borderMode=cv2.BORDER_CONSTANT, borderValue=0) - img = img[:, -864//2:, :] - cv2.imshow('preview', img) - cv2.waitKey(10) diff --git a/tools/webcam/warp_vis.py b/tools/webcam/warp_vis.py deleted file mode 100644 index e3f1284..0000000 --- a/tools/webcam/warp_vis.py +++ /dev/null @@ -1,43 +0,0 @@ -#!/usr/bin/env python -import numpy as np - -# copied from openpilot.common.transformations/camera.py -eon_focal_length = 910.0 # pixels -eon_dcam_focal_length = 860.0 # pixels - -webcam_focal_length = -908.0/1.5 # pixels - -eon_intrinsics = np.array([ - [eon_focal_length, 0., 1164/2.], - [ 0., eon_focal_length, 874/2.], - [ 0., 0., 1.]]) - -eon_dcam_intrinsics = np.array([ - [eon_dcam_focal_length, 0, 1152/2.], - [ 0, eon_dcam_focal_length, 864/2.], - [ 0, 0, 1]]) - -webcam_intrinsics = np.array([ - [webcam_focal_length, 0., 1280/2/1.5], - [ 0., webcam_focal_length, 720/2/1.5], - [ 0., 0., 1.]]) - -if __name__ == "__main__": - import cv2 - trans_webcam_to_eon_rear = np.dot(eon_intrinsics, np.linalg.inv(webcam_intrinsics)) - trans_webcam_to_eon_front = np.dot(eon_dcam_intrinsics, np.linalg.inv(webcam_intrinsics)) - print("trans_webcam_to_eon_rear:\n", trans_webcam_to_eon_rear) - print("trans_webcam_to_eon_front:\n", trans_webcam_to_eon_front) - - cap = cv2.VideoCapture(1) - cap.set(cv2.CAP_PROP_FRAME_WIDTH, 853) - cap.set(cv2.CAP_PROP_FRAME_HEIGHT, 480) - - while (True): - ret, img = cap.read() - if ret: - # img = cv2.warpPerspective(img, trans_webcam_to_eon_rear, (1164,874), borderMode=cv2.BORDER_CONSTANT, borderValue=0) - img = cv2.warpPerspective(img, trans_webcam_to_eon_front, (1164, 874), borderMode=cv2.BORDER_CONSTANT, borderValue=0) - print(img.shape, end='\r') - cv2.imshow('preview', img) - cv2.waitKey(10) diff --git a/tools/zookeeper/__init__.py b/tools/zookeeper/__init__.py deleted file mode 100644 index 598e0a0..0000000 --- a/tools/zookeeper/__init__.py +++ /dev/null @@ -1,78 +0,0 @@ -import ft4222 -import ft4222.I2CMaster - -DEBUG = False - -INA231_ADDR = 0x40 -INA231_REG_CONFIG = 0x00 -INA231_REG_SHUNT_VOLTAGE = 0x01 -INA231_REG_BUS_VOLTAGE = 0x02 -INA231_REG_POWER = 0x03 -INA231_REG_CURRENT = 0x04 -INA231_REG_CALIBRATION = 0x05 - -INA231_BUS_LSB = 1.25e-3 -INA231_SHUNT_LSB = 2.5e-6 -SHUNT_RESISTOR = 30e-3 -CURRENT_LSB = 1e-5 - -class Zookeeper: - def __init__(self): - if ft4222.createDeviceInfoList() < 2: - raise Exception("No connected zookeeper found!") - self.dev_a = ft4222.openByDescription("FT4222 A") - self.dev_b = ft4222.openByDescription("FT4222 B") - - if DEBUG: - for i in range(ft4222.createDeviceInfoList()): - print(f"Device {i}: {ft4222.getDeviceInfoDetail(i, False)}") - - # Setup GPIO - self.dev_b.gpio_Init(gpio2=ft4222.Dir.OUTPUT, gpio3=ft4222.Dir.OUTPUT) - self.dev_b.setSuspendOut(False) - self.dev_b.setWakeUpInterrut(False) - - # Setup I2C - self.dev_a.i2cMaster_Init(kbps=400) - self._initialize_ina() - - # Helper functions - def _read_ina_register(self, register, length): - self.dev_a.i2cMaster_WriteEx(INA231_ADDR, data=register, flag=ft4222.I2CMaster.Flag.REPEATED_START) - return self.dev_a.i2cMaster_Read(INA231_ADDR, bytesToRead=length) - - def _write_ina_register(self, register, data): - msg = register.to_bytes(1, byteorder="big") + data.to_bytes(2, byteorder="big") - self.dev_a.i2cMaster_Write(INA231_ADDR, data=msg) - - def _initialize_ina(self): - # Config - self._write_ina_register(INA231_REG_CONFIG, 0x4127) - - # Calibration - CAL_VALUE = int(0.00512 / (CURRENT_LSB * SHUNT_RESISTOR)) - if DEBUG: - print(f"Calibration value: {hex(CAL_VALUE)}") - self._write_ina_register(INA231_REG_CALIBRATION, CAL_VALUE) - - def _set_gpio(self, number, enabled): - self.dev_b.gpio_Write(portNum=number, value=enabled) - - # Public API functions - def set_device_power(self, enabled): - self._set_gpio(2, enabled) - - def set_device_ignition(self, enabled): - self._set_gpio(3, enabled) - - def read_current(self): - # Returns in A - return int.from_bytes(self._read_ina_register(INA231_REG_CURRENT, 2), byteorder="big") * CURRENT_LSB - - def read_power(self): - # Returns in W - return int.from_bytes(self._read_ina_register(INA231_REG_POWER, 2), byteorder="big") * CURRENT_LSB * 25 - - def read_voltage(self): - # Returns in V - return int.from_bytes(self._read_ina_register(INA231_REG_BUS_VOLTAGE, 2), byteorder="big") * INA231_BUS_LSB diff --git a/tools/zookeeper/check_consumption.py b/tools/zookeeper/check_consumption.py deleted file mode 100644 index dab9483..0000000 --- a/tools/zookeeper/check_consumption.py +++ /dev/null @@ -1,27 +0,0 @@ -#!/usr/bin/env python3 - -import sys -import time -from openpilot.tools.zookeeper import Zookeeper - -# Usage: check_consumption.py -# Exit code: 0 -> passed -# 1 -> failed - -if __name__ == "__main__": - z = Zookeeper() - - averaging_time_s = int(sys.argv[1]) - max_average_power = float(sys.argv[2]) - - start_time = time.time() - measurements = [] - while time.time() - start_time < averaging_time_s: - measurements.append(z.read_power()) - time.sleep(0.1) - - average_power = sum(measurements)/len(measurements) - print(f"Average power: {round(average_power, 4)}W") - - if average_power > max_average_power: - exit(1) diff --git a/tools/zookeeper/disable.py b/tools/zookeeper/disable.py deleted file mode 100644 index 4bea3e7..0000000 --- a/tools/zookeeper/disable.py +++ /dev/null @@ -1,8 +0,0 @@ -#!/usr/bin/env python3 - -from openpilot.tools.zookeeper import Zookeeper - -if __name__ == "__main__": - z = Zookeeper() - z.set_device_power(False) - diff --git a/tools/zookeeper/enable_and_wait.py b/tools/zookeeper/enable_and_wait.py deleted file mode 100644 index 51b8dc0..0000000 --- a/tools/zookeeper/enable_and_wait.py +++ /dev/null @@ -1,31 +0,0 @@ -#!/usr/bin/env python3 -import os -import sys -import time -from socket import gethostbyname, gaierror -from openpilot.tools.zookeeper import Zookeeper - -def is_online(ip): - try: - addr = gethostbyname(ip) - return (os.system(f"ping -c 1 {addr} > /dev/null") == 0) - except gaierror: - return False - -if __name__ == "__main__": - z = Zookeeper() - z.set_device_power(True) - - - ip = str(sys.argv[1]) - timeout = int(sys.argv[2]) - start_time = time.time() - while not is_online(ip): - print(f"{ip} not online yet!") - - if time.time() - start_time > timeout: - print("Timed out!") - raise TimeoutError() - - time.sleep(1) - diff --git a/tools/zookeeper/ignition.py b/tools/zookeeper/ignition.py deleted file mode 100644 index d5f01c3..0000000 --- a/tools/zookeeper/ignition.py +++ /dev/null @@ -1,10 +0,0 @@ -#!/usr/bin/env python3 - -import sys -from openpilot.tools.zookeeper import Zookeeper - - -if __name__ == "__main__": - z = Zookeeper() - z.set_device_ignition(1 if int(sys.argv[1]) > 0 else 0) - diff --git a/tools/zookeeper/power_monitor.py b/tools/zookeeper/power_monitor.py deleted file mode 100644 index a081baa..0000000 --- a/tools/zookeeper/power_monitor.py +++ /dev/null @@ -1,40 +0,0 @@ -#!/usr/bin/env python3 -import sys -import time -import datetime - -from openpilot.common.realtime import Ratekeeper -from openpilot.common.filter_simple import FirstOrderFilter -from openpilot.tools.zookeeper import Zookeeper - -if __name__ == "__main__": - z = Zookeeper() - z.set_device_power(True) - z.set_device_ignition(False) - - duration = None - if len(sys.argv) > 1: - duration = int(sys.argv[1]) - - rate = 123 - rk = Ratekeeper(rate, print_delay_threshold=None) - fltr = FirstOrderFilter(0, 5, 1. / rate, initialized=False) - - measurements = [] - start_time = time.monotonic() - - try: - while duration is None or time.monotonic() - start_time < duration: - fltr.update(z.read_power()) - if rk.frame % rate == 0: - measurements.append(fltr.x) - t = datetime.timedelta(seconds=time.monotonic() - start_time) - avg = sum(measurements) / len(measurements) - print(f"Now: {fltr.x:.2f} W, Avg: {avg:.2f} W over {t}") - rk.keep_time() - except KeyboardInterrupt: - pass - - t = datetime.timedelta(seconds=time.monotonic() - start_time) - avg = sum(measurements) / len(measurements) - print(f"\nAverage power: {avg:.2f}W over {t}") diff --git a/tools/zookeeper/test_zookeeper.py b/tools/zookeeper/test_zookeeper.py deleted file mode 100644 index 89f7f28..0000000 --- a/tools/zookeeper/test_zookeeper.py +++ /dev/null @@ -1,25 +0,0 @@ -#!/usr/bin/env python3 - -import time -from openpilot.tools.zookeeper import Zookeeper - - -if __name__ == "__main__": - z = Zookeeper() - z.set_device_power(True) - - i = 0 - ign = False - while 1: - voltage = round(z.read_voltage(), 2) - current = round(z.read_current(), 3) - power = round(z.read_power(), 2) - z.set_device_ignition(ign) - print(f"Voltage: {voltage}V, Current: {current}A, Power: {power}W, Ignition: {ign}") - - if i > 200: - ign = not ign - i = 0 - - i += 1 - time.sleep(0.1)